From 0f63e277637ab79bad1a1bce40e75c493f3aced8 Mon Sep 17 00:00:00 2001 From: Nick B Date: Thu, 6 Oct 2022 14:59:58 -0400 Subject: [PATCH 01/29] Fix setColor bug for whole ring color --- src/MeRGBLed.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/MeRGBLed.cpp b/src/MeRGBLed.cpp index e6e9c5ba..8003910c 100644 --- a/src/MeRGBLed.cpp +++ b/src/MeRGBLed.cpp @@ -504,7 +504,7 @@ bool MeRGBLed::setColor(uint8_t index, long value) { for(int16_t i = 0; i < count_led; i++) { - uint8_t tmp = index * 3; + uint8_t tmp = i * 3; uint8_t red = (value & 0xff0000) >> 16; uint8_t green = (value & 0xff00) >> 8; uint8_t blue = value & 0xff; From 24348b0f5d0e36ea73c28a3a82dc74793035716c Mon Sep 17 00:00:00 2001 From: Nick B Date: Tue, 18 Oct 2022 16:23:11 -0400 Subject: [PATCH 02/29] Fixed method signature type error and typos --- .vscode/c_cpp_properties.json | 23 +++++++++++++++++++ .../Me_Auriga_encoder_pwm.ino | 4 ++-- src/MeEncoderOnBoard.cpp | 3 ++- src/MeEncoderOnBoard.h | 2 +- 4 files changed, 28 insertions(+), 4 deletions(-) create mode 100644 .vscode/c_cpp_properties.json diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json new file mode 100644 index 00000000..be572990 --- /dev/null +++ b/.vscode/c_cpp_properties.json @@ -0,0 +1,23 @@ +{ + "configurations": [ + { + "name": "Win32", + "includePath": [ + "${workspaceFolder}/**", + "${workspaceFolder}/src", + "${env:LocalAppData}/Programs/Arduino IDE" + ], + "defines": [ + "_DEBUG", + "UNICODE", + "_UNICODE#" + ], + "windowsSdkVersion": "10.0.20348.0", + "compilerPath": "C:/Program Files (x86)/Microsoft Visual Studio/2019/Enterprise/VC/Tools/MSVC/14.29.30133/bin/Hostx64/x64/cl.exe", + "cStandard": "c17", + "cppStandard": "c++17", + "intelliSenseMode": "windows-msvc-x64" + } + ], + "version": 4 +} \ No newline at end of file diff --git a/examples/Me_On_Board_encoder/Me_Auriga_encoder_pwm/Me_Auriga_encoder_pwm.ino b/examples/Me_On_Board_encoder/Me_Auriga_encoder_pwm/Me_Auriga_encoder_pwm.ino index 1a6dcd31..df383fd5 100644 --- a/examples/Me_On_Board_encoder/Me_Auriga_encoder_pwm/Me_Auriga_encoder_pwm.ino +++ b/examples/Me_On_Board_encoder/Me_Auriga_encoder_pwm/Me_Auriga_encoder_pwm.ino @@ -107,9 +107,9 @@ void loop() } Encoder_1.loop(); Encoder_2.loop(); - Serial.print("Spped 1:"); + Serial.print("Speed 1:"); Serial.print(Encoder_1.getCurrentSpeed()); - Serial.print(" ,Spped 2:"); + Serial.print(" ,Speed 2:"); Serial.println(Encoder_2.getCurrentSpeed()); } diff --git a/src/MeEncoderOnBoard.cpp b/src/MeEncoderOnBoard.cpp index b87a47a9..4aa9ce12 100644 --- a/src/MeEncoderOnBoard.cpp +++ b/src/MeEncoderOnBoard.cpp @@ -531,6 +531,7 @@ void MeEncoderOnBoard::updateSpeed(void) */ void MeEncoderOnBoard::updateCurPos(void) { + // currentPos = CurrentPos / (tick_per_rotation) * 360 degrees encode_structure.currentPos = (long)((encode_structure.pulsePos/(encode_structure.pulseEncoder * encode_structure.ratio)) * 360); } @@ -766,7 +767,7 @@ void MeEncoderOnBoard::setPulse(int16_t pulseValue) * \par Others * None */ -void MeEncoderOnBoard::setRatio(int16_t RatioValue) +void MeEncoderOnBoard::setRatio(float RatioValue) { encode_structure.ratio = RatioValue; } diff --git a/src/MeEncoderOnBoard.h b/src/MeEncoderOnBoard.h index f1298888..df4582b0 100644 --- a/src/MeEncoderOnBoard.h +++ b/src/MeEncoderOnBoard.h @@ -590,7 +590,7 @@ class MeEncoderOnBoard * \par Others * None */ - void setRatio(int16_t RatioValue); + void setRatio(float RatioValue); /** * \par Function From 6c190150eec265271331dfda6a7df373430518cd Mon Sep 17 00:00:00 2001 From: Nick B Date: Tue, 18 Oct 2022 16:41:35 -0400 Subject: [PATCH 03/29] Comments --- src/MeEncoderOnBoard.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/MeEncoderOnBoard.cpp b/src/MeEncoderOnBoard.cpp index 4aa9ce12..a2676a1b 100644 --- a/src/MeEncoderOnBoard.cpp +++ b/src/MeEncoderOnBoard.cpp @@ -475,6 +475,7 @@ void MeEncoderOnBoard::setMotorPwm(int16_t pwm) if(pwm < 0) { + // As per the datasheet, counter clock wise digitalWrite(MeEncoderOnBoard::_Port_H1, LOW); delayMicroseconds(5); digitalWrite(MeEncoderOnBoard::_Port_H2, HIGH); @@ -482,6 +483,7 @@ void MeEncoderOnBoard::setMotorPwm(int16_t pwm) } else { + // As per the datasheet, clock wise digitalWrite(MeEncoderOnBoard::_Port_H1, HIGH); delayMicroseconds(5); digitalWrite(MeEncoderOnBoard::_Port_H2, LOW); From 463fd05a3c2701d74a9bbc7b2dd089ce02b3f44c Mon Sep 17 00:00:00 2001 From: Nick B Date: Fri, 29 Sep 2023 09:00:30 -0400 Subject: [PATCH 04/29] Added gitignore --- .gitignore | 57 ++++++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 57 insertions(+) create mode 100644 .gitignore diff --git a/.gitignore b/.gitignore new file mode 100644 index 00000000..87c527e6 --- /dev/null +++ b/.gitignore @@ -0,0 +1,57 @@ +# Created by https://www.toptal.com/developers/gitignore/api/c++,visualstudiocode +# Edit at https://www.toptal.com/developers/gitignore?templates=c++,visualstudiocode + +### C++ ### +# Prerequisites +*.d + +# Compiled Object files +*.slo +*.lo +*.o +*.obj + +# Precompiled Headers +*.gch +*.pch + +# Compiled Dynamic libraries +*.so +*.dylib +*.dll + +# Fortran module files +*.mod +*.smod + +# Compiled Static libraries +*.lai +*.la +*.a +*.lib + +# Executables +*.exe +*.out +*.app + +### VisualStudioCode ### +.vscode/* +!.vscode/settings.json +!.vscode/tasks.json +!.vscode/launch.json +!.vscode/extensions.json +!.vscode/*.code-snippets + +# Local History for Visual Studio Code +.history/ + +# Built Visual Studio Code Extensions +*.vsix + +### VisualStudioCode Patch ### +# Ignore all local history of files +.history +.ionide + +# End of https://www.toptal.com/developers/gitignore/api/c++,visualstudiocode From c59de3e14946b2ee336103331af36694798d396e Mon Sep 17 00:00:00 2001 From: Nick B Date: Fri, 29 Sep 2023 09:02:27 -0400 Subject: [PATCH 05/29] Removed .vscode cached --- .vscode/c_cpp_properties.json | 23 ----------------------- 1 file changed, 23 deletions(-) delete mode 100644 .vscode/c_cpp_properties.json diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json deleted file mode 100644 index be572990..00000000 --- a/.vscode/c_cpp_properties.json +++ /dev/null @@ -1,23 +0,0 @@ -{ - "configurations": [ - { - "name": "Win32", - "includePath": [ - "${workspaceFolder}/**", - "${workspaceFolder}/src", - "${env:LocalAppData}/Programs/Arduino IDE" - ], - "defines": [ - "_DEBUG", - "UNICODE", - "_UNICODE#" - ], - "windowsSdkVersion": "10.0.20348.0", - "compilerPath": "C:/Program Files (x86)/Microsoft Visual Studio/2019/Enterprise/VC/Tools/MSVC/14.29.30133/bin/Hostx64/x64/cl.exe", - "cStandard": "c17", - "cppStandard": "c++17", - "intelliSenseMode": "windows-msvc-x64" - } - ], - "version": 4 -} \ No newline at end of file From 22b96ba9de26740904bb1dc9590f0da8486dfac0 Mon Sep 17 00:00:00 2001 From: Nick B Date: Fri, 29 Sep 2023 09:02:47 -0400 Subject: [PATCH 06/29] vscod things --- .vscode/settings.json | 12 ++++++++++++ 1 file changed, 12 insertions(+) create mode 100644 .vscode/settings.json diff --git a/.vscode/settings.json b/.vscode/settings.json new file mode 100644 index 00000000..6f73c6a6 --- /dev/null +++ b/.vscode/settings.json @@ -0,0 +1,12 @@ +{ + "files.associations": { + "deque": "cpp", + "initializer_list": "cpp", + "list": "cpp", + "vector": "cpp", + "xhash": "cpp", + "xstring": "cpp", + "xtree": "cpp", + "xutility": "cpp" + } +} \ No newline at end of file From 223dba364bc5057f3cf14b5dd6c306f46887844c Mon Sep 17 00:00:00 2001 From: Nick B Date: Fri, 29 Sep 2023 09:54:58 -0400 Subject: [PATCH 07/29] Added Wire.h inclusion --- src/MeAuriga.h | 1 + 1 file changed, 1 insertion(+) diff --git a/src/MeAuriga.h b/src/MeAuriga.h index 5a98115e..bdb0db98 100644 --- a/src/MeAuriga.h +++ b/src/MeAuriga.h @@ -37,6 +37,7 @@ #define MeAuriga_H #include +#include #include "MeConfig.h" // Supported Modules drive needs to be added here From 95761ca0b7f8340059fa9645642724af7f288315 Mon Sep 17 00:00:00 2001 From: Nick B Date: Fri, 29 Sep 2023 13:43:48 -0400 Subject: [PATCH 08/29] Added the missing getGyroZ --- src/MeGyro.cpp | 19 +++++++++++++++++++ src/MeGyro.h | 16 ++++++++++++++++ 2 files changed, 35 insertions(+) diff --git a/src/MeGyro.cpp b/src/MeGyro.cpp index 96d82dc5..b40e9512 100644 --- a/src/MeGyro.cpp +++ b/src/MeGyro.cpp @@ -436,6 +436,25 @@ double MeGyro::getGyroY(void) const return gyrY; } +/** + * \par Function + * getGyroZ + * \par Description + * Get the data of gyroZrate. + * \param[in] + * None + * \par Output + * None + * \return + * The data of gyroZrate + * \par Others + * None + */ +double MeGyro::getGyroZ(void) const +{ + return gyrZ; +} + /** * \par Function * getAngle diff --git a/src/MeGyro.h b/src/MeGyro.h index 75471769..c21e9402 100644 --- a/src/MeGyro.h +++ b/src/MeGyro.h @@ -291,6 +291,22 @@ class MeGyro : public MePort */ double getGyroY(void) const; +/** + * \par Function + * getGyroZ + * \par Description + * Get the data of gyroZrate. + * \param[in] + * None + * \par Output + * None + * \return + * The data of gyroZrate + * \par Others + * None + */ + double getGyroZ(void) const; + /** * \par Function * getAngle From a3d6eda6a87860a2099c65b8655345e36ef9946c Mon Sep 17 00:00:00 2001 From: Nick B Date: Fri, 29 Sep 2023 13:51:21 -0400 Subject: [PATCH 09/29] Updated the library properties --- library.properties | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/library.properties b/library.properties index a54bbdd9..0158c646 100644 --- a/library.properties +++ b/library.properties @@ -1,9 +1,9 @@ -name=MakeBlockDrive +name=MakeBlock Drive Updated version=3.27 author=Mark Yan, Makeblock -maintainer=MakeBlock -sentence= Use to drive all devices provided by Makeblock company. -paragraph=This library allows an Arduino board to control all devices provided by Makeblock company. +maintainer=Nick B, School +sentence=Use to drive all devices provided by Makeblock company. +paragraph=This library is an updated version of the MakeBlock Drive library. It is used to drive all devices provided by Makeblock company. It is based on the original MakeBlock Drive library, but has been updated to fix some issues. Feel free to pull request if you find any bugs. category=Device Control -url=http://www.makeblock.com/ -architectures=* +url=https://github.com/nbourre/Makeblock-Libraries +architectures=* \ No newline at end of file From ecdebf6cdcfb1c5803332c3c7e28cddd922afc40 Mon Sep 17 00:00:00 2001 From: Nick B Date: Fri, 29 Sep 2023 14:04:15 -0400 Subject: [PATCH 10/29] semver.org compliant version number --- library.properties | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/library.properties b/library.properties index 0158c646..137827db 100644 --- a/library.properties +++ b/library.properties @@ -1,5 +1,5 @@ name=MakeBlock Drive Updated -version=3.27 +version=3.27.0 author=Mark Yan, Makeblock maintainer=Nick B, School sentence=Use to drive all devices provided by Makeblock company. From 17c8b18df944eb28e5c2ffad45b0f585a425c3ee Mon Sep 17 00:00:00 2001 From: Nick B Date: Fri, 29 Sep 2023 14:13:49 -0400 Subject: [PATCH 11/29] Added the resetData function --- src/MeGyro.cpp | 29 +++++++++++++++++++++++++++++ src/MeGyro.h | 18 ++++++++++++++++++ 2 files changed, 47 insertions(+) diff --git a/src/MeGyro.cpp b/src/MeGyro.cpp index b40e9512..ef6310cd 100644 --- a/src/MeGyro.cpp +++ b/src/MeGyro.cpp @@ -641,3 +641,32 @@ int8_t MeGyro::writeData(uint8_t start, const uint8_t *pData, uint8_t size) return_value = Wire.endTransmission(true); return(return_value); //return: no error } + +/** + * \par Function + * resetData + * \par Description + * Reset the angle value of setting axis. + * \param[in] + * None + * \par Output + * None + * \return + * None + * \par Others + * None + * \author + * Nicolas Bourré + */ +void MeGyro::resetData(void) +{ + gx = 0; + gy = 0; + gz = 0; + gyrX = 0; + gyrY = 0; + gyrZ = 0; + accX = 0; + accY = 0; + accZ = 0; +} \ No newline at end of file diff --git a/src/MeGyro.h b/src/MeGyro.h index c21e9402..d3730da8 100644 --- a/src/MeGyro.h +++ b/src/MeGyro.h @@ -323,6 +323,24 @@ class MeGyro : public MePort */ double getAngle(uint8_t index) const; +/** + * \par Function + * resetData + * \par Description + * Reset the angle value of setting axis. + * \param[in] + * None + * \par Output + * None + * \return + * None + * \par Others + * None + * \author + * Nicolas Bourré + */ + void resetData(void); + private: volatile uint8_t _AD0; volatile uint8_t _INT; From d540ab47301603a27ffca25a6a8fc8b061a4b722 Mon Sep 17 00:00:00 2001 From: Nick B Date: Thu, 5 Oct 2023 13:27:33 -0400 Subject: [PATCH 12/29] bugfix --- src/MeEncoderOnBoard.cpp | 2 +- src/MeEncoderOnBoard.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/MeEncoderOnBoard.cpp b/src/MeEncoderOnBoard.cpp index a2676a1b..e4ebfc77 100644 --- a/src/MeEncoderOnBoard.cpp +++ b/src/MeEncoderOnBoard.cpp @@ -50,7 +50,7 @@ * 23. void MeEncoderOnBoard::setSpeedPid(float p,float i,float d); * 24. void MeEncoderOnBoard::setPosPid(float p,float i,float d); * 25. void MeEncoderOnBoard::setPulse(int16_t pulseValue); - * 26. void MeEncoderOnBoard::setRatio(int16_t RatioValue); + * 26. void MeEncoderOnBoard::setRatio(float RatioValue); * 27. void MeEncoderOnBoard::setMotionMode(int16_t motionMode); * 28. int16_t MeEncoderOnBoard::pidPositionToPwm(void); * 29. int16_t MeEncoderOnBoard::speedWithoutPos(void); diff --git a/src/MeEncoderOnBoard.h b/src/MeEncoderOnBoard.h index df4582b0..df301e49 100644 --- a/src/MeEncoderOnBoard.h +++ b/src/MeEncoderOnBoard.h @@ -50,7 +50,7 @@ * 23. void MeEncoderOnBoard::setSpeedPid(float p,float i,float d); * 24. void MeEncoderOnBoard::setPosPid(float p,float i,float d); * 25. void MeEncoderOnBoard::setPulse(int16_t pulseValue); - * 26. void MeEncoderOnBoard::setRatio(int16_t RatioValue); + * 26. void MeEncoderOnBoard::setRatio(float RatioValue); * 27. void MeEncoderOnBoard::setMotionMode(int16_t motionMode); * 28. int16_t MeEncoderOnBoard::pidPositionToPwm(void); * 29. int16_t MeEncoderOnBoard::speedWithoutPos(void); From 7b86ccb2b2d751905896a7740ae91d0bef807615 Mon Sep 17 00:00:00 2001 From: Nick B Date: Thu, 5 Oct 2023 13:38:42 -0400 Subject: [PATCH 13/29] Bugfix and code readability --- .../Firmware_for_Auriga/Firmware_for_Auriga.ino | 8 ++++---- .../Firmware_for_MegaPi/Firmware_for_MegaPi.ino | 4 ++-- .../Firmware_for_MegaPiPro.ino | 16 ++++++++-------- .../Me_Megapipro_encoder_pid_pos.ino | 4 ++-- .../Me_Megapipro_encoder_pid_speed.ino | 8 ++++---- .../Me_Auriga_encoder_callback.ino | 8 ++++---- .../Me_Auriga_encoder_pid_pos.ino | 8 ++++---- .../Me_Auriga_encoder_pid_speed.ino | 4 ++-- .../Me_Megapi_encoder_pid_pos.ino | 8 ++++---- .../Me_Megapi_encoder_pid_speed.ino | 8 ++++---- library.properties | 2 +- 11 files changed, 39 insertions(+), 39 deletions(-) diff --git a/examples/Firmware_for_Auriga/Firmware_for_Auriga.ino b/examples/Firmware_for_Auriga/Firmware_for_Auriga.ino index 4596391a..daf76cf6 100644 --- a/examples/Firmware_for_Auriga/Firmware_for_Auriga.ino +++ b/examples/Firmware_for_Auriga/Firmware_for_Auriga.ino @@ -3074,10 +3074,10 @@ void setup() Encoder_2.setPulse(9); Encoder_1.setRatio(39.267); Encoder_2.setRatio(39.267); - Encoder_1.setPosPid(1.8,0,1.2); - Encoder_2.setPosPid(1.8,0,1.2); - Encoder_1.setSpeedPid(0.18,0,0); - Encoder_2.setSpeedPid(0.18,0,0); + Encoder_1.setPosPid(1.8, 0, 1.2); + Encoder_2.setPosPid(1.8, 0, 1.2); + Encoder_1.setSpeedPid(0.18, 0, 0); + Encoder_2.setSpeedPid(0.18, 0, 0); Encoder_1.setMotionMode(DIRECT_MODE); Encoder_2.setMotionMode(DIRECT_MODE); diff --git a/examples/Firmware_for_MegaPi/Firmware_for_MegaPi.ino b/examples/Firmware_for_MegaPi/Firmware_for_MegaPi.ino index 8d12c47a..44b74282 100644 --- a/examples/Firmware_for_MegaPi/Firmware_for_MegaPi.ino +++ b/examples/Firmware_for_MegaPi/Firmware_for_MegaPi.ino @@ -2812,8 +2812,8 @@ void setup() { encoders[i].setPulse(8); encoders[i].setRatio(46.67); - encoders[i].setPosPid(1.8,0,1.2); - encoders[i].setSpeedPid(0.18,0,0); + encoders[i].setPosPid(1.8, 0, 1.2); + encoders[i].setSpeedPid(0.18, 0, 0); encoders[i].setMotionMode(DIRECT_MODE); } diff --git a/examples/Firmware_for_MegaPiPro/Firmware_for_MegaPiPro.ino b/examples/Firmware_for_MegaPiPro/Firmware_for_MegaPiPro.ino index b90b710b..57307ea6 100644 --- a/examples/Firmware_for_MegaPiPro/Firmware_for_MegaPiPro.ino +++ b/examples/Firmware_for_MegaPiPro/Firmware_for_MegaPiPro.ino @@ -3219,14 +3219,14 @@ void setup() Encoder_2.setRatio(46.67); Encoder_3.setRatio(46.67); Encoder_4.setRatio(46.67); - Encoder_1.setPosPid(1.8,0,1.2); - Encoder_2.setPosPid(1.8,0,1.2); - Encoder_3.setPosPid(1.8,0,1.2); - Encoder_4.setPosPid(1.8,0,1.2); - Encoder_1.setSpeedPid(0.18,0,0); - Encoder_2.setSpeedPid(0.18,0,0); - Encoder_3.setSpeedPid(0.18,0,0); - Encoder_4.setSpeedPid(0.18,0,0); + Encoder_1.setPosPid(1.8, 0, 1.2); + Encoder_2.setPosPid(1.8, 0, 1.2); + Encoder_3.setPosPid(1.8, 0, 1.2); + Encoder_4.setPosPid(1.8, 0, 1.2); + Encoder_1.setSpeedPid(0.18, 0, 0); + Encoder_2.setSpeedPid(0.18, 0, 0); + Encoder_3.setSpeedPid(0.18, 0, 0); + Encoder_4.setSpeedPid(0.18, 0, 0); Encoder_1.setMotionMode(DIRECT_MODE); Encoder_2.setMotionMode(DIRECT_MODE); Encoder_3.setMotionMode(DIRECT_MODE); diff --git a/examples/Me_MegaPiProMotor/Me_Megapipro_encoder_pid_pos/Me_Megapipro_encoder_pid_pos.ino b/examples/Me_MegaPiProMotor/Me_Megapipro_encoder_pid_pos/Me_Megapipro_encoder_pid_pos.ino index 2a9dd6fd..aa670ab5 100644 --- a/examples/Me_MegaPiProMotor/Me_Megapipro_encoder_pid_pos/Me_Megapipro_encoder_pid_pos.ino +++ b/examples/Me_MegaPiProMotor/Me_Megapipro_encoder_pid_pos/Me_Megapipro_encoder_pid_pos.ino @@ -85,8 +85,8 @@ void setup() Encoder_1.setPosPid(1.8,0,0.5); Encoder_2.setPosPid(1.8,0,0.5); - Encoder_1.setSpeedPid(0.18,0,0); - Encoder_2.setSpeedPid(0.18,0,0); + Encoder_1.setSpeedPid(0.18, 0, 0); + Encoder_2.setSpeedPid(0.18, 0, 0); } void loop() diff --git a/examples/Me_MegaPiProMotor/Me_Megapipro_encoder_pid_speed/Me_Megapipro_encoder_pid_speed.ino b/examples/Me_MegaPiProMotor/Me_Megapipro_encoder_pid_speed/Me_Megapipro_encoder_pid_speed.ino index d87b22b2..5049e228 100644 --- a/examples/Me_MegaPiProMotor/Me_Megapipro_encoder_pid_speed/Me_Megapipro_encoder_pid_speed.ino +++ b/examples/Me_MegaPiProMotor/Me_Megapipro_encoder_pid_speed/Me_Megapipro_encoder_pid_speed.ino @@ -81,10 +81,10 @@ void setup() Encoder_2.setPulse(7); Encoder_1.setRatio(26.9); Encoder_2.setRatio(26.9); - Encoder_1.setPosPid(1.8,0,1.2); - Encoder_2.setPosPid(1.8,0,1.2); - Encoder_1.setSpeedPid(0.18,0,0); - Encoder_2.setSpeedPid(0.18,0,0); + Encoder_1.setPosPid(1.8, 0, 1.2); + Encoder_2.setPosPid(1.8, 0, 1.2); + Encoder_1.setSpeedPid(0.18, 0, 0); + Encoder_2.setSpeedPid(0.18, 0, 0); } void loop() diff --git a/examples/Me_On_Board_encoder/Me_Auriga_encoder_callback/Me_Auriga_encoder_callback.ino b/examples/Me_On_Board_encoder/Me_Auriga_encoder_callback/Me_Auriga_encoder_callback.ino index b179faa7..adcbbc42 100644 --- a/examples/Me_On_Board_encoder/Me_Auriga_encoder_callback/Me_Auriga_encoder_callback.ino +++ b/examples/Me_On_Board_encoder/Me_Auriga_encoder_callback/Me_Auriga_encoder_callback.ino @@ -74,10 +74,10 @@ void setup() Encoder_2.setPulse(9); Encoder_1.setRatio(39.267); Encoder_2.setRatio(39.267); - Encoder_1.setPosPid(1.8,0,1.2); - Encoder_2.setPosPid(1.8,0,1.2); - Encoder_1.setSpeedPid(0.18,0,0); - Encoder_2.setSpeedPid(0.18,0,0); + Encoder_1.setPosPid(1.8, 0, 1.2); + Encoder_2.setPosPid(1.8, 0, 1.2); + Encoder_1.setSpeedPid(0.18, 0, 0); + Encoder_2.setSpeedPid(0.18, 0, 0); Encoder_1.moveTo(3600,200,NULL,callback_test); Encoder_2.moveTo(3600,200,NULL,callback_test); } diff --git a/examples/Me_On_Board_encoder/Me_Auriga_encoder_pid_pos/Me_Auriga_encoder_pid_pos.ino b/examples/Me_On_Board_encoder/Me_Auriga_encoder_pid_pos/Me_Auriga_encoder_pid_pos.ino index ea6affa7..2726aa10 100644 --- a/examples/Me_On_Board_encoder/Me_Auriga_encoder_pid_pos/Me_Auriga_encoder_pid_pos.ino +++ b/examples/Me_On_Board_encoder/Me_Auriga_encoder_pid_pos/Me_Auriga_encoder_pid_pos.ino @@ -75,10 +75,10 @@ void setup() Encoder_2.setPulse(9); Encoder_1.setRatio(39.267); Encoder_2.setRatio(39.267); - Encoder_1.setPosPid(1.8,0,1.2); - Encoder_2.setPosPid(1.8,0,1.2); - Encoder_1.setSpeedPid(0.18,0,0); - Encoder_2.setSpeedPid(0.18,0,0); + Encoder_1.setPosPid(1.8, 0, 1.2); + Encoder_2.setPosPid(1.8, 0, 1.2); + Encoder_1.setSpeedPid(0.18, 0, 0); + Encoder_2.setSpeedPid(0.18, 0, 0); } void loop() diff --git a/examples/Me_On_Board_encoder/Me_Auriga_encoder_pid_speed/Me_Auriga_encoder_pid_speed.ino b/examples/Me_On_Board_encoder/Me_Auriga_encoder_pid_speed/Me_Auriga_encoder_pid_speed.ino index 3834804f..f65df65a 100644 --- a/examples/Me_On_Board_encoder/Me_Auriga_encoder_pid_speed/Me_Auriga_encoder_pid_speed.ino +++ b/examples/Me_On_Board_encoder/Me_Auriga_encoder_pid_speed/Me_Auriga_encoder_pid_speed.ino @@ -76,8 +76,8 @@ void setup() Encoder_2.setRatio(39.267); Encoder_1.setPosPid(0.18,0,0); Encoder_2.setPosPid(0.18,0,0); - Encoder_1.setSpeedPid(0.18,0,0); - Encoder_2.setSpeedPid(0.18,0,0); + Encoder_1.setSpeedPid(0.18, 0, 0); + Encoder_2.setSpeedPid(0.18, 0, 0); } void loop() diff --git a/examples/Me_On_Board_encoder/Me_Megapi_encoder_pid_pos/Me_Megapi_encoder_pid_pos.ino b/examples/Me_On_Board_encoder/Me_Megapi_encoder_pid_pos/Me_Megapi_encoder_pid_pos.ino index 4530d361..c0f73a1d 100644 --- a/examples/Me_On_Board_encoder/Me_Megapi_encoder_pid_pos/Me_Megapi_encoder_pid_pos.ino +++ b/examples/Me_On_Board_encoder/Me_Megapi_encoder_pid_pos/Me_Megapi_encoder_pid_pos.ino @@ -75,10 +75,10 @@ void setup() Encoder_2.setPulse(7); Encoder_1.setRatio(26.9); Encoder_2.setRatio(26.9); - Encoder_1.setPosPid(1.8,0,1.2); - Encoder_2.setPosPid(1.8,0,1.2); - Encoder_1.setSpeedPid(0.18,0,0); - Encoder_2.setSpeedPid(0.18,0,0); + Encoder_1.setPosPid(1.8, 0, 1.2); + Encoder_2.setPosPid(1.8, 0, 1.2); + Encoder_1.setSpeedPid(0.18, 0, 0); + Encoder_2.setSpeedPid(0.18, 0, 0); } void loop() diff --git a/examples/Me_On_Board_encoder/Me_Megapi_encoder_pid_speed/Me_Megapi_encoder_pid_speed.ino b/examples/Me_On_Board_encoder/Me_Megapi_encoder_pid_speed/Me_Megapi_encoder_pid_speed.ino index db27ca8a..13e3549b 100644 --- a/examples/Me_On_Board_encoder/Me_Megapi_encoder_pid_speed/Me_Megapi_encoder_pid_speed.ino +++ b/examples/Me_On_Board_encoder/Me_Megapi_encoder_pid_speed/Me_Megapi_encoder_pid_speed.ino @@ -74,10 +74,10 @@ void setup() Encoder_2.setPulse(7); Encoder_1.setRatio(26.9); Encoder_2.setRatio(26.9); - Encoder_1.setPosPid(1.8,0,1.2); - Encoder_2.setPosPid(1.8,0,1.2); - Encoder_1.setSpeedPid(0.18,0,0); - Encoder_2.setSpeedPid(0.18,0,0); + Encoder_1.setPosPid(1.8, 0, 1.2); + Encoder_2.setPosPid(1.8, 0, 1.2); + Encoder_1.setSpeedPid(0.18, 0, 0); + Encoder_2.setSpeedPid(0.18, 0, 0); } void loop() diff --git a/library.properties b/library.properties index 137827db..15ca2f6b 100644 --- a/library.properties +++ b/library.properties @@ -1,6 +1,6 @@ name=MakeBlock Drive Updated version=3.27.0 -author=Mark Yan, Makeblock +author=Nick B (OG : Mark Yan), School maintainer=Nick B, School sentence=Use to drive all devices provided by Makeblock company. paragraph=This library is an updated version of the MakeBlock Drive library. It is used to drive all devices provided by Makeblock company. It is based on the original MakeBlock Drive library, but has been updated to fix some issues. Feel free to pull request if you find any bugs. From 2e97c9fd68fc884e05839912f5e977dc2b624568 Mon Sep 17 00:00:00 2001 From: Nick B Date: Thu, 5 Oct 2023 13:54:23 -0400 Subject: [PATCH 14/29] Updated lib properties --- library.properties | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/library.properties b/library.properties index 15ca2f6b..31f514d3 100644 --- a/library.properties +++ b/library.properties @@ -1,9 +1,9 @@ name=MakeBlock Drive Updated -version=3.27.0 -author=Nick B (OG : Mark Yan), School +version=3.27.1 +author=Nick B (Original : Mark Yan), School maintainer=Nick B, School sentence=Use to drive all devices provided by Makeblock company. -paragraph=This library is an updated version of the MakeBlock Drive library. It is used to drive all devices provided by Makeblock company. It is based on the original MakeBlock Drive library, but has been updated to fix some issues. Feel free to pull request if you find any bugs. +paragraph=This library is an updated version of the MakeBlock Drive library. It is based on the original MakeBlock Drive library, but has been updated to fix some issues. Feel free to pull request if you find any bugs. category=Device Control url=https://github.com/nbourre/Makeblock-Libraries architectures=* \ No newline at end of file From 042fbb4a9227c95a6472485618f209ba94ce564a Mon Sep 17 00:00:00 2001 From: "Nick B (macOS)" Date: Thu, 5 Oct 2023 17:20:05 -0400 Subject: [PATCH 15/29] Added gyro default address for Auriga --- src/MeGyro.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/MeGyro.h b/src/MeGyro.h index d3730da8..50c085af 100644 --- a/src/MeGyro.h +++ b/src/MeGyro.h @@ -63,7 +63,12 @@ /* Exported macro ------------------------------------------------------------*/ #define I2C_ERROR (-1) + +#ifdef MeAuriga_H +#define GYRO_DEFAULT_ADDRESS (0x69) +#else #define GYRO_DEFAULT_ADDRESS (0x68) +#endif /** * Class: MeGyro From e5c6fbf2b5aede1849ba72087fee2deb8e40eca9 Mon Sep 17 00:00:00 2001 From: Nick B Date: Mon, 16 Oct 2023 08:55:05 -0400 Subject: [PATCH 16/29] Updated readme --- README.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 8e014617..cd3135e1 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,4 @@ -# Makeblock Library v3.27 +# Makeblock Library v3.28.0 Arduino Library for Makeblock Electronic Modules @@ -61,5 +61,6 @@ If you have a discussion about licensing issues, please contact me (myan@makeblo |Mark Yan   | 2018/05/16 | 3.2.5 | Correct copyright information.| |Vincent He | 2019/01/04 | 3.2.6 | 1.Mbot /ranger adds the function of communication variables. 2.Solve the blocking problem of 9g steering gear. 3.Solve the problem that the intelligent steering gear cannot read back the parameters. 4.Add version number function. 5.High power code motor reinforcement version query function. 6.Solve the problem of SetColor (uint8_t index, long value) function error in mergharp.cpp. 7.The mBot board cannot extinguish the RGB. First upload the program with the RGB in any color, and then upload the program with the RGB in all colors. The RGB cannot extinguish (MeRGBLed bled. CPP file). 8.In the MegaPi firmware, SLOT1 is changed to slot_num instead of parameter transmission in the command processing stepper motor.| |Vincent He | 2019/09/02 | 3.2.7 | 1.fix the problem that the electronic compass Mecompass is hung on the Orion mainboard 7 or 8 ports and communication will be hung dead. 2.fix the problem that the function getPointFast() in MeHumitureSensor.cpp does not normally output the value. 3.fix the problem that compile smartservo_test.ino firmware error report using the arduino1.6.5 environment with mBlock V3.4.12. 4.remove MeSuperVariable.cpp/MeSuperVariable.h. 5.fix the problem that ultrasonic module can only measure the maximum range of 375cm,and the maximum range of normal requirements is 400cm.| +| Nicolas Bourré | 2023/10/16 | 3.28 | 1. Added missing `gyro.getGyroZ`. 2. Compliant semver.org version number. 3. Added `gyro.resetData` function. 4. Modified the gyro address if it is an Auriga board. | ### Learn more from Makeblock official website: www.makeblock.com From 97e15e3abf135777b8c260d73233a7eace19fa8c Mon Sep 17 00:00:00 2001 From: Nick B Date: Mon, 16 Oct 2023 08:58:34 -0400 Subject: [PATCH 17/29] Added Issues section in readme --- README.md | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index cd3135e1..8c2f9dab 100644 --- a/README.md +++ b/README.md @@ -63,4 +63,7 @@ If you have a discussion about licensing issues, please contact me (myan@makeblo |Vincent He | 2019/09/02 | 3.2.7 | 1.fix the problem that the electronic compass Mecompass is hung on the Orion mainboard 7 or 8 ports and communication will be hung dead. 2.fix the problem that the function getPointFast() in MeHumitureSensor.cpp does not normally output the value. 3.fix the problem that compile smartservo_test.ino firmware error report using the arduino1.6.5 environment with mBlock V3.4.12. 4.remove MeSuperVariable.cpp/MeSuperVariable.h. 5.fix the problem that ultrasonic module can only measure the maximum range of 375cm,and the maximum range of normal requirements is 400cm.| | Nicolas Bourré | 2023/10/16 | 3.28 | 1. Added missing `gyro.getGyroZ`. 2. Compliant semver.org version number. 3. Added `gyro.resetData` function. 4. Modified the gyro address if it is an Auriga board. | -### Learn more from Makeblock official website: www.makeblock.com +# Issues + +## Remove old MakeBlock library +If you have problem with the compiler complaining of ambiguous reference to `MePort`, you may have an old version of the MakeBlock library installed. You can remove it by uninstalling the official Makeblock library via the library manager. \ No newline at end of file From 64b741c14f1c1483c74e5c401dd89eeaa7052aec Mon Sep 17 00:00:00 2001 From: Nick B Date: Mon, 16 Oct 2023 11:15:38 -0400 Subject: [PATCH 18/29] Removed MeAuriga check in MeGyro --- src/MeGyro.h | 4 ---- 1 file changed, 4 deletions(-) diff --git a/src/MeGyro.h b/src/MeGyro.h index 50c085af..e785c2ca 100644 --- a/src/MeGyro.h +++ b/src/MeGyro.h @@ -64,11 +64,7 @@ /* Exported macro ------------------------------------------------------------*/ #define I2C_ERROR (-1) -#ifdef MeAuriga_H -#define GYRO_DEFAULT_ADDRESS (0x69) -#else #define GYRO_DEFAULT_ADDRESS (0x68) -#endif /** * Class: MeGyro From 76e5b23141825dfd3111d5d61acbf607d60704dc Mon Sep 17 00:00:00 2001 From: Nick B Date: Wed, 8 Nov 2023 10:31:43 -0500 Subject: [PATCH 19/29] Added Auriga Gyro Test --- .../Auriga_MeGyroTest/Auriga_MeGyroTest.ino | 52 +++++++++++++++++++ 1 file changed, 52 insertions(+) create mode 100644 examples/Me_Gyro/Auriga_MeGyroTest/Auriga_MeGyroTest.ino diff --git a/examples/Me_Gyro/Auriga_MeGyroTest/Auriga_MeGyroTest.ino b/examples/Me_Gyro/Auriga_MeGyroTest/Auriga_MeGyroTest.ino new file mode 100644 index 00000000..800ecd53 --- /dev/null +++ b/examples/Me_Gyro/Auriga_MeGyroTest/Auriga_MeGyroTest.ino @@ -0,0 +1,52 @@ +/** + * \par + * @file Auriga_MeGyroTest.ino + * @author Nick B + * @version V1.0.0 + * @date 2023/11/08 + * @brief Description: This file test MakeBlock Auriga Gyroscope + * + * Function List: + * 1. void MeGyro::begin(void) + * 2. void MeGyro::update(void) + * 3. double MeGyro::angleX(void) + * 4. double MeGyro::angleY(void) + * 5. double MeGyro::angleZ(void) + * + * \par History: + *
+ *      
+ * + */ +#include "MeAuriga.h" + +MeGyro gyro (0, 0x69); + +void setup() +{ + Serial.begin(115200); + gyro.begin(); + Serial.println("Open the serial plotter tool!"); + for (int i = 0; i < 20; i++) { + Serial.print("."); + delay(100); + } + Serial.println("Setup done!"); +} + +void loop() +{ + gyro.update(); + + Serial.read(); + Serial.print("GyroX:"); + Serial.print(gyro.getAngleX() ); + Serial.print("GyroY:"); + Serial.print(gyro.getAngleY() ); + Serial.print("GyroZ:"); + Serial.println(gyro.getAngleZ() ); + delay(10); +} + From 239315df1c963325ddb4a2508846a79893510488 Mon Sep 17 00:00:00 2001 From: Nick B Date: Sat, 2 Dec 2023 10:51:21 -0500 Subject: [PATCH 20/29] Added a way to ignore ir by default --- src/MeIR.cpp | 12 ++++++++++++ src/MeIR.h | 1 + 2 files changed, 13 insertions(+) diff --git a/src/MeIR.cpp b/src/MeIR.cpp index 99cf9756..a2b870ff 100644 --- a/src/MeIR.cpp +++ b/src/MeIR.cpp @@ -54,6 +54,11 @@ * */ + +#define IGNORE_ME_IR + +#ifndef IGNORE_ME_IR + #include "MeIR.h" // Provides ISR @@ -702,3 +707,10 @@ boolean MeIR::keyPressed(unsigned char r) return irRead == r; } #endif // !defined(__AVR_ATmega32U4__) + +#else + +#warning "NOT AN ERROR, but IR has been disabled, remove #define IGNORE_ME_IR to enable IR" + + +#endif // !defined(IGNORE_ME_IR) \ No newline at end of file diff --git a/src/MeIR.h b/src/MeIR.h index 9dbd2633..84910e06 100644 --- a/src/MeIR.h +++ b/src/MeIR.h @@ -53,6 +53,7 @@ * * */ + #ifndef MeIR_h #define MeIR_h From 9c897af59833b30af126e2dd4ba3f349d42a0760 Mon Sep 17 00:00:00 2001 From: Nick B Date: Sat, 2 Dec 2023 10:53:09 -0500 Subject: [PATCH 21/29] comment --- src/MeIR.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/MeIR.cpp b/src/MeIR.cpp index a2b870ff..beca4b6a 100644 --- a/src/MeIR.cpp +++ b/src/MeIR.cpp @@ -50,6 +50,7 @@ * Mark Yan 2015/11/02 1.0.2 Fix bug that IRsend and IRreceive can't work at the same time. * forfish 2015/11/09 1.0.3 Add description. * Mark Yan 2015/11/16 1.0.4 add data recovery when timeout. + * Nick b 2023/12/05 1.0.5 Added an ignore define to allow the IR to be disabled. * * */ From 29ce5229a299047e71f8b7a71645ace9c85d9ff2 Mon Sep 17 00:00:00 2001 From: Nick B Date: Sat, 2 Dec 2023 11:28:40 -0500 Subject: [PATCH 22/29] Ajout de la documentation Doxygen --- src/MeSoundSensor.h => MeSoundSensor.h | 0 doc/html/_buzzer_test_8ino-example.html | 105 + doc/html/_color_loop_test_8ino-example.html | 105 + .../_d_c_motor_driver_test_8ino-example.html | 105 + doc/html/_e_e_p_r_o_m_8h_source.html | 268 ++ ...otor_change_i2_c_dev_i_d_8ino-example.html | 105 + ..._test_is_tar_pos_reached_8ino-example.html | 105 + ...coder_motor_test_move_to_8ino-example.html | 105 + ...der_motor_test_run_speed_8ino-example.html | 105 + ..._test_run_speed_and_time_8ino-example.html | 105 + ...der_motor_test_run_turns_8ino-example.html | 105 + doc/html/_indicators_test_8ino-example.html | 105 + .../_infrared_receiver_test_8ino-example.html | 105 + doc/html/_limit_switch_test_8ino-example.html | 107 + .../_line_follower_test_8ino-example.html | 105 + doc/html/_mbot_buzzer_test2_8ino-example.html | 105 + doc/html/_mbot_buzzer_test_8ino-example.html | 105 + doc/html/_me4_button_8cpp.html | 188 ++ doc/html/_me4_button_8cpp__incl.map | 48 + doc/html/_me4_button_8cpp__incl.md5 | 1 + doc/html/_me4_button_8cpp__incl.png | Bin 0 -> 47829 bytes doc/html/_me4_button_8h.html | 268 ++ doc/html/_me4_button_8h.js | 4 + doc/html/_me4_button_8h__dep__incl.map | 19 + doc/html/_me4_button_8h__dep__incl.md5 | 1 + doc/html/_me4_button_8h__dep__incl.png | Bin 0 -> 12582 bytes doc/html/_me4_button_8h__incl.map | 46 + doc/html/_me4_button_8h__incl.md5 | 1 + doc/html/_me4_button_8h__incl.png | Bin 0 -> 46456 bytes doc/html/_me4_button_8h_source.html | 180 ++ doc/html/_me4_button_test_8ino-example.html | 105 + doc/html/_me7_segment_display_8cpp.html | 241 ++ doc/html/_me7_segment_display_8cpp__incl.map | 48 + doc/html/_me7_segment_display_8cpp__incl.md5 | 1 + doc/html/_me7_segment_display_8cpp__incl.png | Bin 0 -> 48305 bytes doc/html/_me7_segment_display_8h.html | 296 ++ doc/html/_me7_segment_display_8h.js | 4 + .../_me7_segment_display_8h__dep__incl.map | 19 + .../_me7_segment_display_8h__dep__incl.md5 | 1 + .../_me7_segment_display_8h__dep__incl.png | Bin 0 -> 12914 bytes doc/html/_me7_segment_display_8h__incl.map | 46 + doc/html/_me7_segment_display_8h__incl.md5 | 1 + doc/html/_me7_segment_display_8h__incl.png | Bin 0 -> 46692 bytes doc/html/_me7_segment_display_8h_source.html | 230 ++ ..._auriga_encoder_callback_8ino-example.html | 105 + ...e__auriga_encoder_direct_8ino-example.html | 105 + ...__auriga_encoder_pid_pos_8ino-example.html | 105 + ...auriga_encoder_pid_speed_8ino-example.html | 105 + .../_me__auriga_encoder_pwm_8ino-example.html | 105 + .../_me__l_e_d_matrix_test_8ino-example.html | 105 + ...e__megapi_encoder_direct_8ino-example.html | 105 + ...__megapi_encoder_pid_pos_8ino-example.html | 105 + ...megapi_encoder_pid_speed_8ino-example.html | 105 + .../_me__megapi_encoder_pwm_8ino-example.html | 105 + doc/html/_me_auriga_8h.html | 527 ++++ doc/html/_me_auriga_8h__incl.map | 279 ++ doc/html/_me_auriga_8h__incl.md5 | 1 + doc/html/_me_auriga_8h__incl.png | Bin 0 -> 947578 bytes doc/html/_me_auriga_8h_source.html | 220 ++ doc/html/_me_base_board_8h.html | 461 +++ doc/html/_me_base_board_8h__incl.map | 250 ++ doc/html/_me_base_board_8h__incl.md5 | 1 + doc/html/_me_base_board_8h__incl.png | Bin 0 -> 780350 bytes doc/html/_me_base_board_8h_source.html | 195 ++ doc/html/_me_bluetooth_8cpp.html | 190 ++ doc/html/_me_bluetooth_8cpp__incl.map | 55 + doc/html/_me_bluetooth_8cpp__incl.md5 | 1 + doc/html/_me_bluetooth_8cpp__incl.png | Bin 0 -> 66171 bytes doc/html/_me_bluetooth_8h.html | 228 ++ doc/html/_me_bluetooth_8h.js | 4 + doc/html/_me_bluetooth_8h__dep__incl.map | 19 + doc/html/_me_bluetooth_8h__dep__incl.md5 | 1 + doc/html/_me_bluetooth_8h__dep__incl.png | Bin 0 -> 13510 bytes doc/html/_me_bluetooth_8h__incl.map | 53 + doc/html/_me_bluetooth_8h__incl.md5 | 1 + doc/html/_me_bluetooth_8h__incl.png | Bin 0 -> 64105 bytes doc/html/_me_bluetooth_8h_source.html | 150 + doc/html/_me_buzzer_8cpp.html | 202 ++ doc/html/_me_buzzer_8cpp__incl.map | 50 + doc/html/_me_buzzer_8cpp__incl.md5 | 1 + doc/html/_me_buzzer_8cpp__incl.png | Bin 0 -> 49812 bytes doc/html/_me_buzzer_8h.html | 227 ++ doc/html/_me_buzzer_8h.js | 4 + doc/html/_me_buzzer_8h__dep__incl.map | 19 + doc/html/_me_buzzer_8h__dep__incl.md5 | 1 + doc/html/_me_buzzer_8h__dep__incl.png | Bin 0 -> 13382 bytes doc/html/_me_buzzer_8h__incl.map | 46 + doc/html/_me_buzzer_8h__incl.md5 | 1 + doc/html/_me_buzzer_8h__incl.png | Bin 0 -> 46513 bytes doc/html/_me_buzzer_8h_source.html | 157 + doc/html/_me_color_sensor_8cpp.html | 213 ++ doc/html/_me_color_sensor_8cpp__incl.map | 48 + doc/html/_me_color_sensor_8cpp__incl.md5 | 1 + doc/html/_me_color_sensor_8cpp__incl.png | Bin 0 -> 47924 bytes doc/html/_me_color_sensor_8h.html | 367 +++ doc/html/_me_color_sensor_8h.js | 4 + doc/html/_me_color_sensor_8h__dep__incl.map | 15 + doc/html/_me_color_sensor_8h__dep__incl.md5 | 1 + doc/html/_me_color_sensor_8h__dep__incl.png | Bin 0 -> 9965 bytes doc/html/_me_color_sensor_8h__incl.map | 46 + doc/html/_me_color_sensor_8h__incl.md5 | 1 + doc/html/_me_color_sensor_8h__incl.png | Bin 0 -> 46663 bytes doc/html/_me_color_sensor_8h_source.html | 294 ++ .../_me_color_sensor_test_8ino-example.html | 105 + doc/html/_me_compass_8cpp.html | 198 ++ doc/html/_me_compass_8cpp__incl.map | 50 + doc/html/_me_compass_8cpp__incl.md5 | 1 + doc/html/_me_compass_8cpp__incl.png | Bin 0 -> 50001 bytes doc/html/_me_compass_8h.html | 363 +++ doc/html/_me_compass_8h.js | 5 + doc/html/_me_compass_8h__dep__incl.map | 19 + doc/html/_me_compass_8h__dep__incl.md5 | 1 + doc/html/_me_compass_8h__dep__incl.png | Bin 0 -> 13542 bytes doc/html/_me_compass_8h__incl.map | 46 + doc/html/_me_compass_8h__incl.md5 | 1 + doc/html/_me_compass_8h__incl.png | Bin 0 -> 46589 bytes doc/html/_me_compass_8h_source.html | 286 ++ doc/html/_me_compass_test_8ino-example.html | 105 + doc/html/_me_config_8h.html | 537 ++++ doc/html/_me_config_8h__dep__incl.map | 357 +++ doc/html/_me_config_8h__dep__incl.md5 | 1 + doc/html/_me_config_8h__dep__incl.png | Bin 0 -> 745762 bytes doc/html/_me_config_8h__incl.map | 27 + doc/html/_me_config_8h__incl.md5 | 1 + doc/html/_me_config_8h__incl.png | Bin 0 -> 15012 bytes doc/html/_me_config_8h_source.html | 137 + doc/html/_me_d_c_motor_8cpp.html | 192 ++ doc/html/_me_d_c_motor_8cpp__incl.map | 48 + doc/html/_me_d_c_motor_8cpp__incl.md5 | 1 + doc/html/_me_d_c_motor_8cpp__incl.png | Bin 0 -> 47719 bytes doc/html/_me_d_c_motor_8h.html | 232 ++ doc/html/_me_d_c_motor_8h.js | 4 + doc/html/_me_d_c_motor_8h__dep__incl.map | 23 + doc/html/_me_d_c_motor_8h__dep__incl.md5 | 1 + doc/html/_me_d_c_motor_8h__dep__incl.png | Bin 0 -> 17696 bytes doc/html/_me_d_c_motor_8h__incl.map | 46 + doc/html/_me_d_c_motor_8h__incl.md5 | 1 + doc/html/_me_d_c_motor_8h__incl.png | Bin 0 -> 46538 bytes doc/html/_me_d_c_motor_8h_source.html | 164 ++ doc/html/_me_e_e_p_r_o_m_8h.html | 291 ++ doc/html/_me_e_e_p_r_o_m_8h__incl.map | 45 + doc/html/_me_e_e_p_r_o_m_8h__incl.md5 | 1 + doc/html/_me_e_e_p_r_o_m_8h__incl.png | Bin 0 -> 46968 bytes doc/html/_me_e_e_p_r_o_m_8h_source.html | 166 ++ doc/html/_me_encoder_motor_8cpp.html | 319 ++ doc/html/_me_encoder_motor_8cpp.js | 4 + doc/html/_me_encoder_motor_8cpp__incl.map | 49 + doc/html/_me_encoder_motor_8cpp__incl.md5 | 1 + doc/html/_me_encoder_motor_8cpp__incl.png | Bin 0 -> 48564 bytes doc/html/_me_encoder_motor_8h.html | 228 ++ doc/html/_me_encoder_motor_8h.js | 4 + doc/html/_me_encoder_motor_8h__dep__incl.map | 19 + doc/html/_me_encoder_motor_8h__dep__incl.md5 | 1 + doc/html/_me_encoder_motor_8h__dep__incl.png | Bin 0 -> 14224 bytes doc/html/_me_encoder_motor_8h__incl.map | 44 + doc/html/_me_encoder_motor_8h__incl.md5 | 1 + doc/html/_me_encoder_motor_8h__incl.png | Bin 0 -> 40193 bytes doc/html/_me_encoder_motor_8h_source.html | 169 ++ doc/html/_me_encoder_new_8cpp.html | 284 ++ doc/html/_me_encoder_new_8cpp__incl.map | 47 + doc/html/_me_encoder_new_8cpp__incl.md5 | 1 + doc/html/_me_encoder_new_8cpp__incl.png | Bin 0 -> 48549 bytes doc/html/_me_encoder_new_8h.html | 270 ++ doc/html/_me_encoder_new_8h.js | 4 + doc/html/_me_encoder_new_8h__dep__incl.map | 19 + doc/html/_me_encoder_new_8h__dep__incl.md5 | 1 + doc/html/_me_encoder_new_8h__dep__incl.png | Bin 0 -> 14195 bytes doc/html/_me_encoder_new_8h__incl.map | 45 + doc/html/_me_encoder_new_8h__incl.md5 | 1 + doc/html/_me_encoder_new_8h__incl.png | Bin 0 -> 47003 bytes doc/html/_me_encoder_new_8h_source.html | 250 ++ doc/html/_me_encoder_on_board_8cpp.html | 186 ++ doc/html/_me_encoder_on_board_8cpp__incl.map | 11 + doc/html/_me_encoder_on_board_8cpp__incl.md5 | 1 + doc/html/_me_encoder_on_board_8cpp__incl.png | Bin 0 -> 5273 bytes doc/html/_me_encoder_on_board_8h.html | 260 ++ doc/html/_me_encoder_on_board_8h.js | 7 + .../_me_encoder_on_board_8h__dep__incl.map | 11 + .../_me_encoder_on_board_8h__dep__incl.md5 | 1 + .../_me_encoder_on_board_8h__dep__incl.png | Bin 0 -> 6624 bytes doc/html/_me_encoder_on_board_8h__incl.map | 9 + doc/html/_me_encoder_on_board_8h__incl.md5 | 1 + doc/html/_me_encoder_on_board_8h__incl.png | Bin 0 -> 4224 bytes doc/html/_me_encoder_on_board_8h_source.html | 314 ++ doc/html/_me_flame_sensor_8cpp.html | 188 ++ doc/html/_me_flame_sensor_8cpp__incl.map | 48 + doc/html/_me_flame_sensor_8cpp__incl.md5 | 1 + doc/html/_me_flame_sensor_8cpp__incl.png | Bin 0 -> 48064 bytes doc/html/_me_flame_sensor_8h.html | 235 ++ doc/html/_me_flame_sensor_8h.js | 4 + doc/html/_me_flame_sensor_8h__dep__incl.map | 19 + doc/html/_me_flame_sensor_8h__dep__incl.md5 | 1 + doc/html/_me_flame_sensor_8h__dep__incl.png | Bin 0 -> 14054 bytes doc/html/_me_flame_sensor_8h__incl.map | 46 + doc/html/_me_flame_sensor_8h__incl.md5 | 1 + doc/html/_me_flame_sensor_8h__incl.png | Bin 0 -> 46617 bytes doc/html/_me_flame_sensor_8h_source.html | 161 ++ .../_me_flame_sensor_test_8ino-example.html | 105 + doc/html/_me_gas_sensor_8cpp.html | 188 ++ doc/html/_me_gas_sensor_8cpp__incl.map | 48 + doc/html/_me_gas_sensor_8cpp__incl.md5 | 1 + doc/html/_me_gas_sensor_8cpp__incl.png | Bin 0 -> 47884 bytes doc/html/_me_gas_sensor_8h.html | 235 ++ doc/html/_me_gas_sensor_8h.js | 4 + doc/html/_me_gas_sensor_8h__dep__incl.map | 19 + doc/html/_me_gas_sensor_8h__dep__incl.md5 | 1 + doc/html/_me_gas_sensor_8h__dep__incl.png | Bin 0 -> 13470 bytes doc/html/_me_gas_sensor_8h__incl.map | 46 + doc/html/_me_gas_sensor_8h__incl.md5 | 1 + doc/html/_me_gas_sensor_8h__incl.png | Bin 0 -> 46631 bytes doc/html/_me_gas_sensor_8h_source.html | 162 ++ .../_me_gas_sensor_test_8ino-example.html | 105 + doc/html/_me_gyro_8cpp.html | 200 ++ doc/html/_me_gyro_8cpp__incl.map | 48 + doc/html/_me_gyro_8cpp__incl.md5 | 1 + doc/html/_me_gyro_8cpp__incl.png | Bin 0 -> 48148 bytes doc/html/_me_gyro_8h.html | 245 ++ doc/html/_me_gyro_8h.js | 4 + doc/html/_me_gyro_8h__dep__incl.map | 19 + doc/html/_me_gyro_8h__dep__incl.md5 | 1 + doc/html/_me_gyro_8h__dep__incl.png | Bin 0 -> 13000 bytes doc/html/_me_gyro_8h__incl.map | 46 + doc/html/_me_gyro_8h__incl.md5 | 1 + doc/html/_me_gyro_8h__incl.png | Bin 0 -> 46392 bytes doc/html/_me_gyro_8h_source.html | 213 ++ doc/html/_me_gyro_test_8ino-example.html | 105 + doc/html/_me_host_parser_8cpp.html | 227 ++ doc/html/_me_host_parser_8cpp.js | 4 + doc/html/_me_host_parser_8cpp__incl.map | 7 + doc/html/_me_host_parser_8cpp__incl.md5 | 1 + doc/html/_me_host_parser_8cpp__incl.png | Bin 0 -> 2332 bytes doc/html/_me_host_parser_8h.html | 181 ++ doc/html/_me_host_parser_8h.js | 4 + doc/html/_me_host_parser_8h__dep__incl.map | 7 + doc/html/_me_host_parser_8h__dep__incl.md5 | 1 + doc/html/_me_host_parser_8h__dep__incl.png | Bin 0 -> 3266 bytes doc/html/_me_host_parser_8h__incl.map | 5 + doc/html/_me_host_parser_8h__incl.md5 | 1 + doc/html/_me_host_parser_8h__incl.png | Bin 0 -> 1419 bytes doc/html/_me_host_parser_8h_source.html | 167 ++ doc/html/_me_humiture_sensor_8cpp.html | 196 ++ doc/html/_me_humiture_sensor_8cpp__incl.map | 48 + doc/html/_me_humiture_sensor_8cpp__incl.md5 | 1 + doc/html/_me_humiture_sensor_8cpp__incl.png | Bin 0 -> 48160 bytes doc/html/_me_humiture_sensor_8h.html | 233 ++ doc/html/_me_humiture_sensor_8h.js | 4 + .../_me_humiture_sensor_8h__dep__incl.map | 19 + .../_me_humiture_sensor_8h__dep__incl.md5 | 1 + .../_me_humiture_sensor_8h__dep__incl.png | Bin 0 -> 14878 bytes doc/html/_me_humiture_sensor_8h__incl.map | 46 + doc/html/_me_humiture_sensor_8h__incl.md5 | 1 + doc/html/_me_humiture_sensor_8h__incl.png | Bin 0 -> 46611 bytes doc/html/_me_humiture_sensor_8h_source.html | 181 ++ ...me_humiture_sensor_test1_8ino-example.html | 105 + ...me_humiture_sensor_test2_8ino-example.html | 133 + doc/html/_me_i_r_8cpp.html | 153 + doc/html/_me_i_r_8h.html | 417 +++ doc/html/_me_i_r_8h.js | 5 + doc/html/_me_i_r_8h__dep__incl.map | 5 + doc/html/_me_i_r_8h__dep__incl.md5 | 1 + doc/html/_me_i_r_8h__dep__incl.png | Bin 0 -> 1320 bytes doc/html/_me_i_r_8h__incl.map | 46 + doc/html/_me_i_r_8h__incl.md5 | 1 + doc/html/_me_i_r_8h__incl.png | Bin 0 -> 46579 bytes doc/html/_me_i_r_8h_source.html | 314 ++ doc/html/_me_infrared_receiver_8cpp.html | 198 ++ doc/html/_me_infrared_receiver_8cpp__incl.map | 55 + doc/html/_me_infrared_receiver_8cpp__incl.md5 | 1 + doc/html/_me_infrared_receiver_8cpp__incl.png | Bin 0 -> 66241 bytes doc/html/_me_infrared_receiver_8h.html | 334 +++ doc/html/_me_infrared_receiver_8h.js | 4 + .../_me_infrared_receiver_8h__dep__incl.map | 19 + .../_me_infrared_receiver_8h__dep__incl.md5 | 1 + .../_me_infrared_receiver_8h__dep__incl.png | Bin 0 -> 14338 bytes doc/html/_me_infrared_receiver_8h__incl.map | 53 + doc/html/_me_infrared_receiver_8h__incl.md5 | 1 + doc/html/_me_infrared_receiver_8h__incl.png | Bin 0 -> 64066 bytes doc/html/_me_infrared_receiver_8h_source.html | 204 ++ doc/html/_me_joystick_8cpp.html | 192 ++ doc/html/_me_joystick_8cpp__incl.map | 48 + doc/html/_me_joystick_8cpp__incl.md5 | 1 + doc/html/_me_joystick_8cpp__incl.png | Bin 0 -> 47720 bytes doc/html/_me_joystick_8h.html | 236 ++ doc/html/_me_joystick_8h.js | 4 + doc/html/_me_joystick_8h__dep__incl.map | 19 + doc/html/_me_joystick_8h__dep__incl.md5 | 1 + doc/html/_me_joystick_8h__dep__incl.png | Bin 0 -> 13207 bytes doc/html/_me_joystick_8h__incl.map | 46 + doc/html/_me_joystick_8h__incl.md5 | 1 + doc/html/_me_joystick_8h__incl.png | Bin 0 -> 46485 bytes doc/html/_me_joystick_8h_source.html | 175 ++ doc/html/_me_joystick_test_8ino-example.html | 105 + doc/html/_me_l_e_d_matrix_8cpp.html | 194 ++ doc/html/_me_l_e_d_matrix_8cpp__incl.map | 45 + doc/html/_me_l_e_d_matrix_8cpp__incl.md5 | 1 + doc/html/_me_l_e_d_matrix_8cpp__incl.png | Bin 0 -> 41161 bytes doc/html/_me_l_e_d_matrix_8h.html | 268 ++ doc/html/_me_l_e_d_matrix_8h.js | 4 + doc/html/_me_l_e_d_matrix_8h__dep__incl.map | 19 + doc/html/_me_l_e_d_matrix_8h__dep__incl.md5 | 1 + doc/html/_me_l_e_d_matrix_8h__dep__incl.png | Bin 0 -> 13817 bytes doc/html/_me_l_e_d_matrix_8h__incl.map | 41 + doc/html/_me_l_e_d_matrix_8h__incl.md5 | 1 + doc/html/_me_l_e_d_matrix_8h__incl.png | Bin 0 -> 37768 bytes doc/html/_me_l_e_d_matrix_8h_source.html | 211 ++ doc/html/_me_l_e_d_matrix_data_8h.html | 162 ++ doc/html/_me_l_e_d_matrix_data_8h.js | 5 + .../_me_l_e_d_matrix_data_8h__dep__incl.map | 5 + .../_me_l_e_d_matrix_data_8h__dep__incl.md5 | 1 + .../_me_l_e_d_matrix_data_8h__dep__incl.png | Bin 0 -> 1640 bytes doc/html/_me_l_e_d_matrix_data_8h_source.html | 251 ++ doc/html/_me_light_sensor_8cpp.html | 191 ++ doc/html/_me_light_sensor_8cpp__incl.map | 48 + doc/html/_me_light_sensor_8cpp__incl.md5 | 1 + doc/html/_me_light_sensor_8cpp__incl.png | Bin 0 -> 48027 bytes doc/html/_me_light_sensor_8h.html | 228 ++ doc/html/_me_light_sensor_8h.js | 4 + doc/html/_me_light_sensor_8h__dep__incl.map | 19 + doc/html/_me_light_sensor_8h__dep__incl.md5 | 1 + doc/html/_me_light_sensor_8h__dep__incl.png | Bin 0 -> 14054 bytes doc/html/_me_light_sensor_8h__incl.map | 46 + doc/html/_me_light_sensor_8h__incl.md5 | 1 + doc/html/_me_light_sensor_8h__incl.png | Bin 0 -> 46719 bytes doc/html/_me_light_sensor_8h_source.html | 163 ++ .../_me_light_sensor_test_8ino-example.html | 106 + ...t_sensor_test_reset_port_8ino-example.html | 106 + ...sensor_test_with_l_e_don_8ino-example.html | 105 + doc/html/_me_limit_switch_8cpp.html | 188 ++ doc/html/_me_limit_switch_8cpp__incl.map | 48 + doc/html/_me_limit_switch_8cpp__incl.md5 | 1 + doc/html/_me_limit_switch_8cpp__incl.png | Bin 0 -> 47986 bytes doc/html/_me_limit_switch_8h.html | 225 ++ doc/html/_me_limit_switch_8h.js | 4 + doc/html/_me_limit_switch_8h__dep__incl.map | 19 + doc/html/_me_limit_switch_8h__dep__incl.md5 | 1 + doc/html/_me_limit_switch_8h__dep__incl.png | Bin 0 -> 14088 bytes doc/html/_me_limit_switch_8h__incl.map | 46 + doc/html/_me_limit_switch_8h__incl.md5 | 1 + doc/html/_me_limit_switch_8h__incl.png | Bin 0 -> 46669 bytes doc/html/_me_limit_switch_8h_source.html | 159 + doc/html/_me_line_follower_8cpp.html | 189 ++ doc/html/_me_line_follower_8cpp__incl.map | 48 + doc/html/_me_line_follower_8cpp__incl.md5 | 1 + doc/html/_me_line_follower_8cpp__incl.png | Bin 0 -> 47918 bytes doc/html/_me_line_follower_8h.html | 242 ++ doc/html/_me_line_follower_8h.js | 4 + doc/html/_me_line_follower_8h__dep__incl.map | 19 + doc/html/_me_line_follower_8h__dep__incl.md5 | 1 + doc/html/_me_line_follower_8h__dep__incl.png | Bin 0 -> 14050 bytes doc/html/_me_line_follower_8h__incl.map | 46 + doc/html/_me_line_follower_8h__incl.md5 | 1 + doc/html/_me_line_follower_8h__incl.png | Bin 0 -> 46646 bytes doc/html/_me_line_follower_8h_source.html | 165 ++ doc/html/_me_m_core_8h.html | 475 +++ doc/html/_me_m_core_8h__incl.map | 269 ++ doc/html/_me_m_core_8h__incl.md5 | 1 + doc/html/_me_m_core_8h__incl.png | Bin 0 -> 871629 bytes doc/html/_me_m_core_8h_source.html | 196 ++ doc/html/_me_mbot_d_c_motor_8cpp.html | 196 ++ doc/html/_me_mbot_d_c_motor_8cpp__incl.map | 55 + doc/html/_me_mbot_d_c_motor_8cpp__incl.md5 | 1 + doc/html/_me_mbot_d_c_motor_8cpp__incl.png | Bin 0 -> 67517 bytes doc/html/_me_mbot_d_c_motor_8h.html | 221 ++ doc/html/_me_mbot_d_c_motor_8h.js | 4 + doc/html/_me_mbot_d_c_motor_8h__dep__incl.map | 7 + doc/html/_me_mbot_d_c_motor_8h__dep__incl.md5 | 1 + doc/html/_me_mbot_d_c_motor_8h__dep__incl.png | Bin 0 -> 3568 bytes doc/html/_me_mbot_d_c_motor_8h__incl.map | 53 + doc/html/_me_mbot_d_c_motor_8h__incl.md5 | 1 + doc/html/_me_mbot_d_c_motor_8h__incl.png | Bin 0 -> 65872 bytes doc/html/_me_mbot_d_c_motor_8h_source.html | 145 + doc/html/_me_mega_pi_8h.html | 576 ++++ doc/html/_me_mega_pi_8h__incl.map | 266 ++ doc/html/_me_mega_pi_8h__incl.md5 | 1 + doc/html/_me_mega_pi_8h__incl.png | Bin 0 -> 874619 bytes doc/html/_me_mega_pi_8h_source.html | 241 ++ doc/html/_me_mega_pi_d_c_motor_8cpp.html | 179 ++ doc/html/_me_mega_pi_d_c_motor_8cpp__incl.map | 36 + doc/html/_me_mega_pi_d_c_motor_8cpp__incl.md5 | 1 + doc/html/_me_mega_pi_d_c_motor_8cpp__incl.png | Bin 0 -> 27186 bytes doc/html/_me_mega_pi_d_c_motor_8h.html | 213 ++ doc/html/_me_mega_pi_d_c_motor_8h.js | 5 + .../_me_mega_pi_d_c_motor_8h__dep__incl.map | 9 + .../_me_mega_pi_d_c_motor_8h__dep__incl.md5 | 1 + .../_me_mega_pi_d_c_motor_8h__dep__incl.png | Bin 0 -> 4790 bytes doc/html/_me_mega_pi_d_c_motor_8h__incl.map | 34 + doc/html/_me_mega_pi_d_c_motor_8h__incl.md5 | 1 + doc/html/_me_mega_pi_d_c_motor_8h__incl.png | Bin 0 -> 25476 bytes doc/html/_me_mega_pi_d_c_motor_8h_source.html | 165 ++ ...e_mega_pi_d_c_motor_test_8ino-example.html | 105 + doc/html/_me_mega_pi_pro4_dc_motor_8cpp.html | 190 ++ .../_me_mega_pi_pro4_dc_motor_8cpp__incl.map | 48 + .../_me_mega_pi_pro4_dc_motor_8cpp__incl.md5 | 1 + .../_me_mega_pi_pro4_dc_motor_8cpp__incl.png | Bin 0 -> 48221 bytes doc/html/_me_mega_pi_pro4_dc_motor_8h.html | 213 ++ doc/html/_me_mega_pi_pro4_dc_motor_8h.js | 4 + ...me_mega_pi_pro4_dc_motor_8h__dep__incl.map | 5 + ...me_mega_pi_pro4_dc_motor_8h__dep__incl.md5 | 1 + ...me_mega_pi_pro4_dc_motor_8h__dep__incl.png | Bin 0 -> 1792 bytes .../_me_mega_pi_pro4_dc_motor_8h__incl.map | 46 + .../_me_mega_pi_pro4_dc_motor_8h__incl.md5 | 1 + .../_me_mega_pi_pro4_dc_motor_8h__incl.png | Bin 0 -> 46667 bytes .../_me_mega_pi_pro4_dc_motor_8h_source.html | 166 ++ doc/html/_me_mega_pi_pro_8h.html | 619 ++++ doc/html/_me_mega_pi_pro_8h__incl.map | 273 ++ doc/html/_me_mega_pi_pro_8h__incl.md5 | 1 + doc/html/_me_mega_pi_pro_8h__incl.png | Bin 0 -> 920513 bytes doc/html/_me_mega_pi_pro_8h_source.html | 262 ++ .../_me_mega_pi_pro_e_s_c_motor_8cpp.html | 191 ++ ..._me_mega_pi_pro_e_s_c_motor_8cpp__incl.map | 48 + ..._me_mega_pi_pro_e_s_c_motor_8cpp__incl.md5 | 1 + ..._me_mega_pi_pro_e_s_c_motor_8cpp__incl.png | Bin 0 -> 48256 bytes doc/html/_me_mega_pi_pro_e_s_c_motor_8h.html | 237 ++ doc/html/_me_mega_pi_pro_e_s_c_motor_8h.js | 5 + ..._mega_pi_pro_e_s_c_motor_8h__dep__incl.map | 7 + ..._mega_pi_pro_e_s_c_motor_8h__dep__incl.md5 | 1 + ..._mega_pi_pro_e_s_c_motor_8h__dep__incl.png | Bin 0 -> 3693 bytes .../_me_mega_pi_pro_e_s_c_motor_8h__incl.map | 46 + .../_me_mega_pi_pro_e_s_c_motor_8h__incl.md5 | 1 + .../_me_mega_pi_pro_e_s_c_motor_8h__incl.png | Bin 0 -> 46686 bytes ..._me_mega_pi_pro_e_s_c_motor_8h_source.html | 167 ++ ..._mega_pi_pro_e_s_c_motor_8ino-example.html | 105 + doc/html/_me_on_board_temp_8cpp.html | 206 ++ doc/html/_me_on_board_temp_8cpp__incl.map | 48 + doc/html/_me_on_board_temp_8cpp__incl.md5 | 1 + doc/html/_me_on_board_temp_8cpp__incl.png | Bin 0 -> 48119 bytes doc/html/_me_on_board_temp_8h.html | 223 ++ doc/html/_me_on_board_temp_8h.js | 4 + doc/html/_me_on_board_temp_8h__dep__incl.map | 7 + doc/html/_me_on_board_temp_8h__dep__incl.md5 | 1 + doc/html/_me_on_board_temp_8h__dep__incl.png | Bin 0 -> 3612 bytes doc/html/_me_on_board_temp_8h__incl.map | 46 + doc/html/_me_on_board_temp_8h__incl.md5 | 1 + doc/html/_me_on_board_temp_8h__incl.png | Bin 0 -> 46680 bytes doc/html/_me_on_board_temp_8h_source.html | 162 ++ .../_me_on_board_temp_test_8ino-example.html | 105 + doc/html/_me_one_wire_8cpp.html | 194 ++ doc/html/_me_one_wire_8cpp__incl.map | 36 + doc/html/_me_one_wire_8cpp__incl.md5 | 1 + doc/html/_me_one_wire_8cpp__incl.png | Bin 0 -> 27190 bytes doc/html/_me_one_wire_8h.html | 234 ++ doc/html/_me_one_wire_8h.js | 4 + doc/html/_me_one_wire_8h__dep__incl.map | 23 + doc/html/_me_one_wire_8h__dep__incl.md5 | 1 + doc/html/_me_one_wire_8h__dep__incl.png | Bin 0 -> 15875 bytes doc/html/_me_one_wire_8h__incl.map | 34 + doc/html/_me_one_wire_8h__incl.md5 | 1 + doc/html/_me_one_wire_8h__incl.png | Bin 0 -> 25654 bytes doc/html/_me_one_wire_8h_source.html | 188 ++ doc/html/_me_orion_8h.html | 468 +++ doc/html/_me_orion_8h__incl.map | 255 ++ doc/html/_me_orion_8h__incl.md5 | 1 + doc/html/_me_orion_8h__incl.png | Bin 0 -> 774358 bytes doc/html/_me_orion_8h_source.html | 197 ++ doc/html/_me_p_i_r_motion_sensor_8cpp.html | 189 ++ .../_me_p_i_r_motion_sensor_8cpp__incl.map | 48 + .../_me_p_i_r_motion_sensor_8cpp__incl.md5 | 1 + .../_me_p_i_r_motion_sensor_8cpp__incl.png | Bin 0 -> 48179 bytes doc/html/_me_p_i_r_motion_sensor_8h.html | 226 ++ doc/html/_me_p_i_r_motion_sensor_8h.js | 4 + .../_me_p_i_r_motion_sensor_8h__dep__incl.map | 19 + .../_me_p_i_r_motion_sensor_8h__dep__incl.md5 | 1 + .../_me_p_i_r_motion_sensor_8h__dep__incl.png | Bin 0 -> 13560 bytes doc/html/_me_p_i_r_motion_sensor_8h__incl.map | 46 + doc/html/_me_p_i_r_motion_sensor_8h__incl.md5 | 1 + doc/html/_me_p_i_r_motion_sensor_8h__incl.png | Bin 0 -> 46636 bytes .../_me_p_i_r_motion_sensor_8h_source.html | 158 + doc/html/_me_p_s2_8cpp.html | 205 ++ doc/html/_me_p_s2_8cpp__incl.map | 56 + doc/html/_me_p_s2_8cpp__incl.md5 | 1 + doc/html/_me_p_s2_8cpp__incl.png | Bin 0 -> 71906 bytes doc/html/_me_p_s2_8h.html | 308 ++ doc/html/_me_p_s2_8h.js | 4 + doc/html/_me_p_s2_8h__dep__incl.map | 13 + doc/html/_me_p_s2_8h__dep__incl.md5 | 1 + doc/html/_me_p_s2_8h__dep__incl.png | Bin 0 -> 7761 bytes doc/html/_me_p_s2_8h__incl.map | 53 + doc/html/_me_p_s2_8h__incl.md5 | 1 + doc/html/_me_p_s2_8h__incl.png | Bin 0 -> 61387 bytes doc/html/_me_p_s2_8h_source.html | 212 ++ doc/html/_me_p_s2_test_8ino-example.html | 105 + doc/html/_me_pm25_sensor_8cpp.html | 216 ++ doc/html/_me_pm25_sensor_8cpp__incl.map | 56 + doc/html/_me_pm25_sensor_8cpp__incl.md5 | 1 + doc/html/_me_pm25_sensor_8cpp__incl.png | Bin 0 -> 65646 bytes doc/html/_me_pm25_sensor_8h.html | 257 ++ doc/html/_me_pm25_sensor_8h.js | 6 + doc/html/_me_pm25_sensor_8h__dep__incl.map | 7 + doc/html/_me_pm25_sensor_8h__dep__incl.md5 | 1 + doc/html/_me_pm25_sensor_8h__dep__incl.png | Bin 0 -> 2946 bytes doc/html/_me_pm25_sensor_8h__incl.map | 53 + doc/html/_me_pm25_sensor_8h__incl.md5 | 1 + doc/html/_me_pm25_sensor_8h__incl.png | Bin 0 -> 64089 bytes doc/html/_me_pm25_sensor_8h_source.html | 221 ++ doc/html/_me_port_8cpp.html | 197 ++ doc/html/_me_port_8cpp__incl.map | 41 + doc/html/_me_port_8cpp__incl.md5 | 1 + doc/html/_me_port_8cpp__incl.png | Bin 0 -> 37704 bytes doc/html/_me_port_8h.html | 640 +++++ doc/html/_me_port_8h.js | 5 + doc/html/_me_port_8h__dep__incl.map | 321 +++ doc/html/_me_port_8h__dep__incl.md5 | 1 + doc/html/_me_port_8h__dep__incl.png | Bin 0 -> 466223 bytes doc/html/_me_port_8h__incl.map | 39 + doc/html/_me_port_8h__incl.md5 | 1 + doc/html/_me_port_8h__incl.png | Bin 0 -> 36331 bytes doc/html/_me_port_8h_source.html | 259 ++ doc/html/_me_potentiometer_8cpp.html | 188 ++ doc/html/_me_potentiometer_8cpp__incl.map | 48 + doc/html/_me_potentiometer_8cpp__incl.md5 | 1 + doc/html/_me_potentiometer_8cpp__incl.png | Bin 0 -> 48030 bytes doc/html/_me_potentiometer_8h.html | 225 ++ doc/html/_me_potentiometer_8h.js | 4 + doc/html/_me_potentiometer_8h__dep__incl.map | 19 + doc/html/_me_potentiometer_8h__dep__incl.md5 | 1 + doc/html/_me_potentiometer_8h__dep__incl.png | Bin 0 -> 13619 bytes doc/html/_me_potentiometer_8h__incl.map | 46 + doc/html/_me_potentiometer_8h__incl.md5 | 1 + doc/html/_me_potentiometer_8h__incl.png | Bin 0 -> 46646 bytes doc/html/_me_potentiometer_8h_source.html | 153 + doc/html/_me_pressure_sensor_8h_source.html | 177 ++ doc/html/_me_r_g_b_led_8cpp.html | 267 ++ doc/html/_me_r_g_b_led_8cpp__incl.map | 48 + doc/html/_me_r_g_b_led_8cpp__incl.md5 | 1 + doc/html/_me_r_g_b_led_8cpp__incl.png | Bin 0 -> 47851 bytes doc/html/_me_r_g_b_led_8h.html | 248 ++ doc/html/_me_r_g_b_led_8h.js | 5 + doc/html/_me_r_g_b_led_8h__dep__incl.map | 19 + doc/html/_me_r_g_b_led_8h__dep__incl.md5 | 1 + doc/html/_me_r_g_b_led_8h__dep__incl.png | Bin 0 -> 12808 bytes doc/html/_me_r_g_b_led_8h__incl.map | 46 + doc/html/_me_r_g_b_led_8h__incl.md5 | 1 + doc/html/_me_r_g_b_led_8h__incl.png | Bin 0 -> 46494 bytes doc/html/_me_r_g_b_led_8h_source.html | 209 ++ doc/html/_me_serial_8cpp.html | 203 ++ doc/html/_me_serial_8cpp__incl.map | 52 + doc/html/_me_serial_8cpp__incl.md5 | 1 + doc/html/_me_serial_8cpp__incl.png | Bin 0 -> 50482 bytes doc/html/_me_serial_8h.html | 303 ++ doc/html/_me_serial_8h.js | 4 + doc/html/_me_serial_8h__dep__incl.map | 90 + doc/html/_me_serial_8h__dep__incl.md5 | 1 + doc/html/_me_serial_8h__dep__incl.png | Bin 0 -> 102171 bytes doc/html/_me_serial_8h__incl.map | 46 + doc/html/_me_serial_8h__incl.md5 | 1 + doc/html/_me_serial_8h__incl.png | Bin 0 -> 46461 bytes doc/html/_me_serial_8h_source.html | 205 ++ .../_me_serial_receive_test_8ino-example.html | 105 + ..._me_serial_transmit_test_8ino-example.html | 105 + doc/html/_me_shield_8h.html | 459 +++ doc/html/_me_shield_8h__incl.map | 250 ++ doc/html/_me_shield_8h__incl.md5 | 1 + doc/html/_me_shield_8h__incl.png | Bin 0 -> 780699 bytes doc/html/_me_shield_8h_source.html | 196 ++ doc/html/_me_shutter_8cpp.html | 192 ++ doc/html/_me_shutter_8cpp__incl.map | 48 + doc/html/_me_shutter_8cpp__incl.md5 | 1 + doc/html/_me_shutter_8cpp__incl.png | Bin 0 -> 47867 bytes doc/html/_me_shutter_8h.html | 229 ++ doc/html/_me_shutter_8h.js | 4 + doc/html/_me_shutter_8h__dep__incl.map | 19 + doc/html/_me_shutter_8h__dep__incl.md5 | 1 + doc/html/_me_shutter_8h__dep__incl.png | Bin 0 -> 12538 bytes doc/html/_me_shutter_8h__incl.map | 46 + doc/html/_me_shutter_8h__incl.md5 | 1 + doc/html/_me_shutter_8h__incl.png | Bin 0 -> 46518 bytes doc/html/_me_shutter_8h_source.html | 167 ++ doc/html/_me_shutter_test_8ino-example.html | 105 + doc/html/_me_smart_servo_8cpp.html | 224 ++ doc/html/_me_smart_servo_8cpp__incl.map | 58 + doc/html/_me_smart_servo_8cpp__incl.md5 | 1 + doc/html/_me_smart_servo_8cpp__incl.png | Bin 0 -> 66162 bytes doc/html/_me_smart_servo_8h.html | 446 +++ doc/html/_me_smart_servo_8h.js | 8 + doc/html/_me_smart_servo_8h__dep__incl.map | 9 + doc/html/_me_smart_servo_8h__dep__incl.md5 | 1 + doc/html/_me_smart_servo_8h__dep__incl.png | Bin 0 -> 4841 bytes doc/html/_me_smart_servo_8h__incl.map | 53 + doc/html/_me_smart_servo_8h__incl.md5 | 1 + doc/html/_me_smart_servo_8h__incl.png | Bin 0 -> 64117 bytes doc/html/_me_smart_servo_8h_source.html | 354 +++ doc/html/_me_sound_sensor_8cpp.html | 144 + doc/html/_me_sound_sensor_8cpp__incl.map | 5 + doc/html/_me_sound_sensor_8cpp__incl.md5 | 1 + doc/html/_me_sound_sensor_8cpp__incl.png | Bin 0 -> 1595 bytes doc/html/_me_stepper_8cpp.html | 240 ++ doc/html/_me_stepper_8cpp.js | 7 + doc/html/_me_stepper_8cpp__incl.map | 48 + doc/html/_me_stepper_8cpp__incl.md5 | 1 + doc/html/_me_stepper_8cpp__incl.png | Bin 0 -> 44614 bytes doc/html/_me_stepper_8h.html | 245 ++ doc/html/_me_stepper_8h.js | 4 + doc/html/_me_stepper_8h__dep__incl.map | 19 + doc/html/_me_stepper_8h__dep__incl.md5 | 1 + doc/html/_me_stepper_8h__dep__incl.png | Bin 0 -> 12309 bytes doc/html/_me_stepper_8h__incl.map | 46 + doc/html/_me_stepper_8h__incl.md5 | 1 + doc/html/_me_stepper_8h__incl.png | Bin 0 -> 43364 bytes doc/html/_me_stepper_8h_source.html | 220 ++ doc/html/_me_stepper_on_board_8cpp.html | 207 ++ doc/html/_me_stepper_on_board_8cpp.js | 7 + doc/html/_me_stepper_on_board_8cpp__incl.map | 11 + doc/html/_me_stepper_on_board_8cpp__incl.md5 | 1 + doc/html/_me_stepper_on_board_8cpp__incl.png | Bin 0 -> 4954 bytes doc/html/_me_stepper_on_board_8h.html | 230 ++ doc/html/_me_stepper_on_board_8h.js | 5 + .../_me_stepper_on_board_8h__dep__incl.map | 9 + .../_me_stepper_on_board_8h__dep__incl.md5 | 1 + .../_me_stepper_on_board_8h__dep__incl.png | Bin 0 -> 4461 bytes doc/html/_me_stepper_on_board_8h__incl.map | 9 + doc/html/_me_stepper_on_board_8h__incl.md5 | 1 + doc/html/_me_stepper_on_board_8h__incl.png | Bin 0 -> 3825 bytes doc/html/_me_stepper_on_board_8h_source.html | 256 ++ doc/html/_me_temperature_8cpp.html | 195 ++ doc/html/_me_temperature_8cpp__incl.map | 54 + doc/html/_me_temperature_8cpp__incl.md5 | 1 + doc/html/_me_temperature_8cpp__incl.png | Bin 0 -> 57144 bytes doc/html/_me_temperature_8h.html | 258 ++ doc/html/_me_temperature_8h.js | 4 + doc/html/_me_temperature_8h__dep__incl.map | 19 + doc/html/_me_temperature_8h__dep__incl.md5 | 1 + doc/html/_me_temperature_8h__dep__incl.png | Bin 0 -> 12830 bytes doc/html/_me_temperature_8h__incl.map | 52 + doc/html/_me_temperature_8h__incl.md5 | 1 + doc/html/_me_temperature_8h__incl.png | Bin 0 -> 55681 bytes doc/html/_me_temperature_8h_source.html | 176 ++ doc/html/_me_touch_sensor_8cpp.html | 188 ++ doc/html/_me_touch_sensor_8cpp__incl.map | 48 + doc/html/_me_touch_sensor_8cpp__incl.md5 | 1 + doc/html/_me_touch_sensor_8cpp__incl.png | Bin 0 -> 47968 bytes doc/html/_me_touch_sensor_8h.html | 225 ++ doc/html/_me_touch_sensor_8h.js | 4 + doc/html/_me_touch_sensor_8h__dep__incl.map | 19 + doc/html/_me_touch_sensor_8h__dep__incl.md5 | 1 + doc/html/_me_touch_sensor_8h__dep__incl.png | Bin 0 -> 13070 bytes doc/html/_me_touch_sensor_8h__incl.map | 46 + doc/html/_me_touch_sensor_8h__incl.md5 | 1 + doc/html/_me_touch_sensor_8h__incl.png | Bin 0 -> 46621 bytes doc/html/_me_touch_sensor_8h_source.html | 159 + doc/html/_me_u_s_b_host_8cpp.html | 238 ++ doc/html/_me_u_s_b_host_8cpp__incl.map | 55 + doc/html/_me_u_s_b_host_8cpp__incl.md5 | 1 + doc/html/_me_u_s_b_host_8cpp__incl.png | Bin 0 -> 65242 bytes doc/html/_me_u_s_b_host_8h.html | 572 ++++ doc/html/_me_u_s_b_host_8h.js | 9 + doc/html/_me_u_s_b_host_8h__dep__incl.map | 19 + doc/html/_me_u_s_b_host_8h__dep__incl.md5 | 1 + doc/html/_me_u_s_b_host_8h__dep__incl.png | Bin 0 -> 12908 bytes doc/html/_me_u_s_b_host_8h__incl.map | 53 + doc/html/_me_u_s_b_host_8h__incl.md5 | 1 + doc/html/_me_u_s_b_host_8h__incl.png | Bin 0 -> 63096 bytes doc/html/_me_u_s_b_host_8h_source.html | 517 ++++ doc/html/_me_ultrasonic_sensor_8cpp.html | 192 ++ doc/html/_me_ultrasonic_sensor_8cpp__incl.map | 48 + doc/html/_me_ultrasonic_sensor_8cpp__incl.md5 | 1 + doc/html/_me_ultrasonic_sensor_8cpp__incl.png | Bin 0 -> 48189 bytes doc/html/_me_ultrasonic_sensor_8h.html | 236 ++ doc/html/_me_ultrasonic_sensor_8h.js | 4 + .../_me_ultrasonic_sensor_8h__dep__incl.map | 19 + .../_me_ultrasonic_sensor_8h__dep__incl.md5 | 1 + .../_me_ultrasonic_sensor_8h__dep__incl.png | Bin 0 -> 13020 bytes doc/html/_me_ultrasonic_sensor_8h__incl.map | 46 + doc/html/_me_ultrasonic_sensor_8h__incl.md5 | 1 + doc/html/_me_ultrasonic_sensor_8h__incl.png | Bin 0 -> 46626 bytes doc/html/_me_ultrasonic_sensor_8h_source.html | 166 ++ doc/html/_me_voice_8cpp.html | 196 ++ doc/html/_me_voice_8cpp__incl.map | 55 + doc/html/_me_voice_8cpp__incl.md5 | 1 + doc/html/_me_voice_8cpp__incl.png | Bin 0 -> 66195 bytes doc/html/_me_voice_8h.html | 244 ++ doc/html/_me_voice_8h.js | 4 + doc/html/_me_voice_8h__dep__incl.map | 5 + doc/html/_me_voice_8h__dep__incl.md5 | 1 + doc/html/_me_voice_8h__dep__incl.png | Bin 0 -> 1362 bytes doc/html/_me_voice_8h__incl.map | 53 + doc/html/_me_voice_8h__incl.md5 | 1 + doc/html/_me_voice_8h__incl.png | Bin 0 -> 64093 bytes doc/html/_me_voice_8h_source.html | 176 ++ doc/html/_me_voice_test_8ino-example.html | 105 + doc/html/_me_wifi_8cpp.html | 192 ++ doc/html/_me_wifi_8cpp__incl.map | 56 + doc/html/_me_wifi_8cpp__incl.md5 | 1 + doc/html/_me_wifi_8cpp__incl.png | Bin 0 -> 65237 bytes doc/html/_me_wifi_8h.html | 228 ++ doc/html/_me_wifi_8h.js | 4 + doc/html/_me_wifi_8h__dep__incl.map | 19 + doc/html/_me_wifi_8h__dep__incl.md5 | 1 + doc/html/_me_wifi_8h__dep__incl.png | Bin 0 -> 12872 bytes doc/html/_me_wifi_8h__incl.map | 53 + doc/html/_me_wifi_8h__incl.md5 | 1 + doc/html/_me_wifi_8h__incl.png | Bin 0 -> 64190 bytes doc/html/_me_wifi_8h_source.html | 150 + doc/html/_me_wifi_8ino-example.html | 105 + ...pi_on_board_stepper_test_8ino-example.html | 105 + doc/html/_number_display_8ino-example.html | 105 + doc/html/_number_flow_8ino-example.html | 105 + ...p_i_r_motion_sensor_test_8ino-example.html | 105 + doc/html/_pm25_sensor_8ino-example.html | 106 + .../_potentiometer_test_8ino-example.html | 105 + doc/html/_s_p_i_8h_source.html | 441 +++ doc/html/_servo_8h_source.html | 232 ++ doc/html/_servo_timers_8h_source.html | 165 ++ ...ooth_by_soft_serial_test_8ino-example.html | 105 + doc/html/_smart_servo_test_8ino-example.html | 105 + doc/html/_software_serial_8h_source.html | 234 ++ doc/html/_sound_sensor_test_8ino-example.html | 105 + doc/html/_temperature_test_8ino-example.html | 105 + doc/html/_test_u_s_b_hsot_8ino-example.html | 108 + doc/html/_time_display_8ino-example.html | 106 + doc/html/_touch_sensor_test_8ino-example.html | 105 + .../_ultrasonic_sensor_test_8ino-example.html | 105 + ..._white_breath_light_test_8ino-example.html | 109 + doc/html/_wire_8h_source.html | 199 ++ doc/html/annotated.html | 190 ++ doc/html/annotated_dup.js | 84 + doc/html/bc_s.png | Bin 0 -> 676 bytes doc/html/bc_sd.png | Bin 0 -> 635 bytes doc/html/class_m_bot_d_c_motor-members.html | 140 + doc/html/class_m_bot_d_c_motor.html | 285 ++ doc/html/class_m_bot_d_c_motor.js | 5 + doc/html/class_m_bot_d_c_motor.png | Bin 0 -> 623 bytes .../class_m_bot_d_c_motor__coll__graph.map | 7 + .../class_m_bot_d_c_motor__coll__graph.md5 | 1 + .../class_m_bot_d_c_motor__coll__graph.png | Bin 0 -> 1998 bytes .../class_m_bot_d_c_motor__inherit__graph.map | 7 + .../class_m_bot_d_c_motor__inherit__graph.md5 | 1 + .../class_m_bot_d_c_motor__inherit__graph.png | Bin 0 -> 1998 bytes doc/html/class_me4_button-members.html | 137 + doc/html/class_me4_button.html | 319 ++ doc/html/class_me4_button.js | 7 + doc/html/class_me4_button.png | Bin 0 -> 429 bytes doc/html/class_me4_button__coll__graph.map | 5 + doc/html/class_me4_button__coll__graph.md5 | 1 + doc/html/class_me4_button__coll__graph.png | Bin 0 -> 1261 bytes doc/html/class_me4_button__inherit__graph.map | 5 + doc/html/class_me4_button__inherit__graph.md5 | 1 + doc/html/class_me4_button__inherit__graph.png | Bin 0 -> 1261 bytes .../class_me7_segment_display-members.html | 153 + doc/html/class_me7_segment_display.html | 923 ++++++ doc/html/class_me7_segment_display.js | 24 + doc/html/class_me7_segment_display.png | Bin 0 -> 547 bytes ...class_me7_segment_display__coll__graph.map | 5 + ...class_me7_segment_display__coll__graph.md5 | 1 + ...class_me7_segment_display__coll__graph.png | Bin 0 -> 1431 bytes ...ss_me7_segment_display__inherit__graph.map | 5 + ...ss_me7_segment_display__inherit__graph.md5 | 1 + ...ss_me7_segment_display__inherit__graph.png | Bin 0 -> 1431 bytes doc/html/class_me_bluetooth-members.html | 173 ++ doc/html/class_me_bluetooth.html | 378 +++ doc/html/class_me_bluetooth.js | 5 + doc/html/class_me_bluetooth.png | Bin 0 -> 1163 bytes doc/html/class_me_bluetooth__coll__graph.map | 11 + doc/html/class_me_bluetooth__coll__graph.md5 | 1 + doc/html/class_me_bluetooth__coll__graph.png | Bin 0 -> 4768 bytes .../class_me_bluetooth__inherit__graph.map | 11 + .../class_me_bluetooth__inherit__graph.md5 | 1 + .../class_me_bluetooth__inherit__graph.png | Bin 0 -> 4768 bytes doc/html/class_me_buzzer-members.html | 141 + doc/html/class_me_buzzer.html | 476 +++ doc/html/class_me_buzzer.js | 11 + doc/html/class_me_buzzer.png | Bin 0 -> 425 bytes doc/html/class_me_buzzer__coll__graph.map | 5 + doc/html/class_me_buzzer__coll__graph.md5 | 1 + doc/html/class_me_buzzer__coll__graph.png | Bin 0 -> 1248 bytes doc/html/class_me_buzzer__inherit__graph.map | 5 + doc/html/class_me_buzzer__inherit__graph.md5 | 1 + doc/html/class_me_buzzer__inherit__graph.png | Bin 0 -> 1248 bytes doc/html/class_me_color_sensor-members.html | 159 + doc/html/class_me_color_sensor.html | 1182 ++++++++ doc/html/class_me_color_sensor.js | 28 + doc/html/class_me_color_sensor.png | Bin 0 -> 480 bytes .../class_me_color_sensor__coll__graph.map | 5 + .../class_me_color_sensor__coll__graph.md5 | 1 + .../class_me_color_sensor__coll__graph.png | Bin 0 -> 1329 bytes .../class_me_color_sensor__inherit__graph.map | 5 + .../class_me_color_sensor__inherit__graph.md5 | 1 + .../class_me_color_sensor__inherit__graph.png | Bin 0 -> 1329 bytes doc/html/class_me_compass-members.html | 144 + doc/html/class_me_compass.html | 563 ++++ doc/html/class_me_compass.js | 14 + doc/html/class_me_compass.png | Bin 0 -> 442 bytes doc/html/class_me_compass__coll__graph.map | 5 + doc/html/class_me_compass__coll__graph.md5 | 1 + doc/html/class_me_compass__coll__graph.png | Bin 0 -> 1303 bytes doc/html/class_me_compass__inherit__graph.map | 5 + doc/html/class_me_compass__inherit__graph.md5 | 1 + doc/html/class_me_compass__inherit__graph.png | Bin 0 -> 1303 bytes doc/html/class_me_d_c_motor-members.html | 138 + doc/html/class_me_d_c_motor.html | 428 +++ doc/html/class_me_d_c_motor.js | 10 + doc/html/class_me_d_c_motor.png | Bin 0 -> 631 bytes doc/html/class_me_d_c_motor__coll__graph.map | 5 + doc/html/class_me_d_c_motor__coll__graph.md5 | 1 + doc/html/class_me_d_c_motor__coll__graph.png | Bin 0 -> 1277 bytes .../class_me_d_c_motor__inherit__graph.map | 7 + .../class_me_d_c_motor__inherit__graph.md5 | 1 + .../class_me_d_c_motor__inherit__graph.png | Bin 0 -> 2005 bytes doc/html/class_me_encoder_motor-members.html | 144 + doc/html/class_me_encoder_motor.html | 611 ++++ doc/html/class_me_encoder_motor.js | 15 + doc/html/class_me_encoder_motor.png | Bin 0 -> 484 bytes .../class_me_encoder_motor__coll__graph.map | 5 + .../class_me_encoder_motor__coll__graph.md5 | 1 + .../class_me_encoder_motor__coll__graph.png | Bin 0 -> 1336 bytes ...class_me_encoder_motor__inherit__graph.map | 5 + ...class_me_encoder_motor__inherit__graph.md5 | 1 + ...class_me_encoder_motor__inherit__graph.png | Bin 0 -> 1336 bytes doc/html/class_me_encoder_new-members.html | 135 + doc/html/class_me_encoder_new.html | 1145 ++++++++ doc/html/class_me_encoder_new.js | 30 + .../class_me_encoder_on_board-members.html | 143 + doc/html/class_me_encoder_on_board.html | 1319 +++++++++ doc/html/class_me_encoder_on_board.js | 38 + doc/html/class_me_flame_sensor-members.html | 138 + doc/html/class_me_flame_sensor.html | 348 +++ doc/html/class_me_flame_sensor.js | 8 + doc/html/class_me_flame_sensor.png | Bin 0 -> 494 bytes .../class_me_flame_sensor__coll__graph.map | 5 + .../class_me_flame_sensor__coll__graph.md5 | 1 + .../class_me_flame_sensor__coll__graph.png | Bin 0 -> 1338 bytes .../class_me_flame_sensor__inherit__graph.map | 5 + .../class_me_flame_sensor__inherit__graph.md5 | 1 + .../class_me_flame_sensor__inherit__graph.png | Bin 0 -> 1338 bytes doc/html/class_me_gas_sensor-members.html | 138 + doc/html/class_me_gas_sensor.html | 348 +++ doc/html/class_me_gas_sensor.js | 8 + doc/html/class_me_gas_sensor.png | Bin 0 -> 481 bytes doc/html/class_me_gas_sensor__coll__graph.map | 5 + doc/html/class_me_gas_sensor__coll__graph.md5 | 1 + doc/html/class_me_gas_sensor__coll__graph.png | Bin 0 -> 1341 bytes .../class_me_gas_sensor__inherit__graph.map | 5 + .../class_me_gas_sensor__inherit__graph.md5 | 1 + .../class_me_gas_sensor__inherit__graph.png | Bin 0 -> 1341 bytes doc/html/class_me_gyro-members.html | 149 + doc/html/class_me_gyro.html | 727 +++++ doc/html/class_me_gyro.js | 19 + doc/html/class_me_gyro.png | Bin 0 -> 394 bytes doc/html/class_me_gyro__coll__graph.map | 5 + doc/html/class_me_gyro__coll__graph.md5 | 1 + doc/html/class_me_gyro__coll__graph.png | Bin 0 -> 1153 bytes doc/html/class_me_gyro__inherit__graph.map | 5 + doc/html/class_me_gyro__inherit__graph.md5 | 1 + doc/html/class_me_gyro__inherit__graph.png | Bin 0 -> 1153 bytes doc/html/class_me_host_parser-members.html | 116 + doc/html/class_me_host_parser.html | 357 +++ doc/html/class_me_host_parser.js | 10 + doc/html/class_me_humiture-members.html | 144 + doc/html/class_me_humiture.html | 530 ++++ doc/html/class_me_humiture.js | 14 + doc/html/class_me_humiture.png | Bin 0 -> 444 bytes doc/html/class_me_humiture__coll__graph.map | 5 + doc/html/class_me_humiture__coll__graph.md5 | 1 + doc/html/class_me_humiture__coll__graph.png | Bin 0 -> 1214 bytes .../class_me_humiture__inherit__graph.map | 5 + .../class_me_humiture__inherit__graph.md5 | 1 + .../class_me_humiture__inherit__graph.png | Bin 0 -> 1214 bytes doc/html/class_me_i_r-members.html | 129 + doc/html/class_me_i_r.html | 658 +++++ doc/html/class_me_i_r.js | 19 + .../class_me_infrared_receiver-members.html | 177 ++ doc/html/class_me_infrared_receiver.html | 515 ++++ doc/html/class_me_infrared_receiver.js | 10 + doc/html/class_me_infrared_receiver.png | Bin 0 -> 1253 bytes ...lass_me_infrared_receiver__coll__graph.map | 11 + ...lass_me_infrared_receiver__coll__graph.md5 | 1 + ...lass_me_infrared_receiver__coll__graph.png | Bin 0 -> 4857 bytes ...s_me_infrared_receiver__inherit__graph.map | 11 + ...s_me_infrared_receiver__inherit__graph.md5 | 1 + ...s_me_infrared_receiver__inherit__graph.png | Bin 0 -> 4857 bytes doc/html/class_me_joystick-members.html | 142 + doc/html/class_me_joystick.html | 470 +++ doc/html/class_me_joystick.js | 12 + doc/html/class_me_joystick.png | Bin 0 -> 444 bytes doc/html/class_me_joystick__coll__graph.map | 5 + doc/html/class_me_joystick__coll__graph.md5 | 1 + doc/html/class_me_joystick__coll__graph.png | Bin 0 -> 1232 bytes .../class_me_joystick__inherit__graph.map | 5 + .../class_me_joystick__inherit__graph.md5 | 1 + .../class_me_joystick__inherit__graph.png | Bin 0 -> 1232 bytes doc/html/class_me_l_e_d_matrix-members.html | 143 + doc/html/class_me_l_e_d_matrix.html | 603 ++++ doc/html/class_me_l_e_d_matrix.js | 14 + doc/html/class_me_l_e_d_matrix.png | Bin 0 -> 448 bytes .../class_me_l_e_d_matrix__coll__graph.map | 5 + .../class_me_l_e_d_matrix__coll__graph.md5 | 1 + .../class_me_l_e_d_matrix__coll__graph.png | Bin 0 -> 1320 bytes .../class_me_l_e_d_matrix__inherit__graph.map | 5 + .../class_me_l_e_d_matrix__inherit__graph.md5 | 1 + .../class_me_l_e_d_matrix__inherit__graph.png | Bin 0 -> 1320 bytes doc/html/class_me_light_sensor-members.html | 139 + doc/html/class_me_light_sensor.html | 392 +++ doc/html/class_me_light_sensor.js | 9 + doc/html/class_me_light_sensor.png | Bin 0 -> 499 bytes .../class_me_light_sensor__coll__graph.map | 5 + .../class_me_light_sensor__coll__graph.md5 | 1 + .../class_me_light_sensor__coll__graph.png | Bin 0 -> 1356 bytes .../class_me_light_sensor__inherit__graph.map | 5 + .../class_me_light_sensor__inherit__graph.md5 | 1 + .../class_me_light_sensor__inherit__graph.png | Bin 0 -> 1356 bytes doc/html/class_me_limit_switch-members.html | 138 + doc/html/class_me_limit_switch.html | 353 +++ doc/html/class_me_limit_switch.js | 8 + doc/html/class_me_limit_switch.png | Bin 0 -> 476 bytes .../class_me_limit_switch__coll__graph.map | 5 + .../class_me_limit_switch__coll__graph.md5 | 1 + .../class_me_limit_switch__coll__graph.png | Bin 0 -> 1332 bytes .../class_me_limit_switch__inherit__graph.map | 5 + .../class_me_limit_switch__inherit__graph.md5 | 1 + .../class_me_limit_switch__inherit__graph.png | Bin 0 -> 1332 bytes doc/html/class_me_line_follower-members.html | 139 + doc/html/class_me_line_follower.html | 377 +++ doc/html/class_me_line_follower.js | 9 + doc/html/class_me_line_follower.png | Bin 0 -> 483 bytes .../class_me_line_follower__coll__graph.map | 5 + .../class_me_line_follower__coll__graph.md5 | 1 + .../class_me_line_follower__coll__graph.png | Bin 0 -> 1251 bytes ...class_me_line_follower__inherit__graph.map | 5 + ...class_me_line_follower__inherit__graph.md5 | 1 + ...class_me_line_follower__inherit__graph.png | Bin 0 -> 1251 bytes .../class_me_mega_pi_d_c_motor-members.html | 115 + doc/html/class_me_mega_pi_d_c_motor.html | 371 +++ doc/html/class_me_mega_pi_d_c_motor.js | 10 + ...lass_me_mega_pi_pro4_dc_motor-members.html | 138 + doc/html/class_me_mega_pi_pro4_dc_motor.html | 426 +++ doc/html/class_me_mega_pi_pro4_dc_motor.js | 10 + doc/html/class_me_mega_pi_pro4_dc_motor.png | Bin 0 -> 601 bytes ..._me_mega_pi_pro4_dc_motor__coll__graph.map | 5 + ..._me_mega_pi_pro4_dc_motor__coll__graph.md5 | 1 + ..._me_mega_pi_pro4_dc_motor__coll__graph.png | Bin 0 -> 1413 bytes ..._mega_pi_pro4_dc_motor__inherit__graph.map | 5 + ..._mega_pi_pro4_dc_motor__inherit__graph.md5 | 1 + ..._mega_pi_pro4_dc_motor__inherit__graph.png | Bin 0 -> 1413 bytes ...ss_me_mega_pi_pro_e_s_c_motor-members.html | 115 + .../class_me_mega_pi_pro_e_s_c_motor.html | 346 +++ doc/html/class_me_mega_pi_pro_e_s_c_motor.js | 10 + doc/html/class_me_on_board_temp-members.html | 138 + doc/html/class_me_on_board_temp.html | 336 +++ doc/html/class_me_on_board_temp.js | 8 + doc/html/class_me_on_board_temp.png | Bin 0 -> 509 bytes .../class_me_on_board_temp__coll__graph.map | 5 + .../class_me_on_board_temp__coll__graph.md5 | 1 + .../class_me_on_board_temp__coll__graph.png | Bin 0 -> 1379 bytes ...class_me_on_board_temp__inherit__graph.map | 5 + ...class_me_on_board_temp__inherit__graph.md5 | 1 + ...class_me_on_board_temp__inherit__graph.png | Bin 0 -> 1379 bytes doc/html/class_me_one_wire-members.html | 125 + doc/html/class_me_one_wire.html | 651 +++++ doc/html/class_me_one_wire.js | 20 + .../class_me_p_i_r_motion_sensor-members.html | 138 + doc/html/class_me_p_i_r_motion_sensor.html | 359 +++ doc/html/class_me_p_i_r_motion_sensor.js | 8 + doc/html/class_me_p_i_r_motion_sensor.png | Bin 0 -> 502 bytes ...ss_me_p_i_r_motion_sensor__coll__graph.map | 5 + ...ss_me_p_i_r_motion_sensor__coll__graph.md5 | 1 + ...ss_me_p_i_r_motion_sensor__coll__graph.png | Bin 0 -> 1417 bytes ...me_p_i_r_motion_sensor__inherit__graph.map | 5 + ...me_p_i_r_motion_sensor__inherit__graph.md5 | 1 + ...me_p_i_r_motion_sensor__inherit__graph.png | Bin 0 -> 1417 bytes doc/html/class_me_p_s2-members.html | 179 ++ doc/html/class_me_p_s2.html | 628 ++++ doc/html/class_me_p_s2.js | 12 + doc/html/class_me_p_s2.png | Bin 0 -> 1155 bytes doc/html/class_me_p_s2__coll__graph.map | 11 + doc/html/class_me_p_s2__coll__graph.md5 | 1 + doc/html/class_me_p_s2__coll__graph.png | Bin 0 -> 4752 bytes doc/html/class_me_p_s2__inherit__graph.map | 11 + doc/html/class_me_p_s2__inherit__graph.md5 | 1 + doc/html/class_me_p_s2__inherit__graph.png | Bin 0 -> 4752 bytes doc/html/class_me_pm25_sensor-members.html | 196 ++ doc/html/class_me_pm25_sensor.html | 1158 ++++++++ doc/html/class_me_pm25_sensor.js | 28 + doc/html/class_me_pm25_sensor.png | Bin 0 -> 1227 bytes .../class_me_pm25_sensor__coll__graph.map | 11 + .../class_me_pm25_sensor__coll__graph.md5 | 1 + .../class_me_pm25_sensor__coll__graph.png | Bin 0 -> 4841 bytes .../class_me_pm25_sensor__inherit__graph.map | 11 + .../class_me_pm25_sensor__inherit__graph.md5 | 1 + .../class_me_pm25_sensor__inherit__graph.png | Bin 0 -> 4841 bytes doc/html/class_me_port-members.html | 133 + doc/html/class_me_port.html | 924 ++++++ doc/html/class_me_port.js | 28 + doc/html/class_me_port.png | Bin 0 -> 9968 bytes doc/html/class_me_port__inherit__graph.map | 75 + doc/html/class_me_port__inherit__graph.md5 | 1 + doc/html/class_me_port__inherit__graph.png | Bin 0 -> 107537 bytes doc/html/class_me_potentiometer-members.html | 137 + doc/html/class_me_potentiometer.html | 317 ++ doc/html/class_me_potentiometer.js | 7 + doc/html/class_me_potentiometer.png | Bin 0 -> 489 bytes .../class_me_potentiometer__coll__graph.map | 5 + .../class_me_potentiometer__coll__graph.md5 | 1 + .../class_me_potentiometer__coll__graph.png | Bin 0 -> 1342 bytes ...class_me_potentiometer__inherit__graph.map | 5 + ...class_me_potentiometer__inherit__graph.md5 | 1 + ...class_me_potentiometer__inherit__graph.png | Bin 0 -> 1342 bytes .../class_me_pressure_sensor-members.html | 116 + doc/html/class_me_pressure_sensor.html | 138 + doc/html/class_me_r_g_b_led-members.html | 148 + doc/html/class_me_r_g_b_led.html | 826 ++++++ doc/html/class_me_r_g_b_led.js | 20 + doc/html/class_me_r_g_b_led.png | Bin 0 -> 437 bytes doc/html/class_me_r_g_b_led__coll__graph.map | 5 + doc/html/class_me_r_g_b_led__coll__graph.md5 | 1 + doc/html/class_me_r_g_b_led__coll__graph.png | Bin 0 -> 1294 bytes .../class_me_r_g_b_led__inherit__graph.map | 5 + .../class_me_r_g_b_led__inherit__graph.md5 | 1 + .../class_me_r_g_b_led__inherit__graph.png | Bin 0 -> 1294 bytes doc/html/class_me_serial-members.html | 171 ++ doc/html/class_me_serial.html | 755 +++++ doc/html/class_me_serial.js | 17 + doc/html/class_me_serial.png | Bin 0 -> 2898 bytes doc/html/class_me_serial__coll__graph.map | 9 + doc/html/class_me_serial__coll__graph.md5 | 1 + doc/html/class_me_serial__coll__graph.png | Bin 0 -> 3911 bytes doc/html/class_me_serial__inherit__graph.map | 23 + doc/html/class_me_serial__inherit__graph.md5 | 1 + doc/html/class_me_serial__inherit__graph.png | Bin 0 -> 14467 bytes doc/html/class_me_shutter-members.html | 141 + doc/html/class_me_shutter.html | 432 +++ doc/html/class_me_shutter.js | 11 + doc/html/class_me_shutter.png | Bin 0 -> 424 bytes doc/html/class_me_shutter__coll__graph.map | 5 + doc/html/class_me_shutter__coll__graph.md5 | 1 + doc/html/class_me_shutter__coll__graph.png | Bin 0 -> 1190 bytes doc/html/class_me_shutter__inherit__graph.map | 5 + doc/html/class_me_shutter__inherit__graph.md5 | 1 + doc/html/class_me_shutter__inherit__graph.png | Bin 0 -> 1190 bytes doc/html/class_me_smart_servo-members.html | 200 ++ doc/html/class_me_smart_servo.html | 1424 +++++++++ doc/html/class_me_smart_servo.js | 32 + doc/html/class_me_smart_servo.png | Bin 0 -> 1194 bytes .../class_me_smart_servo__coll__graph.map | 11 + .../class_me_smart_servo__coll__graph.md5 | 1 + .../class_me_smart_servo__coll__graph.png | Bin 0 -> 4821 bytes .../class_me_smart_servo__inherit__graph.map | 11 + .../class_me_smart_servo__inherit__graph.md5 | 1 + .../class_me_smart_servo__inherit__graph.png | Bin 0 -> 4821 bytes doc/html/class_me_sound_sensor.html | 115 + doc/html/class_me_stepper-members.html | 155 + doc/html/class_me_stepper.html | 839 ++++++ doc/html/class_me_stepper.js | 23 + doc/html/class_me_stepper.png | Bin 0 -> 440 bytes doc/html/class_me_stepper__coll__graph.map | 5 + doc/html/class_me_stepper__coll__graph.md5 | 1 + doc/html/class_me_stepper__coll__graph.png | Bin 0 -> 1273 bytes doc/html/class_me_stepper__inherit__graph.map | 5 + doc/html/class_me_stepper__inherit__graph.md5 | 1 + doc/html/class_me_stepper__inherit__graph.png | Bin 0 -> 1273 bytes .../class_me_stepper_on_board-members.html | 135 + doc/html/class_me_stepper_on_board.html | 1027 +++++++ doc/html/class_me_stepper_on_board.js | 30 + doc/html/class_me_temperature-members.html | 138 + doc/html/class_me_temperature.html | 421 +++ doc/html/class_me_temperature.js | 10 + doc/html/class_me_temperature.png | Bin 0 -> 492 bytes .../class_me_temperature__coll__graph.map | 5 + .../class_me_temperature__coll__graph.md5 | 1 + .../class_me_temperature__coll__graph.png | Bin 0 -> 1270 bytes .../class_me_temperature__inherit__graph.map | 5 + .../class_me_temperature__inherit__graph.md5 | 1 + .../class_me_temperature__inherit__graph.png | Bin 0 -> 1270 bytes doc/html/class_me_touch_sensor-members.html | 138 + doc/html/class_me_touch_sensor.html | 353 +++ doc/html/class_me_touch_sensor.js | 8 + doc/html/class_me_touch_sensor.png | Bin 0 -> 485 bytes .../class_me_touch_sensor__coll__graph.map | 5 + .../class_me_touch_sensor__coll__graph.md5 | 1 + .../class_me_touch_sensor__coll__graph.png | Bin 0 -> 1258 bytes .../class_me_touch_sensor__inherit__graph.map | 5 + .../class_me_touch_sensor__inherit__graph.md5 | 1 + .../class_me_touch_sensor__inherit__graph.png | Bin 0 -> 1258 bytes doc/html/class_me_u_s_b_host-members.html | 145 + doc/html/class_me_u_s_b_host.html | 425 +++ doc/html/class_me_u_s_b_host.js | 10 + doc/html/class_me_u_s_b_host.png | Bin 0 -> 435 bytes doc/html/class_me_u_s_b_host__coll__graph.map | 5 + doc/html/class_me_u_s_b_host__coll__graph.md5 | 1 + doc/html/class_me_u_s_b_host__coll__graph.png | Bin 0 -> 1228 bytes .../class_me_u_s_b_host__inherit__graph.map | 5 + .../class_me_u_s_b_host__inherit__graph.md5 | 1 + .../class_me_u_s_b_host__inherit__graph.png | Bin 0 -> 1228 bytes .../class_me_ultrasonic_sensor-members.html | 139 + doc/html/class_me_ultrasonic_sensor.html | 379 +++ doc/html/class_me_ultrasonic_sensor.js | 9 + doc/html/class_me_ultrasonic_sensor.png | Bin 0 -> 518 bytes ...lass_me_ultrasonic_sensor__coll__graph.map | 5 + ...lass_me_ultrasonic_sensor__coll__graph.md5 | 1 + ...lass_me_ultrasonic_sensor__coll__graph.png | Bin 0 -> 1407 bytes ...s_me_ultrasonic_sensor__inherit__graph.map | 5 + ...s_me_ultrasonic_sensor__inherit__graph.md5 | 1 + ...s_me_ultrasonic_sensor__inherit__graph.png | Bin 0 -> 1407 bytes doc/html/class_me_voice-members.html | 175 ++ doc/html/class_me_voice.html | 488 ++++ doc/html/class_me_voice.js | 9 + doc/html/class_me_voice.png | Bin 0 -> 1163 bytes doc/html/class_me_voice__coll__graph.map | 11 + doc/html/class_me_voice__coll__graph.md5 | 1 + doc/html/class_me_voice__coll__graph.png | Bin 0 -> 4746 bytes doc/html/class_me_voice__inherit__graph.map | 11 + doc/html/class_me_voice__inherit__graph.md5 | 1 + doc/html/class_me_voice__inherit__graph.png | Bin 0 -> 4746 bytes doc/html/class_me_wifi-members.html | 173 ++ doc/html/class_me_wifi.html | 378 +++ doc/html/class_me_wifi.js | 5 + doc/html/class_me_wifi.png | Bin 0 -> 1131 bytes doc/html/class_me_wifi__coll__graph.map | 11 + doc/html/class_me_wifi__coll__graph.md5 | 1 + doc/html/class_me_wifi__coll__graph.png | Bin 0 -> 4693 bytes doc/html/class_me_wifi__inherit__graph.map | 11 + doc/html/class_me_wifi__inherit__graph.md5 | 1 + doc/html/class_me_wifi__inherit__graph.png | Bin 0 -> 4693 bytes doc/html/class_mecolor.html | 117 + doc/html/class_s_p_i_class-members.html | 122 + doc/html/class_s_p_i_class.html | 158 + doc/html/class_s_p_i_settings-members.html | 111 + doc/html/class_s_p_i_settings.html | 126 + doc/html/class_servo-members.html | 117 + doc/html/class_servo.html | 140 + doc/html/class_software_serial-members.html | 123 + doc/html/class_software_serial.html | 278 ++ doc/html/class_software_serial.png | Bin 0 -> 2771 bytes .../class_software_serial__coll__graph.map | 5 + .../class_software_serial__coll__graph.md5 | 1 + .../class_software_serial__coll__graph.png | Bin 0 -> 1352 bytes .../class_software_serial__inherit__graph.map | 21 + .../class_software_serial__inherit__graph.md5 | 1 + .../class_software_serial__inherit__graph.png | Bin 0 -> 12810 bytes doc/html/class_two_wire-members.html | 135 + doc/html/class_two_wire.html | 214 ++ doc/html/class_two_wire.png | Bin 0 -> 382 bytes doc/html/class_two_wire__coll__graph.map | 5 + doc/html/class_two_wire__coll__graph.md5 | 1 + doc/html/class_two_wire__coll__graph.png | Bin 0 -> 1173 bytes doc/html/class_two_wire__inherit__graph.map | 5 + doc/html/class_two_wire__inherit__graph.md5 | 1 + doc/html/class_two_wire__inherit__graph.png | Bin 0 -> 1173 bytes doc/html/classes.html | 135 + doc/html/closed.png | Bin 0 -> 132 bytes .../dir_0619a8f54b4fad7043a6de45be8fde0b.html | 137 + .../dir_0619a8f54b4fad7043a6de45be8fde0b.js | 10 + ...r_0619a8f54b4fad7043a6de45be8fde0b_dep.map | 5 + ...r_0619a8f54b4fad7043a6de45be8fde0b_dep.md5 | 1 + ...r_0619a8f54b4fad7043a6de45be8fde0b_dep.png | Bin 0 -> 1192 bytes .../dir_3643b276fb9490c80d50926eae963c39.html | 415 +++ .../dir_3643b276fb9490c80d50926eae963c39.js | 105 + .../dir_5f3ac822815499ba28918a50b5949c2d.html | 121 + .../dir_5f3ac822815499ba28918a50b5949c2d.js | 4 + ...r_5f3ac822815499ba28918a50b5949c2d_dep.map | 4 + ...r_5f3ac822815499ba28918a50b5949c2d_dep.md5 | 1 + ...r_5f3ac822815499ba28918a50b5949c2d_dep.png | Bin 0 -> 933 bytes .../dir_64e73385a8b7738563c26ce10415b58d.html | 127 + .../dir_64e73385a8b7738563c26ce10415b58d.js | 10 + .../dir_68267d1309a1af8e8297ef4c3efbcdba.html | 420 +++ .../dir_68267d1309a1af8e8297ef4c3efbcdba.js | 106 + .../dir_8ceffd4ee35c3518d4e8bdc7e638efe8.html | 106 + .../dir_8ceffd4ee35c3518d4e8bdc7e638efe8.js | 4 + .../dir_9b7846f2027e73718d3ad8e9e45ae6f0.html | 112 + .../dir_9b7846f2027e73718d3ad8e9e45ae6f0.js | 4 + .../dir_aa34f34d6add6a95738b68d2f2b128dc.html | 106 + .../dir_aa34f34d6add6a95738b68d2f2b128dc.js | 4 + .../dir_afb59ca96f269ed3ae4886598dd661d7.html | 106 + .../dir_afb59ca96f269ed3ae4886598dd661d7.js | 4 + .../dir_c11a2e8b7f18769bb813191fb9c7b9de.html | 106 + .../dir_c11a2e8b7f18769bb813191fb9c7b9de.js | 4 + .../dir_db69409d93ff26edeeb565aee0626b58.html | 106 + .../dir_db69409d93ff26edeeb565aee0626b58.js | 4 + .../dir_e6bb53534ac0e427887cf7a94c0c004e.html | 106 + .../dir_e6bb53534ac0e427887cf7a94c0c004e.js | 4 + .../dir_eedf9c315589113fcab5c9c13bb437c6.html | 112 + .../dir_eedf9c315589113fcab5c9c13bb437c6.js | 4 + doc/html/doc.svg | 12 + doc/html/docd.svg | 12 + doc/html/doxygen.css | 2045 +++++++++++++ doc/html/doxygen.svg | 28 + doc/html/dynsections.js | 192 ++ doc/html/examples.html | 168 ++ doc/html/examples.js | 64 + doc/html/files.html | 221 ++ doc/html/files_dup.js | 4 + doc/html/folderclosed.svg | 11 + doc/html/folderclosedd.svg | 11 + doc/html/folderopen.svg | 17 + doc/html/folderopend.svg | 12 + doc/html/functions.html | 108 + doc/html/functions_a.html | 115 + doc/html/functions_b.html | 109 + doc/html/functions_c.html | 117 + doc/html/functions_d.html | 121 + doc/html/functions_dup.js | 25 + doc/html/functions_e.html | 112 + doc/html/functions_f.html | 110 + doc/html/functions_func.html | 115 + doc/html/functions_func.js | 24 + doc/html/functions_func_b.html | 109 + doc/html/functions_func_c.html | 117 + doc/html/functions_func_d.html | 121 + doc/html/functions_func_e.html | 112 + doc/html/functions_func_f.html | 110 + doc/html/functions_func_g.html | 152 + doc/html/functions_func_h.html | 108 + doc/html/functions_func_i.html | 111 + doc/html/functions_func_k.html | 107 + doc/html/functions_func_l.html | 110 + doc/html/functions_func_m.html | 158 + doc/html/functions_func_n.html | 107 + doc/html/functions_func_o.html | 110 + doc/html/functions_func_p.html | 120 + doc/html/functions_func_r.html | 159 + doc/html/functions_func_s.html | 169 ++ doc/html/functions_func_t.html | 118 + doc/html/functions_func_u.html | 109 + doc/html/functions_func_w.html | 112 + doc/html/functions_func_~.html | 108 + doc/html/functions_g.html | 152 + doc/html/functions_h.html | 108 + doc/html/functions_i.html | 111 + doc/html/functions_k.html | 107 + doc/html/functions_l.html | 110 + doc/html/functions_m.html | 158 + doc/html/functions_n.html | 107 + doc/html/functions_o.html | 110 + doc/html/functions_p.html | 120 + doc/html/functions_r.html | 159 + doc/html/functions_s.html | 171 ++ doc/html/functions_t.html | 118 + doc/html/functions_u.html | 109 + doc/html/functions_vars.html | 108 + doc/html/functions_w.html | 112 + doc/html/functions_~.html | 108 + doc/html/globals.html | 109 + doc/html/globals_enum.html | 105 + doc/html/globals_eval.html | 106 + doc/html/globals_func.html | 106 + doc/html/graph_legend.html | 165 ++ doc/html/graph_legend.md5 | 1 + doc/html/graph_legend.png | Bin 0 -> 13473 bytes doc/html/hierarchy.html | 194 ++ doc/html/hierarchy.js | 91 + doc/html/index.html | 141 + doc/html/inherit_graph_0.map | 3 + doc/html/inherit_graph_0.md5 | 1 + doc/html/inherit_graph_0.png | Bin 0 -> 662 bytes doc/html/inherit_graph_1.map | 3 + doc/html/inherit_graph_1.md5 | 1 + doc/html/inherit_graph_1.png | Bin 0 -> 732 bytes doc/html/inherit_graph_10.map | 3 + doc/html/inherit_graph_10.md5 | 1 + doc/html/inherit_graph_10.png | Bin 0 -> 367 bytes doc/html/inherit_graph_11.map | 3 + doc/html/inherit_graph_11.md5 | 1 + doc/html/inherit_graph_11.png | Bin 0 -> 507 bytes doc/html/inherit_graph_12.map | 3 + doc/html/inherit_graph_12.md5 | 1 + doc/html/inherit_graph_12.png | Bin 0 -> 429 bytes doc/html/inherit_graph_13.map | 3 + doc/html/inherit_graph_13.md5 | 1 + doc/html/inherit_graph_13.png | Bin 0 -> 932 bytes doc/html/inherit_graph_14.map | 3 + doc/html/inherit_graph_14.md5 | 1 + doc/html/inherit_graph_14.png | Bin 0 -> 765 bytes doc/html/inherit_graph_15.map | 3 + doc/html/inherit_graph_15.md5 | 1 + doc/html/inherit_graph_15.png | Bin 0 -> 513 bytes doc/html/inherit_graph_16.map | 3 + doc/html/inherit_graph_16.md5 | 1 + doc/html/inherit_graph_16.png | Bin 0 -> 374 bytes doc/html/inherit_graph_17.map | 3 + doc/html/inherit_graph_17.md5 | 1 + doc/html/inherit_graph_17.png | Bin 0 -> 486 bytes doc/html/inherit_graph_18.map | 3 + doc/html/inherit_graph_18.md5 | 1 + doc/html/inherit_graph_18.png | Bin 0 -> 542 bytes doc/html/inherit_graph_19.map | 3 + doc/html/inherit_graph_19.md5 | 1 + doc/html/inherit_graph_19.png | Bin 0 -> 511 bytes doc/html/inherit_graph_2.map | 3 + doc/html/inherit_graph_2.md5 | 1 + doc/html/inherit_graph_2.png | Bin 0 -> 655 bytes doc/html/inherit_graph_20.map | 3 + doc/html/inherit_graph_20.md5 | 1 + doc/html/inherit_graph_20.png | Bin 0 -> 474 bytes doc/html/inherit_graph_21.map | 3 + doc/html/inherit_graph_21.md5 | 1 + doc/html/inherit_graph_21.png | Bin 0 -> 566 bytes doc/html/inherit_graph_22.map | 3 + doc/html/inherit_graph_22.md5 | 1 + doc/html/inherit_graph_22.png | Bin 0 -> 476 bytes doc/html/inherit_graph_23.map | 3 + doc/html/inherit_graph_23.md5 | 1 + doc/html/inherit_graph_23.png | Bin 0 -> 344 bytes doc/html/inherit_graph_24.map | 3 + doc/html/inherit_graph_24.md5 | 1 + doc/html/inherit_graph_24.png | Bin 0 -> 558 bytes doc/html/inherit_graph_25.map | 3 + doc/html/inherit_graph_25.md5 | 1 + doc/html/inherit_graph_25.png | Bin 0 -> 607 bytes doc/html/inherit_graph_26.map | 3 + doc/html/inherit_graph_26.md5 | 1 + doc/html/inherit_graph_26.png | Bin 0 -> 460 bytes doc/html/inherit_graph_27.map | 81 + doc/html/inherit_graph_27.md5 | 1 + doc/html/inherit_graph_27.png | Bin 0 -> 120179 bytes doc/html/inherit_graph_28.map | 3 + doc/html/inherit_graph_28.md5 | 1 + doc/html/inherit_graph_28.png | Bin 0 -> 464 bytes doc/html/inherit_graph_29.map | 3 + doc/html/inherit_graph_29.md5 | 1 + doc/html/inherit_graph_29.png | Bin 0 -> 527 bytes doc/html/inherit_graph_3.map | 3 + doc/html/inherit_graph_3.md5 | 1 + doc/html/inherit_graph_3.png | Bin 0 -> 673 bytes doc/html/inherit_graph_30.map | 3 + doc/html/inherit_graph_30.md5 | 1 + doc/html/inherit_graph_30.png | Bin 0 -> 489 bytes doc/html/inherit_graph_31.map | 3 + doc/html/inherit_graph_31.md5 | 1 + doc/html/inherit_graph_31.png | Bin 0 -> 559 bytes doc/html/inherit_graph_32.map | 3 + doc/html/inherit_graph_32.md5 | 1 + doc/html/inherit_graph_32.png | Bin 0 -> 449 bytes doc/html/inherit_graph_33.map | 3 + doc/html/inherit_graph_33.md5 | 1 + doc/html/inherit_graph_33.png | Bin 0 -> 572 bytes doc/html/inherit_graph_34.map | 3 + doc/html/inherit_graph_34.md5 | 1 + doc/html/inherit_graph_34.png | Bin 0 -> 523 bytes doc/html/inherit_graph_35.map | 3 + doc/html/inherit_graph_35.md5 | 1 + doc/html/inherit_graph_35.png | Bin 0 -> 362 bytes doc/html/inherit_graph_36.map | 3 + doc/html/inherit_graph_36.md5 | 1 + doc/html/inherit_graph_36.png | Bin 0 -> 518 bytes doc/html/inherit_graph_37.map | 3 + doc/html/inherit_graph_37.md5 | 1 + doc/html/inherit_graph_37.png | Bin 0 -> 381 bytes doc/html/inherit_graph_38.map | 3 + doc/html/inherit_graph_38.md5 | 1 + doc/html/inherit_graph_38.png | Bin 0 -> 435 bytes doc/html/inherit_graph_39.map | 3 + doc/html/inherit_graph_39.md5 | 1 + doc/html/inherit_graph_39.png | Bin 0 -> 419 bytes doc/html/inherit_graph_4.map | 3 + doc/html/inherit_graph_4.md5 | 1 + doc/html/inherit_graph_4.png | Bin 0 -> 646 bytes doc/html/inherit_graph_40.map | 3 + doc/html/inherit_graph_40.md5 | 1 + doc/html/inherit_graph_40.png | Bin 0 -> 461 bytes doc/html/inherit_graph_41.map | 3 + doc/html/inherit_graph_41.md5 | 1 + doc/html/inherit_graph_41.png | Bin 0 -> 499 bytes doc/html/inherit_graph_42.map | 3 + doc/html/inherit_graph_42.md5 | 1 + doc/html/inherit_graph_42.png | Bin 0 -> 569 bytes doc/html/inherit_graph_5.map | 3 + doc/html/inherit_graph_5.md5 | 1 + doc/html/inherit_graph_5.png | Bin 0 -> 550 bytes doc/html/inherit_graph_6.map | 3 + doc/html/inherit_graph_6.md5 | 1 + doc/html/inherit_graph_6.png | Bin 0 -> 751 bytes doc/html/inherit_graph_7.map | 3 + doc/html/inherit_graph_7.md5 | 1 + doc/html/inherit_graph_7.png | Bin 0 -> 374 bytes doc/html/inherit_graph_8.map | 3 + doc/html/inherit_graph_8.md5 | 1 + doc/html/inherit_graph_8.png | Bin 0 -> 480 bytes doc/html/inherit_graph_9.map | 3 + doc/html/inherit_graph_9.md5 | 1 + doc/html/inherit_graph_9.png | Bin 0 -> 337 bytes doc/html/inherits.html | 402 +++ doc/html/jquery.js | 34 + doc/html/menu.js | 136 + doc/html/menudata.js | 85 + doc/html/minus.svg | 8 + doc/html/minusd.svg | 8 + doc/html/nav_f.png | Bin 0 -> 153 bytes doc/html/nav_fd.png | Bin 0 -> 169 bytes doc/html/nav_g.png | Bin 0 -> 95 bytes doc/html/nav_h.png | Bin 0 -> 98 bytes doc/html/nav_hd.png | Bin 0 -> 114 bytes doc/html/navtree.css | 149 + doc/html/navtree.js | 559 ++++ doc/html/navtreedata.js | 61 + doc/html/navtreeindex0.js | 253 ++ doc/html/navtreeindex1.js | 253 ++ doc/html/navtreeindex2.js | 253 ++ doc/html/navtreeindex3.js | 148 + doc/html/open.png | Bin 0 -> 123 bytes doc/html/plus.svg | 9 + doc/html/plusd.svg | 9 + doc/html/resize.js | 155 + doc/html/search/all_0.js | 10 + doc/html/search/all_1.js | 14 + doc/html/search/all_10.js | 56 + doc/html/search/all_11.js | 76 + doc/html/search/all_12.js | 16 + doc/html/search/all_13.js | 6 + doc/html/search/all_14.js | 9 + doc/html/search/all_15.js | 5 + doc/html/search/all_2.js | 6 + doc/html/search/all_3.js | 18 + doc/html/search/all_4.js | 23 + doc/html/search/all_5.js | 13 + doc/html/search/all_6.js | 9 + doc/html/search/all_7.js | 49 + doc/html/search/all_8.js | 5 + doc/html/search/all_9.js | 9 + doc/html/search/all_a.js | 4 + doc/html/search/all_b.js | 10 + doc/html/search/all_c.js | 166 ++ doc/html/search/all_d.js | 4 + doc/html/search/all_e.js | 8 + doc/html/search/all_f.js | 20 + doc/html/search/classes_0.js | 8 + doc/html/search/classes_1.js | 6 + doc/html/search/classes_2.js | 7 + doc/html/search/classes_3.js | 4 + doc/html/search/classes_4.js | 5 + doc/html/search/classes_5.js | 56 + doc/html/search/classes_6.js | 6 + doc/html/search/classes_7.js | 12 + doc/html/search/classes_8.js | 4 + doc/html/search/close.svg | 18 + doc/html/search/enums_0.js | 4 + doc/html/search/enumvalues_0.js | 5 + doc/html/search/files_0.js | 104 + doc/html/search/functions_0.js | 12 + doc/html/search/functions_1.js | 6 + doc/html/search/functions_10.js | 64 + doc/html/search/functions_11.js | 15 + doc/html/search/functions_12.js | 6 + doc/html/search/functions_13.js | 9 + doc/html/search/functions_14.js | 5 + doc/html/search/functions_2.js | 15 + doc/html/search/functions_3.js | 18 + doc/html/search/functions_4.js | 9 + doc/html/search/functions_5.js | 7 + doc/html/search/functions_6.js | 49 + doc/html/search/functions_7.js | 5 + doc/html/search/functions_8.js | 8 + doc/html/search/functions_9.js | 4 + doc/html/search/functions_a.js | 7 + doc/html/search/functions_b.js | 56 + doc/html/search/functions_c.js | 4 + doc/html/search/functions_d.js | 7 + doc/html/search/functions_e.js | 17 + doc/html/search/functions_f.js | 56 + doc/html/search/mag.svg | 24 + doc/html/search/mag_d.svg | 24 + doc/html/search/mag_sel.svg | 31 + doc/html/search/mag_seld.svg | 31 + doc/html/search/pages_0.js | 4 + doc/html/search/pages_1.js | 4 + doc/html/search/pages_2.js | 4 + doc/html/search/pages_3.js | 4 + doc/html/search/search.css | 291 ++ doc/html/search/search.js | 840 ++++++ doc/html/search/searchdata.js | 36 + doc/html/search/variables_0.js | 5 + doc/html/search/variables_1.js | 5 + doc/html/splitbar.png | Bin 0 -> 314 bytes doc/html/splitbard.png | Bin 0 -> 282 bytes ...__c_o_n_f_i_g___d_escript_o_r-members.html | 116 + ...__u_s_b___c_o_n_f_i_g___d_escript_o_r.html | 140 + ...i_g___d_escript_o_r___l_o_n_g-members.html | 111 + ...c_o_n_f_i_g___d_escript_o_r___l_o_n_g.html | 139 + ...__d_escript_o_r___l_o_n_g__coll__graph.map | 9 + ...__d_escript_o_r___l_o_n_g__coll__graph.md5 | 1 + ...__d_escript_o_r___l_o_n_g__coll__graph.png | Bin 0 -> 6041 bytes ...__d_e_v_i_c_e___d_escript_o_r-members.html | 122 + ...__u_s_b___d_e_v_i_c_e___d_escript_o_r.html | 158 + ...n_d_p_o_i_n_t___d_escript_o_r-members.html | 114 + ...s_b___e_n_d_p_o_i_n_t___d_escript_o_r.html | 134 + ...__i_n_t_e_r_f___d_escript_o_r-members.html | 117 + ...__u_s_b___i_n_t_e_r_f___d_escript_o_r.html | 143 + .../struct_cmd__list__tab__type-members.html | 111 + doc/html/struct_cmd__list__tab__type.html | 125 + ...ass___calibration___parameter-members.html | 116 + ...uct_compass___calibration___parameter.html | 140 + .../struct_e_e_p_r_o_m_class-members.html | 117 + doc/html/struct_e_e_p_r_o_m_class.html | 145 + doc/html/struct_e_e_ptr-members.html | 118 + doc/html/struct_e_e_ptr.html | 176 ++ doc/html/struct_e_e_ptr.js | 4 + doc/html/struct_e_e_ref-members.html | 129 + doc/html/struct_e_e_ref.html | 235 ++ doc/html/struct_e_e_ref.js | 5 + .../struct_encoder__port__type-members.html | 113 + doc/html/struct_encoder__port__type.html | 131 + ...number___font__3x8___type_def-members.html | 109 + ...clock___number___font__3x8___type_def.html | 119 + ...matrix___font__6x8___type_def-members.html | 110 + ...l_e_d___matrix___font__6x8___type_def.html | 122 + .../struct_me___encoder__type-members.html | 124 + doc/html/struct_me___encoder__type.html | 174 ++ ...struct_me___encoder__type__coll__graph.map | 5 + ...struct_me___encoder__type__coll__graph.md5 | 1 + ...struct_me___encoder__type__coll__graph.png | Bin 0 -> 1891 bytes doc/html/struct_me_port___sig-members.html | 110 + doc/html/struct_me_port___sig.html | 126 + doc/html/struct_p_i_d__internal-members.html | 116 + doc/html/struct_p_i_d__internal.html | 140 + ...uct_p_m25_d_a_t_a_s_t_r_u_c_t-members.html | 123 + .../struct_p_m25_d_a_t_a_s_t_r_u_c_t.html | 161 ++ doc/html/struct_servo_pin__t-members.html | 110 + doc/html/struct_servo_pin__t.html | 122 + doc/html/structc_r_g_b-members.html | 111 + doc/html/structc_r_g_b.html | 132 + doc/html/structirparams__t-members.html | 114 + doc/html/structirparams__t.html | 134 + doc/html/structmega_pi__slot-members.html | 109 + doc/html/structmega_pi__slot.html | 119 + doc/html/structmegapi__dc__type-members.html | 111 + doc/html/structmegapi__dc__type.html | 125 + .../structmegapipro__esc__type-members.html | 109 + doc/html/structmegapipro__esc__type.html | 119 + .../structservo__device__type-members.html | 113 + doc/html/structservo__device__type.html | 131 + doc/html/structservo__t-members.html | 110 + doc/html/structservo__t.html | 132 + doc/html/structservo__t__coll__graph.map | 5 + doc/html/structservo__t__coll__graph.md5 | 1 + doc/html/structservo__t__coll__graph.png | Bin 0 -> 1359 bytes .../structsysex__message__type-members.html | 111 + doc/html/structsysex__message__type.html | 125 + doc/html/sync_off.png | Bin 0 -> 853 bytes doc/html/sync_on.png | Bin 0 -> 845 bytes doc/html/tab_a.png | Bin 0 -> 142 bytes doc/html/tab_ad.png | Bin 0 -> 135 bytes doc/html/tab_b.png | Bin 0 -> 169 bytes doc/html/tab_bd.png | Bin 0 -> 173 bytes doc/html/tab_h.png | Bin 0 -> 177 bytes doc/html/tab_hd.png | Bin 0 -> 180 bytes doc/html/tab_s.png | Bin 0 -> 184 bytes doc/html/tab_sd.png | Bin 0 -> 188 bytes doc/html/tabs.css | 1 + doc/html/twi_8h_source.html | 165 ++ .../union_p_m25_d_a_t_a_u_i_n_o-members.html | 110 + doc/html/union_p_m25_d_a_t_a_u_i_n_o.html | 132 + ...ion_p_m25_d_a_t_a_u_i_n_o__coll__graph.map | 5 + ...ion_p_m25_d_a_t_a_u_i_n_o__coll__graph.md5 | 1 + ...ion_p_m25_d_a_t_a_u_i_n_o__coll__graph.png | Bin 0 -> 1691 bytes doc/html/unionsysex__message-members.html | 110 + doc/html/unionsysex__message.html | 132 + doc/html/unionsysex__message__coll__graph.map | 5 + doc/html/unionsysex__message__coll__graph.md5 | 1 + doc/html/unionsysex__message__coll__graph.png | Bin 0 -> 1709 bytes doc/latex/Makefile | 27 + doc/latex/_buzzer_test_8ino-example.tex | 6 + doc/latex/_color_loop_test_8ino-example.tex | 6 + .../_d_c_motor_driver_test_8ino-example.tex | 6 + doc/latex/_e_e_p_r_o_m_8h_source.tex | 150 + ...motor_change_i2_c_dev_i_d_8ino-example.tex | 6 + ...r_test_is_tar_pos_reached_8ino-example.tex | 6 + ...ncoder_motor_test_move_to_8ino-example.tex | 6 + ...oder_motor_test_run_speed_8ino-example.tex | 6 + ...r_test_run_speed_and_time_8ino-example.tex | 6 + ...oder_motor_test_run_turns_8ino-example.tex | 6 + doc/latex/_indicators_test_8ino-example.tex | 6 + .../_infrared_receiver_test_8ino-example.tex | 6 + doc/latex/_limit_switch_test_8ino-example.tex | 8 + .../_line_follower_test_8ino-example.tex | 6 + doc/latex/_mbot_buzzer_test2_8ino-example.tex | 6 + doc/latex/_mbot_buzzer_test_8ino-example.tex | 6 + doc/latex/_me4_button_8cpp.tex | 64 + doc/latex/_me4_button_8cpp__incl.md5 | 1 + doc/latex/_me4_button_8cpp__incl.pdf | Bin 0 -> 24436 bytes doc/latex/_me4_button_8h.tex | 123 + doc/latex/_me4_button_8h__dep__incl.md5 | 1 + doc/latex/_me4_button_8h__dep__incl.pdf | Bin 0 -> 18358 bytes doc/latex/_me4_button_8h__incl.md5 | 1 + doc/latex/_me4_button_8h__incl.pdf | Bin 0 -> 24359 bytes doc/latex/_me4_button_8h_source.tex | 67 + doc/latex/_me4_button_test_8ino-example.tex | 6 + doc/latex/_me7_segment_display_8cpp.tex | 112 + doc/latex/_me7_segment_display_8cpp__incl.md5 | 1 + doc/latex/_me7_segment_display_8cpp__incl.pdf | Bin 0 -> 24149 bytes doc/latex/_me7_segment_display_8h.tex | 151 + .../_me7_segment_display_8h__dep__incl.md5 | 1 + .../_me7_segment_display_8h__dep__incl.pdf | Bin 0 -> 19504 bytes doc/latex/_me7_segment_display_8h__incl.md5 | 1 + doc/latex/_me7_segment_display_8h__incl.pdf | Bin 0 -> 24065 bytes doc/latex/_me7_segment_display_8h_source.tex | 109 + ...__auriga_encoder_callback_8ino-example.tex | 6 + ...me__auriga_encoder_direct_8ino-example.tex | 6 + ...e__auriga_encoder_pid_pos_8ino-example.tex | 6 + ..._auriga_encoder_pid_speed_8ino-example.tex | 6 + .../_me__auriga_encoder_pwm_8ino-example.tex | 6 + .../_me__l_e_d_matrix_test_8ino-example.tex | 6 + ...me__megapi_encoder_direct_8ino-example.tex | 6 + ...e__megapi_encoder_pid_pos_8ino-example.tex | 6 + ..._megapi_encoder_pid_speed_8ino-example.tex | 6 + .../_me__megapi_encoder_pwm_8ino-example.tex | 6 + doc/latex/_me_auriga_8h.tex | 159 + doc/latex/_me_auriga_8h__incl.md5 | 1 + doc/latex/_me_auriga_8h__incl.pdf | Bin 0 -> 47369 bytes doc/latex/_me_auriga_8h_source.tex | 77 + doc/latex/_me_base_board_8h.tex | 126 + doc/latex/_me_base_board_8h__incl.md5 | 1 + doc/latex/_me_base_board_8h__incl.pdf | Bin 0 -> 43780 bytes doc/latex/_me_base_board_8h_source.tex | 59 + doc/latex/_me_bluetooth_8cpp.tex | 57 + doc/latex/_me_bluetooth_8cpp__incl.md5 | 1 + doc/latex/_me_bluetooth_8cpp__incl.pdf | Bin 0 -> 24587 bytes doc/latex/_me_bluetooth_8h.tex | 75 + doc/latex/_me_bluetooth_8h__dep__incl.md5 | 1 + doc/latex/_me_bluetooth_8h__dep__incl.pdf | Bin 0 -> 17996 bytes doc/latex/_me_bluetooth_8h__incl.md5 | 1 + doc/latex/_me_bluetooth_8h__incl.pdf | Bin 0 -> 24495 bytes doc/latex/_me_bluetooth_8h_source.tex | 37 + doc/latex/_me_buzzer_8cpp.tex | 73 + doc/latex/_me_buzzer_8cpp__incl.md5 | 1 + doc/latex/_me_buzzer_8cpp__incl.pdf | Bin 0 -> 24599 bytes doc/latex/_me_buzzer_8h.tex | 83 + doc/latex/_me_buzzer_8h__dep__incl.md5 | 1 + doc/latex/_me_buzzer_8h__dep__incl.pdf | Bin 0 -> 18149 bytes doc/latex/_me_buzzer_8h__incl.md5 | 1 + doc/latex/_me_buzzer_8h__incl.pdf | Bin 0 -> 24400 bytes doc/latex/_me_buzzer_8h_source.tex | 42 + doc/latex/_me_color_sensor_8cpp.tex | 89 + doc/latex/_me_color_sensor_8cpp__incl.md5 | 1 + doc/latex/_me_color_sensor_8cpp__incl.pdf | Bin 0 -> 23697 bytes doc/latex/_me_color_sensor_8h.tex | 225 ++ doc/latex/_me_color_sensor_8h__dep__incl.md5 | 1 + doc/latex/_me_color_sensor_8h__dep__incl.pdf | Bin 0 -> 16708 bytes doc/latex/_me_color_sensor_8h__incl.md5 | 1 + doc/latex/_me_color_sensor_8h__incl.pdf | Bin 0 -> 23619 bytes doc/latex/_me_color_sensor_8h_source.tex | 160 ++ .../_me_color_sensor_test_8ino-example.tex | 6 + doc/latex/_me_compass_8cpp.tex | 72 + doc/latex/_me_compass_8cpp__incl.md5 | 1 + doc/latex/_me_compass_8cpp__incl.pdf | Bin 0 -> 23827 bytes doc/latex/_me_compass_8h.tex | 218 ++ doc/latex/_me_compass_8h__dep__incl.md5 | 1 + doc/latex/_me_compass_8h__dep__incl.pdf | Bin 0 -> 18187 bytes doc/latex/_me_compass_8h__incl.md5 | 1 + doc/latex/_me_compass_8h__incl.pdf | Bin 0 -> 23613 bytes doc/latex/_me_compass_8h_source.tex | 164 ++ doc/latex/_me_compass_test_8ino-example.tex | 6 + doc/latex/_me_config_8h.tex | 74 + doc/latex/_me_config_8h__dep__incl.md5 | 1 + doc/latex/_me_config_8h__dep__incl.pdf | Bin 0 -> 50035 bytes doc/latex/_me_config_8h__incl.md5 | 1 + doc/latex/_me_config_8h__incl.pdf | Bin 0 -> 22140 bytes doc/latex/_me_config_8h_source.tex | 32 + doc/latex/_me_d_c_motor_8cpp.tex | 68 + doc/latex/_me_d_c_motor_8cpp__incl.md5 | 1 + doc/latex/_me_d_c_motor_8cpp__incl.pdf | Bin 0 -> 23942 bytes doc/latex/_me_d_c_motor_8h.tex | 84 + doc/latex/_me_d_c_motor_8h__dep__incl.md5 | 1 + doc/latex/_me_d_c_motor_8h__dep__incl.pdf | Bin 0 -> 18808 bytes doc/latex/_me_d_c_motor_8h__incl.md5 | 1 + doc/latex/_me_d_c_motor_8h__incl.pdf | Bin 0 -> 23866 bytes doc/latex/_me_d_c_motor_8h_source.tex | 49 + doc/latex/_me_e_e_p_r_o_m_8h.tex | 164 ++ doc/latex/_me_e_e_p_r_o_m_8h__incl.md5 | 1 + doc/latex/_me_e_e_p_r_o_m_8h__incl.pdf | Bin 0 -> 23561 bytes doc/latex/_me_e_e_p_r_o_m_8h_source.tex | 59 + doc/latex/_me_encoder_motor_8cpp.tex | 162 ++ doc/latex/_me_encoder_motor_8cpp__incl.md5 | 1 + doc/latex/_me_encoder_motor_8cpp__incl.pdf | Bin 0 -> 24001 bytes doc/latex/_me_encoder_motor_8h.tex | 86 + doc/latex/_me_encoder_motor_8h__dep__incl.md5 | 1 + doc/latex/_me_encoder_motor_8h__dep__incl.pdf | Bin 0 -> 18130 bytes doc/latex/_me_encoder_motor_8h__incl.md5 | 1 + doc/latex/_me_encoder_motor_8h__incl.pdf | Bin 0 -> 23452 bytes doc/latex/_me_encoder_motor_8h_source.tex | 48 + doc/latex/_me_encoder_new_8cpp.tex | 158 + doc/latex/_me_encoder_new_8cpp__incl.md5 | 1 + doc/latex/_me_encoder_new_8cpp__incl.pdf | Bin 0 -> 23973 bytes doc/latex/_me_encoder_new_8h.tex | 126 + doc/latex/_me_encoder_new_8h__dep__incl.md5 | 1 + doc/latex/_me_encoder_new_8h__dep__incl.pdf | Bin 0 -> 19156 bytes doc/latex/_me_encoder_new_8h__incl.md5 | 1 + doc/latex/_me_encoder_new_8h__incl.pdf | Bin 0 -> 23894 bytes doc/latex/_me_encoder_new_8h_source.tex | 115 + doc/latex/_me_encoder_on_board_8cpp.tex | 99 + doc/latex/_me_encoder_on_board_8cpp__incl.md5 | 1 + doc/latex/_me_encoder_on_board_8cpp__incl.pdf | Bin 0 -> 16902 bytes doc/latex/_me_encoder_on_board_8h.tex | 158 + .../_me_encoder_on_board_8h__dep__incl.md5 | 1 + .../_me_encoder_on_board_8h__dep__incl.pdf | Bin 0 -> 16318 bytes doc/latex/_me_encoder_on_board_8h__incl.md5 | 1 + doc/latex/_me_encoder_on_board_8h__incl.pdf | Bin 0 -> 16815 bytes doc/latex/_me_encoder_on_board_8h_source.tex | 163 ++ doc/latex/_me_flame_sensor_8cpp.tex | 64 + doc/latex/_me_flame_sensor_8cpp__incl.md5 | 1 + doc/latex/_me_flame_sensor_8cpp__incl.pdf | Bin 0 -> 23797 bytes doc/latex/_me_flame_sensor_8h.tex | 90 + doc/latex/_me_flame_sensor_8h__dep__incl.md5 | 1 + doc/latex/_me_flame_sensor_8h__dep__incl.pdf | Bin 0 -> 18342 bytes doc/latex/_me_flame_sensor_8h__incl.md5 | 1 + doc/latex/_me_flame_sensor_8h__incl.pdf | Bin 0 -> 23723 bytes doc/latex/_me_flame_sensor_8h_source.tex | 47 + .../_me_flame_sensor_test_8ino-example.tex | 6 + doc/latex/_me_gas_sensor_8cpp.tex | 64 + doc/latex/_me_gas_sensor_8cpp__incl.md5 | 1 + doc/latex/_me_gas_sensor_8cpp__incl.pdf | Bin 0 -> 24064 bytes doc/latex/_me_gas_sensor_8h.tex | 90 + doc/latex/_me_gas_sensor_8h__dep__incl.md5 | 1 + doc/latex/_me_gas_sensor_8h__dep__incl.pdf | Bin 0 -> 18084 bytes doc/latex/_me_gas_sensor_8h__incl.md5 | 1 + doc/latex/_me_gas_sensor_8h__incl.pdf | Bin 0 -> 24007 bytes doc/latex/_me_gas_sensor_8h_source.tex | 48 + .../_me_gas_sensor_test_8ino-example.tex | 6 + doc/latex/_me_gyro_8cpp.tex | 76 + doc/latex/_me_gyro_8cpp__incl.md5 | 1 + doc/latex/_me_gyro_8cpp__incl.pdf | Bin 0 -> 24067 bytes doc/latex/_me_gyro_8h.tex | 100 + doc/latex/_me_gyro_8h__dep__incl.md5 | 1 + doc/latex/_me_gyro_8h__dep__incl.pdf | Bin 0 -> 18673 bytes doc/latex/_me_gyro_8h__incl.md5 | 1 + doc/latex/_me_gyro_8h__incl.pdf | Bin 0 -> 24006 bytes doc/latex/_me_gyro_8h_source.tex | 89 + doc/latex/_me_gyro_test_8ino-example.tex | 6 + doc/latex/_me_host_parser_8cpp.tex | 130 + doc/latex/_me_host_parser_8cpp__incl.md5 | 1 + doc/latex/_me_host_parser_8cpp__incl.pdf | Bin 0 -> 15275 bytes doc/latex/_me_host_parser_8h.tex | 89 + doc/latex/_me_host_parser_8h__dep__incl.md5 | 1 + doc/latex/_me_host_parser_8h__dep__incl.pdf | Bin 0 -> 14401 bytes doc/latex/_me_host_parser_8h__incl.md5 | 1 + doc/latex/_me_host_parser_8h__incl.pdf | Bin 0 -> 14801 bytes doc/latex/_me_host_parser_8h_source.tex | 52 + doc/latex/_me_humiture_sensor_8cpp.tex | 72 + doc/latex/_me_humiture_sensor_8cpp__incl.md5 | 1 + doc/latex/_me_humiture_sensor_8cpp__incl.pdf | Bin 0 -> 23930 bytes doc/latex/_me_humiture_sensor_8h.tex | 89 + .../_me_humiture_sensor_8h__dep__incl.md5 | 1 + .../_me_humiture_sensor_8h__dep__incl.pdf | Bin 0 -> 18721 bytes doc/latex/_me_humiture_sensor_8h__incl.md5 | 1 + doc/latex/_me_humiture_sensor_8h__incl.pdf | Bin 0 -> 23832 bytes doc/latex/_me_humiture_sensor_8h_source.tex | 60 + ..._me_humiture_sensor_test1_8ino-example.tex | 6 + ..._me_humiture_sensor_test2_8ino-example.tex | 21 + doc/latex/_me_i_r_8cpp.tex | 72 + doc/latex/_me_i_r_8h.tex | 273 ++ doc/latex/_me_i_r_8h__dep__incl.md5 | 1 + doc/latex/_me_i_r_8h__dep__incl.pdf | Bin 0 -> 12562 bytes doc/latex/_me_i_r_8h__incl.md5 | 1 + doc/latex/_me_i_r_8h__incl.pdf | Bin 0 -> 23619 bytes doc/latex/_me_i_r_8h_source.tex | 185 ++ doc/latex/_me_infrared_receiver_8cpp.tex | 67 + .../_me_infrared_receiver_8cpp__incl.md5 | 1 + .../_me_infrared_receiver_8cpp__incl.pdf | Bin 0 -> 24256 bytes doc/latex/_me_infrared_receiver_8h.tex | 183 ++ .../_me_infrared_receiver_8h__dep__incl.md5 | 1 + .../_me_infrared_receiver_8h__dep__incl.pdf | Bin 0 -> 19179 bytes doc/latex/_me_infrared_receiver_8h__incl.md5 | 1 + doc/latex/_me_infrared_receiver_8h__incl.pdf | Bin 0 -> 24190 bytes doc/latex/_me_infrared_receiver_8h_source.tex | 86 + doc/latex/_me_joystick_8cpp.tex | 68 + doc/latex/_me_joystick_8cpp__incl.md5 | 1 + doc/latex/_me_joystick_8cpp__incl.pdf | Bin 0 -> 24450 bytes doc/latex/_me_joystick_8h.tex | 91 + doc/latex/_me_joystick_8h__dep__incl.md5 | 1 + doc/latex/_me_joystick_8h__dep__incl.pdf | Bin 0 -> 19337 bytes doc/latex/_me_joystick_8h__incl.md5 | 1 + doc/latex/_me_joystick_8h__incl.pdf | Bin 0 -> 24384 bytes doc/latex/_me_joystick_8h_source.tex | 56 + doc/latex/_me_joystick_test_8ino-example.tex | 6 + doc/latex/_me_l_e_d_matrix_8cpp.tex | 73 + doc/latex/_me_l_e_d_matrix_8cpp__incl.md5 | 1 + doc/latex/_me_l_e_d_matrix_8cpp__incl.pdf | Bin 0 -> 24246 bytes doc/latex/_me_l_e_d_matrix_8h.tex | 127 + doc/latex/_me_l_e_d_matrix_8h__dep__incl.md5 | 1 + doc/latex/_me_l_e_d_matrix_8h__dep__incl.pdf | Bin 0 -> 18963 bytes doc/latex/_me_l_e_d_matrix_8h__incl.md5 | 1 + doc/latex/_me_l_e_d_matrix_8h__incl.pdf | Bin 0 -> 24060 bytes doc/latex/_me_l_e_d_matrix_8h_source.tex | 92 + doc/latex/_me_l_e_d_matrix_data_8h.tex | 74 + .../_me_l_e_d_matrix_data_8h__dep__incl.md5 | 1 + .../_me_l_e_d_matrix_data_8h__dep__incl.pdf | Bin 0 -> 13864 bytes doc/latex/_me_l_e_d_matrix_data_8h_source.tex | 140 + doc/latex/_me_light_sensor_8cpp.tex | 67 + doc/latex/_me_light_sensor_8cpp__incl.md5 | 1 + doc/latex/_me_light_sensor_8cpp__incl.pdf | Bin 0 -> 23824 bytes doc/latex/_me_light_sensor_8h.tex | 84 + doc/latex/_me_light_sensor_8h__dep__incl.md5 | 1 + doc/latex/_me_light_sensor_8h__dep__incl.pdf | Bin 0 -> 18121 bytes doc/latex/_me_light_sensor_8h__incl.md5 | 1 + doc/latex/_me_light_sensor_8h__incl.pdf | Bin 0 -> 23741 bytes doc/latex/_me_light_sensor_8h_source.tex | 48 + .../_me_light_sensor_test_8ino-example.tex | 7 + ...ht_sensor_test_reset_port_8ino-example.tex | 7 + ..._sensor_test_with_l_e_don_8ino-example.tex | 6 + doc/latex/_me_limit_switch_8cpp.tex | 64 + doc/latex/_me_limit_switch_8cpp__incl.md5 | 1 + doc/latex/_me_limit_switch_8cpp__incl.pdf | Bin 0 -> 23835 bytes doc/latex/_me_limit_switch_8h.tex | 81 + doc/latex/_me_limit_switch_8h__dep__incl.md5 | 1 + doc/latex/_me_limit_switch_8h__dep__incl.pdf | Bin 0 -> 19582 bytes doc/latex/_me_limit_switch_8h__incl.md5 | 1 + doc/latex/_me_limit_switch_8h__incl.pdf | Bin 0 -> 23753 bytes doc/latex/_me_limit_switch_8h_source.tex | 46 + doc/latex/_me_line_follower_8cpp.tex | 65 + doc/latex/_me_line_follower_8cpp__incl.md5 | 1 + doc/latex/_me_line_follower_8cpp__incl.pdf | Bin 0 -> 23928 bytes doc/latex/_me_line_follower_8h.tex | 97 + doc/latex/_me_line_follower_8h__dep__incl.md5 | 1 + doc/latex/_me_line_follower_8h__dep__incl.pdf | Bin 0 -> 18930 bytes doc/latex/_me_line_follower_8h__incl.md5 | 1 + doc/latex/_me_line_follower_8h__incl.pdf | Bin 0 -> 23842 bytes doc/latex/_me_line_follower_8h_source.tex | 50 + doc/latex/_me_m_core_8h.tex | 122 + doc/latex/_me_m_core_8h__incl.md5 | 1 + doc/latex/_me_m_core_8h__incl.pdf | Bin 0 -> 45548 bytes doc/latex/_me_m_core_8h_source.tex | 57 + doc/latex/_me_mbot_d_c_motor_8cpp.tex | 68 + doc/latex/_me_mbot_d_c_motor_8cpp__incl.md5 | 1 + doc/latex/_me_mbot_d_c_motor_8cpp__incl.pdf | Bin 0 -> 24462 bytes doc/latex/_me_mbot_d_c_motor_8h.tex | 86 + .../_me_mbot_d_c_motor_8h__dep__incl.md5 | 1 + .../_me_mbot_d_c_motor_8h__dep__incl.pdf | Bin 0 -> 13331 bytes doc/latex/_me_mbot_d_c_motor_8h__incl.md5 | 1 + doc/latex/_me_mbot_d_c_motor_8h__incl.pdf | Bin 0 -> 24383 bytes doc/latex/_me_mbot_d_c_motor_8h_source.tex | 32 + doc/latex/_me_mega_pi_8h.tex | 213 ++ doc/latex/_me_mega_pi_8h__incl.md5 | 1 + doc/latex/_me_mega_pi_8h__incl.pdf | Bin 0 -> 45610 bytes doc/latex/_me_mega_pi_8h_source.tex | 97 + doc/latex/_me_mega_pi_d_c_motor_8cpp.tex | 67 + .../_me_mega_pi_d_c_motor_8cpp__incl.md5 | 1 + .../_me_mega_pi_d_c_motor_8cpp__incl.pdf | Bin 0 -> 23271 bytes doc/latex/_me_mega_pi_d_c_motor_8h.tex | 90 + .../_me_mega_pi_d_c_motor_8h__dep__incl.md5 | 1 + .../_me_mega_pi_d_c_motor_8h__dep__incl.pdf | Bin 0 -> 14743 bytes doc/latex/_me_mega_pi_d_c_motor_8h__incl.md5 | 1 + doc/latex/_me_mega_pi_d_c_motor_8h__incl.pdf | Bin 0 -> 23177 bytes doc/latex/_me_mega_pi_d_c_motor_8h_source.tex | 48 + ...me_mega_pi_d_c_motor_test_8ino-example.tex | 6 + doc/latex/_me_mega_pi_pro4_dc_motor_8cpp.tex | 66 + .../_me_mega_pi_pro4_dc_motor_8cpp__incl.md5 | 1 + .../_me_mega_pi_pro4_dc_motor_8cpp__incl.pdf | Bin 0 -> 24348 bytes doc/latex/_me_mega_pi_pro4_dc_motor_8h.tex | 83 + ...me_mega_pi_pro4_dc_motor_8h__dep__incl.md5 | 1 + ...me_mega_pi_pro4_dc_motor_8h__dep__incl.pdf | Bin 0 -> 14602 bytes .../_me_mega_pi_pro4_dc_motor_8h__incl.md5 | 1 + .../_me_mega_pi_pro4_dc_motor_8h__incl.pdf | Bin 0 -> 24276 bytes .../_me_mega_pi_pro4_dc_motor_8h_source.tex | 51 + doc/latex/_me_mega_pi_pro_8h.tex | 245 ++ doc/latex/_me_mega_pi_pro_8h__incl.md5 | 1 + doc/latex/_me_mega_pi_pro_8h__incl.pdf | Bin 0 -> 45838 bytes doc/latex/_me_mega_pi_pro_8h_source.tex | 115 + .../_me_mega_pi_pro_e_s_c_motor_8cpp.tex | 67 + ..._me_mega_pi_pro_e_s_c_motor_8cpp__incl.md5 | 1 + ..._me_mega_pi_pro_e_s_c_motor_8cpp__incl.pdf | Bin 0 -> 23706 bytes doc/latex/_me_mega_pi_pro_e_s_c_motor_8h.tex | 103 + ..._mega_pi_pro_e_s_c_motor_8h__dep__incl.md5 | 1 + ..._mega_pi_pro_e_s_c_motor_8h__dep__incl.pdf | Bin 0 -> 15189 bytes .../_me_mega_pi_pro_e_s_c_motor_8h__incl.md5 | 1 + .../_me_mega_pi_pro_e_s_c_motor_8h__incl.pdf | Bin 0 -> 23631 bytes .../_me_mega_pi_pro_e_s_c_motor_8h_source.tex | 54 + ...e_mega_pi_pro_e_s_c_motor_8ino-example.tex | 6 + doc/latex/_me_on_board_temp_8cpp.tex | 79 + doc/latex/_me_on_board_temp_8cpp__incl.md5 | 1 + doc/latex/_me_on_board_temp_8cpp__incl.pdf | Bin 0 -> 24216 bytes doc/latex/_me_on_board_temp_8h.tex | 90 + doc/latex/_me_on_board_temp_8h__dep__incl.md5 | 1 + doc/latex/_me_on_board_temp_8h__dep__incl.pdf | Bin 0 -> 16424 bytes doc/latex/_me_on_board_temp_8h__incl.md5 | 1 + doc/latex/_me_on_board_temp_8h__incl.pdf | Bin 0 -> 24136 bytes doc/latex/_me_on_board_temp_8h_source.tex | 48 + .../_me_on_board_temp_test_8ino-example.tex | 6 + doc/latex/_me_one_wire_8cpp.tex | 83 + doc/latex/_me_one_wire_8cpp__incl.md5 | 1 + doc/latex/_me_one_wire_8cpp__incl.pdf | Bin 0 -> 23013 bytes doc/latex/_me_one_wire_8h.tex | 99 + doc/latex/_me_one_wire_8h__dep__incl.md5 | 1 + doc/latex/_me_one_wire_8h__dep__incl.pdf | Bin 0 -> 19386 bytes doc/latex/_me_one_wire_8h__incl.md5 | 1 + doc/latex/_me_one_wire_8h__incl.pdf | Bin 0 -> 22929 bytes doc/latex/_me_one_wire_8h_source.tex | 64 + doc/latex/_me_orion_8h.tex | 128 + doc/latex/_me_orion_8h__incl.md5 | 1 + doc/latex/_me_orion_8h__incl.pdf | Bin 0 -> 43937 bytes doc/latex/_me_orion_8h_source.tex | 60 + doc/latex/_me_p_i_r_motion_sensor_8cpp.tex | 65 + .../_me_p_i_r_motion_sensor_8cpp__incl.md5 | 1 + .../_me_p_i_r_motion_sensor_8cpp__incl.pdf | Bin 0 -> 23728 bytes doc/latex/_me_p_i_r_motion_sensor_8h.tex | 82 + .../_me_p_i_r_motion_sensor_8h__dep__incl.md5 | 1 + .../_me_p_i_r_motion_sensor_8h__dep__incl.pdf | Bin 0 -> 18686 bytes .../_me_p_i_r_motion_sensor_8h__incl.md5 | 1 + .../_me_p_i_r_motion_sensor_8h__incl.pdf | Bin 0 -> 23639 bytes .../_me_p_i_r_motion_sensor_8h_source.tex | 44 + doc/latex/_me_p_s2_8cpp.tex | 71 + doc/latex/_me_p_s2_8cpp__incl.md5 | 1 + doc/latex/_me_p_s2_8cpp__incl.pdf | Bin 0 -> 24791 bytes doc/latex/_me_p_s2_8h.tex | 160 ++ doc/latex/_me_p_s2_8h__dep__incl.md5 | 1 + doc/latex/_me_p_s2_8h__dep__incl.pdf | Bin 0 -> 16262 bytes doc/latex/_me_p_s2_8h__incl.md5 | 1 + doc/latex/_me_p_s2_8h__incl.pdf | Bin 0 -> 24618 bytes doc/latex/_me_p_s2_8h_source.tex | 92 + doc/latex/_me_p_s2_test_8ino-example.tex | 6 + doc/latex/_me_pm25_sensor_8cpp.tex | 82 + doc/latex/_me_pm25_sensor_8cpp__incl.md5 | 1 + doc/latex/_me_pm25_sensor_8cpp__incl.pdf | Bin 0 -> 25142 bytes doc/latex/_me_pm25_sensor_8h.tex | 115 + doc/latex/_me_pm25_sensor_8h__dep__incl.md5 | 1 + doc/latex/_me_pm25_sensor_8h__dep__incl.pdf | Bin 0 -> 16902 bytes doc/latex/_me_pm25_sensor_8h__incl.md5 | 1 + doc/latex/_me_pm25_sensor_8h__incl.pdf | Bin 0 -> 25056 bytes doc/latex/_me_pm25_sensor_8h_source.tex | 100 + doc/latex/_me_port_8cpp.tex | 80 + doc/latex/_me_port_8cpp__incl.md5 | 1 + doc/latex/_me_port_8cpp__incl.pdf | Bin 0 -> 23239 bytes doc/latex/_me_port_8h.tex | 199 ++ doc/latex/_me_port_8h__dep__incl.md5 | 1 + doc/latex/_me_port_8h__dep__incl.pdf | Bin 0 -> 47076 bytes doc/latex/_me_port_8h__incl.md5 | 1 + doc/latex/_me_port_8h__incl.pdf | Bin 0 -> 23167 bytes doc/latex/_me_port_8h_source.tex | 126 + doc/latex/_me_potentiometer_8cpp.tex | 64 + doc/latex/_me_potentiometer_8cpp__incl.md5 | 1 + doc/latex/_me_potentiometer_8cpp__incl.pdf | Bin 0 -> 23705 bytes doc/latex/_me_potentiometer_8h.tex | 81 + doc/latex/_me_potentiometer_8h__dep__incl.md5 | 1 + doc/latex/_me_potentiometer_8h__dep__incl.pdf | Bin 0 -> 18498 bytes doc/latex/_me_potentiometer_8h__incl.md5 | 1 + doc/latex/_me_potentiometer_8h__incl.pdf | Bin 0 -> 23628 bytes doc/latex/_me_potentiometer_8h_source.tex | 40 + doc/latex/_me_pressure_sensor_8h_source.tex | 68 + doc/latex/_me_r_g_b_led_8cpp.tex | 140 + doc/latex/_me_r_g_b_led_8cpp__incl.md5 | 1 + doc/latex/_me_r_g_b_led_8cpp__incl.pdf | Bin 0 -> 24515 bytes doc/latex/_me_r_g_b_led_8h.tex | 105 + doc/latex/_me_r_g_b_led_8h__dep__incl.md5 | 1 + doc/latex/_me_r_g_b_led_8h__dep__incl.pdf | Bin 0 -> 18635 bytes doc/latex/_me_r_g_b_led_8h__incl.md5 | 1 + doc/latex/_me_r_g_b_led_8h__incl.pdf | Bin 0 -> 24448 bytes doc/latex/_me_r_g_b_led_8h_source.tex | 86 + doc/latex/_me_serial_8cpp.tex | 75 + doc/latex/_me_serial_8cpp__incl.md5 | 1 + doc/latex/_me_serial_8cpp__incl.pdf | Bin 0 -> 23873 bytes doc/latex/_me_serial_8h.tex | 88 + doc/latex/_me_serial_8h__dep__incl.md5 | 1 + doc/latex/_me_serial_8h__dep__incl.pdf | Bin 0 -> 26388 bytes doc/latex/_me_serial_8h__incl.md5 | 1 + doc/latex/_me_serial_8h__incl.pdf | Bin 0 -> 23603 bytes doc/latex/_me_serial_8h_source.tex | 79 + .../_me_serial_receive_test_8ino-example.tex | 6 + .../_me_serial_transmit_test_8ino-example.tex | 6 + doc/latex/_me_shield_8h.tex | 124 + doc/latex/_me_shield_8h__incl.md5 | 1 + doc/latex/_me_shield_8h__incl.pdf | Bin 0 -> 43746 bytes doc/latex/_me_shield_8h_source.tex | 60 + doc/latex/_me_shutter_8cpp.tex | 68 + doc/latex/_me_shutter_8cpp__incl.md5 | 1 + doc/latex/_me_shutter_8cpp__incl.pdf | Bin 0 -> 23693 bytes doc/latex/_me_shutter_8h.tex | 85 + doc/latex/_me_shutter_8h__dep__incl.md5 | 1 + doc/latex/_me_shutter_8h__dep__incl.pdf | Bin 0 -> 17993 bytes doc/latex/_me_shutter_8h__incl.md5 | 1 + doc/latex/_me_shutter_8h__incl.pdf | Bin 0 -> 23627 bytes doc/latex/_me_shutter_8h_source.tex | 49 + doc/latex/_me_shutter_test_8ino-example.tex | 6 + doc/latex/_me_smart_servo_8cpp.tex | 88 + doc/latex/_me_smart_servo_8cpp__incl.md5 | 1 + doc/latex/_me_smart_servo_8cpp__incl.pdf | Bin 0 -> 24349 bytes doc/latex/_me_smart_servo_8h.tex | 290 ++ doc/latex/_me_smart_servo_8h__dep__incl.md5 | 1 + doc/latex/_me_smart_servo_8h__dep__incl.pdf | Bin 0 -> 16558 bytes doc/latex/_me_smart_servo_8h__incl.md5 | 1 + doc/latex/_me_smart_servo_8h__incl.pdf | Bin 0 -> 24157 bytes doc/latex/_me_smart_servo_8h_source.tex | 202 ++ doc/latex/_me_sound_sensor_8cpp.tex | 63 + doc/latex/_me_sound_sensor_8cpp__incl.md5 | 1 + doc/latex/_me_sound_sensor_8cpp__incl.pdf | Bin 0 -> 13674 bytes doc/latex/_me_stepper_8cpp.tex | 113 + doc/latex/_me_stepper_8cpp__incl.md5 | 1 + doc/latex/_me_stepper_8cpp__incl.pdf | Bin 0 -> 23711 bytes doc/latex/_me_stepper_8h.tex | 103 + doc/latex/_me_stepper_8h__dep__incl.md5 | 1 + doc/latex/_me_stepper_8h__dep__incl.pdf | Bin 0 -> 18000 bytes doc/latex/_me_stepper_8h__incl.md5 | 1 + doc/latex/_me_stepper_8h__incl.pdf | Bin 0 -> 23641 bytes doc/latex/_me_stepper_8h_source.tex | 91 + doc/latex/_me_stepper_on_board_8cpp.tex | 115 + doc/latex/_me_stepper_on_board_8cpp__incl.md5 | 1 + doc/latex/_me_stepper_on_board_8cpp__incl.pdf | Bin 0 -> 18860 bytes doc/latex/_me_stepper_on_board_8h.tex | 130 + .../_me_stepper_on_board_8h__dep__incl.md5 | 1 + .../_me_stepper_on_board_8h__dep__incl.pdf | Bin 0 -> 16210 bytes doc/latex/_me_stepper_on_board_8h__incl.md5 | 1 + doc/latex/_me_stepper_on_board_8h__incl.pdf | Bin 0 -> 18785 bytes doc/latex/_me_stepper_on_board_8h_source.tex | 121 + doc/latex/_me_temperature_8cpp.tex | 65 + doc/latex/_me_temperature_8cpp__incl.md5 | 1 + doc/latex/_me_temperature_8cpp__incl.pdf | Bin 0 -> 24293 bytes doc/latex/_me_temperature_8h.tex | 107 + doc/latex/_me_temperature_8h__dep__incl.md5 | 1 + doc/latex/_me_temperature_8h__dep__incl.pdf | Bin 0 -> 18638 bytes doc/latex/_me_temperature_8h__incl.md5 | 1 + doc/latex/_me_temperature_8h__incl.pdf | Bin 0 -> 24202 bytes doc/latex/_me_temperature_8h_source.tex | 59 + doc/latex/_me_touch_sensor_8cpp.tex | 64 + doc/latex/_me_touch_sensor_8cpp__incl.md5 | 1 + doc/latex/_me_touch_sensor_8cpp__incl.pdf | Bin 0 -> 23878 bytes doc/latex/_me_touch_sensor_8h.tex | 81 + doc/latex/_me_touch_sensor_8h__dep__incl.md5 | 1 + doc/latex/_me_touch_sensor_8h__dep__incl.pdf | Bin 0 -> 17894 bytes doc/latex/_me_touch_sensor_8h__incl.md5 | 1 + doc/latex/_me_touch_sensor_8h__incl.pdf | Bin 0 -> 23807 bytes doc/latex/_me_touch_sensor_8h_source.tex | 45 + doc/latex/_me_u_s_b_host_8cpp.tex | 103 + doc/latex/_me_u_s_b_host_8cpp__incl.md5 | 1 + doc/latex/_me_u_s_b_host_8cpp__incl.pdf | Bin 0 -> 25039 bytes doc/latex/_me_u_s_b_host_8h.tex | 419 +++ doc/latex/_me_u_s_b_host_8h__dep__incl.md5 | 1 + doc/latex/_me_u_s_b_host_8h__dep__incl.pdf | Bin 0 -> 18453 bytes doc/latex/_me_u_s_b_host_8h__incl.md5 | 1 + doc/latex/_me_u_s_b_host_8h__incl.pdf | Bin 0 -> 24952 bytes doc/latex/_me_u_s_b_host_8h_source.tex | 381 +++ doc/latex/_me_ultrasonic_sensor_8cpp.tex | 68 + .../_me_ultrasonic_sensor_8cpp__incl.md5 | 1 + .../_me_ultrasonic_sensor_8cpp__incl.pdf | Bin 0 -> 23957 bytes doc/latex/_me_ultrasonic_sensor_8h.tex | 96 + .../_me_ultrasonic_sensor_8h__dep__incl.md5 | 1 + .../_me_ultrasonic_sensor_8h__dep__incl.pdf | Bin 0 -> 18237 bytes doc/latex/_me_ultrasonic_sensor_8h__incl.md5 | 1 + doc/latex/_me_ultrasonic_sensor_8h__incl.pdf | Bin 0 -> 23872 bytes doc/latex/_me_ultrasonic_sensor_8h_source.tex | 50 + doc/latex/_me_voice_8cpp.tex | 65 + doc/latex/_me_voice_8cpp__incl.md5 | 1 + doc/latex/_me_voice_8cpp__incl.pdf | Bin 0 -> 24576 bytes doc/latex/_me_voice_8h.tex | 107 + doc/latex/_me_voice_8h__dep__incl.md5 | 1 + doc/latex/_me_voice_8h__dep__incl.pdf | Bin 0 -> 12605 bytes doc/latex/_me_voice_8h__incl.md5 | 1 + doc/latex/_me_voice_8h__incl.pdf | Bin 0 -> 24502 bytes doc/latex/_me_voice_8h_source.tex | 59 + doc/latex/_me_voice_test_8ino-example.tex | 6 + doc/latex/_me_wifi_8cpp.tex | 58 + doc/latex/_me_wifi_8cpp__incl.md5 | 1 + doc/latex/_me_wifi_8cpp__incl.pdf | Bin 0 -> 24267 bytes doc/latex/_me_wifi_8h.tex | 75 + doc/latex/_me_wifi_8h__dep__incl.md5 | 1 + doc/latex/_me_wifi_8h__dep__incl.pdf | Bin 0 -> 18557 bytes doc/latex/_me_wifi_8h__incl.md5 | 1 + doc/latex/_me_wifi_8h__incl.pdf | Bin 0 -> 24178 bytes doc/latex/_me_wifi_8h_source.tex | 37 + doc/latex/_me_wifi_8ino-example.tex | 6 + ..._pi_on_board_stepper_test_8ino-example.tex | 6 + doc/latex/_number_display_8ino-example.tex | 6 + doc/latex/_number_flow_8ino-example.tex | 6 + ..._p_i_r_motion_sensor_test_8ino-example.tex | 6 + doc/latex/_pm25_sensor_8ino-example.tex | 8 + .../_potentiometer_test_8ino-example.tex | 6 + doc/latex/_s_p_i_8h_source.tex | 330 +++ doc/latex/_servo_8h_source.tex | 118 + doc/latex/_servo_timers_8h_source.tex | 60 + ...tooth_by_soft_serial_test_8ino-example.tex | 6 + doc/latex/_smart_servo_test_8ino-example.tex | 6 + doc/latex/_software_serial_8h_source.tex | 126 + doc/latex/_sound_sensor_test_8ino-example.tex | 6 + doc/latex/_temperature_test_8ino-example.tex | 6 + doc/latex/_test_u_s_b_hsot_8ino-example.tex | 11 + doc/latex/_time_display_8ino-example.tex | 8 + doc/latex/_touch_sensor_test_8ino-example.tex | 6 + .../_ultrasonic_sensor_test_8ino-example.tex | 6 + .../_white_breath_light_test_8ino-example.tex | 14 + doc/latex/_wire_8h_source.tex | 91 + doc/latex/annotated.tex | 84 + doc/latex/class_m_bot_d_c_motor.eps | 203 ++ doc/latex/class_m_bot_d_c_motor.tex | 164 ++ .../class_m_bot_d_c_motor__coll__graph.md5 | 1 + .../class_m_bot_d_c_motor__coll__graph.pdf | Bin 0 -> 11300 bytes .../class_m_bot_d_c_motor__inherit__graph.md5 | 1 + .../class_m_bot_d_c_motor__inherit__graph.pdf | Bin 0 -> 11300 bytes doc/latex/class_me4_button.eps | 197 ++ doc/latex/class_me4_button.tex | 198 ++ doc/latex/class_me4_button__coll__graph.md5 | 1 + doc/latex/class_me4_button__coll__graph.pdf | Bin 0 -> 11760 bytes .../class_me4_button__inherit__graph.md5 | 1 + .../class_me4_button__inherit__graph.pdf | Bin 0 -> 11760 bytes doc/latex/class_me7_segment_display.eps | 197 ++ doc/latex/class_me7_segment_display.tex | 679 +++++ ...class_me7_segment_display__coll__graph.md5 | 1 + ...class_me7_segment_display__coll__graph.pdf | Bin 0 -> 15721 bytes ...ss_me7_segment_display__inherit__graph.md5 | 1 + ...ss_me7_segment_display__inherit__graph.pdf | Bin 0 -> 15721 bytes doc/latex/class_me_bluetooth.eps | 215 ++ doc/latex/class_me_bluetooth.tex | 231 ++ doc/latex/class_me_bluetooth__coll__graph.md5 | 1 + doc/latex/class_me_bluetooth__coll__graph.pdf | Bin 0 -> 15224 bytes .../class_me_bluetooth__inherit__graph.md5 | 1 + .../class_me_bluetooth__inherit__graph.pdf | Bin 0 -> 15224 bytes doc/latex/class_me_buzzer.eps | 197 ++ doc/latex/class_me_buzzer.tex | 294 ++ doc/latex/class_me_buzzer__coll__graph.md5 | 1 + doc/latex/class_me_buzzer__coll__graph.pdf | Bin 0 -> 11457 bytes doc/latex/class_me_buzzer__inherit__graph.md5 | 1 + doc/latex/class_me_buzzer__inherit__graph.pdf | Bin 0 -> 11457 bytes doc/latex/class_me_color_sensor.eps | 197 ++ doc/latex/class_me_color_sensor.tex | 1002 +++++++ .../class_me_color_sensor__coll__graph.md5 | 1 + .../class_me_color_sensor__coll__graph.pdf | Bin 0 -> 12648 bytes .../class_me_color_sensor__inherit__graph.md5 | 1 + .../class_me_color_sensor__inherit__graph.pdf | Bin 0 -> 12648 bytes doc/latex/class_me_compass.eps | 197 ++ doc/latex/class_me_compass.tex | 380 +++ doc/latex/class_me_compass__coll__graph.md5 | 1 + doc/latex/class_me_compass__coll__graph.pdf | Bin 0 -> 13023 bytes .../class_me_compass__inherit__graph.md5 | 1 + .../class_me_compass__inherit__graph.pdf | Bin 0 -> 13023 bytes doc/latex/class_me_d_c_motor.eps | 203 ++ doc/latex/class_me_d_c_motor.tex | 279 ++ doc/latex/class_me_d_c_motor__coll__graph.md5 | 1 + doc/latex/class_me_d_c_motor__coll__graph.pdf | Bin 0 -> 10893 bytes .../class_me_d_c_motor__inherit__graph.md5 | 1 + .../class_me_d_c_motor__inherit__graph.pdf | Bin 0 -> 11304 bytes doc/latex/class_me_encoder_motor.eps | 197 ++ doc/latex/class_me_encoder_motor.tex | 416 +++ .../class_me_encoder_motor__coll__graph.md5 | 1 + .../class_me_encoder_motor__coll__graph.pdf | Bin 0 -> 11690 bytes ...class_me_encoder_motor__inherit__graph.md5 | 1 + ...class_me_encoder_motor__inherit__graph.pdf | Bin 0 -> 11690 bytes doc/latex/class_me_encoder_new.tex | 825 ++++++ doc/latex/class_me_encoder_on_board.tex | 1056 +++++++ doc/latex/class_me_flame_sensor.eps | 197 ++ doc/latex/class_me_flame_sensor.tex | 217 ++ .../class_me_flame_sensor__coll__graph.md5 | 1 + .../class_me_flame_sensor__coll__graph.pdf | Bin 0 -> 13652 bytes .../class_me_flame_sensor__inherit__graph.md5 | 1 + .../class_me_flame_sensor__inherit__graph.pdf | Bin 0 -> 13652 bytes doc/latex/class_me_gas_sensor.eps | 197 ++ doc/latex/class_me_gas_sensor.tex | 217 ++ .../class_me_gas_sensor__coll__graph.md5 | 1 + .../class_me_gas_sensor__coll__graph.pdf | Bin 0 -> 13211 bytes .../class_me_gas_sensor__inherit__graph.md5 | 1 + .../class_me_gas_sensor__inherit__graph.pdf | Bin 0 -> 13211 bytes doc/latex/class_me_gyro.eps | 197 ++ doc/latex/class_me_gyro.tex | 553 ++++ doc/latex/class_me_gyro__coll__graph.md5 | 1 + doc/latex/class_me_gyro__coll__graph.pdf | Bin 0 -> 11301 bytes doc/latex/class_me_gyro__inherit__graph.md5 | 1 + doc/latex/class_me_gyro__inherit__graph.pdf | Bin 0 -> 11301 bytes doc/latex/class_me_host_parser.tex | 210 ++ doc/latex/class_me_humiture.eps | 197 ++ doc/latex/class_me_humiture.tex | 403 +++ doc/latex/class_me_humiture__coll__graph.md5 | 1 + doc/latex/class_me_humiture__coll__graph.pdf | Bin 0 -> 11675 bytes .../class_me_humiture__inherit__graph.md5 | 1 + .../class_me_humiture__inherit__graph.pdf | Bin 0 -> 11675 bytes doc/latex/class_me_i_r.tex | 493 ++++ doc/latex/class_me_infrared_receiver.eps | 215 ++ doc/latex/class_me_infrared_receiver.tex | 353 +++ ...lass_me_infrared_receiver__coll__graph.md5 | 1 + ...lass_me_infrared_receiver__coll__graph.pdf | Bin 0 -> 16587 bytes ...s_me_infrared_receiver__inherit__graph.md5 | 1 + ...s_me_infrared_receiver__inherit__graph.pdf | Bin 0 -> 16587 bytes doc/latex/class_me_joystick.eps | 197 ++ doc/latex/class_me_joystick.tex | 320 +++ doc/latex/class_me_joystick__coll__graph.md5 | 1 + doc/latex/class_me_joystick__coll__graph.pdf | Bin 0 -> 13224 bytes .../class_me_joystick__inherit__graph.md5 | 1 + .../class_me_joystick__inherit__graph.pdf | Bin 0 -> 13224 bytes doc/latex/class_me_l_e_d_matrix.eps | 197 ++ doc/latex/class_me_l_e_d_matrix.tex | 374 +++ .../class_me_l_e_d_matrix__coll__graph.md5 | 1 + .../class_me_l_e_d_matrix__coll__graph.pdf | Bin 0 -> 12317 bytes .../class_me_l_e_d_matrix__inherit__graph.md5 | 1 + .../class_me_l_e_d_matrix__inherit__graph.pdf | Bin 0 -> 12317 bytes doc/latex/class_me_light_sensor.eps | 197 ++ doc/latex/class_me_light_sensor.tex | 256 ++ .../class_me_light_sensor__coll__graph.md5 | 1 + .../class_me_light_sensor__coll__graph.pdf | Bin 0 -> 13314 bytes .../class_me_light_sensor__inherit__graph.md5 | 1 + .../class_me_light_sensor__inherit__graph.pdf | Bin 0 -> 13314 bytes doc/latex/class_me_limit_switch.eps | 197 ++ doc/latex/class_me_limit_switch.tex | 208 ++ .../class_me_limit_switch__coll__graph.md5 | 1 + .../class_me_limit_switch__coll__graph.pdf | Bin 0 -> 13627 bytes .../class_me_limit_switch__inherit__graph.md5 | 1 + .../class_me_limit_switch__inherit__graph.pdf | Bin 0 -> 13627 bytes doc/latex/class_me_line_follower.eps | 197 ++ doc/latex/class_me_line_follower.tex | 244 ++ .../class_me_line_follower__coll__graph.md5 | 1 + .../class_me_line_follower__coll__graph.pdf | Bin 0 -> 12349 bytes ...class_me_line_follower__inherit__graph.md5 | 1 + ...class_me_line_follower__inherit__graph.pdf | Bin 0 -> 12349 bytes doc/latex/class_me_mega_pi_d_c_motor.tex | 211 ++ doc/latex/class_me_mega_pi_pro4_dc_motor.eps | 197 ++ doc/latex/class_me_mega_pi_pro4_dc_motor.tex | 279 ++ ..._me_mega_pi_pro4_dc_motor__coll__graph.md5 | 1 + ..._me_mega_pi_pro4_dc_motor__coll__graph.pdf | Bin 0 -> 12908 bytes ..._mega_pi_pro4_dc_motor__inherit__graph.md5 | 1 + ..._mega_pi_pro4_dc_motor__inherit__graph.pdf | Bin 0 -> 12908 bytes .../class_me_mega_pi_pro_e_s_c_motor.tex | 235 ++ doc/latex/class_me_on_board_temp.eps | 197 ++ doc/latex/class_me_on_board_temp.tex | 214 ++ .../class_me_on_board_temp__coll__graph.md5 | 1 + .../class_me_on_board_temp__coll__graph.pdf | Bin 0 -> 13546 bytes ...class_me_on_board_temp__inherit__graph.md5 | 1 + ...class_me_on_board_temp__inherit__graph.pdf | Bin 0 -> 13546 bytes doc/latex/class_me_one_wire.tex | 463 +++ doc/latex/class_me_p_i_r_motion_sensor.eps | 197 ++ doc/latex/class_me_p_i_r_motion_sensor.tex | 228 ++ ...ss_me_p_i_r_motion_sensor__coll__graph.md5 | 1 + ...ss_me_p_i_r_motion_sensor__coll__graph.pdf | Bin 0 -> 13104 bytes ...me_p_i_r_motion_sensor__inherit__graph.md5 | 1 + ...me_p_i_r_motion_sensor__inherit__graph.pdf | Bin 0 -> 13104 bytes doc/latex/class_me_p_s2.eps | 215 ++ doc/latex/class_me_p_s2.tex | 470 +++ doc/latex/class_me_p_s2__coll__graph.md5 | 1 + doc/latex/class_me_p_s2__coll__graph.pdf | Bin 0 -> 14673 bytes doc/latex/class_me_p_s2__inherit__graph.md5 | 1 + doc/latex/class_me_p_s2__inherit__graph.pdf | Bin 0 -> 14673 bytes doc/latex/class_me_pm25_sensor.eps | 215 ++ doc/latex/class_me_pm25_sensor.tex | 963 +++++++ .../class_me_pm25_sensor__coll__graph.md5 | 1 + .../class_me_pm25_sensor__coll__graph.pdf | Bin 0 -> 16200 bytes .../class_me_pm25_sensor__inherit__graph.md5 | 1 + .../class_me_pm25_sensor__inherit__graph.pdf | Bin 0 -> 16200 bytes doc/latex/class_me_port.eps | 309 ++ doc/latex/class_me_port.tex | 598 ++++ doc/latex/class_me_port__inherit__graph.md5 | 1 + doc/latex/class_me_port__inherit__graph.pdf | Bin 0 -> 29192 bytes doc/latex/class_me_potentiometer.eps | 197 ++ doc/latex/class_me_potentiometer.tex | 196 ++ .../class_me_potentiometer__coll__graph.md5 | 1 + .../class_me_potentiometer__coll__graph.pdf | Bin 0 -> 11441 bytes ...class_me_potentiometer__inherit__graph.md5 | 1 + ...class_me_potentiometer__inherit__graph.pdf | Bin 0 -> 11441 bytes doc/latex/class_me_pressure_sensor.tex | 32 + doc/latex/class_me_r_g_b_led.eps | 197 ++ doc/latex/class_me_r_g_b_led.tex | 532 ++++ doc/latex/class_me_r_g_b_led__coll__graph.md5 | 1 + doc/latex/class_me_r_g_b_led__coll__graph.pdf | Bin 0 -> 12056 bytes .../class_me_r_g_b_led__inherit__graph.md5 | 1 + .../class_me_r_g_b_led__inherit__graph.pdf | Bin 0 -> 12056 bytes doc/latex/class_me_serial.eps | 241 ++ doc/latex/class_me_serial.tex | 530 ++++ doc/latex/class_me_serial__coll__graph.md5 | 1 + doc/latex/class_me_serial__coll__graph.pdf | Bin 0 -> 14131 bytes doc/latex/class_me_serial__inherit__graph.md5 | 1 + doc/latex/class_me_serial__inherit__graph.pdf | Bin 0 -> 20644 bytes doc/latex/class_me_shutter.eps | 197 ++ doc/latex/class_me_shutter.tex | 294 ++ doc/latex/class_me_shutter__coll__graph.md5 | 1 + doc/latex/class_me_shutter__coll__graph.pdf | Bin 0 -> 11610 bytes .../class_me_shutter__inherit__graph.md5 | 1 + .../class_me_shutter__inherit__graph.pdf | Bin 0 -> 11610 bytes doc/latex/class_me_smart_servo.eps | 215 ++ doc/latex/class_me_smart_servo.tex | 1067 +++++++ .../class_me_smart_servo__coll__graph.md5 | 1 + .../class_me_smart_servo__coll__graph.pdf | Bin 0 -> 14678 bytes .../class_me_smart_servo__inherit__graph.md5 | 1 + .../class_me_smart_servo__inherit__graph.pdf | Bin 0 -> 14678 bytes doc/latex/class_me_sound_sensor.tex | 20 + doc/latex/class_me_stepper.eps | 197 ++ doc/latex/class_me_stepper.tex | 655 +++++ doc/latex/class_me_stepper__coll__graph.md5 | 1 + doc/latex/class_me_stepper__coll__graph.pdf | Bin 0 -> 11339 bytes .../class_me_stepper__inherit__graph.md5 | 1 + .../class_me_stepper__inherit__graph.pdf | Bin 0 -> 11339 bytes doc/latex/class_me_stepper_on_board.tex | 799 +++++ doc/latex/class_me_temperature.eps | 197 ++ doc/latex/class_me_temperature.tex | 264 ++ .../class_me_temperature__coll__graph.md5 | 1 + .../class_me_temperature__coll__graph.pdf | Bin 0 -> 12438 bytes .../class_me_temperature__inherit__graph.md5 | 1 + .../class_me_temperature__inherit__graph.pdf | Bin 0 -> 12438 bytes doc/latex/class_me_touch_sensor.eps | 197 ++ doc/latex/class_me_touch_sensor.tex | 221 ++ .../class_me_touch_sensor__coll__graph.md5 | 1 + .../class_me_touch_sensor__coll__graph.pdf | Bin 0 -> 13378 bytes .../class_me_touch_sensor__inherit__graph.md5 | 1 + .../class_me_touch_sensor__inherit__graph.pdf | Bin 0 -> 13378 bytes doc/latex/class_me_u_s_b_host.eps | 197 ++ doc/latex/class_me_u_s_b_host.tex | 299 ++ .../class_me_u_s_b_host__coll__graph.md5 | 1 + .../class_me_u_s_b_host__coll__graph.pdf | Bin 0 -> 12580 bytes .../class_me_u_s_b_host__inherit__graph.md5 | 1 + .../class_me_u_s_b_host__inherit__graph.pdf | Bin 0 -> 12580 bytes doc/latex/class_me_ultrasonic_sensor.eps | 197 ++ doc/latex/class_me_ultrasonic_sensor.tex | 252 ++ ...lass_me_ultrasonic_sensor__coll__graph.md5 | 1 + ...lass_me_ultrasonic_sensor__coll__graph.pdf | Bin 0 -> 14003 bytes ...s_me_ultrasonic_sensor__inherit__graph.md5 | 1 + ...s_me_ultrasonic_sensor__inherit__graph.pdf | Bin 0 -> 14003 bytes doc/latex/class_me_voice.eps | 215 ++ doc/latex/class_me_voice.tex | 328 +++ doc/latex/class_me_voice__coll__graph.md5 | 1 + doc/latex/class_me_voice__coll__graph.pdf | Bin 0 -> 15040 bytes doc/latex/class_me_voice__inherit__graph.md5 | 1 + doc/latex/class_me_voice__inherit__graph.pdf | Bin 0 -> 15040 bytes doc/latex/class_me_wifi.eps | 215 ++ doc/latex/class_me_wifi.tex | 231 ++ doc/latex/class_me_wifi__coll__graph.md5 | 1 + doc/latex/class_me_wifi__coll__graph.pdf | Bin 0 -> 14740 bytes doc/latex/class_me_wifi__inherit__graph.md5 | 1 + doc/latex/class_me_wifi__inherit__graph.pdf | Bin 0 -> 14740 bytes doc/latex/class_mecolor.tex | 24 + doc/latex/class_s_p_i_class.tex | 52 + doc/latex/class_s_p_i_settings.tex | 19 + doc/latex/class_servo.tex | 34 + doc/latex/class_software_serial.eps | 235 ++ doc/latex/class_software_serial.tex | 105 + .../class_software_serial__coll__graph.md5 | 1 + .../class_software_serial__coll__graph.pdf | Bin 0 -> 13066 bytes .../class_software_serial__inherit__graph.md5 | 1 + .../class_software_serial__inherit__graph.pdf | Bin 0 -> 20515 bytes doc/latex/class_two_wire.eps | 197 ++ doc/latex/class_two_wire.tex | 108 + doc/latex/class_two_wire__coll__graph.md5 | 1 + doc/latex/class_two_wire__coll__graph.pdf | Bin 0 -> 13254 bytes doc/latex/class_two_wire__inherit__graph.md5 | 1 + doc/latex/class_two_wire__inherit__graph.pdf | Bin 0 -> 13254 bytes doc/latex/doxygen.sty | 694 +++++ doc/latex/etoc_doxygen.sty | 2178 ++++++++++++++ doc/latex/examples.tex | 64 + doc/latex/files.tex | 112 + doc/latex/hierarchy.tex | 95 + doc/latex/index.tex | 56 + doc/latex/longtable_doxygen.sty | 456 +++ doc/latex/make.bat | 56 + doc/latex/refman.tex | 534 ++++ ...___u_s_b___c_o_n_f_i_g___d_escript_o_r.tex | 34 + ..._c_o_n_f_i_g___d_escript_o_r___l_o_n_g.tex | 29 + ...__d_escript_o_r___l_o_n_g__coll__graph.md5 | 1 + ...__d_escript_o_r___l_o_n_g__coll__graph.pdf | Bin 0 -> 17222 bytes ...___u_s_b___d_e_v_i_c_e___d_escript_o_r.tex | 52 + ..._s_b___e_n_d_p_o_i_n_t___d_escript_o_r.tex | 28 + ...___u_s_b___i_n_t_e_r_f___d_escript_o_r.tex | 37 + doc/latex/struct_cmd__list__tab__type.tex | 19 + ...ruct_compass___calibration___parameter.tex | 34 + doc/latex/struct_e_e_p_r_o_m_class.tex | 37 + doc/latex/struct_e_e_ptr.tex | 51 + doc/latex/struct_e_e_ref.tex | 89 + doc/latex/struct_encoder__port__type.tex | 25 + ..._clock___number___font__3x8___type_def.tex | 13 + ..._l_e_d___matrix___font__6x8___type_def.tex | 16 + doc/latex/struct_me___encoder__type.tex | 68 + ...struct_me___encoder__type__coll__graph.md5 | 1 + ...struct_me___encoder__type__coll__graph.pdf | Bin 0 -> 15294 bytes doc/latex/struct_me_port___sig.tex | 23 + doc/latex/struct_p_i_d__internal.tex | 34 + .../struct_p_m25_d_a_t_a_s_t_r_u_c_t.tex | 55 + doc/latex/struct_servo_pin__t.tex | 16 + doc/latex/structc_r_g_b.tex | 31 + doc/latex/structirparams__t.tex | 28 + doc/latex/structmega_pi__slot.tex | 13 + doc/latex/structmegapi__dc__type.tex | 19 + doc/latex/structmegapipro__esc__type.tex | 13 + doc/latex/structservo__device__type.tex | 25 + doc/latex/structservo__t.tex | 26 + doc/latex/structservo__t__coll__graph.md5 | 1 + doc/latex/structservo__t__coll__graph.pdf | Bin 0 -> 12382 bytes doc/latex/structsysex__message__type.tex | 19 + doc/latex/tabu_doxygen.sty | 2557 +++++++++++++++++ doc/latex/twi_8h_source.tex | 60 + doc/latex/union_p_m25_d_a_t_a_u_i_n_o.tex | 26 + ...ion_p_m25_d_a_t_a_u_i_n_o__coll__graph.md5 | 1 + ...ion_p_m25_d_a_t_a_u_i_n_o__coll__graph.pdf | Bin 0 -> 14644 bytes doc/latex/unionsysex__message.tex | 26 + .../unionsysex__message__coll__graph.md5 | 1 + .../unionsysex__message__coll__graph.pdf | Bin 0 -> 13587 bytes 2359 files changed, 166162 insertions(+) rename src/MeSoundSensor.h => MeSoundSensor.h (100%) create mode 100644 doc/html/_buzzer_test_8ino-example.html create mode 100644 doc/html/_color_loop_test_8ino-example.html create mode 100644 doc/html/_d_c_motor_driver_test_8ino-example.html create mode 100644 doc/html/_e_e_p_r_o_m_8h_source.html create mode 100644 doc/html/_encoder_motor_change_i2_c_dev_i_d_8ino-example.html create mode 100644 doc/html/_encoder_motor_test_is_tar_pos_reached_8ino-example.html create mode 100644 doc/html/_encoder_motor_test_move_to_8ino-example.html create mode 100644 doc/html/_encoder_motor_test_run_speed_8ino-example.html create mode 100644 doc/html/_encoder_motor_test_run_speed_and_time_8ino-example.html create mode 100644 doc/html/_encoder_motor_test_run_turns_8ino-example.html create mode 100644 doc/html/_indicators_test_8ino-example.html create mode 100644 doc/html/_infrared_receiver_test_8ino-example.html create mode 100644 doc/html/_limit_switch_test_8ino-example.html create mode 100644 doc/html/_line_follower_test_8ino-example.html create mode 100644 doc/html/_mbot_buzzer_test2_8ino-example.html create mode 100644 doc/html/_mbot_buzzer_test_8ino-example.html create mode 100644 doc/html/_me4_button_8cpp.html create mode 100644 doc/html/_me4_button_8cpp__incl.map create mode 100644 doc/html/_me4_button_8cpp__incl.md5 create mode 100644 doc/html/_me4_button_8cpp__incl.png create mode 100644 doc/html/_me4_button_8h.html create mode 100644 doc/html/_me4_button_8h.js create mode 100644 doc/html/_me4_button_8h__dep__incl.map create mode 100644 doc/html/_me4_button_8h__dep__incl.md5 create mode 100644 doc/html/_me4_button_8h__dep__incl.png create mode 100644 doc/html/_me4_button_8h__incl.map create mode 100644 doc/html/_me4_button_8h__incl.md5 create mode 100644 doc/html/_me4_button_8h__incl.png create mode 100644 doc/html/_me4_button_8h_source.html create mode 100644 doc/html/_me4_button_test_8ino-example.html create mode 100644 doc/html/_me7_segment_display_8cpp.html create mode 100644 doc/html/_me7_segment_display_8cpp__incl.map create mode 100644 doc/html/_me7_segment_display_8cpp__incl.md5 create mode 100644 doc/html/_me7_segment_display_8cpp__incl.png create mode 100644 doc/html/_me7_segment_display_8h.html create mode 100644 doc/html/_me7_segment_display_8h.js create mode 100644 doc/html/_me7_segment_display_8h__dep__incl.map create mode 100644 doc/html/_me7_segment_display_8h__dep__incl.md5 create mode 100644 doc/html/_me7_segment_display_8h__dep__incl.png create mode 100644 doc/html/_me7_segment_display_8h__incl.map create mode 100644 doc/html/_me7_segment_display_8h__incl.md5 create mode 100644 doc/html/_me7_segment_display_8h__incl.png create mode 100644 doc/html/_me7_segment_display_8h_source.html create mode 100644 doc/html/_me__auriga_encoder_callback_8ino-example.html create mode 100644 doc/html/_me__auriga_encoder_direct_8ino-example.html create mode 100644 doc/html/_me__auriga_encoder_pid_pos_8ino-example.html create mode 100644 doc/html/_me__auriga_encoder_pid_speed_8ino-example.html create mode 100644 doc/html/_me__auriga_encoder_pwm_8ino-example.html create mode 100644 doc/html/_me__l_e_d_matrix_test_8ino-example.html create mode 100644 doc/html/_me__megapi_encoder_direct_8ino-example.html create mode 100644 doc/html/_me__megapi_encoder_pid_pos_8ino-example.html create mode 100644 doc/html/_me__megapi_encoder_pid_speed_8ino-example.html create mode 100644 doc/html/_me__megapi_encoder_pwm_8ino-example.html create mode 100644 doc/html/_me_auriga_8h.html create mode 100644 doc/html/_me_auriga_8h__incl.map create mode 100644 doc/html/_me_auriga_8h__incl.md5 create mode 100644 doc/html/_me_auriga_8h__incl.png create mode 100644 doc/html/_me_auriga_8h_source.html create mode 100644 doc/html/_me_base_board_8h.html create mode 100644 doc/html/_me_base_board_8h__incl.map create mode 100644 doc/html/_me_base_board_8h__incl.md5 create mode 100644 doc/html/_me_base_board_8h__incl.png create mode 100644 doc/html/_me_base_board_8h_source.html create mode 100644 doc/html/_me_bluetooth_8cpp.html create mode 100644 doc/html/_me_bluetooth_8cpp__incl.map create mode 100644 doc/html/_me_bluetooth_8cpp__incl.md5 create mode 100644 doc/html/_me_bluetooth_8cpp__incl.png create mode 100644 doc/html/_me_bluetooth_8h.html create mode 100644 doc/html/_me_bluetooth_8h.js create mode 100644 doc/html/_me_bluetooth_8h__dep__incl.map create mode 100644 doc/html/_me_bluetooth_8h__dep__incl.md5 create mode 100644 doc/html/_me_bluetooth_8h__dep__incl.png create mode 100644 doc/html/_me_bluetooth_8h__incl.map create mode 100644 doc/html/_me_bluetooth_8h__incl.md5 create mode 100644 doc/html/_me_bluetooth_8h__incl.png create mode 100644 doc/html/_me_bluetooth_8h_source.html create mode 100644 doc/html/_me_buzzer_8cpp.html create mode 100644 doc/html/_me_buzzer_8cpp__incl.map create mode 100644 doc/html/_me_buzzer_8cpp__incl.md5 create mode 100644 doc/html/_me_buzzer_8cpp__incl.png create mode 100644 doc/html/_me_buzzer_8h.html create mode 100644 doc/html/_me_buzzer_8h.js create mode 100644 doc/html/_me_buzzer_8h__dep__incl.map create mode 100644 doc/html/_me_buzzer_8h__dep__incl.md5 create mode 100644 doc/html/_me_buzzer_8h__dep__incl.png create mode 100644 doc/html/_me_buzzer_8h__incl.map create mode 100644 doc/html/_me_buzzer_8h__incl.md5 create mode 100644 doc/html/_me_buzzer_8h__incl.png create mode 100644 doc/html/_me_buzzer_8h_source.html create mode 100644 doc/html/_me_color_sensor_8cpp.html create mode 100644 doc/html/_me_color_sensor_8cpp__incl.map create mode 100644 doc/html/_me_color_sensor_8cpp__incl.md5 create mode 100644 doc/html/_me_color_sensor_8cpp__incl.png create mode 100644 doc/html/_me_color_sensor_8h.html create mode 100644 doc/html/_me_color_sensor_8h.js create mode 100644 doc/html/_me_color_sensor_8h__dep__incl.map create mode 100644 doc/html/_me_color_sensor_8h__dep__incl.md5 create mode 100644 doc/html/_me_color_sensor_8h__dep__incl.png create mode 100644 doc/html/_me_color_sensor_8h__incl.map create mode 100644 doc/html/_me_color_sensor_8h__incl.md5 create mode 100644 doc/html/_me_color_sensor_8h__incl.png create mode 100644 doc/html/_me_color_sensor_8h_source.html create mode 100644 doc/html/_me_color_sensor_test_8ino-example.html create mode 100644 doc/html/_me_compass_8cpp.html create mode 100644 doc/html/_me_compass_8cpp__incl.map create mode 100644 doc/html/_me_compass_8cpp__incl.md5 create mode 100644 doc/html/_me_compass_8cpp__incl.png create mode 100644 doc/html/_me_compass_8h.html create mode 100644 doc/html/_me_compass_8h.js create mode 100644 doc/html/_me_compass_8h__dep__incl.map create mode 100644 doc/html/_me_compass_8h__dep__incl.md5 create mode 100644 doc/html/_me_compass_8h__dep__incl.png create mode 100644 doc/html/_me_compass_8h__incl.map create mode 100644 doc/html/_me_compass_8h__incl.md5 create mode 100644 doc/html/_me_compass_8h__incl.png create mode 100644 doc/html/_me_compass_8h_source.html create mode 100644 doc/html/_me_compass_test_8ino-example.html create mode 100644 doc/html/_me_config_8h.html create mode 100644 doc/html/_me_config_8h__dep__incl.map create mode 100644 doc/html/_me_config_8h__dep__incl.md5 create mode 100644 doc/html/_me_config_8h__dep__incl.png create mode 100644 doc/html/_me_config_8h__incl.map create mode 100644 doc/html/_me_config_8h__incl.md5 create mode 100644 doc/html/_me_config_8h__incl.png create mode 100644 doc/html/_me_config_8h_source.html create mode 100644 doc/html/_me_d_c_motor_8cpp.html create mode 100644 doc/html/_me_d_c_motor_8cpp__incl.map create mode 100644 doc/html/_me_d_c_motor_8cpp__incl.md5 create mode 100644 doc/html/_me_d_c_motor_8cpp__incl.png create mode 100644 doc/html/_me_d_c_motor_8h.html create mode 100644 doc/html/_me_d_c_motor_8h.js create mode 100644 doc/html/_me_d_c_motor_8h__dep__incl.map create mode 100644 doc/html/_me_d_c_motor_8h__dep__incl.md5 create mode 100644 doc/html/_me_d_c_motor_8h__dep__incl.png create mode 100644 doc/html/_me_d_c_motor_8h__incl.map create mode 100644 doc/html/_me_d_c_motor_8h__incl.md5 create mode 100644 doc/html/_me_d_c_motor_8h__incl.png create mode 100644 doc/html/_me_d_c_motor_8h_source.html create mode 100644 doc/html/_me_e_e_p_r_o_m_8h.html create mode 100644 doc/html/_me_e_e_p_r_o_m_8h__incl.map create mode 100644 doc/html/_me_e_e_p_r_o_m_8h__incl.md5 create mode 100644 doc/html/_me_e_e_p_r_o_m_8h__incl.png create mode 100644 doc/html/_me_e_e_p_r_o_m_8h_source.html create mode 100644 doc/html/_me_encoder_motor_8cpp.html create mode 100644 doc/html/_me_encoder_motor_8cpp.js create mode 100644 doc/html/_me_encoder_motor_8cpp__incl.map create mode 100644 doc/html/_me_encoder_motor_8cpp__incl.md5 create mode 100644 doc/html/_me_encoder_motor_8cpp__incl.png create mode 100644 doc/html/_me_encoder_motor_8h.html create mode 100644 doc/html/_me_encoder_motor_8h.js create mode 100644 doc/html/_me_encoder_motor_8h__dep__incl.map create mode 100644 doc/html/_me_encoder_motor_8h__dep__incl.md5 create mode 100644 doc/html/_me_encoder_motor_8h__dep__incl.png create mode 100644 doc/html/_me_encoder_motor_8h__incl.map create mode 100644 doc/html/_me_encoder_motor_8h__incl.md5 create mode 100644 doc/html/_me_encoder_motor_8h__incl.png create mode 100644 doc/html/_me_encoder_motor_8h_source.html create mode 100644 doc/html/_me_encoder_new_8cpp.html create mode 100644 doc/html/_me_encoder_new_8cpp__incl.map create mode 100644 doc/html/_me_encoder_new_8cpp__incl.md5 create mode 100644 doc/html/_me_encoder_new_8cpp__incl.png create mode 100644 doc/html/_me_encoder_new_8h.html create mode 100644 doc/html/_me_encoder_new_8h.js create mode 100644 doc/html/_me_encoder_new_8h__dep__incl.map create mode 100644 doc/html/_me_encoder_new_8h__dep__incl.md5 create mode 100644 doc/html/_me_encoder_new_8h__dep__incl.png create mode 100644 doc/html/_me_encoder_new_8h__incl.map create mode 100644 doc/html/_me_encoder_new_8h__incl.md5 create mode 100644 doc/html/_me_encoder_new_8h__incl.png create mode 100644 doc/html/_me_encoder_new_8h_source.html create mode 100644 doc/html/_me_encoder_on_board_8cpp.html create mode 100644 doc/html/_me_encoder_on_board_8cpp__incl.map create mode 100644 doc/html/_me_encoder_on_board_8cpp__incl.md5 create mode 100644 doc/html/_me_encoder_on_board_8cpp__incl.png create mode 100644 doc/html/_me_encoder_on_board_8h.html create mode 100644 doc/html/_me_encoder_on_board_8h.js create mode 100644 doc/html/_me_encoder_on_board_8h__dep__incl.map create mode 100644 doc/html/_me_encoder_on_board_8h__dep__incl.md5 create mode 100644 doc/html/_me_encoder_on_board_8h__dep__incl.png create mode 100644 doc/html/_me_encoder_on_board_8h__incl.map create mode 100644 doc/html/_me_encoder_on_board_8h__incl.md5 create mode 100644 doc/html/_me_encoder_on_board_8h__incl.png create mode 100644 doc/html/_me_encoder_on_board_8h_source.html create mode 100644 doc/html/_me_flame_sensor_8cpp.html create mode 100644 doc/html/_me_flame_sensor_8cpp__incl.map create mode 100644 doc/html/_me_flame_sensor_8cpp__incl.md5 create mode 100644 doc/html/_me_flame_sensor_8cpp__incl.png create mode 100644 doc/html/_me_flame_sensor_8h.html create mode 100644 doc/html/_me_flame_sensor_8h.js create mode 100644 doc/html/_me_flame_sensor_8h__dep__incl.map create mode 100644 doc/html/_me_flame_sensor_8h__dep__incl.md5 create mode 100644 doc/html/_me_flame_sensor_8h__dep__incl.png create mode 100644 doc/html/_me_flame_sensor_8h__incl.map create mode 100644 doc/html/_me_flame_sensor_8h__incl.md5 create mode 100644 doc/html/_me_flame_sensor_8h__incl.png create mode 100644 doc/html/_me_flame_sensor_8h_source.html create mode 100644 doc/html/_me_flame_sensor_test_8ino-example.html create mode 100644 doc/html/_me_gas_sensor_8cpp.html create mode 100644 doc/html/_me_gas_sensor_8cpp__incl.map create mode 100644 doc/html/_me_gas_sensor_8cpp__incl.md5 create mode 100644 doc/html/_me_gas_sensor_8cpp__incl.png create mode 100644 doc/html/_me_gas_sensor_8h.html create mode 100644 doc/html/_me_gas_sensor_8h.js create mode 100644 doc/html/_me_gas_sensor_8h__dep__incl.map create mode 100644 doc/html/_me_gas_sensor_8h__dep__incl.md5 create mode 100644 doc/html/_me_gas_sensor_8h__dep__incl.png create mode 100644 doc/html/_me_gas_sensor_8h__incl.map create mode 100644 doc/html/_me_gas_sensor_8h__incl.md5 create mode 100644 doc/html/_me_gas_sensor_8h__incl.png create mode 100644 doc/html/_me_gas_sensor_8h_source.html create mode 100644 doc/html/_me_gas_sensor_test_8ino-example.html create mode 100644 doc/html/_me_gyro_8cpp.html create mode 100644 doc/html/_me_gyro_8cpp__incl.map create mode 100644 doc/html/_me_gyro_8cpp__incl.md5 create mode 100644 doc/html/_me_gyro_8cpp__incl.png create mode 100644 doc/html/_me_gyro_8h.html create mode 100644 doc/html/_me_gyro_8h.js create mode 100644 doc/html/_me_gyro_8h__dep__incl.map create mode 100644 doc/html/_me_gyro_8h__dep__incl.md5 create mode 100644 doc/html/_me_gyro_8h__dep__incl.png create mode 100644 doc/html/_me_gyro_8h__incl.map create mode 100644 doc/html/_me_gyro_8h__incl.md5 create mode 100644 doc/html/_me_gyro_8h__incl.png create mode 100644 doc/html/_me_gyro_8h_source.html create mode 100644 doc/html/_me_gyro_test_8ino-example.html create mode 100644 doc/html/_me_host_parser_8cpp.html create mode 100644 doc/html/_me_host_parser_8cpp.js create mode 100644 doc/html/_me_host_parser_8cpp__incl.map create mode 100644 doc/html/_me_host_parser_8cpp__incl.md5 create mode 100644 doc/html/_me_host_parser_8cpp__incl.png create mode 100644 doc/html/_me_host_parser_8h.html create mode 100644 doc/html/_me_host_parser_8h.js create mode 100644 doc/html/_me_host_parser_8h__dep__incl.map create mode 100644 doc/html/_me_host_parser_8h__dep__incl.md5 create mode 100644 doc/html/_me_host_parser_8h__dep__incl.png create mode 100644 doc/html/_me_host_parser_8h__incl.map create mode 100644 doc/html/_me_host_parser_8h__incl.md5 create mode 100644 doc/html/_me_host_parser_8h__incl.png create mode 100644 doc/html/_me_host_parser_8h_source.html create mode 100644 doc/html/_me_humiture_sensor_8cpp.html create mode 100644 doc/html/_me_humiture_sensor_8cpp__incl.map create mode 100644 doc/html/_me_humiture_sensor_8cpp__incl.md5 create mode 100644 doc/html/_me_humiture_sensor_8cpp__incl.png create mode 100644 doc/html/_me_humiture_sensor_8h.html create mode 100644 doc/html/_me_humiture_sensor_8h.js create mode 100644 doc/html/_me_humiture_sensor_8h__dep__incl.map create mode 100644 doc/html/_me_humiture_sensor_8h__dep__incl.md5 create mode 100644 doc/html/_me_humiture_sensor_8h__dep__incl.png create mode 100644 doc/html/_me_humiture_sensor_8h__incl.map create mode 100644 doc/html/_me_humiture_sensor_8h__incl.md5 create mode 100644 doc/html/_me_humiture_sensor_8h__incl.png create mode 100644 doc/html/_me_humiture_sensor_8h_source.html create mode 100644 doc/html/_me_humiture_sensor_test1_8ino-example.html create mode 100644 doc/html/_me_humiture_sensor_test2_8ino-example.html create mode 100644 doc/html/_me_i_r_8cpp.html create mode 100644 doc/html/_me_i_r_8h.html create mode 100644 doc/html/_me_i_r_8h.js create mode 100644 doc/html/_me_i_r_8h__dep__incl.map create mode 100644 doc/html/_me_i_r_8h__dep__incl.md5 create mode 100644 doc/html/_me_i_r_8h__dep__incl.png create mode 100644 doc/html/_me_i_r_8h__incl.map create mode 100644 doc/html/_me_i_r_8h__incl.md5 create mode 100644 doc/html/_me_i_r_8h__incl.png create mode 100644 doc/html/_me_i_r_8h_source.html create mode 100644 doc/html/_me_infrared_receiver_8cpp.html create mode 100644 doc/html/_me_infrared_receiver_8cpp__incl.map create mode 100644 doc/html/_me_infrared_receiver_8cpp__incl.md5 create mode 100644 doc/html/_me_infrared_receiver_8cpp__incl.png create mode 100644 doc/html/_me_infrared_receiver_8h.html create mode 100644 doc/html/_me_infrared_receiver_8h.js create mode 100644 doc/html/_me_infrared_receiver_8h__dep__incl.map create mode 100644 doc/html/_me_infrared_receiver_8h__dep__incl.md5 create mode 100644 doc/html/_me_infrared_receiver_8h__dep__incl.png create mode 100644 doc/html/_me_infrared_receiver_8h__incl.map create mode 100644 doc/html/_me_infrared_receiver_8h__incl.md5 create mode 100644 doc/html/_me_infrared_receiver_8h__incl.png create mode 100644 doc/html/_me_infrared_receiver_8h_source.html create mode 100644 doc/html/_me_joystick_8cpp.html create mode 100644 doc/html/_me_joystick_8cpp__incl.map create mode 100644 doc/html/_me_joystick_8cpp__incl.md5 create mode 100644 doc/html/_me_joystick_8cpp__incl.png create mode 100644 doc/html/_me_joystick_8h.html create mode 100644 doc/html/_me_joystick_8h.js create mode 100644 doc/html/_me_joystick_8h__dep__incl.map create mode 100644 doc/html/_me_joystick_8h__dep__incl.md5 create mode 100644 doc/html/_me_joystick_8h__dep__incl.png create mode 100644 doc/html/_me_joystick_8h__incl.map create mode 100644 doc/html/_me_joystick_8h__incl.md5 create mode 100644 doc/html/_me_joystick_8h__incl.png create mode 100644 doc/html/_me_joystick_8h_source.html create mode 100644 doc/html/_me_joystick_test_8ino-example.html create mode 100644 doc/html/_me_l_e_d_matrix_8cpp.html create mode 100644 doc/html/_me_l_e_d_matrix_8cpp__incl.map create mode 100644 doc/html/_me_l_e_d_matrix_8cpp__incl.md5 create mode 100644 doc/html/_me_l_e_d_matrix_8cpp__incl.png create mode 100644 doc/html/_me_l_e_d_matrix_8h.html create mode 100644 doc/html/_me_l_e_d_matrix_8h.js create mode 100644 doc/html/_me_l_e_d_matrix_8h__dep__incl.map create mode 100644 doc/html/_me_l_e_d_matrix_8h__dep__incl.md5 create mode 100644 doc/html/_me_l_e_d_matrix_8h__dep__incl.png create mode 100644 doc/html/_me_l_e_d_matrix_8h__incl.map create mode 100644 doc/html/_me_l_e_d_matrix_8h__incl.md5 create mode 100644 doc/html/_me_l_e_d_matrix_8h__incl.png create mode 100644 doc/html/_me_l_e_d_matrix_8h_source.html create mode 100644 doc/html/_me_l_e_d_matrix_data_8h.html create mode 100644 doc/html/_me_l_e_d_matrix_data_8h.js create mode 100644 doc/html/_me_l_e_d_matrix_data_8h__dep__incl.map create mode 100644 doc/html/_me_l_e_d_matrix_data_8h__dep__incl.md5 create mode 100644 doc/html/_me_l_e_d_matrix_data_8h__dep__incl.png create mode 100644 doc/html/_me_l_e_d_matrix_data_8h_source.html create mode 100644 doc/html/_me_light_sensor_8cpp.html create mode 100644 doc/html/_me_light_sensor_8cpp__incl.map create mode 100644 doc/html/_me_light_sensor_8cpp__incl.md5 create mode 100644 doc/html/_me_light_sensor_8cpp__incl.png create mode 100644 doc/html/_me_light_sensor_8h.html create mode 100644 doc/html/_me_light_sensor_8h.js create mode 100644 doc/html/_me_light_sensor_8h__dep__incl.map create mode 100644 doc/html/_me_light_sensor_8h__dep__incl.md5 create mode 100644 doc/html/_me_light_sensor_8h__dep__incl.png create mode 100644 doc/html/_me_light_sensor_8h__incl.map create mode 100644 doc/html/_me_light_sensor_8h__incl.md5 create mode 100644 doc/html/_me_light_sensor_8h__incl.png create mode 100644 doc/html/_me_light_sensor_8h_source.html create mode 100644 doc/html/_me_light_sensor_test_8ino-example.html create mode 100644 doc/html/_me_light_sensor_test_reset_port_8ino-example.html create mode 100644 doc/html/_me_light_sensor_test_with_l_e_don_8ino-example.html create mode 100644 doc/html/_me_limit_switch_8cpp.html create mode 100644 doc/html/_me_limit_switch_8cpp__incl.map create mode 100644 doc/html/_me_limit_switch_8cpp__incl.md5 create mode 100644 doc/html/_me_limit_switch_8cpp__incl.png create mode 100644 doc/html/_me_limit_switch_8h.html create mode 100644 doc/html/_me_limit_switch_8h.js create mode 100644 doc/html/_me_limit_switch_8h__dep__incl.map create mode 100644 doc/html/_me_limit_switch_8h__dep__incl.md5 create mode 100644 doc/html/_me_limit_switch_8h__dep__incl.png create mode 100644 doc/html/_me_limit_switch_8h__incl.map create mode 100644 doc/html/_me_limit_switch_8h__incl.md5 create mode 100644 doc/html/_me_limit_switch_8h__incl.png create mode 100644 doc/html/_me_limit_switch_8h_source.html create mode 100644 doc/html/_me_line_follower_8cpp.html create mode 100644 doc/html/_me_line_follower_8cpp__incl.map create mode 100644 doc/html/_me_line_follower_8cpp__incl.md5 create mode 100644 doc/html/_me_line_follower_8cpp__incl.png create mode 100644 doc/html/_me_line_follower_8h.html create mode 100644 doc/html/_me_line_follower_8h.js create mode 100644 doc/html/_me_line_follower_8h__dep__incl.map create mode 100644 doc/html/_me_line_follower_8h__dep__incl.md5 create mode 100644 doc/html/_me_line_follower_8h__dep__incl.png create mode 100644 doc/html/_me_line_follower_8h__incl.map create mode 100644 doc/html/_me_line_follower_8h__incl.md5 create mode 100644 doc/html/_me_line_follower_8h__incl.png create mode 100644 doc/html/_me_line_follower_8h_source.html create mode 100644 doc/html/_me_m_core_8h.html create mode 100644 doc/html/_me_m_core_8h__incl.map create mode 100644 doc/html/_me_m_core_8h__incl.md5 create mode 100644 doc/html/_me_m_core_8h__incl.png create mode 100644 doc/html/_me_m_core_8h_source.html create mode 100644 doc/html/_me_mbot_d_c_motor_8cpp.html create mode 100644 doc/html/_me_mbot_d_c_motor_8cpp__incl.map create mode 100644 doc/html/_me_mbot_d_c_motor_8cpp__incl.md5 create mode 100644 doc/html/_me_mbot_d_c_motor_8cpp__incl.png create mode 100644 doc/html/_me_mbot_d_c_motor_8h.html create mode 100644 doc/html/_me_mbot_d_c_motor_8h.js create mode 100644 doc/html/_me_mbot_d_c_motor_8h__dep__incl.map create mode 100644 doc/html/_me_mbot_d_c_motor_8h__dep__incl.md5 create mode 100644 doc/html/_me_mbot_d_c_motor_8h__dep__incl.png create mode 100644 doc/html/_me_mbot_d_c_motor_8h__incl.map create mode 100644 doc/html/_me_mbot_d_c_motor_8h__incl.md5 create mode 100644 doc/html/_me_mbot_d_c_motor_8h__incl.png create mode 100644 doc/html/_me_mbot_d_c_motor_8h_source.html create mode 100644 doc/html/_me_mega_pi_8h.html create mode 100644 doc/html/_me_mega_pi_8h__incl.map create mode 100644 doc/html/_me_mega_pi_8h__incl.md5 create mode 100644 doc/html/_me_mega_pi_8h__incl.png create mode 100644 doc/html/_me_mega_pi_8h_source.html create mode 100644 doc/html/_me_mega_pi_d_c_motor_8cpp.html create mode 100644 doc/html/_me_mega_pi_d_c_motor_8cpp__incl.map create mode 100644 doc/html/_me_mega_pi_d_c_motor_8cpp__incl.md5 create mode 100644 doc/html/_me_mega_pi_d_c_motor_8cpp__incl.png create mode 100644 doc/html/_me_mega_pi_d_c_motor_8h.html create mode 100644 doc/html/_me_mega_pi_d_c_motor_8h.js create mode 100644 doc/html/_me_mega_pi_d_c_motor_8h__dep__incl.map create mode 100644 doc/html/_me_mega_pi_d_c_motor_8h__dep__incl.md5 create mode 100644 doc/html/_me_mega_pi_d_c_motor_8h__dep__incl.png create mode 100644 doc/html/_me_mega_pi_d_c_motor_8h__incl.map create mode 100644 doc/html/_me_mega_pi_d_c_motor_8h__incl.md5 create mode 100644 doc/html/_me_mega_pi_d_c_motor_8h__incl.png create mode 100644 doc/html/_me_mega_pi_d_c_motor_8h_source.html create mode 100644 doc/html/_me_mega_pi_d_c_motor_test_8ino-example.html create mode 100644 doc/html/_me_mega_pi_pro4_dc_motor_8cpp.html create mode 100644 doc/html/_me_mega_pi_pro4_dc_motor_8cpp__incl.map create mode 100644 doc/html/_me_mega_pi_pro4_dc_motor_8cpp__incl.md5 create mode 100644 doc/html/_me_mega_pi_pro4_dc_motor_8cpp__incl.png create mode 100644 doc/html/_me_mega_pi_pro4_dc_motor_8h.html create mode 100644 doc/html/_me_mega_pi_pro4_dc_motor_8h.js create mode 100644 doc/html/_me_mega_pi_pro4_dc_motor_8h__dep__incl.map create mode 100644 doc/html/_me_mega_pi_pro4_dc_motor_8h__dep__incl.md5 create mode 100644 doc/html/_me_mega_pi_pro4_dc_motor_8h__dep__incl.png create mode 100644 doc/html/_me_mega_pi_pro4_dc_motor_8h__incl.map create mode 100644 doc/html/_me_mega_pi_pro4_dc_motor_8h__incl.md5 create mode 100644 doc/html/_me_mega_pi_pro4_dc_motor_8h__incl.png create mode 100644 doc/html/_me_mega_pi_pro4_dc_motor_8h_source.html create mode 100644 doc/html/_me_mega_pi_pro_8h.html create mode 100644 doc/html/_me_mega_pi_pro_8h__incl.map create mode 100644 doc/html/_me_mega_pi_pro_8h__incl.md5 create mode 100644 doc/html/_me_mega_pi_pro_8h__incl.png create mode 100644 doc/html/_me_mega_pi_pro_8h_source.html create mode 100644 doc/html/_me_mega_pi_pro_e_s_c_motor_8cpp.html create mode 100644 doc/html/_me_mega_pi_pro_e_s_c_motor_8cpp__incl.map create mode 100644 doc/html/_me_mega_pi_pro_e_s_c_motor_8cpp__incl.md5 create mode 100644 doc/html/_me_mega_pi_pro_e_s_c_motor_8cpp__incl.png create mode 100644 doc/html/_me_mega_pi_pro_e_s_c_motor_8h.html create mode 100644 doc/html/_me_mega_pi_pro_e_s_c_motor_8h.js create mode 100644 doc/html/_me_mega_pi_pro_e_s_c_motor_8h__dep__incl.map create mode 100644 doc/html/_me_mega_pi_pro_e_s_c_motor_8h__dep__incl.md5 create mode 100644 doc/html/_me_mega_pi_pro_e_s_c_motor_8h__dep__incl.png create mode 100644 doc/html/_me_mega_pi_pro_e_s_c_motor_8h__incl.map create mode 100644 doc/html/_me_mega_pi_pro_e_s_c_motor_8h__incl.md5 create mode 100644 doc/html/_me_mega_pi_pro_e_s_c_motor_8h__incl.png create mode 100644 doc/html/_me_mega_pi_pro_e_s_c_motor_8h_source.html create mode 100644 doc/html/_me_mega_pi_pro_e_s_c_motor_8ino-example.html create mode 100644 doc/html/_me_on_board_temp_8cpp.html create mode 100644 doc/html/_me_on_board_temp_8cpp__incl.map create mode 100644 doc/html/_me_on_board_temp_8cpp__incl.md5 create mode 100644 doc/html/_me_on_board_temp_8cpp__incl.png create mode 100644 doc/html/_me_on_board_temp_8h.html create mode 100644 doc/html/_me_on_board_temp_8h.js create mode 100644 doc/html/_me_on_board_temp_8h__dep__incl.map create mode 100644 doc/html/_me_on_board_temp_8h__dep__incl.md5 create mode 100644 doc/html/_me_on_board_temp_8h__dep__incl.png create mode 100644 doc/html/_me_on_board_temp_8h__incl.map create mode 100644 doc/html/_me_on_board_temp_8h__incl.md5 create mode 100644 doc/html/_me_on_board_temp_8h__incl.png create mode 100644 doc/html/_me_on_board_temp_8h_source.html create mode 100644 doc/html/_me_on_board_temp_test_8ino-example.html create mode 100644 doc/html/_me_one_wire_8cpp.html create mode 100644 doc/html/_me_one_wire_8cpp__incl.map create mode 100644 doc/html/_me_one_wire_8cpp__incl.md5 create mode 100644 doc/html/_me_one_wire_8cpp__incl.png create mode 100644 doc/html/_me_one_wire_8h.html create mode 100644 doc/html/_me_one_wire_8h.js create mode 100644 doc/html/_me_one_wire_8h__dep__incl.map create mode 100644 doc/html/_me_one_wire_8h__dep__incl.md5 create mode 100644 doc/html/_me_one_wire_8h__dep__incl.png create mode 100644 doc/html/_me_one_wire_8h__incl.map create mode 100644 doc/html/_me_one_wire_8h__incl.md5 create mode 100644 doc/html/_me_one_wire_8h__incl.png create mode 100644 doc/html/_me_one_wire_8h_source.html create mode 100644 doc/html/_me_orion_8h.html create mode 100644 doc/html/_me_orion_8h__incl.map create mode 100644 doc/html/_me_orion_8h__incl.md5 create mode 100644 doc/html/_me_orion_8h__incl.png create mode 100644 doc/html/_me_orion_8h_source.html create mode 100644 doc/html/_me_p_i_r_motion_sensor_8cpp.html create mode 100644 doc/html/_me_p_i_r_motion_sensor_8cpp__incl.map create mode 100644 doc/html/_me_p_i_r_motion_sensor_8cpp__incl.md5 create mode 100644 doc/html/_me_p_i_r_motion_sensor_8cpp__incl.png create mode 100644 doc/html/_me_p_i_r_motion_sensor_8h.html create mode 100644 doc/html/_me_p_i_r_motion_sensor_8h.js create mode 100644 doc/html/_me_p_i_r_motion_sensor_8h__dep__incl.map create mode 100644 doc/html/_me_p_i_r_motion_sensor_8h__dep__incl.md5 create mode 100644 doc/html/_me_p_i_r_motion_sensor_8h__dep__incl.png create mode 100644 doc/html/_me_p_i_r_motion_sensor_8h__incl.map create mode 100644 doc/html/_me_p_i_r_motion_sensor_8h__incl.md5 create mode 100644 doc/html/_me_p_i_r_motion_sensor_8h__incl.png create mode 100644 doc/html/_me_p_i_r_motion_sensor_8h_source.html create mode 100644 doc/html/_me_p_s2_8cpp.html create mode 100644 doc/html/_me_p_s2_8cpp__incl.map create mode 100644 doc/html/_me_p_s2_8cpp__incl.md5 create mode 100644 doc/html/_me_p_s2_8cpp__incl.png create mode 100644 doc/html/_me_p_s2_8h.html create mode 100644 doc/html/_me_p_s2_8h.js create mode 100644 doc/html/_me_p_s2_8h__dep__incl.map create mode 100644 doc/html/_me_p_s2_8h__dep__incl.md5 create mode 100644 doc/html/_me_p_s2_8h__dep__incl.png create mode 100644 doc/html/_me_p_s2_8h__incl.map create mode 100644 doc/html/_me_p_s2_8h__incl.md5 create mode 100644 doc/html/_me_p_s2_8h__incl.png create mode 100644 doc/html/_me_p_s2_8h_source.html create mode 100644 doc/html/_me_p_s2_test_8ino-example.html create mode 100644 doc/html/_me_pm25_sensor_8cpp.html create mode 100644 doc/html/_me_pm25_sensor_8cpp__incl.map create mode 100644 doc/html/_me_pm25_sensor_8cpp__incl.md5 create mode 100644 doc/html/_me_pm25_sensor_8cpp__incl.png create mode 100644 doc/html/_me_pm25_sensor_8h.html create mode 100644 doc/html/_me_pm25_sensor_8h.js create mode 100644 doc/html/_me_pm25_sensor_8h__dep__incl.map create mode 100644 doc/html/_me_pm25_sensor_8h__dep__incl.md5 create mode 100644 doc/html/_me_pm25_sensor_8h__dep__incl.png create mode 100644 doc/html/_me_pm25_sensor_8h__incl.map create mode 100644 doc/html/_me_pm25_sensor_8h__incl.md5 create mode 100644 doc/html/_me_pm25_sensor_8h__incl.png create mode 100644 doc/html/_me_pm25_sensor_8h_source.html create mode 100644 doc/html/_me_port_8cpp.html create mode 100644 doc/html/_me_port_8cpp__incl.map create mode 100644 doc/html/_me_port_8cpp__incl.md5 create mode 100644 doc/html/_me_port_8cpp__incl.png create mode 100644 doc/html/_me_port_8h.html create mode 100644 doc/html/_me_port_8h.js create mode 100644 doc/html/_me_port_8h__dep__incl.map create mode 100644 doc/html/_me_port_8h__dep__incl.md5 create mode 100644 doc/html/_me_port_8h__dep__incl.png create mode 100644 doc/html/_me_port_8h__incl.map create mode 100644 doc/html/_me_port_8h__incl.md5 create mode 100644 doc/html/_me_port_8h__incl.png create mode 100644 doc/html/_me_port_8h_source.html create mode 100644 doc/html/_me_potentiometer_8cpp.html create mode 100644 doc/html/_me_potentiometer_8cpp__incl.map create mode 100644 doc/html/_me_potentiometer_8cpp__incl.md5 create mode 100644 doc/html/_me_potentiometer_8cpp__incl.png create mode 100644 doc/html/_me_potentiometer_8h.html create mode 100644 doc/html/_me_potentiometer_8h.js create mode 100644 doc/html/_me_potentiometer_8h__dep__incl.map create mode 100644 doc/html/_me_potentiometer_8h__dep__incl.md5 create mode 100644 doc/html/_me_potentiometer_8h__dep__incl.png create mode 100644 doc/html/_me_potentiometer_8h__incl.map create mode 100644 doc/html/_me_potentiometer_8h__incl.md5 create mode 100644 doc/html/_me_potentiometer_8h__incl.png create mode 100644 doc/html/_me_potentiometer_8h_source.html create mode 100644 doc/html/_me_pressure_sensor_8h_source.html create mode 100644 doc/html/_me_r_g_b_led_8cpp.html create mode 100644 doc/html/_me_r_g_b_led_8cpp__incl.map create mode 100644 doc/html/_me_r_g_b_led_8cpp__incl.md5 create mode 100644 doc/html/_me_r_g_b_led_8cpp__incl.png create mode 100644 doc/html/_me_r_g_b_led_8h.html create mode 100644 doc/html/_me_r_g_b_led_8h.js create mode 100644 doc/html/_me_r_g_b_led_8h__dep__incl.map create mode 100644 doc/html/_me_r_g_b_led_8h__dep__incl.md5 create mode 100644 doc/html/_me_r_g_b_led_8h__dep__incl.png create mode 100644 doc/html/_me_r_g_b_led_8h__incl.map create mode 100644 doc/html/_me_r_g_b_led_8h__incl.md5 create mode 100644 doc/html/_me_r_g_b_led_8h__incl.png create mode 100644 doc/html/_me_r_g_b_led_8h_source.html create mode 100644 doc/html/_me_serial_8cpp.html create mode 100644 doc/html/_me_serial_8cpp__incl.map create mode 100644 doc/html/_me_serial_8cpp__incl.md5 create mode 100644 doc/html/_me_serial_8cpp__incl.png create mode 100644 doc/html/_me_serial_8h.html create mode 100644 doc/html/_me_serial_8h.js create mode 100644 doc/html/_me_serial_8h__dep__incl.map create mode 100644 doc/html/_me_serial_8h__dep__incl.md5 create mode 100644 doc/html/_me_serial_8h__dep__incl.png create mode 100644 doc/html/_me_serial_8h__incl.map create mode 100644 doc/html/_me_serial_8h__incl.md5 create mode 100644 doc/html/_me_serial_8h__incl.png create mode 100644 doc/html/_me_serial_8h_source.html create mode 100644 doc/html/_me_serial_receive_test_8ino-example.html create mode 100644 doc/html/_me_serial_transmit_test_8ino-example.html create mode 100644 doc/html/_me_shield_8h.html create mode 100644 doc/html/_me_shield_8h__incl.map create mode 100644 doc/html/_me_shield_8h__incl.md5 create mode 100644 doc/html/_me_shield_8h__incl.png create mode 100644 doc/html/_me_shield_8h_source.html create mode 100644 doc/html/_me_shutter_8cpp.html create mode 100644 doc/html/_me_shutter_8cpp__incl.map create mode 100644 doc/html/_me_shutter_8cpp__incl.md5 create mode 100644 doc/html/_me_shutter_8cpp__incl.png create mode 100644 doc/html/_me_shutter_8h.html create mode 100644 doc/html/_me_shutter_8h.js create mode 100644 doc/html/_me_shutter_8h__dep__incl.map create mode 100644 doc/html/_me_shutter_8h__dep__incl.md5 create mode 100644 doc/html/_me_shutter_8h__dep__incl.png create mode 100644 doc/html/_me_shutter_8h__incl.map create mode 100644 doc/html/_me_shutter_8h__incl.md5 create mode 100644 doc/html/_me_shutter_8h__incl.png create mode 100644 doc/html/_me_shutter_8h_source.html create mode 100644 doc/html/_me_shutter_test_8ino-example.html create mode 100644 doc/html/_me_smart_servo_8cpp.html create mode 100644 doc/html/_me_smart_servo_8cpp__incl.map create mode 100644 doc/html/_me_smart_servo_8cpp__incl.md5 create mode 100644 doc/html/_me_smart_servo_8cpp__incl.png create mode 100644 doc/html/_me_smart_servo_8h.html create mode 100644 doc/html/_me_smart_servo_8h.js create mode 100644 doc/html/_me_smart_servo_8h__dep__incl.map create mode 100644 doc/html/_me_smart_servo_8h__dep__incl.md5 create mode 100644 doc/html/_me_smart_servo_8h__dep__incl.png create mode 100644 doc/html/_me_smart_servo_8h__incl.map create mode 100644 doc/html/_me_smart_servo_8h__incl.md5 create mode 100644 doc/html/_me_smart_servo_8h__incl.png create mode 100644 doc/html/_me_smart_servo_8h_source.html create mode 100644 doc/html/_me_sound_sensor_8cpp.html create mode 100644 doc/html/_me_sound_sensor_8cpp__incl.map create mode 100644 doc/html/_me_sound_sensor_8cpp__incl.md5 create mode 100644 doc/html/_me_sound_sensor_8cpp__incl.png create mode 100644 doc/html/_me_stepper_8cpp.html create mode 100644 doc/html/_me_stepper_8cpp.js create mode 100644 doc/html/_me_stepper_8cpp__incl.map create mode 100644 doc/html/_me_stepper_8cpp__incl.md5 create mode 100644 doc/html/_me_stepper_8cpp__incl.png create mode 100644 doc/html/_me_stepper_8h.html create mode 100644 doc/html/_me_stepper_8h.js create mode 100644 doc/html/_me_stepper_8h__dep__incl.map create mode 100644 doc/html/_me_stepper_8h__dep__incl.md5 create mode 100644 doc/html/_me_stepper_8h__dep__incl.png create mode 100644 doc/html/_me_stepper_8h__incl.map create mode 100644 doc/html/_me_stepper_8h__incl.md5 create mode 100644 doc/html/_me_stepper_8h__incl.png create mode 100644 doc/html/_me_stepper_8h_source.html create mode 100644 doc/html/_me_stepper_on_board_8cpp.html create mode 100644 doc/html/_me_stepper_on_board_8cpp.js create mode 100644 doc/html/_me_stepper_on_board_8cpp__incl.map create mode 100644 doc/html/_me_stepper_on_board_8cpp__incl.md5 create mode 100644 doc/html/_me_stepper_on_board_8cpp__incl.png create mode 100644 doc/html/_me_stepper_on_board_8h.html create mode 100644 doc/html/_me_stepper_on_board_8h.js create mode 100644 doc/html/_me_stepper_on_board_8h__dep__incl.map create mode 100644 doc/html/_me_stepper_on_board_8h__dep__incl.md5 create mode 100644 doc/html/_me_stepper_on_board_8h__dep__incl.png create mode 100644 doc/html/_me_stepper_on_board_8h__incl.map create mode 100644 doc/html/_me_stepper_on_board_8h__incl.md5 create mode 100644 doc/html/_me_stepper_on_board_8h__incl.png create mode 100644 doc/html/_me_stepper_on_board_8h_source.html create mode 100644 doc/html/_me_temperature_8cpp.html create mode 100644 doc/html/_me_temperature_8cpp__incl.map create mode 100644 doc/html/_me_temperature_8cpp__incl.md5 create mode 100644 doc/html/_me_temperature_8cpp__incl.png create mode 100644 doc/html/_me_temperature_8h.html create mode 100644 doc/html/_me_temperature_8h.js create mode 100644 doc/html/_me_temperature_8h__dep__incl.map create mode 100644 doc/html/_me_temperature_8h__dep__incl.md5 create mode 100644 doc/html/_me_temperature_8h__dep__incl.png create mode 100644 doc/html/_me_temperature_8h__incl.map create mode 100644 doc/html/_me_temperature_8h__incl.md5 create mode 100644 doc/html/_me_temperature_8h__incl.png create mode 100644 doc/html/_me_temperature_8h_source.html create mode 100644 doc/html/_me_touch_sensor_8cpp.html create mode 100644 doc/html/_me_touch_sensor_8cpp__incl.map create mode 100644 doc/html/_me_touch_sensor_8cpp__incl.md5 create mode 100644 doc/html/_me_touch_sensor_8cpp__incl.png create mode 100644 doc/html/_me_touch_sensor_8h.html create mode 100644 doc/html/_me_touch_sensor_8h.js create mode 100644 doc/html/_me_touch_sensor_8h__dep__incl.map create mode 100644 doc/html/_me_touch_sensor_8h__dep__incl.md5 create mode 100644 doc/html/_me_touch_sensor_8h__dep__incl.png create mode 100644 doc/html/_me_touch_sensor_8h__incl.map create mode 100644 doc/html/_me_touch_sensor_8h__incl.md5 create mode 100644 doc/html/_me_touch_sensor_8h__incl.png create mode 100644 doc/html/_me_touch_sensor_8h_source.html create mode 100644 doc/html/_me_u_s_b_host_8cpp.html create mode 100644 doc/html/_me_u_s_b_host_8cpp__incl.map create mode 100644 doc/html/_me_u_s_b_host_8cpp__incl.md5 create mode 100644 doc/html/_me_u_s_b_host_8cpp__incl.png create mode 100644 doc/html/_me_u_s_b_host_8h.html create mode 100644 doc/html/_me_u_s_b_host_8h.js create mode 100644 doc/html/_me_u_s_b_host_8h__dep__incl.map create mode 100644 doc/html/_me_u_s_b_host_8h__dep__incl.md5 create mode 100644 doc/html/_me_u_s_b_host_8h__dep__incl.png create mode 100644 doc/html/_me_u_s_b_host_8h__incl.map create mode 100644 doc/html/_me_u_s_b_host_8h__incl.md5 create mode 100644 doc/html/_me_u_s_b_host_8h__incl.png create mode 100644 doc/html/_me_u_s_b_host_8h_source.html create mode 100644 doc/html/_me_ultrasonic_sensor_8cpp.html create mode 100644 doc/html/_me_ultrasonic_sensor_8cpp__incl.map create mode 100644 doc/html/_me_ultrasonic_sensor_8cpp__incl.md5 create mode 100644 doc/html/_me_ultrasonic_sensor_8cpp__incl.png create mode 100644 doc/html/_me_ultrasonic_sensor_8h.html create mode 100644 doc/html/_me_ultrasonic_sensor_8h.js create mode 100644 doc/html/_me_ultrasonic_sensor_8h__dep__incl.map create mode 100644 doc/html/_me_ultrasonic_sensor_8h__dep__incl.md5 create mode 100644 doc/html/_me_ultrasonic_sensor_8h__dep__incl.png create mode 100644 doc/html/_me_ultrasonic_sensor_8h__incl.map create mode 100644 doc/html/_me_ultrasonic_sensor_8h__incl.md5 create mode 100644 doc/html/_me_ultrasonic_sensor_8h__incl.png create mode 100644 doc/html/_me_ultrasonic_sensor_8h_source.html create mode 100644 doc/html/_me_voice_8cpp.html create mode 100644 doc/html/_me_voice_8cpp__incl.map create mode 100644 doc/html/_me_voice_8cpp__incl.md5 create mode 100644 doc/html/_me_voice_8cpp__incl.png create mode 100644 doc/html/_me_voice_8h.html create mode 100644 doc/html/_me_voice_8h.js create mode 100644 doc/html/_me_voice_8h__dep__incl.map create mode 100644 doc/html/_me_voice_8h__dep__incl.md5 create mode 100644 doc/html/_me_voice_8h__dep__incl.png create mode 100644 doc/html/_me_voice_8h__incl.map create mode 100644 doc/html/_me_voice_8h__incl.md5 create mode 100644 doc/html/_me_voice_8h__incl.png create mode 100644 doc/html/_me_voice_8h_source.html create mode 100644 doc/html/_me_voice_test_8ino-example.html create mode 100644 doc/html/_me_wifi_8cpp.html create mode 100644 doc/html/_me_wifi_8cpp__incl.map create mode 100644 doc/html/_me_wifi_8cpp__incl.md5 create mode 100644 doc/html/_me_wifi_8cpp__incl.png create mode 100644 doc/html/_me_wifi_8h.html create mode 100644 doc/html/_me_wifi_8h.js create mode 100644 doc/html/_me_wifi_8h__dep__incl.map create mode 100644 doc/html/_me_wifi_8h__dep__incl.md5 create mode 100644 doc/html/_me_wifi_8h__dep__incl.png create mode 100644 doc/html/_me_wifi_8h__incl.map create mode 100644 doc/html/_me_wifi_8h__incl.md5 create mode 100644 doc/html/_me_wifi_8h__incl.png create mode 100644 doc/html/_me_wifi_8h_source.html create mode 100644 doc/html/_me_wifi_8ino-example.html create mode 100644 doc/html/_mega_pi_on_board_stepper_test_8ino-example.html create mode 100644 doc/html/_number_display_8ino-example.html create mode 100644 doc/html/_number_flow_8ino-example.html create mode 100644 doc/html/_p_i_r_motion_sensor_test_8ino-example.html create mode 100644 doc/html/_pm25_sensor_8ino-example.html create mode 100644 doc/html/_potentiometer_test_8ino-example.html create mode 100644 doc/html/_s_p_i_8h_source.html create mode 100644 doc/html/_servo_8h_source.html create mode 100644 doc/html/_servo_timers_8h_source.html create mode 100644 doc/html/_slave_bluetooth_by_soft_serial_test_8ino-example.html create mode 100644 doc/html/_smart_servo_test_8ino-example.html create mode 100644 doc/html/_software_serial_8h_source.html create mode 100644 doc/html/_sound_sensor_test_8ino-example.html create mode 100644 doc/html/_temperature_test_8ino-example.html create mode 100644 doc/html/_test_u_s_b_hsot_8ino-example.html create mode 100644 doc/html/_time_display_8ino-example.html create mode 100644 doc/html/_touch_sensor_test_8ino-example.html create mode 100644 doc/html/_ultrasonic_sensor_test_8ino-example.html create mode 100644 doc/html/_white_breath_light_test_8ino-example.html create mode 100644 doc/html/_wire_8h_source.html create mode 100644 doc/html/annotated.html create mode 100644 doc/html/annotated_dup.js create mode 100644 doc/html/bc_s.png create mode 100644 doc/html/bc_sd.png create mode 100644 doc/html/class_m_bot_d_c_motor-members.html create mode 100644 doc/html/class_m_bot_d_c_motor.html create mode 100644 doc/html/class_m_bot_d_c_motor.js create mode 100644 doc/html/class_m_bot_d_c_motor.png create mode 100644 doc/html/class_m_bot_d_c_motor__coll__graph.map create mode 100644 doc/html/class_m_bot_d_c_motor__coll__graph.md5 create mode 100644 doc/html/class_m_bot_d_c_motor__coll__graph.png create mode 100644 doc/html/class_m_bot_d_c_motor__inherit__graph.map create mode 100644 doc/html/class_m_bot_d_c_motor__inherit__graph.md5 create mode 100644 doc/html/class_m_bot_d_c_motor__inherit__graph.png create mode 100644 doc/html/class_me4_button-members.html create mode 100644 doc/html/class_me4_button.html create mode 100644 doc/html/class_me4_button.js create mode 100644 doc/html/class_me4_button.png create mode 100644 doc/html/class_me4_button__coll__graph.map create mode 100644 doc/html/class_me4_button__coll__graph.md5 create mode 100644 doc/html/class_me4_button__coll__graph.png create mode 100644 doc/html/class_me4_button__inherit__graph.map create mode 100644 doc/html/class_me4_button__inherit__graph.md5 create mode 100644 doc/html/class_me4_button__inherit__graph.png create mode 100644 doc/html/class_me7_segment_display-members.html create mode 100644 doc/html/class_me7_segment_display.html create mode 100644 doc/html/class_me7_segment_display.js create mode 100644 doc/html/class_me7_segment_display.png create mode 100644 doc/html/class_me7_segment_display__coll__graph.map create mode 100644 doc/html/class_me7_segment_display__coll__graph.md5 create mode 100644 doc/html/class_me7_segment_display__coll__graph.png create mode 100644 doc/html/class_me7_segment_display__inherit__graph.map create mode 100644 doc/html/class_me7_segment_display__inherit__graph.md5 create mode 100644 doc/html/class_me7_segment_display__inherit__graph.png create mode 100644 doc/html/class_me_bluetooth-members.html create mode 100644 doc/html/class_me_bluetooth.html create mode 100644 doc/html/class_me_bluetooth.js create mode 100644 doc/html/class_me_bluetooth.png create mode 100644 doc/html/class_me_bluetooth__coll__graph.map create mode 100644 doc/html/class_me_bluetooth__coll__graph.md5 create mode 100644 doc/html/class_me_bluetooth__coll__graph.png create mode 100644 doc/html/class_me_bluetooth__inherit__graph.map create mode 100644 doc/html/class_me_bluetooth__inherit__graph.md5 create mode 100644 doc/html/class_me_bluetooth__inherit__graph.png create mode 100644 doc/html/class_me_buzzer-members.html create mode 100644 doc/html/class_me_buzzer.html create mode 100644 doc/html/class_me_buzzer.js create mode 100644 doc/html/class_me_buzzer.png create mode 100644 doc/html/class_me_buzzer__coll__graph.map create mode 100644 doc/html/class_me_buzzer__coll__graph.md5 create mode 100644 doc/html/class_me_buzzer__coll__graph.png create mode 100644 doc/html/class_me_buzzer__inherit__graph.map create mode 100644 doc/html/class_me_buzzer__inherit__graph.md5 create mode 100644 doc/html/class_me_buzzer__inherit__graph.png create mode 100644 doc/html/class_me_color_sensor-members.html create mode 100644 doc/html/class_me_color_sensor.html create mode 100644 doc/html/class_me_color_sensor.js create mode 100644 doc/html/class_me_color_sensor.png create mode 100644 doc/html/class_me_color_sensor__coll__graph.map create mode 100644 doc/html/class_me_color_sensor__coll__graph.md5 create mode 100644 doc/html/class_me_color_sensor__coll__graph.png create mode 100644 doc/html/class_me_color_sensor__inherit__graph.map create mode 100644 doc/html/class_me_color_sensor__inherit__graph.md5 create mode 100644 doc/html/class_me_color_sensor__inherit__graph.png create mode 100644 doc/html/class_me_compass-members.html create mode 100644 doc/html/class_me_compass.html create mode 100644 doc/html/class_me_compass.js create mode 100644 doc/html/class_me_compass.png create mode 100644 doc/html/class_me_compass__coll__graph.map create mode 100644 doc/html/class_me_compass__coll__graph.md5 create mode 100644 doc/html/class_me_compass__coll__graph.png create mode 100644 doc/html/class_me_compass__inherit__graph.map create mode 100644 doc/html/class_me_compass__inherit__graph.md5 create mode 100644 doc/html/class_me_compass__inherit__graph.png create mode 100644 doc/html/class_me_d_c_motor-members.html create mode 100644 doc/html/class_me_d_c_motor.html create mode 100644 doc/html/class_me_d_c_motor.js create mode 100644 doc/html/class_me_d_c_motor.png create mode 100644 doc/html/class_me_d_c_motor__coll__graph.map create mode 100644 doc/html/class_me_d_c_motor__coll__graph.md5 create mode 100644 doc/html/class_me_d_c_motor__coll__graph.png create mode 100644 doc/html/class_me_d_c_motor__inherit__graph.map create mode 100644 doc/html/class_me_d_c_motor__inherit__graph.md5 create mode 100644 doc/html/class_me_d_c_motor__inherit__graph.png create mode 100644 doc/html/class_me_encoder_motor-members.html create mode 100644 doc/html/class_me_encoder_motor.html create mode 100644 doc/html/class_me_encoder_motor.js create mode 100644 doc/html/class_me_encoder_motor.png create mode 100644 doc/html/class_me_encoder_motor__coll__graph.map create mode 100644 doc/html/class_me_encoder_motor__coll__graph.md5 create mode 100644 doc/html/class_me_encoder_motor__coll__graph.png create mode 100644 doc/html/class_me_encoder_motor__inherit__graph.map create mode 100644 doc/html/class_me_encoder_motor__inherit__graph.md5 create mode 100644 doc/html/class_me_encoder_motor__inherit__graph.png create mode 100644 doc/html/class_me_encoder_new-members.html create mode 100644 doc/html/class_me_encoder_new.html create mode 100644 doc/html/class_me_encoder_new.js create mode 100644 doc/html/class_me_encoder_on_board-members.html create mode 100644 doc/html/class_me_encoder_on_board.html create mode 100644 doc/html/class_me_encoder_on_board.js create mode 100644 doc/html/class_me_flame_sensor-members.html create mode 100644 doc/html/class_me_flame_sensor.html create mode 100644 doc/html/class_me_flame_sensor.js create mode 100644 doc/html/class_me_flame_sensor.png create mode 100644 doc/html/class_me_flame_sensor__coll__graph.map create mode 100644 doc/html/class_me_flame_sensor__coll__graph.md5 create mode 100644 doc/html/class_me_flame_sensor__coll__graph.png create mode 100644 doc/html/class_me_flame_sensor__inherit__graph.map create mode 100644 doc/html/class_me_flame_sensor__inherit__graph.md5 create mode 100644 doc/html/class_me_flame_sensor__inherit__graph.png create mode 100644 doc/html/class_me_gas_sensor-members.html create mode 100644 doc/html/class_me_gas_sensor.html create mode 100644 doc/html/class_me_gas_sensor.js create mode 100644 doc/html/class_me_gas_sensor.png create mode 100644 doc/html/class_me_gas_sensor__coll__graph.map create mode 100644 doc/html/class_me_gas_sensor__coll__graph.md5 create mode 100644 doc/html/class_me_gas_sensor__coll__graph.png create mode 100644 doc/html/class_me_gas_sensor__inherit__graph.map create mode 100644 doc/html/class_me_gas_sensor__inherit__graph.md5 create mode 100644 doc/html/class_me_gas_sensor__inherit__graph.png create mode 100644 doc/html/class_me_gyro-members.html create mode 100644 doc/html/class_me_gyro.html create mode 100644 doc/html/class_me_gyro.js create mode 100644 doc/html/class_me_gyro.png create mode 100644 doc/html/class_me_gyro__coll__graph.map create mode 100644 doc/html/class_me_gyro__coll__graph.md5 create mode 100644 doc/html/class_me_gyro__coll__graph.png create mode 100644 doc/html/class_me_gyro__inherit__graph.map create mode 100644 doc/html/class_me_gyro__inherit__graph.md5 create mode 100644 doc/html/class_me_gyro__inherit__graph.png create mode 100644 doc/html/class_me_host_parser-members.html create mode 100644 doc/html/class_me_host_parser.html create mode 100644 doc/html/class_me_host_parser.js create mode 100644 doc/html/class_me_humiture-members.html create mode 100644 doc/html/class_me_humiture.html create mode 100644 doc/html/class_me_humiture.js create mode 100644 doc/html/class_me_humiture.png create mode 100644 doc/html/class_me_humiture__coll__graph.map create mode 100644 doc/html/class_me_humiture__coll__graph.md5 create mode 100644 doc/html/class_me_humiture__coll__graph.png create mode 100644 doc/html/class_me_humiture__inherit__graph.map create mode 100644 doc/html/class_me_humiture__inherit__graph.md5 create mode 100644 doc/html/class_me_humiture__inherit__graph.png create mode 100644 doc/html/class_me_i_r-members.html create mode 100644 doc/html/class_me_i_r.html create mode 100644 doc/html/class_me_i_r.js create mode 100644 doc/html/class_me_infrared_receiver-members.html create mode 100644 doc/html/class_me_infrared_receiver.html create mode 100644 doc/html/class_me_infrared_receiver.js create mode 100644 doc/html/class_me_infrared_receiver.png create mode 100644 doc/html/class_me_infrared_receiver__coll__graph.map create mode 100644 doc/html/class_me_infrared_receiver__coll__graph.md5 create mode 100644 doc/html/class_me_infrared_receiver__coll__graph.png create mode 100644 doc/html/class_me_infrared_receiver__inherit__graph.map create mode 100644 doc/html/class_me_infrared_receiver__inherit__graph.md5 create mode 100644 doc/html/class_me_infrared_receiver__inherit__graph.png create mode 100644 doc/html/class_me_joystick-members.html create mode 100644 doc/html/class_me_joystick.html create mode 100644 doc/html/class_me_joystick.js create mode 100644 doc/html/class_me_joystick.png create mode 100644 doc/html/class_me_joystick__coll__graph.map create mode 100644 doc/html/class_me_joystick__coll__graph.md5 create mode 100644 doc/html/class_me_joystick__coll__graph.png create mode 100644 doc/html/class_me_joystick__inherit__graph.map create mode 100644 doc/html/class_me_joystick__inherit__graph.md5 create mode 100644 doc/html/class_me_joystick__inherit__graph.png create mode 100644 doc/html/class_me_l_e_d_matrix-members.html create mode 100644 doc/html/class_me_l_e_d_matrix.html create mode 100644 doc/html/class_me_l_e_d_matrix.js create mode 100644 doc/html/class_me_l_e_d_matrix.png create mode 100644 doc/html/class_me_l_e_d_matrix__coll__graph.map create mode 100644 doc/html/class_me_l_e_d_matrix__coll__graph.md5 create mode 100644 doc/html/class_me_l_e_d_matrix__coll__graph.png create mode 100644 doc/html/class_me_l_e_d_matrix__inherit__graph.map create mode 100644 doc/html/class_me_l_e_d_matrix__inherit__graph.md5 create mode 100644 doc/html/class_me_l_e_d_matrix__inherit__graph.png create mode 100644 doc/html/class_me_light_sensor-members.html create mode 100644 doc/html/class_me_light_sensor.html create mode 100644 doc/html/class_me_light_sensor.js create mode 100644 doc/html/class_me_light_sensor.png create mode 100644 doc/html/class_me_light_sensor__coll__graph.map create mode 100644 doc/html/class_me_light_sensor__coll__graph.md5 create mode 100644 doc/html/class_me_light_sensor__coll__graph.png create mode 100644 doc/html/class_me_light_sensor__inherit__graph.map create mode 100644 doc/html/class_me_light_sensor__inherit__graph.md5 create mode 100644 doc/html/class_me_light_sensor__inherit__graph.png create mode 100644 doc/html/class_me_limit_switch-members.html create mode 100644 doc/html/class_me_limit_switch.html create mode 100644 doc/html/class_me_limit_switch.js create mode 100644 doc/html/class_me_limit_switch.png create mode 100644 doc/html/class_me_limit_switch__coll__graph.map create mode 100644 doc/html/class_me_limit_switch__coll__graph.md5 create mode 100644 doc/html/class_me_limit_switch__coll__graph.png create mode 100644 doc/html/class_me_limit_switch__inherit__graph.map create mode 100644 doc/html/class_me_limit_switch__inherit__graph.md5 create mode 100644 doc/html/class_me_limit_switch__inherit__graph.png create mode 100644 doc/html/class_me_line_follower-members.html create mode 100644 doc/html/class_me_line_follower.html create mode 100644 doc/html/class_me_line_follower.js create mode 100644 doc/html/class_me_line_follower.png create mode 100644 doc/html/class_me_line_follower__coll__graph.map create mode 100644 doc/html/class_me_line_follower__coll__graph.md5 create mode 100644 doc/html/class_me_line_follower__coll__graph.png create mode 100644 doc/html/class_me_line_follower__inherit__graph.map create mode 100644 doc/html/class_me_line_follower__inherit__graph.md5 create mode 100644 doc/html/class_me_line_follower__inherit__graph.png create mode 100644 doc/html/class_me_mega_pi_d_c_motor-members.html create mode 100644 doc/html/class_me_mega_pi_d_c_motor.html create mode 100644 doc/html/class_me_mega_pi_d_c_motor.js create mode 100644 doc/html/class_me_mega_pi_pro4_dc_motor-members.html create mode 100644 doc/html/class_me_mega_pi_pro4_dc_motor.html create mode 100644 doc/html/class_me_mega_pi_pro4_dc_motor.js create mode 100644 doc/html/class_me_mega_pi_pro4_dc_motor.png create mode 100644 doc/html/class_me_mega_pi_pro4_dc_motor__coll__graph.map create mode 100644 doc/html/class_me_mega_pi_pro4_dc_motor__coll__graph.md5 create mode 100644 doc/html/class_me_mega_pi_pro4_dc_motor__coll__graph.png create mode 100644 doc/html/class_me_mega_pi_pro4_dc_motor__inherit__graph.map create mode 100644 doc/html/class_me_mega_pi_pro4_dc_motor__inherit__graph.md5 create mode 100644 doc/html/class_me_mega_pi_pro4_dc_motor__inherit__graph.png create mode 100644 doc/html/class_me_mega_pi_pro_e_s_c_motor-members.html create mode 100644 doc/html/class_me_mega_pi_pro_e_s_c_motor.html create mode 100644 doc/html/class_me_mega_pi_pro_e_s_c_motor.js create mode 100644 doc/html/class_me_on_board_temp-members.html create mode 100644 doc/html/class_me_on_board_temp.html create mode 100644 doc/html/class_me_on_board_temp.js create mode 100644 doc/html/class_me_on_board_temp.png create mode 100644 doc/html/class_me_on_board_temp__coll__graph.map create mode 100644 doc/html/class_me_on_board_temp__coll__graph.md5 create mode 100644 doc/html/class_me_on_board_temp__coll__graph.png create mode 100644 doc/html/class_me_on_board_temp__inherit__graph.map create mode 100644 doc/html/class_me_on_board_temp__inherit__graph.md5 create mode 100644 doc/html/class_me_on_board_temp__inherit__graph.png create mode 100644 doc/html/class_me_one_wire-members.html create mode 100644 doc/html/class_me_one_wire.html create mode 100644 doc/html/class_me_one_wire.js create mode 100644 doc/html/class_me_p_i_r_motion_sensor-members.html create mode 100644 doc/html/class_me_p_i_r_motion_sensor.html create mode 100644 doc/html/class_me_p_i_r_motion_sensor.js create mode 100644 doc/html/class_me_p_i_r_motion_sensor.png create mode 100644 doc/html/class_me_p_i_r_motion_sensor__coll__graph.map create mode 100644 doc/html/class_me_p_i_r_motion_sensor__coll__graph.md5 create mode 100644 doc/html/class_me_p_i_r_motion_sensor__coll__graph.png create mode 100644 doc/html/class_me_p_i_r_motion_sensor__inherit__graph.map create mode 100644 doc/html/class_me_p_i_r_motion_sensor__inherit__graph.md5 create mode 100644 doc/html/class_me_p_i_r_motion_sensor__inherit__graph.png create mode 100644 doc/html/class_me_p_s2-members.html create mode 100644 doc/html/class_me_p_s2.html create mode 100644 doc/html/class_me_p_s2.js create mode 100644 doc/html/class_me_p_s2.png create mode 100644 doc/html/class_me_p_s2__coll__graph.map create mode 100644 doc/html/class_me_p_s2__coll__graph.md5 create mode 100644 doc/html/class_me_p_s2__coll__graph.png create mode 100644 doc/html/class_me_p_s2__inherit__graph.map create mode 100644 doc/html/class_me_p_s2__inherit__graph.md5 create mode 100644 doc/html/class_me_p_s2__inherit__graph.png create mode 100644 doc/html/class_me_pm25_sensor-members.html create mode 100644 doc/html/class_me_pm25_sensor.html create mode 100644 doc/html/class_me_pm25_sensor.js create mode 100644 doc/html/class_me_pm25_sensor.png create mode 100644 doc/html/class_me_pm25_sensor__coll__graph.map create mode 100644 doc/html/class_me_pm25_sensor__coll__graph.md5 create mode 100644 doc/html/class_me_pm25_sensor__coll__graph.png create mode 100644 doc/html/class_me_pm25_sensor__inherit__graph.map create mode 100644 doc/html/class_me_pm25_sensor__inherit__graph.md5 create mode 100644 doc/html/class_me_pm25_sensor__inherit__graph.png create mode 100644 doc/html/class_me_port-members.html create mode 100644 doc/html/class_me_port.html create mode 100644 doc/html/class_me_port.js create mode 100644 doc/html/class_me_port.png create mode 100644 doc/html/class_me_port__inherit__graph.map create mode 100644 doc/html/class_me_port__inherit__graph.md5 create mode 100644 doc/html/class_me_port__inherit__graph.png create mode 100644 doc/html/class_me_potentiometer-members.html create mode 100644 doc/html/class_me_potentiometer.html create mode 100644 doc/html/class_me_potentiometer.js create mode 100644 doc/html/class_me_potentiometer.png create mode 100644 doc/html/class_me_potentiometer__coll__graph.map create mode 100644 doc/html/class_me_potentiometer__coll__graph.md5 create mode 100644 doc/html/class_me_potentiometer__coll__graph.png create mode 100644 doc/html/class_me_potentiometer__inherit__graph.map create mode 100644 doc/html/class_me_potentiometer__inherit__graph.md5 create mode 100644 doc/html/class_me_potentiometer__inherit__graph.png create mode 100644 doc/html/class_me_pressure_sensor-members.html create mode 100644 doc/html/class_me_pressure_sensor.html create mode 100644 doc/html/class_me_r_g_b_led-members.html create mode 100644 doc/html/class_me_r_g_b_led.html create mode 100644 doc/html/class_me_r_g_b_led.js create mode 100644 doc/html/class_me_r_g_b_led.png create mode 100644 doc/html/class_me_r_g_b_led__coll__graph.map create mode 100644 doc/html/class_me_r_g_b_led__coll__graph.md5 create mode 100644 doc/html/class_me_r_g_b_led__coll__graph.png create mode 100644 doc/html/class_me_r_g_b_led__inherit__graph.map create mode 100644 doc/html/class_me_r_g_b_led__inherit__graph.md5 create mode 100644 doc/html/class_me_r_g_b_led__inherit__graph.png create mode 100644 doc/html/class_me_serial-members.html create mode 100644 doc/html/class_me_serial.html create mode 100644 doc/html/class_me_serial.js create mode 100644 doc/html/class_me_serial.png create mode 100644 doc/html/class_me_serial__coll__graph.map create mode 100644 doc/html/class_me_serial__coll__graph.md5 create mode 100644 doc/html/class_me_serial__coll__graph.png create mode 100644 doc/html/class_me_serial__inherit__graph.map create mode 100644 doc/html/class_me_serial__inherit__graph.md5 create mode 100644 doc/html/class_me_serial__inherit__graph.png create mode 100644 doc/html/class_me_shutter-members.html create mode 100644 doc/html/class_me_shutter.html create mode 100644 doc/html/class_me_shutter.js create mode 100644 doc/html/class_me_shutter.png create mode 100644 doc/html/class_me_shutter__coll__graph.map create mode 100644 doc/html/class_me_shutter__coll__graph.md5 create mode 100644 doc/html/class_me_shutter__coll__graph.png create mode 100644 doc/html/class_me_shutter__inherit__graph.map create mode 100644 doc/html/class_me_shutter__inherit__graph.md5 create mode 100644 doc/html/class_me_shutter__inherit__graph.png create mode 100644 doc/html/class_me_smart_servo-members.html create mode 100644 doc/html/class_me_smart_servo.html create mode 100644 doc/html/class_me_smart_servo.js create mode 100644 doc/html/class_me_smart_servo.png create mode 100644 doc/html/class_me_smart_servo__coll__graph.map create mode 100644 doc/html/class_me_smart_servo__coll__graph.md5 create mode 100644 doc/html/class_me_smart_servo__coll__graph.png create mode 100644 doc/html/class_me_smart_servo__inherit__graph.map create mode 100644 doc/html/class_me_smart_servo__inherit__graph.md5 create mode 100644 doc/html/class_me_smart_servo__inherit__graph.png create mode 100644 doc/html/class_me_sound_sensor.html create mode 100644 doc/html/class_me_stepper-members.html create mode 100644 doc/html/class_me_stepper.html create mode 100644 doc/html/class_me_stepper.js create mode 100644 doc/html/class_me_stepper.png create mode 100644 doc/html/class_me_stepper__coll__graph.map create mode 100644 doc/html/class_me_stepper__coll__graph.md5 create mode 100644 doc/html/class_me_stepper__coll__graph.png create mode 100644 doc/html/class_me_stepper__inherit__graph.map create mode 100644 doc/html/class_me_stepper__inherit__graph.md5 create mode 100644 doc/html/class_me_stepper__inherit__graph.png create mode 100644 doc/html/class_me_stepper_on_board-members.html create mode 100644 doc/html/class_me_stepper_on_board.html create mode 100644 doc/html/class_me_stepper_on_board.js create mode 100644 doc/html/class_me_temperature-members.html create mode 100644 doc/html/class_me_temperature.html create mode 100644 doc/html/class_me_temperature.js create mode 100644 doc/html/class_me_temperature.png create mode 100644 doc/html/class_me_temperature__coll__graph.map create mode 100644 doc/html/class_me_temperature__coll__graph.md5 create mode 100644 doc/html/class_me_temperature__coll__graph.png create mode 100644 doc/html/class_me_temperature__inherit__graph.map create mode 100644 doc/html/class_me_temperature__inherit__graph.md5 create mode 100644 doc/html/class_me_temperature__inherit__graph.png create mode 100644 doc/html/class_me_touch_sensor-members.html create mode 100644 doc/html/class_me_touch_sensor.html create mode 100644 doc/html/class_me_touch_sensor.js create mode 100644 doc/html/class_me_touch_sensor.png create mode 100644 doc/html/class_me_touch_sensor__coll__graph.map create mode 100644 doc/html/class_me_touch_sensor__coll__graph.md5 create mode 100644 doc/html/class_me_touch_sensor__coll__graph.png create mode 100644 doc/html/class_me_touch_sensor__inherit__graph.map create mode 100644 doc/html/class_me_touch_sensor__inherit__graph.md5 create mode 100644 doc/html/class_me_touch_sensor__inherit__graph.png create mode 100644 doc/html/class_me_u_s_b_host-members.html create mode 100644 doc/html/class_me_u_s_b_host.html create mode 100644 doc/html/class_me_u_s_b_host.js create mode 100644 doc/html/class_me_u_s_b_host.png create mode 100644 doc/html/class_me_u_s_b_host__coll__graph.map create mode 100644 doc/html/class_me_u_s_b_host__coll__graph.md5 create mode 100644 doc/html/class_me_u_s_b_host__coll__graph.png create mode 100644 doc/html/class_me_u_s_b_host__inherit__graph.map create mode 100644 doc/html/class_me_u_s_b_host__inherit__graph.md5 create mode 100644 doc/html/class_me_u_s_b_host__inherit__graph.png create mode 100644 doc/html/class_me_ultrasonic_sensor-members.html create mode 100644 doc/html/class_me_ultrasonic_sensor.html create mode 100644 doc/html/class_me_ultrasonic_sensor.js create mode 100644 doc/html/class_me_ultrasonic_sensor.png create mode 100644 doc/html/class_me_ultrasonic_sensor__coll__graph.map create mode 100644 doc/html/class_me_ultrasonic_sensor__coll__graph.md5 create mode 100644 doc/html/class_me_ultrasonic_sensor__coll__graph.png create mode 100644 doc/html/class_me_ultrasonic_sensor__inherit__graph.map create mode 100644 doc/html/class_me_ultrasonic_sensor__inherit__graph.md5 create mode 100644 doc/html/class_me_ultrasonic_sensor__inherit__graph.png create mode 100644 doc/html/class_me_voice-members.html create mode 100644 doc/html/class_me_voice.html create mode 100644 doc/html/class_me_voice.js create mode 100644 doc/html/class_me_voice.png create mode 100644 doc/html/class_me_voice__coll__graph.map create mode 100644 doc/html/class_me_voice__coll__graph.md5 create mode 100644 doc/html/class_me_voice__coll__graph.png create mode 100644 doc/html/class_me_voice__inherit__graph.map create mode 100644 doc/html/class_me_voice__inherit__graph.md5 create mode 100644 doc/html/class_me_voice__inherit__graph.png create mode 100644 doc/html/class_me_wifi-members.html create mode 100644 doc/html/class_me_wifi.html create mode 100644 doc/html/class_me_wifi.js create mode 100644 doc/html/class_me_wifi.png create mode 100644 doc/html/class_me_wifi__coll__graph.map create mode 100644 doc/html/class_me_wifi__coll__graph.md5 create mode 100644 doc/html/class_me_wifi__coll__graph.png create mode 100644 doc/html/class_me_wifi__inherit__graph.map create mode 100644 doc/html/class_me_wifi__inherit__graph.md5 create mode 100644 doc/html/class_me_wifi__inherit__graph.png create mode 100644 doc/html/class_mecolor.html create mode 100644 doc/html/class_s_p_i_class-members.html create mode 100644 doc/html/class_s_p_i_class.html create mode 100644 doc/html/class_s_p_i_settings-members.html create mode 100644 doc/html/class_s_p_i_settings.html create mode 100644 doc/html/class_servo-members.html create mode 100644 doc/html/class_servo.html create mode 100644 doc/html/class_software_serial-members.html create mode 100644 doc/html/class_software_serial.html create mode 100644 doc/html/class_software_serial.png create mode 100644 doc/html/class_software_serial__coll__graph.map create mode 100644 doc/html/class_software_serial__coll__graph.md5 create mode 100644 doc/html/class_software_serial__coll__graph.png create mode 100644 doc/html/class_software_serial__inherit__graph.map create mode 100644 doc/html/class_software_serial__inherit__graph.md5 create mode 100644 doc/html/class_software_serial__inherit__graph.png create mode 100644 doc/html/class_two_wire-members.html create mode 100644 doc/html/class_two_wire.html create mode 100644 doc/html/class_two_wire.png create mode 100644 doc/html/class_two_wire__coll__graph.map create mode 100644 doc/html/class_two_wire__coll__graph.md5 create mode 100644 doc/html/class_two_wire__coll__graph.png create mode 100644 doc/html/class_two_wire__inherit__graph.map create mode 100644 doc/html/class_two_wire__inherit__graph.md5 create mode 100644 doc/html/class_two_wire__inherit__graph.png create mode 100644 doc/html/classes.html create mode 100644 doc/html/closed.png create mode 100644 doc/html/dir_0619a8f54b4fad7043a6de45be8fde0b.html create mode 100644 doc/html/dir_0619a8f54b4fad7043a6de45be8fde0b.js create mode 100644 doc/html/dir_0619a8f54b4fad7043a6de45be8fde0b_dep.map create mode 100644 doc/html/dir_0619a8f54b4fad7043a6de45be8fde0b_dep.md5 create mode 100644 doc/html/dir_0619a8f54b4fad7043a6de45be8fde0b_dep.png create mode 100644 doc/html/dir_3643b276fb9490c80d50926eae963c39.html create mode 100644 doc/html/dir_3643b276fb9490c80d50926eae963c39.js create mode 100644 doc/html/dir_5f3ac822815499ba28918a50b5949c2d.html create mode 100644 doc/html/dir_5f3ac822815499ba28918a50b5949c2d.js create mode 100644 doc/html/dir_5f3ac822815499ba28918a50b5949c2d_dep.map create mode 100644 doc/html/dir_5f3ac822815499ba28918a50b5949c2d_dep.md5 create mode 100644 doc/html/dir_5f3ac822815499ba28918a50b5949c2d_dep.png create mode 100644 doc/html/dir_64e73385a8b7738563c26ce10415b58d.html create mode 100644 doc/html/dir_64e73385a8b7738563c26ce10415b58d.js create mode 100644 doc/html/dir_68267d1309a1af8e8297ef4c3efbcdba.html create mode 100644 doc/html/dir_68267d1309a1af8e8297ef4c3efbcdba.js create mode 100644 doc/html/dir_8ceffd4ee35c3518d4e8bdc7e638efe8.html create mode 100644 doc/html/dir_8ceffd4ee35c3518d4e8bdc7e638efe8.js create mode 100644 doc/html/dir_9b7846f2027e73718d3ad8e9e45ae6f0.html create mode 100644 doc/html/dir_9b7846f2027e73718d3ad8e9e45ae6f0.js create mode 100644 doc/html/dir_aa34f34d6add6a95738b68d2f2b128dc.html create mode 100644 doc/html/dir_aa34f34d6add6a95738b68d2f2b128dc.js create mode 100644 doc/html/dir_afb59ca96f269ed3ae4886598dd661d7.html create mode 100644 doc/html/dir_afb59ca96f269ed3ae4886598dd661d7.js create mode 100644 doc/html/dir_c11a2e8b7f18769bb813191fb9c7b9de.html create mode 100644 doc/html/dir_c11a2e8b7f18769bb813191fb9c7b9de.js create mode 100644 doc/html/dir_db69409d93ff26edeeb565aee0626b58.html create mode 100644 doc/html/dir_db69409d93ff26edeeb565aee0626b58.js create mode 100644 doc/html/dir_e6bb53534ac0e427887cf7a94c0c004e.html create mode 100644 doc/html/dir_e6bb53534ac0e427887cf7a94c0c004e.js create mode 100644 doc/html/dir_eedf9c315589113fcab5c9c13bb437c6.html create mode 100644 doc/html/dir_eedf9c315589113fcab5c9c13bb437c6.js create mode 100644 doc/html/doc.svg create mode 100644 doc/html/docd.svg create mode 100644 doc/html/doxygen.css create mode 100644 doc/html/doxygen.svg create mode 100644 doc/html/dynsections.js create mode 100644 doc/html/examples.html create mode 100644 doc/html/examples.js create mode 100644 doc/html/files.html create mode 100644 doc/html/files_dup.js create mode 100644 doc/html/folderclosed.svg create mode 100644 doc/html/folderclosedd.svg create mode 100644 doc/html/folderopen.svg create mode 100644 doc/html/folderopend.svg create mode 100644 doc/html/functions.html create mode 100644 doc/html/functions_a.html create mode 100644 doc/html/functions_b.html create mode 100644 doc/html/functions_c.html create mode 100644 doc/html/functions_d.html create mode 100644 doc/html/functions_dup.js create mode 100644 doc/html/functions_e.html create mode 100644 doc/html/functions_f.html create mode 100644 doc/html/functions_func.html create mode 100644 doc/html/functions_func.js create mode 100644 doc/html/functions_func_b.html create mode 100644 doc/html/functions_func_c.html create mode 100644 doc/html/functions_func_d.html create mode 100644 doc/html/functions_func_e.html create mode 100644 doc/html/functions_func_f.html create mode 100644 doc/html/functions_func_g.html create mode 100644 doc/html/functions_func_h.html create mode 100644 doc/html/functions_func_i.html create mode 100644 doc/html/functions_func_k.html create mode 100644 doc/html/functions_func_l.html create mode 100644 doc/html/functions_func_m.html create mode 100644 doc/html/functions_func_n.html create mode 100644 doc/html/functions_func_o.html create mode 100644 doc/html/functions_func_p.html create mode 100644 doc/html/functions_func_r.html create mode 100644 doc/html/functions_func_s.html create mode 100644 doc/html/functions_func_t.html create mode 100644 doc/html/functions_func_u.html create mode 100644 doc/html/functions_func_w.html create mode 100644 doc/html/functions_func_~.html create mode 100644 doc/html/functions_g.html create mode 100644 doc/html/functions_h.html create mode 100644 doc/html/functions_i.html create mode 100644 doc/html/functions_k.html create mode 100644 doc/html/functions_l.html create mode 100644 doc/html/functions_m.html create mode 100644 doc/html/functions_n.html create mode 100644 doc/html/functions_o.html create mode 100644 doc/html/functions_p.html create mode 100644 doc/html/functions_r.html create mode 100644 doc/html/functions_s.html create mode 100644 doc/html/functions_t.html create mode 100644 doc/html/functions_u.html create mode 100644 doc/html/functions_vars.html create mode 100644 doc/html/functions_w.html create mode 100644 doc/html/functions_~.html create mode 100644 doc/html/globals.html create mode 100644 doc/html/globals_enum.html create mode 100644 doc/html/globals_eval.html create mode 100644 doc/html/globals_func.html create mode 100644 doc/html/graph_legend.html create mode 100644 doc/html/graph_legend.md5 create mode 100644 doc/html/graph_legend.png create mode 100644 doc/html/hierarchy.html create mode 100644 doc/html/hierarchy.js create mode 100644 doc/html/index.html create mode 100644 doc/html/inherit_graph_0.map create mode 100644 doc/html/inherit_graph_0.md5 create mode 100644 doc/html/inherit_graph_0.png create mode 100644 doc/html/inherit_graph_1.map create mode 100644 doc/html/inherit_graph_1.md5 create mode 100644 doc/html/inherit_graph_1.png create mode 100644 doc/html/inherit_graph_10.map create mode 100644 doc/html/inherit_graph_10.md5 create mode 100644 doc/html/inherit_graph_10.png create mode 100644 doc/html/inherit_graph_11.map create mode 100644 doc/html/inherit_graph_11.md5 create mode 100644 doc/html/inherit_graph_11.png create mode 100644 doc/html/inherit_graph_12.map create mode 100644 doc/html/inherit_graph_12.md5 create mode 100644 doc/html/inherit_graph_12.png create mode 100644 doc/html/inherit_graph_13.map create mode 100644 doc/html/inherit_graph_13.md5 create mode 100644 doc/html/inherit_graph_13.png create mode 100644 doc/html/inherit_graph_14.map create mode 100644 doc/html/inherit_graph_14.md5 create mode 100644 doc/html/inherit_graph_14.png create mode 100644 doc/html/inherit_graph_15.map create mode 100644 doc/html/inherit_graph_15.md5 create mode 100644 doc/html/inherit_graph_15.png create mode 100644 doc/html/inherit_graph_16.map create mode 100644 doc/html/inherit_graph_16.md5 create mode 100644 doc/html/inherit_graph_16.png create mode 100644 doc/html/inherit_graph_17.map create mode 100644 doc/html/inherit_graph_17.md5 create mode 100644 doc/html/inherit_graph_17.png create mode 100644 doc/html/inherit_graph_18.map create mode 100644 doc/html/inherit_graph_18.md5 create mode 100644 doc/html/inherit_graph_18.png create mode 100644 doc/html/inherit_graph_19.map create mode 100644 doc/html/inherit_graph_19.md5 create mode 100644 doc/html/inherit_graph_19.png create mode 100644 doc/html/inherit_graph_2.map create mode 100644 doc/html/inherit_graph_2.md5 create mode 100644 doc/html/inherit_graph_2.png create mode 100644 doc/html/inherit_graph_20.map create mode 100644 doc/html/inherit_graph_20.md5 create mode 100644 doc/html/inherit_graph_20.png create mode 100644 doc/html/inherit_graph_21.map create mode 100644 doc/html/inherit_graph_21.md5 create mode 100644 doc/html/inherit_graph_21.png create mode 100644 doc/html/inherit_graph_22.map create mode 100644 doc/html/inherit_graph_22.md5 create mode 100644 doc/html/inherit_graph_22.png create mode 100644 doc/html/inherit_graph_23.map create mode 100644 doc/html/inherit_graph_23.md5 create mode 100644 doc/html/inherit_graph_23.png create mode 100644 doc/html/inherit_graph_24.map create mode 100644 doc/html/inherit_graph_24.md5 create mode 100644 doc/html/inherit_graph_24.png create mode 100644 doc/html/inherit_graph_25.map create mode 100644 doc/html/inherit_graph_25.md5 create mode 100644 doc/html/inherit_graph_25.png create mode 100644 doc/html/inherit_graph_26.map create mode 100644 doc/html/inherit_graph_26.md5 create mode 100644 doc/html/inherit_graph_26.png create mode 100644 doc/html/inherit_graph_27.map create mode 100644 doc/html/inherit_graph_27.md5 create mode 100644 doc/html/inherit_graph_27.png create mode 100644 doc/html/inherit_graph_28.map create mode 100644 doc/html/inherit_graph_28.md5 create mode 100644 doc/html/inherit_graph_28.png create mode 100644 doc/html/inherit_graph_29.map create mode 100644 doc/html/inherit_graph_29.md5 create mode 100644 doc/html/inherit_graph_29.png create mode 100644 doc/html/inherit_graph_3.map create mode 100644 doc/html/inherit_graph_3.md5 create mode 100644 doc/html/inherit_graph_3.png create mode 100644 doc/html/inherit_graph_30.map create mode 100644 doc/html/inherit_graph_30.md5 create mode 100644 doc/html/inherit_graph_30.png create mode 100644 doc/html/inherit_graph_31.map create mode 100644 doc/html/inherit_graph_31.md5 create mode 100644 doc/html/inherit_graph_31.png create mode 100644 doc/html/inherit_graph_32.map create mode 100644 doc/html/inherit_graph_32.md5 create mode 100644 doc/html/inherit_graph_32.png create mode 100644 doc/html/inherit_graph_33.map create mode 100644 doc/html/inherit_graph_33.md5 create mode 100644 doc/html/inherit_graph_33.png create mode 100644 doc/html/inherit_graph_34.map create mode 100644 doc/html/inherit_graph_34.md5 create mode 100644 doc/html/inherit_graph_34.png create mode 100644 doc/html/inherit_graph_35.map create mode 100644 doc/html/inherit_graph_35.md5 create mode 100644 doc/html/inherit_graph_35.png create mode 100644 doc/html/inherit_graph_36.map create mode 100644 doc/html/inherit_graph_36.md5 create mode 100644 doc/html/inherit_graph_36.png create mode 100644 doc/html/inherit_graph_37.map create mode 100644 doc/html/inherit_graph_37.md5 create mode 100644 doc/html/inherit_graph_37.png create mode 100644 doc/html/inherit_graph_38.map create mode 100644 doc/html/inherit_graph_38.md5 create mode 100644 doc/html/inherit_graph_38.png create mode 100644 doc/html/inherit_graph_39.map create mode 100644 doc/html/inherit_graph_39.md5 create mode 100644 doc/html/inherit_graph_39.png create mode 100644 doc/html/inherit_graph_4.map create mode 100644 doc/html/inherit_graph_4.md5 create mode 100644 doc/html/inherit_graph_4.png create mode 100644 doc/html/inherit_graph_40.map create mode 100644 doc/html/inherit_graph_40.md5 create mode 100644 doc/html/inherit_graph_40.png create mode 100644 doc/html/inherit_graph_41.map create mode 100644 doc/html/inherit_graph_41.md5 create mode 100644 doc/html/inherit_graph_41.png create mode 100644 doc/html/inherit_graph_42.map create mode 100644 doc/html/inherit_graph_42.md5 create mode 100644 doc/html/inherit_graph_42.png create mode 100644 doc/html/inherit_graph_5.map create mode 100644 doc/html/inherit_graph_5.md5 create mode 100644 doc/html/inherit_graph_5.png create mode 100644 doc/html/inherit_graph_6.map create mode 100644 doc/html/inherit_graph_6.md5 create mode 100644 doc/html/inherit_graph_6.png create mode 100644 doc/html/inherit_graph_7.map create mode 100644 doc/html/inherit_graph_7.md5 create mode 100644 doc/html/inherit_graph_7.png create mode 100644 doc/html/inherit_graph_8.map create mode 100644 doc/html/inherit_graph_8.md5 create mode 100644 doc/html/inherit_graph_8.png create mode 100644 doc/html/inherit_graph_9.map create mode 100644 doc/html/inherit_graph_9.md5 create mode 100644 doc/html/inherit_graph_9.png create mode 100644 doc/html/inherits.html create mode 100644 doc/html/jquery.js create mode 100644 doc/html/menu.js create mode 100644 doc/html/menudata.js create mode 100644 doc/html/minus.svg create mode 100644 doc/html/minusd.svg create mode 100644 doc/html/nav_f.png create mode 100644 doc/html/nav_fd.png create mode 100644 doc/html/nav_g.png create mode 100644 doc/html/nav_h.png create mode 100644 doc/html/nav_hd.png create mode 100644 doc/html/navtree.css create mode 100644 doc/html/navtree.js create mode 100644 doc/html/navtreedata.js create mode 100644 doc/html/navtreeindex0.js create mode 100644 doc/html/navtreeindex1.js create mode 100644 doc/html/navtreeindex2.js create mode 100644 doc/html/navtreeindex3.js create mode 100644 doc/html/open.png create mode 100644 doc/html/plus.svg create mode 100644 doc/html/plusd.svg create mode 100644 doc/html/resize.js create mode 100644 doc/html/search/all_0.js create mode 100644 doc/html/search/all_1.js create mode 100644 doc/html/search/all_10.js create mode 100644 doc/html/search/all_11.js create mode 100644 doc/html/search/all_12.js create mode 100644 doc/html/search/all_13.js create mode 100644 doc/html/search/all_14.js create mode 100644 doc/html/search/all_15.js create mode 100644 doc/html/search/all_2.js create mode 100644 doc/html/search/all_3.js create mode 100644 doc/html/search/all_4.js create mode 100644 doc/html/search/all_5.js create mode 100644 doc/html/search/all_6.js create mode 100644 doc/html/search/all_7.js create mode 100644 doc/html/search/all_8.js create mode 100644 doc/html/search/all_9.js create mode 100644 doc/html/search/all_a.js create mode 100644 doc/html/search/all_b.js create mode 100644 doc/html/search/all_c.js create mode 100644 doc/html/search/all_d.js create mode 100644 doc/html/search/all_e.js create mode 100644 doc/html/search/all_f.js create mode 100644 doc/html/search/classes_0.js create mode 100644 doc/html/search/classes_1.js create mode 100644 doc/html/search/classes_2.js create mode 100644 doc/html/search/classes_3.js create mode 100644 doc/html/search/classes_4.js create mode 100644 doc/html/search/classes_5.js create mode 100644 doc/html/search/classes_6.js create mode 100644 doc/html/search/classes_7.js create mode 100644 doc/html/search/classes_8.js create mode 100644 doc/html/search/close.svg create mode 100644 doc/html/search/enums_0.js create mode 100644 doc/html/search/enumvalues_0.js create mode 100644 doc/html/search/files_0.js create mode 100644 doc/html/search/functions_0.js create mode 100644 doc/html/search/functions_1.js create mode 100644 doc/html/search/functions_10.js create mode 100644 doc/html/search/functions_11.js create mode 100644 doc/html/search/functions_12.js create mode 100644 doc/html/search/functions_13.js create mode 100644 doc/html/search/functions_14.js create mode 100644 doc/html/search/functions_2.js create mode 100644 doc/html/search/functions_3.js create mode 100644 doc/html/search/functions_4.js create mode 100644 doc/html/search/functions_5.js create mode 100644 doc/html/search/functions_6.js create mode 100644 doc/html/search/functions_7.js create mode 100644 doc/html/search/functions_8.js create mode 100644 doc/html/search/functions_9.js create mode 100644 doc/html/search/functions_a.js create mode 100644 doc/html/search/functions_b.js create mode 100644 doc/html/search/functions_c.js create mode 100644 doc/html/search/functions_d.js create mode 100644 doc/html/search/functions_e.js create mode 100644 doc/html/search/functions_f.js create mode 100644 doc/html/search/mag.svg create mode 100644 doc/html/search/mag_d.svg create mode 100644 doc/html/search/mag_sel.svg create mode 100644 doc/html/search/mag_seld.svg create mode 100644 doc/html/search/pages_0.js create mode 100644 doc/html/search/pages_1.js create mode 100644 doc/html/search/pages_2.js create mode 100644 doc/html/search/pages_3.js create mode 100644 doc/html/search/search.css create mode 100644 doc/html/search/search.js create mode 100644 doc/html/search/searchdata.js create mode 100644 doc/html/search/variables_0.js create mode 100644 doc/html/search/variables_1.js create mode 100644 doc/html/splitbar.png create mode 100644 doc/html/splitbard.png create mode 100644 doc/html/struct___u_s_b___c_o_n_f_i_g___d_escript_o_r-members.html create mode 100644 doc/html/struct___u_s_b___c_o_n_f_i_g___d_escript_o_r.html create mode 100644 doc/html/struct___u_s_b___c_o_n_f_i_g___d_escript_o_r___l_o_n_g-members.html create mode 100644 doc/html/struct___u_s_b___c_o_n_f_i_g___d_escript_o_r___l_o_n_g.html create mode 100644 doc/html/struct___u_s_b___c_o_n_f_i_g___d_escript_o_r___l_o_n_g__coll__graph.map create mode 100644 doc/html/struct___u_s_b___c_o_n_f_i_g___d_escript_o_r___l_o_n_g__coll__graph.md5 create mode 100644 doc/html/struct___u_s_b___c_o_n_f_i_g___d_escript_o_r___l_o_n_g__coll__graph.png create mode 100644 doc/html/struct___u_s_b___d_e_v_i_c_e___d_escript_o_r-members.html create mode 100644 doc/html/struct___u_s_b___d_e_v_i_c_e___d_escript_o_r.html create mode 100644 doc/html/struct___u_s_b___e_n_d_p_o_i_n_t___d_escript_o_r-members.html create mode 100644 doc/html/struct___u_s_b___e_n_d_p_o_i_n_t___d_escript_o_r.html create mode 100644 doc/html/struct___u_s_b___i_n_t_e_r_f___d_escript_o_r-members.html create mode 100644 doc/html/struct___u_s_b___i_n_t_e_r_f___d_escript_o_r.html create mode 100644 doc/html/struct_cmd__list__tab__type-members.html create mode 100644 doc/html/struct_cmd__list__tab__type.html create mode 100644 doc/html/struct_compass___calibration___parameter-members.html create mode 100644 doc/html/struct_compass___calibration___parameter.html create mode 100644 doc/html/struct_e_e_p_r_o_m_class-members.html create mode 100644 doc/html/struct_e_e_p_r_o_m_class.html create mode 100644 doc/html/struct_e_e_ptr-members.html create mode 100644 doc/html/struct_e_e_ptr.html create mode 100644 doc/html/struct_e_e_ptr.js create mode 100644 doc/html/struct_e_e_ref-members.html create mode 100644 doc/html/struct_e_e_ref.html create mode 100644 doc/html/struct_e_e_ref.js create mode 100644 doc/html/struct_encoder__port__type-members.html create mode 100644 doc/html/struct_encoder__port__type.html create mode 100644 doc/html/struct_l_e_d___matrix___clock___number___font__3x8___type_def-members.html create mode 100644 doc/html/struct_l_e_d___matrix___clock___number___font__3x8___type_def.html create mode 100644 doc/html/struct_l_e_d___matrix___font__6x8___type_def-members.html create mode 100644 doc/html/struct_l_e_d___matrix___font__6x8___type_def.html create mode 100644 doc/html/struct_me___encoder__type-members.html create mode 100644 doc/html/struct_me___encoder__type.html create mode 100644 doc/html/struct_me___encoder__type__coll__graph.map create mode 100644 doc/html/struct_me___encoder__type__coll__graph.md5 create mode 100644 doc/html/struct_me___encoder__type__coll__graph.png create mode 100644 doc/html/struct_me_port___sig-members.html create mode 100644 doc/html/struct_me_port___sig.html create mode 100644 doc/html/struct_p_i_d__internal-members.html create mode 100644 doc/html/struct_p_i_d__internal.html create mode 100644 doc/html/struct_p_m25_d_a_t_a_s_t_r_u_c_t-members.html create mode 100644 doc/html/struct_p_m25_d_a_t_a_s_t_r_u_c_t.html create mode 100644 doc/html/struct_servo_pin__t-members.html create mode 100644 doc/html/struct_servo_pin__t.html create mode 100644 doc/html/structc_r_g_b-members.html create mode 100644 doc/html/structc_r_g_b.html create mode 100644 doc/html/structirparams__t-members.html create mode 100644 doc/html/structirparams__t.html create mode 100644 doc/html/structmega_pi__slot-members.html create mode 100644 doc/html/structmega_pi__slot.html create mode 100644 doc/html/structmegapi__dc__type-members.html create mode 100644 doc/html/structmegapi__dc__type.html create mode 100644 doc/html/structmegapipro__esc__type-members.html create mode 100644 doc/html/structmegapipro__esc__type.html create mode 100644 doc/html/structservo__device__type-members.html create mode 100644 doc/html/structservo__device__type.html create mode 100644 doc/html/structservo__t-members.html create mode 100644 doc/html/structservo__t.html create mode 100644 doc/html/structservo__t__coll__graph.map create mode 100644 doc/html/structservo__t__coll__graph.md5 create mode 100644 doc/html/structservo__t__coll__graph.png create mode 100644 doc/html/structsysex__message__type-members.html create mode 100644 doc/html/structsysex__message__type.html create mode 100644 doc/html/sync_off.png create mode 100644 doc/html/sync_on.png create mode 100644 doc/html/tab_a.png create mode 100644 doc/html/tab_ad.png create mode 100644 doc/html/tab_b.png create mode 100644 doc/html/tab_bd.png create mode 100644 doc/html/tab_h.png create mode 100644 doc/html/tab_hd.png create mode 100644 doc/html/tab_s.png create mode 100644 doc/html/tab_sd.png create mode 100644 doc/html/tabs.css create mode 100644 doc/html/twi_8h_source.html create mode 100644 doc/html/union_p_m25_d_a_t_a_u_i_n_o-members.html create mode 100644 doc/html/union_p_m25_d_a_t_a_u_i_n_o.html create mode 100644 doc/html/union_p_m25_d_a_t_a_u_i_n_o__coll__graph.map create mode 100644 doc/html/union_p_m25_d_a_t_a_u_i_n_o__coll__graph.md5 create mode 100644 doc/html/union_p_m25_d_a_t_a_u_i_n_o__coll__graph.png create mode 100644 doc/html/unionsysex__message-members.html create mode 100644 doc/html/unionsysex__message.html create mode 100644 doc/html/unionsysex__message__coll__graph.map create mode 100644 doc/html/unionsysex__message__coll__graph.md5 create mode 100644 doc/html/unionsysex__message__coll__graph.png create mode 100644 doc/latex/Makefile create mode 100644 doc/latex/_buzzer_test_8ino-example.tex create mode 100644 doc/latex/_color_loop_test_8ino-example.tex create mode 100644 doc/latex/_d_c_motor_driver_test_8ino-example.tex create mode 100644 doc/latex/_e_e_p_r_o_m_8h_source.tex create mode 100644 doc/latex/_encoder_motor_change_i2_c_dev_i_d_8ino-example.tex create mode 100644 doc/latex/_encoder_motor_test_is_tar_pos_reached_8ino-example.tex create mode 100644 doc/latex/_encoder_motor_test_move_to_8ino-example.tex create mode 100644 doc/latex/_encoder_motor_test_run_speed_8ino-example.tex create mode 100644 doc/latex/_encoder_motor_test_run_speed_and_time_8ino-example.tex create mode 100644 doc/latex/_encoder_motor_test_run_turns_8ino-example.tex create mode 100644 doc/latex/_indicators_test_8ino-example.tex create mode 100644 doc/latex/_infrared_receiver_test_8ino-example.tex create mode 100644 doc/latex/_limit_switch_test_8ino-example.tex create mode 100644 doc/latex/_line_follower_test_8ino-example.tex create mode 100644 doc/latex/_mbot_buzzer_test2_8ino-example.tex create mode 100644 doc/latex/_mbot_buzzer_test_8ino-example.tex create mode 100644 doc/latex/_me4_button_8cpp.tex create mode 100644 doc/latex/_me4_button_8cpp__incl.md5 create mode 100644 doc/latex/_me4_button_8cpp__incl.pdf create mode 100644 doc/latex/_me4_button_8h.tex create mode 100644 doc/latex/_me4_button_8h__dep__incl.md5 create mode 100644 doc/latex/_me4_button_8h__dep__incl.pdf create mode 100644 doc/latex/_me4_button_8h__incl.md5 create mode 100644 doc/latex/_me4_button_8h__incl.pdf create mode 100644 doc/latex/_me4_button_8h_source.tex create mode 100644 doc/latex/_me4_button_test_8ino-example.tex create mode 100644 doc/latex/_me7_segment_display_8cpp.tex create mode 100644 doc/latex/_me7_segment_display_8cpp__incl.md5 create mode 100644 doc/latex/_me7_segment_display_8cpp__incl.pdf create mode 100644 doc/latex/_me7_segment_display_8h.tex create mode 100644 doc/latex/_me7_segment_display_8h__dep__incl.md5 create mode 100644 doc/latex/_me7_segment_display_8h__dep__incl.pdf create mode 100644 doc/latex/_me7_segment_display_8h__incl.md5 create mode 100644 doc/latex/_me7_segment_display_8h__incl.pdf create mode 100644 doc/latex/_me7_segment_display_8h_source.tex create mode 100644 doc/latex/_me__auriga_encoder_callback_8ino-example.tex create mode 100644 doc/latex/_me__auriga_encoder_direct_8ino-example.tex create mode 100644 doc/latex/_me__auriga_encoder_pid_pos_8ino-example.tex create mode 100644 doc/latex/_me__auriga_encoder_pid_speed_8ino-example.tex create mode 100644 doc/latex/_me__auriga_encoder_pwm_8ino-example.tex create mode 100644 doc/latex/_me__l_e_d_matrix_test_8ino-example.tex create mode 100644 doc/latex/_me__megapi_encoder_direct_8ino-example.tex create mode 100644 doc/latex/_me__megapi_encoder_pid_pos_8ino-example.tex create mode 100644 doc/latex/_me__megapi_encoder_pid_speed_8ino-example.tex create mode 100644 doc/latex/_me__megapi_encoder_pwm_8ino-example.tex create mode 100644 doc/latex/_me_auriga_8h.tex create mode 100644 doc/latex/_me_auriga_8h__incl.md5 create mode 100644 doc/latex/_me_auriga_8h__incl.pdf create mode 100644 doc/latex/_me_auriga_8h_source.tex create mode 100644 doc/latex/_me_base_board_8h.tex create mode 100644 doc/latex/_me_base_board_8h__incl.md5 create mode 100644 doc/latex/_me_base_board_8h__incl.pdf create mode 100644 doc/latex/_me_base_board_8h_source.tex create mode 100644 doc/latex/_me_bluetooth_8cpp.tex create mode 100644 doc/latex/_me_bluetooth_8cpp__incl.md5 create mode 100644 doc/latex/_me_bluetooth_8cpp__incl.pdf create mode 100644 doc/latex/_me_bluetooth_8h.tex create mode 100644 doc/latex/_me_bluetooth_8h__dep__incl.md5 create mode 100644 doc/latex/_me_bluetooth_8h__dep__incl.pdf create mode 100644 doc/latex/_me_bluetooth_8h__incl.md5 create mode 100644 doc/latex/_me_bluetooth_8h__incl.pdf create mode 100644 doc/latex/_me_bluetooth_8h_source.tex create mode 100644 doc/latex/_me_buzzer_8cpp.tex create mode 100644 doc/latex/_me_buzzer_8cpp__incl.md5 create mode 100644 doc/latex/_me_buzzer_8cpp__incl.pdf create mode 100644 doc/latex/_me_buzzer_8h.tex create mode 100644 doc/latex/_me_buzzer_8h__dep__incl.md5 create mode 100644 doc/latex/_me_buzzer_8h__dep__incl.pdf create mode 100644 doc/latex/_me_buzzer_8h__incl.md5 create mode 100644 doc/latex/_me_buzzer_8h__incl.pdf create mode 100644 doc/latex/_me_buzzer_8h_source.tex create mode 100644 doc/latex/_me_color_sensor_8cpp.tex create mode 100644 doc/latex/_me_color_sensor_8cpp__incl.md5 create mode 100644 doc/latex/_me_color_sensor_8cpp__incl.pdf create mode 100644 doc/latex/_me_color_sensor_8h.tex create mode 100644 doc/latex/_me_color_sensor_8h__dep__incl.md5 create mode 100644 doc/latex/_me_color_sensor_8h__dep__incl.pdf create mode 100644 doc/latex/_me_color_sensor_8h__incl.md5 create mode 100644 doc/latex/_me_color_sensor_8h__incl.pdf create mode 100644 doc/latex/_me_color_sensor_8h_source.tex create mode 100644 doc/latex/_me_color_sensor_test_8ino-example.tex create mode 100644 doc/latex/_me_compass_8cpp.tex create mode 100644 doc/latex/_me_compass_8cpp__incl.md5 create mode 100644 doc/latex/_me_compass_8cpp__incl.pdf create mode 100644 doc/latex/_me_compass_8h.tex create mode 100644 doc/latex/_me_compass_8h__dep__incl.md5 create mode 100644 doc/latex/_me_compass_8h__dep__incl.pdf create mode 100644 doc/latex/_me_compass_8h__incl.md5 create mode 100644 doc/latex/_me_compass_8h__incl.pdf create mode 100644 doc/latex/_me_compass_8h_source.tex create mode 100644 doc/latex/_me_compass_test_8ino-example.tex create mode 100644 doc/latex/_me_config_8h.tex create mode 100644 doc/latex/_me_config_8h__dep__incl.md5 create mode 100644 doc/latex/_me_config_8h__dep__incl.pdf create mode 100644 doc/latex/_me_config_8h__incl.md5 create mode 100644 doc/latex/_me_config_8h__incl.pdf create mode 100644 doc/latex/_me_config_8h_source.tex create mode 100644 doc/latex/_me_d_c_motor_8cpp.tex create mode 100644 doc/latex/_me_d_c_motor_8cpp__incl.md5 create mode 100644 doc/latex/_me_d_c_motor_8cpp__incl.pdf create mode 100644 doc/latex/_me_d_c_motor_8h.tex create mode 100644 doc/latex/_me_d_c_motor_8h__dep__incl.md5 create mode 100644 doc/latex/_me_d_c_motor_8h__dep__incl.pdf create mode 100644 doc/latex/_me_d_c_motor_8h__incl.md5 create mode 100644 doc/latex/_me_d_c_motor_8h__incl.pdf create mode 100644 doc/latex/_me_d_c_motor_8h_source.tex create mode 100644 doc/latex/_me_e_e_p_r_o_m_8h.tex create mode 100644 doc/latex/_me_e_e_p_r_o_m_8h__incl.md5 create mode 100644 doc/latex/_me_e_e_p_r_o_m_8h__incl.pdf create mode 100644 doc/latex/_me_e_e_p_r_o_m_8h_source.tex create mode 100644 doc/latex/_me_encoder_motor_8cpp.tex create mode 100644 doc/latex/_me_encoder_motor_8cpp__incl.md5 create mode 100644 doc/latex/_me_encoder_motor_8cpp__incl.pdf create mode 100644 doc/latex/_me_encoder_motor_8h.tex create mode 100644 doc/latex/_me_encoder_motor_8h__dep__incl.md5 create mode 100644 doc/latex/_me_encoder_motor_8h__dep__incl.pdf create mode 100644 doc/latex/_me_encoder_motor_8h__incl.md5 create mode 100644 doc/latex/_me_encoder_motor_8h__incl.pdf create mode 100644 doc/latex/_me_encoder_motor_8h_source.tex create mode 100644 doc/latex/_me_encoder_new_8cpp.tex create mode 100644 doc/latex/_me_encoder_new_8cpp__incl.md5 create mode 100644 doc/latex/_me_encoder_new_8cpp__incl.pdf create mode 100644 doc/latex/_me_encoder_new_8h.tex create mode 100644 doc/latex/_me_encoder_new_8h__dep__incl.md5 create mode 100644 doc/latex/_me_encoder_new_8h__dep__incl.pdf create mode 100644 doc/latex/_me_encoder_new_8h__incl.md5 create mode 100644 doc/latex/_me_encoder_new_8h__incl.pdf create mode 100644 doc/latex/_me_encoder_new_8h_source.tex create mode 100644 doc/latex/_me_encoder_on_board_8cpp.tex create mode 100644 doc/latex/_me_encoder_on_board_8cpp__incl.md5 create mode 100644 doc/latex/_me_encoder_on_board_8cpp__incl.pdf create mode 100644 doc/latex/_me_encoder_on_board_8h.tex create mode 100644 doc/latex/_me_encoder_on_board_8h__dep__incl.md5 create mode 100644 doc/latex/_me_encoder_on_board_8h__dep__incl.pdf create mode 100644 doc/latex/_me_encoder_on_board_8h__incl.md5 create mode 100644 doc/latex/_me_encoder_on_board_8h__incl.pdf create mode 100644 doc/latex/_me_encoder_on_board_8h_source.tex create mode 100644 doc/latex/_me_flame_sensor_8cpp.tex create mode 100644 doc/latex/_me_flame_sensor_8cpp__incl.md5 create mode 100644 doc/latex/_me_flame_sensor_8cpp__incl.pdf create mode 100644 doc/latex/_me_flame_sensor_8h.tex create mode 100644 doc/latex/_me_flame_sensor_8h__dep__incl.md5 create mode 100644 doc/latex/_me_flame_sensor_8h__dep__incl.pdf create mode 100644 doc/latex/_me_flame_sensor_8h__incl.md5 create mode 100644 doc/latex/_me_flame_sensor_8h__incl.pdf create mode 100644 doc/latex/_me_flame_sensor_8h_source.tex create mode 100644 doc/latex/_me_flame_sensor_test_8ino-example.tex create mode 100644 doc/latex/_me_gas_sensor_8cpp.tex create mode 100644 doc/latex/_me_gas_sensor_8cpp__incl.md5 create mode 100644 doc/latex/_me_gas_sensor_8cpp__incl.pdf create mode 100644 doc/latex/_me_gas_sensor_8h.tex create mode 100644 doc/latex/_me_gas_sensor_8h__dep__incl.md5 create mode 100644 doc/latex/_me_gas_sensor_8h__dep__incl.pdf create mode 100644 doc/latex/_me_gas_sensor_8h__incl.md5 create mode 100644 doc/latex/_me_gas_sensor_8h__incl.pdf create mode 100644 doc/latex/_me_gas_sensor_8h_source.tex create mode 100644 doc/latex/_me_gas_sensor_test_8ino-example.tex create mode 100644 doc/latex/_me_gyro_8cpp.tex create mode 100644 doc/latex/_me_gyro_8cpp__incl.md5 create mode 100644 doc/latex/_me_gyro_8cpp__incl.pdf create mode 100644 doc/latex/_me_gyro_8h.tex create mode 100644 doc/latex/_me_gyro_8h__dep__incl.md5 create mode 100644 doc/latex/_me_gyro_8h__dep__incl.pdf create mode 100644 doc/latex/_me_gyro_8h__incl.md5 create mode 100644 doc/latex/_me_gyro_8h__incl.pdf create mode 100644 doc/latex/_me_gyro_8h_source.tex create mode 100644 doc/latex/_me_gyro_test_8ino-example.tex create mode 100644 doc/latex/_me_host_parser_8cpp.tex create mode 100644 doc/latex/_me_host_parser_8cpp__incl.md5 create mode 100644 doc/latex/_me_host_parser_8cpp__incl.pdf create mode 100644 doc/latex/_me_host_parser_8h.tex create mode 100644 doc/latex/_me_host_parser_8h__dep__incl.md5 create mode 100644 doc/latex/_me_host_parser_8h__dep__incl.pdf create mode 100644 doc/latex/_me_host_parser_8h__incl.md5 create mode 100644 doc/latex/_me_host_parser_8h__incl.pdf create mode 100644 doc/latex/_me_host_parser_8h_source.tex create mode 100644 doc/latex/_me_humiture_sensor_8cpp.tex create mode 100644 doc/latex/_me_humiture_sensor_8cpp__incl.md5 create mode 100644 doc/latex/_me_humiture_sensor_8cpp__incl.pdf create mode 100644 doc/latex/_me_humiture_sensor_8h.tex create mode 100644 doc/latex/_me_humiture_sensor_8h__dep__incl.md5 create mode 100644 doc/latex/_me_humiture_sensor_8h__dep__incl.pdf create mode 100644 doc/latex/_me_humiture_sensor_8h__incl.md5 create mode 100644 doc/latex/_me_humiture_sensor_8h__incl.pdf create mode 100644 doc/latex/_me_humiture_sensor_8h_source.tex create mode 100644 doc/latex/_me_humiture_sensor_test1_8ino-example.tex create mode 100644 doc/latex/_me_humiture_sensor_test2_8ino-example.tex create mode 100644 doc/latex/_me_i_r_8cpp.tex create mode 100644 doc/latex/_me_i_r_8h.tex create mode 100644 doc/latex/_me_i_r_8h__dep__incl.md5 create mode 100644 doc/latex/_me_i_r_8h__dep__incl.pdf create mode 100644 doc/latex/_me_i_r_8h__incl.md5 create mode 100644 doc/latex/_me_i_r_8h__incl.pdf create mode 100644 doc/latex/_me_i_r_8h_source.tex create mode 100644 doc/latex/_me_infrared_receiver_8cpp.tex create mode 100644 doc/latex/_me_infrared_receiver_8cpp__incl.md5 create mode 100644 doc/latex/_me_infrared_receiver_8cpp__incl.pdf create mode 100644 doc/latex/_me_infrared_receiver_8h.tex create mode 100644 doc/latex/_me_infrared_receiver_8h__dep__incl.md5 create mode 100644 doc/latex/_me_infrared_receiver_8h__dep__incl.pdf create mode 100644 doc/latex/_me_infrared_receiver_8h__incl.md5 create mode 100644 doc/latex/_me_infrared_receiver_8h__incl.pdf create mode 100644 doc/latex/_me_infrared_receiver_8h_source.tex create mode 100644 doc/latex/_me_joystick_8cpp.tex create mode 100644 doc/latex/_me_joystick_8cpp__incl.md5 create mode 100644 doc/latex/_me_joystick_8cpp__incl.pdf create mode 100644 doc/latex/_me_joystick_8h.tex create mode 100644 doc/latex/_me_joystick_8h__dep__incl.md5 create mode 100644 doc/latex/_me_joystick_8h__dep__incl.pdf create mode 100644 doc/latex/_me_joystick_8h__incl.md5 create mode 100644 doc/latex/_me_joystick_8h__incl.pdf create mode 100644 doc/latex/_me_joystick_8h_source.tex create mode 100644 doc/latex/_me_joystick_test_8ino-example.tex create mode 100644 doc/latex/_me_l_e_d_matrix_8cpp.tex create mode 100644 doc/latex/_me_l_e_d_matrix_8cpp__incl.md5 create mode 100644 doc/latex/_me_l_e_d_matrix_8cpp__incl.pdf create mode 100644 doc/latex/_me_l_e_d_matrix_8h.tex create mode 100644 doc/latex/_me_l_e_d_matrix_8h__dep__incl.md5 create mode 100644 doc/latex/_me_l_e_d_matrix_8h__dep__incl.pdf create mode 100644 doc/latex/_me_l_e_d_matrix_8h__incl.md5 create mode 100644 doc/latex/_me_l_e_d_matrix_8h__incl.pdf create mode 100644 doc/latex/_me_l_e_d_matrix_8h_source.tex create mode 100644 doc/latex/_me_l_e_d_matrix_data_8h.tex create mode 100644 doc/latex/_me_l_e_d_matrix_data_8h__dep__incl.md5 create mode 100644 doc/latex/_me_l_e_d_matrix_data_8h__dep__incl.pdf create mode 100644 doc/latex/_me_l_e_d_matrix_data_8h_source.tex create mode 100644 doc/latex/_me_light_sensor_8cpp.tex create mode 100644 doc/latex/_me_light_sensor_8cpp__incl.md5 create mode 100644 doc/latex/_me_light_sensor_8cpp__incl.pdf create mode 100644 doc/latex/_me_light_sensor_8h.tex create mode 100644 doc/latex/_me_light_sensor_8h__dep__incl.md5 create mode 100644 doc/latex/_me_light_sensor_8h__dep__incl.pdf create mode 100644 doc/latex/_me_light_sensor_8h__incl.md5 create mode 100644 doc/latex/_me_light_sensor_8h__incl.pdf create mode 100644 doc/latex/_me_light_sensor_8h_source.tex create mode 100644 doc/latex/_me_light_sensor_test_8ino-example.tex create mode 100644 doc/latex/_me_light_sensor_test_reset_port_8ino-example.tex create mode 100644 doc/latex/_me_light_sensor_test_with_l_e_don_8ino-example.tex create mode 100644 doc/latex/_me_limit_switch_8cpp.tex create mode 100644 doc/latex/_me_limit_switch_8cpp__incl.md5 create mode 100644 doc/latex/_me_limit_switch_8cpp__incl.pdf create mode 100644 doc/latex/_me_limit_switch_8h.tex create mode 100644 doc/latex/_me_limit_switch_8h__dep__incl.md5 create mode 100644 doc/latex/_me_limit_switch_8h__dep__incl.pdf create mode 100644 doc/latex/_me_limit_switch_8h__incl.md5 create mode 100644 doc/latex/_me_limit_switch_8h__incl.pdf create mode 100644 doc/latex/_me_limit_switch_8h_source.tex create mode 100644 doc/latex/_me_line_follower_8cpp.tex create mode 100644 doc/latex/_me_line_follower_8cpp__incl.md5 create mode 100644 doc/latex/_me_line_follower_8cpp__incl.pdf create mode 100644 doc/latex/_me_line_follower_8h.tex create mode 100644 doc/latex/_me_line_follower_8h__dep__incl.md5 create mode 100644 doc/latex/_me_line_follower_8h__dep__incl.pdf create mode 100644 doc/latex/_me_line_follower_8h__incl.md5 create mode 100644 doc/latex/_me_line_follower_8h__incl.pdf create mode 100644 doc/latex/_me_line_follower_8h_source.tex create mode 100644 doc/latex/_me_m_core_8h.tex create mode 100644 doc/latex/_me_m_core_8h__incl.md5 create mode 100644 doc/latex/_me_m_core_8h__incl.pdf create mode 100644 doc/latex/_me_m_core_8h_source.tex create mode 100644 doc/latex/_me_mbot_d_c_motor_8cpp.tex create mode 100644 doc/latex/_me_mbot_d_c_motor_8cpp__incl.md5 create mode 100644 doc/latex/_me_mbot_d_c_motor_8cpp__incl.pdf create mode 100644 doc/latex/_me_mbot_d_c_motor_8h.tex create mode 100644 doc/latex/_me_mbot_d_c_motor_8h__dep__incl.md5 create mode 100644 doc/latex/_me_mbot_d_c_motor_8h__dep__incl.pdf create mode 100644 doc/latex/_me_mbot_d_c_motor_8h__incl.md5 create mode 100644 doc/latex/_me_mbot_d_c_motor_8h__incl.pdf create mode 100644 doc/latex/_me_mbot_d_c_motor_8h_source.tex create mode 100644 doc/latex/_me_mega_pi_8h.tex create mode 100644 doc/latex/_me_mega_pi_8h__incl.md5 create mode 100644 doc/latex/_me_mega_pi_8h__incl.pdf create mode 100644 doc/latex/_me_mega_pi_8h_source.tex create mode 100644 doc/latex/_me_mega_pi_d_c_motor_8cpp.tex create mode 100644 doc/latex/_me_mega_pi_d_c_motor_8cpp__incl.md5 create mode 100644 doc/latex/_me_mega_pi_d_c_motor_8cpp__incl.pdf create mode 100644 doc/latex/_me_mega_pi_d_c_motor_8h.tex create mode 100644 doc/latex/_me_mega_pi_d_c_motor_8h__dep__incl.md5 create mode 100644 doc/latex/_me_mega_pi_d_c_motor_8h__dep__incl.pdf create mode 100644 doc/latex/_me_mega_pi_d_c_motor_8h__incl.md5 create mode 100644 doc/latex/_me_mega_pi_d_c_motor_8h__incl.pdf create mode 100644 doc/latex/_me_mega_pi_d_c_motor_8h_source.tex create mode 100644 doc/latex/_me_mega_pi_d_c_motor_test_8ino-example.tex create mode 100644 doc/latex/_me_mega_pi_pro4_dc_motor_8cpp.tex create mode 100644 doc/latex/_me_mega_pi_pro4_dc_motor_8cpp__incl.md5 create mode 100644 doc/latex/_me_mega_pi_pro4_dc_motor_8cpp__incl.pdf create mode 100644 doc/latex/_me_mega_pi_pro4_dc_motor_8h.tex create mode 100644 doc/latex/_me_mega_pi_pro4_dc_motor_8h__dep__incl.md5 create mode 100644 doc/latex/_me_mega_pi_pro4_dc_motor_8h__dep__incl.pdf create mode 100644 doc/latex/_me_mega_pi_pro4_dc_motor_8h__incl.md5 create mode 100644 doc/latex/_me_mega_pi_pro4_dc_motor_8h__incl.pdf create mode 100644 doc/latex/_me_mega_pi_pro4_dc_motor_8h_source.tex create mode 100644 doc/latex/_me_mega_pi_pro_8h.tex create mode 100644 doc/latex/_me_mega_pi_pro_8h__incl.md5 create mode 100644 doc/latex/_me_mega_pi_pro_8h__incl.pdf create mode 100644 doc/latex/_me_mega_pi_pro_8h_source.tex create mode 100644 doc/latex/_me_mega_pi_pro_e_s_c_motor_8cpp.tex create mode 100644 doc/latex/_me_mega_pi_pro_e_s_c_motor_8cpp__incl.md5 create mode 100644 doc/latex/_me_mega_pi_pro_e_s_c_motor_8cpp__incl.pdf create mode 100644 doc/latex/_me_mega_pi_pro_e_s_c_motor_8h.tex create mode 100644 doc/latex/_me_mega_pi_pro_e_s_c_motor_8h__dep__incl.md5 create mode 100644 doc/latex/_me_mega_pi_pro_e_s_c_motor_8h__dep__incl.pdf create mode 100644 doc/latex/_me_mega_pi_pro_e_s_c_motor_8h__incl.md5 create mode 100644 doc/latex/_me_mega_pi_pro_e_s_c_motor_8h__incl.pdf create mode 100644 doc/latex/_me_mega_pi_pro_e_s_c_motor_8h_source.tex create mode 100644 doc/latex/_me_mega_pi_pro_e_s_c_motor_8ino-example.tex create mode 100644 doc/latex/_me_on_board_temp_8cpp.tex create mode 100644 doc/latex/_me_on_board_temp_8cpp__incl.md5 create mode 100644 doc/latex/_me_on_board_temp_8cpp__incl.pdf create mode 100644 doc/latex/_me_on_board_temp_8h.tex create mode 100644 doc/latex/_me_on_board_temp_8h__dep__incl.md5 create mode 100644 doc/latex/_me_on_board_temp_8h__dep__incl.pdf create mode 100644 doc/latex/_me_on_board_temp_8h__incl.md5 create mode 100644 doc/latex/_me_on_board_temp_8h__incl.pdf create mode 100644 doc/latex/_me_on_board_temp_8h_source.tex create mode 100644 doc/latex/_me_on_board_temp_test_8ino-example.tex create mode 100644 doc/latex/_me_one_wire_8cpp.tex create mode 100644 doc/latex/_me_one_wire_8cpp__incl.md5 create mode 100644 doc/latex/_me_one_wire_8cpp__incl.pdf create mode 100644 doc/latex/_me_one_wire_8h.tex create mode 100644 doc/latex/_me_one_wire_8h__dep__incl.md5 create mode 100644 doc/latex/_me_one_wire_8h__dep__incl.pdf create mode 100644 doc/latex/_me_one_wire_8h__incl.md5 create mode 100644 doc/latex/_me_one_wire_8h__incl.pdf create mode 100644 doc/latex/_me_one_wire_8h_source.tex create mode 100644 doc/latex/_me_orion_8h.tex create mode 100644 doc/latex/_me_orion_8h__incl.md5 create mode 100644 doc/latex/_me_orion_8h__incl.pdf create mode 100644 doc/latex/_me_orion_8h_source.tex create mode 100644 doc/latex/_me_p_i_r_motion_sensor_8cpp.tex create mode 100644 doc/latex/_me_p_i_r_motion_sensor_8cpp__incl.md5 create mode 100644 doc/latex/_me_p_i_r_motion_sensor_8cpp__incl.pdf create mode 100644 doc/latex/_me_p_i_r_motion_sensor_8h.tex create mode 100644 doc/latex/_me_p_i_r_motion_sensor_8h__dep__incl.md5 create mode 100644 doc/latex/_me_p_i_r_motion_sensor_8h__dep__incl.pdf create mode 100644 doc/latex/_me_p_i_r_motion_sensor_8h__incl.md5 create mode 100644 doc/latex/_me_p_i_r_motion_sensor_8h__incl.pdf create mode 100644 doc/latex/_me_p_i_r_motion_sensor_8h_source.tex create mode 100644 doc/latex/_me_p_s2_8cpp.tex create mode 100644 doc/latex/_me_p_s2_8cpp__incl.md5 create mode 100644 doc/latex/_me_p_s2_8cpp__incl.pdf create mode 100644 doc/latex/_me_p_s2_8h.tex create mode 100644 doc/latex/_me_p_s2_8h__dep__incl.md5 create mode 100644 doc/latex/_me_p_s2_8h__dep__incl.pdf create mode 100644 doc/latex/_me_p_s2_8h__incl.md5 create mode 100644 doc/latex/_me_p_s2_8h__incl.pdf create mode 100644 doc/latex/_me_p_s2_8h_source.tex create mode 100644 doc/latex/_me_p_s2_test_8ino-example.tex create mode 100644 doc/latex/_me_pm25_sensor_8cpp.tex create mode 100644 doc/latex/_me_pm25_sensor_8cpp__incl.md5 create mode 100644 doc/latex/_me_pm25_sensor_8cpp__incl.pdf create mode 100644 doc/latex/_me_pm25_sensor_8h.tex create mode 100644 doc/latex/_me_pm25_sensor_8h__dep__incl.md5 create mode 100644 doc/latex/_me_pm25_sensor_8h__dep__incl.pdf create mode 100644 doc/latex/_me_pm25_sensor_8h__incl.md5 create mode 100644 doc/latex/_me_pm25_sensor_8h__incl.pdf create mode 100644 doc/latex/_me_pm25_sensor_8h_source.tex create mode 100644 doc/latex/_me_port_8cpp.tex create mode 100644 doc/latex/_me_port_8cpp__incl.md5 create mode 100644 doc/latex/_me_port_8cpp__incl.pdf create mode 100644 doc/latex/_me_port_8h.tex create mode 100644 doc/latex/_me_port_8h__dep__incl.md5 create mode 100644 doc/latex/_me_port_8h__dep__incl.pdf create mode 100644 doc/latex/_me_port_8h__incl.md5 create mode 100644 doc/latex/_me_port_8h__incl.pdf create mode 100644 doc/latex/_me_port_8h_source.tex create mode 100644 doc/latex/_me_potentiometer_8cpp.tex create mode 100644 doc/latex/_me_potentiometer_8cpp__incl.md5 create mode 100644 doc/latex/_me_potentiometer_8cpp__incl.pdf create mode 100644 doc/latex/_me_potentiometer_8h.tex create mode 100644 doc/latex/_me_potentiometer_8h__dep__incl.md5 create mode 100644 doc/latex/_me_potentiometer_8h__dep__incl.pdf create mode 100644 doc/latex/_me_potentiometer_8h__incl.md5 create mode 100644 doc/latex/_me_potentiometer_8h__incl.pdf create mode 100644 doc/latex/_me_potentiometer_8h_source.tex create mode 100644 doc/latex/_me_pressure_sensor_8h_source.tex create mode 100644 doc/latex/_me_r_g_b_led_8cpp.tex create mode 100644 doc/latex/_me_r_g_b_led_8cpp__incl.md5 create mode 100644 doc/latex/_me_r_g_b_led_8cpp__incl.pdf create mode 100644 doc/latex/_me_r_g_b_led_8h.tex create mode 100644 doc/latex/_me_r_g_b_led_8h__dep__incl.md5 create mode 100644 doc/latex/_me_r_g_b_led_8h__dep__incl.pdf create mode 100644 doc/latex/_me_r_g_b_led_8h__incl.md5 create mode 100644 doc/latex/_me_r_g_b_led_8h__incl.pdf create mode 100644 doc/latex/_me_r_g_b_led_8h_source.tex create mode 100644 doc/latex/_me_serial_8cpp.tex create mode 100644 doc/latex/_me_serial_8cpp__incl.md5 create mode 100644 doc/latex/_me_serial_8cpp__incl.pdf create mode 100644 doc/latex/_me_serial_8h.tex create mode 100644 doc/latex/_me_serial_8h__dep__incl.md5 create mode 100644 doc/latex/_me_serial_8h__dep__incl.pdf create mode 100644 doc/latex/_me_serial_8h__incl.md5 create mode 100644 doc/latex/_me_serial_8h__incl.pdf create mode 100644 doc/latex/_me_serial_8h_source.tex create mode 100644 doc/latex/_me_serial_receive_test_8ino-example.tex create mode 100644 doc/latex/_me_serial_transmit_test_8ino-example.tex create mode 100644 doc/latex/_me_shield_8h.tex create mode 100644 doc/latex/_me_shield_8h__incl.md5 create mode 100644 doc/latex/_me_shield_8h__incl.pdf create mode 100644 doc/latex/_me_shield_8h_source.tex create mode 100644 doc/latex/_me_shutter_8cpp.tex create mode 100644 doc/latex/_me_shutter_8cpp__incl.md5 create mode 100644 doc/latex/_me_shutter_8cpp__incl.pdf create mode 100644 doc/latex/_me_shutter_8h.tex create mode 100644 doc/latex/_me_shutter_8h__dep__incl.md5 create mode 100644 doc/latex/_me_shutter_8h__dep__incl.pdf create mode 100644 doc/latex/_me_shutter_8h__incl.md5 create mode 100644 doc/latex/_me_shutter_8h__incl.pdf create mode 100644 doc/latex/_me_shutter_8h_source.tex create mode 100644 doc/latex/_me_shutter_test_8ino-example.tex create mode 100644 doc/latex/_me_smart_servo_8cpp.tex create mode 100644 doc/latex/_me_smart_servo_8cpp__incl.md5 create mode 100644 doc/latex/_me_smart_servo_8cpp__incl.pdf create mode 100644 doc/latex/_me_smart_servo_8h.tex create mode 100644 doc/latex/_me_smart_servo_8h__dep__incl.md5 create mode 100644 doc/latex/_me_smart_servo_8h__dep__incl.pdf create mode 100644 doc/latex/_me_smart_servo_8h__incl.md5 create mode 100644 doc/latex/_me_smart_servo_8h__incl.pdf create mode 100644 doc/latex/_me_smart_servo_8h_source.tex create mode 100644 doc/latex/_me_sound_sensor_8cpp.tex create mode 100644 doc/latex/_me_sound_sensor_8cpp__incl.md5 create mode 100644 doc/latex/_me_sound_sensor_8cpp__incl.pdf create mode 100644 doc/latex/_me_stepper_8cpp.tex create mode 100644 doc/latex/_me_stepper_8cpp__incl.md5 create mode 100644 doc/latex/_me_stepper_8cpp__incl.pdf create mode 100644 doc/latex/_me_stepper_8h.tex create mode 100644 doc/latex/_me_stepper_8h__dep__incl.md5 create mode 100644 doc/latex/_me_stepper_8h__dep__incl.pdf create mode 100644 doc/latex/_me_stepper_8h__incl.md5 create mode 100644 doc/latex/_me_stepper_8h__incl.pdf create mode 100644 doc/latex/_me_stepper_8h_source.tex create mode 100644 doc/latex/_me_stepper_on_board_8cpp.tex create mode 100644 doc/latex/_me_stepper_on_board_8cpp__incl.md5 create mode 100644 doc/latex/_me_stepper_on_board_8cpp__incl.pdf create mode 100644 doc/latex/_me_stepper_on_board_8h.tex create mode 100644 doc/latex/_me_stepper_on_board_8h__dep__incl.md5 create mode 100644 doc/latex/_me_stepper_on_board_8h__dep__incl.pdf create mode 100644 doc/latex/_me_stepper_on_board_8h__incl.md5 create mode 100644 doc/latex/_me_stepper_on_board_8h__incl.pdf create mode 100644 doc/latex/_me_stepper_on_board_8h_source.tex create mode 100644 doc/latex/_me_temperature_8cpp.tex create mode 100644 doc/latex/_me_temperature_8cpp__incl.md5 create mode 100644 doc/latex/_me_temperature_8cpp__incl.pdf create mode 100644 doc/latex/_me_temperature_8h.tex create mode 100644 doc/latex/_me_temperature_8h__dep__incl.md5 create mode 100644 doc/latex/_me_temperature_8h__dep__incl.pdf create mode 100644 doc/latex/_me_temperature_8h__incl.md5 create mode 100644 doc/latex/_me_temperature_8h__incl.pdf create mode 100644 doc/latex/_me_temperature_8h_source.tex create mode 100644 doc/latex/_me_touch_sensor_8cpp.tex create mode 100644 doc/latex/_me_touch_sensor_8cpp__incl.md5 create mode 100644 doc/latex/_me_touch_sensor_8cpp__incl.pdf create mode 100644 doc/latex/_me_touch_sensor_8h.tex create mode 100644 doc/latex/_me_touch_sensor_8h__dep__incl.md5 create mode 100644 doc/latex/_me_touch_sensor_8h__dep__incl.pdf create mode 100644 doc/latex/_me_touch_sensor_8h__incl.md5 create mode 100644 doc/latex/_me_touch_sensor_8h__incl.pdf create mode 100644 doc/latex/_me_touch_sensor_8h_source.tex create mode 100644 doc/latex/_me_u_s_b_host_8cpp.tex create mode 100644 doc/latex/_me_u_s_b_host_8cpp__incl.md5 create mode 100644 doc/latex/_me_u_s_b_host_8cpp__incl.pdf create mode 100644 doc/latex/_me_u_s_b_host_8h.tex create mode 100644 doc/latex/_me_u_s_b_host_8h__dep__incl.md5 create mode 100644 doc/latex/_me_u_s_b_host_8h__dep__incl.pdf create mode 100644 doc/latex/_me_u_s_b_host_8h__incl.md5 create mode 100644 doc/latex/_me_u_s_b_host_8h__incl.pdf create mode 100644 doc/latex/_me_u_s_b_host_8h_source.tex create mode 100644 doc/latex/_me_ultrasonic_sensor_8cpp.tex create mode 100644 doc/latex/_me_ultrasonic_sensor_8cpp__incl.md5 create mode 100644 doc/latex/_me_ultrasonic_sensor_8cpp__incl.pdf create mode 100644 doc/latex/_me_ultrasonic_sensor_8h.tex create mode 100644 doc/latex/_me_ultrasonic_sensor_8h__dep__incl.md5 create mode 100644 doc/latex/_me_ultrasonic_sensor_8h__dep__incl.pdf create mode 100644 doc/latex/_me_ultrasonic_sensor_8h__incl.md5 create mode 100644 doc/latex/_me_ultrasonic_sensor_8h__incl.pdf create mode 100644 doc/latex/_me_ultrasonic_sensor_8h_source.tex create mode 100644 doc/latex/_me_voice_8cpp.tex create mode 100644 doc/latex/_me_voice_8cpp__incl.md5 create mode 100644 doc/latex/_me_voice_8cpp__incl.pdf create mode 100644 doc/latex/_me_voice_8h.tex create mode 100644 doc/latex/_me_voice_8h__dep__incl.md5 create mode 100644 doc/latex/_me_voice_8h__dep__incl.pdf create mode 100644 doc/latex/_me_voice_8h__incl.md5 create mode 100644 doc/latex/_me_voice_8h__incl.pdf create mode 100644 doc/latex/_me_voice_8h_source.tex create mode 100644 doc/latex/_me_voice_test_8ino-example.tex create mode 100644 doc/latex/_me_wifi_8cpp.tex create mode 100644 doc/latex/_me_wifi_8cpp__incl.md5 create mode 100644 doc/latex/_me_wifi_8cpp__incl.pdf create mode 100644 doc/latex/_me_wifi_8h.tex create mode 100644 doc/latex/_me_wifi_8h__dep__incl.md5 create mode 100644 doc/latex/_me_wifi_8h__dep__incl.pdf create mode 100644 doc/latex/_me_wifi_8h__incl.md5 create mode 100644 doc/latex/_me_wifi_8h__incl.pdf create mode 100644 doc/latex/_me_wifi_8h_source.tex create mode 100644 doc/latex/_me_wifi_8ino-example.tex create mode 100644 doc/latex/_mega_pi_on_board_stepper_test_8ino-example.tex create mode 100644 doc/latex/_number_display_8ino-example.tex create mode 100644 doc/latex/_number_flow_8ino-example.tex create mode 100644 doc/latex/_p_i_r_motion_sensor_test_8ino-example.tex create mode 100644 doc/latex/_pm25_sensor_8ino-example.tex create mode 100644 doc/latex/_potentiometer_test_8ino-example.tex create mode 100644 doc/latex/_s_p_i_8h_source.tex create mode 100644 doc/latex/_servo_8h_source.tex create mode 100644 doc/latex/_servo_timers_8h_source.tex create mode 100644 doc/latex/_slave_bluetooth_by_soft_serial_test_8ino-example.tex create mode 100644 doc/latex/_smart_servo_test_8ino-example.tex create mode 100644 doc/latex/_software_serial_8h_source.tex create mode 100644 doc/latex/_sound_sensor_test_8ino-example.tex create mode 100644 doc/latex/_temperature_test_8ino-example.tex create mode 100644 doc/latex/_test_u_s_b_hsot_8ino-example.tex create mode 100644 doc/latex/_time_display_8ino-example.tex create mode 100644 doc/latex/_touch_sensor_test_8ino-example.tex create mode 100644 doc/latex/_ultrasonic_sensor_test_8ino-example.tex create mode 100644 doc/latex/_white_breath_light_test_8ino-example.tex create mode 100644 doc/latex/_wire_8h_source.tex create mode 100644 doc/latex/annotated.tex create mode 100644 doc/latex/class_m_bot_d_c_motor.eps create mode 100644 doc/latex/class_m_bot_d_c_motor.tex create mode 100644 doc/latex/class_m_bot_d_c_motor__coll__graph.md5 create mode 100644 doc/latex/class_m_bot_d_c_motor__coll__graph.pdf create mode 100644 doc/latex/class_m_bot_d_c_motor__inherit__graph.md5 create mode 100644 doc/latex/class_m_bot_d_c_motor__inherit__graph.pdf create mode 100644 doc/latex/class_me4_button.eps create mode 100644 doc/latex/class_me4_button.tex create mode 100644 doc/latex/class_me4_button__coll__graph.md5 create mode 100644 doc/latex/class_me4_button__coll__graph.pdf create mode 100644 doc/latex/class_me4_button__inherit__graph.md5 create mode 100644 doc/latex/class_me4_button__inherit__graph.pdf create mode 100644 doc/latex/class_me7_segment_display.eps create mode 100644 doc/latex/class_me7_segment_display.tex create mode 100644 doc/latex/class_me7_segment_display__coll__graph.md5 create mode 100644 doc/latex/class_me7_segment_display__coll__graph.pdf create mode 100644 doc/latex/class_me7_segment_display__inherit__graph.md5 create mode 100644 doc/latex/class_me7_segment_display__inherit__graph.pdf create mode 100644 doc/latex/class_me_bluetooth.eps create mode 100644 doc/latex/class_me_bluetooth.tex create mode 100644 doc/latex/class_me_bluetooth__coll__graph.md5 create mode 100644 doc/latex/class_me_bluetooth__coll__graph.pdf create mode 100644 doc/latex/class_me_bluetooth__inherit__graph.md5 create mode 100644 doc/latex/class_me_bluetooth__inherit__graph.pdf create mode 100644 doc/latex/class_me_buzzer.eps create mode 100644 doc/latex/class_me_buzzer.tex create mode 100644 doc/latex/class_me_buzzer__coll__graph.md5 create mode 100644 doc/latex/class_me_buzzer__coll__graph.pdf create mode 100644 doc/latex/class_me_buzzer__inherit__graph.md5 create mode 100644 doc/latex/class_me_buzzer__inherit__graph.pdf create mode 100644 doc/latex/class_me_color_sensor.eps create mode 100644 doc/latex/class_me_color_sensor.tex create mode 100644 doc/latex/class_me_color_sensor__coll__graph.md5 create mode 100644 doc/latex/class_me_color_sensor__coll__graph.pdf create mode 100644 doc/latex/class_me_color_sensor__inherit__graph.md5 create mode 100644 doc/latex/class_me_color_sensor__inherit__graph.pdf create mode 100644 doc/latex/class_me_compass.eps create mode 100644 doc/latex/class_me_compass.tex create mode 100644 doc/latex/class_me_compass__coll__graph.md5 create mode 100644 doc/latex/class_me_compass__coll__graph.pdf create mode 100644 doc/latex/class_me_compass__inherit__graph.md5 create mode 100644 doc/latex/class_me_compass__inherit__graph.pdf create mode 100644 doc/latex/class_me_d_c_motor.eps create mode 100644 doc/latex/class_me_d_c_motor.tex create mode 100644 doc/latex/class_me_d_c_motor__coll__graph.md5 create mode 100644 doc/latex/class_me_d_c_motor__coll__graph.pdf create mode 100644 doc/latex/class_me_d_c_motor__inherit__graph.md5 create mode 100644 doc/latex/class_me_d_c_motor__inherit__graph.pdf create mode 100644 doc/latex/class_me_encoder_motor.eps create mode 100644 doc/latex/class_me_encoder_motor.tex create mode 100644 doc/latex/class_me_encoder_motor__coll__graph.md5 create mode 100644 doc/latex/class_me_encoder_motor__coll__graph.pdf create mode 100644 doc/latex/class_me_encoder_motor__inherit__graph.md5 create mode 100644 doc/latex/class_me_encoder_motor__inherit__graph.pdf create mode 100644 doc/latex/class_me_encoder_new.tex create mode 100644 doc/latex/class_me_encoder_on_board.tex create mode 100644 doc/latex/class_me_flame_sensor.eps create mode 100644 doc/latex/class_me_flame_sensor.tex create mode 100644 doc/latex/class_me_flame_sensor__coll__graph.md5 create mode 100644 doc/latex/class_me_flame_sensor__coll__graph.pdf create mode 100644 doc/latex/class_me_flame_sensor__inherit__graph.md5 create mode 100644 doc/latex/class_me_flame_sensor__inherit__graph.pdf create mode 100644 doc/latex/class_me_gas_sensor.eps create mode 100644 doc/latex/class_me_gas_sensor.tex create mode 100644 doc/latex/class_me_gas_sensor__coll__graph.md5 create mode 100644 doc/latex/class_me_gas_sensor__coll__graph.pdf create mode 100644 doc/latex/class_me_gas_sensor__inherit__graph.md5 create mode 100644 doc/latex/class_me_gas_sensor__inherit__graph.pdf create mode 100644 doc/latex/class_me_gyro.eps create mode 100644 doc/latex/class_me_gyro.tex create mode 100644 doc/latex/class_me_gyro__coll__graph.md5 create mode 100644 doc/latex/class_me_gyro__coll__graph.pdf create mode 100644 doc/latex/class_me_gyro__inherit__graph.md5 create mode 100644 doc/latex/class_me_gyro__inherit__graph.pdf create mode 100644 doc/latex/class_me_host_parser.tex create mode 100644 doc/latex/class_me_humiture.eps create mode 100644 doc/latex/class_me_humiture.tex create mode 100644 doc/latex/class_me_humiture__coll__graph.md5 create mode 100644 doc/latex/class_me_humiture__coll__graph.pdf create mode 100644 doc/latex/class_me_humiture__inherit__graph.md5 create mode 100644 doc/latex/class_me_humiture__inherit__graph.pdf create mode 100644 doc/latex/class_me_i_r.tex create mode 100644 doc/latex/class_me_infrared_receiver.eps create mode 100644 doc/latex/class_me_infrared_receiver.tex create mode 100644 doc/latex/class_me_infrared_receiver__coll__graph.md5 create mode 100644 doc/latex/class_me_infrared_receiver__coll__graph.pdf create mode 100644 doc/latex/class_me_infrared_receiver__inherit__graph.md5 create mode 100644 doc/latex/class_me_infrared_receiver__inherit__graph.pdf create mode 100644 doc/latex/class_me_joystick.eps create mode 100644 doc/latex/class_me_joystick.tex create mode 100644 doc/latex/class_me_joystick__coll__graph.md5 create mode 100644 doc/latex/class_me_joystick__coll__graph.pdf create mode 100644 doc/latex/class_me_joystick__inherit__graph.md5 create mode 100644 doc/latex/class_me_joystick__inherit__graph.pdf create mode 100644 doc/latex/class_me_l_e_d_matrix.eps create mode 100644 doc/latex/class_me_l_e_d_matrix.tex create mode 100644 doc/latex/class_me_l_e_d_matrix__coll__graph.md5 create mode 100644 doc/latex/class_me_l_e_d_matrix__coll__graph.pdf create mode 100644 doc/latex/class_me_l_e_d_matrix__inherit__graph.md5 create mode 100644 doc/latex/class_me_l_e_d_matrix__inherit__graph.pdf create mode 100644 doc/latex/class_me_light_sensor.eps create mode 100644 doc/latex/class_me_light_sensor.tex create mode 100644 doc/latex/class_me_light_sensor__coll__graph.md5 create mode 100644 doc/latex/class_me_light_sensor__coll__graph.pdf create mode 100644 doc/latex/class_me_light_sensor__inherit__graph.md5 create mode 100644 doc/latex/class_me_light_sensor__inherit__graph.pdf create mode 100644 doc/latex/class_me_limit_switch.eps create mode 100644 doc/latex/class_me_limit_switch.tex create mode 100644 doc/latex/class_me_limit_switch__coll__graph.md5 create mode 100644 doc/latex/class_me_limit_switch__coll__graph.pdf create mode 100644 doc/latex/class_me_limit_switch__inherit__graph.md5 create mode 100644 doc/latex/class_me_limit_switch__inherit__graph.pdf create mode 100644 doc/latex/class_me_line_follower.eps create mode 100644 doc/latex/class_me_line_follower.tex create mode 100644 doc/latex/class_me_line_follower__coll__graph.md5 create mode 100644 doc/latex/class_me_line_follower__coll__graph.pdf create mode 100644 doc/latex/class_me_line_follower__inherit__graph.md5 create mode 100644 doc/latex/class_me_line_follower__inherit__graph.pdf create mode 100644 doc/latex/class_me_mega_pi_d_c_motor.tex create mode 100644 doc/latex/class_me_mega_pi_pro4_dc_motor.eps create mode 100644 doc/latex/class_me_mega_pi_pro4_dc_motor.tex create mode 100644 doc/latex/class_me_mega_pi_pro4_dc_motor__coll__graph.md5 create mode 100644 doc/latex/class_me_mega_pi_pro4_dc_motor__coll__graph.pdf create mode 100644 doc/latex/class_me_mega_pi_pro4_dc_motor__inherit__graph.md5 create mode 100644 doc/latex/class_me_mega_pi_pro4_dc_motor__inherit__graph.pdf create mode 100644 doc/latex/class_me_mega_pi_pro_e_s_c_motor.tex create mode 100644 doc/latex/class_me_on_board_temp.eps create mode 100644 doc/latex/class_me_on_board_temp.tex create mode 100644 doc/latex/class_me_on_board_temp__coll__graph.md5 create mode 100644 doc/latex/class_me_on_board_temp__coll__graph.pdf create mode 100644 doc/latex/class_me_on_board_temp__inherit__graph.md5 create mode 100644 doc/latex/class_me_on_board_temp__inherit__graph.pdf create mode 100644 doc/latex/class_me_one_wire.tex create mode 100644 doc/latex/class_me_p_i_r_motion_sensor.eps create mode 100644 doc/latex/class_me_p_i_r_motion_sensor.tex create mode 100644 doc/latex/class_me_p_i_r_motion_sensor__coll__graph.md5 create mode 100644 doc/latex/class_me_p_i_r_motion_sensor__coll__graph.pdf create mode 100644 doc/latex/class_me_p_i_r_motion_sensor__inherit__graph.md5 create mode 100644 doc/latex/class_me_p_i_r_motion_sensor__inherit__graph.pdf create mode 100644 doc/latex/class_me_p_s2.eps create mode 100644 doc/latex/class_me_p_s2.tex create mode 100644 doc/latex/class_me_p_s2__coll__graph.md5 create mode 100644 doc/latex/class_me_p_s2__coll__graph.pdf create mode 100644 doc/latex/class_me_p_s2__inherit__graph.md5 create mode 100644 doc/latex/class_me_p_s2__inherit__graph.pdf create mode 100644 doc/latex/class_me_pm25_sensor.eps create mode 100644 doc/latex/class_me_pm25_sensor.tex create mode 100644 doc/latex/class_me_pm25_sensor__coll__graph.md5 create mode 100644 doc/latex/class_me_pm25_sensor__coll__graph.pdf create mode 100644 doc/latex/class_me_pm25_sensor__inherit__graph.md5 create mode 100644 doc/latex/class_me_pm25_sensor__inherit__graph.pdf create mode 100644 doc/latex/class_me_port.eps create mode 100644 doc/latex/class_me_port.tex create mode 100644 doc/latex/class_me_port__inherit__graph.md5 create mode 100644 doc/latex/class_me_port__inherit__graph.pdf create mode 100644 doc/latex/class_me_potentiometer.eps create mode 100644 doc/latex/class_me_potentiometer.tex create mode 100644 doc/latex/class_me_potentiometer__coll__graph.md5 create mode 100644 doc/latex/class_me_potentiometer__coll__graph.pdf create mode 100644 doc/latex/class_me_potentiometer__inherit__graph.md5 create mode 100644 doc/latex/class_me_potentiometer__inherit__graph.pdf create mode 100644 doc/latex/class_me_pressure_sensor.tex create mode 100644 doc/latex/class_me_r_g_b_led.eps create mode 100644 doc/latex/class_me_r_g_b_led.tex create mode 100644 doc/latex/class_me_r_g_b_led__coll__graph.md5 create mode 100644 doc/latex/class_me_r_g_b_led__coll__graph.pdf create mode 100644 doc/latex/class_me_r_g_b_led__inherit__graph.md5 create mode 100644 doc/latex/class_me_r_g_b_led__inherit__graph.pdf create mode 100644 doc/latex/class_me_serial.eps create mode 100644 doc/latex/class_me_serial.tex create mode 100644 doc/latex/class_me_serial__coll__graph.md5 create mode 100644 doc/latex/class_me_serial__coll__graph.pdf create mode 100644 doc/latex/class_me_serial__inherit__graph.md5 create mode 100644 doc/latex/class_me_serial__inherit__graph.pdf create mode 100644 doc/latex/class_me_shutter.eps create mode 100644 doc/latex/class_me_shutter.tex create mode 100644 doc/latex/class_me_shutter__coll__graph.md5 create mode 100644 doc/latex/class_me_shutter__coll__graph.pdf create mode 100644 doc/latex/class_me_shutter__inherit__graph.md5 create mode 100644 doc/latex/class_me_shutter__inherit__graph.pdf create mode 100644 doc/latex/class_me_smart_servo.eps create mode 100644 doc/latex/class_me_smart_servo.tex create mode 100644 doc/latex/class_me_smart_servo__coll__graph.md5 create mode 100644 doc/latex/class_me_smart_servo__coll__graph.pdf create mode 100644 doc/latex/class_me_smart_servo__inherit__graph.md5 create mode 100644 doc/latex/class_me_smart_servo__inherit__graph.pdf create mode 100644 doc/latex/class_me_sound_sensor.tex create mode 100644 doc/latex/class_me_stepper.eps create mode 100644 doc/latex/class_me_stepper.tex create mode 100644 doc/latex/class_me_stepper__coll__graph.md5 create mode 100644 doc/latex/class_me_stepper__coll__graph.pdf create mode 100644 doc/latex/class_me_stepper__inherit__graph.md5 create mode 100644 doc/latex/class_me_stepper__inherit__graph.pdf create mode 100644 doc/latex/class_me_stepper_on_board.tex create mode 100644 doc/latex/class_me_temperature.eps create mode 100644 doc/latex/class_me_temperature.tex create mode 100644 doc/latex/class_me_temperature__coll__graph.md5 create mode 100644 doc/latex/class_me_temperature__coll__graph.pdf create mode 100644 doc/latex/class_me_temperature__inherit__graph.md5 create mode 100644 doc/latex/class_me_temperature__inherit__graph.pdf create mode 100644 doc/latex/class_me_touch_sensor.eps create mode 100644 doc/latex/class_me_touch_sensor.tex create mode 100644 doc/latex/class_me_touch_sensor__coll__graph.md5 create mode 100644 doc/latex/class_me_touch_sensor__coll__graph.pdf create mode 100644 doc/latex/class_me_touch_sensor__inherit__graph.md5 create mode 100644 doc/latex/class_me_touch_sensor__inherit__graph.pdf create mode 100644 doc/latex/class_me_u_s_b_host.eps create mode 100644 doc/latex/class_me_u_s_b_host.tex create mode 100644 doc/latex/class_me_u_s_b_host__coll__graph.md5 create mode 100644 doc/latex/class_me_u_s_b_host__coll__graph.pdf create mode 100644 doc/latex/class_me_u_s_b_host__inherit__graph.md5 create mode 100644 doc/latex/class_me_u_s_b_host__inherit__graph.pdf create mode 100644 doc/latex/class_me_ultrasonic_sensor.eps create mode 100644 doc/latex/class_me_ultrasonic_sensor.tex create mode 100644 doc/latex/class_me_ultrasonic_sensor__coll__graph.md5 create mode 100644 doc/latex/class_me_ultrasonic_sensor__coll__graph.pdf create mode 100644 doc/latex/class_me_ultrasonic_sensor__inherit__graph.md5 create mode 100644 doc/latex/class_me_ultrasonic_sensor__inherit__graph.pdf create mode 100644 doc/latex/class_me_voice.eps create mode 100644 doc/latex/class_me_voice.tex create mode 100644 doc/latex/class_me_voice__coll__graph.md5 create mode 100644 doc/latex/class_me_voice__coll__graph.pdf create mode 100644 doc/latex/class_me_voice__inherit__graph.md5 create mode 100644 doc/latex/class_me_voice__inherit__graph.pdf create mode 100644 doc/latex/class_me_wifi.eps create mode 100644 doc/latex/class_me_wifi.tex create mode 100644 doc/latex/class_me_wifi__coll__graph.md5 create mode 100644 doc/latex/class_me_wifi__coll__graph.pdf create mode 100644 doc/latex/class_me_wifi__inherit__graph.md5 create mode 100644 doc/latex/class_me_wifi__inherit__graph.pdf create mode 100644 doc/latex/class_mecolor.tex create mode 100644 doc/latex/class_s_p_i_class.tex create mode 100644 doc/latex/class_s_p_i_settings.tex create mode 100644 doc/latex/class_servo.tex create mode 100644 doc/latex/class_software_serial.eps create mode 100644 doc/latex/class_software_serial.tex create mode 100644 doc/latex/class_software_serial__coll__graph.md5 create mode 100644 doc/latex/class_software_serial__coll__graph.pdf create mode 100644 doc/latex/class_software_serial__inherit__graph.md5 create mode 100644 doc/latex/class_software_serial__inherit__graph.pdf create mode 100644 doc/latex/class_two_wire.eps create mode 100644 doc/latex/class_two_wire.tex create mode 100644 doc/latex/class_two_wire__coll__graph.md5 create mode 100644 doc/latex/class_two_wire__coll__graph.pdf create mode 100644 doc/latex/class_two_wire__inherit__graph.md5 create mode 100644 doc/latex/class_two_wire__inherit__graph.pdf create mode 100644 doc/latex/doxygen.sty create mode 100644 doc/latex/etoc_doxygen.sty create mode 100644 doc/latex/examples.tex create mode 100644 doc/latex/files.tex create mode 100644 doc/latex/hierarchy.tex create mode 100644 doc/latex/index.tex create mode 100644 doc/latex/longtable_doxygen.sty create mode 100644 doc/latex/make.bat create mode 100644 doc/latex/refman.tex create mode 100644 doc/latex/struct___u_s_b___c_o_n_f_i_g___d_escript_o_r.tex create mode 100644 doc/latex/struct___u_s_b___c_o_n_f_i_g___d_escript_o_r___l_o_n_g.tex create mode 100644 doc/latex/struct___u_s_b___c_o_n_f_i_g___d_escript_o_r___l_o_n_g__coll__graph.md5 create mode 100644 doc/latex/struct___u_s_b___c_o_n_f_i_g___d_escript_o_r___l_o_n_g__coll__graph.pdf create mode 100644 doc/latex/struct___u_s_b___d_e_v_i_c_e___d_escript_o_r.tex create mode 100644 doc/latex/struct___u_s_b___e_n_d_p_o_i_n_t___d_escript_o_r.tex create mode 100644 doc/latex/struct___u_s_b___i_n_t_e_r_f___d_escript_o_r.tex create mode 100644 doc/latex/struct_cmd__list__tab__type.tex create mode 100644 doc/latex/struct_compass___calibration___parameter.tex create mode 100644 doc/latex/struct_e_e_p_r_o_m_class.tex create mode 100644 doc/latex/struct_e_e_ptr.tex create mode 100644 doc/latex/struct_e_e_ref.tex create mode 100644 doc/latex/struct_encoder__port__type.tex create mode 100644 doc/latex/struct_l_e_d___matrix___clock___number___font__3x8___type_def.tex create mode 100644 doc/latex/struct_l_e_d___matrix___font__6x8___type_def.tex create mode 100644 doc/latex/struct_me___encoder__type.tex create mode 100644 doc/latex/struct_me___encoder__type__coll__graph.md5 create mode 100644 doc/latex/struct_me___encoder__type__coll__graph.pdf create mode 100644 doc/latex/struct_me_port___sig.tex create mode 100644 doc/latex/struct_p_i_d__internal.tex create mode 100644 doc/latex/struct_p_m25_d_a_t_a_s_t_r_u_c_t.tex create mode 100644 doc/latex/struct_servo_pin__t.tex create mode 100644 doc/latex/structc_r_g_b.tex create mode 100644 doc/latex/structirparams__t.tex create mode 100644 doc/latex/structmega_pi__slot.tex create mode 100644 doc/latex/structmegapi__dc__type.tex create mode 100644 doc/latex/structmegapipro__esc__type.tex create mode 100644 doc/latex/structservo__device__type.tex create mode 100644 doc/latex/structservo__t.tex create mode 100644 doc/latex/structservo__t__coll__graph.md5 create mode 100644 doc/latex/structservo__t__coll__graph.pdf create mode 100644 doc/latex/structsysex__message__type.tex create mode 100644 doc/latex/tabu_doxygen.sty create mode 100644 doc/latex/twi_8h_source.tex create mode 100644 doc/latex/union_p_m25_d_a_t_a_u_i_n_o.tex create mode 100644 doc/latex/union_p_m25_d_a_t_a_u_i_n_o__coll__graph.md5 create mode 100644 doc/latex/union_p_m25_d_a_t_a_u_i_n_o__coll__graph.pdf create mode 100644 doc/latex/unionsysex__message.tex create mode 100644 doc/latex/unionsysex__message__coll__graph.md5 create mode 100644 doc/latex/unionsysex__message__coll__graph.pdf diff --git a/src/MeSoundSensor.h b/MeSoundSensor.h similarity index 100% rename from src/MeSoundSensor.h rename to MeSoundSensor.h diff --git a/doc/html/_buzzer_test_8ino-example.html b/doc/html/_buzzer_test_8ino-example.html new file mode 100644 index 00000000..aa33ed31 --- /dev/null +++ b/doc/html/_buzzer_test_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: BuzzerTest.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
BuzzerTest.ino
+
+
+
+
+ + + + diff --git a/doc/html/_color_loop_test_8ino-example.html b/doc/html/_color_loop_test_8ino-example.html new file mode 100644 index 00000000..f9751b4b --- /dev/null +++ b/doc/html/_color_loop_test_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: ColorLoopTest.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
ColorLoopTest.ino
+
+
+
+
+ + + + diff --git a/doc/html/_d_c_motor_driver_test_8ino-example.html b/doc/html/_d_c_motor_driver_test_8ino-example.html new file mode 100644 index 00000000..16993b9c --- /dev/null +++ b/doc/html/_d_c_motor_driver_test_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: DCMotorDriverTest.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
DCMotorDriverTest.ino
+
+
+
+
+ + + + diff --git a/doc/html/_e_e_p_r_o_m_8h_source.html b/doc/html/_e_e_p_r_o_m_8h_source.html new file mode 100644 index 00000000..d6a39991 --- /dev/null +++ b/doc/html/_e_e_p_r_o_m_8h_source.html @@ -0,0 +1,268 @@ + + + + + + + +MakeBlock Drive Updated: src/utility/EEPROM.h Source File + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
EEPROM.h
+
+
+
1/*
+
2 EEPROM.h - EEPROM library
+
3 Original Copyright (c) 2006 David A. Mellis. All right reserved.
+
4 New version by Christopher Andrews 2015.
+
5
+
6 This library is free software; you can redistribute it and/or
+
7 modify it under the terms of the GNU Lesser General Public
+
8 License as published by the Free Software Foundation; either
+
9 version 2.1 of the License, or (at your option) any later version.
+
10
+
11 This library is distributed in the hope that it will be useful,
+
12 but WITHOUT ANY WARRANTY; without even the implied warranty of
+
13 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+
14 Lesser General Public License for more details.
+
15
+
16 You should have received a copy of the GNU Lesser General Public
+
17 License along with this library; if not, write to the Free Software
+
18 Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+
19*/
+
20
+
21#ifndef EEPROM_h
+
22#define EEPROM_h
+
23
+
24#include <inttypes.h>
+
25#include <avr/eeprom.h>
+
26#include <avr/io.h>
+
27
+
28/***
+
29 EERef class.
+
30
+
31 This object references an EEPROM cell.
+
32 Its purpose is to mimic a typical byte of RAM, however its storage is the EEPROM.
+
33 This class has an overhead of two bytes, similar to storing a pointer to an EEPROM cell.
+
34***/
+
35
+
+
36struct EERef{
+
37
+
38 EERef( const int index )
+
39 : index( index ) {}
+
40
+
41 //Access/read members.
+
42 uint8_t operator*() const { return eeprom_read_byte( (uint8_t*) index ); }
+
43 operator uint8_t() const { return **this; }
+
44
+
45 //Assignment/write members.
+
46 EERef &operator=( const EERef &ref ) { return *this = *ref; }
+
47 EERef &operator=( uint8_t in ) { return eeprom_write_byte( (uint8_t*) index, in ), *this; }
+
48 EERef &operator +=( uint8_t in ) { return *this = **this + in; }
+
49 EERef &operator -=( uint8_t in ) { return *this = **this - in; }
+
50 EERef &operator *=( uint8_t in ) { return *this = **this * in; }
+
51 EERef &operator /=( uint8_t in ) { return *this = **this / in; }
+
52 EERef &operator ^=( uint8_t in ) { return *this = **this ^ in; }
+
53 EERef &operator %=( uint8_t in ) { return *this = **this % in; }
+
54 EERef &operator &=( uint8_t in ) { return *this = **this & in; }
+
55 EERef &operator |=( uint8_t in ) { return *this = **this | in; }
+
56 EERef &operator <<=( uint8_t in ) { return *this = **this << in; }
+
57 EERef &operator >>=( uint8_t in ) { return *this = **this >> in; }
+
58
+
59 EERef &update( uint8_t in ) { return in != *this ? *this = in : *this; }
+
60
+
62 EERef& operator++() { return *this += 1; }
+
63 EERef& operator--() { return *this -= 1; }
+
64
+
+
66 uint8_t operator++ (int){
+
67 uint8_t ret = **this;
+
68 return ++(*this), ret;
+
69 }
+
+
70
+
71 uint8_t operator-- (int){
+
72 uint8_t ret = **this;
+
73 return --(*this), ret;
+
74 }
+
75
+
76 int index; //Index of current EEPROM cell.
+
77};
+
+
78
+
79/***
+
80 EEPtr class.
+
81
+
82 This object is a bidirectional pointer to EEPROM cells represented by EERef objects.
+
83 Just like a normal pointer type, this can be dereferenced and repositioned using
+
84 increment/decrement operators.
+
85***/
+
86
+
+
87struct EEPtr{
+
88
+
89 EEPtr( const int index )
+
90 : index( index ) {}
+
91
+
92 operator int() const { return index; }
+
93 EEPtr &operator=( int in ) { return index = in, *this; }
+
94
+
95 //Iterator functionality.
+
96 bool operator!=( const EEPtr &ptr ) { return index != ptr.index; }
+
97 EERef operator*() { return index; }
+
98
+
100 EEPtr& operator++() { return ++index, *this; }
+
101 EEPtr& operator--() { return --index, *this; }
+
102 EEPtr operator++ (int) { return index++; }
+
103 EEPtr operator-- (int) { return index--; }
+
104
+
105 int index; //Index of current EEPROM cell.
+
106};
+
+
107
+
108/***
+
109 EEPROMClass class.
+
110
+
111 This object represents the entire EEPROM space.
+
112 It wraps the functionality of EEPtr and EERef into a basic interface.
+
113 This class is also 100% backwards compatible with earlier Arduino core releases.
+
114***/
+
115
+
+ +
117
+
118 //Basic user access methods.
+
119 EERef operator[]( const int idx ) { return idx; }
+
120 uint8_t read( int idx ) { return EERef( idx ); }
+
121 void write( int idx, uint8_t val ) { (EERef( idx )) = val; }
+
122 void update( int idx, uint8_t val ) { EERef( idx ).update( val ); }
+
123
+
124 //STL and C++11 iteration capability.
+
125 EEPtr begin() { return 0x00; }
+
126 EEPtr end() { return length(); } //Standards requires this to be the item after the last valid entry. The returned pointer is invalid.
+
127 uint16_t length() { return E2END + 1; }
+
128
+
129 //Functionality to 'get' and 'put' objects to and from EEPROM.
+
130 template< typename T > T &get( int idx, T &t ){
+
131 EEPtr e = idx;
+
132 uint8_t *ptr = (uint8_t*) &t;
+
133 for( int count = sizeof(T) ; count ; --count, ++e ) *ptr++ = *e;
+
134 return t;
+
135 }
+
136
+
137 template< typename T > const T &put( int idx, const T &t ){
+
138 EEPtr e = idx;
+
139 const uint8_t *ptr = (const uint8_t*) &t;
+
140 for( int count = sizeof(T) ; count ; --count, ++e ) (*e).update( *ptr++ );
+
141 return t;
+
142 }
+
143};
+
+
144
+
145__attribute__((unused))
+
146static EEPROMClass EEPROM;
+
147#endif
+
Definition EEPROM.h:116
+
Definition EEPROM.h:87
+
EEPtr & operator++()
Definition EEPROM.h:100
+
Definition EEPROM.h:36
+
EERef & operator++()
Definition EEPROM.h:62
+
+
+ + + + diff --git a/doc/html/_encoder_motor_change_i2_c_dev_i_d_8ino-example.html b/doc/html/_encoder_motor_change_i2_c_dev_i_d_8ino-example.html new file mode 100644 index 00000000..dc16ce76 --- /dev/null +++ b/doc/html/_encoder_motor_change_i2_c_dev_i_d_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: EncoderMotorChangeI2CDevID.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
EncoderMotorChangeI2CDevID.ino
+
+
+
+
+ + + + diff --git a/doc/html/_encoder_motor_test_is_tar_pos_reached_8ino-example.html b/doc/html/_encoder_motor_test_is_tar_pos_reached_8ino-example.html new file mode 100644 index 00000000..920cc885 --- /dev/null +++ b/doc/html/_encoder_motor_test_is_tar_pos_reached_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: EncoderMotorTestIsTarPosReached.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
EncoderMotorTestIsTarPosReached.ino
+
+
+
+
+ + + + diff --git a/doc/html/_encoder_motor_test_move_to_8ino-example.html b/doc/html/_encoder_motor_test_move_to_8ino-example.html new file mode 100644 index 00000000..5d15e2b8 --- /dev/null +++ b/doc/html/_encoder_motor_test_move_to_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: EncoderMotorTestMoveTo.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
EncoderMotorTestMoveTo.ino
+
+
+
+
+ + + + diff --git a/doc/html/_encoder_motor_test_run_speed_8ino-example.html b/doc/html/_encoder_motor_test_run_speed_8ino-example.html new file mode 100644 index 00000000..51c01507 --- /dev/null +++ b/doc/html/_encoder_motor_test_run_speed_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: EncoderMotorTestRunSpeed.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
EncoderMotorTestRunSpeed.ino
+
+
+
+
+ + + + diff --git a/doc/html/_encoder_motor_test_run_speed_and_time_8ino-example.html b/doc/html/_encoder_motor_test_run_speed_and_time_8ino-example.html new file mode 100644 index 00000000..94ae9fe8 --- /dev/null +++ b/doc/html/_encoder_motor_test_run_speed_and_time_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: EncoderMotorTestRunSpeedAndTime.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
EncoderMotorTestRunSpeedAndTime.ino
+
+
+
+
+ + + + diff --git a/doc/html/_encoder_motor_test_run_turns_8ino-example.html b/doc/html/_encoder_motor_test_run_turns_8ino-example.html new file mode 100644 index 00000000..7a6fe947 --- /dev/null +++ b/doc/html/_encoder_motor_test_run_turns_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: EncoderMotorTestRunTurns.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
EncoderMotorTestRunTurns.ino
+
+
+
+
+ + + + diff --git a/doc/html/_indicators_test_8ino-example.html b/doc/html/_indicators_test_8ino-example.html new file mode 100644 index 00000000..d73747d8 --- /dev/null +++ b/doc/html/_indicators_test_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: IndicatorsTest.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
IndicatorsTest.ino
+
+
+
+
+ + + + diff --git a/doc/html/_infrared_receiver_test_8ino-example.html b/doc/html/_infrared_receiver_test_8ino-example.html new file mode 100644 index 00000000..54e85c9d --- /dev/null +++ b/doc/html/_infrared_receiver_test_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: InfraredReceiverTest.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
InfraredReceiverTest.ino
+
+
+
+
+ + + + diff --git a/doc/html/_limit_switch_test_8ino-example.html b/doc/html/_limit_switch_test_8ino-example.html new file mode 100644 index 00000000..fffbf1ca --- /dev/null +++ b/doc/html/_limit_switch_test_8ino-example.html @@ -0,0 +1,107 @@ + + + + + + + +MakeBlock Drive Updated: LimitSwitchTest.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
LimitSwitchTest.ino
+
+
+


+ MicroSwitchTest.ino
+

+
+ + + + diff --git a/doc/html/_line_follower_test_8ino-example.html b/doc/html/_line_follower_test_8ino-example.html new file mode 100644 index 00000000..ac7c224b --- /dev/null +++ b/doc/html/_line_follower_test_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: LineFollowerTest.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
LineFollowerTest.ino
+
+
+
+
+ + + + diff --git a/doc/html/_mbot_buzzer_test2_8ino-example.html b/doc/html/_mbot_buzzer_test2_8ino-example.html new file mode 100644 index 00000000..6eb22911 --- /dev/null +++ b/doc/html/_mbot_buzzer_test2_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: MbotBuzzerTest2.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MbotBuzzerTest2.ino
+
+
+
+
+ + + + diff --git a/doc/html/_mbot_buzzer_test_8ino-example.html b/doc/html/_mbot_buzzer_test_8ino-example.html new file mode 100644 index 00000000..32735dd2 --- /dev/null +++ b/doc/html/_mbot_buzzer_test_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: MbotBuzzerTest.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MbotBuzzerTest.ino
+
+
+
+
+ + + + diff --git a/doc/html/_me4_button_8cpp.html b/doc/html/_me4_button_8cpp.html new file mode 100644 index 00000000..8df08ef5 --- /dev/null +++ b/doc/html/_me4_button_8cpp.html @@ -0,0 +1,188 @@ + + + + + + + +MakeBlock Drive Updated: src/Me4Button.cpp File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Me4Button.cpp File Reference
+
+
+ +

Driver for Me 4 Button module. +More...

+
#include "Me4Button.h"
+
+Include dependency graph for Me4Button.cpp:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+

Detailed Description

+

Driver for Me 4 Button module.

+
Author
MakeBlock
+
Version
V1.0.1
+
Date
2015/09/01
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for 4 Button module, It supports Me-4 Button V1.0 device provided by MakeBlock.
+
Method List:
+
    +
  1. void Me4Button::setpin(uint8_t port);
  2. +
  3. uint8_t Me4Button::pressed();
  4. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan         2015/07/24     1.0.0            Rebuild the old lib.
+Rafael Lee       2015/09/02     1.0.1            Added some comments and macros add setpin function.
+
+
+
+ + + + diff --git a/doc/html/_me4_button_8cpp__incl.map b/doc/html/_me4_button_8cpp__incl.map new file mode 100644 index 00000000..74af6252 --- /dev/null +++ b/doc/html/_me4_button_8cpp__incl.map @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me4_button_8cpp__incl.md5 b/doc/html/_me4_button_8cpp__incl.md5 new file mode 100644 index 00000000..0887ae63 --- /dev/null +++ b/doc/html/_me4_button_8cpp__incl.md5 @@ -0,0 +1 @@ +4ed68d08e53378fecdc39b44f53e1a23 \ No newline at end of file diff --git a/doc/html/_me4_button_8cpp__incl.png b/doc/html/_me4_button_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..e5c2673397fdf6158a9ac097f87a74ddc7d82ba9 GIT binary patch literal 47829 zcmd>lbySqm+bs+N($XL$NOwwy(o)h$NP~2D3y5_05CYO2L$?eKDj*Gmba&T%5r6A` zYkha!`1`*8;bP{kbIx=2v!A`634Nz1je+_c6%Gy#LsmvY1rF|s7aSaX`cov}6Ezm_ zAn+fOk({&y-2KD9?AC&KIJg&ZvJ$V=+`&8Z9^MJ7jrWJ6r}A%}(KN8Bz2kSGY#`7+ z9pCyY8CO|Yhf!Cj-4{gfSvsR#=jG`;U(2fQRZN@ef6bw#gBT~99Wt{#^VSOghqh$G z?=lD~D|5fl93KEI`^N}aWyajqVjhbt1 zBtr*1BCH9MnEm(U_&B$uUeK2>Ci)-75x)S3jM;aiDv~aCA-*jE6N9IpU~Cjmd>4%|iKGB6Hy?4HWwpmba?aUq1P&UD$E zL^&t4rNCv7y0`QsUuEppH+IjpBqZ{hAIFStm{G4SiO>2mJq}oaHToTF;2{2UWo)IP zZ@Hl**ITjM{@aoe7{#t?pc(L8EM+Mhlcm6C4#AnQ@pKWPjA%7GKkLfv{@8u(Lux9j z)~|_w=UZG$3F2@%nN-mh(VUAkte5fh_vPuV_VoB{lR$K1u7iNcV*ENVOh``-tJuS$ zaW2m}jr#az`J55+dY)_)%Ej7l^)q}BK0F#^JD#zsC~MrzProZ;I}QEP2g|e3{ogGr zPAu7}3=TH-CdU8U;>WZUqCI;UpO$sba<3VNo2WbdvJ zS{Bws4m^Us(ER^47$1iE{}8+XKc8OpxPaK3k=35jk<58QmFKtef-@QWX@|nF)iY%A z-o*v6`L6d#1HRvYd7A$AxMPvZ!t(A}gJjKWL9moSV!qD^4e^8>%XKtoRWjlD*x3Cz zHp@UfVaL86T#ABI;k)F!6w7>#-e=`EG?UpbyrnHEAyF;)hz{u5MR;!4n7;WgFA1Ox zbUHktz#dlk&v$6~vn3sN0XC<9WK)mRn~KhkUS$H?tDhg$>tPp|*mK#=-i^)reE{%o z@^L%HzP3>f^YX78q>HSq^Vc`4rvhH&Bg5aV8vA-T$^rsUXOSrqyREP7@SIQ{QcuMo z4_r<4?~Xs5mR)&`_Px-J1cK!xBtBC;Mlt6`Fyb6m%Xu4eqyou;nFBZe!+T2qdrwa^ z+F4pIUzA!ngWB(4FM^Tk$e$XtR8(<3k9Vb}3$mwE^u1E_ed;Eq`+yzPkANbhNF*5X z?MW?<@vDXBsvXr|pi6wc6;IDIF%081mzDpdJ&`LQ(|3DNw z`5}1!9zJWfhk2s@&60Xyz}?kOqO%{sutmw#bd_gMgmz27lZpA}$4KYr_Er)XvQ|^G z?c$P>cASS~!0G-U>_lh2yu2*fYh2G<22w|Rq17(T!k)FF?H z^>>(*kCXIp{{QOqtD&K*6K}T<#%6j8NNE9D@n626v;3Ramk@kM6RHi1^}YX^Sn~ec zb7CVlEE6MBmw?k;y=E&Rr)hgrzqc~TeCCz)$SU^x-%^#40~vvSBt# z#JGQpC}3mvfUTnc-gp~Q_oiTZ@=V_>yvgRn~rwdD)cl|R0xrePuQ#(F_c!?KQ|lNYb&Q)K3%Izb*}(| zA{9^KF(p1kf=SeWU59`90O8BNgZ*pCc)wSPMlN>?H{U$t>Lm0Y=9l%~k|4$W{wck` zGcx~LEXFf1=_pUsu5t#J`a_GXgDZV0bvA5wzR(IEJ2pV}aVPY_#odn!-|O<8<@uar zUD$8nrE*}Vz}}H|^z7|$qko~h#Sc{fS_6%kz%1#)V80n=k2XH%u7M2?hV+^Qe zbXD=5YKwnr6cR2rG3XyfL4VOXTT$EKR7M;hVApiK?2cOzbF#{2v&M@wh)V-O*ZO_v zvN|l17L(IKMED#RRM5AC2lgq$|D#Y!w>fH9T2;w{jv6sxX9G(Ou3^R>ZU%;WXP`{@ z;$hDr47PY2XDWPCK|bH6zI=IblTmqoSG8;9I)neJZKA>yU7|{Bhm9B5IFxXvr{p9& zVY&0Ef9yYXhKf-hFhcL&>%eMiAyXfwe!CwNT-&l-MxbS&AW3544l#7`eSwT3==iU* zYb=#IXps?>{H`!R?RpR4AlZKp#Gc&aY`2WgH9Ca{DBp5GkS{r+GQ2pi$q(QA?NgKl z=G*CwO}H#A6;KR!()rPx%~hA&7U|yWd3P!qR|s8duQ84mpYrhV zDCh|*YwUMRMXeZ{dE;DQ!Q2h_4q7^Y{jeArT=pwbf}9GbtqdWt%`reb$ssl<$Np4c zl#Z`r=pTDL`XhKYp+8ExVkWvnj=zu6%?hS^H3I->@h|L|2I56%*vlQ(*?Db;&@L1; zze=?9D|KH|LFIl{Q8HN$} zbij8AVz#41NS09!qrJ7Uv4if-kta{tBlq#UtaK4EILHPxvwL^xyE;(!V*#gZML4}}Q+W*Th9 zn`XqqT#;$9f9jIy5$;nz%t8AEUXoHLU0ez7OisT#6VfL3FsL}hf0LP8oaD8jU;l1z zCrp}1Ujc8nt~Eo)a1`?GzL`|APoCEdt`|-Ro!nV#ZKPuB z?e1tQ*hw*PAD@dh2x>^QJWPxgfqaI{Zk#LV2lar0G;oe;gG;@)^)fY|Qd9l%`u9*{ zUa2Lh9$R;9T95G95hm23~*pn5e`IL7X$4j6Mn_*xka0h?I1ma>Fl+&49XwJGl6i+|UC=xIgg-Z!S?& zajN}WJP{_l6Y=4O=P7%YDMGBJ=|)zN^R#MD3JtBkvJQ(i@2`;Yynh(gov} z(vB^4Wf!R^c<}e%FX}oujpj53d#-MsYk*52R+Pvgo4#Ut;Ag)-)r>?=AeGEShb}Vo z43Okcuicd^Ntjf=dn^Z936!q(Y`rJJ$LN{z!QQ5K++GIK6(zbWFI6t*5WpXy1yc?E8iw z$|oYk%hOUjpZ*CB_Ga2Y(2sT2&&&cLH#>~2;Vrfqr`c?bSdH2owd#PWEA1F14?k_5 zsnJ@gPK~wy5>ATZS>}d0!@A9GSe$)LN7#DN*8>86s7h1Dd_i~l7ri=+={J>lx{+MN zh7JbajQ}uhoNXsxO{s-_6Z2(WS=q8U^Uk+Yn~K-l+&@PLrxM*`wjkPIWY$07p3|`2 zm(nwqMh%cKDf~B!vlCTpSO;{0;Z|}x_nw?mrtuU>j%fiH}KFF)z1zs#OdPelO0_xMCUg9YLG&PCpfXXxsQ3gNe!65f(4jRHmdt*#J)>Co07Cs z++8eO9Hy1dF@38`*ln&ps+8fVnDW9-E=!LEQ2_!SJc9u-w3V;@ZNil3OV%nKJWyz# z!9V^g@?t)DU4RSIaouxq2y08RuHH*P5rCubjf)xh)=RYu5kGNJy^tO^qsI`pF_I!f zWqjw+Guv6xqmsQdujeukw-b9Tv?UkP)r({X+XgU%4=(Xgc!rz|BNFbp;=D)7#LGS1myhV<6 zZ?LFNj=eAoge(6b;ggpO7nw{`iBS!#0hXZ>`8F-Hd;z!Kysk@ zgTo~SEU8KQ-xvXEPjUUs{nSIu1O02!H#X{t!L4L9LYwQ)Z|X@zOVS4bsu9| z0B?Fb@I!H$g>YTYg1Rz0D;$fW6~0|KU#V3@rytfo^L^dd)r3PnVCGJgXd5hcKp3G; zP(5R)ZcuvnBUflXIa@=*G34LN(k{SywIZzM`LUNX)%w0YU~U$YOMRGGx&1m$NX2;K zloFS!4ZxTBS)87?^npg$`4ISsF3?8G3_Dnk!)^4&PfZ^txmJ#H*;p}_Bm^M@0oNa4 zEV%`t^wly$h&mDzg1Mvv>NvEG6e! zhLpS@Cw4}h9#=V}fnEGy;l`4dX}Tq_=?J0!JjNa2dQx_xSBd$Im+~axx1(!s6Lzrp z8}m=EW4oU?g|S1wv3a1mlWSp=+H2vj9IEZ&d9gGVOXi6_LR-Is>8VI*WsFCMU+SUj zhIejx$}DFUS$^q42!7NbSFkGkhz#Cr1?M}*3WlA2p9lKzzR!e<(LoX673iFQPFr)R zBBbk8#a>$dl-n$+@tbGw@VbIJ7*LmF0$YJ0ht|v>XgsN8M1L>r&8KwZUEPXnu|)OD z{Bf^4YPIy6;~c3*_ymxkqF(ssi}b0p9$^=G`@)0$owReteKSHGuHP7r{@}E$+W#G= zL_ETeNdf->w09&_yq!OlR=7=4I3xaoi`KJ=?HTlE$H=DK2M#U#=OqprPoTx8+wWWL zlWZcYZLv3j=z8Ev{2vv6iQ;tBbF@+!&cx z20M8DF)$a0)bul>{>a_H88P>SdWg_r)s}IhdgbMw*?ibj1K|d=!-Z<0g>I#uNqt|% zuuKg1mau}CeBFn=0KwUiiJ&sLKcU%n&`3MPgU0hQ>7cn=cA9uGbyZ7#Mt^)Hp-N%#(TZO%wYSMQvC`&XP)`%8%)8%)hvfdqEHYc*$DT`(TryC z<@|tZL=Mf`bA&FwIhf2$REQ{OipQs4AfmuN^9WMGw7AeQhGssUv{6jZFZ>u4NJU|^ zSsNpD9VkTS-$ATJBGVtXdK=?9#;S<89?0JEc-F}t!Xeu7)DzqXbj`*jdaXxTvyhWZ| z&_$~t;bh{>%UhmBFp?<4(*}y=&MAU{Vqja{@@PIhF0=6CQK+HJH)8!KDtmMI;SR>b zYF<=ZGoL^0o*)RIKlQHFZg_v-VhYUOJNDxH%_-Bci6JaYliLKPQTA3?0O5!5!6a;XfSMRsgREg7*s=*lo6 zB^AJBr$tg!ek%QZC!=je0X#uoN#(C@*tb=`XcipxnedYEakUUKntS5C36|d)usM}m zl8rVm>8zl}$Hmc@v7;P<;|$2)^5#jlmpSB$Nuhi_o$Fg>>|W9aGCEne%Hub7$q zxCT3*9R8&toc@Wt*VJ-{su9Zpf+`HGdhGKbcK1D);(Xh>Pdk)wdc1uqNxzm>N^_c? z;Vkm9MY~^7S8yP;yDqo)3U%G0Vj)G5+al@&SIrpRDC%@lPd)+rh zp>_-q>xc$LEWl9_e4prM(pNFnaG2Yvv7EOgzd9c5AZ|Q;Z5-4sjo}+z<8rO=u|*i- zucWB}`7INc___q3T+LBA+(90EG#$@jO`kvng z(m$&1Rt-4J6I9|CDpKvFPJS$UiNzQRFTbdX5W+2j?lup0n{b+WnBtptJa9!h8u|=B z=!H(0m@bF_RUSFa8FKGbW;~Zp4;eKpV(wQ?#JIC7<7l&1B$a8bdcg+Ux)VTD;@sbn zy!-k|2veyu)=Wn{8>NFi8`1swvMiQI9FZTYjyoqw34`Rn%DqqQprTDk6#i^TLqF3M zKv*W`yyq7=-S1s!G_oQ+u8UiKiYj!l4Y?7WfivkL`le;<{T7LGK5C3T)-W6ciU|Gp zVOEv})4ABmw5>lpn6y61a~C{aela7$RYF;dF7UXis9x3o6iwswwX`R-4_Q5|vp$Qb zFF7|14xU3v0AO5QF(3nuD;=xX4 z0X@!hsJvw0{yx0uleVWf(4{|3IM=GLtoTa$-N*?X*`U2oQ({vru}q!ri$vE~!f_~kXQaR%UX3bF#H4TdgGdvU#o@Uw-F2iC~Hp{58c93p%ri5)&y<=}p zw>ADa_kq4!Cv$p*?vsT7d=i1GB43tjJ8IVaS-zFu*xN|7j?ip89{(rpJNLEmc%7{4M_?F_DuxWfkj0TP!n!t0i)v$VOj$CXVnwm0 zzDyt`4UGwNApJ%F>?CNjIs=+Zp|1+hDVECv(sm^C3VL7#NcxYE1VD+5bnskka3VjH zfv)h_4Azt;j-sU3y&w%Sz}>?&Oq0U-Pme_E3xP58Jqf`@P1DuDGrge0I4aw z^dC}`ovgMM444w8(vuNf@`LXwhC-@5)7meYb&%K}LFyJ(O1s$jV#Uf<7pb)S(hSeX zLm+K-g90NGiA%#q-eG`j%vwC*)I_`G=cEzo58p*YJv|QOjlf!TZn8I7n`Wix86{8x z`vQ>$IrGE3{XP4HSj+&}M+1;e2@&s7>GzA5Be<_Sa4);vkJjUNGrkNa!T(z~Bz1L< zgI^BbKVhiZa1BNheM-3xv+MDTj%05ApktOKB{5u>5(onkdxjV+>&^yFW$VSL2Ig3s zFy0Fe0{g~p^MLjFMk+ft+cKb>RGy?o(424_y`DA0ROpllqzXa#4Uu%OIH9TFD}Bec z@%2%llliRnFq6yLVA;KK477{0hom{~lE{0-U^a&_M=~2f-FWr7+Ndb{9Is?{ANkR9 zsHTnGOKJX&g<`CW1V+3WUJCK>s(zt)U;6f*-tO$@ntW|cDEYe}E_foP+4VbK2MwJ%a&rDo>Q)XR50*Oq_{5e z2Q!o-o)>TG0C$? zRX;P?z75~yfxXDyE5QU{bPp_k%d`4xPCuL5x^%}X@Hf?#r-Y~Y*XWaifnMRoMOX}; z{Pz?hK1s}8I4?K`Fri>3Qj+EB`GZE^n#z=Ug6yx966?6W^$FBgk@;pC$a8?An-|iw zHCSVaFv$uw)yXL@(-YcEh8OK>;8wQQl+;s#d{4fB|E?t-<`BAhW;A~Kn>I2$Wd^;fjpKtnf zY;{#Mhioh}7uz3s#)(+d&qJP$rM>aS<1%;`Z;x55$w@w4*a*MNx1=vkdDeiuKrxXx zGnrd1POZAeeVGEs+8erjgOO`Flsgx@J9ue6@v-**g>jhYN36kU zU)A--GJq|`!OW&=ek|*FI784aDRq86%jx884DwQkVCT%dsHUo_DuoLfr~9zQ5eLB$ z3)etEJItF`xl34^l5$$Du}``defi6am5-pPPX6b7AR_qM9|U(dKOZ+=^E+}ybYlO1`FmM>{ zy#tYBBe9!0_py!L$vtn(Rj{nBT*aIRvk$_|oq2cRJYUf7GWZ`Hd~|%)Okak&I}8@= zmycIv?=3ZTnxh1^3Vprl8kdy(u2hqwng04Tn{T}IGl$a~ab8k1Sj)rT>+wt@&BetY zCtb6W@E*$<7#RR4Z;55@bSE26YwFbW8USt+6`QJ7I51cJv>m#5TeLET(v=;`g_KdT zFrJGK=Sg0)y`O+jGun%Vjc5bX`oQ8$rsn_j0wk|BR)z4R{gGXJpPQwsW2poYZQO6W zKGXlnZ=_?Wq&Zmh;7xq41%|rPw0sfxx=irAN1KmZ*=Q2udp2F>$vm%}VNv%IX1rBc z4avzD8E4D<8Qf5ubVJJC=CQYZf%vle0$!mM*e*7lwTTm6Ltk|U9fvqN*rS{-j6LG@ z+Zp^Ov2S&aM#csnjGx%r>0w{{q04}R>mwpkRaMK9oN_B2#`red}jyKaFWOx8ZeEe00FY7j{+@1M|v@)-DD@!;F-(G zq0!9=jNK6c55*~y2&E}0Zt<9}@`ld7$*KVWWI8{F!qwKF=~tEtJBQD6HME%aQ(ypZaK3aJiU)YRjWR(54d*3m~ z@@4(2O0y;ASt1u3@!-D&0CC)($h#sJC=b%|d;VJ?W6(A16^nnYeI9#;-D$z(1zEy+Lmh_I4cntYi_xcqfXA0Exc`LQ`A@azt)zC zOe&BZLU}!ep`3w}-7&e_VY^+O&ra01FX;mGmxaKL*|mzVqrdEQ+*q8Q&!}8;zB7Sx zi5a)_CnxY;eFah%)$OBqh>r50{U7Gt^FjmSw%2TV6uxF$nX**L$F@@Ypg@khoT@!$ zkPFM4sq)CCOnD3afaN_M3aj=-k6?w~YrxJcw`pxFxfGbJZ9Vi<4et|+-%~$J1oo6M zu&4O%buv$SY{9(kQ@QDwolhV>VHB#{I(yl#O^tx4;t;z97Anr@wv z?Yr@AZ1$g01@?R@IwLgrJx7~`EijpW>@1n9Uw3EY+W=@Jp-m#OdmD^H@0(p&tR~Cn z*PM3S7Z$W;uUwQew`F&QJ?76I8z0a;6QjL+CF38;RMPJrdKV)m9x}!WL+15^_fWY|%3#TxgRtNoE(Y;EbUkmFY(-U)F~ z(F+|W9eO?5sLX{oB{g@HKu%+ve)t`B(IAA2_wlq2WctEoyGXtr4m z3xG^A^;egMMR>yuW}==*aX-0SWWT<34$4pF^)%Hh z62@_{p{m^V|3;^f;)eI#djE1SV)`1sDKS}>FFfhm2sbYj zCoVY)>+(_u;VTc3mHltH3RsIZyp?vy;mxQ1GmYAP#m`~R?U`F)wEA0=ys3xpJaQ*1 zgXL=9Dwx0?JqLu5f9m-m-a3L35g4e>?!%kP&wOvVG@ zqh0rBhw^b@f-pf)VtIH>)X4cSuMH^;g*N>VKEVA>IV7!}|Kz`34CsOHJ>@uM=GCk# z5V8R4(bdiJGcs5=^Tb^*lqJ0BRqWTdf6H|VOT|D!M0m|*Jma~s=bWami^?K_HDOY^ zYQ((Xg^uE=Ha@KxB0r`6C3}^SXFgVsmGU5IC-lBXLSC{7i0S47E5RYdc@*IR5sUg-z%xXg=3N|@+iEb-Z4m;sCrCia2?Vv9BV{I229nt5gV94u-@GWvttFYT6$KAhJx zl~{DKCADZ(maT%RY8A-!oC$w*nAlRrzsk=L5FLOi1NFETP1Eu5fH?m1IAA#vp?ZWa zvaLYbCta7HV)Raa)`odR6ohqe-7R%+u^cU}mt&%JN^J#y7uVLR1k}D>9xss_4h`!e zFX*k&0!7S6UVr7VZg?%USphd{Ahb<6igV!nA$LN|#)iO_N zFv^jCe^c=`>~!{G+)6VsC@C+`T;1cpKR3-!nOxuobi{N}8X-fk3o-&_s;YP%~xV zpmbFO1SN-Cn;Epg;X?$Xd<83noQA$8`2xF&Xb>Z5JZUPq={W5uuifn69*5?vCUa<_ zJg2|Hd7UbRZ8C96p_Mpy%pG^W5ivzf2Vq69J4Wz<`uUJ~Ri?JixkcKnJqzgu@r^IN zo3TYkKm-~iNJK~L*1+ts4-rIs9Qc0ZctPAsNCaYh4VE! z5FwCz100yO%9CjQnmxZxbo5NPd#f(8sy?dJ+I zJe{C?CqMBNzIkLfXP{|1IDdhA0x`5AS?=SvK^Rmus))kqr9LWe*?joDu+KrSSie~~O1|lwK{GWpt*?qIVe)#agfNzGV(OAX!*G{nK0~(@$ene&+ zR|DHzKW^?lI9Hc~obvI#=qB3#xZ#|P3oBd>!m+4a^C1 zelcpuP|02q?Db&Qq=MO!|8~DbaZo;`pP3c@BLN@$a;8=X%>>=79KatY z`(0G671Zhy*p3}uhcSHR;vzdj?|r`vAMQY~OM2wTD_=A0lWP3e3W4eJvOY1g9dc{1 z^sOq}9&ErL^v)eD!NVQ3?4j%@?t~2##!D%N+-J@tbMF%O(43x(#F~+kb;WMJTsH0yBw`8>Z9JA3 za_6iIEof?Xl)sYp#Mk3F(1tVRp@9GhB;ojIMs3C)nNcW&?WbWQYcx11|D{%X(<+Z< zUf|?$#IN+QGOu1K(>{+upX6bklpRX0A$oWy=)U7ZKhQMqV_}Aw-|%-`fH;~wT~9xx zfhjoIjwm_k(L(ru{MGu&e^tzvu}8L*KheTAmoP-iQMIpd!CHDY3GI1{fw5R!cWMVO zE{&^XK6LM`M@=*&h7-&g@jp#^6|YLs^$|&6GJ@7QC{0N*NKNgjZR(Z%5v)E6TI|V2 z&|%zhk6+W9&OY>Puy0{ta;<|uoX_FJmOa*L6$wD(1qXW*U(i=H+&GL6h?R2)%AwI16Z8+Ct zP;E2t{bEx!EeXEavm>y zfNYr5GG7%eM9$*Uoay?FW(@+_qn00cOxU0H2W0q=edbQ6toQvUJkv~lzyw~6C;jbh zk_}K2+s&J`De3H2%o?+ROUfdsS|2+*JRce;T8A5pUHC*t#*yzkjT8g3@Se;?9~xMr znciN0%^R!Q-~t*VCfR+rNB(@$ATTWsux|!H;5XT*GuRH)YirXal-QGc)8ST-A{;?A!_sZtaM=si~-#XW**_xypPexF&v8*1i>o#lJAx`rRB6e7;KhKr(t{;oy zSC7pXtl4F3qdJ(2&n*EdyNz9%wQ` z%Jzuh+KsoI2=B=Wb!p~0-x213BEhX-<2KUvj?M@th)fgwoLX_?g7~($S z+!L@Q!E@ey8KKSQ^uza9{3OeZ0lf2#$PH!XK_Q>FvSzLMy;Ap;e{@k}rQiwl5|d)> zz*~dJk;z}V^NqSo%1avmUqm5-0zC74?5m|F_pczq+Ufy z?w30|ZK4IR!CJmJ_>=~x-PwM5P{Wmj=QiKr@Tpq9-91lzE|__O1gnz>9qu1bnFpW0 zfmw19lrpTmG%9&tU+%+AxUh!PBK2JHUv3 z&9<|XfA{Fi!1wSvOwlN_){)Gm*gTL!qqko_kqEtIeTXH2zp->A;zV+rOQ{>~AY?Di z*z>KGA4$->L8m3O#2<}pZ6Z-i!A(DH*!X9&vDMgW%pki6W~qI{-7dyl6=20ybKL7k zuWIm$L@EP4C5vW`H(_}d_F8H5RfAmowr=0!KY(tqMh0&D$B=(*1p>+@Ofi*2KgXuz zrzPw+(VPIDm#t*cU-5&FoNocPNEU@C1+pU%T03Ar=*y1@xptaeGXNUO_W0Zk!6xh# zkne!N6yGQISm60X+Jr7IZ=POI9i+d2G4ZJGh8Avzsl0FPMMWz@YTK~a0339?{VRH4 z?xRj1MO^5t$e2!AAYDyOqrqy8pyoun#{L;l$QTYy($EPWU_Lpm&orqt(~cRtS>4f! zlCJxb(!s_hs>&jAqHF*=752^e(hW2)#E(0Lv5t+_;9?whuiOyx(4I6~7t^i6j=jEY z28N43egi|{C9jS_Hum7w1oXd`th|n!?eTtax?740039sQkO+1DYtQvPoBYZ)TJNvv z&=yNy7py#qU+0XlBp9FqP;KvShm{R zL7XG|e8V?eAiZRJXy*G_6`Lrlhyl`b%PEaZGF(*1Qa8&b;>(-SI&|J=w@Pjh*GUL8 zBeoSM-Cx3K!7L>0~>9@ah~RsO+P-I?yIWXT3@tcyFHqUiduu=~xhy zM8d4!o+Yc{4_E)jj z1lUChBh)spf8d!gYz}ezSBIk7ibfXFf1&@vY+@EL+Lh#s?4jGTyI_oc+nYZpbLH&`h-)~7q1Qgr-jH|QJ4RkE0 zPv+5(ZOytoDS$}UyK3{p7skpvIN?^lGh8T-cD%P&0CS1s>g8wsaESfx!C&G`F#S7A^DEFXD*I zK#G~V-V?uo_1pEgL~{w^MJ*a74}5d>9ELL0)p}I4S2oltPnkHXXZhPBRN{BHPts7` z_}MEs=$URtMorS~n&t6U(NKHiHWAOr4=TG580YF|U*4Ef<85vcY@KbY?13=xzC!ok zRB&8=4-*Dnd*~^S&2PQ&B}W*#y7n{Hs1TEHiyo`tGd)elFT~ykmFXo@gjG^dL`wQ; z!mxuSEmkud)sMp3r+ulxKXS2I@l!xT-|Sub&*s+L*uw4Kun{aV2G<~uO?lE&F$g2A zMsIRw4HbO;Q-kx|Id~CaR0f3(Uq#u)tR@QM>6khn!W5bo%K)f8!Q)W&C~omGH3Eyy z*Hq)~M(O266z1M=L00He(!AsBQ!uT)p|Onbwwoe!1%c^|$T))IWk)K*tybe;y?uj3 z;^ezFb03ep*&&*%OaEVa14*c+AXAfk0v0tbh{a2+HC2lErd91U-*C3#1D1g9cjVBe zuqhLQ%f{eRRqn5Zg$Gs%$42Uot&@jTC}poNZc`iwoaW)0MeF38_x%Uoz>HbJe00=) zr-B8YVfoIV(74_y;!lyUVh16X50*Ih4g+~JiCWsyC;rwyBfnmW!Uzcr{jdOBE9hv8SNr`3-L+nu)YWG#rkVPCj1 zQ){kKo2iT<_&!7H?{&hqtE7^h*GNR9@fd@aaru^}z z>&A6ywXc%IsE5zF>^M@5N4n2Dc+I<=xaA`asvoecX5?kK(A%jQS z;Y)*B{Pd9r{SVdyI{dT@OoGu&s?lrkni(41i4680{0G8hi^z$iw1-h3{~Lvw+1p;e z0i^&g|7*!cKKUgQhu}-sR@V*J86EU z1cBhlD91q5N$8s+$YP@lq2gBZ6JIP{6109^M`FRaUnCQz`|gRP$%75zu{LwwWCIx_ zyx1eX*S3{r%wxL)zr1Dj%wCWpwv-KIblkXq2|;TtR4@IzQE_O^{6rNIA+J4T$q1IJ zvtzRAcYgOvils7sbx#ypf7k|Tk6}dhb2?c%ST2Bvev!h$$74&U)?^r&lrlATBi>(J z;sS1UY0vm)H;VAu zEbnKb%Jg&ybO^@pKH!81$~tKp<45CbFPTF*=gYZ=sS;YpzY2)FPrA;C=V&zPAqVzv ze#gXQNzK~Rk!KAcdgO8M#$YuF>B$x@l8r(31MaSYSS ztI|0_=(;ryxNa;dtQPIZ+X@hS2R3^vW|{G5!r<7vJ7RYsg1B%;GOt1)8zgkSktSM2 z)n|qh=GMdsj0AH9)cBM2a|>rBD>^xG;5UT5&7VFr>`1Pr@Pe;km@BupqU0f}&?(f( zAJpJQ0DcT{nO;z|MUX=|vmQ_C_>R3N}ZyMX-$w zUfK6upUkqZC{6e0dN&fL-oO8MY?Y5=^WRF^D&OQ5g&)Dw`W?IWr%`nUnBb$g?x}kW zWb(Kv#RvSHOesjh1j2FSasgSCx;SV9>L1qUvzmgNe3}xT+Eb?bzEOZ*I{KU~wC!Yx z0Hl?d+P7eS;0$X%0>wdle6c+hNQ&M>W85IVHU#UW}vHgubizHoQ_>iG=9EP^Iq=c#pJ3lth3{6 z{9^jJFkiO5uyjROIz^*T6e}Y#9dXZfCY2utDwWkNQ*Xgyn1*1^NQzvFOu#S{j@($0 z68<5$G+!1W7qZ4D>-4-U*qr&#Y7g0BrjY%-_Fzj(pgMNHt z8%-1=w(o&P-V|#sz*kuO>e%>6I&R8*Rb_Ig=z*h^KaitGu{u23sW#xc592F>aTDr%*AtkgWk1oO4ZY)gqE*s0A7^G;s-1ZtC^}YC z0ol;7DI5QoPkC-0Fp0fp>CgX|zyS>WC=rzIPh#|%wenLAgT~{E9O?2E;nEx{u4t*R z;mPS|0?8l<;v`>T{F6ybz%8eA5lpnsYjx>`Sr2;c!p9E)1-kfFU@qelUN1c1TeFr! zT-5f3I>*x;A+C+mk?ukh1Q*PK= zBuP2vB;lx zuMTAJpNaD77td1{&)HDsvf1hMJ+FgQwP^|{!%;n%uCB~+le#y zMYW|_R5mnkE`qoo-*p~50ASfFUO3!JT#nlJMpC=zWD`#*Bp4Vc3h~Twc;dE6OUv>b z!qPi>17@+ynOEMBiPgS$Qw~86z%V8AUiw^g6t&3jf=YLyLj@*8>$mk?=L9$L+L9mB zFOu~$J$nGUbCA4L5xgSOTf8I?+S{2%W9kz=Mv0}Mz3q-kH9ol@6?NbByhh72JdcI_ zIVxFpgfN5;?Fl_cC3R4IB;{wDk-^Ejr8 zPoyM;J$O}nMn@dhl;`^kU!^z#6g4{W5%$1cL%aDIb)P;_OUboY?>x~}PMk3lnIBWD ze+azUPK2l*3j_v#T4ayxL{)YasEgW>L~zmim3`O$1k0%8cG#&m*5?J*lorCf$hkO6 zr{M-X4|sOKYR}g7iNll{b@O~p=5T^wzPK!sOZ`%ylF*(vRjNPwI#tt^WP>V5!az{* zyk@$Eqr3lc9mv1rpP&`rpib#0^3#xcSG?{ zr?>IDq%{Fi(ct6_#Xl;6DuD;@u|K#iDe4k@FIk}k*zA27z^EppR!lS-C1C8?J<8=N zdNd5}jsvfx^h*zVqZ_?1A2_QfD-``79TX|n%ke@^$Z|bf#cufMDx-0kp{egl9DYa8 zg&_VsTtwz)(1+|Uo~QRQ+#$RggH|yX8(UpC34Tum3Xht!2oyJdK21iI$6m7Qa3M1t zI`-n6co(dC<=??UzZ>P)wZkYo0onK+ppgWxQ_{_GDezn*?w7QLM=b}n{<$C_n`wCJ zd7OpWUC$m9RgUa!S{Dy0?jOqcn@UM{VXPCkn=m|lMT9e?Ozdy6!HcVwiCM%A)sC z=*13|#puo_wmz)_R?#M?1LywTqSj49sgl7$ZM@*|!?^d6H2z^Ru3t40(EOFc4lcbj z{qbbCw1cdSUN;Wx>$W8AqMQo8csdjoY$77YR}}vw4mFD2FEp4hCuYBY>6yaj6GF2u zj;IGH28itKY7M*4?3PU@&;0QBD8kGvH(H$Mr#^p;&>>8DR!v_8emH3U@P z$#uJNalZcxcf?ZDDB6CnQJ&09*IaMK0p!l3EV8oXM(YLK4Ijn-;Oi};;%cI8Q6zY9 zcY?bIw;;jYT^bDm8h1;O;0f*?2yVeO5a{3pckkft{x*E)jCb#NW4!aQ#va?E!LlOoij~wbAN-o_jZv5*UwyIn` z$u_b~M*gzVpK8H=omaa9W&iuwe$zbw*l0|?(4TwYt5DY=U`oJB>sNK#oO;Vhzsydq zb|P_%woAs!&8Fm4->?KtH5n0tKu{D`ECSS;a$<<|tuhIbcE5BmahH4-0UR6qP!;1A zJ4gEOjJ$}#bE3o?IN1VLt!te&h3r8qj5-aU#4=XwCf5|%G{N|c{ETkv7Yu5hI>|P9 zFhO^ZU~cmY&l>Xiw0@*2JVB@*yHdwW9N&@A`8t>qAt4(8C!rGqf9LuJvg2eZEn*Fk z4D_Y`AvoyTtsY<+iMcD*eeF|b)+Qx(<7~{bT-u?;aPP2%@Cabf;1|A;DY-6#C7oQ>Y+TDW z@sGGE(rQ6}0}=P*Tq+uz=W=yEIu<=6d8;>)tkcjZNDLG0e|0(RokNt)D+6zd5GgHj zBl5MP2{J9z3P%+2cO~k2TI(+AQuS>DlX@3y2DJ?_1s3nT!LBZcd<3GeqHn>hEj{^e z#ENGnPfD~U;z%9uE`j-gBQL#o-k>kN+pAN1u2lt1`k|Wr<(1u`D6W#HGb5ngboZ)Q z7(xL~#iXY%F8+p0o&AkWT0L*l$LzHQ!sB!<+`hvw8xdg+IJsoZbqy(On^zt;C0FbE z#kXyGiZyEiFCF-MPn;s<%Q#)X;i6e?FmgrL42LDZ+d%E7{~w(y7$AS4Q+M--x~H^)h0;^8*l9TjsMX|rJy9~!je-@9-Sh`G#l9A%I^@W6CfMu?mu)XIoH0R;ksrm zy7*0<5RQp@tZ#D`=N#Pa)H*DF{;sB2Lk8t{wm}OpW!^wxYeO4#@*8}b5+F#=vs!UiICH_sc8C~p%pFGipC=q26L5^}{5v;P+* ze44a*oiOZ&cBHR^kUQt9gR7i$3S_lWiUkZ;buD$wUX5ei4P~)%oL^M$hm@88y9Dx; z>Ak-ILA#~zqd=+yT0jKtg-;0M{Kjs=Q~vRSm)ywS<4rm}TNzm|xh4G<_dw@zR8?d$ zI1%ar?N*UK%E)$IDcZah+3Po=<;lDG#-TXQ%>`|rz#SL-z?(!?!)w0ouX?gKKZ_qJ zL}N3i=j5d#*qF}Oa!%7CL;%%ONg}}?q1MDRMIS=zY76_?1`7m;BBQTc^JS!qZ|-Ng z8iMc#0=wzY&R^ht(TwJaHgAmdWoEk{S7kYA)dp;iok z&9X5=w0Pe09ULP*G;SR{wcpQrcuSq@nCF}@;S86l#z zkdGhCXCgIMSzHx0o+l~6gPYy4;+|nBhQe@eL#@>->GE}@c~b!Z)d5Er;nFhIP$11(u9TP=9JNvFwW$QywU+{ zgeZbBG}OzS^FQL%mJ3ZU=rYnxsdLfF^o2Qf4??- zKZ&}O_>Uu%{pjj)_62l;#j80U@O)algpEf=dY8BP z)5j8w!-b{4jqH_vbqhJ#x>LwLq?Y%`Xrd#CAG{ywRsG+}oz|7of4__^#*Ek6L`G7U z%;2Y3iyV@&ZRsqJzNv?=l{niM<5$ti6l}d+>)%>QVE*k6*2Y^fzumDpxoD<_h)6cQ z;A3lczYV-M!}zlztY6R8@)ko8t6_)r+_tFMi8Skof%%9@q=?gS&1m&lLb%|T-D6J9qE1OwkG;OTUW4tlwDBJGqWr|t+)`Sj6cFgmjT=af61K~X`)u)LaH9>3Sn=)Xb|ViD;!vs`_Ni{lQ1;cSlap z5>yz__c)|p>MPSj4_CNDVmC!xrk1EnsR82ka&Q^=nZ&t3<|H+iS6G|fFV+g3AxnWW zi$okJb`1b%Ph{3rHf8s*@TR?6;L%e9IN2Q)YT5a#kLA_3LU#CA7?S!B`;COn@4+IK zjwOe?Ma`z>Rfndy+u${a5dK#tgkDlSlukm&VSA^eu^1-V{K}CHUVuKhg-4;4az}n` z0;(6;1(f6@n`O!(>ZPLq@YDocRit)F`F@Svs$>cp)LD$j1Z8>$13`qKsv~Uj3)tvcq(!eb&{?MN5mN#FiVGvuel5 zM!pe>mR!+^ODha=>}6++;=%&)grW0#AE}ebxO3(w-@|E#<{1?yr;C!$khX{I2Sc}y zM8|JEzSABrLdsM;zSZJ1US#21eU8E3@m$fboBGvQJa|0=<~QxQoVRCTVP=->@m8r4 zZG1SHN;+_AzwSp@72{VbHqzGBZTyfr@|Lj<$0wCVgaUk{1)!&GSq%7Zm{;;75O4pC z9*jl3%l^+--u62cR)?)L54}6NM+@5;ODhMf`6Gc*oGrx`s&|VMuPyw5RmN3E#H#_h9&9*O z)9cmf1DE+9tGcI=lS)6*QC2*DtJR=~7wynI5*X<%H2{w;c^o}v9V|ZxcSZlYzhIpo z33zI|3KV-P*a^P}H@WPU=I2{Pmo6XnHn-P~8m7JB?zt}AlnvtO&Hh;(E^(XnR6QMc z4WER06(N<*qT#5(Us~5;59E z>bS-s+AF#2<#NcP1{-O+ob@4|w@~~T#~WH|rtB!IzF(vX{4eohErB7pi8UhTD~-{5 zGIR5=o)qihW1E?NZbh>KJ^>1!rTG(*Le&EU5_`TfweABh0zVa z%eow^vWkXN5tR<_<6lUID}jM^1dR>^!J2=HB)jey-LF)_yMS}12 zg*_uh93~`&zR>Nz>CW}FBnCwqg6i9nRW#AbPAhxJIDnr7kb^E|xSIK1AE37!P0adV z!=f*>d$TsY^jRf&vIi!@AhZg3Qd;9aC#5FypczJw0vUWXWWDrjP_OTG;)|9-1X41` zxrBLs+=l>D0S+p;8eXR%G*u=5&Eh{lc8gUO zzbBKr!QA*BNG~S6Y5ek!72W+^ZwlU@p;fID@u>Y*OryCFw(3W#an&3bnxeTLb{IEA zR*CtCjf?s1zw0^!e4I&AI`OPWK5I>z420PIqK^QrfMbDu*s;InK#fvb`KOYIX|y&7 zx8SgLOv(XziwN}yEkmfha-sXi_3)n%ulnU&^g6$@>dMV;3j&^BJj3u53w69&@;o{T z#GDb7ZCS27QmgWPV`|9H8$$nFQCdj_I)zWHlYZ8{=B~&ABAy_9nfMbWr_ir?cs^PeJ#lNy)o$Wd zJ1b_7W`WQo-LQwuUdJCZ7P&JmKP=OEIt@%YDpyMIK1tqs4~3JR%3tkqQ3o!E%d^tT zhwcUM+2gjf>N=BPBwb1bX$EJFTNxby({XF@Qlq^q>Zm5BzyyBLT%q!bOH=7QS9ZWp zYwYeq290_@@i}Z7cFhNIb^@BRNiRUYr>Q3MCqp%TT7VGQiFsLXucG37CDq=Hkx@)* zVeKo|^ULdzK+h+GnNiONr>nDz^ZIPBn%*JRR^WVKIHj@p%thx?+`$f+sHg|k);>$I z1t-}|;~iIfFOia1sC0;ECN;<9xqFV=lV_l~V#e9otR{tj@8O<^)Nmd{sMpG+HRtG_ zS;tmKrMlDToKUdafOUn@av*^jw(SQ*jqD+!@}V9Bcs?qsf||I~&f zKFLUlch<9-|#Ri#LC7!o9azdyQA#9{TJ{m~g({%!K#< zn0LB+dr1Id994XyW)){)GB>f{&;1qh`tlyW9m#i~z*mXGg=iZT^;e=wR`s^!J$!p- zm?-4e@{~z(YAWK>kBe(k?XWMU6%y#r9|`CEb@O-YBU=_`0lfu}O`@ zL20=E5P*0~UC_C~XJh}4%Sn-_axWtabS86&FfoF6GJCO{ol?n>*h;8_sOd&rxz&E> z?c#ofzwWZ_DN%M zT$2vO)@J*+j@cODqO@l#`D~ZxKSc*PJOT-dgGH)t+$ep_Rn#b=XfF^GSyY^+Tb)Xh zV@!JIFSr8QFOgNc-xvnfT5>Y(Hx;L+j`s)bauSXVG z+=0YaW-rJId|@*FDaQxiWy!I-b=nB&hF@G-EDge~gO@um>p1=Rt^_GOna%gi={$X8B*fH7lvZkulgA0lKuzOTT%+{;K%y>g8U!Iyb( z;Mu(me*nLo-}f1j3|t$_F)~_N9x>&e(V4?#TGkdlUK#bTB%Qx>$HZu0P&M`Te4_9j z%(FdQ5Igs*2y;Qd721->naNuY4?WLZ;?!P7VYqmDRf*2v<^jk@XUxwc63{;mr@j}6 zANK{lyUEb4iT{Y)0z~WX8xtZ#VJ|crrfwh(^O^7_~=C#uDUX zhfz=(_J8X5qoRLQvNTXs{w8MQ$nQYc3fbM_9>IwydJLU{r$qVHAWuTE%f$d-XC5 zx~w|t-q`uK``j7`62vzKQvy1yN5tWQ6)T`#ezpd{@vr~d=Y1RCTxKL>vZjV4X9V#W5+Tweyox`bc4D$PWo$T)a$@Y+tjtP9*R5(g-TX{*uRFapsi z0K>0;P|tevWvQcK02S=ihvlwiKrh(2lJi|+jh(qFOroc>egy`m@YrfgIs49P75c=c zXpnxLHJe#?$Y;L?`e-ghHFKxDYX)ax&^?zhZ5g$EyKd6ax^qo&K)#!F{4E<5HlTb1 z%>U1zm$l`~zrss^}2N)Xd4ypBK4-31*G11=rC! z34;@sD8mF&9PAS8v5F9k-&KXJqZkAsW$5qZ<97r^OMwcqioNWo-<>R;0Y?Wm89Dz# zzuWU)wY7hXcY%odP5&ytyA$$ezbR#S_x|XVYbkISNC+glA6h_OEV>H^`X#c)$AZgx z&F@X*+W&+Fw(*y5QNqo*Q`$K=Kuw?K_ZRZaBE0zD=}Pm#c(y%UE@byI!j!q-Z{J(9 z1**;}qX8kg#NgducQ+kygdxrm7W*~Xm4<2^}I z#v0;jVN6|Gz#XP&iTKE9!G-`ay#x2|0>&H27nkBLu~=~5elF`NwaNj`lJM$jV%HU^ z)al?_@4n&6|9SyLJiQ_gHyH^_xN(Wl7t6pPkw5-lX5$$_e3}OqqEuL`C2r~PTPoj* zA4VWVnv3~N{-|Dnl}Eh_6pHKf2{{l8nhWSQ1AAUY*Dod8562{5ID#A2ij}frb`BF9 z#J756sk2wEruUtlWlL+&&}5SvAcRJ#k=*EOa@Ypy6gqme?4Eo;$H(ON0p2s2Ob&U`WcBH*l}t{6zNqSOR~}y`;ZJqBfr$~xUA*!B*Ry;3)+2e zl(14zkdfdDYQx*|swK^mx_4p9XK&QAOR5NG$})u-ZQdy1LTSySyEEXJ5<{W*w3RuG zPbbU)x_=X=OI*kmxYfGT&>@3}RiJ5LkXCf6F!mO2PJR+w7%N;UveZkESJQR3m-7CW zsvR0^>ccCrmE6<5R$!&QyUmK?D!QIxn`E2#UXD;19lD8HwIPG!!`yvjWF9B@?&RY_ z8!_<FrVCv(}*9 zZxFoFC+U)wQloTI_biaV{FrO@SGLppKJJ)l004T`P0WyDiyPkZD8!Q z9i^JYC~!!ZER-k#&B$PNx$mpr=zqf!$h(U?j_%$xDj$fUJtssi{NfIE>-YN%{ zCv3WTJ-W^_VM@@@A8h&EoZu8-?w0oS>InA49D{7gzYkRL_b55P_-ZUK#tj*cboSg* zoEGYQzB7NrBZSe-Tm1VEYj}#Fp~LbDvQj$0^_=~yM7mK#4anFfZm5qdnE|g1PqBf{ zT~Y$q4ej0GZ5=h)JW(Qkz!p&A1iR(4=)ey8NWxGHIxuYsX6b2_SJI>x`5+$0Gf{b8 zI3lmN&i#(OFF$&tKwghj?Xjp@A!Mqw+}6{Jni3T^>(t#>$EjmJ->|*`o1t!g`>xs6 zMSuvXym+&|iYX@ns@EmP<-&+?nFyI^(b!FfE`T1?2Yg3Z z6BQPQ(TaH8`;ij!)-2cDNZLYXJ6{C-3|kYdLJ`c z^q|L_6fhpvKU-5mqB|hp=_lyMWx0vf?U_+NSg^Z-lwU372t6EmRtP()LEt)&uFX+&sPfOjs2p@;zFrzcneiFZJ7-YV!Vb zq2;0wl2ztWcxE*00DYjl5P<&389J;3M9Zl`XPNsd0(Y6Q&X3ys{7(#L?!ua?sNO(? z)b=)IXs5lWxZK)N^opQhW{)eyiP7yh>O9*~{J+!QrUh#`SF?2j!1-^e;wR_2e${*> z+jTEL##xd#GSM_w5Me~A+DKamJu`fhA9mxl6)bbY=(vye^%zg>2D1NmJ|1lg&nE&F zgkG3!%hAkNy@+3@A3k7Zxz41ZDzF3V5J zJg#=2|2r{P(S+11RXctJuxJ`huLu=_6fLSQ$L8%ELit^n)e}9rj$LDuM@%`5 z=kHbQT`fr!IS9;M0N=)K)~FfK;>+ z2$gu*5+4CqBy4Ylc0Y;<1eL)(zH1z2e-ev%i2rYN;B(a>CU}Ni>>y}Ck`Qi?e=tln zidXi?vQTwtK?uVOZA&>hX8HHBPu&ee4H04yMxsIs{~l$ADbkjB!iE1t$r;%yad-e) zQ?|}cFwm&3)>7UQm*LD0`UjqleXq4Vn1{oF9w%VZ0Ja8!vRxLlZt>vU@?Ky6v%5xU zcma-qKWvkN0|dm!vugBN0|-zR;T(dL&(eZwp(kBlM(^PxPiqCre_O#GCl-`{{IUMs zg2ly+1O>>cxGK9|iLGSer@Vdv0BJoFE?&b6IvcNUdEJ5JH*@3{#%w}|35z+!K1~h} zJA$)jgq{BvXtgNxq@o@IHJ&_R%T7rg18>czGl8>@NLP<`Am%&eu{RaesvI!ONYR#z zmVgBSaLU8jPzxcND0_AnmGpS&5>O8RP3&2#1q_^koIZmWa3Da&2OJC7@f7RHd$BGbBlJf*iT`hY zV^3Em;n4&78Sc4BjWTIK!5Mze{agT`Ea|4)c-PE{RP*mgt$mw9?3qw9(@UdPZ6%-1 zete(Vt}kNnm2N6knuA`>5XC9Rz%#tBrG{adcG{dnn4mkbS#IXWX?)&akJk)c-%EKD z_q)6SC9rkH+ndgi=q5p;KUG$+mgrXAU3;e7_dB^Ytht$CFadsLjI#A#x#nW!$Bh4c zcUUQ0y=?~LM4AHBOzmVTnikr%DKjg7 z|2#?hh$ieN=qXCdH&@ox(7g=yQGT9jwBT)>9s3#x#RS^xgbqm zFSgppKdvA?}vY8v?Z!P;-hu@J=>x|kP+n2S}MEv6NFpC?_Bd z6xpB;KWpF4ws08u=GK6GaV%Wyho!s?TwDI$keEngShw@g~O0hIG%z&tgCPl1Vi$Nvhd&jFH&_bHZ;1<9$LaK|#S zPuD?GMaDEIHfQDqq|MPnFhaNJCU~3Qk?Y9)M_2DhgiRl2F3YF)FIlbLg3ExUuu`5# z0cG}tIie<;Bf{HD`UZ6atG6UhsR*XP(l{#01KQHAfMC{NGg8$5 zKUfg{lHu&EiNZ>|!S0lK#;V@%*J(2@6h3ES#J54z-b-53pm@LuEBX7Nfd8Si{*kB3 z4So7#8fwh?=^Wq~n>_Nn*J;)BeEmuQO@NSy2HeSv4q|R<1yqddtQ@9~YlS8ZU^!M= z*&BfH^tll#@4$DhkbcIw;8qdHBaC{sNc4FTL+}WnOP(yScR%haTpmvI-k2FRz^kpH zYwHLMz}csZc<}*a$yzCg9tj#1E4*rQ0j~0D>@Wd9$AE0iyMOOBGAl9or`TqsNHLN; zI$cjE7MV^}S0itI9(vPhuHhuf!3*;`%h9y%CRAM)0AnKoCM;Bb6)Uv!HY=Q~?_AD% zHZ-9fg9c+yz2Q;_SV17Ir<#vRO>Clcbx6QmW2SwJF6-x0cJ%bJ2vA$T;MnN4oTzK# z0_7bV835-r^t4AJb^DiqJ$CdVWqTPmrTA6H3Q@f2ZI)_B$&3HEE{LG#?qff|X1lNrKBSLE&Q{r zhM1R9)E^EfY>j!7Q`9dkKETr;X|es$H@Ok;HfBoVR=K`p|b-yA1&x`ku~oITVCyzv?0 z$2PE%>r<*9p3SjU>#6G&KuO+_S<)b1`uhvEombgW*XtcO%}8KObqgLv>&uZJ&%C+= z{pN&&QP=-?^4z~x>mWYI&8?)QOltCbf*+?qllZ4u%TL(h9zY5@ z9Y@!MX31&fxUMmF0gMxImWn;G%l0`PN<4#>(n-46x}G&EY>aLzk?w1^bYmHbq((Bm zl4E3c{vu;uQy@)4IyvaepLWIp$LSok2$9O} zIlzsDI{BVgSZ8309GYo`KFw1Lvgz_?&1}fa z+n4HhK{SwOf{2xJ0W)vz?>p25u#9NNx5@?$+H^S{A)kLksqitVd#`^=eU~suB9zu+ z>PBZTm)0W&4j&u~A6ZO7F3X>Q>01UI2wWpb&oo&`3qn7L)9K1=3GhP3_{sOd_9MoH zisChy==O1|WnK8FhKTdc1YWa8B4_dq*KaXXfz9@kS_cgcZ=414{x`dx@jgxr1$}0? zAL#))c=-bp)FExr*vMnaDpFnFhXw_TngD}4Ud2R4eXWr|^&TH9H+mwA+Pt<`@DN|Q zaD`p%6%cS&&qtLMgar5~;)Q*0eR%UAEdvM0PPQoF`Z;N9*vQ8fZs|-FbVC6L$R4tS zL}0A>x5MgsHO0EXxl7ng<3=qGXJZvuc9>midE+;dJz?lW0H9sI5>(#!{Bmw+;7#e` zJ|H?1O%%ff_EIA@Tv>7;G?UE zc81|lAbVmH!olQ5B>)2liysRcu;v=+&9T5y3Tun}0%0YR_Ly0ksWZpuwJXy!*`^z< zUU}Ci!INL>Nq9{@YY{~pbnL3d!9koDUR_Z{JA5H90v`Z?2nJ*bgzp_PiqnO2+T&?S zLUVR{;cKT6fVjt44o*ZsEh96(*rzJ1$o(qZAUa41$Pi`SueG({Sj!E6AiY&ea5r`M zTVarbg`@)4L5SH8uzdri=MzWd>!s0ec-Crvp4p?uc5SKQ-;wizf!ILy`r%P?NQ4Yd zM&63VilM&<&?f2A0yoBFu?57syz1@)#C`f#Bml*el3V^l>z=g-hB3kSC8G_(_Z?aV z)_$|%y*7azn&d{(KeioY!59oLMsnpwM0*=?lR-=OM5=J|!vBA6oo40jWAHBpRo>^2jSJ{45{9uwwa1r5G$J^K+ap zfqnm-Wyy{bNiqwZ53J1JZB-eyX1GuB){<;dV^qj?3BdVb2|F}iBMH0aPpoWFtfiNkmW=Pmn#Bx*dED@^AL6^w)`ISB7^@l&_0ymrN^z`NU3dFc zwcLS}`2{bPHE;ab7Evlv5jJi}Q#DQZ-!YppcuCfOoCs*XVXV$Iop5^UbGdgAvVZWu z^rD|Czt|?A@`u_~7dE=89KT~j4A^$Pag_O-JUxWBN05ksM^7{9Z44B**U}bW|H+pa zbnZ!&E0+TwU3yC;Z$d85iO z%IqH7R;!PevL%I!_@G(C3}m?Z8VLRYu9B<&oNI zNTCvxgl+6fkdYuq$X&yNue`^Z82vY%3DR_=Mg_+3`bJ5*-D&KM`&Q`yw8c|4+7~Yt zK@Dnoi|kwOtMjj{RAUQ0Jk;N>K+RoWtwSrvP(bl9xntl|>VT;hWokl7y;5t<03xF; zhI@-g<<}c^>!NQF^dOX5$z6&BNpx8))q@qskhyrHU1|?s3n#H=p-l#>4wm+!n*5Ox zq6pRDSoyq@Rh6^>bMi~mWX1yM%HZUDD-)RPT3)+;tD+IXNzkRuNAJ5t?-?fr`S1ykpud!=1p3k{d@-U)jZ`NaC|8~5JO;Z14cPRuwm33jl4DXOK{vkMpGV}3#O>2WpFblKJv(1(9&|p2)VuJI z_2&2I_+hHwAsOnCKE5WoQuyNC^r60FDXkOwredf_o6x9?^VDfRg8WRC^{`0E40uf# zG~e;UBI)$4%CRyup;V+CJ3D+rafW~juh+iX>@x{v#Zhl#MqiamCW4H@DSeG2fh|66 zk9=2X(TfqSe*NbY1rHIyrDcs-K`dbtN-C_H)}L=(U%RtcKN~2$2^Yq|HA-bgde?a6#PNm5B1Sx{uuwqX$^}~OMA#u{h|IG4bhZF zB9D(3a~L%;If>KmU3fA9#ZMiy9oIdrx#$o2j025ojuH~NSRWU&-Od_urEeX7m9G-6 zUF#vK>hNy!+V^j_4_EYc$X3#WMN>km#lj2(Ox98v8ao%I=3HYq0m-k3ZcfuN+;Bk}ZnnCJUj?IQ@S zD%6FXGzvS+tL#(21gUxXD1?FF+%j&!hn!fmRDDr;Fl2;1zO!t9F{0)S-|&fuxY{cV9T|17j!q6fU)2{NUnllp;VTlJ1>fmnTR4>&9*{(>cY zr&du@x@|Ofa;(c53|zxETupvrHGdXRhaF7goKTFbukCH6xTduVzz1akUbqyG!s)0-7-rvRLG@cO^gF1B=&aiJlY6q{gewwwyoeaJ?8e1SW`zdpgg zWh7Gn@t6-s)~T8)*?D^(K$i1)SGjjKrrZ}db6Wyx zoGo9m3m&c;&onv5t3qiWc1hJ&7piX^4s7e^_7E9~b70T%TT%+jJ&ikD?v%V)iQS1o zN-bKvyM$U^Bf(OHuQo$1D}{;v7E61x8ZqnAy0+6d`qK-5jXgQA1hCS28w?t%o!?n`)K34e9>tB=eM!a#$iBXDk zGssUUQc>JOBS|)u^7?sPeTCl^`pPt3Ir@G5R~RN5TisgLmNn#_zBps=1^$IVSXhVAQ~b1r zuP%z4vck9z+tnpIW=EJp6GYKN5#+qlH`no2zTSE`JuzGqCV^hrVkA?LX(e{Y(BEJ5 zuPrZhq2^5MQ4Z44FxoLGe`?c}5>&i560aIxFA0j4Pnp-W)MU(mdY2&l;G>-+M4C7n z<-WoFd2+>zf_|wltEsU?NyiKEy7;#f7hLWb;>R7fd->>vgo4H%pwUm1Fo@R?V)hwC z3aXtGhRad>hiWPuHVPX6q`#rnS(xFpe^Zc|@G7w<-K{ zD)i*{oy!;0T}B7g&~F>A9hkK>~EjX17EZ3S?>ms^9;))JW%CZsCdpjxWG&FTbh? zH>#~lm{BuAlu-YB%{Vxs->8`R4xZF8o2laE5kBkZixYqzMhe-ELBNlB`6H!X)Q2|a@Y3q;7Zjowaz)i_9!Ik;>nDc^LZmwY?&3Ya zJIbqUY;-@rx&}8ct$3WuFkd;$0Om&G{T6O>ar7&HH`5t#%3#P7E{9c5O@`77w zmGAuM($y6>d8cDIm_qk~ZDQrF@l5uJd+nZUY{QCb;Z$09BKQ(Jluw|Ji@vqwl)YMW z&fI|tim3?CgCX%$EyQO==HvG<^Ivf*_pZAVi;S_JgG`D)vx3bE#_`2 zj!W}i7tvR<6YhH1)99oiCDbo*$}rcADt)(;kT*fMe)p!_(>AAy3a!o;Gycr_Rq_p$ z3zTxM*TEfpDPA>Bt)^dI7u`u-IbeQ|eT)qarr_`Krfh!@n}y!`272scJiQfd@7Oz9 zLU+r#ayPfzDs}L_Af8+h+wBOvHKfnj>^XUr=KCmzSaq4V$F02DGfb+Vkc>_OjKcvq zZUW=S$xOWGniSDRIyGShdKt+8WM4k466hJU=I%Jmbxi-AxD3-QBX0V&zc2!A6!tAPKZ2%fa4H=;V@1}+m;F|T4dt^R!@1}hL~YW;nkLCm2qYUI1XAnWBSp} z->IS{e6y9<^r9^dv+^mw$k5=88yc^;CO1Z6XNFSt{T*F2x17f>imR-I0{NRO8qXjS zu_;QLQ-uMmgS+#Idwr>k;4>vVgn5~G+)HF7Eg;=s>Cf`O%w0m6biMsy7wZ*gC5{%a ze%?#0K-6Mee@)wt(f%xb^3apmP*LkI zwe>PN=q`ce7%SuuPK#f%oDbcQJ#FPYT-|@ zt2X_?-pI_QB^BF!SZj_CDwfaQDUVijfXF**a!q)_z}Gr``%>l@-5OPcKqKB#!>W$+ zK3SB!TN-vsXPT}6IDHb&C*f-9iR^plPxVAGz=xzcD$yXCcr|V6KS!Hzc_7iMdU16v zad~DIoAir}|3P$Sh5NJMA)-MQdF!0(KE`EDHpOV~Ll)DWkHDRv{^0BHm3i5^h^M{{ z1BsvyR8^GwC-EqEoJ~rex+yfh(DX#7AtKPYy(_oDrJNu5-$i}#pCZ~x%Tu*!w+-%> zEZh7`-5NeefLvtvIYT5^Qrh7d0IMopj+R2)QjY8^WK-Oq)EfFvv%yKZp%%m+INQP3 zZw*tnJ;!HE%PR1%3+Vp2N*-%?>E=E1ek6oT%c=a z&f0>kFgzW=tZ5Rl!)bUKJ)ixcHK$TRnnD~_h(7l5`3cZzoMR`UhO{DMz7q?tutJ>> z@7=tfwy5m#(HdP{kPX4`H~tCZGN1~jOG3b{&Nqn>L9vXhy|hVIr(Z*#uPFn{#vjYG zR;tXR0d+Xp5-{vQWeprJ-rtm9n;;vtbTp921R{@&{>GPDR#Qcx>u`2Bq{m!%mO7hj!!>vzF zw1xrbnlK;3MSo-Qy3Q(&)M*Z6+%!~uPI3uAMueSm8Xi1+sXc3|h|l!5vbmruiN`Zk z%PzC%QIRvHfI~wV2Ir<$@_y6Cz*lY`1AmI)g z-HQ6|Ls}xBx|1qOH67_UsaX|&Um(06<#(JuV^t_)5_sud=n>Y2(1tMSDWpce3hT<(h9tOg_71W+}gOTs{0=V5Py-M!4?eoLLo#Vc@o@A3f4UHPix z-#fN!4G4CY$%X5DTcI(0EPs z(uUqe+^q8B!zhyXc}r_T&7)=H!DZ;^;9qFUPI_qPN&AD}uAxA*u(Q+EkFx;zy&~Ps z0~^YCnXhDsKadDA!A;gV{D}C+Fy~lkc+s00npvAlGynAeey*!2SFT|#Q zuV3%z{)>v%ccoC*Ao$>!AYcFP?p>Ukca7szL{pRzE-^HjExFS1^CGl(f60TjyNdYM z20au1$O2xO6BEY#6u3?TXm(6Ss;OtP-@3bUk&U+YZh6iS9=0{S4e(uns*+X4_ar~8j(R(28t?DdP9^by?qP@a{qj;^wxtpY8&HB2^fGn=uYgL27rATU{%u}^ ziFAB#gP%B%h~3;qI4*6iy1E$YnI}%OEyi$?BZtDrpVL2OdFD7XN(maSx=QeX!!ZdA zd7zuAD?cDj-347oJ+L<_%#GUEe>s>~b)kVD6rsK)i^=lstK3V*Miej@SZn*~IQoa~ z%KtQh^f7+?($%(@ss8 z8#49=NZn0ky);7JvXKflAF|5d2!OYGGZ4C_(abirz*F*Vd)!;Rx}PD_g0M9$ zuhvAi4^@x}`#2LdS|O8VFIe2lb?=W7P+N@0b7d$6{m`$oyWXLqi>=Lfv@8)#Ht@`F;v+X|Ru{!Takf{X-q9 zo)cH43(%5)L8-hihd($;8F5oFuGMvDCZQTEf0R&xCDJabTl2Ec^TQONu+?d@(?s+9 zP9wtK45+S#Y8^Nje}20;wYtO*Y~PXLeU?W~zyVIDNnk%4#L$AGx%zQFO#Tq~_=D+N z1*cYUxHYrzEX zJLfsiv!A{9IY%|J6`5H^%@R#(%WbP;SM3d9}AUYNK1N$x5E$LWUOcV?J-09LmkgHg|@j@wNxaQXZ#O5BW?_1F+4suTC=>7 zG)1F6M|Hm<16KT3bh()rmo{||{*VC+m4yUxy2YGiLdzg~-jZWZAi+lzNY09W)lQ%@ zOKcwFeg_~kSQJS8#(XG!)UOa8pP{GHfv7h)7+XbySF^XHu9tYT<+);27i-AK9-3H#v73%hzLU}&P8MQ+dpI?O~MR)ES>y`Zd|`9 zBYH{ZLXcTRdqfAadjfJdf9=tsp=Hf%2%vI66=`XRy}54>-f#?Wt=E5E~mxum+ZCTdQC4OnGej_jeE{|l zA~Hp0@I`eZ(@1`rP397N3}!2@fEtltH#K+YNgBP z(?|XZePlkm#lTG*$w&qIgIW3Rn@G?K*L5mfXajal_^DJSoik8a*{Ug0 z@)Nh~_|K}Uh)_3_01iRSJLwu@y^P_+mgD0$9OS=J24!pZl;4;k=Q4$A8-i@q7O@q) zaF3uO3JC4-!dSzukpgu+sZL?z(*^R?u8&|I~OzIS3T4M$)njl5$c9YMlF zHA6W#e}wHBB%J3*C^;C`r_f^07M@q615FHq^B>8GFf1Lz=y*{7ii5wTqe0uRELi<9L+@xM5{JUl_^ugAex4&g z`-Qp=5BD?W%|DMHGt*@(DJlOa%!)1K@ySauq};8Bjd)f6taz)NdN1nr<>72Nhm8_G zSh*{4tC?hN%N`lz^6K{{sbS5-u!VL32Mpj{$5yc^f}gJ!$n#!-prM%db4e)!x`f|V8>@G_LTq8DI zVE^_*DsbT}C|^K)%MZY~G>YFH(lVcXC_$qJI3tpu54nLn5RPWtGok1K(?3;EBOvb- z)=4EwbNyC+jVSI`5^s4&yhYc5`k4k7I=9(d@DVYOs1N(eRza`}?DSmkBDU5``xPUU zT`G00+ayXlYhX9oN{mRjyTVM?u3y=)r$FtJ#{yfS=8ciD}jd@wYme<{|sTs>Ovwiwm^W4iQr{_eC?sF}x@<_sN zsqBVEE;x^WqQv#Uhy0IMS50jeSH`9Y#T2zd8F-_jv8Zlv&mTP>DEB@jM{HV<$?l}3 zA1U~4)$H^UjQ;VMLgf;>r^n~JJ9R(zGV1i$^2IrZ(FakBQG%1EFuhyHjK?@zX)e6P znxFT@Lep4*%{PA|&+ozRRxi@)e(lYwodB9uyEUH~;YMYKPV3U1f1Nh|)6jTyA9aa# zb0|~um>Sd zo;XvyYCzzVyI~#6YMDm_x`s%T*K@5r#J33;Ok(EC!pm(?nS%>hcJ~V}X5*(loYc?w z3l6v(PGQ9my(YsT>+eSb%jM2DnZtsBf=BMo#!PqQEU6?S8^rY;W#$(LFY$)l^hBBS zXEL&c73Z)+WDHI&G}lVpek>p-4-m)fj%p7EiPtB@!ILB;QDqX}CcHymKxTOM-BDbc zI?-%H9oAlxj4z+Ym$rf|OBke_eESzTR*tTdV+ZKuGUlI>1mjQM&ZcKZTPnM88|RBR z+@#Ch<#U6a(RT$LjMuN@j90N#7=n7#bQ5mbzG^2 z)j!$v4zk-GBy(Cxgiw&n2dbN@j~&0d3iw#!8XKiRng0fv?S6%I?PZ{5_Pf z`6b8P{rU-GzHKz16`eG|g>1utod&6GHQ=3o5wH(@DKmn(Wr+#E(Y1i~TR2$MCCXOA zG{5d-|6F*1i!TSz&rZRmq^b9gc7xPr@Wcd!W^Iohr4o3TGm<0sHso@N1r+0bbk<{Z z!lQ{T%%X%!?cIjS6XWqpy-Y$n7cPJ17&dglVRfmNr8jNE0}NMb-Sf)?(Mc3*1(8-j zmTj+gD3$&HmC%fMs=?IVYAO1PuyZEU;;kOQo1xwLw1-Dew7v;UcLa>vdy3_Qgf5t2 z?8H8{^U|i0S3ZYr^^s6mc-Up=3zo*sA&hIf3$JqLv3v2rz@f0~a%ZxQUroraW`gQ} z_Pt%~mSqX=%_BOaRM!ImO*@B54YaQNYns9tPyp^qHQbX~du?mN-Yk%62bm>zzCrPD zFW(cm{??OC^5tdp!PsUAo`}Zsd`76mwzvA%DL?np9?`C_E~l<`DND<8I}r|qGC(=R z)Dk$N7e7=awVhYG$jHlst_ut(;KX3fjAZm@Kl)cGMW|$E@FWL>+9{pR&Nz%d0>T5C z>8?D6>|O+aOct)zzA>7vufi?>PQy!mr+3A|OJ(@G_o_^N>C^RV?Wd$gNT~%q0vjRi z)qQ7G9Y<(1N!qfB zU;3!f4orKL0&V@rldaso_?wa#)QymcIfa(oV)=4igT_mudipB#?3s$Ui7uf{fAkO> z3$S|>(1m_1ca4}q)TRHnp?CXJC?P7wPU4APKu-m!)z*}0QL!L9;)kkMzMVsWVKaEj zAqS&>P0tndkW6E*e*6fNN{}P&QQ0 zd2jLpVBBF1QFfjE$Sci$TZeO{C&D28!r+IQ$~`7zoY35mV%d3u%69W*O)*UizCR94r3I?u4F5z`~52TM))*K|FX$219st;3Cq=M|r4?CHZnQv-`Rb#J zIaQl*;GPn-z;4gk7b@O{SK5~El&6AT67eEW$DTmopzW_@W(}WJ)tUgC4!4Dk2tx_3 z#Y}4G?N_8$j`QU7KpV@1C~k+b{Dh#%+^jechZeBwIjq>L6_MC>?eUJ^O@V4DOO;CB zk)AZvB=>0x--unE$SBs03gs!@BgvBXIIIwrT>@t+yZ?{c*@$Gc?ybJ_aeLDjONFur z*h)N7i9&``H1Qg^i4MRp!=->4_JA&hKOYVaYLWkQ;O-#mW)^<1DgyKkzD}y^b~Sr^ z={4ob_ij!69ZsMpcuHk;v}1~G@9YG|DpgL|Hg+=YRVteGs3$rBG#6dlQ7q4KV_fYS zoAWsu@?Bb$kCaAP{24kstf-d~PRLf1a zb{1K`ZVtSj<%IdZb@zCc(grYiJ0!8Y3G%Jq2{lZ$7*)l1{PjdIL7&3)0#$^(zmlMLt}GGo594{ycE*z$wBV008Fn|ECxltUUjx7+(LH z<)H^YHsd^WNusEsuo@KVQ0lpej6jJJ7L!`-8qz#jlbKOiVulyn|JGT0RtNd=rk4TX zMs4h%ASw>w@NR!f9^*)`;oISJQJT$kSW>Tuz{>-?|K@FX*-F;s3`j%&P0(h4=T?DW ze)=D+=H5iij3*8VM5UoD{~WB0@h|T7xLw~t5q$!Yq`a)BN206ri@xh8 zf)juJw;mDHJ)R3~O*m`|Q7UFXPkUF{#l2zBkPiBy# z@0GdJzCHRsrW!8h^0wW}W8-tLnY5P*H?hRlcdw035_%biiLDgoXJ*==e{>}K&yVxP zP#x|2`D>P<23!D#MJe}$s`a0+Nm1s9Dy7)w@2avmG z#PKCkr3$|Msf1@v+(IRymDkM*`I0NI?{8|tQWm@0&1Xxi(tg!i4#1AR@$xPE*2$Cc z^^Sj9+0DoQZDpgOGJn==+gaqwR9;fj=f=i8jIcz6pxh#NlD^Vjv*rmVwq@#Zn_AI# zZzT~aDT)lj@LaGS)&dM;E3XMZ@j$VmA*$G?{(GK*mSAZFt@!N62JQ>S7UP#|GP;AyGEo`?7< znJFu6fSes*_48}Oh~@rO&f`ekM-Xa~*q-VeEqUL`D~noNBm<1CVG#I}SIujGf^^4XU7axT>!Q+U@we|U|X ztX``C&HKSK1Lu>tNJ*ny#_|b0Bb-WN>5?h6L|>Rx&P&EuoqHaJEKPQg6a+)Z*<_=z zc&=%Xe|OD&zBIz3*~R+XtPRYXA%_1ty{HEgM#NBDi(Goz>}jrl`7?gh(1(>k%XV;) z>1yjn-&L_ihD7g5&PC?6S?WyUyG$=H6KYQJ2m!K@_o*-`coFlQ9>;vcB?tFt@#pCO zK}-*e{%x((uY4Waru>e%X5FSe{egm-)zpL2ttg4K!Vx`+bFI1D{PZb!>l9Q&s(s(V z0S75WN6m&I6ViFoXq07hQ%iDxRVpqa#ZHsNXg z5P?S`eU#OMD=b&2%nUe6H~9wWq#MTQBB;(aF+D?( zBYcwLx~v(8!5f?_p%TgEF6IsLzAw)OqOKHPfu?aL?N0@N{S|lynb^KCwZ-z2LJ71s zh-a??Sr%<^70(QimypaBSNV6U)5npI$;=e+d>^Ulw&V&kyp!PemO-d5Ine)LjQ-ER zY*>U4a7L46(STy1&x*b;W_qBQ@IsL-AEOi+&6bSyH2y@K)OE0rn>G)`vS7p6VEFlQ5>Sp!WCoJnb<>UgIm8@wpI?tF_DwZL+!1m%B zE#Nn-;X=NV2VjCVm$M1G*j|ipr+IfA2wu4=#ebn7H&oyYBr62OrDq5>>G?V%$f9$t zBiXaH#@=N)$Fsy2F$j&G^amR!09~=ARFpj-&8lw%{i2gly;)|@pZFoUcr7mO65E^K zp3%>}>{Ba&n#>IXf=Jp!4K&5UVi}FOn3U~#hU5SS(Z=zjY7h6RJXZvvLteEsl zJ2~CsbyjC{@7)Ht*oGf0t?*V0GjNV;ISvAxK5~xP*hMdzFeb#9_&vr1IE9ZguT8nx zw+UL>|Le$}2#R^USLuSB3mB7mvX~!E8Y~h8$raB%_Xo#NB+=Y~eNWeCi5%3d9KM5q z-23T2>^aGw$52r8pIo9G? zD+hC}@$B+b&iK>x5*#R{<00sFNj>x6L9#ucuRFnf()q-C?7AyltLBS~D2y}nV#79X z03W_`p!4U^7^Tq(So{y$HgEUDcvlx@)IjQK-MsFSyTY3HVkAFJ!U&-LA`Ge%dQSX* zwJs5<;u=>h6`U0&J!F6fPQ%qs@5Ei(-z<=9W-930 znkM}pBt^5WrbQZO90e_1?iQSFc5Ond0A_uc^sfmSW!!lsqklO%8iF z`nsmsFDa64Qdo}H*zH!vSo}~F@`R(x#6d?hTuY1+tXjic<;)fYpLr#@XSiTp+>OQNkhqqXf$e9YFUy8w0 zA5Beo%eP`YFzz1~nhNIAMz}rN9|6!bES0pWWD7PIM*MN%oVNjdNl1UmYV6Y940rU| z=gegXkmagXd|#g0ssL>N%}I)eMxya?pCF9SDi&!C6eo)S3(NE3rZB$o3D3z=2EH>u0DJxyg zrfEpbr^`vaH|A8K{YTdSsGYzURQ7UgZE{6m!3?s}GN-z(%;U%(4lq0`(Ma2!cx};I zD1jKZw^i8RQ0UP*Nb&mJ+RMC-UIThzm*$7j*r!vEkFq8-x{C9JS^QrASNm_<=>JQ! zB#FvuOA>B;K1g^sq+IJbTVU4pB&yUMU$ z$FiP5_Gy7wxt1R}#ms$cugo~6#1;p+z5m0Xsw%1FK*AAp#ez!NQcu$Z9~v^GiS6+! zl`cI)GS1aK?2^H#fy%9ama@^mJ2Gc;<#`@c?xE;XCh>mQ1z%AioNnvJaAtIJ{J0Av zn|kNu+lto~0s>Q;T!rl&$!RBDnevg$%D1uu6$1Qguix-7D>HJoZkTp-kP-e}S@SQG z?}a+0+U9c8C8xfTxQ)!et<4wfHT?<>_Cz4u+~kZTW2g3w9D!ei89J4HgX9QfUsm;+ zeDS%jjLwq}qD|5p{gBXJ{sV|HAiFKrMKaMuJ>pg)Nma(|BXA>~eSOkgjWkAAVPtPQ zGEwlCHhQ@-;R>OZso&%8bAQ!5x5|fcV5Zgc?6<&TVK@+Qg^c;;IxAQZJI0pY&R6Fx z_zEvE^nWGw8;l!Smsk{}h|3yYt6>-7Ez1#hbZ&7t*6oLvBAoHXX*0cYIqAsx$N00O z2T@mor*4eHk5c=W5=~VBhie30aK+J7@A1*jLnD!{rGkqL^1$MOOwv>Rr8KK-ISNgB zYi#B}30R?U(#8K`E0VzPck;3?9LDW+Sv|WP7-ILGqBmftte?&fvY~%gNl0te+ zj<291JoA8-EiNE#`K-KbeC2ui-<}`HUJC$;q<2lmtDR@+zdK%#+mmjFgK0!KrB_a) zY7Zi$@A|17Wnyd%@r0{6DEq1p_yDkbW@OZDvM6iuAw>-A;7hX!e853vrAz=eLGIMG zHE6;WgBVQ1-?@_jE7yj@%r6Npp0_b4jD{tEuj{cwN}sN*rNF7-bl&PJ)M+FL+?s+Fn*mV@iXpC!8gOLHSf!u&v z`u2!?dNw9#qn|`w#Yzou1q^unU2+!q6*%7P&I-=#-c3L1|Efe?gn?G~wQoiz7~dnP z?Zw@dhc-E-Tpo*AAhyV9zvgny{c;ncgLJASwX z0H|I$AoHKvxYh7%sCpap^$q36?n-=RV~g1nDXrkbI5=+hT!Lmiqylj?ZB@Oq=u$!M zf(4&KUyqVo$mS~pm=5e-3=ar7UOy^8g2<7_>{2B$ZMP;{`c}j4G+o#YY^+}C{LBp~ z|N2J0zaW0dR;b7$5e_UAL9hOQ2(05rNMFXB_>3m+ ztv(wV`z@O;u(Iwa;Q8U|3GeND7SK`qmS+jDRR)+=Aly6aZvoe+>9L`PuSEwoYs~ma zN&T0*Cp7Qriz-sIxsNbkj83jwJyWyQH3Q3;G^o*a=3DhL&w1QIQ( zC<52SQ+h;m1c%CWpb`K?3^UFhJufrmQb-(Povnu!BDqC*&~SifM3n^h9{mjx_=9CwtYukqS<TmW zum^gVTCd>fBb-DjticPQc{m`|+g903dUUzw^+ zHunCnn*@jn;#fy^0%(${-VBPRfrWwCm*+v{v~Q8{R4i9@Z7fx>Nz*5b0F7T&;i{}6 zOP~5ZsTmxw34cOZHQwfQzM%yH3J}-P69QragR6En__{3SM~VuUf<68{KqjYf{xopZ zIoX#qOL>w47s|M^vDCx^mf6~WwJF9L_CzZYX4oq9&x~eyXaC&_(h8WwIH%@LbpYdv zRy_6UkTluGYd|0tC{ytMfVudZEou^V{RHe%GQo^%eD?XPHRdSeJYn|8pv_{D2F<7e z6PT~|fDrU{y!*lJFj#g?WK<;nA=_x+vvJ8HOVxTBDo+DJA{`DM>Z}QVUa2}mR7)R` zvn6x0mOuMr3;##$Z)AV20_q6)?0cd)m%OOrlJ`AkyKFv|&D;t^k^M0?kt!L@7!HX) z9PNC8@2#av6!gQ6f*GaTj?*@Qnnhp5j{@qVJB`XbPAK`XS6|ydOSnmois3yu?3r`j ztiX2~Nu)bftM52VQ}bl`F$iDN5OW!S_G2Q4Ub;B-)Z=vI-LnNAi3xFo5DR)cTI|q) zFGo!kQ=P^29TU1NL4D68UB)k;Nalyn%+XiagSIC$&sWar=QPGT$Xr_uvL-Uc0-;f~ z^RCMR$~A7Ty9Rz#+jQT0aD6v++e~*lI=qJNhp+v8{TB84aj;4IEHp>Bo<1$&j|>tVn0EwPGSZVR7j?GW4EwZMZ0+Gn{CQwM!@6176ay-!) z-Z8pd11WkQCmb}ihR;Yxp~x&HpOqq`hZbL)U2dLUSgfRc*)7bWk&0{_N?*_NniFkr zlW;r42r>f>);q`w;JaUP#@P(onO_{x={%sab9evXbRUBq@`Rt?b90z-YVW-AYk#B9 zm#QB>oawi{_ivjBFYPmaY&LmnY>j+UWh&HhYBbKcUSgf=3?7jh5F=Yp-13{KudmO@ z%p4L+8ZDkY8 zgF=i0u$$*yw$38rrG%!kY&^uAiaX6IlZ{}>&Bns@>5L& z$HlF}VIR^NuO}SuV8>HweCwG<=Uw*gua2EIPyg>~(zu_ttfGca)khBwoorX$+-}59 zP`7KMWu~W>L9%Hu!X@A5ODSN2fUnTE8PW|Q9YSt!Q}s^wpVi_e%(TA6aJpBV2eLx)JH>~go8AmHELqffj|{A#rK7CzeR3~+d=*HY+K*MM?w;>AS0O{nC&i-WG<~b zGkf!&l#~uwP5az$xPK&gzir8=IN*{a#g1nQyMI?K6_ zsY693oQ+G{~V)zjHz$K*&ivr&wR%~KSh}4*rIBM#{%4c2H}#ZkBi0!#x(ql z2U*lEb|3z^6g5}SZ`!lqEdE^@h4{;_m@1(k1 zL&fV@5fR0A>^s8LO@{}2+_TuBb<|0^6H-bHeT=v`7fD^Uy#!v*3GM0c$vL$z#dn*o z>PnZaiI#S9k-FVO-iRrgF(<>{v`bfVRZ9G4H2)Q2lN~-;PWiQ$NSg<7d{f=Hxl}ANg0LM`UX@Pm + + + + + + +MakeBlock Drive Updated: src/Me4Button.h File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
Me4Button.h File Reference
+
+
+ +

Header for Me4Button.cpp module. +More...

+
#include <stdint.h>
+#include <stdbool.h>
+#include <Arduino.h>
+#include "MeConfig.h"
+#include "MePort.h"
+
+Include dependency graph for Me4Button.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

class  Me4Button
 Driver for Me 4 Button module. More...
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Macros

+#define KEY_NULL   (0)
 
+#define KEY_1   (1)
 
+#define KEY_2   (2)
 
+#define KEY_3   (3)
 
+#define KEY_4   (4)
 
+#define KEY_NULL_VALUE   (962)
 
+#define KEY_1_VALUE   (0)
 
+#define KEY_2_VALUE   (481)
 
+#define KEY_3_VALUE   (641)
 
+#define KEY_4_VALUE   (721)
 
+#define DEBOUNCED_INTERVAL   (8)
 
+#define FALSE   (0)
 
+#define TRUE   (1)
 
+

Detailed Description

+

Header for Me4Button.cpp module.

+
Author
MakeBlock
+
Version
V1.0.1
+
Date
2015/08/31
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is the drive for 4 Button module, It supports Me-4 Button V1.0 module provided by MakeBlock.
+
Method List:
+
    +
  1. void Me4Button::setpin(uint8_t port);
  2. +
  3. uint8_t Me4Button::pressed();
  4. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan         2015/07/24     1.0.0            Rebuild the old lib.
+Rafael Lee       2015/08/31     1.0.1            Added some comments and macros.
+
+
+
+ + + + diff --git a/doc/html/_me4_button_8h.js b/doc/html/_me4_button_8h.js new file mode 100644 index 00000000..4fd61745 --- /dev/null +++ b/doc/html/_me4_button_8h.js @@ -0,0 +1,4 @@ +var _me4_button_8h = +[ + [ "Me4Button", "class_me4_button.html", "class_me4_button" ] +]; \ No newline at end of file diff --git a/doc/html/_me4_button_8h__dep__incl.map b/doc/html/_me4_button_8h__dep__incl.map new file mode 100644 index 00000000..bae00b42 --- /dev/null +++ b/doc/html/_me4_button_8h__dep__incl.map @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me4_button_8h__dep__incl.md5 b/doc/html/_me4_button_8h__dep__incl.md5 new file mode 100644 index 00000000..b5a9f3ab --- /dev/null +++ b/doc/html/_me4_button_8h__dep__incl.md5 @@ -0,0 +1 @@ +61b3715faa7ee6148ac39926933eb062 \ No newline at end of file diff --git a/doc/html/_me4_button_8h__dep__incl.png b/doc/html/_me4_button_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..3474d7f291411be1ab89aec42f76841bf7579aff GIT binary patch literal 12582 zcma)j2UJsCur5Wa6ctc9f)tS=MS4>}K&k@Ldyp!duPv?J$vSxZzhp%)fGvJX^FA0ut?u1$!lU^-LVJ$ zcP7LKUdz0$XMi_+3l&9qtXs@qerIVC7S>~|H}bEvy|ee0{k)A(0f?j1(`ZLC|0f}L zqKUdf)gF9;gndqq$4bPOlYNrOt76A$O3dSs88ER|@6a|>Zz}?68ue^f>uI|4VbQ2E zJb7;JLA>~>tc8Rw5j={7-RJ@DQP@3|OflFs$ZGe9uP`IQ%H2vKZ}x;5v^^pQ8$aJ3 z$r!uhea!Ozyfo>f+OY25zhB0bQbxz$2^D%#=f_9^U_jBGS5tUj{=Ei? z{+R^amX|O8^3P0Q^8JKo-)a^9xe1K_`m_>r4|A2V{BOg{o&h3CY#+!j##qBLZlS2s z1#OTTAfl$&KVysRHtuo`-JdF2_Lw!UxzO6ZaSM~dD1f5)pC!t{Z5}%PVzUyFEMoTOuY{(y{M(}3aq5jrb)fjaB(REsXw+SQGBIOM5@Jjk0A_zfY z#J}!vXD|#tV!rdubj6%;(I6%>7V&jpwrF zcSL!xtVmw#H-GsusQr)06~$8TdRmJqjL`Sn44t8A9E}JXTF2+8BcRejGtmd(%&>vE zwJezh>i2t^`Z?D(exgASfZWi7HCe;bHp9KVk+bw(=u}#CbiS3Uy3*Y--AYklr^F(C zF_tnV;B|TU5bF5RB7~!bx`pj?iN%9Qf(i_W@$LQbw}E4g=%q{{dtcjJ}e5fw0ieMPnPwA>#+1*%G|Xn!i#tecA_^Jp%JX$|APAv+?u9v^TRq! zN>FS}zWntV@gNg|F57%;aW1q z$z7qQ7os89dUBxXd}c9Nw7&C%Cu!-6^WkpE2mXlqIIDfZ@vfV=(eoG3(P%j1Z#uo- zZpA4LEZUdsPMLw?h$6W`ZNt1cK_h#V;upX6QZlsTL{euf4o&T&Ni^lp7E}cmV<>WR>dTUKq*YGMNUY zFhCo}kxltL>AF3$lCI`RRt&*9Ar zlg-A0FH$#qH7|^T7raM91K&{}_dif3ezOAd-yFPu(~&)fDr&p9&WVig7KXbC zE&)bS@w0A1{Nmcm?S_V$dHsY4p>=9xKlXmzY=35cjA`wP2TNytNbM!z@PT8!@p%_) zdZV}3>oAX0+MciQ_nm$#lJ=8en)apnd7Is~`sqOZziu=UjS?OFfnQpE`o_+S!kvrP zuLE{`m8sAR>ygFd%8bYIODL9xr}s($ytTk8Ka(q1I}I zD1+X9q=gpOZO7JOsg#4KQ{BM++~(zIy6Ml7LhAk=p5-dE)35z*%4YQWFYGI--wLij z*74n>>s-P--v9B=nAtxB|2&b5ba|*w{{;IARCu(l9QLT<@@kpPl$l1I(ulq5cZbwdr=+Wm1+^XFz^nO4G_Mb$UW4oCC-{Hb`oM{oR9 zG8GFaoQ@}YRdG^55EDV_N7$3W@64XpQp{~bp|xQQ+a_!b0XI)VMe-WtK$HU^W5OaQ z5Ka4o-4hKu|Av?3(W14BbS(uB%%_nNS2%yJe5eoeNd9;~)8kX%0WZbqE<7I!7%>vR zxO##g)E~(#UifkgY;2x=s~?#w-0X-F969^ZyK(+W6f63j*UV|dJX7kA+s5m_Ku zPsnmu{ob$!r}sDYoQ1|zdFIcx={TIG&Jj9@?oo@Zst(tewZFP|9M-R>Kk1j0;(@dB ze(|a!{Rr_gLT)La6TVp3BjeFLpXtiz#@+n)vY{m2x)xqwqA76i?s5y)m!sJYvbY5i zpO2gF(v0|5#cZL?O9e3$20hJkXUhJcFZYdYH6HmzLjz4C-AW~D>Z8qd>*B+9YU-}f z8NE()^2R@QaB2j*5nA`)dNPtb8_-0%+Dz!p5||M|R_yq|SDLSSy8HpV0=739b5zUp zH}nL&e<13g3Z-XkUac}!*R5&Bj*lbkaatxB_`>NOcWmn;qI^C+%WowvWoW?`B}K^a z`Hr4_mq1uav8uZUt}V7NR?bDnM7i2`k2S`}>GvFzrp7{r|_4lL)JDVAY%zN+#3(bLph6M=8)O9Jqa!_!_3UW!!KGO0G~ z!%%0h0dv^*a3=L)t@g?^`mVkGhw0V}%&J`xSpcBbfiS=-VF$R^P7e^`Z|K#jSuO=1~@f^ppaiapEA;1 z0Q3a~7|NqFb%5&cPMu?rhLE)_Ko=o|W{{|?D*zb!UGP?f} zLWNdsGPq{ovYhsGB6^UmmVJ&tyriEAIB#4I_NwYg`vSnaV=@oM|`MmdSu~W+Wx(-I>x24Gg9v(iC7Y!P9KiN#5XsMOMPIk;SuRs))Vj(2)#*4CuJ-D7C$~T z#-(JzuGu*6IW8ZnyTvDxmKWKfO0H_0ymB?M*QI zvu@adb*#9ItLUWqUr{Aj6Xgaz>&o|a?EO{OH|QQ8*0E;4w#7;}&AXZTLIGVPIi4bp z_z!V3+FXJf@kDHs_|3f<2fJ=?hJ%Y)BS@gi4#EIltDdgN%=Er;)14bmkirJk7>QA) z*qaN|S6keIiJg|3dAq!y;3`xIV<`I29KSI0cQa+P)9Ivwg5Cr1VS$zP=_&cr3?y4V zWNIE!!9N3+eC_&O{YOL$KT=&+BkS6u2(QE)eO}0_E3QnSOty=|+oLzWYzO;V*+Mi( z=qN4kN>y6AboPw76CpixT8=tp2AukRNG@j$v2));PkDw5HEn$zaQj5~H$Qw9mP9qc zp$$?BR#&6JX7NZ)Ib1mm-ZDsMV&QSaqqVaoTEju|=f5%R9CdOBCDGj$7Dsk7Fj@&Z z(?He~`U^=%T2Gbz`2PrCZ|$C*N-SB&(tIwcM{m8`&kzfJF4}+xP1!Kw;UcE#9aZbW zV@<2v@88N<{Mls3|IIA`S zaT_&NaAkZ<{baDL(Z1`8k`yM%)QoUl&X(Y=U-uV4Xo4s%Qoq3i^VBJvpu|>Cj&sN{ zb9RUUiPZ#BEdR}p_wSmf_?lK1U5$!s{-WGdzFT6W9cC}I5vcjK(WZ;BF{7jhryr3R zIXrb=_!5VeV$jexGv^_#>m5;27tbnF+ZuTT=L`%G2ql7!Qmk`hF#70XmH_oyo$qBU zaLRDQgn)Qr*Rj09fR77$yz=wLE*r1~6yr#dT39f9RpD3--yE@jS$j(C$jLOIt4ZtH zg5I-{3!Oy<^NgB_`Gan2W<`{Xvt z@A$$GgRkYm80%1?;&PRRi9&mQ^WGkBR!JAmdu!#IZR(1Ka^ML%2;Z~qrFfBoli2{I z;dF<5hrbh^ENMUQ=bdpxYf;2}#7%8+^BE)dlSF1dD>%Up!sTDdyT3$_FAV?4NHk|K zT%h0?jN37~sycxk%Wt-JWdGZ%eQ~$=i%NCNUxD>hGaBeb|)guj&}l&=0$1`v21rFLosojrYf)Z_TyKBoYw{|aVzn8v*U>qR@Q?ut&gcIoKu zLJ%0)#a7KjXF0NAZ9sy2-$O0M9e^IB*>qaHqs2Y^5kUmLhMBE3jI!(WQqC*H9lWT$ zq-w1~{w`e}H*U3XOa^}K4jmU*XJLVt0vuIQAF=9|A2x)|3Oja95)RJq?a|Iys!KLw z-`v%MS&babP%}9GR^pGrF4)>uJxtX}*zJ1}pEL4Xw2$oTawuvD#p& zm+h~zXbKBXJo3}byB6F+8DiSNu8{ky+#IcmG?vC=eRtxP0%D|?K6Jj@LLRS{H4DrF zY=HP(l7}tzJ<-7NVwO2##*-x4^_p`62b$&K?Mi$|F7UnU{#yPACqOZAhGMXh+aQja zd3wjZQMwCUERABhH;({q4orFUd3RtwE%;h%tt0>tkcuAOXYnaRKAUODtxD>VZ7T z^>4KNnrvduId*n+@|3UOKs(FksEJ3~PZa#a;uB5O(KQD7v+%U^QU2~QC?ELMj02j= zIaLkwk;c-I*{!(?_wP5eYzR43FJ9x%0C1yw#Eufah%T<QbL2`Jx+)!XUMF?PJ6W`Zh!lWx-4!W{yo3B`kuFfF5Zt zG#>aye$YfFtiYF{k3SXT2V?<&1pi4F$9W5>!^ymwkzN<1AZo&$q##<6nqG-6*>pc= zcW&W?`pE?4Tt7o*egk0B7;$*(O7xC%HD0C*WABz4>)Elk4O8)7$;tud0*d0tit@-9 zAcSPNvbXhV^7VmsbQic1q$3G!)x+yJ^EtU2#WiJ|P5OMiIyIWI#ulo&9^XIYS%qv` zRnO4>;_RAD8 z;E^=bj`0N`xlG$;=9GxCvLAgD-s^-`yx1mr7idV{-`GPYK!CfzrcvR&_+<}USDUmx z6k6pW1#j#aI(SV9y|x|2?GlYXQZs{n882xSR-eJRCjKNYt!~2uf|BB(W(CFbSwG!{ z$#=7&^NuS>!OR$u4I*cswjHm1-^AJTS8l#={+o^53J0g3Yzig+1`&!? zdhmG$PWA-n;QfTBfF&f9r_ulms#F#6GwI219_Mlp2mrti)wPb2w-)ei!CQR$0 zHoY5LwQ{u+>;7+w6YA*e<(FMP$Nz5L*hufHKEgc+wcH}!59tUmi z_0X_#C?$tovy!S3mJ4U?eyx8h5E;-a; zQx18qn~hdu%#zMgA+ixcuqVn15sYpZhdg)c7-EcS1KW*vL9(ny&E8=sfmyt0m0+t? zLZ}ASs_GIZ>WjpTki)r&qhA-{=ByK_Z9g6eDGl!IVT|q+_4{>07QpAly9?Eu9^dbNQ5^Z9j#btHqW>OmY5k?R*Z86xXiA{WLv~e=`q#Y^ZBK zp6J(;q!BCx0Msi6kY`lsyWWhDQ|lU&^&aZK)VN4~ZUGN~olE$!wXjc0K#`rrIGaN? zXoQuWx$yU_WqP42m)9^ZG)=vYe8^{fR57%uZVQ4o7*Yz zrREfB>eKXfV2Xq(ZrAVSAv@zo1Em$ip`lKQoI4E!hl~3o*kmnr8SyK*!d(@44vwuj z^mkk4aQ)(di6p^QiLg&1-~1MeacV?nT>yvF6Nt@V*n`^ zCAN81Q3yNWLmZ5rUB^^4Nh5vjAV}%%-hxMf`DF#LB7Kp)0AkuyZ>PJBTz5|9SZ*=x zRdZ=;^6Q`M=Y}9dP97#Qfuj@Yp>9`=Hkl{5YN^K3^HI;@I}Qwp|A9($_-O0Xw~oOf z81hNGF>3G(qu3>u+7mxm~F5yU_(y`z==b)*r1$;0|T>qO4HEMgt!@3GbA`pDGE4Ff?V*J;hx_5EgMBsRaEB_M%9l_fFl zm}YXu^Id=+LFvw~5$4GnD-j5`L8>J2UL@J0guBOM)Euwka&<1{fu(-{OV{=;TU~8{ zbuKHu@02NGpfM|KNt*nx`Cq7mMHag+uNvCkaFrXiuKA~aJc2BVcPu+(SSdW219rfM z@KQz(5m6H>c&o~NfBmhnR-s6J`Cradl434rAd-zOjzHicds;_RFmu3!rb)3UlP;g2 z3$e|&@uPfG2WC?@cr_pl99Wwm=Xxci{{C4#0DDyd;p%}rhx_x6vyMf_UGMvIU&rbE zNCONCtgn=5pcOtd&uRjaL`HKVSHJcDfLX}(Eg>lt53vzN!YZqh+h7xwl~T!lY`?xc zeo(*UP-F*VeyA4_Vv3}?1?O@Dp%t^#D*RI>USwX7G{ZpTPqqxb~ zBlSckN6FxEzjeOr%(q^D8a|nOv=zfj8>yovPSeW#hS^vV13sj|G~F)N%gyEJd8AXYx<;cCiS&vwAa%aOpukviMrVkwMMvqb6Tl);ZbSzJWqN zFxI{}xDwUxFaM)PvLz>*@CS%LWjL)m`a=?BHKpOtiaF5J>3`m6O=*@uvIcVa=X|yZ z+fm_-0)R+q01re5;_nKnhifBz@qVUE&Li^f+>o3(1Lu+%>09#6@G`)0bt#?Lkryvk z>`LPI;>1WmUVEQOY#Z1&sgM9_7&2SjbzRvH?U~=kmQV!wAFOcg{d&5SQ!aoQfMk-p z04^`bB|B6sjbYZVfTaeg%~>Y8|C{L4?RxCLS^2RUk70zDvD9;odPyJ}X9mHAqB8IJ z1X}?KOQF)Hg#LHua%?tf1MCcZasqB_SG!lQ98ZaNV%l=cc7Y0GI9?^z0_nmCHEB)_ zZf8I9E&BQFT*7zzN?kFWY!y-dJ6A{|`d1`cV_2!_0l0CC^_1kYn18OU$~PiT{q4Au`#I6c^%j#*wGrWi58 z(T(Vp#=^QchUo=(k@O@zIL>)*gueH@>{EsfXMP!J86zHy7~r>83VoiiXS92u-O^}oX<8gX z71w@KY!ITHfWWqX57yAE3T%wYo-#j3RA{XcEdGqtU7gOm? zc*y{ZB9$7V6y{6^@C?msnv#d2u{|y&o8#w<5F8TzfMO=t$5G#`YA)D6T)k+su3*gc;fmMk#e(d43>8B7LnoMlXb zF{Z#K9DUM27n+(mck2E4M4HUTb^#erX7$6dW5U>m9Dc2&B9mVyruvcJ&*H9qk#{3`0ZD!6jAn$-9y9)MKcP{a_@e33DhX`>&zdv*H1;Cya~*2rc5V)fyI2tT1)3WV(x|29{P^a zuzSMfOSNmp5ao=L@nG(U8}G;P0l$%#&)$p?TE=R;_5910tDQE8EHW!W1LBd}dwGMd z@b(40MVNKnO+hlzfOu;d46NMKjXm5Se+neIqzZtH&v(Rqr1&VPUzCb4!cF&E7tjhu z--@=nin=P7*J6(3Mn<#g2Fz%{S)z5C?_C*{sXwnz5rpu6PkC890mw3{r13&QQYa$2 z{>78{H(m~(cWK~SkEX;%C09JceiizY2{hs4nOzfG9~RL)_IOooKx~6l0Z=;utXGC^ zX;s}GU{uwogdi2g;olwp8->UjXgOpVVH1Q(gLZu zgmas10hFMh(+`;Z8D){uuV_*YjeP_^{tI(Al-5hF(xs}xIEm0;Ls`T^uJ9tG$D2gh zs9}JDTTefJjR^c0s3`#kXnBPx0$sTCvgI#lXDN}v7y<3Aebgi`M*=Jo26QLrkPEEx|+-O()W@kotWmp$}sxr2YQO<|PDIse$A>ayrhFWZAEe8Exw& z45#2#7gfNP-QYw4C76wucbzE_92wZL;qz0ektAiBdK|65qF*ufU3N*^?-N(r$d2gs zs0T&Q^~zTGxA#NW_|bot%oGbNOu!Y%8+;Tlf%$AI_F4dfpNf{bqk}UUe1O%-fA+Pn z=>j0Yy;_f4va{NC=hD7aD}MFb(UEyVI7jw^{ee-ny+gn@hB{Gc9RX@bJuv`~W)wM7 z24#1jUwNP_zS}4NStoYpUbXO2$2I|?EG|eb95LNw!pv^xZjo@&F6rh&&S!{V};Aj%D_V=aTxpBNJ0r0MYgkeo0r; zU>e;Bo37B!16k!&xnB#obZsHseEN$|e9!|j%^cmQZYDPybrA8U37@0?Q(Phb%+q5`^SjD5|IP_ zk=-)X&aCcwu9s^Ko0TwPv^2tvHv?W{{P$wDpt?rzf(`}#j(uLOZ@k#Kwr!qjiR$sW z>->z5co)wTM`C$iZ1lWW#t77(ajDnrxUAUE*Ws?2`z3lfoRn_C35djsxT)UJ#iAwaa_@mOT5k_xV(?|bi+vYXbFwD{L3lFpkF_B&T+1RVZ}dY+p-R8$T~9p$`` zL0&n(c_iOskYO?R_NYhm9&Y83C%O?2L+GTbPe;v zW`9`jzvdG=y@QL3yLNbZi1ju>WZf>5d{Q)OV>nIGScN&okuD}CMx+DXSd$Yp zqi_A*;*<(L28$TA4PC>s;HjU-}x!g_XeP*J~roc3V(gyKLPtn4bjbf zDf)$f(9PvCK6*Oput~%d!1FVr?xy?fGMAK2__gs@piyg3J0;Wq>^(NrwzRIu{Gk6f zD$LsWo^6PxXPH}<2ntcLUDJ#a%a;2v_%3Md=Ip?yAFotVrzlzNtv5vm(*IT@Z_BYh zfY=V`;sbi1bPv>0TP|to)(-_UlRb&IJ0TC~svD)~bmsy*&+^&xt0@2o_wV)p)jRo~ zW+r|9P0*tSN6Aa*l~=WlfRL({Azhqu!|TR_x|DV`d5@UL;|1Xvm#G`#3VAwi)aAPl z#&QQr9a4wF?60lr+r9#UTAiKR7ani-YHF32tpSi4Xz#A<(F27qEe!nPg zA0_b`J4YSua;5oSj-gPpi&U4QWzrjt_WROn==>(iD%ZxyNFxwCOF3NmJh_52^#@aD z^>p~t1qC+BHubW-lmTsr=e`V;j42;O!=PnQFZUsrm4O9CeneC1SkN@8avV>aJ!&D- zQY$O|`|D+VHwGC7NtK3gj&z!aQzoo-DK??!=(5=|WP!bgPYO>Z=M)>KY4cB6*X!e$ zl|N7Ijwx-?I=kO1 zzE|Gex@GWKlp7DK1@&!V(TwvFqN~V1khyg-y3}PdrM38U(>LKdTRFg_6>T^ojGC~T zGI<6wadoJ%pCOuF!H-HXwy$&GcDpR|zHz%YDnIXtYmD2ii9v`K=PoKYg#9219l8mL zLji59I_2TAaicmP)5=HS>$GTrggiCRn2j@gOPih+%N*n)i7KU#g%DLbH@HQ4FE zWv*dw^&CL6_BDCB(^B~db1M3>sVG|Ju3w6ul=u>L=HO*|6oxT0W+Y$b#P8+p#>c(=~Mfn1IRnE)ot)^en5weTx zmw}#(^kZH2#zIZKuKT6waQUM-13sz+g|ZrrFxd@@SlyZ_6O*bbwB`u9&1yrp%AuBe z!#D1IBxvf>2ttPxA$2L*iY#9bP}4qb`aopQegUpC`ue7`sOi0*p-NEaZ;sbV`dXb8 zXkq^Gfk(c9DUt_TjcO_7CJSc8+V;jt1uF|+?^D4UIP!c{y==;aSVo;m{k=|S<10=R zq3lbGF~7E^$iHpnR3CQqwN%S>Y|o`%L$4&RZ`-_QtL+@@K>;-rkHU>aoG8L5 z#e+an-O5t4Wh*7h?{^$(<0Au!Wm2ZK7O4-^>Z;j(Y5BeLi!_h|zFut#Aq_hkGFIVf ztofnJCz){9)+$|di`1Eu<5|6*_GaGSSv%wET)JP5hQsBpRWYb^i?*>8i}LIP3vIWo zbR{+Tylye{TH9W$xV%_c&qk)T`u#@7n@l^0vfKrQy36sM$+NOf%3GGLJFOzm;pR=DQ4j#><>`b22p_9(9HM?}} z?K-PA0P|){s|fdpRh&MmHL#&5HUfdgn?X{J-v)S!ON=h*cN98u7n!CM=(rJGLn!}g zVQ{xYu^sh6Ao%h^yWH1F(C+z$!*h6ny$-6m*J$rsGAM1QQ@@iFjd<|OXUvO-daQ2X zQc_UO%JBOj-*;J4rh{4KYcGBj~yOM1o=E_Fa5B{UC3IbAgXmxizH$L9|K!eZ5 zlA^n}{1<2~wwu^VN|xPwEng%`r4RJ(4vk4&=q~^rsXw++ZOvl&87;niy0=|09 z%QVQNxB+rqJ6Kz)Qo=LOQQ}Xl2Yr0IRZ};`zT2pBwDvJd=|6+a|NXrr{FXd{!2-v` UYZ~~O0~Xes*Xr`svSy$D7e{;-m;e9( literal 0 HcmV?d00001 diff --git a/doc/html/_me4_button_8h__incl.map b/doc/html/_me4_button_8h__incl.map new file mode 100644 index 00000000..87bb2401 --- /dev/null +++ b/doc/html/_me4_button_8h__incl.map @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me4_button_8h__incl.md5 b/doc/html/_me4_button_8h__incl.md5 new file mode 100644 index 00000000..e08375fa --- /dev/null +++ b/doc/html/_me4_button_8h__incl.md5 @@ -0,0 +1 @@ +71e8a9cccba2e8f6fc237d964aa3d0d9 \ No newline at end of file diff --git a/doc/html/_me4_button_8h__incl.png b/doc/html/_me4_button_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..d21dfe7c5f47ddc927c2aa9469fefe0601d1f04c GIT binary patch literal 46456 zcmagFcQjnx8$YTGf+Tvh5YfBnH4#Bb^cJF*h;G#AFCuzGXNKs#GdhFl3{j&G!bBe> zdikA+eDA$$-L>vL`6G*U%--khr+msY;p%S`i3uMPVqjnpD=WRw#K6Gu!N9;&zk>(- zh7ZfN1^5roTt)E(#tr)4x7LDq42(w@$}gU2dx5tXyuEbR8n5^FYCQ1hKFim|=;yu( zbngUBOdadR$l=Ku3cokZ`a+-myNYCT#nvub8d5uzRTsfTKyFvoG0T~A3KHg4OI z`ct#vm@xs_Mgk^pUSiXa-SfjkYCqEdc2=XTc_yd_&pa-yq~@J|G%2LvPm8> z1J{+)?tEh?j8_BsC2FqHdAZYag6YKzmgZkC=;hEKb8f;-d7(l5311N+FUWQ0Kbt`L zY&a7$^NfO3?B~y)`%w4hY%=|RdM^3pz?oW%3^3fk zz2cZ&{QYC}@B8j$S1bP8ujL($naAi&0heG%;r74V@6$ZjKK^@epxDKB&C~XNxgl1bn1&2mME>;Kg4#ld!oo1kwH>F?>dOT*yM9lKJfVd{kV?jw+kLM*Nn)d z8#*>V*`x**>H6<>Pcy}34ndnARCLv#D(-ay)^?$z(A~M@2ev+p<5O)5#^vzo6U!%Y zx}@QsmGb}hW~#@N6b7LFEvv{3%2wVKISj&S!W^mw@<1>R7x@;XJTS)qjuiZq~I#M>{VBDjNRz z^HJ3QHhKLsZ8G^Tq{i(Ux_a^U3Gk}2F^ADFtD3^kKx4cyYGzTlWN~PD=0NFBOePud z`pW*k!??2F{UYVpvj>yO7miMHAU(GK9L~Z+~)xf_8+#YxB2^U97 z)lVDyM9-j)G=};AI?@WmO4AO-95}GtjKW;Q|3d83y+mpB7SNac=l|~`w)}FSpV1wE zU1Sh_omE)#`LojT=#QUD6_t< zb^DZ;eN7F7^xTQ=Kp(pdKwxo zWzDe>68M1>+colDzi7h74?H5Tvd+VK`5so;Wn}X2$!>=?v7PmTh8NmSNScvhVX6%D zmsV>;*Nd`-f|L>}X9URTeZN?@Z$GkJ3cf7e6n=-Ex#*Q1z3coEEM*zh;YCWV*mOsN z{4=J57+>QL%gU)JcQYj|J6KLV<*X$3z6%heOSicbhv~A*x#SHZx(RlPlib2y9V8-h zI7^z=Ve!o*FU9b{W1S|Ssaf#rnGcC2T`s~PG10fQ6H1k(?WVnC!FolI8YO_|HMd+J zRP&Wi7s!o*W}k{NiIKUwz+ibBql?xa?A6(J`XBx?C3tr7IUIp?Sv7EZ1`}=bfRRf@ zHfHA5yxY`1Pj2oe1IM@!t7G^&^?uoEejB7Y_1mH}F_Aj`tzl}lWz$t1TkJzeD>WOd zXc<-|fg(TS5oOpeY>T>G=>2?4s*lh47J+)>0Lb{2OJE*#tPotfmHEypyJ^Ak;Nti3 z!@!}jrFGbBF|&_wJY&x1&u+1|fw&o_K$;H)G2c z;$;ciuj@rWp0_L;9lPniMOHyPmw!HLU9k~##@g_P#5Ts?jXJ+N^e%MGuKTklZpGzm z^1O#8%G1WkG|ENn!Oxnj2atQL%nvYcQ{bx$=&KB;a~m-j_p%2ZSrS>cbtYAt{QQkH zs-fQb)eZ-=N_0eLX1orhcLpy@KdTK>b;-FSmg085rZa0%{-Izah25g-(hfFTh`7aU zeHi9bYzZdS7rB}LPBSVs^$2nx&+Bd>gL(j;wu^AsfEsHpBAz&M<37|n1OG^l|E7KH zrq-KOF`DYgPt%9XfctR4z#n$AZ)%knn(Duc|K?8cep1H$rw{K04#R+-<|>2o^Mtt5 zW4@Bz@BhH*gU;&Q5l${?uMID_U;|+ve);UIQ3ia4*q^oML6qdnHGzVPxd`p!BcpD? zr7E7}SPNBAq!0`fMoV2XZ@{n)8d(WH)(x;eecnnHbw_Ln;$j`uO%o|VLjC$Yq*51Q zFgDk59dejJtF}jeP_T1FLw27g<~A{vG805k3lOW(NX4$MFs9NxTfT( zd<#~tc=-W413RPBYZg%i6-it44wL1Bn5E-$7JOEM{%ba^npI<@N_nT0{NvxMc)GhI z3ufaNyd9*L4}Hu_at(7J1M@O`XimUAwmMv8uT{-j}ptVtHkj zxmhND26&yBV-m5^bo~T4327kCN?BC4q%x5{!^OSuVv922fhdX+>G~a>m+l%^^lv`; zm?b|^H)OE85afFGf@SVsbU1E2O-6ngGkjm}=(ygr>zHiIN8~8@*pa`!sgKf1B4;2Y zNJw;fb%Dd(;vqlgDO*p)g25Z2_U)bU4_D8geEED=^!E5In+G1q{6I*Uf+ZuHB$Er| zZ6U}VO;{O8LCWFTrg?LTtZVUhc+WP4zw?(BA?i#4F@~Qn&h<}B*1tD2f2el&EMcK1 zkt|0k*n!=%9EDGkXTe`v<3IS|eHgi#Er0E2OQG9rsn*#KVGP-)2Wtku3?}kZh8E&aq|C!OJBs`&COJnP8CSg&NyJp`CKoHuQmA%u`cQ?b2hT zfMEIOHsB7gL^)=`pZ{J3X-eyWXLOx2jdNDlAztzX`AlnT%ZQ*UI8?Qaw<=61^LR=7 z*fM#h#CQ5zXnc@nFo)dl(L3D3&@$r%jkieeW=dyg&sX1I2CJ1K{Ar6H*40#O^f^~f znFXW%tq`!0GKlTF^a%fSz0lX+Nc_j_$Bz}jRtM*lFnsbf$vsYT%iGjv;#)tx-5;M3 zdG)O;5aT^=Mu)x~(`(M47rE_4x8Mc?NUR4vbufKT%C*}4y5f!FmleD26#*gCT!HiY zeZPty`0&=)Hs@E{IH%Old)oDzNo=eXj7C96&x9-8UdVVZJpHj4BVoZ>i1Q$>@OE=F z>(&*hU<-J?hH8}8{Ndy?&l%Ch)Q zxYf>aJRb%k4MFS%g8kQVag__Xz-GCej#}TZx`hcTkse)3_KXNPmO;!*a^TZT@QRbm z*O>T!YH?=w%reSLYx!r7n7_XM*PDeBOQeu%!wI4Ao3|eew{Jv5K^7)@cfZG9bAYXO zOBn?I)5`uCkyCB+J0<=|Bk0iEl*GBPD-#PD18a2u2F10GtZw$pjRj7cE=GV-Y~GaH zS?=P=9zrU5KSA;}W~oDPes}lrbGIS|mRGmo{wc0HM2#@YZb5t~Ivs@7rXf5da`dMS z6fZNJ1&92KVX}GYepx$^kyUhc;?BxX`;$l?d;X!_8gvn!_>izoeGgaiyO@|;4{a2P z+6gWeg{>S=K7CgT`zfZKK$=v~?5r}BcMQQiw)gJ|u|a!(6yWTD8iWf#H0olvvcCATK}yXsl@v4=sG2a*BbA5ku)^q z_dQ5$3h*97HiB|!MW@~@KOd6PI@u*ol3>B2aNQ5t+wGxP2iu`uaQ<3Rc;aD_pQ#1ZpT~->=`>Fq!N!K~iBtVwniOrvl_yjj zRb{M1%F+ECHcgb&$$5zyWXF#neL^pvrR*Zsvutm{{uHj|C{-oTVCR(f-bpd}t>y23 z&!7bCU>?Od)NHVc(Of9{SP2?;*4inSj+`;&1~ z?ov%dLBfVvfmNU8qT-$<&FJ2iRoL?5gmCVZ+PUGX8RMbiNA}uPsn~s-9<30m`$S#` z!^BeKi~+IXciC=J3oq-qQED0+zq#t$lkT-Ecl(2uwKhW)lEI*0?%cxs?+iP!NK1f$ zZIoBz$xeKmk2b(#>{R-w^at~?e*UD)RmGwD`>~q99?UT8GkbATcGGC+f8qbwP~5Xz z=8dpC1isjlE8*mVnwgXH#VTq7Q&G?S3Cg+5i!FoHZ`Fz)i)-N)kBL&=zr=;x1huDY zCA#{z6n?*EaBo|-9Q2mU66gTCP+QFMc@x=`b-fizn>P?L$BDJ&O6kM@7hgCMBWsup zq78*jef~?CBj5!@jzte)SOTpUUYEKdaPU+BWbK(P#25&I2<+~E+4>N<18^H+n;N~d z@(xxKQmmd({>A64rgQ|`^ZxxMBz6)ppJF@G>eJ5Rq5t(e=l{(XmPqswP0)ggw6XTm zT&x0y*EUN1zU>eOx92^Nz#AmQPn7;j0DR=sz;;B2<& zoB^@guf0DVhSk6x&Z^-?ikFl`Y)}4v5P6sGw&NNU`|*wtThsl9leUIBO=p^xU@s9 zHjuB*Y5ybkX?W4uF6l147>*`1yR*j{=%$2*CxMcU8EV_omgn|qyA*17nb z66>aTG0Paczi=v>n)Q$t0FSpL^#%PGMn zKE7lSJsk5O=!2$_p3tOmltjAan^;}U4Slchl)nrs?#}nEtM`#E5XsEW1|f=rM4-EN z1|pSCeG$#OLlr#GJ<_8?V1*+=Feg;=n0ly;w^{)kqVg#d&4GA$z6V7HUD0n6G*o*; zl*LG-ACZ<}eYL-(jg}ZX+=tS$2MzP!Lpp}4z({5q)TZM;%QOa+*iZ>ibtrZQlRUZs zKgL?baFs>9$q`QM4Wm-4t;dr|y{iX6X3;;MGQk3jDS?L=n0k}sv(<$){jgEaN8xF= zo5xfKiY+eg5O$kwPtWMt2M4D5mo8%}K=UOeEX0C$ikIa7Od@gnq#7xDDvj6exJNrN zk2e7@0uGI}2OM@NGJ$nkRcr?L27e2odLD>b5&H8vo97hq9*eQK^?1I;b$g1+I##JA zR1$poR|8U#jb!taV4AkrCcb2s&2&=uLot82C4I9HI2UM+s7+&5c@g(`9B64>2&CKj zjUm1$GAc{mx*s9Rw%m*3%!Kj=QwjM0oL5bJgL=3=UzQytkmbVSjDxA@)fY#N|MmL9 z9vj8dLxvYyfY=xD+MIgs!#0cfx^vrcj^dBicFVD4!d=)Lj2^DRrc#xcI7ZH%pcrvf zBP}oVWm8)R6u-aq!v0ybik$ayTE&yeRm*>pu03&~IA`wL4<-y-hc$|eb`y)L)rjW6 zS!Z&ZO9HWMqVY?^Z>tTvkc!7Gt@>(4L9kRXT=euYNhv{8Bqil+u!eOSfMMsrD$?*E zlF&MZW3L47b9wJECwJuCM^rh&&i-wcebx#Pm0T{MoGrl`M~x+Ii4!DUOI?U&7`CAMs7qt3204Wa-k-l8XoK;={y| zj6||Bo=qd>1sDHTWINSrBusRErVEl;Tem;_WPGPW!zR9?z`PE5PD?lD!qO6|`be7U zz0IT0!))5u^m8!o9>!v}nXOd#eKjv}SYcSvBwWo*TJyFU=3i5)oyWSs-A`Q{;;uX=ykDRj=b^_;=*+GWiSJKHchF(G zd}Co^(D>i=??e+M857j1T{N2r>(f4bEoLX^@=(8}BOu77xa09UxTf;wbxLaN3#j64 z(DNk#wOZLFlx7XaxX@S#{mBp^p%>Oje9f5k!?Z_hFHh_Y&FCb?<=BCw8a{26%q-=B zUgW?Zj~ODTeXe~l*GLY7NU@15Q1ryhiK^*nDikizHZD?005g-rc)BXJ0mxvio>TVo zeQCSpMm%cgCJQsu-*}#yuTOk`dzOhNRq|4Q$7-3#_AlT{SFKyO!A>Vb!L{narb?0L4lV986DdblJG8Lj1i~i0&3# zY>)tph|#ZpFjWJU+tPNNP^#6w)==Ckm0B(kyPOA`;P?m@Z0g(XRM|BufAb42vkIuxLG#eO*n3RA7;>} zL81svmR0=WLf2A5vMK;pBxbM`@`x6%cmE+F7DF}~;_?RQo~DCDl-&Bx&+p+Fob0JU z3A<3UAV3ZFyJ@@Sl`}Eb6#k`o4GgO|2&i^Mh2^TUxD`RBm3pv-@Fo*{Z_g|RgoH!P ztUc*KLjqT4DNM_8iVPhKBl-=_X745pES=NQ`W4tUtm5G|#(XWuFUc;el6=cdab-pd zn8rHY+QtEr+Vm;L8^Xs^lUsC}ctPT_kCXX48ScH)(Gl)i*!$_T*NVR)Pd#Dmvm-pT z9TgD~adLI>l}zUmTD!IvwM*Sgj_(rX&ZS%RdMWJ-UDrA;`pV@Y+j%WB1*2N)Gqfu_-2qXb6&0`85a*@hs)BzWbphE2k z{uK70guf%8&6No!e+*lN9!orahvf~sYqy%<)!8n?naSuWqp;uiICgvFw|u8vh5J=q zfoUKJ?O9m10#RTAh)E#OSv-vb3Ft$Fy*ZRpdOu`D6p0tCVi$o2{e3^~z4mJ;v9N-N zLTRD^tZd!row}S>OUKCfcamZ(n&@h~aK^qc^ZM5>iEVr5opZ_zcC}Ns3)$t-Teg)O z+}usu@-$I}%(+oqR%s3N-XV@BT;gr=e3{hpH0Dwddj)Sb;|qG_7kIir!ODU5@m75a zUN{r(QCn5cNJ&4k1&Yja3G?y=hL7W(gxbj7Ow^Cf4S(~}u8Pb>yN?|CP1$_4(JFvE z7;>bsR>U%GK}R}oEp9aH?JoyK6R9mS?dE-PA$Tcotz-_Ih51JjZ&h+o4RYdw_*vAz zsDW+od$UA?qd1SK89F{X(-ra?~KoB-6M*Ffxp!{ zqU^Io{AbHBg(p)uL+nl{wPqI`jDRS%D;p-?IzMQH(hVra{j{LtaQ(7B8cCN?6NuC- zld5l(Cy6O5epr|*pY#_S&?IptoyC}um@px@!~(j-a{wgp5@P2Af43&tKG#{{9OGi+ zxi?hqL*fBvC#L+F$o=g6b>8ezp%z)uWn)R7s29J>_(M zmT{PTkgJz4<(=GX7HRn$Nmj@5@GrEp{0V3Wva8Aruv2m8%r$3q_bQ$1!tZah;ZSKb zBS6TQ@*(1Z?Y;OO_p#f44!_2J?+Q|}wOQ7FglttfH=L}RdaGqATDy+Y5Z!e{_BNBF z!o0?0DcnWk?D;<){pM|7Vm#UFzc|13&+dA!{b>u3T2=`RTkswM=h#Kq>xz(??v|GR z=+%!{!hUAQ#Wn?43K}+>k!2KY(mdMpSJ+OiJXYH4ea@AZU$1hYqr6IaVtA))a6c>J zwx|9T0W6#L%vVM2go*a~sc1+pXgREU{^pD+xk-RgKNj?I=h4sdNdu{ku<@5;(e3NC znwmlji|8}H>xforVZQ*lPHQ9|m46TtP{EVA$CvRwJsZx(>{sv?;S2uK*8QlSgfj4k z*EkwsXzx-VRCVwJj8R-!mINt-7^!vEoV>^JvFUA)g>}OPe)-N8Wm#Ek+iEXlX&Pd4 zbmAcp7o@HAe$d>XZNeZ{xem0Vofb=hV}wpi;>?Z_H#q_S$v@NJ+r}ZOeB^o}2||rVu3+aeD>S$pFKl z?B3?i7GP>hp6qV?VGe!4?Xm3N>lg+k> zuxZ-oLQv%#h&!-5mi%sMDyZ*P*27Noam~z-(OQeSYlY?=Y0T*qpH!c&c4e&WSLZIN zd(_7QEI`T0t)72lvq?39NBRfj$gOJ`JUf)Tr@e?s3_7Gjh=GNQBkf%;R3o0Dm$I10 zn-|Qh)Yv}Q3a;b$3p;Um*r?v^lS7Pzp;I@R4C5)Uv-|6~ca-iK_TR7+EfICe zL!v`%(|ezBjcj@#0A*qm;4OrhR{&+l((Yq(^au8_+YEODTE5HGeyKpA3o?WM*Jv7Z z^M_GN>0L^-QyrKmJud^Vf?BU``7Wiz!zgaSN=mi5=?@V*Ad(xao?h->d_V!`D?8Mm zn0W!sos`=97j5qWws^0{)A<$g!v(P>Xy3<7C-MKy0%QQF#{|gY(ntNna;eW+^7|+i zARLDF-XHXwthbMT{kf736sME)^EJrcR0{qBXm2A?i$=MOlaw>XV-m6-ljDXwR|o#X zf~U+OZ1}jLvM(X8bLD$Q%HguRrH8LFc`6phrgm$}Z0z^W-mU#s`&%Mdwjlp32s+*_ zZzleHKEQ&|KyH?xjl8@-L;5!YfWld|K;fQ$4Ydjy8)tOdLpJ-oGXWjt-#O@tXtzfZ z2YPjiF1MKXNQCJzU0sbDPzCFiB_d1m=bEMcKP$-^0E8Wzb5*%L{tIr_zNtZ{Q=jb` z?RgF7jJe&DS8AX5ohm-hOkFgCMtCY_7Gr%>{w9ZISxlo8506oF9FdX0Pvn7Hq5isL zzUx_NS2)S|hlnzPP1Uh>^FcmoN%u{6(jPt4rY1ti1Q3BBfgZE}BpC&Ma^UoZdUY=0 zO#LvvlX^%9mmt!odRQ^_W?g6K>4XxV_UkO^&=z*a z1Fcy}7l7sgWuE22)JS+XSfou?7+qQPSci<)n)5}f=&0?O;_Y5-FBb~+W4!k(sPp(* zhCSte=I>deRP9N9a9{MLcoZ|@@wzXIQu2Q}{KszipwDdH=^^cRT0-`}c6{_S?(`C% zM0K{2qFez34*OhS0A;#9sV;nB+|I@pmi}L$4p0QY3>#_sL^woAWPJV$wBophd_o!N zKy5oaAn&^|#`^YlIq*b|wdl6w`Y*7bT!|~=!GAt`ZQxrQCoYct;T*NX^gWU5-YKwUqGMFO03;|tW4TuwWE4Dy*5wRr+4Rc=!(!4aj`CMOx)fXM= zTWwt|P36u?W8|-G&XcQ$=TKKzq;x9d0Dq6wlLGqI6=Y3^MgDM`^!xi@Ab>DN()WFT zml7e)M)j%eR>kKcktH#8Q<&$KmS0LZpm|7^t2SNaL!sRmHa}atDDS_r37l2X=r2}| zQ*s|#%L?6#zYd5$!~b=-IuJfZ=?+ybRysH1u)!VO#v}vOu0-IZMzwV;=}UqcW)J-S zxn@6-GALg3wPn?)nbK{*ZHP(kT2MR5NiA1AEZxzkm=NG&|2Z`Nu#d~|t@`@_Z0khP z(+WC&@LUg>l`>xiPwl6|n((`dx5*?3IFh!lE@d71qK>h7B3bo4*0v z7ntr-!T4Yu#RJ%jxzAl>&2b7QRBP*V;1jfH?GQZdI|gC? zcF#sC=ej1eAX$O_wcu}ndEqhG2KZ#gct1-rmx4DO$A2erwIS?z9|maM-4Tz_V;Is1 zf8$Zu@8zugzH0*CEUArlH=Ab}TKX9%K3%GrJwOT&G}52I1mL0NDcY!-19$l%o|{5w zO&A7LE|IK$Y4Q-setLPheP+Gj`vl?hlto;}}t{_B_gPdu|?&x*YweaCYL&?gTLT=COgi%QXq4rwWi<<3y|)J7MNBA{-3 z5~m}7h>snH2e?65xl0}n?b{B)?I9?eVA<4t8@2u9VS(#x9Y%RQ@0>jfsD^|3U8C{& zA<@4eANh4#_m*FLmgqG#v$oOJ)^6EbqWTLT#`ZY%yy1iC93Z5j9LA*+NJx|yVupQ0 za|w(5zik^CYU_Jw)Y1qipdKF_2V z>fYqDjhs&lsh!VK`4x~dc0X1rCowiY{NS{^-*yo#x#r9$`Ny?$DnNhBN2TlXKU}oF zVzMWh0**f-tTK$#c%PiwPKzT=(_2cI94bYKa9ra`*@BY} zd1ZX5DURF;FSJlTe%s)@e7(E)r=9Nr)A|@O-v~1CUm8)McnKWzr?CIGarOdIBAdwO zmmw+IU`Ss3uU#8=`4V!7Il+^g! zSO}CTxM1kLtG?Y!ExV{X&LF&k#*=dC`V_1ArJT~mJZbKFVUg!{vm1pMtrsl^6o z)j*qZ;(yv~hQvmqZ}2==Tm5$C>bj4S8H*)=If2{kED0wkP0^O@*7ZcXqq9_>Xb-pN zC^Qt>QZTaPjIQjomG@4iP<6mc#q}q%n%-kk`pWsGaV@ z^a3LT>&*HT(9rC&#UEKfplEowYA&>{L-kf?BJR;U@OCwkVxtg&jYJPYZvC*7HQW^| zNk?rtZqeVp6`%oMREbb8MtToB==Y8mifdl1VWa4sX2SUq+lwMijI?UDjS*^>QM zkfhP5ngw+Q@E7>;#$ql#+ys~RyjZB`_{~82gF?*9`Jkq@S`~a zYx_=bSk{lIp3Ucm<4F8QLtotSp|h_AnTLg4e}Mj4BSZS_4VAPk-U_S;kR_bdoHUY9 z;dt%gb=5YkvT;s)al4qa+&xE|{l{+kyRCU%ot~nrZltN9`!0yrp1U}XWjrgG!=f8) z13DRp)08B{5Er~vd5ix#a7;6gRmKcEu%-}zE?g&>>-C`$k|s)?@WeN%W0+cv+PAG~ zG$U3bzR&bl+W1(8Hu}JJfkh;P{mcKM{q#*EY%A+A&jF%FqE#`^{7K5WE9^hpJM@tm z0~Tv5;ZP2;kz2hEY|GC`ZHKZG_16aⓈiU;6bj*4m@-huvYC)j@B8h2xNy%Hwt|Z z1pUqpfQhEZiGzHBIoPX*eyIc#J2vG<*qR(N_(M#7A15PWBMSxzMTsh1Kem1R_8uia z=KjS##uXTYLGoA{>`MmM$|d?X`3&}94pR5lVeDpBWpXa46?-)jdw(gVPyN>C`^cSv zT3Bf41cQh(oL94#MV!pgs?w9NHP|ys&54Ea?2jb{z1cRMRGY1)FJN?t2Z$~hJ*H7z zW#5$bf%qE14YbP_WUWgzx6|6DHpVsI2pH-fgO+V1Xq~jVhlkoGZnGM z|1oA-;1dD;vAHv)11Iz?bC|0Z&beK2V!h^cxZ61PSPY)}(KWMJx}r{qjpa%O_iupd zf*!;9?ACDxS+_19t*BAjyNxl&Envdve-5(H{I!kmaci3=_e-pwJW2xI%i0$z0a9$^ zz1g063Y{kekeY=CjL(f#>`MDrXx)2!gj4NwjYJQNLRdj}A=w9*F$~~e0b)!2(~A2Q zIK%|Qh-d~^?vM0YDpk$gq~ZvVO#C`Vj&RocdO0em^NZv#wHbfT2-|k}U7=gWCw)NgTwiS;``b@5Z&P2}29go`n>u|nRK2#6 zhKZW>>_F9TCX^RzjKUt;Rljf1)}bwwf#o>Q)U9?7Qg<*2?j6?u4ZoZf2le-ZD}L{^B|+0{c=Um1S;?AuUFxW`?|Y#M2B7%um|Rl*)6k92W$isfBe(Ld^kmESxp1!r0OXwIn~ z3;x5#Pl4Qm1*}NP!E}VR^cR=90h`6-dy#uX3$(8-zUqSY(h(#AWQ9R$6Y_ZI!x8CP z-f5_0Zv#lzDNMyi)4O$V53^u7!Q2%WrBq6 z|HOX(L>jq`Nz^Fo=07(*=G6zPKcMiPgm48(iqh^I674_=Ey67&|3bq9nZFhz9`b8O z&Or=~-tNu4$u4h71@GX1+34n=B~ekWCbv(m(+kr{Q)eWPiB4Z2Eq(-@++`U0UG;mx z4VcVr%nKEBzRy39wHWQh!&!R+xZcTZS8kq;_-$HRmU@;4i~D%(OW0Erl(V?0Eqlkc znYvKeSXVs0oAcrE(Cbq#&sWmY+UGfP@!~37MoD)I;t#8z8RW!fMUx4zrW_I=-ao=H z?rva2VhZgp-7qoG!vmHaU$=CqG5fup=HfsKMMmy~77B&`8_7H1+s{?&ZG=bpEu3Z5 zqjqMs>@6l5vnQ_YG?A!5u=J_9C)Cv5h5Mtx22<0Pl&Ltp8uA<%iZIM=a(y!~u+Lp}_DjLY1{RPPxP zp#p$BJx{TMBLhj7r9!Hn-aSjzO}^WL?kGqvQn4VnvqMH09EOMRk6L-7%MGEsany(T=Ew&4Yg3zX_6SK{;F}$J7HU`cm<`Bwrm6pBk(BzJ0t26L+#R zaX?3xR$wf~&G*x~XBLDH1;zUs**G_^avTKO$YJxNGt^?DPVhBFH2cI8RGcBqG-oA&i^x~DkUe#ESTi--G~kA-F153* zFK&f}2qa-jK5%t?9WMRQD#PKgIrdU;7#PPW9FpH=-ep`9eNGDu>Nl_&m&YPM`2HtixbZ!NYSR6r%{SX2V&&68{wn?vjBX z_^S>zOhMGl=9Ouatq0k()7NsC^8Tl=aYWs!H{O zuFYi}^F#^-@nQL3zlMF)j>zQB_)wvc{ss-Y7yIHa*?P!>AB?fx)QQc9xj4OvI7g4V zZi27O-n8z~;LH=#J^Tc2D*V0+^lYVx+lO$W81#*WO7V&!rNR`=dqRnbb~*q_DmZ{X za+kbG!?BWU)Ewm#*28Z(ll{OhLIRm&EqeO<5rP@CA~z7-?U3I1vES{&Zej*uB4oFV zJtZP4U%XO@h7LtFE4IsxoW* zFB<)OkyYQ&6V+m~?PyuqnGt2~FQerMO!tv~2Mxww3wv4vWuOClzhyC{wUaa^lpEVa za8)SS8#=J9Bf|_$?T4w3v5kh3M6Yv)@AOw>)4kzk1U&1icOJ{^&+~mguKyH(`QVXC zaFa$iXG;k1=KywL2Zf`rMWq9T{NJpW{Ad!$`{3|wO3rT#;(+$Q>g}zw!&HTUuP$Jm z;`cZWdEZOfsLYf%bBL2>aGB>#6g~~7J|xb^jFmL`CsOwZ{imk}ouTeFc- zr6#Q}gehPLc^fWWAICXbUpPV&;S9#V(@<#hj*H z3A-SfbCIrkB=gW+4UGvIhq^i$hqs1XQ{9;>4+Mk$<0_;Gvcwxb@@^`O{Z2ny?2gGZ zYi{Mj)ITKME^BRWF$ABVPwn?^H*QI=T+fJ?6zv*H-4kDmIE(*f;*Ydc4X84Y73iUk z?-k7KGbX&e_ft@P{lHByfO#_B;fIhUQ5lX1-rGAmnat_uSNOl>-0F6fiKvR4In+y^ zJH&PIf&8qdqVVW7C%)$pu5CIS?YuY(WAuKp(nRU?i1I7r#r^h*YyxTJ#EbjaNv~W# zGVMAhay+67?jqM{!`=RLAlCU+j>r=^u=nk(Hq}L%6JtqRj7*H$3%7yo(R@0eA$X*4 z`aY)FlUH();zb_+wQPF6={dsZI;OUW67c4%nLHYX*(fw}81%Rk^$dEnA0E7VnuU+S z#-S>gdgt!$4)k};=AX!Nb-vC>#yl}$s-!<7`bC+Z2`Vp&aG;-E!w7FG+ULHVo4}o`I9x$@&M7o;e*gZ!yJgxsGOOq%ac`?PkR*R< zQ|1A3M7o@u8AWAoVJLpFS{$k0n;&k>Et;`OYy6aB-jp~@J*d}6zt(|E<_91fHblSGWksI~%68;_5xj;@!E|QeBke@I%8`Cv1& zA$rS}@Fe`;TMfR@)of~B@hb?iiJ71?#ei6XET*W_LXW&k{;Ppl@Hz9iOas>Ge_O7X zm&(=f5ns;LCQriaAZH_P_M0smUP$*lU4nYGplFo;P4(Gn z@g1i|)FWP%4_v=u{gE~jA_Z?$WXazsq!6g$ERr>FrDlsz>5XXfjzhGba6c1&Lk};6 zuyb9(`>8ARt9pSD>vu_|AO|Uptj&}A#L>qNmTGi`jAuO6i1LNO$Dv z=&V??U1X$d7349BfuA^2pu9sR66_B5vCJbVSyDZuFvhiO09anNj+}4AzOw$ zr@p+{M_4Z}%LxhLy|vSFOJsQUwMIJykM4zaWeuTc_w$2@rL)u+g)KK~Ot_vEp7WPZ zE%y3GtNCOVE=sQH_bwmEhytCM!SqA}T|gd3QT==WoI2s(#mScOOk8aciG(ZUZvP0qjbLD*K_IB`q*p1jZ{|IIp72? z$&k>kKW_IKR1>Q~GB^IU6wzDLFk@iV5h(JEe5sx@v?wQu+JwYleg z6xFXcKp*oT7e6rQpH}C6B>mHyOFdoF@dQ+^XQ-pIX;0l-CZ`?Zv}SivAn@*A-3hjy z+@gASD%`0T*sR4--Z%a3Bd_Xj8$+X*iwWrO$_G{k$`O+e^$H_NN=6kp{!FOWv@e%} zbG>`7yy_T~A_iZCV=-b?Va$U^Y7+Cgr(oY)DG9)=_lgPn886{QIxOYM7_t$eziRxE zUtcG>pEo9SJ%-&=JbPJAK7IM6@w$gd75@#s$AkCIW*P<@qzfX(izkwbhqgZ^n+l-( zDs;TsR!*jkoji3+20NaPg|D7=RFJQK7R z2-~9%yGaw($oL~!u~_(FG+Q*CX57*6h&4!-vvl`^;Zf=PLo9|YLCS=;YAbH0)<&_e z2v-E1DYi4{Td4Qh*e9*VmywcSn_SK~oJnR?P-1@_lP!v=^$lFChgBE<&Y8wC=I?#C`yG$_9iC2sciKU}2$JEW-0YoTQ1OVdL3_Mxywsl-7y zq@_S_?HuJ5c2F-xQb9tV@v!xsUiTK5#T`<|g-(OAOu~_(@v&H}`I3R}*FUYS2F!VA zwBa*f{jp^puBnL`F%k_3@~wV+@^!S4y+&iIabW+Dt-l>3o1pbs;-HRr4fHv~zT`;E zijOYic6kiT`Cj}wJwI_*t!mV4&+}aqcavYa zknodH6SQE?7Ytm^5}u{E&!iqRyGY+zZe~Yf86`X1JPx^~c?@zRDEk7X&eP|JE{RL74&bm;A& z%M?*QC9S*j(G~Ri4l!0qdb&Xsirl+I78KF*=cx{Z z;~`;>&SwHTl5M_MmHE#z_BQrAT_Ebe4&MG@IrH(Xhg3a3;dE_K4;>5)Bs_$Wi|+oO zLNz{mFrE2jk+O~bFpm;}{msbCy1btJ<;uBCXWo@~X1`i$QnO;5_7SR3vn5x_>YiRc8YgUNkhP$Vf33R>fH#ZkC(?7jc<<*IM+Q4T<7N>qTaw|+%H(iA zV<6EhJYXFlwV0#(*b>^>jfV}o!UJz*~Hd)6FiIe-bP=CYI`2&CkWd*&F z-`xdK_wGf8T6);jM^0@mbNW(=(R%46NXA=T=Bv+Iawc!UiykaKrx`om!cwMMq&hX{ zW~n$$H1XtpTiz@}weO@zFkJE_Wa;cEd4{-2MT^W6`&q~h*&0_G#}omJj<*D*Ie57A zES84&E#>=l7KBv7xDr*QUSzfNmPpdEht*1HNJh)v>crU}uzn$@-iCiai!3=4H>%|h zXdQQL!tR`xgU`zK-(0D&3hDQWeVz79Cci0c)eF5DGt5@Qh7kfEhSx+I3~ z_8$Dc@BQ7i?p^l}mTR$`;hg8}XYc)q{hW%|NFOH(j?aGQ-GBX`jtw>gO%0-F|wPluHeCi{FYnIXG>|{bREvV=FkBn}oMuaK01n;S8@v`wHg9(ie$#=eI_*&=~ z$ye~mhPnlhBf@3$*9jYH0ig5Sr^8t)kkgq>Daie8qkgiR9qXoNz?R96f4lEpHB$Af zwQAj^e|DdWt`95&LW1%1yDY{^^dFQK_Aiw_duXw-PsigjPZEqo` z(pujRq*2Bf>;>WIb!&0F9S@8>lOZOXy^C0J@f@(G((e@2!!=#M`NijC;7yvL+ zX&XUWlTu#q<1rJ=tx@O-J;VE5oB1`Kk(HZYC$~i?B_Z0ep&8xr)S9|;;oP>5+^3Xh z8KuZ_Ld@ObPW7FeR-zX5{r@#&RH3?i;_LOOzmSFXW~M&>LlCDDT`}?LtS%)?+TaQP zDt`8IHXvM>{5nO(nUNUnd;-Ea7Ycl-apzcr>~`~B=jYM1Liv+K`nP6dJqBUq8@Fno z&?4(y;5wJ^_s^T8@MGa#!Gps0#S;a)U@ZY;fj+6zqsP(e?cNI?MrRF&&@7QU`oFQNOTi?S`GHeRomH@V#_oQcMYr1irB+CMIsFMp zpk8ys2%zODG-JksZsbnee!9d%z+u0&EF`Rzg}E3sCzsF5&{4R)??et_w<45=}0-+V*j13I{2 z@>!(2pF_UPiZwfnubk~;<5CMC!fF(U&$VK|lbF<)WOf^b5i;K39S7Jl4{jSMS8yNb z|AS$>MdhgMzb8~EU?=XTJBW-ALmiT>40LB5B9B0TPUU?wN=>Iq6qm9IdDAMoi5_wD zHix-U{qVcXLm9Hfdv*_IKIPl2zm#ipOE1-8>CQ=$sD3ugiE{Lw)#Z_=7oEH5SU<1W zwr$YD{3%N*FvLlylG5U@Qlm@b;;)l@3v^$>D{a?LAoZzChwL(KM`{!VHCBr%wlF(# zD4w(#+4m1KCchA)E4nXwF5r;8;il#gD!L9aL7q9E5pJX#@<$&mca5KWHaf!cTY{Dk zi*v29{3PL=Cx=_4po7x%2{t!2Hz| zjMKlk?LU3n$pqU!r|!6KX_qxVi~;}P{1ZmE?J@CNlZfHG0c~Xz-$x7T5kkt?PhIyV z>lFs9UMI$p^+C6?@J+Fc-3n)}>*+fqf?5pHJVIhWd~y>}Lp30RNzxKdaY-hAxmw9Kdb=KbVnhHl#929=9~VG>D%@>1lNZ=MNP z(2>rWvKnF8gSO@zNzQ!gL(h}?Nr^#YqQU83IC`x|*&I^qBb%o~^yXmrZBwH_F96FrXOPpE&D=?!KYc-}4l2V*p@^yFuD=@#t{>*82s` z(l`)(eZrjPCH%o(A6J2=u)#ySVS~mc2FWx0xFRFZXw9W^2>KmeqWa}flgR*2am|1D z`&Tz+egyyn~Sz*QfRA>y9{YEyu_7-hTV2Tl5 zEL{B=4B6QqqQHNfJs$hRUZPtkiTe$~Y3It#CL1_ie|(N2jD+c~Pbvi6f!-`IjbyGc z>s;e(_S;C2`yA{}alANb>N(6YFd%#yK97d+?A`aA)pwkpdyx!{TFD}>tOq`x8rG~6 zPwD<^FQ%&W8?4!J;&~s&zIzsZ%Cj}}h|>ps_Jxf~d^1nO=!mHAfI2csgNQNre@-re z6eB)GX;t=q9n&cQ>FRQ7&UE_j8vz3BC4YbW>PHMw?@?`IV=)7;>G}FE6Gb6ct=}x$@s=v zYk>ADCBb3oOPH0(AE3X7KwEIsBA;yqc12sMI6*pO76BRuQScawEOgTMai8#Xw4$aP zRv0I)q#6o>KsrcX3WpqEGGlSkZPl~FUda;|aLJg@1u3WI8evh2rs2@aS@K?V)_I>< zFMDmg9N&m07fPtF=NaGF%;=0Qb_TL3MNAFVq!)?3q)Y6}w z&nNwNd3cPy&nM+Ox>T*zR9hN82sccriPQndkX>9Hde=xqigg@yi*)S&T%)P{c==PA z^QKF56Cr8NZ!CWhbq|tYce~L}u`}K=KfADfq8G{rq-kOpXW_-Ihid5Jmf|~_c1T^0 zuE`h`TJ3pfNB~4rL;RR7g}ckL!-eE28>My9^&$%1Xam^dJXcR6fZe$P{mo=+z-Wb_ zaxqN)>or5IdPMz%hY4?6@4qqxP?(%$f97D67Ak*9FHu%-^2b7-TQj(~>bks3+bdaLx@O0%cdN34<}O=2OY={k`LA~XZsthAX940c zpMDXr{VsaQzb=mr*%5#3k8@Y-Im=i=+0T7+8${ot$hP?k!TE2*qJ=n}P&}gb_xzjB0;bN{KU_@$e&TVqa%~%0MlFwgLGI+Xs#ZBb; zgZ^NAQ1ae?JO!vin5`<>*M8nYb6zBNCK@Rf&Qa(sx(w&9I4ww~aQ;Q*kZsko^yYf~ zV}RUc#KD4ktnd8{$Dys{;)4FNSnk?WJoOA24nFz}ztH2fAb7de0W}~Z^ligS{x(aP$gjY|iP)_JNV(tj4F>)Ws5%H- zSZOY_aCcwHA#bS2LVwFY=5)8aH)pB!QqNnj8c#CFwfb&(n3Z4ztrt1^1FCu>0u$D=fbzDzhDeqy=$nbrDYsK%ae=Q@@VUCzIJ14HiJD9uq~9(>uMMPbae;VbpKpqHi3O9FH;1=YMGSo+fX^*MVaLLOg56u{7J5tg{pFy8TYt3hC5i{f<~wzpIOPQa*Z~G> z7jwHM+{Gy{>#_av^rZd5KsV0YbX?bSPQzyI9lzVL(uHC@Wh?sDUA(Z^&tW}4MM&du1^QLGy|76KCo$KpHe&9S_7qoMDX zy6RMOQUUj265kx)gD$aXEqS+ZWJK@I874;dExGNGM~$8v?SRQG4E{B8Dr!3id&E7! z5s&!(4#Qkx7TcbK3O<5v!@fr+DJyMWMTM74J-;sW(|k@_|NMmPgqE|o*i=nN8K=Hk zOZKZEJiKJlxnQnm&X`aJw+VD=QI!L9Jupv-sYjLyB&~pn->{jfb(ICMco)g(erRy( zdg+A8$Tq1+j|hkMzJ8Bo`PcigB8kQxYXjXd$ffntFw#5z8q+)DA2}5MBfi3T z{eE0d1)>#7Bf)SRfgKK$f$|ry2dMPA7KKUqCt!J^tDYE_jgHG_*@w*rM+aA)bh(#< zlxVDx?RLB$?s~-yKk+Y6@~*51x|c|dIoS+yCb?B`mxbbTi(^}N#U+8>x9l-aAn4eQ#HEk6+%5O-s+|^>C;Btx)G?ggAouh zDk8{rkl{2@x7zpSHBZH(rphp_0=7W9`k}_6|KsAbd&N~k(1C2&NyvZj)Wg8A#o#YK z>;r`b`dhl{4n*mhHToVmZtK@%-0x(To9rM~Lm*qZYZ4_oqZ(SVmkb3QMjTumS!R(X zbt6Gm|HLzj3?M(!Kzu9(tEVm|hG_4{N_xtGbQsOuCY>CQ;0TKpyQ$PbM?s#4*Yub; z$8F5A-xGR~tPPqBW>6)RXcE3y1huJnUJB=sc-dP&X`uit8F}fP#uUaHjU$LDh{6O2 zT{WDY!?P_9YE#4(ufjfQW{Ce9Km{&z06&FZo1Q>*Cr;xqSHDCeQ$lgpn?yabO)If; zlkkjUmGtRp{i{X1K`Q!{^wO{!KlB0gXf0y)W7$wK`mP|WLS#GRHSQ!b3iAUsW|PHb z=Lh3x3g6=KT`~(yrrhTyluQfNWEQu&qcW7ybl1wzHKkQQbqm!mo-`Le00V(pGp+Ze zx~86tK%WX~G_%H9ayvFhA&MNb1#h5S`>R*)QB82(qXfj%RukuR(lY(s-_dKZ9^D%p ziQz8B=>1j-91Uk7N>f00E(iWIS~^F?S^8zJ3p15vV@`I|h>Zi7F+Q+j0$Xrm!Xn&|SY^}c@?$OuTEr7#;&1r3ZE-q<-w5Ug~1^V-c;o~$wwx0?80 z%mhT7P0CZ9TrMCtymUJIGx~sQ1DrG3`Sg-CP%N&6fEXrLrV4r%a)jX48Qo;oX^%a4!4RBlnl@qTe)%nvyX#*t4ABC& z9>-*%DR+`fAQD!(j%F|It!PeBYh>bgvprWOcJ!xZuds+7cg{4@S$d1-K@rGZ zL&IK<%$_J2tp(3Go>!mpq>u>q9iad%m!H8F3q_WSYuW}EEOc_6htM3eR{7tuQWR;L zSJ753T)lYI0@FM4udAC@Nh=$aN(#zSqhX?&;BUb)(94G9qSZB%-+!ziC8ZrLs0UxZ#f%kqZ!pb0w)0&I`@JKux5li=El|sUpfBYj)NDB0 z+ZWsq9r;CbhgP_zA7-&we?k+OMcERr*^tG%^#=zakiWth>gkHLLC^iSf#tz34I0J! z0}_;o+^5a)Vef$>!^S5KHB3Nyti8fuQbY0_ef%Ws`fO!DtYcDC!x7Y96NJ9?Mlw%l z!Jg9zx1mxDd*Uyw#GOfsFQjQO`9IJT1ji zC_YfO$V9hSCOS2h+iP2xf(p3WfPT1T{4=o{}caGqMi< zQxo6%$%Z5bYbz3^Ez5eTByY(grs(9-8Fq#*%~lfl)RL`wLMhR0W9&C;M2nopd;fHr$Gnsc^bq+s8->#hn(-YB%FpfC~armK{LeVzStXI;TS|&1h?X5d0a#hM{s=kZCIvyr^<9 z#wxA)f(OWQ#JpUVI>@PmQasCWy(f{BVg9vJ>ysKPoWpGY)RU%B0LH|_EqpgY<^e%2 z)UfYhArvNtuC5z{V4|RHoE%2z*&Dpg?8lMG@yklJG9|ii1kk4PY5RqNtj8R?C!!iQ z?2UWPMYt(gqodJ86ajxLi64%zg{BNHs|FbIz%4VCZuG$mbtLscsrB7M!2#kamMQUe zBtb#K1l`V9-~-4s`zClv8(pzh=$TJ(TKt>^5X@ci3Q@4+g~-jLdx?X`tsPIXSG`w- zG;_4Wh(4zt>q;0vT#Ljic&GLnJ4ei^UumUjlO=cuY~jYjiG$yi8|fKR*F8py{pTSd z$k#GQI>yyl(2^OAJ0T{U%{2~u>q zkmBPyL{z)=U(0#m&SPl9rh(dsz)4$4Ag~mftaLj4ap<%;S7_V7SI4H{!lxA-J3>P) zlGl!52rpn8K)9U2BwBr?k0y{AmUbmBKXnH>|zvJvdZx~1mW}f=^kbs_O_etvr(g|D<8;oA01G595L%b=*@&AdH zs38CZ@0%YZ`dvMX6IKYCf1!ZH*<@UWr!fl(vn*WkZb^n8=w}a&4BQAghq9bSUasQS zv~V6&@h=GFl4A^^_naYyGq_j6wRQ!wN|d5luG%h#UOm=KNk$&PWBZm6{h>{J6T%{FAv;%(b6xLz?A!A*7$&@X}I zD!!%SmtGPyxGaFg2Krf&Rci+@L&_8wYorSdh%9%;mXT3lZ7?MVpjXk~aCOA!6 z5rWVsZ~l}Fg3!a_f&c?c$qWE5Nm|>=m7Me?V)0~3K~|35LJ~23kYF@VAfLbKIpZ5} zgE4_;Z?ZpgTbsEi)5kiyF=t^e9zjGkDK*gweIgEKZEt&ZfQ;#CLR104di@}JSvDiQ z&^(#OSwVT)Bv!$?7NUk%WDrskX|_l4_NHV-=t4%Ynh1UI<8bP`#7&Z(vt1QyjRSWx zelC?&Zg4r!pmZ3S>{^Y)hWA16cKNFf|4S$TnB^wl7e@c<1)!Qn*}|-`ki`?$Nq!Ui zJ^qXV)?hNo8~W5mrDbV7xs(#g{|H9ADiV3Vibe4#{xmO4YUXf&;ytt7=*zyc&>*Z0 z$XjF?*CftGEHih>E-vB^7nWs{sMrBbf5wM|3dkgsUth%2Kd1Ssj*QU#JIO!9i= zN)U%H@(wpGL!Og9*fN?;##Ei?Dx)P3=r2Lk8# zsVCcLbJT@1!NGdlOfff|1|?lm_Tzgh)@3Ksl5Q;hBsbj_Ai8P^WDbH<%{Pggs=$MZ z5rP=p<~x_8C8Og7r3U>@q51IC8$FDTr*(%joZpp?#D-c*{0mz9_*U^USVI$mYw%nh zVC7Rz?#KwGZfo=o8N%kznWnj3l-ImEwgLu$a_jskV!f zyo!u8jzxLgv0~HqvbT!kE>;IP*43n8;!y4a@>tgp!RXl$H9e>@(|FW(HxAKM`#(3K zB|i)Uwhuz3oW}P?vV_?mCe{dlR!IwB0`3!ln*wY+_UZa1gF;v@(QNuYp4P71?1%q9 z5};+XlhenJgG8xBY(OzUG}mWi(!Bxdy0sZb&2(Y^7PIESG$?#qc1OWT0DTdJmtg8c zF^o_66g2I{ENk*YL4-h^lndqly23{JrLDgwc>AeL5_xgx_x=VF1y~2pU+H~RAw^B6Waf~HJY2M0?>fl zBR*+!5t>&PM*l>SN9drlyt^AQ1T~-)Tr{1sH znMFUrgz%Yg>i9VT7u74x^$f{06fcu~O)sq^jILM<^f&--TL-oO-%VR^9h7O6D-Q+0 zG>D|Za$wS7nAhwXJA>PZq{H|gVE;@mUo8K^gzoH^U+J-{1c1V4e=1z<0Y&D}Q+!?r zTr_s;lJ#1O9<~eZfFj`>R=$AQ0p>szy6SDjGo%jQ(%bj8C%~?Yj+lnyhxi&s{+fc1 zVgoLa*R|z(zs_Rw?x&s#C$R6*kaV9^bnX4C2==k5{_HMZfqACdS%TSoKGZyyGo8ow zC&FQ50ed!QrVa2q{NZ!SgkqvQi>rGUxEP1lmhdLkh2C2?@KpPjmja{4Eeo0|+V=Q>Q#(s!UTB1g^QMbu_H*fk>UzFz(Rn{KS*k zCKnQI$tR0WnX}gd`0LEV2vM7c?rPbui{lk?{~yCt_$tiqQUPuM8KOT+Bz z{|F#z52|Z4!Q0xI*Zj_(R&KnC01Ij`yo7Bw6E&IFWQ_;saAl%zK*5Npt#|R}?fj}| zjfKFK3K8Gm%)i!fwF*2^@?hGemU&9YhcF-M92qZ#n?C zAt0ktAxXGvk@J5UlcuYF9>46uj+8{p1}}|CDS!}TX!MD-<*w=l z^grl)-52tGNTq_2DXt!{_v|`>o-hmuDTYDS|Iqk7<7bBN@vWGni(et{PZNUq`Pxdv zXL6ENT5N3F#aM;E0Qo8*eVmtQE7&@0r$7|-FP4dT)->ouWe?eHu z)h>~E)DQ&c;p!169^<-HIWQLtz`dVYuSQl*JOnR+ZO=uBETV0dSI41&^1ARGlbR%5 zFYw<6ylQT-C*ba?@LW1^5Q)|p4UMm`vtT!WX!!Zw#AZ(YWo38fQeFq20FL%nCKTI( z+Oc+>8WfYdITB*B$`lwo3l~Cmz}PWlP{gZ6(Ze+^3Tx*eigbmzB$O*irIu+KlO@aq zY}=wo2}XmRZT|>8<@K~?ts+sJ_r3H(g3u{K&tP3y;w>voZLi9hVPYx}Aix=_M!P3# zA{FvVC&r;(!WK8Rr4z6GKlWgL4Q}-}KhPK9z@7Ufn4QwV!OpAOg77qY?$!WMO@U0AfnN8m-CCZU{T5YHRAbyw~W&3s!l*Y)?6(HEUtjb696t<3R2_p zZEiNH-_kv7oYtR|I?w)(_=a{}yUaiZnR=d$rTPbWGGsIPn#jQ0VdCfZhuWMf#fC-J zii8!E^bxYqjVLgNF2qZc1ZZ50(a957tfC1VB&wd|>VJul-dQw7FTbbeNC$c0c6nP~&APkqJWvrb$zXLo=TUp~q@RR#VPPne(rybtcl z9Mu3^`+0dc8Iq&V8~^-32&r7U9;Y<`_O8oTLuiA518?o|rK){&A0(c2B%3M;ST0-F zsN(I5PM^D>)0}_NO_T##8#Y08j{H^0JV7UoaCi0d=`u%xlIGw3G1Dc9`D(M@dgPh} zRg=Ux<^eW+h5h?_Pap%)Q?=L_6TM2&39A%ih4Y+w8*LeYKQud7{1c!&4Q@Wb2_H?p zg{JuWDM~5h!awW6gXzk2w)$YnLeQ z5AthRd^zAorv$Kb%(lkZDNhhG)z=`JHC~ee?$Cbg%e0TFyEhV2A+$!Rv@(LYf?v)r z{^qcZhaa;Y+q3jH(0csgZ2s6smiu8`3A-jB)!ld2)o%PZHvoD&PY5m#>_ht+h1ogX z^w2`^|4e_jG?6IL`vN$zXlv!no1xWEb;Re+uUIVJmR$(-XZ?>Y|NjZ8dtaPZuiTIT zZr|G!mY%YzFTgxRKe2^y;(X)Ua+M*;=8PQ5e{73@k@@0%p6ISDkh_3>kC|AT(9Uea zai6p7{PIsVm(J>YGfo6BKMfxeHd7^rzl#LItjdEz!T)kL~e1(9N?nJNIjjmT$f|0(YoPwZSP;ss?wWEUk3??;}ywzyH#`f8V#|X#hMKK-WT(aDNqLNe7p7g~xwT>*;mI_g#7CGZHDr zz}d9&QrT#LhWu^9ID#U939fln>tY#JjAJAt&`ky2WM4@Fnf8H`SK*!^WIX9bl*WUc z9W^gt$E(ml7EM&)vHE7|y|C?$G2s2;K_%jJ1=@mQ^q`*qJP&QnD_3h+IlWCjH8gc^ z=3gE*Gy~l5F*G27Z%h0Lfo5N52Feob)mlJg7Aj*tP8ginlq2#5euy=ZVpzC4kJbZz zADdj#vjm=OiVHU%e+-J4$2^lu2+(edIZyZtkt}410np&i46f1?x83-uDPKNznJbS5 z+bYfd`(eUrR?h8hC_(uM>+es><#8#5J#Osy@gV`ot;kkP*@0dK?6Ujj2MYc~syljf zML%5x)sqRqhi+z$s-dDQQx+lc3)Z{jlcXw|5vq8fhh((DnGnm$e;djZ*!prI;3ozn zYUAH{(ApdMo1dNN-moa*;^SX1%0%s6RtVMP2-MQNlBw|hI#fmfR4fUyS4+Bei@PZ7ZwHIb4!Xhx+Vcq;5h6 z_Z9;2mP84w78lg~D%j5rtq)MHhEAgt;k25`eKH|=zwU?ghY8eNeF^Zxvc?4073I_V zoQoa#={=*46Hd#39q?%IT-Ef&2EN@I&%kC35lCpH;uDcjILlY0*#Rq`F#y~WCEGRX z3Ai}hk);$yYYEmvGTjLHkz$adK<`!Pyffx4DEgni_&e$v}g68XibOSgfbT5}REY2CC7rKt%zA10{r{gEXu7;I z48+9ivkEl&{N~L`$Iv=Cu{OtVjy5LVaZcSYEA853qk3l8KT@J+-hyIQ5NO@ z!{I5W2i%_cGmxNBNL_g}E^+qnKD|7Zyk}chs#lwwxqohH&G1ye^}QlRt)-ndNjolnpF)gJ{<;k zDab_RR2xfE1VH_Q>fW9Lc89!P45mA|^>#x5a*z2Sq`no*!@BetJ5L+k=hmP3{W+8e zomkbUdo2HJP17io-Aq1C(In2S<9sg$FsRf}qlk_0WP@ky+PakaX(;vS)VfmYb4!nd zz=8fSki0$ro9?2kinEmuAvBYnwSb+0?-&r-M!R39%A9-pCl0j!3D%Jk z%nJ7kFZ@}g0t#J_YfW$U@sJMQ3$F4%bT`8#zZgIQSu-Y-%&J+WI>6%9T#f-6_Kyk@X-!ht9>_)rBM7KA-HQP;$x&al zwibVXVLO~dQEdV8Z7RC71$Ei+Q&+r;1CF4(ezn#MxJ@z-zK6jtKsYJIO7phgyykNb zHZprH9gLot0b_bc_^Tg0MdrLF%egz=dfGZ#f31jiT>9fDjVF&JLi?{XVpxth`GYm}VMqZwpwIaZt~4*FQwH`Vo-vFL3@* zO-T(p8gZPU5_oe$sImNQlw1UiA2y7vS1qo-e8yC=P-Qn2pshn2v`odV~4+2yC$I_CIxLcvmLYcoRKMH zwD4+DphDVn__~mkjn+~C>&xPiB1g*-#e+bD+7$wpI|XYjsl{njFP!Pl*Y)^3Oo5+q z>O7Lb_Y~A>(o=7e#_EiM#H5H5n@7~2qwe5_Wszxqqyjc8EcX0vQ2ez;sD;1s{#Dr= zGtD$hQqxj)88S_+_Uj?e3RZi19q~zomSM)+9_@tXAl9PYZ%tQkFtC5;xdl$EB?SV6 z#vm5y2zx6CDYn9I>8KNxl!yaIVRF=tLQ^IrYA!I{oR{?6@DlNJ4^r>Qqw4*ze-Z+3ZoTiSHE)@>$hU-#cB0JRVY7B zK(p&FGN2%hT2myuPY&!=hI~mnW(^6?4A@?IP~mvi68`F!>x~~!J>2kFG$h{}M_i;~ zc)n>9wLkD|qvnmi`KVx&E7hu+l)pCPWA;Q+9xb8*zr#j~Enyu06!ej{w@h}lk5zZq zws|-&E~Ex=oSm36^Fa;hcYOM{UWVimh3QyfuNrg4I-sWl%iEXKZ=hu|CfjNhrIF=L z`}brcm1N>}>wjtVM)MdYhjp$znN|O!9_mWul+x3`3ms?IrF(8C8@bym{I8G*jg$yl z%E66b7wM{*NXuTWM$$SKd>(2Jc8`-;j;qVL#+GFrxI>Lk6?%G*Rw~2qNMORa?tKjg z%lkSdcw{673s_-M%6jbV&Vqq>oi3e@*Uj2{xkfi>Bx@@@>&S0hX#9o)9!Vow=lt1k zXS9T;Osh*P&cle5;PR6mUYuq4YQacff|wBXtDoacMui`RkI{OmvJUv>iS_4McT#V? z%^x~w?-gmX(DdpVkwK;SsdG4TteA<*1I=2{d~IV;p28ZdW@^|UKD&N)-pz{ai!yZ*uD3hrlmhJ7p(=9x12+`b?Ni(~Zl-A?;tJ0Yd85YAjXxTKZMRkG=(G zm-qvdt@0&40f8}5j2yPg+@)KnsE@_|UoJAma!)0LYrpR8;7>p64*bNP4|Q-tJ2-=W zAk|n5X^D*amjUnZyDBPtu-|<@XuHt30WppH>$!V5dYh5D(m>9)xiL5SO;IwwP&DbI z7hv8iq=5~K=P~iq&J8m!-wVp?rLQ|=h|bvwRA)N2Gbg$bul8baqP#PHBU7fmhKmS( z{jG66mq7-6!=zbIGOQ_2(PSYp;J3c`wx-SFz<`k5AgNbReAI>9)XIvU*Lp+&9-#6! zBQx_w*!PDfVlp0)=LE4TS&93Lsp4g#&(Zw!*XBb5ym{%#_y*E24S14UKIojrSJr*Ej0?J`4fk8J3&(bH=8j9JGB#gzxjyEA<2JHbXh&?%&~Z_9B1|WUS+DZs0C67hSM1lpWpm7<3DsWr-GX|)!gk%k<57+T@{$fec}adi zY|aAdp6mRvz=;+|(h`Veb0hoEB6~;hN_1ITzj#|bkzMzJeQIU9<+jjsUL%ms&?I3# zl_;|L%nJOu%;IS|9P!pD%sfHbI(3n?61`DnzjK($ZPhQ&JA*W4LWUuMV#!1lG#|?^ z+eVk)@%Rs)*BuC_hy|i1>=W+@?{ZC#PbMa>1P?dW+o6s}xoH$wEV=c3GG>_E-gQcs z*>ZaQf{L|7WO(+LHWf|`W1sw0-Nrp-mRnj!@dnIEYi-mKJdKt(9B4((~Yy8ShQI-sGxz_};kUWMd3AZ$EQ!GNx(o znKKl9cvv<)yUtI_v=o;w0GvNrfq9kt49lNWty;DppKFWzCUOpn5XC|`b}GOcJf}sX zZyl4$-041b3VwFe*(DC8HDa3wX7ByA`g9O*?+alcAJ>sy6|9{w61l$~Wg zIC_7A*y3j?9qcYUsF$PcR}K^<)ZrqzGbi#Oy*B|*yT-FeWAEs5af{X6Z@Gepm-IS` zox$V_)mt4sD`!oh{s}{pJtq<5d4R$5i?tjGCuU;pKu+AP7fEYpOFu||e7U7})inA@ zr-VlT;U#~X!xh1t87wuqBv?`YfqS}sb%q;1t@8L+@03+0BO<^|qWdFIB_XWy&=4%R zCBK03hX0C~#ndy2o=DOL9 zxkYXDO|7-eU1T&6pC9K=a}}5%R<-_mmPR&3KQ-i(NOI$+f=vA&T1)j#8*r+f%2YlZ z3ri@l#O^b^B<4jEO59g$E^~7lzPz}V+&q&_)kSr+=OvI1w6fx=a`^m?3vQ^d+T)(G z)E#Tevd6>AHLs!mQqJi`UiZ6}(`1r1gJLa3bDraF-jp{cg8;G5d>+8k?lQv<*E17n zvWz47niM@hwKCNQ!u$+R&dIHs;DFWd{<w9k{ z&@$}EbI0_xoh36CGS?nKH`VJ@I>@Yvl;6T3@hSOe>qUKq3cYq9CWw&YyDiOP$MO5! zbKzGO(Te%lTHKNihJEG;vMKxApOWekGwyt(ek~jg-TQLgkt>J}?fY`&R`p!FD)Lh- zSazsiT>0<}dcU@^dc9TLb9HNI{d$XI-m7Z=kJ>!Nj$MSw_~1r1`=Afgpb&T%lcDXwVwt!63FNT+dHGG^NHVh0e8j-o_L=(@gR}oq!1vfD z#W$?l2rAlo3tY0x$N%n+IbS1j8aMpB$9H_Qej?iAA_{HEWxz1H!hv z?G*uu0d__PxcxboP8C@y$;Ygn0jsA{XHh?W%#G69j^rg}oWsQOZYgr6!}ou^0KHRN zGs}cTVY}!~v+8RRm~yt!+$7Xe_@3eHz6B}>;q6b)!3M~=Pv6A*e((BK>Xp%&Jx%~_ z%sPrxyR3OOntEyd7*0-U&6gMi^eM2d+}EJHdJ>D%6x?ql2K9rXFOZJd(-|_g2~wCv zfiL^7wlN&_j20-hA*?3M2(NF%2}y-SFohLlvGrP&C!t9FM!nY#wFnB^4s-9_o;{9h z7k24-Kmm%jFpbO%#c%)SKI?TKVOi>Qq!~Nv&fVfn9uoOwEy*v}J)JEs8*(De3`Nb3 zOBwMGm4+>`0?W0EhMkvxGM%g~C3ee8@ZZ*d6~8ptzXuUNwG?9Gh&>YE<>!>qe-Sih zO6d!Sg}Bi1DAHo0XpHuOBLOMYee=M%T44|-xL@rUuH-|Kqo#vt%nZ=AT2^Hz*FGdSzfP(!}1R`Y0A>~c2kxP;uw;~>0#_hioU?3TT? z%d|%@wt*RZr&fC)zwCcy4E!v)AJA0ne$yUMw)JLKU%K&AYU#M6?r?>c-3`$Sh`tCF z?NYjR_weBG-G~vm1PB{mzd78iUl?)mFNgVmEd2Ev?~v?dq}i=3(F(vysC%9QzuvfV zy~?Uh?R?y1t$&OgFSg%cruiT<=d$KBSa|(bG*VRdxu))|`J{b)1v;n4 zuAJ~^DnQ*bT0MiFp?j7NQ$&?SsurbE&s6y&pjF7UHg`(_?=E!6+}D^YHwCRZN)~8# zH(O@hFTvAPj`sGZy)OjSUahID!lB*JVWvPiebOuzbsw^|l2Pnk6rvoD)mqsA#k<5# zZ}#>~TBBGEjG%grB)h#5nBDGj3$xLgfxE!q+RLQ*Z%S>2+jmWNOq_3mClt=khs!_)q*37kC15!p~WTKX`A4Z$uBMZ* zX8g;-Hq`ISh%lt0Y3Bk9>o5mFN)VSA%N=PP86M6UQ+2a*N&qzV|m27->C zJ-A+)&0>eR^J_>f7A@}a^5UoLE1Cu9sfV)!5_(M$ShH0tIHZPFmyDfcCg?*c`*J`_ z1z5^t#o;ei5@@zt-UA0(d`F_7=p7m|F~X92{Z-<509$V(fSUx2@3=_{Sc17yk^dGc z`TL4s?7wjJNbfKh&cafYN(*+ah934M?g;YD=_-t!%U`kp_g1c{ESKU|4aE-nu0h$m z23y5Xv2jZn*-VkF5D))8U=}(;3G?t#M4&+2m->kE#c<#^eF^srH= ziY7-zO_E(#>`>n{Km7Rpi;{d0B5yDbG_in6qj- zlBj$OiiWQUJYy_APKzRpdjQ4Yf|9)XC4U_S+Ais8M4l;!qRabYs9t>u_Q{`v7UYuG zMz1QrbWFAN0BGelKaTk%GmSUc9I3)s@AsPPRh4!Td-mP9KydAHxNG;u@s_Oirc?Sa zo6e$d{zw~fJCgAU9}QBUSgZDPt=A2^b#?F5oPDh%4B)Tcn)tN?*c>3Si&S zDn4qbSy`A^_FQ}33x_6CaBLeYw~t@|DfZaqGt@m)TV}^S`7Wr~&uJ-bbSQ_T>1wa^ zeNr2AtIt4=FEY+_CYR&yF+We@LA!Mdj$qp|=ihCJXvDb+0^;DnAYxQOXF)HjygpGb z)?GFlJwS|fYddN9qXpg}4)&jC|OEDM@O2a!Je%uWo#V1t0#Dw1KR5^!A6o?+M z*l^^q99ar~7OHSpQA}!>w!-Rt0riEVhZHwEG=8-xE;G`?n~f+JMOdUfANB)AI_3&Y zUC4DJPb*ZK(0Gw`TMVN3A;-$^1Zs5;x<2Pl&j6FCMxiv~;=eJI%Du9i3G`xrb}r=? zY2=h{OVyVQe$AUGS%B&U(hl*v z#19CaWwq6;h|{|pYlaNNJ)O~W#EBH;(zjob<7V!*e36X>Uj6JrvoF6I7MQ}xWM)g* zC&`o4!Z@rfdbq(@O$Gi1)Vm6fQNL@i8c^tLSlmlBd(GMLIEMuv*_ zGNg&Li1ONcf>XIGc5vT*jDgo?g*J5>)z25@pfZhTejw`krvYLoaM(GwCMB8<3>&r4#J=+vI}1nv^rLDwavUEEct}!D5l(o< z_-<-S=Napkc#TEITtV1vh#Tk{)%n$NB>FI@&AZMt=UBMgJxVtg8%cIjOU=l&-2Oti zm?K!{;bm_T`Xg#j<)tts96T!CR1$Ocp~qV`*sFEX_#d8#kY=Vtck8lu7U{; zl-Gd2I&%Eq@;!tL{bsy7(lwaq(kW( z0Rcf!85-#v8tHZ@>1OBPF!!T);{ZLr07)Hj571R7@r^m(_*iXpSiY~SDXU3Dw&zqpv}HOTg006>+aq^n-}8YvvsHHMAi@~DBu>>w&0z6NR6N*d?~(fj+lxUST~+Kdesb6SNiem;b+4$ zyjIskqF4>ZT@!(+%IxG57&$_6bm_6S?K{-LeXZ%@u7SZOraQWnmJ=kC=qHud5Tz&W zpLce6xw`pfH-&ualElFo;SX@pi)X8a3~~<0oH-+nV}5fWWb=bCyA;W)ItEzqV$XEU zx}&N$UDBBi9s^^6r)EJou#BBv>SJE~uqIXIz~0cF;XfKozj+dRxU|v=?b&(gUEE@o zVHJ^*ng>6V&GQ8xYfJOaCE&pH$|)n$b^SVjtS?3s4T@A+Z#nd7d#CUrc`fb_uyv<_ zmNQG$@BqL|x-Y3YQdtRKXp1WnsAIWyroM+KLh6(1xumnXFHtBXBw5x1=Mu$zDBo1p zu2li7$iU|dWnFpf8E>@khHfcfX}qm5F>y5(R?GY))}8U*4cJP_Wiu3D@U752+yL%c z!YlhRfp|Y~x^l->l^GlVYH()w=U*LmSL_Mj;C04*Cc;4DFSi@dKQ+tAng z3c01fOEL%=y^`^X=r)zX4syaIZMjjREHQVH4XJ_Q*+7}~CB&YQEXj6eg$1Vqu{R>O zQ2taavIQ0-FILnp1GF_jo3;Vs&`FWvpqzrA)uWsP7t->R8yqd z@FgPz;(mKTR?LJx1L=twNzVGlXJoFA)+b3kWT;&4XTPb-O7?rqfWlofGgPx#~uT3PdUq!$g_k-K~>}xQ1M#p`GD+>W60Y;vS`EP-zdZGR~xFSC#fV#KT(@wVF z@lP-4b&2DYB|0zV_K-pzNw+Wd7mLwFJJ z?M+IznqYc&{(S*W*SGM4r*p#Tx%90-T^iT*G>k@Q0b_7D4d@2leM~RI38{3&bu4g@ zg3?4|Zw^m)iLyt_*O+FkI#Z4ih6MpH!iRAt{!JDCR^`Ip$OSPc1|=QT#+yl_qv}sQfrJf?bwXBfSO52*Hv94;EBN_%Qlt7 zJ&2C*nXQ+^X(IRZ;H!N2A@lQ%Umh|dBO6Jo-z&ztf~1nLdkzl#oDqAszC};6d8Fn5 z$L7E~OCgKzCLXuLFEQ$gQ78{uO4XCV-2a9{FxgwX+H3O`5yAoB^iA_tuho}aD};I~ z38;gVZc6sh?lmsmH`sf)qc{wqUWhU$w;zJ4R}7OKK)o$*f*jZKRx332Y$Zn7Y2q{q zUq$wlByIPHN-I4j<0bI^f_C~+a+r@2EI`K1U_D^446z8~QlnsMC~TfqV=kNKI_?w= z3pPv}a0zhv8yvzFP0^bN1<;1{?Jxh9KPx!(w965iL2QabM3E595&Yhq)_l^zhf6A> zfobdkl+P18RSIJ~OOQ4&PLoEvK<);^C#h|YGX7yQ^2Q7VMws`DT0jwKwzs-^k1sUt z)*IYUoxeIIz7b`c!uwu&EXr9=aNj`hD;9%i9zrPHgG^@BdEmAKS&$mSu!d6>hzGab zIo)p~{mzfVYyK;Hs%`LEkXdPjxoSohkZ5nb%W)1diwW-WFd({;_?etl!1~=;`(Je_ z?U8CZ>R^Lfmngi6@k~H>Yhl6ALW9Zrd&P{Y4BMHk_9O4wS)|A)2=z7hbAr*8%#G0+150G^GcYVZD% z!|I}E4C^`4rDm`9e`T9{tJK#T5GXipnkraA(MGttgjPC)tiWjD!*{*NSjq(R; z@TY)hOjY3Nu+&@=yAaXh8)QYPE?a_Qhr<@iDR0Qn-@uo~G3v*dtK9kVNq>o1!6g-1 zGIt7#De5qQ6Zz-+p~dxizC?Zpd818BRXoY}%#NEHsX0SH&N8<%2SjyC9ZL#VF7(IG zBrHcad((|fbl|;iuMXrf zE)>?N`)`;!@-LX0HdH$d$QUW#2%V^xdA2s-GQO`FUQ9EwU1=pgWPqUW0V&Sz5npq% z#3IQy4^sS?=8&$^`f#8Jn8zH)Y8UkYYzuk*rUpMp8JzZJzIh}+i#-6}&Map4J5_rD zvLTvXm_fHGH%BY;SfXA=_okfaX~i+2I~o*djq9^9J5~X6-gUZO2T|d1U|TD_$AY}w zmt!$Or6K{kCWI{mK-bFG{0vTbuco~%$yDE`zpAo{S9CP;LV$b-AK&FJfTUu#dK&8H zk@7J0*jR`RKs$8}@PxfUKF4LNH;bt#?DAGG4RIeyt^9L-;_zby_%9lD$NfQn;JFn3 zBblb^EtFZa^+53uw+gW;I>SJN1yPdDL%EAq{h413$8v#j$wQQ9KC8b#d~t&`e`~^O znzS^%Hk}CbbBVb=BcoJ)AlUWcTEn=ipJn^p50wCC)-sqSU;rQ+TNO|xQ^;PujSH#- zAYLo9+YS`Z9`IP_hKtLg|M}cjA?NXjZN~`dZH{TOK&-{Eu?+^<7i)5?u*AjJhmXRk z!e|a_`&jIC{*5&$&4N?{SVyFU$f+EH;x5~E7w_nxwK~6FC3E_vj~-`|Mx7#OQg;_O z?V|&qeN8fZz?;GwCNUue|LPXn7ar-}C?pnvK3}{RHP(5AsBF!!hs|W0)B1wr`(2+< zNq1Hs2%>YjDvPVWXwLK$g@thaO!jGun@h0)Rvo~M;PKdan-BIF7k9jN*Q=7*9nlE{ zdQEEjtfzUr82NpO8JPzRj}tvRP=dA-8M+dM_XiBOgb3Ddtv*?O1ScYe8tZUdR$3p) z1WNBk;z|7^SFh(Zt$xNT3V>5!$S|S}wV!aqR>$!yeVe>9DqZq6M6n)cP&2JTvesbk zD;a?DKW*tfAzF*XnGB^1#pD$%+JyBMYB1-2hT-#lTYb}i_z{TOiwW6yV}jirS6IH< zmZthR#glzq4bY?zKl)0+wi41!>)glWWpJjWI+H->tUXen^Ne9f`-z^9PYjutZA+f5 z@`eN1U~$_EYF6B)-=}CA3_DcA`kO>$KG8M)}(83KS*W`T1%2@iK z;U6R_aYLW#B6NyzNb%~i$_dq676=!dtDJ}D8s!FXbTg-g6sMAMZw&U5%5STV?X zp!Z}HEB@BC&?v?i`Wx68X@r3yzfaVOm_-NDdbH7Cf%QlD%;XdL6cr?TU#HvnsneBD z#8)!`j%v{4RpA)mMKLZ`QH#nd*?&k=0scd{!V|7XyrkQ(rOaAJxiBr0hqu_K$ ztvCmAL>97?8+M79y~L<(ajGL($JnrSZpYJ3q{MR&cYhRPiq_IL=MMSlQoZ#)6S7aI z*{);Gtzj!9r)>bB9b24oe}1G@b`Pq5TPC$6`-U?bxC`qGsJEIMAHcR_+a_}+FW~;R zKEtlP;YZdr5|vgpqJ{R3P`!KQnTI;C(PGY@3|$BZia5MM+CxsH%Ju+tbY@>0Z zD=_&%OXZO}eHABi31Tw+Kz_y_Y+Nxvj!-nDDuXwf^;v@^Z=xV66V-i@-x{b(S*(wt9(EfN}Th&)$;Z>AK5Q~F=q+W6=QFc8sd}Ff14F>-@m9f4Hhgbd|Er9EmFP`rZ3vO# za(ei{2yFNLBB5{I4xCw>IALL*IX@1;v5R>?d?)&lP)57jJwU1s3)`wcKG=>6v*VWG zWEbg`Oo_I$DCA0>)*q-d>l3D~8`ocDd(Dn+hg;u-|M3-?F*M!2Qs6EV0gXoY6)kKHN*nz&_e%GWjf})c96? z@nFoibw50cf|-N0_*aMF>(-C~8Tf+knQ55$3@ZHCYPExnJ=XY!)46z=a%I<_$xG|z z87%1zLgE2OW}9d0>hoOXK?Y`ZtZpgH2h*xvf$?Ul=e1+$wJbCE*Xkt#)Xhofpf zqTpN@>~)pznbp~7wbr;xRPM*;U%XxgHBlc%m&~tEK41Q~oP0MnCK*!!mLDRwlo-&- zzHLh)lOQ3Ce#s-8kdgLY>N|3rwfiIJEmu@1D_1B)p0up|bg()T-x%vZxa4KKmKdVi zEeFCsL2{eYAPwA_e zj@tg+B&P?L_1^qndy6^%wW^Bn50+fwN^A(6X?i;PU**U@JoDQi-A7whhni4)yS$-W zCK0;Q+C}dA73Piqi+-jZc~9nq^lwIHJy*!S5;oxOIFcAyo(eyDYsufCBn(sv1({KU zrk%#D8JgxS3{MC>#vIeVobyvkq!Xp_$Z33^TQ*U9C<4vCgP1#NCxqcgk~sQ2)W_8Z z_nC|u&>z#Pc7Gs!?^NU})K*o2=hFr8E$>XE2(Mp&#$-N8?Dr8fb!zDJ^q`$sH#80h?hiM_C=hq_V2E z?OjZBuRw`uY0n3~GD=_+$v0=l&IXP${gOk|S&t9ENfT^UI`F*$j6z|l7hZL`+tYn) zcQTm-x7#@pimLV!C+V(rme(>mes?SrOUqut8KS)iJVH??W?fQqVhP59`v(j1jRoyi zKREsz90q+t4v+#zQxrVXvxwLYi+^~lkSBvxrl@q0Kp3rEDwN=VW3Z88s-(JH=E#4| zx~=;&8egEhPbY=ggftfWZckt3mPT@jFGH&64a@++d}}xrJg^BOTc-NZBnfEtJyv0k zHh#l$HmTn!Y;q~Z135TUI#CUVqXznWQraFGT|p_B|7YvFjjc|h}B7lZOzr-`g5OR<8t|Q z316x^3&()y|K*usTFIQ`_p%8=cFhs3WN|`HtUYWV^0fK-@sIELaxa8L%Ze^dWTMsi zLFND&brkrvr4|VEzft#sLfs9kWP<4gm^$uz%X&>OJDn-ln=|(GO{M|hUO?3thUOYx z02_I>9jEl)Ij14V!lFJR_DcbEVA#gF*Y~epm;BO# znuE1^bCn_vUj^n3FXF|9uQcP^?0R88^Z0Oox3QAw0^L#)JA9|gMq`91{P+Rfju|qL zWfB=e^^Qp~M?29X%$)y3WI*E<(jT8cWY=(lI+yf{2b36deJICa4e)e*ig_9I9fnW; zvhPk@lcxHQ9F+_0V&0Nj1Ts`(%Li}-NXR#RZr2(al;iD3xK2CCH>PMbmo>6x{Aiwf z>t2Rj#P3){+r|c^{s)7Abe9^Uwi6N{pK*jo9DUrTNHO0_?n#Xs3^X$RB$3V`sFuj2 z%)42wzBYd%;<|&ee5O`v_EwfpN_`MrkpX+(PQ0Dgo%{6m1sd_H&l*~f0Cq-mM40~# zO>cW&3CqQ0J*(-YbNp2v_(pKVVnw%*qhW~hJj;Lb%j(?uG70XdAkawcb(o#o8PLpF6^SaOUo$-r=m$%nf9x zBN&U1r)ela;Zc+8B!)N@!&mJ1g{(bgb8o#DV=NeWuo|>#Xn|X$p6Io+^Vp8;gQudJ z!Jaf0jJJ&Ejj^3392jUDOmRTLIZT0qE9^USSMI|KD3&NaU7Sw z^tULsC>73P9kark74X`%_mVN%;4W$4%3t#bWtw6iGyA#O-|idL!r8QfWlJH`mchLH zSzHu_ufH3w?Lcsg^JJ^ z_h&&7SAuyk`h>16J*RODm~k-=Z|p;-yVXOnCuC)8nOO7kevijDXnO-5v9uv|f2-v$ zFb`Lk_V9(0DbGS`sCjU3)a@>^5DL?j)Tc#UH`pE7bpne zHyB}(KfR^&o@?6S@f7rTjX^*Dr;f3e%jLt(_;%ZObv(Lem_prfBiX(+){hw>>;C~4 z6||Km8x3*p>!T;pwkc3tqfZe1cTa(lDz$HAG7C>G&Ip|{_>U~`RS(KW7%m$5p9DUeK{W6e0e%;O!sJT3q z06dIG+w-v7RNLj0gB7_4_zVtjM>Hh(@mG&hG5u}bxJmfk4sh#wM}peZ zYbLNw#93$njrs>yQAcTg`FKdo{K}7olHCB)e{?XN9Ca(AtWO_9K%a0#@vdu_6EDG0 z(xvSy`RWbeTCvBz^PnWN}X~mmgN~vF&C1G*#2u|CVs{b9F`?$ z87Ee^@o}Sktx7m}$$P#3cL)W#QLcRWoic&y$wtaekvp|^Td_oM&BiLxADQkz!CEnB z3CKOpc6r+#zYe1b_wVlSWSi^RNEGTI{?Th<4{@!uIZru2WyfDq0mNj7STA-MZzB&b zN1g|M6vmcby>@Zg-tD2v1o#T&@Qw*pFq=$KGc{Xni6=o-ZI0GG#-a8RxA8+Q%V@%f zn{3#Sv77;wh^Nu+@oHqwHS%5tJUsl+^2rFXbK19Rt}| zyZuJg0!Wi;fuWkw!@R$8G45&X{qOq!#Ysh*GD)cd{+6Py1XZ35Tn*e2wnya`oHXqU z+t2os>b-lDlV6JMzX<%mHMUE|!B_S^#GkH&TNsF6mVe90)EFUius2OI*Ao6YbyVYi z2%r@^Dy%mH%3fY89$e`^U1%%go&_(=>_{t=^7iIdOg6dP6E-10MI!+Ho%ac9Q@=GLVi=z zHflMsyk&twAsP)YB>~DtY<2``TqoZ+;Zq|aHUAUiVTb76`Jb}-x$7%o!A(NogQ@bF zT>XZZz}X2n1)!d|ebfa=oE?0L0mOhmZw3>W@ZZN3uTmxV^{||2!X>pl@}5)87)AV{ zk-xZ8_Lw8-thu9IOPygW_?>d3v_Yj}lib<`en;Q}#&>9Sh#0dRH`pt;ete&G6#{Ik zA^Ai~b)P`oM*?Mi;sbZFba$QIegvjd&ZjIU-4JAf6L_0y5niT5+3HMWMb2;LGbpMs4Bqy$_%*AZV6VgrUDLGa~P382|}M*NVwLmRS*2ggUPk;U-XXhTjk+n|aP1yiM- zBcYB}vpRb%#;1G<@4lHb{n1DiAgfo+J1|pI>L}QMXk~5xYEN$~_tnxY^>K=tCI#!3 zr?+guVnVe=0^sEH1Ccad?JdV2eELf>_TNeH2MAm$*l6#{GB@^yg5hUhMC-$`pdr%| zf(w&O+2^{My2&wz?AThs4XAMM<(S+BR0rH!G8f=gM@6xhni0IGVshHqz}o2h9&s$@ zQ9=uZ(NfIyVb5*aVi(<3?#4A(eQjwwU|MwM z$db*7rZ1o-@kBxT1j_1Xy?bPO?kZBK^oU%5@kOayH7F6Z&`HL=j98*L>9l1eZ6Vq& zucmM5?QPk^e)aZ23!sVrbl6{-3O|OJNR?H>B`U22du{YiZ@rgbd@F=4CVWFaW?T6l z^@99bDt7<^*kpC)?AXvbLpdjcFnOaZvls@ zVmf|jm17Y}?!#-RBS|!J#`N z`~?edc8*i4nI3nDgV9hLzu?n>q6X3x3<=!oomwg>k`Qi1!HBY@4khd&AF$#P(xX<4 zpwzwhq8QFpBq5Rjc5U7)TzUI-*{n~{fQfpid656Zsi$`*RCnpsS_ED23P#Lx_+8A_ z-j=&Uk~j5^){J4T>gFt&Ss>5Sk1dVSuwy~C<;n``@F_FY{2^#4I1@9D0sSx#&u!b@z46V@vZ@h27d`DO&1rJ#NxWc&~t8CvU#++u}wQ5`*f9 zsaWKKR^-l8M+so>U2!ts&q6H{$N0u^$u+Ku_nFiQreS(*yawD^{`)&(Bl!~(6Q331 z?=Af*=hdEB_i-E9WC}W>Sg3dTWwXN30?^#VJHYV*+e-K;;WL%yqsDG+Xs#$rt*st&sCr>fH9`obA%W`Y#F$NU? ze$$WhUsim;RZmH*k?iuy30r3&mp~3|_S60m0X7Uc6DSC%@NOzpouO4nXwJnER^eas zKJWqs$wlN*e`JV(ax3gddpe}u=4=4exfsA(>HGG^+Yaqi2YG-|`? znn#D~+}DtWP&E-Ns8sd8+8=pzj_sbKkT5n zmuzU(X8~oY5ezu&Y`@&SEXi_CCKj}d2|PDO5B_+-@gb0F<$RwWde|IyY7yU(NM{YL zQ1W?_9CtCcWsm>@!hpx+Zi|3G$JJp`aI-$Sp5aD)vU#w03EKajz2q+Nm=_7#;=m72 zO;nqfL}g6*y+?BcA8(GV93p>Zs&qGjr)=mha4+YhK)W3R!^*GuaA(;JQ%-E)w&%5? zp6kNSrr-R@ucW~mg%aGsG?Ll0EUhpN1w_vZiq3Ip((jhGs~!c1EMWH9+S|i$OFoyI z@!u}t{Tw~>`Oqqs`&Q5=^8jO!@x7Af!d*UvQtM%hIjmvv3j5F9nHpQo%X{bkrzrpS ztnGm4q@8=Rxz`*FVVkD89mb>Uiwho1KfMEf2QcrE*f90_+Gg7}cGzkeW*N0PQ!0C< zf(Po$TY=^gLm^aekm;X7s}Aoa=T;lOfJ152aIijm5)=)0wjE#be6qr%#BM_~vwHhv zZ$?*&`GAOxrq4PX-E*h%SdZiKqW$)fLO^l#(WzO;pix_fxn}|JjzEFtGJO0zu zAfWDT)X_C)b79kbDXZ=K(Z$1p^Lc{Pgl1m>A|g&Ode#qUg#4KBGsDTNko!Kc(gIc7 z60>#VnkpN954^uR*lEv5BudcmPx{f`E?_!%n%qjS#KUwcl?qc)Onn42d7$)7QJ;02 z1PLvvVPGK}X z(WXIi)^>R0OQ@|!nd2GcO5X(*8|BCEiJMvD#CD8i^h22p>QCdU& z=X`+XJK)0nk6!=kak|;K{cQge9R6>=iAcYsHR=d{ftbqV meZb&{n>+u1d^w!_L$LL<)X5JoW&jKLQkGYjtB|pH{eJ*XPXNpS literal 0 HcmV?d00001 diff --git a/doc/html/_me4_button_8h_source.html b/doc/html/_me4_button_8h_source.html new file mode 100644 index 00000000..163135e7 --- /dev/null +++ b/doc/html/_me4_button_8h_source.html @@ -0,0 +1,180 @@ + + + + + + + +MakeBlock Drive Updated: src/Me4Button.h Source File + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Me4Button.h
+
+
+Go to the documentation of this file.
1
+
39/* Define to prevent recursive inclusion -------------------------------------*/
+
40#ifndef Me4Button_H
+
41#define Me4Button_H
+
42
+
43/* Includes ------------------------------------------------------------------*/
+
44#include <stdint.h>
+
45#include <stdbool.h>
+
46#include <Arduino.h>
+
47#include "MeConfig.h"
+
48
+
49#ifdef ME_PORT_DEFINED
+
50#include "MePort.h"
+
51#endif // ME_PORT_DEFINED
+
52
+
53/* Exported macro ------------------------------------------------------------*/
+
54#define KEY_NULL (0)
+
55#define KEY_1 (1)
+
56#define KEY_2 (2)
+
57#define KEY_3 (3)
+
58#define KEY_4 (4)
+
59
+
60#define KEY_NULL_VALUE (962) // 1023*((5-0.3)/5)
+
61#define KEY_1_VALUE (0)
+
62#define KEY_2_VALUE (481) // 962/2
+
63#define KEY_3_VALUE (641) // 962*2/3
+
64#define KEY_4_VALUE (721) // 962*3/4
+
65
+
66#define DEBOUNCED_INTERVAL (8)
+
67// If you want key response faster, you can set DEBOUNCED_INTERVAL to a
+
68// smaller number.
+
69
+
70#define FALSE (0)
+
71#define TRUE (1)
+
72
+
78#ifndef ME_PORT_DEFINED
+
79class Me4Button
+
80#else // !ME_PORT_DEFINED
+
+
81class Me4Button : public MePort
+
82#endif // !ME_PORT_DEFINED
+
83{
+
84public:
+
85#ifdef ME_PORT_DEFINED
+
92 Me4Button(void);
+
93
+
100 Me4Button(uint8_t port);
+
101#else // ME_PORT_DEFINED
+
107 Me4Button(uint8_t port);
+
108#endif // ME_PORT_DEFINED
+
123 void setpin(uint8_t port);
+
124
+
139 uint8_t pressed(void);
+
140private:
+
141 volatile unsigned long previous_time;
+
142 volatile unsigned long key_debounced_count;
+
143 volatile unsigned long key_match_count;
+
144 volatile unsigned long key_debounced_value;
+
145 volatile int16_t Pre_Button_Value;
+
146 volatile uint8_t _KeyPin;
+
147};
+
+
148#endif // Me4Button_H
+
Configuration file of library.
+
Header for MePort.cpp module.
+
Driver for Me 4 Button module.
Definition Me4Button.h:83
+
Me4Button(void)
Definition Me4Button.cpp:54
+
uint8_t pressed(void)
Definition Me4Button.cpp:121
+
Port Mapping for RJ25.
Definition MePort.h:128
+
+
+ + + + diff --git a/doc/html/_me4_button_test_8ino-example.html b/doc/html/_me4_button_test_8ino-example.html new file mode 100644 index 00000000..c603aad6 --- /dev/null +++ b/doc/html/_me4_button_test_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: Me4ButtonTest.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Me4ButtonTest.ino
+
+
+
+
+ + + + diff --git a/doc/html/_me7_segment_display_8cpp.html b/doc/html/_me7_segment_display_8cpp.html new file mode 100644 index 00000000..ea91e50b --- /dev/null +++ b/doc/html/_me7_segment_display_8cpp.html @@ -0,0 +1,241 @@ + + + + + + + +MakeBlock Drive Updated: src/Me7SegmentDisplay.cpp File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
Me7SegmentDisplay.cpp File Reference
+
+
+ +

Driver for Me 7 Segment Serial Display module. +More...

+
#include "Me7SegmentDisplay.h"
+
+Include dependency graph for Me7SegmentDisplay.cpp:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+ + + +

+Variables

const uint8_t TubeTab[] PROGMEM
 
+

Detailed Description

+

Driver for Me 7 Segment Serial Display module.

+
Author
Frankie.Chu, MakeBlock
+
Version
V1.0.5
+
Date
2016/07/27
+
Copyright
This software is Copyright (C), 2012-2018, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
Driver for Me 7 Segment Serial Display module.
+
Method List:
+
    +
  1. void Me7SegmentDisplay::init(void);
  2. +
  3. void Me7SegmentDisplay::set(uint8_t brightness, uint8_t SetData, uint8_t SetAddr);
  4. +
  5. void Me7SegmentDisplay::reset(uint8_t port);
  6. +
  7. void Me7SegmentDisplay::setpin(uint8_t dataPin, uint8_t clkPin);
  8. +
  9. void Me7SegmentDisplay::write(uint8_t SegData[]);
  10. +
  11. void Me7SegmentDisplay::write(uint8_t BitAddr, uint8_t SegData);
  12. +
  13. void Me7SegmentDisplay::display(uint16_t value);
  14. +
  15. void Me7SegmentDisplay::display(int16_t value);
  16. +
  17. void Me7SegmentDisplay::display(float value);
  18. +
  19. void Me7SegmentDisplay::display(long value);
  20. +
  21. int16_t Me7SegmentDisplay::checkNum(float v,int16_t b);
  22. +
  23. void Me7SegmentDisplay::display(double value, uint8_t digits);
  24. +
  25. void Me7SegmentDisplay::display(uint8_t DispData[]);
  26. +
  27. void Me7SegmentDisplay::display(uint8_t BitAddr, uint8_t DispData);
  28. +
  29. void Me7SegmentDisplay::display(uint8_t BitAddr, uint8_t DispData, uint8_t point_on);
  30. +
  31. void Me7SegmentDisplay::clearDisplay(void);
  32. +
  33. void Me7SegmentDisplay::setBrightness(uint8_t brightness);
  34. +
  35. void Me7SegmentDisplay::coding(uint8_t DispData[]);
  36. +
  37. uint8_t Me7SegmentDisplay::coding(uint8_t DispData);
  38. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+makeblock        2013/08/08     0.0.1            According to hardware differences, initial revision                     
+Mark Yan         2015/07/24     1.0.0            Rebuild the old lib.
+Rafael Lee       2015/09/02     1.0.1            Added some comments and macros. Some bug fixed in coding function.
+Mark Yan         2015/10/29     1.0.2            fix issue when display negative data.
+Mark Yan         2015/11/09     1.0.3            fix some comments error.
+Mark Yan         2015/11/12     1.0.4            fix driver API.
+Mark Yan         2016/07/27     1.0.5            add display to support long type.
+
+

Variable Documentation

+ +

◆ PROGMEM

+ +
+
+ + + + +
const uint8_t TubeTab [] PROGMEM
+
+Initial value:
=
+
{
+
0x3f, 0x06, 0x5b, 0x4f, 0x66, 0x6d, 0x7d, 0x07, 0x7f, 0x6f,
+
0x77, 0x7c, 0x39, 0x5e, 0x79, 0x71,
+
0xbf, 0x86, 0xdb, 0xcf, 0xe6, 0xed, 0xfd, 0x87, 0xff, 0xef,
+
0xf7, 0xfc, 0xb9, 0xde, 0xf9, 0xf1,
+
0, 0x40
+
}
+
+
+
+
+
+ + + + diff --git a/doc/html/_me7_segment_display_8cpp__incl.map b/doc/html/_me7_segment_display_8cpp__incl.map new file mode 100644 index 00000000..75f13f8e --- /dev/null +++ b/doc/html/_me7_segment_display_8cpp__incl.map @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me7_segment_display_8cpp__incl.md5 b/doc/html/_me7_segment_display_8cpp__incl.md5 new file mode 100644 index 00000000..a5f395eb --- /dev/null +++ b/doc/html/_me7_segment_display_8cpp__incl.md5 @@ -0,0 +1 @@ +19e40702f930d46c9a5a90cad6f072d0 \ No newline at end of file diff --git a/doc/html/_me7_segment_display_8cpp__incl.png b/doc/html/_me7_segment_display_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..47438ec41d02c39435847c5b02cfd045d7fdbc4f GIT binary patch literal 48305 zcmeFYg;P~w+dfK3he${xCEeYKq_niOba&^Ll#~YP?rsp+f;4Q9knY&h-Qih?@Athk z=bSmeKj188U}nu)>!~}g`?_vED=SK4pc0|Nz`$V0%1FG2fkE(wfq_j!Mg;DtF{cj! ze-J;)NlU=|dHl(4FN%kOc?BaY@kY%feQ(jzC*8E=&++KF{CI-+L~XbXnwoZNwKlHu z4^`W={D`%<+}atl@#@c?oM5n6j+;M~?_kTs*9Qa?HjB->j3*iNJX0nXvw*8j7-x9( zX{?r8VXMW@e>gwni*UTqz{ag#`_>d>nDf$CVO)G`{I)wB!*(U54BS)8e!W8}At5CY zEKCVp@D?{`+bYSgIOukEck@`@NJxx-diwC=6k>-}W~d$?1Fkqp+>5Y(mkIXM+mH9P zC5&SJ-Il@s@5f!vT7mmANdmj&b`}NQ?ZRzyT894^pci(o#=a=xb6-J zb)Q>PQ&PT7?jm~}6g#_4Ij8PtEBdteT4GoIe0*eI`q%(+_s@t8MgYi*<=eTJu3(YtN6u!JB>S`oc%v)35Y!Ul#sB4MyZDO5B{NnfMN=#qH6{$|7TQDQ4jkRSAg@k&3;??IX->-KChA zbhP}bgNeIsxo_FJxf(bxa>rhRueiwbz7qrO%eSe{AP z?}43^?_WMM3+Yvm5L&3%ycwLlRGcr8kf6qSItO$L_!{mqQSSOFb>a5e1Mab0)PbAZ z_6SM>9PHS=d|Tbe!+9&=FS2my5}{;&JArPpGNumy8W$cRQW?CB^U3qA2pR>f} zt^uZ|j3fP@p+_{bL31Zl(~g3IN#FK&+lboso$vYAzKI$nA87nKgWmppxOe51vhP6L z-#t+J&zd7zVIEJq1`GVh;`~_glB)03oAMDtEjKui<5C+={;KY~4cvv3q!Did)a*SILCx`Wq z{d?_kiT|(m_uuB4(Mtn7$`O$1wNp|o2l!1aw$xvJRLuYx~VGf(b*LR~7B<50RFwy)eAY;A&L4H`9Vy5~_=?~>$Vg0Xu{NFC^>irz1R{xxe8Fm_vD9^`jq4gz&B>Rc0OBJl?bU&%Fjx z*#np^%q*_1Bq2ZHX1vc~VG?prQ54;}2~xAqhjM!MS@+M+Pjz0i=-xDOUBH(pbN_u& znAdMhYL7YQjeL>A=dga6{D1e`*<#uPc$ZGHYm9Hp$|DOYfgykYXASnV=<`OsRUk8% z$gLFTzLRGcX7!1{xacBJI~Ip0-i$%Z>r2ZUG*8JQ3xt^$sNRnYpk|aO>G=Tnek3JI z^Yumz%UayyTymbqtQEgTx29tsE0Oix-9=}%`_BVGt-i~GZx5vP3>WHVU`@cUPt^e}z z6C7qCZI{>AzpMquFI-9WCKj9Dsw*wYDRtNhr_xRs{HOg-u}{d$wz_%?8>{RC}5Hk{VBXsW4(S!U_5O~;D0ihZ^ypzKKY?ldi0XL z`Fed;9jyRSC-12nkC~>ii(6+|4KV-uC^_J_3BvC7Mft^CsI2hp_|%2p?Xvs%+%Kr0 zx2@*6yNj*${{3vyRI;bHpp?NbA&bs7@WzUT>0=<1NwOmDKjVh^z2jQ(U3OQUemUJIc3`=LPm`sNIBygk5kth(;|?JE&3_}Hp=qS~ zdiVG58~HQ*zp0<`uSrT(ci2hq>}j1eRvlXHHIAM`!%iP;igxTw6_mVpTwH8#FQ*p? z+OLV|V1Ty{p3ZTAW04!}z>;%Sp6l5G3)}X@66G(F z%GtM1x!+{0L^KMB72uzPkFW%r&?Qx1gh9u(>6tvRXvTl;@nV+9#AMCabaz@xLIN?g z(GhT}zt{g6M%sGxhW_V`|8i#WZh!LvyT^gu3^A*#--zA%>WC&{RpF{djJwzjy8T_7 zK{vJN$$1;0{|Y16c#BIbQaa7q(*|(v*i>;z2@|$$uD`jGVtDcJnPOCHwEXca-rnN~ z^O`@gSr@$eR_Hq&Zm!bP!4o2$=%J7sr@aAJ&1 zBT-Jx>oMF+56DY`TL{+AyREu!7hT;K+ZY=_8nJd_PxgoKUEzHzaFFTvRr&w z(83w;=;B@H`pETBXh*91w=UW3HoCWM_ELOU*jbjwUjW&kO(%Ob3~rvwpjv1ap~JUP!iz04p{==b5> zg6)ID6hbI>*1Ftr^K0?}?eC4G=)}p_Q>!`_HggUbGW4>854MLgIW3Sg6wJ5;xDfb- z-t$k?iWuTx6JkF3SAW2VZ-ZE9&R3XiV_bmERUF-l47(mg~Cm{^;t zHJziXtBcxe@j8?^LJ2WBN9bTM;q-Z%M~yNFcNx&iJF3=`%a7raQ$Mmz37<3es(@$C zXjs=vj*7SuC_@#dIBiv5FJ%E65cw2o2%kgC&xGB#98er6j;N0kOU30}+PKgwxXBjXapi>DCrsfzOr z8g>H1!KVdCWy9wEH0DzCPbgwPeSol1QrZ_h#c2+P_J-mg8HZm4?$77vn@;0_j5#}N zy@t|>a3#{KS&F*%wF6R7UF5vED-1nUNdGN`t%&V_euM~Fw42=eQCyK?s>8t#<4=~&;hZuI?^bgzG$aw<;T%+4k&Q$|n-B&?_G&hsYH8-=goWk*%X5B=+WVnt zj(BX-Ml}3BC2bR@MyTOP9;mT0D{0sY9gT0W+W6TJSHkT(V%{RFx0VP?);$ zcE9idc5vWUId!Ok8l+YlsV;Mkh@4v_>utA-ss&a`93}`8>7y7LB8kV31Ju@_1+D(_aQ+LmLTj}d&gOB0Lr=a_b`cnxZmnI&VBweLGcE)YrXFsx zd0(OUj}SGbV6llkQHn9Thq@OQd2gs7y<-+Wu7WX`!O!I+@{9frm^^o}3HxB>U}Tze z-@$AAcX)G*>P2`n&Cy14q+E?);h*#sr*Flf>xkq?A_!c9<($Q{*iKMoG{3nW8=5bK zstdDGie7NG^HS@Nfa}L*MA)~erx>uUJc~H0(9z!_#(xw-xV&R&klBb&bJq?_O~TW( zq3m)h?`KJ@ z)r*{*>zF;enfuC73yG=dvjJA}N>N2EM&|qpDh|_t8d~bo_ie+r=rF8wuh0;{%S{Di z&Uu*du(#2kpiQmZ_J^!J*-Avz+wtV03Xd-6*P4Y4?g1f@I-8LFeuozOylQg`LGyyc z*@SMN_urLZzt~{-NkNaxvLMydlq@v{gFGIUo&83nB-s84&tXQuI0P8@<1<8X?Yn+t z%&bjpb32mMY5&j|L>KA}rM?c~hpr0!b}({{z0avyPprHcZFP+QzK^tp&6;JzoLb(* ziRv8^1qC^UAeK`aQx-NagAMhZWTWrdLx7*BI#r zuubw;IJXPTdf`(V|RX6!OV)o1^wpX09@BYwf5<89`$`Sm^NvU`n7mn*iNLS{n{VKzou z=57QZnwR>ZdmD?SL1OXa$=}4SXvTEjW~VmNx0Xs$qy8Hv>@hJ8(RJ8CJTbAfz`^Qu z`!V;VP0hW=*VnpOOkH#p4Ap5I%63_Fdjt9ft|G!goFmsH)h{8w_zup^f%Bp3pY>B+ z9%DUy@8m1PcgU*n=HW%rq06Ga14ACAFTZH-OtTI20%7HvZWlim^i)Mr58+K;72o+l zU>~LbkkQf7&D~KY7iyz~$B*RW( zrX+ldzSI#tyFMZm(;xS+?)X?^4o!AEcAug>D=6MUv4o+vjg#HZpKgy(dr;#_WI$IW z(2)p&0i_0z&ZfSXyFaoA3g5r%z?=(wCUTc8BC3j@|aQla%g)> zsYGp}xEGPS5t`RV0|Z6H>98c|cd&UJjq#g!r~6T1L&W&+eqF%^m8`FVw!yfZh0S%u zW1s4JqND;5LwgA(J8Lugl31%veiTH=2tFNgt&Dcp^6Xkd8aC1n{CXG7GdKI!P&z&6 z;Sv5$z&)E8Rsl{N?uCqJ3zClF3KgRH*JDffuZ!0$#Jnub^#Czx-%M|C$p3`Sm`z%d zpE9}SS%6mt`s)|M|4OCo=3e)qQD_AC56nC%%a9rn8Q040UVSX@`RvJ3 z7cxgLit3$T;jD3!Insg)Z{Prxd0(Wqh|W~PQ136Tvv{PTyPnqzb+&j>c)4Oy4FoNf z-fmvp8ML43%p6WnVT5pN%~gaPDqtw;T)A+;kj!deXm93~Io=>L8($9lkZ6sI*@I;Z z48!?oujurg>s+rwYPvGQci;|wp(YG#1Ac)d_`W@0E*;&CtJ?l1ZgRj7_I$f=EQ+65 zD7(UqGW7|0nWQjOoNgcJ!lws0N;9qGhHE#P!a(1_#Pog~u1YbTNBo%i@P3ABk^ZkE zt2#oQJXnu-4J`@Yx4T5&Gw$5fs{168o4~3r^1U!7Dk&U`2MGcBdA5KjCL z2Z?%|_vx5IQscP&U}QTirRa}dy0etC)ZQXmbx1ZmtiD=di4^_e_FgFA&oh0an6uus zsfP~ggs;cihPaR_(ub6B}(uci-*S5?<>C?Mk(gEtkc0EW|IDE4xrdP z)3mnFdbNV??$+w4O5ik7OF2&hEN<~1d>u(S$P}Sm;=?C^r*_PA%ws=Nd;9wdz6y{$ z%+thK{@c!KU^~-kTJYB;R(_epMI?_jK#{zb#)Gn;M^r1J>d$;!o4KmhXQ)!0+%gWQ z_n6=y@JpM@Xu3rqkhgMeZNTs+Ta?_Kpp^#49Pr9;Q1pOMl> zJ7}&YN8K}6t**OXbLTkB4voO%l;w8m@GDaBlmoSsx%!UR#0mP^uzl?oH)rTQ1E-GL zG0r$6V&wb`Qza+BV9v7`(_kCG|F_aFPvPqtJRRUK=+oXhW=EDVuvn2FO-`h{;-Ki7 z!%Udqc}tObBp9GHem>d|eOy)wcYF3Kkw%+Af48sIv5~L{p84QTh<4>`IGi`r&Ro9v z-ypNiY*=D8RuPpW4bKc-2l9Ghbm%1k#uWLcWyMz9>OT%v`6#PHNEG3Mu)IU4BHUUi zDNE^@Lu)tTRImmo!RdwOfYl!a*iNoPp1o@mbrS3rMXOsR1N)u@4s+T)0WoGRXBMX9E2^g%l)91b2ImbuiaPvgAQRE|M4cGGGFseOav)DU6c;K zLtVc|7%uy2>rXO#&6$(`s|Y9K9RW6>+@?bVu(~IA}7&e$*AQjDE#_Dinlx5B;m=W-)J;; z^#$?k%7c3j?%;uR8g6rKIQ>|HIh$ja1<1Y;TQ%ekfYiqYjdE$tuf~^PaC4T0?;U(E zmzAo#Vi4_jzN+PSe6`)n5jj+5K3}IY{Td!x|6z2LGa41HFeqOUv70Ysk|7&Eow+SK z*na;R*94EGUXuyylUD?8iUMF2;erENx|n|W2Y|8|ZuDrH*AF!WuHfcZ1A8>i`^Voa zDO3lCglD{j{`{DM+A0yT+AjABJ|-)Kf&pX=plqXwXF_0sy@0b?xV8hZA@kgz37cyj z>TkSsM66=0YzlNspL6w{DKweKIPu85ywXyG_8~#I!N(F~0D2u45dD$Cjmc~`3<)8_ z0m2I@WOl#NX&<4oilH7Yw^VN9?!&0J@QPaCP{1YMB#}>B>DU7hTwX-gHi%Rf1XImd zzzN_Jyfvr&WQq6XEbeJ<}^>Qf<5fJrh-l0MPP;f8yEnh!-U}uC2D(1 z{(DM7$A+m8-a~yQ9IABPn z56*!;yA0#`ymH!!wK8AM-ZvGOq>UOc9lnUj3@NMD&M9>@|1cyw(hM!5-E!0cc;3&g zJcJ+cr*1m%9b90f;iWxyB&zB2HP{ajhyps{u!1SDHn&ccdzj|&jRrU*{;_V^Cr((6 z>ELa|WOz^Trm=WsR4%KM4h>3{kwa0paFw0;8=i}xFxopoaE};EHO_iC5Ldi@n0|IC zHHjiOhxG7e!SN9Ku+D^LZO^!EzXOUUj6Xdl?^j2EnvtwKFje!yKwd|NqLVqT=R7AH z4B2lT|A$#P^6P&o9T7~gkU$mBivy~bl?_=X^d3V=3SlRVAKrXu@a)Z-T9*o?3+kwf z%O{p8w_G-#b`8ZJ>qvbCedQ2*`SI34wedkO5u{Svi}lJR{JWZ=*Nq#(^D!@KA2DG? zUqi0FB$IWqKW`;wKadwCO8r#+s|$=P+1{QIEG))t3=M6~QK?Knd#-dvD8?<-6Libh z`E8-A*qTV@IEeSl+}e?adXB>9R@EUp0X;gMdK-oH7q`F{Oj63EBlw0CG=S1?u? z>i&4~E+Kk>t6z!WQ*If`tCY@X9sG6k!z4})^kU^%I(ejHY3>px!)%UEJM=E^b9X%3 z;v?M>h!fyDo-71aCg(dRQzm!jQNx{c_DyBXJn{yJlUNsM={KQ{_yIOqfug^hM1Hcs z&QP7N;53tgpKDz0=Hk`>ok<~oL;AmJ&33R$-g+6x@<6Taw1L9a$8#riw~Q3x4lUoIEDLYV|E^Ix z*J+?`40N^A<(u@AVXi#Z@)Jn}Lx=e)YQYBt{nz-c`riP7p8bpSnd}$%)iJ^EbBjuP zwI;F(ldkW#l>8|xiX32DGMn4&2jqM}0=`nnwT2^B}|1GzoT z5QUJ)fou5s*3vh|W;H5E(9t1;wmyy2s|MQ^*3&5{im;(DI_#c|Lz67)`r{g5N7d+E9xPlwdV+AY{f26h!$t4Cf=OuTlU|d zX?>~+Gs<04w%Ckizpo$)Q@+S3a4xSY1>++?j`{4@7F53;H2}#h7O*ZV9RL}Uc-1rY zk-(#`BZMN!?c7NVI`zd6uDqzrd}7G+nRVAgd(#iST3KVh*T{vJQ|z<~s3sk`he%}z z8iTOZU(Us=OjA<^+RMh?Kf98V?J|cGjqLHD%RJH%UK!t+y|9@)AL!>4$)XaUshB`Z z&nIL)*!b9npYsh=Gn)>dN$7uf)&0P2(H2|xl%fca@hdNnYhJU^Y`}#U!JFHe#!gA; zX==XPz59}1hi`7~%t^Z_wETeWszCXoVn`f_5u0}Qp7b`U@?RZ7 zT*q(Ui@wz3a16WHw6u2Y0#Gzjy16kku6n~YthR(yfqW}h40@&k9-qZp3A(HN~%sv*V`mSYuBu?NY?+Ws@)_}Tp54zra~JFHro>GRPJ1g_W+d+q zuiA^zI}BXxlW6N1mH~mg=-msy*AS=BL6pnm>(wRayt zr54A|oEJmp5i21Rd}S$1J!^hiRe0Fh?8&pFa+Z1;L2*pZyz$kYJD(jnja%8r4NA>H z905X9oa;M{+f@QhqG4yPR2-*wJtW=?JFQ+oLXrzOH1+{FvC7Y_nevu;p!I_`GVAtb zzhH&=TidF`5{UltPoI739jk90law5j3j%$O@Gn_)*X2G^Os5{-#syWmtS=NiYvkU! zk?<u`N?+ShF0YavHRG9hs+aHltuTg{mvei+Lyb+NFzoQ> z>1!WnKNCn^LD~JFZPiKpS&2U7TYYIG$ks^O>^D#6qS1zjjffdCG}cGaWw{W$^7&)el_Xe}&4{P@(o6l+ug9A7-E z6SG4xF)tU*wU?K5SG6ioBv3oI!1K*UUMB`O^6Y%g{iVKc63j}Os>!~*1k<6SvCG?l z0F+bimR}-72@HKD+kw{5pu|z(MKoX81PzI9H1sAqkp3$9rd*>cm1a%qJfw7v`IExv(+xj zLLJ|#YF?#WetWFPH!sbnMyQZrV4I0Meo(r1SS!{MLIE0o%0WP?oyyeO_oH)MgP0xD z##?pg(B%>%_=0;&ZQt#hiL_}f7kINj{hFh6_i8;q4{X?Hta>>IUN@@wFX)f_mY^g| zTAFj+UgLf^W!va|P8Lafw_`%K`N(w?@8WG|*emV3U@(sl^% zgKqq(n-7Tz3jno*GvTM`y_{eT=SHtc<`D%Ozf*-w@`Id0lTezv{hT$TKj0Z32=A3! z`Ddl1*FyT*7M(GzJlMa547U|6fJG#KEna}fa=Wot)jDiKnsgtlGe3c63EVOSD+dh{WAqIi8breHa3_ zEUh*j2mRqnXsuwJB~Fw9tST001rK}pAf`xooQQse=u+-rjk-49pz zN3DcVG7s{^S(g(zp;c#$B*AhN>C;qG$sKnJ`(%CL8gAcPW9jLHg>7SFPkHoJ!%!4h z`J;f(eA4UbYrU`pZv@b9c#rA@mC|YkR<~15xhRx6PXyAES*tSwuOFzr)$nFd#$6xU zs#CLItk+ySNT7SA;;q_V?7$4u+?9_ih2G-xMAvq4swY)bAs#eBV8H zz*B_nC1s}IOvantD&8FgScI(oBY(TQd@G)phDoz|nG$o?$0XKpWJ=3RTj_}%&}b4& zc0L59XX2Rg4k8F72piP#KnWE=ptL3g`v>Jy0BwWU+qqJPYCM4cJ`5z)wL9AN$Y529 z&Xu1>mPE|@TX%n!ur?rbhID(5t#0gy-@cu6#R&4~VukgC(bd;8OqSA9@@FnRr+*Xq zX~UW|lT1g4%$0v!dU~`j8I%k{niJJ*{O;`jkQN9J75>snNP?OULxR51Rk?4})!zlB+d}us~;OKcZ#7GY! zvarsZ=4|$ zhr%lKt7y7YVM(iN;Iz8JzxPl3HfJL5(#-iZBU-}Weu@|WdK?x~B}(nTz>e_gjLhH? zMFFx5r0}mIq>!~&t1R0!%5{ZO9sGr}bZaIMz{PKMBqe*`+(&Qz=$nP7W_-}l&^S%% z%Vhu>bR?vrB~kqChk@pkc=m(r;6IgLtw$yFro|p)@==SeexLfyVnjX%H*nFg%${v)f0qrt^!9 znqcd@F|B@Ku&Q8Gmk#RQdFC*ARo+1Qs3!jGetT-wBEd`eW#=LebAygAOXHKQ5jY}K z86QJA*fEpZNiLWES_kh*X zMPE30s)H(i%Viv^`#onr`0fF5XA|`O;n4)}B+VvqnnKyxUX2yoLkkta!O{n&p&ty{ z8og;vb?i(`_O9Oa5D^or;m?A<=xV_-_AF1;0opYpQd4Mkm`YDk%;aAW)W0$eFM9A% zfIXQ=7Q*6c{`p+&Ex|ZJv{{~_KhfOyyo5jI9yvio67I}kvGt1qo~O{6_oPv+keYY` z64(=20w`9Iv+B}DILT6LWwa=L0>ymkw6^uY{(qF+8j5l=|#T$y`)}9G4FJW(C zJHgGlqKEDEzp%~%mSN|m8jfO@f|#~#DV0(kbxlE2mkl9$4doYk3(aU2jRfRn>83Fk z?!%3cs`GEWABTJC5k*io_{yIpLAjizfy#|4{?s)7QF&8fFGPe@bvu9dDG%feEXsWB zd7%c}RA2Uk-sNd=BL)U(4|m7>jN=_R{d7_J)GQYLsU{$dJy3AMaCp&6S`!e#U^bfs z7$^F6BAvD4$IPMf9Y9$w{qXMBb^fb?;jz>#Oi!tGo0EV3b7n%rS1nqom)=3Z2^DjnJ#6e zD_!-RioqYv_Gz@PYqNczkAdPVu7EPOi6d3h+BCl+RSJ-}?5P_v>40wVIw)^ky01F_AoTMjFk==u$kFGTb?B!;o7V=15Sj-KeW2Kr)QLtfqpsfEPET@vS-6Xm7 ze!az@w=W&+kV%+@q|XEGU7(&e{TMNk`(c?ESqp39b-YhAYY_*t{{FL^*coh&O4j+G z0?vLF&~`%QRRGU<V`uIOe&ZZ2!p)@1ZCEJTL|pT>aRH%mM4#RFnX0eQu7<< z^vd?N<|lwCi)UkDPq8jZ#1^$A>=}84z4DP+A_bPDY)kNpm6^7q7pCbRU7|=#Wel(E zUpevP- zJ6T(2p-+>`MYepz!r2|J#4~YlMAGB_%ZLE=5;I6XnpA8D_A?$^Qpl+ecp>8aVUwJ}h%zgkDXVl+! zGqKUi3dnanJXwT@=5R$Y#^}F79fp1j`EkD>%Ec;lp1vg$baRL#oG_ZMaD6uBjCl@H zJ%l~SUmtyx-D2_6pW#nk2Z6OQ<$0)p;@Mq7FTUU5sokU1bqm#BQxS8SEf4o9B3PI0 zIr&3qV4Q&HNO}RHI?~dpXR5$r(PGW-I*?;3AAWn$-zFV#i0e8Um`qIJ%Z8xb*4#Qg zyTOyPr)cN}!OKF%$STIosZt}1d$bHR6l`IMx>Fd;ifNReV7lEkMI5rKT@>Cxr+F5^I!!2 zM&#@-ed-m-_(5rRa5gRC%oTT=|0!0K{8L=>Z%)3g9W})MdK91jS6OZlH3&V3mTV$$ zH@zu7j82%kY18@W!yeFc@XZXOMGQ1ITG@zna`Djz#XPoJaIo8LTm4BT z2C9QO`c#4{!M|NEu)HwlY{*e*Z8(4^Y34Kc7V_f?=BQTC9i~a`C%vO&>IB~A@DJyu6&L6ulwu7?SE8x zX{*OZjlUhG4wgXB_?gU(xUO}U`HnaF;l&Yux;dL4uC>{K*ag|AGyDc0J7+rd^i;X< zJ=Rnr!OWu%D_QEnjdZHU7Y<8+7?4_HGtUFj1GqTMtvga#@;49Kp}|RWPW8{47c&Z` zBrlqP78?3Ti8*N_kjx>DpBy2Yru`o9R6c)~A`x?ghkSL$3`W_jpNQ@-#tYYHG6Kgc z`Bi^;n|>W8{ry90pmqf)9oxOU3)*pYtOjG@ zbg|KYNdv;wxwFk{q9Y;5pT`omcsKk*E9l7f=+A81=~46G4rqPZnU+{aRpU)|`6uNh zxM$iD+3yA7>z~1@ei@I0$ivg6(H)3J5u;MVQOXI#|I!e9kDp^}R>+KiZBm1W+8EIP z>l588mspyih0|LqoG^B8XDGx;WHcTrZJ`Ca0Z|xE_gr=^hEqH&<8#!1C%SatboVDx zGPHm$VsM;^e7oj%U?QQlh+NQ++AM7IqU*JGW07;aQ zG-x_Wk5942hc{dGERoz{LebJm(FTP5HpjEj(i-mCVd9mo0w!RkjaukVdF|FRb!Wmg z%5#TYrJDlRpD8M*e3=cIjy~bTWQJoV<~i!`vOMWnZn>fPI?kzPDdAbnG?MCfAI<$b zS-Yl>z&Mg#gZzB+n!h@Ou9NPfLrBjo|IFBw#ht>3D3tzK_QYX&dPk>zV~VHuoFHO} z;pj`36Kh{CmWHkPB{DJ;77Cl&^(~sGGF?<%|CB0A=Dk0nkHTs>NJAQ9`Z~fjt?|VY zzR`Oox}k4j>{{o{A8IS3tW_W{H$!U}N-jCGK$DHXepm~X5#uE{zTUhHPbOvB z9Ypwa4f=j10&ESA0>SWJx7<_3jg#m2prsIE4OHm&l*n!SS#A=l^!Ai)&{wUYOL7&s zmfn3ZS}lx{I5DD;G82TpRJP*q&Cpk0WkK5N`&2uAcqdf?LvioF}Cj2FN`uuD?UmA934Z-Qq_>tE^4 z5yYwcK@%A{SV`Vf+U&Rb7zEv4SuowS!Nt%qDKcITm&GODk6ci#29ZS^VSom}s;HXD zHlwzFm$k^WXYa8q-}AZCMOB0X3tCrx_@a3FS=WkAL@?)#<`wBtWP*d02%fq*_wGyp zn?i6Ms2#+e%j6=Ly3D7deAg!?z2+uo`y*GuDjjDj0(Y*ydw5sfcVbHytb<{ttK`jQ0PNCGMMESL{6m&9I z5_O2zcH_J5j`8~@ak&Zm6Hh!A96q>BBa+H6rH?gPI{mE@I9{=+)7iSutKx{iMZc7_ z!00;cO;F9;N1TB#(JQ@0(8Y%(cV10sp}3A%=EqRyDp=P``Rr5(zMzYF#pI%Am!ZRK zf0L1QEmNrC(SSTP$A6#~Ag%mW-GXHj&Y!yECA?;t!@XV1QQ}9fSrd8x@)=;;dvR-H zZccQcslkcPk8gf8P?sxPF1cooo3vF?R7;_A;OJ6BCZ!vpWU{n2{%jy@cXL{RzgXIk zi0nXLT_)}=qb1u-Lh(A64aS!j7hcX*SLcikVE;8%_=QpBQ45;{=2 zmwOZ=>*`o84IKZ23bK=Af0!?Rg1U@ zymycxR^KQ|O%F0tckE2L&e0&xqCu}t=Y0j2mIE0d|SrttfMR#qKSRw&z4Owxmk zXNHOZatopXe_}VKcCrmtuPLk2G~Z_@dCfBAVs|Y>V)61S4|PNlNp4F%sq;F0%M6Y7 z%mVuWR-Xw^k!9=8GH1`ollOvB6UW)3PjFUjR{T_0MiN6BW`A+xXFy_q$AfG^{%}Le z_ywdQ$aGC~cSaLZg_|GY7v~CEWAb!gz02s5l5SB6-d&^coIhOfLZv--0WHH$1N%Q^ z(;J%T%d5tjyz6Fasi>KpirfcdU*<$xoz4EE z`&xIBLCrP7<<NWk!1v6W^^gIE zR4C?hzNxZG4E~UCh_7Rid4tcaeG4ls3za$h3^t^Wt@*tgl*!b!57qNn!|AHq##Cg^M{JFyX%&QpAasE{z(e4D#jm~MTKwJhyf2C|{1u2E0=dyh6J)+1SIK2JsEhYcVMnZ!Stl8~lB6=W`tPiF-+o1{56<>us! zAc72m0f{JrOm+u78#~8nm`XQ=F-mB6cS_rxE1olNFhj%II$3^o zO@HN=$CqMqR#Yn4dz>Q=A?jok!3zh;xEtAE$!NAgJdtHSS&gfV37NEvNqF59*mU?k z3G<25>us)1`g}OeH!6uT;Zy+=oaEl{RSXN24%Q;v1XY&f%nXbz7w{dK9XAzQzuftw#!lKEz!x>aZ7NDbg5iOMU5<&*K!%Z6A{tY-`+i5 zP0*(Us+iGrifgmRlY`OVkq-}*-Gp$0dq3*dU=5Ia~4QTtyCc7i6kEDg^r>@+q>f-HpSI*);fTKoOU z7syI=3fl@M?g&ySs=rZ<6r8>un(%{eCLTF0$_b<}ut~1gxl|ewooJoOyzhj)!(H7y z&eq*@U4jQzJzpgE8Rq50tWq)kE8R@idz#!4uLJ?6XGziYPu`CuK17Mhp0VZJizxpFPyiBHT-}*Xdmn*rgynP}B1d2uW>SYrV23F>kVz)pO}9HJX(Zo$pzYB~)9B(2~PmJeyO$ z!sx<#dz0zI<6T0w*1CWtL@<*{B_&f4N0%`JFiW7M0jk zX7aufIpWM39;|vvvN_>gx-sgvRojv)dtcs_0WPa_7+lCMKNT#p8IXS=q+nRsWds($ zJ4oU>U7I=yTE0$Q@-2~Uva&9a5+ru=NAv)AbHtSSzp1-3lagK-iKfuu)Go$Jr4qj| za#r`rL!5N^N^lVTP$Jb$?Q+gGKeJ4eHe{^dkVNQzul2++x!?NH{FLGGkW0HQqvB1r zk@H2kN?#~CQaaSQMDzNIuYO$|Y?&IhRq9r6Q@ccI7DB#jS3uqr&#}^|BRk|1dITBb z7B@Q6<=#c4_^^4To2S?MV4~<*Sz)n6B0MuVZ#ZiS?XYh9k8eB&0GxDamAoTDV_8_H zj24OAY>*hDYt2FanDp&II=pt&U*%c|Ip06!=#65T_oAO2_}@i=o$xwdU=14FL#&$- zx$%YR7^NBXw-&eB@OlNi5^Q({D=o)sRT9(bGkmo$#XJc@8Q0!uCyWS5y*JChAP?}j zVEnFYSxPLsqYbv_vCGd@)~^pf{Hc=QTn3gE(R{952K0NaB)6Y<@^U8z`8Vm!nMC&z)eR=gEzu zuir=5O zW>i|A&|p)9=g`1oIMWZ1rQ-%$ihb_lFf@`CbjN)gljno0_`8VYsumR*rd&E`pTVU$ zlFHr7R6cs0JdkzrZ$%nRXo&;+b7iB-E_KfdXGwLd zH2&(Q61$(9t$Fj`;iJcv@D01}KA+f&zTcChE}4eOiVoc%=yX07r!G-hnJ!(>8UN0& zF&WTmD$q(bLN692hV1dO`K8fn3df7KQ@6Z zv=)H^dnS6@k0*`SjQU?7g8iA`r64FR_Nq0!68v)sLZo0d><6qnN`~Gt-&bi};wbxT~ zjxpw#&+_IjZUI9OVqkR1wj%g70^-^%>-+d@!NlO8ro5_FboWIBF0_?Cif%Y(Ll< zcC{)gPfAh}ribqE~9Sa5oh!e2|oBQ(*>6cGFAniKNiKk&JJ}T$}e)sX7-VtTy)+dm=!FtKWG0 z2?k4PUm~dBD>XQ0<82Ih$H$pQLS0}vBrQJ^_7J(^6+t3u6BLg7Dvi2w3Fb)`giy-v z`1$2D`@YwD7i%FH>nIkBpZ6(vt1X#hxDh_x_dhUc@yeXe>WP>Z%gVAkyIlT14h{lD z(IA-9pZbS`lfY@jGbUZ7)l5cVd7W7EYmH_u?x>v#<*7=n0~r=3*gX+~=Z>}Y?20gn z*ik11O|1m9{A1Ta3f1BD8h0c$O=9&M=eVMVQJ!zp#}+jCl1AQn!l1qZd*h2_4Kh>h zL%|(hW&Ti<=7635P6CE7>3et%V+3|oM;OAlWUs*vz6xBHPza+zi~Gs~t{6@a`B!sI zZhmH4yA_T@DE*}94t;kmLnI!nO-1}pUAp)VY7QP~$&6wx)6_n~{ygJ9xQVUSB-5mv za%vfDfTfZ;NtDRu;U}Cq6&~Z*!1Pe+2=J4eM~2kPqDD#POs$wYt_LpxQ+@8nV)8HA?dbZi4t0kpf^;ve!je66_QAI?;pEYQ=4F^xdwLikGM%D{q1@T!rTKhf~rTJZ8ANO?zdU~t)7 zKNG}QiL+JQ{mcNdCKV-{h!`HmlidwRjttV<_?X|@DL1l7|6iP?&IQH>S1I%cWKu?1 z72`N*jma3I)f7zmbBck5)v2W*PuGyhz5+@oAblKXxkAnS{5Jq3hm-Q-BUmzVYK<~) znF^qbpUQzXqP_UqC>VsP`CQ|KI}OkC4M>LFyQ+^;AzXX<1|eu0JE5Cw2K`e!2g~HJ ztj@-bOfT45p^a+(NjB;wQexbBkWxnq%F6vcC0LE-W)6lfu)W1M=&o%BZRmoQqj9$+ zyDkQb(&;cXVz!l=$(H47tH@I_Hm05P*ao(O0G^A#hPKa%yGFE1u6YbYz#Zz@+(mf% zFES0TV9k^}>zc{v)}?qk?egZGGv$g0-y2ZAO|DGh{YQ(k;2?zFqU`Fa|0R7}R?Tpl z7T}4lY!a^a9QTA-9aJ+6zUD4QSVM;S4_^Wo^k=I$XnfGOYPr9(Jlc zWk#ZkT-%ul;Vtvpzd9P^X7Psz>8GmiWm0xdL z&54r~gwkP1HX<(Cp5o(79(LwJH<0j2k>&ODyUC>q>&_At<{HWxf@Z~}mJT~=)Z)tr zxRu{ej`DkjXL0%&TfZVf|H*u!aQlIxuxqws0SPi{Y%raauLm&wcj6U)B!)VL z!#_PquH=Dnqu<8-vSax6Ua%CYMC~Vt-<6;j0&@Y+-u0HI8eSs)o(i13RMnBcNU{4y zt)$naOEUdRg^VP~?^P!@nzK0X@qv|^CF36i*2s`eLc@Np|IGq(=xYTd1ciAyFVb#7 z+HeaOrE3J5Bl3Iw3rSM=Ws;&%Q?S0Y6!8ablo@-Z+#gNyH`qTV8SL^BEU6N>b?6Kb zrX5*~mR=jh!N^J8edE*TvBZ&Y?LsaASYnZUvv%-C!wpD^WDVbqA5aP?NX{Inkfs~0 zBy*#+RT~eE4)R?~u*ODElvj>Ahu@_H0Sb5kM?9zV_!K|E;`91l=!P6ICN-?^fAJXX^^ND$*}e3JKslOA%^I}VaiYlSh-@RTXK z&600~YO?9uEc*G#W}4Qxc@>av2)*e%4vqhhF3pBIX0xVag|yrtBC;GocWI2j4evvh zi3{jn9WlhRds_@f>S2rkyC{X6{aunIHdAI57ZYkqYPnl(kp}PZuz2rT$ zDj3$>de6y)f&$DCkDzf^C3U${`Lg`44=#4)!;ZsB`>@t)d-lxfF#32{yf7I1js_bv zchU~A)pp~R@OCWX#L_1i-$iN0VotxA?heKgYd?Pl9fJZY37BDZr`8UDHwlSl#MGrJ zy(vHUHA~7o@L=`-Ydf78#HmN#h+X*Yr312nPvX6>Y!zBmBn$sj`XZER;o3!qL=vl$ z{Ph6-C;6(sQ@}=9g|`<=eG9rVO=w=6e9tTJa4{^&hmo?e0Wdbp+9+b!|5#WkL!E?2 zzexzP-c2oSi9BgmhY6f3fo&%~pc=wwiOyF@mpYPSwxQ=s4_{e_9U$&6B~()}b`T=x zC0a!2(RP2qu3D%GLO?4Xc<>W;*Q!5WYMCPDa7n7TYhBeto-YG& z)07badARt|Dl7je5J6hRc|Gv@X{1+~N0Ed`bKq6br*6XC#|~;=4F-27{zb!F`|MM- zEE?9*-(=-qBXCxlf3UsgrX52!Dsq5KQ?a;4FqEy_(S%PphPPr(Ha7CS*==rgLYo9t8Yq!&37)1@m+rSIjV z-N7$TGn%eg{Q}ID<3`;w1im^B8qGVc-GN!jB*>!@$N>n7tsFFi8*kH=4M8K_wB3_1 z^PfE3|EyVP91SlIzhSkUoTIi~H4_Zz`y#D*u414jx@Kq5%M64LY`QY%sKolm$KKXx z?OGDdlXAuWb1zT5I#t>Z295sAHH+`*=QyP#uTsgpM ztxI-dSSO!kF9bv2Z&zehpS)Np;-5lE*eE69TgmuPzgwd~c$5+ekuI8B&08}vw*5mo zeEb!2dqSG94GBFJSKW>tJ$r&61}OpVuBQ`^rD`?3->lR`%TIG#7f-r9OsCIF0O4EP z;%bHzm7XW`bIZ!zW7y;g;L&4ypz_=Blybx;)~6*kM~ zxJA0HO0e%l=&?vTOEA1rq_fT5d&AuFiMhJjM!UjgIiP%Wn)aJO@y2(bc|}UXExBAV z0aCUmw7}Kf?uF)G9a$WH`1JOzdqqFV`v=-~jw|2YEZ-efig@j&Hc@s2M8;rz>+Gva ze3kv+Ic?3VrnTPKslM)CQ%m)9ENIgtaCz-Y{6ey~JqR)IFff;tl(eE5-D}us6fJG7 zdm1Jbsa+e`k=jixKiJ>biXCeS{p>Cl>lo4x&zfUfl1%vc*M!}9O+y+VDBJ0^Xm%9 zMwnR)udcPVwJ0d2RB@LAw)yqilWTf7Aj^q%fQ#M3De#a_rHy5U{?6SAA^*lJdcH@8 zmULj6t9(ko`~C(dk1m$y5z++@Q|EP(A(I=$O-Ad;1fHp?X<%3=scC4neTTV_Ys&_{ zX0nY|DFthtkMC15GMnR!9SB~||k9_8gtvnEEs{G&H2_zD1=MG)Zt|4j1 z$$1!PlbF4Ke#mHOwyQ@zL}^cE8+M4i5*gr`Yj%jdyE&F2-9I^lGIXnYC5hCOom}vD2Exz;fyr{dKJ?K4eYKhnSm;?WEd z&Z(|k;CJtEt4?Y^_F!$PIN%@I*=a2nyEhCq%gwpztQs}0&LD)mC(N#I`S=NGNFx;+ zP~{B!nC7w_V3n=Yi&`aH3sY*N_WrAJc@|ZR{dGhYF1ugrm%-QZ&W51dG6d9g0r#s? z`;UmdU$o(vwJ}f;$l&TyGh(Y+Dc$_$d+#+ALgp+xdZ3ypdO}SDlng)^-53ohOFiX$ z7-8~0Z@SaENA@_Yu9;#up8gFkHFHKYZqJ?uO$1nH8ZgC|;k1W_ehMEQlia_vE+RFG zq%G(=gjfUs@$CklK|i1ytee>CC|B%*-=Es~pI~9>%?!TOYTvtmRB2Sd5|TEGJ-PQ7 zt#*6yy?MD7GIB6Fh$hq?Gr}bI2%lcpZqOl!Y<3@+iBV3DQ-U+ccc1EG+?U-9W$0sCLSM8YB z%|Xw?Q@(ZPYusK&iF@6}%+fADQfdJaw7~Hj!}}22dqy@h;>rJtJ-7BQP1YEfx5q{& z_qy7(CDouw6=&l8vljcM92#j?jzt zO?b^~mdzw#za{!_UPCIQqO(3VO+wy%msDZDMH;a%uDvgdx@@>-A8hz;)*R0V8g-I{ zXu-;={`!DK>_dED#%hF+O}Liaim$tG&SKVD|4(^Wc4G^?Y$&5A<@das6+5}%nk6KL zCvW1{Lqqk_1IZYy*pg)cW${$^yukjdo2z!$fV{=}8qUQ0K^fr_;n9RjA2!Mpz3Qu* z%-1*G7_P6c+}L71V;auYgbxN03I-!;2>TRoYfn$?7x1eG*BuTIS?_wXF{cf#!rmV0;i6j zfs0&DNvlnvaw<^WY@>Q)nW%__B0u0j@0tFKjQl1gGg-ZSQ)}V+>Y?C)a9< zU7wqbBZWKcV$UO&azd=xM{QV_!VFVM6Z@%TJFvGR_J+N0-c8qym+Q0%_wgLWtZR^w z9BAzplVYa0SDO;UH%1Qv;f27}Zi~d$spx?zCy(3fT8yKLkLj1_woA0Z3U)1hjrFs{ zUDHbVXYo;=A{#dyBet0imNzk*Pd1`x)Rrze7r(EA_pNh%I4Bd{PKDp79G?oaZA?KT z%jGnJmEGEV%>np>Xlo9|17u_Mxm;r;i69Rea7bQ#?jbYOBdmw>yveKR~|lL2|oX zFt5GHkNr}WN9Ur|H?thoUX)i`9mRIIwFX=ad%pnk5eVg}6InE(;Bwhh<#}I|#q7U$ zhueYwIrRJ_XypBD^$lTh^^5T01qR)yFGnI>&Nu$XF1jjs9#8V!mAk)#2Ma4#jEOeP zpiboMjyHq&Jx~0^yCU~oVk8O^PA@sp~iS6AK&ejUw*eO$eR&_El-A&j>%^UmyisFMNE(^1S6Omu)k zD3yMM8oA;wiebN8aT-RHkq-@5N0fQQ{|H|ct&R3>et6(7eCr(G@m{6w*gl`yQij?~PQ?`^9)|%yHM#IFQPLbz-!uDQBng6Xx)Brgf z<$!&eZC+L7;ecg`+8YK7wysC#-@>s~Jxzhs7Qnr#%!DxD7g$<+*v>sK7WKq`6S&<4 z#pAAN$CQeD#6J=ZDU|l9Zf2{=_B;&xh~QUW%@XDo^k@NjOG;~l<`eAV5tC?XwYIVm zbHDgG?&EYk39(*JDaXYC8U{QL;GbCl6)#e=A>;3L)y7ZW zQ5@N=`m41vV#-l~mTia_5k^BSyH6>3i>b0@&Z4gWZ>qh@0Lf`z?=U0u49*N66N|4M z!yOzI=P7L*El?q0?HD{wZe9VD1+N#(i~iROAVQ?no?_^qmSJ!Ip(eEV372S-N4Lwr zqp8$2vi{3-S;ZeP&q>#dzt+0Y!(n}5a5U5O7^V(tAo$$ooN}}5-*{)8 zZPaM*GP*#>$mp?1ZAl5%3kZ+CSGdWki@n&HWm5ErvfcX9*1>d@8Ywb( zP(A~`C?%XdjlGe&eC%0mJ*KX#tb9B$%J381e20BPw;S;naW$rC#ebom$jjKR5zb(? zV(SE@%_h6@u=at5-phSu{$%OL&eq9UCm*J$y7}H=q4(cR+4F*w+HDP4ruZr8#gS>@ zoEy$$MvA$YQlP>+S)5MyZlN{aZ-Sk|r2S`PgHNKXn4TGKPbBo^Pb8n2@X)vyO+okEis?5XLmfeVzB?-_*6pqDyp5|F*(GEofb) z>jE%LHCoAyBKeOK7!N@!c*@^O<+yuMLv}Xa@=s3c6fyimK|;J8pO~AFYhugE0@)4q z`>4s#qrhb6tsuFeX;d4y8s`*gucA&v{c7j^`RovO%|!Je4pax^0u_QJ?YL%>uaEuZ zw@Z@hy2aothJg<#T!2Xl!?3>sDDHygvSDWW#MiC4{E=LXW`RC&}7W128otiw-Mp1ttH#d_vN2Fu)>(I zi*kc^S$Hd92}PW6vevkA)KCQbf2HgS z+*>yx8qrH&=lcFTntZ$ETj zPR8DQyBP|8Rc^)H!0O8*%bfe#;Ikdq6r|a$j;xGQF`s$1oxz;aXn94OK8CBm<{kuT z2%c=;P218k@kgbp=+|{*E>wgVUzIM8vh1a$3K0l@7t{TSN{M9 zNQC$OtI-3_Rf-=4&nTXZ6!Ck8{plSNH*WAk2Mn729mE!>-=Nfn?q}?>0DqHiak2hF z_B6d_ctJCAGwN0hZWQs% zCgFpgZbXsJFqDd*`M`7SkZGz4Rde&U9^4j{)ZO^n{iB~^(2@S<3u+E@77*U~#>O}^%{KLa$#Uw}N)tEK z)=9G|ck>2^9ewf(r@2b#Ug}n2upN0!>&|!V#n4 zDq+qfr-KqITl&_uuY0u@up-Xe-RBZl;dJ4$_oe3Tx9Ik(_A!w~47#U@ z1MkB!v^6czv1jQs^Rl&mT_NIjy>r(J+Cpx!U;JQD^`4AEy^p85@m!M7Ud&C5b%_mQ z`W)_bIGygvaEn1H&!u5h_y-}mkmM7rJ96S+vpG^bU5Rs zor2N!qEPu1d>T1VP=Xgs+#%Hnw+C2zW3@W6HgOz?^KX%!yT)cFy@HRY!n*j0Fa}= z`klrN)6q(ZCd`MNxn0A9AVpght1|_(3^Z;|6n@KuM2t9jg&<%Srtfa2d zHBp4oIzDF@1wj9S<#LZIGO$JC(~@1@*K{yUnrfa0Lfy7}g^&nm_tKgd#gAS+C%%aB zj6_Pf&A}r%X_kQ*gM;BadU<21of2x^#um)SZ=>IS+VTKM^g3W~NccmGk6h!!d%puz z(cwIWDB{_?$OrK#7W&Mi23k9{4w_eyZN=^~+zCVpb~e6bE#nPcSNMOvu47ZtF@U4z z)fhPN-{B@ZIz0j!?+sc|Q};YX;0IWavR@Cy{!jSY0?-0O<`@vcY6$!3P8gBkk1}}A zqgG0Z%pxE~S3)YE28v?1r@Ivm`*F={<&Iz8nK~y_0!YWRD0W&P3}(R+lQDH#Ko}po z2h8s;U{cC)7Jh}J0VI#NYjU0}t#3kJA{7q}%-MB8Tn4yO=H2+klOlInN~-YkOnMLr zHoZ@1%)D`xc9qG)25NK3{@aWMvim2hnVw0Rhi(;)YV@cqXx$?id5^xh!?)15nTm}K zg;|_hBD$qq6t{R-Fubq?sS$vpl$7DLA7MH9B)!#=kH#KJ5B zfER9M`aqe$r<#-=@@{f`kJ|w)lK^Ng02p3KKa|RZ7C;N_?wEKf;u8EiAx_ruiO=k-%emw zt_5?}0PYqR81@A)1O>tDe0S_b9=B3E(JnMmK=6Pl$6?8PnjAT^on6oJ(VrOmLMw*|t z_=HM9>Xfdhmr$;}QqiHQ0qkIG+1)f`4#026J-Mxz8~|8#2?2*)9f&8U2OC-J8*n zOL{Cx=?74|T)@eIl)L9B76AKbyG_;M@vPxBe3B`pYvDaFW^7_0cO%c-(EWa*@bOLj z#Q%WAfO>Ap!L1L$UH4g`9DS~Hzrv-NnD3hSG~lxdeBh4SQ&|xNX3>DDBj(ndGgE*q z(aS5mCwRc*USAv^k=2Q*u~3TR>FrePX|%*p;?A?&7|R8l6@rN0BWz&+FVvV$x0GKO zU##hsUn}?JafF_f6JhNCjr`cQLB#`|GGZ?*Ao1Eb-(Dz6Et01x1iB^0iQ-GM`{nk% zu{$ZylpMVcEqc#lLa>nE1<*(}L-aFDO41~`bRWST4awABsgjM~J^ zjvv?*6O0ITj!NEwCI1C$>g*CG(^Es|&##LMca4Tw$^FQ+mtjSAg zuF!#bg^bz>-tPC1O?0-6RFJ8#Pt*Wx2alqELv#;b=bNzZi#%Os-CDl>0|gZEC6p4hIsjJrL>W)yo?9qPzr+6zDg^Anj|58l zS8!py;?7afIIo~Qo+twI2-uNJQk(#LibintA92n;=n~F?Da?cb1CzO)cAau;(LmUG z9eE&Xb$Q){DuM3gW?uc?C+Y)`#k+vfHE&I-?j*piwQzN{exIey8i9~TD9d3$ZeOLB z7xtcv^$76E76V5wryKw3>i(iZ`iwtVV71Y$vK^4|A3p?={?}GweV)*5f*Nop_!?Nv zr1KiIVlQ$jvYDT@M{Z>5I?!37&P^#A*a%XFguP!>jW7+!#y1S1O|@1}}O0hyYdoNP*Za??Fzr_klk9S^dN+*)nM*Yi+d zg9|QXCkdxL3qgL;z|#)>#&_QOYfcCQ$65L9) zCQ<@G4Zw~7OgnZ+rqeEUPW`ZOf2A|&V5Xqd>J-rqWIGpDGI&p|!*LkWKOs0o7|=Wn z^&+VzwZ8Ik<0GR2y={&XCrVMO&p<9YFM=<}qxij5^lPxJj@+wp_Q5rZCL=q^py8b^ zw$+xDrp5R34Fk%Ju*Q4aT>?NkcN81NU;FK-R?HJxPJ9=+@Ws4 za`YY$mzJ%~(-~5bS%B^f;??bQ=XI^WJWKqJB}~fZ5ut!bznnsxe{m3Iy^i98V1+|0 zu@LihYW~0Nt?8UgO-98UR^o`v*jGr-gfLMi#0Fx*ws$qb2bBT+2Cus=SS6lpNAE=! zvbVB6F_Lfib{io3l#09g#Wss-R>%32yT>5PEI<@ojZH@PIGrsLXPXjktC9 z`0u32bM{u>bw66k^|!IQQRy$wgJXfyhOrh3HNFZeZ-^d|Ii3cucmXFeK*LKnI4*?) z4t9RR8o4>qi?|<;0C?H2Jb+3v81k*np(npS$QePd4HaMm7zau=>4(5K-?lo^2Ho1? zF_i#mBdfzt7|NZu+=Bt`OkFWL^cVS6GfS3*vki)ip>Tw-3MK+su)CrQy4K;IItv4H zkjp{x9$+Ql3XBYFl~L1<7^^XXM+4^m#!qSTHn&q!ex|`Wl?muOAq0-5c3{_f-6T-B zG=Zu}<|VE$dVBVWKx5 zt~g|}+aX+cv?%yw6s0{VeG*zON7D z2a6vA?|jjH?*;7 z`qj0dYiCogr6*3OreF5w3s0N^Omu^$O1QRNh+zZks#=N`a>?hki@PTdTyzc}i|wIv zFA)kap}#|EE+Rer{9HSJosrpPm^@{N^0uLa?ISyQWI=5COzxN@&FMII%%_k#^VYD@ zer?HSjo|b1?;>S#)1B0wV?|lR{xO^=dFCh6v**;QF9ytUQo64N=bF-ub1%J7~M9`s3p z*!=DXiFG6RmK`2%ySx;}?)O$!F1|ht!a+{?OHGlI&ckXwwX|ShuV%t3hj)5aw>yh) zMOKGpC}-|BXFRTON9gEhUij?$M582L0`pvxmvkeBZE$$uqzB|h(KxpdDsRQ9wIIpK zt*uQhI~>Vi+@NB+Q%^GmI;=HGH-4&52RDM>%iK0NznPiD%A%#PPG{-*Dd5e`Ae5Ih z@XTPy=OUzZF}5?Pl*`o%e&ylq86HcLzKld=3xz+=$!lM3wJc1D_48F;g_*Vs63=Eb zvUS+-3L(_syN(I8J^l5UWdk&V-2XA><7?#clAg~jhs1Taz0Y#S=8_#0cy2l{uYRgN zw+ZDdGA)v2k4!9&@c$0`g>@S=y0x%%rK=_^UZJOgsKSSxH*+8W7=zxdf8!>kwRx&~ zUCUc(QNwb`!APiI+*Y0n^$Sh@bf-ILNzYS&x>+R;rtkwf z1sd;eW;%}7?9V1+#M}y5kAfs|a!>GqE--)(iCxsbJk|zH3j^XXDc8Z(3!mSi`6x_i zRE!Hf1&aTyEmefd`-b5R~5IH4T67*;s5$CPJomQENK_2 ze3JXxEPw0fjsW{A$5?_5yE$oDHwgxgoZ+N#%V}!8^!x-bIYs?zv@TVx^^tUL4(0?| zad(yY5wA5O9fis$b~6qiBJeRJq^jE?5bD0;g@1W7SU099=Nz$8V-4i^0rR?*z$}XR zdmY`A&}LHF^C~gCd+kq5 z@oUwYzG8ld>yHvF9&h{`!ag2mk5P>S|1Cealb@-gxs+gc@9FaN!LiHgL_H{iRxzsNA8F7<;RZr;5a zwJ6|*H(zS5`@oRT6-2r-y=NV1Ij9$|>tLR6zw*W07cb%!9fJZMA9l(TjE1K)kH~O~ zc>TR+twmXTddX47TAEQcZYJ-sG(U}h?Oex|v>;gAo`uB|H_V&?VmJTiXM@Wo?rS;T zZ&>*D9~pO#yZ{IMBXS1*v77#}thrwc16iCltIfoQ-hxiBGv*m76RI7i0wT+y?2mm@ z>+B}A>fr-p5#ORhO@+hE+bs~sptndnO;)Rv#i~) zSXW-^M3cqR7tbANL#nXuOI5f??}i=FsRa?$oOute>dYnt0h2Lqr+4Sz)|{-&HoBm} zkEk=ha`0`?jZL2pSs~cY?2rtRugn%_>tuh7rA8;I;b)?yecIc~0dG+{C+G>XN@V|| zi+`E1jBMs7B2t@6@1ila_qRkXWW7(1&ei>gMhHIgO$@^-EUD0fI2B1~#@9i&tmY}4 zHd1YkTB(b&7~Bj=YJ3gJWEaMqtiq}=^8s-_tT3J}41tbT2}7BWAw`6&nQ*p0mOMxP zo#{A3Z9ab41B&vo_yV^K7IPD2#L@~4%O@IE+a+){R-fw=4s)&Frzy9)3EF+;#k40{ z5}Q)oob5+XeGx*VP4bZKTOwS@L#~$zhs_a46u1v?w{)E022POc^sITF2W)E!pO%h} zb##diyS7y=5^15outRPFk_-p6rcsG|JBnj;+b80AO z%Smkh=N%;I2ezS1q>>&+!og!S0xnZj!A@%fdX3tN_C8Gw7Q<0UDAHw`92O{i_#%Zs7>73xbQCd~2Vpvh-s>cQ}Uxf}ehS*ZFnAK6CJdbvGq zd!GM%pqJ3-5d-3;EO(#5UfQs5TYJdsPdL2rR{0S@1h|!C>OGaRub02?oyfV=W_j0} z*Zn8B^efdOU6lPhtG9l&_$2}uD^(jCufuq%20(CNA+TN?KMpXZF0ECc$yk4s=l#@L0O)7QR{JDqWBbu&X(s z=%&clJRK1{IsJ`9*^Wv>8#i!2n)?)SZ$#Jc`gADYcaQWk2Z6N>%8Hed;{QbdBL^0! z8jZD@qbbvW4grQKW=~oz3)@`#F&&rWnh#`Hb*@AOv92?!Ui%F!V2YnUj~_aoPpvL!q=Gc>}7unbI0rq_pavMVurdIkpM(b3Vs zpIODu(oEM4e%G|hUq#_Nk%iO+rA1_?P@_5MG@(!-@B1^7;^E~%QqsPyiU|Eo^dP!g zz=l_<2B`mG>>6T)k39-(mfcP(uC z{3+FWyz}0*S0@qg0hd@5aXa8r$>{d%1yPtOY~!p6H0| zKwv;$07> zg@WC@j57a(3X80L&|Lh%N{R#Qq9>Na0pl}~Bep*Qz&{X~amIHOB4k&m)A5>RanJ!x zaz1dlxGhSWm~gy{oZ`CBjrU|b1ih64@C-0wE2(=9{llnyf42Ol|1=(|Zhd%jSD%+! z0RU_0^P>vRiFT{tf6DFb63}IM~<-#^EV6U5`vR~*VuQweDxf3^`++&HS&8nSG2ZSj&UHH zaNV2%;GV8}X$h4l*Q(R1m*cX7jU}Um??*QcBNBGZkOJ?O>+AWTs`>-xaG^d#o92_B zf`a}?Y?CntT&{+`h!~p<;szFPPKqBmg*$SBL}u=q?=)JoMLF-tezN0xo;Nbq_5K?% z->YS9N2yo~%hji~s_Ht~CsN%x?WtC$wBLgf_WD^y76Rf~zuWr?-Y+QAsn6AB2u^qz z-DoWsi?Au~7hZ5A;eqxTVm%E2K^Z;eZ(|_+TZ5M6=inz;QB#vx;`ZQR;SL`BVuk3WzNkHjJ7W!-)6GISE+F-Xi5aP06!!0^88OxOo5 zN#WfYnvpV;k<$A47ij3dI^>D|9?{UODzwI}*nKjwM~2Z{qiw;yN|*kh2)*gE;99iLKOk zmXnVT&VK*hW-~A(9_m!o#CRfS7Pq$JA`|!OATJ+C88U0CeoFc7l17~A%BPGW=>V%@ z)Ua@tM3UyMKpQWShS*-~Sk%7h_6`W@3{<`aC`9!;N4P{tQFY0}79}{G7Rmu0xVRid zRobmxP5KXN$x086O}edB<<(C-ivq1xZCx)Zo%=GE4@7d&?uQoFwSsYWn-eWeS=Vkm zHa?tj1pYls%EAc99d38TWwxT(Z#rU1gEB=CneDFg*hx*&Am)G|MparTN#sA6jcJk} z_=WiZM>SMd{ zIeg?o+y5rZn9>?f_ZnG2q5>_2xHSsdN5HapAh|7MTfNaiv8c}My~k`PZ@5K2UI{0z zjw+9y$UizKTT=qxxmG1%w$uzr0^-ToCb4D13JI0AE9na6{r1N-es(zTAhD$rw5{-t zt)?4SL}qnrVVEw>i2#(vHE9PDO6Xf^AkRQ!c|y^jx3_Twn676WW_%b#bK^>WIOV|0 zR!g|0zVnef`WsYsm8O=K3Ym}l0!)a(nE_#nM`7W*p6+&L};u=W6tu=x9V(C1BNCAb!@zs!*X zOffFRjW@0xXc=Uwntt(9XaSK+;?t(n9Poa4I5u-!6$iFK;i%OsypoMHWvmH4z_|ZC zM;!8uvSxaRds;ja1`q-^)d&?jtPGLca%4zTZlU%&=LJPv)FZL z8Ou&mWWQ8f_INxC^Mi=*(gCL$Rk7%UkQ$f4GU77gz5pe&%>=oh-W@-ti-ea!h*~10 z71Bfpn$E9pmIT9z0bVzlz)V@a63{0%oTaXf6N=A`SBSY+nEhF%3} zk?~0Hg*x_So#5_PG`z)G^gL7cxS7pBQu+XCWVdvf7PL!LH#bI)5B24A1%zO_;829XKmDa>9MT+VzK9Z(N7uM z&LyF9$#B-v$X*8^OQBTWINe2-JRjDVe0B3FvK z10M!c4S#bNEUDRR`pv%ZLyc+x1Neq~ts-6r&ZfrF8_;`zjJa1vdu=2oa7zem6d)%@kGK+XxqVb=vvR#7NSXhz`;X5Pn1sZ>T zqn2d&Y9|_oogsNGp4hNI7BzABZCm4Mn83-DfZ!sO_4lg3Ys^UE(2~u#lA(cV5g+p}bNFI%I0}yy zBgl`z2rcEW-N3ArV<80tc?IHg-N_fZ$urXlbVESeJ#BJs10i&K^uV?(AEXaiCb6m- znY^W6Q(=;0tf8+VC{Z`JRt%)aI_spgqihF4Skn7_KEf)zLNY7uwHstef7=>S0y_Y< z(NjrTEf$Sm=-5gi90;HtACy4e{Pt!87>%KM*O#{UeV>a}ezK|(mNNdBc-tZ3o^Xb= zX6oK>kxGn-=Hu-MRhgH-!pM_>DtvEH9L`s~ZivIw5?kQf;D@`jM08At6LHNxexo=+ zjfL$(L)y$3Sk&^8_&;@hby!thx9$Gi-jxSZ4*Q@LSDHK>!Bt;WAzsu`!ZfUE%+@Uz$OS5Cl6aw?6g~(3se+7!wrh zB<>vPB*;8ev-Y8jNj?X0z!34__B~k^h`Fm%fZrDRmvf8w2 zM|9Von-DM%jpZZXSK#z%gAKDLq)=bvG7RPqg)8y|q=`pnNrq7Z8W8S!IuW>Ssjk~1H#BVy0I z0PD}AaQ`BhY}VA$$gM{0#+v%X7fZ$|3xgAs1SFufMVK4WU~n7>o^{DbQno?={%xm~ z4_8z9+)Lby^Q}va6*a8ai%Eu+En(uA)qdu4O{4fbIVu!GJyTKJPtRP4ZGOgfuOR3* zL6t}ymX_HAXiU5)Dl>U^r{%3Q1C?DgPU-Md(Mlv`d^Y6iPsiSHkcA2MeO1i(Q%=0^ zXg)sx2N+IYJ}?@O+>bi(E#KnP_h>twfw8^Nifo!FR-KDcj>(hKcUaf{${)8ww5~^l zpn4D#qplqis!mR~S6oJy4k#(97-r8~0+N0r)uWdHwC{zk2hlXOQqoC_vBzkHz)Q{-a{RK=nsd9f^{shPm3m-6NyG+sC1P9QU+gU$^o}e_!wfy^iF?rWMfh+DSF~zI z6Ho?w>eaE+E(B6t@f~{eQ6}P^)qM}WL*vV)rKEe^&Jk-3Oj+Os(VXw2aI%#f38fVw zM2zN5A224=oWdjU=m@z9a;t{R{0d_xT>m?eds zsMqV`I_gun28ucId%X`6T!Sh!QBgPyi6t+b>IW;o;TSm9ze??ot146jATHUSehF+t zv>l84*Z0Vk*1?V5As8SBfa;(^QJ! z>2YVAC@OW(AqIc3e|%Mk4~eK@)~C{<%jJpH14fefizY>+AcipzTPC15Nqo@7*E@}d zO=(4YS%H|MGrzt-;%>*xwwNS*OMdy4M!SX@6|W}*SM(A~NIzE)lPfslQWlKvxJ^$q z20BDHf^ZG+M|>FQXsuwFV*yf^IG*Zqpe7<*9Cf62k+*sc;3meazFi$e8;c65Iz}eZucZOm2ccwIgHh|}>>uC{ z*KmKDID4D1D)Zt6gL7AgBC$0W>y@y1u|r+w5xvr~gO9s_9LxHMZ8q914y?g@Z#R9| zpu$%RxN4W1Bv>%|>f`ymIvg z-11u$@gY`_KzWUhz7L?5@8;zjbh6!2qpA9$;zA55JA zD}LVN2+vl$f26_tA1GO|evqwKpkuc~8y?`>D(m6O5^(H!b@CWPoZryzp;P=~UeM~a z*s@u9yXq?Qq)+%lvROD6Kf*Y?R^&bU5h=|(t))@o3LhjhrtESfbosT`64ZU12R~iUac8@rbg05`wv`?H!C?Ihzn!N5AKUE%${PaQ zGY`@a8J08`XP7a4rV~yp{*5;eFI1@ ze#<~B%N)T#wh<`*dDOFG^GfTT{`!_Zhc6h;{$uo|cvg@^FAiIQwF~ktbpL+gL>Udv z^-N%P65ZQyL3AjwHRVAX%}kYWnVmyW)eK!)@*d=cT6T`2wA3GdA&SE^)X(9WYCuz+ zS$1KE86ZxFkA8E-bikx!WZtn@3+}GnU;$!UKXLe$s{f}QKlwk+2`+FU5VB(EQWlE4 zboPu&%G&sMk@uX-&tluf@NJ1{xRR!BjvQaV@D@G;h&M#6_TS>|b)RIU0Ha|OHoZ#G zyYu4ImW3b@^h2gH%76lX9G)G89Q7h6U4^i+!E zKyR!Tr1K`QNQ+5u*=aLRtUEE2ONT|AmSnOTgbLRkqC~rsjr!BElj5ilXvEqFN!8kHNjPr3`7RaCZB`0E z*B6|@nIO37uO-uFK)(BT^5lp8lRUp^`ft;d0t+l(j;q7ru`_D>6S9J;$Bo6bluT_E z!><*KRD8o#f6v9=+O`(_*nS0Kq~ZZTcft0Xr!U>Rv5~im=iZKL*Aymte`OSmjUjnr zrmEJ=v=Y$FUBG*^s;VoAw2MOrj=!Y znJyCsN%v<>`6joc9XKeF z%lie~6k-kvT&uvs8&)8CCky_}KsOsa#mgL& zs~9Za79b1lmnS)UEo0I2(SKUB%DxHq3@BO9Dy^TFUG(p?f=RtzA`cRgz={5ZlGbhy zRl+f&x?<^{tbjJnk3S0oqMCS6h{mO&LfFkb@C-6DPC`E%J*M%ox;J)%XpTPv6ZXk{ znGM^_72e?yIQvB~0qm-P0O^SjpO?`ap9*)tjKe`0GC;U}V$ zn)js|z+)o@Qe33XnWW#@++>bqc7^$zFM&bfu7^W_)X%Df%|k2q2+&9|?(sH?b_hJ) zi&lnh)gf!`>vbAz^OaWh>jOhm`RlkSLg@*2kb+ioc|pdNgA%syF8Jh(GGNu6sf>bt za<;(pa}#sNv5X6O3u~evq?_djgRw`A0zQfdW|le`D1-@aL4{^0g*z8s`a#F&H>XLb z+y5(fB8MOypnP$$8cxJ^5(3Ill}dEz#YHm;w)za!fUT{^e2sg_%^YHOs56M_ssqCp zmvm6l0B$VIodoJDEURXp1~~tJz#Cqo5BhUgK@8T<;#d?=+~&*aNN3wcE9 zI$!%^m!KTSz`37jZFXn>58T?HvQp#{w$Ju~IeN9GrBr^PKzJ)#s!hY_BT>P;3bPWB zv1zd%vT$O~e2XO~w$)}IodG<~j*)3n$CoNrG6^*eo9uCG1+1%aV*i{-X|_?S*!=zI z*@Fw`jXqdy#k$kND2#B!*XC;fgw$q&KxM~~pGQ#q4vz4YU;4N6fdoX3#@87_Z@tFp z$9 zWmN`Koz;>8>ZC65zU(yM_#?1cxAQlq8<3efGwW~(yTa-{r1PiBjF#b9SY3t~RHA0` zsWa$Vqs7b>lOc5(J-3K?3$T#k7tLF*Paga)9J-5e=$4G?M3vBI)Z zkZ11(-6W@J9Z;!d0CQ6$rl%l^3`|Y%?@ylOYLwpXi69H=frvR&(eARkQ9KjlPx$F{ z$^d8%^=CF*%!+4J|Msn_GE&Q&U>KG`#ArW(rD2Ck((ui}l4lq;F{2CmZ(Q1y9>qVM z1rIw^z(;;4jaEw(Ujm+=pU=J%mhcI`G^{HAjt&-XnF;9pPBlb6G=x6$w>Fqfl471u zezN;c@N@U5&*ZpidM`~1n0a?wZ_{XmehF1k!UH)3(KW7PMVh=#4QRB4iRQ`$!E)>P zl?e7QLhpCj{hLL0NI%^>(Sc(yEvTYBqHH-@So-8ReTyhM!bD?r$dQvsO^h>j$@3=f zmBPDw37c@;zeD-yQk$uvvs2-q|3ITgi_TSV2PGQC10zZ!@)=$E=oTe6abt z&@2#!9&L)MA?SX?!Yf0jQ0gHfVyFN|%INly-zKw>`i*@h&V>m~cP=@ww#t0@(-Th) z7&p+UUdvA}7j?efBHZS*xn5t3V(glzCnSQu2Ygby1fX(Hgl3d08Eqq*ihej=6#B70 zNn8i?iQk#QumFPArUpWvBZ54FiN4-0c;Y`nIvw)*-VMu7`#X=)$g9Y35* zHl|co<(4`y-$M#D0*&*AJU=Ch+vsG4Azd1jSe>cfRBUDX2d((&Z$pK)nTf{!NET^s zuxCbBu3K3H&J#DyB-A)8d6XOaQhckBxss7QfH@D)s+W&;A#10FY5C(yHVLr~D0HOL zy!3?Vfq~Tk6vD4zL6hB1nefx6_W$-eDF-SO;rd0PVEGNxvucA(Yjo&y8bF!2=<9N~ z;JG3Z$tFtuAtaKRRMV=eUTR`!vo%*Vx_=l|T4MP^Y;y^a=v72GHInF*A4?ExBG=uy z?jHz*>Uht>G)e?(mejoY6WcN30I?Kk#H5dp(`VmWLAUU4rlCBe0BYCcOf$3v#f^3RY(!j2x?@F;|<%9T*cP_f9!I%{7Tb zQJp+DF_*mn1oJ z-#YeWxtNyb9?*|t0yqmGo97Qa1U5~P+Av5NnjecOxtJ|irnz^yU{p;%{CgrA$5)?v zOzy37JVyKx98x&|?dC;b??C1KyB3huh`|+@ea4m6vhnV`9h@q%__QdQ^nwE*-Tveg zAaos~0(=YuCB_Z!A^);L;0svyv0Jp{AUo35BUOOZ>s^Wz$;L>-=FGz^~_!!S%qQVbo); z?K3Atw^sC;7Gxk(2AcSN0UFYBK#(cj9$DLzfn)6es|9LM2r%y3j|rt{ibddr(ZV9G z*Z`o0A^aXX;ut7dB3M6Zwx1G`X#xU~G0I51RbSxD>qexgf=Rp=lx%(uYx#Hi^J=(* z5@!L6XlVm#foAvfVT5~T=o(vlc_bm}XhK74ML*M#|L{GiEJBLk9H5R8;oLNXpF$PY z^CyVgnX8NKme8sGi%~FuTM&%GGF~gk8&MacXuY%1FWn^iSZ9cIuFaeKBe_A zt#N1gPemc`x=jNTc>Xj9Rh0G#5TPj!*V==P8;ew=H<%8J4k6Z0EWh>xk~l%8&X!VV ziv&NlpxWYLbAdV*&knBSWjl3RU6po%tHDW$gRld}p@2iCl6Ks1fUes^9o)%iO(L$th^(^eI^dayzmO z$j*we#Q7*K#R6ax6a$@XH$)MNR;t-Rx^gA!dSAiu)+mRG2vZ)-6-~e|5kNDxi}KF( zK5lH=#ec}+$^|#*S+&FEH77%>AyFzdNTTF}C zPdOlgYChz+E~5t=ZioT-Z#Fl6Z(IglYsdfBcdO+iA1zKgE$|I%CHzx#&>TMaQTq#= zzEdFQ)91@gXleJ!@Wsj66f_H|7-)p#H%?4Fa;MU2Vg1brq~+XJmEIN>LJ}^TDm_!m{xnLgy#mI>BuxDQqw$lrwI7Y}N@3G4 zE0-$9)QOJlbi%Ijjj)R7-ohspKQ()FN-1KafWas}az)AMydR?hS-D*pTJM>omHbm) zb(ggMK0orD*prHR8tS6_A|#Tq zKTGKZDI=QaV{ONkfJ{|NAE68eDA7G3L0{QMZHn`pdWmp1b8pb}F5$?~dPHTo0Qs}w z%@g-dXA(BXkDnjt-ZM?h0&^g^87>V3M5#9Jy?vhtJ3=1KvT2#y#Y#PATDEy%Ldy?+ zSRiEW%nmFLp<-=Hjdt&=1-GHL+j;+#YRWr5M!A8y1CppIB+_4ykVtzC#r5+eT;;_@ zT2!%cjr)D!a;Ovt@OZ2UZcAAWvB66`Gn-vE9_pJHe4vZSP7yAivsJh<&#N0Lay!CA zCci&=x_m}#aG{>ZK|w;6;QwZcI~s(06S;QwJD3vARrMGBegu@BV)^FA{~BrWC7nPd z;o~TQ_E1sNoaTsTI3{dethpT@2<5j43UUyNu}pgXNL2#x7ioc)xKbyw{)T)ohHdXJ zs#AH?SI_y_|CP_HEs!=@0m?>A$B-%zppkpf0$7NX&@NOosV6=-BRDzvvO^b@cJ(LW zn^jbTc;JLTs_L2}C4eEYOJ+#o632mHfUr}6CDo&|{j+%0+tHqtXdIWK2&JGZYVVu@ z)TxqQ(*O!x5IOoT{sRc>gZD7LFz*IEdU1k}U+{CIR{t%z1qxYE>qxJpMKmkCVgRz@ zr=Hht{J>cDgEk@s6yj+*1&*9uPt`pd5PyznKjAilr3*}~6O<)T=$}xz6dl%#zUowL zCA{@B>%^~cSS9bSd8IN}`u`{kMu8?o)z1d^k&#Q}7wsS2>n{zkV30=SV0Bbtz5|SR zUQQ1*pY>Wl&dU6QQNCgnYT54^iN$-+5MIh*X_NC{MB!yUdt4Nd3|7v%jw=vSwBo;jC1oa-T`Bg(%$Yxx*x<|G4ZC^ujjyT`Yi1 zO+#xoJVQs#7-BX%cSqRC2VOwa7_CDi`IQL)EIlsfg=h6sglY)w7;jbuIN(h3K9~_8 z9*$jV>V39V7m6oGZH!4*kc_aE6Z^-t6CWZ3Q*_R5&>_|UQRiFHcqNN9=WX{y?x$mh z7~X{LW~FjtKn6rLW@-JOe763MUmPI62(QS;sRs6U(qTn^H7oCzchdh0KfJTpnxngg zqe!YE6sUJ2l_hXBSDaKBiGZg14UF??5fA~fQ_qH;=9bHPFR`%jD#?}RFW`>$2NGL7 zhn)c*h-520ACRa??ud{GSC#BZL1EE_ElXM4Gc*%LwT>Q*4NO+3ks_1h1Yk;xgV5vg z9l!aMG69AC8o(kvq*vUsE`6EH*ed|L94o(>VOX{d3h)yoR*#eEf2@RNy(qgt!#eP0 zt8n;f*pu*0@k_}@i3&v>mVYW0XcON(o_0Z1V?mNMhoyX8jhW}S(O#hY-Vo_uuqLL?&u7Cug^Ie~>nn(A z7GzE2VM?Az3b$qLg<;#^HRcFV;^r4IoBR^fiQV6_*}(W>yP|~ez*mhZ+e6N>Kp$mJ zVYom3W)#cz5IOb+exeAWI&L|vd`>a8d}n0Y0|J&%+JDjK#0CU>N$$SNVG1ml=RTTh zabSp%Sfpn>Jum%5i%>o&=cch)f>F%?&av?Fr8(x18Xt+fS`fNJaXG`64jfk>pmr1s ziRM*hkLbFQ5*jOH)_96N7i5vuh&9Yj<0Mvtc*>^1U^rqpu_0kP=ZGii4l;XQ1%AGf zX6kbZIP=~-F1+skTN$Yb@&9OVZNrt|Xo4om;C>HPjGvx1&Lob=D0C%H9dt+3(2_6A z%3@rgRYe0q`O?ww6%;@TNUxUD97GfHOQt0LhNRcR1(kMKvP3J?8pzxbP$)S*#(R&*{Pw^Ja0v(--wa~q1O>n|~36N`MVUbJs%LlD#}-6XFh6_Er? zgrRmHD_&X(KpbXOmOl8b!{kZclQ@8@MNgj)Q^4|FI||)7ATagV8K3~0aiBV&+PzAq z3-WESS#{>&bGRzj&h;2O=a&OIM@C8i3;WL21zC7|p7Y`#qvlj_G|*D|p46OWV^mC_ z4_!;&&>9|L6zy8vls6$ZY}+it zD=;0GgWp&ft%aE*CsVOZfZoku*`1tb4miWHB)^fFy^r=%QjWv*5ym<3?EG;V>6w#T zM$uP8C8#Zw?%cL7OMFn^j9;DE=2w?9QR1LwKW^H4aP~1PhP6sEu4$4+HFInBQ>3Rq zz1y$*CEGUx3dOrr@KgX`lDJF0m-eh^A?M>CgWx{MJV!^Ot&>yN*A*Y4+mTZq{O8Q; zugPR-cyi}5=qpRQRQ0W_kp)*yt1WBPs#NU7n)39tDtML~9zd)HSW{wz3z=_lrJC`19lsOu4++l2kXdwHG5OWrvQ zs1ckR(9_r2l^UzcQs)&?j>zN{%Y+-}tDAG%T%izi1P+<3%5Pcbczd+{U11+rj{t+B z!|My-uqX9syt^$a)`T<2d4CJ!CW#d~iDA;J8<)>Qw&qlVn&55Wc)#K6i(%O9}xnIFi-z?7_Rw(nThfbmbC zjwc>_rsv^gZlA4U#qQH56t))iKQ>^?k?uy%y2m;s5#v5oh$C-cA;R`1y71(q>^Lg; z^&L3nG>Lp4;Qhg-7{`Az-4&VVN!@=iEygU;JlQu3$XO@&RugKDMTg3qFX-8B1K@*M$ zo@Cepv3RyZTq+Z?cV`7r! zL1C+^fewPzn%OM$zKG|by|xtS)P^88BcKm(MUx2c^-LmhwSa5ML(ZF7D4@$3LEYYy z!fOhQz+scO1JqZN#1%beXrJVEBebHgl>=Ru`*)1_x#PKAv3M+!sRQFjzlrXEc)|}C zd^A31bSfZR`!w_tO(cZ|Qr- z#WO99s9~}6g(y+5+^9ppmv?|nzJ2%BMqU=cuOgidp>-10;*GELnU~HRnK^;ync)5K zxRPOa91)qU&6N2Ps9x44GwBodb|>C*WS%e z>5?0npd~;$=uKf)AZ~C<_`y%$EC#GMxAAToE z+-3`!=nK7z5QRr<-r1p=-|G?nza2zrQD2;x;@=_9=~j#IbI8PgeLDUE+lxcrBbTHJ zYzPhXc-}G%4KqCKt)W=7CB#wej$2MAVICKUyu7D$^=_ia5sO6}*SRFWVpIVZS|g+3 zmigoSX;S0F%m$m4SyS&K&57-I@X-eK3!LivbHPAY4MuC^<8cZ5N>;N$7u?=nrku|^ zf?f3V;RwE>(lXHgX@m29twM#obF?<%SA_6>>0`88B7T0llDXTZBOj%Ryavky0o52h&2?x`f1{;P&6Q_$ zU95^fCX{l5-glOTt_^f=Htb`n|yFbTy@)YV58g3qpVTi+h2Wyeil=A#@^mwn&B z3H0hhx*T~Zq+w4h079$?qVr%j>yH%y5d;r?n@YiwXIrP)zSrO-y zinWnG@kcGr^ve7>RAq-IMbbnme1VCL9EY%Z1XQ6XX$8Rm65|V=)=u5)9CX3-o5wHH z;gYP!F;D&L@EZ8wU#J3ps0IiQHGheD1bj3I+Vt-Lww?u+4}Kqk`|~qmEZ*U*S5Wfs5#T4SMpiv;{714T}3*zZU15gDPRf|ThY43 zNm!6e>w&-)PF4oXRSso<}1qahO%^g*_{K@Di1U-ZvvPQtvpxbGDD2kQ>+~ zvq;Pe-#!xRythC2D8Al^;EVEYuXU4ARCBIR(KnI9A(lr3yu(ttF2gl;jzkUmfi4{5 z>9(#baT9={ixq;=T`2ie?<;4PlFcKQ$=8Lb3|5kPt3vEev;*m1oZK+l^beGd>^3(8 z=4=~MlNW&B)byEiY~-2rndF201Ky>jp@WYd&x%bwvu=tYN{l3w3??0p((1oD)WGPPenV8Vv!-1$w)g>*ZUGtTKfE;fPvUVYXLrV z;~ zP5YQ^JqZQ1T^1O$ouJM=o}Ie*>@~nIRJarH z#%9wM#a_nq15`s~w;*cY^|PU4?54C$&6%f7kI&$xr=#bO-yDyzg`!3>z?|IN@dJ4K zw)WAocM0;_QF!NVA3g5&1=G5QK05BtH`TV()Pj_57N6jh^}Y$FxH(`I(VEpw2RE_w z?~S0~yOzo`PO&Pr59Px(JL=B&#}F_1{*;#c%&x)jRNKp21l2N~88r^{X!zTDT{EO! z{WUS4M5zvCYy9iJiYU7BQvIFg$9bL}^LY5f1S}H^N-G-Q7>{spBw=y#}{$zbiL3;Pj)bw}X7wYF^WJ3a< zD|kdiDkmpxUT#5;@b$v3lbxDc_tVC!O?rP}6#x8SZq9w!!8_%9qT@x4(Egb&IEoN) zKg_}*7l?z>3z=J5$_x$;t|)bhtF=wmmkD{_r!A}C#H$na%e>nb$4qn_vY&^C4zq^k zc$%7;->N!4JN%p(k4HmC=jP&ygFc1WT3Rx|>B8ddy=!Z0bwd2eraOE^dbQA|;PATE zv;m(@FEQ5oYY+QgqzQIsQn&qWXYpTiyiOu+Gd_970{dx-N!zK}Yx-pZLQ5_+s$=sP z#ODD>h31G%EFLztpUxgNgf3^I;a5bjKo37uj3OWITiJ{g^<_ld#wy-i)9g7H6!HoV zM?#>5<5BqZ90Fc{FDyPxi%Mk}iQK$?P5$KsQC+$p6nW=$R!H<**+PB|`Qe&8m`ra# z#^_EO<5$xI`L)@vE`$8H;=j`JQoq`zblgJ0dj1!DR)6odeF%l=oHmbtqbWp9u8{E@ zPP6OVF7RGxy{~NM=C^bcOsLTZE4{mRePcy=zO{?=uiK9%kC&@v+L7JG-Vsh@qfmOd zoc+C>D!Y&|X>AnJmgIa^6DT+& z25GGHSoy=lWTDg%%22Wv)q+4oFVlrkHQt0_KQACZGngi-sxmvB!<^M5@rwz7g6uDIoJ(?U>`!Yl!)q8J<&AQQinAyZPN4-mqJz#m~&_HH9E6 z((Ag{z~}iS6-dgbto14AFuzpIj_)66mcCSV2>2r5@uQqobPBd(TDwNGALLqC{Y`hu z3UcgJy`DdUEK0#OSS(}DS-O|y2HebOcJJ19>g|NgC{OsSGMouR{RsmUk64!|>P#xz z32Klt4|++K%!rhdQksfsZ9B= zH4Y-eNEiC|KMQ#^{~Q>QoqFZcHat9BCcf3Tx@tW23KaCMzP{%u-oLJ{u1vhI&cNpU z&teqHG$b`O_1gjdsd4HjBbPIm?4Tf27G`Esaw#}xZJD^m-0rT;!#}TG-%YKqQqcv> z%nS(lweC#1ij3~@`7J=N&um9B|8By69^n7;m+Ra&0<`bCm6)^taD|MdqC|z5(Wn0d DnC6wV literal 0 HcmV?d00001 diff --git a/doc/html/_me7_segment_display_8h.html b/doc/html/_me7_segment_display_8h.html new file mode 100644 index 00000000..ecfc201e --- /dev/null +++ b/doc/html/_me7_segment_display_8h.html @@ -0,0 +1,296 @@ + + + + + + + +MakeBlock Drive Updated: src/Me7SegmentDisplay.h File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
Me7SegmentDisplay.h File Reference
+
+
+ +

Header file for Me7SegmentDisplay.cpp. +More...

+
#include <stdint.h>
+#include <stdbool.h>
+#include <Arduino.h>
+#include "MeConfig.h"
+#include "MePort.h"
+
+Include dependency graph for Me7SegmentDisplay.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

class  Me7SegmentDisplay
 Class for numeric display module. More...
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Variables

+const uint8_t ADDR_AUTO = 0x40
 
+const uint8_t ADDR_FIXED = 0x44
 
+const uint8_t STARTADDR = 0xc0
 
+const uint8_t SEGDIS_ON = 0x88
 
+const uint8_t SEGDIS_OFF = 0x80
 
+const uint8_t POINT_ON = 1
 
+const uint8_t POINT_OFF = 0
 
+const uint8_t BRIGHTNESS_0 = 0
 
+const uint8_t BRIGHTNESS_1 = 1
 
+const uint8_t BRIGHTNESS_2 = 2
 
+const uint8_t BRIGHTNESS_3 = 3
 
+const uint8_t BRIGHTNESS_4 = 4
 
+const uint8_t BRIGHTNESS_5 = 5
 
+const uint8_t BRIGHTNESS_6 = 6
 
+const uint8_t BRIGHTNESS_7 = 7
 
+

Detailed Description

+

Header file for Me7SegmentDisplay.cpp.

+
Author
Frankie.Chu, MakeBlock
+
Version
V1.0.5
+
Date
2016/07/27
+
Copyright
This software is Copyright (C), 2012-2018, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
Driver for Me 7 Segment Serial Display module.
+
Method List:
+
    +
  1. void Me7SegmentDisplay::init(void);
  2. +
  3. void Me7SegmentDisplay::set(uint8_t brightness, uint8_t SetData, uint8_t SetAddr);
  4. +
  5. void Me7SegmentDisplay::reset(uint8_t port);
  6. +
  7. void Me7SegmentDisplay::setpin(uint8_t dataPin, uint8_t clkPin);
  8. +
  9. void Me7SegmentDisplay::write(uint8_t SegData[]);
  10. +
  11. void Me7SegmentDisplay::write(uint8_t BitAddr, uint8_t SegData);
  12. +
  13. void Me7SegmentDisplay::display(uint16_t value);
  14. +
  15. void Me7SegmentDisplay::display(int16_t value);
  16. +
  17. void Me7SegmentDisplay::display(float value);
  18. +
  19. void Me7SegmentDisplay::display(long value);
  20. +
  21. int16_t Me7SegmentDisplay::checkNum(float v,int16_t b);
  22. +
  23. void Me7SegmentDisplay::display(double value, uint8_t digits);
  24. +
  25. void Me7SegmentDisplay::display(uint8_t DispData[]);
  26. +
  27. void Me7SegmentDisplay::display(uint8_t BitAddr, uint8_t DispData);
  28. +
  29. void Me7SegmentDisplay::display(uint8_t BitAddr, uint8_t DispData, uint8_t point_on);
  30. +
  31. void Me7SegmentDisplay::clearDisplay(void);
  32. +
  33. void Me7SegmentDisplay::setBrightness(uint8_t brightness);
  34. +
  35. void Me7SegmentDisplay::coding(uint8_t DispData[]);
  36. +
  37. uint8_t Me7SegmentDisplay::coding(uint8_t DispData);
  38. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+makeblock        2013/08/08     0.0.1            According to hardware differences, initial revision                     
+Mark Yan         2015/07/24     1.0.0            Rebuild the old lib.
+Rafael Lee       2015/09/02     1.0.1            Added some comments and macros.
+Mark Yan         2015/10/29     1.0.2            fix issue when display negative data.
+Mark Yan         2015/11/09     1.0.3            fix some comments error.
+Mark Yan         2015/11/12     1.0.4            fix driver API.
+Mark Yan         2016/07/27     1.0.5            add display to support long type.
+
+
+
+ + + + diff --git a/doc/html/_me7_segment_display_8h.js b/doc/html/_me7_segment_display_8h.js new file mode 100644 index 00000000..11715e97 --- /dev/null +++ b/doc/html/_me7_segment_display_8h.js @@ -0,0 +1,4 @@ +var _me7_segment_display_8h = +[ + [ "Me7SegmentDisplay", "class_me7_segment_display.html", "class_me7_segment_display" ] +]; \ No newline at end of file diff --git a/doc/html/_me7_segment_display_8h__dep__incl.map b/doc/html/_me7_segment_display_8h__dep__incl.map new file mode 100644 index 00000000..3daa8822 --- /dev/null +++ b/doc/html/_me7_segment_display_8h__dep__incl.map @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me7_segment_display_8h__dep__incl.md5 b/doc/html/_me7_segment_display_8h__dep__incl.md5 new file mode 100644 index 00000000..f654c2a7 --- /dev/null +++ b/doc/html/_me7_segment_display_8h__dep__incl.md5 @@ -0,0 +1 @@ +733f585832f991a42cf54b7cf136af18 \ No newline at end of file diff --git a/doc/html/_me7_segment_display_8h__dep__incl.png b/doc/html/_me7_segment_display_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..be5cb14804183d0e59687f47e986df599f343232 GIT binary patch literal 12914 zcma*O2Q*z>*EWoZ=)DVqgdlqKmgpsjE_#dJdneH%I?)fJ_g;>6l!(qj^iGt6qxbIH z-1qa2=N;epzwvKl*vDRH?>*OCvt099Q`kpEX)JVdbOZzhELj-|6$Aw2T;Q_+>EN>I!;T^ybg!%Z4W}P4#0!OFSmL*t7W`?bOhy6 zOrsU*1|d^&W6{Vu6MRIA!ANdZOCR2kE|z1GRM%8@SI=x}$&8k!8qq6&UV=oH1YEcE zmiEsBzWx6=#>vB*5b*HuENupo*hFUrS;LyJW2+p_dnQXi9m5OZxOjL)+zQGhFKB6L zBZmfAIcmJK%f(G2%AZY2>IHrKCR3*T;uSEaZnW6qshspeC9X^dET#7q7#Tv(W_>5| z??E1p#0b3R@ksfIp8KEcrecgS`2SvyMaz39_n!g!AOC&BzY^fr5ix5xT>KxZ9gG*(}yFae&)xuoA1MhbvlnDbgVA@NfvWAgbO@wYDrQ^>M zMAx|ergpfl(g2W}v+Av>67WWH?K0%|buSm@J^+8bq<*RbjH$$HlxjI17@X~M-3!iE zH?E+@T@evU!wS}OSj;x6_&CrUxADgt0pZ6DVlmtNhNbkW1A z_pP>Y9_DUIZQ<9JL#pQ2zXX9bVPwOa0lpfW%9VkTJ-wov2TfAz`)FD#JH`x&tSYyz zeOC^0UDIxT?yLtWTIO?6=np{O;~wC9SD6IIG{xFtzPMO7yzUl-Bm^^?jAX z&_5ng(r0%>+R}{vPlDBeX-;(hV<_Zv3cL$0=_w0b_KPir@#ITz_5oD1XF2B*m>t_#uaLy%vGa zCpXXRQlhDoY4cgLzv5e&(`0j1TU;U7c*AKCiS^#RqRj}Zgq3j=P{u-cv!&_%y~J*I+wE_>12gFLj-22iU?-;D{Sh}7zeZiW zq^w$MQ?xn2`nt4F@3xF(9BBVOxo}fN9*c|4CSA_>s47VMxioNk8O0a%8*dDafjUxW z`)FF69W~_a_y)S`sYxPw&y^In3`b$e_lJd2*&XRB^)GMJ0N#bwkIwe6lAKMSA$RCx z)V<+GQbIxMRSZ*Shkpn%`s20OAP~hhcet17s(*6yECh5W)7WJF;YMw@S|D+0SElau{d+Ryhz>n|0A5XQ5gtnP{o166eb*5>o z1GYPvbT__%@MkIot90pQlG9ZMoR>DupApx1^ay0mPj>BQ zfJsQO2P8r@g2#M@m2Vx++jH(9mx0q>6Hq^%O~=PpAbO&GCGODP{smc((;NB*e%glA ziWI6ejTzA}YI+d(0_v~pnV=$!Z7Q#pgbwtZC05`l6WEWnA4q21T zD9K%yi}^R5)kvF@lt6uj}Rv{r4N^%$7`ov z2=dwmbizaiR>9axPoWw()8zCXe+9#LPmSwOQ$$3oyFNu7z5*4QBCDc^@6As_dhd*D zUFWMiqNywu&tzVndJTCjWTaL>--9%rA^PWgd2KKO!H*w?fEYp``H(DRD47mu&U~L= z;bwq)y6$*At6&1mR&EEM(^>)pyk$;}IlqNU4T8K)x|d3=z~;`v`;(E20u~^WUzeoE zm>c{caZbWnoSS*W5hc5f%T>AWt!DAXw@I2U?xdtj?U~({{_BvP)4Z~wjtktpo z((6^ok?ZN@r?43Rj^sXz&IJ&=%iRf}2OX0I4fBd&oaMAV5WieS18>0nmP2dDhn5_H}FuHMx%iIg#L*3RB{BU4+zjwRL7qw7c3d+m{o*%U^MR~+k5vb4@5%z z{19|x&-l>hFO!lF^CmECb-Yr_Sr&Ji`MFA9V?u`bmDDg2s!AerYs~tL6XfAiT}zsG zF#7v!GK1BF3@%4rV-)vbv{o&fiUb>Z-s@V!ZzW%_xn|KUp`O8OL1qERV21l26}i^T zN$Y7hLP#1-&bDT_3Ha_8;dL0h6zlUF76QDNHb@zL9BP~y+Z?BL)2QGwZR0jJn42hg zCYqewjGHEtYF%#PixKD<>V@9`s_1k1!fK})UWm}|Hs=erM9lYGbDG}{JNMk0d2YjX zcrHf8IX1Mb7xM4Z6^>G`xI@dfGSrAy`?xW7DrNTs_m3HCok}_k5N++==+D`u$(1#0 zy*erHr}&UbzM2yRFb z!rMCT^8A+nR{=(V26~WE<9x#?8x|53ibLm6$Fey#*oCc@p+{xE0~ek3S*k-u`vuJb zc#YKS+hJ6PYaWzAtycje!uz&0;#fAqqe)sNajC}`q_yKCyB?Ri=}W`!#r(+$yX+R* zA8b#3pEJK(S~DeTT{-)r7ablaZo8ByX;j;yWPQ_+)pq3?#P)@x3EWRkX8iYy|{ zsb-53LfP8lmUTNdn$Zl1jDf;mkQ~FbVe_eOM86rpM+%%G_K5CfmSC8CQJpUONx8t2 z@%$xkTYRoDedy@QuvD3(kz5!DHK;KLV4U1GPM6UFp^=%fdwm zTViopP!W(pBEHDFQ>T=@b!64E&~}f7bWyk+Y)|FP`v-0@1Loz@7L~@p)lKNen|{>y ze^J_wkf&S>EZGuO&MgwpFSqt?q<<1H{611bwLggD-aSiNpLMHB6kevL&mHm6MO#+j zy*ukgF0s?G5nrG6D~2t!B|ElIqi^G5gG==+N@%#hcwi*0xFAd+#gFxHqrf#-YNx(0 zELQ8^$8>@*MFI#6-)!q!K=LLRPJb#z_VByc#`GJeiTh*Lo1MKZC0-{zD_K+rzzO+d z{3UXMOWFGt1jiqpi1AVI(bjF^LYW)AXfQi!5>jQF)H3IGq_MD%5V|iD2YfV{V8&8=!C{*ovPjXrXCUU4rr6gA1I^r9v3}A^-BhFf%E2V zy_GlrdK{UE3oVKw)VSRg$TD zX0B5fq?ST|m5&Yxp7tm>;Ybx!C;xe8pQqQ8!H__RZiu5_dI|44d5pR6-3fwV?R!I^ zMO>yiz$#L^E)1+$!RAb=j(;AaASRX5YN3#`G@|a?M9=E}?uEqD!{_Wzu-ho~tVGzJ zCAzWI`WL$}4)9*~pnB}5x-}R4fGq$RX9?{BwHx30j%`^u_g4|_o_=$0y=MO3KkKMp zVF<9e0+PR4A?;FI4~d6x^@QCtq+mFw8&f`0XQg*MyR#jGRFK7#q;f1$Z*OP5EfeNl zUbC`!CMF@#|5y&8K5ZKnjTEQ;eLS3WM4(?7j1zLo=~6gPqo!u((+fj(%%COXGd=qu zw=4v#0c%)cZD8WLXHuvSGq)-05F*{$Tag-}n8fS1g+9o^9YZ;RJi!rsK z;1A83RxZqPz&SpkdT>mGB~f&3A4@v4~PR6OB07SzIG8>G@yTBDyBE@o0 zk-k{rhXJ0;sV_PU9s`EteS$43AmBFw3$)571A{sx8^-|NUQAbjmnKN;Ho8QN#g zK9$a&hyAp)%Z-UvrQ*RNWELz=JmtSP)@YvX!su8UWKK!N@>rJEm=`Yap;#L?zavA@ z_=pP7JT8AQ@Ikb_n%?Xmw>g@>!u4?CoA{egs>JYDD2O8+nVJQrhsrS9pFq{(f|rCl zg4a&n=!}2RLIFqH`qUgFT~bwGn6FEd@D#KUHC?s^`8!XWNwo>;obSW>yvVM2W=E{J zHgfM!K0br!N=j@8Kd7#VjG5PaOdd^fXl%fezHjlBW#6LcCkW^-%TAL?>u#6@Nx#{a zStc>2lOo58DlJsiUDvWLtacfH!WlK8-Y4FFG15NS@i^5@=c&W0l)n=0K}9=1ia+2? zx5M8Cge-t?vD(M~=U01!v1_w1%1GT}wEWu|GK=P`b9gLN70gnfB@@nCgS1bXa*SZMv|9^+ zi8B9BG_)#ZkE&Mx1Qae$(G&-dJB(QSR$e0n@>Oh*YlGd{ZiT02zM#72l**xHzUhv) zCZ4vZWATU}rwNjS&#%c3X@wsqE$p7*q(r+4Z>p}MwF(;hG|g`O`ZNi@?|Z^i4*6AY zdUv-Wk}2|62orhocV68r%5fiRfrtWUyT?qVH`*5eX@QW2HN@&DNR9dhf7V5_Sg`}X z4ghijV~O?N&p@nYTc-wT$RrdMSQ6d&+}Q`YN)o5{>E;meV#yzQEPCB9S*~21#6zMu zy`O~)n1u=D90yQDy7=lwBHvO zuSnyeSjyeuWXKpA9oVvo6PH|G=%gdxrhq}8-AEjp?jz$Q2U6c?P*wjbVDBI}#fQE% zMopN!3@|XF5p`KTtJ^&b2E+xIKf4{5_)3k~c1XioagOts_w;HWxBSBkh2q%}{lacD%b=Xq}2WaDC(AUf#Xc-Vn6bxbGK{;p@FslGN8p1H0V8 zky-q5s7Es)(>`2mySXJnY8&T@P3>2HE`w*O^&rH{0wj{Ll=yb+c+lpB9t5PVJ-zsv zT8eA^qS6h~!DoA=2`BRpp%|r;Nu~iI9}W`E&RoywsR+Llj6T!0n+~Nd0$iP&0i*8! zJac;|VyqjFr?~rcaWylNC$ zaJIj??X}Iwl?v7OZ|i77Qli3hQh+QpmTB>xT{3<-?o;D);^Pb_xUOiZJZj`I-;l>4(V&5^#&YPbsbry>lb5GFR=If@< zBpWEy#f1@^R8bR_s`W*mT;LtpWG8e*PO84nF`o`BsCDu!Q@qe)<+VFG*J`JYt4Iho ziwJ_=BYKhkUG&Oy#*l-**H&_dB@7Jtium%G=98Htm?v|M#ovp@uT{#*v@$@Dciv7v z-N8(!d`}=qAI&~exKjB|?UAeHE`P^XaE@3tp6%()Uj)BzUcVS|!8@S(v!WU}9Gi_> zT>0QfI2RlTb5hC6f|+SoH*q6dPxge@(Gq!_qWeE&`u0ZKes_M=H}z34#=!%1)AGCH zQt^PT{qI+b$trdSA937C%6^nT^R*&%lG+?ZhO#GHc7Jd;LuAM&#*htB7Ys-z6-1hj zMV+bg7aiu6!%@U5!hW!rV%;x|^kzt7oW%Y^hB|I+1^?Dbw6np*n*GR-NH>zA59nFn z-JLU)sNJa0BJkWrCSOC=kG6JBpQ6Ai_w?tWoC@PU4WA)?5uNHU4RkaS><&yqv4*-A zB1zjHE8FiJQ*jXGv3n@}<>h*13=!OpKnQvHTr;m?ot?pppQozSQc&Qx1vL5M9oxU+jJnWBzW%Hh!- z7<1&deAVB6gaYX)7EQ&_Vj&_z@^}f!>kF2Ix<5-lo`@dObMdGH%X`0irV)7+RBkst z`0Y0d0vy8@wiTbXD9JOiac=c^sDfV^8Qj4RU=Iu;nlh}WfYc*X>p-UX%z=fS|5p1X zAfrxmx_&>XgTAd5Jec{1KTGTzTk9@74iZ+QJ9B*0H;Eji8!1xzv0TKIa3P+u z$Qpch925QJ!NaxCxSTI|an7G#`;Z5V6&}L1VDWRa4NFFL@s3-?Zr(iGsl}t!3X5MH z!4&?@^$V@fU4`qiP12R@()zywzK7-T61qw%Oh+(U$N#(j!HQ8>WzRVTR|dm{X>02xnegS`7h;U9;`(Da%OHvZ)FUC3{B~$ zn}lKsOAoNg2hZK;4b4x;HM;lP?NqA{0D`M7^90^k0&wNL5MHGINVFk|e62!;jiHRm z2CLG{L)>C*qno;|P9OQb7t}zC+(3XKv8QVu73Htz{drzEcI6we5MDrDX%1hxv>jdH`0$khdWN~V)>WMJ!U+*0DN*AS56 zEgIWqc5Mrxh=P2x1$a`Ya*~?7fcNbZg%2exaZl3Cd;D~~>A%3V zz_N$R3ZcS$&4!aV{Wf_CP?OoGOm>%+o@WEJfFU)MjYvgZaf3UxLl-AG{z~QGO`LER z;u%8opDAnS@4iyHv()>JsTb??z*9-N2^#?^DV^z>caCc4=@5!3M6CPXo$uXTw_mJnyUpPOrfYFYZ?M&!Gc&9N>RjV zH?u5_)0Iqt+$V^bU%tD6WR9dz)D>qyPd|6XGc?Mmvhbiv1tvh1zVF@u`9)vxdTC8k zk6lCm3&thb@lJu{Xgv$p$~Z5O5JUm6Rp;5|1&OY9M-{1uBz*p*ZJ#g8bhkR>NgUA- zDG_gC1sM>Bo2xQnGU_lq)s9bp&`){K85xxF-EUM5MfmwvseGC-kO*PtJqXO2uzbFK znb86_zLJ;8Su(L1JN+r+@*s`6_5*^IbFczTl}mPr<6VXhmQMS-mS8>iL9j61o>V8} zsg5a@E2(Jk$5E};KGFSd-oXY>h32yFO&MO5Hu3ko5p0Gx%I?i&(ZB__|G~(LZ*Q|H z&KW`E)L6n5B3ptlbiOv`iWRp5^n8+O#rs|m$@nIYN>+lM1f7Z};508e|K*PO#R_)z zrXHX$divQv6ejM9-P=;36;-bctY9UgTwEsYBEjEfT^9p;Zr7oJD^Tp!w?x|uxHLHq z&AQDIy2?hrpaWgK?MriS+3AJ^oq(=Xsm46LeE_iA#AQR&yJxG!nVZ_V!do?iu_IJk z;45<ISU}FWli?-&FA(%^EodKwPqmSO*`L-~QyUTeEI=i`b<) z(nT0Xfu4aEH=bf45;8^sX@@MyMRQX~91f+QQJ^$Lg(c`hKyOD)UHe+F>II!KH_U>R z_M5QI0G?$c9l{C7o&}riNS^e>(dAlw zKdvoLr`Mk%wm(~P5>NnbL3c*@$Ks5DWVLUF#*VpzoZ$-NH}qZ>f+G&QveokD6zk=Z z1DoWrUx5e@V0c*E4In>C8`I|yC5MA0o4EL2%s$@(#0s~^XW++JJV;A$y8_jU!2a#o zze8bDmm=NLLk%_x&9;$E`BL>Q!%FTjD-d>syiDuTQuJtzJ)3W8X|t14keWZj^Jgz* z7Guv0Ww`MVY97dVT9$?{5A{=L43`roqEPr6u0n5vMtzK5sBP+3G4d2ZyICgb;1B#E z@y9^=c`og5@u#O$Uy+5y=6=J+TkzLH43fYDJ9=2cZo5Z#OULh7m`DfCY<@2Ujc0g1q zxC;bB*o9JY>@x%dl5zmUo2d#?qJnoUr%220g~^3?0fe~~nZ<@&5fLijzs z#y=Z0Qlb3sBcjV1=QF~Z==s;WMMPgYh@_wwu%e()-Vtr4jQ8W5NKX9j8;#!ZyzY?DKi?A2l)+Iv_%h#~?vK zi#=Jq1uYQJSzBK?xt&UL6V*x4As@^vSjjwID3jXFk<7WiRNJCLQoHhXP_gm=?^Pew zfypvh(+eB+V8c#ATW8k#%K$&gr>CH1lEYHevn5| z-(vfDz9M8^xv=tyHvBT>UoDUFBROWt_ zNvi)7<3oP*Jz!(fHIVVI0tryTUc(epw2E1-bLrY{ba4HbymwT`&QX`v*JS5l_2&AVd>MBa6lu*-WuxmJ=zxgoCc^t_5 z*vbjoF|db`ySa>d-F~)lchoF3^)G&}cC-8dgkJh-KoCY52ji#_OI8Q^kssPFxUdPK ztT7%e$|APBAf(Nh0`o3P%(<=HLo@1EGJD9IXF!5q0kxHI;1ca|mMMk~(VJqc_2_L`k4Gy;7j2E$k zsZ|yDU`_9SkW>cee$1S%FaMn!`Qo4J+j*^sXz$|C_zujtd-^Y#}XQjCZ1EZvQ^gzYpqEcq#tc-2-Q= zGbCbX=kKU+IdAJeDSv0x^__?$)aat?^>@6m-w*vB(3Ty-uhVYMDD%_79EQ;L1Joz0 zyY!0_6B8?YQwb%yDSUf(=GK#?m#)C%9>Q}MHb$nDv5*@K$=js%bX!PA@Yk^@S5kd^ z{*1NgeI4ZFqU8CsAgA&i_Sa=Nc**a2H9-qJYZx+FpLp;`^uBXB1*>gsy}-)2*XGq+ zH_*g1t{Qf#F@9205DdFNd|K6Wcc{E{p1Q%+hmYK``tX1$=Bm9gp(HI;=Vb;x_64O3 zcYNvR-amvd)}`rqb1p`R$>EuXb19x6?FeRCsSgj%F)M?dA)x!c>@S53{CoXXd< zc^oxKnq}IjU1`@oUP7jd+k5`ztDr~@3cdtWdJfDT2N+p|d4NI6Xq!FT@F{@n8z=SR z_cgItr>>P%&%}&KGmOnL1@3Q-8Ok|hQH5_$&e8l1ho>s^AzpgHJRI(Sa%D3?g6?)7 zvrgqxu&}ZJ-0wICY2J0p4v5rUeGrR!if<=meem``-MwBh_4jZOr-TG-M*9!W_4UeY zMMEeVLH$HQre7*Mrgy;iAZ)9^&|_Y|ZwfG#{NeDXA77akcm{V=xy%L)XKO7Jw0yfR z;G*qj=^n2@q^^wW>zA-h*bpx>FYNkvrhJIe!J+BWspqi>_j`&2N77wT0y=qp-rWLP zAI*4c8W#b3^s=GM1ktbDr2BwdU|Yb5M*TR1&F61}NpyzeFEj?z3VqtMS?h`_@AEyx zGy%6&CNt1t zBJNASiNYfYHH0}vPN&LPQW68dh?rn>a&C533g{FZ)jq_M{nT=`UE*^&U=Xshw11M= z=bmVzodyqvYB2Cq|lb^p9BPzf6cH1j3g-;=DAp)7fFJ^$X`Q5%IH|^53^5O&0 zG5QqZf9no3)lIU51DpF2v~j6A7V_KFF*~ve7nHEKkb?tXkb|9$%Y^K!T(99<&eQ#j zlYK!Tz>G73*4abB`VE5o!6oCISTz6iaK@%qZ6i@^0jxreZ-wIYd=x$;18(CnM0+g> zwD4q5dN6N0fI z)~+-yQnb|vTYs3`TV2|Zf9t%vPta?o2cI<(pUE?sw^S7A!pZmHlD3@M>sAEH z>GIZ>&sk;Htpf8(3#Q?SVTy#i+4$(`Ipcf%1~i_c1=U(Fe2nG~;5raL`9Kit5t z^SUW15B;H-v7UsDnai=o{c2{M{-u>NxWmU_V-v!utqjH}61L*Puam3o@PUtCtDTNC z7WniN%MfjABvx2k(lqLOhNoLsu5C_b;N;KSd60nF4@K7r))13V`mj=Q;1*)K=1Jo@t&O8dx4WXQRgqZ%r(N-) zImXkA#Ae|ipL_MssJ&}5F<5kp$dCH$gt}bf2f(72i{GlLhtKC#?nBl|nYc4dGqwDl;#AW}B^lV^RbjIi!SFQCJHW zOHW*+l2;hdX>c%X9NOe)sGFp{K9S)z!Yb!$&qSC?QUmeI=Q*~^t4}dboZ@G0v$75BDm*bC@De$j@R$$pd&T6bN6=Mg z`w6M&(9hyclCcUz?C6!>x|TZ)K~<#9x`3PVxc+eQEqB75Zj6vPVLfRIpVDm-3UG)7JH;EU?;uR$@4((B#jOY3=RZ$QIyr!69vm*$;=&vY*wwDF)qz zDb)j1*oto(G*!4W&FOu5_4AtgBV8ev`Uf*hgD@TU4U^SNc9D!Wc}57f+=AV|J;{N( z!Y{hDYNQYJD`1|DvyzN+RPqa_emf<%4J7gM zKTHI3SduKWXT>E$c8IQSwfr@=hlBkLc2y!ttdTOBB%4N33wM)_U^IFl@9$+0Cg}mB(DGUFPI<}Sbu$rp! z61-U{;kxiDee)kqRE%ehd6Sy*<7P}#X5Y(lVuwF{T(EU0jgAIK^8Tu-I9nCTFwrk} z)~y;yD0%c(x{{4Od)hjgiibUB9xwYim7<|<-v~A8sZ=8SAp&Ob3XRjZ5sLI7`l>+V zgzd@V%RH4dpn?3u7d5hRIK>D4vl3nZv_lu$AG0|oOh99{)V_iWQym#z?5Jfg(5U*) z@xO!q|5uh^+Rxo!)+kNx6_D7Tg;%sK7Ek>!RZWX2EW(mw1#+3$>Gp(j5)HQm3_nbc zG$ag*f~V4`Go(;H_PKGDR(2eG>RNr*Tl2;GUNqvA^v7@+Q + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me7_segment_display_8h__incl.md5 b/doc/html/_me7_segment_display_8h__incl.md5 new file mode 100644 index 00000000..ec0e8e7a --- /dev/null +++ b/doc/html/_me7_segment_display_8h__incl.md5 @@ -0,0 +1 @@ +4a3cad6a84e56ba06609ba9ef67fdc0b \ No newline at end of file diff --git a/doc/html/_me7_segment_display_8h__incl.png b/doc/html/_me7_segment_display_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..13eaf831ab8597f06bda9effa028f2285f2aa790 GIT binary patch literal 46692 zcma&NWn5I<8#N3J3=INOQUU_fDP0OkgEUAt(jnarI$RIUHcR7S~cRdHW z|IhFF_P)ah>I~=Xy{}l;T8q$kO48UE&oB@W5U^!sBvla*ki8KQ5Z|GJfuFD=Iky6z zz$Wt2k_h(?AK7h%@dyad5o9G_t9zvHEO`2)n>XDb4xcI{*6^@=DhpQC(KTbnczKl@ zQm-@niH5Q0-JHTRWSknb#9W$AIG85<`8OU}8@$-3Dps-2t_Avgl4)qT4j%s)={heVf-Td}nd!t&QA3epB%eYmw&q7oDY2sEB_+SG z*}?IFdy-m!<$rM{e=Lgwz9U6@yf+rUWx5menu^T7<9K68e=ecoQ`k^BbY{L$1U;_# zJwfWGY-tt9phF@U|mRO-ElBtNoPqx%ve0_Ezu%l#{%epx*T+w2BQcqcagpWs> z`lIGyyUd=$J1aALKi+w-ENT;XX8NkODS@|%sAn?Y_IBsTuAHP~v;4n<`Sm)6@aiN{8_4v9sT%7z6Q)B~$4800~oszdv*ti&L z@oxX!y0SeXdRVW-|L&S;i_$-lSh*P0Qf%5MwB+w%>fTpe zLW0n*GFet+N&kYxYD*aiq*3n2C#3<+iVK9=X3vfiaR4Xk_jsbe0{GN}B5Z{#zF*A) zA-n(K@x8$N|Nq70c(x9(n=fdFMXzng=_CgcqMOlx%%OgaZ5c7lPe!gJUm7|t*V9yz z@X?uP?Me@RtKk%!?rL7U?85a8cucO5#MTFur{UPj2hdv91xoKy3e4_XhDe;u_6-#O z{iSjpX0HGYF%{1uU$d+X?c>3Y3$0_ZAb;Uz=$vl1D7M#5lk^v%z1q^YTd(krV=wut zy$K@!?X|?^NXtd%^Rwq@nwG^rczAtyk7`7P8ly-_Mc}Opo8Q}be-Z%nr(d|NFd0v9@ zd|auf&`Z$5Jf2D#QYc}W-uW652>CiV#4dP4=rOunxmSiEeK7tB{Y;aHD)H;rlh`iG zhm7uHbq{CYCxy#pqg{+lQcvk=Sx~+ARI48B)h0VPDs!+gJ?i>!CZ}BR%-&epl5oIB zA;u)9TQVIUND=67ax-Ey^96f;VQl00wmRu*?{mZ}l8wx}2q!cSE|b7Hpmb9ynHDO=BMK2#wR;V_^&H=@&F{v>5*~?!~qRov-?`4;4T5MVkQec;fr1 zThCvg-zd=@BsVyl+=kXy@EtSlY|iQo_|Da1lW$PRFT6xNqow%C;%apgQ*dd1=2gEg zl8ox~8nLpWmTcKV7*T;j3-D|T=W2~YA}P&`<4oK zmFAlNH3Wt8w6iq~X=Ln^W}VkXn*b76k`X%!u`d_ZQnan~D8yA~ZA-36H0{ zS-WM8Yap09hQ)@85jem%kyKdg5uX)S{RCdGf-<Q7_q?kml2+Wf2@?b<<1x-NVpi4y>Cfemm1q`yDL$X zG|T?4Ew!n-M(-!c9f~Y}3^LzkWYgy8$@~lRg`;PIZk{yeRQzOvX)0oP*D%-aTGt3M zAeckWAhh=Lq}+Syd^41hITc4>_UZPox4amEPz2O?1D(mJV^wK1GpLKPjEgRWmXCN& zNM)RbW;E-uLdis@*UdL9RApjv`+6E+MPP0a&c)d;%q;wo^+VQMb$sm`svkcz`}Ay8 z$up?;ZPY3WQvZ+u`ZR&ZNJbtCOQ`Q>$)VUuBBw}{Iooc;*AYQTmbUcB&*Yn_T@jxk z4GRgI|Be{hftK)YFb0d$aD97hlCk!i<4GGBqu9QcRv%Wjq{i$d-1oB3G3_~M?KxWN zf391$ybTt)wRG$1ZBpBVsv8L(I7BQp)qd9W8=E7TaQ^Pqw9)p>gk7E!$FfYw6bouh z4z`VN+R+Ho_&!1oVJb()kL^@=1OT=wQe6xrde{-JmVWNnM;~809DLdhYn)k;bZJ-D zwRT_4Q3@6rNp2cH$5i#ffxCdELEExa+jnWLB<_<6HFYXejf{lyzV2NoZXBcEC$yKJ z8*LBL?T3i-GlNVussanG3uank30Y}sP#!bUEdCGr5-}W=e+@i<1>64cRTYRtrL|+5 zW$lpRsif%|@`TbVON1i5^_I`O=|<2E$EaZ+q0P4vHeo#t-*n{jP~5tq%z-kfuPL&m zt5lS;qoBV9DHJ5Z7{Ndi(9j%Fb0=M&Rco?=VJ;qv%U#X*EiFlK7BKYvuWz$l-Y>5w z?n1gU1I^c+mqe}BkhABFxSj~IfQYbvlp8Emr#vYdfc~bS{;kQF*;+C9o|e@>@(baA zf4M!XT^JILeH5@C#k6WUK~UCKXsW?>tlye}TqVyW<>aoswS^fh0-Ab<=_gqFe&w?L z%PpU`r0@-eX+kiMP#MPmP1vw{FFew)#~4FH0MdpM&b0j8eSM?uxIFbkeSwzg!mc-g zDPs&3W{SF+#jr)gYz5;EDLG8rld=@A1*cBjCo{U9Z`qO5oy~Db74i>19j|tUL%^EXP6mI zU{eaH`I~HCnGQD_#5)`wP$@?$AyTM})_>@bdtyLje+^sxGwl9-bJnl>`X7$IhTb7R zq#Af3aX zO#^X@&0*s(24aQkshl!hNoVCp49LN8ZNDTo2>0e+!;wFF0~?s!`s&fufy~0u=sNu7 zkII?0$~5P>426 z-w}RTp^1C-n2lemlzcs5sF^5iMaS|M|6ehD}O1#=zkLV@EjG(1Jpul>HWCvMV5~HNlM0tDMYLa>? z94`6a5j{~ESw&4gBrpo=#y{fcn=3s0#^+I1^tB0s#ceT8G-o$M-cbqMC?rhC_eHRe zXuuc+J(54)MpAJ=^JP!H;MNtmw1hBo-)36uBlKAWX5^u+AmyUTO_N*BE%#`b)ECmn z$P3aFUJ+_`Di*LL70$$HGV)7VNZa-7Cu=oYm9gi{9gK|M4lie%b2$M(z^2@qh+jyEt-yfvxg$K>THS!EDSSo3K@LUd^V=Q(k4Rnoj0 z>2KM6ruaJ}m_p!zT7hXpjm7oTnbFPd-;3a89NbWEi&sye#t_~Vc>`DN4^{o&1voVA z68`jU_m{ouZ1?W$o1|4yvlU_3U4 zcU}uq>J37W9G?Y=4>Ij0b)9#lQMKmvswU8d>t`}KU;m;eK_zgmBBeqV1+OBK1z4~w zJeiH`4SK3Po;WiwqRGbP@n4uomc;oPVfcMgODt^{&KPQ)bC2wiK@e)>ZfYODODt`w zd2JkhqW;j`i8z4;rVoQE)70Xf{dhYD4S*G{tUj!r7>e)6vHA8l)vym`Ler`uH>LXq zI(O#t9yp5b;VL%4&hD=;BGT;tN)=MZ^$|ieX}Y1ViGTlEI(M4S$3g9_7-!QXBP;9D zD(R~nla%Ocw~_!kBi)D=;nl4xRd0^1*)O$`*N8g5JR&3lVpHTrs|Z=Z%uCiQl}*#5 zOkCRkEeBGf>EUOMZHYJmX|d4zw&SSP1DYBxHLthy-%?}a9w_4 zl;5p*_^$c>9~{BO*-~Wx{4(lMds->Nq@)PH@WTwTl{6)QH-_&x-VQ<$dDgu#JZ5~ z<&)^0s(V-IewAMcoS!!4#e0kJsb|X@M9ytjy;uqq(%pqdt)1E-PKh{yZUcHp-_<&g zW<47%QrpPP7ieY*{*4i40exj9m+0@ds$OukPZ~0yXz*S-+0Ucj6z2yY{X>k&4Gl~L zcNv@fJ7S?aGOz~_*3q5y$%H4oE;lLOr_3vIhTCSN!IdIxw&~|?Ri@~5 z>qFH#aZu~Qs{HKDBjo(dKoNU;Oo@A_?phbDGQ~DZ_Emf@uJv;ohy8vLWc>RRr++92QJtZCnxBlX`}YADI59S!duN`EFFs81_DP!*a$?9 z+j_EMZ9R}Osvq^Cg0DvH*fBzZ)5RqT=f>fGf)?Nk858H;EcYoDUajt|DcAVI_n0Mk z+W&7OeSJ)^)=w`s6nP1*^A`O%6STIlGx)){GRDt%l8%quboi?8ELu^Y zc9e`z(a+W>9e&`syaX1Ti|NJ2WSAubR^6uMR2Yr*w#r{x;xB}B+wolY&z|2)@IA9DMiOl{`qVaYpU~&1QP*{>R(UKCApr46 zzeaCtt(Yc~)=xW$4$E&BGA_XTc*Rq7Xj?)YQ|tT_jk3-7QyYbT57+o(er=+zVH>Vxy`sjSB5ad;*ZrbAUG z=u}5mdrby8lQD$`trQ+JWh=D>;Gl}eHLYrdBnaXuJQOv6W|4{Ni5HEG zvEgt-sbFSV^;T&M@>a?vZYOiZe23xlz2Yan%6P0DA$pem0kh!k{bc8mfceYMI$Re+ zau;}r>8L*F8&VNj^*`R_613(4Ib{#?NUy%JqWa<^mcohfpm;`{{ZoZo-pqJ2^5NX$E z>d^{34vdA&tA|msC!17C>7`=f8`_`byn#RAhPGIyz9EAL;z7X6q(*eJVBWI-mix(L zv~Wca(`P)Ld8z__6j~IP;=$)bTuu-QL(o(KE zE8522jBy{VnBj!vIiGjf}DW?L{2pC|4tDbti!eY!Y zw5XKUSF7lWzvE7?CHK=bG`Xj66`>K)SX@S#v+GrGXG0X-f_;KqE`28-m%HDz0^3o; zB}`idOgW)u_I?va8df~;vWU+9_DnF5!;ztBy4gXMfMJG~wSV8JL@X=N_kiJW6!T$L zRn@b8OLsu*4y$CZL(Q!y?cSlkm$c$ZIb8K-RBFs0e4kTMET+zLS#5FCmoYq^H0!G} zMLVjy!Q-{!jhKMr5)h4aY;q8kitqhuYu3yvrD?tachaRQzroMdhaBN&fGdBrP#IV5 zOh&@?WOYpovleswU6@b{*^iL7gXzuMWcO;^LzAlq)aZ}x#4E40vw?}}j}4?Dpn<$y zpbVS)15phw%9gS?VDLhg?Qe|t93>k-o@EVA`ubXz4TdO?`8|5_; zag>$EoGSJFxc6V#!Fgl_F^nu-Dr~7bqlpx%PF0d7fl9CZ@ghN>1INum6JRp{Oa$YH zN0@eTv_1#ObxrLby}Yjnm_ZenR!@+%7Cw$Cf-Fvxu-G!{-8Dc`kW-Xhy$ag7{0?>Y z^H#0*0?*CKEvQ3MoU{u?#g~Oc4qw7(!MF`%bG_-h%`z0^z35iZ3+n~57JoSAIxNFm z;R!NmZz(B|39Gxb{c57pZ+VIMu|n&UsPur$P$c@UQZyZ5}8Fl?RYbhTIr6 z+D?26wA37xMsZ9Q2oWF$lfUkDI#9x(ot(HOR|N+ObiBx_oKpJX?>4WgrpCRn;4tSp zrGE{l#fqLiL7hdul;8|k>?V%=1wCvIQ+A?%ds-S?wWBR#Vm8pq@ zu)HkO%`r$t5p#X`waXqij6YYbknGzDxoo{z)L?u47Nuc~oD-s>pE0B?EYIIz;l2HP zo&{b>{ah^e<8ZrIRnN5N58JqtE^zEFc?8Mpim!E=8JH93spX)I=+QVl7$(?)m0%|8^?() zP0C7z3rlCimEVtKZ(dMKPg<*Rf-<*bsDPL(p|iMeC~HLX54I*<^R7y8d$fvLh(x_P^ZB=fVw2S&|wLBn^t%n8bt1Q zKF&7Q&)Gxh``u3OVMTe-Ov-dkV7S#X(EvOLb_)WhZmnfD2)-^SGvtAf&ziJ|Y^6%R z5Uevl<8p+Sz3t%rszMqGg5t8CG~KN-#n3I^&mVW69zue|I67A^h@Y;>tx0h7 zjZ7K!piE#m7+PDM;c=K9LhQe|pd6KbLM`#HfnwPtM79^A-aP+2hIO~>DCrw2LgcES z=JL=)TLX1D>AfL8n)~W`fZLlHB^z1{K~4a$28$d3UC0Y>c3`cfr7SYhG;NS?9ykPT z3|*Fz4GRj}APyJIdbr7lkdy1EjTt83==`e_X4)n1cXUHMeS!iUmRmo$$mtiehBa5P zKH!^cd*+TFfvybM(|AQ`&+uO%10ZZwZe& zCJ1&$i?&H%KhTwcp8O^0{$$OwKeCd*xo46Z757UvL*@a6uC5L^f_tO!N)<(friRqQ zK-adR*KJ*VIStZ;0vk(^tz>dIV2kc1>iYs?u$JZdhtqyl;VEA*z-9M(F9;ng*Qy=t ziZu+iEXq};>ggV8@3Mgr@iKQ^{+Y*5y3??kbzF;?(cO&7?JZg@XMuW|iV5-$c0knG z=~7a;z}?*a>h$0ieqDB!W_;dBAYP^O)8JZ+utLJpAO z?mi2b^?QS{+q)(-x5WUU>~;HNw48=R+%s9rw79yaGDSD4n=2jdcb|KFF6h5_G0Pe` zks;9RqU&xmOjQ2B*~e1n*Nj9PP{6HSqCOV3KVOb}z%E7GTg4Bugyny-gxr^f(2bi?#_iD@JmqkGnA0 zeg19}8+aJUH@Mz-xtQ8*O^Gy>Gt`~0`laP2Jn*wzF9zkViaffAy&$0V)(kl(N#EiO zPLiNZK%&@!Is_U5wF^_iNmpuPLZl5_soDDXe7uvFU||;pX+MD6#kS;Z-;!{3Mnrps z^)kiz+4W?Ia&65@dgZnR%4$uS)7ox^>J2`YAaLD7fj5uWLWPY%RQL8+MV&cyYGS$>YYLXp)y-tf45U!+9g#WsYL}%z2S%BY0hRn_13HxGf-k7xPi=D zayx&DwgDA;`RhrC!Y`lQ!Is;4ZODYhyurw70|9*gVL}78aOT^heeScc#~1-;gnd@l z_T^#5-kNV>#uCT|qz$ScucKRf2>b*NBtkI1$p0RzPAF{&jCw{Jeo~2|wo})vdY#kl zpK|Dg>G@FJ*RUzWn|Wg+KfD@7{b2q8_pzQGe%=p11f@F%ncI^a7@8=*)z>n7Ago^Y zMT!T%ZmsyaF0DT%UVT`s-?mvj7Jt3bjOgO=`-c-@XsQIZCP18Z)CxAr;7lYtVg zmD@HHZRnqFAfuIJKB&(#4^H{-Ip6{zTGY4OzdhN&mG8-hrxa@4y@f+%qF7Sx_Yo%! z^Olr;&HwhurdgRlfy@~oew$;HL7C#B6M-uUOk>TKq`u(e_z zQNGd<_(PNx*$~9uKjKr6s`==>O`S_Zr}qC91L(J!Ym6V%in>fX$ZI05;)+4aux9#A zRJ;8j6Usj}0ydgk7Zyt5cAkCN*@eCgQ9<6ZgDt)md`cc%T`QC23j;znwjE+Pp_ zv*j2c8eSbh?ADQ$R9ecqGu8XDJ1Ax9%@7ci6|KVdXh?}#JeR_}j>do@%C>bRDfxJ0 z9NbA)ew-WEnVSQqju)+}x`eL!GpbF4?uVNABrSQW0Jf4j)LA;-NJ!QiW+8^KKsNESI2 zie`NlI6{8TEt{kQz)iy9Y!+{%u+;r$Y8iK`Q>X zHpR&@wBdnPJ!>G5@^038LfsMqvk!DC63XJ6W{5B@3-stRe5E~6%~X_Y_zqCc#$&X2 zc>%s2Ww6NhXi4yfr6Z%4InF@G&{pxG8qORFa=?`Vr_ZXk&}JTpAxx#XxSMx5SifRx zZJJ&T1?tSoW2l_8%(!3Q8B;FNjwLY=9`#(BPm;UpH$73lvRu&Ffra7G@>kmfbcd^A z8z(?R{+feW&NCv0IYBwM;>(5W__s!1gxfRL5-qO`_M(0~!K`@-cZ6Cf;m=KF^pWIJ zeA2cdX8sgm5nXLvdF}BUJ2xbx8ULE^V68vz9-7gFqU2=W)u9UTs$mb0)b;3J`4atr zl*x{gLFuT%8_=ncBmDar*{rSK%Sz7MF>2hmn&8MVb5VL3&Jkmp%^1rUFc+Kw79-iJ z)h-$v{qu0vNVrf0bkXO#yVNS-n`s>568H1{Vr{=GQ;9@3MikGBDATG}{=Fi?=8LVK z*fXRaM#cY-+78*XYeZCJKxRVB6RRKAJFD*;qrMqhuC%xrQWI{YhK{{I<^1@dAa=P~ zW6K3H>%PB${p%jhW=5sO#VLDx4O05OM#dI}>KYop|C@Z`T>g`~02$>u!d*jt@HVkx zgP#}5()}Owd;BWM@}vl6DDD?Z$w#`LB;vz*Izj~a!8T&Vf`f$rDt;$FYMYsv`JAU# z*;PQh?D;{rl0d(^&<-+&bQC(}U5}LTeQ#28s~bV9V+&H&Mfv^r(+q#`09)Ez#`Wj1 ziuO-anslE!#_!r0T-wAo4wtUN9F9l2Jv>$jI|rBzcZW!*NE~)TQLkUCu~FN4ch4^B zJ|!X=Drc|my%O9rI-1Dy|M9BlHBpsV3c|0^taIwNF-YJ9#p`!QWpepeN`wci@1~Dl z2DE6fnb!-6al$>{D3!9-_2#n4gDX6b*LOGf^zW}}s7x$y2Qx*k*KmE*q;GfXyjyH7J3zLYd7w?1{Brdj~iZm6_r_op2?o$uk8AFK1X93mvl;o49EE$ z-U6lzW1U5%`MG$t6xfH8E_Wm)&I|ggED2f|?w0(n#Ly?cLSVKI3u^>j@KE1tXjw#m z-0(a6+!5rYsb78D%5dyjBzIxYcwtv?ws}fdU&aUjsOcF^B`H+ccxXP_=9oI9vkGMg zkU&a%l$bWa_jbAo9aL9kfVc~TcX7#)BT(u=ju*tRcnd%#=E`kig)#+;2aWBt_}+6s z-*Dq}HWk$;lYx(xqG^Is{@FbGLc{3A5a4n_#s8$iQbw{X>BwFJQPc}OM^F7weR5Y3 zveNfELitC@%N(3&$$wy!kZlrw4s9a-aPC5Z(_dw8mjo=*ccK2Exwyslvs-{c)m82V z5WV(@+k6=J42XVGxt?&LX=!jxlxDKuJCM^3a4KzXwo?4tA<#OaAyT`BmPyjNTUn$A zy{``%_n-jEG>SI*e7eJYs=$zpjKigEBqtjh30YU;|0S0B4)2l0aY{c4XBK5x-AB~e z&(r|3+WC=J`!2L0kWO5xpf~!f*`raZuf(Iv9l0Gb9k&ca0+wZHasF0MbFWEPxRa2C zIN8aa)`8oF~W?&9bO}9~^J79Z9 z9Ax87K;k+sRP!|rTZ!l8rmVyiX}E9njgJ9Ngz_+RJ*pS?{ew=pN(RB5FCLmpx!>!< zC}iyuhM|MG1BOAmq%62A>v+NQPTkM#Rx@mB<3#%-f@GW=pKwgd@`Z!LxRP2i06h{Q z9U<^em~g^SR)$$`SsoQ3e*@AbiD3nEy%^A*e!Y9N2-W0R2XBNpa4?T0^#<%?p8}Ah zpG;U&{imMM7gBEPaMsa+IPU#3{UDO~q2w@bylF&_#SCw(#GWJV*{Sl6wfKILG4?-h z>6Yo1XSK>akXW(3XiPp=q_mIgo( zQ6S)K(hbg#UI19u9cvHq=n{MwdGkn1Dnj}o3Dp^mk{wG@HIK9Li4Gu^Khp#4Y(VEH zpC*|_IZ__|zk+2hzrO9dGZo$s=dw=8Q7Y-=YRV125OWKbQr7we-^^bNf8(ujc~6WP?w-^KZnJsnnpmg?w|NeMJRqPJy$2Jx+bV+yhoc$nXQg1mK> zetuz4{L~QHB386*OKMqbZ*X|BKYzt)eWBeZW|*4DnPihtJOlwX&R(gVazl0$@pssB zqu||NOy#_NZ3;zR%vClz4FJQ+RiIg7_7+7}VgHhSv68*oDYqR%z zb%)av?GxJz=Un1Qv}6=LG@qx9tN{ZX3DYIEFtwC}eW5|ljS~PE)J?%(wDo5UY|Gh( z*iKHZ{1b&6(cwHb^NpVJT!jT0O3l5)_Tt=C9AHfEIV#yZ_`@YaMtWE{uKZ6oWFoo) z>;g_9rZ~)wn%a=C#5&&K^ANJ@NgbtBz$R92%EZ$`gYdiBa@AxGe7JHwxWj3m*Vi*KN&L!u;e{k3se;C;wg39(Ws2Z>~9`tA1qY+NiVu}99K7i+Q zt%vSyX@3myPjPZEjFQ@~7~~DZ3{(r`8*D1}MV?{-d_QX@?Fv@Tb)=S4M01h8l$Cw{ z5r;F)_(DvWYj&Daqw+(Sga;n&hrutS6tkM65OV{&eLMON!$9MQe8&YP}ySkXZ2s|18v@irw2L~k!e)t zQ|?UUiY2C=VV9Yr`kX$v#h{C&l5g=XKeH))>!MLZGd}YW)I*o+*#6#w1**?)Y?L0e zyK5&>V&3FH^}`wIo&7tEG7ymv3m}ZSTkoU`0dg6Kvo{X)>MscYXa=op7IGqL8MJ9> z`E?Mgoh7Bleb(N9EnNm~I)YD&Sc6g+mfK_K%X24QN*}5E^rqJaN@K$+S*yjQ^tIFh z_s9RV?B8>_1AKx+zW7zQ*O3XeA6dNI)wR5^+83 zTQ}V)-C0msWZHqykdBtFb)mVk*8;#*d0mW@Rd=5P{y~Dv0KiF-^}bst@4Bef6l(4*DzodjC#5p8+S}yBa8Q^?)DPgq z^Jed*Bk+>78D7?&4~yVIW+zBTgs3g;!IoTKkB2E%&?6#q~ zjQYR?^Y%vZUHVd1)wEB;hSnQ(;{?iWEArDA&TZi9tSK1>PJ7?Hn~P6+11wyKf-hOf zl^8a#kpcTK)-HKC=VH1tCKTmU7%EUeT<#>1PruIkCPk3{z`7YL3v>|)k z;A=B|Y~Z6gv6VgZ zOY*JSruRi5$61&+$QPbKuH*d36iASzqUyqOX-D%x-gq4$W&Df1t~u|%hoC)IK-wF^ znb)1Aj4+2}6L`&WXH@00`<{}*Uh#mBuGV_D0b<2n03_mmZiTE__T!XD(PmYF6vk<< z9PA^ppZdl;K5HH76ErJA^=C)1ZLWQ!`Y!{LH|QREkWfq+CAkke70{8)}vYN(WN^t(9u4=RU_htYyA?@Z>@^y z7d&q^^lZ4udgdEYl_FV8-dNC$%8F-pi$HRC;Zw6T1d$Ky_?3vL5~Pq*G~9)}iu-{6 zK-#EDV8BM+!-W6bNKj;R?kT?*suIt}HbB*mJ(Q`h|I!`HlS@`#w^b? z#MJ;3cyu###Wq*tQ!hve$%dSgt8qBO{C4E0FXTZhb3hPtEOc8Cgppb?Z%XF;vyPaN z0Pyxx4h;;MjT>&a+|u3lKLgtIWnPg^WV?$I`3A>GL@{KKqBp0d_NS4oe(0@Gf3r|3 zTZ>C|XJJ4Bj+p*b7psaLsMzYr6fo^5nJfq@4QWvP^YD03@&m2pE*PJ*_j>3l&OE41hnor)-00Ko@cr*mnPRsy zAQtP|c+poM?GY&(gq0}2KCIy%Xf#U>W$=AQJ!Q0mp;rhrjJze*c6@%~4O>j@!|$de z8TZ}V!ZC{~Vud4^OX&PP%O=YRA#X7+Q~*UytiSnBq#r+G2WXE%L&lR$D-@t&0Vm`W z#j_P^w~$O*FfrzmjS-9qUBQeb~qeJj(HS4j3}DM`Y~l0)|_TiI<=A0(G}7zV)9R zTPN`dGZmJ}@}gbahfHp&+~PzC?abf(gSX!43A#cItAMMzAofh3mDQG_N3(9ISivhn zNX$k1M@8_3c&URtmoAYqYCF;n1`h~RjnS{&D6Eah&UN%VFxdgl?Rb)S?0%W7o2e~F zcIbj9<1?H7otdKT!Qh9uc;d+5C{E%$dc)Pi2WUC}h11uE0jrJ}5V$Obgvq&KXJadYN~$lFrx7p;wgL3Icn&K60UhwEdJstYRC5IKf1UvnzvV7T&|9#6#(-uM6e_2 z!iCKcF}qLaO9(%KyDJ7W zfE|e)fb)q3N*+`UAWN-XV30tam6ZiXHzvnBv{s$p zu)_y6^V()FEYHw}8on*JJAId0%l80_Go&oY*I=8c`DbZGHe00+EK<3r0_LcHVif8k zQX>C91kx>HMEUiP`}Ja?bc&E#0D7MHt*|vL148j2a{VAYQ?$rmiiEJ62&v>BsC=RQ zCtgd)tT*nK2AXo(N2BOzbN3klLf+kjk}%Ng*eFE6-J5eS_B?y6`Y*sMhWP)eaj|-_ zz$k~J@XSilvJ^1*T|aBLa>R4w_#XfP9rheY^t4O+iJr%aHhaJE&r$$P5W1|{RrS+K zTf?5-xer56Yi8;Eg~LN;cbS6@EoaG6Ap0*KY__PHEr)5zoc@bu-aLPf@-QFE^8K)} zwUG}jLnNRBzQ(SSDgg=chQ_r9TciurA6N%F)w<7Ki=Fj*Hapy-y zyUIEzf#Jg9-v4Y*ShVEI`sQL|zONu5AjcIXWh3>SkZ?}brt~EjfnzadkrbZAm!g-} zS@pB;vv|wPUAO-zJE5nDcM^_=iF1Lhu7vf+rT^gAO*97(*;Usx#+a>VE>Uq;b6Qy1 z?+vcD8nPS6ak&ilWuzIe51ywx=t-AyNd<305FvspiOUCbsoAaT?tbfIB_-oJ_k``A z9KS#|^Qap5-cdSJ>}64XW4MJ?^I1SoWl$4A_m28Z>&kKdml^S#w>@DZP!dxG$^jo5 zZ^i=&qXF@hfw8`uP<7>cso@=#ANbQGR@CagHMU#lRN0`BiDm{?y}Yh`@oJ1ZDV&bM z(*zyvXCGx$2%?$3m3CLx5v)=9t>T4lzh4g2mhsz>zG)AmKateflfKYp>iZDf*rHJo z;K+lcCV5FzMb-~TlSg8m&tUEdS|0-*?iWJ(cSm|hjspxwW${Kn!+QQKl}cKqF1c?3 zL@p+~$et7X=@FZ_nme4pBOj?-ly0U44u?6b)kJI)MI`O|ZLB3&y}?CLQcn)x!XufV zvm3FT*iO>>Zt$5{OwLJ;jb%HlT2*ZSWzttwbX&YN9Kt(8|AyD6JwF6l*+U;5|aLcepz#a(H?i zItB+q45qCXJ(Q*qobGxf+Ds>rjaUwhEzXlC z@Rws#3D(#}L=1So_m&=2b=}*}^{aR2TFheUXJXw@G``a4&$v{rD%C3xDhw+oUU5+h zGc9H4Te|JfFL@o#%QNz#OXt;VPe`S(+fS(h*QrDrB4%=sqzQFX?|yo#W|JH$gIYR< z0v=jy=J^R)SKJES_{J=PbNr-z{-glpU0|=C_76K|`5Qm`-N6Vj1-_LDDTiD_JXp1~ zmNdC+8dwQ*HI&!IGY6vf$Juk}g=g1(YfW*k-H3{TM#$RB0a5r-NV{z~W#o1-#(C&b zb}cIR?QBYZiChM@p*fc$VL$&jF+@Ix1*n94fn0xd`W4NXXd}|ar)}r?8`&Dzun!Zw z*&X99(9xFV<^8rLn~+Jr3HG<7W0z%&)&bM)WzQ5I%L08D5(yb9DVaxVGu6`%zmlteJu$lRRqsV_%(P> zl@)PrZt!~>wT}sua&fil$zXCxi>g`-_ntRLVM~`OQBvCIkZmrUo8(v;Oal_0reL?R=&i za3eKQ+`c6|xs9_{=^PD>xYUu815KO!NySi7XTh$bPFdhl=X^NVh>Fr+0!3HXsaGl* zZh_p4K$gGQY#8)(8v_@~p{a}UIH;y`KmF#3;$Lmzf^cV|Du&-^EKEduZL}}%PXt89 z@H9fpR<~ag$58IH5*8^kHe3r#m6n$weH5}F5jwM(8x5ck(w@&5RZl0}_ zLKcdjYOQXwi4fDD)UvYm`dI_J9a>ZNqGzjqF2_>-MTHhp$CC>KMH#=8UAQ}4>wDZ6 zJ?1%*fw+O%2==gz896l~8>4pu;mAsaXcM1Tas4*NneeCN1E_$_)ah{PE9e)z)$3ou zGy0nA!>tu&34sl5hUzOfU z;%rRWnGl~kUFxzHhKpp1iW;^1Wkww5jM-xXhbR~pToVx=V=n70pGS5352d{vzRJ*Y zP=94Lk~S3ap@G#a9zsQ^>0Za`rTN1XG5Q@Trd&CLlOP9og*5+BB*Fi@0D_JJjyP3_ zjRL>BT75or7whHrP{6oV6J$PF;}taZug=EsT*Md@cAZ{f;=QSkAzyK4n;|kN33|Ck z8Hk=USi_f>lA;pCFB`mx^cpV?V<1o}@cYl()IM{;q)Ydev=Tima)yH+m{SgO{Xu@i z%;7Ii-hX2bNU4rtIpQWZt?7Gg1~^vSNq}E+3FBU$EH2n@V?wPwC_!kBNIxxfDwAoh zhLBygQf#_8(vU5MX~?d_U?N+JtX?h1F{-P zPZJXMC${kp>q7L+3!-mJR|z5iJ0z&`eae6fErd^D}CL{Yu%Sa`49ZhfQh3Jq>dc|D75x^Xfz_rVU%!4n(TRBL?z{ zXcY65B&Rlf*}r<Q$gq^Aaq`7l$=80zb|OT~ zF7@Xb%6iF>j7r?`T!%nrohq)ons73c>CUIanwdf#U$rK=bNPIJ)MWGs%+g}j zv^T3d82IY-hn+3A*hW8{l_?~6KuiAD{RxE__bbLB1Dgict59*qDje;CDz7=syM|ji zGImM)tEc^VXxTTsL@xxd&wUDtLqh^-HBxrg*tEvBezXo6(;w(B*FtV_^u*X-*tCUh z)}^>Mhrp`>PfSyh4R9fRdX17Raw@RW;uvpVrCK%MBovn`Qe*Vs?ra9(W#g5_0}@DN zAVj5NQI*N=-ddH+*VAN4x~B1FQAVLx5@z7cQ*B`^o9Kf!SfkCjHHm(HH$UU4^VEpssK@7{z0dPQC4;^M)VN?~N~A8ju5o`h~I z%Q#>fe!En~JV1O`!NEPHi$Uw;OSLk3mp;5&s4%cV3$d?ooW0iduy7Q>#xO(*L!5FV zNpm=EZ+)kc54);#`7xb= z94#(pAHSFnCBC4Ar*+d` zDMZXVrJojl(UALjT|=g8-{)#z2fUD99NH52yz4&nNMq>fHga5vFa;(j%wqDUHv-Ix z$>T!fNZDVU7v57UrPJt2Chy(C<)ryWdG_3C>&8ooMLnVPV~1HBRoD|E4};GF$DfWi z?gptj*3k-wG5e41BJ33E|7#|3GH)t7*O-u{Q3#WU0%>rHG9iaSULwEZ>ct6jx*1O&hEci0aIs5E=UBBAH$%-qYRwB{=oh*Y+Oj?V46UPnMMJUFi`!@MB;?oP6ZX4`B3z-+`ox6ksB{rllkd+>#ov7) z@M6^h8rEg-Ft=C6vdZtykF&kGh7;6(9`rwpK9v4Vz-+k?os^Y1$Z0d!I`QKyA|v&8MuEC8_BGcbHl zhDt&FTID@O;-|%5-^2dEXS)_zLIbGlnC{znnM8|A)GT|nk|Ukp9&bj6fRxQVE7Id^ zlWMe)Hv>Jv39Az~@NW95w*Yl|7PlGvI8w<->x7MXQLN_nE1}!WAA_;3TlKpQS|>sI zvuzDBG@QD#3BBa$IUbb)Y9DM5_23YVn}hopp~Z1u;I<{Gzer%t-~|j$y}z;fYazl3 zlxVPwzc%eq^cUg5@`vh_5&%G6tT)N8Xn;T06P-#|n!b!v{0|Pfsqj~Bzp?E)FB%a4T>@ zkt68%opCyo{K7}#X{8t~JqHq{oug+_?=fOPp}eKe_COaHtz5v;+2me)2Oa@;5z*ey zV&mE0d3X@Je4z%cwuFjm<=rAFJGg<~6= z$jw13>xMpCicpn?_uk2(@$Uv-%I^sMr1@2@38`jcNK+5wre15le>=showtPZi}IM5 z^;AyGi>7A!!3$w#&}E~HzCVgWM6g-ja`Sm27QyW-y-@kklB?m)C-a_^JEoN1)gT3u zO>$$VCrXG%Ddic(yKVTMN12W9x&P-<+o)(hi?ZJws7Uw3q!{{lN zy#Q6EaEFmpHV#j+vH!jCN$J&umguH3#LEC2&5OF#7IHrS*n4FMQ?o6(1?C|QqB_M= z#RwKG8&-Nus-sbtnl9OtjOEqgh8@Gu-V4kXT>&N;rXqAu751i*Q*(XpVm0?bQ^zFr z=N#LGmV^g^x%cIG!B0@38mE)F&dMv{&#x}*>X`dh|5|vnWBU>YxrQDMtJK zG*hlJ1rf)uf$TF-GNPW@X}cH!aQk&2D!y~jCv--eTOTY6Ax4ZQ5Iu0G?ppxp2to9V zbbeMua9+^xQ+VRpHmw9W)FO|Y<1gGlX1D-@%%@>f7^B`X}-Z}kB%*4D> z*^{|Zwd8|DW>`!>kto$=Kc~tiI}>@ziHCBDx`e1%67!pobsHf67i-c(vOsmMN?pSa z{$bY%iWy0Zg9W4_vyZ@SjUfQq&e4YjY6-KXmwjiE{N|+?+T&rT$0S37qfd0`ilm>4 z>tIETVE{d~XQQ8d7|rkerJIdb+S8~JiqI24EZ`^N3=aFF`SY`%Vikg7>EtPQNPSm_ z>#3pK1giia3VG`KdcIY9lzPY=G=AN&1y%|xsGQF3lYK;KGtwP$YM!33R`C9B5qlN? zW3TEV&g6?ga#z;>6oglSF?fF%C2C%M_{NG8X1+C$7yX;e1RI3gEdJ3i#uD=&?#@x) zf3FKyH^Kn(SFFf(r}Q<%Jur?AqaAfKL4Hpq??H?IrHQ~$Gi^K*bvdi@gk5;5yqXV)MDOHO z)?6G{mf3&zhoav0b(%T={5;ZOVsCxxaoA;@GrPG;^fw^yd1}Ki$I!p_$n)1*x6!vp zT8>2RR1CnL8u)>&)tZ}rRAK$^IOezLO|gE^<=f3)=$$0jUzxUFQ?x7&nrgQD75m_E zgmVk}{sjFkw^vQ{HYGZZxS<(rrl@oK6O8e|*6q#{oIzMck=-xrB*R8OFz~siY%)^^ zfa2*9&P2k09pzPUqUq0H>D=Nwe`i`orgv%Q&0g4Vd0vS?$MT3Ev3 zWCM`qdYaX;M-hu9Ep_ho8+LVQ1e56e`eCyl`-A(hhIgHa1fwUm!{VxpmSKQyZ1cx$QpYW++=pQ&PUd3zSNOc}P z%EACGqG@!YQk=0CcA@1|zF%N$-MZ|sBlLSV_4XZSRJ;I|JuwMI=qO8A{{;*)5&0GP zre3eVEyI>Z*t{AQHGxOjm?1C1F`1@kqJu(dMS|op>{tn5y3m*ouM%6Xoli93Zvn@o zZ-l%Dwv_6Y92aa`qE%CxTkyP%!%d$4fk5s3Sx1}qupHF5`3cW_4GUVoRfnD; z=o?YQe)Zd~rQ@EDt|T&7Pz)A2au<0g54M;-!yYg}9TKU=%NEzen4x--{uqV-v_Uvs zm>26${U&OeH|wA^^O;n%7hb&G;?S8Y#-^F!^p+fqa*a)#pycYT`{`2t{_})?@WRz* zx=cr2azml>?ATzJ+G_6mqA790YKG65vLoqMw|&k&2$1veh)|JRU0wOWYHKSwgr%It zwFyj9Q&aL9Z;vPiwUGEz+7+uoO)E&shG!aDTG5(QB<=hST53udh zwh+Bp&USB44?uxO8T5J&KeHK~cLii+@jqK!T(K&9x-D+O&+IGUyJsE%G(%s=?WU-I z-#jv$M(fm$bIscw23&dN(<3RjPYitpEG`5zN)KwrG?kb|@ea?6DJ{?Qap~gXn34*6 zzTEdARp~T+h+p#b-K5CY&?N}JFzvr|+&zsO{t<}A^RYM7wjhI#*I{Yol|$RAXWBP9 zX*EsFEzdOlGg#;2+u1*Vwx#T59TAT0K_p&tFN zHF3oL#;(p<*Z|vCQ;UYu^P_J zs4o-b7FHFO<*{;VzyD z%WnH^9P59oA0WoYTKkpnbM>EBnkXMr;P2^s7+Z*kcoQ-5>MW^jx~}By$W@%OL~*s7 z{1Z%o@2LF1^i_KUlL5#>!_AY!+SM@&n7tas=>W!Ri!@ho|Gx_xy`;rK=&A?W zWq}PA!_YALB=i#i%RIHmHc0j+_V|KD@Xe|{0}duPZTa|bR5EtU@Fo()qf7km8TFoh zzZ`hG2>*q32{ZB+h7Yj0`U;Z>3&VmX6Y#Ciyu8>l{is}MLi8sdeV+F&U)dJFx{3VSzR589gj;i5r30%BVp5$b2ql}u|5p-E6r`n+qr&;hjgAxr z!FQ&vZhxmc8~+;4S2jL4+^s{-+oL?jKW-J`(|z!{FFb(F0aApWpuh*|tAjzV)}dlN zv-SIiPDM*DuQ+AH@otVwS4eu@UvKwLdBM}W8C6PyzQa9!-(T5uo}P$Ph+l~ z?&4zS!IfSoOqXr1?D$WrzL)o%J|FGbpd&nUnq;dyleqEWPt$>&_vx2x#)17^-?Id* z?Z#SCUr&AKj1q)966aT1mM~f6!^!#etMixpOwpHI?LV^%uh=Dpg{dfZ_sB2KZ})~F zGl@R;c<7vHGmO7SaN8r*g=HV3oS|L&$8zaA=4_^OHUGe!ay@&1YePw)sPpk@N3h6I zVW9(eOY34(9WkM^o_NEkgZ~1r)<}`5vhlV!=+gDFsm?cdp`&UdHAlXI^6GM6x6+1# zs#32Ka*=d(;RA8UhPbg?@Ss&{WHP~_r79g%#glYxkwm32cX*VJ@pEL@0=>i9{dFv- zf`~vFK(*B>1*VEROy3)takPJb$Um@(5U{q^&3-9%_?%@lK}f;v;@pXSW56GP;|+e~ z+o6tFB}US{waN}izebdZYk7ZmeIKOBGQkHVMDQ#$gT5Cwbib+#~Zs zcpBTTC>?InBeVppqfa9YGJ}g5qisM2A%;aIFWjf)+Gij-1crl+)~oiFAHkVysW}+! z8VTM#tQXmHVKoz_+Wi6bPGqK$yJ+R*`oip^bq1T0sWfATq@k=)m)d@A z7f+tTk^Zg3olOA*qHXCg-OfgBadun39K1g}KG0UklRXDN)Ez-PV;HI}=_POSa|=9N zGcQZYTEG>e2TcJ$`zJ6wGeb{~O^1!q?_K-SizPpQ>C;dC`_QVKqE_DA29EvOw^p?W zTxSnoCERb<@7>()#osmVoq7f(K8*Ir+fm&;Qd-SVy`7m)7Bbjee6-wW3lVR&Z=G0d z-Wz_mvzH|7tAFQ3u{Ce{oo%aRjoy-%?*#eS&A67(shUAYp1BhN1T0Omng1#k0R@qn z*V)x!6m0Uyov5((?-BgOE7r1O=U2>F#zI3WO~oR%$HC#z&ClVp`KcS`Bo|ilvTk+1 z!qxhY#|&3@ii4lN-YF99R|mg*F}GR{J{XO<%;)GkL^bE0w8S|?&vs*++S6x?BKuL6 zPtMyg45k|Pl_XOiNv_@6L7(xg>k5j}D|-_SKewIkHwPL=9S@#fW8@$YS_JVWFiZ-6 z=URfBOWMj2D=q~z*?t;yWun->pE7hMRsK(}`BYdBDZNn6E}P~mz>{2SdBv$gVR$M? zVv1S=RD%tJR!yz%3JDfLnc0$n5HK-mOuN^;iL~C0QQ+}%___8!b}*R@)JJ-?LTNx2 zFu+Y0dXk+|fpR!N8YiehhOtsmHWN37nJ>l})Bbo1e|E)hzu4^nO~m)xhm_sWc)m3M z)};t2T9%dT$mx3Fgc!H95^Gnfm>2n7c*93^E2j&)RXVb?kNrk}KT)i}NY zx1svSk$xmsu=${dtQ5g5UHqNp^zInoszMC=<33jWq33As^FeFsAJ(>5`BzAvQv>$I zV2ra!=I3gpT*41nKC&jtvK+>HCwI4rJ`Q-1d_q4{bve z(S{n}KqCh8d_$wdczog5^n!nRQk!5SU8Wr{0&sg+-)ah~KCYSz@l^dAR!j|#{KLRu zCg^zA%t+=p5DH2PR14)L)QGN(^$X(>`jDug008D{Z@FB6RrA@A)0$nspENp@38P&# z!INk2VgQR}1H#dhKXeUICo87^oFmM!xk%Yd!$%YJ0fsvhA5~^K|L# zovr&saMbzNud{dPbp;&tR=CKyisj;gk`D`Y4-#v0yWT?abF6iC+GuRu?%5Y-WorU3 z;;LX5Ifp4b&^>#c+GSU^0jr24-S^l+!9nNAu{)IkZk=vOJ6;t)4Wl$A{7CaEhHBbq zY+Bl>Y-`EE1RIMKVLHtpA{L3>WDE`GIFZf=a6aqZ?HM<6N zS{WV+Dl$j7v$u1Vom- z8q!rU{71AV-(h0EMzfMPmON2h$Y8VJL*)RN6F&p5>f?sHNPki{xLLtniKzB{&?}qI z&grm|9E^t!7EuJ8(BO?_!vUV)v8SH7o?C*-uABK$R5l+=V2=~i{EZ{i?)DBl69-Ef zkx4qsS9Y8+HUM1Cjy{=n@$`&XX?c!pD_KI&Dusj)8`j?1=)4|zNK8B+a1u2M5XZvX z!=C|ay4p&N2D9mtqdzO;22K!w4>+}T)1KmL=XO|4Gj<$z(ls8n9tMH*(+;ktxX3uhVz8!{pQrsxC?X zG1!gYH7fSPyd4uxp07&r@@?1L9DxV+;C@_!`IDRYo4SLgTegci4@=>QR;Xa;GzUSx zR5_mAu-D#Z8dG=%`&iHzH@MbXVqyg{@*kViC9*%Yeugh*u79QU!_}CVQ(=V*ToRIa z(pqv7d(Kk970mJycEsevM;zP!Fxp3|e$8Eq@i)WM_cUw!WbKx2rKVhutii0rX9FUn z{$HWj(F6=Ohqqi4zX)CRP0E;Z@o+{KHiY9Ld%uC=0W)80uzPbkAiDRh>F|p)QuiRR z9Re?2Ys%!^P|btfjjum3jm7J8daY(GkJorB=X(U^zW#kt^yl+Tux60-NG3hJE%NPu zOq#Mu!I--WUwZ@7WgE>rFtPe8GyQnbbQ1^-ka95mwm(Lak#d(phfQh7jv!@ECTW~4 z-fMlp4fUiLBjkMod?PqX)#6vq;qM{|P02|EdrV5mkqG0KmVC;ADCQaZ7{SU-3dX6D z|JIJBw`QTn>sY|N*9BWQ*qJK%kJTqXiO8Em7(S#}&ShGxMRO6o7u3|4k^#;^`6U`K zRL{CjXHEvA;PqQZXrU?1iK{!gY2>GbPgDkomiLNjCZQKS%r%O0cOuC*kf7I}=Y_TRX z$PZ}&k%YehcK(!Bl-Nkr%tiY|4oW4HY5!H>?+~@{CNotiwbJ*Ga(w*GzTat9lGhfQ zzzk|<>0V38(qA=a`)_)YReAB~q2-U`Pcz7CryeY(-m);x*R}xuzD`MRfTbF9!L(zu zuJ}(s{A7a%>)#h&2^jKcixO|frW<@&Z{FNd;a zt-Ew}OF;XKJl(V~aRrsF>aLa- zo6=nge%q7QKRjliFX)5w8_TE$PG~hsxEtHjGC!=fhy@ASd_GNC_I$bi&ODw4ey`L+ z%EQ?_^g_C+nNSJo@Jb+qDVixrwY}F3{>ImY6{w!?DkG)@&|>^3@BUb)+s#{zB!Y2o z<}#)d9K{R6)Y!Y#r8qC5vhF93(!6K^59OKtkIms~+0)478&?LNA~ylfSELNbNi0)6 z!`B9&%5!cDX#n+wxxRvx|9e15v==FOA-L9`om*hlIT#eBLoWwbLjnI%2S8`trU2tr zP%75X4~&!T*x`?KmL+k=i$ZWK2%HsoX>9kD4%@EtW?!DK6;OW)B&1xEIp(uW-6c3V zi9C=eQ*b^?XS>d8cI;h5y%Mwrl0(l~EQK7CyUdK~s(un}jp7cWW=`@j*yKP26exJ9 z$zNd&{k=_(=CUvj?}rq0+vVr)JI#A|E>9YlypXLj%xYnvhXFX0kp8La`EWfI(1ZR* zgR<$_$QoWFEx0TFvfJ2R`9Fi)QS|tAyknX8_v>_ZqaZjW4}A=A`BxzkN^-h*ju;A) zw04Oc#4bkK?xu0jecUTOuN%|YijDs7r6ASQI`S+(Yv|g2OQW*~X#?B^=I+(%7@t14 zcERxz;#+UF*Mc*_!P?tQUvJuU3){tknW11&d?F#{!qT^U(_yMXUm=PNB1%*R%7|j; z+3weO5Z&8s$8hunOoD*KfVuCq*2I9z@Gv@-)Dg;XepfOQ6>KKj>B80j-1b|ONbyiD z;2S}oo{6x0LTgGeO>>=R&>${v)+}ip_{nKuGVL=j6NnTi1J2YaLeCkpP@M)KfOd|Y zscLLtDG-c%7!}lO`83w@#t0}aFM#kA_z>l#T&zOt1HI?iQJUMIQ4q{$#Ss<9J%+M3 ziO(L8OuJqf%L1{ey%v3@p{YLE5@5j<0D~l>d6!0^J5U6{)F45kY7Ui(zG& zVv7(NUU;}c6v89GqSZZY&4G2T%%Zis5Nm1 zh3&3|M~@%Y3PynS`+9TJc323u0DppZh#+D98}@j;k3^?fl|52xEx^k|h~tZ&nq}Wy zQzREvDUdm82@6!`BsM9_jhsLUL2jkXs#47!S0!dCg9Jg&K9{{h?=eFA2-HO&Bo>J- zuhP&0T7RNGe%l)fTeOd*OoIY^gKxX?{kG$gaFup* ztcX)jycTAmz@c}9O!(EjAX5b#Jk_-nu_P1^!+li`wRo)dC{xU6KvlE|Xn6{>5E|E^ zn?kF*m{uahFn&L8LwbYswdBqBgp;yuJ%z0#=u;uG5@!WBgK1O=R~E!|4ki*D^$W2^ zv^JA~a|9NSd}_-7S;hQ@L2~hv0q)RevY19p00Vzq+F6Qz4r0r*nWg)>J4dTE6bg5H+)HLAwttYs3P zo{Oz-mES`EYIu{}NL40W>caD~ZsgM%FO-aM#V6xXa=ir;c)0ZODBR3qB`E1R~8JeO>a)Jx@4e} z*5WmPj?!*ZyQPrE3VBcLR!}?7PUIjmyht!*oiaXb7R$D7bJ~T@?69xjnn2FM&HwU$ zLch9lK&EBE!=!QYhk#0-i}6q^j(1!)!*kEfYfCCkfP;nvU>so!pluAQm+PhFMk0NP zGc0#u+FgbN1ffJC7um)j5i;K}Zso#1(PBM@i7sCnc&gRuGD5@yKi78BW;=H4+C1Nr zJ#_~XxAJeYMN#~A@~+p!1aN^Ql%&@{J-SL%l}5te9Cb8Kkf%YvKM*#;y4GQ%=eq-z zUw<9uz(paF<$${Pa3z0GXc(fFXoCpT&efE}+1jmOj3z(G|c5$8QLS9@y@Xi*aj zk_rht0aX3s3&wpCMSysljM3hu`bZ8qPN;LlzZ(@|8H_Qi=v(A)AqF7A&Al~x@V6k4 zdVUKped)vKBq6aAY3a(uh|5#2<+96{^Q8S9Bp>S(P{@9WR2j}WG)xNglUIpcB1M1= z)tExM%aV)o!SV|O)wBJC=E1@*3`YP5C6hsRy6c{+b<+p@tgz!4mOG|2JBKAv_Ls1E zqS5Ddj#d|gHG@Y!_k{m+f>Bj-UQSdi!t54|LqkIH8P*>PZjvv&zOqM%){ zPi3O`aC~ z9@WHvOX$-)%VlJ}rMVVB2ASMTPrc;cS-%f%J9JlS-l0omb;opcE=e*%sJ$N@P_8c= z;>~(l6vg0L23KS5c94sI)pOyMiR@y-(u)dDp>WFUn)G8diR7YC-5jGOKky_^yux$4 z5Qt)CdzvzA))XmhAk!%m!Xc|io;RL6Lvsxhaf{s3Pinrel3=ClWJdi6@U+Chv=|i# z6-1kcjI!nzgQwZcpEhe`+Lhin83kbg0ql_@ALqe;0qQj$W1Qo6+@-z^wkF@O!}!{X z!r&jEsn+7B^8Yh77{XMWqv-~ymUHRtVd|BZbPGgSYPRJU1%-eHs6gc^@FrOqThU%4 zJyEa>m*;;WB_AgQ2mBb)$#2>+hJdVM$GAAOsZ%YTz)q|3!kE*zk8+X@C^-zd z&QEz5E=*Fo-S@es0X_4!PLHU^Y2ATcE>fT|O|9dS^65dGdErw3UvfLL70x8ba@1X_ zQ;b7ioi0Os!0%fbaew+D$T+yAX-o1(e*Q?Bz{}#7BxT(;dJ)dxhm~9Ah>L>vn~_>g z3PE>#Z>qUoz@#cT-ThQ}uhR<$*;6uLXM0bXqJQhmz(Xy#(u1sv`D1N?Sln~O{bl)o zmx-)qftDO-VE!gHqk6q#_#2WSB74_xUI;^FP4?i@jfVGkpM?yFfta=~Ma^Yd+3?7= zQ-Te+c(&o|J3z>;1!h!fx!$$^=BC0Vp?j7WIqgdzTpOFGn?S&#BJp?g?!C;LDJBH$04h;}e4v9yI3hwCqx6 zO)(7%w*NZft=Yy}q8IM z&08JVLGTGNghWlwIMEq+o4_UQhmv;>m_4fdz7e}ztd~h`fBg8^0IkoFUseQ}9_%3- zRKMn2DDb9*IU`9__HomF2|2jl@}hHu`Xm)kM4f?6{35kHctoZ>qg)*OSb=*m{wb@H zImu4C{ra5e^^iaE@(afc(O}8|+MsnGId%^7ElL9*9j+y4o|Zdg3kCm!UW+L1^9c9Q z_u-_4ay9Q3)$9OX2XAL@6Y}7s3Ojw)#&XFolXaI$c7_3{`p!%L!_R4{j)LA2lgi#I zPVr92Kf(|J=w(0uAy-SDNpYY|c-VhDNF;AaR;)T8;y9OGuc-ncnaEm2+?7_ipkfg@ z-TTpc6(C-$xPlX(?fSSH1^}y&db$gPH`%5JiE;z0LSS8u<}qmVTcT4RkOpYkgTtjJ;AQ<`P@EOYnGsnlIZc|oo z1tpBiKfaPY$Z^5dIgvSG$UNqQS1QxRJ=XDXk}^b>YiII7 zMp7q;|FH6z4BN{*E9^`vDOY8-WzKS#m>2?HsRZ&u?T$xZEFO7V-;XufwY4or@1}OV z=x3hpHjf;9#Zh!BRf%J`L0uAq3H03EcK{zS(x@2!xY+xn+)g`+TW&RU+HMp)gZ>7S zO)Z-%VT0L5crYs2N!Zz&=jz>&GjObd!=cTAPV;tKkRNIhs@jgfZm8t@RZg%{1o$W2 zqq%m{$M-kOj_s6aLXj#_Y748_!4{D6nK*2${$Y!itrC`Y^9TMYl5Dkv=FQFfH!ooS z1BU089UjIN@Dd-K$fp1FX6BSaKK?@S90;NMajvrYlHF~2(=k}^Nw_ri+L6KsUF@x- zcz!JeUD7l@&1urHr>vLSDkpw_3AdcFt2Kcslp9JMpZIn$u2VmupEv|~2T>rJ#_O8c zVJMu(K|#3yI5n+st~Pe}l1;JEQmP!7N_`+$Nfl#e8WA#eP9B~;Cdbs5Id$_?svDx3 zIn0~&b8~@$rXV1getm9=AQ#5Z+sK&8UHVQ7xs>&3e^3E(E%?UpO+|FEns8g>a(x9` zJYga=J$`tAgzUI>@^6f(_pD0WC4U$I?Le&$b?}wx>1Rxito>JEaC;!aCkRK>M_mmN zn1R2WH07-wFaz7XA|7HgezSWc5E9!l&6`^W4*3xOWY?HuaXh5~Iv9izM#?6I)6T!o z6UaJXU=O8MW0EaBHZ0azve#agE#Mm#ONR}|)rk~P;OhnuRfnb73yyi3Dy4t-!!xdE zk`%bns()8YQ7R1cH2eSR5;7E&F@(wp(CL8>)WyfyU9xX!ZUX&vQb&Ub1f=6L`#=xMiEruEp``em6pqDiqY zQieD1Ppo>}GKfs_F3l1Oj@z|W?Ds#^D0nZ4<9TfTk@ij81{>WeBB2>Th#{3Ectxi%%8@>G9d0h~x5TwX!zv zSlbI4yGaRn13egw6DnER8X_orn@PDbf-D@KW}* z)3>%Www+0QI)+FcJgx8j7yk6>iFu;&xgg*-@x6ozTZ?ly`q#cOP&G+o0`?1q0Qs1t z&=)X1!Vex!9%w^EDdoRSy?VlhJ%JERI^Td(NB7r~=lMa>0iuULxj2Bd3-2@1MYq(m z0tOsJa%g!|TNch&95z>jX+WH;W=vn;0m@(5^5{n=el^1P0{VSg8{OZS8f5}D_4v+u zV~b<=uFMoGpO_-1X!g3evf2}~s38woM*Z@lksWq7(3W-ou1#%#AB5XF^o#5pFLQ?MT3zdCm^HZQojpD&LHEF$y&hLrJJM-FmeR_5*> z4gQ#rUdf4+aspwio&!U&&PctO+7ODUBF4FExI}aH8HDw9gCOLL# zYhkYHR3gt1kkU(4rrq2Na6-G3p!A((6;%n^Hx5d0uM#4Oj}J2ZOY{ZE);r9ikv?Lg8)>OD z1`YgIt|WqBsvo>u98t4pO1%GFD$l=^@V#VkC=;`o3ikzN)Xt8`LE}4;#A@`A^;0tH z;{PMiY+o4djVLkJfMGYY+s@GU{5etzK` zC{W}@2aZsqahvU>Ako?1+19h`qCJHWmkJ*TJ3<)oJHLr23vEu+X!78A;oI zdQEJvEVr!1*2rm_Q6*FIyKV1`!JAQ?j5C8su7|Z#7I7(oa7}aE6{B6I`3(;F%Z<>I z5A4hw+b{I}!c@pRzb!ZaT|=&;6t%36as`go1T9weOEo&8sL&oG4!NMe3Sao?Cb6>o`e%j4Cr_)FKsTkOOt31}UxZSG)WGiIA2ev2Wd4IUw9I!vdm4r9?jN zSM`W0*EN{D@+n*lBz7p5vcsfdL!?14b=`tN?@X^Xu)2C}bZFX+6ep_2#kbqrTZ4|D z&?=>YP1GQ+b6!%`6Uzs#RA^`MDPK^bkLu%=9=abE)@>QVSR@5@A5wuc0>Q_FWdhISm7C0J z2#FGRM72a%^d5INC)4e)NI=gEb60$X(RPahrJYw~Lxu?=(B4+)cF4IN$|ppCTC8&P zxc9}_DRj1QDBfudxlygfW3#$Mgv7s-k{DW8t1-Ej8$M2mf7h3vzZd_U$bCTiei`!B z)yK-z;59SRc7VJVyz0_ziDdQF1(CBB%Nlool0xyPX@Wni<3-M0YjU2i6U@=XZ?n3W zU)`S`XneOhoiEhA4E-5Kdn(QGnG0bAIKzRhmN|&bh-mO{_<3}jzjq6UnPSM9iy{T@9%-A?SJRy-;psn z$A_rn0c_PwL(;Pkjj+#R!|QclU$j#YV0le$G*h-ZE&81ON{;M7ATe;o$Ag#9$faW@ zViqA`6#RO8LsK$zDH)cbBu(XeK6*fU7Iuc(wl!C8qtoPQf@ym5X28iOAt6B_Q$)CY zp34_V0g$aaHdPXv23l-qb$<(UiA}$oU`*IXfO4=3HFj}0SQIm481G30h#ral=tRufnIYLDtnOY!!X{x{rxWdO; zmFt{5m&r<6N`H5{EEdZU>#RF}IF5kSRdP6nDW{`4H zl=qd^cWVKy24v*{e>bN==f#Khk2p>rO)bd79npt8R>X{b4AKQ4kTnZ_v!{q?65`Fz zffFWk)q1mNE{2fiwurbnGi4MUynt-mJsTa3Xd@U*n|{{-?`-{h-dJWkqa64^ zzBv4H-+A_!??essXHkP?<01XfH{D9qeR(-hr{In^u3XEPeG<0axGp_bvwHo_)>qa- z&yZ>EM_k4Mi`R zvq={2GxJK^^__3#0KT7bc6=E!VN#WuD_Gk3kZ1#eJx?Rq&XT-qxpPBnQOFsagmH)M z8Tr2u(NuO%C?AN{7wIqJ#<(8H!L0rv{gvz8FV!VPIgpi!N6C=JCIXnZphQTW|1{?n zOw4{w5XLq8>oRT-tm%#=&3gpT_&A&|DMmB2C6IuF6ep>(2_XmOi1s(_Vag%$O9d%U z7tNieF3#Q-r{qU@*_y(_g6^;u*^7$}&SZ$1FEqtUPxx)7QbU_hbLeQW@BG8(ra}m0)brkWPmw#5ZoI+EW^~y|)14r3)qL@w;{p0-EMsH%5%@?tmX{4te56mY za?C3T3&kKc$K~oiSU_%7hD08Cmd=@k)kI=J_{B_PTD>#~QNvikUxeT5M*F8cS7$P@ zVxeVm)&`Bs!rwbS!tEA)*7`aQ{ODqf(lRc!uIzB>qdNA)Yc4D}Gjj`VX=wAs*jXBOQn3BOUZ|=&!A@ zd1Gq4BW$QIhWFI}=B;0I&9tmci4Z2`9bbRuF-v7c1l9_sFFMtCgf(t9qRnPtQR+zU zOWNGBbM)`aHa@z2d^pRX|=dH5nP)XQtv zC?68AXYOy4%Cy5BA{lrln#aEG#_w)44o3Pc6+!_=m>;2<8TOUSlXe25pVq zJCZCQP4<$0{!eqExwm(_=;=+)Fzdr?V{&+QWea!AG;bhR%td)cfsp{*-rZu%8u%QrS{Q2^&u+X>WgT`w^x$b}03i50d8P~)~x zHc}=~=OV4pYVmInZ)F-T@SRs@GZ@~p^T+0msxZI0aNlK*((sRh_F6&s8sYZb^GtcB zVBQ1xD1<<^Ab8pMN<9ZfT-m@6m1P-DV5XHWw{<;kq*I4m81A_I*)*>QE(TPfU=f8r zgkSdfA;^R}H3QF8hES~z4=_xWI~mW8ptiN5C-k)kP@jg5wc*#Zbq;X{B2zH<;QsdG zpM=LhsU1sjo8-qot!C@>EvbT#Mj$fgB}{eY-mnkZLEcb)}!c4q-{Y zxYIMLG4XMV2mfytfJ*c29v-x^1(cZYYYLQ59V%+(q_6U%xNV(4x4{;nR}XbA0JM9c zc|;E4Zqg;8JpUmb0jmaPjT|#o5vR{_-;9T_g`@Mwy$cP+YP*`~1HHJ?vO{8=c^Jb~ znGzx=*u<{K%yaVJz2*nusD`VnOnCGHL%iagV;)`dOChe(b~#1g9Mb4G)4^M;c?^*Q zs}#_d9SabeM#{d0hO%@J624W^=grF^SI=^$1*H3@t2vd(3Z{ell4~DA*nsP{21!bx z!U78{5)Pk5YQp=?QE3=kp5nVePhorON(im0K*-QYWQ+*cZd`fpSzg%JXOhybcM<2w z9jFQ{#t)%*eH3QH8BFVlITf$HN4kJ#@vrnhPZAL6-SpMsmk!F5%;ks1*sE$YcE^>J zxdbu7S?je_j;2 zDg@0vlf62*DMMCOraHb2Z$l@4cr>LR`0%iDL1eK|x*L1`0_%R8{ zlY%2?_1C)H`O?MovZOLKLm*6WpQ_OpV*N?_TP>32G3?$d{b65Wrl`B>gOmeKyv-Hf zuoeisEp$NL>t0H_=3?qE%WdR@9XHpxo-Bxa@ zfgt{2$NQ*#0QgA+PM&`&?0Txr%+9g7+iEEDso9&dK@ct7EkMX?U0vnpWNDtVwDiCP z-?ER3k#d}{ggb{*bnA}xY?W(Z+gbEgJ65kZZS3f}#?aV%?%Ne-3h!=_!=?4BZ+sbE z;OW07&GAGTwA>p!`G+)?`$t0l%d9OA?U!{9jx!nNhs9bxQ=TpltU|5lQgeFldA_Ob zRW3$;HUe61c&(p2dGRLB0*E@s)5`Vu=`jf$lc+%ic-96?^6?0Bb3>x3qX|U=R6y~# zrN?{EOty0if$Z6S=Ac>lHq@lB${Zi!<*S~shu2BC8iL-5qqMcGKAtF4C4Q9~`ZE3u zICz6Pzutu54h|C!;7ay)VSp9P3yl0&oMi1F*XU zz|-~hCmurI%p$pTatoyXW_4F(8I6+vzP;Ktd1)RfKt9i@GhHAcqR!7YJE@o@H722r z^5#w;souE7C%&X+JJ_|21&mpXhl9c!Izf2iG`}_&J2B0$Mex={xC;zy${U{>igXns zE5m>*fDiFj^#Dp?S~ASHgc0P*;wX4rN9d#k1UTm5Nh5{ewNz^!;6pc8w5u=BcjDt|j!VBFB0I{S?g)i+*)6$N zcR0;W=|fVKb4FK2Z`=+)TWMuX+HUkdxTa7YocsMb$F>lZ3Lzv{D6$9qV~}lZi#~Y} z*y!hr9`f}EX7bx4XD=B93XJ^^pHX7;`sexz2M3t1(E&TFFs15I)?h9$;q)uC%!p#z zMwNm0db3GmzydSkwYQf_yBuyj`f$LvJx)3U<#+BPU%%+kj-Y(W6$<~Y!M5O}9^4ie zbwK=iu3ndXQ5?%Lsfj%E@(`osh4x@MlaT~Jvo;OyXTPWvqUlAsc)b9!9DPG0W|${M zTv)L|fkf`>v?#S_BM4s*mBVWE_3e%L!5LTly@)3Qvy)&*L`LMX1oTtaGNB(|L;O5k zDK0e8DS1KDJ2UF*2T!T^PZtRjX?v%oFQ@ow(l{hdK6mkdRn+sLJtm_@5>ie?QPFz^ zPZ>=(D2@VhI!NqZ960l+DKj`huGq(Bzc~^M_}{1-12Z$i!?!wZ& z1^dI#fsJd$5uGkP=oEbC=WgY4_l1qk=8Z(!`1%l&i1% zWKC3=q%%Ud2>_U!$?xoGcIwk=M z15&O`3<68|u^CJ2(JNC-b?Q8JOozAE`7NFBY0zZ$_{Sv@b0y#W8H8UJD!|Q!lzh1O zN;-O^aoxZqT3H$2^4!i{<_4Vsu~x+bp`x25t5~9G9@OAX(pl7|wgSKK(@7b$8#Bz$ z4W}zp_2?`LR6pqEa!1kJlWkhSZe#CGz96a@hbLiz54b5Pm@P0>UUQN;KBH9A21zX> zJD4(>n*#GuQ5)BBwKWGNAQZEaTHo9tO3@!hyoJ((|5b(tqYOei@Ir>1UR3B(GQyst z$52Hxp!(pW@3Mdmt&8F#Zrkl6GNP)6i24h>nDEs-*k$|3UiV!gUG3GQv%* zWNUnj+e-U-Vms??l3sh`$|ZMf(c)497`zEn%EzZ}mkE4gI;Uw2#IPxFeg&UO3X{YN zr*HAu?1td*K&i0EbAGeo01fARNPE;Tv%-`Z!(vXG<+uBp@&hmw_JF9@yv3+pdYEtl z0x=2^%4SIH{qV5ISFYJ?fjnHnV~=*D4%jjTndTv)tH7(%hlip%`TrI66;M(B-PSX7 z2+|=82rAtm(jXy9NDbX0h;)t8f`F8ON{4iJ2uQFM!h@x+G zus-?g4x+Q7sr_quuW?3jmTUIwUp|5~Xia+VTa3`Hm2JM0;p-3TP&vEbHW?X3+oTk- z`G%;0*K|J_Y1x+!Ed(?_r~7yK^wB5X4wZ%_bP|9?u?&}Tq9q6^)J)g1h^wCGU?A44 zH_>T7XiY&*>r-4TO$M8BOLUP=rqZh*m*m%N9sDIN(Y;-RhFQuOUmo0uwY9_VgCYwJ z`QX5(*xji3#&pG)#ppcMLwqz7qIgk(4iAUCIca01O?3g(ue#9pPX+1+puzj-ENWoM zoA1)OT_m+gi5|!6w?wnU8rcHIEgAbgpM*R7On`8`>2)~3vpO)onfpo~;~r!V_6ts; z86&a{Fr_edH7mI0jFYhxSPm%B z3NNvPo1eM-dF#TX_4rF&WFIDK$Fw+&0+EyybAEFQM_z*ZGtAQ{LX3S0@BAyCZqz1& zOj@`YJlu^`01su2Ffc1DyY3Tiegd* zERCrA_f1^$=mjhUQl7@6|wKOM2g6DZQw*L%w1fB_KW5NP)Q9W~eHAASmwd{(?q8(V~`E z)$O_W+GeF*gj)rHY+1!Sb03(7(CR&p>)5YIe_5AL?Nddh*eoc+cAzJ;EAzjI&LXD- zQPrvm=$&mPHCoFX{ZyIPtV!f`l<{9KNSH3}N%WY+R)D)^is$~PsJ)8g`kITbi_k!s zq`7}Yy{(@@y!l;tzjJdmd!ormDJl<1>+=xesN^LogX_x!g?HecGttMwHaEv-Jh0wl zj(?c;mDAdOW4`6<46>zTpKB}^IIFCgfg|@j-SZ^^dhss9X!8d_=^~(ziB>8r@A76yexU652pNNqixyEjHPkn&#w(r(W#!~ z8vG{qXV7F(QTNOH-GNT}Fmd)Nefnz}GluLlZC2mC2+cZ^u-+zxGN@VK#Exde_ytem zL~yNMJepdsuF2#bciCjMl10c)XpAs!K4%)2d}zu1brF;{ce{z^LvY#m+0cpD>(EOI z)Q^Ysm$B+KoGF3CpMFw`{T4Q0scDYBV{Y1L6zca|P&q>2e!MHz8hJFXN`PKm+e>wb zpA*StB@K2@uKri91=U*)G-7#+{FjM?5?8$HCDnd30qvyz7v?co4kshH3qgSG#3#Dn zalv&#RK8|jpB;;zDe-_mimREh2CEs`&)bQD^Cule?tSFe;$MxpM{G{=_5|UAe7#ZK z9Vw>GLW`F$q>Cu2wbhYqyZHw;4-mDAc>X)QVifxh(j%@I^YRsUC8PBWY3L6J$L&Nk zk>Jc2XF9wY=QAA{HI1Z}zmBYu83-C-f&KDrdlxZrF+-*kiFA4G|1O{3O?&JS^g{CF z82ZN&AVO?@cB#jig`JUnY6jmE*<%ga$wm$3{2m3jI8xBYs(@323^BXuK1^2C=>kBEu1tVJ1B;%r>Q4F>cj`BII4oeDmnQO$d#HY?P<2 z@8BOBgJoRtoJTcsfXR&n@1uX&OX??tj{|=th@Fl`7$^zvTA=8kI9Q}L zGp)^3D5=hB)@%5XXXY>*xP|m)Lta?2IHZ)H%|pR6i^GsGCLE+w^sGwWNWh)$^X5nA}LX8Kt)lHyC=imaN` zl_iKH|I5olypn;>ocQtkg63#W>KAo*0fq$lSPY8KBQT$NC(4|#{+rW$fG2F%{!I>d zq<(M>zvZ<~S$KLKAev6#TwnoMu;eCPm16gw_?f<;=lx?0ph7?~j-HTu+yE6Dq0|Pl z)=ITuAv$)Zge~_T7yMJ5TV*Y2A1`=he@49^-JZny$zj1U0&Rwr-b#nes(Z20_Nt4p zeFVi16O#EgH5I$NDfKR)Tg!0o;>pNVZps}Wq1$Am!;qKIUe>e>4Gj+T=D63k=i|3a zibFUjtS2Hr^$-T50)~r>YG>}L$K27KD$7&%+kW#<3qDItseG)7y1#sqX>JF|2p9mp zIY`~kuUq77Z`CU8_x7r0^_3J;FwJL4)3@#1n+MK-l(kIlCv~7%pdPm?83-xloapUoGuW7YZhR7CBKq_* zkKhszMy5U%*-W#9B!=1s+>Aw}-bs3n18&GNq7nbSxd1aOIBLsE~{NgO4oD zG$-A*pK16Cc3bYT^`A{{Pvi#O@sT3ScyV4YH*zn<*?J)EN0I1%;pUjvzi{(Ia-G)+ z7fhGYG75RF1WPj_&~U-#{bdzwUg)N$kT;J;NX?Yy8=h)~`UG4kiPg8t|5-(-nKe9Z z*jY5|@*vO8QiJwuPTmwLQW&!^o=QHdd8%!xZM5}^ra=7$G;r;Gry?TXq zi5nxff)!X(_!kH6fVd~?w`li<^%z}#M&f`?fgBXK10q-1Y2}$A&JjtRh0z&gWP;5^<5N9w?DsI%;8A&+)2<>-nAj9pzlJU7d?b;t zRs!hzt!_1FF%BDcdAkD9Kwg-n<6!nYC{hBGmrC=PB?hT5FP9IAzD5tkAL~4gnyR8s zNug;`3o$>Fm>xDVN`4F;J9bD;AV<~x%$IBd5{&893}&%tEEdz?%4e1G`D|5NK}60X z7}RgIE*qj4aEIVy+2(Ld`jPVfBY7{@nHi$MY4zg&#?g`2go;?)4b&)m0(M;P@ANSW zLxumQo0$K_j(i7g%1I;La(#oD9k=`Dyj=&6{sUX@j2R6*1$`0M9s^r6l}(5mL)cIF zU$o}1;oP~d5U_VI@nIxqn|02Oqu=Q1$Jd+gB;&E z9iCN;YAL})B3#mtX?Sh(+X%G{5&qmY-6HKQB078rs1aF;Q9XIxOwR$h``XS!MAArC zOdUZ@pkwwtoDnt4P|$a7)|;TQTIQXO%S7^*ye9pAe-kPK#W?)l2BGg1cQ-QsOOsiT z{WZCpxfLuXw59Lty-heoW48|5Tkf}+q&NIj%L0a2oo0LrnJn1($YpZxM5|Swpp2%m z*y&rWlEED$;u}Y#9{|=gd`65J~dt|PRSS3=htD9ak7s(o8Pow*Vt-@*me_u~JGL2)+ zp-wi|$&^xVQ-IW3sw$Lqgcl0G7DGLn6vIZ`^+9Y-si>$TPWI@N0pg(sB_@)?ytpE+ zK$t%JiXHTU#!Tt!mgFN_XbZipLAWO6B({llR6FH@an+Us3i5yH!UwNIEuSf>8$2s^ z3q|GuTGNO26yhWsEo$FxAL~ZWoOyf$d82iuGdWBlo?{(irD>)YiVB%cDSKyF&3^Hh zQsmwE%s9=k!bDx}1j>^VhSaNuiyj%<0d-U33fC zIQw(7|JsI^-`!I&v!#CjIjA500anK0+mnet*e)d!JbmjMc_j+J+yj}z1#0VKl^4UL z>HjHa9UTXUL(5gKlAbgEv%&$9VBs}vZ6~rk!cgn8X}iAL0O*o+0MK;~h-)n4x37pM zxx0bd{`slv9Xq2Vd1{&xp;k?{WPt|DAv@TH@8C+`?Ev5YSzLdwfw2Jfp`sEU_LEBu z?Op))_+Cc) zP*-h&D)_kR_m#yg-XKlx)UJJTPI>TaoRN>4$;b(u3X?CY3VV zO?38#a&(E-U z8;w@3lf+ZZqmC;VgWUqx_D~_QC}(U=AOD&J|L<0Azioc;ScJ9P(I$K!^BCWc?f(bD zn%F*FsY$(-MW53W26SqB3$mK=r_F=i!L!AG#qs|`IA%lG_OI*NvWeei@tY5^QVhF8 zO{GN!Rnmm$Mlc!}?wOQjR$oTk(CdJz5>b87#aq;H+thn4=;Em!jc+i_1F$CP2$sT3I_Sb2Lec(s)$@TDi#oK*PA& z=+Eh7i%Tf)jbzI{z=X6P@y9Fu^zW z?fsK{h%Oej9DJE21f|{e@i_LoV}+H-%q_CfT>_IF&GCUJ?|p3-5>!F`5kR~|eFvhb zYw*@ZH;diY-sngO@fk0VE(}X%`BohM>v*AwwY|5GiZ=5k(kNQTd7&O0Ro-nRD0)>0 zeE_forkz5oHL;u_d1#Wl%c=F^|5CR%rkxrm-W(Hap~!=E%d1DVoLDDe zT~M>7mn7%bYidsW9lg6`E0ez>OjCdNqEG*kxxd6u8U#`|GRq86CFQ#m6Tr&dWJlsO z%KFtdzZz!woclK4-||U)M-)-1k;Q(anT%P-lGFuPfau>u??vE|MRDP1l5mYcAk+(w z6z{`V`_k#UaTytR^qBQU)IKD(M2;jKHG0&No@1<{sVrY}t>N_CVpQE?YokW(0&K`I z?v$2 ze#0wN41C9j^8=#9Q3mT~^hDo2OYF_sf!7;Fiq;;|2s9o7*Z*};^=+M+mxI8tP{~d! znlqHE5>2??G|3I<W_euj!h7?=imMeEZ9w5+ zm~Ry{-QFX!VnRK1Ym)g~mpY-?P4(3W%|Mz968Wo7(^!AhB$}In$f6f(POOrVP+{GQ z=k*I%FCDq%OZsXqkNU%E&x34~x>o+Ae*f6U^vS%==kc`&wT4Q?RsSe)N{kLNv{}{NHa_lixDqk;opsBZG+;godUt|N6J&ae})znkXve4I?`9T1C5Ovz} zv4!h?k&*eWeI0uU6z^8O;BcDf}xV5AuG(pT$oAK1o+ zWhsq|>R?)Yfol>>4Dd9Do@6kIQ4b`JMcefeC*W;iy`f0$*ub@b?cjd?Eh}3%zYq$EQJ!IgU;+ytfPW?XUD~%4nzIm40&eZa0OOx8> zF8qrlJxO^gsM`&KFUJ)%$|MQNP3l;EWeqx*t5<9quP#IMdKX6hQtip3w7+gd?zu(L zU6zY#q&ZZRb#<@qK{8Vst45wsc?!)%w#09<6-C!?O!z^RRH&Iu^XP}D6MWW@Y+9Dz z>FM}c+nS!0Wz?^VjTEmS?i;I!xxoN zj{^UiN9?9Uy+mC7gBE!rUUVssM!PK+gjd~)hzvp zS&WVh5SSV+pMysq1he;o@Y;S~mjiD04c--xI4%pkD*ws!B}ICmk3y*-sa%J+ zcWA}2+~q-j?}BjtJ2+@kc`9xm1_TmUqP4ZPH-2xXkAEC`Jc88LRt*iol64tIhaarO z;&*`hN_%kShNXLbx1{FcyC;vopj_wGc7W1E3YuRM+L4}bKD!rhrzK- z5d7;5OTAkzn}(NF8u|KiC+1gu1R7j~j7@|@8oPixHM2_wvS<|bfaIstNKQYp?mFg0 z@wu7)Unh)Dr!dw4`7H5!hJ0xIS0Ec`pkAEc8p)3AUh&<&BS=qs=Y*as$e)nJ)~c9- zz&)8@%GROXZHaG}3r$x3Kc-8pgviYJWRL1yOVjKsz2I&FShU-^eB0oO1fQ@#t$nRn zV@Lt~?Dg%37&29i18ox3(ZCx0^~#K5gdCC+d(Ej0VGVl|Wc0&|`^Ihr%R_y*#t zIU?(K!1Q>ZbU2p1pUWgxTXX!T7^sezgUw4^pc%K-A!HZ}V{RYs{b1m|Xwa-w9J#zD z&r&drAUD!&pfniO4 z-AVt=Po#=YGhf6Fn?S)-730{2&v4s!cd!8oZ z5N1*aeCsN|o{^)9RoJ;wbcgyNs{pzVgtUuTBJ*1(H$7GD8LS2d#IZbiS|3u`9uiX0 z!oSG2M2=J40C-tBTj|eIJa|93fV3%6HI6UHmq^hB(}vgPdpE~*q2N}w)*_w?i@#Nc zqEdrh*g=W!4U2M#-1@M+sKv$!sHA2c=b&w2obnjCvU+5CF>+UnbU{2JW|hdqz?}1C zu2rgZk#U()s*FtwL8u41U|yUpCen?$a=IS>lt=7=1YToV1B>)*ppW8oQw)uw*78B7 zc{%K7-P=crp#AF8bNt=xw>Wh>#{Ep9!pb{D!AGK*5sN(~k>M2fqq4jPoTmk{)qf&~ z>FVRBkDn+mf7|98tFA@Y3fkx|P|CHt?(Y-ka8wjmc4$p@7X-Z$TeyzAx~DQPgo%TX zh?Z5JU?03H0KPYl{3gCp*sw zx%Kn>RiNW`W8KSEoai9`eD}tRa%6$Zseg$$?>7U6mY-@KzkNpd_496}Up0`;lJebe z(9VQsO_TpIGG{5sxAKuD3_f0RX(%3mjFMCPt{w!7;nXWP2vgr9x@%dci!s;AP3-8m zdJF|{gCUmhDH-XrIF7GtW?t2vj*X%`|0O3M)DmDt}0}|R@ z@vP$j9$AeIzR=!crJ2<&Gl6N4;;4MmM^H7#tku~W;@kza>*;24m~f7^AV~? z0}%JZTp{M-Y z{*Dg>#yVJB@lMwJhA-`1%a$97F`L|ZLuiAyg2@wip}C}MnmyQStIoS0t{O(1ir>BT z=H?&CUWe9qR}4Q{QzQDS_*sM*kB9V=t(Z~I+o4eO1j|JOHUlWwzW@_$1#qAQ!%B<$ zI>iH9nO{yT7G&B^&6s5_^Oy6F*|KXL2ESxUE}mz8xe(h{7dD;pJ6et8|Kr$LKNc(Z z@EPKH$A`F;xh1K}=8H1ni1`zk()*ZMWyhuIUG`fStVkd0^Qb?AC;D}{2+4NRXZ53w z3MXfSKd+llr$u|`M>JPHLkSy)?i{kIRQ2Sm;ak$FR1rj@g|Os;SqQAFsOfnla^%Cg zt^6SBEQ(F@n?2q>n?(^;YWVR@ymM2 zPSv@{7u;x$*)or#Q2v&WJMM_;S(OtG=GL`^Pf^2b$6oVvW3qo$8NauQ(-_&0vZ3Tn z1@m{HR8f11Q!I>FyuTPi1{67F3^S{-?<<`la^IStjuWrsr#k&=T@#}mJKw;2*5usv zj^&%9r1ADE6DhZchP`?kz3jzhWn~9$=RH0xG47T^k9CLX1)tz3ygA|y9VzhhWPY># zepHBZCXz#d^-rvfalKPs%fg&%dXT^2=n{g4$H1k$_>aqO%V~6rW~=@#cW%3x!|<0E zkP~bB+0B_BUsJ`uFC_HL&d&CHa%lf9)$3|=4JL8aZrS<93)X-0>5rxqJ7(WKD40C^ zHV|;f=hvh8pHrtd%CFH=;2H_Ll|P;|GyRilH{-%|ujgnuYV5n;au((~B4T` zzw9_$Cs#YQ`M5t`YW0(xt8+YjI>*)o9020&w#z?TYIsS(lNIK}bIxts2s-SOJbu4E zG@0AbkFQ>LTk9Xiwwx}e29Zj9K?@KKsq(jU4e+;ZA?Uo`V)Hnw&P-R@-ceK2ll29 z3rx6O%`t#)u@uBZ?;JgzL*a9!_)0LdEvviu&_GI4Yd?g6vu(`57<_QqPA%)#5hVX# z{{u|PD2C)ve_)7I<9x6e?q-<0r>!1o7B($V({nBOYCh|qAIw#DkT{JtO9+EVHvTSe zZzAIVyoWmNKVkT|2#M;`n2Z|u=LoFSj5rwasZ@EgbSPe_Yc0NDOxMA%?>$-9_!Lar zG&ERi(eXN8O(mu)0s#rgQJ1tpeeu!`Qv5Pbf$?`n7W-_L)p zwVRl1)@z~0QZ49n(EjIq_p&I%A(2?nCeruJ7&Wji!1ms^aOrH1UhP2Q^i=M&X@b^D zt^DDsD<7;^L9!4n4j0vP=;{~!&f zBh>gdoAp)J5mhi{^}6c62PsVOk@iE+ccPLSa5QRvfXkS^*&L=iuGUmA<-LhDIp$+J z@CdFaQ6tzp5r z=z$QHc!cOTZ#{Fc8auQ8&|YJJ?U%If)VOrFZLfi_rl_2IGO8h_=(MSA@wj$p zm;Kx<+q$Xeoo!QJkA-)_&)rEs+0#!;=f+N_uTIxn{y22fRUFlmp4O^y#T2|S5e?66 z93stkDBXy8_kNwv-X{4pxb0 zlliKC=od6xgRW?r`J#-!$FrT^i_J)#5q>FxgQtVyteZK799GCjqk#v3%?x1dvg@BC>r ztw@mvVm)JGF}9wD^=&&RTOy5WUeYZbJ2!QSXxAdUEGsqE7iOY8N#Acvtj`LLQBi;? z7@53+piCGen4GwXXF0o=Lx`79vSoNw47d21OC;`cdyQr2$(;BJUBpLA*n<(n@_H-N zQ@xFz@51&ov1{HE76{q)JDaZj?gKe<{5OjC zs4h5j&cCWuqewjrYf7G8Mi*gHPZG!&w(<;XA6kD@ zf6->_2d-np)8X2n2KLR3<3J|vZ94nWj(-jN{0*+}A&mQSV0_a%a%#G##L zp%!Y3S`$Ab`CGq$KR*#1xQ`UG&3fOJ5FIyX46M6aso7j*q_3&>Kt>W2@BScd_(0Ld z8>Ue1V)`<6O7JK#ObTmShA9)XG@O(^Nc*1L3}36g&I=~T$MyZtpD(>PN-%l7amV@c zRg=3M76gJNaBZ + + + + + + +MakeBlock Drive Updated: src/Me7SegmentDisplay.h Source File + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Me7SegmentDisplay.h
+
+
+Go to the documentation of this file.
1
+
82/* Define to prevent recursive inclusion -------------------------------------*/
+
83#ifndef Me7SegmentDisplay_H
+
84#define Me7SegmentDisplay_H
+
85
+
86//************definitions for TM1637*********************
+
87#include <stdint.h>
+
88#include <stdbool.h>
+
89#include <Arduino.h>
+
90#include "MeConfig.h"
+
91
+
92#ifdef ME_PORT_DEFINED
+
93#include "MePort.h"
+
94#endif // ME_PORT_DEFINED
+
95
+
96/* Exported constants --------------------------------------------------------*/
+
97/******************definitions for TM1637**********************/
+
98const uint8_t ADDR_AUTO = 0x40; //Automatic address increment mode
+
99const uint8_t ADDR_FIXED = 0x44; //Fixed address mode
+
100const uint8_t STARTADDR = 0xc0; //start address of display register
+
101const uint8_t SEGDIS_ON = 0x88; //diplay on
+
102const uint8_t SEGDIS_OFF = 0x80; //diplay off
+
103/**** definitions for the clock point of the digit tube *******/
+
104const uint8_t POINT_ON = 1;
+
105const uint8_t POINT_OFF = 0;
+
106/**************definitions for brightness***********************/
+
107const uint8_t BRIGHTNESS_0 = 0;
+
108const uint8_t BRIGHTNESS_1 = 1;
+
109const uint8_t BRIGHTNESS_2 = 2;
+
110const uint8_t BRIGHTNESS_3 = 3;
+
111const uint8_t BRIGHTNESS_4 = 4;
+
112const uint8_t BRIGHTNESS_5 = 5;
+
113const uint8_t BRIGHTNESS_6 = 6;
+
114const uint8_t BRIGHTNESS_7 = 7;
+
116
+
122#ifndef ME_PORT_DEFINED
+ +
124#else // ME_PORT_DEFINED
+
+ +
126#endif // ME_PORT_DEFINED
+
127{
+
128public:
+
129#ifdef ME_PORT_DEFINED
+
136 Me7SegmentDisplay(void);
+
137
+
144 Me7SegmentDisplay(uint8_t port);
+
145#else // ME_PORT_DEFINED
+
153 Me7SegmentDisplay(uint8_t dataPin, uint8_t clkPin);
+
154#endif // ME_PORT_DEFINED
+
155#ifdef ME_PORT_DEFINED
+
170 void reset(uint8_t port);
+
171#endif // ME_PORT_DEFINED
+
184 void init(void); // Clear display
+
185
+
206 void set(uint8_t = BRIGHTNESS_2, uint8_t = ADDR_AUTO, uint8_t = STARTADDR);// Take effect next display cycle.
+
207
+
224 void setpin(uint8_t dataPin, uint8_t clkPin);
+
225
+
240 void write(uint8_t SegData[]);
+
241
+
258 void write(uint8_t BitAddr, uint8_t SegData);
+
259
+
274 void display(uint16_t value);
+
275
+
290 void display(int16_t value);
+
291
+
306 void display(float value);
+
307
+
322 void display(long value);
+
323
+
340 int16_t checkNum(float v,int16_t b);
+
341
+
358 void display(double value, uint8_t = 1);
+
359
+
374 void display(uint8_t DispData[]);
+
375
+
392 void display(uint8_t BitAddr, uint8_t DispData);
+
393
+
412 void display(uint8_t BitAddr, uint8_t DispData, uint8_t point_on);
+
413
+
426 void clearDisplay(void);
+
427
+
442 void setBrightness(uint8_t brightness);
+
443
+
458 void coding(uint8_t DispData[]);
+
459
+
474 uint8_t coding(uint8_t DispData);
+
475private:
+
476 uint8_t Cmd_SetData;
+
477 uint8_t Cmd_SetAddr;
+
478 uint8_t Cmd_DispCtrl;
+
479 bool _PointFlag; //_PointFlag=1:the clock point on
+
480
+
495 void writeByte(uint8_t wr_data);// Write 8 bits data to tm1637.
+
496
+
511 void start(void);// Send start bits
+
512 void point(bool PointFlag);// Whether to light the clock point ":". Take effect next display cycle.
+
513
+
528 void stop(void); // Send stop bits.
+
529 uint8_t _clkPin;
+
530 uint8_t _dataPin;
+
531};
+
+
532#endif
+
Configuration file of library.
+
Header for MePort.cpp module.
+
Class for numeric display module.
Definition Me7SegmentDisplay.h:127
+
Me7SegmentDisplay(void)
Definition Me7SegmentDisplay.cpp:102
+
void write(uint8_t SegData[])
Definition Me7SegmentDisplay.cpp:342
+
int16_t checkNum(float v, int16_t b)
Definition Me7SegmentDisplay.cpp:518
+
void set(uint8_t=BRIGHTNESS_2, uint8_t=ADDR_AUTO, uint8_t=STARTADDR)
Definition Me7SegmentDisplay.cpp:750
+
void setpin(uint8_t dataPin, uint8_t clkPin)
Definition Me7SegmentDisplay.cpp:187
+
void setBrightness(uint8_t brightness)
Definition Me7SegmentDisplay.cpp:771
+
void clearDisplay(void)
Definition Me7SegmentDisplay.cpp:210
+
void display(uint16_t value)
Definition Me7SegmentDisplay.cpp:404
+
void reset(uint8_t port)
Definition Me7SegmentDisplay.cpp:157
+
void coding(uint8_t DispData[])
Definition Me7SegmentDisplay.cpp:790
+
Port Mapping for RJ25.
Definition MePort.h:128
+
+
+ + + + diff --git a/doc/html/_me__auriga_encoder_callback_8ino-example.html b/doc/html/_me__auriga_encoder_callback_8ino-example.html new file mode 100644 index 00000000..dcf14656 --- /dev/null +++ b/doc/html/_me__auriga_encoder_callback_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: Me_Auriga_encoder_callback.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Me_Auriga_encoder_callback.ino
+
+
+
+
+ + + + diff --git a/doc/html/_me__auriga_encoder_direct_8ino-example.html b/doc/html/_me__auriga_encoder_direct_8ino-example.html new file mode 100644 index 00000000..2de489ee --- /dev/null +++ b/doc/html/_me__auriga_encoder_direct_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: Me_Auriga_encoder_direct.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Me_Auriga_encoder_direct.ino
+
+
+
+
+ + + + diff --git a/doc/html/_me__auriga_encoder_pid_pos_8ino-example.html b/doc/html/_me__auriga_encoder_pid_pos_8ino-example.html new file mode 100644 index 00000000..d097eed2 --- /dev/null +++ b/doc/html/_me__auriga_encoder_pid_pos_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: Me_Auriga_encoder_pid_pos.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Me_Auriga_encoder_pid_pos.ino
+
+
+
+
+ + + + diff --git a/doc/html/_me__auriga_encoder_pid_speed_8ino-example.html b/doc/html/_me__auriga_encoder_pid_speed_8ino-example.html new file mode 100644 index 00000000..fed0eebf --- /dev/null +++ b/doc/html/_me__auriga_encoder_pid_speed_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: Me_Auriga_encoder_pid_speed.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Me_Auriga_encoder_pid_speed.ino
+
+
+
+
+ + + + diff --git a/doc/html/_me__auriga_encoder_pwm_8ino-example.html b/doc/html/_me__auriga_encoder_pwm_8ino-example.html new file mode 100644 index 00000000..41518278 --- /dev/null +++ b/doc/html/_me__auriga_encoder_pwm_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: Me_Auriga_encoder_pwm.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Me_Auriga_encoder_pwm.ino
+
+
+
+
+ + + + diff --git a/doc/html/_me__l_e_d_matrix_test_8ino-example.html b/doc/html/_me__l_e_d_matrix_test_8ino-example.html new file mode 100644 index 00000000..531d1d79 --- /dev/null +++ b/doc/html/_me__l_e_d_matrix_test_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: Me_LEDMatrixTest.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Me_LEDMatrixTest.ino
+
+
+
+
+ + + + diff --git a/doc/html/_me__megapi_encoder_direct_8ino-example.html b/doc/html/_me__megapi_encoder_direct_8ino-example.html new file mode 100644 index 00000000..1c940ce3 --- /dev/null +++ b/doc/html/_me__megapi_encoder_direct_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: Me_Megapi_encoder_direct.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Me_Megapi_encoder_direct.ino
+
+
+
+
+ + + + diff --git a/doc/html/_me__megapi_encoder_pid_pos_8ino-example.html b/doc/html/_me__megapi_encoder_pid_pos_8ino-example.html new file mode 100644 index 00000000..e0f2035c --- /dev/null +++ b/doc/html/_me__megapi_encoder_pid_pos_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: Me_Megapi_encoder_pid_pos.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Me_Megapi_encoder_pid_pos.ino
+
+
+
+
+ + + + diff --git a/doc/html/_me__megapi_encoder_pid_speed_8ino-example.html b/doc/html/_me__megapi_encoder_pid_speed_8ino-example.html new file mode 100644 index 00000000..0c428aa8 --- /dev/null +++ b/doc/html/_me__megapi_encoder_pid_speed_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: Me_Megapi_encoder_pid_speed.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Me_Megapi_encoder_pid_speed.ino
+
+
+
+
+ + + + diff --git a/doc/html/_me__megapi_encoder_pwm_8ino-example.html b/doc/html/_me__megapi_encoder_pwm_8ino-example.html new file mode 100644 index 00000000..0139a908 --- /dev/null +++ b/doc/html/_me__megapi_encoder_pwm_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: Me_Megapi_encoder_pwm.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Me_Megapi_encoder_pwm.ino
+
+
+
+
+ + + + diff --git a/doc/html/_me_auriga_8h.html b/doc/html/_me_auriga_8h.html new file mode 100644 index 00000000..0a484e9f --- /dev/null +++ b/doc/html/_me_auriga_8h.html @@ -0,0 +1,527 @@ + + + + + + + +MakeBlock Drive Updated: src/MeAuriga.h File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeAuriga.h File Reference
+
+
+ +

Driver for MeAuriga board. +More...

+
#include <Arduino.h>
+#include <Wire.h>
+#include "MeConfig.h"
+#include "Me7SegmentDisplay.h"
+#include "MeUltrasonicSensor.h"
+#include "MeDCMotor.h"
+#include "MeRGBLed.h"
+#include "Me4Button.h"
+#include "MePotentiometer.h"
+#include "MeJoystick.h"
+#include "MePIRMotionSensor.h"
+#include "MeShutter.h"
+#include "MeLineFollower.h"
+#include "MeSoundSensor.h"
+#include "MeLimitSwitch.h"
+#include "MeLightSensor.h"
+#include "MeSerial.h"
+#include "MeBluetooth.h"
+#include "MeWifi.h"
+#include "MeTemperature.h"
+#include "MeGyro.h"
+#include "MeInfraredReceiver.h"
+#include "MeCompass.h"
+#include "MeUSBHost.h"
+#include "MeTouchSensor.h"
+#include "MeStepper.h"
+#include "MeEncoderMotor.h"
+#include "MeEncoderNew.h"
+#include "MeBuzzer.h"
+#include "MeLEDMatrix.h"
+#include "MeHumitureSensor.h"
+#include "MeFlameSensor.h"
+#include "MeGasSensor.h"
+#include "MeEncoderOnBoard.h"
+#include "MeOnBoardTemp.h"
+#include "MeSmartServo.h"
+#include "MePS2.h"
+#include "MePm25Sensor.h"
+#include "MeColorSensor.h"
+
+Include dependency graph for MeAuriga.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + + +

+Macros

+#define buzzerOn()   pinMode(45,OUTPUT),digitalWrite(45, HIGH)
 
+#define buzzerOff()   pinMode(45,OUTPUT),digitalWrite(45, LOW)
 
+ + + + + +

+Variables

MePort_Sig mePort [17]
 
Encoder_port_type encoder_Port [6]
 
+

Detailed Description

+

Driver for MeAuriga board.

+
Copyright (C), 2012-2016, MakeBlock
+
Author
MakeBlock
+
Version
V1.0.4
+
Date
2016/09/23
+

Driver for MeAuriga board.

+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is the driver for MeAuriga board by MakeBlock.
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan         2016/01/27          1.0.0            Build the New.
+Mark Yan         2016/02/20          1.0.1            Change the port enumeration
+Scott wang       2016/09/18          1.0.2            Add the PORT[15].
+Scott            2016/09/20          1.0.3            Add the PORT[16].
+Scott            2016/09/23          1.0.4            Add the MePS2.h .
+Zzipeng          2016/12/15          1.0.5            Add the MePm25Sensor.h .
+
+

Variable Documentation

+ +

◆ encoder_Port

+ +
+
+ + + + +
Encoder_port_type encoder_Port[6]
+
+Initial value:
=
+
{
+
{ NC, NC, NC, NC, NC},
+
+
{ 19, 42, 11, 49, 48},
+
+
{ 18, 43, 10, 47, 46},
+
{ NC, NC, NC, NC, NC},
+
{ NC, NC, NC, NC, NC},
+
}
+
+
+
+ +

◆ mePort

+ +
+
+ + + + +
MePort_Sig mePort[17]
+
+Initial value:
=
+
{
+
{ NC, NC }, { 5, 4 }, { 3, 2 }, { 7, 6 }, { 9, 8 },
+
{ 16, 17 }, { A10, A15 }, { A9, A14 }, { A8, A13 }, { A7, A12 },
+
+
{ A6,A11 }, { NC, A2 }, { NC, A3 }, { NC, A0 }, { NC, A1 },
+
{ NC, NC }, { NC, NC },
+
}
+
+
+
+
+
+ + + + diff --git a/doc/html/_me_auriga_8h__incl.map b/doc/html/_me_auriga_8h__incl.map new file mode 100644 index 00000000..8e2bd554 --- /dev/null +++ b/doc/html/_me_auriga_8h__incl.map @@ -0,0 +1,279 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_auriga_8h__incl.md5 b/doc/html/_me_auriga_8h__incl.md5 new file mode 100644 index 00000000..dc0d43e5 --- /dev/null +++ b/doc/html/_me_auriga_8h__incl.md5 @@ -0,0 +1 @@ +b85565437ea1ce52e108ed1ba65d60f1 \ No newline at end of file diff --git a/doc/html/_me_auriga_8h__incl.png b/doc/html/_me_auriga_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..90ca64f5cf0fd8db9fb415bfbe08a500e78e9dcd GIT binary patch literal 947578 zcmdSAbyyp3*Di{?loBAgl@Dq8&>#&Kytqq~ zQrsO5?>=Ym^SyijzW2J$pXZrBW@gRIGqWCBYu)Rfk2+c}$VnJTu&}VmU#dOR!@>fl zV_{+cCL*|((Dx&x?{@??8ZVw<-TiC()>ixl3yTfwN4OGD?x?kveopF>8Vna%k6X9WgF**sdJD%3mruy zI5;>(NTW8af4cIYWS+9T=?|#>zmRpPS$xTIGL< z6u4fC{iCk`L8C*S+&tp{Z~9OrY7^7E`p3`yAHvoTOTl+HQ#q3Iy9yIQER@2rDZ;P* z=@p414F9nnv;>XNLgU-DZc4>~UA-tu#p``|w%|W1bC&-fv`C!RG$8orh8ZvXPtOq^ z-d^oh1vNKH-nH)51S(wbcP}}fCh0ENHV2L@9{Zn(AIqN>UAeYso>>I_qlT7*;s0@z z<=`)_MQsIjY}N>Z=}QkkwV=+LJ!8;LErTM9Vii%omjA1B|LcK*#((JOszSGbw+wwhiKf?b+5N0mfzY*eaKYTFZiRmHiF;iT%yb;XDWZ5^e ztu}W>%makQV%XmpV0XKqP575BvLVyZf9&jQ8U6ouTnF$5tY6(aY~i%*tXGjxbX8NF zG;)PDy z@_BHRHONvjuK|GbyBU@(q1H|#E(!<~z4dg8gfFjBQ$s;#X6UjI^EdbPxr87HLG|rY z9m*=G_wMQ^$3m|9ifIkjwRMpJ{DcIAb*|EJH#n~-aZ7n;wsCiDxhHmm;Wzf>96oK`d~I`n{X#8G>@ zS^P@CU#P>IQFvju=7ku-e9 zjBvs^4+YMOx3KTCAj?y*oY62QZ`T`N@Qj&N^}#CH{>gYmfIZvPUIrnoFWT>tAXYi@ z*k5T~3x=Kjrb-%J9=No#9E&sfo5V4%BHC@Qe_FCqki!_#J06NN1rGP0G8JV1%Cj@a z;4x~qB2P8bmb)~BcQ|_fUcc2#8|(5t|HH|{g^Xe=$k|ZtQe$T8@46E;OxwGm;Tp6* z++)oVddVl2-e`I!Q`g|`mA5qc*F89HsYAzEZrGyOWM*H4gvr(P!~DWoo(5a zQ1Wj|=u?(JZ{R1?COGy!L2o?Ym3X1GI5dZvnkU1vYUjUp0W)nR1!L%YgJP5!MB`k| z>&$2?r9d?q%iws>r!}+)eN-ALWi0Q00};|tX@Ip?s}4!C*~Nnx*xL{&|5k!uN=neCAvP{zhL{`y-GFK)F# zJ+%8x-o?NIk@Qo=MLRs7Fa!EN$5~}aSjE}z4~X-n7KWTx>bHf?j{%Hdvql8HvyCLc z?U2oGxj<(B$N(*~MaWYB!-KERxqj#o@A=XXw8db}p zOkv{LDyXxC@`79WQjK8uL_E6l2j--u zn+W`?wOcacfN?vL+!k~p<7C`MgnfidzXni)tF)8RCb%P*OWIfT|+Rgh3NHs$tFxpwp$H(9Jw zEClRW!e8kQ@T==q3g+!I?snwXb-SjvFYgD$OKRSs#}hDqx37*m951@X&wBf$RcHgx zVvBD^YME(+uMJvis{i+C^lbOVKYOQ#X{QyzJM)nhQSp|VM7UCa{Ns|G&9wW1#9%Y5 z63$548pY8O<>38};={04>>(KgIFH+NkJ*6nt%3kC5#g=iINA6=lng50QX&WD!oxXf zrvI)^g@YSU28xtT0d~IJ`V>_cg#YAOH-AM2rw@`ni3{&rUrzAYxibl@OJ4_)n39w* z=w!qDl1N%;{(IN&t?EC={ym_=<4OgbvbAl?*WW!z5G<0#9TH`Kk6ZyGzL=3IzeUkR zx~%>H3*g0^gfaXl(lh?ImIY|YGv+V^ zbHx-p&|;H_efAU2%wlSC0U}NC#<*4TnF}kmv5wvvh?|We+{zhVJMuY~h6xWWsp>66 z;lYyT@n<-kT@{EPDmZK`T20Le{9@(NU~(taAvB})tZedA9g)Jg9bXwH}}ER>I+ zSLH@=M+0c9&Es^Ez>~doeu}ozQmu+P9ZTAk9WIRuxlp$IDS9JbxG@dIydQ1NSl{r> zPmQq!(M0zIWCJ`)l;00;gihTm8eUyGG!^1J1ku<%*MlnaI;-tD?gs=twE&>up*HW$ zDLzP-9j#4em^Lblzj3Rl@b*E=D+fJY=5aYgzM7b=ZXa3XHp0jW)7hT$E_BEg8b52o zp|x`~6T%EkD9A;g6+gJMhtjKm6SHUO$K*~P(qj-dC(ZiAy`^jdIZ+jsPS1zsa=yrH z<8d~7%%ywxmkZgL{F*-9%@i%ykRTvEMa>V^F$s}#9f=$o5={drRF@WChpdKrL^F*V zg%Me8|LmKQ8HsmnS?(W{`El9ozmg?PLPNK zXY|Qd5blS-tt11CX)L7Da8sr6LH;eu|M3)L{(X6{#o0T!gj}(o<`(gdy7n~t(yVie zDrRo}qaCQs$+H%D`$XQ`^-WbcMb3stSRHZk=Y$yaOlXSckdzxO9DXDwR&_;+rqGuC zDT9gK5(KS`NjG>^B&vfsj;ze!+-F$u*jQvmH;^EUv5^6in2BMvW^A*^~odg8XKMZ-$@?*!++Ln=uIjAh-75}SL0Q&g=a3J_{XhTr9Y^W`Z|@g%;gwmu&I6K`Wy ziF4OdiWthq0B=S-Bmnf!)RzIU26l&`nQNw%F2C$`tscpUwv&jw=k~9q@;QEue8eRX zuIv&lRze2DPNlISH&9JIBn5|4Sh|M{h;+88-$LwhCqr1562Bo?ur@s z-(tWGmhU|AeCX3qUH>rZ1c%ZIkK8b^m#5mhsb+h<7QqAAu37(Tz*bbu*6|rYVQ%`Z zr-n#4B?tv!bFX`yMCFlO@KovO)LV4qs;p2JQfuH_Z2e3lx1LlouQ<>mG2Fcv&67T( z_kF8xB7knJ`T@~cnz2E4V%T^V0H^H|WrGI;!mKToV4b6_wM#&3FpRpDYWtnmKEhjc zG`sma*G$4n`fG#YjG=2Wqx;UqnH_s{y^P1WsXh(O#?xT!)j_VS>2N!z#hv)U-fd$B%i8@ch@^*zqFE+x zqwBPJ!-NlCkBax`KWK%NVePck1T3gwUu#gJ+$$HP>k-1k)KS`~3pioW+eFq#cEzmD zi86bp;JvK|miFt++kL@6d!NM04m2)`@Ip?eS~9i9h{3WU%)?!^X5+}#N)pk~*)H8e z(IRXyv4aoZMuvRmC;4z;>XtevLef|G`c;h z5Ibd%F|S>dMLJ>iGM1cSr?Qk*JoU^jSY+o9lHs%0cny!}98-mRiK#x_M@F>Vo|{im zy{*`e477T>HpgB9ZO;Rlmfy8bn`IBb#(GS7e5(o~wCN2Hcw08j!i>_RH%9Fxf#Gso z6|9rv6*MaCR!{0$9!yvL)~8pMB)V>z4P7ZoC}BR_F>h+Dsv4S8+E}8?ULqE;U<{sOy1eZ?f_kIMX z#2$p$3haNM8gi(H35g$GW)7g(+~1X0Ii!sQ($P+Mk8@)gGj{wXxXGwUS&8VAe%>aZ z6gU4(pp%$O!TeW8%J6ne@Ny+TYap}poFQKfalY>>DphXDuWQL<;6H*ZO_izB)`}4) z9x?4TeIwULv{ar(3V!&i;$7t%GI-r08W$A{vodDh5jPvi*vW~Qr@y=wG=e2K6$#z{D%_h zM?9rcuoB@q`o)99tNYcoO5x=vvNgZWkirK|u6@7!e3MS_KsYS^DfZyh*Xh4_ec}8+ zqPw-u!Qwg6_FwKHD{EQM?RlB^ZS3CF+pRnb_9OOg=-8X(%PB|6$1L-!wt-t>$kFoJ zTU7$%7OzkM_Z+$H7C+G@xmgU8aUy>mpJ03&;oaMU_ofzC45Q#I_W$YR?n z5>|pYQ4WSzQC6GwC)xK-eR8<934Raln>HgyxJr=XR>JV{>;kXzP3^bgqri`#UNfUu zqOyo}uZ)W}+I|ReG_HoW?r4l$ZXvzK8B=awe%k@;Mq z*KyafG!Q+im-MW!f418^ohpP~RcVfL$vce>L1zC>h|~S|aM!9Fp-WEURK*0-p=|wA z`mE<_&y@;garHtrM`Ke-t5C4S7v3NtA^WfKf$P^tw2kwEuh?^@rHqVk7t@+O-X`De znp35wLu_NO@`~q)G$FcOle}aygyun*Gbtp>%{Y$kZ#bpg^>)Xqiy(A9tC74Nt2Oo@ zxs%TG<+HP5Mx+dGcKX4utYUy^LPw}#SPe1_LNERS~ zr?5ASVOFr;$ItXRpY6CBS-OtDJ5)3p>)G*&;d)~-*5eg_es+tQ+Q~j08dP2JcLyGC zf5|UAk{em=+__=~RY$`^24E156ySt8PIdY4dk#$!u#M2i&2!N%AOo4)j$qDRwIwsF z91VGs=n(s9FEA(dh#Hn7ef=vo=O?=&c97TnkEE2}POKMGOPmxjeYqGNC@E7j1UT;D zH<;NClzJp03?5t^&Fq#FsK#eP=WJC<+qq_@Lgu(P)8LSoE8`p(R}g;|pQUeqW*B>@ zHP!-sQ!Ndwi_^ahivO5p_AztRgm5Q6Y3wQkDsgg`%gF&LQ0pE$tZEy~J zqjN$!50~Ze6ktN5Wq|Rpt;8)+H_yY5P8`=8i!tHtF!tls3`-b9XLd1DhQhnqEcrko z2_w|W*#lzZ2XYpcutRt+5ioUKm<9)i4T`Oj)5e~+Ink$)E`ZF9do~50&_)LM2RXZQ zMg+Y2t%KIz)`?Z|^&6V>G;E|tMnq$}65csmsafc#uw=ZeHz-l6 zSEkNuB<(5}Wbkg%7v*8ljI+hQPEkD7l-#HVw~HW+i9INCO;c5fGQ9~>fvbvFLUvmA zaqcb2vY%7SQq)P(AgxA2t1!!)til}esSlXXi$yj`I6dHSz4U9AW`% zyQ{~d_WNXZlo_Eulb_|yQhS@F4$jdfcCP`=9Wj}En0mECE{6BamVLDT-3T0Fz3B*c=l*x$ z|1b4Xcr!3cPBGWbxcc<{DA-A%HDa`yg-U930X_7zGU-HzbwQf=J(h8hNU_%- zab_)3=3=V3cBeA$D+fBz2HWbeoL!H1r?O>J{0rLWV*<~jhd(RHqPPX3&1|m%o8~(2 zj>{Tu7397}5%st5u-)e{>s3x#!;GtbX(I7U$4H?_C#gxmFnnb zX%kygJ1`Dz4S&7<(FK`O|NMaD1KOAPdC14^KC2ZTfX@>`tzAs@ApiIU+GU_w z;LtPMc!fh|0_#b3!%11dtBvSW_em)LKR&5>M(Oa|6X$8zmU-34s#_pFpiYlGE-2{4=EzD(-b zagESRj;_p((?mCBru_?Z?*j>B3zdTXuq>iwxD>F?>;Uki-%TvRM;EM|Rk&Z*=6By+ z#VZu&eVq5dyE!uo4xZ(rPWbdV=)9ZN^Vp2l)#xX_?Pcq7y}9OtRZ`#{`g2&L+L=$c zZ%Q)GH;wUGm^GPN?%d*fZ&-6kZv}6S+H>5k&ZhofSzwLcZTw9+_MMFJ8sD^dbLvbN zpHt#(Q<cRxL-~GHl*q3jA@9u25 zX6a$a^v`L9!!fh@ZPa5XB)u#yI4Vp&Ue0q}mqJ*fx-Yc&+bymr#lpl6BL8~gEL%Wr zo%9L9<5t>3int{6phu;7S^kC|#_6MFv$1iVX}^5cTtUZt>Oc#W7$l9M$7S7k@cXkh z+2(1&K%zHW%0mDX7PZ+AR%>M|tkzIr5&IQnyDXRkAAkPhnr!^Q>+8r!Z>(}MFZYrf z=Eo%bSNI#;vlCbOR3?$VauQ)VAd7yDReEqA7kxj6aeKQ*GKDbESEj05;f2qWblp^4 zw6Z{V^w`8jAd%GY=tK;oUXtCp{7BRn(Q%JP0e>|vQPQZ?5hsEINSgGftz|PcNQg6w zkX&VDe8Rux+oN>hXlW){DO<5m57MAkX)#9ODvpUJjdE;z8R?;GDrbIj!V$wwcDy#y z--CaC(}&HH3s?$H`;LKQ7pwOly5V`4*`sQT%{gUy4JQRu)!p!*lD*_@M+>{gxxL6# z+eQ$ZJJX@xme5gNdyvbAz>dEhv5fHf#=F)w3UjIX@Cv`oW)x$E;Pd8oSLW$O zUw~)l-#K6C2Kk|J6C-Z8#YnHeXoK3cHhcVwo!?MXmTvXu!kaR7QO!N?)vnTgP%*|v z(;A^=^IJ}!hr!eHs7Z@zc-e-!cq3Cm#)2TvfjMw1l3{Ug+q72;(OhVJyzBN2Bm24DlaCGIIGbwko*Z%6+NqHjKeyaJ z`+0rr2g^`^XaA;473IH!P7)VlcOx(V!D`VT)yKE`I<-(p!9|eP=7hnf{SD$I5Avq1 zZ90YG-&=j^3>hVI_^8=Rwfni-;YDmOYY&rpX86S4{Uoh1Ww(73$wzkbAwg=z<*WFc zA1do`N3lfX+L#lTNNf)PbFT@@q=X3{O-&e6x;Q31X{sg4wFr8O%55cQcQ^2Bv0_J% zInjYYDX8uy{c4>bsrSY=H3@V#t5|K=*;RI2(Q#^hP<9E)p%h}Rn`X{{SUqRHognA` zn+&od8~W>r)DmJ1k&Q2>km$BxQ2|EB$c&$@6m(G5wSt8DacD$gh%-!-^#`@O zsw+(HhnJ8j0Z)AP&YuXhIRSEMJk3k_%Tl$@o>QLaK&OELaW`VZr4yDbixwi*+6UN4 z6Oh!_-3?lAhl|OEh2w|+0RST>tq%>pIk3?^dF?`+-G$m}8`wG*{JK>d_4VQ3vLE3@ z4~+3e!gPzab%=!J5jbOkG!AZtM%*9=JbbjyFLbkBoBd!wFb&?eG?}}OOBu9dflQUs ztE-DeljKjjK`%~BCb%LmvpCB>(-hot=(=KSFB|4no*P&WKad(DzdJ-+l?s-?M} zBqt*q_La6ZfdTbJKsfPsswPtTU8y~Nw4w4ETwGDHLX9s4Qf5WLR>Qf)J2vs9Rz*vg zipWtHp~0$)FhHvBs+J>CjPRx4P@2Cfon66*KM5?)Ll^JyE{Y%DZdkaXlx?|n511Hc zJ~aM=ki*Olnv=8rdFr+wf~T3hL1YaXDAoSS46;gAZtRaV81hV{6QIlZiWo0-UjV#K zQ|`QnkBs1{>@-XWk%F5uSb*z#NvkyrPD&3GUIvM@z);htVSOAbdj{peYax46io-ql z+i%T#vK_s`c0(sQlnVR%2X3A^akDYiDsN?Fq9&U+tKCXgtOaw5;})R+P)@fh1xRSv zx~-)EvW8pRdb_mUqwjtpjg%f2Xw6HC-XM-qx$SX$QE z4J}MRhqxEFNR;v>WGFUNn*Sd&Uh z>>MZ2N0?#}+70t@sIu1>KNXQQ_G>QU^9?uXt(((d36p@zj-3GfEIX{ViwM!HTBy<@K=(;+8`d9=ru zEp-jR6ay7;vnx*fL-VCJW^;ljizJ8829A}~+40kpHI?rLg5U(v~&WAZDBn8z9TUxqyU(Wx(LUyo<;XUdPC_eOXH z)wpGM&&A%Dr(2KBlAnn0(q8N(f1*%@lCzepi;kb{Lh!5o+mWbg)K1wdox4IN=~3xR zS@=LzGeJeAN`9e@s5bURVl%F=#33fu{4`46*Ux-))0DumVG58FLuNvjY)+$5w73>=w`qB?)bzc# zw7Ia|137Fp>Ki!h?Ys>(nvPBDOx1~hbq2VksF_MV2vN0aGAZ6~6um|7bd66z7EQ6& z0&`a=b9q77GSesUrbmMIWUZdFar``FC>5IjcUFvwaT9rPnmHWHN z8OU3zsFU;15$TMcx`pDVyp1=U8bf=%1XS9F8A?JNzV;Hq>>THD z5ByLd$+MO0AY}oifo>lt>~M9cA8eO=YOSw*wU8!j1Z~U2PDvi%*g9!8nVRR`+yOkV zWU;hxt3oe;5*=Ym&J4jiPup6_7CAhcEYhUP={~89oLRV6*&O_ZE;^nhd3tFejgA}? zD=kDQ0+)}J8NT=ngHK%+_x$F6uPx%lX_cH;ko=UjU6bcp+i`r;I5IHd7MEo>VZPHb z9#)Uksb{7Bugo_nuxkAd$@PC)z-fmMe&(7);i`xLQBYY#sCZY2Df_cftcrv(YtFB} z{MGr4daSS)Zz5;>DIS-y&QmOexwKM!YGTm}o=2ctJin_{GSQ-ApKfUpMVZK=WMq12 zJ$1~r$CTA_dxnG#3_~Qcgtq@Qz3%}kE{K|spG=5rFF6-|rqougP4P#n3iXXkD- z6B#E9V!dDG-L6xMbxfmTkXJ(mmZ%$G6KL*R`-f0VSwQ^Wy=a-6 zYRQd>tRM8h&$$t8ran{;XmY@l_wJIkjO6{Ef+!$iDeFR_X5M|6!2R;qyoWz>5@R)6 zp_8I4rV{XEfqi38|Dbyz%T`FhhIha{d^{GIIZhtWqX~)DeFy=%P<$R*MI}$~Su4B& zB;%NtfnU#!oNExXnh8f6{IOs9Y;Qoq={R40Y7G%p)~qV2tGh-!`tyT!?mndsI)Zi} zZbzn>b(O>XNuSN(qCV?0dJj(E()PQW9>c9G1DVAJ)z0_u42s`f^R3cKISBrPYNC^- zSkpM*tg*tMDZqVF`pmhf+3+Zott5+nBw564BLO!4R@JPri&(N0SI;Os z5jz6Iu0iq@kQ|mLcA5S%dkRmo;&U<}*@NJ?A*sPL%au$#saSjri?lr=jbBoW}D&yXAt2Mb5AEYQ*e!w0nNy!dp}aVOG# zaK3zF#G8J8+~hXaV-dK1r9e!&^gWJh@^aotQ%Q!_YucKr2)okr+Ycy7&{Cei)|Ub9 zpx^tyVEQo8af#|`#AhNFpz+&{(i(X*5^8^eA@W5JPas`J4qZkTptPJLm6g7yd1vc6hC?3T zJrQrE`@qr~r(wd;9}-Dj!bK0S)1=tT!Mi06>%2pu8b0bUN41|s5FY`#Shp-(Jl}1{fHhQXnYpWwB|Z-!?QSM! z>zF!3$Fr4bHUBfjtlHPJ|L35B+f8@Jan|BJFhFKGmgBFMFvss;pnM!qJevSR)xpi|x#a%Wsh<|Sa z*Kzun52~$fJbfKHx#g8-B5>f5#~8klxms{=idou22X0Hh$L@Uz{&pViciq7IsJnm5 z9lY=Zp52J#JCd@8eNATFip|@9AYH6B|Fk~1j{Y}yN{%A@Z7GE6LesO+?GAb+-F4o?fsJ^iGRuPr>SZ?00fdxvVk8@oS+M-b@Y$uW45hPz zqC_@p`7K2WG$2Ylm?!za@@@kzzdI=Zdw6(%7UUvE%7FDR^1_(CwXH$V@zBf|k*$RS>`*LZLU(q<5jdTQdG~%Y1Vrvfn z$`~19Zz_9PsDqelHJvy_uB+Ia#tId^GyVO|BlxXM_H;)u=B&a1xo_gNZ1cfRiUrG% zQ2aga&jsk)hReneBbF$utgtT`;h*;MO{z!9qZBy_?QC||sI*7QNGQ+zsYdTcfCxgmPFD(mloj z_9U9y8RXG>u=W{nTVHpa&dKx5jRvOjO-x(q%=MW@JkMb~#^wWd_HmWFdctfTz$@WUV~Y4_jntw^p?C^BGC7WKPvKw!d`d z-h&wkxK}S>qd^uddJ2*H8%NK1HlNi31Tp1F+lno)p>MwS0vJpalsQO2k>C909z(=< zLrXQk3&cP}&K?uu7a`im_1sHd7~g|JR=;^1ugq{DRT?bAWCH=_X$Db{ z+jNP6nJ!Vx_u$$LF*2@O0J_+49K^iw^cUbX0|#EVvfSompQ>CbD370=g>CW!MdC58JXx0PB2a)eUtKZ+9JgGar1p%q*aA!B6ulz^}DD@8gvNO_|sL zw~gABOSqsfuL-n!{B*2YK-Ac8P77Ut^F5IsY}_&>)p?GeXkWIYXu+6cy26pHDLhOB zirzNp{rpavp*PX4W*XBxI8lwl+zkfozHSmF5pqq&K_3-)-F~f-=Z})Jyh0X^!(Tf$ z-kN5VD*vP&Z{J{AM`a$R#`PA%kN@<*Cd|40lvkv>`q|w54q+41>|__Lcaib-p^}-$ z-QtQ%0%gXsQT@|eLmZztMYEfa_@bV4LT&a_!{Y5lSy%yb7x~NeCO$HU@5Fj*uaH07 z7`m6lycZ>17nzo0ektuBDy7XRz%b#G2ryqfbioL974cez*uaDwnufLC{3*=54-7Q! zah-v*^2X^lQy(>r;}qAu{vh5cW(V)X%-23;=-98LY$I}~T3vt@k4Z~lcmXJsZ!0ME zgS3$ugk?VD$fWxQeYP&vedB`kFj!h!;^uoboo3q} zXb?R|Ho1%Ut_nHDWY@zK$NX1kX9Yy;=)8E3+Le;u5MHK3) zHM~S&9%&tljyn)Wu4hvIu{h(+=X1UrRJC=iW$n1!px71~3eHSsZTz-PCR9!9GV^+B zcaN*dk7iw&s#5hw-v^#}E^F5-Qb4y!Ny+4rYKuJfFlp}@>`l=(chXvqs{5=DsSah{ z-2)`8yoxbAs72+QKy9Z$?_p3K>%4i&q73*+yWL&Jn=}jUY)<{wzbk9c1RXx6($%u7~53X0QMiDLK^@N{_yVNq3nMF@Zju4LN zmwM<0-qXs;(j!;tCVj@?1v^b1%P4T!uYmUg2~{mdziB6pT~GWKMl`RkM+JU4&=UQN zO(J}6;T*LEq;Hm{D{hDN{;L^#lQw;nqxXOOV$$b?3E#U~S&spf>&g7|&CGm zNi&Vy7P})1y7y0*?f_tBXE(7hJeYhu&-Vgq?rLzhvT1s*Lc#v-4N}gVk)2Ovj$N5@ z_2KuhDfQM{)?+j5Qy#IuHudH_D}rcC!_{e88FnT2RcR1HPtB4!fptrVMigBm9Ej7) z9)ckGfLloY)XV zk=C~E%5V)w){rPR?*qgDYMpas`_W9lSSPxTn?;|bup}r4WdZ~oBUJwcKQawk<^&Cy z*f{&oA?=}l_@O)RT514~=p0&e*ty=ts@nsU;~uGNXRnY|9JoDNoH}hSAvzNxQN&*lR1Hqi8T{$aoE!lX4sMvEnoo4^vKa z>xKgNi;|W-Elur~9r<{l-i!2T02wz|b(t4Mit@&;3@0bSToANe`1ma>(pc&mIXBt( z-Zlk&)_=d4uL$+`Mkdm;%d~XXIKaqA^g6>TZUa&gjaQ~PM!;Ri^(vgV3%K?MN*}sG z1z?Kosolx;g%vR*6YZC!J4f)`iAT3|r9uo59qrLUp$D08FTYrvipKDO#}ca;4pTx>z@7=Xnf7f96x~loFBs_;{6I@e6ojZ!j@5X)6anuXA^cMuJy2CI8J&!ZZ_?VM6E zZo*q!YDk04NmR!9TQp8}f- z_H!T{U~A|4-fa=TYbr+L;9rpVMT9)-ejl3Y*$gXS`?)=@zTGF0{o`_vOS!?M}x zm;yMi&j{{tU6k|DOH-xz-HO5}mK?Kt(ogL5{<5XQym7a2@BFO6>ahkHPR38UyY|^$ zONUl;40jxcKYy!;P&)Agd0K@AYH#T@^W*F6nqA&t*(=gL7Yo;DiBrQaD9%zW>tL16 zG;UwiOY0*Jtz8XUH!>jO=$E`*P*eo&KhG3=zCMT!=+6{vKCoTUK+rknTm?JtL!xr9 z?A>+MWFg>3x9I4|BFvWFl0c zTZkot8YK}woQ&^@SNbX)^VF(EnKkakESbK#PZ|@0<2a@f3Ushpf zc}JF30Y9^ld`XM33H|2D3MD4T?ZpZp2g&>UET8S)qWw?_5}yZc(AKIP7O>5I75 zl}8|H+rIvQfz4fkC-;AP$Sw=*+!KB7mo_8FQgm$Cr}61Q9NFAp0umRYVDP;g1S0gV+|^NfW9F^@#lCRsBQmQ-N>r5we5}cj@nwi>Vf)v+v@p zDTE6=_-XbsTgH<;T+84lAmxoCo(tmyzb;kk|tGhz+SQfLf8WNh%vX zNh;OG=;v2v6cKEsa!O%XS$OVY8}V#JA}m6m%VA(bwl7vp{Vx6J2qM*NV~R*$D+jLG zyhrc+py2<>1vnkp4XRptGbq1&eIVQTcWTS8%F?IfaZCRZc4^C-$qF-r#$EZdh1vkc z0ybY!L23_O72T<;V|u){$KqpA@Ql(|Bo? zSZLi*H&!S0_$M$fG;wg^0~qh^QlpOld}OKOBuw=$<15lVKkb^=lX622JX6oi*TD|n z@$yn2^}n8^U=5F7#pWrt9y`YAv5#i=gVX=H*SobJ#X+IF>C>h7GOz1IIXL+HH5VffAD^L|-$ZP9H#|sITYhi`i1tcCh z`S(}G9pZmEK9FyG`N?0+L$2~ivJ3$cCJ~c_5=8|EHj7X$Ymq&P9-JX@JZySaAVF+l zeVqO2I3~<`CF9wP*hgXCBT-n}G-8?3#?j;p!b&eyJbKv2sT~zRu-IUw(%+~9aUuY| zqGT_s6HdkDXrAD6aBzo51&R;hlk0|#e^V-`26!jDnHJ;X(O@h3*5EzIV*Kr6)e8^6 zJBh%FRT;@os-cSL{&$ldy7?>hUxU5>bZBISmb&cal)2>}BDu&%#mR%ev?~clY9}9B z)xW#&1Rn0N2F)v1Fn#nAmQXeremV_v31_DF0PT|?RjRJ>yI1&TXoB#;w)#S}e}2@6 zhX2~f`V8b@Nb)T%p#LKEQ*ObLz?&H&r19{4`{6B!$HtClp$EaiZ>5{8{4y|5|5ncw z-D{CxeOT?U_~p6jG!uAyn!HyY(wX}EMC9D*^8jo zU-%Scsgy5+M9J=m@%ZE&UW6K|j}w%|sD^mSL@zyrH4q7;;g3i} z?e;~Q5fr*XoH|d@`=A7-D zI9#Gndj=hmj4if&4Y5y(BmfzPMe8&%DOX#G=PGkW13v+*bgLi0E&{uN#H{Z<%%_^aoJLJgYE4~s3&u< zl*^NyH(2kV;joMw+yz&C8x{%dP5LWagjEq|#b0nY)Lkt@HARv_{hk16T2=4`|EZ6J zcE|U}DZbyuSlIWgdpHT=u_!rN5KTFLKqhmNeN(PPp>h@l>$! z)?oDZc~UCjqLhK*M%r0F&f!(>;L97j&snmnD}97`t40_DWQ$JNhK*M=%YL4@J;G9m zdAzHzq@MSY(YEn{9i{M3T~RHDg({~=qe5s)gnc<nwxf>bq=@ zHSP|<-D#ZQ?(XguT!On>0|A03I0Q?u;MPbQ*FbQ03ynKmo|$=X&7JqweCq1cAG*4# z|7Y#>+iUNWV)G<8U__!J{P(tMQ0HyjO^>?1W=OQC*8@XPZDS2)kS;l!i?fr0qoiKH zBj&B!VT7w!-W+Rn%gyXe{=+2^+pM74Ms@k(CW3qJI~p7Y!iB}Il8-mYqfL#RD5j0q z*@V!pMyD9qJHnS%2OfFHjJzByRzc^;kU1D76{6+`BUe<_(c@&wqO&fJZ^#VFfP{Iq zb@6!#`yT;RRoxz%x=J6jXw`oQ6desdw!-5R(zmv!3#yL9mhpj{VaIPwJ`wNO+YblgfwKucUGomA%C-5dNaXQRJkpQr$dv7)gSKFj@~W8JY-x+ z6;r~!(;WJIvm1e#N=)+(zuS4yqGJiE#eUlIXSFSNPDf-UYJGV^3rtABi^PZE+KUA*4)gCfoMQR5oXTg7+Dtp8J){*j@}n++EM z3;usot^X!bmp6sE$X)t(&!xkY0=NO8(&4w;czOE^!a*l;*&;b4u0c|l)T(xC_B5Bq zG|0O?m-oLNv5I4>Pk3`0X;5U+f@F#{P(7-V2InLF5YUDqOML)?lgcW2NWGIJyub)q zLVT@?4JJW~-jCR-hNxyFfajm@LC-A=W}o8r;L^fkVKHa+vEJgSHvJa&5~!G;E%yq_ zC`=a8Vxuiza{ok44J?O4H>#8>U?`Gh3Fy)zOm(`zAgZL`8^o7YV87MF%3cZ|mT-;u z_dw~neWGCN8ZyIq1$1q=*f^PYCk~7GnlkGXbC(k(%jvXXbcI7@MZ+ zyY8vV@88(^51Ov)=);m2y4C~xs-We0Ta`pVdAs6W)Nn{CFjc3^ieiv3WwRK@;P4?j zAZ8e5bm>C{*yW_F;Mh&WG$f;0=>rVXQi&h!cd;IZBW#LPQAm`lM=vH;S2zr`xpB-? zjVh9UF|kwxcjxOHFxILVR=n*Dh;csv?YQtDjQH?gy)+-^?1COd#H`&{x2?xvM2H^9 zxdonRG_7I15U-qiyaZQToQeQw0Nc_3C-^^qT9 z-t@t+0jEf7gSFh^Nn<-9)B2Fa<9d*!S0u+}7uZCajj2J#f}$*M-YFBf2d{`;G;Iy^ zSx&tExD4|LLl5`|=Xm;c%_5752B8^XEWrr2dvDP}{|8e!;asj>c%@BX3hP`VFyZ@WK9`h*I~O&QK+OgcJ0L+ zzjpnxg$hEpf#}4iv>{r}q5eT_|xcVbMu z^?vhTSk}ncS{cra$E>TCoJ<1zB1d z{YX3`oN5(m*KoP@UNg{Gh3rfcQb+B+0L=KdK_(hr(=_`+?@ZdKk2^!51mwoZBDnBa zR-M&R@^B(loWGNE&XMapmJFF5zsC(xq%CjB_XHD z8jFsJoGljumV7dgR6o=15rPX$*q8HWHIbptx+kk}`^u{DRrH-iaU~N)X$}tQMKHSyOS<39$^9 zsQRYcU?7>g1%P%6&Bx+yzvCGT8B@49ltE07452txd%RHuSCsPT0h`WMe;wp^IL7Ul<`U7z~ zt6n!w?QlN>Qv%sJE5kyxDQW(3ktNlIxxI~Tr9hjr!o%ZtN_4&CgqeaJEc>!C`oLZ1$iwGQ0XCRZ?8&4clbKv_4A8(Pi8W%b@9 zRvn$pkLzAK%^2wOax^&p=w^K5u-2g* zxYUKHr`YxVs=-g|-h`-XplYl+_lgFECx+(i!KsVP{3bTLfApAekH*ba>I;n~!zMqN z>Kgv`{F!5GAFeS>RQs7*q?`3g_ChvO2ei9jP11%a<0Jhj$D8r6 z^f>z5_X`U&(bcg_GDl1nR%Tcg<7PNatbe z`MU=kw22+AucMw*PLHxLY7!h4C5xH#zbeJikhGBqRz-bDA{J$g^TA zEh#0D&PAx6mRV#el=fiLDT=>u&^>_jb3ppA$Wj4YVu*&EC;0*HFH>PZF#uzY&6GH% z#ElB8SHN1AqLT|rwN3v+ zcM#@6H=o$E_xOaH7aaoWYQ!%G1Lrym<^}q=Oi&2}oD~D$*QCW*UY!F1-soPDf@*v- zi7YByWuLUY%};b^V)s)^^6yK}j-lTfQs1?Z2Du;?;j5XdV(t6Hp)gQmWwEfAPGU3L zUPU0GvnbL8OpE7*(M0E?he;_?q*7EP5h5zDGbBp|({y80_YlbUZe_LxT zgrK|4GHkg?2>qarS&DjouzC7ftea#uFCbTpAYv2Bw2o{!AHZvr0?@NIN+~OZZhAFw z+uZIv39w$-Yi)?AWWJhkexzU+4c*8M`xY59*}sV#_Vx}$9+@wq@I8f#IDwpoUJlq_ zjFiq7fi#BZki$fy$c6_Ddd-)@=Pr*#!XuXvnU=f?yT-?!<1?t_YSc@+G(8jybHZkDTt0M&3>8<<4X-YG8wFYsQ2kOCh554LQ}-o#IreB zYN>+mS*wW6r<|&%OXVFuY7#7Tc8}}^x!nBOKO~wXGuidSzCEQ@^NZ6otw|I#CZa%| zfZum;-%}3FqFi$fJ{-26%QfFJz%k^|h6xfy?`B9bK>TYP)IFs^L2V82;Fy)cO{kgL zF|m#>IMEl&7b=4uA^BI}_^G50j`^|m31d+Fa?|Y!GTtIk5I9GL z>3OX6I2W#s*6%rIA?oouzW!2@!ZFZuNokJwf(V_sIv53;XWubwah7ksc96q9x!LBw zXtP%hqL7lY(hjn@t8AI!4Td2B|Mrg-(#8Rt=lQBzEKl<%TLCpWexmJln}dKanmb6a zX6$GaKWaVC+tiJQVeg+lGzl25xY1)7>`;^3!ehZ;k%(Y#!g`@ZgtC=TcDc3{9c*cU zXi!wXoj-gqo@zcGALOM2`-G~OsN2v2pg&N4Q7bv;T-K!jGaz=PFTwL(ie6VWN^rC3R+3jG|wa zGHy_ocZ=qrHI(37UGLjn>DmbY3qL>@o-d<*0kes{fY7XRrR?T(44Y?nb<}%i80PWV zW>%o+jV^U`yD<0mYhKb62d%wBPqL#{gX#MVPxE$`Lec`>)hgFF!&beZd|r}(jX?AG zeY;e7#MnRYa253Z^dqsE>AHIS$&!R6& zC6Q)IEHKa5l8l3M+-l;FQNrmzDa6pKmOnG<4U~Ew9NlUXaB_`$H>P@ z3*#dZz0^^2vhjz4;bHM~KS9SE?2!fhum|`yalxfw@kXr(D^_3xa6Hjr=U3^9qel`@ zY%bW3SOlc57o#~84?2{Jau_pINKd5I#<3f_{m#PcCw6My3nG-$P9-6sj;@&`#*ZkE zik6Vh$nJ&b&Tai-fls;vE45)=EQR`PDdo3XWKDz1v|BLQxHAAQR5_za53>0b!B>S{ zii-u$^85C5R5~KpPUccVRguC0p9Z!>27Lu60nbFQ1mc$iGQ}e(ZAXcl9|pO^fx{D`fQOqlV%?o;r61)xWC{egqcF2Gp}miW-Dy5IJ&DgIo=e zE+4BU9e{;IOU`m!%j+wa9zYjYWM@iRCUnK8=VlM^u|1@jMp4tj^B;%t5>gb8n7X; z;TY(snpi-{ti<9K2_x!DkGN_l+3A>vMFL|ZG2Fw)Sva`e50mQikC2Y_0##B80Q_-> z^@zu(=1H*xqk6RNJ|J*0By>ITPQ2yIy7KFP&l(AQMM9g5Fw%l1tlX~Q^ z=T?+=NB6hKrZS zN!f0QT;@o-%lIusfvPqnsJLSm8JNzym2b3hgR(L7BTKJnxmMW(*_~qhnrXst19z)f zc0#rPSb((jwR-Xx0e+3(SI3wix*wZM${_KaTP++XY%Q`G*EWHy*$3iUkxMRNEcYV- zUx>-YRMhDs6O=;kI*((k26RRo)UhY2$n^^+wqWwSb_h(+D9A1QuJQ5p%USp0R+K<9}t92>G-?Qi}$0_W^$YEP8yFC?`YP`pStfdO;9-AT#2H%;zyDs7qje5I-S%P`5`_I~7-govSF^nEV3G z%~Q$m`IL~ht7JKF1c^4AV8lUIP3;`g3{?U2*c+BO4Zh-jeT$5{$;@8Ap=1B4 z4I4uu781tsU+*$Z4nrI*bK(g$I#X?wAPK`~@cXEO>uz2*YWTOd+-~wAZ-W0J-EPss zamu3oU`C^Vxm0^ODu+wH)bKi*<R*nA7MPD>KU*d*?n-YYA|6qXN%Ez!I~? zv)zNtXA>Nx<3L;-qHmcO-GyejlUO^Be_>yIb4rP*lTdI> zCMf0ulTjB*F*qW$<$3w~7SHz1_t5f6_2ci`gJD2X|IIy9vs7=U|N40OKr*TjAr=*J zMT>Cx%erE4PZC&O8?f#L={%awsJ~ zkQ*5Z528HGTSyz-6#y8A&-%JJV+=Ny*0c2ommTdVme}sPP~}liC8lEJUa{6c#vA@w zM=r8^)7=$UvCG(8H=?y>v-otFS?ek$E%MG%lE{KfG|hq8P|PMTL~QFLUnHoQ5+#~0 z<*Nc|k7SxNlc_cc;(kK0tTo4q>Ub8IK07FdSw?JE^G0;(TG5n%2fLO9{i}cD>FC zdSy3|XmXFjhl)L<|1x+K20UO6-e((7C=rGc3q}Cpd5Adu{E}-~2k`eSOQ{-<0sALJ zxL(4*^;m2iERDnqY^N|W4lO9y538R7o1`?XFx($m0Uqo6fbo0)te;e+*r}Dq`>7Ou z3K;q<0r`k4^AW@D^A7d}73iqN1&-&#`?~tV<@Yz3`rRaQG%+5`%A!<3#0>@AlX|E! zu+#GtG>9TY-34YmU$WVf7}($u3|OC^>+omc|7j8eMF8*WmPqgT+d6;kB_TjoUH-Z8 z5z@$pI?{PE(V*e}GN?;7z{W@YDMfFuFc?fwlcv}934yYIUWpAMD|uFWmq-hFEWvl$~{zQS6HLoANgETx)@ zbbZ^@{cyOlHaPl~gW{qoyxxT)+90c7nS)l3i^JH4owUoM2DzPOK`Z6jE`5!MvT5SQ zE%;VbTrXkBlR1;Ujt$Ggl)s)V^0oHLw`!1W`|-i-@gB2|d&PIx@_A44Wf{RIEy~(f z1&s4gJB+(-=5PJ8Fs1#qUH|-<4g@aU%{fqiIS9AAD>yHuxv8GJ`D?mh5r^RYjQsmo zJC|+7g1M_LGI?uvLmB)*DN|xtd9LIwTZrZcae6dP9ysG;he`15$0Q*J5HduG&EUgX zoo7qDDYqM@dZ;W6Fzj}$POYLjzkQo%!fBaG?VLO+s=@Ba;GwTUN!$Y@3tc< z9%^)&6cLz^_E_Sfj=ZA2BNO$A{GQ7HZgH8gX*OBAz;aqXfd`Z|I}w6MNp?NY}zgrJILs{5J@I%6UjosHyZ50Ym`!QiHPo#HhYd)*rAw_9F71NMF{bO<*HcF8!9} zqA>oEK=1xBG-0np&oNitOJM2+HN}KJ*EZ~N*|6Fh7Uf`sbDw7eo=D zd9jT1Ae|MTH8v8uRC+mvgFzv|b3kR;P)#ogU=-128QP+}n|CNOt&=wTEk%&;&?NX% zZDu=*E!?8_4$)&{g8#DGS{aA!_xGJ=|9k$Va*Mh&8g^{frwwOCYD zXm^@4ZLS^)Pa1+Xv4-fHc}o`Yb%2hG(Yv^AP<|Vkk)1S-+}!*hT^rW;`D*AP-=+1^ zBf1s)fY9}*?sLa=_iB~-t?Q?H9qQc-DBV>K?UW9^U}ebq#;bm?H1`=L&75ZJ=610Q zQ2V-fME1f<=lN%G?}4uNUmg^^o!RIjQsL>%!s%&I#BP4b_jCO7xy7oP5m}X5} zBVyJ{H_saJVaG{R+Wj1=u?eljH}l?>Sv5&uF+&UpbNm7)!KYV5`VFRps}yK9zaVN> zWaQJA4agR8-2_6)$Q_>Gz~dmxuxEhB+_8`HmZ$0af1~D@v23|R|09m{-$dU_zD`)h z&-WA1L|D?z_fwstWq(IxR4ob)q9fjgD}7x@uDd=~I0N|bT-9@o$8H(a@OG)SCbPDuTkO6eAlPF5!EsXi^)%cRk9+eE z0_8k?^cM^TYabOE-82}Sv9szlwIO8cXzW=j9nuvOCNx}8xUzVMVx&TFGL@0cUAL|0 zVm}OqbUyWzY`;bn#gxoPcI=W@24M+aEVnpfC0ImM>z@syw#Um5v)i#DeX4f zEfbC-TrQ{X`7DG14&K0Kf<@T)J?iD7_-A$oR_^s}H!{{}AZ@a`5>0TOoWrSq3J@h?5;$Dxe@M^g>cvVtL z`B=sTl@FLDbp_<#9b8Y2PadOZBd$)UG2GB%#=>&}>-Lr@DY?H@q5EPVc8lC9gtOa! z7Pi0mmka>n%F>i1XuR@`3joBE2bz*oKvV-+f7h z+($;`uQL@qR%LboQerojWudL{w{v~dk8uS$TSz?X9RFpsXPFZ_BLC2eP|WzK6&>p4 zEy?7_z;{274W2w%hSc`&4BP9naa_#Pi&;T&deJ8qsh+bunJQO~~f z#xITLzs2ERSV>;jvhwR*H-X}4cOG53&`a<)oL2@8%sX+w>y@%PbP~&0&GYTPI^pBr z0>V;!B7=r(blrJ)nnBqk-4vb{AB5INX28Oc|5P+9WM_3?a~{9gfk;9>WDnd+p?v>1 z=R}lCrtt%1XV_yq6Z|hcf}C$X1K(<)27*q0MWfrdGNFXwEDjpiON*Prw5q;eVBPe~ zoTxM5F15FMPpasLmIK$;=2F|vYN^HcfZshTk@{L|}xU;KT7*hM*k;2l6PQ z^jW4WU)8L1s;_Iwn$cWcC2iugJwHzMhiiB8DZM@I_2G&3U?+QVf~1Yzo4L-Jm`A*2 zp7X`{n_kdQX))^xJ0<&t{%b#uec0vDvU86QV3 zEA3t(LWEMu2a+w4V0s_9;fmEIxTMnh1n3|1rs(uAF-VyedQdM4l2UVu3)#6Cnb0%Q zQR5fsS{=6bb^Ehb*PGIURyO8k5zD~NboKgahq)wat}G`loCjt6$N9aO6ihwV-54#Z zpQjhNtX)!o_ruS!cyPgtHw0aPUv<84vGkK-8`(sy{80~7R@aIr=+2V@8uzus& zaqi5yX+OrAwrbrM9I$9NwPsmn%q^%8X#9`E#8jgnUPj@q+1=**#}5aA%nZ5hdne(0 z4YUTr`lK9>6|9kAfO{23jUN`V<*Y?n6w}wq-_Uk_b$h!ridQQ4TccclTw}cJ=+b=HjF!9M!p{o`%r!w6&8D(>0uA=CK3Qg0fURJeF08mF$h7$ znsF^1eu1c}M5$=SlZ*UxLIaDe82QDOAf+L+GbH>B!jJmYrv#l%gTsmB`V@F*?GD9YTX0=gMRdij$~NVdJ~0Th^WVyLigr=q@&jD2(T1lP#MjT z6kGI7aYNU@qGRypjnka{(YWfeF?Rp1W81TRM%WkYDqGIYp|yCHy=-3GaC_dIB2k93 z&~Dr}EdB;^uo}l?vgg9+@p$mZ42FwIybc9&)h}XmnC#f20jp{vN5zD4g@K4`%gk!@SF3Z}cL+FN7-tXC!_1G0@ zKI&4PN%$5;Lv&=#GvzpeCgv>%l)#6u^w#Ey(_JDcVWQS%8V2qt*Ql=jqSaQ=nSA8)1c0JKJUEDmHa z{V>>23S+h1QNn4nO0AxJ!qxZGu-xha%j}$wZ`8FV$ro+S1rkWp zDX4cSGt3JLg2t|F&~Q6f$kL{M>H-{`)Nfgwgg%dV_1DgCW0Zi1JCDvW0Rb zdGg^(|D*HNPAJ!%Fj)LyYw)C}hx`m4nj`+l%T6Wq-1$S`nx~pW?y#YF8(1S?qMoPAo0-#q^|zj))bia29x=MR_mNmzuy^nqNZ^*SyO?72v%ohf0NYJjX^mw!a$!~q&*sm=Vb~}Q8GtB>a z`j=#7NUQN|`pB$&{Fi~_@{B8_PKu+30x*{J4vU<4Kmi0LQXTYf z92MFypv>auk8OZvx>VE)FQXO(ewI-iYBhJSy}v&-JG!vL`fdsk%J_muOFF z@^%B=Q{5c4=MxS55}W8!o`^VzMDZnL0Q6x1=!_lVY(_P%@DoO8hGm_cA?N=tUybl>kyH<74$SxWA+z#p!et^k3S(?`G8YYjh1 zGDN5=QoU}U9kTP9F7 zs+}h}Y1z%6ngfma+ilvy&5wC!7Jd*Sonl?NpGl@|F=bTSNi|rSzl28-+I>vVcEEcj z*AE|uG3M5*x}Zl8nl2O0i}QvPmidFhk8%R@wZUfD=;Wub!7%m4KLw0EH-E^Vw^URy zt^n+S0-Ex*C6{&O8kGTZxD<}^wn63Bvx@m1uD$VSRd(fIDqLk^h=Yhqu(PM>XO9vc z?__q_cJF&Yoh$IubpNCml@M-y70-OFDzurI@*7!KH=f0JUZqA$(-@5gA%`MJ*r^p* zZIMAOZR6ho^Vk2)dG4w1RTA;?bq#;~&qhWrFPpVe>LCpvSYHw`Fq#-0zDsu5LXLt- z1F*qPjs8vzwI@fyve$j)H)-)eOnO%!V%~=|9Y%K3XhCO~XBG#rg+;ikY&qL7pjaK; zXF>stqjzztBS&HagHe|d^E8==l@rAFB*XP86k&EOiTa_zA5?09tObHehAvX1z?G1> z06Dx#U`d$)T3}s0_SFNw81L9ZCUG=n6@x9Xoz6qjYFtDiwVjQ&%T>D=2^&A<}5=W5-9DUFaD<~29t_HcqUD+NR749V{94a zmDgP8@AewYyFk?TqIUDVFo#sL8U|X14@%yY_rcYPT8`;B7$Xj1ZS@pi3ezew*RkH( z*Uttk`LgCObxEa^Im-}jPKOTxc*}1t6);|P!dYZ_xKOV|hbMw znlYF%`5s=`voPR(E-H0p53y1`dsX7!M`kB8$ za04Vp7Xck1*dPuC+j5!(`sX^G$PRtcPxdTFclY-`Nw0>tMg3Hl4awkSF%o4#lQ z7WDhD;&-dm%m9n}-os8itfYvwU3R8J&>8s;W&Jn7&IK0gwl$68=+~xyrZm-uodb2s0qPU+AIqRt`i>m zn0oF$O?`N0^s8Sz$U?fNx0B;`cS>`zh{} z!D>d(jX)Yk)*Lx@btkD1oPD@2>&k`aWhtIwSp+!(k#B@S=iqIj;ws{qWG9hV zxRmz_8V5-b()J_x7QWL4dZ84{^Ol4N=)b;tkGnHC2yIoI$;l1dqlVb}&Yf>v#C@#6 zep{Q5ieqlRyX95z^8#ayUwNG3jP=)ctIk%J%v$6*Fk~eQTn)a(UjKF1J#b43-+epA zcyh7dU9}sME>9qO5R|2|HN9l~Rp8DC-+oLmQqVe_=R4v0>p$jR;6j*^Q2jaeFFRbQ zF%*X<1lA9G0eI)tdub=~8qIiOoNo5WYCaz+`D7f&n7*^YNAil4y5D_;c9XPx-zI*^ z_z)(W51-&5a^Io8AmDcV7_8c330=n@6bzUO8=nj@eZ|@8A$a;`{*e8AbNUnnWO(#L z#R_^Qga*nMtcUL5`P}>Ty#5cs{3PUoajs9i4!&z-2)Zl~vCMM4-5)07D0t3Iw)paM zNE%f{YUdli9}<)*^--(q<3gCM4~%Ym0(+7B*BcUAFaF$XmWHX&T8Yth_Me;b8Cl_*Wpw zHTxCxIL(XL9${bgi*!fvB3lo?zlX>XMT zUHKUN2~lgvE8xysL%b=A^%;W}MH(Erh_;%25cDMSIcgDacZ62)P@}!B)}0#VC#M@u z$~d-o}Bpp{+ZqgW{yid64lvd(KZ zKqZw1@UXT~b+~Db5_M2S*98r^bcsw-z_qwXgV0^@Z2|&aU$5G^4rOu8oF^N)va-3o zoOEpAz-Eu{>HGs!|7snlSWkLrw!+wDIS02mkQ2Wx1Bn_=yAB=+Q@qI73_(6&Hm@9D z<(%;^S*oapfi{dkfgK#cX#luXdgY5xxlyI4Fa?9PfrPu;ftlFjbd)(nKedC~qq7xz zdL>74w6Nd2Q4CFDyTm@#@d82sL-Wq|Zy%MKkp+eAF+G>7jvBdoJQ21a_UE_9M>JSs z_>6#!P8xop3;VD9lj-W@TdWO%bEow_KWc-Y)!bML7#SaFv+y+qye&+FZ7rXG6JSV+ zbUL2u-eOB0{U5~luSA0b&A+kX|LcHd2n1^w#?5-kf^(^X@`^l&dl3#OcC2lZs0#&r zPaZRub5YAi*&zfBD{^B7Z^Xj7WLO@ljMZ8=EQ6arAV5mWx3tHEnqq)QLe_m(qEwv?AeLaYcZ(RSfind%4|Z=dYF+5GoM* z9v!Wqsd|MOyobz-!!!L0ORSz<)iZI5pDR5=Fq57Xti>dPZCq@t_^Aj#*@J&lk_O;bYa;D5S`0WN&v0=6N@N--}~qKdBYr>zvB zP9ox)u2_b{DoMpGojH}l1j+T@9-faMz#(JjQI|f3e?RC$w#xec;r^LS$-`a?z{17uUf5l zu!MmSIE+1lw=IKfN`zd5TzlHct2F~@Bwl`Bt@P@?91%788Fmf4SicGZKa1ADI#t)c|D6cxe8xPiU}+>a&1Q_y|Hshm~nz02XXpqHOZkwYrJ3AU^`l4GU8R+zPJ zlfQ;&!gF*4j8K7jaN~psmv&=J+<7-eBtNwEGbn|FWl+$^;u5k!795R^G;fpec!+?zrUhdJT_K`~w+duLWIR~y-`xsuThTi)P2@~~e&pNN$hEW_h})hdZ8RQD z-Vv;A6j^O}m8D3UBCb#|kh~%s;A!bY*j@eG6zTcbPXkDC1^99$Drp&_eRWyCt-bZ! zJqAWJNK;2}HcVjmA6+KaP^dlsg_psPbZhp|){WphU-;U|P^>$#tq$<*=+Nz65+ynf zPlqioVv4oM1QS(f%3VB(z0W9}5PA3I3ZqM4-(Y+7-8d0%%kNz`(jbJMXLPfW7uF5` z^Vi1PA6%KH`#Ecu--9{4-)B|*J#zI)cb;Ki%&bVX{T+^{on8<5si=q}64{C|$)qJ% zxPu`i^VG@P?k0U+B-U!wYuY0qF3P>6zr5!~4rw}L z-#KCInI?82B$u6B6*Kh|yBIN2TiGPHpnMqJPelvgZ?gwj3A6VFA zIdz(O|MR0IBbEs77}x3c4U?;RJ$sGYsLo0z>lVwjO;@751tPZ+;v5E-RO)CpPivST z-rzfM3f+Xz?)MKTp>NL5TgQnf@Y-PzO7Jj@ z^cnLvhR%Cf@-7j2M(ClOhU!kkh(SV#a7J6P({GDy>u3zTAv0hD&$_MAnl)6flz17M z)K+i5gP-LP{W>cVvm;Bf#P>SKZSiH<+A)QjWQ)L179hqu6;86Z5rGPl&(@*FiDzz* z;~bg-kJeK?AE`mkU1iLnHiS6{5zv8;>C zPOOnWJ3NYoh+rLu2zV{y{`1vuf1iK7+~N*9{681|pO0JU81wZTtv@SGvB`i-B!X%2 za;d8m>aRNC0MOt9OyIi|8I7I+jTvCyapQ|bre z1gXY8;(^nPJt$$q$S5ieLc;o2990S{j|N~=g=g8+)U}1j&f`OQ5wUo*g=CP6!3I24 zeT=oiidozhe5*xBy-*NFCL8{~6%Z_?iCshV3gaL{M-Dc@mL~ooKqvs;O3~FoNl06t zf!vp5!DK_0*dCOn$g1i4{&9GyxMGTq#CostUL%_?p38DmoIE|7m$pCqCzX`Qo-7L2 zW(1Ru2U(1<=Bl=jJhnD6rRL|hQ2Q$s*=f%fxa zWD=)$=t9k0`wJFhII8cJlIPa%zj&{o*D9~@CeREwfy!C8xz(jftDBfWG` zr*RFj33w_VsHn_(vt>SGIBF_TAq&LGIRm0U*+q8c1e`hYO+Bjw_nUA6Sx2BzO~{QDP-3t<4ny!~(>$pxtI6H6((I^wj}do%L_9>zmo#W4J`jPDnvIhFi!c=^+8lljh66Q|>NM-IdIg=~*H8LXCIiJg^52_gfK^4Gd?4Yp$ zQDSk)?6pI<(8Tiue=~y4Es#EIwaI~+=Pg5evNc$}K7`{h_1e<^;p;o2n(D$eL3;0y zK%{p<2_0$DRY02bPNXOZ1eD%;AT((KA|NQB^ddz%gwR1m0qIRp>Al0m@6Mh3-C1{L zCBKrabJjW8XFvNX@4M}I?OQ)0OlJ;T_d_-}ALp6;u3%N>f^~FVM|5Z-@y(Zs=lH7Ji40*t=`qy+l4GSJ8$37eM#q z{f81ebU`yqOvD%iyzcWIM+qCr{jb}L%a_k~Hm>{jjhL&Zhj|&d#y-WiSZ7islJz# z(fazY@`Y1DueeuwI`yiR9>2j0dAg#tu;1f%8|$AjULwv4;07(f}zMM!cuGM}10Gr4regHhzVD?L+N4MRN zo{y1I1i0r?5}(IG?RuJ13UVA-JzCJn_^95wJ830r5zRiY5}JnG*9Wyof@fXI9m`}B zYO2cs3BR6Vx?S8HWe86+%I`Z4wjnH1nef@i(#h3Sj@bI5R6bFElPY?bg7*~iIFUOHNYx9-qAeW#VKW>cAV== zD=~)ONHdevz`E!G0yMzKK8`Zs;Ea<|xCqioO^6WzjEZep2mL{k&Q|&i<3)aPD{nl8ZfaWc+o_A3Gjj@CU6HRNcWe zliRW2V%A?+Ls!b~r}K&zpqOD0HSeruHo1njQ;aPPFG@g%~%eewg?JsVto;`>!W(r8z7yq&s5dMhX1-zsFf9JjXj#1% zL~+i3^dd>XYj6SbTNPp?%h&^vDQ5qgZvTXaAtKBW=*fs5EgrpMt3?fI3h6`cjU({U z_c5IjI4ZV+%kWp+pC49CV9n6 zC60?&ci8hi@ex0Z`g#l}3qGuwU%XMI+#cLtCx#tI^~3K?MU2`Ri-^Kl_(cq_7G8zZ zELo^)Hb^mlR&n5hw|QeJ1(Rv%>5vWu;Wrdnf`XCkpY;#^MNZ2X1p-Bk(WvJJk~NIc z4bRJ&qCGT{_4nrEBOVTkXO5WNF(JX2EJU9UMm#hn(PJQs@roNb3#N$P&2e&tWM!D~ zx8u}Pld0Dc(^b4JZCUZoGubh#rmS#!NP8KC3Gp6oLR|wcV`A_zH{GRS ziG+l?`v_)rv}Nz?${gu%3;T&2b{YxFKIc=0z7d{04PPVe`p$p$*?disw3*F*Q_0g6 z_WfAN!@jEw$pZ@>^AKT>)5gb!H7)bzcOBKqLzYcs&w}E`$Gh=%p`Ecj4O3I zUR0?F1;*oPnj-!%0l|*?$diTa~C;EOR84%HoQzpJQgPFJa0m&S)pN%Js-+> zI68{R$(~MEO>^$zK31q&x9j8+Q=$w4?Hfoa5rX19%<)6)Fjxth>582yhQ-(!lqM_f zz`IW~Nw9M-&Rg6@%J02cMgcmzNc7<1(m!Nl?O}7{jc|y`$_@Y8t#A0f6~q!jB$L?9 z);`gTkdkACmlja-WLp&w(T#O?(9&V2Oy9?=s*X#b<-+g7socd2y6g0@Gw6~u-%Z=% zZMmW^R|nhDvh#6NS1eoTmz!zc73i-;F@{LW_YImn$3>_0o4OMr{Fy5KM^-?eOEkp{ zU8pxk48$Z&kx)?`uupu+3CZCvGQd!TBi)b}SWZtXNeZ3^&jY&3^+)i3#QRJs{*xSB z6y+H)kP0xOC_mbMNxZR=q^IV@{YS1pljrxj&t-@*j_m&%%Ln{oxr;Dam8eb=Kkd zvk!P-r-B|-o&D(X+=wEg^!qfW?F3=wYAtt-iwe1uIX2iB{nj2IJXGgIncZ`aqU9Mp zNFSDP$Eaxb&Q3)$pVqx;zs*iXOoA{*e4bu}|-VxZFUy7bc`j33&N45)uWJ zaN3&6h@r8(c5WtK$tdlgx1)~v8o$2rSn zOHGGJY7-2lQ1La_HK<$shC<t_M)yV>Sl=u$`iUiz$c zhy^B?HlJ{ZKfV3 z>i9zkCv{b+k5+;>oSwQ2`R6Nf@g{e+CNvg}F=+3Y?IoR8-HIQwy{mbMrG~A!Zj4fk z6(24bH6K9BPrqBjbc_E;7ieiN4nDaKBiJbYsb5PyRmsWg$+3QSm4*lYfpgNDc$Ueb z3gY}x6|nfkOlE$1fV#ba;w6nX{VcNsgG#GSIX}Pyd>?`Btz%DB^9$tK{OhR$L?!?$ z0*aKa7GAoOHSCy3p5_pECz7C>RBg<^qmd`iRXMz(TZKHjp>fpt_|-0wOE`R~KUfdP zz-S41T5GzpDLb!mxF!#GT7qTdCd{f2c3{H!C6}NewmH4U&T`q=T=sSwTNcRJpx6!~ z`_AebI6`r`J@K)k0^-i_r&3SY7m-_PDaOa#XK59L3R5*lYV4XzK}Qfg@Sh6MUO28?mNrkO zkSq9-GAr~{#=TN@A~1S8X?KKxzdFRq7#4*lIjIjzY*s#;6E@yYIix}5< z84eonOBFg27Pn`uo^H%GI9`T-j=nQ2FzG>d7&~99DmG@Jc?8KM=A|~RSMw&P-gdcD zgTJ{AtNR^)2u>UCtND|-W0$ytRru46JQ~g%S1^BNGh;%@bfc`29c@W4m6ISXg_T%T zwH-Z#XS~`IG`0HG&Uv}iu^aM(5!}q~*GgQkTmRFHH%?6WVVBsQqQoL&+94(9=BMdi zP;sV-b!7WTJBR7KNH@iGa8!B3^pVIgXHsVK%L57Nro7AR$WC~PWEVi<8kPN8Hbvga zN-TD^%7xb6K^YTb7h}h4u;^g?B0>d?vSUOx()1ATO6O>;89RAo+8qXlS1A?!aTwM4 zG>E&~Od%UaLBUO_k@^KMs*kAYKzTpn#~Isj4nzn-X2nT-J)9E(R~He{ML;e?HZA`O zm>F_wy)Ou36+x1#K8VNz5M-5F1t;{jI9cS*#&FYGuN)B*L)05lSxCaF17+5e<%6{R zn$e6!)PvSrK+cc2o(QhEWKJcKRW(8_n#+}-Uorj#E`!psvRatrcS0202O`e-XHu>n z*CV@%tTzowOU->tQ2g+-K;qNBFx(aJ9$r_n7~>m*lj<=zbo|MR$Yh_UY0g7Gn`3Cu zZsc6-&8qXuPGARj(;~u_V299z;>Kz(0w@}^ZF(N+Bjj>zxj0$Ux}n|aaYsw69hw&^ zw}%QiIP_Vzz7ml4`s?)hoNsh0XZV%Rub0V8RR0nZ{gpz9%Gy8YW35(h%Y3D9P<}(R z_X-_)d*-~Y+&-GybSqAL`r9NW#Mw;~Yo<-W? zP*SgdvBk5IUe%xzoxi!;p12tISwQSIqido;ED96O(5I`t)bN=YZV>%Rbxr>lykUTsBIs5(m49tr25%i>CB?ZW_c|R8f$=Y?bJaHsg!A5hsS;R&5SL z-;CxgRsAbc^3N9evy$pDMNd_NK2xJI?S2&S6gfKlKbCSj;4`+YMp~D}N7JtkJ*L6y_bw~}ztv(@ zk2izY-ABOEIZE5?kCmT~Lg-y6)(2hV9y@^%q;(63*333$+|CUDN2WAGZ}2e`nBeI# zXhWmlmS$uEbwYFsi#_4%{*|pK4>|UqmB9uczZCm?0A@KFL5g~<;a|HLeoZw?sQH}- zd;!NTj85fZgdM%#v)M57t`_hAl`&~Hh){sdb#@jga_+Qpj(aC*MEj#P z5P4msdB!SJU9V%qa3JV}%iG#VCwSc3+yo?{l_Xbe%|Mu|IS04R8^~ZfB$0z-)4UBcM z^FXOi&AJ$0mv1;lP82MO%s!T#EiCbzi=MXSeCe|nuC$6oisT#7zM6|_PJ{<*5r*q~ z2gCpgEnYD?$JKBe_rJko{ZV&(k>*8yq#xC{v9neQIIG2G`O4g^J!svHLoV9V9) z{`F@8W+@Q!X(q<-4QV4N9w7qtOukmfH3K!4)MzBr zJ>SYoGU@>~35p#B;_R3-fSvE)@zSIiJ&s|J@iYGJiKmx^mu2HwkZL>WuLR^hMJ`=- zYnuFpnI+t@5}x~j)<3??(Uzk+UQF$mDJ1KY~J@k%ZO{pb?gXjPL1x`m!D` zEiYiuRhnz?+C{csK@!T6jS-vF*vJi>E~l(^!hBSix3{OSFX~)3AC5$AG#T_gm5OBYWDKyTTE&&|EvrcZ>@MZ(8RaFu~^!NcKH<~7}-akjaW7qr9Q$+HXDiMU>f2#=!L z*p9@Xh`Y8rUp$6u(sZKC#bQ#BX~<7lJd8XK8MXRJ?QIDU=9vV>zgZt%l3iOafCD4? zH#wHVmcpWMe@a)nozA;3!hlU-kc16!Pjk-!V4c^nlS2|~U2<@jlgE~5E5wblC3*FA zkDxkKQLC_X!azF5_?Wnug$(n#U$N`H1HaSfKmLbQ%Ffy{H(5NiGO@9bU5AfP7D2>~J3)n5Mxs z85)E-mWz@hDV+BvbhSx;0}`y zmy6&ZvBec7wm}|Um9-HYgq{n`+h8{eB(ya#Tg>fbYew;f+#a6Hv>d3NbY|s$-F`1# zLaqcqtLRg9y`30Y;0?o?o{PkJfh#JP$(8w+3~&c2@7d)7z9KrdJnr#)4pi*a-I6-Ynqx z{C4v2SeabG3KpLYmwgC9-q9p#AR=|On3f;YdT(T8H;R7KtROO)w!9xv?i_XL|8@?` zPud)K+OII=RBnGn;~0I8PJ|eyk_D{uQ>>P7h+IhTsVxP@b<~QNbog{wx7u8?H=ILf z&RUXbP6?KC$^n-zsW*mYjkY3}kJaH4TDEJ)r}14wkG}OWmCG> zEXeWHWX)oZ^%?~9yMn9JgP30b1#vMEXg9n#g5$Iu>06!c*pO$+EK;1>=MVzRZsr#J z>jcRprSbg~xltGi$rey}<@il&l|4ce(KiM86QQ}~s;OJMxdlqIWj1Fdt8){zaH=m< zIob0^JGg_*;h7XJ!ooFYBa78RvBw?{$9>(Ut*c$kIH0X@*-6a8^y>_{I*ghlat%`9 zGw6){(F(6V>1-dXR2k{#3p7yFHe+4mVCzVco-1>KJmW!y6>G0&4**}t9jau4(8Xn8 zW2$1>%|bE{T=s|Y#&E4gZ)@niC+d&DmeP5#oYy-jy(RD_>)Y`L1xp_O;V>CCqboNP ztNTU9NZ}=Fu?|qjy%DJvgno}kl{b)1gj4(4f`^IX&3p!h{7?OV)nhQGfZg;D=9=bs z#h`S2ibz2RRk7b7hTUftVl^(b2c&!>(N??!60x+)NMVjYT$-|h1Nqire#6sZvCqs4 zW5@4&J}74fXOGi?88#C9Y_=bQ<;T2sewo83`}gbX&w~P1{H2H-zVGF@CH2cO>~9Q8znyXtFJ@bhkP`d(4ZZfqJ)oK z>IRnY%p$`nHnCp z?@2xL^ckVlNxkS6wQgfbGU%YfCKCk6WuJmeiqFq8oI*5 z>0i%@T}Uo!<{3A3q{ueb7#zZ1g883Y@;BHZiiL%}AH2Qxv!m&MQ?u3^M*Cu_$n>QA zUEy1Fh3Yt=DJC1R3#-qEbtYt&Q%6umFpo?xN>ZmWlAdCU0D}OPtpdPD=wMWY2Lu{|fP{vZqpqJ4}e+Objy&U}IQ56p7#OI*M^c zc)o!2oD{P4enMk5Nz77eJbPb7)l}Qht((bOtbcv1$@e!}XzLXE9v$MbB?EzW`Pp>< zF9|LoCtN3VqjW^mev0N_2-m6W#MgDeOVaTd14K2-0$?GbVZP-Y-^Va=ciQi^$|usK zn|gHQWYYN^3D9j+#Qk5tAPr&NhuJkL@{CD0a!d=0YC-LXC=`XZyG-TcxtE?0Ltd*@9MaEt}0dHcft>2{?}M=D%)QTng!0V;q|0Tj;JWMLqHHN*s4F%k<%R=z1y2q@dSjG!C)&9!it8zE{B;sSI9 zwYgn&RXm^Z{L3rGw*`me(t5sUTs$bt>~xORuuj;ojhzsK=(*uXB5#w;0wiG z)}<%Y^5;4`R=*y^)KCAreiNX(3XX{4CBE=vyi;n2b-X2trE=g#(BoMGh-i=OpI(Ub zF#oW@6Rk!eOi&a0I@ZA7uZ zv#Q;8&61DEjO2kc09_dmXbJH-nqC(~q&|E?jrF|t^c(F8o8{OXf){k{Z=l$kj3%da zXM0&TuMGc&zv@`)C3e*~(q5wS_zfa}kmB6VB;26SCC3Fhew0@%QLG>-yoMuHTg}nDh=+EgA@Fk+9tC@Re zn1&|~qxZwdHNb}GSCMbE`g$JmGPXf=fo0gUSVFhkQsnos0#9O<-9PaHNjpKZW-BA{ zVeBe>TFgUu&1*)iL!x~L+{y-V)EF(X7cbUTGnk`=Ol^N87W)k7PJ_m!)S0xp14cXP zG55c3n|uOBR#HV=mN7c)2=QZ98so5~<*p4H3(!w}79lJ{1IVlS)wdHlAHhbNSdy4(Tr{bQ5}l2E{M>Z+n!`8h>i*wCI=I&5Ow1Kr-F>H4=GyebZIhdD%ye#Z zZw7C;{I{1@QZhaXpOYjfAO9O2VHN)`@f4k?RjYN&O)pr1Sbk(cth8xpD3HUymfl9T za##c4r`KSFcijgA?&8JWA7SdQNd&CCDcr0E&P?A2vD?pieE=atPy&=x#wyc zrt0bKk{4E^PHl1DVccBOtlDnQPSvI!2OKvi+Iu>Pcw71!a9%z+wfk4fMvt9>-G~PF zKbGgpPluT}hT%}^er;z|iSCYr3KuO)!9e1bCfXZ01RSImQ?|y{#T`29r7lY&UZByN--fq9h_M}2^&)b&m4@{Drb(#=VEll`o z^7eK5ccum|kMs|7d<_&tpapJ`@z+RW(gFK23Uo6@ga zh_M2N8Jlu|4?p$I1fI+4%qjQ?Rzv!ZOtwSnM?9e4=w>cHKhzs{_vw*pOtUvgtf_u8 z9fbX@JVV+e?ga=es7(B)jpoRKSi^qdGUBy@k=GNDPC)b&nD~8qTgh+qJMm%~I>0M9 zERqBPJACr=3C|-&^c^2d5Y>_}aUcb;wy4P62)_q?EZZ)m4g6*r!}rXLG5-Fo@JyAR zL>~VObIgI={V`*6ff>7jnjD=3TA9S@n+wO{VV8h$oSgM%f{2H?09}MYP^&2O_*&J& z{k)3bboehbiG#-r$sE*G!uaDH!4JVXE&@;khZ^z(Jm|CX;jg%buKPA;@Xk|o)|E&j%RG{MQE2B?bIUP>)@YbvZW|I zKgt0Z%Su>u!^=1qcADEVJhWU%9FYi9!cqiTF-=zRnTN=oEbXKpR#pMZ@I?1M(|m(Z zFF>Q>?pYfR{O+OpD?Vf^MX?Mg+bYtd$1lSYI^`m8`{aO3Bi<^WHX^MiL(S=tILIicu>-?>hIbU*BsjGw{B-}1S8pq~eDr>0F4H4WjZM8(wrfi=s6P6X( z!n4DP)TbXRrRkMhLPW9!_9=AZK?#ZI$x)=M#jJZ=OO8tn2-Cp5RXD44#@Q41xrBWZ z1vU%}KRO7vd!O7ClVnQG#Gre{Es_HZ_pIoYUb5ECc`K7r(D*qF_Q8mr%BiJ#oneECVEAJ1H(=)GqP z6?dD;cFlW5y0;-XC|$b!&Zu637wpneN7|E(X;vg}U}vlr|k!qnFMeZ-K=g(^L7r zEL{5Cu(FbymUG*?@oZkO+xb88T;oFag3&%t>f88za%P|7 z0;M_E9Df6;?B#a!=;b4uWym8ZYrFf`Z9abiRz5kL3}y0lW3(&HE z1Hk9(g$AnM5~O2GwP?nl6@U#`l7f2xpLKpE58~IvwB-o-tA+}ZYt+Q(yuIykK)8wN z1B5CB5rKi@<>iSrVa_D0;?*t~0#OUceW#AWpukMFlI|*WU^I3*Q<}FMbjA)&BiUk< z^WfjC%R}r--ja#fp@{g44`H}<;TI~EBWIQ9>9IJR6rgsT29PY*P~HSf@r2uE#K-E36X%lsM7eie0WXzpA7fW=H^f(|X5i;@J#mLn)z3bl%sf z=9U|e_1E`%kAI?#a`vGhcBDd`ky7{ZQO^g?r*vJ$<6z$1D zI>utPLxFU48s;^)cKy#dWAZv!-J4O_E8p|>aV33|IXiKx$Wp}pmcz|cGNa5QpmSAk z>0#TTXMPgtoF#obQy;PFX)eKi`8e;+bBEjPl?sAG77vv2#fH^`jgM%eL^{1^4*DyP z;j`dXNhVgHSL+Gta;7`oWMQ#s#<2#7_EDCta8Dg^M?GzN{`Cp4qAWpL|6xAj2A*3?-CBHk$cWrDP9G^2xCI3e&x2tzUyWp11x1m_ot(MX@W#2K9h=kBnkEHzujd%5au&|nfig*(4b1i9!+eqy91a+D# zcRl|!_N^4S=|Vozf}HhyFR=O8pS%swvs1wT!3`PS3s8w>S7_&0aN5Jxv=(=zVryF0 z58vd%@l&$Ro-dlEyHuply~zIhfboNmt4_i;{Qt zPgByH10ACG7OZrVzVYE{)r=OFrdeu{F35!FSZhxO>?(d-PNn3Ux99!T@0kf%>3vGm zz?}6X4#-7ISF_+5<@v?~t*UFuaRAzBv2N}+iVYAQN8lbEGFBeHqCSksj1FkL;H_{R0aX3vIRF zY7)E$$0cCE4+1ctZ`_y>z@ffO5wok6P~2O;O1T#O_pKzmiF4h}w;FIc=a&k@IWG2+ z4#7RZE&++h{;N+(a+-^b&F$6$7V>%i!YZuId)GkssWs}6j-Q?hEp$O5%D{T(FroYY z?uTpxX#m|*(msbIb~AAA=MB{pDIKJYG0Ew7IopL+R_kuLqc58bJa$pgiaaI?XFs-g zwsK#(%~Xd)PU-wCNZSH+nJ(j6oioL?GYFi@2Mu$)|Bd9Z^9P0h#_#{4xDJtF!{C8=L2SzbZuv-sd}lU<`fut|~n zh_z85DBYc$upJLPM03##+V^#h={S9O52twDg`tZvKTzkp;1ec^=SQVO0BM6{FND1} z0{#;-4x=j~9eGDLG*sfUk}%R8JhZObDgcZU&*5bxzo&=|AK3fBf4niCkultJUirG; zTlDc&3;74Mx^3hYGTP}&0Hjg~F~Jbc`!z>}0NPqL{tB@Y>gLY|@lP#@rB
e%sx zo7j3r5MMM8n6O#{e6eeexbr@v_!qm$^OFGZXVSZij_&F&FB>n_SDybJE##u&^+yPhg)eLY9I38p@2ROpv{7?W_Qs2;_lg7RpQk04gbC?r-DP22)`x46kLxD33;t>|T zJ>og^JdQSoBgQkGhC!9?G6(vm3#2)bPz?9Re`_w0`}F5AOkN7vLG7Y3E>#S$DGyjtLmWrSEB5?yKA;A?70==X306!Iiv*$1)?m4 z6L4~5nOSpqw92x^TdfW{E?K`b!nZSPMigdSr(Ed$E$?NKM-|G3Wq zLUP7)k&kA}ZdjjH(i+Wc6yI#oO@0RL{?sfXo`X3w+9h`b=(+K$o#n)y2Mct0rG(Ic ziT5`E)#PSK-xf-sn^N zqd17EMsb`E_s-u4Z=n45CZu0EE`I;M@r91r*21Am?gS@LXG>~25t^^McdZ+hQh)QR z;~_Cr5f_!RpR@F?t1Q!-RCdS5^B&0ttqdnol8cMiYwLrpq23l*o$de30=V;?40fM< zKmEj1s32Xfomxgh~u2Urv5nBwEn2ni3ylQ#>QN?EN16sw%lh%Q&E7Nd9ku29axj9C_Yrzt8jQ z&DtC`I^6Ahy1F76%^FJmOz(`vV;XD4MH<5iHK`zO7)Cg0jMf$H83d#J=xW;Ws!6V= zjPBKfaNi}j5>6|dpXl4l71WZsM7#5fxwuU|Xo_#tGI);7gYK!ubz4JO(m4&E)#8h; zhl417-Mv52n0h=dNyEkNololYPIEJSOq-lGn{?I$!06TKFVxB{Ha(3yp@#Cp8>U|S z(uHxVdp?nkb%uBnM6GfA-spq~rZ*cJayD0k^U}dJ8`y1x=T`jlyY406n)h0$PKT+w zh%Xg=?C$NjOU``iRNv-;L}Fl*=yYFHy#n!rH?mm?-Xg0g#BWz&D}}$TifO%*#t{ld zl%b;nbe>}H^GGVJ_;Nb|zRNkM_+=fW%@-EKw3QiBVKD{vnrem5?03GgTgj76y^;C- zY5iFBmoVYT5CHDoltA#MqlS54?~@_Z4^u8VfWjhE9`if)8p^8r=sKAhx&6d%&XqjW z{OdNZ-yD{0&$5}+75wks^o;X9 zICKh2Vya_&>YLysiEr&Zy!`A^f9yN>xpbhWkfj6cLH&B!ux+L5w2WZZGq&33gsD4B zpE`Qm*RHPPT!vCJaNv2d21Lee&!3l3YCa_wAg0sWANn+)78N|LIcX}YB{M1i3F5?n z51ybbeu~QUqkulwf4(-PQ*sRXhjy|=s_D5XY_5Fn(XpU%#>mP!?mFD6{URf6GuGD# zeoYGHJW+nkE*@E9Hf7Cqn@5RvF;F-n7G)KwLBWI;B1ZhgO#`HsCzpPF#Y0cHuG_&527RDJcz@>Omou33*XkN2 zYgG>JPB7_Lf@D*gL%XJ&5z;<|2+vI=6y39A9v-8>X${G;=R z4EzP+Ku$y8kZqC8R`_W~94Nr#=NA2^9kDd?WE!-KJ0jOWNcDA_^IZ3Z%tvZFv3P(K zz=*&5uF5y!TbUUq!5UT#z%A(Q+j=f!a#z{5Unrk6a+GXcM-m)$KDO*)ncRSAt}Quy zulKc6hsm!!Q8*!1DhHUMiZL7n9_Wv}eacZVZ_dgiBod|E=eWurpZZo1@B^p4`jG|}iq|6i>Vm2U?zA~K`1Ryo46o_g;#0`FB2||H`&LePmr0fzN~bID zQt*9~uoz9H`Z+v9tIg9l#}?B4*~1CQME@3`QRhU17+++U0VJv9qn;MXxnHLs7(^C8 zz8o|U$vbyF>MOwFx9|0S48J#Hg|oz}Ue)UtoBV+k(!Nr7wF`jgQE1K6GpCSTE_1-) z4y*;L%rqx*MN!p-B;CQ0Dqma;+{lExo8}1D!IBcgNayj`>s_#>%nlo=zs^J;BV@+h z&2tYZ;hx%CTatz^0C!DHlzdvn(>`7St^^a{ z4m~pa6TZtuD2-!d{SQuF38IXtKH z8QL5n0H0Wwh33_X7gLvbv*8nX038KKW*0zI3WbAim?W@sm5h(w7R-SO^SFx@aW}3F z|C#o!Y}*5BP1Jo9BT8~Ly$eWHLR}JGXAL`u$*6zev&*&h((y!Y%m!=k)-XXu9h5ol zzhWzMG$-qPc)?BE31iFLF01SlI0S`aan$#Qj+b^ydFU`YBWy*?G;H4Qg!-Mj3?2Fl zfdoE{HZf0q&Dfvgqb=9nQrJtU7F2IJ@SradEh6j#a*1ZP}8~T4}R-OsVuS zkh~o~NM`I@CRgRgYtP`?gYY!yr+eVg`+#BWx@EpIRP|~jH|BiKDaYuxt0*8jc8ms} zPdG1>+=V#wn)~2Yey308`16kC9x`mi#~rpGR%wfB3wYXBZYW6fzVLVA_jU-y z2wh*c{l(&E;lVtO7WZ*mr9@(1?CUvVNCf)%#FB73USdQ8yb)*D;b*`CIogpkiNwYebC_i~TC*T^{%Q0L#&ur`E$!^K4^f{pVdFb0Ds5KU zwSY&v-X)7l*~d27Ta(M`0(zh@vLgGB2>HDGbY7#d84@(FX07NI4;_{ik{LvwBIKc} z9R1#^7AETl15cn`CjhIRKkjDQ{O`aEiA8{ckpt-a4MG8obcA?YZc``0==6*~v zQljrQ8r6leGq7*ja?+%8!Q>1PVmKWp?Isfl$UarPF>_vc`NjMQj98Ntb$szBaTG7P z^y?u)BqO`uTeB8H3QyW2nncMA!@-JM}@hd_X!!5xB2zR7#;x%X6k=NC19 z*t=G(-QACLH;mAeA8-7GAkips=ZalcWLfnwbCo*qJCp-bz0 z-VAyz(e)K2s@wFArt*<`;U>hYSGG{vEdFNT>|JQ?%i2Jb zc#A2n%PhrGo_^CdNO1M-Liby}rk_^rrW~(dksM!hmD6XuvGmI%j_P!8tz44WYVsRM z@VAye17~LW$>kO^Pa-F2is^bn=njHVW(aZ0c*{@)aJOp1yiznMO#vd`p%A|~5wNry ze(2gqP=q~>JleG0+gF^7j2>fhVRB#X8&o*4xIx+Br-ZI4@and~IprV_=KBo_$eZqs z9_X1T{3Ith;3H~7|{H^=)rEDhCk+u=g6PZi~sTlJeqaD>dlyNI_D>>z< zfmvAEHZOL!%!2M7*7lgc{7vs#(@s?WtB)-n6#}cf?p-sI6SxzOsDn3FN&N@zK@5oW zEg8t+!s&+M!IL>cE&+D&pmzI)6+~i+l8T&HH6;Llv?hzu!qem)l6oE=q^270OO12* zush2e5~#-P0cHo<7xA$aNS9#ni56E|{(!f7VW(_+)bH_B&W-A08}ap-&o2F#4lqR7kTwN!VwvtK-*&4tHPK$$6O$R zJWwh*DmQmbo^Gqq_%)XIFDoG{QLC@LE+!q$NAa7nR24WAtdYoH!?b%0?Y*!>le z-}J5gBAOtse9Y*9v+u_E9+^O>)`;KB>_g2rb!N>?gMh3p*LNl&fd(h@YwLQ@n9#Ks z5;A~UuO8)a`?1@+$-8IzM~nLCY;y=2wPpz))XbmG0J!xOYc5c`MnTwgANWYX6D4d% zCOMYwt5YoIB_2s{mH>ZEpGP6zd}uBx<5?)oAIm3rW?d1|-KEo){6I77Onm}6Hw0^3 zYT}x6aGjH8ONG8W)x@?pea3@t;FUDudR`dkO}~3&xL4i1HBP-vjX7zsPCszRm8g0z za-NTmds=?>W8C{`0}hFNtiFj);@3G?%GdV`>N|hRg?U`ues@ceMj9qgmM?YPJ-rod8TG8lFxuZ0v7ay zY{l-ni>3Ci3E$e{u9nm0-iDIVXyK7x<4N-SqWZ#8eedCyU0?A2KAs%uD{a036Bn0^ zO<~$PbD!7GU^~D?ZDw!lXB5Rlbl04fKU`{^zq7GgbHslaL981gMdnRYFM>6PNXCSB z#JN+H9&i0Ss)%>#g#xyYcl^-K)S#j~t2irgq7Kt{eqFX#9bXbOsNQ)#8zW)IQuW*E zq*{5uJE@+t{Oql66Q|P8=tV0YD_Cp{JFL{1u|{|-ffV_Y1U#L^J7LMc>6MXe))BpH zYrdH-ZS1?>d$T;V9sK7nYu7RcZEGmuB^=58fawtr*0Ibx2OETerdi5>_Og2JtHlIW z_!CnspVG~{zEjIwM7{et&3XlP-qJs@+VM{fp!PQ?RwmP>D9ZDL;T4CMi4oQ|IT95o zfz&=|>ueookrfjN^j*9}+*nACBx(Q@UV6UnhZw>a%vIoCd}t!9uidF;QXdtu+s+)A z_7=gGguWHBzjpF5+^u_=a~K=&{!QPm4HIy(Ek&ouMPqn?)oQLl3wg_bvc=PefDo0K zTP{~qA202#CZM;HBXS?7R_ms<(BDtW#WH{>dc)mGaYWA&0CJs5wbxA2(;Q^TXrh&J z92K@Ngt@3mDb!m`xlbL$MR8hx_iu2HjjB))fX&`+foTwCy@&eVLb#_cx`}Wl~*I&K) zH9#*nT0kevBJ31&WgsgVeGf}2qV9r&?EMVJfAA`l!d8P|WsR`Kta|0Jw3yo;g&P)q zxc9ItcX*9;ebpJXuPx}=nr8YR5^0tCr~f)kZWJ2EFw&G5je3&=69~|a_o;=NoUXB$l_whx6h)h2Jf0K0>i87ZiT1V zxN87sa5&gvMlnNh=y_YJ^i_1OyCH%Kdrnpi2;vTDizAo&835y2F&8S1E*(V8 zepT4I174O!av&uCwuH(R<;A;V-+-^mXXLx&0q+TKn-UiJD!Vh1XC`7@Yi#$~K82U2 z$=qTE)1Gd9J_m$gLtt%}!gydOd@9XQ*jf`pdqPN*J&vqPC>``E2E!?a!#tKgGzbC2 zZ9NV4w3;m7+HiL_#zGj&n5N~&Y2@Uu8@J-zNRRkI%DBTNkwz-6)bKJ+OGkLMEq`lQRv1wWV?YiELrZ=QNrYsz^u zk;lM666i70y-LcPMPK7T@BimM{&0b_qI>E-q_*gOE-<6zd&^YDMYIeaMY;)b1-13d zu3UJLgEN$E=880G;ilC+Rt}U-cp3_YI-xlwl*b1Rj9nPCwt@WYD!=?H$0tu!=+OMj ze|g7bzVjoJ{p~E;!w8e<<|%S*&$KxX0w=fpbdas%jR@!Old3l-+7L_pSIst0AX_m| z7}Ge8TW^|ojO+(hD-r|OVAfJui_&!j^K`f-;k^osrj5;D|BR1n&-3M1CcDTN0~>af zN^>%5Uzt?3xXMg>-uE+M!qg|I*D{3~bPPaB(l!~t5BTB0ErTXIR_jk8X0N_uTjS=h zxkODm{lpvJybNbe2HfNit^dl|oj(*{eY(1ca((0RZH$XO%?W^K+8PwR{&aD1wP`@N zd$wtS$^xIhA@*DJd)KQ|=8rA@f77u`9GBWr+HRWHwc&#SS1vm&qo(_SaFu8|#g?*r z&ayKmZ_1Z@7fEepBXJo^LIrQ%3r{j-O9bkfcIjh&_qj8WE&t&ks=I}0bq8Ag!Zq2K zV)M91w3xC2Ab0sXy2nE4jBmYt;v71IH_2EC-QHbKZX4KMVQV2gHz!0+wFfBMA^!dZE#4>1)?h)OL#Qh>9Yxi+jU()gG%lS(amy-Y;SEOe|-vsC`&3(($ z*Yc+`R>`~PV+2^Bf)aZwVnd0 zR(>3&S#w_NUaCITa)W2f!|Q!q}jw3oi^ zob>#*3cZ{v#2-iq+31^$+%{#399t+-_)N0fEdUPM1RlP>!;?rhw9w-@EFg1wZBP70 z&N%i9WxZMm3WXbh?v zh=-o`!2`UKP;kCBU@}*`wDJTvmYs1Dk-Q19Wn3Sj+TVsKlqGnVR)e{X%AA3z!JG;qPi( zHdc-@a6PXuHhkNQ+#o)+TS95||KX z6>|IF(ISc`&9ILd7sVQk_wIbOFIvy#*9E7op|8Z@^aRImrJ{7N{!7*I>AQP4XMo+6 zE@PFMC|Ev2%Dtt|(iqkYCpmEB3^XF2y5fvaBWyk&wi;+K#+JOZu89Cu1Dsd*_~E3ihr zMyZ*s3f}k2k3bc1f{?tHGrnjAe&ffA13|FinBeT>^art@@PdmO=Btm>Oy?rBg>&E62Fe4Aah;pAkNZ@|9P-_W zmvKeD*h}T!I*x6Y`k<)r%Wlkq6K2r>e&IoKE*^0@d~VV-#HWbmZF~F3uyg_mVQZO% zyhm_F*um;z@|}UObU%W+LfD!!;V_+7Z&#c51O%_NKHa`LYmAX_Q8z8yZPi-2$&g6A zC0u7py|3Ey=lkSR4QywC08v%`St9P@C*Y7A%JPsRmxu^<`w~_9nKOI^|k9>)3_z4I*6-x ztL)PDP+275GA1gr2tOj+^D-s0EGEcqMFmfWii?7Y#TbcFrs?2QWagSG3>4)FL5;#AVrIwnwcTcvgCX6hW4 zLg>srL8o>z2`U$#DDgT>^t`QE*}vh-(=QDu_17HWvy`i>mhjTj@Pf(Y)i; z8{_NT75OsTTK2Crv49vgWHqemrEyM1$Q!*)7Dn61Q@j(DVg%gcl{>={wWe2!F4qJb zNI`C{1k6fr>I(L(GnnQO1<@DecHH^#sUlFMW(ydsR|~cax5O@29YiK8QVoWvDhqRd z44~{(r(f>>UqY%S`>(QFhdbj#pLw)JOBAobC~LY$bYKe4EgpsfCo@eS>mVxe=k4$k z&4MD}3XTO#I64^^mxxZrQOIi@Tft4Vf=_O|3Q+Aqx~xSg1Zbf;ko^j0;*5t2Qa4@Q ze0!|%G%MtrF~BS(EYrN0)SjDFv7coq=lye(mDM4z3!z&Hg1Au_Y1g;mJBYhIWbnnd z`z6F0@}SWo{1Rlz!(6-rX_Mg+MEO2mij9n4CD&jBAA+1*Yhi_hsS38^#PA>WAnrHD zf3Q%X-ld#K$cp$xl$8&lJLtz08dd(c7a$1bQ?>qc9X-KbvL5Fsa(IhXAs$9X(HR~8 z1UF{_%I0aw+0AHp*y2zMBT^V#3ti#X{HkIq;?y#JR zu>Yn{g5{Q< zo*`6RNLy-HL))5JUxVxPYVVi$PK*o(`d5Ml0$HTP|DiT_1~PhCt@xvfA&AAG4|Nz= z){tTZ1epvLl_jO(-%%|!SYY@JjKg8tvFX@Ba!&%)OU@MW+;Y&LKbxBK{^Cu)l;5UW zm-97^$QwdK#lq*;&~8Lct*omI%_FMJKgtPP!v>d2%m4v@Moh<6_Ac|FJ84)h3Um98sp2V)Lq}9PqW0+#?yB=$Qb_e+hCQj{!-U7mM&q-r@zP5?Wl*c zA;O$4op0?6K^g9$?(-nW3N}k~G{Ax;gRC{lH92YiwvIPe}0G2l;Vn6-tp?4z}HVYKmN?8})ml$2Zl1fK zeCXU_?o}0b5v--@o1AEA4LKoej@k-`$I>Gx2XN4qauTAS`O9W$jmd@o-j+TP}>k)r#43AKt?xtvu4^vk=K=QU; z-N5O|Ue!biN4#R%EEAVvMe+9Dt50B#22mX&ufqR%v;@aq6wXJc;+|(S2h(ib06w+4 zDm^MXiiR|j4fY|)rz9@iHS<1mo!M8C{CQfCw7%4T@aoh&fnzJa&5+jp<)ao#gts^1 zRm3Lm@4Fti80k&WPi^6#h*ps))|9|V~-X5!OmsC zu8nal4XL#mS=Z(1Ngbd5!xgiO%1MYyGu_Fjb2`Fi_90@lsA=)=GY_Nnq7_R5YpFcf z%yS=Lh-lVjZaJAz8*D{H!PxSB?CwrqYfEkgj+>cAOWtCG8%|FlPy@vn<69_{&Hk~N zbZ`v5OJxT_O3oGR-#ITBbOO@lIC~lAgV?OpF$?iQIJJ-seZV;5gGyR;SmcG|#E@1! z+?CnHbPel8FMhv#Yn(Ph9$+F&(?V!X5x)x?01DD#lR*8&(CefPrO7R ztuEnS*ue=*`bKhdFw>p44xI3Z{IblZY63=bSTm0Nena3D0W$eO4AenCRIgptL0`xn z4gW;8%}VLp>D!ZSa52SaJzT(%!BF7|@4F*$YAXVi?8{Q9x9e;+QuB|`0u6s1ZBi$F zeHx(HT^G{1VJefBBOZJB+K|`}FG{@8rit6-wcvLg!+gON=X7O}01?v@}MkV!v`7 zn0T=f4>s2xw}_mo*Jt?cLP}q|(Y5Rp*K?oA^xLV~x_h;QZ3vwh>QPU!vxXTd;x`(w zgZ&D}XfU7MZCzR3cvM){0)gggOA)fH1=Gktt7qxHk%rG{b zIqbN?+@kH`$Bj_Pbn2h&WxV+*g_4cdYGPR>R{ zd+~f0bOJX?nW}m7%p@`%oc`3wbY2@k*HIC1p=%QH8t1*)m~&!IYXR}OA3o%fc4MOC9N+4 z{Xg{+Yri=P*2b|Rb7}Uo72}OMSf8wDt|Fc62%d}99uc2OtIQ0I7?x* zQ%=(eBlfFL4}u=AQgrnTQi`iShcz0`> zIjb!4wR+*hxKpmK#|Iw0BM@jmVVM-bC7{ZSbVMZuKn>{ zy+BVjM{?*50gMvB8>c@myfXlTuzA{~)sIu0dcz(zP1+N0KT=N8>qTt zQ@sBhl;2-E5%`d=u-yVQq$ml+9M5bd#t737eRuL=8kVV=C8z8(2_y$xr~Ryl9Pi*7bZyb8fuV zUzio!hkF+?M{j{=BG6NUaI8O)z4;RFNJE0eY51rl%4VEQSJ}3_<3vN3LwyL7G}SQj z_I$Kqkd$C9F3QupN16W*dBbG!|?gU zNGz}GrZn354Q6YWDph4425$(|pTE{hG;62|6%+tD}MpHI*+h;2jf^*LkG8zQMic zeTjixmp%B{^DK)yeV`sa(g_CFOPJv95B5bS>-=6pu)-~J`J}kg#;et$0(&rGrW962 zWxclsX9eNQu8(d9M7()$gJAai1*UHXtuAn5-JEKLP&CnkR(x&oPm2SiS3<3Ziwfi4 z-h27mK`Q9T$e71yzK;(7h^?_I!Kn^W)0kTiO3=}-cr*!gKT~q zEhRr1Nc8*#Wv$8Gl$%N5>b;G$iY(683A-K`>je-mN29Dmj1Hs^fIvLQ?_gYvM1XDX5R-`!`sA*$Y|=ZeTHNPl=J6ik+p$O}U5-l#eqA(}w7MuejSy<*z$9cqg z=hNCrpbAY|zDo!K$SoJdI9U10^iyg%%w0qlb*+$9T6J%b7;*-@YTc8#b<7T^9|hG4 z{&l?9fvU{#5;H(uoMdr`1okSoQ*PP{@&~K{<;}^%VX%MXhnh^`?+sy1Qp*X^QkcbD z4s>wI$CH1^F}v8A?6^YtK{>xJ(~Da2qwwEY;!I)t_S+b8UK{U$7NEfg2K8v^EVZ5k z!OkIrcZOUf%<3NaacN|i1XMB!Koi_|Zv6Ppgj6&;O4t#GG~vghI}X5i9@B*~?P#j$ z(~6$O&_*y_?I8~6(;cnmdEUnabiG*mb^%84p}@|KXP%91O>4V4wU^o6XdMr`Qk1uZ zvS+=ZUp{H@6wPmOR)~RP4h>dfG$t~Q0hSmLYg{or3u5&?4Pn6+##kM^8D}V_oI(RhTg04cFJudb=EgoLWfzL*C|*-A`_F z+(+E^j`EZBn2WoX&3xCsi;gw=HT`kdW;txBzLj;* zeaXj2uj&zscB#KN-MapWGj)-s1pfi=0n2-IQT_Juy6*nc31JX_5Ty2^npRDC&`Dyq zam@YAWV1+a(bp~KFVfgkSIz9C3_+M3= z`>Zo2cyLMoYQW_~ZxG!X^}61=bL0(bO{}ol5F@!Mf9S^MqYGFdiRP&Qq&{$AW_!&DT=@u@_$5>i&-> zFTA4;tpgxt57TDOTYYd2{*+`%pr7!NKc|+~GTy!|GLD9CTx?^hM3><}36$S3>4dlO zutnsfKa<=BC{Zq}495KZTCg?(28%nUpp*ZnEiUZRvo zws7n|`*4_XQvd*K2sY)^JsGkf6)ci46i6OA3oFBj9acc8acQRscaHz|62h3a$ydsj z;2KJ$$}^#$1$?!yZtH(d0oQl`!qf^I32v%>31Y@!TtMTov}%FsM~NYAG)IJ4k_jI* z%n8jEy;~fWcAh*H3YEzQVV_PDpDv@nZsWlCHYJrs`YoF|D#)<*pyqqeIFO7f9khWu zLX`!*v07I3$RFX0Y>;P!2Ig{7WB9lM%VN!x=k)KXkpi}98UAg@onn5W{<~x79g)Dh z1g0i-`#vQ&tGf~a!(Xo1_Mc<7q$p=*Nr{XjM_0FP3OOTIhE zF=_~#g!rEORpipWA*2avSg#Qg;l6U^i!!LANs;;H;9o+@io)B5W)z?xh?kY)ozxpp zI4BOtJhm*jx&|)+7WG{6S-6QVg-K9Rq7~ofz_aLf&bKE1hHdqM{|Qi z03btlz70MIwHIl;x4gIx7JIB_1VPfPP$I;)R>`mBh@@J8pW@*IK8tP(0g9QlM92$P z5gUN={&vAW0v_f3^YtQclPMwYcex$CAnw^(LP2LkoLC^%V^`| z?~X0wVSZ<#A>a!ACSvr>5A?C6;Wugd#$S9_p?ZSL5xB(;Dx@Za#WVIn+{p-c(xdRCsPVgQ*38N?nPO6z zg}KS$_5@rj07S5e&B3bSd_%&%!9=a!wgK)B3wh!b3@J&IwYv1&vrN3lKRD3j?lYK3 z2KO+MgxKAc8{{YC%P;t0;FC)j%k0M$*cP7G<#`DIaGhF)1deAD9ZG|MoIa_caJ zFk4MP{K)ux;f_(jvaT_Y{nWW7XC@2f8hou|-I%TE(!v911g^{{(lu?v^e*2f*UnqS z=sV~Pz?+*=@$~S(7~e_cRI;O9AUfVXq_ny%Zw9sQ=0JZ>sZEsFMMCX1ruxZE$*r7* z7qcE}oHJ^5IhLXR<`IL6dBCx-%E))Ismo6{!x_{Ey!CLlwt4{+l=xv+@g6B(ADJ?u zE(-;UzHUSJV-GhV%|4o!<=VdE(=UGg^oTW$pNVz2lP+~EdoF=-?jjXZ#|<8%cJq3=>#6;f z`vVrp_h*82wgBYmjVHW7Ixt?`^;ivWA#>-08G~HXTF4d$M?B15n8|fO&g;myxBPze zE0+*dAF;X9ALIT-v~V50V#H%Jk#-;SQZPV@)lj)E6s6BA9X_HdfHI(#!$KLq$h*WjmdX-^GJ zK@G5*KCS>64AaX#>13v6rg}|^oz~N=dX}l#+NO=v>FBa|cE=WX=zP1d*%3MQ5eZM@{Qi(L`tFeZwDjzOwcsoTUoFdTHTZyow^Pk^7b!U>LC4mIcBN`W z9?u2AU)Dj}v`SgSQjV5k#4mET42uwDYG5OA!2RV)Y*1tb+I-F*tadz!su7px<4ssFCz1f-x8|CaMWGls%~Zt{#{!E; zHV%W@l)211BZ0XDKJ+TANb}*8w|-Ms9t?E@HSriob<(&z{>72AzGBpq*E2xOX=t5eNkUXPAu8_+zbR88cgarjcn9B3^NS|4E^91iM@I$Emo&|lSEjwdh3|`@CU2tA@7a8v3kSE( zeZ}&!bDyM_@W!S;v%NZ^9A_*1L2hJFQRztFAn(vSQ!({666Y}Q{h^DItb<+&y3me! zT-2+aA#DqC+gBJooQSi+L9S|1j-0cIgs`iDulQe_Ur+R;hxo z2T3^e{e9m5{QBolMIQXoQ^K;=8AXLTMQ~H2K~_ZxPN9efA_dup*tkdnHIw{4vKI@O zbH*i#kwoBfBPf9C1r5$49`LlE!v>al=^b&hZN`{f24#F2hNNlw% zmE2%Y2P%9Razn-~j7oZ(KRmKPNa=^WnRkcW$|qTYZg~PMeic<;_NLa8MrAfEY3BPC zOwJ22i8575Xuq@Tsgpb$J))2b)!k*wG2o$-yb_G7w4DP=7swuJS) z-3E1P4CxI-7G~_u*attsa`biWFM80F^AC$tg+G|K7Vc_RzD4n4LW4b)f zLO4{CQ1)v-bdt~|L=9^TZ}k+lolh}Fv!xWZNWfBBYBg%LAbIS3(mlVmaTPZFLj)-@ zS)vnoA-g0~Dp~9m8+DTo(G53iQ02ss!xH z(mG|%YqB8gnW7-Ba~(*;_vd&%B$|l* zrPYv#VbV0BV9^q}{fWIeO7Z1d>=)1-wa%g#IJRBcTr`?0EWE&E$iW{$}^sR#!VFJr)uJdk&#bKo|ij z^B3UN?%qMHWXQ-7JjkK`{-U1*<)tX0;NH4Oqm5#$GMrL zEIeOJsX6l#mI$l#u?HY~GaSYDF}e&!X@Kj*iPXr14a>P6m++mP2qenS42dPs0-5hc zWy8$b9uaSCO*75!t`e@She3x;>RUSrt1pt+D3!0y>Kl1dmLxw@ee>&zzc`&g9uzHl z%r)w|8B70lbQS#6xY>i-s7vmPy1f>A(f#%h@t;e(BYCl49W>oL$t+IOH9wi1s$Hj` zOWUWE#ty{C`ib))JE1XQUybor$sNz0V){p+*G3z}nq4%%FU(!!kXj<7v&i$diVqNT zPf$)^F=T#%wCAv2XYX{d%Xxmi&2q0c zzJf=`#DQe_hTw^*k{0YetwLk2pC3;?Q;;+(q|Xd^%$^%sm_$~zd0kcXWPsE5MCfM7 zzYd|M9r57~-!646XQy+Ze1!U6ky|qUoWm)75`Jk;BIU;8V|KAv=a zRf9PcBm-?`PCt#U%7f8@`}S z&JLnl{daz7H9VIh{Le)3H`QY+321u}lUI1z?axEz<5WVNGRs-8LMcM!Qle!Rr7;^5 zmfwId)sQLVcjZ#pcBvnYucA>>A36koi$XmM&e2_iPaVpRreFtbLe)r;- zzM*`IF3mgA+XN&pZ;Owec9e;x$qWw;rY`R7Mt7hO6KVk+=t9mU z*s8}_)>}XR@G*#J5?m6Hl@G*9n5s&{F%)z8>3I-brGy6N;QaAM^F{nQ^F)V4jNByp zz~V16F2dLcDiD!$e`LxqnmCcG+!o^`sSz#HHGXFWL=O@FIw$@qC;fo-Wv@ zs=x`a`IMaAO+W`SYR}r!1Q~D!vyquKzsL;9_iAfz_LXAL6X|9`i7iO5R3dqZkyWCj zE+wmW+DMDd5{dEK3rH`J~173Zh zbsFuBcry`{R2jKKUqiLk$LO}Zf4wK@2o`$J7c2bU4M&)Jq(*mwqTj7`?5zI1n!5amu35l6;UA_GYY6R$ zi6VK+r_Fa|5tl;!f#YE`Z_4K`Sy)3b9@#b_;bF-|ScV(+%me3NZ$?V4ergXko6k+O zhKj>#MDLTfc;en~?l96~Bx`J>^bEH+cWBj2gr$4E2A^p5cPh@>SP*Rpk2sa(C|q5X zXKySnmQupQUX-82w-K|jP7L!NGW|bUtOiBGy-rTHeZgl1S)TbDlgM2-k0=&+W*Xby zq;W3}?Ao6tp5s>w=|XUS7d_7N;f|Ic!p8z7^fLGxJNW9atLFtP1P6DTbKk!;mlY8& z7rTg%x7qaX-jTCdvvhvzv^`3X#r{a<(s}2%-YShddVaOqePwe-?983ssvQ|XbV7V< zZL()a=8GnbkM`R6L4Ngm%XZTL9QvVYY~tb@wD#UGNArwQqXt~gnutiMbK7Y2l7T-C zlTraSd^>E7EeGtk+%wFZ<9|&z;Szng-_>ulFb$Khs57>BPwt)Ik=;jKK>eaHl&Ku7 z8Chp^fNX@{RIlTSKdD#^gtg)C&Y+qvG}yI>KT}q?HMh9s`gWvAiZ0B@wH9kQ)!#o7PgHz^?UoRdblz1BCEkORAE;maEY6!-37bF}X< zpTBqM84O$jYRkxUHXe|Lu+d`py&U7eYh@*QWTw4~|Bknm$k*a^Z|TrK!vu~Ye?_!3 zFcUWQWr}`+s9DcI35Y@&x!LfE#Qjg11$4eDll+g6T`luC)o4O5v3snnP7DdvY&k~l zkP4rB=WnII#YW0rynq3wrOy+rSXH}MHpf<_k2+z2PhqHEd6 z9O4Vur}_`dWFCUF3&QHFhpg};_*=#64gS63j$eks_2~ODjszvcZOp+ zoj^D%Sgyqq&0IiTqFAuH=@Q1A;?H<5g4tYdi<1G%j8$PcsqM=Nb0ppgW2+rA&iJ(F zZUd8uYB6^DSvjyR%yUM(_m)YrRvb{59MuPQx^ZRl}SOI5vi3`l(&2IUT&OQthepP zo$%i05?Fp-Uz7|H9;rW=D1!k^od~9nq)#it5Fw5avkWJYP5yE_hoohYjN7}_ikRvg zxYBH>yK!tKxuf)jQhDhyNn9-F* z_FRYt{E3CCmN!26Oy{gHK4p#l^EK&|Q>07dyM(FAsl=(onM4ZiD~+FSMF1O3UUnN4 zc+p?!-dtqk{911Wg5p@mmv-cdJ2FS!HIF^Kj=4nmy>{N9$*^Bfw~5TQ9AlZNDIT-# zhmuvWdL)^yJ-;rOK@WQ|%%g zeKQgR!Y88CB-`}SmqjMXFC+T~-10Enjaq(1ATQ*7W^2dy<^uV-!G4Mw7`dfK3{BBt z@GFqlv0zh+mG9Q3Hz;GbGyc+xG)8erl=x#DW*m#9ROEdL>2oa3(d;K%hv2U&k9&TP zIrbIgh^TgI6H{}YNs%)xea&0?hDCWd#4hfh3}`PGfy-^Q9!KY#nY(*QfTrB@)qUYa z8$(i{Prd&`e$XjCnQ?WH*jXKp#gE(;<^f9rntozP1jSmOoUkHM4PlI81+$6$nV0G^ zXTHX^S!96DU3g3DN8Yn&jOxOi48taXGY|~S3QU5%EwKJQ zrtA(2>a@WJs6W+5YvdcZm7F|=vlUL0@LR1@RxHZ&E+&my)88sF6yqnNDdsB#d$H9B zzT|2fM5c%j2z3C%IY+cmP}Hc^(9#E$px1VX+`}sso?{eo)l}0>ZK2-MpSg6GWcFqD zH3}IH(B8oTdX?lC~n++a!Q=f1na}+;vt0ym4T!!Zz z9EnzVLfPq~{Tq?lKg&8u>+{b?eJ0_bzA-IA>x{=s;2I~=pQVvFlXezRecMcD zjMBt$gl9>SMg>?VZjwC|05Mr0ZzH;yMOlVjVvs^?7rzKM&$O9qX)`O~P9?M)MqvcK zmQ>>IBk|hG+F=TLohi*Kmv4*?_&NKz=zd6U#h}Bea^M}mx7(GdW?JW{>m?RCNu8M{>LM?s~}iG{LJsEz!vFkGM!iWY0-0ZD^#SPB?Z$taQ}l3yv| zwb6jM`fpF-8?lMc+e$^VDD;-)goW(&L*c;28HFH0GamJfDQX%FS>F zev3A-ev^70Dt1rxAlWa~gS+tesgiuaahjTySx%WrdGmQSQgbMx1YiHfjD?AtYI&5u zJN<)Q0d=8uudv~MEb`@e+;zEUYCAsWE{moT{V!rA!~vOXU7Zq6wK-F8CS;kFQx=P< z{MWn|1|svW^jjqd1*w9mx7c3g{5PkC{@LvZHL;)9AMFGumQ*OkN_T#Dz9U!Gx7bH+ zE86;^JTIPGM9=vhg}5MiBJvkH8&<=In@xeqH?3Mjij;fW z#au_syz>>{@oTrtjUd_VMHA+STzMOpN(rR*U&$l59cDWU6ZtFIN>sV1Fq{FEs7700 z=`imUJz^vGr~L1w>jJ?h94XbvM4A@>!XBC5Eu}nkYNaMntp*-^;(lVp6541h!wie) zBJR*miN8f_z-*Npi03!mTRL_t9p!w`?=p_JM|yks3qloGiL6BsItZPO>@cg%|KsW` zgW_77XpP(8I!JH}Zo%C>5Fog_dvIsa!QCwcg1ZwOf?I;SOK`VvhjY$Xx9V;xqxNl9|k+2db^4(I&u9T?d92LEMRA8M^CwamgN3(@+%_jol$33B*4vq^L;BKbTS4W(%@v;r-UG_|pK?NgoiF zMMo-e|Gm4mZgw&6MU+o!gcg8o0)jy!xZ2qW`2Rn}J zcRRDMesWiDM$q3+sO#0`+ai8suih*A2ddI{+62$-*8{&10t3>do&wXb%gCwgkak7 zZX@ahP%LouB6{1A=muQmH@{*jzX_5x)a`x0@DB%en-WA$;Tm5UeHHbP28Oh_q$eU; zpwK})s{Xdbp7Wtx`o_x5oZc+My;_X93IzJ7B}hi?SOA08Lp61`x*8^x|)OKI?{%}AfW^Mb&QOt$;BZ~Ls%Ip_yX;>|j3QU~}Y zi;=JliQYK|smD`zKP7d!+up&lFq*;DF_>Wve(E*17{2FEgEVy@eF(#EobRTvbO=<8 zL(z%h)q%wl`Xa^@4dQxMqIA($3v%L4o45%Ujy<9Vg@GvLJ5s~MKU2^i)HAZR1`(Cn zPM@H8=n(x&E6pWz^4uC%(TcxOlCx6F z-udVMGLxqRx9?QwKYfe;D@EGsAbjGMYnn|{hAJ#9U(xg+bO4Q#%OoeG3X6!6vjjnv zD2cXRQiM~oi;4>>206h3RvEW#>7h!h=Nm@|6N0F3{1jrcw&}{*z<@FYLD^Y&A&8C$q{OPutmvRJ>r(KMl^lT=f0I<|ei_bAwI zL=-E%x6vBjNZM$Q!Ha#Y%v>j1^^!zcl+#{s+Pa6qJRdXsH!z(6aZDlOxuWAL(Y^Ll#&u9kmsp0I$f7@znH{!ef?V7g~Ep;)FjS=G#tr6O5`#r zC_6#y?0{Zn*3l(i>q4dw^V{Sz6LrM+T*vf}{TIl`fshm9HZkA6{kz2^fWXD%0B#BL za#3@%mavxamf-pOk*SDnpAV7s1Pr?I<_7KnWw={~ZTHR{a#6l=?*;Gj6)Ojx?mWwC zAy=}uZ?KI*XP%{)Vi6aZVwv^|oU&m)kv>qd{Lu---W+tcS9hG;?iMCMsr6LGjqD@O z=H;d9g_}bTVO9hh_lE8$iL&eFAD|V@3G9Gsx;+a>l7fGMVC-ARAAQ}R#|4p zIr15=>AhXbfM^itq5_H2hENJ9rWXj8Fs#Kj2ehsM|Gi10X*M_;Rm)BJ>b%#HL+j9d-fDd2CgQXJtg1ilWtYg^Xw1TXl3RQCXs!%k=_Ic zaiUmC@}gy{?kZ08EoKeWEJAXu5oHD!m%A~H9PIGd+C#i*q3`GuPgiE{f?w1{VqLm= z4T4xV_NXSHha~x=GxG#HHCgm0{eZsuv%7)g*p&^RIKNCs~@p zap!b}&&cPyusUcPH*7T(r zX>wert-2xAmwEBE&Y!yG84d`L_r3UDEo)I};8O&-z2+JlugK5oNAjXE86eiN=Au|K z$6MEP8=$Y$@~HVK?j|Y72mUXRhfW`14O%(ktvS;{(Qetf0O78&+`<;C?yszH!Z`%riqlsKIh#*&lvej|s&zAo-Xn68CAmE? zZfg#Y7IF?ym-Kz3mcPBX*K!<qLp)e7h@@0)}~)` z#@{%{q9f{WdCAD%A@%t{<`27-HuSc$;HPs-NX%^YhX{$7O8sj!6Y}ZPJ6pFH9jmj| zMjPVMo9)ph&txnd(E9=Vr^XHouPRnDQNWtgjZvUR*2vIMez_zU)y*}cZq^`B ze0oEt$|O#%Qo>@^DHY0H?iMjc+*M7#b6JOU_T7blMj>0Hj}MJcfNwaX{I}vSlD_nV zT66Np3XhGs<5d4a2e2Qq@uw8uuXyM|d`tzvPYggNr3;T#q>e+daG$*V5zLd`Iogio zFwFK`e9Rd!4Kae5z3kvvlF;@3r;f}?2|Xe z2kAq0O>}=*Ttt2L>z>4N{QLL}i>-%hc~5;|t+=6jito5lLnr!XFh8gdq<_71aO}|j zn4AgBN>NjzjZ+hR#*kIcV;#MlmW2_H~k6x~~)rWh45VPb_w-j;j{wY)OHjNdF z3IJH8K(|0Q`%s)`6tudbIL*lmTfrobPgAa{(l4$W&XLQpV<$S{#&!xw=fU`hYCU?* zBos7Nf(?oh)l_GiqnWba9*Tyh)>mi!NskSRE9D?XjNgF!s~yuT2Ntj#w2#bACA=&2 zpR{??Vtn(Wbg3*wZaVHDac2sw(-t==sptWT9HvZFYUIc`4T24|h$vD33cTv24SoKp zWj_TL^n+XEvtdAF2ao@41s$Y5rb_>&4+elR3xvQDlo2p$E3F%(GP=0AGqJ>X8m2^r zS5UNYv=xamltB)-*c9Rhl}~))s;C1~Y^ov(6NtC=Oj{-!3ubgI9n>82-{~={EiCGc zns5mIieI-B9yF)#Cz7@MIN+w@j<6CTdd$%$p7g`xs~WuIu+eb&k3 zTRWgu%898dkK$Vh*IpXR>bp6~PH;6dt4$p=%EcJOkyzs3>{FJjUDay(&ZxW|TZ3j! z$HM!S^TN==*%+1zXT6z6)?Gv_v4e7L~|lCutxQ&4$p1{sso5JF&-P`Ft~0 zPsq#r^?Uu*b%{}Uqn!jWqDlxBMnDCj3}}TH2tXm|hnLBgAY>2QRN*tE1OFWlaq-e$ zo1)#kplZ{HJw?1N{4;RV;R3g* zksRQ;M?qM9``YzIa+wHL*o6~Og~U@EvE~o{LeY`K08^-Evg*WlrxAL(&rg354d<`_ z(EA;7Ex*|mRQl%VyPL>(ZX+b@l8(*lTW)Gpsq{XX^JYGgeKzK*K`j{p>y>Y8^~`^$ zBy_-Vw%7YLw+iB9VTSHPREDBc=Tqf)euP*jj&wSjEMH2wo(zx_<*GDVTYsG}&0AMO zLVhZVwRDx`fw@a3^Y^m~bA%4b=F>gM7A&Jgz2UFk2g{KzswBq$2F(M9fVPs25N@jp&TAKx|cn5@SCx#P*=G}o@o-{q(vMT z7T!uwqmGpsaxlX{!)FejzBYSc{)h7()& zXoR67Rr+cELgBsa=5%drS!hRJ{THI`6#xGke-dG1x@c+TQ=vmu(1f~d4#)yzp>ZU6 zs4kJ?9H$=Wb@VuRUt(qnE|p zDDVODd>JAg$`v2>)JQQwYF4cRnQYk(j05}vU3W2DeZvb&aZm*lN>ROJuayQznVG4o zo7FIayIC`$Str)@p2=%GcRIGdoUul6U{|k7+YB4CMPwj@c6^2S1i_(qRjSQamk#_M zUSXF(DnUqh3SiXsUG*C3YQ2Lxf=#6x%P-8HIes!DkSir&yv9j~6-$!-$8CYhBQ2N8 zYNm}?r3Hexw38M-5Vb~hGh@s}b@O4wkgJkviesnZnVu}h6k`}OjNe82h-kIAAy@8E zfj7k|HA~eXVVVw)U+IExT)IE+SEWXTy=)(VbLbK$?# zt&A~-09yE}N7%x!g0584`@I~woJ}zatxrFVvY7P%Z3#wL^n$$VT71#X(@SeecDYmo zWl8vJu6WNLf^%;6QPyqE$;X2EJnZlTU35@OVm4PxNaK6kIwF+@dnlB00E^lKOnwCC zs`#+`dn#dRa6U*STpPw@D1`s>0_;o#y88c^axJQ#5^lZt)FnNi1$ydLPK_;h?cY=% zIUMOOb9onVZd){;3vtZw^Nd!cl z-tQV?r>cF&b<~fu{T*z~{ReN;z=&r8?f?zX0B6)WRP*KD)U*a7o=#4DH7%PF4 zUV5f$V)OD|QCvmdz}aSK@?P-ZRffZl-9n8C(-vx{wd7X%RKPzlcdxUHXZ#)Q1`DhQ z1*8E};&kOeaW0_hZ@-zR&PPG>_wdch`0^umf6z#y0GF{6OOxGAgWwwx=cc! z4>+f6L8PXKv2GWByf3;H>!qk_nS+OLEHI|iU$j#ckO)KBHCW(NM`PIbZX9?>--Icj zMA{a2d9)ZFWu!{fy_Ysys$=!#{@!s2$b`@~~OodM|%ICHD*+^N7 z>tTX|qc$LCep{%9=oLxZYM<+#oJW11P+n3<{fm1YmddULYT8=bTZ1KC>Arm$i5!;qS~gapl2+641#+2AP%-p7g>?^;KY_CqF^@WM|Apc|yVmR^SJ7G8PIULsy{odz>q-QgPlE2uyBA}amw=YRVL6~Xd2 z*EWUxNo=R;5Kk1FxFZyiwjPsRaZ{^hq7>(KixCa>GP7J~T&O!_1q-Dro8$-6Ygu1S zkx501Ok`FSNFrcI#3*aMX0^&IFT#=tK|aJS#Ymye*UvWy#kaKhe^w8S8aJ0-GF&FTV!!3r;-a zB-=cb;yS(k>U^w~Zb-q$6a#iut5E3ycJVmzI3yu0x`RP|wZ!B=FcP5#2aG9$S)j89 z0WF0*H<+qcZn12zG&LOJIGuNf;glOPXTRzXw?9yFhcPKIlI4XWk=wwNi}a1 zMV^4;>!JCG*-n>*CcSF|WQmXV4w$t0m70H5Mo5GqH?L zeqf>m{l-LeaLYc5&5Ef8O5x5xyrz3xWii_ash%wA)pXP!Rfm_nom$@PcI*^>$fnPg z^qojT^tzajT3m<-_+z$%=L5fUl?EY30^9h)JX|42%Z`AgRtl|?zLQ?JKL~B znuK@ufu7d{cN;Yq7KpabyRTHsEgVv9>XxByR;>$$1rhfarZlH(8)Zjc{Tf1@U;@S2AvaZ+@>_E2#+qpeve{dh<`tsNl< zoTT!FK8PE<>B8Q%L=nLldA_tkwGx^ShaGZDLtZSeA=rh^hqbi3b`3HOCHbeLu=a#J zk!`PYuL*Jcti*8|KZ;?Vza>D|2y#M=1U3gIqqUFN@Ml!E8i zA(xRio-d9hzu!qeM2Zvkz5EbqOMV*!crq166lCZ%gjRx)z|U1kx%Uas*AjaBI$Fna zC|8P{s=LXy_s~bX1-g;3VxupYngVw09d|ah8A(OH>C#`MF$f~~!WiorNxO@!Urd&f z5b)mm2M_*$6zE4VrlCSB5DM$LHMh*>6^6 zi(Db;RyB}-)C1hPTs8|dWEdf=6p&YA?eBWvKcNQ@QcQU`AHbX&csPH@gr@PMa5|tZ zw_Y<_MlGd>tbP<>1>};}tKVYJ=rI0}2XD~ad#q)^ivJK}DD>9%9ZdCwPpR3a=Ru z@1oZYw1-f})?{X0iTRzjacT!9XF_w}CiaB7J8qwpsNxBv936;&FB+MX75N?AZeibJEy=Kag1kXF z0#vpQAlyt`kd-lS`Rc^Sl$4Qa@<+N<;{4YhgVL^#))G%R(YH&6oh^Uw;_n^v^FB7U ze_FtUksl;xSDY6W+?k!xd2*}YCEp6ij>E5pyL)4}d&gl!I}tnB|BgWnm19a{2g7V@ zSp->sP>h_BFT8D{ysymK4H8SyWA6~x>$HETQXS8cYVo1r`wXRW(rU<59LvL474JlD zQ+Bo9D=`ELUZoueN~Y1NJC)*k(HVi&b)}y972<^wc+K$VHAJq zDGte&4ct|Vd&toqH%b{UxFA0@I|x|=?FeQBek!1)tX2??QXBOXg-%jv`icA|2KRUi&v(f8 zR9?&hq;m@n0o~Tr9WXEAOPj2Ye5uJPmJ0l>Wd~bLzND}5Wcky6ZX@ewyb+`F)GBdg zmwsS>A(oS!%Tk|9?KN&f>-&G}Tbhu~L>-PG3W*FwdBP{i$bf_WdVwW##H4G{H6v>O zeiMBTx2j4!J^4cK1$e5#F&eu?p6VKH{7HRiXGWvaqgPc+Wk0DtA&&z^Yi;B zHsy2e?u-t6uyha>G`#6>d9jfKZb#(po~fLc`iv1RdQ{Zu_G5esg&<%c*cn={(zcVw z{Az{%tsYl%5z`n&u}QlFHP;Jn)YypdYOgS}nSiEqtXar9K91P_rR8A<*b`l6{iL_u z^l?2|v}Zb@nkYb3Q~gOy_z;_DVP@IQ_bRjsRL9L>CHmI7b#?!U&l$}@*=t>%tsE8} zzt!-%#)BV6`g@PR1+PVeshM)6Y_et*60@@Jbb?&Iu*+`0s(CT>iQ@aXi43` z0|uCbx8`#ymZ6j9u^n_EV82Zo)Y%Q$fYP1Z&5CD0z0)Q5hA)=7?sl*$^U6$#&A%Z3 zQPrPO_Kz5NaGMwIeZN6HV$Gi2RNqmb>dF?vY8_CzQVv1g;m%<~YA{`rUgIc3_CiCQ z-;B0vUS--ou=)Pj63D{6mjRhllK4D|@zt(9Wtg3p`ZKBD!p3dxWrwMI*%bbK_29gn zM(?P26=#}+4Z^$iI}>~O?R_>Yy>UTyOvTUv3_}%!(3%#~r+==BXbJHJa6`zXEBx^)MN#ZXRz1XV3-_;Qk0W5Hq-;H9O0LWjziIT`3Cl8F1n0 zUFB68ha1sF8p1MA=&Sy_C)V1r_H?}X?0ZGCYPzYq0W}qKsf!n;+7x~6tf$iLi0e;; zB$9*v5PnA-aeG40=*nUghvZTI=H&zmzpHdk{STo0auSDCHYkS*ixCwpp{zk{5m*uq zBWA^Q?%^y6#3{?BC-nF09E=@qb>Cu}--R9@HWHKtyPLWy7S`;g?9F3zRKOOlFsHUx z+8+OvUEw!FdPe8P>atw!KIXZ)nX6CE9J01s__JsBrH0p##C5>5k#_<_OtWH9TobiG z-V$ZOGk0HUR;8=|5%17Zb4LC5Bn@!)a%4d;oc$cFqI*07vJTk^6h76jy}i2a?m7D zMr2XkWO877K_3xd=%AwLTE8&lBSS2wSy#{_V^Ss40S$(-EDOcjY}kZqx_JLB%e88Wwd!3uu-jHZCe~}o6jBE3M{+oXQQ`_a6 zzjthk-o4?|Hw_SiDr7jUCovYk{wUBQ6hE0?gCFjQovWZ>BZ`(k&^wtn^z%yL=MSb! zHame{$?rqulD)7l8OC7M$`qs6;u424yp@Y^HRvM~H6hI8bAgrkUSljw>LP@0G;yh2 zi!;Uzxqf)FKnW>vrOmiS%!JP1qMU3k_0nSLR1~j@a)!~`7Ul8P+C+oC1ktX{L363K z|3uAZYerIpbgCP8i?*zjtwG44CfCon@&uYFve{aWAahY;>7p-pe%hPh=!i~ zz&(?NelQydsaFxaHHz4fC93Ili_RkqQUNLTD5hJzR2ls>I4Q16<36(l$xrvc;-K;j9< zs>h^Ou_mGZ$9_LQKpYO4>`TZrFClWkGB4>>2E8l%14f;A)aK&LLJX7QEg9k4$VS>{ z%Em}`J@lUNe=Dz>dA79&H;yw|_7}w#LBUAZ6*>vsL2CIFM*S-QJ0wKa2Scw-9>atu;n%zGV)?bUHjJ34Mn0c_Q-n>WIJ*f zYRU1@{i^qk+z)s4C&+GShP$GbxEe-=9Y3X%Jn{~H_8w$M#U^J@6Ior0{d+~+usVW! zu8D{{v^Vsvjv=yaWjy@$pxZJAM4l@JO+uf+d{l_C%v)njgMjKP0*E(8gc0{%yVCXG zqKLnA!~-+7K=5%)g5$^BQ;Vt>M9Iy+-!A+U@M!$dezO!e6nBWve8n(D!f+?_RMSE5 z`lnl=ZN59YJK*(N;*xC6mW&7cjeXbtf&Kf=iC|*tuuS%_*P%;dkDuRFAxB>Plj!1$~W*T0~o9DBKdX@Ln*Hh$cJG7*&Sk#U-Tq;5<>zu( z!o}xu8_Ig=#z-BE=Lo&k1DD6$|LjK=`;v2)v3~ZNyG-njNVIz3Uo~O{z$d=bYvBaCpb27GWK<7w^#I`IPSML&hIU!%RepSV-9&O%lxUPUBXOj(a!1lYgl7_EGEG0 ziyw_lR3X;`>tCp`TbD9C&~-;}eNP4Fem-Ne$v)|86N3+&z7Ns>w4#W58;4=THPlY6 zt_Q;~n6rBiG;}zP3fBc5aXuQZ9ViJ3J)k_A(Ch64%Qn4QbN{S081x3;2$RI2S#Y5c zDRF)Mz=Rf>ACd{5#{qktF}*L;30&1igB+kCAO~btR7**&GvKuQ)Qc8z97K%tqKWkK z%MiuDW3b%Q;O_ir&SmW(-yI(Ep%j`39lNL;TZmWYdZ;J--UjjS@{1LV6-%ZNHb%Jb zl_pzZ{?aO)FNb4jiO|dvrM0M0i33|IN{cv6L>h<@YzA;qn*NGZbws5zp=TYGmj^0+ z13v6^qFU?+!w#hgd{CB1ED|#*ilhbUG$Ql@^WS$m(6_M+a%wvMvMsQvq(f^u>^s1} zzK8KMNA?SF;pw~(#Qpayjyi5nNO>ubWApA8f9ZSCN-vur9WX!B3iroK9vkNCC);S2 z8wFoCXy6zN0;~aQCc9PY8h(gY3-^%Gk8Yz#QzN7Fo)&-7e=p|Z6(NT6|D5a*NST-BtXixh z!rEzKG;8Re(mm1ulNAtUq+CA1bj-98Z5!UI#Wl9#oPhK7-rQ{a45~RL89E?3lEox> zxntvGAI}Y+00)o2<&*f(PrfA+EXy5nCe;=0>hlF8Y1mNHx*#c(WUay}UdE+Zi-&|= zi#rM$4UGyOQ@^bRsEWIS4F@3#pm}Exf|yW&EDYvD%0o z><5CdqzEpt(0Obs?Bg3x?B;Wp+%CSp$S<*IX2-A2_`Ejr*h7&y3@vXzF6Bfxw6y%*wyZ<~+e`z>!d z>70@VuGiq>1~id3LF)#Nch6ma(zs5A-l&*?f)=z#uw+*T@B_>n27+&Y59Dq$c);t_ zkth7h=i{tf?|FVm&^F~T#N~o=i{IY)$)_x%wv#fXnfJ-o8d*S4FT^?K!3j+dwt-{b zk`zW6`iycdWqXyn)1I^AY2k(Yhhlrp-f%DV&g?qb3fzh;n^CELCsg)c+!!SVcP2IG&k+Ufnc&n`6J_oRYl zBiI*=OypL5WfymKbM>$<R%wn~PWl?<;joJ*pYR*(>h!?G+R) zZS_lZ&m*~>1<+ieMKBrcuWOR`C#0VF?Ews9>-S|z3Oml*<4!LpW84m`Bu&RwZ%(eyu zpY@&T)u~;+3wmproAPmI6XbrX=+gCl5t`+NaMj>Rw!)w1n#3pvrfaUNex+H~5uZf-fD#KiPUv?()yHz-yds)% zzSfA;=jXs;#bzyBBPjt!Tk2bO;V@&`wl}of3_o9IhDEhut(jsi-#+En^~n ziY$kF8!d7^aDL1aZK%8|w>j;~)9<=wWbj?ei0XbxsiJ)81$-0#!l_Y_2N!^7d^W!6 z>O*K_dMgy==J+`WY7T*-`WO(hu9oT-TC6zbAeAzBgx!V>6_pS?%&Fs~NEiDl zuVfH=WaoQ}sOXHzhmCsU0PU{4Le~V)5P!!s;nU-PQP(zWs|E$E6G?RSYoydwI!7`` z((g-qsYN|YCsTz+Sj{b$mKz~CTA3D5E69}XJsVpRo0S)W0udqDbm71AnFb>Njp41l zi9(klUhtU;iLT(GVDNvx9vy;&fNEfoNm=$I^+yoch4pB>v|BBgXz26T0VsD42BuJv zUlem#isQ$D?r`;2OV?i(rT$*?iji*rNfjzf?b1q*|Ctpp+Z1K8*nYQHC1R`a`;A^lj_=0;OaS0}lmvw@ z^1jK_{bmv#DQ)hfI71jS{;)y53O);EJPp2Wh1VCdPg3^GSsj)*HPc|}e%e+{>ADDQ z2j>FwT=K9pDYwmoo>|*i(z8Q(5Qfx;k|7=N&^WS3Z%WEbCKkOAvsPDy}O@?TFq=_;lrs9QpM&1efd7P#y)kt2t{&@SRqU%hm5oqbOoxer(Fj0QSISry@XaZ8WrMbKQZBxQVh}dOItSloQ;^4 z1v+Xldp_mokLJ^%?Hs30Tjm;suz(FLukj^6ay96ZT8xiID;0y^Nzn=|XAtizQY^_S zd12DY#dwc7a}e=YE0gk8WTKe1ho4yJnbzpnalhl%RR_Wm?WCqax9BYBkNuIjsR~Bdmx7Y4@z1{gZRXq3f=U6>5 zSUgbkoOc4*aBJM#%#l1aYaBzmAVEiAuWEPZo!%jAB3aqCs?QRe&s!&SVWW4h<*?HN&oc3jGYzNAg5NEydlfBtM9 zo8*u=uc?DMLrDSu3P+!_>cRV&e!rFOtgdHwZBBNh8@jb=(xtqA;ur5TK-B%hBkZCt zMev)Dlj!N#$#Waw6V@yI6q>JxMVQFr#LL`|m1U3Og*$L8Hfj^vHX|gQmq6VL7saJt zyh3N~cy2_tpDgaK&ZLa?O&$b-!_iOc>_^hd+=$8kqr8g^QR>gd(Xa$(odD(tNP{ZyMg)Rc; z_qf7!K9ui0_;BVjGw(b8y=NiTPkk3%!3TMbpA02Td+L#80Mbd3pT&v@D-F07S31%N^#IZA=-}4f zH=<#OUVi^-$uvTJQAeV-Uuf4HN<%n?wF!(rToV`v-{e4I(RWEZru%$$k60yaVkIsk zF6&dE&X~F|0P28-L_}Zt+W6YU4dCrd(XqE|*tEvj=9-`}DvnlFw^TXMhfbuG-=}fF zI02+aX`Dj9HFMkaS|+THDf7Voj)X~A56-*1TW;tk1aFb%_gK;MD|}5?p~X`KP1(c zAVGH5;VeF~qQ@y^KuVBqJ0YIndVCm@8S!r@w@m?ZVL|>REfSLJ+eGjbkpbrF`!U(y z-haeqpvDI6IA@n)QFAcpY4yu}JtvW7?tRaR#_gh|v%q{*QTmQR{Zoe%m&^x##{wST zTi?ER@S_x|uEQnVRXtyScgNEpJ)7F~vss%KLST3>VIM%)RJM2056%=gTYuNL(`PozW!}NAYOCLt!RXrnJybbj$p2s zp3Y{fvgzF$-O~@8jFuZ^KPUlOzDt_!Ajgi>Q+`Vnef%RO^55^{#VNRJ?(bXD2MFS# z#VKascaV)-jOis!P;p%pH!>>5X31a)(y)d}|5C&}yeCp1VTLanHc}%ZnntRZ!W+*H zAbt0V?e7UzgDz&xm-nGE*SsIwIlXm94uqW2cB}7yNL3-l306M(#- zmgYV{w$shWx_up*?l?~{xjIM?Yb(O!ufs)*W%RHSWZsjr>J?W_4~ZeoRN}&fQL1B0 zat8>TKz8HK(H-zi$4#>ycu14w{s=zsKz@llAOn7T_35&o1vFD(x9TxzcnW`nODDP` zK!!>?n#`HMHIThe8=buvf3h=5n2glh^?hk6yPUOS5v9t-50M7bVvOT2Eh$+PbSFLx znUEe(0Czn$4r#8*+Gm8#O9WSG;Jr!P*B?{O_bC(Ze!j^8&I%6{zjY8O8}Qga4p%x7-v;LM{`N$Ew`rtlR- zxCVPDLZm`$j{wJ7M#f&w*@}z|s%q!+p8$EZ2NJRm+eHy^M!u-`NKR-yxbv_jK|HAb zkr&?x9JPa*o1TR%O$A7_t^WvrojKws%C=JOgQ}}3D-JIIh8z_CE;`o{JOMoF__7$F zHII+&4{#Pa=M(K-r%(oFC#u$xE1JkW&Jp%64)juog?ZZ3gzKAAz;_eS_^*NmXc#c* z*!@HAjU%^ZG|Rnq<;~C7PnyR>R=m$_yWor%lW&b=f zTCZ<|y;!I4kFLqRc~$oMJD%sa7)EieG3lTA@uxTv(O?doey>1xJ+{oq=)-ilHqH%1 zW+(5rNagC1_=<1ggX3_5RV)MN12xS$>;^~8X`X#6f0+q6X?@s5?h0^+ zrWAaaR_qqsaTOg-{n`kx1yIArRWF0Zc;Ba-I}mFB$hV9LokB>m!B0O4DPGFmQmKLe zb`ldmkplNE&=u3|RNh@U^~g6c7LFef8`Pp)e>*(!Tj6jJpF|-VUJVuVQ4SW+Xe!_M zWAOsFuaGirFcCbxY{&Cvv!tmMLydlmyTi}gk)+uY` zmts8d&QK|bObSogn3{R4w^(r`gIJ2>J85_Cu9;v&RWxHob@=bi)0DD`S?sxCpB1T4 zfSUofypn{4Fanc^!#GQk23HgZ7(?2U&4l_9=&ar&qt=FuS7QGIIv9fx?J1B`@`JiS z8UAReG^qr=Xd;sTtkk1WxhL!U{in$pza@&^1$RuKBJ3Ih=02`(<^-Qi>oGHEFK+WA)l+-)LVcw7NsYFO0 zSuXDeE9ljYZ*NR+oeh=>LpFn*#hlB;2)zxT{EbPD?fhLH^?*YwWYrMEcuC64N^lZk z@gb$UC@&RU(3p@U+7&#`vC5-|{T%r6#lMTtG*o&y##Mic-N1(+8Qm@w&^5yM-I z0TX_f6cEBcT=N?v#SO6^gz5$L_`YYzGBYZ~mU2D#C)2V_%*U16w22mHeH)?sg@>Zf zM*zn$Q7WNcVv@md_FZ3GR80X+Vq_4w@z!f-ITkxFQH_!c=*?^gd;LYzy~jr8Pn zC$XP=+CSM7a1+D5;G z(vkscR+{#-*kMTrvG=DFh6FqJ^Trl%!8xrM;j)LavjBP6t&IPCh&82lM16Wc2yv5Y zku-SoLJH$w)ide9ah8Hc@=Sfqp(dnEefnUlJ>Q;3>YnH3cLyI1MBTOzCi=ha9nx16 z3FPw3vpmIGb>7*HpopUpp=Dwzk!I>)X7gZ2Sw_vv4I&Sq>+c;T^g2tj2^>qi`4p)Y zUk`56xlp9icVwWkx5{D>;Nq=qh+lmE45e$gWQS}I0SsYP=ciItCU5y!gBcB(%iD@; zI&j*kkOIw9$8iwBs1vs;=u%3!jEpzDc-{#ew2bf);VN9P9{IPUBtSZQ6s$~{0ARQM zDvSeGhyqwek6jV~$aNc5#~p^wOMlu>g~{mYlkirpe3#?STCj+<2hQ^@P)??DiJA~! z%{M;<)^}^;l$bYU@Ro;i8e}himbc_`(8=j1k1YR3m?$C(e4@I02LQJ;b6PHNKM5se zI{P?tAXW=Ejq;~CVpNf$lW3kQ2377X8apNR$4o3xv_!V9?{J-S50+b(PTEd*x}*3% ztoqp55%P#&XAIdb_f@Fw#KKcxFQ@mTWGwsx5@Jo0_U2Ft z(2|@6Z7an@=S(pd^LsT zH$x~QtzKg^KHd%R-``;I@y+0N{9XIXXU~j#Z`s|~4Iu+}XSgWO%XDXrRneWVo0iwk zgaMXYJwp(^pb1M%_3Z@l1mRc+I&OjH@-DsqD9Ef~9G*RS z1g%4(M2KYLzIt!+|0xRB;NH8>hA=yyK;58@{woWT56(Lmtcw9ZNS0gfv>Ve~#s!;$7+3n?dcxoP z;IQuE7V^x5hh)asiKhM<13lp;4CS;AEVH(-H3y|de-C;y=IfmY-({FC9QVK>&wjL%a>?S#5m%W%5L zIz3})C8GB^IS6a;6ZD-qR~-semMrEm_OGsGIoV$s(f~KN2EPPK$86--kC1K(HAHEo zDV`8g5yP&z>pdKhk07;Pu8L7h!9;epkJ_CtF=Nr(Xw`yR>c zgWzlxm_4vg4gm@!3;0qKl})LciilqRZ7>N}GO-$IC=qW@oPB27*#Ig$e~=G*FWlUW zg61m@x{-QTf`mHpPLw#Cc)qlj6K8to4_rYCx!Do`WB?iXlNd}77YCLD>maoPsX2S_ zsjSZjR4g3q+5V8s!VfvIOiCtNa#DB=!f-rA}va-^;Pi34%u43j4g5O~oEC=YN zbG*vT)QQxQkEB|ZkixaB*t8VCpudBbhBvkDa!NNc6GlM=gyjHl*euv8LMiq$x`7_> z2y_6&&qUkn9cewkwKgCpynp72j(lXoyMDlgQMFasjwx$6sgV99h6Ii;4c6XV|0Kmj z33mX7p&B?T?kNSU_D2wgkPe=Mi6L9=jKIX;R+tdpK{;UD;G%6>IJ#|7KW&;RXD%&d zphYC@9+_<)Twj4Q=aQUMCxX!0Y;N*Y(&RK@2>v{GniXj$XzDW_XZ3;S zcgi%n)23L)4uu4beknkuq@T{$wv4O&oO-^Ut0>btlV4UQq}u4W{)WF>v5AE28bZT@ zOM1Z4cpzCQw9w${7!}+-l5~!uj|E0Wh|_V~*-;Wy8`=G>{j-j_u5qg}0VFswYm9FU zCv9p+uyXDHu=Q4PQFh__u+rTP(%muifHcw|NQ1y2-Q8V7cXtR#OCv}R-5^~v3Mefg z4gcZYd;h+Z?~DWHVe!mb>$uy5Vh?_rbnQdLAn!-@9AYX{EXcQ_|oZTxnQV=gS zn%%?naDMjpgLWxc3cBocxUneOj%Um{lp0uQuc115D8vC1$Pyy9<(9(QaWT3$BmR1h z9|&piB;ue-m|psnHGh%P01WB-zOauw_BNvUW0AHJP1-MJK3&*0pPU|mY$BhaSPFUZ z0_yqaE<)BV*jTQ2a8^e+(I$|BJ9Hwe%wDsa>V9+vHQbBFG)8n7HRU+q6Zzz#>@ps& zO|4$t_j^ujD`BL6d>?KHSU|s1gj>OoGEqH3(Kf+>9z&l1T`ZxBwa!qWH{ zFUHRg%rn%)>Mx)Q;dwth_^^F%$=uD~BE~EuHRQSyzyz7PDW?80aD)abwrq*EjYofv zig!fGlW_2Y2!YimbA(7I58khB_f-bslqDcIN{-~%Fnf5WMW$wVw7r7sUequ{0I7nV zf+@7NU%c6z!1kMnTjD~EXOIWn8*6QSh#gWNdL%1isx5j72UofRTXSVFbj9Gi5cu?0 za7NQH97PTS10mXmSv%mP zI&GgeLD%ayZqD0oUr%G62w*{g88i|?Q}nl@KJ9@)oo$YSUr(!oUd6xZ9trX{XlFno zfAsuVf$0@0P(E?CGfiUoBETj1GER$M+hulR2N_KYm2%&DxT1 zIir5M_BrtnJ_^+3(%r!kJps%(A}u_+nf?C=dDJfxR2Q-w`iy+W{KWck`nfrM?~91k zRQ!ENCa07d)Hb{l_vEX4mZLvuga+9L#5iQX`wT2o*xQ?~nZMNcKU6IRVfVVX_zju# zgSDtStvaI%)ad$b&Cb#Jy0<*_K~&Pba2>fw;CvOJsTXD{S43VG;T|X`ouy6HD1q!j zx5m51SsPivcaS^>!Ezh~dDP2=&yN1F*45ChHJ`-#wjb6@Dq%%Zw6)&RShb);(N;gknN5NkI<3io61u(GrJ_zb9YQ;am6 zsmkE;O$G!$WKY#5KHLN{u9$=v=5Q-2N;L-p2YMSN%A8Y2Ui8aUyDPN7CMUUQa+B!= z!HmkX?wrDvCzCfX29Yc>g)#w!E8NV)&czn;wQ*C3lVd39)%mt_{3z8fmnABOCxP-N z#>v@(X*TEjvNq$afAp96HC=}8l8ZY+(HT_RDgdJcTpU>>bU=Wm{4oB5VypZLon(4%-&F5J6T*hclx$UYQfp!*#;y*GYzL73Tme|9vTz#Z4kVZ6`5 z=-r`}st=zi4?IVSR5(`0bU9Sq_rG4s=)luq~i@Ha?27_RuiAh$AZ};>Y+m)c2?DlEyyouc~I?biCn3N0?S#%#dt? zG>&2`uyYa6#;6v`L#!iKW^9gM4=GM>e5ap+0kcC-;sV$i#{+pSARRz$E3ENsAwG7p zk!%?(cFuvsTt27-;WQunOd~lVHH3ig=Nm$0vUXtj;GnA9U>yAaG}!#_d#up;Rh$W2 zGT@CMt|DF(sZyPqwnxiim%+D5z(qO8_zhY@G9R@_`$LY{muLSojd742y-?`TkJJ{>7>cyw;*(sP8N0`Q-7X@8G@s&y<>I ziIES}SVnHhaFWeewuBmLT@%LIouO&0se9SxT3kRo?__qPU7$S;RU9@6f zp>-CpNE-(V11`8Oc8I~$V%d*xTl^tS&Yps5PWd2-lXI4u!~@p;ZO(5yyAsm^;cUCcC2)krw z&~k7ZN+kwV2P;)y!ct-5Z}axKT3h^?UM7)(?&xQBd1wp@0xmj?+E{&kZ=st6}bHKM8(bRWgPK*(oE zc~4MJ7$%23U&Finv8P`cV<|nKt$OPS=k3pY+6bEqK64T>9S44LC5!1-@83ta0)o|MaS} zf;&aq0x;aRhjhrV+_-nL%s~#CC7pQF7x<=)r(mAdG(D%oAMoI{?yAqgW?y*BHY3@e zppRz-EGN6s29(_|83u|jG`c-9AD-`TVLrTev63P=zq{kb8BZ9qkAvfRoj3kJb*{ts zLKglggM4>WN=_1yUAKo_(8rdNiY@n@kd2&~b0v;O%$3M<@;)RUF%b*syTiErj*b1O zo|!MmGzf3edn1Q~a2qg8Rd$Bjy;f_o-2Ll`UJ&=L!(94isDZ$)CkpR5J5nPVcFW?m zHuh_4?|K5RV`;MP3Xrwub(oxy59I%Tbw&uzn)FdDlynDV&&5{CLr4bJE=UIM3|;X) zWJyQMi6=H!YaJLA4>Gl6?TOrvc&{E1Z?BH#?!VOH6HRmre=Y4pi4GZNmd_^t(2vTn z0!USxQq>%n=~c+VqGiUVPDR{ZhN%e=K0GCSj4N?G`DX1T+9;IpCX+b$Crh$wIQ-) z@ey5uwrp!m1;W_~tt9In@+FM#NbVeR10c&sn-O}tAM#iP9)1jcG58PFj0$`Ts=r~7 zSB3cQ@s@(^lIBti@l|0da1V5B;^Jcr97tY3r&i}hlek2>va0nqpY{n9O2VoYwhGi) zt^{pe8T+XF#y2|gnwfXIsaw2qRfmKKpmf8{g(A{N{^<V;gI$RlkyBe0Ptg1F<}(?-X5s0aVWVz z`-R82V^tjAkU?Td!%;w60=bOwRtozS=%A)i1_Cgra2#>^j%=fmtC&Qgn*cir8#^0I zOM%MNrW(OrPe~u6N=)o8$}La5jo;L!L)pd;m`MQ6PVaD!-0)an)WcB z3*$9`5hqb+D*|QQ7QY(rlOqStYg#lL@$Lgowh{@9wq=pjy_di(uvSnxA--l!AlBQwaF_L|h@PWxGg?Q>Xo8uXOShPf z!%TV5DR&-WQ;n0A6&^q+R4*nh%hR-(uhE=cjGQ~PI(Q@8RVr%vQ~CS~_9d6RvSP<( z$i}U4tdeds;=+k=vc4VQ^3>sv22T)@U%n3feZCoYkTw@RmnYzdf^v`$HI#xI$ArlE zwY0aj7sop)>0e z+jpEnCMN%dfht;3aZ6tN7y<#L$Y>7MPJtc-b9^(JrncE~=x;P0P);F2E?3RG#%9uu zqk@yI=!ktv^DtU*?on5MYRv!OTaSP2YO7;w2z#ref9Q&AneY-nNAeHX4i~t6@;npV zK6<_f6R-34z25orvu31)E@#imJ%AH4lNY8i;7cj<`t~qP55IvWak=N_*BS4rf_CL- z#^;WPerU;uVNe74z=M>cR}kHs;2hXbxzKiKw;m(IVY82GT7QB*+JJ>L?R&co0Zvwd z6?Ogn0Lqyn|C>0tuw-gfAJ{?lA~fbGISIog%~;Nq2A+3)`}qVC;VNB${@#>vGnELf z_dhS{;Tt_Ph5}qqmy7p%{r*X|(HxE1jfCg&17ZQBkZlU8vcBDsUI#}#7hy@jOYP&B zyN&b|IYb)L&h*_Dl7{NN+WBkid&U4hRNVGJ zxB=8nwcZHlM7Z(W4DpF7nE@qqLpfZZj7brjB}HC@T=M4(;K$((L=nsf-+tFw@S!S| z=~*WEkP&jn^%&1;HAnBTect0twNTMMiNFcohHZaLAVV_h7Lt1Qc{iBUFnIisChGS2 zyY*!fSuj6vQW!?&jbuzNX21-CW@3Ul#k053sMt$i2WdY3L@r3r1-PTs#k-HtO51Bqrf+G#|lF0Bn zpPE--jmb3qrdrfAKZIZ zS=ib7XH_t_QN2B~laIUn5Kw-&IPA`{YN&?wm}tyRV(@XRDQ4P&~#Uc70T-WnN`m~@LaAAtFJaEek-*+A0 z!eVEhd7$e7K_SWM`^Uw|Y4@yRmiT^gJ<=TS1kyaL+&~J4u(=o;t9pfE^M0df((yio2&ws6sSczZBr>@e?G4gwkPE6O3(hJ{l-D|HU@uI~s zY&rk@i+guZ>SY}q=sY*nwW%ozY_4YC3H_kQt|c~X?}d48}+_Clt}WTF7#^kf#3Z# z@!`S*Fqi@}NMN7w4qck~kt~q;F7Pf}^p0cltswkQx4Vbh zD=vu;lK_RpU#e%^DXZo<=eh_yu*K^MqFGry_J8E?cy`=D=3Ml_g+dW<6It=pj+jS* zJ_Q#77lkvgYxCGj>NSh$m8#B4x8gB?zp9h#2jVfnVuXj5I%bOq84~na_uwy-GtsH2vJR+tU9e7{jn{F*EvjV!s422*Dy;w!u8V5iLAKUDo1cm(- z#wMlNgLo2O3Uqs}sYzTYzJb16$7O2NyAA+AW)>!wq;Wt=Ue1GZq#&vKueY3FTb8hq zTro|KBXg_Bh;l?E+J)lnp+QJ>yMMg^xm#(;NBLVV;7Gv*GbMp} zNB;8d-T7$8{2NY;X1n>cI9W^mwNsG81%9z6(}1iMp7nmTcQ5}(& zkGY+n!hnVJk`3&9l8G-2DoQk3;1n0sz{WtyPmL(Zx?iB5~)t|~w;k*K-x4dQ|Za5!Lv}tFB_KdU)TCE@- z4cvGZ6ZjyCAW)H0?~U;FUHxso&h|>)|5hF9)s)DF`=9~G1>sl!9;EUJM)r~6z5NKx z<0b9R7Fr2VQlGqNgkaw2_t!0i!5eqIp zpl(eBp6_~rke6g!q1P+$$L#a7ev^OA6HPQJ9PkLWp))ijUJ>=*@?osj~UXr_m z6c!}Y>xgm=im#l!>4#mfe9N*vB(;7a=)O)@XG-oHu{Vt7-D!C7kEW0t@-qSQw?-W9 zm$tJ%9Q!JnBxP^7b3+l%k_dRjV3jCu?;B-oGQ)k33px-xh+SgR$apNJ#Yr)Va|EwH z;z128#X8Hq_yvH4)_;p&mc|!x#@sJ;^-oqcCAK`1*=r~Dq=hLd6^i2d@qot-tXU?J z!(z2rlzjXawrq}~%{#&_U3(*!)@0-lJFFUibvQ|McQ@hr;!YwNj#yP^;jfoIzXJx1 z=I!~+tIv-u%!%iYgb2U^E1cC67{?~=e)a3BRlnG+LI434d?vaUSn27mVs=Cg)bJ&2 z>qwm7)?x-=!~Wc7Bjdn)nM3mLN@6y_X5>H9X$#^r5#LT{tZRrS&$sGR12B&h&UJNw zELbRTG#bo0nA5}^iZi2wYK6iDwhrDMilGpIhDgcM81NTG!n_B88mN)>m@`WiL85}3 zCPhH?y?xrKDKa7~^e8T*KUjH@>!w%~SmL0SK^G`l;WQuBa^L^38@V4s`;pYqO)e_u zRDbEsM}|SL_=~-SX1v*oy*QYm?0*etIl}*oy-ma5$%D7%4(bGL7;V{eb{OsGaScY< zMdd&#eUIa|#+|h^@*y;_f;qvAvO{t4x?s_NEO1?pmh;3jNy~(_jABL%H{-?ZBGSp# z`X$l28dwqMHYxE@g*CQLmFJ4|Hchs?gg65E8~(f|1`o;JWYrooj;V80nE@^eNDGtA~-zL&;m; z+Xa0W5kR8r*JNiTW5!MxjX?VCj`+8_>Qz*aHEZbZd%o^;w3q(v^#EKdT{Yyz>=))k zFyA(>)yvC>P)4G0+?^cb(y6)alwSLmMIm-=3Yr|V+oB*p@W?kjoQc+-@B8+66WLR@;MgINFL-Ygka``RZKquyTj4qGk(_d=dk^Gejjc~< z6CElk#FNX3U-(W}89{IYTqP)IH!Y)@i_W}9PLG|0*HY=ITd5+;h_|`-n~b7@r7#?h z9;*oL^sh;5oATb#V9G10O$zVM$mumRBjxO{=O!uE6E#Pzxc7r{%x#-|e+%v9-Kdqe z&@M!RmH>KHIZ~BOEp>}w#qY|qq1z$u4$Aj*YPt69Mhk}udxs7RNXIA=VP2@4lG$S( z=wgHi@rOTaieAuaawQQI?OUHRMKSsj(V@)7RB0A5UjZJ%iF92fuLS1LGgj&u?pptR zyg1_%OxZ`-5sQTF8iv1#n1Eb<;xChhzS$}7S8~oDa-Yv|;h%1(<^FHEN-V$MK_OqB zaPNtv|9yxK(?wHow8nED^O*n(f9lTh*|MwN@c?*#l#ESSl-T$=ln|DO1_PiSmOD4o zYC^%=JDZp}v-0#bC@-LsL*O+@p*o2h`n~X0K@>5Wg7hpt;7j65lK1=R-}T;%>>4y4YqI&JP+2P$^BY%XH; zH(K}Y@YMFv1Ra|CUyM8K{;}E?xVz^6Q?&BwTc*F!OF85=BHQ<@kX_?C`MiakPffko z)jCUE3wSAC45su5V0ahH_Rb9`_LA%RC1v*271QS_srs~C8pjYpeNsdIUvC~WR+bm#k$7yGq z7~^3^W6R#;^veCapDLxY)y);a0~%C}hS9f9c+YLgdnL# zMk5-=w=)w$s`fCc;cih8e=N!BU-TgkygvUbR~)H`fs7%MK8Sk+{Q~IB^e|;t@Ga;+ zo&JUj@+RWni5~h@gGrwTZ=rYLzR`s5ub%0p6S$7c`l%+GghwdPMs0bqo!$`bbD9dp zBEepQc%#|hA|e|aD%g=78dtzgcCHZ1<;d;v((qGd3wIGHZs_yS3KX5W8mH|BPrWJU zcH{_aR-HmdnnEUYzs0>JZMMyDJ!+H+6C1)iK2@a;&moN3)KXQ^#y6ALZSgaQqVr>K zgf(L9FWf^SNYgNqsk6-|3WVk z*VIxoLgfQ8(UIR7e;?t8){VG!|CP|;K)PbDNA!|xWu2me!(hv*4-_u$cZ)Nj`@BKC zz#+`6hXR$hYtdZ7rk+>J`m+Tl9IjlD)`;(Z3aDo|XX+FyX9|)tluM92j=H+Fz;_i( zOU59GCx&74VaOq;u`{Utsg~4-@|^iB>ioI+dT-bB!*%EL{2mXASfzlAnY`6e5Jg#F2;YNk@go-EE@S0+3o7BR6fGVa z5<=+t;1|1J-?%^jd*lDFKzJJCwZytl^L=h-uP=1+X1;iga%#j#l%J#?5g`=*2{M(4 zVzAT>efa~vnpY?1kp2Pq1iu0WGZgufC`no;-{(~o0|Bbwc$K$8S%nQ1M`_#3hcG0& zBB=)pl55IWZuaZZlG3-54dZVY!)$>A$YWeQa_Z z5OipA?25~YC6%Eo!W>C&5XM}TD-|rgUn%P|@kn)AVcK@*QX=-qHY;9-KHGZLMrpOG ztL^70A)9+cP^IiyZRhbN>QsTftMh`Cs3aZF)y3@fcn z3)DuUGJtk{E2k%ce539!KP2Ef+R>5#zI)B)^e?^N?M73oHG#F$V*Iy zSzD+3m2KFe$m+Y9G}SBKk6Ix^0oIdQtTEf%rS#{9gjZyqn+U^z1W|OHhXo9AK-f1z zGUjn1cJIGB%EqJ@-F!2Cchf-n*QY?gFe_vL$hF^|(@GxTYjZa1^H)S|*M}T_vr*FF z`z%>7nBYRo1q^k8b$Y^LMG#bARB9$ zVbrlm+1z8DD2)zrfSy&oj@v11?Po5gI~l=_Vcr+n(Wc5a>lRwWNJj__J-|VTMGVHW z8s7WTJVSu6D5LYR%CDKMtVfMX-7#jUXqJT_+xKO}(^fro9>D2Qsv{Bl8WS9*!2bxV zDu(n2^#=+30WPwuZGs7paM!@+!+#vRhP>tF8@MruM!CZZur^`eO{EE#?Kq{?*vFoD ze^B~cVj*?wTQvfNV5SO|`uS`=POt4oBM63=PwUgN1}HX0|L&@>=O>$Wnst)uiGn(Z zGA@yhzpGO*nip|@P`yu26(pJB ze<)I%X{v}D-S`Yv4T+F1AwW^<>^!=KsCiioc`>`FZ9UnB##b2F%gx<#)C6B)ryYDd9)B}Fr={z2g9mL7QR?#|$2EVr_Yn(%pu`Is zC83`%^#$!{4S~Sq4~&yaxNmEO?4{>@G+huMDajScQhla((EHn9BP)`H^)utbhYIl; zlmV}rXh4BZu~*yOQ-%s%j%7JXPVj2$oM3K4<0I@Ihjyk|?Ti&73%1pP-z|BorB$)i zx6JJGIWhAV>Mz80S`L#%3FZbBqR+WMoH0v&-6gqiPjP_xR0K4$PwJ0INfYA3FE8%7 zz~~Ss(@mnv(5Pa~fGWpL?l}WG3R!`I$lVA>0GJZt`u;Z9%F;X2 zi!JyIJw7&egtW?;a|#pG;f7T8uizY|uZU^^#SN$ZougWplz(`-WDuSLV1Br#y!tZb z{#Ei1SR*rBQwxqPH^cgik#+E;*p$|;yg?SN(Vcam?>)a`JLKgI^nDB8kAM6fJL;{)f7NwNAhY-#XkL2b+DCH!N0xx~_3fFDAYbf(goZjV*^L zNH>$CS^`)kP_3Th!x>z$jZG^GP?pUWRRUZ~_xsOX68P6T-P5cX;|=)tFs#J+6d}f? zPXbvs-ERdC^}1pp%Ge^gs;*U8Ht)mk>T&E;yyt;bfmIf9^`5{u=n=0;h>=9|A1QG%BK&lv4n3_Q9qAo?*SM1lR~S*Y?(jfOBAVl zY;J7d{1tIQgYiOHp)v6cDA9a46Yh+=BB}qV1Yu`^9LHC?>l6RMBZQjHh8~Zsa-&n; zy}-Ijl*D&NMu3C>Or-)w*&xrw7ZmxYawJ@)t5EhH@R?xo@d86!l;8gaS4nB?Ycha7 zsbd8SCBn?i3E^MNl%p|&J}4$UE@=^UH77kQV)p*YfU;>X(Ic#x$1`3CvOd?LvAxP?k|xQR9h8wsH-6#gaJI#=+b z%X3c=(V*_J;>@|G6jzP<$L4Dtm5f4{V}=#Z>)v*S2o3R-%7h3_L>%<-iLU(=-7CE( zK^(!2=99*;RvcjIMq0h$6X< zY!rjOKwe`@%A{`{@76|=Ut*Fhe}OjDhnXRGCU|*C5fAX|9`8?y&Y7qbV;8 zS->mJY&k0LcxSX#j5j^qQK!^~zn5jCh=GK@u=kY2|4=j7X}dG>gij#}e_h7UV{LO8 zWV$F~1DQ+byLt*nv?m>>Fi1%C+Opmp1cH6_@xNPRo>lW?yzHai38Sq;? zHDPS%Afr=TuKOMDn6C4#!p<{kI=-zL#J*$bQU|9!*Ok(ODdnG2J2=_}*tYxlKtFk& zfR|dgHBNyW>`bq8dRrId3c)?e@f;j@DME2hcyB;v zaHl&|B-~}KBUC1*KDlS3cDb-qF9#4T=62W)a{c?ruvzH9?#;^L8L=&JqdjC14~RlE zEw~3{Mcd!@TVIh#u+4mf_Fhn?2%W?70W?@8qGd>9KOCU^qFZz@znwRIOH$lgHn15r zAj1giIVWW?#fKPcm)cI}$R3e^1Y9g8SC@sNS49Yg%8WNRch?4wd7DnRR$P1|$0+Se z8)zQrZ8_)Rax6)SC>MQy>vA2Th8M<%3HDqVZ}VizodZoFUhuN_sM{O)+sI%myw)a$ zbFQ9KQ5<6po$xiBqgQPzK&JD{cBj@shSeXKGGE1o-R0@~{Ta6qyQAO9dQ3Bs4)Q19`P6xCl4w$1>oG%kk8Y2WGX_!K z%ChH?RTFdZ(*Wzw73V^+ta7Kv`&viV^*b<)opPmCcGQ5JI+0XLHH{vXx_POlmf5gn zxQsmPS{2(Dzb9PqtEj@yhPf!4L3wE+Zo`?wf1Amr*Y8? zvVG<0l3CtE&EHVYQG6UKfISaIT3m(@Q6j*156{@pZCthKbmW z#OYGifw>bs`Ziss@To(VP7MM`eWE%S>`BzB0al05ne^H>cJrMBUeGy zp6oNwhqC}jaVF-yJdh-0prgw7yFBEV`){s)5(oe*jJ$Jz1;9@u5C^a)4O@0@O-xzM z>l+@D$V>MY>vuTKfthhb9Quvrk#C#1FzmY0Ibp8-B_hDmx#HJz5oP_wV{+Q#?l!6v zOh^#UPm~{cec7Ae$w%IzG~coP=tc4)7iyIXC?r)|1q~wsiv9v3Zh!RY7wh$Z@=E!% z=eqd3KkMI98a{gTh3(?aDD`#JY2R=^rLhrD@qV^w@vT!wJ#|q8FE}m>Ue7mdo|Euo zT5Kw8sDKfe_}w?SSnq=Kw8EQ=(7hs`?+;1>YOG)ec8#jBCsVEoa<7wR7AIDYht&JI zt&a*X1WYlWd*i}e?SE0!@8j&monLPtq7R+lJ2izO%*=q{Wr9-AbUY_R@^@ytRR!#1 zK?oiokDj5`tXSy#ShhaHQxbU=0{SZ?tB2{RjDMrPjy2D`;7@XoTmo53r#?R_ea}O2 zSL{ib32)18+bvOd3u(BRoF3+3L7 zM;RU6rZ}zZms->~CErv_TSim3-#4oj1kk&lU2DbHm>OesQ&7UR5?$E%O0%71^o@R0EK<*T94WeX^vNVgo@d?BAITrsM|}Pj>8_NN*v*)oz3k?SVV|a(bV_v^C+Xj; zAe4g4SeWAzVw@^IP!Xx%^veGH zB5&H=m2-Q2%1ZQiEWLw#@=A#oYslZn$Z1j1gwut@Oka)jHT_eb7x@gnRl{;7161F_ zMys}j{2$2bw9{X81_~|MPiCWIOi^*n*OyNw- zOon=1P}2|rJp*G5bMN(Q{}4S!)7Ssr9ic-MUw)s=;p-sBeW2NTg z%z~xyB{v!FI7cg(E_2`*XXwMArKUi|lMRhQ`fE^{``xOXymT1fm7=VtK}53oodv{} zXDwVr5>Lc?+5$&sJV#y!k-{{Qg`udA^5WhIAdrzL%Rp7pH_(A+PM6XjOdoW}N6&Zg z)S>CoD{PnknVUuJ_-_4p@!heknTPuf^REK8$q$@BNVapzfzRudGanp@$66COn&)W6 zRca~p2vBgzgASD_WOiN5L=M_TM77OeIck?{2-AZBZ&{MMTzY88)Vtz_4t{?NRHeHk zp=e{sjk$MfGp{brp@O$)uEK@3_UY5E6Ga|btW&3fLuGVwxwIYDM{EWtr>=XGtR?{n z--yT*PFBmi(>f=~ch>ySC3fcm5fSb9nP(~&j<7=+U}??p8^X)1w?6gpg7NtI+eB5g zT$y8bT zd(pg|p5~=-O`$g!)^(D7$cV3CmMdy)@SxUyQQ=V6 z%GH<&aA;_y?{~63qHrkdS<2I)9|=a4RJNqrpoO6lY(M=_z8^LVoPPHnK265be6z^g z(SyW=bVU&y6o8-Azl6R1dr)E#Cz*KDds#^755n5@-TQ8IWFoupwFF+Jn{b>*_np30 zRIPPqdou4PBf@2=`I2!e<}++>{oYs(u$PBAWQUqG%0M}Q#5^7X$88=Xq0 zu8?P;ky`B2{W^0=*R!gX+8K+7VdN*jJVKhTYm#;Tsss!yu^Q^-3^39@Nr0tCj?MX5 z^}XI&xa>wtA8*qa!`u3_ULjXp$RPY)=c}pp+E2W1%N)uuFycDMwNN(H0qx(`hh#;l z*Bb}CaQ60l4B&KQgyz?mTHeefsmv2v6mS9T6Lk$-5ob<1Ea;e{T&CD~cNr|^bf(Je zz)&!uF(bqyU`S5u15NMOW*`U7(S*NI;7j)UT&mo9-sTr$1)Yx(+Hoc@36QWMLbQJQ z)65#5NUAv*PPW8CCk_-@7KGz1cn7o*ULTmmF)(cVV@&HNrJ>io!if3fYBevAm8T}| zl3Uo7fAM8RN&VNE4c}`VBn0Qg6ZelvaFxZGdum>6ro#J7tygSrvNM@cuoFE%5A`1P z&Nw_hnh4^TwKqZO)CwutTfcKXOdvp1XxCJ58^C}bA)0_J0I6`kYIA%yPd00 zI~T6Hsz6MnW*&O&iigZeR;()+36~QTAm8=ULXG<5-`dAy_fA|(M7s|4X?NrRR^=x ziBy4U0*|=z|83%k1TWRL)(}fj z6`P4troX-wBm-rFv7S-+2eOZvMZ17$%6aV0FUwp#Lv>9`j4ed?0C+PyzZs^9EvR1d zHuavxu2A`ZH7k`alxvF9{>_BJrCgj8#O(${?gf_8#tB1_QrM(8qC#{dCT)n(%9bL! zZ9Jn$Tg-jr@*=#syA)f-&ZP3vznqR)-5mrj2 zQJ<>%uM|%Uizr76iHI&1OiemSZjS#*j9VGHJjS_Zg)Co8jsF?Qg=5$~m#R9ODkiUj zM}&$HI@foLB<~StASbEtTI;|p*jI96 zFVyqgcKw1Un}lFE8sg}Tx@nYtMsJa;>>ph|GF*w5-Y;l ze03LEsu3PZ_Ah`X#bpI&z9ups6?5cCu6bJUp0?tIQiiF>SI{X~5}My+%@>r6E&b!*pO~lo_X(7u?&DGpEDk%T(b+&U|6A zHp~LiZbau_MNR(|!gV1P({7+}(i+~lU~F=&1!ml22gSKizftI~%j}F+I#U1)Ies6X z=ks5m-O#*R&#OO6OjiHA8CLH4crC0bmm5AlYi=)3)Oa+9_g+CV_V9l=cZhABZ!xy` zHc9;{#5H;cP$*DLVkRuTYV|8tSEwVrT1e^zSljt;8ew*=ssE}-Y{h+|Mu8w${d@bP z)?i^GqOx0Am@+^OLX1}X?75ykloaAZbbIQ@*zeDKd=Mi{?a06+1;=6O@UF z&!xc{_&Ee`K~Q@q6x<@mDW9oaLF;@PM1x8F_vIU4QLmlOvSKZ7RrhI$9;eN&hC~l> zl(@g_o91T)a$$)j`(3~oOtxo_VTkoHY74d>ha-We*K}ZvKcpmZF*bIXbMGmN&h)iNe6%3lF+YasBK51KhjA8Z>w4alccgC~{@#}V zDHr8|^{>1S<`A(v;YA5TS+umK45Xq_--GMm{qDODW)Z$UG2$#38|+OgF#v7dtYXe-P~Z zBn|n8ToWLRqFtub_yprc=etz2G5&2onxA2hN;iK&oLn}{cT=>(U&@-*NLj(J; z($4V!zq|CrmZ(hF=V4fOXh_FRg z&Ck^6Uqs+woxb*sBm}rCC8+F8ok3Gg{i<&a?-PX8vO>|nbIg#Q_74A(A}dOu#E5kR z{GLZwg=-niQ~AZ{+RQe0Q0BjJEMwWrilAlX@}5&~H3mGwX@AwloCM&vQgLXpPF_nq47Tg82n=pce^_Flw%zx0HcoPtfWDDKsVRUT zi7QM!FN=V&go|FkUDS~*q4&)Mue5VuEa|J4e~hw;zoLg=#_Uh})YDGImC#&fFY5f_dC;jar;91XfNky9Y>K^V}`%gBHP&N?#JRf(7EWu*=m1OgEqGXgxo=o1B zm7m7HfNYpxcyo*8d@7#4dfEPQPDw{#1Es~_r~kZ_LJesh$?Zx@u8p9g{hH!+=I15v zIg)OT|55;GND74~$=6#?8qJoICxSDS$T8D&_EYrC0`2f0AxU667Nd~QNPtQ>l_`X_ zYOepMQI*gmsUaaSNWC!M&y6eo_0ru_Lm7MeB$%zV{2g17F!`alFq3M=nIw5>lmB3r zVG8aOxLD+F=)8{1vBmrTGxC_s>UIru)*QkBQip0TpqlbmI)jFYaG>-Jv!;cmm>Y)b8$Vo53&!j7RWVO z4h^|OP zB>&#*LiB=^K+3I5k9=4o3L)yd*>qkCLqi`fq$gwu0=!;GlN@#EtlIWx?boufC^Soy zM^;=d$u^N&mcw@K4aQas_ca}~@hJS9NeGbeh)%F&Xzz>EzKw`|59QC=b&?V#< z>vJy~D~Y;APN#^@Ku0dCerfW-w{FEV4r?IKIfAWe_bH;T@a#W0-Zf87ni_X`u-)F? z4z^N;;+rkkn|v=TgYo=m_}D9SVMxV${s~;eH=jSXajBY?VbvcLZV2|sWB21KeTDm+#tQiV zh~XlX>cJER*Vr8^`?1O{mkB!=!*kdl^`8ekX-{%$Vb5ARFFqPYK3)I) zb4Jet=(|?M%$5?;(t$rdWEMqTjz!r5t<#~+eL~H&#_(!mIG*^W^Kp!cwzu~KNlD2D zhrvi#Ao$$9QGBd4u_R_KZX1r3SsY}cOw{MOJQ(b3?Q!g%5GnawHa{}s`=2gP_ZrBT zjrobQvjp1HBjZkAfT#T3?OBtJw5)*g>Hne~`a^ZpA7;7K^!oBrI^K2DTtF&igtr1V zSfAK*-vPS}ex}1Qk-h8R5y81QJH#<(xwi3rUcax{GYZ>22jeh#jGAPQRGDgibAHThew*TdSvh*RzmT&At#&D7z|1PKs zrtq5D!3P3Hke!mswW>OASyilYG(ahSnLmux!%q9L`P5>bW6Y`K;%FpFoEhi7#FX$6Y9iq}>c zI9_~G@@#>V84(C7AM}q`q(l5hk1ZnJEt;8mz1<*-`vzD2kvM2HzOk|!}kKopYmIeI!R(mn7u3;qZeBC z`Q!I|m-~*W@TB=UdKoLO%2~(E^f>|XlU7+Qcjluq#Yu<;;=$G;Cn~ombhfGg<0H;q zdd{(1##Td3!~L2fC6@0mo&}ALzG$VkvCp#$Vpj!%ztsIz?5EVx7IAdK))O34*n!ji z=@A40?Q%xmTJ(*ds)7U}g>T6mpyVOs3eW9$-HF`)FzI8rCC)9mKds*Cj<3D$#;1=r zb=~qa`K{p8ZWW8bghx=_dNf14xBX9TeCY|dw-H!_sifgx8>oL)8=1fQ8D>JOJrfk`~;hV(2ffm zkD9UvbJ45D>PoXwsi8)nf;V**pux_FUb4_g$%yF6mXgUkDIb;SX7t;Ac2`R$|h1ubk1WOK8MaRr-c=J zKF4sMNgCI&A=!Q)QYw*l>ZjUSxe0kd7?%XOC-NM~x*%P7Q-0hZ<-^aTOd}?3b2Aq3zlZv!0?r zisaLIsz$vK?68T^f3_>w_e<1m=7ys%)`s>f5@22;KRfhw?J`?C862BTyvw zcP8GOBj_pp<#_{d5)C&TxULas(-3xcbD+uC*cclh6^0C6tfCu6?m*cLOJs&l_m@T6 zHjVNd3J;j0NNxQ!b$80vs}FsRp+df|*8Qvy zPE(6jjoTYT*!%u0|JJ!dw+RlZU7q?!W%x&h@f9)3Fe#s5uY{tR2n?V>{{+!Aa)$6U zKJCL^BGgTTgOhOiR51U82OaJcjBD4YUE~I8xN3;^LAwh*f#~kLMOd}9UjxM=pWfWP z7#UjH;#EHX81cZOfv^ASbeYgQ8DJ?=M^p#faNC!HqWAfuE_Fmkde4VPx(W&PbF1+ z{3Z9%7|(V1i0*)h?NW`Txiyao&zWb#{<1HU9es9ip4O-t+gmSL*B=)m2j)bOf~4W> zz0E|yAO$Z(XI4$9pMqz^C$?$VU)^gP?iCS{gwvOkfiS6|&L7W!cA-Xr^8UI^;zxHW zm!W=1f?}6teSdQ`C-K!cT)bhiVYd%+e0-%CCzaIP&3oN2ZOD8%2Rx62iqIJFC%cf< zAj7S`tJ@Gz-F)G9c!SSABi&E7?MCdE0{vCMbQxAJBfrY(JP0R0un|Z3e*zC`0)< zl70|0H>k;OU|dE$5v-|w%^^2v78d&Tr9rQd~tsE3Gm^PUjl zwfV1smA^y{jL^S?;H0n#m}E3zq)xcv;W6Z?K>44~T~9ibye9%1rJE!n@`{qt6S1X+ zdpRyORD17l-0K-Wo{|wRzBly9d2Y4kOd61P+C@A~vBN1`B7L`1KBa5u9Dniz?N2eh z^*`qF!syc2^pTFc2O^4~?P&b;aXJdT?o*NR&PU9ppGP%t&er$00^@~bXl1B9*~^D^ zfj}L$T`4hb)w@R_BR$uYD}Q9zbc8rj|2RD_5&UaTJr+m3cj(yta(D#TyOGiSO=HWWM_d<&)xlD(J~8UU$$2r%5Zq z9;HdkyY~iYEj)l+T}3n|7U#yAR|t-GObQY)#nP;Kg>Xz~P|iBzJzOmQu(?Spy*!lZ z7v*@?6PU791ddN~OMDRhSv&%v#`WQ)HK0L4hM3p$(Yfkb{k#6v>?IFyaBpqAY~sfx z0)RF(Mg`{>sxTE1xBvQwiZD82a)B34Bnk-o(&R;}WX*Z2&u>e4Lx;}8zRmgWX0Tbxh4d_&{I@wm+%)~MA?&H}WLL&3b z#9TuAFVt6}D(}%~#i=VA$9rZ}DzWbX$xFgO6wJ!$M9Qv$=6Iq2t&x-zDx=G_CF2s= zJV0)L#HiV?km}x-=t5lvOxgc3t+V=brjKs?2AAPq+^67?V_l#?W;Y3hxaEw-mNDIF zCQ%OB&w45Y8D|PJ*efm8@}+1_i{fXSd11z?r_;6q{T#y$qa|g@LBt>8?2w+qHD0ds zKEHe_;?JNA_z2?T7z?;LU_z7E;e-kD^2E6-ay43U;@v{+-gJ;33Jx zu0o8|D;klcO0qI)1=8@5u*gs(Uf3{*BVdhYqR_1Mv5jjV8K{2D_(TK_Ynop z0G9S(LcgGz3Lsqny00WuxiVstgd;KFTz2Tw{f$xUeMF3k!$H&Bn=~?h!yz^%eOxJ= zu9dE@_AEa;@p0l}7u*9rYfE!d+#zB4N5Y2f8NMZ2)5L4PQQwCUi4d14V{E59EG+9( z5$l#dP6w^2Z<*6%UjevS$Z>wD4jXP07i zj&|{7jCW7U`r$>gV0ft^ zNp`CeI(*$=@32PnzbwErqAY?0%zJvH!s*Q#;le^0O4rVq@0?@}UdjIQ7hy(SnbhM? z3-8_Klbq^+`GSb6w7*%HR0XSNGf4g~@n)B9)+UeTE%N$-QiWIkMaVncynudw3= z;>V6u9wq3{;usN^Y3v1%D%;4E?DvBf0lNu@t-j%FO@Fr@g6&P5Rk3l<{mCLts1708_B=$gC$-0C~{f;(SAP#a?qa|qlDA2_J&F? zpaZ@fUGEl7f(g}A4b3HE*pt8n9zu9>H_+s3K3ZBngbC4BGd9%g&rJZ{o#WipR3R^cBk#^gH+m?<1PN*IltS zX02VZLuTssf6f#w0xW&7-#)umrDgXN`Y-mhQF6ZJOPAU)8FL$5FTn#iJ2#BPF=0qR z*1e!WNOWw&7qcr)VHi!sD5q^{_OpfIB_$yxp(xpyWMwlEne0?d4*E;1hirRr<2n1v z{w)@VV%>V=5bE1>{=YCeX)F`dh8;{o9dPqoOpol6N~uTN90tG1X?B17553>kW|6nu zfcE_8ezmT?L0Gkns74wRnuxtiDdR|!O)0JJL@66F!a-t41q`<^$gCZLn~2++|L!)| zOc4j{5~OMS4;gFgv}rjG9yTBfXH^@nKVvFu>xH~4-b4fF^pp&t_hfdU^pw4L>-nv` zg17ot61^G_}B&-};zG%fz z5mORJ>$R;#T2-)Csv-`*t{D{x2$Pf+kXyeV4D$@C_S_9tiGsKDL38MV?2 z4;HvFiL$4kfccZCJ@U~TdO{!)BHxqopu~!QEH}{&_D(`TB3*pUD@hT?O1)0o2VKb4 zZu0=rf=}Kovw@gzJs&SBy%I1j;+r~R$`ZQ`TZBxvj}OH__~-LN?xYhCa$sJ~QLgy- z={sZoh8*=gQIp=tL#()~t+Oh49B3-^Y_rS4YDBwBR>aU#KEU}veC6wJA-bB;psgOm zGzT?Xq8~+>RCh9Gru@;}o|A$U-Hs&PZ-0I#1fZ(2IgrXRu=Pe-4+VkdDQW%Lw5V}}l2gN&0>B((MAUub__s>)4_iHM-W#FRqU zFMKbwy96n=)6Ktq3fW(onI0;q__iNDlNBB`GC@~jfr}zWDaYKLw2n!jhnDwY+S0s0 z6<5M64f&@(lgFvdCVjBaX6Zi{$xKdfzyrATN=mlX%dJ00jbh64d}rC{47d70Y+@** zqf2w3lB$Humrg}N-P_u%h=03=UwmEaczSa9LpRPr`YdS3gNkV2-SZSONb5HS8#!tp zrh3f;O!(0s6jQFvvry{>k#5=rtnObEf0N?0euVxQAh%l8?)+n$gey5f7%n_O2N{(8 z#5F*2X{V9PDh>H!;4xG1IGgr3M(CdOt~uL!mbzRQW9VDaPWgpGQBi_BnuwTb?YzvH zrt3(1AjtEK+iC-_5DIuJiZynBJV+cb&U*8zC1Wyq;t9M~YnEa5lZmj&AxjXiO&ziK zX3X?tv1s>128%_eXwRsY6OF&?vj>^}#?Y3%mgM1KnLTc?9>vt@>jd{Mq(p_H3q)S{ zr5dV(3@$s6VR&4XJn?*m*6!h5cvkOlF3WaMw|97)5~HeH0QR)Z*N z2BP%Hq$=tiSCly8Tpm&?l6Sxa)4gQ_Y+|s$DK~;#H&y61e_F^n^4a->9;*yha=!=2 zXsIfkM5AhKDG4EhJ3a8OhYy7|K5-R@Jq4A}z(OBIBfI&JB;S|qtPk@u~3gNqdD8RN& z7NzFHcW1DT<;zgzz$QK9vNNetgR#FN0&9QqL3k&|$rMoq+|ddQ|1a1os&c334&G$k zZ5rCkF9W4XE&WWLdMM4)_%|0)m@Al7d2(uO7w-R`zHwW>e``e{H?ZUJMN&RkJ$a%< z7+UBHdc`MFVaK2vQ-fcLFCzdMz5kpQ4?jlbm9m9-z0BfA4&gio0a^j^Rteu6#^~v4 zKIUiAEkrI||5!oTh(;&u?9KlleiUuO;knor6odp5mr0{~W9@VnXo+2MV3 z9XsFGtW)<2S*OZQYCmm^jQ~k*op(Cs%RaH?6~@p029(%a&SkNcRWUmnK~pIq#XX2q zfOT&=%`>ZY*)fG-{dYwIm*kj3jbHaTJ5CIV2WY3hhP)fV!a6BKhZfr+VOgYo~z$wvCfk;5l52-C5YWmQsW#VMBj00^&T< zbWLlEXs(l&v%->r3aP6pNI_;RPv-IX>9zD(#t?SoKiS2*S+Su6SsHx*B(pv-9s%tq?dUZc| z*EykjscC=hvU7F+pmV{mw`1AYd(~Gkt}1A6>I{&mqhY#XKg%C&vp5cWu${mDqNujC=i+r_N4M8^18-{EY4; zOnCZ%BCE`8B9pvw`Mm$lc5IK-4?O(A1G!0-m^O1{KFKo_pGZu3m?`?L;s};T-v>Lx=6~Q2j6X=D0c9VYNk9 zn%OXb`-o`cRGs>zsn@D-cf@1aLB?$z2TB?GQBRsxRWw2PdTT0MYQS>E^88nRS`v1hxRu?};re;!VLnRwxKJpP08M z&z*aMMhu|a9E8uu+2W{%HJFQ8zPdP%xK#Sx7m_$;#mi+c zg`#9mw}w^6(n+0r)8U$~C|w?q*8h%^rn>Ba=jVPG&#gb^`h-kgzaIthP_D()QJSV9dxR)Z47DYGxQRi!FZbeDLhWi)O$F=e_iH3^U{9fXO>OQ z{%A~~F9KR0h)!00gr!N1th#3?hc#<`$$C%cs*b4h;+jU-rV;-SPUZN}Zxwy&l2sC3 zc98{g1%J){B>6YBd`pQLHJ7d>ud6DNP*Q^uf3TC7WB#kT3U!NhVyIvt@E^W;7za#< zFc1-~Hvnfoh5>Qd)^)gPtRO*%-YlzvcB7H2$kFY=d;~A_r^^i(zZ)V>4Dt)07^A+s zka%W~^Mrn?Rj?;*@fZuKo|``UnIo}@p*G{#)(nE=fd09|BV^nB#-BGVqRIf1l-n59 z8=Q;aNi8IEzw2(TV&X8?8t^)nh5lGtY~XGmW1?&d+S?L&kTuV_9$-+RbJ9Td+*-+@Y&&ny|$8&@yS) zRjH}Sh<*MDkvmol2V217{CjLm%a+#c)_`R(9;L#|O&xA4vc5rG$5__JxXL=b-<4~l zCWPE=I%BStviAedg>(M*r}(x>XMu6TG_2cxPJrVT?$Oq(0qyEs`g=?7qk^HtcYxp&Z8;`5w)vk z)N;z_{nxf*i>md~B1rW$bh2_lM0tNqjiDR@~kwSwblDiUencv%A6#Q^}gq6+3 z^BAU(qyy8&j^Ci0^~`5pzO#@FphdHQJmDFWWqzv*g4`L__>l{e8k(SP2(2BUy=@G1|dT+1cp3-bEiml%NTGAoC0ufrplQv9r{*!nX! znq!1fXZ2>*UA0Ngr0s#oZt~iW)V`x7#?q|lp4cAPVD?6DU3;hFiZH6o&C2$=o1 zwWrR(ILMr?SCRs9VbHGXclWT3Sr zB~!B(4>dWRJ+ON3RK(Iem3Ra*RA!q4+NJ;5L+Y}5%}u%7#|h+E`PljQT@?_jL(P;o zucK4(E6>#w9#8*YHB<11?I4{mAR6W`DpU3ujDK?dzyq2Q1jP2vqaa9M=nEo4^c$rzt?v^ojfpK%5i*7A<}5TvBu!^ zVF8k>8TXvwWUJdiJqhyXux65X?)TqE8Xb4_Qtk&jzoj-EFL-FS=epwrqVGbme8K9w z2f=nJWe_gFgr5-zleFs)tZi7BG^&F|Yj8Yd!0(f0L?=a1&yqe)1U$6W=D-Wavf=I| z2q@ohPio|}70FtPjKF&mk3}Yj!3y^_G{ie843aNj#|biOmJ0KUo(b4C|L7bk$<-E{ zVQ#|{7o8jx&Dvf;;zP$s55yLHu#L_lyDv?0=gy$r@C`)}J+3$lvwr|+%mq~JdU-GN z`=1mvMr(cR^p}nT_RVVucEw@WipCF8^R9`u`RF3Z&%j)738%0REbe{usA4B}2OGIN zOP;x26KmMg?345g6f$f5u4Rf@yWI-S56mUy#Gi#zqn@ayCLQOGxAHz^$w!}5Iux4Z z?%o5MVBgAn-?FRcs@BKAgzc0w|Bb)4V>Avf7s4BZN`-UJ2+ISIZP?*%s@CMX0=m%6 z{BsFQ3BxZTMt#OT)}}<=U*Wdmeu5ubx}SDLx*+9GbrmQEpko z#wfZLLzWg7C!s?PPS8MUbM5r zwMlS1h@>n(9qFtb7Onj3*+p?uVTG%{8^}$CL4;6du?VU$nk~k-zlf>uZJNUgM z!BRuwAvw#tR~-&z(it5(!OPmhTz$EsE3%r;%o-|!gzO!m`7Y|kZ@PFnsC={6c#7`j z(zO?7&#Qi2mX79p%spVBUQX#-C<4XHfMHC;ulaN5+=sfdUCwlrI)eI}1n+k>_M{Dc z79QBvzxEcC0lpOS$tmY0aOGtYrPh0mQHtl3krKwlQ}9tmdP>^Qpws8D3!H9Uqzlir ztocYv-dw-ffnrN}Y7f7~QvG;4Ng22G0an4F{RnYUAwzPCzO4YK+fi;ybe>u26K*Mj zqvcoesVPmJt39hR*R_S4B-z7FgS}4IONhiGNj@kaU5a5??Klu-& z8@{&8XG4Ppp@sy|V1%cmk0UhCrJbP?zfx3_Qxn%EFajPM874Xdx9- z^7wbyE>*H3RhSKYO&+}%Q?l2M4po~RKGF3fm;Lszy4WR89N^;7D6VLT^Ee%YH`nzD zIo|PYc}w%6qs=a$6*jdqd+~+=vi6GZ?7d?Ob1{m`sBHfA+jfM9<8xr~q~-4$uL)!4 zXzFH;vZsg{nDBV5o`k9NEWz*RSBFKkMFj$mz!ff#smP?dJ~mH$a??rSG?s#gF?z#3 zPMHTvpAhep$_s+n4|Y4{CP;D@FelH%h$A71OGEq~@XErB!=8`jMdKtpWcR`)Ya7>{=tYtu%LcE-Gju?*~PvBf=zk zeIGyFqc=tt*~)LF>h7&fobw0)XCnX3cL{N3V?qUz6``}Mx{(Fs7$P)o`qyV4hbEV! zzJc~vnwB5H@(66^e1TGr^i8>HmmuF%Au@OrR=!Td9hT#K2REZFIiaat-G5;DSM%#L zLTJrI_fxN)#)%-?viWr!mr`o!$Y0n7kHd2n^LHWt3e;n{F)qBnhEcQb$QG+!9=tj`0G0IkK z-eOa3pa~xMcy9FbdW2ZxPbyk5rNp!43Xan^U#;W8e`2m?`x;@7%2F=GS(EASF&;88 z(%%!3ED${FZHd0uVSNH(npkjjc3DZ6`~gSn0r1FRzTpdem`fZ_Tx3$*ge)APTJfEV z%%b|_&5*k|E4fpks<@HR`z128D{r4tkih`_(1rfqZiDvdP=o~H0`*^Qm`4Vd z?_<7Jz3t#fh$_9H2J6E>yx^=M2o#+7I5s<4H0B;(bOMhpP>d3jP4>7FBX#>+5ubS& zv#^ENt^Jx$PX?Zsp*L|IfJ1=bEv9tLI9$MgqE3A#p|SF(llJLnqZ=>d`wF-F3w^%`)g?FB5`=8ua);4ZgpgdJT0`*KHZz7}q zm<%Bw4$KqB{$7#mUt(1|M<1{jWRmyh!ty*qoR|5)xycGl&#>O%*(~Qkc;d>_Mq$O;Pz#k`Jdy{ z2l8fa$9-g)**pf$%bmW81N~R;_uazQ*S;#P#ZZ`rJVT#P^4_+h5o~GQOU?jvi&OaD zi~L1^A_WQXTYA6652wX=fCdBE4+jBwBsULs8`0JMGBCNj#Jqocy4#t*A3+#oe90nzPFo+{-^IeM*Z=`>!h-^9{o4Dub5%o4cG9i^}{wYCFO2L|Zeon2KaJ zaNKca?@LVE_}-+=$u6xgudkg#4tFBN3({)VE*pMo8G3j!o~guZEkoG}gL9##|bA;9e(C3@u7pj_6^+bPZoW-aV5!DirzQK>z0C z6}-YUA<$om&Lfq2yAfcaK&Qu_7^l0e+YpbzY?@gI!KSzml8McJly+zQ<#06NZ%m=M z4;3cBmahK#m)jZhRaT)ucwRnlqJtEcU}jB^eG`jmGb1&6XMF?ybXaTO{l&J)WzXme zeEoI${g{?BYnR^O z1e@r`I_JMqPos)+7T`CIF@d6d#3v`5163~t#qXXy1pOkfV_e;3y>{XhBwbCeZyqe~ z-LdovYG0POu91&W==W-gpg(ml-&fi3X7Fr1bE!t1$bFp-if@|x`8KMhrgih{ew#1( zQIEIf&zGvPH#7nOBO7BRL7!R976#-~(o<7N5XV zLve2iU2skz_Dji-*T0lfT|xAONA??!l8W(1OuhOA7F=6~ph3LK<1T7FSCJRrPN|Nl zj@+GcPhDIEi>7`}V`;v`&(N(8g8DS#Jjr$Z4CpXL!V#MGhbil7VW_HQ{@+=e*>nn^UYbt*YBCRB-33@#KNa1DN4+)6WNbwZ8Jv@g$D*%{p=7^kOT8p;uw zcmKm~*=N>=ksF0gbG-oC=r419b`L?!1A>l;4h`v&$Cdss3jl$u#}SY7;p)15;Q)p^ zlI&pz-wkFDCTK~y_jlE?rX0N+x@NoqNM>>N{Ea4wpYhw6Dv}Y@(Uu}}_xzMNo*a~T z5I$w8`479HL(i)!tT{FFjEe$t5-KE`(&UHK>xhAsCHxiTpeh)ix(*0O^%pv@b0zJ zV`PqMD?UaQXS>uMmj|lN#|AN?AG#BW%*alPyATAtPvMbg#wmM>B#H~eH{!}xU~n)7 zv`+v*b0@h^rt*F(i38`s7bi@dgt<kurc^>Eo>r@vN zAmKFP)mWzFBM>Yo-K#aI2PHXiB-dCV)s)cSC;Q2tWDvD~eD;w_p>2+t!}A9pubo`p zxmCy|Ql%1{i0v4xu(yul?5y88uN=JI+DtiMK2(Y5YY=xa*~Pnz3kwC`?|p4)J{j139f^OC9NIL zQ1Cse@ln5QV_-`7%Z0MAPr?~6%hLYWVzWjr;3v%Z?i4t8m< z%!d8OGlqGA2VL@kEHka$fLvCDIdnJUC>uKa^7W}r=5F`<`ZgS57TUD!k5bk*N;Jf> zBxbibAr|Kv7eh4k2?oB(3hm^a2M29hEvqels7}o^a7tQBJn{5pU1!~iAQo=Zce5T8 zMLpfP=t-^=PCJ=Q)@he4m}E%P@K?O)&%Gm7JXLT&hr{rx*}sXT9rgA>k5Hn-7lC4z zE+Oq*nxRHOw;q4ja~ja(vZK9{)?4=^dw^vCQSNN!blLDaDW9%k?oqy@$pBB0Rb(Lx zwgt|E2X9a6kePi`_~8q19Pxo1-FiBdA%pVg`3PING2p`7m3r!RWWiZ&MFsWlBT0p- z_JNQiEal1k7v7kGa6a?OHp=p`?#k~}13A`>!osEAA!xaQ>sdCmuvS>Zbxw+uR@0wF zc`2<2>fi~vR3VbWA8;=9LWXSaPb5kLq90#nkVx1LXPQ}`#Qs(B3DS(fvZ1sgerZ~M zIO?k?%r+Y689b)<5>UNN;pJ|vJzroYPKmtH7vKi6VBfNl0+Ur>;O0PinTNz*Enxl}a_nWe zRq-^8;7so5xCxSpG{0p~tZ|)Vj+aV72E$$k+Ho01il#Tl>-iC?yfY)MDF&B0Cdj&f=%&NC zeO7s!u$niAB9j6pdAwL6B0pX+juPtMg9mDy!u8VoIHh$|>MEGItLV6OgfwzEKH*it zqqLxhue9-1=HmISsUP&>oFXE|{^N(ZbArbWL<>am z5L9d^jIsuY_l`(^~8d&oK!Y+TkSM`Swa%Q9pL_{=mu{rFNsw7 zuRAA^8)fsE$xpa-Q$j5@OPF9JNr57hRY@~gi3FpH__H6+;$?RlqHFTTJ1w6w^+;QF z@VpFmX4GUb8D97DBcI7}R4=(~n}$BGcroa8i_bjnE+Pqio?mUw>;?@p8R+YP4j<~P z>IWfc;>3$8hdwlp8UcSmDB+Z|f+K>M?&va+ZU==8tS^6MzE+c&L|GyPPJsV}{nV7m zWJTq;^ChPLQFHg<*8OssgL7a6o7306dadR&kqxaGIe zwq2I9>;~0VSSO*1$QMz|kwoYsFyLkY!_Y@bkgo9|xFI!P<#4Swpt}>8 z(b*?g9Cy0iz&(mND3LIMYrkuUjVOAd*>&H+fr6u2%4Q$Zz*R@Qz-*z;!Jws*+}glY|| zI+Q3JtQ6)W%XiNJz4^?q+_zCjSYE&H8DMR7(irn-F=#SOFBAfnF}Dkq=9gK#x^~8x z=g{Zs{R}6Dv)OO1XYrQl?cEC_S4F3eu`(**Pzvonlx8Kq2^KTfoO8pFRZqiZV=% zF_csKdf!7UHqnhy1Cdp_#aShU<5=#Xa4gIs#a%|B?~eS9W28?gJGkl;Lpi7ZVu z648}?syQOE-gb1g6jefr#E;aEVV~9ntSM>Vf>@_q;CM;ZUEG#RPh#%MGE!^0fWB;} znEg|xq`$!T>;FQ2&IU=!VYCy#AEQla0;rI#ahRw25)g8PdK_3~BlrGG zK3zzBO%OG7Zor3%ifV$V?@+slASh_lL4;8Jw3>-8R15|&tv1fmM{gawG>G1xc6Vo} z-#g`V>=N5!4Q37-h$>|H^l|c*=4yYlru7gjaiOEl!E*0NY!hJgf2U{6lvs7QRxo;f z72v~La_+(*fCLts^mwaa6Z)8d9*dVfLt`vOHjl#Cn~3!UAFFS&J@OO}dxlwGdQ1R% z{1Duy%7>|dzE=^T_aTD5AKjcK-HL(RAB2bJCMOV}a7O$hWmqVGTL`wYDg%cPUP{@>j#*;Ri#lkIptxUEM|D%Y$A0 z4xMtn4i{ry{f$?Lc8$xWW1fRoX{>Em&sluy<(DV6LK*H7Fo6XlV$G>)PFr(7$*rAkQb@$Sr z;;2<)^L+V0@7wl`gakNc=&@L20N0Q8U;V~er~CgXYF9#C*R>xvx4%u-{-N*u;ge+8K1`@9z2GWa!*< z=d_)otkLe|)w@-9%U1Ggm%C4o2b7jV)H>IdwNmQjm%YMlluFZuZ9SWQDP2`1VEEE{ zAG{5EtknKGZ?Y8~6ZN)sEoWck4Iw*jIp6{N-|DfFZ z2$0;=mT3PsU!TJ^(i}L=LStECtPsNYVrQ>gv=omY1}ubz?8rkW$*?tv@x1Px02PLb=&F8EJZ2Nx{Y zdHX{r=N3B&M?#z&2CfzRJJ-Is1ku18@} z9k5KS3%(PBmxT`nid=f553$$l|D_Aa2?J80Q*WLuyk=aDLmjvU`l>a#?0bVTU&c_I zbkU!J_=z976T5Q`P~ojSDx9l#zhrEkhLY-iY8)93R5QP{w_+1kkJnfoG!V3ElUnhmZvVs1n1WJrDVJiDX3Ga-VEnv{%@s)du2Q4{LeJEesV zwU4@WANnkM4Bhg+KLOs2(C7kg!|>Vs4*=-O6iobI?d=Nz4p(AkCCG@FddVJ!hrp$# zaTvz~;w5+q*ag@)LzJ(kt%a=_f~D^XK? zCr0jGYHe5a^QeaB=M^W%Rzh-!Du}Z@z%My*JTpC8JUK2*L4UefcL5#uqBC}$?f)DS zmg4Eq_JX@yc!V+NM5UA{Artv3Iol{SRRiq6|korXh4GXRI z_RjTc=w8$Hx`jVHX95+B?o5lE3U)Zw0AQI0=XnA&N+tX_N9)XaAkD?9MVI&UnGxIp zt3ECxdDL<-uqUlvImiNv1JN=`KGk4+&+nc&ak#iPw>q}{ge|?(Z{XH~%ho#MMW1;L z@yNQbNlooMWwCVl=@nKRw3_zYjjH>gJydQvf0F8x`*HU`>T$4Mv#Z|Q1iP*75@y<> z4|A=|yLLbQioj*JhhC_JU6=w~l-j{arc=PG(MApP z?e&_+O6lRpG$p3C`|SY@<-06bgVKMFt&oR5UEJFmV@~aUxCvh$)Tif%+zJL+uLJ`0 z^Gw`D7(^MmRgg4sTnyUZ0y5gm@*zV|dOTq~1hFdYm|E%`C!11~qW`Nb6C5tlQzBN8 zR{rVnq8KqYl-1OEn=G6Es-M;$#U;5##Pf!Eo0mHwPL@+%A@<8Yf5X$N8t00yluB7V z2Ci~Sum6s3d+DE_TEpYTKbzK{(1X^!44<0wH@>Y3+>5at3l=~QjS@s4{KdcItN;O*74(vs19C{CR znJ|7H`L5$g>@$`Pax>UdI!`(g@yi;|_(e>cE7rv(Ua$$Gf;~&pGd3nbCy$XPvmnV#@FZA!J zF^CK~_El7@Qj55QN)BFeiFhU_n=q^HNmSam5U>3m9GaAVcnv`-$bTX4-40!&_zp;R zq3CRK&tx26N^p6mlU$1)Lhel#vAi)sRaj4^?k)*6{ikji^f48{@Cd}j zc1W%rk=|t28`(9_OLeLw?}7&$6By8-lI1V(XDP`qJ3c_>Hi)1aFn4@~);-)>_ zbNEnBoDLYQnGG2xm%{u~y+A58YM4fcNUBldK;7YKu-Xt{-DObXUs!Fi4AcXqYF9Ro z2E0v`-a@M3hB;@m_WSKxwguCU@f+26vxea>Y9hYAc-^=Uo~f?AmEBauk)ag>`Mumv z(&+~W-O404<@}ocZ{xVjBR$DH;RBT)9+*r|+LX4kFAl2>1U$NaTWeAACQ+Q0mZC5f zqRfB*hNq21(}Hej=zcA4=0CpnaA#F{U#!yI#nxND-qtU;JhnX%A)n{FX*wLgHfNpl zdVi|Sr}EpIZkU=st1LDy0@5P#o3Hoh`}=d(#kjWTwa5Lq z&$-WiPQQ8w4#FVudiv)U#o6Zpi1;<^GEKd449O9XdfyE_8oHcC%SzD+*6vYYs~PXcDNm0GH}Im z?eqQg7ug!$O8X2kJFAymZ`dMQ#U@U#X`=mgRVPm~aF?9+6Kpv!aM2KT$YSvk4eS1= zc`obRnoC`N5by2Ct*g>_Okfp2Tl44A{Goq&>ud2C-1TnEKedl8$gZSAVo%q}zv=nN zciUW)H0oR)5Fg&>9pY?``BlfcyVgUSxf%H=ikqJ4*7oJdL;t+zP#DKQrag9*+L<$*blwHv z)s1}ZxS6kPG0Yo3R|o5rI(iH3c9wWKyVY8W=^?*6>j&24za@NA%qT%>uq~!-WUJgq z&gBLQP9`|K?_tg#)urYY($}qW-&5w{L!iY>qHn1JhO`|d5*siL0-5$?r0Tv{(UKLE zm+M)0fDVO0^F_NPX9MliG8S4y(a68k_(P>Ej>PLT7U@qfS@M<6C@S7`F_1}Dm^UJ2 z;t+FGV0R0)Ii`YwhvxxXn;K)0mSQo{BcAb<&aD01mY=9q2B*23vHi+_y;q(7hznFB z-dAp&oNDAwC|(PI$YUGIGzY5hnn)*y?#LXDu;rF(_Se?Oo=!?yV?EdrNX$(7_0C3Q zP)PQwC=8)V#$}#CRX^mh1b+_IEcgYa{^kEQ>i?z^_?VYVPLSEb@`z%7DDU0~+0iH( z33|!RB1Uh+@L_RW3Yz8ab4ylB3dQ1K-)*A!lm>z9IW{Fmj1%$p4BFuHdSnNA78C!Z zrpnX~XkUiL=VWI_CDT*=xnQ%bKy@T*WY4GH#n-xgIr}=6i9*HL9*G%WrD*XP;^n86 zll}R&O|S#ZKS%TEPSCBLL#LVNQW+HEG@Tv<#$yI9bcEug{FxQ`@q+G)FHj@u+Ox{@ zBMZ7^ClYjhCq8^;ConW7to7tXj*l0t2z!hv19OYNM-G&<6Xb5ALXp(}Shpf2ko!4O z3rv=YqvjAb=aKTrQdGn`^SXNIu9s$p3{%|CsiOxO*>c`pY=A_+d2a66P%x=Fo0QzH zchOUZz)*dA`;5%CzliCx#cYqN*u$Yv3fHa_+F;bErLBJ><^yyvw(v_2Nq5us9Cm3w z;HLX7d-&*wIx6QE#NrJ|J$wP8-pdlHdxJvq=%(Poj4~c?q-RqfSZEZ8WAoRSVi}HB z-gEz67p+C$>qz%IV3th^ZxnK^Ps!6;>;mh_kb#K}=2fwId^Dk`IA~U@)Ib**bzYWZ zZzho9%_`>BIuJ$Cqt1;YiS0E06gdm4wi|WSXNn6erqK*T5RG6Wz0U_Xa;0@0yH>VC zp=d0ERwqi$0KCz5{!mpD6fR}EtfT1smuqP9VMmWyeNdu)Y`zp09BZarAU35n6CVHz zpARq}>JU>YPx7TPD6flh#^}knMUk4A)xeBKNmPZ2)?Ioxqu~4Xo7Eoc{k<%7g14pD zZ|MIX?`>U74ghBaT%R`4*O6+SCK_X_-IvIlZ(f0@%wS&bXj8@dttPq~5U>Dss5gf}Y5e-emM>8~|c11C>jz;|5g2Xjx3t8suQA zw$4rtmPYTmyD*0gFlH_j@{pQze1m_BGQprT6iEx187c<)I>DcD_Q>i4EZYC4##>VQ zR{-imJv5*rNTm%iaB*8+fnp72nfn}C7E3~}a!yQeDuUk41zFe@0GrDGL4n|3;GonQ z^g9g@nHv2=xpO>7E)rh^DM%d{=JJAj!nnd!V{y=W5+Li8#~<973w@C~trUcN56$nZ zfIRoT=Z9H6@1C2JYZZy@%D!pA+)7(M!bO45{@Wh<9&?F-6w6{w3ysFkoqn?tw}qJq z)8Rr#cgL6Wmz=a6K6)m25o4E*j4+j=*&zUAi8p~55MqcyJ^F=rX=s^SflHt#MT?NG zF0wTO@R1?7M5ggjOGQ2O+H>Zo*yyv*8fh=M6uI3qQ1fwzUup(tQapwdxD`6((f=Iw z4tD_9#56{+Ofx{huL2q0Xi7`$BJ{F?}8&#r1bupM}t8jhggZHDAsZK@+t|tyOG5I{g;c!`^RVMm!au z3e?_H7JPBZksXWknT8+X5GzL<9nNNQvj@3P!Y!6R*Faw!+IzrcnY+X*@KqbX4-DR7 zvH!Va{{>x|Kq-u7k^%wJ#Qo`vcEKup9KEt8`3;H){SKJl>h78HRihV{$~uM@mFn(SUxhwXJ_NWqnQ#;~oyiu57N)MrqvVmsHH2ETafSLZagmT> z=B>|AV#v&1EGx&Nic$(W6!j~#`PJhxDU7yZD1N2HAn%z>KugFFMiHLwN3};W74k5E zQKRsWP^%Ydtf6D%ZIYAW&@H~s#rE+u(o6`GRLwIF_4wjL*N5^v{wX2WcBBs%{wx(W z%v|0q5?w-*`0Gn-?8f)dUbRqA8Zqxx^fV3!-j^`qn#PY6Wgcz3dZ5{xKB*GNs}R`> zuk8}~FkB@2yXHl!<2Pki?8i*Ag;Gmg&15~DQgt$7JSsrwt;fG>kHOs8)nheBu?DA3 zdAoRyZFAR3sRZOmPg|SuqSXtT%s6}4biQnMbt-4h{(&1C>SHl>zH7OOFP?b}>D)Ct zUjH$3*vEQy>U=g&eVFvOsqFS@>GH^|E+5zMPR*d7q@TNg)QfheA%+CLfxX^=EWv~Y zsahNEAYP>6#NBj@t<~Udx%9 zOTH9SO%$OsZ);}thnSWqgJ9d87!Hr5h`GH_yHQzTYS^VUIa^cO8((sc4;N8pV2jrjGA7li9^=>5hS!bdYC$oA?maJlE{ zGUVNTvck(&^sXrnX?J=$f<bD4XRaXZ~vislk+v)=I}n+ji8y zO1r%i3x?~&=eOY{GpO`DN%b!bghF~GbDR%~g=;}pE|pQ3UpqN>3}|jK@I)?xX3Rz= zDeB&p&0%l{Ndu{^WaxXfb%#GsH2)O>>RHn`rO&jubbJihHuC<^@+>4KV}!6}($vw? z5im8-^KDoul$S#esbS106eMiHDaXgXKSc^(pPOagc28e7OOHIwY<5MD`+TzN?Q=V= z{NZ}7&OM&)GXUGQtf$AchJKV_!nC49v(tz|sA&Mgv?f*5c9W!8QnS=p81$cuuv)Wx zkY64|B#Fo7Q4c6@DALP1OZB)}2JXPP-7kqo|f&kI3CBe5|eF~Mnd#vFg;X;CUdF~b-AGb!#7Z- z5$yBHDq*brzo>9NR=%Ddlx=FTi`Q|_kBU8myg?4T>Y*mX`Uz+Tnj4=7QISMJ^m~2n zpBokL`%!2fs1LPx)F2!`{FE3DG3V?V8jm2FeWu&PGbbcQa04Y}s=Kq-S$%P+&B%X_ z%-?269*YHugp#tr^en0c=MYZ$B>8pRGM{BooKPFg+@)dk=P@K*)_8gutVro?q}?vM zAM$Nn;%7hf12->!h!#JaDR~ywgGuo0W!f@W94`0n!fKD^3s15-G8<7~gn<`4l$@m^ z?2$+lm_ked19d7hwj3r6l!RR`&b;mS45L5tLym=KM)#KyI=#QfsZVER+r&I?+}B>T zs0o`I`@M)${Scow#FT)#g++(qYc8Ixcek47)?!D|x}WUz!RYL*Cdi`4%b25~HXyi^ zodPY2jr!zrS1VjIr(r3Ou4GuK?I}>~yX;hQe|q#M&HOwQ^APdRYx{QOefqJBOcsjC zMwjhZfZboI3b|lc=}qSw-vCWN^0ukzKf`~-GG)v=EDCCb^+ad*2=Xv#0kkpG#7tQX z?vx-@JVqAx69G^ZV3f@c>*UpN5jBl8M!*C6Y}rjmbB23$t%wWdm-s`*^}aO!BhHM2 zD{MRUEGxtGXpwl?cz=FhI%+!sU&emp)U8n>60h}EWs-|?TZ22hZ`;5SlV}U(LJN-1fnWnET{Bg@aY_b~Tt2vnf_HNigeH z%EdEFP1L}}pvcjp*WW5iIPzzmO&VG{JXChSYlBl!8-|65zWWswp3`csed@>#9y9oG zVM#*aKf^4n$EY??c;Eo#C9Gvd(`(TiU&r3F9})slWOK6+<_XHZC@f6Pxa>} zI%CRV6ozLlft;E_Ya^aflCQJ~)v@6q}~*$y)lwdqjY@uqIJi3 zKU(U~PB$LOw4zsJM{ilvMbAr$6qlcekHjyD*TLfQXIZwt9`k8MXGDV0W@`G2G2Pk` zm=8;lu1nu#l@j2Sz+K1`^Fe3d%8k^LRl$iMkFDUXQ~2+D@V0<$Q1kPb;yLoZmASPL z`&xMG(|z-`E=)Z6zTtH0M%S&NHxWXDYtN5N+WhT|+6Q_eDH#9V5IotOL}2P_ zy3o(L<$IGfl;b+9t#g&y1FioTluJi8QtMLO1f zSKH~V5{!5g`%mNWP|y2-+2JQqQTP_`LH8=x+4n=i({E3130ok|kTVU5P{dID&h7r1 zUNbXEbmGHx{P$IEj*EB(WJNmknO1hcdwG z!$G`Jc~-jluUHk+tj5alUMc1kM_9qBM~ovcz6=ic14!&vA!{9jc}uJ4^+JK)O!{0q zjUuOQs!RABBpY5BU>Rc>JI*R1kF_^Cq;W1{aR2V+bZKQ^{%feGV@Cki`991=%Qc^I&xz0My(V395Be_mfJLop8l%bnTF6UF9A$QQ?s?MgSQKXzk7 z3S!$(XC^!dEFW&DPjYZKy8rLaRJNXDSUH&S3N9JDe?3SA{e)S?#6y@{fd40#AQvlF zKhI+NS6N*DD@v>>;g~~0STSHG`!GopGF>8m43!I)6Zf0ZeAfwdru2Bs>NYZ$CRH+|@a_t1Q@d(n7i%DmG4aL9)d4pXn=i`+ zzJ@JLF!%Z{t(|6JxO!M8H|$&N3-qh%EQdA>h*RH?`3uw!hXHm-$cbq~lq@xC2mA6S zU$-Zxs$T!O+|>@h_B4(&kiz6eGiDKed=EzIvoiQ@*mjan-FC4uM}B-%)^T0?oE}Gj zS_uZF3VVDSp8qr$$zp2l-Y`tHtYML7|qlP~@DcZWaNxMwVgu~EeSZbs(FOoj;pW6YX*HyiTP@~`5`SVR_n zw7s17nEfP<@!InOk5`;gzc3L1#{O4OR-)pSt>VjMQzX-Djz871SbSR7Z^usf9t4mca1L=RF+OUmKZR0;rC9T`(zc71nc z&YNr>(_YN63l|aubWd-0pUhWgpPa@X*e5Igt97OBPpNrg`YDa5#SC|JmIUY2A4g38 zwMnX3g9DS_d#^Vu3T&E|88Wob)ql_Omkb%FN~&`;usn9k;MO`gr`luc(8ZQ4R=Wv` z?w8#@*fv|J|8`6kD$RKX*>SeLEICkAmO<~E-CM5t>Rnt`36TZcs(9tqggY!s%vjq$ zD}2+Oqr9he*46%NY&rrcS@TCRFcCE_WZQ$D5vM zKd#pOYhkOHa^s!&x&~0n;nnbcD$L0C%9_=KH3?iLwe|70@Ztgwft46z=w6f8v@i~2 zxE!oPtN_&_k(*Ep;9{z?0&z!VAYI$xn4+i@n*{8`JxMj}P{wi}ox>d|Ryot*>zG;02XL3a4A( znw&{NFaO7&HU11AFPHhCguw0xaim9;;MrG|Yp=3x^?ok(m^8T*Zr)k6J_^(p9CuosdX={3jyvDy@~BDlv0i}t zGv?Fq{dyOAduC4!*%HXS_~WT7*Wjc&{4hLljaYIk9p^#T$CcrqmQb%Cz)9te1MWt8 zmT(s6k8$kbJZahSC6e=8X(?Orv1$#h?{N0w`}yjyX$GRP;KlHMx#31&3jz0@ktjF| z_zYD|b5odAR0f|_=S<|5>WN(&FW`TwnHVNbbvAEG%OO_dFFui|7?5)PIq$`nU;x;n z(E?D@D$p=Pb?}p?JZx<#Y1Lq3>y<+5+F1a|kCgxFQr zvK$5$usrSFbqWie0 zLqbYptZi7R);^r(JhaH{zUTYvr%w@rtiWPD7j^~f_74dy1(B8yMkihUnl7sqPVnWp zyTeV%_j7@*!M_wAGHmNQzPq;g@RVRFIca}ZUjYaxR#CbTOHA7{+hD`AMLL=E0L?jb z>~kyzyMwJYn5Q_Gq8RcTigfpUPmp8wz^yXTQsG63QR6kf0?_j6sb;g3Nb-!`XDi~Y z7IQ8E&1o#KFPJg9k*~axjknMlb(lKI_VG=N+r(cDY!O)#lhoZFy7EkAn>1|9edfVS zk3t53fL1aHT{joRrWxk}P>RHfhHJ^tkm}Y0rFO*`nbL~KN5&a*0^K->JAB$aHA{?- zv`x{w4e~Rd@nQsP?^=d;hhdMr8omYQ6N+2xVrQHWM?iMfzE?4f9+Y-1v|3`DhF09<0kXBm`UXf0=yP|B*ihULU1 zHv#>B_)jr6Wrx$NFZwSc$1K|l<9I{|kIVqR#>zv|eQkk5*Zn$zR@3OvYli%6rc5|L^9UlWOHk2G+!D|jG#c&0l)%qH(9lI75!cA7(d3=5`W3nwKB~T_OBj+w(oYozg9>T31AAq3sAd)6px09jO_CTgwjFD zi2Z54H~`e9V3n93&|+jL!xitg?$7%Me?MZ=DAR^_*wC!{c6`#ju_OAA3D|=(fs2<@ zB}zdAj5q-g{LfEZY~_=UCVBzk@(gzWA^pN`zcx`7h0U5^S2R<{bAR5yXShZyM6@6O z5efe~jYB@6Gd(9hn2LyAj#Wvl08SK96$V9Sdp}Lpx0(B}AZ>M3Qj#z`j0gODFvR$r zIs8yu{CHc$j)sE_ax?983a`6MKr#kiX@1vL$Z)$BWG7dA+JelkN1 zl=KLnI?|vOd04q}@X_9G{Lx|gXv}UPWBWX`-3(U1Qg1h<4{>f_fhdwk<@i-Cs2Has z*P1fWGRn}pX_WC2sDjWCPIRsJX?1<>*oh+^8)M_<$Oh?UZ$8ETunln?`XXALG8P1s zWS)kes48x`s}rU)cA1BJb{HN1D0)*H+~Sv3hI^3EiZqvderU96EWb=0W!L!|kabt* z#`De16>~nKI>t4sbjG@QR`-aapHg)}t=^y+F!hmE+?#qnGHQx#Y{uNw+*?bhdMV=F zQld;Mqae*LKwoesEghz|&q6MrVU{9M|HH}gt%;pec#lGTyN2@TDTB zCyxWP{=?4oP&xmrC7VI-cULmejD~caW4y&luL{azrbQGayP+i`9(j@3$n*-T^yz#o z%l+|Vu9369!Tqmib>8PxP<^yInLhxs^k>Y_Gr%8e%c|{To6$D%AvX_@7I(j!u_^ah zorxazwA*^CVf9vf_q$we?!A96mZe-?W(TWH5k47^=%B|6E?M^xyPyw*`pR|_|GnJ< z52U2T7RhMAp1pz@V07an?f$%d=H}MQ%<(?c7YfvM^c|GoM}mpV ze6_8#>yKq0>p`oJ@#<<{I#|{MSqxPy{MnxcsHmj^<2`>#UwvzVvy7wwmI!zt#&fHyF5Rjbo zuHCGjP_>LsaZ2ZF8jA9dM&Y#*nhMf40;aTXc7LXwTzC#_>}aNjUmslFHrxnp?R$xA z#?lpgtfn$@;hg=-l-$E@i1AzUxtt0?bBX1QR^Nu8ZYsJEa6ht1O`+YC9jSUGW_A^jdrxtU>DFhC8J=28k}*3->Y z*L8FUvDEQMUDB_-smI^V{(rYg+#2epj^p3$S>IRm1+Tq$T!aj+^+4JNXfZCN0w1n! z!!%9q$o}rDWoh=lFFr*H_Pu=ZC`8j1uzWK75a{>g?DgHej{jEh{02w0fo$N)+)rFm zT?=-_P5HyUKiS13nsinb7z7!INT02!03_CR_T8=t&e#c0v9+AP-@w z@7Hxi$b-Z|u@6@do42u=LAyU~j}w@g2#}emO}j@bVOf5xvp;o2;SK0k*hSREZ)fA| znXmLQ!UZG6o5azFNUJnT;woN#V2v4*+sLg!@r)n?=NK2#6Pkh87$+p**Q6LE8ftex zf?SUJ6p7dqKst9H{Sj=I&W&}%h*YoQmdCdV7e9>c0#F$35bHMSb;bgp?~FG(;Spgt z$GHs}=qSu2XT$BofyfL-4`AS9aX(`W(ss=#V$_Om{Ex6{F;?aT3X!+b*xC`3^Ss4u zoLwvpH+d_sd2=CryIhgC41JmF(Ma$mrvryv5znZ=T5x4mPSDDpajhSO1Tn311(P9R z2eK4100gyQ!f{%t2`W%Ak8jjN(}3E)u6b7CWF!kTBbEM!K7W19p`Udu4!Uh7)0aFq z{VxNizEgRLygRmAW7#a2DM-B!K7827ue{jlXtrr}K~ioyAXje|chOO=gqDqQ$-{#% zeDUBrlAYdP5#^`)Rj7+Cuuy3NoT%5E7+OwmAKo;;p>!lJoAxbluy(n=?Re{oiH0wr z_k@w+HaOV2S`#z;!8rg;Z)^4d3t9zc@c*2>-k#MDl>sJblS;vqjFRgcf_h}?yc z`vRQrR!1ham+6zABC2 zs22oNh3thNE1vbz{r`0ufJ^=&1NHJ$VUNu1(5iX$nj;tHbZ0v9z5X<=?gM|Mi*!;W@ zx&?y(ap)AOR({q0`U{j|nb|i0ekvRbpyw5~Jg=v?6&=MgnOJJ;iR=OW6mQCWjZAu7 zUR{@$W;RUy(h(aP($?Y+No( zuSoL*CEkD=cK(2%c-fE3wvQN#dc3G z@aDVRWM|<$?=B!#&s%J+HfVL|5{Y^SGJoN}aJDw+*Tq4`>+MctSu=o3mcj%Ni}@u< z63Co?asFQQPVe2x6zh~az!QPTEZFoxjw22f%izhe()sr1_p0_Wao%g#WTx4Iq5r6+uQqE-FeTI63C#x;LcWjd_ z{oW8)I=pe5K|Sdn(M#=YcY7t*r%{w`yQ^;i7G;k8FkKy(tSM8M`(`!REL+pcq$*(Ae zU&-|EuKu4Ez_@2tdBbLMP(q)@G&)RrtbM?1695E7fNIseH3kf9+!mBa%w^#+X+LQQ z@Bae`UP#2TXq+rX*iCTvE#i>k=?7-c2E;4b9eH(m`&=~jyQx$s-4$@Nhd_``bMn~t zgH~EcO0RWou3ts~mW!>Z=sSa4t3-JXx{`>EdmO!qOGLkvz?$v+d&7^1+7x(+yaN|h z;=GEv1f(kZ&Xmzg8g4_3NMNBoDj{Wq_(n}xFdNx1*FHGZ6>2te`HEPPIUVuNHi2h= z7~C0J5^>QJW*!R_Br%nNgp|IEF*FP%2X|uMvkfYf9lQ#%wccr3$Mu(E!5d=~N;Tiw()zw?^rV7oFRAI^M*yB@b+>ON!_lJ)+{O8m;k~IV!sAtMM zJqI0qZJJU*gjeM`?*!PKeFNYR7Ok{e3iHJsTrwe!6$v1WmB|?V(XEN(&Ob8auA2iBLHW3ZPCi#z$5~}_@=U1aoTjV)%H8DeB2mZRW%GhB z1acs~A^|Lsm$Z2*-?a(PPTgmDl)8d|?Lb_ww^{wcRnV|^=_KafS!0vREMme{_fiio zxGW)iNT~C6N%Od_apg$+#q(V$fNl^A!-@R3Slq#oz`*mz^l(sQP9o zn{!Qq*w5^icIKvAQAr3#oc{tS#wi1taCa93?+J7c1wyL|CI#3y_nHz2;R$h)dvHT5YToF{laduLks|RE6>{e4lg84%PF;sp ziyFKDC16%y3Gj0yI4|6u+`QaIPQgoC-X$wrd!$?|Tv9D{`nMUHWZAsEWcRvK9HkJ1 zlMTp#pR=zM{QHqCJbaK>Fa>m%#5UFLS@T$|vDBLz2dVQfl$sNlU!bgc7uF^HseYzT z>H-W%CBZl=mAbqJXU}5*+Af+dgt}gHR}SgPH@aK&e{++utm%Jqm=r6YY)S<{wf2JW zU{f}b{SuWgV>%meRE83Z#)2UVNEB4)$dC*Ozb6mAYH)I~mf1A;_t`YWjQlun)sj`M zjk!JW-SP9|v13oSNY)9Qyr3!^)(;4n2={%1IO4Fwh-oYGw}9BI^#r`+xVUM zE&=zx*}v|{{_`63J8|6+$p1}A{#cl%#_}f6_p*;>5QgOT=L?waG&owGez!b!-G7mw zL2;{TbX3g`c)q8N(;FMZJ9{die%@ArEejqnj}%*4X%?ImU7%$-B@j-4t7n5I%j@JF!z`u-@rR{h+zpHW|*B zyvXkJH}ot)dhoXl&tFjB$7Q{f0g+&uIMoYsW~Su~K%^HUetpMh3zX_{CoJT^Ty5S+ zVAR&Bi!Kr%dND1`vBfroXPXuT(NxbKO%ebxlOjMz&=ow=WN|-89 z#z}YvG0p#CoOdMI+)Qco~ z&|HE#_oV=*)8BCV-CsDd`hY)7))Rm6_0LOPapy@#o8Ak7kbzgE3(33;&9X;!Aj z2X{>qvMERAE6~Ej-gw}pB2kJc3bECoEa)0oR74;8*4I)#;z0%ri^v9A%+QrUSxo*@ zEOD1T&}vL(PAq`Nn5CU~W&s_XZwLCjV4lHo<(6pW^pDOHiA65vQNP{O#Bd7r+wus1 z+?Q>0;OX{??lgoJfDsuV$S~J>5Pq#@Zme9c$VS+4v&)EfgrUdkysBR%R#WBAt>&hE zG^4JQ@WNBpw$+A;l%;!9ON`(-?oIa>tR430lNY1O*Cd}I~8sZdJ$p`2fyR@Y{zxpuPGgjO}-ejy)WWLa9LDwp1zN{Rl{LJh`>(Uf^%uKt~H`(lnC zv@j6vO0nrOgy(r8qd+35+O!b{=Z8iSZQgE~IExt4;usG?56RsP;GU-Ks34ymJ%6ET#2ZdnE6mRd!OJ1cHA_eY8p2S5ko;{hxgV?%aaV2ibH~C z1(1}!F{Jl7N$`kvxu>U%)=1TWa zwWlm}&Q&LBm=@rF_T4u@-m)UhU%5;MH-R~Zc?ICRu=k$b;zzw`!UpzyDL!xdvg{yv zj^Pe73m+n-k%lhO{R;~*_GCm4iXo6Df3Z?HNJsuPObZK zQQa=ClZK^D=6U37i<(Qpl;+7LeGXd|oqHSD+cvB6;~GSLszDz9pwaB9_r`^iJ)!QK zeWAg6DM_~r%C4tmj3*sVwb3#1EU%w79)jy8FAfEE{T?u|oK>uEr3L%Cq&}ckSe*~@ zUY=A;ct~s*f@OylnE-ya z#XX*grx7AA<@{H&PoiAq!ZXjY_Z|PrE&$90!*8qm0>uOQga7^~s2CItzcw}g5k@qk z2#tRq29hrEE6eAzsuQB~Igg)+$^IewWrN2HItml{S|~qGsbs-d0Lz)|)qL5jDWXVd zGhFVKMg!F&R_Prx$YD!p14|bC<@_HQr6=)nh99r{9QXW=*G^cQT8_9dJ6j%en<`P< z{Rf_t%NPkxKbd#8^H0*cvJQ)?HU-tckP&-TP>p-!tym^s1}z~^7f{`C5wMDkCRSV- zzUNsFjCL2;lRbQXKkOe?v1V=jBa07b!;ksL={%9SJkW6m#0L6dJ{%v2XKD@;1GYN< zoF@>!LhH&EhFUF`(6A3BtpX%7tdcd?&EJ9}2;A%}hDAN`4tgd%Z8^9slct~w6hu|MATPRL<^8|;0(q44 z&nNox1>57TCb`3XD8+FlHY-{(guaB;rnhk z_f{zHasAgh;O0DBD{hA<{}DcC9?--mxX{e1a{OOcqRiB2KQ7OzPg%{JiA=0PE=j2q z3Y*xt|FxF2y>nBp-x`pKwS(VfQ#?#T7NK?+SV0p52Gul3WJF}oVR;)M`wEdXAQ#is z?GaK7&!7lrv$Eb&2#B&SG{d{8GIPdLQ%u2&E~v?BAo#X~2 zU3vF;RBpR8Y)!n|W$W$i8ZXnTarng`7sG(+n{XmoLbQC>?q{_80NxYMuR)lMd8YFc zYxG|8zt2Q)FmWeX6scO#CUJ5c&lTt9%!LU#>Ju_^^oYf`a{yEZBwA+Xcvh=t?}|=n zrqt0J!>SzWvSh3Qg@(>cU(_9_a5_r+FcmLJ=0{?qX&eISs&pYGUdBHxdi({=yE#Z| zHPrto!-`pMp3`~2iVNC5C>6Vh?CE+S1*YsQ)phx)8pa$3W-o3Z%xPrAvBe!{6EDh% z=~n)-1QX6oj#=9L4-wi`=ZM#hh$0X3(dk6Yd(6O|3k9r@gAvn$UwL9%j`I=6npj43 zdXoOFn-S&=n$gTU9-(jD$#IHVE6698c$(g1>QYE;hY>1oG*-9w{%qloE#X6YpIHf0 zt)iM|yS~}~yjDsf=2H|E1GA6*ok>`lWAridRwuDEM~+!-i7xB9ashx93j%R3W){BE zyHJN>qLVEV8nFSC7IHWN4&Y+eLtzeqOa_DZG>k`s20O!!1Can;zBwL70SMJ{JTilx z_nZwM_CiC~9p6Rmf@m#xuo6VpaKT$6`g$WqT5GI%{zL=>$%`U$X0GGcyUu!Ijjdd&^g z%Wm;mz;wcJc4G>yVQjF>$iGMB6lB}wxKZI&Z?ynb?(zx~Yfn7_J#~2mIlc~g;m3Hv zhPxjR-thnkgGROq;LAP_ifdj)qp|V_@wVO%P~?~pS7@s&gDIcj^&c!~-~{t#&_Cf2 zQjOTK+$hIeDeNk6gh4!Pmc|)$rDl&bf=l4PwwFBUY)a-Xn8PVRP{b>^qT%qhcBLh* zdlXCb%(}$OPkX!e=u7O2AM5UD?;|NT96RF(yR1QpJsaXDqD-n`yxnvMmV+xA7ztnt zJR`&j3-@zv9z_Y>p$Oi2E$C|8Chf-kue_F_f$xJK<46cxS1StE|B^q9-ggIOdyHTs z=?fJ-uFqB0-W?Gy2u|PC>a`V)QmTTco6`0-=WHxA8pObwj;Rg9VHd7B^lpj_0&0^B z)Ze2N6ipP9pGT=iTr3d3fn`2};j7>zVw(>}kPhcnAsS71VuV?Kd0U^_gXTEw!S++~ zv^5-}c}&vGOwuJHM?bfTtNn8#{IdGqatzJAi(MdAu$_ zP8c;JEA&1y0uP4QuO*vF>e+`r9cIur*&9K#vp#{FONsFf$h#4W*91Hhp$E9{#z3`V zLFUV0JAX3G;ZT{E2PQ+JjXu~`+$4AhG*)Hwx0eMULN>c~q*xI8p;Abn`@aXl8|=vN z#Y>Iq6gyg&qd8gq>T^`<{#EVt%Z#Z~GW`4u3?k5Q8|`{@4k`7T8T+~Q-@2_p3EPms zlr7agn*QEPf{-the-VuR{zzrpG}<(l>9cM{i~D;ZGkw>YN*t0$j)0IO=-r7T!94QoZx{YzGMpToH2I5D<;!sqjqaQw2jn9>(iF5#d-!V^{NbS`gR6Lu1I&| zaU)SK{+mSt-LO;)5p(lOvs5ii6^*oRwj3?wx~CSXm@PRwnV}o&olWDY#xquBAPc%C zRWtGLrAwgRzi_fxq6Db}S);1UiUoNDEEq>NLEW~!ytOjp zVK}1D9wwZRO=Crj-~s612Lgs{9@{gMK(6W6mzIOW5FZIk%dg#R6gNxSmVZdE_5XJR zYJgvcH6@5G_#+y7S*Y{6tw*!n5Y# z!3V33b0uKFWF1wd8g64nRKZCbIR-b7p9SHzKbB=&)_8g<_-q|*{U1O1pwdm(KDW&s z!~HsWZZq$97?hSz@?rdAtJ{a1AQ;jDX-)GcOU@+WYJqqO@TZh=va1ttx>4aa)-Wo5 z8+b8NZimDVIp3h5Q>=qDlK21HLy%Z`Y4-?}(Q#-g92GyVJRmhFpRA@VE^gBdkMKau zzSN*(jlMuc1%tYJ75>v7h{%oq6ncST=49N46e)5lK~TsRMXd6MMZt@&HZ5VyVF{#1 zr#i`nbL~sGtQiYLV5!i|HS+z@Fp#gK9gR*iByinX%uf(a9z5M(zJG z3(9*)waj8~TFYzq?cfh26ohalJyoPH8d^0+e0uhuNg|R5CSd=caDweA0Y$V1x`w$SD-7&1A-JW-p>)EcOB^EokdM zW~v>ZPUWnaRVOrtEXU8F^qu|+67WJXBh|%Cs0=9+G34xEx7e~B9Ef4=)gm9@X+p$;Nq?9WQ4 zQAe3JPcwh!YlxLxRXe|W$1+~3u;nh%03+tD^2zwyyEgk=QjxcCbGC~K;_B+SO{$Z( zgp6Bc_{*|o0b3l&m=rEe=z?TsQS~5%C_f&#u_(udu=qCo z42I$rB*$(x2vSy_zCblzUJ?!Wc|GWp^Lrtxz;+!t1^+x}t&-h~KO5zkzT!QPUPv-l zf+q9j3ps1)3ZuY}V?p)=S3~)aKP)TgA=-UY=$75Cw>rCAEf^;YydNf zW`zrJ?W@`foDu8D6@2b|Q4PiU_OXSRWdY8IKQh$GeU?svq>v>Z!|IXEoS*ZK!vm^P|IZf91JhTSmgS> zKmRXrzyBVes&Og&=4KBOji%JT-fU)NAu7(>!Uo=TTBu zxNEUE{w~~Rv^_C=pf@vv7s>v|8#JwW7wC!2xJ}IC2AL&%T&rt)An!D3YVfIA*U@j7 z+osU*2p^cY4Qkiko=Ifp@?>d59@j)?V;%d0N?H-{_s8o0kEp-!Yx)nn$8nVIhK-Oe z2^j;VkxohJuF)+e>1Y`s-Jl>{(jhe%17Uy&Qqq%dK|(;jd*Aox{{61~1AFc9+Vgp? zbDeW8A%m2wN_((^-enn7{%7BGvCVEfM)^eapN`7qtys+|8Y2_^Y+X#BJI&$3k9)?Y zUV-waMS2>7ku5jB8^^9IsMkc!zU4Rm{!?$k=sf!06v40I_t)ghA1}lIGDgdHd&UO} z%wBI|1`B*fz5^Kpb1P%aOy&MEAEkZaou!yYL=~SlJHHIyAr_W|o0Dhish171x4Uf3 zdY?K+Bm!^7)$qjK+pI0&44yQ8Tsv4cTEhBIg zaNOOBoP7*Dq^aYy{acM?9thEp_3x;KO%~zf#fa$eNNb*{ugc9YOB}Lleb@-y&+3eY zF+WTn1j&^^j`grubAG702;0HArNGBcEjUww&rF^RAZMPCE&C2FAJ=+yZDkwYka0MJ zE)hFdtN+~P@ADiyO?blS{oIThFM^$>hP4C$m36p88jowViB?}y_}P(<0+bJf#HMiZ zsT_m_f6smuR`hKIz7>+TI=0PVYvU)?|7?6Ag2Kf`Fpm zzeuxff6>6A{J4o?B6yp8Ji$ORY{Td^L*a^1;-y+i^?<7;v4`gs>_4^zeq1yf3Q z<<}fAmG%kpvA5a25v{OY24_xKq)=(IBMSi;AR&M++uCjdJz9vGKX6kRX$l&NdMUib z{Vpk_LHvJu@X^hk%j9-X|B@%vcb*2nJ{HK=1})zh-(K!X1V&FU5fZ*!d)=`lmGeC# z_>E)h8(oVc_4aAE(h2D|+KYa%TW0@4r?fY$NSzd!a@1dcHB}^FwAyCMrvCL7s$8q^ z(G6xyyCJmop`(N-oI#bup5)QcfL`{`=ZSBW-N>kew%25J>K&7Lzw4(N&(QiFnshzk_XR`B-dAc^8=hs63;SE z$#{Le{rS&Uso(#5OD1J_=2!q13S=w(r`Ovt-7=|>J*h;M%`R7ndzqILW_n3V{GeHR=3AU6S>1nXDPca+O(d* zOH(M7eZ!O!d}bcaPhmnqWjmg5Vk>jF;SQC(p$(HRfF&uXBng%n2JLsDWEy`XYnd;%bpd|lCd(ND8N!z+VFNh5+_^Y zBKpzqlndSu_$O1}jAzJG#<<~@{j1y+qQ{)KtI~eHhcp7`@(I-Q--!|7z<120@|^zl zimQs~j=rl8)tc?%%oQVmzM9u)36nE;zP&&Hql(QaGT>~Jon25kB%d=Gr zPJB;q1Rqr(H*C`L#Ntk|UrZz69Ge6g+!k}HQe>RP4_^M!=zY1#npigWGF(xUuOs{5 zN>&)DEE+27-*wZ{Js{a2j3z?3gM>y}NUGL@NzR1-${+TIbXxrg*}l1*lN%~(Z1@&~ zu#ExY0vH*i;X)aB=-`Ae>Fj$5U_y)$k~v7$$Z93)Z&~fDy_)^X?tKlDZjo15(q5In zG2MXXBXM(>z0#L&0-Mhs z{jta@h$?t{b(FVZ71IQ}$6GT{x4p}@7)}}fJ66DAK>jTw5WK#B!S<%7Y%1~52YfYM zZK)&VG&-Du7+l6U{cQ71Y5cc}y~T{@e(xRtf({zdcEt9t38Ugc!UJm8#JK<7#SZS2~~ zv8ZV4YRH{&VPcpYk3bPK2o-&o^+>7yq<&e$;-Vn0d6DN6Mi5IL-*PzK1K!E?dE`aq ztz0jad=2n{`3%lLRcFj9fz~tY5hyS&E6+`A4EBrfN{VB{GY{yb?+ackhi& z6R(_77*8$H$>%TYMARB(erODt-Y)*KF@n zy_zsgR;4K7M1**TUj_hlPYFVWx#E&6n3M^iv{!%z7=4w=ZuPf z2lK*rde*%e9Fh~;^jlM=Dhc$?3L=QjKNw-C5chGpFoaNDSd&VlZ=xA%B6yHnH3vtC zz=CvGHpWN3n4n4IkhciU~0GJSaar7L6N*AnX z#XWzxp!h?XC0G}nHy*GdhyELX+{?-irL)kc5TM+r*Ut7>O(?3G0YBwbm={m>%{7V0 zbdr8z962qA$Fr*3UDZrnBl>-`rf4*;Brjj?WBoE({;iBlKR#7_v3=izu>9(k!;hfG zcWIA-@E$uVB|K_^XSsf*$Be$e*aMJ`GPAkFKXoDRrAATj>8&O+2%iG@O5Z(F1?t+T zq{H5cXp&`*LvK_#Cbg4Kk^uDdPdbaHPYG42(3|-nPdr85d_E1b#yQdE41M3^M)i$P zl$rZ4sQT6zzK!y*=8C_h-d5wGEe2#Qj&5U=_nQKG2fotN^KtWC!#^ruWceX2i2ld9@%2l)>r8mZPn)7c zKW0M7nRgE2b*9rwCM(nYBlx)ep2*|`Y-pqOwOlFtyhzRaUGXUjB!#fD3w<`d1Z+fD z(bDcYlITN9QgKnK!0=hI?Pqb9cWJkDOEI)!KcnEUzyNnV>X%CsqE00I2u`wba3NqQ z&tV})@^z1c@9~!(m)Irvau0j)Mn$ie?N34Qk%?>Pg7z~ai$CwF$zLZn(tNCWRQJ-P!9x)M7N?fR%TgCwAXXoml zVRv?RbsBaT6r{K&EE>$g=dc|=1coP?F{o;-}rG$o?2G<#^ z;^+$Z-D>dsE1CE}-1!7;NB;b75&vi}!>R%Le+7=7Ag>+?^8IKqH)iT=Uj*+GnH({7 z@aaSBn;#w^5>QG5)?jNkoT12hU?ZV5XyE{{+NRqiuk!(OQecXS+M>PoLNmET#W1np zGND9koeACv)MY#VgGBd@p`D{yzi-FSW&nO5Z|gK8-ReOa& zyYrT(2dp`B<6+91kaekbA{oeOzHK}_@_n$q2aLJWZ_pfGJ!M6HAfwee7uqn4*#>bb zfMy?XWD>btfW> zPBNaw@?eJ?+nui>r%QKEq}*V^v$)Cj)Y_SNcd+DcqDB`Mr)tiX;5kn8Qz7SB3MzjK zjS4n}4*9FqkTtJ-+lJnWXj8~hAFh$h^JuKU`VGm{>C|{qb9-zifw?RHG_a%wC#3Oh zwhg-VBp}D9@L<;dE?9S>&c|QAqj?NbL33Vi>q?J34}h-0i8-IzFSS>87dikVez#;u z8_!!W&e?5w@JIr=0evtpm%SL00X#=2golx?B+*0$Vcg$2MNPzKJ#a0uh`P*^5v*k> zbS6dD(`0RyWaxe?oPnsQm{0`5YrT`YVFwg9W|>8O=tkO=cfG?Uk7zg)HMOXFK%}`y`yKUo$2) zrZ8_O+Sh&huzoSv7`YZI$SL7~_m#wBslpXeg?QxOqm1+deyKxr@Pm73GDwMtbe>wY zkM{a;oa9`K7TZu9BF}YOgyceNCPSBRxa#@1?$YCJ&QG6!t+RHfv{D{UipiJGdA@|H zjWb{I0~vl%k$ayPyHEHg!+(knb$?hzJ_7f7BRgd7zN$Tp_x}xOFb$giDij1yYdNFD zG*|_k5!9xM!Lu-%fSuEUJ&(bND|#`}jL&S|@6wrnb$<%l`YMEZQ(?c3!!os~M~1V{ z=wKahrf9c22M}WtBYKZ4Xa4XaX%GugZF{_tgM|6F^r&-B{I!OFbJUJkQ(8#MGE$bM z?dwa6KcAu>-m-GP@+qwDy=7@wy-0h=eZ(=4BoZir(Xn=%vqF-_J$5<|K=sB*rv$CH z9j-gr^zc4vgJY;6J!zc-n&U4AxcD=bO`^T6+OSostC*O0F#1h&hn;0ZxIDn|?^m?h zFDN)>Dr_O5eUI|~Be4IL@#pK4CP0jsGS;Kt>`QK_p^*h8_goo7FhatFF`KWhu`|WY zT{_WA%~C#WjyaifApaJ?s*}}`=%(~VFA#mBMd9Ujmx{(sRG{v#UB>Cbx?5O}D$yb^ z*Oqn|`^m2OZDzgZRgqf2G#W;XGTo6K#|@tZDAwWp#g!$)bG#@EPGQq&`D6>x=R(G8 zW0U7M`adEh{djr3(k{bp&hJPi2HvNlCPU&RVg&5tPMmm+lsLbOX?kdq1uF_l6ZCiU z`H(e){v;EBCz2bsPmXqt?|Ql7EE6=$bkXJnYYH98IdEIiVVB}0o=LXX)|s0O zz5at^={o6p z*YI2~IwIienZszJKdw7hoc-$35+F2!%_kaej&NfcD#63EoiP@}vA!a*RyqtgHRncZ zA>p%NOU%AnkqixCU%;uJ5i%;(_jq!5WQLz!J5Epd05n|`ipNESl%ZAr`awY7Yj&Qy zko?SAW9B+)af&<1zvPCfuD*}^s`OqmTgB7jYg&F4@jg-0fta(l7K&ougQetU#&)jg zR7{XIEAl1GV$e=GT;CA;gPn(uPx?@$UvK8~Kk70{H|^>c(m2_nzG=XnN41phsHVpN z;n)&(p9tu#c{Qk66ub;-#Bv6&c*eoC3906PwtA)R?ASs+^L9xORosyj!)jFEEEp`Gsafo z{|xVvT3$x7Ih%q=mhqQ^cFMXrDGNx%iRI$Z3NjB<&JnBI%ooeeR^|897gMi6%9`?} zEcE|^kj=SjKiBTScxNP=OY+Yr#+*IvP^@mycW^)W2Y4*ql5dJ|u_3%F-#aBa_Foiv zlLY3GG7$;3v$iy#cbH>+Blj5ym_(VFFcp{)X@qe}Zt&(b`EQv~HI0I%Jvkd|}JLF`8@0kuOdbJB4H4nd5Z zbB~pvKY}eMa~}_a@7v{Dnb_krqm+NgPP#C;pA*j7Aoalc_N2OE;!M6UhX#BX- zChOl;q1xCR=eiuzREJ)~2+FryIY{&)Kvf}V5Vn%AGPxk;m%F386;c6(I+P3N^GXOU z-&6@{$UInYIt*~=SVo@Udm5Kp>iu7RrU;7ESNbDzK>PT7{_&1|omw6K9OQGHz^Dx4 ztnjKH2iE*KcC_dA!olz{j&;GsVInmt?*9}|%-TZ5YV*z!WZBW@fM3k(U1Iz#SD)wU z30E<1{ja^r7njN8RsH#`$Q?+xIs3qBM&>Nl`JZBoIAxgGhoCv-g%`fs#-sJ`?T#vlp!&{|Z_#8RJB4@C$8JY} z>R`+L&e_n003=>w5VjH^q?hOxD(P>DYq`0u2qPvHN;lnNip#xF z_;e+P$a&jq4a)@y+Cyub$T|tGPb=ybnUBiNJfG+{^;FZgEQt|zT`tH}7>CEnP>Q_!?mNwRYDc+H>d{0|+e+<|Jt zf0mYbpn1IM%Lw>}K#%~Bfo15=QMht`s|=rI+*rU8^c%U3NVrrImiJQ4mPEsVe=Plp zcqdh-4B>n`_P%w`I)+z%u-cU5Dej<>@7fV(wDNes#jO-c#>pgU80wsqnV&$N3hh); zOiUMEgCzqw#fp1&$^uUvbGp`N(S|>NJeQqlqod06TE%|OK1r#KwU*H|A@iV?-rU<6 zH%Y=^FBpQACUB8F3)DFk$468{@`%pF#j=p+ezaMzG>3}8`p*7)Kbenj_1-^uvZkBbI7b!y-}<{bwL#Iv4}5A3bW?I z&7y^8Py|cK+lMs%xuQ>CUI~Na<%R~w{M7s=GlkKJXQz_je;0i}kA^d>`ZzXHZjFGu z4%meAtPP+})zfx{I@n4`@ zw|v0!mI*ePtX=>0QOj!xru(SGfI-DXvB!uMK+h!FWKmpXyjjpjSS%Fe9}WLPVZygz zk1&r`D9_Bl7sJ{J4>)D5{B&dvZ}J(r*EGI}k^EB~qhNv*L)^Ep`mN+fvWRZ@TmW8e z@!8qsAw>LNamI~p@-ue0<*0o0L^SWl&T0v3KAlMjZH3f1IRIbyv%j&9j=z55@ZDC` zZQ^SIh+S#m6S3mg0N7dQ1cAM&@LT<%Dm4f6wq9GcXi{c; zsSV4i7KBv!?kII5jINz^?z(Mb5jJ*V*wgN+IRxl!kvNPue4~xp3WxGHTOyl6PC1GG zV<)!knc<`nX?%#dHOp>R=x!-Ae76M`CGzDy380R7~q)`F&C6g#6oqdzeJmkNS<_iWP* z@duFeXy;9?u*3(7^Zkk4tV;4S{IY#!T0@FUuUg$5Od8*XQdRuhj#{>3!3wI}OZ>d0 zPNNysgXcwDhk_M7!9$3C@CXt73n)VWH1!rg#9>CX{C zA#zCOQ!XI%X`1xYs7exa2cBWsHbumVgI{=$D%NU?G@F7QW6m0Asw@a3YsW!erFhz* z9N=8>+~4o>a}gkosz`2%03bR61a=EX8aON@`tB$SgjZI{zhFD;7nO=hyn3>CS+dm7 zXP!KclY_C6Mv)E-1Ik@!&Pvw{26R#9>`vCN2KhCTUpF|XPvr>?iz5Ua>MN?Vr}Erz z-y*$;8*7QPEa*suVBN4;nuZ@P;+qa+sstggZ3j6ENt_3J^xxspTNPF4_ya9{KJ(E@ zGWVYhu9vQ(SoyGxpX<}rVMh>Nmvg@T_Xu;!B##HvUVCj`E8ZKme-X2M1g`^(SWxaL z2{%0YyZ`4px9d6^L{ydt&Y;a%CaW7z6u3p!r^7Q5pQC%Jz8Kk8jxVGodSjb#`+!q| zf;(qz1%(sxyP{WzK0D3e`+7yZy@i6)uM2P07(4cW)K^DcX&sSwcK7>>4L?r1$QN|q zuB}{0{Yy5wCS8vdM_XVRAd3MOOTDdr&#vL`cj9OFK6ldG;&LA%x}({+2=9ZlB~{A4 z*{V*bf_7mF%KeBaNjyw2rVdIEC95NK#r!h?0V<#c0H5U9t)c~T7jRpMcrEHUsgjzc zEO6;ao}$bvXp-flH*#;m0uDG+E!)8;>F$YhA;gr%UBAX43+4to$-8Ff`nTWr(?h>( z0LsCEe0vCsyn2x^#JL4o=Z;Qg|99nx*Y8>zA%KfcG#H#unL|{4`0!ypm_m#``%cDc zGlf5k%F#|Wv>cToA zi>kxE?rLBFtL=`7|X~%;2^a2vwDHtTRi#wf7@T+lZ!MT3cvOV_Gzq(;W9ufC$>zD!lVfBqWA> z&c^b!*M67n(u6Vh{>c938_+E_9l4NJ)DV5j5^0KUH1bDhS(^rl(;XEKbtZk1^B<$+ zyveBwH=Epk<}N%DoJ0Lw?c)O@0sNltG(*+a`mr=o+5@y~3v+dui4SmvY&gT*2{o?x zPN`u<+lyQyWF=>>rcb2$MAOX}PtG;!zZEYK)&H79-s+T9rv#EtAJ(+>EnUqoR1DSC z908IY;qBq=CuNLVs}{GQw{k9dHbtxqiErz#LRxqaOrKEWF?tsyMt5!9v`-0~^C@oD z)!pZM-o6?UZ*V99?Fsky*JWB1YmMScNPJbER+aeEb(_SHud%SsWb!5-&V2xy8!>`J z(F+H%2NDNLI_&K7e$jE}NQOdXFf6aRVT+Y-#=2}w--*QLt>58`Lv`DcUY6D(o-aMP zmE1+#p@4bnCF({yOdh48z1noVT)+Z`71Pn3F?l+@!xa8o09-c37)}@SKARG`_&3TL zrjYoEIvfy=_=M~X``Co(B+|+W2Nw#GRPDwIzD_)GVA%-yk_2=1Im`k)2Ynb61V%nSIe-RiUvuchRH^ZH*EnQOlUlyY624GM36Ef(Ys4;_* zb449qArlatKn#5~=4im~dLWVi6@)RMMJ!YhBKSn|sh_SP$!n>^@sI zkF@1%>0=Y8MOK#6Q~m@StZvRH+UtD*y60OnY`$MW6)wnt821ie<{-+=tq7t+tU&w2 zF@wJQF7ls!cXHz1t6|$HYHlYVtrCOxz|1f7HXz+`0Nj9~;V~z&F)LK* z^32{d((*P&q)`*wSCDONck$0&CxtsD zmArw0)}yX^9FhKHeaYyqYFJ6%;u(FAY#rmTU=dJ5=T2bgKlS$B+v6{h=}wDWJT)FX zFauhFpx&&fyg`Dd24qLq2`B}=Agin|c}BF^Ukdhj{kYVh=1SIuF8Z|pyT1aEXl4pe zX83~av%qh9cm)j_Ay8L;CPWK-W8q3ETUM}_MHwSeO zua5KlEwZ|WcRqY4HhH+0{{u9!uSKQHx>epi1E z{o=v})C~xo@=_zFc{{A6pJK{Uq#`VG9F%2#*8&b>PqlND^HDLm$RAT8Z`hZT z)f}n>pda+DMUfEu& zOMN~PH>;VeDZs0`uS~o4u5seSJ|c=Ki|W-3>`}DQs%bW0g(^qg(hC^^NJQWesgjaC zCGyvD!sxl>uu1dm1?uh2S7bn#^^bO|{X$h{{7(WO>pmSSsLBIzfE@HP^p!F}Pp2=+ zets~qf6sa$ouL1fg`lj$*7CQiXf%Ka-~^K%5oOnRdBzQJ!p^8tW&TU_@ulhTZdO{Z zI?9J=OBkw=WS2>q@@-XH;P6@E(d2I^?bpL+qYk4asi~j=GClq$rgHw-lNZS6XO6C2 zg`(EaONgf*mERDHT3h%FGz8prty+v5sU~y#a~8R-A+vpIym; z)gt)#j)7BIbXM z{aS3(bVsD!#ho~@!BWNz+~`a=OE|SZI~bl%xs)Sv>IQ86b&#Pv7e<#&qy4=*S1CB; z(dw({Bs8sIcgXp+;6T63+-v;4}6Yb z3COv6SSP1j>a(o|nETVVpTs9M%!^0Z#rd6(5~HcoBu6Nv)<*s?I>hEii8qp_C!k!XxvjGg@1DoBR7K1wtpX|I-3|8G7~r`s0wR zcxXY2zD!W@iNNopE(Ca%V%;k@Zu{j|f!thiWaDqN@p$fzf;%QJxanKa z7=zrK)@}H93O#Ap1UQ%}rB6ag_VFEJU3zr^mq`Q!bwE^-SR|%3QO4=!NW{;?{)dh< z5`);h*ng>Z48LZSfovwS_qSp2oA$;Gd974_Q>nQV7qAwWzqe@+t_k}=#gAFJVN9jX zhbI-N&w(I$!U|jKJ&u+R5o&Fyogl0k!@7VM?PHmt2>IX?7G;ja13jv^Tc6>z19H(jjD)Zl$Hq4c%&yv--i13PazTd}uqWZc_L&*0q;(7ecBGxw{>$>r zkRRu_4)gI{`W$D<)tGNfVnI|8MLI>GgNz*#&0WkJV?@lFuugJ$Mt0K4#-Q257);D2 zbXPerGXNd{$CID;Dyp}wyL9@0$?kG(7$c;$!nagahcaMCJU)CJs64&O%mePcoIEn0 zlcjw5aV*naqxLBMdB(m+<710Hh#sG8Z;se- z^0wX%v$x-|nalV!ILJ6T_#r|#xPQvLXZCk z_|+ZO6FNn>cdeCb*F;DTxo2yoL4kaBJGiOm-}hL(O!Pj#5|1>Cb{+dMCo=P8)s~hG zcsqhaiD1TH5dM&Ef+(TfB#eaRaBZDI3&-Q!G1=-FDMKJpgo>qq0rr;2 zPGEeQ%L0x9mOBZEeWcTnLQ`ZU;R;sChqkhURU##Y(8h@cZ~N79o%5B$=#wC@6z{?@ zjXc~DWF?Dn!1qodT0HtE&O8;)ZgDnxoG>f|Bm8+MH?%lhDSyBBc5iP_@sMV8vVTM7 zYI5!G{AKUM-)F&RjL%9Ae;2X_u7;lUj>uH>xz=VE_zD)+_W1H4pWvCeN9~y^%<)`<*rm-?A3L#fzNgJm};uVs7iFE z{)KrJe&6e&-P%Tmnd_!ZA1M#!7?sRp4TMT^ZN>i3(`6m{(I)@u`;55P{*VMZ0J6;5 znaOJZhl5($=P+~odS%r^#;TK5j*+YjTc*Zi#m-h@%o zu2V+`ZN**lxKHMB8-o?g53eK!C*|GYE^T+{C(_M;f%+bB@og+%JhO_NPti?fokJHq+XIFRVA8Z`nNpzQUrm@TF4pGFQR8BG>*f zk?;^dFLOu?il#UdMB|$> zpHT{EvYYEH7i36jZ6{Fd3>Y+>fW4*WeC+&DsOFtYGH*<#h8(WQuYS2A<|M{&K?o2Nxkhy&ukhuESmHsa#;QSyr!j=)iwQ$iKxC){caigU}c~v zlE*c7+4f5ZrH>1yZu!|qS8N5@9_Z#Z%E{0LzilGVqY z51;a_7fZ`2nG)pKoN=9b94^S0(fDj3$k4dtHA?=3w>)6{d&sTx<20RTE`1QQaMixz zrJIvCfel-$8Nk*&x;!Oowm=1>>0{UZDy{&{u~S*l>a-@Tvak09#P&vWMbJ*NT)-bW ze|G1bbwiD%wUaQPdwch$+zh(x$;p0}eCDaPDPy&|o7BW^6^u6l!g|ft?f6RjCFL(6 zm^Jj;C(D*qFKybXbZpSGf`Q#AL9O0ymUVV!yJ{rRBkmNUz$*Ff)ak`y?4=?^6^gNE zbrDTXh6B+4EAXbisgZSaiz4rfYutTm;+>$n3ie7e1=o&jZ$p)tSUsbixw13awmF%; z04sni5g9@KJR&{}EtNh^GwPM#FkVWEee@^rtKXld!MusJC!(53b8B=KPofgX^7MbQ zkRuEb)Y1Ja?qUTqfr`X^q(?FoZnYK+czkqHWZpH4gOAnUkv&O%r|K!hdiIWeRv9yA zS@=h0A-OFUo)@pJI-v|vJ~L1w1w}&@VC0)8h7u4G?)D1ijm5Ofj{4q=nuQLL zNo+I2g@g7IE2vfgPKk0BZ)|G0Il$AMkqi&3{mbQ;^2lm(NaYtgdohyK=ZX280GVo zu*hAcNUE!;9s07OcAOUT9YPRdNND_P|5&z_3e2O7Rj9kqT)&QM73T=sZ(eGBZqojdcx~fLj@6#^J$xtNI!o3I5@s;w zn885}1a5s*Vxzb7c=&Ynhl7fLDq@2?qNGIjCg3sof;a9zW7^p1M zbxzsK1$shJn6%STQ(T$ynk9MXCXsioI!b0o`m8p=CfPrlTx!HQe300`{zN41bT+&z zE7f0H*`dZ^Wdg2Ik&|u`IC5V@5&(WN_(9hcj|5rx8*bW2f)%~mVgKqQFg`z0w%`<1 zo2Lf|N>v@LUp+7UlbHyVR3#z%>aULctYT=qGxPwp1IKLvbzmEqDX~Hxw#wbc;C~{# z*OIHzz8Ub)w+Cg_%Mpp*o7Zu=H%mKmh*TnUA_fSzyuE?(5yb7gM`aN;dASp8(-fTx z;=jd)^awRgAs)dW!NRHVqvneoN@|-Pic^=M{-OUnJlU zkee)8A2uJkRxV%I}raF~lIJ?NVbEYx5dJI`N^*HIw*7^Rfttc{uUW>95r!SFv_~Z3{0J?us8v4PD75 zw{JR^HXZZ$d8Q!DmK@AmF4hs<45u7EuyryXpCkJqTf1VMeqji`GMub%jaX4S+ExcuSxQ%B6HM@+Obqrf}NA8;`J8?q|y`r%&LdbTIX9 z0u5lWQmh0WZq>FSRJipak)Ku`=yE_|}-x!nav zkczCn>|}Xyn0?j?TtfzLpAxJ|=EWJ|R*IJ_R~Q8ZlW+EZ6NLz1hrZ?E>cf>;? zF`_1zuWCbmB(bZ>xhbtl*#1s{zNwF8?B)QPZU0J9;F{tSc-}e*c>I!rAnl$ZwP6Lg z83c*G(S-1-_0QC3KNuR=^8WpEwyDl%VCy1?gvHQxQ|pPiT*V&@jE2`IlweOjLXs9M z%4{T$gvzeTSTtnl%GbH=OMXn;X``wz7$><_)~~SxeSEFo(=-{fN^1G6GtE}-u0|l& z&wOwuB>Icl&!GIr#jJ%*+W%fAd_fiP6~E|-^iOdR{y^4ng{zr|sHZSB%Vp5t!d2ocRaB54a=~$!~Wmgm<(GI!sw4fSn$<Cj_D z@Q<0A_$L(y%SH-RF2IZ^!+(>h&b9I#jdktV3y<+h#&@ii*yg%VFY5!&+p5|;nPSB} zH~e>Baaf%?x5Z9**&QaR$PiD;WZMg6^{c-AG;irKDY{hd&)j$<)vB`3J<+$bE#WwV zKaDdWb=inKvp5iZbJs=o)GowMstnDY%BV8)UebxCyrT1BdM$IL)mH&7(0o0=JJg!T zn7culasJwj0Y%WGprHph1kKavy-Wyiy)>`j^CO_cojmVINi97+b9LX4j8tsAoAmdX zi+1~wI2JC?9H;P2WY=ZQM$6PXd8hYnruSD-AZoPk4!^7fggR3{CpeKqa ztYd|kNb~WW@OLRK7t7QQdAja>=LfP%g9=U@A zeOMY`t>qLf2MBDP@Ft*&7J_*xG={vPLAQ`T^}KqkpZc>hCe#oC;xb2T5GSeQqa_Q) zYKBw}I4f?2q>PDo78O*v?ca%1?CTww)yp~ zQi2@)l-PI9u;vr{d ze5GeaK;TE_={quXZz8o$QtE@ypF$+pchgAG0|I~TDlQ>;;E8+>02KeJ(~Do8oeKfB zS4|+jgb{vMmHCJZzb14FHd3r}AS&yfxsJ}z7J%S2VMvim8waEEL54&zI_>OvU|qTc zsXZwiX3yN(Fh8mQSBS>eIlS8Zz|}+4(}2nFj=?VHyR4ag=TMhpww-JEB~9_4deubqFJNXs>tuxb=k2FKlas39)Xz31waBh*`Tr+3Q}w(ksf z2)J-SH+ubXQ`ufmTt-=qs*Vg5tqS=NF3wG)g=WD;k7iy6KRuOAVBX>9L`1?Sw9BR@AA}0POq~OpJ>Xyvt|K*JcD% z7BZnWWZd#sWZ`jm@2KKg3@$D)=6Ao^AbfyxZiP^l zR`(ekOB}9uXfhc@n&k8B`QIAS=&2Brk9m~Z1rCGGumaE{ZN&AWFD#l0JpnM6__YyL zZT9S?#JrSEqJGw3_`$*Tah;KFa!&RA&5=0V6@|H-zOPLM3`_t{T5RP&>Z3My73&Av zH-9&LBTg~G`Er!ne^!ISX^eiX`!)yk3(*B_1MQ$KRUFJX!gK)G)=IZ`FNR(PE|fOa z!R(Uan(1I!mv7K*O_Z1Pf4nf_LX5odZ0Goyn@cyUT*!sYGOm*Z^NE>T9E2l~@VPmw+2AHmi6&NGqLg zDbqL549EBK@bSIdNKjUwNmk~R>%*h+_hr_tPGhxK)d2CD-(b0xdC*0pRTdfE{+`qP zEnLRVf_+r?lDErH^v2~YF<@RVxIUMaVq6BT_?Z+6gvHI=!NS6dz|Of-xeE600991f zpnN#*&96coee}NQgjCP3Tp7lgpAolq^{)w^vwA)D!d=xNVEx;KK;xy_g_TpJ%6?hI zsJ=4%z?XvV8$NEz{Q)jG_1JTS|;XhQ_}Tw|HUQcb-S6~%%r zjS5~yP+zT13ZdwTR|O^Tek1k1d6D6sGb%sw&sP@9-kKmBCXEo48f#Dt>sf!b`5)JP6kJPh!r<{9t%<->d>_w|pmUhkG_Lq!#Oq}7$B*Hw zf7f)3HjY;qshwc|&HFhc%^nLM4kRhWlK!Vm8MLx6m?#)oF5^F?=9x{Q4nIRbZ?EoX z?7P6Zty4BJmlB7=!oFOap4wyieuU$}Y6(h3cKA8l`w8wwnWVFt!1*N;$PEFD?gc~` z;Fa%)(DxJBaERJ7z_H4r&zZ1306NVKecEr%AnH>ZkPPSmW=lPXW>IfJxn=!W~LN% z+S#NB?V^*;RN<;B|GdB)p2_2sOmqK#4F)>#MME#{Of}B4t-rXW`iF6PdrY2^=888j zXqa4c^-Q&XW%8zHQ8&>g-!nHZ4zpg*Efr*c3o=K1(3X5F-onefWDdDzZU4EeODOPe z&CKgzTV<2UR5(gxptQ=xVTH8`aO*K~FPa@gp4yYut;ZwU!P>E;L1}0HBIap_!MXI0 z9`N@~?e^T?%vTn-VwB3;`Hz#obr(lvzn9&(wRlnIqF=gRB(Ti#t~BWhN7CcKjb{n3 zrVwKelERMmnry09Saj`8Jze)QBST{7iEVBI89}BsDrDstlr7qc+c*Txgula^60V$9 zssD^D?+mXPd*D$bb|S|F6BoF9OJhRcK=X$rMoNX7@m7c!swWGrvm@F0IIc{nCW*Ys zqKzrckXZ9_OK5e?Ha$-J4l8g+S&XNNZ5|UmW+{Uz#Q@|rI1}<9%=7;rQ*Xi5#sh6{ z7k77upe-7l;_lkgLUDI56n6@N0L5JjZJ~wY?$8jRc%e8X1TPvi_{;C!_rKQt05h|a zSu=CaKF`@Zaax4?AHJjFRv?)elv*U{H*Fq9mxlR<08#W7Rp}R2x#!V}%H*O-&nX65 z5D(i7wdb)W-!geluO1t(wt?vuJ6Su&oq_=NoOcb0#?^62Jg%J03m)G++Bwbm3&@*I zJQ!wX&--LWgk5IXLkLBMPWouAt!=4kS7RQWz|0b}`Gr6&Pg{i4BS@I#~u^fa5ntNqw)@-wT4xGz99 zFXQdEh0-Bv3YA_@UvA$Oux4xzmdl=XXTLi~K!u{a@&m(9${Yr5l<@|_Fr34k9VK{B z_|K_W5HVVb(pzRJ(kr6liKVHF)|pYmY)!Av)C)&etJ}_v)mn}0IGK`%Go}_xA;Ty6 zEcVNIYe6GXmO?Md#L4!#UXmA3OA6MjLGgWrKR1AM2R5YwQ3`dQJ~&F8q);a7`S2FSEc*F(ncp~v~)lRe-3{Rs!%$am)+RAa0suXzze0r z`b-(MSUqGeKx_h60A#<6l*iby)z~yjn~&=QZka2y4*My^5n15*O(z!9C3bKM~h%BWpdjLO1l+yml&NJ#)}mt}_GpXFs(rEH}FPI{N1lO{D{?s6~VKq7l_I z)f#lJ>wWO^ulu$1F`p1^)UKzJ+;0K|j_7HJnaFK30TpTS>XaZ$AC_#KqAi7@+e-t? z+_@WSEaM`Vl`@903i_hy2ohx5Qk!!!KS-3Q&sm>vn~3bH*idtMhD55o_d0N=899EW zOSh0fN>F2N!^yaH87EIx5CFW5GR`wp7yFN4NPPX-ojJ<9#X?9!Ji&>|AFm&aO<-=a z`-MTmzpT*o9#)(63=JOC*>`O+d1I^h<$STPac!G?`bF}H@EEV}-R+G^BIWeuG#Ved zsg1(^ww*Eid`@gplpe?j5kcOZ>WYuu)V2y`4}pT$rAM}uY$%8`lbDhp^INu_>?V@H z^8}V&0$&0?SnH)n#Pyy>Ne)q^}AV|;0^h0T7A4th@Dry74%oS?lC$c%@WO0 zbW*K+2#DROV&5I}^meeCR2di@^5Q;sqEa^#O#fbaJSw!wUQBt zBvOGBrt&i@RTB>?W%-hp3pJ3103{Tt%8aOS4VPPO&h$^2Wz0)ij3d`md5iI{c? zs&#R`(gq;s?CNP$JG|=J3v#svZ)6wPzV%>mh^NDhSv43X0>z+;{lbV_M;Ya~|`xGHS^Rf;Fj-N29;mu-@~2v=AW-CMc4qX=B3dj=%>|P0lIg`lSrs;_|vwkAeTr3iy#b9Zhvei3y`#kD20Jhc?C?dM-?Y*0ZAPT zH1Z~ww1H+A%4o)Ldxd6J9Jdbz=)U~#sL>c9d6@@sv6Y2GIYd8zu87y+wk3Dj7yInH$iD#o6(4u^PQl)Xd9#F;qNt z5CL@ACkiA5@9KxK_Eh%GJ9fz27}40@X5ln>S)E7kdRnthv=IRTP@$NwfX9YX3TvAw zOp4DAoVI8&VfP<<(-U65^Qr{)i7uqH(Cm=pqjyDyTJ3dCW5;O6oqa){x980)*)Pb% zf2qr9Q=w4Mun=AUV?pq8%w{SwJ6{Dm?(ynqyy{PiiLKyHj*d7)Xx!$z6l zw|(=GL%`zUkh?=}IqM1mSc2OuEp)YH=3!wg+qnyEBl|r+4804z53CDmC4*7R=)srU zk*FJC{hpQMM_w$JaFs^C{h5sYD$T|WU0A~Mt~GFfNch{}gCr4~RWw~l!VJYiYNFL) zTh|W;4lGll6nsx%AB)(h@V&tif=N6*c0II7R=roE<viJoqQaylACQulxW! zIB$kve36JeA1X+9{|n81EO>b1Uw1K@rgs=<+f*_n$O&lW?V65@DliUFI7+zhorZ&Vb41(a5sx3wv6r zGkeijXP40{*q-?kU6YvH85fi6B7Nq7_in#IhS8vF6?$o!B2;r8q-ty|j4j60!%Lux za-sC!n&0WB3m)BEd*)Rch55ld9sV?}$?U^dEN6JL`jnJ$Lnb>7&@KtdI zBtg~QD6Y{fi@6k%q6&DJI$ zhBn%&R<*Dck5OnN5*+q?zWI~8NnX2m0N}*g>`TtUXH$IilW6mmt28u?CUg*AdqPg& zk=xrE2S6&nuU_u*Qds9p4_Nxlk7&vc4k2++<(*bs#t>CYFu92V2va%@iwffRd{*SW z{AeMqZ@TP1mHF(1ZQI8n8OjVTz$de9z=2t`xB#FoYuhHWCZHj#Nc7vQU|7T9PK}I{ zc>3hld@qb9@2-RYlcBj^8dv|2hqbR+`N?Rslnd?mfNEA6K#>39u6wSno8Hn^Y&hHB z&mJQNCw3xoa=UKH5o`1|6@i=DgzdVd*O`ST-GL<QR#gH@Tgv5~#KUOu2b;pRht+ z@91@xd(Ln85$E`d@u{!#tFw* zwfCv7vyoToKC?KJM{H!Zqs$?K?v)SAJwM5`O9q>Ch$%VXTl7zMajT;RDSEr|fpVz( zg=7Hzdn5D4w@XiPpH#B6J={c>xR&4hc*%B1t%#y}Q>XCB`0Sn&AH5yhB^?>rLuU{c zSEf%w_tV66E`Og&!sb{gm^AlpqRT<_v~Z=t)m9_veM34){;yCQ-uPihIaPBX?h@;< zmlD4Nxe@%dLw~N#bkFt}|IH6vk+ZGmi8@uo(W!Pgvfa6D-ML3$RBTOZ|Bk+)`1`>d zN6^@1d0uG``*!i(UMciBMdp!_v`OM z+#Ek*(lCCI7G0H~M~TE~7|qtfjN-V&(5?opr<@G=D=qOTcEnhF0PV?g(3>A$t|j&=|@nRs`+MYwB$+jtRCp7h7JhI@3>LsqC)dK%qap z7mb0s9yBPfHT|o>(2s(l2#Xd%@A;UQ&WK=w6`nRUpKds|h-YR-sMVx5$q*g932sVJ zfm>L&`{+>k8ov2YN-z9W`7(O@({ZrI6V1cR*NOZVw3bc=CzP7z zPzs-MaPXj}{Gj%>`>A9iDnu_9w1y_IlxYxqdek$2+3ie|~?Et#pP) zT+}Zg>I?qT$1XHDnYuI3r+Bt++XHOvZhh`HV_+9-MartSy`Z`(q+swp!VTYK!J)Sm zB?Tw$x3XKA9GvA3nw*Urs#v}1t_%&GW{)7Vb6&(Wr0J`jU@J1L1$z7tJD1%}akkju{`hlZ*FBy|$8tBQU&i5^h33{ByyjF0+2W=e> ze3`ftLv||_HPAz~&o;$YN0uA_`$&G68a^eUMf>f)3b}?Wbo15ADL3yf(q?fXv+splQMfSLXfcoOc|5nzPDX8Xn|JXtajg>^C8sw+s zP=9~ZuqoV(7A77D9&VM^?YU5IT|CS2nti&4xh7VNm;grj7TTd3-D5mmuK-Fk3f6Wd z8-Valt@@uz{i&`lhYH=GSxZub3pi;q`{Fn(36uwMwEHq>^#R3v1e(>w8#rQlmdW%p z<>rL11)dqD4vuLm<^uyolq2I*PUg97nc41^2}H+mfx$LSx=ht0RtX{VV4;i?(gi9%)H>)FAUwlkt64@8AS1VXeBx z&Xybhe#xd*B4dcX@J>X?k3|D<1X3FLo?JqD!6$KV$4;7G()CEM_>?#jkEaSQ983^H zQlW}Wj*afZQ75nC8eibCC0oSCkwP;T^2tsM3&sPp`gI+YEc+LqP2v`(q&ZNyIS!*I z&*p*#712K953DH8Sd=@

4pSKDZ~VTEd{!%){#Lf`*l?Kad_OrJarRd&<<-V- zRjY*qavK5*rD!$5PZOJ}zs^89w#AD5el)F*5?i-xr7G0Im|mw{9G4wh=w7eb8a_YA zWheOJqxZKfH*x%fGI6UVm%}1n;*6Mj^sU`qp>AteeZH>tLOO+*h{c(MSH|T)u8$}> z(Zxa|r+EG%YU4lcW%)a(R$C-?2%t+&&6D^9AN-cpGD^aZ_Tjcf^$wTDI85zC zhjj8s^ol0bcHz4rJ8|d*lXvMqWs1)UB%gqt7;I{4rD^$6T4n+iUNnVo% z&_-#zA+>Z-_(WUH3iGr2VF*;GT29u&1YpaG*q+1YMYs(Xbaai#xL^GHtRm-i4kat) zMo&&@KNM@$eTB!Zx_4uv*#C{4mq*$57Z>BLi^i|=-1^~tAxrMSpHgYl)Ciou54fRk z5qWGSdJw=RANy~CKPh^c1NbV36UF=NlZ#Dxt1Q0=6c5OEPWKM#wWDaXIj(DP{7I2# z(aU3jECRd1)Ei_m@zP9k_v$Q7PFA}6MFl3XMU6>1~|W@pvCvhm%=p_H-n znD%y-{u7Rg9HX{`^A@L4w2r;cmp$)7L8gj?(Oc{Q{b5N?@!WwHVW2wvZ-QA_U^yKT zBo#N50@eAs&EWZtEI$+)4kcAE1u!nPFmaclp2IB?TEBUOQU%(p-QnybyQlqA`09e6 z`8FW_w@^nUd*jGCrF@si3SouiChkLh>8cy&u7r}p@ol(=uAnmD^QA@ z*A{-tLiytBH*{3cwU!QO5-a7WA9gZWzx|mgE=7D8Y!eo27^#P@U-V==Z}rJKPtC3W zo*3eQyTo?s>Yh)LFoxLi)??-t92#yVb(3T}e0Tm>pbC}=?g}l7cr8YvQA~o#TBkaZ zO-PW9_*nLRY{Z64S8-WpUVN;YD##;NILb^Gz9l zQGW&@iz&EwD^@8K@Mw(7&^bnRN&Lc0)&!QUf0nel6CFiB630K`=5Au1^Itz@q1sUc z-_EKJyJ2-aPnpA-8ylgQ@MdEf8>y%O@Q8dhVXS_=Eu@|B{F{VK=#!h-OM$O9>hR>~ zE9{M{FKmCVnnfR?c$7-bAf<#81!-5o@0CV1wHOKty*9@N!Ol>%))CvWx`q>fVj^vb z{u=-e17}D^5=#*O4+0?)S4eXAUQpfmn-{JIGveF_o5ZOFfbu)q{I{Tl|ZGm#EzQxG(rj(7M`T@qxH zT~CQ#!SDS;|6{M}9G|O=$ZO67@x)3H#N)5`>7VbKhMbPLjKome)5d(-vp$)!yqdi0 z2dAk_3gEG>zm6X*kzd)O&tyrlwaBn)ixH9HGPnkRz@~M&g*+&NWI>Cg%dpHPiaCux znS#JyF-@BEDZmO-JiYuJCf<11$WiuL;}=-UZ#wDo5*tBS!@aOD=-YH{t?!Eij+V?8 zFG_n@%q=7u7U7_{`sc-cj<~PPuia@X6IjoWm#1&DhyQ3(1Ms}Eus*S;lZ{GoeJq(* zZuX|)so4-9)zv$<41LRHLKwJi8N99P{Rj2AK4o)BYZtdHC~Y+y5b~2W-TT&o$b_Q$ zH)&)`xGjA=qO5!*C&!OZL%-XHoudJAsLNg*k3KCyLJg9(MWn z@aQS5Fncyik%{em)huMg`o6dHwmtj4M{R5MfTioeeNq%f;&DLH>fGfb)`7b85WChW zHfxe5Auw#t$QqjNoC*54c|6m-D#ZSZgQHXC7s!~wk@>9w2Z0)w^S2;Yiu;#aO#2b| zk2P&9M7HO*HSsX@!2>eQGF@__Ka4JFDbsZ(`8e*ZrDCWA({7Cmjnm*LnPhzh9bjs| za1_yRxx!%|cw<%pna! z*fGhH#IL?ql`e_8eGdJWYLRzA*}5OX>{s7uO3`S@mz#7e${#p}R&Um?!zuk8=X_Jn zItLDTewx4AqKK2K9AMOiLqWazCW$*c6hCt-dLy#o!X2@AR8~A{IdhpCoyT z1$WP@Urd$f#e4fDS5@;v!Pa2_mpRF}M5ZB+yi| zWgEwJ)TZx;L+ouLn}SQs>rE@k=Q9go1GE3{8;McwPsom30t^Y#SWFr*e_$yd9Y;6eLu6W3 z97M+~F|&lCO=T@KDL~@pCn{K$QpX8wy@~O(k@W*ZP3cz4tk+fBz{O-rmLjp%2w`-7 zU-2#EUpkS~U4UcWdRRUA?YIetZyz|W>B+k@#Ikwt$W|s!p)l$9S6Ei~jMn@5qcbk? z@?|yNXz}7-rZi2ud^Go_!fzPVq)7_B&KJgl-S5|NOp3RI-u$Oizr{a#D7?H1X2c@K zX?x=t!GfK_mSSt3v<#mYKA6AMh>oV^PAE)E+9(o6nhWUJ>lV8`4X}-9hO7R!ycdv= zJAKaN?9|1E>6v`;k=2u`3#1t8gNKYow<0(R1k2QS{GPXTo?fGW%kmFUPH%_YFPT1^ zMmgiV-%oTOH_Lad*!};Vg6nKxJL124TGvv_7TY(|78dKqwzm=EI+78W1j6Nxw>6_I^c9Xrt_Hy@)PEx2_$+(IRWBWvf`3WRh z%>yveh?~mJPgiI%YLuj>#KX)?MEh8<6979G15;@vV`}L-imSY@cQ1Wi*hXx*nY5cP z;XxB;?}0y!Q|}s8+~w0CcvG4=H3>;X2PQHT!JOP1f!r{sqVpP`W_WM727xYe2D^1V z;_;c_%RQR*iA@=EZeFXNwhcLl+pDt;^5echX~b%v@;P0whrA&L5Yji@d3>LqEu~4W!J6RxLxAPuQd&gME`Z=}B>%<% z%B8Q*|FU0Z-O1iitHQzKUEZI}&c~FqwGlVfk6DHA6Zlx_3Uvxf;I-v5?;|dZ4n7{YRVnYT%sR{ z2Ih-@Zs(=Kze>%Z^TQ&;j0A{mywUSJS+IQ{WeVa`T3dK2IV9fRZVWB-;4Yx8wglh{ zML2@RtMpzz=KcG4gybQ^>e{_!8VqPiEu#MJ({4x#OAVK)TNe#x_J9QNkZq(kzUrXw zVWi|rdk^x=6CL7P^r3G|$v6c!I}PAQ<*9h8NswtB{#r=tE$$ytm~$w6YrkmyT&zux z-!f)8g9xHr5mgvizs$|MfEUF-*nezfZ$}QQqGK|asmh#bQ4{MoOK?x2z)W20YTf|W zGgk%eBiwcO>t$vN9!ydIUSw9gAMYNw!!0C4en}^ES*&T?Im&R|gh6Pqtei1>P}9qY z(mBDf4=WYz-ARnY032VRK6D%oVp>KaA6D$gR3I-f$C9PbBiikI%Btr&)`zuR{%m_b zx(9icM?n)|JI%DOV1YmUPtxc5E|B%3X`*n->;+lh1IXcA^BImC%GfKxjzSG0?7R^h z$IVtx59xR0DfDS3CoL*(NvfcmU*z7!szAz*2vmGV*O*A5asDA;Kd&BVf2iORL!Jvs z(Z-Vv2xSQ@9HyZDi1*};O05oJQSV`4DEYy`#uIUD>r@`wstdr0iiuX1G*l)rp{l0k z6FE^V>I%9e-nIrTb|l$ZwdZDDG0p0~?tk*{cxw}uF32d`(hJ1|5<|WL+LLK4jR9iA zTJw9mvcT)`DTC)tGXY{cn>4JM>3C52CR&SFNuti1+?nTEt@udSD?f}Ut#qTvAhjs@@Di|!IqjThPa?}^ZOb>pZAYE z+c6s7^u%1;8OXHTuPrC*eD3{e_>l+Iimm_lr%1B5@!y4SWaD&8la%N$vu=No{>^hN zs=xImuZAFHIW&Zma+}w8l%;UYxWrmH?v^q0>FXQgPpdc)r%k;%Rk)LbzdZOj3sOJ% zI_`CU$yE2VvCkt_!=Xt}NYs-nnVA3LH?`xg)+baD2&%uQUa zPu--tt}131iq|f|tJ3~aeCxW^XJ3KblDS4|SWMtiqN~?5%XtfI!P45hEq)dgH*V;mO%gbaT}d_bl!c zbzCZtbovFEtnF}(u-LEW+!*lwS8QOcjG%>Bt2q!@hty=jg?d_;odKRD!8ZK(jKti^Jj%nvJtd;^Q?Zph@ zcMc+6VP;>mJnnr}h%#dReb{E}KCNQr`8L4FeT(nc*=z$*9zo%d)|qGG&N+-E2?Icb z#sra(!Tytat;WWXcbr+T#0X|nnH$zR^R;GQDh&vEujjgResr(8Z0LQYH5kt_jToa( zUSqtyxr)h66-a2CFSUunXmehc!)H@Io;2^nV!s?#<-E+bC8%ise=NX|Ax*BqPLdVI zV0Ran2|-mOtD&(TXoGSCKn`-Mk^8wte{bu6n;mJqx6Fp-I3t2`($K1 zM3)5fkFY9iS0NYmth3We2F99w@{kxn&SXJkIkVHv7`1{O(1lK#?3oZr@DQt#!enro z*F9O0hsej#vMbyoPcj?kukPle#)@}fY)Y^x)RZNLjSNbN_}Fs$BpE86r-o|b1QVs~ zH~`VK0T@6Kep^D2pM971ClyQx=ovTO!x~&gRBsK%sh14lh>ztu>ajXorK!VjCQolR3UOWqrq&hI=3ko90N?2Js|-C1lh~#xv=ekDpx=BwK}P$WuY?qbsPc`#2Qy z=`rqpV=PH9po~Sr)e%A`71_vJmXOx4Ti?_}*M2X#GFdZ^H7}^VYUnd(%{xvgw{pzm zN&WJ{c?v^Nn)guH@0z>~XKA|#c01tYqCV6I0zeqxGQQb-2UhNr^E*nqp52(u|3Nbn z^1`>vsRiTxlNo^YbFU6GcN+-p;ut!U>bq?p1Q<1-cu#8&^x2PjR2Ga`j+g^BSYu+n9yd|B2$BgrET|VoEtP z9dsX1dD-s>w+%6C?KdcI0ii(Q3;vQ}xPAE$D1Ybc|4P@i@QKNPk|%1u;bUNlbp%B# zBB-&34wi!WlLmlcjo%ao)TACw~8T zD$BsTOAObalip0Sp5lQqke~f+rU*xH0j(%2ADX_c3@Gpqm^-N~cWQmv-^M*z8-GOZ z)P=@&*zDktE;$z`ogl%geoG%nzpnzj%mLSO$bZCr0%8y{IO>8w1J(9On#tb%F*dw~WbQ zg4Yr>3wMxC_m@W9|A95hB=Tj8YVi>qNWZ>Gv`5n6u|OS!pwNR1!QEd1-JZbajS2ag zwKo9u5!JZ@22v~s4|>;3d^g{GAYr1bI>U3qcddZ-!(BjwzAV=aY< z=(S&9Qe5Vnd#y#5*2&7V$61zWDj*2bGpw^v6T42X|Lr{E_Tqr~-C{xXe3-I5 zwUM8*o|$T6owKz)ZPDwxwP)PxdiKBqmv$~yWL^SRl&)w#SH9t9KS6z>oqR@qX9zie z9?SA9=4-i$ag_%pR{*W{c{guDi;+kHNPNwJ{5I}{eTeU+qWUj5eNYriF?}HueX<}B z8(ICd^>d;Fpro&^HJZ`V+;wUC?pbLgKsAL?xC+1HmbaG{r=4#*_5QEZhM19h4PkkP zGnPi>uxWd0d}q9V3TUm0zWXfpu}}asmmJPW#LflmAj_4|H1_n0 zt@Om*(AWkiI{reVPKSRYz#)=YCV@I(e#H(0=z@bnQ!H7<+}Ws&FkWlKlCI9y&1)h8 zJYep7*Z(##w`6R!IeV+4U)K&wrh#}d>_CW34%{r*vMABMm;ff$_a{TXWM(J902)?5 zbTC4eeN=UX0ckD6ZZ70|_?{~ct3c=9v=>*gf{Y1eot=uY`3GOKN_h#>LE(Tcyv*~u zLrh17vY(%w|0GgfE#b2dDd>f=TK|QT_75}QLGi?zsj5bB`7$vTtAH(^{({fIY~i3M zn3NFDY%zc_3b6WQM|j#L(Mu|1h4>pia2BpAE9VA>A|8U(Q;hK>M$1!G3_k7ms7lw67zz3XDik zj)y3+k63qK)IUW%OGS;d_4lZ(x7#DC!7TYmnX>)_o*!5MPAdueaRV+p|FZt|cUY4! zu|I-iKcjKQgNrxouEn}>B!?p-yOT`Fs>w{SCO8{vY+xp1h^xOQod#)YxeC#lv1E=P z+9XO@BlBa6R3)r;Zg;iRjO7}F+g(%=JO(ZcWr790pK|&-dZP3kj8#h`6ol#vW)W?e-|2f=}qAt?Tc?+ne&1o#%%3Xw)0r0x-fi2UM8NO1b@}NGq29C z2XO0|3)kC1r9d;==p{}JwqLnhge76o0fL_LG&D<7VMAg0QlgVeA=w!9<4V6wSna&t z8?~x}Fvydr|M;&1qg3y%eOd2ogVkt&QCpi=g5?kUoT0@s1*#KjNJc~s#Ck}7u?Ne1So$x;Wu{ntLXdx>Rs|O z)>O-5>a|im+3Wr$iQ;8oiQ?=0);9)7uER35NnG!~{i;dW|1YES9jGJ?)jQ55!<$U! z?lhfC&b6d!%=4G$2wPg-O3gYdJHT&(@fB!$wo;{dyMJ%Ppv=kk)y(*>`7#xHd-q(Y zAK!|4Zw#ph025A$q^WtMCo$l_bA6+4iLiWtlUUs|G3z`_OpZf0(t=x7ysRBewP#>)0NM`%sMZp)7u;*g^Ksc~!TQ>o{H?L4Nj zbcOC-|6UfW4A-289w2Pv&9ZNV>^CK^tue(N&Z7lq6yH1Oov4$mXsdJ$V9kEfP^NP< zMto$hSj>P<3pvA;qJ}Vs#w6*xckIy=01|~wE1}i!W@=Rr*9=Yn%8z_yWgo@=YNVxX zEJ&?p7K>~{roOz~w0+QoQB7unSC@+fv7X{ueTs@8G7`B$5{t3HNlY7PwyJiRxE}HC zvxTKye@GTxYVu$2vqfZsWtp>wTZY0|e6vGD{l2|Hppz(xkG&^N4c_r zk6uw*mJ(%$Ns@ZVaNeo9y#B`O>3-W5er_R-wkS1Q(*AqTele~Z?SgrHF+4t~$-l@>^z{K}#R-p017YR24P@CAH<(!|CKvdZ zj<@YjO5ld)=v}|=au`n~)6!CS)Gl@>XO1z4wWDmU>Pz+({Ff)2XwJ@_f7B$2P8)4* zS;{RUwDWLHAUw?=A&5F?RO!8l+BTneMQTafhTM9M)?D0P7aJ;ZL4{;X%im$1pHP9WlA0A~$w z^7!W$l#?-^4IWLc$%|Ot#2b;#MA|Y4E zNy2cNz#@3m80tRaLuc6De`Wmu)0K-SEc_{c4egG6&F;bhtpDQVzdidzLGy`L4vD*Skrv z{5q0Qj9X`4i#sj>ou%63V}j7X7f7)u1sbnZkf)MEBQ2Kari@b4nY49q6d2ED*iR`h zr$|nFaBJrgZj$ut@BftHIqXLdKk~27x+VZ#iIy0*j*x;#hCcx9KG+D#krYQ#RgSuYZKwfN}we|T{pvCpI#b%js6e_3ro)w!{O zN+)ep(d1FwPL8Of#|wcf4w@>T3!5fVqEd6P8r#25xE;!_zFA$s9@c*Xn9SA+I);XY z*s4BTrS;)&lRtB2GK}yN^p(EGG!>1+;dU0+kG!0huxr#`Ggn+$;dU2D6MKA`1gv== z-~89g5I%t>4fnU#KA>enPl_&#TvZtmQdNZc@IC6BC2Xp=d&Q3bjGs#OBE{(#D1Ns6;&U7>BpL_uSS!pzs zG85AKZEnhj-Kufgl$?i2XVO=;icuz$f^zFYKsN*zoQk$qW3tn~5PswWk-(EN_Eey1 zqGK!Mr;oxU=@&^QM7JPFQd5vD2>aAbN$=-H(0JQwbu*z z4bBcWR8VT#O5!1UgQBu2*PBdSaa;T3ZxZ!`;tYOk1|y3^EdkmS5tHn$GBfK#n~+DZ zoIodl;sHWy&8lg*+%#2P?nY6%v%q6MFi)w0BqHUllav?PT{$TV50Z*^N!!FO6ZMqL z00W$wIG=Pg2LBT(aLBqk@)n_9-Z^`yv0;ln9OpDfU}q#8Roj+4WBbHu1os$Mj=r8% z5bol)iM}t#)FjWQH~2WGsXN6so+`o)Grf_odW!xyLs$6j{C+G4!!{BBHTmBB0uf+s zO29ZIsvYYknEjEaTa$wj+k?PP12e3k;58{StM0QQpm+WL!|%!d-$2>|{EZyLFCKMo zRB>??zIZ?#!S8XYh}J0*j%H}%V>4QkYx%ys?tbj)wJa?V$r$(c69`{{f0Oa90+|6l z^^&Te!ElP7F%JbQ(WSy}&t!~mZ!-)b89#b>X%12cf-xIG_CJ#BKw!0kkE6I7pw5qX z1=C1cB4e4W#M-aOhs4E8Cj*!25O+e&KN^MZlo&p<9@2$6Dg+ducUG>sDi1;@L~4eY zR4;m&_36`w+ka?!KsrP%zu55^R#7CrPI{j}t0cCroMpA}DA0D|zGdJ(cAWIyt}&P~ znYqBU_U8J;7H@j>ny#C8!)Y943Xw)CHS)u~B5O_HW~7P?mq`1D)e)7Ww}7Y+>8;MHH2P%T-qTzq2B}5Z?iJU|?ATL#dunxri(aPqLd!HG zTi3oTM30}M%S4ewq{GVD^qExqSU{Or4p#0jhGt%mSAN3XT=e=zc?ioaxzB~41oJc4 zJd)D5ghv6#Lcex}e?dwkGuSSA1B8D?CLzbYw=6z%_M0Gok-wo;9>)2;w_32VL*z)b zEhgz`v0`N|ft1-+F*IgK)Ekfk&c*Gzf+y!#rYK{p*qb>wvKKjY+9DPeSsQxU-tZo0 zeO8t9lK#}92O#5{TB1Kz#@OUXXe&b8zy?!Mp6~$lR`#``qmf$Z@O?5^{S^Evqh--O z{bFvBorYTymsBP@YjD{7M5Zc3_I5uAOIX!1Su)m#zYYd=OKew{i?5+;;#}&-^=;S( zsEKnAyDO-@BH##_Mi+tn2?ul8ilhAG z&dmv}z1?N50&_VkzZ!wrK#>-wLEL{sGk0c+(@PvIFQ#?vCLz`-#}t#dZk*%|=+eFqE~|~M&>+UB!`Sy2RDmJUDr47>F<_#)i089>^?lvTZQ^82;Jr z*DRfy=uPy=EolK6uTuFy?bnhro?G)Z^T}L3xT>!cf}z8~iSkrES+{3uufM#VJwP4y z6B(LQfZw9mDw?MbRn8Ii#G`t^+*p&eg@jY=b#L`Jq`YkPf0&tlTHpn;pzA)rF0-`) zh^(;Fbkfpn@NI)FZ|?Qr2lGDcvUX6WV{tvwHWzO_fi-VAluWOxHE+Te&l?>+UOS8u zw!)w4ms>RhD@IiusXlc#2xtn-M30Mjwh!-5JBqtadTVUjCe-=Rc7%#)3MIIa zu!N}OkGy(;)-@eGOAWxHUG0ZlqsL zYh9-4hpgsZEKr~)6WNtG#9BhvrXWi3ve?N3Z(0OGg7XOc^9gXq$nu(BKNf96u>9CM zf`Z1p6rZm-3%Nz*?bcT#8rvy1g#5^tO6|Eh%r=zVEkWVon3iq%`_rgy0!&J8vXX|? z7IO&O3twE1EZ64W-P~}0hb@_`EZ3$@pG>sHO=qTR6A~Ni4ejd6^#H$N!$#@dxO%LP z9K^fZzwzg<6z}9t1Y+XJ9)At3Il&48?q3)tsnB-+j5qNmOY%KF$?aLkAiN?t=6Wlw z6G>P=US!?GacRehNnPZU=a=AAj?{^C@-Z{u8WYYucrq)evA4{0&aJ1RQ85*zSzckE z7QF&CQdZy}90gyR*}#>PYk2QoE<-{J-bN;Grq-ImrN9nJg^Aw8k~ZHbe^%xQxIRvJ z);)}nEJ7C6Yvn3Sgr25&UTSwYs~-D zyQVK`d+(6Thw?`Ot7}rkPTn2@DQv_~R;mbEZ(1MB4W9G3=fCR<1qAHFu_bK;j8KK} zFLX{y!Av3(H3EJC6>b}@{qgcY%T1w9k?dS+odrR)YL9C-4lyvaaC{W{iJ*MAG|6o9 zhaBqv7U@jmKlo84=^gwJkHarH<@%JF<~b&8Nyk1!*)|7ZgD7?l1sQ6V4#>zY)8>?m zk!|@?Fs*zv!OGU*dwwF5CSq8~K9rw?O5M}=sBmE#(U9g8FhAfWwgylA(9;`$L5B_yJ`|B6Ggl(Ie5j_S{KwD{UJq)r+_@YNHenMcZ#MSV^$s=7SCP z!H`|FYVB}}EIW4huI#Sa^M{pYMSlG+2~r&k<|2!#B033i@bCwE%f<$9l4s4j*xG2K zfRW8!Gnf;7G?`i3OoR`1$D{3k_~Ac6-+ATUSgcjg*Q0!}eoS?pSlism`zN|OnYz#I zt>m&>`UF}9ho0$f5~(b2pnyv8*Z#e6fysxFTMysyC)WI_b*c2Bg0q+WiTc@BpbXdT zE5MRx21|UCQ5}K<`z0c4wL@cwBi<&7ci$P%7|-u+JmI@J zZRE&x^`?dYkEpkbYO8PFzj1eWcMtCFR!VV)0HsK)}{_8#2XM5+nRV{4%#{t_Z>y_55 z+=ulCS!o`zr<8X`vVWA9a&NYu=uC!svLFFm6rSq4&HNHa;*5IvA-BM?1c&cT4!9s^3N#db1ZVNUuUk{`5d~Dsm4K<)l zmA!b{*I6*2lc9+Yhss9F(R_gKK{sYYmrujk{blVXjISw#KpA`)M5)mbShizGGuvaZ z$*Mq*(KpPz?=~OVE99fM9gn%~TD!l)hw~q)HW`(>d5zN84e|D<<-$>Pd7O|Rtc)qt z*Wxnoh(;~=qe?{y~|_+SH}uiSOkb#d-X3^QX!%GDgRJQPi7aqpj2l3+c-p4y zmV^<*tm6n3krQ5oqb?azT=fXp#)e-Z=o`0zr!Jk1E(mcY66RFUnBp<5S|BzG&nOn_)@O7~xQL1ha3A*1%t$4S!HLjU(Al(`~l>eq7BB z=KOZP)DHi$^A4_g#fa_{H z70}uZcGAH&1dv~6;#Gpxvl7p%P4O^pt6z4|U{1|ax?K~(f;$*saw@QM8z#bJJ@yXR zMM6utq$wE=!(mfnSi`RrIQCBf{89SR#u+KGT#rWG%(mV1r>69fEhi|A-d|D<5zaft z*3~tfgr~sjmG=erX4p^23&OT8(r_naVmbl0BT4dZo9GVA~SzRG=tWLN2vx{j`w< zMP&$)bBXC^fSZ%)TnCa81_~8Sf~#%Szn0yUWK0ep+f3-7U!;=*$c0GDrqhl5R#`VWMk$<^usLKiW7@@o;tKdQCWDB|pha3Y=)djW!n)B`->E#k! z-({Yr$~Ui}JpP}tVo-v%_hKT(FuX-846*E{2|jPgM?2+!dq<2xW_WD)-EXOqng@y!R`SUg+c8tu3ub%GNwNmah9d*B9 zSf~^#_yN?gxMfTkPw#yZ-@{{~XInp5hQqbweUm!CbbUv=2FtbQ+f^DV}1B2 zusze&Fe?D6G7?HzQkGCMq0B;6k0E;1dCc_IW=gI&X%u&gV~`wxqH#Zqf^96Nx4*lS60ij9xGp4{=u?GXuigrh(HC|lmq=f36`8=&+|5{ijb{B6AtdMq6R2NWaSrP6CqwK`hkJ!jGcMm5%7YpzIKUpUhX1tm0_w?EBKd7+PW53Vj&W--OY9F7gg-$uH7 zv2l5FAZ<&l)j>4w*st9r9VuE?%zYd*1F4*K-^k|aucG6CN5}HdQkt`rHi1P7z_?eR z)~LA}thqB`* zL~OTM1l40a6VH+z?Fl*(&17YB|@FJ?g7a;kE6fa|bXVbYE3(u(OJtpLis6~`y% zK$j0Rjj&mn)}04o(%7W46P6q&ZAgH$d$a2cF9^7xe=53wI3Qmh)nFcl`Li#HGU)RO zLl{aK9nQ&umoYnBrzMows;1{?McCtyok0DDpW=c5H$<4<+fI23Y`(h)v??Ebk2a=i zJc;Ru;>l88ylhAANgzPb+0e(dO#wb)V~H1^Oy2u#fQPqtlVgB4b$GIx@Hx;jV;K$7 z5MU;*VKqF2lH!G6Of*HuFKK%%f;~C(MxEft!ovJddD$*h3dJ*Say$zQ#3p6UNAuGC z&2q|6(2gs6#;a?+Fj2b`AK{64Jq}9R>zoq&ebK}4s0}fGM@!h7z}X#exux3@27DQCMj#}3v7L%JkG)7%NrpK!E1>7&Jr#@o8%4~A?`@9vbx&(W+CmlHs zT}W12qJ_%9tz!m|UdgQAYrSr~=YAa6*`(Jx&)K8tmjmDJc*fNt6ujS@Q8vjqbANj) z>aZAb`gHZj0p^4Gg$Kq268KLV;Z0^kyD$Tf+(7ZrVH2`kf)hFR5OVFZp1UTig8q|G zF|g2P%n)P0&u+iv*2T{>w~Pi6EfOg*E@c+(Ivt<+v?t0)TCKSiHiTjIlWgRG>8_e- z`d^5YWHs7K{I?qmp3ybYOMDr7(nu5iqU6Km;Y#7mzDA>8!NXQuEuI<2p~J((8PYd$ z5(RX(_{wC~5k>z6!%pw|jZN_fzZVKqZQ77mE2`wSjQO^#rE6XW?a}b>Nh&)? z+e!$$k)xQ4zDNC*+q>x=Q?UF0_YllbRGg}R0jVO!yDoD+l-u3{pb;nmzR#b{6|#+% z(bmSkR+*sI{I1DpsR5-S;x$p~Edn{144x9qyn_pn2BhE2sK{Ub?@|A|)VRN8HgnGS zmViazYTs%7fHGR(o@(VbhkgvH7=L5>W@5fKk{Leh-dxPrLrwB885=!_4j+OADfwy* z+rMGrs7YeqqRrHl$bSEj6)y2ZmV?ur>>OF@k=L4B2vzo*sueH26c)FNK_ zLyAF$n6ZF;&rE$@<5IC#i?%0`I{yF~qZ!BQTh{S!bXv+>NFHQtJQOZ&a$*%Odo&^v zbSQ7F{7G5Mym3M-wmO?>&w4rfjpCsd$1wW`IrlwI>ORU zzp|6a4JOFr)$YmHbl3$*NhiyJIXI#94c|*=_?ifpt@%{wKAckY{>?4|f5`e`g3JD9 zM;V;$Zoq(cJVwVb*c+~IrSAqAVi!om^6Oe+HYg)nPVR9n(O4eoh`!FMCb5j>eIXa!6`DmLs6IMQgh5O#W0yf9tP2igXQ^4sXkVND35Ruc#;R@gj zQ-WS?Tnuim`uWhDl9PV?$=g*&Uu(b65SQIG2ww@2nC}(Yf_4#as`L?xvj0=%ygZxx z;}*dQe;25Rs<|54M*Q|d63pthlX_q)i9dwjztiut{pfnRtNP40fR;Ef_L-F?`5#VK zkT2CvRZOiK)erMQ5zNM7d>-n!!l58%6h~nL7mSYddY^h0S|2(*t_zH6W{5oGGk6jS z@GfBuzg*syA}bD}7xIJ591Mim@?U?eT>3zn*tf3>JQ^iRD+g^o(i#}Pp{k|RLZ_!)!VdI~)nxb+A zzL|WysU+rB`oMqvz26{yR-aIV9YyM- znTU%%d@PsyyDqZm3#x?R%*7>lOZa<{m2WEeN_;J7X(vj1lAQ>M@T1J&>={cCqzylK zrmD|<6FGK)#IJX!W^&rEWu;y1eFbz0bx^!3UCj&eOlox4-(YaMmNSqipx+u2HGh!u zNH(}0yx=!dGw#CtCvb(HQ7^0g2M3)}O0{c`ja{QWr>4)#aJU>B`3rIJOZ8tz`m;gA zz(qi7LgbH6{NmVUtc$k!Czi_4z9xSy?$?bexkiS`?~QNsPItW{)Cy&9-ftw0v)kj8 zcBA9gSZhJJ!$Qj){#Az4s48rAfp9u+{|-Q-!Jyju@V=rTMO+dG8%-wAdW6+{o&tYt z?w9n0+ITU0#qI;d^-PmN?BR?lqpz?AzOUGpPdJ6F-&H~9KSsgG(7EqiN=72_M?utphJaE19U$e@C<9$E6Ewm%FNPW89}ymOQbI{p4~dB8556B8$>fWcp^XUbo)^aDS}UE>7aOCc{MYfzjX$Me3r0)osh+B}r1 zIf94AW=^gEC`zU5^~<{}JD7@jZT1!^?Jzw-cTUs1X0%W-Yu4E=m0elv+!w~3Ssps5 z>t(;!0K49i*W*Yu*f}SA&L?p@;Sc}xCaWuPaU{$?Q}+wWr;EPw!_c3xHtT<46B3a= ztG)$J`=}yaP5Wln<*Wi zlI;LiJf5c1N#V_inCJpa_&%FtAv~@(Ohc@&+C`u@8FS_qaX`=6Pjbm}C_QjtpqPVl zaa%2P-L>Ghk=M#8#vX)SHEp8mK?}sqRyd57A&27sC`56)4u0a;lT|tqm+8op+pG7x zcf&UtA}n26McC}c`to{UTVD&+F$dW)*3fG9Nb`zD?QHgYr9tm|K*Z8Ka$Yr7oNZ$g zf_t|UBo+m(SH;r+lzi(3qPpK7__c*i94n5smfMkr%6rVt{`b*`jCtpH;6qHEKFXrszmGP8Hnnk$!uheL=(w`qZ%9fV( z?8}E+KT`M6XX`-0{38d{=|y6L_mu3K#l42_akAMiN?Dx?|9;~bVRm);UbEPM-Kxi+co(axTL>f`Qf|L3%;8^d^J#bJP1tK+Hs5!{PNG& z8&Iyb8Q9gbnYPIsP8#|l&e_C`aTl!~g+2}sLD|-9`rQwBV>GY|fKoEeC#*DH&9kiG z;aYo^Qq&kH{Bp-~NQnIPb=ZiHrKDGTZAcJO9nd3_de1F&cXHi6*84^{!wU(`?XcGxO4Ouc@DXvx&R{iIrH)E_5O0 z1BqBo-;b%$u?h0~xupL}1&I;*@Gsd{Nwl!f3HUGPAMP%IzWYcX4EKz(Z43^UB7V3} zFZA+b-d-Qf8O?d--=@2Sw?et{0?!yF1ix)|o|Rqyi#$O8J1sD7@}z!lkNk0=ddEfg z&t&s`V060|wHo+{!BMewo8j)S1!|JhFL_sUL%y0kwIQSLjhT7o{PqA6U2Z3m3)*+( zInNpW7-cWwN$jY*xEqwt-J6`PTaDVO*y8Eko1w}FE6m!YpXyxM zca!hbx)e8&w$qTc_r+v>AZ!1C{MZx7^J{-aX9U9%olWst?*znlUA#PI8aOJxHf=Y! zwr~C7HwXUwYrHJx3AlD@e;yKildQ_fNJ*{k2RyR!ic=mDzbMskzr{PK?8m5fOF z$d1?hj@^s*c`cwD56vTCbAjU;%7So*?b6JQ9}3G7@egP6lk{`vf~>=p#3&1~F{CAL zTKg;$^e^FVlcTQui+vX1Pg8VKM23|8nJky;<#q@0rYeKo*0b2 zG-d#beu~ZT++36Zhf>j~Zm;ibnRjS0)qEB>&A3$u)QbfjtTd#G{}PWBBZT7FOBsRLs$7&pN^|8ILz!bubhVAO#O-UF zq*HCEq$l}8_febg1!%grP6D1B8UL9%ry<(F#fh1H3@5q8Q*ZS=uK&F9I245Q`D%oB^OBo;YpYi1`N?Smv|13} zIR7;ZUt@cZNt7Y7VALy#+D6~H`a{o!2VJGDrt#Nsv&tF%3cloPLw$nQ&zdolN$%ku zvSFhO0lf;#s{M*_pN9qIno{d3?!;3@-dSttjVV$zye*ge5+q(yH|pj zdV+~j1Dfx{qx=VlcKHn&rQriQwFJPpafvH+lHI>K!)BCr2zwn3J7irWs5f6n^q}lP z9MKY3AmUZ~OWLggcvUTv@Db#9wr;kz<1z#3A;lK<5NcfvCBVA!7aX_M%_|4VP*DQ# z$O=$W8e@mTI)Vp>Mpsy7B-eJ8-JR5p^wK0C@lqkS)+T^Et~TJ2#(%$o<`j(-2^IH~ zhqnlHZaV~-WLI$?nGh3jZ&|iNhS>(^EdqlMUYc zj2J$mZ0FEeB@@Tyd&-Rgi$d5@Ark}!nIoUr_wd9Mv?J8SAzMdHi+z7mm!Gan#u8a& z*ZeMii0)2QKVrmySM9u;@r`q^uKz+qzW=1&@MqCa2Ljzf*}HC~RUIpVY?f^G-V0lz zKG$>!FzI@#AtJOTl{bP5m6^&WXn)l#94N41eVz!c> zBt0*4FzS5zz z_98HP&b?^exN!Npy{$8G^1NqX4D~a~6yoROQdxAu9e#*zZ!xy>_|$jdd8eeJEvaSO zWaEG(AjP$Wh=RKP>AvUSBe4{;ErQR1v=>HNL~f%lJ7Ga(f_r1=(K4{;Bx={Nt>V&Z zRrZ_=U2$znn#|+R%_`Tj4Sj2ev>4X-nh*PjwsRbM0x9W`gi9zZf0A~u9tLhxW%2KL z#fSjA#Iir-3-5HsTv$IRbMKRdDYJg>pbZ7*<)U?=_+W!pA1SOjrT_&hR6-)JK^O_wkO*VmT^{y!X*TSxlHs(I3vg!I&w6U)giP^oc3t<)9myAvxpZPD%B<82@ zJpZNF?MstNx*0Vecz`g(Y86)T5^@n%$%e7_3)ZxBj%6q*<3MEbx));PY^*{3m?-be ze@ISl1S@tBZiI$Vv;Fob>3#X>d@`AX#Spb|qmvgWN_9i&I$N)@-#y>efg2)u6gcb*YuK4twRS@k!%S=!8~ z7Kzwy_JJFoN)z*hc*eL=J{w(v`vpjRT9$TyCv|VM2-WnO=#Y5`L$W3rFx!pT9RKv| ze*eC#u}Q(uNxU4MB?6ouQj9R)cPg`HX?F>qLIeEr{F8yz$?m+jw`I(}S%Ky{A^Jua zP37Rb^&KcnTkT{8I!afwAJE0P)5!am87Wx7zR$(&sjzRfy^CIN;dbIDAI*4j>|wSf zely6U@@;^L;C&K#Xr3>oW-ghbZ4!b2%RjhIf`ZR7;RSXIbyQu#pQ&~tz|2FsXp)4( zn0AOiql1Pm0(=X`r!R|C{`!WzTX(tWB&xkrmz|S2iXd&xX4YZlPkP@v3I?BG2Wf3< zgFmqJfFMaFwe=tQj(@o7JIJ!&H}ZQk1EFVw97Sk^&ajzd9uF7YDL#Vb3EqyPJ<)I z#ba(NpY8}z6fijkwKP^w2#$|W?2v)-5GotejIe|ui;e);I2-ndi`2iS!w%&)sBwPr zsGgeMj(P0&DK`gy3P^R=zTck_r3Y?7ku;#XC6p%Qx&?xbTTtPRin}njN1pp;e&_d` zu`Cq)!t?FD7G^8EkD&={Bm(XR7L=x~6r5)y6^PX%;O5QeiDo>%lY79)nMPVOJaQEB zx=UnIfVKoSq)`8(^f{kAEK_Z8{wP!?AKh9KPDaDf`vTC-xw2jfx$-;bS$X~y-1G7PUZD<92Y{9>kG2L07i0anQUzJlgw3vB413` zRrA$!Ir3!Ae)8aKLCsXS=uGf8q@00UAcqV)*5LA65GHg|1U~+=d^h(Lmx;Y1!w#7* zk&7qe*|zwviN@;=IVq{2qIMFO!=Qir`;Y-3IcbRMuA<3>$Zm58-9<0qJfOl?-@GTv ztp{9CAVjy>Jqpf0UhTFtUZnLfv()=biAcjQ4f@reax$8bGbPGdi(JjHwC8u1fM?7+ z%RiS$Lq-xlYGYLd!&n?eL-i)E?sRbWmg_;5(^bYI^_934B(NdqRTITNrRqw2v{C_FK151JYa|hVc{}A*v5V`tRg?%Sg zX*&9F!19WINpRWwv-&cYv*@EYyW4*&AT<3F8l5`jR^?;~^U4lUIDywaUXryt{lo|uG7)+*bD%~-zY1%(oXghkd%f zv$h^jwysP@Y`zg?v+_BmWZOt#OpYmVkX&BIMd~@_3LU6pFDf84*aR)TWkp-(3jvjE z@OOx|naNpWy6_NYtf?lpc7NMxcRMW#$NfJRzy#6*OYOI|3oU2t+^AC!0g)e!a)NiL z3a^=ggk^YfoAgBGAW&E6`rskV|4=gO zDocqbUMo@ZFFa)>JmuE-@I+}xf}7CJ`ixU>#+BG63)u2)ckN&LM4;yX>ZJc&G7K7 zKEaD^W%z)lAeVNE7N@F=sf#gFZ=1zL3SdszX3>5%L#-R&kDKe(CLo`o&x;Ei2<6;xQU?$M#~> zEB&@rg9Pwt9@94vZK+U)=^Q+<;dc@qwGiT^An_wU{XWW^kERkK>;vD*>n%NeQ@1@z zEYxgDlc$^%#ccYTJfZ|-zV;;2U}18wI(mvA)?iv^7^3ep2~6EjC(B#JukP=hYQt<3 znxgE9x;GK*FIHs2(2dmt!v!u1~ zBF8alrWf$OX=S)3rCV;~t#&ceANcl@>tlx+8!|!FOU1$yi&EI|!)@7^0EHO*O{uLC zt*K;Zx@5G(#qHBI*SiLGa+}Pu1oP>!?c9gN{A76vdsfH}$n^%oH~j9x6xdwWi^kaut1C%`X`_d%;zh2WD}VyTyG`OLXGWX zE0b-A;%^`=+`H1cR{q!hcN;Dhyc=_gZp}LimW!aFGy5)V_s-R{w}kru8|r)MOY`sx z<*T)*`}JP`TI{$Q*b6}LpQ3@A+rB53j!YA6W|Kk4_^w{ ztaBX6>C)d`+uKOnWV&ocvFy%~Cx3#T*g2C^r3}IGt%MkyQJUZoE^rH|+Y1`KL7)?Bnn`LytS|4rEy1v;{9xiwXbXw2JmV5dn|w^n4uG7rV_lXYEar6DkLXkSXPM zogRUPRYN%LkXuRHO4MX(=kYBFs4g|FzGHj)LW9K3NgIz}g3=&>vD+6#-X2AspdwPF zZO<1D;b-ukMn6Hq4|mw?4l$Uy(l<+GGKuUr_RBBYXYwF)rnG68m*UCN?0qTPh{vYD zYyS1*qvdRRlE(+gK+uWmp4Cj(sSj6GMUkwf@=5TXdW7WnPjwy8;SZ2d!FeU{v{E&4 z&C)dx0=+*~$)=vawy0R21Gtz<<4p(xaE0V>mAjcRXr+U%J!{T+EnlR;iN8nD)~o)! zzbsW8)T21TIsq5~j>}%nso%aW?V(grH$ozG%sx)}7v;ZTOh%ExDLSMl#G~NylbbwZ zHWj1lbk-;3226d1$haE>eXGgI)xsfcH2uA(&cN|GxN0BebWfldO^Sl|g)_*toqQ?_ z;(b%4_ia5_eQOy)63Ve(aK)TmF}lpBE;m2R1OBpLR>Sv)3z$FOEY%Tf4ORUpgcAA0B*8|2LcGZ!{ipR~gT>Rd$E|EJB28SwTB2>X^cclw`VjxJ)MF)4U{wOEbTG3IY{QaThrc z@qhq3OY>BX@Oc24R+CTIg4m}eohWNVG8-dm)&%dV${=&U1SFrbasN!qhx~N=3@-YL zx3(!xJn(lE-t2pjz}i)3s87+oq&&fQ(t;^1%f0NXqMk-#7(Dk--Oo-)8*oYU)Ho3+ zS*r*uTnLTBQA1>s?;Bw}6ZLJYCCz^#gVaPqzYq7NEA}@f$@q;Pa*=GdIvYr19F1(~ z6&IwD#8((o^69GcY_y0>9DkV>~ z2Qvq)&E^z+4ZW@NJ>$!oiBy^L>p%u@gXP}Jz%tDgB9iwY|D(O$ zn~8Xh!do^hg)d=R4<^o&RtWWR?u)B!O&|shlBarN0j&9gq4KBCMO`U>lBteg`QK0 ze+q_syp@5=l&C)1q_=DAZ2#>6Y8<7;SdDAL_7Mo0GF1++ylf+Xr%Lq+xu=`Z^S1K! zz&@XR!tdlH!&8B!VKplSreX5~D5c0CSoUGjWvA)TiE@ndx-J_1L9)zT@gy}()556l zKrpAS$jW<5K3ybzQ9nttDSy}X8xQRlKGiZ5nzej0N16E74Fkg4Y!95J_`05hv8kh{ zhx(5b&Fq+H*o(D(j_*Eg=sW`+H9K>`hl3pXwlR+=RhR`eOOeHu83@L#}ehj21pX1vu^yVfsuErSS zJGKv}Cm$R*k9KzoIclOg133}P=@zeVSQ<3TT@f7%&AjW!RC1l+$E3Ja%hfATGyw`b?d93 z_R*-Y+L%+vtYVVPb2-n3Co^{CQZ~MJ;@)YKPv{%>Oz)mk>bYwjQO{!S2nTsQ z;b%W{k zoHiD5S1-9AiHzcM#GQm+yx@Dye^G*xk0ltc3|rB@qt(qvrH|$9C3Pp26?qblN&iI) z#tInS49D#md3|OGq^hM@eY0CzOnip2NOOr&4voks$aD||+`wXsjYq;5Hc%2QpbukJ z_^26yWDBKM3pSuaRcxR^ayBZH-H#SLK5ybjmvpb2;d_^S_h+*%O^md`=nVY&?_NY+ zTYo8#Q45Q*mUQfT)Yvx-i;4L`a;x}^GPzBS8-&k7+k8PTCypEwCQos6l~oD6Za>`K zJ_@D#E`R>`YJyWBKsK`=B$~FL82JS*ncWv_Gz%@|6POaMOH3Iww4DF5MynlSfI|Li zI(3;meIv*8lHrCkVGJf7@}Q7-XPpP$R^&@Gjz3UHAQb_pd!nCp=D2MXI2jO5R!s$< zosJ{iz`&m@)`nd0|2VF2%f|gs^6VMPmNS_LstSCtkQk|xamoT2uUZ%0CYjJTYNyM= z7N39WCXIE# zPtsV+qTRyikM6A&;XJUW!xg)DNxl1x%X&&4w+7*f!| z#)?v8H%8I3y2)Jj?q3(Q)!32WdtsB#^Nyh_b0U*B({<(4r-1_ubO+0xvIxWe^gjda zs!0b9Kb%x|>k=&gSAtZb_CD0@?=u(!!y<7)3(1_!1p)dowKld8a7TY$o^0JLeG$v{ zr&wq4NHSj7@}|hemZbt{^o4HY|4l4oYfqP^Kt{4Y!unVJMkAljgl73P(=oV>|f*< z{z|fVZt$(~L#-mH5|*O`mSjvtZ-kq5V5&S zxP9=uM}jp|Tv!Ek+6TD0XVZ4;PNpiiiC;b8It2(^K2n|YwduQ=7PS8%xD>oZYFqZ0 zyk9Tl8zzVS1c?6wt+)=fkx9|2FIaaEz|H zq;ITn3;6gEa(5NL4Txeze|F7Ml+m0SAdfTDzUHOQ0aD8RqN*%&Qc|t6LN89~*x4E* ze;5Ykhuf=EJOAe8hPIAQS-V0wb!P}+jW0ifZmJ^I-3PMRu?@(wGkpyBO%laNYr&#P(@=^vmfw?|bS9Nq?oH&N! z{Mu@d2u_S+3)2?<1;cmL%^1pWw+@Hv&be0Tyg3(EmJH)9>zQ6(+L`AityTv}bl6;h;x%47UGot7Pc7%}N6f9V-C=DjnxImBtlI!Q3k_Fd=k}I<`?ztn zThFUk)NA+^h6otl`RebZo8}~f-HfkHlN|gspNltX!tb^MS2B@sQLozT(R)7g*gzSE zT6j-84=1YWUM)fyV_;lufNyqh?`&QpM|gXv73Pk6JWY9S>%&sT#z$73U4R+){h{@g zv#<~KrQhJ2de<}FS4ZWM4`=+5KY1?D2TQCV#GQhG zYmmRgh~*{P%62Qw++R_%+`;C4t+?9yJ`0AY5GTHW2>$eIG=jX&a5C`P=ob7ttSs8r zd2!pH`LyxHekJDNcxjJ_f0TaVS&@Y0`<|XuB3IG4>%g~1o9^C9xR@|nr_e|ai|W|1 zESeQLxFIA7kbpTi9?8{dT0y&}TCTtHcICnJf$t2UW4zuUFbv|fh4BJ1t@Oz0+*4qfqt zg*mziHwfoaE*vggG%&l-+}c7Y$K_(lT+5u?0?piZ9r?L5VKBwRr1O4oD|j=e(<%-@a2_zKxvo3f++pOCQ`jE`YZ@*NNoqY%O_t#4?mwK_V z?7XGC#U;zHxT$;&I>Czau++rL3T3S>>hA$oelf@{1d)YHEfh&D$Gvij)|v_%sSu}k zfkb?S5wF0Clf!sf_6Pk9DcPceO6!-54EI0xDxlf zEymu&x@7nvZFP+D!PYHc!Dm0f=lDOv+b<&!{wF4+nG7}NG}SAN?I$v5=)i9;=#JnL z;gVrn2@Kq{CJNiBA>m#1h}g+=a{f;an%P^`!)MW3WHSt<)!kO)xL$kL4Gr=TOT3GV zu%&$ns0Fnf59(1a@<#_GU!-Z;`9mJ8COONW)UAp4LgJ)<${RNdI%OQ&mDL-4wvZ?! zBCwJI-jJC_xLzPBIe23Tg2RLm+J}B`j`XJZB{}UwVDtSfgo$D673mqX@Kb*ty0EOX z6!ZpsfP5MKjTJO?vSbFjgcFX+Bi22vbzh4nIj+o^W%T8LL+y?3t z+|jql3hCHGop;^H1@D5oKYxMhbuFiREm`id-bE-F8zN%JCS~B&$*SIA*37)A8$_nSeS!L()=4#ER^m=@cw`b3bM*DqF znX&KLZ#a_y*ylMC2WG~8!TzBlS@)>qsVt5S+694e^i*XSf1@sMkuQ~&1?MRwK52gG z!r?tqyOV-kr`H)AqSFv#l1Ro3#9hv92B(8|%HN=X0LjZgN>{(f2HC}}iMM(BO+(*4 zTpB7_DcN(86wGJ^55{tCHMY;s8PCM#I)gV5gAh|VuP*@71#*lvCtRhsUAreqiHXuz zL5P~1_sw%dMn@)dA0`?=)Xo)$waA!8^5*#gpImxM&tIr(DjuGtE+VLzX_Sg8c%4LQ zrsj<(%_}dXV3mlp;QdTUILepYxx{VWkeNl3XBkF?Cr;A4V1o~5;&1i+omauFJ9+IF za7p_R%SDJ!gKq}nE#M#dYO)GWM4!-ps5GYHKVvHzKy;Rk&PVfzFJUKRE-SMU45jj8 zJ0nn5&OY7C^*Oa6jTplHj>iRpj|~9rXy0kGBO2s`@FbcgP0w&&%+t6~-#s(VokzNV zV{J62TDgRzxfadvX;1M>4+CGRaHyxWt$L|A|$f@|di z4&xuiHZfyZO}(TqD=u0VU|#uujUoSg56;gtjFpvDTNa*}j`gx5V(J{qWY*ZQ#&*bdM-e4t9N~7$sZpR7 z4-3b^_e2fF$&91ZQx;1Gx`gR4;-|s?nT%3&NK64#Yv>B6k9rqrZ0nasc`30X|KMCZ z#cLLqV@F;@SC$KpIDC-5cY>sW0TI@=dSp61nxcS3T&7B{jv|F?ui}rY%CSMt?~7fu z#}j1PCVwJ%mHFB8X_B&n>Ae$ILUfm9#iJUGKOBnIp)Wk-^GfvFTl3h0%Oxb6@ zb`+Bn=1Ohn^i`Uf#i1*uBk_Hz=Iqu^qEj`u7LK&){A(2cwXK3Mo}NQ1Lz?cHk1xbl4?Aw5E-Zl=4wsNDtjc0a`R?YItO1CqaK;O&)TTp z#lWQ(h>kC+wnX4rYKjS8g@uvOHfHjx5C5adjk*%yD$`)V8Rg@^n=OrAj>eFcb2+^D z>=Su9Hc+7N>x@tDk=4|5J$(H)<1f?}%KTiky%>|rC12eYBjr9PqG&P0ebs53mux;< z+x&MX7cnP+RTSEbi`5Tw7cN6!+p( zaQEU;+?_zM3hopuUc6`^1Pe}a4^oN+X$eyJ()XL+ADPKy=H6s(?tPv;yL0fnekDOp_s<9pL-bJ=R8v~y#I5ouQk^s*r!CJfoWKk}aiVI-ov>#1 zzzYSLYp4V|*6A@Ew=sAiJ*#%>Uv=W7d2&=7-OgomnktrVbgHJ^2~-XsdvMTf8A#HW(XmgAZA$0Ua>>ft9_ln(V9yEju_eCz@FaW{MXjc_!;JBW z2aPatfPS*P_MwXbHBxYhc3(yWw>B+wq6|wHC(zWB)IsBkcpM2rwn~qv_C3TU+Qzd$ zjA_bH0%Q{Ku~=GuW3>J&I`P=jyJ-YidCdQ0$DKUDW(|m>>c&BmLya_8qe&j{Bd&d1 zxc^m|iIxpE*{t$19#9H$bweX5AJ*Vmb`WA)@TXHLgUuSzTHMr7Z_N1(Zc*3GQK&2T zzQBJ?Kpx#DU!{8KtX?w#0%g8S)m=NB?gI%dJi8x-f56{`bNz5URakoo&eq$f|cp>ir_?hy=psedo$l)q+ieKR)%|tWmB5lS%@}EAozCPfhvg#Gtb{| z>>oCb%(1h7CW!ghKX)&^s16sW?x2IWCZf7_Vo-0?zWe^fM&yH=qfwo2n0i>}Wz+lB zyn8P?&j@adV8~Xz-rf}SX|a(^ zrc+=IzWD`(Y6;I0Mm0Y(??mG>6PYHE z(jue(J+jjK&X74U>m*bbA%gfv2FM~J&;s(1TQS#5gIPN$9Xj=&<+?e!ht8Z~+ms^Y zTqwzv^e(a|x<`$>*fwCuVmQntL`DmM>SrwTxtldy45>+7zfv*MeGXmN{>t$De? zP%rue7D4NR;FisHSs(L3gM416^W3A-ZYJN%k?+MejY`FF#?)fbO-wcuY&rydWbd{s z4D*6gh{R2PaMTTu&qX2s=LJ}MP%6W5h$2jSGt?5DyVtn|z^ zSPuw_KDW2=yXyY#Oh5QrItjch z>H5&Sp&%mQ8QG1RST7Liq0{nKOSWRfP0VF4yv14o^P4@}Ne`PH%`*;muDL_&(c16! zrRE};0))an3CFaAxJy#_a_$K)T%%g&Bc4U8JI%RjV`zwB++)JOK)k`i1Tvmp->Md? z-MpBM@s&`@80N))9gMB02EHF1mVf^yh;O87i>GuxfqxZFp2~yj@bL&yThpU-hS*SD z=$9Z8ZxUP0D5=?d;0Pg9@`3TxzV=jI&x%nQJke8-=V6}&GRjt_=0T63J`{!V(-8{d zQ-=`xVkFPG>lU5ecL}BQZ!UfnWo~|T)}SgIyCGFLrgn@c>v*c~uBp2i>Az(?8)WRA z?fdmt*e9Z`5R&>b_n-2PU;9>n6*j)Td^I`vGb0+b+SAn8^N4PCv6

6 zp}ZiJ2>K#8T_9J19jh*1)s15Vj185xWjuNjucY3Jk=^HE2G!nqfMpBYL0cd);g9c0 ziXbVKSuo=d#vdhJH?qt{j%sBmu?Cg&{gb?{`yk;2$2foTHU;YWwK|qJwWv*?lE8#e zH>;^*`Lnjo-rH`v=x@}u7w5mW@(77yDebRtXaePJBhCCX42Z)IF?B~ZqeOqXjA0%b z55peaz^zS`YFO#vPSN$%exO~$d#KiJp8hQ4Q%nm+?GHdtM2PTW8)~-#w65N_JBH#0 zlAp_mUNGIkh63vdqGA$0ofQ1~yZ+C-{@dbXaLm+f!J~YLCljBE-)2yF_<>_@7(b6c zDzMR1fuR@+^BX9RC%vDz-Qx7HZLdG>jZO8stSkkEsI2Rvb_m;d*}0RS9)7DaScXfC z6sNEB#$8C?0KbiWQ$Wu_w|}EST}7&|&!^f`w~?819eR+q*?A*!xmOcsYRP}ika2#o zo)>hvmIpYKJqYMczQ&WzBr;3J=JhVwaE0Q`W$%ex>X*tUGNZ|(JMPjCWu&_Qu8Q%s zZ$x7+6L(e`j{(eEyjb=p`NZFq#dv6ZVZ6n4q?N7cZe!f+LXzY{5dDiV(uK$s12>A$ z;NwpK2_P(COY=!g7UC{`(^sWPG3{R3K=sNPJSr1j=%BhuB>E*$=+mk9gL~CzgbWAG z9*=&Of#{~kV6jbo6O3KOx31jEAoCWaI<2aaw$mF5DFWi;@NHcm$6XnJ%5Lwky$K7Y zCc)r6ExMf0PZn5N@j&}Hyp0rV@~*iZR;P7M%pg?ru@n1YuEwGEVc!p8jcErOao$0s zWP2al{Q9U`4C8=O+D@8J$tv0lSX5R{WCJs9C}ku#vp;5&Kry4FeqT&yy((75H^lcjX$WG`7O!yCExGha^-K=$yboU3ReE85cXSU0 zmCa4j@O0R3T(>xO!1K#}>!!Wco2E+-Eg@k#-Gx+t!`=25NmPHCK*2opZ?d0B(#=KP zyIl(1)Zw&9j3eIyAMuOqim)GK66N#qZH5m?i6bQJF2ke&4PGC&97R1a>$SIg({TN> zo8TYL&UZ@!$phTy=z*=MlwNYz81F*J${PZCD>Tsk@kSQ^Mn9=#-MZycbJy_sh?Jom}by#;N0IR z(C^OX_B-fcss6y()~jt_|Mgp;fx(vtgj{Uh9`yuah5f$NH#tC~=yNDUtRbuKH#w)~ z(`UV2eNYA}fiYRg30n+-gVuI)Ao5sxWw?SM(I_$u(^Bym?T-QGlwnZ02vp0-7NHMB z9rj7mZ)O)K`*KKF4z&0(FZ}sTV8^S2u1b8T-)=+I0=EL*`RASPw;fyITQ7nH`+}v( zbu~Zn7?i32$(@)bJl;McXyKT*-?0C7QrzFw4v9@{xB5GIq1NY7z|J{G*W;k7|ZYos0 z1rkC)O>B@Sv_z!|{a%VLsBto7>b5-n*0CEZ_`inY$eFOw%G4E?1nOJokdQxOz!vfX z!nax~wj>)-c;xR|I@+E~D$eJNeHsPYGE@&xO~ zsXQ{lVVn5m%XPcU@!a1+EFD{ShL??Ze`{Ds1>U1{yK8Yg=g%#C>vI>Dwy>KZI#ez) z_D0SJ=RWo&8{1*o_Vf7?LiX^#Xel5L(XIhnQMGTHY!dD9VlCM2l$fMxzG7a!ZPp%F zG~~d!6wc%)K+X&MIJokcW0iXU3l}jmB0jv*d5)!A3d=IKu$C; zN-40JNZ6}@mQ|jlTujFY;}0ZOz2qCNeMZXZ-tapB-4;4PZeWzb`MNaqNg^!Y+34O1 zckoHl(c2~gnq()lnQmpTKz3bykK7B>-RaR4tBs{KydaL&e)&#T=MNX^GcO z!`w&3T04b#BgFu68gsP=Qp7D-_Zqgu^R|_8R(&Jl7f+UGNhL8e04=X(){!PoON1XU zLBF}*Eg@dTBu9FKe97K|q%)qO&+V61zMLoY3S=q^_z z^i4v@a9r5`Tw5+o%tM+T84IS6`O2txyyJ79=1DH@l*2K$; zqcYQ#tT?GBT*c+~-TwC4Y~1%?U=NbT3*CN1gwKGUS(|#;&ProjxryHSdz*UayR;A- zDbJ0-s`8`>>ryny&ld2;C+a^}`gR|Au+QNS1e9ff2D`8lcUjZt_>VDt=z_?r+kVha z43Z|NkFd77nR!H-JiXhqz4_C2^Sj>=sdJdPpP?)BLFo?<87o~mrjHi&1=oBnpmlJU z=`jdkN0391v#WMG?h=yZ;q1-xF~AS6@h1{AX5%kP@#gU2<{i%3(!rIw&VonmCfV3D zHTHKl5MK8t0JJEbaDLSPl&N0?tJ@|)cr42*g~Zc~dezlxom8fA7vUbD_?uOgWK{ng zf&J^5%x!wZVHKQlN3^nT?tM8%3U=%C>iT@&iJy>ohu2S`l;$Qi;~k{U+@iQ!kBlp{ zC^RVM?{&?3Avq^;oX(3Dx!pCsjvSOtFiw}@SU<)6`r!lPYiH<8u~s9b5)pFfjhD%z zq~P1Ju%#I^;b`Jj2lfDqa*w6=L6(yRPv@s?Q}QS~*Fme1T2TPuUWdk*e4O6o#|1rLZGZh4EEjPxMAZs7`^p7!Q6Y|JT8KWt{ma8UzVTJCuj zTLh}-3cMb$^guBa|C)}W{cD7C>@{ZJq&a8D*!|5OlE;_q+$C2qt)B%N#78&7j~+rg zWh0Y}d>2`y2CrQ1?AFKsY{bma{+xk+k1g5U5xPn!Fx;WNa4zR1}pEHhfg^j$9??W=_D#4TlHcB2}tbYyr^-S^L`xoOFtDt zXE^CKNGl@jW}DyNs2Yz;s6{wDf^uw`XL!pzwZ#>FZpT9VSNgrA3Z$XhV%!v{*P4w? zYo)|5d86z~$>rzc+iMxKVgJ3m)Sx7&!-MhQVuC|%o)XHNIBE}(a)sK*n#7o}iK12b zW{V5gFjc&ex8gryb%@Xg+|OX&ow~Fix+&R+nZj;NQf9Je z>}(}D23-k2fC>1zN`pERY?k}6ASL_fXJIB8(o*>ehAV4zCsIK`gG-^AK`(rhph zssP(i(YEQ%V7ODZkBB_PB_hzK7VjM}|8qZ_Bh9!!jrs$pMo5h^&ch*hQ6#tke7c=NO!hU5nz3v57fhzLo<(0K(BS%s@F65@f*TMQksvVz)Q+{ zya3rLx^D_Uif8lN2}hB}Z(1P?g4&5SaRy(ppmR@;RbQ61sR^3IgWJ_aYF}%2ZE%9$_Yc7JT#bqQYx48?(kHW4X#G*b{O)~u$ED1?| z+hX=?$>XTr|LOHwE3&~%vF8(u44DIR#0m8cqRg+a@-DTpKg`?~2Qgru`-VsUan&ax zDaam9xntm>kH)&pol*L}&ljU1U8M}}lz*%816>wd*5CnvWp`y95^_Pwr?1tWmkTr% zS*hPfvr-Sv-w=USXv)$4yY(RQGJ*5}&QhQ8Je4nO%K zmc1vltQ+peE!g&vBu}YRVhkxBQ-p4nBs4b`b+X&%e_{FJrarEs_4nVpDDmjl{ujH~ zNq}f?g{E?eR+*pGypMk*6|tH`y!F!V{&=U9kw5a~<{@~0oPYX-FOE?@V3j&TCDh$# zkyT|qX`nsDKyDIg`S?VH;_v>QK?Y-yLhYB&GP&@bU_ExgqQ${Q$UPfd`_=}70Uvob zNooCv;<(H`8;xh~qG82^vLLnX)&$JhO@*tu|9v_5o_S-8AR&J|^SJ&56;}HK`_ZDd zx%rh%2NN9u)#PAIXadIqrk!@F;BUaf7X0hR&#*k!e61B6!l$nie&vtSZ=l5B&E_Mu zzhs|ok%^kpx<6QyuH>ezcZv-IT@OOYl3F9PJ@NEiXkjXVtRjz|hDtAvQCFkR45Tj> zx8Pw{a+5jPpLD>_hNKkQN8|d>e_vH0?wr2n+*c=VcI(j?)!aXSkPRiwPDkqX7j1;( z$#$=tpoF|okFE{sp$Y6F%y6_m!0GVP%U!`YdnJRvUl1o$fIDab0E)g5NT6F#s(jz4 z$znW`gFJ~Dp{lNvCsdbP;BdtTMrn;^yqhpD)*C+<%f_ekc(5yZgCm{bu2ch>r+vm^ z4Mz8c;k}eDj@#|`_-cee4T3nPoj`zS=L0Uy6IUX&*E)?MvQr00NAJg|Mci&sAX=d1 z&Ts8*t|e4EqTGvd28Xa76f{+jUQkG~uI2VIxU|erdX8YZS#W*8Y@E_Sqx|BPl&O%E zgVC*TneZRlgaG?#0$i%v`V(+bv#}Ww2HkoV|MK<0NL^UaZkoKiXRV9flt?}~HYTSo zF>0hl5dY!~BydhLHU$5q< z=iuXp!swG8?+G@V`UA-Vt(jg;JC({;?Cnzw!THf};9nNEA^U?s>P&RP&{CVig)MY$ zxuZt~ygJ%^TWF>&nQvj#I`$KmzxpqgXvX`<+2P*JKqiJ2oZ9f_hw!43R$emc*{ z^T2dk9Bj7xkPW47e=#)rxNMRY;CUV9(0-F2h#H#8nz2k(%^}Rshm~yID3H{i=Z)uu z7SGCs^%{-%OBmmV5htE&qeS!#O9JT#6DxJeJC9ClfgM~Qbi)`i8%O=*3*U{}XMa@V z<5a>@wJQ9{b;-5jU1UW>d^K%0Ge`xAaVV1Ufu$Yx5XW~`YY;u1SASkHPGMoOo~X0r zNZ}8ZK%nXvo=;OhwA_c?tQGj}%rKZhjuzr#s|3?brgxC+-48`+aHU zSuZdMx`COnwRsQnEF3_uvXp_WKsvtE*M%(HiwLhSKlZ^a$+xV_1tf?K{p|ytdl}tZ zIU1VFaFRe{M1f|(u%>7a`Fi6GYl?)A9EgD?j24Njo1WO8Mi$`?waP<2>=MfJ4Eu9# z;Qy;`8v8>gbiO4GcOm59ggc&?T@!(7wnoSBbCIPkh>Oh}z>h40m#F^3y&x3FgdEaF zM~Q70P?oU1ClwO-o{$;HmuHz?)hcG|vfz4Z=+apAgcXl85R??F}5iRl#6x2=HO0 zuTEX-ZBQG0^3EiT1HcS-yy#;EHY*D=ed-K)vhR4xC2|~#dEfIE)`pF-GP@ZA;Vfws zVP@8PPoE88(O&o=^df69DU%UkO*}(zl|wKbVjsI@x5tY~w zytoiXn;E-X%0<(^7$p;&t~-aj39`0m<1MS#Xo&NVVN0Gk4`k-6JHi!2Y)yM0q|GA$ z;zdA3za)8GcT^Y-rA3fx_2~}{ar`6W0~;)X#$!YIQQ-?V1>fbBa#Em2U!}9BF^E?G(c zHOec|B#LN$LA)IA7@{-Zs0=OJ zPTlK3N9RR!82I2xceJgLDixWdeXwG^jdVRXvtx8{< z-dEI*usz~+s6ai}y1-24ClZYKdCW$w57KsDg$yU?UR!HtG}*tA&kX!ombeZ1{4{0f zDahtBEo^Eb6sCw4)Ki-lZBq1%%t&vF&u*vS1}~37-yS7vZu&))8)SY^gdny_w9yf z21#z9eAKm8H$$HQ|CSB8d_S@TOj6c#w_$etx$Fi+xpN`^wUu$JM%-YMmD@j%$N5ms|zb|S$fxb~aKq5`Csou(>JY>uWP>aQi^w$nuv zh_qjb*5&%gFVTqB|EeMii=;GX4O|B~ohx+oiNni-CwpN+TG(KbTjlT6bKV64gs}vd zTd7B_mshI|%j)Bc^52fGeHce&-i765LJkCJqQ4;Rr0#^n#6Lg=kY0u_lGR zUy{<`F64T9#ENrGz6}1X7z2jP90CAk4HZF0R6WwOI!f4Nt|H=}GR?enH5bF*?WjFv zSua|-dcnI^mOBg(YC7%e4wjDP{46PDJX$3{d$jlTc-;A*SX}2<=@NxCGq}j9aq5>$ z1fR^~l*ghq=fO8pWA2XmE%KQ0J#fy^Y}wWl41KEde3Hrd)-2{g&py(!9pUU-_NDcZ z(;@IZ5FW2X@+(;MK?>mwdZeVk7mT=~yBl?BKYG(&(cqeG=^;$w(S-phju_jLA4jgp zG8`uqoSCE)1L1K~vQ^g$5&*itP!% z8&k$lAB(H~_NBZICR$KFU3sIpKPdM0XfL^69?gfsDwpQ*mo{FTj0I}*tQ+@zU~0q* ztlSz_yjQ1t+%7ab>HOhg1!NzrU^Hd+@t|G!Kt;2tbnOdRo#N zT7w;OnNP!ysKv76x-gws3gC*(3)rc5H;wVm*qXJjRqxi4(+g;VU^!M7eZwq&IkGSN zw%#Te61cvl3a*J>jOyXCB#z3WaqVslPh1?Ep7}?`5r(IeLEgU5E)%tzrFx=v@mr6t+=(&2l5jf80`mI;UfK~{S9@0 z`KL(Y=yjQL2Jrs+4z-GBTyYaQPGsxFevawShk&2ViR=sQD^2byO%4>lEXV&rj5jSx)e)bmnWcoMh3~8oh>1ZnAF@pUVbkE<(-y@e_1!9-F zXzhG()Q_>A#>aT&Nie*eCKB6GD|la$sho4!~||4qSb* zQOD_P@a_%}EwxGa^8m}f_PabyG+eZtDqdhrOqCrbXS@nqgsLj6_``!Bu8l7FCH!td z2X}}q?wLj9j8#pORWi^j&%~-m*eV&%Dq(wLHpEQl%9QBR6n4I%jW8uVOXc)(y$qvw zeshxzo-mIi~qAmg7Xoeh|qIyM>`ba%mBJ#EoOIc z0Ye0_h2Rdr%75zktL@Pc`O(Y0o?3{@7QwY^cj0*yZ6I^TwQcv}*7Hn=cnDUPjtu`2 zBf4G!z5H{`g1p}P?Ty+3TyqjaXkn^Q41Ji%0+S;tyR30Ywj$TJB}HuyqMDqQ-*_x%D>hunpHTkn;Op%9szNrpNJB%u?lu-ykmVtev@^&U z$1uOknmUmWi&4P6|A;(YiT=d`)|yIF4OyuoDz5Ckq5*~RgIt67mA_d4zFpJYmrc_M zQB)=+v0ZAp0!&xT^&M|_fSN@w!;@q!^p5%?Sx~F1yw-j^t;J$%;)$Vg1gU|QcMs!^ zF*3M;tUk8Xzhm|neXEOkP~WBH&U(=|s@2CE&z}XtaB2uYEnxdM_#iR?hBV~2J1AOn z^JH>i*39o*3N6C6{j7%`Z zYyCqs^LvoT{zQLNJwQ;MXe*%(Y!X$jZz=>+s5u}ikn2ZN0G3@q z#3ae%Nu~RcoIQ|yIQj+i{2rPd9ms6gx6L&&EAqtA&GV|UYz}FCsZ5_jRByQD0{MaT zgs&sd?68qhKvZXcOaI5V_;v2vfYl%UB@P}u^dwW-mm@|I6T~$70czXrZAY(?Lr2h= zxqM`!TuIpz6FDD1!jZXtAXUgXzYX~muK#NrJvuJ$KRc5JzwA_f- zJ4KC(c2uHG8ks!#aXoh7!ywV0+osSz6*#|Xr~~&3iT*6Z8+kcXNuTY)waD`#H}eYj zBjhsr9<3r2*x%Zv(78tY&J2^28*`f`HQ#r?Yb2vH*iDrD${2tR)3$GyWtS4!58E=tOe`*^EU94w(f?QZkvCuq|mOj zbiZCz6roLf#xfvt9~_!fjr`DS2TTig=A#4Nb@o!;Pus8+64tE}LHG|9OeY30C{PgZ zdP+DnO$p za6KRmMh*BVGm`O6Mh;zX1lQ4Ek~H~_X8!f-`x6ZML>dPfid}FjIMC52mzg>3=ukdX zp(kZTp@gJq&5uy?d-?#vNQfLgXMP?(HIK~JUJUcw7lvwj!qGuq>?pbW@GHY;eoXD1 z{Oo6R;+H{tCNZY?Kfkg&x;+Cq(;JXPJp;34NMRMx5JNFDf@^(*1Vk1EsrBrO+)#?J zQ9b-#t>AKgP>Kq0EiF%ffHx`Hmj%L8<2#JO#MoD4kxl$Xmc1b$nt?X!{0G5#@ zzWdX1JZn80eW%RALEbk@%>wYDc4?y?@0xF58v!EdDlCuzA<-@Csg*{Mv^W+M^5@A^ z4iX4yrVf-DGY#jrG{QsvK70rE5G~ADdixFmX~OjVB-z#YF3&>(*%wvA zamopgkYCyA5Jl-Q&l#BZgV7l1XO5bVBKv}_gBn{UC8KTmp zU{j81G2_eGEm2Ga-aOXh?gr8Q;bBEehil#g0KD0CZ5T2ITzY7bFV4vL845QM)}N3h zQONM+vs(kPIuM%Li|vCxqP!58ByGlaYDF?jrB-Sr8%C!?i%yRAw6gnQ2)4l5>0>5f zuOX$(I44tmYj-o9fHw?rB3M!B2%IZG=a*Ecqdk)aQI>{jv zWvu*D|0E{9n5)duR+zC#6(l9|K5#(=WSiO#QmoHc1u+qbCGOI`RnhIY<(NXJtFIh+ z)u`HkG^Y%tS+}!(7uMH_9U>XlRz$H-5kb4R)cM!%#@t3QnuTjG>@l(2ns7MZZyT4u zv1zaSM8e(o$h)S0c&@k!41$xN9(UnHLj-o6Jz>weME@7$(0v3gV2LnG8T zMd5kWH~T|rO|Grb$voy+o(zIA<7Dq%2v+|JWu%v!7t>BCh`^ad`AN3MCHP~13mr~b z70w7Jicut^1JkP2HuX2MVI)*r?IudmiE?paqGqAJP43p->VzTR$s$4>3XP_|oX?=X zmzjC*TYOV$zSab){u+>3Iw!w8E1}iWf<^=5RpPdyOx{^|Kx@baHM^gJdPFS60#%_K zJeJ+H31OVv-Tx81ZCj<3N>NjS!F5wHPKz^gk0!8?UZt;>IjJ4dt}vQ7Tq z;y}+4eoKVEme@gt6q3v8p4xgbW8T+vYEUR}z?sH8Rt#)@lGk>Kf&C)N(`scL>eFca z&)>kQnQzGx&1yP?fd!P!Aj&I^5{M#&OP)6}1AJwlzPv;zq1g@WvPIekRcf$^a$VqG zs!%&}E%%X+2K?jiW`JjsCBHOfqUvb?1R>N*SjW)73j8$28vVL|CpT1TXJOKc=A-)? zZ{>uVIAVbwNF31P-nURs**(WLGR7|YmVIA0(O9U2FUEZSQlrlHjhQkt=^zj!_5oL| z%m9-B#QXi+={@_9feerJm$*+pEm0(K=lKk6bfO)NzTaQs3SSIN^Bd!bB8Kzxw<7dC z`X#Zn_C0d4U$H<(6u-_Bls>wp2ra?CWT2M#q zx@1wq?1>jZG>h8)xVHDDS1!^0K$ zF_{>iWz~O{B8r`c=dU62%4FP*dtCA>|7W{ZF?_|x=r0Jh{>p=F)4KoM$9lN zH7iaO)iA^{$S{i)gl2HnbWZk96{CVH$-1JRm0FJzUF_|A^x(jIP4lfy)xJbFR6#Rj z#^wXZBVr8%7K?ATjhINR-Y^HRsA!;nooKqK#stuya+kOOtFA{8@f`Xe5})Ze1!Brj z3J+KD&I&Q(&{R#!j<9?Y4sJhd%pKt9`YWQ_0}rGf$vud$V8d?sOIgC88fJ~n>;y0l z@6Lt)@^Gf>5{wx=;P_srRZ_-F@cI+_%dR?2@vl^yA-H6(%|_s}f4=cGT4uNkZFoX| zkiVr691kQ!hGTCIFD;II$8DDEmOKcg6ZrO3Tw{)gQ!}fn>7x1p%WJd+w&NOXGuojE_LRW;j z;Q{St+azuQ?I0>^nT7uSg)t_U0F3j>B8wunn+zlLxL(X5LfhR_?y+WR$k@ z3)l5(rfWybLdPLuqB<6`8(v;m?D4IH4#+GffL1x=h|R&Ta3f7&@xQP`*pDRujjI$x zOwW%^u7%`zhm1H=X+Nz0esc6?&qAeM48D$imWjhtKrrznsWOVWVtDiF&jl>wLP^4X z?$I8RcDmdjSD6>IoD-?DdX)!8Dg)K)1~%_5CjP9HSZ5x4C zq0TSF=eIo%)%-K6w zLl4?$qA=XkD2X!y&nJp;=_sgk2&uT7j$%DG<#S>*qfmOk9C`!GAN_17_8%3y&HvcY$8h<_V!5X&o=>Kn{N#ME z8QUIJ!WK|uoblV++JtR=C!TBT4>qFliB~4pDnc4xNbKezksvvlH|2|K8o{(b6+vwX zy|j5rk5~Gl-qYyKNqk(o_BOEqJADdmPWRz%>oE|01|5E{hqcJ=yzS>0G)D%y~3l5gM>GToU3C+jYNJPxdFNO?2?2@SpWpY^ON00wpM+J-_2Z!<>Tg5&|^`Z** zzwBjepe5WjG!WXs{Pehg*hvSH_EJwK{^TvS2PCQ?*2< z3Y0Y&EeA`Dvf7$(+?+cHMp$#$yJ9C)RsJMd`2JR!a9qlqmt}ZD*TU5r#`0@FObMWo z5`HFTN51F>OGnR4gppRM3)9W^NbYJ2?DC4j+i<5$YlE_i7l(IuIY?LmT%_wVV43kXrd3*zFpc~)|t9U=h1 zlA9Iz$OjL@_AIPdq`*R1eyk+mmRmP6h=4wyWZ65z_TQZ+-wk&*(H2LLF>^uY0gExW zMws<|PB9jJEACPo|1J^$`>?v-nY2d*`y!v!x1e8A?FXoYha_c?);%7|8P@VCdfWWP zMsl~DL)3F7t^i{Vm>G*YY={0lS8*Mr2AY309Wx9vZ9_PbMyY8YlqxdKMvX>4p$%ZA%Pd@NYMFu%sTRSiY z#f-#A;=(x6B5!biKcO1Ef%w#QUZ!G*kK^Hskr#D6XQeP24P;jH*r5X!ZEc#c2ji;6 z=j#<*J!A{7_!Yh4*}lN|GUQ`O@APFrb!V*gP&iejL&`|V$)#gb6I^=UyhvztHH zvn)f5a433IY1|H~=-k_O$QhYo7Q&F58^ty+@?))rc2U#Z9m*X^Kt!wpUqx$+>u>9l zcM$B2v-27-fZbqqb_V92b?HM@4P^r6&b?QZVc;X4h9`GImRgt2b2F|4W#FI9Bi2{? zpD!nlR%4>&%$7YlbB#X4x;i*ypwTDy|#TupJ?` zkZc;>J>Wgf;ZgH0vACv4*EVcSJ4VwkDrIKTB`3c^`H#^u|2SOR8Nx5lE%QjexYvB= zc+y8t6FYKy;7{1>aK#~!>ijpPw#i%GMFbBP)v#o@Vu{Im=7`Ke0j`njeA(eeR z7-U2-neQs`@E)DGa0Gn<<&_c)|HO+MS{29f8_gVsfhgVbgaw-JR41JSC|=8$(Q|x8 z{RpoP)Fu>651MxYIlfg>n$(Xa1I<+AIDOyG6~-idNyzyDhO5iRyfY2P_dUD~CgoOR zeq&E&XQ?YxG+aed%`H0koysvI%AAdK6wl+URjeG!;u4=jo0T>-?4>*~11G%|%2Ogt zdU-|{qegbCuMMh9XUP$MMy72294f|oik*ZrQT2?xSph^v|1~4WSf3<}wUUdw`r7&p zf3TSY2x}03-~$~M(8l!7COSsPbhDBvjm>;Mx? zUDSmdNQMgriYLuG#BM1P^RVUXTZt>vQmHt4fSv=jb!)40^FdEjm_&nTWgqL}4d!

h-p~;)6Nr572$svryY+F|IG8cgmMx-%Rt(#<*Mqg;%M&2>M_Hnlh}5`-hul^= zsZ7bHpF+qE#tsd{ce+i9CB;b$tA~~oixdA$$)JBL(%w;E8i>IVKNAHHI5**=bA|J- zcRFmxb>CWA?pla=q*ta{CFh0G*^)rn`vrg&qN1UXZn%hN-l0v0dEZBNZR=3<36r@` zxM`1GV-2a>P`W@zYKg0AO9v zGHZOegN}a{(!TsGwW@sa&0Gg2&|FPB3ajqG!$a*;T8Zh@k8CLAUl%C=pZij=x@va( zHoNoYGE91aLKo|cH}axCimktxVP2*W1;f!u#x=+sF^BdJ@;j@_^K9^tO&0IgtD_Hh zBwGrn6vb4?=c+6?6z&3>i9X=qQ8!Q$vP11b*^5;nUIyU2=tZ4lz`3S5D=s+ccI<*` zf^@>cJ#xtUJ-3^>qjZe=6Fxpvr%atIo&tzYcEMVVfDquL2BRgMXgvU;Y$??sphPB^(w|wrcbs!t6pW@q$f!va9RS5gE(Uto|pkxBh zV_-~A%ZfX{w@b-*=Ox}f;FjZ`!0(vb_k38z2_SJY9qj6r06vK>!lB0|AviVKs^K25 z?LsX!mCPuC5eL@6kw4g4?p%rTIqeU>b?*iz5Qa0sxwf#apCEIrok%y6=r*P4uD?#C z)zEM5{EKse)vc8 zs63nJ_ZDeHZM9-wLt$Hv_uk@`@X zFv@a_4r(1a8tYF7Md{Afy=h3>k1*PSP&szL?neWMLqK$w)%!B+n`#=qX7R!-w8Aq* z52^5YtgPwv$O@sZ-?x5WotVdV{{+Uehn_0BXPjT3b^h20;#-yafgoYlKXW6Yd94>u z2EDBaQV~hP5^xLB%Jasw)w8j+Lui&I6cuW~$Ge#3xrKYVkpAV9D3+Z#?`}tzNSt_f z@uw4qfQT{C)gF|`_DPu_t=+4+$l#|xKmH_v8jDENCyo-noJ2)CH^@E>XrK0lu~Q3i zr85|)3%`@&4w<&5288E1PtvG5mI~%6@x}Is4rZSUQ#Y$RK9A~rg|UJ@db%>1+|Rs@ z0^`gz>-l9vC}7kf(%%8el@THC9^Crdzj_|onrt#lEKVwpPDXNS0u&U+(B^u${$yIn z@JvHpn+i=jmU3gx`eIA5Vq+{{nf%`K1JWW?`@CyzF0^|7{^>ufh+AMbYH|}Hf|r~I zLvREsz0-@*GxzA;Z3rwMwELEK*Zan7NoPVEr*Z3(V0ntpkeN1Jsc!WPC4 z?fyFoX;0&{(2}oa_Qsq*JbZOcp-xW_RWTOI<`JW=ev~HR!{x%)iDN@$KzQ1+l4xHo zWN*q3UuBqkMjWBlae7q)wM5{hv>p0VG_?82P1vX=CtN7YwC6N0$)(1tN&z7i71|jY zH^A6$UXevY2h7`4$*R(x$KIAl#xP{gOH1A};Y#jY8%lL*e}n5G@vwp>(6DPxmJ+b?>d6pQ|M$$PaI$kd>vj;c1N2n0fSGah9z0`Bm$lpgKbrf6 zw~HFhVF6xRFS;D`;nOee|5rCL?oIMMn1~=BdJf+`=v0>-rFJn*|G>W&X`GR1bY0l8 z0{A=}qdfDKMqOc^Q~_biSq9rv2$pY~y$6PO5oy2vuC}N_<;BlQU?@}Di)*(==ECCr zLdsB&yoa)4pQ*Y(yfy2Yb7ZIr_+SkU`#)!O8a-&+l!T-v@oH53_HE3}AQre>ZZ8|9 z+^&3LpNmSClDT)Mh8J54_rKwb-hfcjiT|39NvK}HOny`Ku{ko~xe6BXS4EPj;IA{k zS*a<1;;BY|D`U!(An4-L&O5SMZ z2l)~uzy>qRmk2M?gGS;sSeXJJ&B*c5J~qxzrvGV9N|nPMgxFr4kA(Va$GCpaYn>`T zb1qR;mMhxm)4#fWUGTm{YGG#9Ki97CAAuL_3Y#JkdHkGLt3&XQ8fchkJId1)dsA*Y zo;tR;JPA=no`^WoT)n3P3s1b{r6xZi7S@Xx$4;km}b1!afs*|i^ zgwnrT#W@ek48s;23pCgnvOWd`a?;=FE>4f9dS3+tf3yB|uf~WjQufr~!(Iga-Z?mu z;tQi0xKWVDC#M*IdSgWC|z>0)5nfNJL@_6o+cOi8SRxq7N1 z7H`~KR?24_>cg~3X8+NulTZIuPP6LBNKl@ThX_(C^!U$n1i!Tt^>Wa4g*hW z!!(2rw7FK|`<18{N88@d<2jc0e@M6#Qeu#f*E|wfh#Td2RVlXbO#v4sBlx(y9LPqT z+MbU6BAKbqSdH=%L*|{ziYA9tQKA`7qK~>VsX3K~|ABHh`*^1zG~t87Z~E>_OPp|L zD22)cHZsp;k|Y&?R`YM)#7VvSo)=9ERYoKV(^zaul* zTO64}$;g^tGJQ`^6d*ImVrW{xG+`^e3lob};naC=NQDQ!u3@X9y~<9mO4qx;-s0-= zEMI8i@#NlD*^|~+*ZHV!QcS(R+>$XMY-{76lkcD`0zTHMD3LvE$Sb(*WPH^>I1{f& z8O0jM;+;WRY_n4=LurSvu)|X7;SnfRuma$%vU#S0nTQIA&qYl_%Enrt=roKxKJz?Oalpw|Qs6igXLp0SWx# zdjR|&O=scPWZbp!QKP#?NOyNgBOo9pA&rAk(ulxFNvRPENDl<0K}xz~AdR%tU=j)l zNJ_rrd7k$V*!}rzyYKsVo$qy>b5M2zL0*`vfmUSO;SLC@&1f~Ym6*jCN+MCgbtwd% zH*at+OflLo!exvOZ=QULn(h`|^3ZP1W-1>9Cz-)4j zuh77CV_ry-$2P97kBX~nqL6gi=&(gIi8c}_F^tk4JKifg?E{!8ajJjhtUoo54OB=?F&lAcbaI`++%2EDY%#65$1gZ)-2>2T zv0-y>2J)Ory|fnasq6p#*W_Kn$B4fc8Q%uj8in>+*-Q5~_^a*FZ#-;o(tAmepB^x$X=^#Bo{HOA2_eG~FM9DXvB^-lsc09wcX#jY z#fl5=i}pOu7o?U=Jo}yS%D5F)(x6TnnXqG8ii?Kfg+I5PIp*j>Fd3^0U6-QF?5GNa36aeuH0nEi;ufHtz@8-~F~! zmpM~_=B$#D&uaz~(=bKi7Og=a9co=AiPql!j}y}quD&}l&c3c=Y059(_^1xmogo6O zp7Em87 zul4gA8T7SXyaGFWhl|~4hG)auhLLu!ADansk`mHG%c@9s$0|xIO{8i~ z>U=l%?FwlJ26`n|H_{hLJP=BEExKl4-#rj+fEu5xia|GNgqmzlmXy*dE)zZKZZUdt za#B?Z%GmbO3VY^Y72kr5GF++pI)~>%0L4eCtDk2d*AI+xtrhp_;OWeOYf`0G#!p*C z0`x}Lc~S8L;qqY@_mf*kjvmkCZSs{~xky|1GIB{v%Nh3XoG?38Fw*AAy9FBDlOpCW z)?Ap)51JT>{{$Okm?G)v7L-rC6%{YqaZ&gKLgMhU9@0Cn$j-IaM7^#~97M7v>J7B! z_Vvl(){m075?-(v;EO7pp_?Swrj`N4yx!1z_gjszn<8n_bH;>%!NF~yziaL0ektgL zrM2c{zSoQxA6`HWQuM*BYJelQztY4Q~2A#iju_jgbum7 ztA}15DmgV=Nx#l(sZW_1L+u(~i3t~t?=IV)$&ZI7P3z$ex+Ry|5Z>mJ^!fYCf3Zn7 z$dHJS9<9?WcCqX0FY__(w2O7vZBGWlv|%!ko*<1}kb9%JSc6pY+sGg7a%P2W%$fsY z!XFXC8et}1Skb(mV=kjRFq|nsv{gV9@xjQ-m$c%V7-ilSO4~<44#F}#k*2Q1*}T- z-5~YD9;w9|e45~IZNA%_H*KzPef{Ar(T%?H9PDjf)j)si&f%g(yH*ZWPpAXtPtVdg z&#WCZj@7$9W|TfGKKsgT%p`s1Pxm(L_{?7M{uGMQySFgf8G_aAdh{i{4N1z}mDt@v zHc$U&x!5Vpl*t0}GH0*p=i{b&i%;Ju4&q2}QI6|NW(m8}D3!Rp1{I{EJpne}3f0ZQ z0GLL+!Fuhm102QnMhfb`Z5F)hN1b~6N$EX}vn!ReX`&Qvh)mlSkL+YH=6(|~`?6 zl_TsK*G!r>zv%mLAw$uCruu(>LbRWa&m`{-wU93gqC5q*7)V!bm1G#)hkfm?^0;Sb zP+Il(UoSYKQyjucceLypKl4(9(|xLFf*pCXH)f7}jtfJdC>O9RKYmUZbgC+6FM}Fhrzd7i`{K)@nsI|6J1VBgY*3 zX1@4mlv5Ef{$r795rUZ9`WMZpK-}n2d-I8<2QY{L>}*IgGuK%5Veo72%n>| zVVN1;Tn*TmYAkS7xmmo8Gti(VS%fuEfX$B>q+vV`8UUT!Evkl{i`W?)*Y~Cbyz3N= zf~2HvM2H&mhzGOgh<2Z53JFrR_97pb#2W|UCq#K>);(IZg&(+Y9tzu2`qWs_CKT4y z54F}#rk5@hYY~@O98r4OfzHqh>V}HJQ$Enhb8CFC_EU(`1YA}MkP&Ae` zulMMA19(jfb*OwS&iY(Dh8-&k8}$?;Ir$(%jWruWLCD4M6faoN{!>>(eVomb7H%e- zQ3AV1RCLCERsemFYmoCuj=N#oZ>Ncyz*_togm68wXrdM=kOlNPe+%jpOuM_aOaoe6 z=L;x?&@*pl)-Q8)$9&~{@*Z{Kn%NB_2N?z4yGnhHN_2n>yaXyL?)dNGs=GJ|D+q{fIeq@Q@zzYBU(omu6oUpip6_#Z=swO!0?^kSa zTv>Sf80aMm`3P=YbjiN7+i>84W|#cbai<}Iz3+_1$eaJ3tgtK+4Z;>K;(V_FXx1^> zxXT{7Rca5v2c|NOmGqtA%#v}rDwbgMMy)n>$3C8qqK`^+*ELWURTNb(CSYz1$iciE zukY&YYXJ}rX1imvJDlsqsaQ&wQZVmGU}cNaia9r8pETe7aTT-QXwQwH*HLH+2%-d$ zd-!bp+VEphnF(EIBILTEJCHHyzs~w@&zN5@pWm4c5ghIzRrV1OH}ZB9KiS?kbNV&>KcUg4trH=)YmUA& zgQa;buQaB16=CkNPUDMyO<@7(AM&6p?pfOFxBwbFAyLRDX_`#4Fte~a^g49Ga7*#z z9QN2qGrVONpj#YP&!+)zGv1gjnJO)kpQwN0r9sWkpP#kLCMAX@f+v&&po)J`TsY9L*4RFY3UFl)9} zf3&SlC#}7rwyPf!6;`_v9bLC}%tE^dfAM)537M!H={MOnU&U1SAodKzf|Tk9CjN1Ech3Rw48_V|Y%a=~fo5g&Z$_};%-ow3+3y5bC_M9nzr1Rh&QKCSM7 z&}t|4w;k|F0nPOy({(e|h=#-=CM%Q5N5ioqFFD1}wfD)~(vRthV}EcTxhe5&?^i4Nc)$S@p3)OcgO_s`)ksR$X*dAp;J+qv$HeqR=ic1^<1 z_Qo$f4T3J@KN>id%U)$;00cAeZ2_aQfr>%&*h_t9WF+EP5muQ)pH5!YKn`ZEVh#N^ zTenq70!KnKWPW@A9&lqu_RMU<;-zWip1>rGTM7i$M> z#Syx}J^f#M*5!^57=hl$zq-cT7>>&rN13|j&L@0>9A`T9UzNwrZJQrFd3pOdGWz&W zNW>$({S?SkL)5hszrf{P;%^51GAhcz^zRAJ$xm6@#;1$O0@omgPwTehz23fvoWp7e zs)0aTSP}L&eRMI7mCf~DF7GnGfqX==AHOq(v}B3}DnxJ$}CLP1950SgWRKz4F$R7AJ8q;ngIFyQ?#7%fIdc0@2ZMJ8_)o?!g$gB0Zm|CiWA-fwkeU8 zF(v4;-ZY)U8D<7&k^^zw09Z7h<*{h;)P&y2n*j?r<(az_RYxi@B{5y-h@%#-N9s~X zaN=bakUY|nXaqDY6eQ|wM@G1_4RR|cqIrb%RSYYjdSImjEiSM5tUd+`4b~BP)3N5h zp~HC7OjHt3|1`Xr{BU>?HL%RIhF-o%&|&=uNjroEbSyB7tSrWZMeCFGSd*z%_&c7| zOhAhiw$5fu`17hGi)(*?(~*3Rzw|9g2D{46wz%KK`P`89C{f?64CKo4&WcJ0~iH)=zrkn2$+i#3i#V zkQ~mgmNSUOh zq+p%cg7~fs+bl!TB?S;hGSSn3S8WPiNLa;E)|H)kBDcv5(ud?g+KI-jIfWYv>{R7) zpwEac$CY0j%(hh=eeZt;{QM+$P@TG}(KQQA8$gHB!DSQbedfZB<5^c)tqAi#~+8N~}f&MCwIbB?^uHQEH-( zY7OVJ&6UJ9CXa0Kf+v>el?4ugG3PW!z}bcezY8BP%g;1^9RkTrOe@C|8BSMV*iAtx zHEkIU${46M$fsRvSNdO5KEuE5)E)!93av47dhBxtCV~jtq333GEvS%Qk1u-i#(a-b z;Pc+K%H_WNPBSh%*U~3fBhm65Nzj{)eQ&_foAa0Es3gu>aU=FKY{=>(XU~>kseq5W z@{y5+{w6nt(zwE#2etR8&8hN-)yQ`gBc-EiJXbio{ZJ$gOEhge#iA2_yYM^7`Ug?i zwm93Z@>!d7Aqce~FzfR+I|cWzSd#8vH=Ak1iELUx+iNs^tq97WeJg@$7WD|;l?n=} zSx)`09(?rdbBlO~>>e`1RuSb)sPnuA)1FIO<#0EG&;gj;IN>^!(Ar z9Ez^?_11{w(+~T1L%;IeiY7mwwx<2#5YQTAlilXrq#!+EV=0V?j#ei`gh8^rSh0Nq z*~l=x@P^_*co9HsUqYOutX4a`=R?nNxVGrTL4##kqOrKJIO9uazcNb^tXV27RfkMU ze5Ri~%%fzRcsmW5s*h!*QkkL zd`gs4q$1&z38@W$Z<-Xkq!x3EVjrEgyCFG#`077R%2VTymaI_psa-Y`?OztF${}fN$U6=dK&NSqFSa8$6qJXi0Qv;#8s^!V&hF=OR-_GB?15* zM!^!7=*h!BlHwR-5+_?SM3($?@~yqf-&=>!HrDtJkcD;NA2A;q{n;apZ~f8nvI zEnb6FLuuvdC20%avqq{@3I`4m;tcr=(Tjft29MMccvI8m7IH#G2t@yAY7k5{H~zA`PD8l&^e@yJa>eOOig^=#lynI(?Y<7W}Eq32>P-;Qu?R z^lnosN0vF*#u?2WT%TSlvu+W1THyziT^2;2jAmwIJ;uIa1W7s@5%ngp{LB!!QyOS^ zmF3iZESuxbByUz z#c{>4&5ihMV-*i!wd;yhR52ZGJKL8GVFi_whj>D^BX%Ci5HYImXB?Ak3etIILAr%s z|LnXHLzlv4Z!-qB&9}jE{#GuvWZvvY{5`RB>=YRytNxjoxTsgc81cc%7=MC?dle~h z>EV&Ifi1&V)qEY|-(uswlCF8&Pg*r?J;*caM>RT6RZfw=&XfF3-n{?E0`pLvGRP?y zQYnQ=MaIXFM4s=G{$aUfN-{~EuHfsXl%r?mqMSaI+aJWXTZEAl0%BSF=#SJ+1Cu`c z{v4r7`;LOys5Qg>0SPTt**{Wl4~yxN&3|tXljekrLQH9R(qc5M?SqF zvpHtFMNsQ=GJod|J>>#mfviWHT6JnA=WmDGQGHB?a1`0a9Wme6$)a`uwdC&L%)tjh zC0Q^6nShSJ*oYoOFmp>{YCV6k-h7eEy1R$#VmZRJU=*0+@34zV5W#q&46pjqRAnwR z4 z2WN0R(z@fLh+aQTfnu514+?2FYr4b%;}p%vwdtJVKOWx|D|%Kaon+dEoj0*NH+$Ef z;FY_#-FaI(CsQ+gj*8R?=SK%x8u7}=bm;M(+QBiWxQZ6!LtYD{IentbNO|-OQy!xI z3CN$g{movACBMM&laefNkz?NwmB24aK{g6`wtuPtL`iUFCN@B$Kc*aq9~FH^?qRoZ@ajd2 zP%0{U%#0A-LA}xM>b7Uqyk})dDdC+HBHHeL`-1vh=O}>mo(x481?fS7NQH%ufBvJ; z@S8+knSD6oF-Sv6Gk483IbEzaYn|BNpd0ty5K_I&RHAOQxCKbQ}!?6wSH0H#+y#$yrDq7!@~<~dzNN* z6tq;peqR2}TS%(XyVC21UYPu9#$2P9>=UWNN>x6-SELp=&FtkN<6PArb$pWy!~SU5 z)NH3hh0iXlZ*-H6*K<((J>+q3WhDl%)~^cZ)+$vRdKK&&1N7Sm$KF*n30LmO2_gG; zS!M|xB_kDb0bzZxHdS~1ND<}_jv1VW36`dPIg+k(@!svU;T*u(41rmkJRJlEkU08q zIOmAqt0hxEoo1nO*$Mxniy56>u~=C=GMC+4Sp?^rI%BNQUsTj#J5zWKG3KdcV(kJD zQ46M+%=Cek+Vur!XqHLCSa&o>DT#_5f)&4np1-LH7&%-o>uM{SVaS`9=G6aEFr&hq zkS3DW4wG#FZ_@DIPG0fby{zI9xb=Os~h4lD(WB5)sBl>n&6?m{S|#uDGb z)IPoYn)Aztm@>ArrwgxsWzRy$2{O9DzOT4;cdEmmLpr7$FY_YHEc*C;%UdAS@~EV@ zlFQ~~vp_bNF5_7*A(j+0P>n38g;#Jz)Hi8ObH2Ssh~7&5z3A3f=2nKJeUbQ$Wj8 z^r!k>+ym43PE-v7`e$N_q(6*bv+)#??n)Nvhhtm4-yO`R9BPP84(j7L21pUpJXbfS z?nC!jnGi}Gs_}c_gh%ol~PMLY+Mx#yyM29 z0vBTee8h84P-sQjx@y>+@kaG?i6Z{?-_Z?OL$8Y{SWQ%1Xu>d%1^bB}R#wt@w}?O6 zKA4XRhA{0bqMV1Oqf60PDwcQGEIvgYGIzaVJe02X!-B){T}F03wr(%(1R`5=hUznz zKvyvGO|)X&B!H~W8iSXHi6zQ{p}c(PF@SJ6{RK2SJQ&+KGaC@oXO3w#W=x!|@=v!X zs&5B=MWUK7((|j2yZN${T9hE_U*R@N7ut6V2M0(0nu@i%c{CAS(u2S8j5;h%OEo`~ z0Ml-!;LX5}PNr`6xX-D(TIP@EhkueHn89|c;`vIWt`nGg&RyHj4>`GV<*q`$_rZn& zxJJJIYEJYQ3+@MfVqo!zR3Ewt@<@q6d?9EGZ+$U{&Ohz%nb;Ch4SQ%h}*R`PNQMNUb1Uw(F zYI-aZyZxu4UZab`GP_7{c0IFE!90jX_6oUj(oT?G1^^WE92ZTJ{IqxyQMbYiym4P%3f7dJ3iwMl?o_NdsP;*kY zd8W<-^w~T@cm1yaST%Dmw0;U=TG&+WJ5$TVI^yjMyaCldf@&ZdQh6ug69&au78i|t ziD~+>-l@_r7*>>d@H_xY9~a*pyJ5=R-AMUOSXJ(#4LVO!)8bls$XCirDn$GV>d862 zpS`j@XNPy2Z4}y;fX#cF*!m~xYodp=ep8KA#zBuj@mV_|(O3nu?qC?R%{+K+b`k4h zsBTu^N33Mb`vB+I(w(-HJNvY8T)CkNkX|!I-3PMmkKwtvVb%l6j~SIrwfkYCIQil& zNwrDG^qcJy$IZX6*Mlyl-Jms!XtKH!Kkq&tV|2`ga1#8i0n8vECF9xo|11F620z|j zq$kGYD0JSii8%4-0)2Kp!Z}v7eoQ0KS1_rT@4sQSaTP2sbWGy`X%Z=`{o^|0S-6o% zenP|_Rn90jq!M@Q*x?Ru4$B`|yq%(#d)=3qu@C1qGZv@^)d^5P%WW}67)B%09isjn zsO!8GRsthb0?yU%H=M{#-_4{4b-(m^*1jo$xZLrcYhIp z@+V?gOfM|&SVVlaz-o4cKEKZV`w6IjP$#*iKs;3Ws>>)6BhH(VQk2C%7m34E3vHLj zn!pkE`VHb)04d2Mrm}9Bn;tk>`%c|};YZdx?8{tOwR@J%(<;N*iBFKvrUgqOS+l?1+kS5XU;Xt}2`8%gXm!Ph3U} zxGOUt5@J1{1z&G0A3XJ0MKqMJ2dFAIpiqwE%75l`Ff>cYsi`-j@2{ogWYB9h*uTEZ za0=yt=~Jj?utte?ZY1W>Rek+)+53+mWz0A5&E$)(|I#KfjVbi?v%jY+m&U+Bic568 z)T=;hI%{BF>>o3u6)fYi-B71cv+*QPg>|dc~me?I#mdPnvZgUDTpg++_W*CXN{um`u+k;N| z*0d?sYF;d*hA5%yqTjzZ`RMY!5Zo33suR4fL+c3Iai|tNL(iZ2xYBaYr1F?mxTa54 zi5lh7cc{o2#_PYm$41-rXSpgF^KHbg^dj5j{pHl7^T<|@h1P;4WyA zQ>;#s<-Hf#yfovp3P;}+w+v~17qy3G`Y)5Bky4DVa5eM0zPfE~RmGlf zJpx=9*qnqRYpb!HV!%TGz)j=r5465wH=#&{3s2+qs3I_Do8agE0s;LmjGQOrFj^#2 z2#`~yv|zMA4ZxTo5SG!dlg1G^{`})E65EH#9+q8}14@Tb=wm@(Q~qODzQk(u3sD_( zhGwj6^UV$?m+l}vcoJUWF3g;4wT`AfA+^k(Y8a-`@d0xl+Xdh#^XkVn^Wm9c-(snw z-OAA665SK%Z?UyO%`G~wceKV0xp=+Bgj0)0LEbQy-@qr1#fr8)3&#h%CVR#39dev; z!}ad$l+k0WhOT?5WznH=dDal$$~Fy+G7kK7RaH*{>YZO_8iRD5<8GpoCxaH@)F(3Z zf7vi4HZ@28ktbw)_JVT}nQLc5JNz3Vr}P5PflTu6zj8p75VkCdfH6JBM}JQN84xSI z8&AH=mn0CPoHBDjbJMqJ-f3G~w{LETGX$T9=fC`z7g4~5H0)GTg8BZLD zAGJ}zILCpd39abTlN2t=k#h*2rI03%H&g1tr}5YsNq5!ewgLf9a6+P@>z@^7H4#1+ zEpnUMPHX~k1lwVBvW7`Y7JUK)m+=B<5aFT&U^`e41XiohlmSYG%o=j^GlpRuzDnqA zj$T9<5{dj#OT$lqI;i1lNMiuJ*}NivB5sIG`BX=uKuv2A%mq;mo$*Z=k)45WlA4`W z5++;vkbNd)oNR6ncAn5+(9;;oxR`o6YC_xLRY5>3K`+q?mM&`GI8B9LgIrP|j9Nh8 zT`~m=V`N0O`XXkpvnV|=k)*hx@JPfv@pxs5L;{M_Oq`>4gX=nufGivfZ#FJc85?gM z$Mah7zB7Jtp2vCSXXWiTAjQ{tHvh9PMgK@0GxRw0v`4Xx3Kq*BBOf&d)huVZdYoS8 zyh)E~C-Qi)yOZ9)^1{bW=b3z-@Zw9xY#ae^!l@vk2u`tnd%uu+H93#p50p^KS3%s! zaX~Pf8^gY_{o}Qr_xD+d*(*AW`$kDQdF!I;FuWRlJLtf7PE zpeGTUfOR6~x=YLK2-;l9uqezPflL{8W!AnOF{~WCkn1c~pCX#8iKRU#rUVs$kZZn> z6a~kL#c>p1fdzHYJ*5I<9O8v;z*Z@UBk26RG#Ic9YR;OX_~5??L&+WI183Y)q9U9* zQW+(M&mLH|Vgr0aI6)AYe_V#)_=U_E!a(sI?*Nn}Ko=`g?T)v%=C^AInc2eBIhnE$` zW5X4tM+69>T+Db3d~goo(}^j2uve=Piyta#x(|SG zwLh_%MIS7NiS;_gsitK9OUCl;E5*1S4;;L2E|?wH?Gy~$3hRog8>{~*$R5N5)um?4 z4n#KgW^?90C7oBIcuj`4!e*dqT`6uTUI!1fS6*1abLT6X7v_$44!4K~rX~^m6JO*y z-aitNbEI+o+NYdFfPX_~s|dxuB>yA>ju}XjzZ60rG(k-jg5}Ym=KGR>gmwxC5zwjbOywx>h4jLPHDfI)oX~m?!j#klUZ2Vj1ue{P3 zE746fPo|>UNimg1!4!`Bf8lx2m|qmU5=?CYtcgx$4-*T$M@SK@h6*JGYB`nn?6O` z!$EQUkYzK3C9Ps%?dQ|k1Rl~L3E=HQ2!lS~WfPtA8A-T-=(H`)H#yU+`c5~AzDH|a#`<{U;~gdJ6eciHT!;-3J!}({7_Msq z9y4zt6^$3w2;bfFkah zVAYvGKPFVYR;I7r!WSSzc3*_cL9)5%3V%Yts)QTwb!11(sI=gF$Q3e(eEHddCbzt6 zyRFnji{WAQB_3&e($TVZxO6xzxo{xr^LtjC$^L@UJ#+|>8>O#%gK^|fa);Ex`is6f z<-7#b8+D}NB&2yZrw(iAGz!R_=3+q+>eLR=Ra+|fZuoM_wYPh{_qbP)EEvL0rh1Cb zc6Fz-MoIt=1Jopecf=I8`V{dfm7jDXF&!WYRv#k1!AdnrLKMU6V(zw&UTERhs^t+M z`d1h;fxP|aV(gA3zYVfAK~%?fb*4gsKG+S>@x20iA#tgOcHc=?++%iXzWS8j5o@>Y zcxQdKnxl|uju(l^z~XtG_u|acpu93cn>;XB^^1Hb!S#B40+N7~nlPgQJi-*c%ojB@ z@nV^=00U0m;Am~C5NP)V=@O>aIJztK=#2i!u>^sR-7JonzTGEyHG5#rDC2>2JaIu1 z=3-wT$cV;ejUY<45u(B;*8LqoAVQFXU&^A&FOL-`n(`RL@1n z$6;Kg8}_77A}V3NRn<9s($Pz9K*(pGZ+nsYzCn?(77O+)~Y<_9m#OocYlJkr8oa& z^dy4bCSDfB%rENiv|0Oqt_d0mzT?C)Mmvh^(YW}4x=h=`9>GNu6(k(42(DFZV#mWZ@oIoZEYuLlWymeq{Bnj zQS(0zS-+n+i6FnXPgiZmgRxDUj}8WqUmD{ZrJDnJDtzG#(qu#MSj0a3iGF zHTnRa0s|mDg{=4x5yMhkd!k}uU{wz|C@wsgBP4X!RliK$C3pmxA?ktc!IrsS0h-)g z;(~IKj*j}Wq8(dp1%)@|%EH8Lltto_Z33U!cD<*5^+yCGtEf-C(x5H09Ki9Ou0G22 zOKO(!(CoAHb8k{Nnr1;uzM+}2ftKDV*mHDbXg1hPxtctlE(B9s{hJj}DD2=D^&7-! zR(R8!*&wEBa=a<*s#XI94z%Sxiy01rc}0_hXJOg$STYonM_p?D^l8?r{e-4RjX^O) zBNQQ`Q?1s8(ljeyot9-imbI;lCw|=9XyYdgFGYAuV)22Ap3QPp2nmQKo3~VZAPT_W zpW;PPa;o&l^cgrA^vyWpm#dL#(88PcFIbBdXz<_py&H-;&j-CJ!hg#m5UQ{C;~E?l z1{*5;fDhKemcfIIavINp#k4?LMu_SGHQQX)A7%MM4Qe$$FE8Y4lBo$+c)hv3u)rW; zd?|dXMB^p6aFb2$f1p&HB$vlfOO~?5y3P za(~e{S$%S&ZygVa1(0f@f(WxWE@=||d6)djdaz!d$kks$pZ9GXf!+y3S>3eolotBLsfYPiU5-1wg4V%bvVD)oevW;`xpZ$ zz1vfH{-LD6KA(p0YrPn|mT!EpIi?p3!SM!B7MN=|HWJ5${vA`A(7LaW_L?h>{6+|# zwT{SFI)#Tz_3zh{-95|S8SijL%fo^oW)o?L8h`Su8ss;W+ z$_ISvNy7E0Yu-6xXEfbonu%x}4rz=M`gWO|7}YIrbe(22tzbF#BKK!TeW71m`h;0| zt-ci%^NT0@69miSi(7+21p9%PCpW=dE0Bl4Btx(Yf;Q|W>lnX$%;HZ9_|1tW^eh)E z;^&AjiOT`k?bF_P^hvv8;W>%yjVl$V4$k1jX9 z^C1~bDGVe!6L<<%lhbfI6*w0&f$ZR`oVE*6B^*Wrl0_ihC;RzswaxDMxca^!zPEv` z%}V`thCg7Qz$y~Y{3 zH<#E;@MxK|x^77S?CZq4`t@h7cxi(LrMu666>$Ri2!kK<-S8?VExmnOoelU6a*xet z0gi!^ZPv&D{0Lp0;mwfVXCf?7*ADTXRx_@JY}N3-EmWGs+%We0#z9C)Cq`?w@oi#hR;ui~(F z4DWYT7c!(>TPZy;{N)=FQl0Aymfa@N3aP<7(R1GJf4NGKo-?XD&wQIgZiN_RCZ27_ zTeO>3a^5}iN`!q8?^RODz_LjGd}e7PBcgqw_Fjm4#L>8e)HZ@9?1h6Bku_DE+84U{ zQ}Z^c&=u7cT_=!hn&H-$+8Lf-R-YZGLFDQN=m+@{f(subVgpeF-R%M?;xeMq2wY>mD(^Xnv{!PL(K)b}jb=ZDCvl*(_EBfS8Ps^0Q(4TT;laz@R zu}!m2@4?o%TG;l3f|BuBBz{AGgUZ9d@vw|E+Be|22t{djxq6u;MREbDF%4YteCk4l z0<-FkJmr=6W=&Eo$~JPSX7k<$_Cy@E@$i@*t?Z=4HxxhMeh%AcI{pqPoTO15D~+&# zFD$eBP8He5O|+hLH<(ad^uohUEcw5DNcuj1C13}U{0_{Cz!$DSc{~1)XtB$y9Bk~F zN+v@nQN}KahJueOXus&icTa{G?R-IJ8gq#6^pQ^}lA)9NHdS3asTjKU7Tq=;lV>ZN ziNcgOijuHyk)iuDq~Q5>mdjqb3vhQbO!vu?;EiB{c|~fp%Xn{qkWR&Ull$jKhLulg zW=7LD*h|dNf4$55J3gx=3D5VW_WF5mCS%w8(7Ow6HXfYrq_fMV?Oi7ECfGK!KQVnK*_V3q zh)&2NdUmdgtOou+L3T$`ea^~XL?`Z&Y9<)+GF*_w&$Gsb@lJ(SkeegW6Q@3`m2MR+ z&*;6aRue=uHknvYf|yhe^!2|Jw{C---+IRAfVrm_-6tw3oB}U$16GKw)wMZG%K(z1 zl!Jk1?oPoqNE-o+U zl{<)Uj1l@j|KZ@Ax2H@-_V!U$#Z-{r_yw`6LB0?I&N@eWK!~mwPuulh7H>Otv_cBN z!F>#-IhP!QU=MLW?GAecp<@U1)%%5pj+uvwtNmX=?~p_A7#*`o7^{t5CMh%Zexu0K zTP#Xp)2C3$FTKO)78$EObO6Vd$}GE&!l`PYVYdGR4bOpg$+b2Yeo9eiHTVZtW?@ea znuY#^EIgzlvl&*~)%mM?SAqWcq14VGH%hlOlqKo9OVCbRqLa3)^Csr^kepM`uprHU z15f;aSU$k)2Rh>W`=OuAiTh+MGoxi&ZJWwkx`!RpS9(ndJzf5%h|yEL)adXo*N#dN z^M5sQD&}G8P)N^Hvwy7*d%3N*>YHC-N`i!nMFN$@?)^8 zHf4|Tqy2@Fo~K1gyG>~&Sq~XCcVNf#7Hk3!t1PqhnFhCpbRq37TNJnd;9$DY8iaKk zMjpWRGgEC=w^&9%1Dl(Rg3du@NsU{IU0|V%9f6+^j}qe|b^#JQ*w(YUwJ75mdL4HR z!II1qD`q5B&88kD*|wl)XiO@4%&@75c*1xQp!xUTTO;eLxyHbS8V@P}QwI$#k{`NOp0V^pG z4UB~g`w5LQ1BxJ;q3HP71asDov1}96FaEqrTxRVXl;rrEFW*D#Nn1KU)tlA}*Ne^z z05v=+?){k18oOop!V20=fv3Lfcyq0PKvOk0u$qh!H1#u z;YodU<6(vZ1o%F!8bO328*jcnflVee*ZuQYI-@}j{4ypAb8hTNm41Ik)CiW)FKDz{L~`?u98_85W!LyuBs%}*OvBG7?ZM|6yUtz9ztbPk*@rChGhey-{B#{|L$A5?Mltv;=eDa9DV(JsUz^|z%OG%ABAu0f* zD(`zC7!G*9>|Dp7!F~kC_3e1oU$4^Maf$^*Yc{&O5*Z7#h_VpuGn<(9k-@?)I#qW3 z;1~M4ULK2TDTm=iNbkSYM8BOQf^*<&RNc61&x^QjL8?m|68CXm0S7ONhkh5XPtGV2 z#EVElUip9j?MW3!`_1diRTCd}NRZuqEs+MulMl$};$0_G?&nvG(xMMWLyLdv-7wuf zV+)_~ShvVSPWE4#D_Oo;@OLCVEFBOL2^5Ch047O~I-n&TgAY>h+@5gCs7eZjB1rk| z-COye_1l7`zU%)&L$8fjwfxg+wlPvf5yMywqF}kEI!;?kZgUzfrRGN|wJ(lR&H_76 z6RxYz6V`r*=KV=u$ji9+(83Jd_xtW=!QnlFNzB3y=^;`H6Quwxf0%;3`7Af-dwy|S zcTrvu-7T7b~I!3E_@I#~mMD+I&$L3w>s51AX*~>x^f!yVO_yZZ+9*p^gb1TNo_+;${db zA28;%2~NjlDzQUPET)D^U6GVN$G>L&;vs>+Rf+rXZ2-CxtZWnna2OnA4 z%rn13dDMItXT1x^xG5xj)rO5}IMiwQOsGXT``j6yP^z-pE$;k1yZX=@a*|)fdhsKl zuG;F$5^ojmkC`-1rxSU|lFOX5u7gz37#)_}WZy{T&(;6W08him>b~~S-8DmZ#|#b9 zElLVVcS$25-8C|T7<8io($YP^FodK^Ni!1C-NHA#zxDlp*ShP*Ip^6=>|M3d(iE02 zY+ZFsEcdY{C%4U{>fL-W)&0VXA|^*nfBZv_c&CQD6!gJ0r_% zCX?m>9%V7Gnz@&OhmcQ^!dQinCOpFAj>*iHEo!_Y%3f=38Cj?q6(q>~X;^H_xRvGk zSqpw281jL3?ZCc;1^$=t^5zHqs1P-#fA2~NPWL1%=)wXnK-)v59lUOTu&!tTh_|ip zq3tno@$lv7$bXwqSHb7+$*{ugh>xVCk}&?4 zO7*5S6@0L7lpC9qtXQ%6$7gos&~>=zE`ro%%Wi|GxTeO~Gm^xQukLNF2Be+1gT(#A zl-(zeq(yl2gs+k+F>9Xs;d(dv)x%0VkA7vLC*R>#JLQ|NAitulaN2M!a_i3KljpL> zoyN$jet+uSr$~QtOTe~!CGtK_v2*s;_W)ZQvT?K{VSLCHTLZ|zVu0K&UyUDcIo1%o z$#H)}*v011Om&anA^zv8iUQb5>8dpu4M^dMGLcaTVN3j% zw}bxXQrfrWpaSr$Yf9wRp5DBGiy!eoj430DWH=^ya>-N?(%mCG`fFRSfgABatf|oq zNH@bo?u&)il_+wPK>o`(2194il5#zx1nHL`y%N7)h{GFm5qkS`ZHROHFUk!%9p6Vn zCT6c>)50aRwm^)yAr1=P!6{y7-Y0?FYF&a=ubaTY_E)He;OP`C^>vgLX89}W*xpH2 zMqohD7vNKaL9%iV$NC0D#NKtuNGMXfC~`X9@1$~E1`400GLt$1hVz~xv$xV9t`pA^ z^5S+l$Pb8GITxK_D}SrT*nB4n(t(u}@_z-d_uH2=4#L$u`*0NOYBPPz$p6_gkh?>e zzl(9D)Hqe3Y5dPtd_Os6?YO~KDSwl);)2a^KV|lt!m*r*wHd`Hi-tob1yiZ0Ei=2D zDL0I0%4&g-ElT3yx5}Qk_Zd^wPk{3j-t0@_10tQ5pXs{WPJ;vY+n^>-GNCR_2us^0 zSnDM)$ZPeL(UcC#^nyI3@;tL{IoV2jNphBJe7+=QF|vO4dU>d;BQ$m+r)6?QLrj6w zm#K)hpoiK99>fn?{d==to3cF+;T!wqSCTp$FY1CqDQN}~ZX${b2(}gt8tQuz5YTZv z!_utqpI4Fb2T)J>QrNnTSZy^+^>UF5W+f#YO3*PY$xLnZb#&f5GSD10lJY|L`02V~Sa6x6AyF z{+sj{P8=Hu+B39#OYB_mg+TJBCbkBUk&>~ucW+Rr|k?Z;9DxlV#(oyqJ}9|H6p>W8*aM7~DEZ z{{DGdAf7+4LcfC~Lm5$K3uhO^)Uq%1jxlhsfBi~4r!)=lIWq?7sfdkDM$y}*>9A5Q zrWsSlMoql4H+xdSkv%;EJjF1b2>yn%{?4IgrCdkjg;6wjVSgz7Xs>#)4!9rFsDz?K zf;P8T9gT%70Dg=W6Z3k~cc&Ou&Zm46lQ-0GGWp3kS@PuU*dW}I$#wbIG02u-n>G$^ zJ^Q6q&M)(4#WH8&k6d+&`YGsX?bF)SR|8ReQEcBJ7td4Y3zr2J#`dMqnXa0|h}Z}} ze>3QkonE*5Cq*0BXn^om{+sN-PXw#YE8Q@gFx@$s%?{-hN5`*(b*n5(&KuwZIL%o{ zIoMczq|gCkNm3|DsT=9PUULbl8~s6g{vWQ7FYl@nL@&uNmb2xNIJ^e5Q3aVLtsTmf zpGF+10DyJph*(;d)IQusX?lQ5ag=L+bYWCkGA_3Z#@(+n02^41DWy10rZ2Cs=x-bi zdKN8v865V35P(VGvU*`CeIV_*Q!`b|PvpQWg~&n= zC|0(^9e@v*CNw%0-gB_vg*See{5_z0=lf10Z@eC80rwWS=d_+=07a=cSkHIA`$sl? zKg8%jk1`$eNwfvN1eA_=I(VQBM{)i0?SkaDZd_HPmV7AM_^8uVKn7BF)*8kpCuZ*&LUdP}oxPeg6vX3QdnqD*bX~>6=ZS3c-eVhFpa@wSx#_6ulUh5wIzT6dK^eLV~&f*$2ZtvCHiB(^SmOw&cei!aKc-rnpWNKl- z0mXPFbil!|{OaMH*IQJ?(wZz2Lcqa}ucX($#GHMn`PET>OaAURUT6B$7Zrl-|=YlAs?wGu@qtrl;pEFMEau8d-I&bfDweM+C%) zo5mnLz&IsqC?YBV{F+w2+gjXIZd1&ameX1KK=rNpM?9cfN&ix6&>ea2HFYSD>a4@Y zjmKIZ7MS%?;s#>`og|Z1&=jFL*Z>}Uwgn_d;tf6z%OOoDacLM+YnL)-8aW4x;EtOS zXDtXExyLds&3f{6oAgF+?-||5Jkdz?>v?2O{@F2eX}2o{<60z6W^!-p zQb9~h5%XtB=Th!Nlns^zxM^*U9d*W+FZHbv@!+P{5%<>ZuSB#EkIOOElZ!=3s!?fR zt=_}aI@9VRA?NS_%ywUo<`429)>Qtaxet^jswtp>?3(141&W)OwwqJb>pnPJ3FhZR6o7^@@jX3hs|jhrGryI3G%as1@0u2WY`0fP zTpT6iY-uue@{Te@(9K>^s}xid8ia%;hPDOmKOGC!D@&l7wrms^=RkvYNScXABc{+xCWHm>;tg%fy?>QhK5T!kaEJ4bu*C$~ zobaqG>x`s&w(!C%>J{@j@*R=Hr^u@ic~|g3G}rmxA?7F5KWjd^|H`Kgrkrq%PSru) z*IUvE+0@K4-s1I40q+aryyb#&Jacw^^In^H8m{g|WGB29A1)I}a>fiQ(#@adZ*dV= zy>0F(>{mrELTI-)yQ9@F%5Qq~(h97PxGFVIsivXr(Gfj`Ao)5Ge|VwZgai7_CG!s* zXGH>1su5zDw7^QH;`$Zf>~f;J*IK=EC3P6(tO$y2GkE3h^Z9o9ZjDH#@yUk|*@p6? z#{d2ZQA#9nTbi;Av(m=!#lhab%j7`?Rj$%7#@s@%#YaHq~K$!?9DsD(Q~@@G%vb#=*^lK+$zALo`D7 zu#8cG+wz~7|2lcA!%nr%*LsRCIgp>9N8UQfg01Y+<8xc)2=hD5uz`;1#aO6XSpMZ4 z)0=}(60ig&*F5NEiEQAB&|G$f!8>W!TGiF?aP``F%z0Y5(Uk3M{YYkMt)xNT_)nr;mEH8Z0chSgpGDi}=6(BALvv%gry3Pm9Tjj6GnwpG6-< zzM9I8_?NDH9)>qK&ct@RDL9B}B;w20-}vmRdvKgi@6+s-3@$D8b$pD(+dwPeGv)5< z^b(&W!szRWFLes7*B-}CJ%&cMkbg^mNNE?MYoWa;l<~@0$Cb!`Ff)d;J(Owhaay3^ zZ;GG3Bb-3od7TD}!l^M zG?HEMKH%dd0WhN?sKN<-;uT^epbBDbfi)hF4lu)jsc z&YO;DY9Jr|;-!D7`(c<{YUex$s0X=1M=?gzd)QTann9CK1LZBvc^G|pkNr7hAtCsH zWCf~ls%W-PgwpIPLf6_{*Dt|p)kNwQCPRC7;F*NU_cwlp6-PdFs(Bir(%?HVED^I^X?uqQhBb(*!Kwuy|3a}FcJ^Zdil4hnUJ zqv+Y+_FyyyZG)fo92#-h2?NotFf(`9(;%6SFwn$XruS@?<&x?xC_t|6erwU6zB(ka zTro9-H~~Ug^N1aW!2w~z5!1u%=e46Q2QZ43VF};LP1ju^xa3mUqO-_pT%$RF>W(WN zV4_W#0AM3_QaX8wGfaz^UaMD~!_ajkxm``tImO(ilq`wO3@5?17_Wb$V`Pw8yvv~G z5q+r=aXI0VEoy~?me_{FxcLS=Jj#81s)Vyt80RJD^b=OkAEf&Fxz1Ej;$wFsP==1( zX^obDMCbpEtY31FKKR1HT@8*Lzq!QO<(;w)KaH0c);WG;T zmz|*Jn$KKV4k-`W*9ySaVYbkJZtoIvckK1WDUsuAQ}C&y>xD}?^rSzG2;j1=vp5{m#WrA4Yy&6FY(%3Njlhzi zKn!nuYoEhU!RKGN&gCy9PL`JcPi-di+SVh(GgkanZN71 zA^WQF)H`i1u?lQ;ldwl#KdOV=h%;mO`)} z!VdgwaC`ovkia8Yr|0Ts&~g$F5wziJ?cmpy!R_TC>0PG8?u*BysWp#lOlzt{nd>Mc zol?Gog{dsvd|qH{jihFbEWbrFd-+Uov}x_#Ec7THp&R=^we-EJneunJO<-)!Zoz4p zhOr^UcYFQbfts%W6gsHQM73-d7&DJ`Jh?#S(UEI0571-xiZXn@LEA zCyPF$7^bBpvxRy0%L?^fD!&8ob?KSST?CBdT5YU46WKy7@RcU91l=kU- zc8N)G)}hsVqxcxKX-XO2ctjk=4<`h199as43YDM%L_J;xyCcWo`>(_8JH#UV%;p4H zZ-Nynhy93F)SsV9B@Vz&w#@PS1Ve+W)V$3t62kNyh~49Gn3rOGKa;IMFEBHx!npZr z-vA1O7Ue9SIk@|NkQ&;t3*2vVRCaz8D}nKJ$*%9&^IaTZg1o2=csKeA$N zE>#;tN7S`7rHOhQ`X!Ik9R;ROf?@YmEoy7+OD8<7nlCZ?8(|GfR^>{a+6}a@HY0KA z$;w*iNg#%Q0HI2P zgK~E@9wA6NshQYhS(*t^!%8uUVOh(pr6kgCqlU1n(q5ymT6zt{jRW4XSgel|7cIB* zV3OfMLMS>3vuJs6)2w2*bI^B)S#df3#f zjBIu3SJY`(?!B!>ibGceDXa5W|0y7cC;O^*)`s&gjDa zif)ffG(CbUW~!0zK1ku3felZ`lDy5Ovy1OigP)ek{rG>K9#g7en66yT*^v1M>V*qJ zl&PEPKT6)9r<4#sLG1^A=ky4lgu|Oi)>3?ZB{r?yNN?bkqL(V#l0@I&(fDqfR^dtIpBFeku$~1r-in z8*UHUWc5C;vNr536*~UqeVl8GMN+hNx*+yW+^N<`?Tmw3gVJ1QvH+?6pPUOquy$yw33%UW%>?oML%y-$nPKQRk{tI2|RThf^kk$Z2EmXpJ&O6rJk9vn?j*|ekl#bw!0?^CI?|83T zj;;A&V|9TIVZY)YABk9AT@mK8%fVsq)cEZ-4kxD|aYc-#a@T=x%Nn(xMRHK2tiw7f@xY|)vY!us=Rpbqr2vNyUpML? zZ*20dDRNpCfP<>rm4vu#ZN~WX=Y7P#1U%Yn1_ze~o3u;Js~=CI>4?+B%P2$@u$eU? zwl*I^*ujqioyhI=r*`|bGvzK!Zph9w-a}X1_Fc)B%i4k9KM!9TAjR4QqG~uf8afuaJqyNbbVH5HU{@sYp*T~}gj#<*D=Rv|6 zi#JKX6R2oq28`<VtU${NIF5s4vr;eT?i`pUfR*tZdu^0Ltn1D9STIjR^GYu%9$BonJm?H(j? zf&WLAt`Yt3^F3?%s=v}l$%3n(78PW1%JgQ~l>@L9N>MXhHz%iOkyc>IyJ{xD@;q7O zNW?LWq>L^s5%d0U&%DR{-`Ts%3Gv>Geq%UIoH=itQlcl&f_(m4t@!hm&C*cCNV}?R zccyNl1*amJe_-Tt&gQ{}{J7q6t6jC90b0rJD*xDo_?fP;Y!j^WDvZ_9bS6*pqhg7+ zg9=l<#FF5I0oqHACMM0wP%-Ryy0qKj7v?&zQoaiU=rL=1T8L2^Dq!yoc@UtL%r!46ai9%vih6ZGxFHwFh%9~tC&T-1Dg+){L< zO(Bnhb9)adBCyq`y(xjI^rhGP&I0M}ca&#yp|4ZzWQ^?!E`gQLm@dr-MzhA!Y~Mar zjVsI)1iN_X>v9d&GroJ@c`ecwzlc?beybbKxH`9Y|DNpOy_e4? zQWu#1`yQxBEoTN?elb^E55vEkihZ&h z`d+@;(jj1md#csWi%aQu21QqD(|6NY)B3`6mV#ZG)&6492IB?WH8;@nY*YxfoGzi= zVU5h?#}yKgg}sfwY7+@hc8Q*R(2P}ZHSBpm9$8OlRUIp=ZM%yl*4)x*K8c=zXpUFg zp%*o5eH9ehJKH5XFd15`n~~ti8!}Esq;Nn?`ED4<9_Ny9GVkMMK{5kG@`FiFV3$YW z6t|i{>A+Ky#R7VVj-LwWL-FlQ$6w*nxgYyLkK-%#TWbQ#)~4>JUAD5pf6(+t$wMU= zNDLVVWwZhuJANVB9XsY%49R|e_hEo|6s7v%_n{tll#CV1R6Che6aYTYrb@HUZrT<| zopYQI9|gYqR@$D5HMI#9urZo^1)+f$6Dor6Dq+h3b9=kjYMtdAzKp6#6oQ!iyjc8h z_~8mvINR3#QLi6l&4yZ~{LjvUG?vMk9IE2@dMy9%1)x25ihf<-9Y>DYrfTR$ zIq-wF$NiGaT&QeUa(b1?5Alyr1f2{%&fLoO%3#42VuhAwU(e?LPdw?GmTkTMPoBSA z9yKNHfSR7c4MSbO4Fr7g=T@T1dN^Av)-R%KC<@KUvMyg;h%`ReyYPFHqly-)k5=sO zHcam`?rme8VM&_Av@2%U@V)cnzsxg^Zv7zv*+<=r-LqX1a}GlR8x8iI!gvw z%fq4R+%|RIM_y3lIKPhWr<8Z%7drX!I!1c3^l#aE*F_+xPD&!COckauatQs7_Rq|g z2-7NunT!-n``XLUVA(u}355RkRwa|&p~qONo_~SzARW*q*>6tv`)r6M11f4#b8?c6 zb~POMEnv{brMG>ZfX^odpeLG7NbgXjZjc#`% zK!?a*rr!{yPo<+xrE}<^CIarzZF5$R?~SrjgWmSq)<~i03cmAoiR1@pM_=(!#VquC zVy7Yw060A;?k=hB6qbBFW++-n&fh_se~4$-2 zgLZB1$hQ^<)1xAkpNCA#n7VMt`9h>jEw!@C*uW~pDT~syghm7W`#K(9bIPQ}stqRS zWEKGNhS2iQ;!%WA<@vJ<+#8?~+NT+lUd1>Lua#plt3+gmGm~Jalx*Z7&o`R^af|$+aC2Mo@d>Cf{K2+i5!+C%VNdICWl#Yfge_F*F>q^*c%@(G9%507x+n zN@hRUYj9{7F#GkumEuSobp+ld(PM&(BqS4nn$awImG;pc)B|hvN_RfbJF1iX@FP)w zAn_U?I%xt7S)Z>C(1}<|j34@#Bd~XHj@Lk_G6ahmUn3X7ZX@YIP6C)SB^0G3x;fYy zn1BB>DMlF^X0XY}2Vgfultm}ACcI;X-e^vZd-KQgF`8H>KV6eihDfqSmkHS@N;qwN z_K}a}Hk~@48I?A0^3(08AvX6RHp6LC65svMoF|X0*ginU&?^zk(0SzmwTX@t#`X8K z)(?;jpU`_y_%o`REZ^iF&zMw-^Bo3CJqC}bgmURQN5a;N^#)=eUzP+{bI^O>b2t8r zp(Dvp4?@ly*^{=91PDHuqRM^4r?;>cTJ`t77Jfy^=AaxxT90mj>kzuR>dw${+Z{e|FVry)J?(7;bt<(|m#FxV+G4=>jZa z3{pEeyV^;p#D!2@_kc&`QpvS zH1%cSO02V`&?PGye!l@tVd|_0@(IYu9_{UlO?8)K6W@|mA@9a&qo{F8^+Tp#f0#MG zvaR+rrU3htP&J33WbvALFWohwx`4v^dc+l6n3+0qeryT$;ZE=A6BDjfV-+#cdFK|& z$lztBY2R=2=6AK(M&H}5F2_Qf*DhFAL%E5P7}zT>x(IF!*D}U}-eY>_AARv2+P5Ci zq#AhHvsu!;nkahL1b*|Tm5zUA?iU(De~LX%`*0rPkR4MHF00WFd%^u1=coO@>P6W3 z_R4ITfr{22wn8ivtB?NLTcZ36QXbNwNesrol)loR?uQTHIQCU*+^Z~+f*VVX^>;W^ z=}}gc^Hx#fzk-hx&4%|(zJGVwzQ22r$@>9m-~pQB1wqt5=MjE9uLRclKDfz>1k96i zKCe#I{s!yGuFsidDsG}Q`{3rKPZEf65p^=QN^V>vU&^6>l7DucyV8xJn0e1AAl%@v zGK4<2Jf%?g?U8l=Zibk@#}}?MoZ?U|W84Y9a8Zw7R0#eU3r)dc`T7fcel@9f6_s%2 zybLirM0}u39NVz0xn7XJ{-p5u@Z&kKBPs~Vpm%Y8IPxI9A2ns5D+Bw^FT%R;{ywFv_UKTE6t_XTnnoto>4>MVmMXIOS&%^Ed0LT3Uf=`7;Z<&l2(A}tPx4wChyy-#;AVt-g+@1%hdME8!K3!3Ii<>YM9dc^kj{O4@huKNe29x5%$m@upf+Lg4WwHL{eVfW0FzF*<`J zFk}_tj0}cpXc*?NXJ&@eB9BTF~F$2pq!3res>eeWBh&Q zul&ZPRMNPE+`+T1qrCaOp&{m(ztdUR=x7KU=FTKu!4Og;USM>TJLh8AYdkMyZ@FH1 z=J73!PZi9Yq%`bAP5zzD+$ZF!-5o{CG=gUg8{0wD{{naPm3=8fliAWuPwzbFWuDn$ zr!vdSHG6(3V8K7Tlt!Lxzwd<~7d z&kpJeU*0?4d5>wD3rt#7!=R;71upTy*Eqj9>l#-`mLCQx>Zq#I=aos6;7qO*O(XZa zO=5p%)=UupvKMEg|0pjEXV{K1sjmY}mhf_ooZLj)6%qj(0QQ!zNNls+U(d2dW}$T=b#P@y(weOl!m`%>4*<1($)p2oCgw9?}-Y z5M~j?x8(7~on@6wJ+7C4F=K)o#tWab;gya<6=bf-7i0E!o74)#WFH9HPu?wR%U9D5 z-`qYfEahZonZz<UEl-~ILTjMM^&X(Tb2Y)`MjrNVRHmqYF@%T`!DMd?`4A6(Sj#k@>e^JF;i*f z`@?k@4peXUk!7bz3#*+=e#L_}lx+N+#pHd(`bkVXftl`2RQF@p!BX?=Qs$pkrswEL zhun<(&S|r#m)7rK8?P@T50h1jjdP4c0H(=w`%se+$>UmA3l>W&CqcK+c+`&Q)oixBwE|%KV=fx5+vBup zsK0XVqF0pU`E3{vF=H&T47L;_|5^N^<}WYX1e=DrL)WWtLBcaiq(5-du6CwR0oDl( z`reoF+x)!X*DG(=OHUE*rvg{D^vq;1eSl3v|G(ePG%LMo{X+`&?_u$n&s<*xF9X~$bBLh0Pk zzC{YzgaC4#7)&ZQe&48I`G@V060{_ zF)Z7|HOjwiwThAa4j!37_<uPQ;lQ`IDCmW0*?C(~JR0vhm^XDMy%NDHnlDg|-?) z$%yD@IAIi0dY#ea1SVdu%U3Uvxelq>FFA(r33Yfkww_0+V)%o!^n15(z>qDPY;)oe zupx1(N-Uwt3)iCwZv~I&%f74R0esz9{yP~V2r3|81E=%1VeQMj8I2T?yQ64Jk z_C@2WY^5p4`XvntPT7@SdXkWao++}<&^YmVfxCs|=y5Oo0ftz<_-tlx+ks${)qfDH z>Dzc3-78?&>)M24(W7=ZWg*2eotjqUgC$SPJ_|NZIi^R3f%XA!|8?#w#})gJ)o%S1 zI{h~gl&XC@hStpz(X_{j!7KT%W+p3?n+{3ee6tKlO{|qFS2H2JNA4>+P^rA5FQD#P zils0fjD4PxhlMIO5*mgbf(B8sJJDuGdfdd{=3mlG|F58y0g!pI#?dHS>iOH(+a`-O zZS4GP9di=0sLGz^R@hp_6;t^0hAb!Ol}GXZn}8A8-rs*R&yJU@C2a=n8voO1duPb+ z1$rzFBTE}^uh49_)j+5RE#n5`^T&eJg0JneGAIG!T!=A9j}y{_%j2*7h=ogN=f!^> z(@HS9SbuV;H+HF8p1_hjxHI~3M@^jh&SKBy)OdB-xCe@2gX)>tEg-g@ zGUX9P4Bv?{skEaB$|qJMr3e)lLB@;7J4${wRkAVLy^}c&Mn)`$@75-@lA!Jm41BwDDTqq%j(^F|?JcC30Z# zndqq{I~WQDFA@C$`SYSXd8DMi_)J;$V-UeS_Vi!e3PPbcaR#P9)d|`C^km{0sp1hE zd4KTr$mGtmYd5v=W(C!m)np%W!KxZZzOolC3HAC}DN zwiVVLcKGvleDn9_U5wG`GLQQ2$1g657hx|D3b-oxrWR9syP{4pRcFs=e&kqvs$1Lq-rex+f3|cn zuvse13CGv%9A3HK-d|m|9z3ZbQl?UB!^6=7kX@PIX(}|!`Ytv;uJTH{V3L4YbnwsG zBTb;AT`6>aEJ#yhRbQGJMTmmZdM-M$*4V*f_XMM90UaOd{JA;O%UM6qZ^-yqrLg;g z6K9gxmN^4yP3Dprh6A^&URzId5qAcP+dTPkF6;Ec7^3Ze^PNh7Nz*#tiA ze=Aq=m~s_J5n}NEhf4`8kQn@dg+bTa#=N98p8dHrYSG%#ZjBIjLB35lxA~&Ltjxl; zgKxY>htY>XTV8AwbGDzik9ULIjR?g?jult?yBTs$aGvF&D6GWysjme~E#wl7w>onZGE*RV9Gg46Tj{0CD$;vNpmI0|I>59I`GRO% z?QIz#BfrH=B*z2Git@(yu)#=0NYMz7$3GX%<(j<YTC7xuOm z`Hp?*UELIP^reSMZ~8MF>p!xP@ZdZzt<~k6BZAmB%y(NoT<2(xW9ILVIe?Cl`&G!I zGqPKGAub4aATr3dt}2*k{wwB5_!O)Z$0pRat~2o4Jle>0rlTWgkGx?DyPbdH@%<5K zy!F#ML&Gn`?}qfIuzg=&*Z(y4N6^SCG=-vv-j*zB!e5kpq0zn-h^@iA(FsF08V$R* zuV%_6GjCOX9x{F~)RME}{@Vi?E+G+i@9*q^ew6DC=WXM{DMR|)QUwWf#;3~SE0}Or z6@GdG@&q5R{TER9Yh0B#!bIO$mg&T-=N1~DgUL6G7M+Rhi4m2V5sd$Mf9-;CAFOsH zA&jS~ukWru>}NgO$`eezdT_yOm7jsRj>I$6s-WCr^e9=SWI7TG%pcm=5o%g$RXx;D z6Bur9mwUgf8dWTNv1qL-3s`G5Lmm!50*Z-%Zy_cEk{zgzHjHP`M;MN)^ET5!?HA~mK$vw(`nXz{XJ-uBC*|yK zcdG4gv1PNHUNTQzquMOfW~n`+Phv$x)iz$9k2PfCWjp=2hZn{y$AxM63E7Jt@mUJ6 z6AmLsp?gzQeo!e|prsoU6TwBetho1aMl}`Yg$WD%3OY;D zWn_px7_V7PqY55F%XvdnhZG5gdrRH46#MvcJb;T`-H_Y(upV>-#GJGy}(-3 z6jKmHA7fukep_ijN(qz`6Z46d`pxu|Zlu=s>vv?JnpTtYP_luTHZ37GPO#f3|4D)t z^+BEf(>b0xJd`Jm_WgtO)ifSTTW ztN9cw064SgNl5b5D*5EIn!F_UjqF-dj#l0IW00AT5WM_@Z zv9$iLc4D%eqq8w1Ujttr)L_f2(I!8My^k6X+O zQ!exOhfGrH#mGY1Nn27)oRJBb*3(}C)HTV5t^lwrGL4mzXah&B6^<43@9>5546u~mz#bs?B^gqN3e8amiizp`{Aba?6S5*-I^XXBnr z3x67mrXHY*NX0?-;LTNYD`FMGoG7x@aO;8FMh%sv7ABdeI8#bvWC2e#UcUul&1H&~ z#lj4DXO$AiZ)r+aNI~73I*zz2RT+O60f3UnZHuW!akdat zlAk){>u&t^i8hUCadV=}@t1uxEJWu#Q4?S(bmU?|8IVZ~yfvzwguS_l%+5G|TW&e< z1MRWprD+ABNU6}w9Gm!sBAS_FNR_*MF^^tiBLQA7rubVISvKh9UJYKl!~uq_D0fDV z25;%7^PY_=|Cg@M4j2#lM~B1u^X9k_S@$)+K*oVBUq-fRx;quwnWHjcDefky7}mmxLZrrvgnWK z*epv1I>C~K>-cB*?7seDW7RnCqVr($qPkO}m>?Dq4SzcetVNYWQ3%g>xD2%@e`({N z3kW{iII7Ykzj2?O`E&6%x}o0VI(pX&q*6LNfWY_X4gD|7=|&t4eyV@GqS_|2?K^?rZVRAX0YV%ceFpeYdRZeZtfBeE-YPNq|M(eZ(L_yaO3hF zP%Sv>#{jiQY`%hXy(*P{(q9{T*Fg?n`R#d!9!PQAXyEA5Tr5#oS1ii*jse z*jK}L@QXA22;4VSs&4VuN;lB$+9C*7)3ZjZkHCeUVV&rp2M$O_DYd8h7*fH~I$%w| zGi!*HqAMH9V&3Bs3lim~4JpFL!X3Z~CTg67;S_y5{;4JkPijdbrx}AlWV&V$?l0xM zAtI|=@3uZpvX$^~gbdWnAg(s*85#x|?nh|6BUn|nM#%BDY|9ZL89^IbH8 z?6S%@c`p?y`{_gTM$Z{PlmAmAFfNOyitmrAt<3F7MFF!^vT+0QkehJ!FbSGWXc;zc zv=rD{<8~r6e`{}jba?1PTf|*5=$_=#LdHw9MVMkJBx1_G{i?Sh?Ze6ApY-a+5@AaS z7J%lT%iHaCj}y~@kH_a>UhlUP5%z^cE5fWQxA-Un@375P^(OC1hmK#;$#RR5J?CKw z1)strd7gm_eUOY~M7fytY*GU`^>UK{nu#{Pc}Sz7uX3qbwGsNK#hd7h*G=Q zH}$NzgeQJ^_*o@-_DSqwM3iDgv0ewzJoH@kq%_r2QU>d!Ts4st4Co!N%-HcM;`5)A ziFNk1?>dM!rwY+_zmYM7CC7jz)l7(QRXn4T!%I`TH77Ca-XMyjmt7w+UXS;K&Ra%T z5N9g@?U3Iw1pU=9wx5;VyW;XTL%I@ClmQ!M0>CI*djU!rp|Cy9y5El6r5upQAQgn@ zpI-M`qt!E;=rV~%Jw66{1()*PcIN-EJ@r6n5Q%%6#PV70{K-r;g=-arf(c)GsCxJz z&#Q&4WtTVkxh6Uch?v6EeW;L%{AQ(X3b?U(ecba>nvBkznJUchjJ@lT^?kku zgDIy5?v(RWu-=sgy=juU@@Jg-Wd2@-mUo3@zOuLkCmngvE9C;^f*5Z7g5J$eXaDOz zp+OQO_MP2T5bKR zAEa9W`aAasL%Er#adYXDwOru@k2vRG4t^-DCMSm|@5j=G-tmgZUL`ujM5kGkd^k+J zl(B>=DMjyVQ+Hn$e}5!fQro;wKQbv}hiOG;!BY8Iz549mQ;?^I@@$2a{Rk_NEMZe* z%jXY)EPZ@Hz|)`o!b^I1jjw`uncbA zi*#|3=HlX7KXx?j(`OrS2kY3A@@#~=_!fUz0~DWO`xPT#vogQel637uTQdO1RA>6xE3Tg&^yNX(g<%$Jh{ zfrp=y7(T>p-z`QOGLEq+t9Mq~LmL>th>=3y5bFABE$J0wz#2Z1LgaVY z2t~$v+4#%dj=ONJrrY*kn|S4~%)Vr~5F)ANNN~^8ahc!aH&3#of_s+_(pFPf!T{OBvr~Ze!g+gLeWY2-S6h(ap!jGq9I(PW?LTP!K7Qirg&L zkR{<22hGxsoP@J984d1d=MRI=9&7Q=aI;Zo{}_M$smwcWty|pi6Ybj!ALl=OoL}RK z8G9Uy-gXGH5f6W`bCj86-Sfbre+Nl|!xU6JRHLL0331G^gEPV=sbP#GY=A4{Gg*O1gCd;Gs3U%sBx!W;hV}R4LGKAW0mW0Mxo z0jWuhtSO(T$owdZn4S<6&@J;6%=auR!&BEYHW;v!B?Mmh7MVbHjrH=hR8emk*-Bip zru?EQ?31?mtk*#$)>=yooXv2jvN+`?Ub0TeQ4{RSrQiKj@U^`LJ=y>)GN6(Q^IFr@ z1mgs19C1;PJ71ZmofXHFxoI2}2d?qYeg0+Em`veqmXG?0wE@s4zZ72ahzGkII-jZq z{HLbx)1aYm#|I3?>9D@ZBOF|?-|BeYDcYWV#`;!_mKw*x3*()QJ+xUpU)(I8%E@Ui zCswD+q!uekd5>;S5|w(+hB2L)q}C71Cod$P8uef&QzK=PJ@Q$|biUGj@DM%RC+JKo zc}7jXGqk#Y^CQ70@PIE1I98))TQA&A+!MVHS!208u^R{~ zZ+)6A+01NRfqKciZEp5pHq~6utiLvC`N|&3sHYk5U!x_?nU#|6bf{7Fbhon&am6u( zs(qAZ^6FKAcf;)!3d9b*KR@06?M-9YVjnGq917NBzMh*DjSKwuS+3YvD~k6))U8-v zY-;SD*KWq_*Qve_hw_`nSx2^PwD-aZwsDOAu`)LTI%(?nsfX^Kn8u2MqBqmLd0R)E z`F73+V%Lg->#%=m=VK1{1`nU>$DPm_5`)e!Sc1rC%|-`Wh(S#Ff781WZcU)?8RP-Q zhg1!S$rYEzKQ?{(T-40* z;zKWdp`XO7iBPCxx@iDm7jreVsNlnxu5eZ?IKmjD zll6lE!6U@@tdBY$)is>VycyaeBeyi1=&zf(-*@*7Fr7i7UK}{yLLP4B`kJ-+Vt$fb zGZQlJhaGn3qV(*$bYvFKvD^JBM6}h)_UIv|wyp3JSsvui!2ML;Uv>jIfy+K~uSUxS zM1Kn&!)Fz#2@wcxGsid-`Xqjx`q$*FzG3J?P|b_~Os_@eRS&IuevmkkH;Qp!tJ|aW zjdY0W7^-?+kT)O)ybc{Q13dnB_cNpY;G5EB>8< zHGRddJuuUco4_Pz|L}ukkZVS(^QfxblAiPaGlObsO7ic;v!Vkk2EL!BvE_2?3G+VX z^<(ghSn_y#-4_DF?v`IUqB8LFPjP#T&4j(jRHh$a zef|AtkTVT58ZaS_VFn2?zX!^ge09S`hlh?FR`>WXnS1Y!d(J)U+VCTyB63f&;eNB> ztB+b%6JdDJHcYDn}lQm+Ms(1R=Ti~Tmi}K;;Bbt z5(rl_P=t1YVD{$%`)}jHTJ63VQ5tP8+yGM;DFE@Dq${MlHSOQ|g>carvcWH~z}W72 zWyGlR2Gb>{r|>=b3bpLB&%_t(P_!%}9C97csAf79K3@}PQ$0phj-)uBQ;p`pu$~v4 zrk?BkLxj#K(E*K?Ye;gm^3w^P@x$lFe}F4|kn=sGyxE^qJf+iqT@>>~lj=B-iw0}V zqT+Iw`73E=?okv0qJ1*4@ZmV>&wQin1;tew0$#`deZif_bhw|00w+5YC6hv;%m$dTSdORkY2;ErrK$y4z&!&{RLU#qD825U5z@D!4>gBR1_-y!`Gaxmg1ugDY6*M zAQaf^p-(hv81}T`f2C%B*_VxS7gPT0UuG%qDvv_l|E+I{1?XGkh=VtjZ_6x0*+wNT zesLvBpsYE0Se)SF2KlCD62y^XOFG6H#AB6*DWDsW&0(J;-Lc6ZQ83cp{UyAv=8o3g z?^dFTT*`cGw%kZ3s>+P6Ujdrt6QcoU-5cVLAmE>lQ2lFo#xuJjp?%5nY?V*cSA zUeg(9A*T2b>?xE#N*f*-DcA(EV(3DIL#~B4w3$(x{cJ#GSycEJyOy^Pn1kOmg(j{u zZ)EcJek}_E)p*g^lm5!3w|@n_HaOhuQV$w@KN^kbo5y2Uti+dXgdpI z$k{>36rkM6>>dVgn&Y_>qKMphAwoPhxJINH@#D#dY<(e*ogMdpiqGUTQRJh6IB9r+ z{QN4ZTUkiG>n&U~Yf{H72f5qvmA51gofW8laPg*4UVc!{K|cRHychTDd+c+R{qU!% zwB4s;pWjF}3y2nh`unFxK=$Ye#cCEBP&QLGt9x9Xn!TArH*=2_t5KsXjVsPdrwER5 z2BraxAoxi$G=}jR0^|K%`1i|SuihejlFJvtQ=OoG*H=ACjMl}I8A`?GH<~blU?j%6 zVnBCN=&38Ofm)s6e@ z(_EtHR#tm^p%ewAD;RWJWh!N^O0@3;4YDC;%>TCPt`{lDv zg;19{za>#br2J2cMan@$jj#%8wjmJS37aICwEFy`F@n&H z)a->&F?nt^|AV;LMl6EwC>s?1tQr9@f5P^~HmC%_Xwm~Cb7v@TU9VxWgn-u&`}K|< zPmv)V5`^^LCqA<_y-Dfu%9g4tBI+LmJ{UB}_>G#kW)NF-Qf=7!vO!;&;QnX++L!7-fE z{W+Om0n4e2wDsrp0UHB}kM{Dpc2x6bg9X}h1c_sC0T-dFn2{#&zu1IigWJlG{NCG> z?1+6LQ8a+l7|%HzBesXhrsv`i>ISkFF15s2X?Hz%Zr8Me5jN%6z@%;FzZR2VA?$q!d4Jf9vGISq5?!592H)CwSFl{@CeRa};DB$BUT zQY<7iR~*>_QF5SO>2<0AyOjpoSYN+{s{#O}H2!*A`!p?=Kio8RzUxfUXoVt<+-sh{ zg_n3%>cN8O^r;fbZa5Pan`qI z*<&CP=3B+ScjZupCrAsyWPY3U-}|Ju+m|wQxO*I5nY+nM$kJZL(Ba}8h!jTcXd z=yr!GRwoN@ME%Natz`TyfEa{gzB_POjjbDpO>)=&V~K)AnKz1V?)-Y&L13jQ{cllk zGwzvE?DKP+)1Lzq))K$Pvh0ub=ZNXkVy&8YZQD z!K?UK__12Jf8}kyWsOkhT-7_j}B75=kxzP2Wy`!5l4!On~Z*h$O+VE0>H|VGGp%j_>%!0x-d80~6w&pGA zg|a%K0rT}%W87G`IT?xCi@t74VYDhtmId!L9NWuLi1)j9m0`Dp*dd!42`T~5zK|Fa zScnG?g~A_<&6d;Ek49xJJktL4xrRSkJ;O8Bz{4+@%QN|4+EDQ5u9j~g^J6;C*kKRR z+J}M)Mm#z`O%y^>pqR|?I+|Xfh4Rx|Nd)RAIlc4d9Jn&_>=b9$yE?uKqf^PUJ!L_C zPf!AK8nn&IEKciy!HC~o(TpYg!G8n)iYgnTx!DlC{uxj$dB()CUZPbR7Yw&l(ELUj z++Y!+XJ0MkB|^cLCi<4$F%49dF(t8jQ{%;g*RCweN)2yu+~H;oJBF;vSq^8iaTkbQ zWO``7kI9Hre`GuBdN*LY%t78G@eEz8cwh);t#YSigO5K(5Vo`1oE*(}BBo);{ebR?5+~15Fx`%Vnug>ta4)Sk-4(7|dac{L z<4OtXMEp`Ty}0fl+<61Do!ew${VnuZ0Wf@M1G7r14Uk1?!ti8qGzjYW)*Kq(P0?+e z+4NK{`@s3F9rFK#3wgp>)d2|uoFoA9u{0Ko&U!vwV@APXHH;J7jU4IDK*1)ID$hvV zEVQ(Ck&9le31|XP#A_Y)xW#1&j#az4XRWr1nAWBHJX;k~IT%ML1Y9kINKG|W5lzP4 z!_WBNs=6axxhiP5;ZxmGo24g(oBf>K^1WT5G(z=jYT>|0k6rT<$}sL-Bw|5NWLNwC z{8-T!SJ0>A!;x;IEazB0NC&d!^&k*xI~nwaWVgaqS}L@_{Q;5To+I%;My3lz!!sgh z{a3yRMqTQ@9BaPw{gh#JF;XDj2yklb`~i8GvWV@)D!FM-|(xHBPY zBnLR1{cl{bSa-ZD-Zj`t$STds9nBSFV`_G9Q=r%kRx0OA8~=oPSEZ5C)E_-Fcr;uE z=_<_1QaF7_B(K{`BAFOjPVZ`xySQiEuY2ATfs=eY?X$x2uT{|sSa@YHU(DY2k8xx# zwXfT+q{mJdDxeY&R!*vPum&_wNqjcB40)HMMQig+x3Z z`R9(tqR1?p5iY_?w0`o0r$-{MHS<08*1EkvY`*eImgrs;hrCLPh=qk|K}<5CSS3U3 z7>PW_rJ`g)c-p^5sbV4W8?D!W>`)~ZBf!d_CMZpOqUnA?r}}mY%1d766z)bgT?AT4 zl@P5ibpIya6N{2Z%^EV@-X55gOIIXjdpJ&@#6kVLl_UcUEXPy{l?GA*nY`Ng&)O6Ckl#ii z5})(0>#B3hOESdL>0o-@QRt{*FWj^hK92I+s87C{>qMS#KEp$Kz@sz+hk}izTx}n8 z;7>L#V`z>+_^@YAxMg^`JmO!kW=hi|Ob)R>kAP;*W&*9nIgxa0c~GyhfqptyI({=; zS$JXq-B7mTAS+FIIAWGx7slAcpC=b1BFY93F(hY4NGWhKFaORHX<^8>gW?9*J4KGAw}JXEgy`h=4^Q;LX@U-Asj`Z+8q?M?uB$ z1y+eMaBT_H&2Y6?c@CPROu!Y)M4nAXLs3^#oso1ob9b#yEw-9A#!=*+} zP%+{}Yj8(U(a(3138gHqI-UaPB?or%_sMny)V?U zPGs)z9qQ*#EQ`)%abfLk;lCl&Je3GWA_e}2dnGiEkzf0ce922P4f$xF15&VMD;Qtd znw68C;oI-E9)ZWh1|pen5fDY$zaV@Etk`rAI*sR6^s2?;ogH!sj@Z06!@Fq(k3h7E z3DmSV{9}UeO06}m#)P~Y@%Bm9V`%DeefT+;i_T83%lF-FTgnDg0y1yD3X$ z2D^MaT0I*dANMZt^9iDO|AKYcXyZ1>|E?q63=oC55_FW+h^IeY>W9XmVhx-v*#~EV zbcA*ahZkb^g5KvSx?QlFABM9R95!NI1?k>&KkUgH6~4Z@$E0cAdJb-Jt|Da)Gf|R2 znNI(AtM?o!*wq|SzQ?u0`M;+M?HKp3zkn#ol$JxH4a|PRZ!PmDHVQ9ehl??vxpTdy zsa|D2^hsmZ7VGeykq`XzVe^S{am0(Sw8+`yvTpFZP@n6z_$YRj`sR)f7DL^Oi_iLsDjYF$9i#M?GdxlhMm^= z0z{y*^@6aV9eyj*y$k;R=JrfRhbpRZB-P1lm&sSG@2zP_Ne2W|-G5N}0#A~4-gfq9 zOXzI2yb&q0wkvUBuTE~I9rx&8!-%~E(~~iOGBl+A#f;^2poWC=B!K;N>_~jlmRxr? z?VgEI%KdtXBf>k43^#OoD}y__hlna!f&g1PKb}Hr5S_QBaLi(DU@8o|l~ip=h3(J= z=XbuDgUKY4B@0CeRv1`nFhBk>0hE||PM*KEb=cx% ze;vP`xxuOsoy-5am7`JgH0n4ra<{4xxeuA_FfLU%G)MdmA`bMniA*xczRNhw#8-Am z5ws_x9mGrg;mhg%-WUzTb^fsPxW&1Hx+hEbudA94$j0(;^65(pQ(3>GMXSJ$f^jT0 zgnuX06Q;OTuEnDp1^L1f`A#iw`|;zPa@+97GRy`4J!X0juk9z3cHF0vWWLY)SlaQg zDAR8=ZD)H8rilOTWd8iVEyPBEI0N*X*eJ)Vw;i0o+^IGtsdOCByq<%eLBTl4fyus* zL!<3Y?LH3AKPoE&1bxCUK|9oxRwxeo zp}sDLdq#fTg-x*C=-Drt z9#Z`9KVK#C!^vxpyw@0h6%!rUyF2kV@pvM|m74L5EP~<^Rm>bjzqqsf%;0KlfdyYk zyUwbBwttrYzH2Jzl&E4j1w1GMIRv~<`0m^DrQ6q#j`FCRcPV6vp0z%bXtw~vcnG!+ zysp=8y1CPm!Xg?D0)Xu0@5|1MjWW!LrDM?i!VaTME1ZV;y4PzhV7+zDUe*H4XetY< zrnYw;sYG>)H~S#46lNEMPrPP)PsdwAf!cs$eD*#YfZ>?4xE&Cin!T|bMH3Jbv674w50Z0E)P@#g?I-w4-@Dj}Oswu%0FI zrG8Fl)Y9DbM%eeI3z*}B8)ts^JmKdz4!*}1)YjX=u2=WQmydoGPBJdIPe!&yWk;K? zFsd#1)@JHOJ^BK<9PUr{o)f)_NuMJQtWWpJNg3s?yLF?Uv+=E3E+|DSGrQxdqn{9` z%^?CaULz`x1rN0NRXygRFUO*z|FHrq@(mteAm7!#9#%R=6@IPlcvUDf^sqa)qQE*V zOf`Ed%D{jB^5R|31FHA0>N^%fDj%g)6iTwcafIy1Iaf;55Qu^dE&r%_#Ld|B z!b!-{Y zcU!*@2Y*GH!_#IH)V>+0w*lrp4F^z-<<554)n^i5_iU<9ZX+K)8u*6d(j*Y5c3;kN ziYs^K3utb`=KxvYHEK4R?kyr}@IWz8W>0w4%!R~RnV=5$BhsFYv{2rEn3K`g_j5@2 zA$c60>1)w*uKXkKeq0|%>OXwy(I3$%75azmaO=M5?*4!VIwvP*B$e{(OWAx+BshqM z)GJv%J~1X1b;-Z-!d@_sE#5jTyfKxo-OF&7C!P9JPR?O>ikJ=I_)nWE?;VP^=q1Fb z%=08EH=((AhHLj(3k+oe*UcVF#K0nUmD4nYLi&67ZbXB>4sZ;8{+$VAjSqJaIMJuPKglN$zOsH^uM6OEnoF2FBVKy9;ZOz`1YPz$E$ zLojNIM!$)Yw?>8Cs;hY0%nY7n0`NS_5t5`ck)dPoyb0XJtUjGFp4KqRiPCx^uOlE} z-;=zhCn7NUu)lztgYL#aOfqu5Qn#FriFGr~e(9^g` z;>pQiNiOh{h8EdTBj<=V>)CbVe{WLIx&>Q<_st94dvboalCFv0cmh@w|FNNt7;&Uf{Ppk`?`zH?9N000&nLkT)k0 zD4xX%D7M9@0fzGg+YZj}1P?7A8-5JJ7DTrR3Gvn^oR6ek&OB*S&l83urBc_Y@rR0k zed9c8y~Q-XW=y2y&}Tu}ahf7O6$o+hXK(Xk#uPrRE=A@)JoX!IZ9IXRrzv!(g8s)g zw&d|(VJwF^088{(L-26!zXm=e?hk@BOj!5&BWq#DQTLN>l`H`~nip+cRAwzpW*j#} zAL~HpuQQK;Y6&EP$b7}G7h;Hdt*Zd;@&y7QXZokE z=c_MzzY20kV#8#_*7KAxu-%mz!irphay7|L?)CdGa+6>23PUE z`^f{K2**UqK^e6L+n`m*eUwJfVx_c4Fg_qC@a~WAp_lF*j9c-EEYh z-_utDw~LB{zhVCKvyu0MldN*0XZn*o;3s!nJu3z8UyttN{Fm_U^MA#R$ca#L0jEvP z%p(kU=&NaoYJq;#FkDNG*GCcKwDLlyXelF>+PVmk#1?VmyEoYQa;-S>v2%@j-kNs| zcXmj3JC)ws0{!ZWfu$A%3F{&yXikB)Gq+~jP3j~il#bRkD+(wh`6zgB%4&0}q@Zfg zM$4Fp|L-}BDTC%8%eyp`ookiwXIXg}O4RIAb3c4PYatb&fVS(>+3z`zU&S~=pB157$3fH)QamU`uKi}OJ`S6%XklICsHv1o;OIuK_KUxNyxp!c)uH1Db#p3UrXmxIF&ubkPno*L;cCDM6~#>`SmovgjfBV23m)x-&hJuxdib!)_*1-Ibxo8zI*NL@%I^BpSe0|;YT0jS}Vt7 zJhYwYXcRRAcmjv{g1OS1wh<~XmGN&3F8;|d{;392UB9339S*N`)NAk+4==GczTmgz zuo6c7Oygnr5Q%3c}u@=snMIV`R@b5p@6J$*}t zdBNpV(s)>t^PlO6`}szWq#fL_kKmcX7TiCnMLCRh7I~Nw9*V^weUT3a-09c;U-xQI zauZOGcJ1YgSF3?mFp0&tw#Cs1mR|*)Xy9J}!xaU?hhvUbTVEPYyNdxj!bDm>hL-UV zGQz)szG(piC)N?CcJE3?%%U36Wm9{=!b74i z41!OKo2gl4O=3sZ=PFWp}dnnOzv&-0(r%(PUg zuC84A%yH&-vRBU)MK;~_{grYbg}+fB9xBSn1m=H!zY$nPtief_wcF{nLtMGqs~_r0 zYV#7n9}~1cNpcTG&J?1gC&k^H60Rylehbz(Jm(Sfd47^{av`Dt(BjlOBBrlDG7M|9 zPf%=gGOJ15RR3mx$9#Hx#j!QrA!NvH!hQ-RS2RW>ihH%GK88-CT88zU0=q`2xTHN} z5uFLVuc`NW;wT1~uVSMWkp({an>m=i{$NSS9Rbzc_YE_t2OdykZT@P7IZFx*4N+i$ zS1PoK75Ilh;TQ!ZKhhPb;G>Gs@_yGI%}^q_@vB?o%UW~PM5?Cr>Uq7$uDj)ZzAYR1 z^m)n?RPvj$U#!=7X$yCKo!R{{T+3XU{sHHK5fP{ztuE)`v-H7-2v8K^BAQHo zWnIkwzN(%KwVTNEq4=;IyN)(^SN})cj{v>C*y9|}XWy|&1VZ#6wTH60JYC%lwj#2d zB85H%a4-M7uW0vOz#Glk4tshFN6OJ(0VUyYO^;Hivh_kqzmwrf@T&;E>W8|-(u8>w zZFb*wcq2ychKPdgCHOA^GOkx+$ePbTqOvX3E!N&%P(nkfuB_}}rRfioW9K9WJ!hkg zM@5ukZbL)`+>?4vr*1A1$(M1&KdHu9)VRK)o9m8M4`02ruN)%8cO#A{F)>6MZWNFx zX`t5Pn%C$M67e4W)C~FXq7bR_ty*Q!TlG7EKM;Bxf#>`G3QTBnfdUtgql^#Mhs=v5 zYt$M5(B~vOC5@C(vkx5^EOLXHP?Kl12_MRrWQrxwE?DowH;g_2f z82kn9qAMcI%lpe_XFcSH zf1UM_`b(vE*^Vg&L=JGbSLGoPMzw=LO#bS@` z7MJCDq%2A@m{gBqf#ph#BI{Bw-fO;tgS3F@JcCtaaZmt=q@w>cbN|1@!KGS#kC@kG z<7vs*X^~j@wRni*oWu(EShAIY&(B>WI@IJoHJ>p>wmF?z2ICFpM(Pcc4bB7f>lnp` z%7*RHZ04Mb%I>X~0&MrCvV-gm?S7!)TSfxo6YDMy*TJ;YTPI36wdthtWxAWpa-pt)7FlFgNEjh1tVhaa>l--%blKN}G z2H%54ze~JP3vmX%=AdMt9&OPufkhItry3nojET@0|CK&y z<_w~G@^#~d7=0HvR{?o=l*lE}We+nu^@L^$}U1>o( zQ_oC?FI=|>h1-HZO-4EPg;#$p=D>PgO&xKp1gA1l&!_;R;x?}vKXMFG{3$X`9%|~V zGSHTS8hhk^y*BobGQDfIrpe3{5zuLpZZx0U5glE?Ush0PT3K0%c=C_jO@}MoC1_cR zPU{{nyR!j27p?snjC#s+Y^W9B;&)pC9Sth{A3am8=;EIt_Oy*XAjbl zTXf>nmhDvP6U6Cc93j>jQ4HqcRF8AEXA)DvI0z>79&!$p)Tqk+7TiQiZMFet5dT+x zd1C{$?-s*)oL!!$P8^Dbz#<{cE#v;q z=8-AZI8EaGc5Vv)ejJv*g!33YW7ntu zrOsE}6FJP^!0O%}9!m8=(>)362zYM5Iq2LN(dft1mjrcwwD_6={K@^m9vdALRRvzJ zpXwyc1`NB6XCF6Nt66cjO&A5=^S2GSi)Ltg=k<6lto4g1v7}-Lt;O6SKr3$$YYcq7 zHXB7{riz)2tbWK84wC|Hljzo4bNBeJaR!VckSqALtpmd(&rNBbGD6geyv&cvIp_Hm zEWLt1KPq8d0E{2VKC9s9gw0`1ojcBnr?AVn(;s&Z3gs#{AsoCiQ2FHu;ik=d`uWXb zb1%a3Mpf*XXxD{Be5kBQp5JFa!RRUCwvTL+7)}G7s&nk6jN14QscF05X_*!RCY0PP z3U-oKA?aMSD?YvN#9Lg=9!^ELOs*M)9XY0n7)}vKJ9gGz zze_mShInDc-=Z!KR$--+?Taao&e$l{7t6o9qE_0m#5ciJ2TK}zYp6LFU zxtY~Rx|-&{kxZhbZ&@J5$Yfa+b`sJ|5R z04eIIIg@=N!-vR6z^We5E~Nx-5t$j-2&zb8ZYt{*PGx3E9* zaexgGT-Ju%g=2Ip7<_J<33C?acO_6skWHmH$1*(%6V(3}H|bvSV8X!8`h-3HjsRzl zgTCeN)_rQNgtn=FZ4$?f-Dvw7Y6lyY@M+`;wPF-+qvoX5tj^#|?a~4)($rJ#`M*m{ zAvE)dB^$(bVAg}G$f&CmOP(+Xi12PxUsS5>s{;X~izxqPtvb3{iSw6mXL8c_kK%zY zT4MDBnp78^NL_#Yg{zl|f+-Jx$9pP?$ghYH`4ydOvSYaQBR4vMQw}Bh*RF=kvula4 zDokn5EBI&=ioDNo2BMAgHT?3O26wv);VoD2tlwbe+WfH+e!sAh4n}@>S(i79=^s#f zI-SOO%Q!UV@8^ZF=Pk1#Bc9wR!A;cwzq{fHZ(EtBGnWHSmF;KUXPzDs1-EUylpg2(SA8FK<;*xO)h!cr_zp9$MT&}nD35+W6-TsN#XbH~o5)?o%Dg3U@n9e8c{o zQ@*S27iE12hHwo*jL`T*x_4PkcHjR3N<|0k(O1{#j}a=5REDzNn||Tm?W9Z@o?(`aITTn4M2(bdQ(ghfx!lsHJTIGLYupL2aviT-!O=gsb(bZx3a%*?W4QKbNbah zHTB?6(TBBNfz8S?Fe%^ZoL+^O5^7H8axe_5CP zJ&@HJUJwVO1+fkQDVtX##{kuP_D+YGy2A|)KNL%1}-e;`lGigMCC5U;`^BeBSwQ{4sIM&0F0uTnyCNEX;2C$ zovmSuo^aXRbMA@N&)HRtd6{e;_*(xp$_aZmbv&_U{Q2GQTziB0(}+)fg%r6txj~9J z9??b0QL~?Xg-lW@DfU`iUgi=5)gP?*?40{QT6+1n2Pfb>X6ph=3IoJ0}mO^zdsq7|pi+G?#6rq!d>GXpoO z5?3mO&T{vg9{pdugP}Lwpv}Y?14Uls%uLwMy zqL=CDos^gBOmwctsi{HG;XPrf0(?*HLqww!NV6+iv)xFFqp8-uzrcT8uCD35So>RN zP<}xA5rZx;h|e&n9yKCyUYs*kR3)V(A-jtEE$MJ*IFnh#w=tIa*4RwHba*WDv-{re za+gclG>zQ-+t83kD9u-mMqA{2;@@e~tBM(0A_6N0*P}2@YJ5;u`68y7i-ILe(P$>miy_jm*=4KwVrBtQa0gw>Xe{UQ zTD+S7IM|0z=U`U^YwG2jyu20@JElx8DN(m{EUJA2>}Z31=53;V`Bqt@hJU2=#u+Qw z$tU^oK5bF z7YEMXb@4k+a#J*nzbw4}?aSCD{m;B}K4P3SZz$+*lp#(^*kK;~>A!uryZ^=S_T7X@ z-p>KeCxDyS%grp<-=l=nl1W~?-8%Y9+cN8u zc6XiFsE*dIZ_!%wgj&Dp8*$}kejmO(`2KpCw{HvADWzOqgVJRrV0@E3!z~4H=XdnA zldarjSLbp$^Js9~Y+P&?{QM<7;@JbmIvp~`i{M;niz2kU2ajgXMjTsSW^C5kruJSnvXZ%T?SiI z{NW4Rs!eap4qrq=@ zX&-rTWAB;9^l&7i2XCO>w-x<7PR0A##;tw0-_mcM5*jU+i=FM{qw%`960v5ZO|GX` z_yO;1z+Qpw9@kiZP*GDyzd^@M5YMKPI|iGopi)@Fjp?OQ*B~c-+l2M#EDk84x(d>p zvQP{CF8}S|9l#Dd}AQo}zk$$YfhT~Xy))D11h z=E)zKA*GFR&m$XB7}GqS{me4FidizHOI8=1nMP05Y{G#=n^hp=-^sxUOFA2ea67#AVC=@%~(;U#JNs)E3I>UqjhrE@fvbU?wyWxjHRN$$S| zmQUI155|Fyx!CU89C#7!Mrs96mppe?BBY)%|9w```Sqgp?Dct*;x(2D`!k%>t9T^ zy=m!bqU38gYw$uos>HziboV+eFY7`ef>KlybRQ>D8)i|USf!*NelML?XDO0)+NC{1|C(yxs^bB&J!L3O||by%uCdFwZ% z>q^TIf};aA3EyD4 z*HqU!a-kv~7Ke(;#h<@WAF7Kv&+6|@meXyhfn+9c7h6C~V)mbD6=9wTM80QoVi6jP z_=aiNHRz^~k1XRnv<`Yb>J`50TU%~oY^<&gxB77pTgr0u@VVmnan-(C0`e6l@A{Ewp`_E%xU>cE{HPM|K z-HZJs-(tKHNl{u?zaHuSrQ36h_0=Z4wHr?Rf_4lV)4Ov_P0atneV9c!Irj|SZWx2h z1p0zzO|Ty_&Axs4GSnHW)$D`?Z-le12tFNEJQPK!$9KP`iVZCC*cGbo1D3=KjtSDL zE(WQ6)2~RKKxkCLvAbg7dp60kUzKVbnu=A2TF6@NtlaAT%}p^ z4k+GGy923yF_}2&xl*QU6`s%WrqhtA!hB*4NO?1F>&CZHD34n)D136=PX5_86_~wL5Oq zb8(dL6k3U6P;Q`2A?gL@UWMbfGJ^#9Fr6ez*yZ9Uo(4G&=O za^zEvck0jyO6Fn)tN?3?WaU^G6a@`N`>=#R%9cGn;DM)-|9#i-?fRf)-@e>d&O%~Xjf0Eblr!) zAsuJaO5&1I1VhC|bBK+ukByysLt?Vg6t1B;z2E$|4EECv0@J5gEu>{rSN+&0cmr=>b6Lukh=FoU>OSfU6EfCJ*wdxP9Yb#}@(TuBx%0=C(X^?a)C zp*0(YPZ$05QcX(?rj>|`p;@VwckwztkPb4G5tAib`P_ylD|Zf6w>K?pi<{Q>`E}c4 zzWaa#$1Pxf1nMdJ$x-~1h!-v-Ph#H3{+grPp?FJ_xJzfr-Ig7wO1?Ph7mk~hd9CUm z2bNnF4_dJW&}OY^#MHdtgGAkuUG?@pattCqgp&I`Mb}LoEo!eiWA*ykzShSU>^oPPjvXfVw8mDA)a_-uEfzDoSv99%EUq~Tcr-H}B2!d;gy&u5-_v zv(MUVt-UwQHf50^N{c*oI7?L|Uiz&Pgq_?c_68f4)fO3|w-e8Z$NqHLrU?ESCh4DPyI+3G2;Fdnr{}?>1gy-a7r!HwoeD-3Jm;=+mwhavws(_UId?^xgz# z@Ct0`%TB}?(-71i?c9d7A{)tU7kIu~(jRI1yq?UY`i zU*-)_e>bA|!*7|R64{q&Y<8lV#BKlb-@jE~EBZa|7O^bR5Vjv!5DdOn<-e^IYlHA` znL&Xj{eyyMHS_z|e0W5h+V%q}A^r&8#TNV;49qjas2>lQb~QIDZu-fXHfHi2d#OhE+Om zHAqCiVU#vRHu@6r7Pa{<@GM}2_+w%68|8{kktafT0Ebhh{5a%MI|m7p_KL*kWqItg zM4Y_<$Wd^Q+Y^Zcqi*ye`N2YG*dJr`5$m=Y1=fXo@tj)P;PZ9HPg)-4v_*)IG$ZdZ zi`mH7hfns_5d3d06M8T+L1tR4+>Mz(zg`m_e1RJ=Cq_upKrCj=A^c!BNb&9~2_LK9 z<)5EQ?W@e`#9DRO9T3HY_HRW?_fcLh#P4#0QrsI9ux79bFUEwTpz2`TFAS-=5X=%X z6vQX#`lPqhQtXt?cW8>UioOb~&mB*8CCg%@>TCN9$!bE|uV#R!#?dOgHir|T8pB!k zGOrMf4%cx#!QJt?Lf0dG7&Kg7RW2#u?(j<&$8uqK0NQnj-K1JuiWD6HHxopW-BGP< zUku?#pUybJiLi6`ulzkac2ST zcRWn!N(C$8&tU|AXv^16{4G&buVp1#)$_xQ=}Wz%#HCW(z2Xy%?Q@Hk$jLvkBo?~p}N>1eYL8X%5joMOBI88B=yVlAeEH?*N z&3>(Q81X6g4D-r9n4kO+@lNJfx8Io$_sA$g{fq2FUv>-Coi=%YXaYG%oq!*x)y$KB zkyNo4N=BQcU|=uI?8lho(i~9F8rcJF*+qP$&v}t+SAzj;3LMSqrcQ66i>TI3XV^}LLKXaArN2RNCURnJNr%7vVIJ0&Qc1+vSFS{uHKM6cRd zizd4FJUR$wX72`bPv0I9+14#?d{F60K2ds#`i)0k!U<2 z?%&hW)_4a#U8CWJ_H3b{k0*ZtN+R~2)u*CF;+lL%65B+X5fv0`o{9sO*d|bf6tUY$ zjTq*t*HkJTLk#1n0RxF1eMAWES$rmt$3YEepJ)e6{`CBtr*hY-Q40V2qy^}bIafD~uxr@z)ceg*OvGF7J=<*#(R zRrk84-0R^%*X`A32!Qg<^=j&|=NPt+R{lUk*+XebS}q)CayQ{;HpD|B%ehu=JK+3R zXr-nzH^PuStS0!wja_XYj#ih_n}9>}cOa0trhj|50RsQSxkLO~&t24$SxLBHHnCZW z`A=0C8DW!cMvT!)HbuQw@fgwW#?xh7=AU-6dN_A-e799>Sao@;i zyPI5f`DTDS2uP`;$_9_Z{iSYfb}FCjAh*eXL1SeSlLW z;Dl@n5hkMbAP3P^K_`iIa?=^!?@_e&1KZw-ZkC?02I136qyg?^wcNHsjMNaK83MI` zjD+gMZ}Z0@S3D($l2fwk{rT|TUh1y3{N30;${W97xsr8s_99WCF?f5!z|?kidLlhX z^V(wb~M8T}V0gBPO7gORQxb)9&{_$E98e(ImBBj5k(Ru~Q=w(m~HF(uoLUU@&s zqFglm-a-hZYW<2sYb45>fulqvrq(|3=e)&W*VxN-t7_AZjU@~pJ5n5n9TQ*r=XkRF z#F{TUsQT&Tc%i&~4VeoLvg(1?yrl)Q#-Cez{C~06m&59VEG@iC9<#GQIh zxzTd(|9e+UiiRC=UD**cT+Y#VtJIg+H^RENEoW27P+80CYgbn; zt*w<2Lq1{e;K42p`Rj>8=c~Da3LkuohIyDljO*rOM-BdIs2w6w{gA_uDR zALR&OkU~18!7!%7y8Ibo24_`^;QjO$U201WWIfb%__#8p7Q0?ALsf2Dn6yyz2ljMh zY~0H5hqt6Y=uV$bx~`nx*L?OO)DmB%|1BSNYABC#^n;I}UP=FB>1J008fYh?ZToIO z3t~`;AOGHdaoxsuQyzq}XMGF9UfCz(V)tI=2BPYE7j=hA!U*r?(r)y{DI@k%#D6?_ zKV%sX#(S15>J5O}FFY%$^JrcQHm6NbPm|CnlY8{)ed-0s8T}4fw~u{ZVW~k518$mr zDjmLR565zhe|M51ky9kFEmBbaz4{U2)L%U%$kj{@r7-Lbvq6WE)!jHDqtH= zo7-B|)fKou{Y0t*gnHk6>ZRM~^BD)Dzl*^rg6<<8cJM7{()jw=7mQuqJs=##Ek64+TK42BYlCV8Co0RcmV($p z^1(J(G7rMwr&T=9?hir->t`$|JU^VR`+8y-B@Fb~IiD3;i7&S4f7M*I3DzA3Z44-z z|3OSUpfVhdenAyEJ;;7%hPwB>5O#Uq}OFZ z;d!j*h{D5PFINj)=qS^TJ>fkQ)V3qWSjJ={Tk@Up4st~02}{#aZgO|KkEY=G>jk91 z4gP5a&2Ukd&^>hi2iSIhpP$IUB7o#fQ0l;Uu^4w>6oyw|Uv*x(RA$KZko;+DDUNJk z(0pjg!laPhZ>HD0^{CvrsUT0)Dhbs zZUyc!H)JLtnS~{;Pd!slanPif0~J! z;%{9qO2*fB(_z`xX|gXoy6L-V(+{~n^Dl0u>Gf+aHL4crCc@^4WMLIFMA#l$D684j zoK|MKYtV{F0h85FN64aW`(m$$DccJtq+j#ma~!fL!WY!9z2`3Uj3K@Pd3YMRSH_<= z4c-h1uG4krZ8%59nzDZAbIhmJ4?@=-$>smC>Hq`hLv(x?2k0}^NC|T%e?B-Y7({Aj z?^58VX_DbD*5}a6hCx=CBZ{NQ- z`tR!w5xZoGy1bBo%SlKk80okD_07{lt?J%{V4{^a2DdNt)De#azt?*Z*Tv1K|Fu8R z$EB}XzOk};`TgOfr_cQ@{wbA9%)yu5IH}G>S)oqX^yPBZ%0zofUXy^yw}wIgcb*=k z51Zc|NQXYNvTs0aEwhby-o;X~YJ$+%_9*6>;FOWqL|`c32ZN*^L0yno z6}e%80}z}z|02~&Tzner%GvS6v(>z~GaeXWkON*oxB zxz&k1sLi!RdSg-2%kn{i(C^gi`3lMfOX|4NIp^qxsx|LfRtjN6*Q`OE` z+?)UPg(X9@9+xR4f*L@zs`^}fXZtMCqGV5#V~f(nUUaG8OV<<42nKMJ;OxdG&MnB- z=Dsvk%^mv1^mdITv!_;@jy>kS=dw%-yi7UeWFI7D1={%w4gPu*$Yvyz5im;|%dF zx&Wpwu)Huj-g^7cIrkyF3L+x~n_F7EAr}iDCf8ku($XBN2I|Vn-@8=;WWqRCMh|-k zV*I~^erV$in+D`^A+t{13%0g^5;hkUv}Q-LKsWxU9y7UDHlF7Tj*hcJK&d?G3tA}Z z6PFnDWL$RWuJWW>B+ad~=CfJ;92_x}CiY;!nf~IPSbG^u%CiSQ$A6$G$jra|=Lq1` zf3j_=EN1$(ODwi@6*^0SUhxp9y!p{8!COj{G9igpiV~)K!Gq5vXKG~+hzef^q|y&q zErS_DlnrhmoFgUbpVFSHSAWul?1CLMj-^saQPtKQ$yNq41g;qMMb>OKwz5b`3bPiX zsnC)F#Z0*mI+RBq(YRObKyzq=j-Tzh9j+ENqO*zYogjPv>j*zndR|@?PyOQcAhe*E z(4b2v{NbL7k=vuSjG0msTFcB?85 z5!W3XrA*65>`qTH*qR>@~521HxoKwA<9sx`cBtXYJ?ncF)M{ zx&IP4GLKo|qsXMNeL_RJ{KTSD2PDj9iEWAKy?o9^NeRKYBRW8MjV-CR|x zMboz&->KZC9e?rT_ zH%8JUsjWFEBr)n~k2sD}IIn|JFiDm(@&$b0nC2orqOFsuM+ot^(=v)t^pq8tc+lhi!<ZRi4h4b%>xR1JDufv{q)8_RNfXqfCM+fk#0R zk1%>;J!pfyrj>(2Yx{hwIo4Sfac=9{1O0p3G;(_rOdTtoP3l5yYx_k1K&wrelhKbv z+gq09E#KN(uc~r3H=6w@OgoqRm8gzI?hNmL zJgV8?LF#dRYbUAg$OA2$t)hE2ii{pQ7%Rf^=)y=Wu=Tt`%*d|h`fPH+z6B6H(=)vu zY)_8=imEbP4gm;fn&Ns4M;^edQC_y_y+{Y&#&2^xA^;~dc8+?lQ@lb$W@^yLd*<0* z#^X>M#oZm+{u`llgre}HE7uQHm%{(kLM$v`X5FIUwdsfhd{4G`;<8F_Bc$JJr3F+t zU;t73ppLZ9SV zy`oS(ZqdXBMX-00v4d&6UoFcBY>G-pk0nUQj=`cG{>#w2bux0R$G-D>#9J6TA(_;MIS%02($~xdRvh4F;b!>VlNO-S{-biW za$rEq^EXdzl*+0_w`jjXF2O!+S?R>{@dR3mFg^d@h>XxSgv>bM*uM|G_AiHh$GfFX z_3bNa?{ftiKLUkR#Mypd!0oAOAQwP&i++fdF#(Tv33#9+!MPuiziE9AA6nxC3G__V z^WmSg#Z6Jtey^>s;iaj$^h_Pu9q7gD{jG`+cNCY6GO&`T!Uau72OkMpH^3Pq>dOrSnMc(A`ep5iAy3jl1mw#d4M(v9wezOZt8^k~u%$bL%6!lu9D@;!59u_Osw~-@GXh@j5p)GBuI0h>rSsL-WJZ(00RRn^wdOf5GA&v}2TgBK{!_oS z;D6XklXPhtD)sG1_6XQiFN}~04z0Nc^q~Zm%qv0U{9zBpOxyRA)hB3cK^D0@e z+XY~w!^fs0rPOt!v%obh8Jf$hXRIQF6?YAR z=&5R|WNlYIi%Pb9H~IAUFGR9W?nJ~m@hChy_Gmb3$tE(!bTz_MS1DrMU!AHuccroi zBPs;cvO3LIwLttlwgXb@xuBq8qqzD{Pu@o1itWIK_WJ`oQhP3ke*c=Thn*Z^iTy_c z$ka%Q_E_$5AHV^3@a(E=uslnKWaNkt`B-{gv+IRp_-6=FrA$C8m;b{m6Xd$|k9D!S zJDIiL&j55;4Tn5OnW2uD#N08s=owy=btU5WS?taH*4?z3O19eIog&y_`B4JlG#h7H zNJ|ron(2G}EubBLE*51*rh!uOWAFq^Y{~@BRtAgZ)RyFyHRps=i$?!_;aIvtr}V9QA)kF2>tz zh;3bSp%rf;oX94wIud2EeWJ*d&iL%ugz-Y#S*R0XIiMK@(a;Pu(xQEVlCcr)xl$%| zhK!{M?`@aOw;$2Td0OhCtddh>IKqWr9vp4kj5+7i&`R+JGfz@PV-XUho^6nhuAJk5 zM;n;!ZlG@K!vya1bJ1S%HfAHNl+EA7(0M&RksI;x0ZaTIHBrU#>&bS&4Sm=P$#C>u zhRWlBO^`BNT>V+G;D{c%$ajsjDEn3_@=Tu9V(ePt_YdZu{9s0mzYNb!+qHwP~n=r>w z!ZNeepll^r8`^EK5qVtf7nU0T=LHxUJ5zaSi@Zb%dUY~;E*(58dde7YqE>_UKiIy9TYgsxZ^~vsb63ob;3pbhA68F;P^;)K+v#G0jF89AMiY0{(Jbz2%^QQGAysuO5 z2su6yBbN=E3HyxguhqSyR})+EPbMTo%FZ6z@_Av|%#&hu^guld9)7MG*ct`4;&8^8 zgi*XKz;sOYLb!*_tpk6h(L@hfKNfj=oAB8&&3c+wshTs%C#feBzgO`>-T!Z_@JMKm zzH3K>j@?{dY|{%eLN`C#B?Wtd_@<8t@MU7tU6Lp2WF!^4iuTU%!P$wwJC%T@s$wbG zvb|y&)FjQmcN*lVO`FqVy!D4?*^HcmcIrL1+<_V`Cv{Hb2$nCAkxbPuzav#X>XZ~1 zn$IEzy#RU+`Z)a@$w~n>h&v}hHVhy2SI@f5_9saKncrvNSln0=sw;P%*!>p^2PlU` z)ySTcr7}WJMTWcVVy-7C5xi0OmzcH5t7=b0;GJF%#!@_3lx*o(y%vA6k{~8pFQ+?~ z)kEmcv)<*&exym28GqC$p{YTzJtlAB~Hz=ZXF?X;w}Relz50&ellmh2x3CD!CM)OFk;I z60mqte%@=n%m9Bd;=vk90f_$1t0q|Dk4JOvJ+m6Ge!PJL@N#$3>w~B{rx(>SAL1(k z+6*HXe?4KFOjtdUriA8jd+EysAT8Mh$SgdV=Re;BIJ_Cp;1SLLJiK}eLMx*WEsvLr zhiGO}i{&fE7Vl|hL?g#xtCkD}0jvU`P`8fP7*1_lBb9YO!F8(~Qz^cyJ)Z&_t&Czd zg{8-lP>KGq&yL7qhpGQ^Rip=F!5)8*6zC9QA=+X6ZMa)mDeOxGw00Cu{5vhsBC58N zeZdi=&!u1i#MeQ>inv~ntVX64;LN-ax1uknkmK)rY;Pi!bM`<+40c~6^>P-hAgMbkdb`&^>=oEJ$&h?#BCx$*Dou2?a+AbIsaNjr3s_DshdSDfJ1 zJ)lk^>2yl(4QE1N(xNQLuW(>_KA!#rtBVLYB9AnJ1Yo!W8RCb=q6#>{t?e_n?zL~z zeihy;1^sBfsM&~Fe0lC~4&p;K>#v#}JN!Oz9ozXE78RYj_czwH4~9yA!P24i1(fmn zxy~fw3Ye$TKyY*Z$|ash&4#+ID=+)#eYTdmB*hsT&tjB?5vof1iV1bhr_<o42V$&ePCESHniW`Z~;WJsfDb{>7{do}Q_r!o(TR}%c{6+5fj$u>%-pBfQ z_f-kxVz~l74*{ctvk3Ew_Iq)YavYo$0x?M&SA(9*wf)73TPcHYyx*c+PMZg1_|1pxu!r^}idVsR1Vs$lAQ z4G|XUr#Cr23waWcbIfA(aM)woCzoSmCevg23DgVMME?-n{zdF-6tH`}VfTM5YdS4O zchTFMui0A)= zpG#ss?@^7v^x0mjg!1LuC_YH->1icN|LA(bBc|0(gEn6P?S3v>EG92}P`}(*dMg?9 zkHe1{PzIkdfOU`p3_c8~6h~?i{-#jKkXbNZG_;KNyFV;7K7jL$F>ZXHptF(Jt1Mn` zh##^EG>(R#yV7jwkd$H$nvf4+b5#$g+$*tQneSD)Wn($CamED@Zj$iu&j=%m7J@#{ z2D!#VY5wxj_9TNo9%pBeF_h}ug4DguKHktz5pxS(o#m#`lzv?eI_Hn zdx>N)Wg@T;p#f=inN~KFm@7O}2Rz#}I0?Xx)mIM^;4L2gW!TK(8%%}PqpiMPuoCII z{9Vm=bBs;&RK=FwT*3y$lVscutA4uc z9<{k-F;-0=(vg=Lu-OLt71R36lnG)blWQNMs%K z!Z{qBK%#f&hgY*9j?k-v?G1QNZd>bkwn4}SR@1_W}6KtC#C=~U+vbos`2QQ z!0mW^F8JFB=0RvW+~lNl_jFKXCj)?HIlT!vv5q8UKKO5>Hz)!NeUjh-@%w77$SDE; zhp?J17q5)TK*aD5Dh*97t=i;Jnw7I~!l=6x^ggcHT6XSl4ZR;(@%th99+5;#kK4zs z-_qnV?DWJ;lI_UtOy@BD;N>lSRF}{^v^dmBEkiBXF`JnNQs`!&-EkvmvUe(zD z40nbF2Zw^u(Or67Gh#P^FMxW6M1k=d6Nd*tBWhkUNM2qR=4y`t7a2D9A;mNDojPlC z(jJ3NiTIb`Vw@9N&7MT+eQA+1EmOVM)i8jm&dG90oSqk>?}J!p^w>oKjX>#?e|}<| zic#*yn~JKU$9ay`RnT8GdiL{|Q!TM0snZxN$C-9rdejxM1rItCrz{W@7f&bgH`5SZ zZzI1VKFzM8sWPJ`rfaPdj+Bpy*^xIy^4x3w@+e}_uI#BE;wUFVSV0crHQ&vd-y@q~ zz&iAyXR~{1qelTQj~lc$MdLW_H!ppf5aaU~%FT9`j`X2i zCgN&O1B%o02L8M9A{H;Ctik!j-bm7Y9>fgoL}tPJD#3c0r(e}z)6 z%eqLqM)JV&LKh9CF@Pw;gL(;_& zkFrhS0!~R8n2L+6F!Oh$EyN(9QzytSQF?= z5cV16W0bb*>_TKHZjiT?dYK~DOSN*T6`Yti^Y_`1O}{A-z`r(iAa1N9e4@ zF-S(qxV#Z?jv%4ef8aVe#uytSu}u)5Dogzt<-h+GK^1nMaLw1aeh3Nss1VfH7?ke* zIuS2|*C9A~UH^Qe#wIj7emoG|G1;$a9_OXNsxTWhl@s5$Ug5MpwaU<;z^Ez(;PNac z2YXwG{;Zg+Y>*a8?_ZC@gXf3yzp#Lk9<2JoDH7KoQ`^>n%_h0(%*C+Yu@Py0)mUPN z8up$`S@o#Ei3|U)V2mzd;nrHCJ7SjgnVAO5c>AYNP;-TE#o!ma4D)pzhQST#hT{AdbF)%5WJ>S`7 zTvzkZM}V}9SRU5urq=4_s%|xK24QKXlA4j*ec;tI#l+PS#f_otcFqV-V4d=pigz10 zELqDtyS+h=px@9;XT0JFQkayOOitWD$+3@SXP*TWZnQ6HF9viy>f1nDVbz6JRzFn~ z0dTUA^t0YJe)?C;iMp>jeckF|TaQ#%`eq|&L4{xWt1eypC@IR^f4vZ{IIwM|4a1S{ zp?FdZ$H}cfIDSF}`{Mj_7^H}b#aILNoviyPLGIpv(UQ`Bbtc0aQ&lZLoL%(}nXG?e z{!n|vo3@DIT>7doo*db>WnQuGAv4OJA9q3LMtI^iFFmU)s0*&7Lboyykr7c;9vE!X zR1}sz&xeuOw#l>`nA!TB?K~xx<6CzTFL>@ZRQxt?5k1D28$KzLk^QLYcyImZqc>mF zB{aH|&$O>$A=z!ep3f$30rf*hPrHoD*$ZtSWR^_PzbWl!frI!!uJ7JHRqd}M#v~l> zr=n!TrClY68}3hc6hZ!c`M29Wnhe3;eeqXmlY5%*m31xK3}?M;9~WFtIc(Voa44Cj zS*Lax;hBvm*01``guDG6_RAc7TJ#dM5%3fq{n5zN;E*E!)L;^-sa5*E~oN zl;C)r$Yks#CnEHZUfy>S=p{BpPp|9Rr3vF8#${LML3KpawR`Tlae=H7SboD*Na-wI zR%%vCV-WSpbq%%U(|mXSeYUW(yzTP{##CCQln$!d?QAy0Y!*?NqQQ+wPq<|Ctc$R@ zZm;hd41y_A9lcHrU}8TOV>DfhZW+L!cd?C3h z1)^D9^D@;xu|A`m9G=L^V=$6=D%pa{sbL?Bt zu+eB14R%vEc9O50UlhdI&3mXOTf zd0a#aBNlf0v;dqc0>dewa;lQ!9zKk) zoTL*w$Q~;Xp6u#-cuOZu1N3K=luEJM|F-Y&mgGsvB=^5NDbT0)SRxUB_oad+Fb$CJ zyP?K+N`FoqEl_dl78^&6!UdxVGIV9mzX-@rI%Bxpz4{LJ-;PJo(CZSje95UbEhzk* zKHX5wr~`qZKK%FNYk@76oyCN>i6MV%m;0`a?WI1g3+}z@`+s@Wa+UV20pUOg#V8-*Wnsy>iNV@%i zIfk%m@g$F#?wU5ka32x#*^gZT1p`c6val3uQQPXpp8g5HNq9S@()&BAt{Tw-30TwO z2|8>!;dX|Bj*26g_#E4liPh^$9I2u(94Tn#|F40$VRt&=u=Drt{%>+gM4oB6=hB|7 zi-KZIVCZ{F-Pgubajt#S6u@G-el8&fV|5m3cWu(dxYRHyf(VOhDNt;_6sq8u!r_-& zE=p;KGJ}kd(AM58GvkS}PtX(5yl#Ij;Uz8V~JUL3lulH#0T%~&wu(7MFna>;htXqI-Gr~x8h`}S%JS33*V`0Ww> zyw42dxSN+%FHI^V5Lk7{3HCBTBkc$c%oMbF2t5C810?C%`dw!9D7~_ zcSz2^^T(ccq!MyBb3N&zwUb5122VE00^lu1gv2O-sag6AdQXC<3ut3|OV=uO6y8d&%#mXNC$IO)782GAcA#BnRK_unYfE<2g0g z;dq8yu2L@1SDh!6akHcCvb6QzKN)djK|~t-7aruI6Hui{v(a8^r;P1ETE{B!55FM-PR4q&RLcM`15ToO2`D(`yG&2j}?-EZkR_aOdDU? zE7lqv01FW#_hWFjL6A4w4pd#^D*+To0LK!`QY^+ebGdF$63bArnBm*Ts>Se=VXq8T z3>(xnjV~DMJX?-uZ^d1c4E2Gh6kbWco89%>x6L!fee4l6@tQbIDvlE$BshT2ZjlkL5nS-kmb~q zPm+^?agWoO6*%$U)Sw+wZftbm%D7W+pjehHab(B~Ae+Gq)3Y*qFoeyM}CqH45i5<=NkWn6~6Kk)Y^* zj%lf(xxJAT!&BzQ&VR`m5@{DvuD{Zqp8i`D?Mf?q(;C$l&klQcXzL!r%bc*Wl*Du& zQf*P8#-h!{^K8R?fhs$)B|&zoe|?7sZ1Z%={Gi;>%^qbL>UCfAOTT{^eDsDmb3#9| z`$U+;SA4uiPi3c*w$@Z5`z>f}(-FP2Xdg!b@BG$a9yW8Tgg`NJ$9-jv@IcOUbpb+J zAD;WD)~~ecCq3_yNVxcekS(*rxAN!PJokt*VxL5F_=o8EA!~QmLt`H&y&QZH@7|rUBvG4cKq!=xK_V#iluaR zD8mObRrTtAo=4rg&Xd6-$s_r6$HL$6SXL>zHcMoq(h;XWao$`t9zo6C`k2`gM=+b| zZ}eD-Z!N<}-TUA~@~F3>LKvy`5K(C|FGA#2^t@rb_jUI6G#jlj7h^mLC!WQ9gop=i zQL4@ntJ?==RBfJ#B*{2uCcP%}?y$fW`m#@tX@{-VpuW7Rf*&^S7CR|o$&!opyI=%!TmL9osP6VTErL zpV<5AC+)LmQ7S$nc3fcFa*D)N())dNoDyHAR#5gd$D(Rp0?tT!@aU1yr zjsW%V$;_F|Kp!hS9mC>V(}QoXnEH@MN8liDw^ZDXxbGNNNX_Ch-x;4jPYPw_Q<~bf zR`Q_A{Tm-;42FXm-@20JJvVm#ei9lDme(>Y4rN_=F56ysRYElOkK8=;V@_7ztE4#G zzq^Q}mx>{s4zILaCA@S!j+YsCfq&WEiIuHLFurWT3?-9|_?|0>s)23kX$AzLEEis`&!~r}ytZFXU06sHKy`6TqCuo$(?@is59@2?mTg z&XA4vqvPbZ$!(*^YnKMPq)GY+)}yLeMKEDJ9~@pAQxM|g4$hJaCMW(TRBqeZPJVYj zyM^t+(Qu?L@Sa(W^gkrS1mS3PY$bYANKt&df$o&{rAsKmpG;4Oilma3dm_Dcs@N8w zWM}og#2gNin{7v65@WsJYAUKvreoQ;N=ET--iUFAhWoSjp_6BI zcD|`hzi<@?KWPjt(0iSz)*0~n)9H))6*wHer7$@<4$fFiB~jq>B73KP-G#WyL;ox% zH%r+C1;yvC^Ln_Xka4}a5@#nz;xn+fft*Az!OBSdD9rcxp0PHd!~>C>#eAVsc{Og? zROwl=-Kj*jq+Q%yQPXgefO?reF5#Jn^*Lj2US>`$zt^>WPB%mTvz~FrRxF-9cRN>n zq~{Kl2XwAKu{WAbo&D})E?g+nh^Bi@!`X<3%OoNItOnf zIHUtrQWJN{rE_XG zr8aBc&hgpxTLx&k3BV(s_c!*L$dN{i*#cvQfh@ORAEPjlPUKXeeEMNj+K|n^@*!6z z<`|F<_Ot1a@#t&ftibm^B*~ZsJ?BkPj%Ksaly3v4S?xX!91%it zVP?h-it z*Y`Ns%a#-X1atmsPg7?TH8JrBhj?lOrm%LaE7Desy3}TXk+Yt!g^W21`2Dwhq>h5vA*lz#?NYKPqiY+vXl_ymPgR@f+LFdfMc zowsALi7w-tUI34nL*(CZW{zpjAjlpeiO@jHk;ql(70{Kv@dO^{>wF&!u!=O6*Y_}u z_(G=bfTg98h9#W~9B>_Yz>}|SS+Zr+j!wdm=N1<5zwdVa19ReVZ{}!IoppAj0PvGL z=id=0n>vS=_Yd(^(^Qb<|GWSWnNx+;jN@aP;!-BI$n=)uLIK=$LTV0;!~Q4Dp$x=N z+jo_$Z7hIez3Xp#nQ@O9N4+Y##Nm%Xc`?Z%n?Ln1xE~0k*Dgh`lFD)D#~o35-^E%> z&1{Qsd2ynS!z%cfTF|X8?iTOQ!Tbm<^v~tvs_6ZoxBZs5vk$lmMtr)!g>#fxQ9E8z}aRRowsj{W2$j z59L=|-BO`N^8vZ`=M~dJ`_VI(-3hFCnWE3ZPbktB>2W79h`@Z?+B=_A{#u?y(W&Ps zIe}b}B62GB#OlPNz;IfTf-aB>+e(~Lr*%|!f2*wstDl)F>4!PTzX`M!Of#q&_dsx94^2%_IfacwzqKG;{sB`7s z16-;;^vGp>2vDue;d)Bq6X$;XDzx21rFllCS9YF?_O`&?lg>tnQF(q%t1DIS`tuXH z`RB^fg&u$2?atDAXdxeuf;^HnZ8x`>Xar>?#8tI{ZeT)VCq^tpHVwach#W|uMW*Z|h(UBSO>;)} zA?R6WN%Tgm$#~Fr$CZ+R!Pz~iu;-SXIZSRCx-!X_y`FVsuIXXyj*9%zar}wtH@y@iC9Rxgb`syJKc^mUnT-$t^dadMJ zYtrmOh6H}gA6Xu@?fZ*M^JVd6t_Ctlfkk_r!=)LgQ-|K*1j(4oXC8Ts6R3yWt9(+l zA1RTyP1sn28(^mNjU@(XzGMaRJdWnVL4Z4p+yT2?ihTXZG6QOhT&{(BJM!|2j3XS@ z%(xw8R#g18!#_uwN9jc|sIBz8B(67GDC+TbET<|TeEE0)-5g-_(fXn%*yybEabp&H zVU7c*vB!qLj);OFG6#&L3}nV$5&WIU*f69~kI9cuXT{HH^tkHRk3+kZ^Z*N2{eWk) z6vRFZ2d^!M>}r+TPIs3yxCQpPC~ z62NzEIJwNiC2OozBgWp84kL`zdWjusdCD8WOE1wDwYBtu8iN;J9M7i9C8!yc$W%oX83?8mpy_*0Hg(R za9q;nR!Vc{t$b1W8}UhD_?Ie4-{6tGD(wfY3mSsHJXbn9210;R>+^W8T_9`&dDqxS z+aYuyP9i?}YkS=pq9UWdo%b#!Dk zXD5H8F&V#R$-2tc4tSBO?l}#XaliB^ts|ebjt7>dQY%{@Ii611`b34f(XDrm zTfg^I&{}g7U25v8_97wTjEv4?ymP3tkW6^UpUU6fhyJ_6)!p(XSAtGwI=S%!8ged= z=I~7Xk)`jT*5%%mRj`2UGx~B|Hh^NTRsBXQ^QzAdvwH{B3bk_B-}}31Tdf2fCZtb8 z3|C4Nt6*bQ`)`LcZEJ9wvR#g$Ff8x|kO0j&%y=EvhOFG5#M>Ul|o;*sV=>cY}1p&@rUa-6+jSNH;@C zN)Di)bV-BK(hb8P4Fb|FAPpj2-{bq9b3PV}pR9@J-utS1?^BOU`jSf*foMwaD1DGs zkwwS_*e7Az9PazJYTMk;`d z!u9klWxX9-Cdl5rhPM-qjMk0P9@rMayFOQ{<;&ljBba9JZ7${0;Q|LEUn@-_6C{}{ zvdYf4uiar&n4aU$>RP%+wGYPTZ86w|vp(hjUJvTA!kusU9c-oQV>?jxx*$XCp7#g5goFgN{6 z>h=2ZWurVl!SApOjomfCwn=i5(0ZP9hXy|GZn;XvnOdK$n6QnV))v3EDgf}rsNc}B z;l%vWp;{vn88+}7^a+w)@}wsq$Ir4&+UxnIN@j;P$p&SB;y}6IfJG0yEcdQ%UIF+& zgI8i?owv`6U3zR(jK#7SDp`qd77xh`NV`x8Pmf2>dJ&&MM49DDyb-{J4$RaBorAMf zr@#l?X8GH?fD-mX@0o#}Ik0FpB+P@~wTUUXS$?zb7YH1{I@_oux;T;DVqK6$bs?gc zJ4zYejl3$dl~&g}Lr69i6OR!x4}0pp*0qQm8}kFpsM!_0#p`IVp5Y(z<6S6h(<}Nh zi3QUvPw6#V36leT&w46}|p8a^iBZ zPE+%>ZBu)}l2TO1yfOUTi}wYuW{;x#s8UXC`dIPUb;6b5O!~rBNHCTPT4n%`hBuAE z*9Vcl`9N;H2{8qxw{_MZUP9T1gfu`TP%p;pW0WS;=Hl~~D!JWl+gmwdT3=xQFtNik zr+xJsztHc!p8)m$y8_cYlGi<+@HToL4K7n6|U`(qy42B&66j?{SvSYUw;g zxCwd<4T%$_8?GZG2eBPVE<_;h8#?6hdy+`+MovdPCVko?+r22|G*>FxM+VM$p^7-~ zOFI^S$j1{Xu2=^22aE$vhocQz%5gsWN$Zxka238bo3@Y~=+qtr^y0WaMN2ZUm6cQe zan%DIo-o7YSsdCIeA!oKPFMEQc^Qvd0Gp^hZ|Q}de4k%ziUZZjF73NwKpdpUbKBm8Xa4|xEW zH3gz768)B-MS5x|SLWtWra`YPz>_grgUYT!-DN26;E>HEfI)#{oYuvds+}O^x5yUP zIx*~udDYz`(qH6dmI0P%SmyE~7n+_s*47U;_B1G@j#MKDa^`3Hi3cbiq?^G7dZ)D3 z@87xR;N-XnDrc@5712A2+e8I9m6nO3e+5BW!6W#9s*o3^RFxgTwG^leLQVLGseFWn zskgLX7kMCiSUMFXsg6QZJlVlvB2vW#P0acmjZ50R8+OwjnZ?d2)lF2esVQ6#_SqgU z&S#Wn0OZyV(Y}+ogBWQ}-G_g*~=IinA*8`VF9mL5mZ7-E) z!HJ)?7{j=&@e%3!>W5b$jZgp4j`$&ddywJZ)Q6R>wax;hXnZTa7|xxhJJ$64_c>v{ zdj!S|nu#I4sima@Bkf%d%9OpoFS|+KINhe|IcaL@c>l9W)y|~XUE(Hya~pzrelzcA z8>YKZAPrKU`?R?IuS&4nuNf|X`JARhzUdwg>ItUyXOnJq2qmq5$W%o;FpTpD7=fbV zGYIzwweQ8@jXhqGbHp`4rrWR!OBW9{F;*E`F&EqZ4`Q|dWFXuELHu|2cpCDbV-&r~ zaB6^aR-+)oPgbL&qvc37{!|M1S_cNPC z?zTKow`@H?cQf$?Wr<9dBcP>QE-R=~JUYCZS$%0g66ACj1c3dUrd&0C;!M@r{uj1F z8|}Hoz!Im|tO~DLpH2J_;azFVGzxl~?+ge|vqRm?kI2v&xWALeo8N>3rkEqJ8!4`h z%;&15tDjldYVz$z>gne`>n@b*pvs|&F?Y>1WlCeb);Fn-SC(}~tN{Yv60j5_FYWAG zFD``9VL;x|w%e^5!I~Pp0!t>1zqdqr6!7MC&4vaPEDID3wb4Yp>=zRTF7m0sg)NeH zZJ`$F*WfKg^C+X3S!3s#m0`PE5x*Wa{`pB1UbKSVH9Tm|4mH-D$5$<9tjOuA zf}RDL3oaV@gJaF=W#W2I%|*(7&;a zci-peup-TzHI7aKCF(OWWJ?MaD5-;Kw-h5kUdpgTBRzETV?oFh*gL?Y?)coRKVzBE z43d_E4Sl^{bO07^^ULa7;J_sJHZ)i$XUx{iq@X-<`uS@5>#s^z*ck#I1xbOa?MNy# z^{Z~SScsiRW9`I})SL*aM$K`6$FuUXPHJ+>gw;-o;R8JjQ8dkb_Pien&;O`R^u4s> zrHvKk11&h%r&g0KZ*KVPe!$zMa~SVh&Xb#Q9S8b#ed>_3=F2v&nY1XS26a~pLb{*Q z<)#H{{9`9VvCfn_nQ9cswpfZS-gzJ;jcFl%h>k$VcBv%-UD|4&mfaEdi*$JB^0wfj>Zd9CTkgu7KXnPIrZ=_K&qP0V?N zP_nJMOOfQ)@a=jvWx?QdXxRr)AGT;pa#o%7;TBk2x0_?7q*5>RXgxIOU{y@F;;rtM z0oUUK45!z*r&+Aob56coI5BXe)GWoHUJWugto(qq712f#WYq*2!qDSy#h%|x{P7s9 zBcb2o7Owou=L{M4C5$J0^SiZAxa2Y8NBc+lfYsk`DzimIw=*rR?4LdyncCh`{*yRq+=OxzQbUuy5gJgEGA*{+vXDG23W#lEP}>5)M9jJK|Qx4c7ExG3IhEQ~>4 z;Kz;M;ffF!b1igZg8AFtasUw#Dyfg%psgkL9kSTr$NR5znJl4N9u4cqy?F=ir0&4c z$KxxM*x=Gmu!RK+#WjW{~`~A(ioa;5BTTwUkOzkuLIRn+n~&xTB8iSz5r> z8$x^_Z}Wik2|rL|zh;Gp#MwNH@TcV)ffMIkHg*IJkx~<3~B@ zI#fKYT%@E0%K?66rzxWH`3g@M*LI5J`6zlPUz`obb1l472$lj^D!qXEY+K?a$VYFs zfH7bTcU+Y#Hq2QiiI7C^sjtf`n2+SsKdW!;1?}{b;l!+J{sn{dvEThq59W>u!e@tQ0=c<#g1?zEV;o^uF9o%tU>lZ1?Gq}&&2DWE z{dr3*|6C|92>{v+Sabi=CW&q}=zGooh+2D!Ja%Duc2JAYq%G2C{`2l^e|xaAwn+@p za%4)pM5y(sO*ILveIDzfi2N1<#=TIG)a$6pf*LEQUWu%NR#s)_rfsvDm9r?t%;;oGmEzK$GwZ59yJY&x;TT_7Ct66RTRK`aSk9a1j*NUwVz- znNL&TB6!TgDI)nSH`eICl_Y+HjbW<>Oi+0J_No;v%N;Lw?4w3}7q)6YK#dOwa00KI6d)su0_}GT{{=PW>4L|= zS5jjyotBZ2;r}1UH4s=FBxKWLo=(wxS*jcCuKQ3BU1E>}NxD++pp-~GEwJwqTelMI-~;bRD}phW4RoR&1w4DMlzP%g9iJqI_A?&J6H*Rne#oDM`}NnIn|2U}Oe zoF2V(!H$MtUA$kac%XiuH{oM0MKM}2)<@#RKXV}ZMG%prz*&YgLJ#x8ndCBAiRSDB z(M^D;2B?%G6qokYpX4nnECK}YawNTX2FDJMEhTa?+)|{15IQdRcgimynR-!mqt*EM zC{my()%u_h?^W(K08!c5eW@DwLGGH;_&oR;o9*0Y5{n9qf{`eX-rqkl*y;QsrFF2O zL4srJRlYu_wyG^w%a>|+wM<5cv55&G)>%b{WgpvA0kPmOQ;}cuzb_;>X_~cKpa0=C zIJNO1j_USa2yxTy`QE0#G{0hjm|%WLAI;cg!ehTIMmLSF!>fZ$esB6oH?rIrdX87| zR{B>G@-MGig#k`~!C!dM9naoNOWfxL)L2su)6+ayBE_v7Y?)_qHPqCa1W7erTlz+& zd{>H0#@^KzlIz$ZE69lu^cx9OGGJ&UQ6TH6f%jx| zTvvuSWoX?t1Hv+7Bqy)rgotnX5qIB3!b!4>iMN3$huq!Lqt^MyW_0#!&;TqoJeAl$ zu#^aG5?Ly&8wuD+z7I1QgO;%L@`P}`^$$r!NS=MOW>b@ue2)bk6!$a)|Ge~}&OT%1FCtYIj1nqz{Nryg3O+zehAFmtZBdR;gTcwD# z=Egs8d8a=)Qw4EqTd#T>qY!_@)(P1e6v2&ea0UL}wLKrQAKm)1SMkzq7o&_U?U6W?5hGAZ|}z+Yc6pq=rI;H7~?=V~L+15czig zmzG$CBAKTB-W&!L2_W|EQ>k`$I^%U|J+r%SP{6s(EC= zthus5mxoI2UH&WPiE29@@x3Nk(P=@Xq)V-dj)IQ0WM{JgKjEXxyei4)FOt5>j91nY zzNSBg+OnElUCGW2V^~B3Y&WheUOcOTb2MBrzW|Gho%1872q)PFc@gJ1L%VZQm!(Rb*GHJ`%YL)W-wG{F2?Qj(M2I+_aTSed&S1U%oF zPu7JRURhi}Fo`*aL47Y|gB;b51TFXTe$E)kFI4*;quRfnEu7YWSZi)JyTDE{5<8<^ zulLFFzbL%{lt4=&-me0U@vDm}{s2;9>@YP0L1T^ z9Aw|ME&Bhu#8cR9^3ZoEg!@J!Fb9UGQ2$w-h?lOrjrF)TYpE^ z;h_>&wYcOryjx!2fn_k3!97^1GL{~ zunuxM!2Z}4D}V}#fLYU0O!QG56M>2h}S5Elgf%x zJ0N(G=fb=YfSe`_fr%s9trbDhrxsw@SDpPZ6LbyD4o8GHeJ*$|RVE088aaH^_Fkmf zHV1jRnxIRH$*F+ti`(Y)M+n{?a5}8G z_vu!|svFYAw_0~lRCg^{DsY|qF7QmYq+YF=sf&55;eyT2#9wyW!X`C?_aAm)DW#ct z{U0c^^6zanNxI43lOmYbV_Lb~j<7#pcNN?!B3x%X9=B5rN+#y?aDw8 z)q72iWla_f#S_eL(e4c_DniPn^IQLswK7TeZE9?~E$bX>Th>+a~UwcfE z!E70krW@98Vjz1p>I6^F%6vWTKpB5X&cVi}wEEFP|B8K6xywu(0|T1nvCwef=1D3a zcedd(PoC4{#*)hwmqG9HLy7M7U}64pzPfh{Nqf4PAS;fIOu~-kH=2y!cTJQcxwV!t z?ja9I65W37t7*O`fw+Qiez5YlAJ$vKcuRF8cTuCd4p&|_xlj|z{MD^F>FVgnDJ(3s zT+_i@4!K&XXlk~6TXoEnf9>ji#L^}Em$2{Z>aG35%4}$Rjjzzo+g~R;J|VjQ;Et{w zjW^Y3o=i4e*#F-1a+iO;%KCPZ9e-R0q>P=^|4;g~{nmSiL#hq|B`M+cw@}T0nL?Ad zv9Z}F&A)z;!y*^)#?^JZxjXk=vChnRUZywe7F2nr)*9b83<1n!cvJ0@JeZ5aZ$=+umKMP7H*b92-OoqM1 zv9nl>r6z_ynyzL?P+%4U_LSE$dNB#M^7w6m>;AFB)`eQD=I_cCL_HX}_Yh;xelhjVcd&&MxdkMo}d3>Ugi2|2`dQ^$m8?pIQEbX;fK^IUU zjOgzvYd?>){56@za0}6}D;h_46TfzIt$6Tm+LEL*&YkF{GIz_Wg&3j`J`33b}=3R#&H25UbQoCF?V=Te17K+rYZfd$>k%1m(xw(=j zX1zJJR*I~y7HGJur#H~CRxb0y@uw37Zte)VFS9^d7X~Hl^%^t+ge*qc~tdXfOl zc|#ICn5TnX5w}HFX6Bixxk>P8l+;RRv+Iip6K8H(9|P9Q1}k0?{#4L{wYFU1J*UyS_^)dv&aP+z-C-GShcN$}X-#VAVk$x+B7w9OaE zU1j8%H&8MuWBWdGYRcOzQrUaZpHjm(!cB;jsFW=6#6fDxbwD%$E{{19VeHZuMo{iT zcF3)XRb~Gz5ZzM|W=zeOnGX`XCF3KZjiKS2sv}PP+=RqKun(nU`C$R8r9<$H5%N+w zffWU}BrqgqVO!ylj(2z3G^VrR+%y+W@4ENQ&>#!V=HX}E|-RRr-FE9XP3)uLzsZ1PrqBBrQ=Z5U^HCJA_ zlT4`5Q^S3qR2VxSLi1Evy~ZWB@Wy4^#lZ`>g={;Hb{l=~I<7Yp?nHPKztNv0Q*Z-2 zIY|8jJqIfZy7Xp?PfEO6w{!>1tfc_wWHS5o4($>8YM5A>~IMmF1MOw8an^cT_3MPFh?e&9?sgU zhEb-`fhiFQ?y_1aClF3k<4rY%AZTFZfE*PeTAfRNM(4Hm@7Bp7b9}CYxzHHEAY!Me z28WpYwNyU9b*+h**I+rW)aS9*Ut3wYcs_^$dyTjujd6)o?pbHiaCOBb2utl$A=^X) zC^a%}k3mmswbF5cXKvJBg9#EZUW%iwp!p%=+4Wpb&QpG;baHYf_)hMzbzGA~o)jwr zhnc_1FX(NRk>R(W>P9JHGmA9e8o5WK${U+5r=0Tnvla(Rf?OM;SqpytjBaBd!YiNu z8FJuMwb(|4MkdG`u`qt~_?XeFoF$W*lj+fIRTH3K-#Q`cee7*N9&+q$L8S59H?m9% zOz{HR(io}Yo@w_yNOwJ|(yvs;(5QsPL}%BfSJb#ituD&ex1>qva6a&L>HbVt(coDL zRB;Q$Zq{Q+4P<_MuhF8D19?S0IH16EOrvxLXnY-5`^a$}7W0uMPQVhIv7?=g4s(7h zzNc`~&%A9-@Gj#IhGcb|tL46pc0Ui|g#7EJF@N3B!BkkWuFdA_B$86~jo51TRAoEq zt5Hf-c?nSX3D0d8x-y#ex0v~IIEzNDqfZ*-CfUzgFq=`6F&T7b?DyVbj7#%nI=l8b z@0oR*PZmT}6-s33)WM-TWSHvYo~Iu={v~x3bt<-T!z!IrMEBQuVtH& zwor;#Q`I)MMvS!O6W675L=ZH-c!E>bI>MKDFznxQp&Au^BtAqJ$Ql!04V)gzaMaMg z!l47gmTo8OpZvByeP%!_uS}Wy7Cz8}jZxBS{<^SG!2oR}eC{4a*7F>;+#c&26R#Yi zzKOBE)F`QoRv>L;^vBqBU0LI*#++YBZ>oSxojlWYm(s(F|Ek7RF<-2u7fvo}x3Jc| zsTM+_hZVA6A%mW8}Pv7dv^;X6;ciwN9Y+;q`Z3jeQTk8nYpb6-EI;&}9q!(A@L-wFuGzJ$F)!?P-JLiX zMj4QwK8tJ)W2R;RCek6#}&O@=Ma!8AkP?qgft?BZrqrY)d8Z>5_H z&G}rrCGF1H+LgT$T|^jmfT?YduhQ)c>21%GKIxbyB*+SQANMlPGZuOm{I>l?Go_R- z#f8NC8FZx;ue-ht(4-7E%FYy)mOR#qJ0wcL(C8)6pCz<{ z^4O6u7I1RWt-))Q<;(42pT>s?oqbhOqj1g(UL)(mFU*Se(AZ(9Vi_`KbFbT8!igC2 z1WTUq)*KEnBI?|%`80SJSF~ZQlA_BMa7O-Wj;GVQof|vRRV_z*u6`KX-7274<#XFWvakN0!&*JCtfV z9d#M%$%i@yRqJ5y5&M+AgXr6_F&?U$=)mKKgXiP&_=6q6b8`L`GM6=B5Onm;@oDul zJT$rkl^bvHXYS*!9`Ez`JNMmyHVdK0wWMhxncuqHgB_W_-$Rk149P66hBkRi$GP;k z=Q0KcwmJhOw;$u8O(VL0_FlyZepC38{YD3olI3jshPR^ZK%LilT=J4Ngu#aPL=zaC z&07(g-C}O5V39d{IinoVsZ5zvBtfEkm|%OpI_`ezw~DGi7p;j#z#bweh@%JV(I}%^ zB7l=RJu@mVq@Lm}T2OsBK(7czAF~(XDUh@kxnmeJ6F+-ZcGZA$Z7|RoXh;v{hMvr* zWHz2(Z*_d4Nnb;(hG)dqQL2*{%%6q!K4Ju6U#89D_mE2CIJu~Wx=G_0eAU}Ona!*F zc@-ckkZf`nbllLurm|$#v$989ESvub8>8JkRHe;NWcwT1wzWLV-WuW+{nz1bpRe%Y zn5m*CJcL{=*Vw?en?61x0>v%qn^#FbH`R2_L7ngrOg(NkTWp%j7*G3T8Qgk`KiD{P zoHO%%edpmMFdCAplLua?@^(=DYSEt7{ZMtXXAFdy)1Zp9_{Y7DC~to^>Kjd!A4n^o zr49(Y7=%K~^B_wTTKl9&r;af#C6(%Ik-5qGz(pnOy?JPal8`oNi$P!MR}(G+D0vP` z0>x9C3E^_ZlsEY*(gEeHkXpd@{yA}8fW1r&Z>ICavk>+?d3(AO|I^-q2G^B)3@sS6 zL!1aR+cRuk9<~=Tku^VkUQmv;iS3GE`N`Cws>2B(1vA0VLOCm^K4@~;Fe-4p@}%3k z$w>gIY+A#qgfEd1REM~*v?o7?KCK8}>3Bh$pEh5c!!Gt9s~397_zF=wQ?4$Hv$*7= zW)+?ROAB(bwaIW<_DckW8G%+39}RmB6P>50Vu6UfpF{i5@mEveh$>)3Pm#HY5N3=E z9f665&z(a1;ejw;g&rs7dme#xCAncKcRKf$^QQ%tT!BAve~(;&LvH@<-Sg9HL635H zCWXfhC!t*4q;P~>mZy8d#6$Hd{Cnyn!7D@08k*Bq22U&A&j*W%8r}hU;_|K)oeGuj z$JYFpO+L(!#XZfHVZ6vI!Qsy(K?@f8S-#Yi*TwNpg$}taN9cu~bbAi4rNj43RJc_n z?R7kLcLIkG6d)KTk6Gi(L&tPX$&q;XRb~NPho*E6=^QV?y%kyr|1eZm3g2(u16tmP zv$f9;#v|;cBw{^q1QU#t5Q32^uX!&~-gXD@B-@=UC5%t164rjzSi7}bRZkptFKLk} zm`~7mk%gcu?dY*`V&G_z4ROLb|E$Z$dH%C@3MN&xqOo37nww)@hcUi`lBkw{nh8!C zQ#WZtYohT%vrP@aay07kLz;jzya=1pu8c*Gt=gG-_M53dhqCy)Ha;=c^g&=-faSxzTQ;e;zL5(p| zEpsq&wj{>yOrA}#9ERL2@V=I6Q zv0W#wb2Qo+lly@?<3#tV;8i^WKy-lCW^hX)X-i`KbkAq`Kq4d!7uzT2!!rx4y@9`D z)Yz;}8ea*@Q8St~gH#IX+&oOJ>Gpc{BI=3}f+5!@uN%bTAAXAv_j%F{{`<{Y-sr5o zf0tF06R13^u4Lu9Ez>1|w`_b4Zkg7k7ta_ZT5~*KO34yg6?|38Wb~t_D(X8R5-D zW!63g)wr5IBt}l!^CzrtH>fA>ke|#&Mt%~SO;VFM&w%XBne|?p*oR_E=k=bxx*;Y~ z%E@$%+r8WRTC%7D49qYCE)t~M3l%YgIh3A7(i@O^TQ}-?+6(n?JA_{F(hHFp;187b|R{N#Ugwu_MXWeUHN% zv14Z*6GxYr2?tGh_?w;tlICI4`tq4P0%=)?U*$Xv(mPd#km7d<=xcw)JzgmljaPFu zbVt)KjsICM^n?E7S;tu)0bZD61vBaMydEAiLy`Ri61lXq^R`U$4CjHudaZy?X2{?l zQ13GPnHtYvD*tpuPnXB?5;Xqz>6i90vr=K++w zrXHGDpQTw|v|Vq^;Z?&#_j}uff>;kT0`*O76VH^5sPC=cDiUu0G1a$-3*pH#4DZE1 zQ+EBr*I?EjeEjJab|I<#>E3=N3;gUWLPTpKYo&D*a&Ytr}cT#g(VB* z+3?jVuh>^aWPB#e;;b=w%QSwuzPoq8|KBr1SEkZfk`~M6lNndpv&AZ~?nrGF|LsqA zT``5yfYEHp&zhUgZr-{%$cSiq7^Vs109%hyB*BcP*}ku(9&rq^0gFcgp#ya=F$g)i z9o&Kj470sM@f7rU9}rA*_6E-I6In^=8=N#Sk5vH662wHaaU3v0Hs_e-WIxXs{xm%8 zYp>s~BqbpzF#NVFBMP(tQ$y3F=wQrXtxKmSRwXY+5+gmWw9dsG`Ei53hDpa;SdIN5KRLw<{d47|b1KRgf)i!) zq)JD~K~RPw^q`Eoc9eLTOLO#`Pka-~e-0FDn zQ<%|L@)AcPw7pkAPIg-vHh7mkmoH`hS!%pi(4bbo&XI=@{q*2ZApP`oqgD0f3pc2E zZKVL^nPif%4~0l2tE!hM;tADF?_+%%DK8IcxRKazi!Kl)#0@D1=>VSwR6XMCaC5=& z(z_;6LR*|-qLxB`Rsl2EGuY@;$6P7MFPlo3yRV$7uZ7841i?udJ97zQIn2P|UM(O*y@<7%OY_qEM;kiyo?^-cuYIbo z1mu$2!@&t&E@RlOOWn33qFTt^z(#=HXdjmyr-5-DP3WbICNn=A{+lY8SpE~m-}}o^Y0P6DqB;n zm@FCbbl4k=X>?3fhDi$fypkPEDapc0b<1hJQ4Icc3B2D-qG~ck6#=}N9;-6kZWCMb zy{}n(pP3+~f;Cn!52ux#2=K#RB=pimQldf;))o5RK|hJM2ddmp)k{+ZXVT^wxl^QQ z&$3PRYi2&pH)cBeGjZn|=5>c35aWxM_=T8yO0dA+s_4XVRJuRUNg3yRQ5NMOBYeN8 z-|nNjMQaO?_>42}^{zIdFZe*$0X|!(bsoIzVA#vQnn2!?VGe05yV=8Sz7FpNP{EZT zFJafk*4n^zR9ZjH5F;Zt_gNoV6`nPnBWcU(PGlOtpW6r1dvYUid)UmHb#rkk z$p>jJ7=(9FJ@wVr0IVy}we5Yt*WjWtf96|KuW<55hW~HKPEa(*wFQyKS)tJ5I!Uzj zb2gcpCuwrE6=pq-ts$tQT)gIb_JRnv2%U&2d|ww z>mJrGsvfPdk+7PdpXNnvVm^MUto&6al~Ob&fiGcX>%OiNksm;OTrM+}hcB)C4>k zYG6z-^1aciNo4m-+Ro*CZYr&l!=HZB6w*;sQ_Gs?4KfZRUCC#irF%KQ6?_9alSWI< zzUR)S&ChKn4)?ck<;^rLl9*-f*%c2e{}c>kCO?Zppl)^g*u*n^;`I)`HO7Oj>18O^ z5<`+;LK^wf^#oL()Z-TjT+mikpW3Hji6pdwVj1&Pv5EAj(HvsRGLM~}!pT?P+(r&W z+dROjjym}~Vgz{B^#Pj9>zw-73S}fjiBvA)u^clIfU=k1p3f287%Ljl_^VD?*5PuC z1!r`g8#=V^>3hl)`cjA(UGDJ2;pnw?!US6pcn8X074x~(ZSnlN>cutyf1w*LL2o(J zrc(RrK4w#`{nTFZ5Lo)}SsAi0VBD@WQt|3QH{a6wb?RDkUZlrxu4TU8FA4M^&g2tb z?z+;hrkCQ=c`yziYF(p+0=C(P!?nmn?;-Obp0vqbyu3rAhW+8geO#KqsjduV0Un-A z49vcFdoz0G)2&PgFRz@E@5Km!D^Y<6g>Z>^STZVlL_Z7hqdE_qbP;FoOwUosF~yXv z?q}gwgD8&uq}_|^o%)Y+Jo@JFyl_zK`Mq5)YcE<{tV2hVAPhUU0aaoNSD#~2hRI_7 zjL+KOwuv74vp`f37DgbhszbmL}Bk!?(u3V<^P;jDTh{Xq9|(^$(`D~QYU?0{w3 z=WNCCY+`r9TAq8{%?v_Y+Pzt|-75GRttQM$?^qbbaToxQgWD>5(k@Jm+3^tiz9fER z7r6`W&9EGE#wklUJKkiXh&SsQJ+?{xv)(#W7DAlI&%0@>x~+U1&m-~ymG_e=J5TC@ z^msLZjAE46_mQ-b0IdY}uH;g4-t&mpFCC{UY+7)$D}&(cV9UyS;aK)f2)_=ihjQNE zUVHD`G;)4NT?LgMs<0+b720LD&6qndLR`q#!#s16m64$rx+q|6@9Ko2p&c*2?*lu@ zYN;)qImVOD3kS52IYanZPY?@2#mPVo$@|AkjYdKSe^ec}1$8@qtBjVS(4lL6*SHmc zK%jm)w(3S9NTM1vEaQ&YDUL5D(CyKW8*FylUUoULau6x!wB<#$bQRY2?vDH)m;nxMQPs09EryG9Sr0IGJ(JIdT? zMoN)#>+HcdT8QlkRL#Q-jg+hyXDG(q<H>r0r#(2#tGVjd5VXDpy~#WzuZ#?6##=)|QFoCr zIg?ZSOuK|5GE@W~f&b$Q=@!qxIOKn?z@sZqNJ)kgG-g(zm*5SRHMJq8L^?^8;5#(M zP!iJc(n1;m4op&QKQ-*yDy$L| z3VH4pJ@}uJN9Jc9Lay^0YhB1%Y!gJvG5hgH#*uf|d)_qbBx*`jM)XJg`<|;-Pfv=8 zqpzy_f^kph8)WO`q*mw5%cdcPt_0Fz4s&`2wgN^*d)L6R|Gayan}i?SVf${pdZ_T% zg#lxU--XZk1!^_2EHOY4KO2H>h-CyC|H*c&-5)`OMTJdpbK7oY)Ay5@ti##sn!*HV zk2aea6I(yc1zI-$eK!lQ&+Q-Uu8v`Cerb)-^a^gDlKc91(NiCad zS>_@f5gO!Crzlx=B3~ly&mE0>7P0P&Wb#d0|-7_(k2RB{fY_FFpk!6kcE#K-DPVuBX_i$1iED=X`*SG{s+ zv9Fy6mB%~n(kyWA|3+Xu{HelnKwT3A0oqCx#l~<~o<_3f`rsqR_+Oc74DGQOUxA4$ z>A1>0-iDuUWq_KrL#2uKQYd_R_4)7lheQIHsMY z#AzK7XSws&xk?K(d%Z)bkK)2_Vk5(LiLTHQ(|Pk+2nhgYbE}dkd>2k$Atn}%|A9`8 zu(1|2?(66L_B8%sIjbw&CU%9%2ZM;vbx8GIB+Eoyfu4^&$hg(3n%nEJX8lM{0DhUdc0*z!pVx3uVq^U&?PktZUPnmVaBJEAt7iq7ZZkq|wrO{a;zV$4*uI}*VKSV$OGgxa1WSvxYPC~XNk zMAVjVk`>xhfL#}j<;<*X;4OSme?j+8UV8aq(y+IxE^24y(_&|T>;0d=ZPauW@tIs} z0fOE7Tw+z^)qJ-AmyO-zFFFr=2^<0G4s@kqZ>Uso2t?=ciPxv1sT#MoF({7Kk(iuQ zB(GEewnt-be;Tqr634HZ!x;=uawJV?9qdz|7&) z(>HS>jHcJO%JEN*H!HfIv}TxO0yXo;G{vDON`X(y6-WD^WO~MCPI0wc`&xhkWzy)G z#dgDuzzhQxBWB(TUX|iXI+OrTmM)^1Ra+U1p3`N=)7*Y@r)~OUX(X9D)rn}CGoJ$( zyyvEs`M`ZR&qNMroe5(t-OLrF&gw2o^C0|;STr#&T&;h;-VsALhWhJZ=IoTPod{^8 zENt*i&l}{!nEor)(+csU5q+T)eS#u35voiByv76A`lt2f0{ zDcE^KGYG?UI$vzOU1fk?kNw0jr*Qs-=Xwc_k!g>OP<*&;WL#`HHJW_!MeYDs)+@)P zohe>NgriuU@~I9?g=~@zlogU}ziR93Lw1LT9E7??PPgJ*%RGSu))wIeR9Sx{6Av@H zZaHa=^Cp+iZRN2ED9JS_R^NT@jD)|kq)qmdFrrsa_}s|=S|aCqQA9G~t{44(MZga> zXPQCJ@+N)RyNp{68)v;;f~3mKeYaCz&D4bho7;_KLzCHNtWS>?^@BRf#J-fh3<6iU zGrJ{lT*zfgt?g2q+}1KJB3}A%3jsnLAqt`KKWaRPvi`+YuZzKX#=Ve1?wDUL3*9_? zaN7PGfa&|H^9))INf%iTu{B{-so`-#muT#`?5`?02UsJqsfy5<-ecZGKowozOA&}d zNDCJTp`>*$m032qz_Qkx=J4!@PgMR$0@N;~K16n3!h-X~t8y>-7#{x-Bz9SYK~E`= z0X$IT;c*HaDrd2q~>?%OGk2`ig_$u8GhmY?N=V=bT`eb4H)rCQxe zFPxW!vH{r3xOE?Urs|75VUsz8d?3LxKy_Ahga`=G<41XH{<7PmNZQ&1VMcz!k;WTb zFoKiP5Sm9^lOUWUOf9g*9i|BrE4c%-R6t8`%1Fb;?+)Q7FBU7R@*uQ*NfVx4Mgg6F zh`W2C0S6SDnajt66!p3uOdc=Vq+GNs%|BPr%XSO5l-aYVN7GMO!%3t@^yO0IObnbt z{}1%_)P%|KuAiDSfRC2DOTm36{Yii@OOhpUof0SPG~%_TxK|Cl36eM4bMha+NfYnF zd*h?VDTCE@^`%FQW9XCrx9N7v*%{ssiRh$0(|e)j@q?ISa3aP{*1^oY>^BC#UY)?;w^dp!(j68-b*Hy&Y}(?OcF}>(nbm ze;5=jE-0G_ogpp3)!?J{GwCOR-6pEpNmX|<0P3oPvfdcM9&BA-3bMl{kb3lE!&_Ix%=@3a49d0{RV^uxs_4q|&=X_N_eABJ~5W z)2yW|{o`1+fYq3DDtWIb07BU7D>2^|SE{dO^;4}8+a<>iG9Vv*4wC^x2&sdRNWqW@ z_}erotHzjKhS+=h0WMx79LK8xWmqEB((e)CN+i@5Gx|@`3z5$=#6r1r_>ND^{DoYG z%$*a&_qm1NO1WotH9(uHM*a$cp{gE!rAtSN)N5!A6+Dff`a50zQ!D5kUVj&^cB9IYGmQitZLANj(EI0&* zAOV6~a0|hL1b6q~?jAh2y9ak?aF-!K(7_!hxVz+Qp7*}@e!rSw&0^8r=Tz<5d!H)3 za~f7n(GO>Xasyg=R@RI-<*8{>C1SYtBEn-Y=svD%GJ5!yg?$@nU8SYc2Q2H*5&$ur zu48XAJ*qI}(_xjs-@1c-tJ;BucS}0*J|pT#ICAA0qtUDPwD!p2%U;J8c4 zeIhg&B1AlT(-BDD$4lhM@dRZ{j8T0&hEXC!9Kf}wDD6u385 zZ1j)Mfc2bK<`XE0NcfK$M)R@g;kVn-DEZTlFt-Sv^(k5#w4>}x1VL}8qn{L#tv>8B zj3C8sQ^``a*Aczf7H_^L*VqfJuDV)L`J9v^>6T5zsSd2hAg(sTQ%CcxZr35HnufXi zFfKpowjG+s_g;=)X$Zy#3 zO>t@5sc{FZv78PEWDTs^e*TLk zg90iJ!AB54i6E4p0m0Gt^XAirB_5ovbUX2-OI9jLp;QmImKV?Z;R4l&lInDF5iB66p$Tm{BD< zPfy_2$?WHXJpSw*dJ909kL#V12#VAOc1K?69nT`VZ@ROGfWh(d%754D=c4J2RO3IkCWp;dpRj4bB+WD^>v6a8j zb49`Yi^^8|l{IkoISGNA!3$>%8<#)WAFc=QR~MFw3>x;W>>>GM+3!h=jfKoJ;WG+c5Vk+i8i99RWfC=QuOU=|bM|elahX>vQ4O9&Y>LB$%UWFZ6a%jZS7XVCehHkev_u zJqtC!Gx@R#aZk(rlP_9E2M#sy{GYcxF>*DA<1Li)C;P{}OMEH6Z)FpL=Bp$}n3{3t z+o6QH>F8=3!Tek!Id1xOm8mtaT!z4$fi5MFT$5O*den7w$37#o{yg}F>CVvwu6r?_dS+mi5Nb-*d`0@#b$>Yk$ZFlCag%A-sg6;faUD|OPB<_T z`!2=140&Ka$3w9{?~E>xi56gm6Yn6(tcEFl&vv3Gkz@CUPF3f@5Y9+wN`#LHoUmUs z79Nwi6BPzb2{hdsgv~DPM>){+Ee~=bG!_-wY#;w1{-Jt~!r9E2hi}69$GBF$Y>SW? z$KKfH(|6eBw7Rdb;~W|13#PD{ONCtB*KaaYet+tYyxr&3lR51^K{^pRCD&UZ&hLww zgeMpvX_9j=0}h?yIHgU%0LLo3fz&}^8ClB}ekNV1L1?2r{V5unJi%A5KNyfhY23=1ej))z;#u~?1y?HxhjmEFqaLy-mRih*7I>NNX zNP;-NZ_VY>2jUU`K9!cT)cKp&uExshhB#URg}ZtADjOcY5*$wF$96NuDB{^L5uo#Uy_%=U4yj5}h(!L68}mMlg0zdVcmK+|~B^#N^>O1O42OzR@i;H6-7?gS5=6!KwyJ z=PTK+ezx3xZi|F7hUnKX`R%sVCD5y)D!Ho2oFyX5LxIF)d-s}s1rg*KX`Pn1MO#n$ zmWbY~_=&N}6xTFnM^l;NTinj$)5puDz(#gOfi;Wfr<-G&U)Ovi)qaq5La%mzUcZ{1 z0-J{kVw-71|4c~B{R>qi4D)O6q@d<<}PWxa(IIQLy;oWLH8XP}g^FE7x-zGl(yeY2}{?5cu zoM~g5aNF~-K35;QlCeAEWII}|WNIAt!Fimu1_J##E3z~I#rlKr zaQZnYUw2|+g>SQ~lO@X6TJ!PpN|@ z$`KRYt@gsM{mDm`Y=Ct2t1OuU4vEqao4w0G&q~XnlrH7Z+aRmnoSv4U@Z3GHeU}Zt z1zX&L8}|Yq!I$$k8{z6o=DMO}MwjqY6-+_BsnQv1a3$qV+6%eD0e3IHnpzvD%2(dd zWco&Iw`>D5<;wJ>oq`b6iATVt3R-u*VnI6iTv5BLWQkhC21S+ zECj^({#(%UWovy|@|VD2pe|)}rCU}vWIVf=h*e{PNT8;zrnWl4M@-K8dV=SK=526tKvP|Fav`;unrVwULAG_%Fuy%67XGcDJMhNDc5ioF{o!JKc zVm$Qc=;vv6;BTUA!&uD1#utw(FFS4DwDA;)k=pksve?G*KXGrWvT?r=fiKf1&guhH%miCY zO%Z5t-{rEkqBUflXp-x~Jh@IWJ^C)xT@AlV8xE0qUCpyyWI!{r`zM*>wQ2BVzp zUj2FcXc{C;SWJ6CI{0q7&&gHLw_g0kwCM+5-IJ?I6d-ptJzp+(aEZ5DIO#P{@q7 zoH@QB(Zcv6uw0?tt!@!<8&``@>|Qe2>2e4JJI0u^g%;+vb)^eQZl&cM8Z1&0KzENB z>Nj<@isv^Kf4dU@zHm+#B(Dv4N>RrMJ7U#j0{A|*g%PB{lD-%^+-WGD!u6#lEihaI zl}y9AK!^koD4I&6EVjSSqs7q5qRC&;1i0VU5?skkOX7LJZ~GZa3{cmZ$hq|XKy)VB zXi{2q%ialJsEH{00R|wdSzBI16c3ii(1Kj^a`rt68S3xzD21H|PvH`85VsxHjeV_d zGTN~82{17zk|#er4S#d^B!WX#y$c1sPZn& zfSc;gM7iAGY0)g|?Z_Sp<%7=V$mhU6X!0)V8s?L*2H7pjYWj@M^19z^3#jr-*zHCp zp^!y=yemKxD2i-{U|PI=^{Cwl4vku5Nzl_8>cR|~9~rTsuq!#RohkL^n9IF~Sr0nS z^ANMfW+m!i+BVxT>m7T;Dn)w+mZo<(xH8~ZSU&DK1{|=`J-dXM!?-ec!l_I-wnU3i zzWze57+W9-`>pCBpXD}WtMxLNzU#SWfFoN`d=T%JRcS{hrJ(4;z-oM_;=$WMmFN8?nGNJ^L|B9KXj$x4=H!);>U<85SB!rl0`WQ>vPh4M^~0vvf7gJM|TFfTQ!Sx{2o| zL6{@0YXdD-;G<}OZ65c$Ep7b-Zb6^;{4_og1(4eB0l+|&GfQf{?L~zBzXTJhMc%8G z=NISJ*B4`lFHB|s(jSlws>|!&M|r$US>ikoP9gL`xBNQsA(j&r|Bo6@L>8|7?0KML z*v9RY+qbchKH2^c*}n>Pw*)uhdhSZ-sxJq|U)6h~;nb=X&v&n^%DxB>#jInf!m6AO zuEO^Q3sP|mybJ)C`{UzJN%r(c#fjm@@t1g*E7R>p2K%IF(74*jM|8gGkjAvc*BwNs zr~*lWX9Ep5ao}ynC=7A(Gg^o4_a7Y%_+d*EcTrLAe61M|ux0`UI2PShU69Xg2rm+f zoP3|;hN#gj>TO0+p}gPbork3-43Ab6R??a{r(0i^c_J+qiao?Cgko=J!o+X|n3(Fq z0{MVW+2M$~F|7hQe}clx%Q@OvbN^l>%O}47i3NtA#N1YC* z92Nj|y{Y*ZvW`K{%8*%~qfFyye$;Kj0RS+o(P{5XpkqMqXwS==cKADz@3C}O9le}A>+p9{15o?S=JQh*N;nGwMHOSl z0Q|b(Z!ld15oa!f`5{1FaCW|NmI4SWDgFv$zAA(jY=v^51NjTEm%h0jRucwu+d73% z)yEP2OW>`j7}m{?Sc$Wc)LHn~>kA+kU<86eL@LDCIReTu3dD2NHZx3gxyIu0&seXh(dMlO z)qJ=VZnLUspR8{0Znt)($s!~Jcg@Z`9FIY}w?V7Vt2(;A$DGubzI|uM6kd^(iEr9O z_RFf`Yr8m`s@uKg4c-plEUW!q9h`KMnau zIB^;rXw#zCG^O|US*r#W4MO7jm~}cMo)^2iW0Bl4!*1^ti4% z>X$G~e>di#W%o2>{X@{|P`h^}>#_UbaeFAl;c9VB_%!F`#M1LbfV~|Z@={yk*Ldl~ z-?BbqA~cwUe&`HHiR2#SrLf_v74Vi&%?P4B_I^Xw8AVdXNuxIVu2vMM?!t!`!rrLT3$L!Xq z^yC;ZwRQs>3Lvr{5(kEyypo_m?U``uoI3!2ZpPp2*4&Bn8tf|JX+z0|L=p0?_8{hG zY;jzU>%~=qLP=k#8#X-}D$e^}qHu3$Dt(t+ISHeSuKw2xa5U~A_OEX{$h7s(fWyxZ ze7M`C;c3Ft!}@Nn{f^ZI6_Bf4pT3D2lHc~V)msP0LQ%igxB5M!W_3sah|?azuHJBY z!AUfUEaV1mm8-t(Ix=YY_BCjpsUFheU@wN`ZvX2dJR$%qrG7MV*mykVdf&6r91%)Y3-G66-7?w?D+B4CtN^(E0zAM zA5md7cGUHDFhgk{G#IPOGWX9-Jl%fCGd=)q3*|##?p#Wo%P?{f@H(4dYl`g^T&}ag zMHzpTdS2c+unql_?x5gZ-UxXALqk>ES}@-N+n+r)On~3R^dFrEEx}#@AH0T!)vdbP z{tI9{Ng-OlyyOMwJF`b&u&doF6#0K72$PRuOjXhc+n+w9%v@H4DQgVk0r6&gsB;^X z{qMy7JS2O0<^EczX*G4Y?Pp0l#5JZ!39S>h`5kh#Qi6ch#(15YLePQ6KpDC)Ti?HyN08Ca(X0mnjJbTcA!uGHxq)wF>NpZ zCU1}S4&u2KljfE43@{L}`L1*Xy z`s_K6KblEXG*w(7BiV`G$7E78A&EU0C7r^q+cBhyfRd{TlJG9!L&}6j@E1+NiS(|F zu35}athL3UEP;;sMAT28pBoucDQCHpMnyV-&x3<2FmkTJ7rHD4k;|@P_L%=F{>-aR zWa}S(4LQi0P`~3iD+-nI9JCfXS8S4rRk}++hKeJ#I{y%VSNztrQDU>Oi0rgEpVk;R z8-di)Ng(~}z!c#=|1byj>R4~$LH}x^`046K2bra^$lAKf99N3;@Fn{+=uP5CU%Tl+ z;?(p~>V-gZ$2acN6+gf620=kPp|R19Qi6Y0ujt4x}}RL0JMAbTjAUP7RDP9|~)0`O@@dYrp@O@@=b9?x6GYqs(I9 z?;8UgGhSQjXpJbB6`+^m5)#iYkN1e_BljY=O#QtbSoEn?Eeu_w#*|8Ad$c<~hTT=e zF5V_x9^$x{&FdBpT|=i`d*oDZi`dae}w0zu%ay1;-+kH=bLO11hWf2y{T(x$Qtj^x(y6&`A-iA!&FX1p{Y{f9vayI=C zMjGRU^Q=BHfi_Pzl5H)??SM69gPIoGjM1{5BDktRtQxG@p(i%<+bkAfcam0!pZ-%f zT77a!Yl zdzMhZ)QEKO9+sP^)~=cZHFmigm=B88r8XXT3WP}EEggt?IaLo=US(|lrhoGyjMq=b zx$=*$-IiV@YU+yC8jn4pxp$y~61$UH&%GeS8C$B>j8Fl^gv*GHa7egZxgkSa%?@@= zIc-^&#kw=)Q(T*ChK2p^A?iB3A0tM|Cw1_l{vik95LdY|5=d%8VjXs6N4@^~_~7)f z5mBE(TRUj3%B3@}Oley=1v{cSS4nzv&|5{lQ&6!`V9oJt=mg7wH({5 zF{hfQ0Ycu0)T3aH4%}?JqEEBzU*!GTJY(V~1g3$(baC>ndMR%dG%=eLiV2UiOxQ(w zvjxcx7D;U>M;#t%+dY`Ex5^ZTjQvV7AfvOM>Ds38BYZ=~Yd-`gov5JT9mmlux<&Wf z4HxCboJdnyKA9rnuiWc6w$`*x7%fYYCUw6*-z2ri#}LUF6h9!Eu&;BbLxU#y?(8E- zDNI_0kI@RV+QNt7pMG*?EG25H_~3AOXlDjcMmP$H&%rEw;s))R+tU49y`=q(C{~9PYTO<|i(x~--XMqyuXR(?q^m!+X*R=|T9%OLaVu!V-OeCgu%!6wFuo<}F zu;(t=iq;u|9%%6|Ka+eDz5j)50lR*4T@aWjj8>_(JGHNHDb6K=ZW7RLF)GlbHuu?A z+A!U~v#U+MCjEs=gzG-*`E>!iGG3!?3eGQp3j_1~I?8m{ZnQPH3zl0>x!+6AhriD; z*^=j3yc{-Ziv#mX3fPs}p07<#-4NM%3qrCFhj1bcJ(+t9*$Ah<&M^ql)@IPDf@DKd zgn`iqoav<~`}q^#{@oyE z1u)YOs!roc6PRE3Ek2tVDHrpPLgWMxrM}&Cx1Gau)Gn%ieD80iE?;_Wr)gu5bFOk;LWP$ zIv{v1le*a%<#K9#Pk3rv+WTlBQ$i{HTZnY|mw>->)zePKnhoXhsSfRx*`p9)WK_|^ zSW@oY$owOhE(LA!izT=m()8s~~cFGWVmCnsM~0*SP-bOHgNqiNT31>72)5ow~LuT5QXy0&v3)?-RBM zHR;}f4NrQhUXhe4(x>n%xd|<9L|oNzpj?gj62bQ@>VLJ#3XFJ>gQxF8uJWR+=@UQocrEX3 z$>j=YxiKKY8AJ1?27c@wpap+d+_VbLD8BHWF)c8U_M^v|CAmzNr&=lb6XJC98Ig2J zl?8G%_TOJWjU+VJ<#;5r208{GvYT=8I2?AF^OLD`)#r*|a->4WcZlt({bhD_^%KLJ zZMtIOHEVT!sX7csqlH(2o5xyEaH_@3KxV$&Sr?{o7GGFzzIS!06tu=RTGE`vWj!xA zP6RvZ7j8&7`eO9{Fu~Wa&i!E2G83b;T1*F9W(QF2Cb~?QW9_{ zk4?q&KVnaaYa(S)_nq>Lo66?N>y!tzu`NRT<9xYN$1aiZ&m7gdsQWPa%`Y_d6iYm+ z#@P7LFU>3#CM{rPH=qCzxYbr+p-!Ydei=oKTJy!c3?O+M%Kp{2{XxL%{+&ZKga5nD zyFHHkc1YVBT;u~mHF6kz_!w)JRDaK^QNsm-R{CG3hZ=SWcJ@q(7ArC>ZSt{ry9^sY zQ$QE>I{RLq?J*&gNjoS6UR59P%a@ws^iN>@Ry8UAOTcg!ce1vUR&w(SJDJuk`? z^rmx!jBf8l+^!AMK6SQ1Xk%3@S_f_6|3yD{gVsS(ZI?_Cuz2?Gp0F%;->+r=9LnUWx>${GF=O^F;^)6ep{^mtvk+O()tSZly}EVC`1|V8{AIT6_W~ciJS+a7xbnbtxQ^q(E)U=_%l*S*K{DT4D90qx_FD+4Oda z$SCCCaPTYpzDA$|D4#uhM_X&+Q)lQbHoapoy8fX9yb=?_vNc&*Ep80l1(U~`HS;+Z z^8P42L4H=E?cw6Vyk$;9G6kb9^2*BU_#ERqnfa91OELbgo=uV%hvXhFHQ_~FN(C>V z>NxnpKNy-BaEV8*W;9XHu@8)(6cle-NA&p|Y(BPCAIdkq+r&~cnsO7ce`yw)g1V?l zFq>$r$qYV)tGG%k_Po#zHDkixd^iZZzR+d!bbKQH{!w#t1(jZFt~#VkpBw?KdS~OD z-soBNF)@o^`uyI3TPAzyiRY}K2eZ=eg(r1h-U4@#d(wF5gL7=18>Wihm@U}cZF9)i z#o0Fdqk##MGiC!pLovG;)l&UEzhpsUaKCMlH07c3x3_}=@1%4#hK)NR+SBs=q>HLE z#mUIs-VkG=awt`TE28b!ig!nHDqo==c_xo<$H=nxGb7G#eJR%ro$lx18#lW%!y*@W^y}-T1xK7*wXm^3DY(zR z+QB*{LZdahnz1(0fo91U@6Iy+VyabK5$49q1j_^>`F1Lj%?=}+oSy7K;G-4af~02S zE{a7fs)vjv2y-eh4nX6(_4C%Yq46O9W}6DVDhpl=|CQOX=$>7DYnfyK6@I_qMfGNS zN|+Rf*)I$Rb7iXAt>?^NtU`2$B-@D9-*xoq42Wm9lwSC;KL-RJOCj^i4JUG8C^R{$atZB?b z-ExP~PO}S&n(JRby2BXNcoj*%U2DrSh$GdWz9F|Rj|+PxOdbMf`b`4eq$7@_a zOD}P_=9tz@Cbc6ks-J|SMhU5U*!y#0^!r8;t)`9c|{G6dmgG2>jT+ z-+z3Y4KZ;KI#lNoj#(fWnRkkl_A3sOYbuk|lFPF3J1u_nDb_7YwPDpckBiQDi$YZp zt!RKd3sF2-y;_&ktJR%UuRn~Vb+A15&x^vn3}BFQ^bQwU{8VKhTk3T;X_O|cD&q`1 zt1M}(maZbpSIWim`-*0A3n-W8J254EJGEXCE-i8u6WD9p z`9p+eg+`Jseif!}2a4(3N9tIHk}*hlEO%2(!dGh2`}V|EEM5BHAWM+W11o#b9wU-u9mPp2n;mNe>$4T|3!-yB*3^hx%;H&at4$z#nUTC})zeWxk zLX-MN2~c9JtFmCyBu@04OEaOu`WXE*-cCRcp~Bk~Z!S~BBPm2cm7sncYTgvTjXg2J zUM-IAhLxZXk>0s0jl$_Upau?J-`v#qoZlzv%T+J8bPpdH(%>xeC{4%TNLymKAMbYz z#k0}kj+*>WbSmI4g+}%(hqWwM<6fsrq<@iu8t9zUTOg*&MCOuqnL zLX9fxQZ&8eP`xcMF9-fN+&Az%Y(uLe{*RT&TDu1oE>C8F<4`}`Ja9nlYbglI;u|X_ z@1p8MvW*M@vJZ;dc}T0m<|MG67OnZp6bYs=m%uy$_G=;rYp;MMDd`Mdt=L3mvnfT~ zqcc{k$F#eDvJ*fobtsL2-I%7W5yRqeo^M^{sFrc2GNX!Br^iA@hvnksa)!K5B^hwf z)_e%9C=~>uT=yWJ2w{pZ@*|kZ?&mB{;U&V#bH5I86W6_^i&#jRPdToiVv_c{zHyvB zh@TiR>;mm4XQti}VyL9tur2vUwscWMh#w|yHb<+UMl}nqZ7Y8y3A!F)Gqbaw);n4G zJ)=5dcHxU@*U^AehWUn5S-`aP@`Fxj!ZBm)FG$>r1%EQ)$a&In{|~DWm=gGIIB10dxIK8xR(-OSEZDP5zB6*RdSrx$HY4 z=WrTg2X!ApjYR8@3+}$K&Xjm6sq%}hpCQKH%%)uWr$%+CQrg@Wo>gY==d4{N4br3n zaj=DFG+8D+sw{cSAqQ{!R;t*LzTaFstM&UV9smSMspVWc89+&rhB(N&^N2`~iZTQN zNnSA;VVGY&d8ki}rQJKFW4o!^rZ<`|NLAWpqUYFoAoE7kCTs=Zf&tEy@0)O}4tN_{ zGpoYU#N7-1(u!g1@@nnx9=y_6 z#j=-vztMkV=SG^5ss`54KO{jjwaWPr@3jPwyYI?kK1XqN#iO1#N^DJ;>=`?evC1u#(p#aNfew8=ifLU`p_EO3?1Jl=$LE-IeJ&A6zoT(*ZCL;pLuW*n$A-@@YnJa z3`MOL)X9<8*v&ACw|>N$F4;z(NdGvy=@RVUs5&xa8e>qa8%g`E054L^AdO1E>h8T* zJO)RI1Cxx&=XpFC=7QdZVCB3dX~m|9fNo4IBvKf}_`ls)^U`Ubq(W-p3fi|T?-4Js ze7@*0^tIEk!mWz7pf0;SR&@426G1l~BcaWc->u)*mwl_yt_s_B$O~^DqI(hU3f~Au z^OzlXF_}ehjqf91-o4uMOyD%H2FX>Pobx4NRJ$X{n7GE!7xmBbB-&lAPo=|a zNPK zq7JuKvlJVo>Po$$@tD|UrI#B1(pc?24dSt#IU`(Ed@&zbN>8L3*sE)H%(KTw%V>*# zf0tGnf%QxWmsoo8%h|SIQ`7&%Ij3wYTstM-s`gV09VBz8>Q9(_PL? z(TsI;DDo6^8`?9;in{;!kmQWOf|XB;wS|wq505OH2?d+iG!f&J0RN2C_3sQU1C8Bc zQE5y8`dn5E=jZqeRgp?uG@m6=U|$5l z8Iry)m&4h#r{a>@F1|sHLi#g82-Aa*BpB>du)NTK9U3m%eL1N{3VEJ`MsSk!hrQbxC|evIfS?;ENkJc&VLfq>ve z%9!T@Mjk(8WAnH0{uCn)d&uX6pQ4i7UL&Hw(#yFO#fYMI0w^WE+Pd*rKi$L>ZRmTS zA<$id<@M&1-xzkGy1TlcN84oW7_3y|t{v|Zz~we3O|n$Q#X&OOhWetaO<}pi`F{s^ z=az&jow9A4*00G!d#Lw`uLY@m+&`sFnz60m(nRZtE$3E=;M9^`=Mq36GE%A_f8W>C zGtTV1YX*Q+v1_XdSYZs1L02D`8SdZTlRXvyh>8Ja^a5B7Rph%{?r9wuhesGREy5hDb1b=$CS9c7Nx!`-*a2% zO5`n8jllK~XAi!qV9%LVVFd}D>iAKoxbH8f93rdIB5LTPIgnYsbZgm?`tc6jhFrPk z{RAOlmD8o*%bAP(O}%ADdL^S!8KIa8CrhCwny3%c~4$vSn#(hdWeQ5!PHidL=l&J}0MXRz#4H%Zl&0!=c< zKG;(1g1)ZGkU@7G(-|~=3YCSN|F0L|>?Z@=?t|C5$Ef(@hegMg_!yGotg;;YM(1A~ zHwhKTaiRD1u1Xa-=30%=-6{P}ZH3X<;im#7wfs)ECO@w9m(QVmS>cYK=T%-Ifef<8 zFt&N~@39H@LY>*_X=+l6$o-<9(uNZT6%JO;MBNfJJQTm*CNN$yQ9rLn$$H7QEt9^o z-_6nmyOT-sr=zoJ`t`fadfNeo$0lHn1Jj4+^uKlcBagb2i6-|E;qW-sgYRJY_T1Kv3!+?r|^2TNOIS|S18%d6403A4!+qHH(T3dF>xG@ zjFG|SSe@fmmu;1ANX=s}PmAL&bNSlA_)`IS)yibECis3#eO1xBz|`#(-*m*WPu-2- z#y&~B!nCj-V!lLZ;zfRm5MvjANe<_eM|n3$KS-5Ssw_7UXI|=6qL3FE9{<}-sX6jb zbp0H5TOdn(_+k{lOL;5{qa2T?3!nePV&L@5wFea>A>u}>ell5l)n9AY4-cq(lbTMdjEPFwl=cC!!gf0` zj%KK57lZvP&Q>>XBC7NGg|MdY3swNq58-;~#LkYC;hp*Wf#HDt1(to)3B_G^fNQg+ z3X_0n=n-ocwNwnY1mxNr>{>TbJ`YWEe2u)%(h=XT)pJpjt~pleVghSCJox~ut^fCX zP$3|@MrVXmnuw3f`yoHo7R!qi^dT1LMqN~iD*DItlgTGvR6_XCUu#MS9eKrnMc_$( zuXIPdikxeJP4H$OM+exng3)dIqwx}YbJB`g`;Si-BDNzke&Gb%am@~vcyEE9>Sim=P^#UH7B6Gbgut}>eiFV@D!CHJk_4oX-bq`CziT?M2$y^KLH}JI`KdT)-!YT? z@8>u0odUIPu5JssBDJzfbco#iwNtD%M@Qz51J7w#ZM%8vA|hNyk2N*K8L zc=QsU-9JLmpG6(n5q=P(?7?QkW#Ts~~c0(e? z_yN<_h@(e6?XOhsl&=NW4@zd~J)Hn&(v#wOaq9B@6X6g)PFYyYg?5|4zzbcsB**u%g1 zu$!72H;xz(Pkb6?>;v@!UV+#Ts2aE^!s>whc0^$EHFM(?3XI&5zP*_OuM zp}&D=sz_=nSKqhEja~owOKs@FIm_u zFJjJE5rE$1_sw30El;|-7Er8Ye)8!h55}+|Eg(PjIBGUmDz9B==KSBMKSGtomWu2W zhQ?`On1gCnhp^CQf>Z%e0*>OdDEm0F_ru>JBLgU+8y|ZD>;ctZ!0G}(tPDl-FqcTl z(tmiAWbkE}sg|*1kPsX*-|oP+!#5P>sb2+y;R5f)p}zQDj>wEhcn%1n3lY=Q@q8Qd z7yV&tr;RQ~Y&A%^1&Q~GhXO7eZR{gu| zapwhNIf7f*B!&$FbUK-Cov-R)jc~i-I(PLtmP4gFg)_F9>S`~utK*;SN^))As_~%f zTKBy#BsOa?k~bayN|U!kBk+!u<3T(UMkaRXhs4kUa*;|f5B|$XaX0}gZwM|sXZjCe zw<3-c9UUF(W5>$>)~3;sVOJ~(iE2$T=^bmZWXtrd^t#Jo3=27l?RqhX7RV43`ZMyL z!NJy%9gQG_tF}@uhrID{um{Z!Vcq~xgz0@ST4@%!GWJHTdqM!~6Zi1&cuYM9)-3n% z<^@1Pij@=3e4XvtSQ3A8umpays0H;0y!dhK zVYCl5RG6h)4LIjo&;Jc`@Q@_S0XW4&+~2f8y>UQOMHJxDUMk}nH->G8bte(~MX#AZ z4Jgt^-O`#w1FL-Mi^RCSUNsHKf5MV3Ce!~&8n*>;T{Q+E(%oX+f8SRjV?|UQlc8P! z5)3Za{A{O&{An_IPJay09l3>+^S&iVQqZTmzq-A;^jQ#TE0ULYE4uWnFgD$S=Z847 zwwrQPk%O=L%T*(k=i-VeG%$zntzG^5Nb}EvA=>{pmH;7U0ivX4+A~aLu2l8^7QUH{ z6!Qj~VKXWc%FZGXHiU@H3z11A7U}z}4{EV@Eu|KDXEWj>DdwhYbIZOUyiF@$Q=^u| z=j0-$7u^soSf>hyC+qZ1SFurFpc4NPKJfeFpOJMFSlD8b-tNQ0!O;z7*`MBHJ0bwF zos|&bqqCWl!7aqs9T$m%f^mv>5m%E+arf*)c4tn!OMHW!wLS5Cn$aBU-iJX(_2iw4 zEXODqc~Jz&VNUrcgeZYf{K_2i7}%UEZ3Sgb(t!T%judtrHCr!andrU`i^hMIaA(Kx z>|pIIS)gE>w>kKqtXki-l6r{wkS_B|)eB4WmE#~gr7*9&C4CRB+7z>kx-}86K|#3Q zMgWm*(rkQQ-pd4aO+XAs5MD(;pvs=PxVSShAg=->>qfasc6`k@J{5LF`tjq|+G>2d z$x^O6uvyXdf@Lnd@Cl?oeL=ub2_2}-sKrnaZeZ5qI#o$FG{ENf7?+d(fuLSv) zpB&}yw}$0Cc*!H(ymE-ee?xEd&JrNX=>MgGRyiBr6s=4%Hkye7bs^D>ik@o_TeBL$ z>_=`Nt<8fv^RzZY&^!4oaZ4s?T^sUG?+ESO&s@W(q&)Cj8L(z?-yj&qB6>$68nMDw zYWDDibp~~yOu^XvDa4)$)!Pz(@potAiLB+lGNe4%_~M{=F+gQt`;-z_gKZMNNWUBi zd4upn1gDory!Bc-z}<{MEEfOMPb?34X8sTS5CK&f54zZvhN7(bsu@Aw#4omym~c`{ zdYRuYMP7Vs%!mRqxT{ooC4;RXIBNJP=e`@8ls`6##Q|Q^k(3;9%?*{$Swg}MV%tBb zR`-dbAc=pfO*XiIQjY2d9(7HHN8<299_Kp;4s{A-m-4~T1#K*BH$L|M3|QBJJGNyG zOXDselK&j$lxM<_;GGTpa=do3{S>?V?XApA3^$NQzjUOXZcEZ?td$k$hW%MmrS*5G z?kso97H3U`;Tc+%ial|6R?B3$ML|!w5O>Ywe)rC4akXJ5`(TbAKg=16#qCSshgq2R zC!-gGa!clHI#$@+8jJ&`z-6XLXvK2lB6xdgXz{}Qz-mUyg?U*%a`~FBGhVR048@OsUI>FMD;O_thwVIr4v@E2L`nBnBO~m^nhDW!f5!rDn=YyZSMo{6? zFnH#HK+_#E9$NSRDhpYm_V ztIR?i9@)&oF)Vx>otQSXAA08xp^}<`T5EV#5yh@R!*ecIc>a&W(Gkxu!eV64TIWUS z%KRrlh>t)ZmJOF@Er}RsDWy{-C<;Rd?PsEg75E^SOvA&YN2$TXtTL9a6S36&T0bm!VnGZ&Tr)cwAC8KH| zf>JCHrB0Cf5#8b3(Of;#a4?%`I^PPpo(9ECu#t>$;_8)+@xUS%B}P*uZ&16a!-m>i zu_FCc*u|AbH1F0p zqxXZ#Dxebs!K?I7gJ*6MxbrPXVb0?{8akiSt3fyvzTX^3ZT^D|v>cgy zC@3AMTXUxhb)%$*3mxlNA{}jWFyz4WX!E~b zEQDz+S3?HE2eHuzNHIHKVPmxzoO^>X28Tmt?q}7Tmbhu|R!(V-VI8b@9IvV2dI@qo zn>F_%2!`ViL3n89X)I`Rbf8$e0R-4^_&mB8^JnXs3T37-q%==77riChL`$N28xa%8 z1kIPXCF(d2^!5aFAb1dZ(Dd3ER?u&Bnm$Tn&DA)rb(4A&z!6)Y`FYn+>m^B&)|o|dYPHk;tsP|4d*-Y&EBvnAuDh>a z@;&^m_x_kc`?PfF7K+v|3n4L#y@{p%fn z79m!7MB92>so${@z0q1H?_J_Rcv0=W3g+bz=U{jQ(oLs8-WY{@&_kf4AePYi9gX_VtoV#sAH8 zsl@Q+SSgsSg^&LRg?nk0*8Ujo|9;R={In>3I9`)zw*c+pY=`|q6hqGx8GxEueP~0( z5ks328bgcml#y<(n5;^AgfkVmp@56c*$He!t#{ZMfUIEj+*08Gh5!&~| zg#%9;x5Sj*x?1c1VSe~%hgMx(j}(HMg`&$sBg&I*^VSx)E_jSKkW0hkDl)7#7?3R@ z++^J-(^}LuC^xD2=vJ!H5wSRUFtWX+=r!*WhIBjVxPcGbxs(a zl=TN?`5hNMMk2Y^-OuSDirVJbKX~ZQJwoO{NYrI!Kq(D}w+t^cynn7Myi{-;PMvfU zkr|mTaGV8!HURx_MHZpun7=IcaOsVpWW2<zfyj8ia)H?eP0HBGikbVAKh(k?yS0x|e zv_wKgDnnB)=J?yc*P3Sxh0dM};G!Rfcd6X3jQML`>TmXHZ}iuON>f1s*^;tOKZc3y z5nBQ{9N4x0-LxGL{-ly`-Nj6~yTN;f*oROqcnjy64`~veJ~?0Y0t%)87UA`(FJAQS z^1ldxccQ#n<)m)H8SA)|)9~g%sj~mVKf$g=zAT1{ldwd+5OL?Y6vJqjS>_? z8j#*2ZpiYhsi_GQ|Guroz}l}XLnRE?h~J?j-TvD6vs9)D(pzWtk3Ajfr$7SFuO)*R zrj^uRmZ7ISyb=6w+2&6S^aU|~?UyxSu1~XW%8ZqNA4w2KkQT?Ps%ck*_F5K7Yi*Ce z{TGfXNZg|co;&Wbk;)2n3@4I`u(e%q$LqcodQ(})tZGyW5fnTAJ z&}yLme>v7FAP+Ik47&11}I4X`-E7$xt6hgE971I`N>V_-Ba4$1YFzLcKCpVj@$Ay!tHnq9mr|p17 z7wOUV+SI~yJPJr~uIVzebuBoMWe>ga2lz*&WPB|LiL+S*V?7!c~VZ_7R}SJd7j|Mvu(xb7X-Zz#J)*X&pn!;+zBfY#?@K zo?dJ0VPMnNdGa5NeJ4JKPG`E`^hx(Z2%w5P2O1Zc|B^cXv{YPU24Nzfkj1z7cdqcm|4IH*p)pz#P*EQ(Moj!U zZGp5U>jphm7~UD)+#-=V@e*_0OjzQly85Z%p$CWW&4qt}P=7}(l9$q2E*;708=&E7 zix4tMjsb1=nfV?Ji5Gv*TNg3_wFdq>W{=riE*sG-8_@t1(2L+s@NB1=O-ZMDi@HXA zizmm}2^Ei#VUsZ;U^MNd)YuJ5A5@|r$bGE>Hg`8j8#|Skf}YX0Y$tI+kRX=e_|KcM zl%uphFV6(aiLx#j5LlS-8b_AOZn(1}$1T4?1MG+pN+ z`{GgdW0B*r_pX%xY!5+aJc|CHhX0N2%YwOOiTVm_qM@(qw8*Pa>?&p~1`x<0nfS(Z zj*5eJC?b2*0tqw_Z~vWk$qBemhcU?scGasc_*LwQ0Rl?w6~pC>Sw=}37e~g2#RmD} zf6_F`V!0Q|IZ>YjWT*IWKc>Q9nV%G`v+$hw#nyQ1scznq8*8fJjlVG7ELYLvSH>^3 ze4j>dfB1{*g|PIQ?KL}JM5NDto`k%PKptl66f*UAKc$(TO|w|xQO#-qBw0DkRlFhq zfctZFPg;)?o)NL23X$>ol5v{6fB!+)eBq$qVdO1A&%-GAqc*FI@@ zF66mSWM#m+zj_)9(I1D>lGv*6LyQ$xK1arVf41%7j%x6A5M1jupIzf8~C`tKk=YT&P<@_4R+ zH^>*)kSLeYn=6^fN$~{gvTS{sHdpw`D)d7jBN+v8F*xd1*&BnfIO%qW)itz9o2%+= zd&nk=xPNv2k^c}GsOwh+_$^z1JiR%;wdBxU{OQ*F@zvMn0x>NH5D|WP-Z_64z0X1XCYJ%n;4Yx;i*We~^GYhWZ>HiqRR)e-oRs=+g%ebY6RVp~+dsjr`JXU( zr#@kOR|hyRZN-W16e54WzOu)b^_dkl;RiGVHsxS5P3rjWT0jTE`7gvIGl_?G=+CSM zi`WKnj@^V7QgyA;_Bps_&g-(&`c)5GE@j}iYNuOpRHl)xDmT7O{ItYRinzEgrn2VA zX2!+rfmY7Fc1Vr*HXO&G{M=C|tCJ~IhEodwR4e=zNC<7+%uE&)@I&{1?+X`=O@Rqh zn?o4)m5b8ag*AFF-=iCex-%FQ@BUvG1e-(}==raaEU%pu&9fu%*-}ncRf-b}Hg39YNFdY-k3pDEL>Mm~i1R;~ z6*B?_Fbs0oGKG`tx!%G{0JXwA|7zG-V3pU9aQEaP)lbT9V4=jKP(I;_Fbr={ zlKoBjmsIZ2{p4vUoc5%uvug71DsH|nD2YID8DAZ5M>_N${va*f82jC?~xzXaE!>ii25%ZkL+CmYdRgMDxQlA#OI^QpHSDU#UEP- zZx>iEwLeg0ofcOZ8zH09U7eys{?=lmBVLO)Cda*HO{eC&V2`q_Wluolwdpkfr0&vBe{ zUF`Hwon2F6MZ_iDz9T@#5Mj_eF?PIeTn}{!V&#^j8zM^Clgq+U)r2i}>=`)}phq>3 zC!!Qi*fhQ;pn8j<(GqDPJk}3Xh6P>D7cbzw-`5M#V_qf1xk3g6FtNCzcib9AT3X^&B#qg-W5TuHu;fly#rn`axz3%4PdUf;4uMj{n~M6s zSpW+Pw1b#1m*V>eCZH)-e6K8T!9q#oJ>9wR`GhCVt^I=lAeGe20FVw~T!!h?1`C0H6b(dyY>Vii6GC-GUK$g2G;?=xIYd<=3^``)k~s>?=K=!sa8e!! zHQp+xbvwXnTO>ZXV%8B~SrciTXG*g0hyq;fzaT6dk%kO?7e1tfVIWgRCn2)yQ-iuU%_^&@YEu=&4AAiz{dRx`2{CC6mt z;#VjJl~AB_p1~CUZUk$6Oflaerh^!<5u4XVUdK&xP&ULQNdN5)v5R7Tzgizbxg}Nu zc*s;a7a`2FH$kCYxg9qqqa zH#=4vmt|~jX1G~ZPlkMc0|Kmt% z(#`XYkV|b>^jY9~)cj-OhCS4Ublv(v+jD%@c|sv*fV}04@|2}iNhxNHz=d9%OXr2E zQF^zjmg~A$-gdg)0l@}FoNpOj_gd@w?k@Cku1eiF=$Q#g%O|}f9%8whBSO#T=Z4?% zD>$p>`Xy&s+a2KT!C7UF^tD8Velp#t4qD_IiVp_TQf3k&D0` zyOdhhEq+l)Az62HPZKZ78NcdSH4TCL@@q7j8TBC~1ilxrt^sN$lm?aT|RC?`jtR zUKdb)GDIk3r~@y53~B5uL*MUP;Q=3rD=@oxijY`fS*7c9adkDvr{^Gzw}*#^9`x$8 zp;(rwmT!_0kf|YsbyNtn!tAQ{>+W^wf|U42ZZ5+Vt2=W$4cO$17W7_!(~deB5c^Clz{Q&`wwiy_2)PYH6V1zbhGvh;9;DIrKeCB|)gdJ4@b?CAT~ZD0Y~k3%%d&#w(wjPpzNcN;si}x3>%P`rZ)n zs3X?kz#*-0Mm0F2&-51V{i-Q{;wR4(Q0EiG1#_};uD&)rl8pknL?BHK^Xs2{%?diP zG`G$+FR!db6nhZnS^KdCWicnRges`QaVE!gTwNAaX#-;$Z6wZ7@+8{Hdd?iJC!VMU z8_oj^W`hm0b+ru)P|JSX(p-WukR7tLpcgIv*fYivDcm#c+o8Ss{`@0;%Y%Mv#Fqi? zMUw|j8@{jH+}yw}OU<9dN2>|8!S=MkiAXMw&qbT?R$!S3sgKY|QTp-B@=(`;{taSi z23E+yU;x}{lH^-|<0S7;z=M!V0 z(jqEYJ-whBJ6+F-R1?vaUyGiU!qiZ5;`iRtPYe9$x4T4Q7)QPd5=FIz{K) z5R6RAJWOKr1w-Zlf}>AlcN+fwK@h9-W+25w@rN&G7%7VkIeaEQ(sevVH^=#-Lk#p9 zr7{(TYM??XJ6!g5(fixXg>PX@>-2)bw^rARZgN1Kkklreov4n_6PX*|CO3>8 zzE_;NQkxmCk9O0zaT?lZStj7a(UoTwJla%US@wo2c>=Z<8mR4c5it-UU@T*luAk+J z+CS}x;HY4W?SrQvy_EoKX89?~YX}CCS@+d$RS4?7TV2EgOZlj5pHA5gi;oQ{Ew0XA zZ@eZX)hELJe3vv39>X^!^o--lc24J^B3Caa3ba6%zo!^%X}$>AaA)8o6+MF{YfSzo z9cCpF%vGw*$TgjtziyZ1-`6EtNo`>L?2=UCtLt(VEQhE=e+Bbyes7ij>ehozX4!FMZ2;t`A&HENg746rnsb6%`xZWhfcxL*M ziok;0Df~l-o0h^vE#*-jog7-*8x`s{t-tRA(a@8mg=;r#_Y8*+?DQxS!84*do~k6O zQmTlh@H)-CwpX^YmSr?URY%_pdTH#uTO1R0ALkoB@Uyp69Ux02`w4Q&WAJ^0 zg;1bWw{Cot{%Yk*Sl&aJhOUdPx`)yN^r5Dg*nMm%-!O}b!9Bd&xv6a{d({W6S^TSx# zCgQ9rnl`AMruzu}0+uh!LV_Y&|4O85&z6Pb*rm5g_@X6i3!*Jo%Qgj?Bf_+fcm$_s zr0sp66|qj?ER&fCs_>;bel2~*wNUPq{1&_;)hb>;Fn-OvE%i=d5egT*S(KgS%9LKF;ICPrhR$4oQCnPsB70(Q4@MONuPrM}gCx-Sgb> zOTPF;kgcgbl;xy)Ra3v(3FBeg3HHv?7*A9357zmRiTzxrpV}4+#1&(J(Z%M+T!v%7 zmG$mW&h5Hw_cr2zXj^X?ut6=XxQu<@@#)UF3ddPX^i1i^3Lm{BqOe7Nkp4)pSMXh? zU&OJoY8Cn?Z*Ek|V)yNiOWKn?A?Yw^F>Bit%F~sJmxVjHS;wC`fQXvzNR|GUO(vl` zXg48mI05O8cCkfa#R>!keBPyW_RIiwM|@%Qozuu=%2VT<-q+g@bEz#cn+Z^B1JL~8A{nKJwQ|9W`aEmXdO=gmbt*mMDBdlj z9=2g(A5>nY{nAmCIrx;NaJ#rl>va6#(aZo6^Q9g!k`Xs1O9b@B2X2Jv57M#eBAqcL zIHyg<_82ZEM+A=?JmUD;nDkBYpiE_y|8GR=(`nNF-Uj7hq`Sgi-ne8=j%Ep}2d4C0 z*@izTfra0cTXO2Fs+5nC7Y&&vU=5G_E-aOE>lm-tD`&UjtpnfI*>?VZW#-@1)Xo%7ak{Mc83i3Y)ddTR-sSp@@HAC$8N}xDM zDJ9sYZd>W&?q}eZydqFFGVph3p3TiP76-r2O z?YA8MK|S{M+9m>$LG)87f=cB*vr%bor)YE5g?s;#khXrc30{v7`LcmidWbW3WziBR z*|FhYnFIGU7bDk?cMBe52G_Dq>7OW6%bA<+5xtW{&N?A&S;3A4NiXV>I$Tj=NA=Co zVM4w8S$8u$p6=BV(PmHLt6PH!*ah!O?Ayuq;IBk;?T2_R!!5r>XuWwev$CLLE8kIo zJR_OO{P2lX#B|%Fy4iEy478facN(4a>9kC|VkS+c?iUyCzV}fsfnY1CPY;yuOyl|P zh26Zf^>I4E*4Mz(zGIt&&;Y|;Zcve4r~$tcErHM&-{?YqLV?Q9W$~jn@`iEg31c^K z!9MNJX5d*@3q+in-UKoAIi#WQrzO-= zv2OnM@Xu7me6tR`A+P4#`i)Ty$LT(WNgT<$u0RZJUh;PoWM+Tft_7Y6hl=RCB&nR6 zqh|OCCTKDgz-SckipzotH^Xpvvb(gB>q)2dTdd}*^?RsRdeDtg9ankS!MfbYl}B0% zV1~RXMl;}Qe+MGH!$16)?z&ww(e9SNaKj$gK{3ekga>BpG16dgsIJBRi0KlJdNM-I z<0qKN`o?E(6iA5VHa!DHrefYl%g+#pkK<>bLBZ(r%p~f@ky60Cgl8}YQ%e?MBU34y zB%`K5L22nRRI5CKdlLGlpb3BK&TH0YcS5s#db42$xcr)hv>URF2P9HN2TD~^D9;FT zQra|i<_w)991abRVka`lBj=ToEM9O;+`>8J#1VT%lFk`5j(=`O*e~BsfY+X+`Ndnk z*`a!pHM;#|X$_mDquDk;hR0?kEoRB>xBR=E39pra2V$6`(2?jFM1?)rC zd0_r*$1;IhP>e2YT$e;Lw+4EaAU+wy!YJJup6b7;8pip8iKNaj_8E?F5`9nYdPU>$ zz9iLYdBuQq-`H1SIS}gcbI{zkWC1+??i35 z>I;ru<^a{FJ^3XCLT_KIIUk$IV`BvU1!nO^S}Gz z-CQXD4^3X(HT6cV`7H*^HM`MF>KK=FV0Hg^3sr0Cm3+@!IqPUyJAnFWvSl5|M|7s~ zq6G$WSoLyG!Tzpx8>r7xIeK9g!G+*JpNG)BGCjf-$YXq_z8CbSSG5QXnT26b$x8FY zIf1&@7vgcUn(?y-PLwApM=c$;;hRA&>=6?eza`n&aEB(Ows$w4?;6b^;^{hMyXY+f zoBU<6jeF$ZyF=WZUMAk`W^7oU8KM5ERCq$?}vk z$feR#gjK_GVEP06JU)S&xmq+}t)bPW{0!2iqsn!@x=j)0+@zriYzX&Fk9a{DB28YD z#Do57se(?%OSTZk8wFTzi#DY5W0)bz>SfoDE*opOJ>kpzg|rxc7DZ{2akO-fNleN86?#jMAbRp1$Czj1bVSGPay4mc)_$D&-5rHCRm) zGyJA7(2OZ_FoBdZ^;dUlTvpcjMIIaXq_; zc(gk(fxpD2yUdRVi(CAnt7V;ZiFxQh@0TVs{(3J<(dR`qVAiFSrDi_#zV}4_s4$ut z?LgpxAs>>K6X@3^pUF1MIAd97P-m8>2Kx&o<62m_+8cSK*xz1a%!|S(E!0u(zv+rT zdB5GtsnkX|{TtJhvJ!>iOpRxaO8iP&6OoTS&OwTuaIldkFVXv6;$nQ?SIF@4gAbhvfKoFzfyileZ$p@4W!|;|jM) zXeRVMfq9J4pTCMN8@_S%9z(i1k0M&4WhKpQSHyJbBbU)mic z;c2FD?Qb01xK48A_a>F4W=+fZ?$!g1VW`1Em?T%cN=UUEV;|YZ;@V{x+`-WYU{1tyH|G7%xvA zno>h)61K(ioQ4V)t;;=`bV=#ZWarL&;HCia+BN-{#oxmWug&yaOfBlBT>UdpM4EiwnMX~$R9 z50ArGL}XNu|Ehyb$UZJbt--)cS)bss?v6P`(wjqOLR7c2A;s@Y6%$-!OwTj$8mETH z6vY(hH>L2t{^NDIxl8m!A9#65s5P-t`%1o4C{k#IDklHkj7-SnL~SOR6s*I&CL6+Q zzF(m}N$8BbNO_!E-y8V6vGpi^{%v3Y8TR`0!u@^CdJ}y8xX07*VExI|?U|udQhu&9 z@AGk);LA2!r)Tqk5hJ5)wA`q0dhvYAC^UkgHmBYgU7w%#BB)_X@zi3>4wlI?o%yp> zEg7r0X<;+j6oualYmAEUl-hx`sFP)dT*3v@8YC}n{e?Wsd>|=}8vFCTUs%CJfmGeP zWkN3smwC#zo{L?u{m!qcz_Y1<6?iWU8h3)Rd?-6V_tX1RKi+58G$D+Z)5QvjkZjs8 z$lLAYkUzynU0rWCi?gdk*J<-An0KEl#)4TYwUN)Cv1}%jxLo$Z163KQnT`e{h{AxWV3x)UwQYfNUr{uAkdaPMnvBU3UL)^by2GSB>)WaifM38r|Uiw(}_vY zao0%Gt01tXnSfJA^3`*3jaiDWFE1K-21w2UE@q{7%Rmo;PO7v(f66TDQ)OHwK=%d# z{*q1K=olrBME;0Q#&LI4GI%5TbqfDF<3*Ku_Nr7WoizRD&&Mg;n)-+eaSMZIuPAk@ z^wF$W_Wn}`IE*=9c$-{Vcq{2+H1dm|Ud2(Pkaw4vr$V~7wlS}D(qglpUIm;E= zL$ms5?ldG*^I0#!y*`gh?k|k#eaR1N`qoeTSLrs{anhDZbP@D9S`3(q%gER$55*6D zVq32T!WBq+hS$LJq6y}j@^#4)@DF9So@)1e{FWWkzWPozF?ulF4WS5BBne84?YY_Y zefGo+FBOlJh#z#|ksw@uEjq={GFxG+%?mO&6u0mIXv?{)RHuEC00Bo;+Y92&E_zov zp=#Rd9|;&a@!*2ZYd_o2d$x^rw)nd~k5>_m<3h}j=U z6<%eJ|45o)RveJ+0<8^~UsK)XhW>31m2H3vvPyr>*tjAdLA0yjA!_7_ZDeIH`q$&8e zf=QW~o@m-NQI-7=J>ea$HE(-ezB3Jbwkwa;9*85%aZt;lNDrL7&A~gMFtfbartefT zHh!lO7p1bd@&xE+(ZVy3OJ7)tB)xSy)WXi8-nn3}(9GzZjd;MTb#AbA1T`016?MpX z>8)2N*35S6jfXUS38M;0V&9tLyC!o@_reSF;yxjbhzJzw?E-{O$oR)SW%5N6!^m&H zpj_-M!b5a@yie9vCF1*u)D%!Yn;2QXBG!@J8A7edj(uc1M`{NY589!q-8Q`KAWNia zcvpl41Q*1qPkvCrA=d$;@GQn5HugL9q@Okl->sG6I|#E!`2wckEz2T;cb5(a^R`(+ zLzr~*D>Q5#skm|c1_!u)`#HjPBU6J9wK!FgOx-=|W3o`TJ$`SFp4yqON#Ct5%P@!h ziMA9O5{Gt?1-`xkRXJEJS}VjtS$JAkH=GCN$ujV6GAKdp0Zj4Qd1xg1hw|jO1Z#U! zR-#0HuiD=~pJ(B61W1ujbYx~^O%Q+Du!c5{XL6=+jU4h_Ozuna64WrAr1^cfp7WbR ziEsli5eqtJm`~OC9tJrU05CTKW`Tgp{pu24BIgFwqtUeCZqyVK=_j%2ht}txnvp_z zg3C)|{>g^Jx|(NU2dVRtTEKY4;e93f$xqX?^KryUX;oitB~3E);&;Q8ylkdD%TW$F zF%miT>5A-~^L`NKI1ilHGui>(|Cet|Rji;`jPi}295?ITKWSRdlae#?X*9B}uB*KB2f?#up_$c&<$ z`z0_a@@xWxL#pK{a~z9NV4vNO_(DwfBL3vG#>^$~{#KcoaZ43T){1@T_1YCK85jL4 zM8;Q)orII0lNj26#7j$QkvEx5uy_>092dd6b7eop(&Pp-d`R?)-}VIO~GZZ-jU zkWFEgGI6+)NZ6UY6y!WzMzSNehM`9~yJ_3uB-^_qNb0l9~lU;Z~C& z2ed1W_iwi>0DZcp?I*Cgx-RxQGBL_t4SSg8@P0&7TP*b&am8;Rzet6&=cz8L!*+0# zPK`>c?6;Mnl%bTN5cFH0JPc5N`wPm-+>^WVCl)5IWL!ARP?s=7`ydCUlqVfl8@9?h z1@2e8ceAP159+MRzX((Ozb8n7h80-f)|IIb_y=xrH}=vuJ$Se|V0@U_nQ}(Q77$qp zn3Wy0ETbGXr(zHYZL=Te$z%iLW-7JztUA}d@{`*Ni@(1y{95bM+fQ)@8U#l1EfVgA zx+8aMYq?6OUEjA8pmTDd4rSduzas517dqB^ML z#@O&%vwEc1`-3)=~JqQ%Z4r1v9j{_g{T|7g&J39ldt5N)N8u z3w2Z&es!k1gyMWXYIqGoFj&J%J97#Y<=0^MTei*lC!<%;9|(^Z zQdE*+)tQG(q>fO~u@{3h1Zf5^0f7(dBpv6E(g7(-(wNh%bPZJBp!RLlFVa?vk_nL$Ufg zV;%<9P&REX0Sn*>-M6hWZXdyTdAfy!KDy)Dip^>QVvg4(X4a|Lj|m>c%rL-(jqWo& zo0(CO6LhbI=SR%p;0;+~pW2OPZ072j2%i*1%iMrw`7!?WsP(nBWdwihU$GXc%m3Xj zDFB)8u8QICGu*cE$_jzgfii4C{-mUZ~n~7dmOB5NIA$@unaT zrTXAYzqOCNVmklsLsahWz|Szj?;Gr*I!J^bP&ue*(SlTJ9S#RvCrv+W^Ma&UehU|7 z9M>eCLz?uBN!OgSWk-7w;_H$Bt0!8Qzzj9T=f>_`3mzErncNCJH6RWg<86;TL)=#rXnTrMJjqF_cUIPYU)Pw3f zkS8Nt6$k>F8deCh=`{Y{<2Ufm^cTR-%DVU#=c3(|pJ%_XtzUvYWBQcykEYl#x$%O> zl_=G|_%jixLEmF_Qr~IH)$3vVs0LeEHHDy?ZY>MBUvMi}Ngm*3R$UR+Cn2m(jL-_vVP^`f?cMpcBgeb+CeCcU=2j~MyKzYvi&)f-? zC7fvVE+-D4!Y$GJ+u8dfq_n))2pfvG?g$1pU)+AR*gv0@bv19WH!xwvYliPEQruK_ zgn$*?Y%z3Cut@v1w-xI=)&Z=aSsyTp-6@!fV3u!Gts^X)Nkzt^n#*WYDh)sF8JV*~ zU!3@u7a4)bv~0&~#EfB5tGQv1TKAp2HgE~g-R4R2xR|at<^=&rR8@~oUEU(rYZ(EC zLv^*O^Uws0Ba%)Q09-tVpB2wno*9Z>6PA2#9q%7}Gl^76hk-=@_Z!UqU8W;RVO{Qk z_}sX*ZREz?0MYtnEGpuQHte|wRB-~tsc=z3+kcizjsX4kE;l&m7H02 zZls=|-rAWYxlH)tk4RRZi{{Hne2=t*#JXZaFco*Q!6?%m>D6wJkv$U?a{da z14H?fld8FRhO()v2M#wP8Rl;a+X|P>pPOi#JB|vx+2#H9h)b+Xmhe69f+JT<5q@q) zO_TDXEv5OjmXa=<BktNG*^`$Wd?l3&Z+R2O&g z6QKFQZSU#4Y1{s+uj#=auFw0eJ=~Of`vLq!s=6th46 zSkC8oIqhiWDVfL9&_!mIVx|6vd>6qewsZgLI|9aEyfvvl*>)7@?#MvVq{65tBO^Me zz&1ITeruf{Fr~gg+9vgH<_x>z71;TslGnC*K}b1f_UksA^r1`}akC*XiUx*0pt4Y7 z$Z-Qj(1<(rKztHJ2*7D*!IMxm}MV+b4s2fMeZEo+ILiJ z3gl~&_#P@*UV`i?5U*q3562|oh*C*j{IVH>xx{ncr{TnfPs_f)e-{Fqg9er7h-^7u zgcb=sJ>#TixQm^sorjbye*^km@dmj=)m71=_%u}O?$vU13PaV75l8s;Q$51eWyzqZchSP)sd+^o&hWkX&}$S@8g&KLp%EsK3n&^(E`{o*LSYIP z06OuLmzDbqw(PMihIB?=NK7`a^@d$!ffSQvP@_kfZ{C1j$0i#JqFT6HxA}(zoT=R` zTMjP~?zj-G&kPxfWgdJ(1Y|(-^G}4Rh{d6GiteT4go3=BB+?3OTiTB23s}Ir*%F1^ zU8{1eDfs-0Ji?5`=0TH4f#U0`RyB)y5S~`JXB4@J=;M~(L$htpxph*nsk20GD#Z$c{K7?YY*rGm)vb{ z$u;ByrFh&7_gY)JR_7OJYgC53Rz}K?g<>z{7;doQyeT}-yLQ`}sxY=Vr5MKF%~QJQV`!4ZRzi#)`4BG1*Og@r8dTlF zk_OLA9`O|qQ65oMiOgQmf4u5JeqP=n<`Qpt*Ddz*Dc4S~9sRB;j+&EY7xHT*Q2Pt- zE(<{DNPF|q-!Q(CI(DE_$m3Zgz~BWjo_{3bI^jINQt!S+iJzU%K0v6s+9HWKLVp;( zhGFy`-c>xlEwAOlCHZ{I7^BK;YfA6e5@&!u%%ece=$YbJOUegcnm_)@uX_WdqusY7 z**<=~xKat^NiA3^7bIxnft@M5H|e#~zvxy|J^7uJTz&ApZ2rs5yzp!KUYpp}|HIW= zhBf_$f5UY5sL|aux=TtaQ3RyfknTo8X$GT2V00;Vzs zpBML=@4*hfivxCD=cmr|vMTaSOv!rS{$66p%0p@nCMnSw6Ojbwbie|S6KS6}*Ifg{ z$<=<5-4&x26d_*vXzUi92SD@EUD1%~*2_WsqtrA`eI&x0u~VtvxSQWd^lt&Wk~&s?dmlxYQehw`zJGAdQ-KTQ=Yrjthu+P_)Y?^0JDab{}Vf#DcXheK>sA;3xwta+W8p z8AnnGNm=nCI?A&)-zi&)(D8ht7kh5)RcgG4i1?qs%ZU|P&nqsB9aEiI8##O>RckAV zYLi+8+-*8N(nWrqt6l-U_G1Th(7++6B7=Uxn3V$CP`bK|fv;Ue@?uz&Yi{p}_4L*_6(!qbLg`dMXP9u!%bd8kO7n} z`4M_mLj9Fn>enyXg2R+amf?ar8hJVjt6lTL%qQN{5Ow&FqF)=OL=+7DMdy=gg%oqV>A!4Fh^kUf=w2ikl;k6Gvwy2 zk;v24>b!fsPUnlKaYxQ#w${$nRXD3jN;dM?X3+rC_QTK$IhO?i-Ag@zmC}!q z2)C)NynY7I%=^#zOCfS82B*N_sI!-#6vYJI-6pn6j$dB%W~_U7EiCI0sTo)w1x!P3 z2_d+MZt__!Qfhkb4#btgha}3lyyT321}`mG2avx$>1T8#M}+`XoV|ik@}7`ezX{(n zK>6V}4Lk=~bfsa+@xjQ?1G_6d%KdSW;MZ5h!{rF`gN@qoCGw^G%BtRyUqexM&Hva* zK)43#FWv@!7%iF*(~~z#a@WV-+ZxpCZFE2NP4w9c*tt_oFY~bOXsr3&id#osAw58x z??*S*R?ULwrR(78$%6@;?oH&KqG#p|XqK+!=r)?uT-eN4+T|XxwVWSNCdYL&ZVWxh z#cN_P0iQc zB-zg{d>qOj0`u1sIsnXR7npv`uiJyQ!aHbS%@?&kjn4E%{!OrQ(*Dn4mrV6>gysUg z67`~qpEh&(gkK44^E(hQ@x!U0P44Za#Wz#SBkS<#fakaaqtf%AbX& zaMs)z(3m@F4t^JQ?}o+@QhP>DUib_In;HMrapXj?#4SF0Z0Dct{qWZ$f*%!I4uxA?@@Rb@h2;Mm@|eL zTL((a*#OE{biJ$uwtjz&FMrZH1i7jI<_Em$bMDOvy$fCr=7K(-#?-Jm1fSPjm2*D` z;0TuepZuL>Xkd~Ait0QhFsWXEdgPJmK9x@E2l275=Jfe;n&Xq~)_PyQ}QSme~DRBnAvIWHT7BNWiRVV=>IlQ zl+`_ArKPsS#_Jw#gY@xLKg*`ta_Dw?dIOVXpuLFDq^E1}NjtmJJ0gcC50-2U||HjX3sq@?WIO&;Smb zoIJ`&ahXxuM*(W1j$hcIG$$hnR)nCt!S-;pV*}uJZ-ohP>&d$EYEb8NXy%t;zlMPr zG-JCNzxZtyy?`v*W#CrasAYrLoX4W3_+yN;;GxMs7mU2qAYF9IKi#nl2&jnfeeBjv z{D2GxtJ(D&N>#3wQ6ZLxEF|p(Q4=OTDG*->`>n~l@PP^j7Fy?X&n+-!QiE2TR$r#r z4f6*((vVKvy6O*Csb|l@n-0+05dDCa>#nd-Tk?E%<0tNL)mfkNRReL9O|p2hyuoavNt4xq*Mf9T1qNY)P;wUx}ZEyZaDXWVV%H7~T5V@hkUF-mH!D+w&vDW78+}8nO`|1lg(= zRfYs9B`8>WsQbVKu|(vA)GSk3{qsTw%(C0?{bAdvedB{Z%^}U*ncMC`lfxg63mezg1_4SGOtfj^Kx!A&~4xm48 zCOd;p9Zs}=MZ8BwUbp4PM&9XF>HU1TuzwXBz^Euikq|qO8Fshixzh~uzxb$ z( z?8mWv*qF=Y)QiLcr2yO4uIUMcqiE8z?2?o#{6V>9Djcm`_M6sU$#>G1_{3uLb86V* zq5atRUxywuv1R&m?XNnRc@aN}E*AvZ84DUk!XFpC`V8IUh+b+3VC&4<)ptMdDf{tradQtmB3?cV z$G+0g$+oUoBZz4Z>k#||knRVIP8aJcW_-}C%fs4o-V{q4Hpt(-mxv_ND;1MG*ZPFv zB=i(qB$$!qC0Ao(6ngzm)GJG<^J}3i_~+E>0W>05p=yD)P}6u7;I(Pqn=ZynK1e>FIl8 zu;gsBl%+Xy5GXdL{57KZ^RoTWt@;^;Ig}cOcroU|ko)$hdt3t^hQRabj^~wRTj_qc zx0+LU8e`ZDnT(Gh((_&|XUFDh(@kS0bd88iR6*o(b($z2BUybb*E^NO%*t!ufkdmV z>gA~K`HtA98AQ@v%W_NnbQBoUP!Fm-IXMd~7SC;%HKc4S3NAr@ z?$0Adob~y*ZESIVD9STk_fo&tSfm%)+r{v}9KnREcEeO)oS zJvMyIy6J*hW#;|Xk2T6GuZ6=Ud3CWFaThT>7XSsiltGmRs^0~8W!q*yKiN!RMPzHj zrht&8E)l&y_!-<~i^`x~lqp4D_K=_s&h2OynGH<^nP%f2zp4*^RNv_;>NNdLAIwi(LEwv5#GIOQp3TCFFHh zm8AK2E}cjnJeP-)0o)@IC9zU2vCfmBI07bN5J9c5h`t1|zp_vVJQutXT1iK(Kk|EF z9%Yz|3)`E#{svr)fb-$o32)DaSIqkbuZS6|R4uOrVmBFbeHKVOAr-*vDH$LH4=l~S z45Eb#!9Ao1A#6W{9=mfd>sA-MP3|92)|P^;rlBcyd)_27QPWemrXse~;@MsiU)X5G z9+)Np-k$f6ME(lE8~L8ZOkIt78YSVu4X(_WqeGK(>5Yi|-z>n^vb3aD#@FDG=ldnMl6y6tEO+8z$yfck8hns+YDt=@8hR zGp3*HuWrot*T>XBfE3ArDRKlKyIwkYy;Y%}N!Um@5`(+Oq-OdRWZ*X#_MF0& zd&1bmg=}@@eiqXAXUuCJBtGOc@s9ZN{!^`{l9kS>*;_Fy~#`?y~3YbZScJ zgA0HFQph*AF1mE;$o+FW7(C9wv}QYeYKzIiPOER(y=3TXe(5fi~6uZ_|KyEOma?#SZC~lLL}EX?!D!YmP(37tNFBQh#Mj zgSi(Nms!;Qqy^G*I{4}gl+Iv!o%JaC`-90S>hmTUd%|@6fw%6`CFGO-&n8towg2$! z7kM9vGF_&#Ffb)wjYJkD^gm;~WWxHdlPgka!5%3qO3ho=F&W7jde_O6K(6M!{5Xg- znBp<`F-#~6qSGF{&!wZs7R8oKoT25xn|UA0hc zz+>MYBw=K>6@mMn8^(8%2kcBGi%+j8OYgkDUlA1Ok%ZY8N5Z83atvQ*4J5Y7bFjjc zj+}Oh8RWVs%<$QMmauYmj8R>U_*?pzzYG;M#pS1@?77-@Xa#iMaqf z!5z9{9ru6PHtbV5eN)qKG1tk)nL0!A8!`+eltVZFK>m@T?~&8Urt4~yE0?D z`t=K?>KkmGP4~Lhh7?0ZUEb-PbD>K*RXH)-y=t@kw7elCI!7#gUDEt_2HM|IB)?ZUk!cWRqp@>+H zpL6pw-=W#be80jlz`C!rg`8^>(>E>JTFGZLvot^YocwA;NFJSzEqxcwSg#nxE+--p zpMe~H(@sMYenP}|@U^HcZYvLDNtQ?-8%`%PiKn&3b+jE1cn&n6S7Oc*y=TZqN=rLy zwO~<-j!Z$%*97Q~*UE9qz6<#^Pr165^DC!SgL5k+0A?d3Kc?e5o|%0rj5))RWMnS= z)0cWY3v{TPM>bIwcs}?c)cBrDvfL%uW^MeIE}1+qqjPFtA+(J~=7Vhs^t&7Jv{-PZaN zQASUn2wz_5+g7XW*oVIR9N$RnNOtz@PYDM}1n*2)zc3R}`(ovSis19nnCu? zBj0t8^01FED^(S`+FNPHeb#???76T4nL5=vg^|v&)XMR;t4UF2DtT4xIa0^5XRs^8 znK~)`HCliLjC(aiCLnYhgHL33MH{hItl4>$eI3evd+{3dFhI%SGk9K`aKvhWc& zF!3~#p#|82Of)X>J5$qo$A!l>(1D}P85pZgtXmB_SfbS#EuhI~i;H)(#=mal%%<-X zjGq4P);Mc2NSIm8?ZZoyrSSD&^c{6upXGumI{~w8Jel-DtJ1#XTN|3~s8@f)J`2rc zJiKsrN@QC5Vhc_eP3{kl_Pd8yDr>(r1y zapY2Bn9{)m6`R$g>GMEH{cR<+zG&fjqWFmPgxU0}idc|*E-=-;TSU(k_4^&yH#3!4 zm-tXi&t4=Qu#}%<_w4P3L9el3fG!gyBiOdG(M1V%(FGVG5WvpdYy+k;FAm!=ZmY|p z-H`Lndd*DU)1xAjw-6G-9J_CpS>yL*cKX%EPxx#H|}O#?>`b9MvH;2f!Id zwR{uBkb{iO zX(G`Q%NVKv`(11TXcR_H8g&3RN%3!`F?wuIypb7Zw?k=&dHITdDu|<-CeP6p3fCWf z=)_&ZO1tFo(7}V}Sk3{2HkN4O@tZhQ8kdpA*7FUn9m(ROKYwm^Owl&` z-Fq(-n_=AAcY?en>h6e+eIaM<1@?Bz^}plBo8`pTQ=+o>P3u0uQA~Z9?F%#HOUHsQ zwi>gYAM5=>)6}N9`SJd*;V@>+zU|lg8v?1C4{ATubb0o{{uf&MukB1%p zg@iJ{6Z&iW@e`h(vWm?NbRz%Nrt_XPm?t=TzBT^O5H75mws2}CNMiVTZk>gbJ1OVT zwfNRuKcmd)1mn-yGJ2Z{E#1~=ofYyvJTdN_@$o|MgM1Fj=)_apd!_;NOH&v6Cvpon zJ^u>%Z^+h_e`Lo`y|wky5fhzme)Y$#E74y{N7Mo9oqF@+WGmUGF$XUet=-N`V>zp3 zB7fMXAg|(eG{>MHF76vEfzPdOr(&r(@wh1}sUWqEhV_}zWS30z2uvYoTUBIaRXYIt z89&y+L<7T`mjOE_8pQG>^6v!C(Wmiz+2PMo#fa;GY^2B5+ChOnXCSVEp_eG5!d^rl zW1y7?OQ?~F9$9s7(d^;3wtn`Km=4R5bbW5kjS+u;OT-;RGy_za=_D{+wFW3y*IfBoyH zv32=#zXld#ITY6h1|=}e)b?|No2UgcpZ=S|GXmSX{WvrKlXcZlGZ{W@FllKS=6XCfsi*iy}S$uK`M#a&Y ze#|i~ei$t!zi{UxGJHLNEVaAnA!{0e!WYmhWUV!iZhG0mRb?24Q^beAoX&-aC`HZcWiB_Ib&Ae7| zZ^;Tw%XW35vkUwsL$Hn6=v3;|qfP%BLtpA(@kxd9UbnI0KvWa{@W0Cc@m4|>D)H`eJr-FU})hedR5s4t4a(+LJjRE z&-xWJ{GytZ?H=AY4}EpV8Cl#_`Y~BN&E9Q0EwiwAoimifQ8<)s0`q>hl$$|kj8HE=U5ARAG;{cl9v!@8ujFtXCOBkHbKID;RlnMaE=2VSDH)5&YS!Az-E={m{Z1M zQ(#0Sa>L;G)wzp`U%mR-ml0Y1oPD)qPZEJfXx3&l%s6?9&gKgsyuP7|SIz(40Q32o z!pg+K56mt;lw0%dc2A2xDT+UN)t@a$4B2yedNWANE&t=tiZ^l{hM!za*AObTVcdLY zw4eFnNNx%lyBl2!7R#K_KT6fIH$6!4d`W94rH-=zQI)tjOy;@A6f+-u_WUGJ#h%Rr zk9QRio|XX-!=a%3%yx0^Y~?i9|LYNk?r4u5YDZ7xjE;S(!Gx7 zGrVej`DcIjq`LIIURxN~kXnb;|Ef#$53#cUqydN=V9ir&91S`6N9PzOJpbe4Y5utG zGa71>=b}DyqMHh+e-hn}S~s!iKO9zGEL~qU&3`7L?k0*^!vM z#lsA?_0K=_T&Q$+{3LRh4|Sv(yvcpWkww{$oc3Uf~mb`LXPxKCwwb@BVX|lEoo&n>RMW zE}v3|H!PA%ryG+Hf2hgI)F~TC+e|CN1K*1EI}C$?VQ=gKrCM8J@TbWyf%?X5If!M) zByC)6;-=sy6z$kTaFcvXP%3*-{VVOym?oWiAf*9KJ2dmj(h`Gc)1tV&QF>-GIQ8W*SEV23W>>-gljHJ*{l0 z0NbzRmvI7wLoosv*{y3CAS(eiyn2c)7)le(_(Q+iZR#ZBAJB%eK=BDt#`x}zvak*R zTk9M~D7pA>LaY)3=SVi8(}PX#gAU^PvcMyzYKZ zOW(Sx?U6L7{8=!YTxMEkWbvmhe^`4$@QT?$AtTxKxiv^1Vuv?q#yClO=P5*~N%IGrc_=~TnM!L$$lc7&_ zn2gK6dqL+76+B>`Xcs`A5e*C|9JaJYdluf(P{BFYE5iWNEfJ1QeZ9)uJO$t371&{h zpbQoQ|H^GMq--^xG;nFra~A>KIhRZ-zej-D^e-%V4QZYVNT3WTaGq-7Ci1E>>HgTe zrker{wBuGn{Tx{7DU7Z8eiZwwN+j3G_zx0e-Y6d^(n1-TQU+`)WCg_x?L;0-bkZeT z_iANFv6g~HBmrc2U$5Q}jeK57K?}O_`l!Jhom#S!q3>ch^jdl5%lFwgNy9w)6}^`oori0$;S4)(i=~~PU7a;G=7r9%*NN9a7~L- znB(9BA%T?TRb$O&t-zjob&jiY7uBiw!AdkE3Qk4ij8=10DVo!w;qsJK)Q=FGZV!lj z=SHX)P?Q^af>35CyBE=7e(zu;*agbzc;n|_0?H9$)R+pz)od4_XCEe`k%h0M`A?QD zk{6i?FsH(ElY1X@`B*da>ksN(UJ4OMmGsYQ>trJ_*!*Met3WKU`%FN zyY!KL;EttmOQFRQ-IBaGBWegQcJ-m_T<)dz$mQUHm8>MK5R1s&Kd5Zb>W>d5JtvL5 z9!B>M#kDebRam3>Bmz*w_O>Lpjwsbw99``3F9PzVI2%$-y;aDgtDLp_T`RjZEg}p^ zg162T=POM_KuTUaY12-SqFBgAa*rdl0XLNKJ}`yJ$Y!YFb&U@rKFLWvF(ngzUEG#1T)_{vwWT0QXe) z{fxew)AMT4`0|*` zeWq}_$DdI47r*4iLZ_En10N-s!jCmKL`qzg6uu&{C0*m+iEf@2)$~DzR+zA z!L1dUIPts-UzhQiP>!NP`&RM@>{i;lJx}vdxWGC8wm={pnM-mVBXc0wj@AR&PrO6>sH2Jzd%W^kH-4xtxb z!NPbFv31!oMy}xPFC$!+Q4k>r9}e~_*}9W{M7w+5rL)C(MtDgU0@!hiC_;=3sDE7v z7P#rqPiO%^XA#Yc|^a% z==I2RjqUd7Ao0#Ry;o<**4lAzEsgdj8?0exwkj)Q=VieI>4LdaxsX+{Oqy>A3WQh5 zZ!yOdIw$kME|51qg!RZmK1klmDa?C5HS8Bw8uWHo=kotF5UjM*-fgV9mu4&+_Oj8B z35;oYh2v6qU3g4#--P*nj@3M)dJ;&5Ay349%X2_tp`;x3@)u?>1(MEj(u-RB&=r^f zlxQp7?Vy7mN7w(e{`2WI86+O6Uqa?`XEhEnuX6dDB4Yae>x=I^j30aT(mm0LvM2|! z6>#H2aG)>htoX*sOe~iJ(<`8a{uZ_&+Ck^X+)aY|k<=qJDi^=SCs?Oovhk40-W5O2 zB#|aef@|2jzjg!jstDp>nMm^;d;B5UP4nsOV$|WZkai2J-fqfD=!OHI;&8mm6-(#~ zdM7`1)LnAlM_aE~Qe{j#6p#PMtiZe0d(j#7zWqv&r*Yc zE}nPGG>wHPemz*TpS`_i2z-Vl;Qjja6^27l9e>^A(DG=i=3~P_Qq&ab zX0utPjdi$#iO(+)8S9=fys(Z%j6=1j1&Bt`m=|j8*oVa3dTc8guALaF_Xr$W-ScO` zr20riplv4gM0mwl_>!W<%=Wg#&=!JfCAc>u=qX^nDTanGfA)N~aNI$Kwjhu4wM z4E0eD!#A<38zf#;``VCaW|%0DM#i=V!&=>6{3FGN*xwkYSBi?NM`WZ!WuQ_kppI&SY~xD>=o6{)(kDDdZ<(?1!*EVE(~*k}vnUcsiaZ zh{LC*djDip$-QB0Mrz7-a*?)~Z(3obD6ELtbc-W&2BaXJ3~(vRRHSmIEW!&F36=20 z+aTDGMH`22$c}`R?o2%w4q=a_&6k(RaE!s)3szkIq%kt)f)_GzrMNal2d-C}$fN4! zj8pnE!<|WDP>J-)>=FtR7iI6zY4%->7F{WiDojN)qk_V#3P5p=$C>BOcT;3S*hBoNC|BG!2>qtVyh9^KqPr;S6hKj zXOi0ZXzQ%-|Ie zk9^VX*c^vl@7lbjm_xOx5PjuFCiUE~69t6Xj*CV*bj<2m>*#$)AC-;SC;xsendp%)(_mz9z22VRXm zdJY#m?TL!>8SMWz3vj!D3EeQMmoXOdof!InEcjGf5WkQV=h_!;^H;H-^ zuRoN5%f@s%UGTA)y=8!bhK9n$;bYqO8kPnmbtXo?P(i9PF&Hr#R)MX2uk?#p@PgJM z@7u&{E4@};o>(pmajnN7Z@+wPv!OUT-+XjUTxHfl4HB`+`{5+@_3Y|aeQSYR`Y=Li zfG2ikH$;g;x9*|o*2s;KmBhCiS_!ZUPzZQ$-rM6JwSo&B9L{-LxQF?^F!xH z+$>@=Cvi30EqLkzH_8A)>69Hz4(+IHHOn)CtN{8^=?F@XD5)AZq+81@G0Rj>RPBfUtF>B1GN@!nRH?E2~=)U%xRHpV0c8}Egm|*i_-95%& zlMlgiefe0SgH>pkkxOMpm2I9j(AkJsK$s>q^<*KuVxq)(>qQGKMW(doJFc43NrPd+ zO5Ryv?NGb&d@hu267QglsQSGrh>FhW+2GlbYVdlQuz-^SSrZit5AP%BOQjy2&tJkO zo>;9gbqpBMWX3Z*ZTh;6Y!IlUl)T)C`JFi*2oN zo8f*a-ynaRo=o!PX{g?kj-l7-V_y_VHG)L<>)OTff5MkGDMPY>*FnSX%1kfYSjQAm zAsT*NR)^i$EZ$ual(fhLDt5GBdZ3w7$D7+(DabRdB{ZSgp``fi5Mx zfWVmQ2Z)7%g1Uet;^y~CM+MNdQt1bu0Nyg)r7M#VlAl9nq*8|bd1zb2Emj9k!KGyqHWbMIIM&}BTq_g3t)?=m=r}N2t{LCJT*+_=<9B%ndL(wQ)VtA{sKtMB^b7){ za4j)crS5&21ylQknA5fK@|ttu4tdKBcXZ|}n9S0ZWzmTx0*(~By>WYECRzy+FA&p( ze9S@lelxN&^(@X2-3zgsA_mVx`QxoDqyWbME4qHWJ9#XdqiDx>p`8lP=xE6%9cBwi zDd!KdO1VRHx_u^3xF@7TcQcgJ2^L}3W}<%VTcB=AX|u_c5(OI`l_*ICM~I&gW3;*# zZBjETX4L;WD9!sfe&?{i(%m-MAalMhc1YP2R6M{d3qd&Zo+uQLlUR?tL~i7PAWyH# zEa6XRnQir@;LfA8WTwC=!5>(GweM#W`wnq6>iq#Ns~HXni}-(WM1$A3kA*51kYR)C z@O}VzN* zRF@r)#!In3;V%s47@$`l1L<7!uF?Kxj^DxD5jCKQXx2b&!oy2QqaC&uPYI{b1tiWd zXu1Q9gud$9kdcSCHh;jqQljOh&i2oSrsD+&?$tiIM!ra0U9LhP#2b6tNK%|1;2rB^0q zNh2e&dl5-OLd{r*%`cr=$m2aFYwii9$E3}s|nwM=gPJlnywIADU5C~;FP`T7>y>eY$eDomJ5GtF=#309yT4gF>}A!An| zsDJYPUWZA#r?D-553Ao;PaHz2cxUX^r_m07v8wxHa1L}P-(PT+#5^2b%3_Fxb-Db+5diUs0i#0c^n{mQv=!z>yu+zc#49AG)$ORkJx$Ijk3u#$QMP-Mv^%0Blh?%1TkH$0tlA|w?Sh9{(#9FjV|-x$X-|h|d4E4qoLKTK z2+zftcs&u57xN0rbN_;CxW=+>uBIka@Z2axb@{)8&g{Dcn7h4^97yf-?>qyH&xHor z5)c?N5~D`YoUX=9%)bv@k4FdxM3#5vTF%Hzv;E?0aN7y^6Z`%ui+qkQ|y^P~y zixJ*jF#m4t>gZ5Wt-7Y?jdMWHqRN+C%QD}b{-1E?7fs|j_GA;EIA2*=skRZ!!?r)9 z0xxXxcfU+ZVNHtywx{P89c(&hRbLPe@}!rF{xl;XtwPdCA-cDyox zQy00Go~c{k#{+Js?%g(jQWkiXd`QNYV|GY^V^u=5LUy)x7wK1$edQ6blhIi@*M78d z`pr0L=$;&G`L*Q~=HozZ?tZIn%(rgN`2_W;ThiM~Pm;*6*Oq)G@(=*6>9Y+lm0L8X zgn_RcLyBT(l~#Y`|2}S$p+_HF7$@lbjuI6C8h~B67(E_M3))|4hx;$2q6MZEAk;hW z;qzv%D-9m=%rGCo*)ZK-|K>V+wU|0Ze{~&*hqS}ggjb?Ad8jCsy7E*!%#Xi@Idr}D z^t1J*J<9`G(Bxm_GWot|i|BF90Q6cq{mM?HfgD0pX#?#U0@g=f$02Wye6HnNzd=6; zuD7Uz z#NecA!o_E)9Z`+y08%WF)pb#&^eVX#E1f*y{U@OoZ>7BTPk>E;X;*HFCQI1~?3-5p z(`=M0-pd*AX({pL>wGA=&uaT_g7ioLX~PDduYC#HKT2P8RtVie{@1}% zuQ164m?lwSoUl;cTx9UV{kt#KFRZD*qjwI3ZW8SS|BMdZ#aj(oz6JxIxnJZB;SJb9 zzAH~X9P*a-!GF_rNSREm2jwgw&2azsbrpwj@5pa44ys>K%5d=QIQ#||v9oI0Q`!n% zClf|@1OM3W=rfz@=&E9UqVMj&hXm;4%2*=FA9h=16Ixo6aRqLu78B0~`PlDB4x|?B zb8;MA#FXM|SBG(b$FI$7lUIMRPN!W?^TBVNn9BM1YeGgCe}#65I^g0bHWSLTh@vF8 z-|&tPcPoS@z4+tVYrNB~P35}-h8Y?aNzSkV0k6m6e@(e5>CHYnc_b#p*}&aQw2^dB z22b}ax$OABv=(TrXVCmvLs71?!?hB7E{orLAUXDb>;C8Hj=7MgkiSh-8ZT@_Kg*vf#eJ0_hEsH+A46iuwk^w zgiE+(^=%1~@`zS)FMxQ4&n0X|FU`jrJ@j)OjH2uh4@#FgFmv6;>MY-07G0}iLdK_shtnOc&hK{+TRH6%N(_y= zSAIBZa22(u{)>10@I~j{qgQMIJf@zOw@k0?a`xJ;jnZi~9SA`RLz0^Z#F&}}Jk*GLte*RX9(0Sl##sq%i7SoQ z`n3GQ*5=i+3cbFB>%Xpypl~66i*9Y*wCLCsi|0NJSdO{Mb?Tt9YbCpIyWAA~`wh^+ z!_D!>V}-v4G=)*0+GOVgvk!)tm92VB@+NAe(NCZn*zSm;UYBpez5?L`&be_n0~-_ud4)#p;unQ)#Nb67rNbcY}gTEvIsOD34c8xSC`CdqM{ z6{)21Z()rM_qN;(aOg+O^Gj}Ei^G(AeJE`^iH|^XH>aGLco;q8&QbK`6azQ~I^8)K z&^g@4o-DGzl2+49KNV|%dApr22BDLBCN-w5wM-wNGX!oa@JFWd_JhbPTt?73uTZR< zQjp#OM#=k;!6?ZDs~W{fjYN)k35d34C81WFvM|XuM3#qzwBki8LdX}=&85CzxL{L& z`VEogLw0o6$~l0cgP14=KUHBrzF}V9t8nKrkN2o_7n9x2l`oUoAac+Y>;oNkrll~= zM?IR7p%O6a6OlNbcR)-2C|7)z9PgWI8c(KUwzVODE@7_kI$Yl$BLhEf1qtnf*h(hE zl658epOXC1MpgE|qJOcvSm?L6hKr3W?yg9?xT@vBAyi-qus}L#GW7EsM|>V_GaWE} zX4+p|EZ2+3B$(zTC;e{(r*lqU>05A*&&tWb#346p*` zY%%4BC^nw|kEySYYU=;vmLA=(!RQo5j0Wj0K?DT>>6A|CuE8kj8Ui9HNJt~i*hE^8 zkOm1Q2U1eczQ5-@=RAMz?CgHF-Os)E{fhVNop15$%^cMXw%Kr_^MS95`&`^;$xRVI z%N;N2*^p3>An)`G0H!1@`ISe;yh^f?1k?Z}PrIY14<)Fm4GMpnY?Q!%p#D>{A71{Y zv5wvc?1GZfrJD2u$y@qwmN~~ieXaagN-p?kzzY}h~4@>2Bl%GR~ zW?B$CY{mi&LGIpmV>Xc1&P@*bbnu9V5l)SRrTa!A;U)VhbQnxqN#Pc)jSZN&oqgvp zP6ZPG93|ag{I!M;R?`u)7T!M`{2M|h3@H6z$jeyObiUiHh}9}i%~LSP)k$X^@pgL8 zYrF^elNUKr#>y~|aWu7$?I1s;<2e7I_`oAnL6x#7VMSj*KW=~fm_W-?q#s`jfn`*NFYbH0l)fA&|T+u0^&A~l9Eg}e?7K0y(aZloLia(SZe zq@M7e3+*~AoYh9^r;*@0{++HjuHRIdjjpc}FY1FvT6PL~42&U70=ckUVIShp5+bA$@ z#0AUlvl;TU9uaSb^M4kji!6OA%JtaxordV{uIgwHANO7dU@D{b2!ADBCK_#&9zzXM zPQ;C8kC|a;tC|AqM7+0R^`f{6QUIuryEM>^JA+D3u-So{4C5)K1s^a>9Wn@XXQu%u zM*CSwzY(k(_=w;UiH(~B_<1guMukjaEy%Pkdoe=Dp7b+3z^)c-{|gjrL(#e;3nziei8A z15%;L8p=uJL2^3bGSFSBjE2@&V0bgkH(U73`_^-i5-g0K&UIuOcY$Q&-FfQWBuWL=|j6C_chi4YyfHq-Mq&hu~BaAnD1@eHTXA6mhC zmPnh>;qXxov`M0adA{0_($I+T! zCfyTUtCBS1cS6kh`m2YFnPT-&7sthc-`06>n|1E$8q;E9GwUaFpw%Fuq_HZl@Bab^ zv8bdLq9hps;-u;Nmzu8^Krk^rNq>hGFr&->s~iJ=V&Qly2h{XAyUfA`3)bR?X@rd0aeblK&)Qx4le`7Z;0M1_B!S8P!7{qtEN zL($TB-hio}C4GvDMpB8+zDC0s=s#5?`zZe$TaE5ue)ECRm(8TOXaTzgA%gh4LI$WqqYSNZzcxCLYKja@Y?*m_JoN zc^5qu(@5bI*iU*WCZ$<;&?MDp&px+M1&rQds_l>HXNY}FQ?z<`RrpBSB}^sv9)Cq> z)A(76`|<+#2uoSBP>*UT{;(*uYSgUIhDy5W2c-RuaSd`pg?q_07v=vtA^sEHoum*` zky{Q*7dMJC;>B75rOGHC;P(1gt&x*ANe(9m2aqPd&c4RLbz$w)B+z3hg06I)} zw8TVAQ22^&PCp-yqBPZYqGd&rHvI9%ZO26oQAHBQe`0uVjDN#{#jp;l#p;Vg|D*Fk z5J`}NfSpl~#$>3PW&J-1j_2K~8=Pw-q+yqWQL-3|be!HNW|7_86C*|(BIN%153MiH zv?N=HGFw%3eS-ojWk?|9qi+Fdeu6ZEG9*wBDko)J%x(`+-0onmfXzLD&dpDgUOZGu zBUZ<=z5B=q$dDF1{`?al|BI~Lhyf)i&V>IdhzXiTYF=VgH1>Tv+2uKNDgi+=Ila%A z*}OkN11^8YrGb>5qY4fiVUIrWsF(QW%%k6zjT3xI7{f7rZ-3N1xZn8)JL|yf!0-JlrkGmK#E8N`DsmwIK_7b?N>?#!a_7;VW^bUO}DYJPXBv~c*8KlOr z-nsth8f{)RS|I+BYwYXjMeue(;P}eke)svu)svUvJqbH?n^g}r}z$ue)#1SIZI2zy5 z)IliDQwXqclfSd*Y>N%CF>bds5)Vw`P-1*B(AZ4ZH)7Tn1+&>YpzN47Q zUWMPOEJ+9BL7!_<*osrmmR|c;_mD)$Cgj(0?i;fVw6EH@38Ux6&%(Ot2*?e|0w3^G zzWz$|=s|I%ccRZNy+PEJd58Dtw-DJinL^qB-gDdDxEA=m{ea?PI=l|8*B0RNfwXJF zZM5BEQ1?0=CV%(mu`bqL0>{KO7rODj$y@qamyW~sB!RI+XYHi(x*0OoNM6C%h`0H# z@`t5t&Se;%>Ymffluggroh5+a1iEkZzpto!BRJ_^?l>rL-8L*dEg@jP{IYPb=CV`$ zy#QM9{`d1oQVWiSnvTuxQ%XfXdksEU4zB+1p^D~hyUW{`U)JL)d-?ai_i88EimWz} zk(M4IEGA6#i5?g4#$v_#nx^dHo{OHtj?5_(Xkkk9J&mMgON5Q?wu5pMDcg z&1VChS~+6@pPSY7gH^@f%fI-3qRxvR{}cC80dK~Ec6-z8!RTPVAX|(Ez@erCpLX|( zZmjBLmxuyy0w)oGL!amk)|OXrRqch@%5$+gQ0Pc>YLmQC<&TG(nr|^+gu&X zeVW`*Y{S)15;FiB@buULz&%=<+KYnVX1)SKlPXLn?GZR{l-J$>rKa36vTVhC8MJL* z#A;H*B-Rz3i7&d78_(RkaQ$)A7*f-st>Q+@bzDRrjThi@@D_6H#GjxyR6<5GM^bF? zJIqSGRo=yI?dsGFZxM^DJ?t1}Phz2L^O%*-Yk1H;GpKQ=VkG+iyZ{E4E_RLJQ))jz z+%Tw^-y5mTqgf1mO65cTb=PmQG&y2tR|TH$tV}FMFl|IyK1Ucc*$rh%pB0_`<+}ec z1veFEAp8$sM%XoZ0{$~G1`vea z(DNtwY6i3NMN%+tJw_sbie7(L9wKHI(-@=tt?rWzQ?VTx(=To?C(NlO2R|X$$BC*s z{#@bj5yGA#K~zpituSrUp5kFy9+;TI`Qc+_yEM&UF(7#o1VyI$^3w!q`U!WhSz6a` zO_pR;3&9L{jciZ!A#765MNsWnLnaXMH<1okhz?J5V^x)fBJwCEi?Tn;Zjm5^5waCo zulu`&nq*ygCs}#=dtEAF%FjZNAHzLWOJq|v)DQK#?8^vf{%|I5#!tQT&JOZ+PJ z6BnZ)Pg0-UwY*Hz-U#C2F#Il*kpBzM-C*7@RTc1EG-)DdDqUHW?q+eA`rkZwedT>4 z`L}eR8uBj6@_3H;iC=cwNbK$bY2-nYK;-%;eI!_&7R8R5PGSi{Ag8?gZ~WBD=a>f> zPAAsn(y$I)ajb+hZ#-=sM)+7C}@*!|TvK-4@jGKmdS&%;*$EFm-2xMfogZkW zU;K3vBjZ;43#qQ!(Fb&Ut=6Jmp#z*OwWe(TeGhtE%9XEo-zWdbGNH7ppR5ZNvv5Nu zFS+ePhvnDIt0T{7o^9uA0JuIR#vD6IX)Zrp5(ju}QT2EAFhaqLBPyggT+1YWH-}w) zxi%1`T2U=Pe^Q!3e+JDzN&N{?GKJM0=e@a+gD)_>@Ndt8ga@#Db|!{n48n%kNdW3Y zofOnL$ofd1(#nd=PO5vpKg=$%Dw!?t^-*0pFBwQJZ+!Rys&jm z`%`OAK`glObmvHt(Fbr9uFpWJr}>5n9a_ClyFL#1V1EmrrreW>J`;&L{#yEN%};nM1xt1$+^nQeia688cbuFD&h_A&TN)Lu}cCe0`RLTpC1I3eodt z-Bwsl1rKR&1Aaj9kY|U+X{1RTWhXAIVyUuQmBtbHwUMP!A^ISNZClIvGosh2$f=WK z1;19xg%^I-li;HzmUym)m`h(qTUPI{>LO{G?b~KY;jo49tq`ei zzwRsxaB7!pd3?Bcw(StPBIM^8>7Ze7(`Z1zf^I4IIF>KSi8nNLyc&h+YH}Z4L ze1jzqCy&YU6+;A}u#l^G$lLkn`Ks6JPXhzb8~5Bttp%C%=wc1(-p?bzv|uTFMULzP zmCBpgi4!x<2qKJF@&0tr<3yLM9L%gX6P-%M_Liv+nhB7CSN^Y<2V4DNN6M>_h%8 zLWAotrw*w|}TRao!*R)9ku@&mBs|#89)1pd&ORA!rcQx2K%sv9i zXj8AJ9`<-`g^dOr^EQ;nL)`1eZM`djhJjbSB*A!2up+?TKSr9z#?haEl)PzP2Dz?F zKR=l(e=}d}rXh{4x4XGL72>w_NR-mP(KR2-85XtHw9I+#cc7j){b{*2Zv^AB)X!iKCS`5u-$Iwwa_1@V|^=AqNq3MEfTCe+`KoZ@<&V^pjwRf;F-?s&v9qbh%xw_ zhnef5R(w@<{I{H$+Z2!++3SH$CF;`=?C~ND!c@FzkIS$nmr~_@oJ%|U^wjz)Dw{f{?0$kgkm+U#eb!d^DnhY9 z1-5r+Y%IK$SKR&q0_dW|O7x3kr%{eq+ahmP0>`>LA(*9DZOGs!+A>(s9K)x-nqPR9 zcKsY`A(mRm5ZSwS_U2f-D$;1)lFxm;>ELt?p1oSe%$??><%-#CuBxt@6c+TNeUfED zUI!4O0?4Z-paAsjAp^bS*J^^-{4b_gdS0YT+U1Uj37%o&nEu+dZWKC_seENl9_JlB z*wLo%kk$emEEyrGQ*P8@Trz2e*u4Km@Juj9W9L$C(w`=}ih#==ULrpcvCr z8}w>&KA`ix4lNx3S`&vBPr-Ct2E(@wfm}3Bn%!4H%VoTWY)3c|oIx}gwKZpgSXFf6 zA6r6$xqR>2kd9^P<7AhJ>*uP=tF{{yrCZkH$mS#cO%N=ANl;~?$-;efC zTk%i05wH<_1jw&~qKG0AFySyXd5;(3$SWxJpyZcbddf*)^-@Mlvk>PAX}A6J4>)cG zSFc=){7;q!s1Das`&2l*ALG8(CCjfsr+AXO-CjF_y%Dz`zRGU?z@J_$WxlCoG|Xu; z{;e9qS41hg;IdF&G>TcJ?$s1sxbq*!9KqVjv1uoQe_`B%d=q(-@TS!NpbnE&bkHYC zwMudtM+Xp`#qJIYwZ=ZydI*h{XOXX0TrX+@wF@I_OCA#q`>;=?F zmW~&&bC6)oenUYnb_56!n*r;Km{ncS?;qwt})zHbFadB!5u;uRtC z9)wf~XI)h;xWSQZ2JpID#vu(md}tWctS2M(bgXAH^_p}qxC3gdan;gw5-O)XGs8G* zXlbU$F*xo>{Dm)Ig6o(+H*_MUcvB;ZQSewz1Wye5^<2j8(k;K%&G-iZY1-vbm= z9eHU!Su`_kmPYT0uKaBM9w9TegWY}DzU*s*u7A@t`(J1SmI7EhIqB2!BA@n@`kSM_ z7><0;CIUpa9xcekx9jtz0DC%~WsIaY*nK>dWug49FbkHAB)GxZ;PR;1-^_aX-qi%v z87QQ?PQCV9Zenb@huWC-KNPfcS9}EZmw@id=5qX`yX8U27E)yJiRtmZq`}-h(X*%EB8lrfSJ9#-l!Q&Ewmoho7d-gw8~t3v_lXhM7{;xH>(BMi=NCXTWst<7 zOhAxneuAaSEco*}RJ{$3wBbdSYwsQo&2wNpVkwA1pQ0OKQnhjxz&ZGEUOtlEXv#)7 z`nF_wA3{(5Y31F|7ftzj@4JXEWl$Vzq?xr)LzJbe_K^HQiwGr|Hh~r-&KL}{P9&!Y z@xkA0=%+pfXKo(9-Lbh1Bm6!n!9S?a{2mrZs2&T`1e25SI*@<9Y;&=zQr5PPf|44t z1P-)(_l(KJCVIGP*5h(CGETW-B4a$oJG*!NG3?gRaZWyhC^yiaH=t!80R@SEQW^TT8!ec;%G>MP;iu%nj4t`*2E=_+Ypd4W<$OO9p_y#?V54CD{ zc1)-w_@2*L63pdgh_S-rGMU{G9*k8Ld_n zT|VyIgN@M@{s{NpyYsPE?ti&s)8NktvK}a@hx5`RDB1pTLGbHlhGGb&ufvWtE-k|E z3ZDKBwG1-^IOv+t#FWja4fQ|_gA}Hz;J#$WPfg3_HEk;pjQrt>z~$D03{y-C13a=` za+4rNDtTSG&t=fMp9+DC>6B0&j2lgrA{qxRk7vpm9r%sfczDY$0`q&fL?xC&oXT2)XO8I47MMM^tKW@VaS0CrGT{M%8S1yYZ~?_ zsA=-1SUF%e-%zx*^kKfWRN!u#4eRm;D!W-dDv=AIe`vZcpff%~$tuMtCJRgRTg&|^ z7)JI8!wF(QAwp;R zdCG-dje&f0*Ss)c$KxyS_u}+V>lWS@DDn&|8!O7F zYo^M#Bz4Z8O9CC}@QHN5MUFg9?P2X2K9D?0vH}gLD7T)duM#NktsGDcc$^`A%ww-j zWTGbnenAV0Z`5YU99lQ{-J_A2Wzz?WU76m43&XAYp|J+AXy7}e9a}{I)7Y&QGnWCn z!)0L*Rt6P=B7m&x=(<8hrI`B1u~%2WlTY;;v9$aWmGlcy0!tiAMvbs^UHLz7B4eL5 z^=$$)IoHEN#$tDi0!Acd_M0UBR6`og z&mR#G5}e4AAe21LhRo+YNEbnyqC`jf){LQm zquwZzv|ijHc~ynvJ`+|abB-ajvNKVDYPFaIlR0Vhk7P&3Kgfs}XrYcGHmvMXsEv%u z1kl8CpJ(dqYgvLToTv)sBb@O;ehxrpxx7RG?=E((pqu*ozwPuqvwUVJd|w8{OIlto z=6W|xj(jdSd8+!>PE*6SvJbp6Xq@VXK~=;!K8mbDCPAB@mIpD@LQZ&(mt-UkJZ-*?%rTM`3R_PXz9p_d@K@ z;dfqd$z;6S-}|$*_F*<%(xO=&8ll#JS|hP(gV*bZ9g2^gcTaaekKgo~9vv0UgA-?c zRjR?UALK?FIPdT7Z=-2DojDdfE%5+5aF`sMsx6|VAg<*8btMb< z0$c_APZBEmTDArj0_Q5f1rF9*15-3hDD)WAJH+k`> zlL*dqd;Hi$BPX-1gD}NnJI+);EN=cjgOsEZr1CL<8$BZdZjLpcvn8#=6EPF?m*Djt*)p^(a2OY zKFpQ?`UsJ#xaW^8W~5~|E2i*&semIF0>xh&4xKyyhkp?PPB#qw5=U+{ZHAT5)8FOq ztO4&oY~)4DD%bZ9CJ{}{NCcEqjjgUaAMeGTA;{l_eLP?YbrKs1XrPb^NiU^z3pe2aAASF*9ApfsWo_h7rPwL1L%X zF~PRQr!RCeoDg5sw*r!r1H=xG?xbv$*2!Vc&&T7}0OG;}e$;7ONhtugyaxaZCi&DL z^9E8<+q$XA$P1G-&iem=CWlqVKtPgdp%1M$&-#nybj*Vd71)7-LYTAIPGc4<3z@1>_iR)L7JGVgWO!3m{qCQDQULP`GSM zYW&c;`W78Pl&tLo z^-AT!O?+jEC$dZLz!j-xvDBB1MufGS$DN}z{QDRt}wr=(J)X(hc=v=~wQ{UDOx z49_1YvWDZ%wR|>e+_ZL~d`m~vIHCZ~Oor8OEpCZXw?T)73Kylx=l<9ujJa%>$L19T zb%5$K&GZ3*p;YbG-uIuGdMwQ6ERLq)9fF{UJb;xQN;0lNQ>)#1H4h_m%;FWc(884~Qj;h;9qVc^ibQl$G_A3 z_nUwT(h{En#=J-E?DQ$c_R&c2TOax9V1kHk?_YI+0xkq{)VDBu{&-tP33pO}b>*IR z{H?{wreC}$Y#5LU#2cPnLRZ3e@}2;>sAli~a7`Th(58oM8s!}?^H82-HM#QNVFfQY z8CwDrb95V(%t(4c`?WrL4lD5Yi;bf4h0tI|+}}=kO_j$iP$GL_6$|;&#yt_SUAWvk z71|H!OV4OqWSrOwWrhRP;jFX)Fs>rfvVBIC==#>KUpL7|!Ez_3uZa;psJi0Dn))nf zgTT5hYeUS2Kx~bDHF9Lr*?{;KnYF#Zfj)Q0Pvo^bIBp#)+=0&t-~;P9y=6j$fOo4N zsJRoIPnBiVgR;3633{|<>XQ}|c-sQ_=@L|bv{~RIc!ZpMvT(d>K*)jtrB;c|e(Fx~ zrYoi474`WSh}IuJuq=IQz(~ofC%Kg%dsh-YFeInZq+x!*`K2!OFXI5~Z%?EZ=(>1b zh*XKs?saRSGq3n)3m7YGA1H|Ef<^vvaR1ThBPA}?=@VWf>Z8Orbb#}v1z=`^HW$8M z^~WVX3Mw4+Q6Y0G&|9-1TCU2>vSpAt=VRoQX2@ba^j36zU7GIFVNCvfY?U^s<9;sn zSj(BK`4JQ3z6$w8s_t_uOz!aCnQy4)S`l#J(9;TPbUHp88bFCCB4@2WlPGA+8e7%a zGB2ML`YtrTo|{o~OT44@@mtgtE@fp_=*2z(-9|6btxkd$H-)I+nBQ+UdMu zu5PVvyk8*B$+Lk9_NW8q=RZsTC-i^1_>&XFs?CyDN`5loV7Kh_@{L>sNf(z_phD^? zBh-H3#kSI;bl*3p!m&m;@S$K=kUibm5B9)sKGGX?Aro!m=*Jx&q86q0 z1a>Z^ab)M z%2AiZcrxlof1xM))maX6tJ3=ojy_zm>UK z!IYiqwIu8+04AFpJV`~J#M{^5Q{D}XyLr2*+dspBw}i_l{(|{}7X=m5p&?`9W;~sg z7t^n2_tG5PjuJm?2fEU=#Xthf*E=3U>BBa;8Pw3oYPU4>}sM{^aHkO zZMg@J$%dg(Rg_wJ>TSg9`Kj$@nmMO8RA>dKun$dHY{e9^TwVf;rm-W)oxTLu&-hhO zq(54^2>vN^0g_VfrEW#G0zK^}f5pCtaJ|&%cVLJCDQFm}<0X6Kr_#8OuHnaZi$|-c zgT(26q7~l~VM~AUQ6lP!;_5d>^bD1D(*Ms3kebH<{N=Q1YDWhzOb?ZdHPNI1YLbn_ z{BBZjBPb6|k3VmjNDK_ER>mcr+ZsyR1039OfYKe{*WExB8JM}AD9rp}Av)%Ti#<(T z6L+&T2@b~#aeWSV0Dhb11sYg)`(?IgUVLXexxT?7tFc z(N?c+hl2-eyJq0k~fVIP|*Ai}pqBq?f~H zfF8kk^4#iXei=>UNBXhPhC{{omdeWYeH_KI`U5Z8m9DN${@sKO0Da<=;cUEsitCN} zFe;$vX8r}VxI!X>3!l_~Nc!{8 zBn8(Uh}A`t;^1jQ-;JuhVi;&n_UhNOq#}UpLEtHJi`~#MHpp>(QTH@rn86X-bBi+6Z7?|sog0H5#`+AVfSs@&xbCN4aiVXM3x$qix-bPgEzykEupY3XCeLG+)r85BZov$*4!W6UU%$ zMOlydZsdP~2ZIu@E~+PX{=?IJz~nL|yvDITTCh&pL@Ieb6{1#l`&*Nl=mgTT=~&!$ z*}+JMDH%;o*1@GUY!d`nD9u*y7*4!Cmf9sh)DQ!P@*2_ZH8yXpSx(=_T;uq z*$*0te!UV+&;$4()vWfVH*Ie8X}B9xu>!|@plcm z^E|u$lk|9hJ2#3ykycD2sR`^qstwAfN$`Lbr-OC+gBJW6`+xXa($4`zDrB62n){y| ze62k<8V-ejY>8pdYCcd;0V1}^DN?5&v+Jc;-ZLpokTl84njM4!J=%(;j<*Y{3jVlN z%?DH+HKi)s9`qbpysN;-vG7KKz;KRy4zg*PY$%1;*LB^EceA1X9K>EY5k&0_^IV%s zn59Oa90hOQxf}Pg|Co^txl>EVp_1r{tnZ7Rv^WNZp3S0C$>mu5X=BS2uxpoxqD#k%YNyP(ev*L*jpm+t`UM zd{s^R*n=;m3-gNfK!cTao(tpWC-1oNaLsxAa=1}A&>;S{Xy=h`{Qi|U$q4g(9?(}~ zvqQt@WkVQ+1rx6|pz5vrexdZLT#j;-n9&_GvB$7qUwG1&?@Wh}OxG25Xt0V&n`0OS zW~%ksc@@@cIIZFK<&N*zR$jWbyPx$@&IQBIwl@*+PienTt_V5)ZLgTDT8qgfc6{GH zLKB$Rw(fQ`oui8_eMKHK)ti5wr9eO%eFg_VRc#|FwKdYC4P|7gy}Gt-Kw2AzS9~>EK2hu7sDX7lsN|{Fed=vGPl2;3Zbd zxcr8Cc76zxaoS_JrAG;2Y4#sj9>aushlYqM@_Xwy#elB4?bz93GrFDT3N)!Lg}JA% zL`c^IEowpfS!u-$n>`b#oO!p-GxF3M-eV;)VMg~rgwmtc0QxMLJmWJC?T-b0L_Z(S zziJ40;vcq7J{vxOm&3kNC0#fbV@B+6f5W`tht*C>V0UDDhfi6EQ@)dtZoL4`S;ol9 zK}79gF~N&nZ`xo~cPmMl@K`OL^N0EGjGJ#|y0@irU+QENJN-=)X0SD&UOmjQr1_anBz=vn-h(7En`+k_1a+o4}q4&}u zy#7^^5{F)FKd0AdUcR#}n?n!XPo4O+UssNazd7+4z(^vzm*5Ge=5I|SAU5E)W6Krw z?x!sB3zCk0`=ie=zdkTc<&CC$aspTHKF6`%I%OGeQjokPuPKNV)DEwq7`*_lU%nX33=K1T0j`GskM`;V~ z?`?NYVI2)relpM_C((%6M#B9n5CED*%2(vT^O}uH}BQQB?ZU@eA)paZbaz z;>(8Y{AGZ!us6t&ZFW+S+6qu}CycoXM#Qf7;ETb`4{m`s&bvK$)liFZtZfn@s zz~-))pj(WJ*eDGBTh6`i6-Ce6vrBt-87A2zZxLjexSgJ~I2zQ8l!rgsx_Wf<`!S6o z;D(`r@lyS@bXzI0(s|g>qI6B;PmGxJ68i*s+*&1p^7tBYKbIIQaz0St?0*ggSf1Df@3K`plBP})!x=k*p90<18Eu(j0zq3#_cLXF!Ixtc=wiPh)Z~l&omYcqap>*7eK1GuT{XQ}!v zKIX~^!j4ZQ@vWLU-QG=&}=@;*9fJR(?(4)sTd(U zw@(u@75*C|;5%lJSD$UIroS#%E1KS!E1JlJgDC%naP|%JD*xF59QYUFT>G@W-ju4D zkO)vbr%1$a8LJ5rFUF1h$4ybHxe}zLQWXyHK_WRo6T$YSvE4jf81cdplQoCz)sY*7 z9_!`_lvmv5z5G&{Nt-F)^;c0fE?aVRe|(H%+?~IaiiH?Hn8u%`WryLX(awfB%BLAC zqCb*6SUs)n^1&LZ8}`;s_DEr0NU$$)40Xb>f|9;Q^NlVCoGr z`=a5Mfq96_*Bh`YaQ$;Z#&Cq8yAQ4vCDJOnc+Gn<|B2-v9@6^V!@0 zJXXTH2bVxQJqvNKM{JLKH*ZcO`uMoI&cl}7u*d7=+4Ljy&|}?xUG+W4pGl*uMy)Nx zrwZ8#Bg-y8A+gNb4=Je=+5yG0xK{MEj9+u$ZhR6Oz^b=#q4j_M10O6&UHae%i`-MN z$bDKy;s0|W(0@AUB)BYGQ(!JSn8rQ~jr%=V%>N)KMlWx%GJYxV7kMmoAd&3yds2Y* z!Yo09`T2Y_OwQ9S(VVJOe_PB?05C9)FLdya0;R@m`t#_2RKQf1eIByr{l^#R;c~~6 zyGgi`r(0`0U&PsrrduMbs{GGc_oLGN&&9-c*1gP|k{*HwMc9?aRooI4qb~bS%Oai) z{0s~?IQ}R%kz+iB3}A9j$oxk~aqW4=P`@^n$ln*+Juj!#au!o<`}q4CkAKO> z2fHRdi%w&HX(@DM4@AVw4mV#9m?GRI)I}}o@-Br@CBTWbU=-}7Ue91tRj1FtG>RW{ za@#=@@~5MZS^P?z)7q%iaYnh~o{!=3m;b0d*)W^MU9S^^$*JE#2#dcGqJc>^ZP-jST-hx1oQGRlsW#gJns#WAQmo>|*0j zM*WDfv(Tu?4uq=UBW;#SH>}-=ORZ=|)wSF=j9}nZ#rU zp!7jMa-VJviW@m|{N;#ijk8Hq=d@2S7G+dgMA=-}wXab_6@_HX6a4b5gS2tKtOknKp-<(l64C<#k*ZY6uh!_TN>Lj-WQ1Xj z^7d=&jH|}~I(*;ToCqE7a+CF@szgi6Oaa40t!jM#(j&Sr<-lmk$c%RUDZAtQ{Ip1` zBM>Unx~RsFbBFdH-RLUmL4KI%)mYIz-evZyotXUb#794^d0kY}Uh#d7W5?wl)g6nV zeHtv5O;tni0!g6EqS>O};x{S^RV$;cr!kQox=#-mR=pK{daC{WazQZv9Un%rKVtHuRissqg zJ20!)VJ$W&-sfNa1W^{{>wOflULjC-mF#2PwFabV)P$G&cE31JN^aItnM?wI#*$uK z-8e~jq(-A4nzZAA?$?8O@475xdt9IamA_9X2cx$gP3V>U+l>G{>;%x%9WmOGvBoDH zPas;N)2wvA?9iL#)fL~^1vC2%1l>8GQANCSfitE)h=qQT_droYR_7=h1gW=+SIPrsx1<&UGLgER#Al3sP#)f&++~1`BM%@!jW*_ z*LA+m^Q3(={+X_EZ9c*f#^0;WnZ+315?(iu@psB_E}sug8xJWldUUK;=3rFf(81`D z&Vg@X_P~n3v_gJ5lGrVR>jSKG~APM(FbF}j*7F9 z4}xHf_Qme6qR>i{SAQzPu3bs)v*Jnwt`uk;gnhe1dSG@}RPk5=glEj`n=rsnn9!Ii zc04Y$f>G35sfX^;wd3?LHA4Q#`975;{W~rZ9JQh)WMX@O< z;Q=)exB{?`Vl(2wVSTYDt@mvXa z$IXvVc=?TcOsZUSQ)DO8C}`sKh#jsaC# z?JYTv%>~;>*M`n7d~CV6I`YeEys|T>k&b@cy!&BPd42dDoOWmfM3%2d?q!rb#pX{C zC^t*e6&MX>rI} zsR>c)!S3RX)HfumzuSipEIU`5)m|+n#fN_i$+DTKsLtgY%iXdqI@l6_(Y{pn=H>tI z%QSNJDt*gW^`)wZt!G6JLsnyNOnwzFJ(KV$HklHPP?V>qQTK@=Eu*&l`8VSsMV^n5 zGX4w^1@cW0m3B;mMgFb}EQC=7cX9j-0%-jP>l5X)Jp+O-GyswM(pZ9^qBp7%Aj`Y_ zmvbGg#!R@ec!XE1rTDsebVwBDTG%o=?s)w3G|&^f5QAdwzXi)SlU|xC7RlX3Ik11$ zIq^ei_B*@S(hvP$hlK}m6=!0y2TUa*+&610e;nouI&8QTkg9nZ(FD7ZqswydF#2!-&Qcoav|3OblkFaD|dyXEj!nt!H2#*)Fy z(YBoPjjy7UKOL|rvXa=Y-MZTUDc!w4>Hg1Rj8RKXRh3esp5)z>Kfc64GLYRZ zFker8-grLR)3vI&7LfW%CA?KBLT2(umu4O4ZUw>SVd)$hDKq(;_*GjiF957`@?c$A z-kNX8;qbQL`O5Akc}yBkE{P2Ka=wBf4Hkpd+5^}6h293iF-x(%r*+Yh^7fi>$4ga! z81?Su?G#h>W({(V#FGbfWW`n1*LRJf{+)(y4^}ndUn2E4&(HoS7mAjB-I|PwbbHm7 zrgawICsQ6Wr2FOAqezzNXq6XZJa}`%_TBvs{PBXGm$ZT94e6$kgy%xX_qIX|X7LA^ z$5$p&q@;pE0rv8=^mei{yDq0xwGz3_M**Y%*7-S(zWY=(gg6SCcYbvsVlm(FqPT`q%-K5!SaCJsLZ4unr!K5I-;FmzRN{ADgOLJm?n=wO$oN4)7JYI$3x^B0Va$75@z zqW?nag98zZQt6yCDaJeh8#@QTWPnn7+B!#uJ}wC=Yl$e3_+t9b>f4XRI{wC-p0~}b zOk^7{zO$XSiTMrFH#sMoF${Re*qfP{!6vFE@t<7IQpyUVgHmc3oE{;D~!|ifYkC-_zEs_TrF~{*0q?i4*_W9)j_a>@|ol zVvdZfu0H+zqEA1sXQ*3alQ-#Lh+|oRsgP!Hl-2T-Doy`<@x;mD-_3Paat)@btA-O6 zAtIl@zv8gD$tY?+p#tPQ9Ad#KHYEyJNVtnUpHNhusO!F1+wGRj6t*f5IkqW`^LV0$ zE0W$^p%0cP^_O&h>Bb3Q=pc_ zz96PZS7x-)T*H^m1C_ta}C)L^~!- zNz}Usixk<}p_^FSeB7(=MCWr_e3Lc49Wn5Jz(#ykbTX#$1T&D>w*4}7;y=;}QJT_= z20~H@W=9gF05HUtQOVW%GYlml9Nq39YJqt-WRq;Yw=ZSm)Uyr&-pWU@~AE4stu^y651lgOFocd3Sql1E-&Qei}e7LB?4ZM z*U9F(H>@YD>(_D-BXHUylJIXQd6a@Ou_}hc94`O9*8TMp{Vf~KG$2j?_nDpg{G=1n^(Qa9 zHK^j`7AMfV7HZ*OTYGYsE4e)L(PCi4r5aWOhqyZ3T>3W_gv!=^k{w<)8yjB52vS9LWP%|Qo7cOnGU?oZ6$FRXuo%I{UulL2z`E&1Vm<;b{juLW$~ z5$Wx4c7!pPM9wZBl!=M_<}A zeU3g1)dYbBTZ2P`WS1r@jSYv)Uw8l_RFMi}!6L}_h&1tDFR(@NsC$TAz=+?RL`2#_ zjht06Ha;(_S%K3po1fPi=@B;{I$`AL!_6y|&OTmhMy@S^f|p3V3xRaTINJ$Jw*awz z`s@umE+Vy?YqE1v3b~fap$N`%+Sa+;mWyYhO(YkF1THE~JoV!%iPZ!OWAh;&v^crW zcZ+!#M>Claz5_Hd^3m=HAU2BI^aCc;AtBwiDTYxg_>Gf4I7(Y&(%26eSiB;44k+~Y z-VEkLRiAb#kkdj{5vsf|IY9z`37o5>+%Du0Z+jfx^}c>LzXY|c1k*TtE7A}oD~uKQ zI6O?0Oq`XC&|rMIv@iM&)0m7kob~ToIwM&U3y2SfJfYg;ZCV1Xom9cIk{#a7fpzr! zs1n>DV%BfYA@{pSpJH6mJ<1*Wtq&hw$!J-GjM-G1RJ;8u@1mIuT+d=QU*N0W??@T{ zE12&7pX+-*yA;1?QVvRwKf@ zP?9k%)6JTZZpZ{ocgs(i>pTB6SHg1aLn$sd;dDMf!`tV3f3i-JX_d8Tu1R2)z`}Uz_Jn z$f$TXT~SnF>~uv7loydmbRtjtIO0%AATc?dsNif%>2Kqf|5diYnd)ISc9C@`Jr61F zkvlJjI+$_HdVH_Png`H8KNC?#qY*gXm_D|xhCh*NQit_ww-UlCPDI?6H~+AEFNK1X zGmS-JQH01efWK;m^RX|_C&M3qB9C2ib`-Z`od5f)D)>G1<9v-)wgO7{{bKTI?358? zz#p5R74N{E&Tw3mqj);W_sU^9L$Rsf(gmCgJLY(tH5W=VNDkSuZ(NN?O`9`$RCr$JjE#rNe{W)1KqiDv4ZYgRNRk z;T(vj@VkyDPEAAbEU6ZY2dy9%fkYca;Y}tp{Z{%BncJ@y3)`C7bUwIoNM}BZZ$7qV zGtPU7GydD(`M)y`qTc%cry+Co7zUHLnvw1HF4N7T4Pqh9=*)<|u8t1#+wQ=+hsZVw z&u%zmOc46<8~j<--%fvPZT=q%ka@O^bBvNJ#xNo3KoLZWc-*V|0Pf!4X!FaUTarq|S^B`Gx zg+UizxgnD@)Epn7sRaHg~+*z~bom!Yp zq6rBsooKhRYJHcw@NO}H#OQQHt>b7sL;W}V$FE8iYZ?kr;`qUkLlL<_Z&TTIm@)yU z0*(uo0Ab%=^BysR)J!vr*PNyhm6k-tcV7rB`L2A*z4EUA$(d+Cz{`1> z`r|M%Kjm&%|85v*l{GN0#h{sTOSq$yvr{u*>e_6%5e|tdmk8VlVMPOCT*DIUP*Pp| zH+E;Z@A8C6X9RXosUf`koS->{oe|SlsqTZ}%_hi0ZWl&PVPo-<5!!bUJiSI&u4PwF zc4s5O6dGqGK$!3H5rVNa=%dq~Dd@q~_0mr{dxSMsuX5iN7}pp(k1?w-$>vtWywup9 zQl!s;25Y{ii8R~U6&~>B(zm?+&W~LWTs^jOyzhQ#sDce`FK__=5FG*khG+U=Gi-fb z{GU1%l|N*gt#i`P-z~LnrfQi2>KLZ;;) zalx9=@@?l&FZKdTr3<89%>uuf8vXh>rj;Fv@`xU=mmhfl zK`ZLLP4QTsZj3J}l2w{{pFPmP|HaO(>fLHinlsBl2d{pIn1w0h+{3dePXf~< zY-|7#clT}Li;DT2503ZYO`nA`!`B_%vw4f4aQ)OrF1E?LOaKc@D&7wo!LV}r#Ha+S zqE)#~vg2^^ONk*z=z@hfT^)&`4oKJ*n~WqrK@(3vqzh2$6Mah5B@Dm9S09E_AE~FO z#w8u&$5H#ksY?ynptq}usu1_Se%_p#B;eh`>*y{zW8GS@70DGxxsLDd2U7!Jt3%)Q> z^Z4=dWMw{BJn3>XzM$ccZNx;amU`>zD{QiDb#6ofrG4VTb2XFOD8$^m$O8M~)X8*) z10S$4cwSmC0)&2~d67v>V4{uKF@1}q56AVfm=QED9uGgiZrcl3y<|eF$TobuC~3F= zPzI^gTWC_3a3SjZK0D^D1T~_J61&r7PgID@`0f2ck>0&|xecLaqv2ysy36|F`Jscb zDzY$4m}HtF;Ao*fM0E2HHtc1GMn!Yp>u4~#HWrFfG4;Zp-u1(ltvbffrQ7o^)1!Z` zh^|W-zpJ`F`qcK5b4*KBD!NJ zyX^9?D%694goNO(VWf~^UT{AD1Nxwvd58!1i^^{F`owtugLQi>;z(ZS5rjETOH_Bn zB;KJmiH-X=SKb2a^0z6c2^k>|!8)mMSU6a&WrlObUUJ-?C zGqzYD4M^2KC=|6o%*WDDv;gZq{o31@n+F{6*I^b6eKISr?yqg6R1QK&kwyJ1vEjd1 zq1qD+51NfPZ@~{>;vlOh^I2jJPAVo^>C(ng5QY=`=$IY(GKa^@OvAv#!;L+StJ1Ju zR}BiE`KOySTIW2U@V<KBzwO&}X43-8~@PTst7%Z694% zNJP=1Hv|~uluEoWWPW5jS?yt=vb3oTY@MnOh7-B z^-@TccKk?AZ9X&6&z7ijHhR75R@Tzj=M0R;udSG!j`0~octTyti*u%rV1Ztr3Vb+o zOMAY%-4`r*G&j$cTi&Rwp&g<9k#_%?fm+KGt;Oi&;(7^VbmOi7&$bL#FW$*^v*G{c zSsb6%6#t|GYUIGTx^h10YP0g9Q53}FGFvPi7asXkF&(rE z1bC;9LI$lJkST?wZs&OpHAi4!i!qjH8}i2X^w5OJ6WGy3hi1J z%amK(k<^o-YVVpSgSZ252i`&{U@{tY@~Odc${%)ho+7WQ^`Mu>Ng*yZYXYDWD8qNj z=OHUEqnuu~H{+vCtTIY9g118D|Gs57rG)N|VY)RHLuK6guz$;O0w@&C*;S8ASlCd5 z$7B1y->R7Zxp^b;+W9(%3!--48fsf9XX*K{AhpSl#4n2xY|=l@Ds%TcZCZ6&T`YVm z2ZYEQITY>G6N_T!Q!scjY$KPdh3GFOJu9h&haGIePe0?OT4*DsB^p5;<^!L~=tdZC zERhC^+C+a4bVyx56Fa-*cU>UoyHV<5H&!R`RT>x@wC3Me|sQ=*L98tU8@qa82QxU`q27G2C!$jdZ^c|AvSEhystzo_|)E#o%r z=J2msH%_SM+4TAH*t+W$?r2SAmnhBuR0qT9o-;n8X&p0`c~DKpxLK#V_w2XC8z69K z{?{<6%OM^`CtOKx5v(2RPJx;*ug_b%7b<(xoc&02$XBgti00TT7PJN%)=3M|AJ`qG zh9TdK?>+i0$f)-l;FRs{#_M=wG!eXfoCWc?dsx`k8AFCO&RQn6460FXRN@y4Nu)l; z)WeGUgUBM}tg@#3;;;s;McMv?@s1cOE<4u&|1+NfbICS(<|h*lgr-py#cc+gS@`79 zl%AHa3nmwtb!Vr>cqLbzisuZRfBD_YRGyQc#zrOY2M?Jw43OLWmXYk;gfXAy3t|7Q z2dtYW+Iw2RrhGPhUHGd0-%*N^B`_2d+fF6@G4K7lbyXDW2|-~;%D$>lMM=h#isI|% z1KmfWjRi;6M`T)D(}*zEOJCET@Zf)wZ-$%OYyx?Nn5gr>6VNe8%cjLciR)b)m2cbsp1v+z~G!Jul=}Ao8YC zG6#TxD$?)>{a7cZODa&4d)Laj!9}o(ctFRsqX>-ij{cHh{cM4b?P_^EFsutD4WP@! zrw#&lM@_}jK8@Zi-Co;)k{XAhZ8!cMagRy}JVBVRm1{c}VijkfU9w!BTlnQLwCDL` ztye!Y<4y_GjuKTfHMVnTu>|@)6|R_qV`E)sJvTn9=h10@c=+|V_SkvZH<P6sl=%qtSW=Ymf0gcEo{ah0l*S%fLmH`>Ugtpul2ClQ~u4^OiKCEu>U2^ z8(Wo?kW3v&tLMWz&1NoVsW&xG5vHQ7ob~bX%@*P&m#^uJ#W)&R^Xu1_e{MF?Kd*2w z_y!jOX@g4>Nc6X^fCE6UG0koyto`fR8+n&Jxzgs<;eHQNEx}fJ#gxBYw$;?``=w+9$;Buc$y6k$ zp+bJ^X5_f_OH5mCG8Ef1VXcbrT%V|V6N;^7_}pf7uYV!{i2Q;vR}K?R6hbo^{K%Bj zrNo+gLS74$6T{RI!(l`I951PT_?c(S=`(VMP+EkBZh+t zQlwp#qSmKVr**{1_BH&!#YMj8NDH8uapfUPFIDjUy#-u(X_z()qhe&Fp;RXB=F|PT z#f#&UWRklLa_DhTivhX*=T_13w38XF%vFK0#bRokTx#YarySxGADvc3fZXwGWb5A^EUt624%h+Fa> zD3L_w4pK8;a=*)pJ41swLtNyCzVd5kGmYsI$!yyZb9{!sr6&7INQ4^A2ki~N*Hg}= z#BWiCnlQ`r#TV=*lS$)0l2HczHJbwYH)@8S+UeRQI0#SWbi1aqYf*9vP2;V{YgP-m zrSo~=;G{EDK1?T#-ocURD&M;P3V1O=aQ0|)+BlOG{n*|;zS`aQ!BCYRJrQ|;#Jh41 zOjgK~mz;xBhU}b9#D0?t&HR6BGg)|@eL;i+j{UJ$;t#o8HKJ)q55Re{-%iZn<`USWKy`ko(e(&#ASfc5@{2gm!fU^f)>rVmr4-&Q$WkSqSC5ob*Scr!7dh zq(Ak>Nq;2G>}m25wz7XyM12L9mwWd>FG_x6M=Rb@^+t`1>M7)PVmTqI8{I+sn(=k8 z^|sp?=(RC1O2Kd{kb|1WkYQMj)Mq-P*YXpO%0v9mSFfgkem(GlZaYUlSup;F4*+vPvvodS@B>UxEiR?ZbiD}3;}i|7K+ z1AGP-cI;t8?D0??5IT`ruRfU>;U#PXGG?WX^RGjzmk6_7?K0s0inJymwsy5m>%c9? zH&oH0*BZwo()cAq0Li`iJL{5){>qpd;WD>UOlu$|=4v(Lq?E?K&QyUm{*L~U)IfJXdPa1J6ymT$Y&AnTryF7Fp+ zoaW-f*%D$`UkcZ8HrZ1lyj}XguM;}07yYjZg-VUzG?}R1n3QTK^7v?$pA<)k-sw4jT1_N`4@)j!< z+`9vh%=6hcw@O62cw11wX`5fCtKLXCHbPo?^9y4T_JAkd-M>vX=H4pG^ie^wd3FDw z(4T`R`B)?ie&1xE?sG@l5WMES8%`!?Fk##8auG=yPVrra6DhvXp3ha{!Z0Gy5^Y74 zxW{P67p?TeCwA+75A?`-1%2!-WbZM)BjJT)*t?>Y)QDg7{j#N3UvXk&1ao;^T~>Qx z@})c|<%<2}%adwAiKX=*^6Xb}gbZf2A-`Y(1JTf%asP7tENyPSo`vQJ@Jzf`rz6Ql;ehPCyt7XXyS?vJ1~O{rzwj!?coE5nMP}N|FI{g?Dpo8G zB-Rz7v6`2HPtLk^{P1H+=ED=D!9#^^S64yQg@J{U0(C}bi398^)em65bDe`(u4TuS z5y5r%H;DM;6QH3NLhz?!u3?zFm?uI5vE4b%P4dy`#JFXToOL$tcce_%dtYCg?7IL% zfuaM41$_B_Y@`w^@|R%%Ai`JBudKyNzuy^qwcPny(%BjlK>0y2ce4u@gphr}K>dcH zn4pakP}cz7jS~hc@`S%2xLv%mesb5j?(Ou+1`&1b*)s9P+RPYRjL`i9aC|c+80yyD zveIgGR!FKvqx0cR4V z$7kZo)yr1aYvd_(fdhVnmBAq9vGP#E_Ug6`Y7v=9wg-K{DEqzJQS^JmqOYIemr<{KXWPnWiOWLPTWd&`S&P_xl__FF1ZjyZZR!#+?4n zn^uQg{Cf8rLH_4~YA(>~{fu@tm0u3j0$^LsPNvMf_wKS0ur_$vmKJh~)e`2v5@J8+ z@{E*R<|O8?>)Y9i_pg*o(wk;Nd_Gg}gLP7leB&Wsu!5dsAo=hDRCTWN1GHh~1Hm_J zzJZ+@`Q7A~uFKI}Q~dx=sW8o)Mp%%}P0+eTOw+eZGYh_gx(}WDn`pu&b;VS4T7mgO z%#6}b?O?vXU~TQDLQNWXs4jNPl@)_I#k3!p^WQ!;MSQ@c@ada$r0 zq!=og;#GroCd=Q$Pvt*E6$fF9m; zA8O~d7MoS7^grj9)-|RLao>(Mejm1elL^P~>c4L=7KhbvD7pi(~5}ShQP^@VuEZMT0TuJdxV65C3zkK?pcpgvt?Jdo9 zkx&1SohvX=U2O8Mm35adl<&;;IORa(_ia5s6;O5_GIf;lVE5~{4BVadyxc<{L83YI z*Oalr-k>S9XN$?x+rup*a)-kpAm3Y(hsoiVkVc8}wb0(}^@54ZzfbaaP0BvO(Ktq9 zej|QB_LE$a&=KrM`IC;#2zF5)>>{)=ZY?*V5#EUA5ZY@u%KgP$*T?42&3f;22)Vez zgPi}Z&MXNb)Rp|*{%2a@5y)}1-v{Irq8T%3FO9C49FRiIErZnRWByP(`mv+Qz zR~HCjg;$wb&uJUyn@1e)?#!$N4kiPEU06{~sAVK;+FBg^<~cO!vFN*mcZ6`-!Kq_YrgrC7xsHx#F?OZ1AOJeLKAcIKev-A z>@hgV$)4=fII$opsk#NgLz()IpZ|YDcKpTXJqj^aDW7YrfHXxt%cZilcb7%{;H&U< z%iXW{U_wdwK&OU!tM&M0Irfy!H4Pa1mub>h>=|RfX5@8Y_`|0fk9_=1ljL1#Yt}c? zBD2}4`iJCQRf}d@wp<)-e@IqA#;wxq^bXnR?4VA=xoZLxIpHt6Q2rk*FW&EO(#aBg z%AjSU9qgEqGBFK#WR&(qYAd_IOzE~0j&(zB*3s?Y*Csqd z$dUbFQLUW>^P1<%mF&0VM`Yp0)XCt<&FmHNlVD6IzIG|E7WXDrl zUq6yg3FwxN@@EaS%gF~97)?i*pMTbU>2B;w5QLMc6R+`HU5nR0yNo6xA+5bpa`T@SSEUJ1Z)8ubVj^Ey>!PpP z96hu?wUPEaXn$W zH@{Skg7(Y1kkimgCK()^EU7KNDhuONUW$y5h{B=M3V(tPw1E7ADGoq_gC^r8ySlh| zX7mfB@ZfGz6om1$0g(Flw~Wj^RF)){e$B0zW_@<~gzDk2dyuq|b+V90&(IIZ7M4pifnuM$8=(#VHA+ zAO`&A4NZj+l+}#UaFH9fv&(95zn!-N*K<718C2NQr%bmpQoV3G7Qtrw1c;*Q;uAFp zx;b|Kj|JEyge7OOvC(_T20z=xd`+C8Dlq=rO#n#VlbcAav5mcZ z1>3i!xJG^GeNqO@L67Tr{bw}-`49V3|6t7FbqOu6f0DR5+N_h$3k8PJsnclNnxoy_6_^C^LI@ zxzGq&{$f?RBJi#nA#rR~yeun9AR6FZn|T|hn(9zBB`BA=mp+{Z7ef$mUgUgTGot}F zcI!+9Gfw=7TYlO^N(f(}QPSzHn1OkUy@|3T9Zc$(FwUes8}lLF^hHz>>N!DQ&bkfU zP&lLkuBjh(yM0dNLKLzi-mz*gfhoojzy%xMKob@mNp3DK`ex6)?RM$Ra`sdD- zw(qXQTHXjrp43T!dPFl?2%^mV?Qy!x+NG+Fu|fCoqG-yJ0Iaf@!A9 zqLrmjx5~LQ3%9OBAxKJ4(8MQXd@LkY;Qac zh8=+>a+`4{N#xCmL?wKvRiAhfaHa55Kn`c1ZO=YBzvDAn^5#Rp8`*Jz`;G#4I~l8lXLR zGKHdXpym;o<;eXXEAi2K?qx{Q@#`yFN4vuSjTbdWC(Ys(!7?gy*Veza#CpjN+vvO$ zSg5;xYN;LF)C2n3uwu3B3R(cUV&iX2htJ}**u2;)vwGaHP?7nKY5$avKZKTqGMNTl zFdTbX=}iulm=UaR+KIFOp8joseqhq0zWuc;`V1>=|L_@u5awl?ton)$C((fVBXR9W z>+R3EBOkwrPK#4pwewfNT>OOhDcg@(I>x5|`9h=?l?K1Gl}ZyUY503)Rwmx=h)n5! z9&3F-d4_Aqcpt!#SS{-@ow9RDwYf_dOMRR+tP&RZ`B&aiOOe;V^#j=*MaPHQRXex& zve9v@ff`Bv=RCttI#t8$QZ|YbFBJbi=qfAhZW}B$J71sL@OqkX z{X2QxVT1T$tZ3vhq~d*qkFB)YZx3Ovui%&xtk{p;O+tk4cAw9N@|HL%N=Y5K#N1Pb zDdlYE8d|JJ2&Thv!pJUp5O#hyR*kXOuK2OMT43aF!kB_61>%c*0 zW5L}T?d}IPpuMvx^l4eo&`5zxn@!XeP<)l_|1;(*~9Zc&@0De8=9_sL6jVtZ5h&AzY zCehm!-MwuxT!-f8fc)xB1y;R&|H9Q=@ENO|Cgu)`oSv$`U<$Kto&ofAJLddi6}m8S z;5O!ukWXjme)jB1P*KC(_s=%Jg(UJNkcF)Q$BdNZX>KjU%j~EWsPV}w;?6Oy=<34% z!*wUF$GerkSK)f690i{_HO=$=?-)F;fWg5v!fE5ogPg{2f;onzXSneAn-0p;=QF zeDh_%5xlzU|K(TF5!O9D??rdza0)UmF)pPZ!S9j!tQjuVn%8k(O~o~rKG-Q9asTX^ zXuuNnR`J)w^f9cnWtZ(i^2eLO@Su}h$%fMI3sn)F>fkIGa}macz{e7=m|F2CjL%QL z_s7!cgz0!^)2mrduTM|Skf}B*p>;};ybvV|eyLYN5@CJO{bz4aR*nYeRcUOBC_guR zY2V}Ay-b7##9IF>2@3F8i*tJyE|Y%vb@o9YVFhJA7Q?`=Qbk6=kuCGF|?0b6cjQ$HM@Cq0yIVF>16z=UndAA$G7@5-XOw_{GQ zgo~mGN+zVYpZyET8E#xiRcX)JQ(CAqtb39&Z|NG>R4Y?H8;gg<8S&*~a~vu^Ee30n z%|UES;5qhsdwz#c4%0Ce0F_fv=vX2usfcv^DygH4FRjQhitllHX{32R^LFPDtR0V( z>WjCBwxaf4lvN_Ux<9gD(tFLA;|=k3tGOR=*bhg$?gEII#^$8)>rGp`WlIbm`cy3F zZ-fcTga9)Nz8(|w%s(1%9Q}Chu`Q^z)y7Fb3>pR6IwPH9AHOMbXyZ|8kZ@vEu;TOk z{slfX0DQmDr+05kr_xq#hhW7~MYMvQac1X?hy+PRo?qnTMT-768GSMLG zKJ)lBZ=O?g~=fGx&JK(cT#lp(XV6W zYPC#7jAWH7)1YbqeQV{9Ru=fq^B)csoUJL&Bc#x(UO~+ z__SAD6g;**goQ+otM)sv>sEtJF9_<#@Kv0K>rb1+j=BP7QM%#~5L5o2WWoY6tkk@F zWXnbU_1+I^zu2*OxAy;W-1GIH`&BlB{bm}@FaJHlmBH9^oPlY_P65aNo6~8qvN|ua zxaxV}oPU}#p=k_u7^W=me3=vO(S?$TnHhpjBM4Ff8XZr6%SL;QW!i=Q5#C8i zms>{ky>!FJG%Rn9EoNi;k(0C_&=Cmfx%I}1AR>LO*q?x@2}IvR%Ef(1H& zeSMl|l4Ywf1ug1ZAY~3pQDPNniAAuK!vE70*yrAnZ}CoiN^mAjwD^!3b;9q-9XCZ3 zxcq*6ms|iQqo*;_jOZAgdH2<4d3@*6DUmrYHcL^pwAm;1iDJzFhJscIUnS7HJ~7x= zB4g%(Y68?lEt^EYMN6O*&@@KJ^a01|cfMQ((b+G(k*P_!OULZ(&RUxNr-@}jG)x|= zYI3`2I*M+{NExiYkfk*HLgWK~O6_xv6l}Fqjpl#c6{$=b`o6vHV>LN79EGjcNCuii zb}6<%I%S4W1$+H_>2bRgZj;0Q2vCuL;oR4!)!0B88KAwI;@(F>~6)CTR&>ULJp@*jqy4T^YRJ zI6d@a9E;;wn5kDZJ=!dg6(co6El0mQ=H%?TOiGwaJ_xx@$m&4GHq}V|IeH zWx-UzZPes&zBmn}gOOGwC;P%HM`eHZ#UdY|VL=dZoD_+Ueyb?orKd6HfC!W9#S3e! zT|H9Dxlm!lGWqlcyP}9LjV-?~fQy{$leigbIi}>dyGqF~iZ$HFvf!_^Dv8zvqOjzH zRaQaJ1FcktvhUjPWF;5>Z!?bGYN-&>9iziNscFa5RK_k&Z3~yTjSH+cFO85&PNR!kv*vJpzk4T<0g8;tr~}$h~0YisdAMQiOnmIlgY# z60sGN{TouH7#phxKCDRRuEs=HA-A<7U+j$?#!KV00c<7kP;F+hkA!3p228f zBq3u2CIn0}o%~#gK9eV(p@gGl-szMW4vJ#V+&^m%PQQ@O_@saDw61WsH{yWiN(e))#K^rYI2)9%D`m2*RY)x<9eM z$o}3*@y=@O2Y>p1w3zKzPZQgsMPtHg77%-{jf3-wBqHz?j}^_IerJ9>rxl{MSd`2^ zWUM8w!IYaQPZ)MO^1uqgKEPN>TAs^3Skkvvg!30kr@{|&)nZEU*T3lT=9E$_8|H1C zBpqSCky7pEBgCpocuPEOY0g!CSo6kt6O8#}EmLRVzU z^Tv}Mh9tkeuj z6*$<>Nk7sbjaEv0uiCPV(|7|h+H4+Bj$r`VAK^0KB}pc zzz7JFsgjAJ-zDpS2k~1FAW|QrI0E0ATnr3s-Hl1tYi+v5Pe9Rh!>9gh4o;(QY~_Ky zc2n?Nw(DRRJ?6mTmI^ta`@DapqXnb+M{~Y*Qk=<96|`$ND~Y*CEuak_@rpm_$amyI zVkP7jq8B6-9a23p@;eN+B_X9bVAUDpt?LSUZ@5%~%$@KTW}BKv%Ny&W1Cvxc8!`BP zYa(&c^j9J2_BN!AyPEyrj4kRxxgF4(5)fx(zZ`C4OL>o_(;qd|3N|@x!Z#yKyp;Vv z{&#s0fq|_z99+lRR%&*YV-CFolKptBcRf<5UddV!x(St-x~x~*;C0{lxv#2&i*nXA zyDm!sUB^l>XLyj=BuBoD#YhRBKvzv?V>{2w$7}++EpD)Oxk}(T(nc=qL+JN_f&iVv zV8$Bp$$awmg)G-V^9iL{nS-q8HMM#yICqboR|K>mt;GbrijR7}L5L!3g_%>QiJKmg zw5Ua`qbzZUE9Ctjt7$;rqv_Xm&u)IpA6%z<{Nn01+!TAupuhat@v~C6!Ri+xX!^xH z&ME;A=WaiYMoI6l^BQ?Q4`N9nYO)erq!Z^fp-r~kH=Giif9w065)%$XVI6RZSAWft zh)eXj2N#aBI~am_bZ$SkW<@I7?~Gn0{?EXL;ToWnnO*wg_!QemnfdDeY}Z#Yh4NJ# zkWI2YgB^Tv?P?l)6E?W$a+~E4uo%4UG@GWDC3;$Bwh{41OL6W&Xx8=fQs_^sPWu5P zHVg!-I^I_QZO>9wPhN#=My#)uJ!Yz|y9+UFZS*_wS^w2Plc=)4zY}#P?fLaWOfKmG&o%ze~3aRUDzOXerrXw9+LgVGsh+JvL&LC?QCVknRR~=J)r1-k%p|an9$y z;=V4h+LTA%4*}_Rzj@IR=SMhwP=h?C&uuy5;Bs)OO~{SrAwGPIlM2YSrrTa1`|EKt7 zWG)vo8Sr-P@BGVce}Sj9;z7tbY`Vq+GC_iF4yXb-^@m1d*GCQt5d$cp7vR0%wn9-4)aKh0bq6B5e+5<$qtyJ*t_t zf1Z~Kk}9+!llk~tC32UUrX^&h}62Cdfb-b%_ki$WT)vX0M; zYvcpD-)50swV;HBHKqa}dw;cuc8{&M#Ikhz{8NFfxxOad^U=os5fdoWsC@YXWMY24 z_!gJ!TB^$<0&9^Gt(dSiCxAXcYIH+zOD&!v7?wjWB-SEmQ&&CwE$2_tJ7MVoh?t+0 z(QT6F6@Nl_U8)o49C~%tdD6=3x^^csTIXx^sCrH3jK3xS9`7H$@aWCq%wazErS7sj zlA%~Fq$Gz#6#^hz%EZqq!Zg&8zrM-J6xXptn&po86<9}1(kd`9tM;iQfn zFQB%DTe}`>qtl{~APhURAD3v#eUb*mu-nmhovaa!*abr52RPNJ@L0x?b1(Vi=Qq{n zoJmTPZjpr4I3epr073)(ovqdFc8MsDChFNd{V76wrw< z_OVzhqTCJYRIn+^3@dximwLcO0L9Gaf#!jSPG*d?G1W$e?#ALKf+gKWVvAm^4vy)Y z3bF;&ybwKDsCpKU;zO^?@>Lp^vvSxX)ZcBWozJx2JB+ASG-bA@X zg@PTB?s<*YdwwJbM{(4F!49lTCN5i8=9)tfghJe+h*M-C;SBK%SSHlFRL7enJvLyb z{=R|=&1ce+th4LHPad0&tuLQN+YoQvYB#oZ=LU{ARCO4=^-U`5g9VQ3JxQEw4?1=p zsw`gs5=MATas92Id4T{X^Qf4245%n_?J6-_Ocvb;o;5N~7S^xEbvBcPvEUjaCq1p* zk`0ex&c?U;H`v^WSj5FwH%u#phwS{Szp35KEL;l~d;kYO9jA0>4=6(zeXFmrd);vM zy|Y=HlkV!-wch0qGdyrFi^F5|S`M%_BN%pvcX~8TEWUBe}z4ZAGQlO z{)f_$_#0~j&dZH_-xpZ;>^YiC)$RafDG*<-Pc?3Mcq6H;8}{Y5;!g(!Mvp0;h8xA^ zS4tc1+n-GFOVwS!Jn_v4I}#G5q0%wR!VCe_7Zln7*Lp2MA2EK~WQZ=BXj;$D^^%6i zKEp%-)Xl)gwV1L454RL$#vd|&l3#Un!u0WXyjy|aC>J6LNDNk9qUf!=gxl)Gp1WoC##v^f46xOP=5dxCiZIkL`QlS{#7XBcbVL z5*1$Dh(LQvHYV<%Uu2WpL^e3`Yk?(}SEor~z}g_2w)ECpz>3fSkrPFt@yh)sVuDgX zJ1@Rjn*k9=EKvcE`Y-A_{$H3O1e4?MaIs#!vwOJjW#Gn*l4=va(im?Rzv zI(q|7Vxo|g7(7^-e)8g3o25yRLRAK?A@3}pyKO%Yc#2sfO_k>pktq?QFa6BtISU%l zO%!M78ozSpL5kTA4?Ax~ef7MbWJmK|2WIo)DP7wZgFGc68c3cjwcFP`n)im{JVUU1 zP>`gTjYmBB$B{f6WFd{@D^BPa!~T$iyp^C;dg(AdG0y1mXP@F4`{>#BO;~N$wsWg# zF>T}1y|)ODTf>-*p?K$!52CpaNgR*QASJ*N2y4xKXk^i^t~^b%7OE1gX1|a63Zkf# zZ24f(T|=9@cpNDU`693AU}Wydah$|2G3-u(mT~nTb)(-lq1_(WnhN_^9b8*H zpjVmJNU$%9G-q7Jn34>(%D?INz4jSO@9AZ~UK;Dcuq6OR$!-bLH;FSTDzoDd>Aaq$ z+O10TMrZH3R;SKVfle6?aKVu8wB7h|VIU<$fJkSZ(#BNXg}0th4uXoOB*yE22e-D}s+ZO$b}ljl=(&{F@BxQ8VBC6;&k z?H>A(=BI@9-m!ulOQyo2CVu_h{+!t|wubpC|M-xgPcK`EVea1zf~@zl7BD6#Lr86F z85Y^JT7Cd}yjm`06dQF%w?Yk}_Qc-ksfY19yn9M>;l1qs_fXXA8>72 zIHTVgU-EZqKNfgwYwF^?A#svyb!xaamhUq!f3^m79Q}~^BY)xpq&WH_n^Zwl`eSVk!t;Tue!!MqYdrt`J)EBezOxEq%S!HNG66M6_6$`kjBler!b5r@+m=r349VWIR63R}d;R?uNQtP3jvql2(hq^*$1+T&X?*-U8 zw{#UHXdQ?$#%37^4ikNn`&8ZEOh_VSo+{QYZ*q4h9( zZU5lw?;XBLUfg4OHZ9$-fFYV8KTyIUwbcO;&#+U`yZVlrp)Nzoz`?_*2kQP651vv@ z+Szm2S!)i zh+y!^kaCz}O$*+z(Q~LLIlU(&>x1xz*lWkwIz{K&w=~-|90j`(x^>vDwF)=CYwRT?u(?&vH(3CTzjX z;n3W%86Pxv=WPicX z?F;vBxGOw$+vha29XPZ-^EkhMKOkC;VrSOO-8QRe{2nOf^N!75&V3d}?;O$b$kgge zlN<8_+bUZpRs+0h8+3K~3g;Z^pJFomYRaR%NmtSbY4%<~(s>{Hk|>V!CsOc}`$7U> zm#)>z^oz1Au+aTF%!&o$!3UtddiIn(LYBF{0zV5Vqq%{z9%x3JtL?AQzX6KNO6J}Z zTk(EgAcwXE@tCkbat}i*{|a5MnQ54G=y_&o1$LC-nchKGe2`zpIlCkb-XmHk}f zoYYo}iAFq6D7mC@$+jCDnB&t5>7*cz{o7ihD1=u3U$L+Pv0H;UqIbr8hT>Lw0n`H-G)ve&4>NeB(wZHQ%XB{_69lP(VUuWpw)Je6cX^3H6jWo zyeGdTx#5oQ=JwxyA@F&ol6V7m9L0`>vD?qJyP{8}b~4vUol#Hhxa`rPu^jHAQ>uks z^))u&qyc{mH07{-T9!^0;HvhB>TG}*hrGqk_{<)_*BX#z9L*ON&fSY3K( zoKAYh^!eX4%fSK0E2}QT$fA>y^Uh8BDrejlF(xMg@;G#XYp9?I@DY# zu+DOU`ZKIx3&a?UvHj`cUIlx(|lSKD2 za@_RrLy)nH`0|3)+^H^S%ASG>a^EEC)G#mRm>u4w>fuDEn6NI%HiZNIfo*79ZUc;D|TLsWDS5ljEsY9 z;qwVvO;ESEKjn5Ra6Os<8re+X|AxFZR%mYm)>|zGp&IDP(ywx*DZ)jlqjxFE_T*)A zkPn)zkCzk|T;Re!O#0YBfxN^n60TZ+l@Wltr;@hkzzE&P+PAjDditGH@;%Pu%VKMl z$)w`G=fXZ?!BdRYOUr+w9J6^YEWc}$!Ss93{W26SXQ=JowGD+Xyk@2zLFlE(U_kSF3s5d^&%O+Pz%`K0_?*X0X%- zDK1-;vHf@YM7?CcBJdI1D_zRnkxzEKP9}OpRW;Vk!FS7=*jrY+E z!mDe?c4zmSsQ2@!vR(P$ zECsvUTvmCpZ8S@C1CN)^!0o=S_C)#94V-?mok~`#@S~krgzUsEGU7O&Bkghv>o?|3~ zW=ri!pKu_3exVP{o|%E}eU=ONqHqQ;=jtr)*QeoS?IC;+)NPrCF89o_=f!uX^<{I% zph-gKqh+|nozG*8A;lsiaIUuk>|NCB)RN4m@ybjum6QC6tI9ZofuuS@S9_>ZhM3E_jXrMpAj zZWjn<0aZn(6xenHn~Uw*e``u5D8%nSi{74V6rOi=#yhX6LVe-}f`iYvI}1gQw6DSt zYurM2C3O9^XxXnCza&02ierVaZLl2$bWsBvH!7`^AW4{O%7x+2zGJShRoxrh5`o9V zu-~jtere#2|E43T*_Tgj2W64^k)Jl*x6jOy*I!iQIWnBk4)Jip1#HD^`L(l@BE#*{ zXCx8TH4}gF5EC5T)fkpA-0wVn7dC?2IXUXSAQ6vWeAT5SJMrr`9-spAc%#}^$${>2 zU+Suij(z?YOC~?~zgRMgG@eCPct^RdQ-s1#oC4<$8P~h_@mTlXPlx}OxS2NDj#Q8l zHV0BpILkhZmWTLWPKRr~figyd^B2aGMcizVx|)e_Z#>o&g4vd2DAv$oj*sPjMgN1w zYR{s>S^@LtJS(#zrK*Uv)}(d^!dH5vpg8dhCF7>bmHX;y{!@uWgv<7JN>EDl zwTrv22LwM3;CXaPd@!wCS?&S`X7{XQINgOg616WBOE~#=XjXXjYC8MuQ)pL}nHEXT; zM6;ZZ@-|YOX%SqVRHBSaPnaV`uIi#OP#h@@4RV4^c5cn#-skz^G;7e~R2P~qo_Djf z@K>3_Yh{G`?dBbQVOrlggdM` z0_q;VHGcA3G18$P@seKi6d#WB+W%_i+1>35u)^P8Est$DQrEM4^UC9p(r*T{1V=o; z1AC56W(xf2@M=;GN|CoBU++f^0n9{GGV~)EqRPF97yoh?E`*3gE#9ZqmgGtvE4%;d zlspK`m!be>s6BYF-J{kYcF&LBiSE%3NwYznLtU_IfV~X|##JxoO|CNDtJ>|Fta(@4 zyzoyR=eXkBkgt9jBA)~;Jz4I#Q8qI`XY6r?7)U;$Ya=9-a zu(vH{0WnND&N&7ghf7%sNec4XNu>qQq_7nd{4)WX@Eo7V!SDo4NWkCS$+<6n&ZY(Q z%r)h7X7VL^2otRfgM$J+%Hk0xS)Nu~t+RIISS;S$N4Ue80!b#cZ`BxG<@nP7YkY@; z^WYx)3uxWo_&YwUpZXy>q@0Ws)vCG{9a=IfOAU^pkFA!)db0Qw7y;7qhVos2e}>0Z6)jZ9OmNp_;w<>Zp?AJB!3+Q(?+-yWG>} zLusosctWqg)XRq+ZH(& zVjJw}7HPeZ+pnu1X z8A?@b9*iPNv=o|);X9VvBM2|(SI01Vt;%F+4ok>N3`ve?G?YVd&UBSS>(N=hxfBR2 zq6cmJfhy)ZhcF|5j}}Ld!l$Cfh+haMf<603^4DDsipQJ6O9~8$$C956j!Bf<-CWOm z&{KeC)Vq7c5mOtR+wI5iuMO6Xigvv7^+wqq19tVIuxL(KLmh@ zH+BN=2y{qB6k-AvzB}Gb+@12Q9_L6-#pxEln?y{5QV{*9Bo)e$DT4#5B&Ok9U2KhA z=OY9>ZA$v~n=pwop4K-GOZ$$hx9I>#^dsZ3OqB@urcTX$Q2WO#Ia;DUl(0}ww` z2;+F{Io-kh8Lp2>3Zo~!GoFoS53&b}9EP&Wn7n2?{2{{pPVTwE4_FC4Qq#uHm_JKN zbFb%5Dnt6`>e4)^F@BvYo;YD?Rs$k}I5{%R0w)VeQ02^}GI zymFZxZ1_rVbjcTA%u!3JWqS~t@V&JEhoe1wf3Q;qa$f641WpSj;6nzY#G<9ScM{HJ zd1&4YxAAw{py>UVm+!o-=~OSVre9RpzvosmO9V)GkAEx#!{|Re(QGn%Zmivn^N@pXg z5~0wiDePS7zP{}#sk9+|mUFeEQTyFmL|vWG?%Ex4WFZ@bTQ4dlaRYcEKJUvvOvb~w~7;hTh4-wiR z13idVt3ioIdx68ZdR+2y@6E5}X5Ejx!vK{dK3)4t3JVuo;{zpFuO=qst?_wVdn^?% zD~~u8srbi?9$iuGAyHt79@8&F5V?G+2p1`7is!wbUP+^;v7vA>hdE`H2cf?A&7h5; zi=B$x$c9Y95rutm?=5krkL*8-!YTfvoiqJu(ab;`wTsmz&`5yqxvEdnCt-c-@FAMV zTFUpb_jeNUB_RA)52ei5=&Ar>EL<^zuhGj(bX}Uh6A78yXw`xC@G$htLU8mXz299OB2`&fCvqEKuu|rtk!J$`nfutxWcUkW8bcl9 zaxR3g*1~eU`!}C(sn<`NHgHq$euA_CHy#TOEgdz#?IKe+|eiFqJZQhu*+2K>GY%n@cQr806{qIfx0<$364`z_@ByFPB@-Nn_Yav3fB0Se zBr8*Pc=O-KLB9?1-Tg#Pf&p^koVoUktaw%BB zm;?&e4J0$%Z!K%n;kj5bI^-j^JjH}rt?BfQ{Tt9DYE~$v(66)<|DsOLKB_|?#iF1e z2|fyH|Ahb~mQpZ>ZU(y#eI&diTS9D_v2iF~ENIsZ7~GoaT1O8ibcX9D?J zCcUq7c%P{~Piz+d*T_~0pFy79W~FGSzPc{8ngRWE$fdDpct-igArbge58KoDw7|#{ ze}`4>KY}RG9PZ>-o%j%wt3wy>n$-%x=4;M@t!<}NaK@sgmu%mIB}li5@UvPCt~+~T zfx^cVwwl0#woQ@~R(OTZ2Yhumu2H+X8<_wRs~B*! ztJ2n0*5RJk9N<5xJ&ul8Q>gI=x=%w6)vqqeqsANuY^Q#6XF5$OPh9L%Y3mGF3S%P= z`D#!-e#D2Bv7PFK5p^-??3ycN*OB>v?M{3KrM6HS?7P2+5zRsG0EL3$qYrcCs>2a^Cv5$XJlzjoZCaf|z8aBL^LGnWg^ zT5N3%W`W_IIq#xYpn$THI4mi9AG#&~eAF>=&BjxKB?u!3sIq%iB_~n{=qfR_H*Wd& zECvTPp{U^v_N_Uixpc6->b8_i(CgqqVyYd=ho@(84<@4T(GCd!0*zeoa_GxHkMme{ zS`C)`7$w0N3WPq{sb(S2C}=+h94@gh4>B@{xwGQPv-swjps&XFm;2i4v-@Di(}gL& zZxf>~J}3N(ykUT|XSWa?&%M{c>C+LGlSNIP8YKD3=uM20jn!oNF+-tDNgz(I#k(~r zH)~DBYl&8_@~ctd*6!xF^``(e#mq!KTxt}mTz ze;i&tyR$cb@wPRrlt%UXKh7BX%=UGH;Rn)ilJw|$>R-@ek(H1kyNjYq6WYPUL%dDu zWofV&SRVY3Xj~uinMJZ=z~R|l%TToIk{AYW0jIJN#Ut8|TMggpeHW)izP(Y*Pn@_f z6Ai@LJ+Jvsrsh1Z5A20;HF)K!B>6rK`|?b>0FzIFhuBpp7kn476T}xIdmS$q?ub5j zaX-|Iub(-}bpA0h`Rk|YzYMfz(FGvfAf6NzE(^xn!IgG?KAt-?W%cj(c_{9}m=>@< ziPxZ=@R#;?hctYIX5cP~)US@giQgnWXML+G)5^GT(g;;=cbvEIQ!3Zu8a$J5X|pUN zu|$G;8fh+cb0p$Zcse^d*45MD(Jd7)KjFvMt}V~a{mHh!%=V+!H)^Ff(=YLjH;u78 zLVFZoLmna6ecKP%IElAq z?TUOjN(9}0Z0MqH_=w+qw?s&dKoNQzwF(MAZ+MW_yA(Uo;SAXdSEj|26P6qyzaiNC zlV>{|r@F0nN%K!M%|%<~wWVF#rf@kV;7@UupKuVt20alDb?$_6hePSL1>e$}KZgs{d zzSb4l6Sf#fDNzL(vO&INYViOnb>x`vm{Tz(%Fd4+4N|Lxcsk#+Z0EUGCkhvPN%&=M zoL6V^vx?%QuIYfpW^~9z?tboldUS)p&ab+(OWXL7qV&`za-ub2fDC-Yk;{xP-igWK zO>&@e`fD2^ueu=U=*qhpVE(}ik(8L^Tx!`{KE-4fYg&a0e}6zieCt}WGHk{yAE{#` z`4vtKq-Hq)n!(%!eI2e@8q^HOL#)i4b=nDXY^@Dn5}g>Hx`BTvRxGBoP83aT+Myks}~&sMPKGV zPrr3C3t^?gCM}6gi1>qyR%q97xCx|Dk z1vOt-VycYD{MOC=`!t6s*QoTN2^3L2*w30Mm3xVC7VoJ{Xs)a1cYEKvwfyc@p7MT? z0kEp)4{poSLO~hVvT7`#DqR-E)FUbh_^#PJ6bKwI1`6uz6Ix;s?6(+~DHb>nmd3q$ zk&icZ$-N*Dhf5$O?tm`HLS6-ee-S-{H9OwREqPi%<5K5z>1w%0_T~Kj4PJx!T9wRq zw|Ew+M-{(Pkyg?dO1EcdAhw#7B`)$9`pcm!^u4CNxLEyO_JBfAZP*z{aiU}E^^kJ0 z>1g&n=r?FxnR`*J|L6wP>Z0fi)h}%;Q!jTjH~Ln~f~QyuE!V~kx$b?ma&!zv=vGOu z4nKt^6`W;RE`F6CBAm#=h*uY%)#sKm>Xbp7#fxXC&H+*v47j&bl-}JAj^py2>e22U zucAyMT?mXlyTqyi7Y-oY4+Dws`!s-OdGY;Pk>!L1^3q@Dc$so0u)OEX5a2LWPb|8% zEGr$M6?5sY(53l_=r&Msh@|mdp{YG>xM-oTyyZ74a~=Dkwblh)i!GEf&E4f)Y0(@o@SlF}X#iO{Q4TF9$`Pptukcl6c!zT=q zc0@1;1f9Uy0?pgwW8ZhESO(TxtU^`#4^H@{oB3-nJvNAI5)8CNX4Cb!VCg7ae==3T zTrT;C^#e0PL8RA5@_z8|Zg8tIJ@&b5$qb}z?$5)MkG*sB3MMl}dH8HFmGGTsfwGf>B!igT>9oxGp?3xJ{UFHRqT; z<%ox7V9Kc)%HTy8YkAgn)bcLyt(y$@H>a2Rmz4xYJz=pPcF7srjO<%Q!PZKT7*tq8Io4?+hQ zwD5g36D!^Xw$H3k-+qJMR`N~XdH(;s0CBx0DCsUJE7eT~!*I`|1&-IU;oN+1_>TU8 z@Z}IgbWT>7mx_+|pi@f3U`4L`jWWEp;$pa<|@-^ zDx;_P>>nK~KPU^9@Bw)@ZVH8X70>${kQM(5k!rW<`2Kg&vDN8W$=vHkr45I_*=%04 zjOp_+u*?Nta4=Bn&%k`cae{P6&E@-UT**S%QyIzlvsToMV0%jceh8y|ku1Z%Z};Z8 zmv$&&BigQogMGuhj#Sv4ir+r0L?Usq4L(Cg*rBQ(3dGHqGLCFSE13lr$8F{{7Vvy! z_xoXAcyen=4a_wK<5yM4br0BN4{$U53~uBs?>>`6jCfh~zZ_W|k>NC+ET80Wk86Av z{`NO*wb!SNzI{e8zIjP%H*X-U`xnXYg@r0&bNeeDrbEp5Dp0dv)H3N1IKAbs5RJPE zPi+kyThi2AXQTCAcg59=S48~uH04L9URbq+g{mxy>@uUYPi{w;*}4}3t8jRktGqaB zguq=Yye#~KCtH<6GBF+`1S3`THo|GM_sx&*dJZ}!*?$BfU(GLt`)grh4aG7oVyK5I z1dF}nwwSQ|=qQN9K*%eP<_-^cr%lVD*tef6BPF4&Jw5C$D^uf)HQfplr`6qvL1J@y ztUfO)L{<9&{`c-45{N6^RS(Nng{ z$}ye3ZBD_wPpn~m^IRuBKNhrNr_TRm?=2cK$1c4LBE+mQ9(+4L?^ol)2q?h(wI9-Qe7Z>sC@qSsSVsEJT6snCi1eZw$u_Eago9lwk zOm~-u;4~$0_B$#-g-CxP1A%Q8>#H9+P*Zp%c0RyE>P#N( zGGleV=TozPq5X_4WKIm09^1SD>7G3+Kydnnmi^TZG(2l&J!p&|yW&P9Zg0;jaP1Fn z42g;s4yJ{I$-5{RGg-GVaXGrMKqqO4%FpBa{qA3$&2tii1={C-tSZP=FKIprrg_drYFS~iYifntFHJWRksk6P9zo{qY&%K{4wW1$jI zrW2ga?Phy&caN}`99P~&$(01XQz*}*;;h-HW&C%en>%hP}F&U!F$3IGh+{j#U|pvPOLsu__VWH5+i#^K79zj z;?)S#=Wa1)m33Ky=xw;IKxp2K#QUa37iPG=HPqL*Nc(HK?>3lpZvZ9|CIx$wqU63XL4E*H+Chod-NnD|GOqft=i++duRC>&<|5)R+dJaKpHnkIRn%8X?_QFV%T%b_kmp z{|4%JuX%y~m`P1#Z+BZ+@QDNzqe!FU8KQJCTaMgs*d8PAIGe)^Pw|}@NBwm{V@pT} zz(Y8{JdN&Fk93sPWQc`?u)J+Qz8_X27Jtq=HPv5WT?+H*p|zYoMF9 zEbZozUFf&8QSa)Rgk439(Mr%TQu^THjZQ@al{DD7XwI*Xqa~u^Oa{c`IXVn$zK@E z;Zy+iFE8|!pjInXOxt;Lcl@jTDmgMDPpn{C6E9WHiH^CVz4M0H3je)q!R?fxjt~V> zFo0X2*>QyDZ+-aN>%V6BmE~xY$?^vNzu*Jwd-*Uk@SjOg>zDS4;oOZH>;ksB-6Rve zq}%m4_xX0sKUc9KE#3m{qJU5CcHVo`nd7M_CtX1DS10U?XWqts9u330^W-Flrd&;#0Ss!>voJ8F_@^zdQFeVxC+iYgZj&g| zAJwC4+cCHqLhigLDCt7`i55e!#$UCoOdVOOxJcax-%ZC+E zKnM8Cd5R(QmY)U4K0L`{;Jsf$!5wZSN&{%85w^%I9*P3kN%4~{&l(~nf^zc5J`fPJ z$Vw{akF79k`ak2b3|v`Adob&WuA+x`;Eg)`EV*UrK&+$RTD&^_%%UC4g-Xd z;M)V>N3l3?$s@i;Jmb!ED}d?u@9N-EWrNtLMo_U?k{%`MMw(QM%Q?5qB57LaD`K?h z9sNVy*Ri+2nlNb6hbIh-nnp$dyJAhWho&TcIunfwlQ!%d{|IMc^%q(D6If7s^}4R# zW1~P+0Av*_ZDuL?*4Zq$yc0ahr^0{c9bM>vPdQt3yX`EfrU_v_<|d5Y%+Of=?k*yQ zL{fWRh-k7ea_!!)1Ky)leE0(P$AHaU$?1hacg2w33wa~Cq`=*EsSyOW$?(9bg0^A30f*YGs%v$lDbU#ZQQyvd_n51;#3AE&1G%brVr#oXKp+ZF6>h9me zZC69YCBk?1VW+3_EcEpM!#yr%PRaxHT zEVhr8z)9hDd5S$eLJ>y8`uRKUrvqkpjwjxoOkfP&})l}Sx)l^|L{p}3Et`>m4 zfDb7a&EtQf9fKXaA zfGbrHz_HT>W7;P}+jrUfb0{-*{Wa~yzacrc7SrU(rfe#!Wo_yLG$+e$mPf0X#ImS=%O16l@+EyWQx>{mcNin!IAe<-ww;ZjgJ^%Eou{$d1cu zR{zw;S%1#|9qU~x2_vGRCsI5EKjWqfbLhwd6&%VoSNaz<|B*K)56M5YCHX(gNC-`$ zBn#?rTD9;%z*uhAgkDf>3f%je69d!)Fz3yF)}nAA;{Vz;a-H`_^@;EvB}#)UoB=5A zRzOjbK!uNTvU7dRLI2XZ-0M3=Bf06>jod##K*uW%HbJ-#mYE~Pq>)`H!3wwBMPo2xoX z)b2uI+&;Nop3?yjPL5v5ren=LDI|Mv`Gp;6D?s_lVRgcOhM+~5HFI!$)({xs6{D9lngHJR1 z-+>=QyeoSK@TmZ|-*w1@RNbX5Vcrnc5!XilPw`5eyV7U! zK9P2xz_JDbJ1>SB>ZRggtV<12Hg0G&L{-R0W|_YD;XhKIbdt|TUn&#EoT9abj;bK? znMc3<=JF8}T>1bR^Mw5~Kfo2@UEQy=A^gkWIFlMbDZMVQs9JgKR#38I)5bD#O%l<7 z_q@H(BbDcQb*Z~xjgSl;5gv|l@Rfdl3=wAOC-ns%5RVu-Y$q=Ge9LO%-)~A6x)!Ex zudkU<@lnLtOcohYczvm=ziYU5Q%Er(`^Sh%#mXA{eSfK382uzSQf|Pa&FzCHdonKR zKd|c(%7@_PM(s~Z3PvMLhWOKVfhsp@e039)*G-#@(ggu%eg;|qM3(D3S^cy3XfYr> zdXJ-#aEdroaHHg}!BBfC+wSj=@zeCIL1z)zS_T{@hV6IpvXPZ>NBN{gmthds<}_GsguO2d0yij`y{~Hs662XPhdanS5U#pUaJC!l)3RkHRU-?nTbLr z&KQ*Z1#EFJuGu}4oIIWhC#LSqr2EFws+LNo$};K^<#DBDjMe>&Y8O?YoV!#E>yg0g z=(d>P-{c6cC{U2nsFx3l10$$-5G1+mS}*2wU^Zy#gtwCC{dpASJJ&=tEXakPa);XT zSvRpdNLH7zp5*D->OLz8XRo2hReqrLUt3q9ywGw!MBeXPGoj8prdc&6R*AktCeUyP zKzY-R#1JKyhWFQ`8*(pD1Fc>hhYrNx3HTsMk6zfw0cfG4VWxf;Ye+V@G6 zq_cN#29f_c;m;|mDb9@Bxq5$v)K5We?lyKIt<>|f*}&d6H`7XoXU)S0!x4BX=2KX$ z6DFzQb4tqnS6Si$#u;>jE=7fRsJ2JbEDT?%D;W-E zpfVVuEg9188xVF0(S3!@JG$3Sgp6F~s?Pbp|McvupuXYJW$00=*k-|HLCA2>{94f5 z{Nbf8sesFn6K^!`#w=Uwuk@$KH;dwJ{E%chaX$#*uB_iZG@=NA&4A?wOFn9RMm{vA5= zb9Wnuqs~!3I~k)!99j0NO!q@)ziIX6Yl(^X^^E_mFuNate{Z3}o*#1Dm0p_TG3)4y zA_g{g6 zdngJqHmLA4Ma!HU*uDo5sW`^p|MC-K&zIBZHs18C3kn!JVAA0pev;@c(vFO<{xE9$ z#_8w`^>kt6C4=858f0E%Q27h=Gy^jnf=-tXe>Fwlm87)cvDS}lkuv9c(Gk-aP8{77 z&7X6qC=W=`b7{4zj<=g?e2SLapKYs1iW8dQ&Lg{HE~4>pxgw30gs#!yoCKrpr5AWTMbL5a7+emx@{4LbX zpJL<}81%6^<`Z{t-ACWZ%|sIhixWm|u|K}rWl=Q_xoQb7IsBK%e5Tk*@qV`x!_R$w z%VvJ#^{4LS1^QGHf=3mf9bcVJCc(aTl!^qNF>vMTdJ)C28E-XBuut;OA!|A{8#qYC z0bY)DE}+KnasBe297UZea2s> z`o3uY#oZl(Ybov$C@#f|6ev&}iU%v+;sJsehhQyUC|002gy2@(B@}lr`qJOLH}n3< zOlFeYxidNEp1s#+txW-$A*=>w&AaokwO=Hns%B7K%$8S8&Wi7ccV)0wFE%VPKz9#j z#r6@H&-yfcE8dMV(uN4hl`{8f`Yw0-cnyc&O8W-2Kh;0kZI08o*;kx&O6E$9dO7tF{lhkd(KdHiiT441kO&tez`Yzssu>vbBg^*Fkg z)#sF4Hpk!L>dxvqoMa6lpl)nh+<9Hnbo+-L$g7nXbm)nrHi=I!I9eMx;P2C2`4m(Z zj=5#-)#l=+uxRC5j%K~y*Qu>mKgqZqI#=b&COnIoin-%(#dI{bJIO(Q%&jU=j{ib% zP1LUf2@hFt(RF)K(_h8^B5p=&ehuHzh`p`hk2>h^%^CYB_?9!iz@1Zsf?g02h`9t_ zs5>)V5}!ikYFDjPyd1g3)#bK1+H-;BeW+TfD*KiFcB91tE{$XTLvT|M5;!J;NG4cH zTbLVO!;ww69XTg`^8QNO6Gh1D_M{i>xDGvP`6Ni&2)M89;in~ai3WZ(s{gp9Rn z=Y;ETVv!1_pU5Fzg}bh*FGowc?|geH4bv1TOt@`y(qe{`=Ie&4@_{CK#J0nvR%6*; zt?Kag(!dt!!e(1l#85e1c!5EZdc=Do_IUbnUCU!D6}(WT#Xn>y<`6z*Z;G1~ z&Wp2;p`FfU^*Uo)#k2%j4ZKtm{yxk${sZ)w&xfz%pilv zY5&JA_A|+WUw&RZN-1HkSSbJqzE0q@mo!)o6e=oDABj`kZa)Y1TWH$%JBw8|SToEu zXSz!mGh&538;5z33FXzDo>&qJM3Hpu$t-Qm|1i($%`@1pvs#h=f>U8e?7~m>#pcoZ zjsI@}{k$hvmd*F-#`!}uoj9B5@&?VqBqqlqtfW=2DQmbmX?VGj0z$bI*)nOM@lGk# zP;Th+e_cFLa7_rC8N6pe|H*v(B6h*|S43JVslJPDvbY>eIB0pD#vOS4;33?w;QM}d zt<-De%#G+o3^5u(y%UJJ28nlHX&JhP9@fsS6${lF>?o(12oxoia!@Sa6b^n{R8Z7! zOzC6|+AcTgbHvo|CRez`8L4`e&dV&4DjGQNdin)M#<%%mlQ=^%(VCSN%+ibgM;3-3 ziRo~WQc`ibIL<0EkEIy7F(7P7K9vn?XFk@!=jN%x`+hEeD+9OP$_Awd5&|+q$SdZSp7c zr&$H~$4swd5_#_V;X6eAwcICBCic$|d7Tgvk`^IauApnL;`_B^A2c><6I1m#pfxAk zp2((6j87+}m79d;6&~l9R%*D}EJ>&)!Wy7Lijw8%^5aR+u2|9Fa*YaFK`rFxl*>i> z1;HiEWhBrrOgbCOg5i~PdH0suHaPPoYosJlv>DqznoN;Xx`zy3Aq%g(~^P<-I@6{F5e5_WLCL1q* zqfnGfMZlQ0m{1ft_$HR*0;y=>4-9e%UyVmLBIk=?n?&C~d`8lfwPfStpRvSe&MMC~ z>kPO$blckH9M{b-p_L&UL@_c#*O_NQDuA)*`;VD46h)>96cKkjL5xbbJDfMme)+?@ z`I8fpvLlA=U|E3P`RW)10^tUxjg@ISeZOF%6!7cV#YiANuVx*SsM>OXSz%%2fyn#i zwFGu|%AsT09nc%nN zC|uz5D-N$uB&>5-QmHr6ZXY15rn&-U9)l-A=Q6282NsHX^!YH+OtF6{7&}*OB>l87 zES}{#>CgPCKO~2yQpbO=@sW2^^WYmhrsGH6IQ<@g_{{>w0}$(bBX8YY-uR1IlSoo# z*`RFDNDRkeJYGFpRy2P0ST$56WG*oA80nGi5){s+pk2us1wjND#T{(2FC-K2Ma=+s zbYcS(xDC_~u=SkUGT($74IUH*So2HIhyFoo+v)|REzfg|V^~PPEPlZFb#sWus6-C& zGX?xsa$Nu}3uCs-r-??tw*^3e_c8#@lZ_sZ!!U>QH|s2z+u7lm(qtPM=3#kz7ZP;m zb5z2lUc=(X^Q?ebrDK_!kqEz_^Pq>q?)MrGzZDJ*_#rFJ}_(yXa9i6^29n61Qb4AL>q2|FbH9hfDEl6tyRjp6S--pM|&k2>9 zX6ozGe(M=A%{OBF9f2h{I*F0*e(sX)G{-RUSiERngJmpA-!AS^jt13QBGKoPt`@&% zxZ(B5-U->{dh2H*iddsDa#B#&JGQ4-U9{)^=FDfGe?+}dKaJK_mE5j7PH4ZLai?Rb z(v~K`1L;B^43eZE_;&Df|Dz}9-R}Qm0c?XNfp6W~W*M?B5726E-fvoSm)1wMBG){^ z9vQy2sOx}qU-!3NS&SYGpYpDgI+%Ux=f2-C0DJ_pX?1@hXrnkIK7C72d9+lDXxG6& z-n92BkPKnSnb+QUto5Y1GAQ-z3E?Iw2nZ7x`8BSYz zlC&&}3z^G1y^)Wl&cSB&CVF-h?xHp_o8mZuKXUAXtc1?aUAmE5uAwmhm3r`-1PyAJ zyI9C0M+e#=Z2lWKuinswNpxdxjg?P?7sSk1iy{o2)H)~Chbk!gVPUbyVq1T!VGc6l zK(bBmQ=32b6+d`z1W?}1#Va5RQCMS=H8rDW4ohCE`M4Il3Ec*BHV;H&Y{k1(@tA;-S(nFh`oBi{?lzs8up(+Qa6V_!Cot3$X`iZ7KGH zOz?oIn_C}EdW0pDv+Hy^&IjKzPAJbm@56VyrWA>ZWt;||#6vTtDC2BQBxFsF^*ePz zAs$C{1yN?ky(1(}!C2JY(_hQL@3jq241cK9*-bR%QiSdav z8+d#`-@zMWKh(Oi1{khaHA(CyS?Sw93B=+&{0Kf$&wiDOjF$}{tHhW?`G&b96V&oG zv!lmH&*s>m3fJqB-WP z%O5NL9raaT`t2*=jUjP-VEVQHDDhUC%Ex{tUVe;p&g=e0ngMAlb&(|*@BtnK-p<%w z{}}VGa{m4L#Kav=AQu5jgdOGVyDVuYx{5Igine0h%2<|nf3yv%-k?2hcYUcGgL9sb zMnxC&4!*--Bj$hMn`V0_u@snY3hqru8z$Z%hIFJ0H;Y%2&GXJ5K!ODUB06{~?kZdD zit0rDq~Tt6xf#e=v7}1toV|#B_EW_~-0OGiFYpoI)IW0mjQ4muCm_%KX>^{xGB~xZ zpKo6{@Kec6u8t&I>)z5x;(4x(hXvc%U~k=kF~pdy*odv&RM);Jb5g=BG%$@7CY*=q zDwJR{zw-+F@PcIgT|(&vG@N~+h-ato2dRx+-Q4N^)-4u>G(N)@KgYJ_fF#Mgi9kC` zekZmB<>yDChM)U@PQEQ%HWgxbwAGh>AA8Q`U)X4fZA#b9f0sB-GZ$do6^~6SGXTfD z#KELZi&&end|Y0i40y7JAn`>3RjMM5jjVl;)d^RrWkC{Fz}6t*6#oZ`*_+{AVJ@2F zQW^n~C|(i&OdikARGBe6v+g}}&fU|6qJk}s?9|*+;coymKxJcU&hD>8VH?2iwt`Uz z0*s*CPPYd{pB)N=x-4s8-9O0y>K766fK?QF- zwKeRoX-~&1d|<0IMk~uasGr+6&n@J2=Lg$RJ#jd0Oa@)9PMHo-z&1K(ZY@>qr-sM9 zh2JlQawgsFdH6(|l|0HZ5XpL@5c4R`_h8IW@wL*owk*}j%~2Cm`lt_P6A_4z{6F{n zuL7Fa5R!sIT5#eWdPO&~@O?+N&M0`VXhH z!sOH;Xa6wYApqzl;m?MN@!s4*b5QdFyyJ16DV#0QE9f917%fbXyf-8S=GEm|9}4~? z)cjYroh9}*3r5F@IG2c)9ND-m>OgKJA@j)XU*uc=N`-sYq$dYeenGyHCpAKx)@b1d zd4BR%E*rO>WLovs%I?{rOAU*%z$qI^imJyF?(dntocqVdu3Ew}P<{E} z)L9nUC0z%_KCUr|Y4LpvC9htmR{xTIA+lTDe^8b*X6GCJxsFV58ov?S*g0eO?K_yD z^75}e+SX4c{XV~vvI*79Ts<1swd6o7E*+zmId_gh%(8e_@!9-m7{aS~K|e<>VyIZl zpVN6wcOgyK)nW*9bfHD&brhHk2!}}XCr&U2lF|x!2dD4SVexxD^6~ZHPRL35o2xLj z^TYmYOpI~wX9=y>PXNAOl5Kw-m5R)Ri?{L8b7~bls>A<~zC<4;;7bCf6L9FmtmSN#V6iD*ashu8NC5B-cX6TyLD)qmnw@L5f&=CfS3SV(+y z_oz-}k00lYZCRSa;lljh363TOJ-H0xH|;w@fQ)wnlrOM;5xd4%x{sh|ufk<+witMT zCxx3ekErFY$hio9)<%U){I5(^d8#n#ze-%< zSeM+y-vdW?&*jbP`sD)^jE|EXRlNgLD~G34q7p7mxZ7$tY}{(y;#QgZd$rq+6K1Xv z>d^7#=34bX%A0GUmFOo61`bOq!mBUH&onV~rnaZOJL)Eu1^Ah>-wNLOjM!Xef>HQM zhQq)=X!Jaf0J^p+M%@F}JYTH~z7LL@6x_jZv6zQ)!Yf1s=tK#&KxqlS`Kz zBnxGwcvQz-;xVRvrLDUbi!M`GFZ;;23Na9mmfP9tO@fqnqN)$F{sQvA|D9@DKgw_q zD}Q-Ml9pULgr%4#p3rl%lalAST~{ttvtGry=0l1qLJ zlK&PdSxJE;ZX7m0$m1nIFD$Jmt$z=B0O-*0l(98toil|fUm{d(XT)gYDQ)eC4 zAsMGZx>-1v<1X+zqKY!MpyV-Dv6I$=GU~)Pj4xJQTJD2qW#~&k9<*oAQGrC^S6!{x zEN@#s2eKWn81yTawr((sRt``KcD5#_X}7_#&JN;6jFmDgrLm(tIq~n>1n@?k_I{bk zz~9L=Q<_KkH{(s_Q44(4GCHEvjQN+s;)O{idu;9%Uci?PF7Zg?4b`LXktaE`Q$SY$MMYyr1eMIM3$cEDyt zYxcz~Tue!LBD}Zo>4G{vnr)L|&;RS3rBSBAa-A}sIgAdQAo;B@Q`ar}4+2CXH1j0* zkEt``5jCPudCxREwkwfoQ7|26<42oaQs!^n-fm{Eg~4qHvcBxmSniiCsQt8LC#=(2 zAs>E>_TCJ7e96pUSY%-Gt=_YV9Jmq8|Ayz_)XQ zOpRVn{zm2yzJ5Y1>2`;?@>s_2pX6p% zxz2R8p|3SYl+6SpxV1I0HE_nwwa%aaP-@1-rarXi!kP=$O#tJ$yaV`AnEP%RporP8 z<;}woU;SpHyke~lQ}2OY&xr#?0Dw*%|JXR9Rt}1X&!>q_{d>p3TR&1S;^xV+{`C^K zu}#7aN+*he@c@mwH9h%0el&7|C4dB=WlfzpP~!E#)%dFx5+irXO>MUg2@w<#U}F_x z+)h>kSZ)ENra84O8KP9+V64Ym=l=g^)L_3`_ibroUR{|uNI;LXy`4+pPm>R4IZ-3;{N zQ3@k2sGAeo!H;a4*ou+MQL${fZkOWzL?mpiu?J zXI&@h$j<`7qH>8b{DWuco4gSZKd6yH{)*?a3*mBo}dl048eIwaRzZG z;{aIR~z~GaNF4%JWTRE&>}{sNbN8{hdCtqFQ38rFhV|~6T0@SoT1~@}w z5eX4QE0yAKlMWYaW;hi-(x5+^hcW46`6B#4pm)1hVX_RH5Z-=BbFk2|$G|&kk0d~& zaRk?QgyGLLu19%pmvnlOnd?oVbq1G$4iEj_GSOtn>`bYA;9KTu5d?jgKRU`%{*d1Q zkO*3i3AeF25;s&AJOOzWE6D7;?JB7P?P#uW@{3h1ReVZ5TXaO>=N}256WyC4WxRko zAGghRh^N|U);=+$^_jS_X3k>YdIw79qh&U1XtVgqs^Rlz9iU?kdKMrgT6IbX2N%EJ z{iK;WI%*54J83;eY1b5NJvCeP_%0)BZd2tx9p6>LwHa0}kY~D9R&V2oP6-qA`DpH- z1HI$whcBv_yPmFv&apD2oKcZ2e9GhdYP}q5!c{x*B2#IgHtF=jBn*Qx0!B&VR2I3* zLcLE9_aaAdZ9rw6Hr03tl}r-2woi3!29QBx9dRwD9-^DHsB6WqRAlMRe)$mX+R2uz zu7CU-33lzuv)epyKg|Kn;IF(J&Nx#=#qu}Ll)hb* z4{m4ez<`oYZKUVJF{U)4xc6u?l(OTK_}w;Pjt+z*FQ*Mg0eU_4VDjtt z9K(2VGy;*k%9jI^M?iX9j{Q99eu^nKn#C_WNnQYPgr5a~>u6)wWCoBsW~yB%fM7z~ z45i*S!<21$y8Wj6RkWR|RM@x0H7>T*%BllgUkuDoI&-^Nw%N!sF0=G(0PDVbKd|nc zhn9e?uCZ9$}XO-&sxi=({nfjM?@d^*N3g& zyQ9q5Km2!F0qY#6v^g&CQf;a%YRYK+{1GkR1*s5>o+eos7`Gap2qNOT+<L zELA?p@V12R>$*%;2Sq?0qzT1umhPk+Ecx36_FKe_!8+TUPjQqD^~Q}eX5-!{Z^ z4V~>3*O}FNTGu%7d$3TD9mfrW1DV^0=|3E@hXC={mxH%OH$mIgGuIEi?;0i~XHgkh zPxYVk!*y2l9Hgh_h(!NtJHI9qyO6#_$vkr}(4QM$23cDhMDc@nLSGHX#m38as4mS~md#*{&@Q zjYf`xV8>Zih2xlC1);#WyxJbfw_1nDm~Zyeq}CgMG5@^QL?_2TQBl+!>Lb|pq5m3W z?6)cz!dv^w6PQZX4<~DR|NOb)La@eXvx2Rn;V>i;P{WG~xvs;t34>DHrRHBz>tlZH+@E2t=#v`apZe`UN~X zFnmfG@a3HAvXmG?waJ#~jSdZf7l6<14OA2tJAW${exT`6gWJ7+a{oe2X(^Jx_}S|c zCw)tXO0qd3^X-dGA+m4ac|dfEf1!C&lVxTtSBnKJ$UiFU^P8?4rj>h*d*Ix<`@#@% z@&c+grC;rTHp!7Ec$z%KJevDwcofHv-H%+%<0r~n*zJlc182gN+c2=YC+45s#)-ID ztX!r{lAksWFG?1a0SOxgar4E1(bBk2fkMqzaTT%g!?_4jqKs^ZZ<2gE=Rb7cM$ogV zH0m)D>Fk7@BbRbT^*Rqy0axx4VuU{0QEIYfkURxbhR^l#^+2^=Z1_7<918itAaH8v z(5$E9&l~DdBwkrnl+A4+G~lgd_NL3wnRA(y*%$i99hI&M=c{)8?L_tte-$`mBb{fwRJJD6yhQhQxn+nUZ|^LZ zhjisPy?u}ig8RPoe+sOPYq6}`>8m=pzZal-A<`ha2li6D`e**=zq0l7oyrQ{CGyec zK6+`q?QxEzs$P)>wH1z~kN@xe|6ix7Z$7qy1b3k2+GSVqcN*)ne-eLqkI{G#dS$j7 z&wb7JKa1D$LC#n9U%vb9)H6S&>%f@(Pow=ONqZg!GiPoi%S@ZDeB{-BBbD89YxC5O zmuI$$c`IW7O4Q{Bt;Pl5sC`@T&`Pe3@P5;NFZCy6f!Zi6ldj)~XZIvUfjqiqNc1;_ zhJ!{LkK20v-GeeAyGK^m#L!P4-TBaHDJ_{Q+ojAgJh`ODbR~gEr zw5)!Mzw{aTAQ$_JZoK1ofx9_x-w>#iKgqwl%3F+M?U@*s-89(CV zXS~llc0qXKD>?gqj-xAIAoiPrDb!EcJvD{Nu5tn&fs-&4QjcaTRadi@pm^rgSt$!TBRkqQO!hmNd<7xR-e9M;SEcH~Z2 z-v5wqjb_-9;M2)37^Pv*QB}Y`xm3w#A59LkKtke5visjy`QSvZY^L=l$}@&RCZ}%Q z1p4f;jsI5@OBYB4rXlAE>&KLRVMl!``VGN7Dc2rR=l=X!L+MeFyYSN(EkRyHNvs7b za|cnfVkW+1QuIJd$>%NOtgm}*xs!Br`sh~Plk&vs<0g)nLss%z;#nt)peXqPn zR3eeuz4-mt0OZ~0M!E0ZAKBdATlCEJliRA{bLTpQaOk-Hb`gK&+92L@_umLVSac^# zu;#sGfPjkYPpkx;NQtMYqoKpS4T2c8`#>D)Z>{XvBOv!cI;|;n?2dn1E`7~QN76tt z=50E*4&uNNfn?f=crEU6*cTI$w5@W@&2i6y#h5n$JKP@TZxTaorHkwe2bB1<+&BuT z6x4o=LavHx=*Jd8!a&T|gypRX9G0-KxHmZs94uArS?g;3TsI zq}Zfrp@3$RM`DvS71uwTb-dP$MpfHLZf`bFl;3w`+@VKiKP7O6b8Sj;nkVc1%&Stu z`=FGlIz&uMFQ_Nmds!jD+YCzS1?crMPOy)YSoF=^jsb)Jb##Wft2Lci=g7{>wZo$^ zZhmEc2c?s-{s}^0zlYeTiyuk?H2lhn)3$4&SywlX@@6m!h$T-lu7C>7@v9ZBnSc6I zTkbxOL7z#*=`=Aqd&M_PO$8?-QqNY}9%22whxZh{eLZh3lf~fjl}b5Y4TDn&lkx+t zi|DQ&F3P_awUy~42>R*fnP|5%=GDu)!Q=F=d-DPb3pZ#R) zCHz@vOoW9Z8a*y^cWuY)Vv%+0$PM(P61*|2DKq(EbE#{kg^%`S?7+7<3uMcucBC)& zCBj;mPa&7JSghPfX>dmvXd>*%;rTkAOF@>B#QHlad>l{Z*+oU@2Jpu#c`|P#ElzN( z+pAF0B8-a!MhHb=paLe;4)+5+rAFTL_qx6_$i4Y;MPumsMM6~>puYj2Af?JeScl`W z84=TdnG&sv6Tr$7&`FFQkhJz6vNK@2xlxLU4Dzf>YNcbUi%HT8I10cx;>&cPrvQk~ z7lR*T7i>13&ub;H{3>bYP-i%Nt%1kkgTHYh$Znwgs4mkJ=lovJ+;|50*+I|zRTOW< zP^{2f&8)brXf9#B?cN|+q%eVJ4;)sDY*gY+s0+jN%g@ah%qsaH$AlFeqo%^iERG$9 z*6neS6ep_44KX`YZWalr)3Mgrm z=a-vlRYoiyi_?c6*|>>hPB^%8y^#L^rQo)3%b-(+p6pYwWXCl9g?sAYlKWE8<`_#l zA*mU5kwp3WKqNlpA%i}?n^YtYXIyf%b7$Gm07p729tD0ThHs`Ger|Lb=Jn8-E2k-$ zP1{RSH01o*4u-&vkU6KoC+|G>&a!-)@|b$|bdH^Lu_1n)4l1Y(){jI>r;bERZckJa z_P=kw$504apysBwl_Z{OJ}PX!AZs;)>9_Fc4r>N;~LeOgf&+&Y|4c#`o#>)s(GObc*+@T7zc(NzmmI+q%f5TUHVK z3iAoR9vCd?_VoMe=O;)fBR7Xg%H(fc%zpk}*dn_v{9v^CwZ}3r|A;dGRr%d5`MP5K zuj$_St`kyNm+yb?8HPQar2Z)Y+1z~Tpl>ikbiGhJHftT@%tWb0e@Cg4gDluDj_;Sy zEBheg0qY=*&1G&;<(v&aF`Nlzijh^}_`b?2_MapIegqyJT~X7a_kDG5ihpWecf%o@>oO1k`9zRCDW zrH2<=ZwR*Du+o?&aIfoxcE9Bq4;=&-2Ya`22L$+|!LK-0F>;5ypj~1oEjwe*u5(|4 zux-|V@^T*wt=ho@x|c>Jn9lfzJnmg6ySYWO3|WpN&zvy#t^X-tzPLymghK~7??d(5 zPDA(p`LJ8FUZ?xia=?c$e3zxzU6SNVX{nIo#43!r}xydd1uRAO^8*lWI zVIQla{c9z{tjE6|+M{HFMds$=+ndb^nOf78ewNm(A-t|+Q zP`gpyIe<|DLwJ_C<c!3b(n$*LU(m6JB7xf!Y0te76Wyq?aXK}X|;-=Rj{dC^I9x6<^lo~i8raR zF6PTtbHoBnY{zA(t_AW^N@N~QJd4Xvb6j%!GZ`Da$})ZJ{AHsjh}y8KsGCpV&Wu5ErPDgy8GV#ciB;26q1KX;o4+m zTjiK^P$5Ca8@m-5H)+LzTky}Q!o;l}76Y@*iF?eyJec4gqJ$7UnBuOPN0n-L0j23Q zh3xT=T%UnS-#Y>~)Kxs&y90-MOGYa(%SW3bxa!|gwx%}PTlQ0(U^tw=rfv-Bh6bON zl8PgJNcW+zREeP!ze5*=@6Aak|Ea9PKru!ThL|=qTcwEL9?ya|%(8qmLplJgS|y^1 zJqXh9#Bgl`bngb-?SNi%W{yCuKDA|K*Ce=_&Bo2YHy(av&Jj>g@NYNzUNYPJ0N?@r zFoRx<)B=pT^m4Xl(juBGHJPtz&jN;Zt-U84*dEbUq*damu*`RDq^aZD?SbwIikz+d z>DFJG@9YMtiL8NOzkz<>dvxBv_!lx&9`HBTW4*>ap!7(o?*HBjZdvE~{Sv$@$S>ah zBS5AdmBqyz#9>0Fj2qO5Eq#^yVOzmM$NsosZLr2cI0?25{5A{XwASo07xXdn^{0Ue*5$9WtJ@~*2BIM|E%%fcEJYr z5Yw2y7Cas*yijF^F>OtB%7L=Rq*9|HuBHtR#*R<&?)VC2AR}dIk zte=W?=LIs+Wu~v;ntU=KL}^KL+Mxv3`DBii>?MsrrMY^Uj${GBnU|!m#QdI2YY<^~VXV4E+=Ym4~ta*kx@7B;V{Hu?^wa_TXT}`FfLc)``sJdKR2Q zNSYvvVbJp%^5~;E7RBQ^7=lVH zT~pnJ&)y@I;WN#|KL$u;_^6BD;!tqp7f0Ss_<^swZB<8bnv5v281CJZXNfrdgtL`T zFwD5YXt4_mtNr1YL;0dV2ji`DzYi{p?kM#V!OuT3H~HG~IeQ9^!BWv+ev}$kvzyL9 z!S^@h;;#CxV*N`|X3xdcYohb%;}_o-?BV~bV^o&eK{BU<$UC0aO#D!kS#~;~q|*2o zvb-hIyoYN_fUhbFrJx=r$2RPYh4EYW%PZN!P1NgGNm1p2-!X1ju2YlNiN{mKj=vEE zma6U2$1eRWYo5BL60R1lwMRHD2^sc7iP>7OkUeC4_P_YwhV)YfUt8;KE2V{HDPk1; zRs^vGnG${>j(8Jp?7+=IrzGu+{dIg2rWaj=v8(8vT|5=Yg12?AOl{YN(|th*B?oE{ z6A|>JL4Ctz-5YMmf-bzd6!~(BMJd}^W6DaxZdXWVOppVPDd}eH4c1=>sv5GCyk*f# z#STf&(UZRgRN$e%#v5-6OIDtX?m<%}$uo9rsGne)kDPp|6BlklV{Y%w_3%j=$|qkV zX_~s`6EKcL)c#G-b&8o-mi}K##5kQ_4$T2hPowH*ev%6vg1Lp`a=%2;97Cy^FXuro z3};mvA?Mgb!Q8uee;$iY(5yTDsMp&)chcNG>tU>6Nnlnq}h-?xf8x?Q0jHrl4(@8Rb(Nhy<;Xo5LU#B zJMoQ$k`*Vmdcf1RVzB!kCZa^LCg{iVe&lNEuYdJQ$%XmIjD=Y~xIN=5K_T^xG=fvM z2Uqzgui&ye`lG7oJ8t4>=v$@|86(BOSQ3H^TX}<)=N%O0Kj{kf-{#4rZN7!i2(5mW zV7sm8d+0S7y+CZRX-#tQB)m!v)Q9#Z`@Ll`Z6S5+p639$*X+=hvQ=>|{BkwpS>vz! zgi*Kw!`4bALL-v&^ZO}Ey4+?i%BO0=p;Mk%_JZ7A+xokZymB3fD(OWoE2#m=?6Bvg zyMUpaJUO#@Wxp`lOC>@y;Hnw1Bje(w?Rx6=7@zPj((VYtFe{D97^4%(eaJTOFs@+K z%vhLx@k@7QVgjj-EMk|ohWYN_sm*6(+_2tp!v+^d1B$X{JhRlIHHd@qQtIh*NPe`c-VxVedE`zc1uhe(K6 zLsKkQ@1PGgyxw+tQO?GcSANTy%?ly6jtv)#F(ON_v}~M?V~^>cX25!NzWD^j?YN#1 z*D^D9{%MVrXYhu~_Ia%=w#v_Ox5>k}GpG&O{9iYw+=|9Hza*K#rw)kcpiIFHX~>$~ zpg zHw-F0;`ifwJf{k)&T2r-_LaS{iDf~3ia@j?%ihGL{&UD=^iqX3hP(_ zTb%60vjqIvOHKY5)k`**oLo9DDFm*Hb_Db$2zr&0j1|94Xp6yD4`N9P9G`lrS{oC) z#UL(xelC&&>gtts01^Qa$}gdrJa$`L;#B)oq@of-shFpc5tyfc25%IQ*8Z27WAqu5 z`#n2T8_F4Y_S7`ZRXG4iqAHP_hKV*6Ve{NZYG+vO#>g#6}Mx`p|*V;a6 zAlCkp#u1FMR2fnb@ z+L4%Vq{E~eQh zC*)N$|0yq8OR`>n7(1rI1`xZ@EC#KGfd-T+nKH0lzOYuH50Bh=T_Q>7|D`bTLw#tV z%YKdYvgSKC)_wm(A{zJZW`^bj;#LM!2DxS76-?iM$ES-R20yAFf*Bi~xo$R>gPTZP zgDR#5t;PrLgPbZR%j}h1+vggnj!&8O`9&~yRc=s7AaUo^kHsg~Ut|8}sj|EvbHzM! zDT@BewF)B3hnMitDRyiqxc?K5AFuuh0aq>&-ki9wMHC2!HXU(8g5N{<)!D3Y;|)a&rp@obQ-HjO=bcp%H>npPC6E7oUcp^;VGG9H?A#3phL;+6&SKw+Jstz8iEoeI5g>Te>Ds2?G4nkSuqOMhJV@@wmAP|IGgqK zRJ>$3xilOuCl>36Fpw=)R6fOwp(VgRrSg=tRI55vX!Fa0G%*wUAx_5qGe6~iKRZ{_ zT`SW;VT@Vd9E|0fcArTU>{$DUx6#|YYch0CuBG=2MiREW1_@V%-vhpjAEQCzJ=?q% zw?A7RURi{9qFY$O#mO(k3Fa0NsWJx7iy5a`Z&0d9&S%;2#W%8l>@FD`2U5lg(3tVw z5-3!kOT=L7t4goEGIt)o<1h!r<%9-=Ex>(amX?rMw~Nz{&VNXCe6xt?mUs8%ZCb<~ zON5`#+rra#V`qLF50d1As~1G*@5H`uM%DT`9GvKxRD%~GdUS!55*TFq?mRz!WYmFA zgF|!RhaN)o^2INqF3m0i8XAk@o!(Bk-O z&KNrGk8YC)eAO#arTg)rN>WUsmN%o6HFZNtO!c6s-%*-%)^l)Hyw+GA-@Dx3hUb6ZMs7){%6$`WE4QCC}_7Xt-n-y7>0kG=eG|Cnu;WH zo#A$Wc=d32sCZ)hKvHB1G%W^YQs%9?$#B?W2mqxIYW{JJ{(jPtDU= z$Cw|?sNDm4R%hKH!Rmw!s@6m#foTpmd2@@CgKf`QVNcEc_8(lT1dKT(mN2vjNlDJx zA-HtlPWb-K88}xVcTO4HZ7P`XAJ&%St|eoF49)mdzmx<}qy~!pjBhDINZX~$knJ@> zmFrq$lI%W4nxE#0w6@aMRhn$Gf@z zLj5^2`K`eIuEFksb1%qjllnQoU7V=qfcxa})yd+{uHz5PrMf&n{KBtE0=Aa8y04jP zw}>;+t+^BxtR=S<@OXJoTj`I#yCdg+Fa2J6^E$_v(5|_V&<;%h4i^(kjY$sQYCw*O z&tu#g`JuXD`?v>=~>Uy6a8?Q%Bi}C8yVX5&8Wu@H+C7S^A4hg(c2%+H>WU; z*fw9aOmjuC?u~nfEg%?Z5>2h`0o~OJd<^-6HhVD@wibV-3KBjz{S>b>N!w4SH2<(E zW8W5MDfF>aQr5z$K_>0BvEFlppZf*({f+usNSuZBDKF~8&FtXv^?lQeIjXbZb!5nu znHR@6^xeBFZhi&<&?wx{cWtZjeEHw+?XBN~KSD=yTk5|@bl){A4VM^RL(AR9t5hn= zl|SJvQ_px!Y6430#+{rd`$Ol%#1}P6e(~1R8l}*k+w3%NUZ-838Zf#ckyK@ty9KB-|8^6m6%(6(Tl!0;K6|DLZloV~ z{rUlcyl$=f>ajTbtA%ODPVuZInK`L^2nX`J%&?O@eibszwUv2C#@zj%xiM}Xs#HoO zSOgZWwUZs9Ge?qSqK&&Z=+8F##k|?b50qz{Uiz$`IkZlqcir(;B-SqzJXDaKGzX_O zYWw8a`?xiP#Bn2dp2=>BPw7wm$LZ&miuG5j_X<)XB2-YzPTJJejFGMzEdoZ=r=Ink zaDTU_OQ)q*Ge_ClzZ#V@{F|9y)CKbvS~`{u`1&W@mneg*Jm{XWPv z_cmp6wvpY8XznXmSG1a8Rw^yvM~Mr>GLbh)X_MBmPL4+>PEaeOn}Jw=qt9ILP!<&p zB5m%oe1xmCA~X|by!8W);i%r+at^9plF_(-6~Yi+7%%ZF*f2*Ww7Fp7aLnQO65TdN zraP1ZbKFsFO9)Po+j0T?m@wgMA3xHEMj!B^vD`nJ;Ei+AMS>(@1!?o~nzc8sSeBqF z?&kn12(jl_nf_;vvby+^@ zu3fEBw6+}ylk+UuUo5OoTLh_CC+1CB8iKR_h<3`@^-fuOE7U$XMRF-z(aAz2v zL0ocb@h`Xqka`=(#LR0{-J%rTue!Jy67oWKJePX@;V8m)0B0qPP8eCa=xgMIlp2uA;vAE9JGPxV)cTojyMI@~1~i(t&&S0A0@- z_BqG1M`Ki-$jM`k$Z-g!-ce;y&5nQ=WmiKp5$*RRKlHLs&Et}i*v9zlyIs+no9Mp* zfn3y=Hu#yR>Y@FXrp{~w)Dn2l-%~@`_AusF3==ppVPJ);f9h zBzaPH(aWzcVVD||0_FT9Q-k)S5UQ`V>GNVv!@UGcxSox``$C-+&fAXYd%(jRTn-G% zDLo^3)w4$AuxoBS8YJ9Ufv$2Rg}Tf{^k57}+iqElyC0hi>pJ6(@B6|oO)aPz{zX+! z;G3EaUpOR8($p5kC6zu*oz4fRtMj$)L63~y%Ka2`a7T+t(3K#^~Y9_&Wbd z$^G|Tt$Tt+gQa8t1770|y=k1Yc2VemuR&gCdh@W`ejt0s(~7hU~STW1|7yMs$7>LFaQzj;t1H5r`wC75R5yP zQV#PrFm(j#rQ%@=1kg}OI8o>$6!LZ1_5LU+3&BUMY_)9L{tr`c85Lz4whPnUIl#~< z9n#$*r2^7OgLE@=_s~c)C@3j00@6JUAqYq}NDBf3NJ#kI&-?DZzWs+azviCBnz^p? zIFBMOqjg=LZu~c5ECdsjd6+piW3oL&^b^D zqPvfa%VKAIAJO(R7Y;n8gKwzEKN<4%Vgn~oUM)?ZG=ceW>Pn&xx17Dnuqa`A7&o7hmnm|(w*S6XqFc97 zv5!o<#yn*!E**|!&R-PTzU_0M&=y#YP(U}$u?h*oh~4DzQu~=Gz08qj2Kf#08kf`5 z1&d9>S3EWkmiT?%{LA?AfNN?(1J@y^#mhB~4CjA|*2B-$hm)|t_zLrth_!}>&B>GQ z*PT(^UHgDr8w**U46&bKxY>1sKkm3vfliO`Cg&4$-G<=1Zc!A4UtNijij>fXe{2Sm z+!emw>l3m@OvGoUeGEEX{$(1!xG#4zb54(y zS!dab4)-R44u>L|Hng6*l|7(vXy{aYt(;mdl=ep1n6_5Gg~`yZ8F`c1{#Q$9{#6FK z7PM&nZfzJ6{23^p(d65?p%g2O943pH?ixFh$+if_QuFg(8|)7uZzo^3*sM!6&p$&H=^D9-Gfxv zzY4~}H%v|MH>+`Jq=vDdM?Qj5vMkE6M|=NfO^_CPoBR~sDwM|n=R%NR_dV%j_GJ!| zYUrTT%v6t|b9Q{eX|@VBznXJN@Xdb0oK?y7A43`%)Xh#%0{%aVaPJH@*GpnA0BI70Iv{SrN+5fD&`$iVl3LwoktY3U~NuRtnyn0DeUt+uC+>zheAA2JelH{de zUorFpnf5mi_xe-c1{hw-Ze9OCQOEiQWMrsP&PP3*oxa_e4ugi-O-ME@eg0BNe}Y9n zep8n{N4l|CQ}cPBfY6b`nEbrKn5=%kG!sOU4>X0dO#BFn*}1)^*_`P6tyI!)VQR9X znNwt!h5*xvOUUrZ=+)oKB^40hGnvJkqMhfavY&F!CAp&6)wMt^a6$4yEq--F(=djQ zLfZ$7lcC7J2|20hX9}A_Q4$DdeMbwq}?^&8P?XlAg+}|+Fa`!$qUykfP_`o z6_*@o8-1VIs0V4?oGGHeS-w?J?5sCB;#6R5g#!5d{5GIIpN8D&M&sD0u6qidK{Bv zYGoaL4B2*~6WvNUH`ap|;o=`HyMq!UyGg?FkAdrEIQ#Cuf zEhUjfvMX`?-elKeSahZ@?9KPf@ZjIZh9%YZ9{jmp(;ph zcU;egjLp`U=s6MD&#z1ai=P;_r8HWzf*E22pb@37mTtHim*(XjNornI6KiAMzx|X#^d}W{qiD1k1nYZM>nSv)~ zlDs*#rFT;6yAG-o59LahBVVoksBs|wd~WMcp-qh?8`&9})>-Lmc>=hq_7+4VSSl2J z#`8qpz;0>Ga0FieUoC)-$$n8)p2&uZoLs4Op@rFoh&5|o3m**}8*{`=Y){)B@7B+< zPb5i@E{Mn}Nh?+)=QK}U4I_|^#*^w(+!OWZzg`oJ241qrh{)(RYlB-dN*9t)P{cHO zyNDL-$GPXlIAq`0W4+o(vd>lcb&-kc!Aih4I5pg1d3G1}q0sE9J}dVLCk@olN=2A> zgyQe-Qd>Eq`)5D5&{5l{e3EY9+tB?JBhNxaow8PIqAK-kw;O>Q6^#ULlH7 z=&?m^*r~E8^T+aU7t!s2BvM_8KoaY)6hY`#XP*$CJfFU#qAP!$`}77w7j9cw`*gTB za%H8yp zuhkyk4qYr$!i~=sUdsQOX|HmB-Bd{Zw8c5SU(wyIIU;}O_d226+^X{tw{PdZnWX!4 zmRoL^l+{ev52pNISH(&5?h8N_rMGXnrPQ3ev;lxq(SSI`_87Xf0=Q2FgP3@WGvnFy zL~6iuo?m{(2DK;3&Ek^F0tRcjhwlLv@uk5x_rzArh~?Ej&B<%TzA5q1e29Ph^}Q_m zfdK?xGL{$>U#>VmCy)`Dy<{0q{L`{rh6v6n`IxK}QkWNu?Ty*2Q9MZGk10vRaDE(vY$K`PnuphWwlHc2Nu6b|NTEV;?O~u)wSd4!;+a628^#hbnO;@@2>tAsNjyNC$S@Gd~*WqNty} z8Y}&KSsKjNy07ck9&@V-?E5~38Zi3PCzP`+yu?2E7DDb3;^>BN#Bz=Wf8l8jZ#^_d zv=9}ULp7NwC}RPN_+R&8jC3fXE9NrrYbTd5OTK)T zJc*09zl4t?QcSs?;`q?}d(#CUkg|hYV))Jh|!{ z@s29G3KAn!N+7seC(U*Fw4}!J(=U$VZ)qPdYZzI@WT=+clg=ng995NmVNA)-3f+7N z_eCpjrFvcTB=%xcO;DnS3y-Qha(W@cfWBzGEGP=;vfT?dYdVZh)N7+=nBF%bZRHF;*}F#(**I4 z)~e(a6ipM*k1`gXUnHPiKQt@%iRyqUl9ew~UF(hFuW)=@s4`{lYEka79RrYuwVjD_ zb_0t{N0ko-$>5y(RYB7xpPEcUmgQ^3W`KoIo?Z2%7ddRmho9XsQ(Ew;3Epf-zUSZ& zYjp>HSdiqXuNE85-*I7#KKX4l;^Fe$SOwWZ;hcb{n^V=Z4PI{`Dk9n0)1@jQ#G(Xt zA9!xRkG-^^XUma+wf^94z0Y} zzDb-YCl?j1w#6~Hmu)fyP8pdgqCRDyoY&7zp-6{On*5oPb_4?3d=(8>FNpKLLbq;3 zpzlkO4L7SJi+|Wzh<+7HjTk0mk!s0Y(SjP4j0|hMBV6!ni3|GT@_s!<+R;KOGDPSj z78c*MjRwP%GRWC+qKaykYjWE!?NI6iq{l!bT@IUY5_+C>^ve*barg*(IWCmYIvYD< zpcl`tpfvhJg!3mxjJB|#%B(41lC@ujY2|*S=WJa-ikIdAU52( z-MTHVGQ< zWV0h6{zn1^0^SPTriK7OdSXkHj&Gf?Pscw!(qj!GB;T`2r$1JgW8LQNf#Rk!Z#^!V zIG_8?kW5VO1$A#O+t)$hK;VhzGq(xqMbUyiLCLQ*y!*GpY3a|7Rqqe|1gBOS4GQEj zR~@~|>6jN6txM&KHY71br9*qiIs5oL)!ejT@D%)pbcsjMv?pzhM9Q684CcDj;#xmB zOHK6$LT@`@>wRBvteT~IC9iBANV}jDkk$`;(tVs8}{f7N>J0qfP!+IE^RI{H=F_XT5K94TMfu`ws@vz!{s5>t| zG*L9iW7cZPV1KWyFzBmItgx_Nn^(Bc5Unq3XD3?En`%iz`SZuGvh*|;rtCs3H80_! z?ZeSzT~GIEhxHp@1bu(&#Le~|&fT89+nt5WT0plcl2)fHe47_&mn=13DN_`_$==g2 zms)b~xV4fOI+qhf-aF8F*?f9Ym;_O;qyG4b(@v) z_JjW*TzQon`!?I630@w?_M)Y!j-u_KsW`ke(POCsSgCPszE%UL+MfZ36-KqgI4jgakcu| z>2tpyK?X_f_0AK)pIh9NKZ(_Z=4ROnJaawQ=ZdX*%{OnaQ{HXLh-k$zqdVJ;oJrMT~952Z8XGYWkP0*DJ0oO zfs!NAJlGEaq$*ImWZ^|RM6~sRTjs3jhGdmu`x*67cL%_ zu;)@fmnq^Xt*)3!SvVDv?TW?@aO|b)v~2Qi^$g z(vR2RB>Yn49{b^wKWGdz%GzX+ClE zvD4q@o>h;S2w5<*)=KaU9>V*ReFgr~eK)7WvUS>#N6_?eKUaDfJfdPtVW=rjBpT}; z$?npraZm%sU#vH{C$^D7x&$PdOdc!HfF}I1gS|?MX z@xH_wBhYOM%fxM;OS&C$c+|xU8s#`BZ_@KPkm$F!Y3`BaVMTEkUEy)kSysyFY9aPu zLm8{M!J&4Mw;s;}aW%iIPxu<7?6IzA%*x$!+0<>mqzv3z6wOvfF$C~7aXYpTSxDG- z(Gt1NEIt9vbL|xY@Q`h<^3#PN`yQr-SeDMbg_O7D<>&gA&ubr2EXP|2+E*6HT_j-r zH@W>J++SDcopJS@R`xsBJB@sC*#v#lwB;@K5TByI(MdFTXv*;p3*x3jCd+qs<$wU$ zuisn#>#hqFH!dC@x99po@A&8V2LRV=Tul!V69oQK*a+Hj=k-PBjly47sTByF%WSSk zpKab1;iZ)~z3T70b4#KNEuxHd9R(TtmVXDQ(p}T7cEG1k@}ce(kpZN}Ytzn(z-zs@ zEdTpq0Ei=T?j`{W^pF?5=~Q$(kAdNM!e9+%nrdi}(t}|L;I|e4znK!d4(d5vk$541 zWCMw1?h1g;q@VA2y~d5Y*wg6r{~s3A0N^(1?>9`>XU6CMe?qiozV+8F9HQg3R-pk@ zQ2&;;1n5h`#4o^Nl;OX3o^W~1Z9EeopX9w_&mAc4zOd%l?CI7VsJ|C5+2XPM;dTiF z*cJ`~AM>wa>%LBo&iNy7G?kE8yO>p1tFJ`HOr*{~1>h*T^=AmhKm1U9655_HBWEa>mZ-yX&zA<697OgfKT3=e;?DEq3 z#%!j>s#KwGD#X-bd+RS@T-}lEvF>SYapUJd$A8*(Q%d&-@(WJB8Ox$d0gc2<0hMb` zz5QU_HW5N1GaRR7yI$fGDkYXaIK#RX*zrWXkdX7QM?ZU&p0_;I{oFzNvaYW;M1fE za^YYT+WYB6V~~<5ZkLu&oHWMD!`c6N@I8)ZPUP2;xa~~!aS=^Dg7?0S$poW{tDd3J_1RwU5ZX zY0L+&&OYPy24)9-Sc{WwBJS1U zZbw4|EShkSo}`?H{0V5yUbu!>RBIaY8r{r{OW$Z&$OOYFzYqSKm1^oEm*U!}_wO%= zRUCG%{B;uyHUY^&!Y^3wy=cnE>BRe7vEY>Ye{Gslr76T6%V|Q0IQF036LQfrDxev! zB!rV{s50&ydXY26V9Qi}v}5z$22K_i*Y+-+>c0#4>R75ckb>YI@A{wdMW=HY#W(Vl zu2DqD+$Q`)ATr}*O1pYOwq}Q?)ho=%Hs_l`LOF%Lw8q+$nAW&1>nQ#id))Orr{c_p zzQ1PWWT}T+RpV!EVdt%Nl1TLOm1wwOr8SF4)-PnHetnX14AZH!UT$c8=~Y{D)zt7i zpu-7SgEeMOW=};h3pB)tI%gkf)vvvxd=~_LkSig({0b8E`I>47a|c$%)GaL*EOziA z{w%mjpEX6I}<)BXHy z;z0x4O|?`OwtVK@c@2#3;_$f3%m!2JH}xBE3_f~r>zxvXZ**G zZ6IE8h?vSo_=}%U!1_f}Wj2_tQ6FyRXNoWsiuc>Bl^pyW2`<&K|7sR3bOlxZ62%tG zaYBa;;Sgrq?#+UBFvJ8iOh!f)|u;Pe8B8Y|Pc z=i}aj2pFDIzYaMu!}%R)KqP}U2>cQYp@rUtt=c21 zjKs+JY+)mp$=UZulPSSkL&TXaH-qRjwu{_Gjb@w;>FFi%W77s<;$G|+Qi;V!EtmWS zPro<4@s*Uh3<)r~KjPUD?iZxPpM4O5ReGK9X4^5^Q4z7}9*0t=>tBGF(%BK04vsq< zHDtcY-<3%}Y$W1MeoX#o9daNaA=eMyN(^<_P?!lBZ3mfDvMV>im zc!CwwAQykbid5~p?&yF(y8HX=sBit_H1w9a*x>L*-By*0~=O+;`Ecn%uETrXeS z#1{D_3l+c(IAxy!L77&hA;1$5u+X#z19X0^J{eC;kEal7uRiD`zQWq7wW1|J?LOi) z*sD@$Wdvdf`xgBzBb$j%4wZ*soN5B=-a` zzC;t7pV9VU)8%=Lse0?ghaAdu&b?2##3VXSEE9eUbpjpZgT&?EClc$jTNL0PMY&_B z1)$L6u6Uc&^UYh*(!+qsTtK;W*Eei`|Ly$rtlyW!D))2syWz+NNy+8ACOmaDqm$dp}O_SLjerb{gLO&WAnMRRmWRES~Nb`_*H#D zX4`yV?n@mX>j|l9e z-f+cVg?zbdN4cy?biYdLMYnQl92`uL5MNHOC=;lx

t&q2AQFC0F#YDBU-7Q9V=MP;hs5Zlx53LDIv zvfm5o=XeFW0x$<^(Hi6*QpNv%YM{w{nJ=mCC`jLwg#J~P&Bu2rX;U zRzJX6XNy<|{O4F(#Rg|CZBA)lA1#d;3mVCXkG?3hvqA!3)BCJyoMrQorP>yZ9w#)Xgv-o*<)4^giDEFE4zHLFG;7jXLNsZ^QZ!)U!7 zlTXTvdH%6;)kfENud2-EJ$&kY5zB>24{PC=F4jYS?Hx&42U+LS{6H(=mZ7!!VwdJ$ zEX!K?=Fv8b<<;$(o3O&y??3G{5iad4duj;kQw1&Enyl$o{SJ*P(ZV$#xe+&(>=qR4 zf8Rv)X6QzERrF3)ap2Ds#ZbP`JaqFt-zDxZ^Hu4N&n@9i z;p>FmZA2}0>*kNcS)7%DXZ*cnaPg^&^b5Q{%aSQi@D`e4!-o5xTwz;aM_Kd-(#tL; z+2D%i+n08*D-k3{IQBfi?UV$Ewv!?%TRS+9&TN~4t$jBN{a>7M`4L1lxL zAfQsFTp1h&ZKlS@;>U`$M!#+f>L@V7?YfF#*mf#mkdcwWs9 z!tjz|R9~ftXetT7jtzrkjtUWxxKH!egOgIWG4=y!a0F01no--dhKKQXm?lxaip7@MfZ zi}Y$_#bR)3ho{?io`>7tG*KztUsb%c8M*?$^knOU2;sUBt?aT?<4;@fnmcPDEO@g= z1dgOUxnTYxqJk~X1iXSzD%08MF4NE>g?qGZ(hXY3P{u`frG09<(>o7i^v)S*K?qkH zZ0aV=KX|_hK&h#{PJ|RUIeQ}Y8*pHbB!hn*@E1Wu&pZM3c^hbhDpx>?!R2yS+ z=X?R(7oqCVh(REkIPg^Et=5a{QAulfpPgqAe-$ytCshP*^flYG=CTKd^|BATxBlKS zA%C@qXTe^PwD5fVyHFZ6z*D#QtPG={YN7Q)mxCL2n8xL2d-HJK)uxT%B+G^mEe3lx z0LdXp0F7mgH`f`6&v7HnG^*72*+QI<{{Eb`6LrM)Iy4Uz!px!spmYhgNa4tvbbi@I zJ3rN$w$|Cvln+aDvP3SBaB+CN#nK8C?g#m`gbXY$?gw@teuW+kID03mLfnPgCPydV zz!@v0hjdYw?OWMzhF%I|fwxA737pYkNGdxGa*46Gtiypb@%wDtJlp56J?mShZQZ|D2MukQlk-TwJ z8oRbpF{m63sZj?VcDavgXS~G1r#t)Ikxzfmij{*l%nTZU zW0jDK(>Qkj&7~W6%KGj4L>i8}{UzRaLf{son z9Pn$)4H5p!6^o`0VnjR2qq=3vUhGaFv-P0h7ZD6R8(bz|`%hB9pCOg4x-P2t`bAjy z@Q1rM1Tz#b?mWu$b%G+tu6h%iUGFC#YxGCltZe;bC56F|i ziz)Tr`?2HR8V9#%eP#pEQ3}=TYv_?^stM&Ws9fNE-?5;qZUdWPt}Q5mTb$zJNTV}I zyBwklqDd4PJJM~`+N4h1QO$ckbSHcW`(+TKD+OCl>L)%W-zfYTq|PeB{Y4$f_qND- zAJV9`-867y2yZ$=-H8BVW9X`bNrzE^*pn-|``(yD`>%*@?pwqAmdeG?^nAAlPQ2_B z#o_QVS@L4$X1GJmz1GQlYV&5o(?d8q$`uOFI0r1Q1=zmv^j2x z=o5B}#)xc^+&VSNjJP*{W)p5oUQ=407xg2TpX#{Um!>xFG~>GO*DVfgwmm4~lw7}8 zu_L>u9zG8TU~d07IS7UgnI0I;#>q&@?Ke<0s5YRk{U^1@5G@0+Ui-FGRB++XkeE?A zg?u|RMB;b|?5iqZgAg{0>zbBY67lK9BBV$f6=LLQ`Fu?N}zd zwl}uUFs8xXzL_2EOIoAoaQYl9@tjS=y$d=njMmErOd^bV5aYjusn%yJt%V-0-6S=2 z4`h9=tv)i)Irb+Kdzd+ei*BFgCX1ae`EmT|l>8D>ntHfD2jzbqjS!cSc?W)N|CFg; z*nNwgP`r*Dq1?8+nVxpx>u=;My?%|o;eG30N>+co?!K9yd#KU?`~LU49kbBDTrf{! zq|HX8rNr>%^65go(hkp@#8I5+-A+iyk#ifeCwjZs?>Fx}EbRXZZl9UWMp20byRS6% zi+HatwcTad|LQB0MxI&@*q5Z%##WG_{Oa8y%jYO` zXQ(YB?0&}$wFX$ecqkiWbbIZ(jhs8a<6*8YXgDD7Xw35F^4)CH>C)Seqpm_$_&rp* zOF*nX)DV@+k6kpn6^cEy5yhx~Oxg>!Wj>1Q=?1-Qw-u+xG(gL<&i=%LN(k4i#Ix@E zqwQbvkXe7{Y$ka`j(d40ZLxg0Yq$wMH!^lY{>+Ng)E!Fe4VZurXeZF$>Xm%!58`a5 zgcrBIaWf6Xa;nzusI?5upj2oOHl=ipqfjY(c!AV0;a&e-zMwX`M4RC>+?_PoA@I#P z-^2^yCNG{yc|0_q?6d7y%3X;>{AqMO6*#=gJ$Z!!NMgA|`>sc^rG*8f!B#Rgz(%(i zyou!^XTnkO7RJR9w2&B(d{ZRxY0S#x;+2}%qyYK_`ZUEU#vh+`^L5{bRPTnbVcj(5 z>wzS2&yL0x;;De(jJYYb2x0*@pJIvE^Oe-toifDWBYTsTw8L&0wYnejc_?sv)KX(E zV+wRMhyV@-*FYYo5jkCR?hfBXq_5YkpPU-@YK;l%#^uFHDXpMO6lra)ErcqL9YyUo zojnsB3b{Pp4^P;DLz~Xp`;JcA)SP4+y1b&-@2tqI+!dhaWg`Bcpbp@h=#fFQFWVZ|dn$$lOuC;7rwy zwv*05Qn>$|?5L;kKhY58*RaV~dd&~pKy8__0R#~}624r6fpLbrPK@&3ic)@vQsNu2 zeo(0GjJpal#fK)S_()RtK@hPV;snm3^|baXtLjhzKZB{uN~^Z}dP-E|NS02a^qGOnjGpNT~#95xVHR1K)iYN^$#_P18O_KIx(4 zk5eY_owHlZd+o?`z3#iV`%w-d7F3Ps8%H8y#^5hMC((;M%==$!yPq`_HE>B|$cFYP zXq|M_m-=x#=^s4lp>GzZNicSPpt;#0@gl~(v5xr5?X7!2${r4(xvT$pGNJ+(QQkJ$UXT8sZ> z;NZ%?ho)GU9<9&CPJrEmKcaSdtA_of@Db1NXRgY}`HQhvwc43^dZs%?F6aSri+Bl0 zQ`)7q@m9qhOfmtKqO>8>X_zhGIVyDUL5Cs$6MpWzA@h3fk7&1_KZ#tLX_|K~kXY@3 zH+{yWxUOyeoug6=#;;S<|LQY-6V?@p}P@cvr357FW%vt%e%S ziP1<+u7WJh@ zxTJ(;GmsgEYML7)_)16U`{~-g!pH~UB1Sq8I^{)#4M<2Y{lKgYA@Xkf%5RX7LPOM1 z)guitoXbU;fm^H89YT;GlH0;H^8Yb)R#9zs;kL%zJ-9=0 z576M&BBi*yyF+j-8eED)aVT1fy9Fp#oT9;@P`t(AIt;$dx|)ZPyR^eyo*0_!N=xmQqIiQb91p^+I07(sF6GGN+~2PvyH_an}h0g*8Q zxQH=CM{KOfsW?DC=L~y*L=3GIoxpA!=n6~*)^|O-*r*-u(FU+XYmt#}$evHY?4HjQ z&Y#}QE_~cWQU=+q&Fi7|k!LAbeY&r`w?NvGU9aeG%Mi>*<;lELpw0;Df;GT*0+qxx zhwwf6etQxA*qsT?jFUw~c&}D>Z{9~jK{!@#GK1H5k(QfN@1F63sKOs=9Xl49S3TC* ztb(3{L4stq{4n$&{D5m>=;D6ueIApy6C`Nc-NP=q+Nct018rFt=$yLqVN{tHy9YHo zfb`3}+Cr9w?W{rIf6M+$)(7qX=~?g_H|Zb*FkpuaDYW%3mMe(tvEQM)E2BSv*llQ+ zh?+?Pc{)aX{S?)wn&fCh$^;Mkg-RLf0r7 z8Eyy9wL`3<`6OAJAu&m$u%?gjwJ`TmSE0TpnL%JTI@#1>OFV0o!~0L7p(eM7BHq`z z?tN;A7a^RV%4k{#g;b4G2%p@%YGximSKLY!=ZpWB1-NL06w#m6#n5I_b-cRqwhfK$ z3Ub+(Xol=3^M%-*P(F^SHk_Z%og>l-T_$m#oEE__ioUMi0e{inct<0oQ}*Rw7lB0V zm^{YCyTF`KI>f{G>jX@6wLr&T?M4ls+c60-Pb+^+9Axma862uT(WLtE_Yj`NW{N85 z(3)R~1)%P>RZa*Wt(U74-6?o4oUGEpcTDxwuLIFM&%Fca2;+Bit-`Gpo2r^n(jWJ9 z6f;71ynrq)%}>^~B1@{@ko(xgvzc2}E~X@}g?ooYNtVJ-p(*P(R6(YM`zKS`RLw1_ zO$Yp1cqj|V56``|`%(-0vh*AWCy~gXE|Fa?jItV}7Rv*NPRSCeLQRX-SR={$?K zpG#;@Q6O?0xN8nsZK0`!(ougfdzNnN7=T(tzOcWBUIq$w#@#3Yn@`)M+jNepl5S!~ zZbDBzPYS<0k7}1XQ53FuB{9yBf#%IgEm@#BB-c9VI=)6QgdO*rj`u~yTk^t`OcaMy z-B=!N9U4d0(aG~8m+21gdPB&jmI=rZ6XxbnHw% zYW9wbMwGu`qG@L@JPH~J^es(^JR9y2);%vae5Fmlyb!HvR-u#awmK0HJP2yr*S8-c zUrXB3m6zK74Go)mC)q*~v z-V%Y&#|%#aw+}^VBg|hu|d)rRy2@=T+M1M5(h&O1?Fw)o?mi}=oisy2b zA9Z{vlm2X?0Oc#e-}+29hzAe#Bj^A935gJSB+xCva#n;r})t!P3m z-xX^jR|VKTpiJMZlfo7y`Q#A?4OMP-Mh`!vNIMoXcFpHS%#<}7MiKksAB`+z$ebK* z>))F^I^j^SwTFmhIGHFHzuxwX;yST#7h~w)I=2Ri$y4i!u;_}PQ8VOoo?lzamEqi9 z3e}E}jLgXCzxLC~#8?$J?df{kJl>g_@iA%)!~$>*X;1c%u#bC1O5Y@-U~{DveI)}- zk=ZkR)BowH)iP2=fumGqSQc;LIh3sVqorme&((T8`RMbkn__ZDs&R7Mm%$@sd)4c? zopli+#~E;HA0~aNT&m77z=4mSy_9Y7qmWhDf%Ph%DbvE0Wz8`lCa!~j<4psm46n#) z3=MROsLA^3+o8?q((xjLK9gTpwyO^c zUe$5XlxBG-qyL%7TWAUFFWks@QRI~55vpiOvyBwF@03pP=dl-TdG5^7&eV7>)_@#~ zi1avqtV7SM>gCQ<2qG_^#67EFW1!ud0+4d!QySx7Vqvh}-uqkR+;H5iS^0d#n z!~B$Ea;lvIe1J5nCsVje)jl$ftm~2G!K(r$+R4{|U-2zuq-5DpIGK5s4H}Qr_Wf9DyL`5NW7nWS5rY!iGiExydUlRrcY5 zRGl_OuKXqIb?%kI0w7maH@UkQwSYtUK%@bqQGDS{Y-J0JPyVCRAjKTwh&l?&WU)|&3M z?|yo4P5XpU$Oc&^7100xqHLcX@ggp<76Yxp&uvk}u$a%zzM`qAF`BXE^o+<7c;B zR+KiJ{h+_GyYk~Ao5Nkql1S^BfWDya0Y~iI0+Dl_<1d7!>`kldK|4C4`OZQb@0h$@ z0tI8<`d!n)X2J{nne>W|A~sRg77nJc@J)Us{I1_}LLk`cU$KA|ayy;+hE1CU&_EBv zUMb_Bo|^K{xyOXD6mxKbwzrC$!UYLAMlmKZX@)wu6J> zjrBR^+Y(@pA$mo8Xk*;a)nJ81T%kD*GyOWlfIA-=$#Et!)r02jWMk$Lj}8DwQIgRV zxqBH#isonj6xh1OX%j~c-y@UO^x&%e_ZJ2(K zPeHIl@0u4!l~-F~@*TeU?XR{gmGq6uUBo;DRO@C0XIX(}cKSSBJKI!4MHs&! zeU7Ofdc>Rf>fbU;!DAGJ|HFOp3z6kktGt|}UV@pCBggRd^6XAz ztjOIAj?+`d5hsj&)zP(PAycr&DPfQ;1*lcGH#$p7IS>d%^;^m`mk(M360e+oT7FD= zc@QXxViAlf$=*<7lqJbgGZ7DVE<>phVlNRvE|>M=o#C+r@P`_(W&P~JT>M zGG#@DR7ZDu^<@7o^3j&&`~;i^Pf1QiQ%9&5ZdM#7>S7N?@Ua2lgDpA>HCcD|JEzXA z3N4L=APOKFU~tNw0~{XE=U*$1M4c24lGjC;V9Cn!5QjQo)~q0}yImlJKUz)8*}e;( zSIu{T{=leAZ5~{|;897be$kL_WFe-J0^2ISk)fkR-8Z+!j5ZZuV%LO@xy!}&rzXpN z>cGaJ3z_WGMD_DGE&Ak<*4E;v$kXS>AA^ejF6!f!Cb}d}<+aYORp|75PadMdck5V2 zWQ)6-3ME#wjDyZ+??u@LK?kY$0W|FWb3G3?Jgc8|F(=^>Kf~&TqTLFIU^bkqEbcRn^SGn{*jqDG_a!rJ8 zltO78s0&Y5O8K=fUs7ASJOeIDZm&@e0r_mZ#xQEf;JY$gB9`{Yhn9aw%teRo@KL(L zEiJQUL^N6R)QoB!v$R1kTh`&N6b95tYMvCbU**#Q2`sBPxqJN=q@to<9B`g2JxMR{ zVw3`k*3fY*sYQ;|Ze^rOl%VE(Xhaw8e2LsKSNU)xrP26H7YRjnwSBMv-*0O)8rH1J z!PR+>et$&2qIzJy{oI=XZmZN`4#C14XdK;GJL)Bic^~7fvQVx)o+1SAttl3l&c?0c zpTLSR+uhs6bZI|Fl{UZzg^j`oCim9i=BZ`x!ZAj(I!d6;(CNw*Szyo;)dvSzjqEa# zQBr(WTiMz9pL+o+L&}*%|dQsX~_E# z6qW)LUTJ!W(d>zDrIbJBbGS|uXi;;ERn?HtAK*C(Bq69~A*hTzSq!ofK(fuK(0_~n zgb$~7?cS1b4i5)a2%`bhFr;aFXr>0N{@BVOr;0#qGwM@k34#kvL}GYt#8<^2qhK9S z;R(>{CuCblQC{KUjYdm80}|6+Qw`a;bp|0KQ!`R0cHNa^4@;sQ?m}syB zMfcuyaE!PbZk+IIu&E3~X|9bB`%eN-GMz+Cv_Bk^saO=vvoh9VP>${`H{0L*Rq-J`}-%PjkZNk-C=3P4kEkTG-9~593 zy!lUFce^BqK5_Yv_O3K+7wx37(+ww@FtpRAz@_l4N5tEqGENwRyo&ii^)>(5&+WU$ zQ0w%@gH_zE8s>}T&97A|rq}0aPM6S!$v_G}6QU~DpAbJc11BIPv}oGoK>?;EfP}_y zwFDQLUVjgZr7p11`fx!;je_zo_7j=DC*DPVBI3GGr@l_TgqUc5e}abLc2!rdCJZpi zu2Zbh*X#2 z&qTN`$xt`L+mT`@LPcWL^Z(+$JnNtBLJ)n`aV06;l6)~diXf2(VH==2I%^6wRzqUu zKgQ4`v(mu2C~H=F+V}qW$(jeLUIMgWal~fz?;@vjMcGYFUw%x~;B6YmC+1jjWj58G zy^9{wsy_>=U#YyCAR-1@a#q@?3QmzT4Hg%mTBHUB##I;dbdNWzoV-L8o&6}wQ#OkEt~ zhSPHlGBong0@(QE5Cy6~Pf8ta?HWRy_&nA=I$W1Nd`*1&hltwi+jHkOWL_4w7_k`J zBJC9Hx|OohlY%Y+GD(V8!> zqu&U5JiBGFHYGCQEX~Li#w*_+1bSUU?or;;Bx=?VCQMnh@uHccfUxNV@#)V9)-BwX zSkKyDlpn`~T72MR&0SockQ;eo7b|7eE}$k4B;n1iwN15?`M%QPQT;5afHr2KDX9*#WPBY$wL7iz!=3>xLzhvnuD|DM zs5jA^`=|2y(1SoT_jlu(Yhsb%*Ew02IE*vW`P{pz*J77gP)dP!(0+E<+kKLc&E{N7 zQC<+DRJ5GDZ6X7qggZYD+==ifraMZvmT6}o*~y?oK^Oo2rI2MthZ{{ z&9-#4SH6i%6hiSy;_I|DLra~dE4c6_pCb#0<_Z1z?&%+DtldsUmf!fYCmrHUT_!j@ zZo;aVN&ZX|`a$8We>n(YOg>pw;H~-rE`mpPIP1)t?S2Hg>kjp9hnQT!QV%epiqK#Q zmkKLEszL-AQeCyWE9v*_TPd2-`@vqlW{mUKwYl4b`Q`5&1Xp&p{p%StL7{VxR2op$ z(_5VMgTD?TQuIfHyY8#EfVe`XR#6H3giEnQBFIuk8^1~KEJNBQj;rK6+g6)6WY$i( zgVL3HJ?0QbgQw^=c8muI_J|s4{*-7ISek|NxqSsPLGT%220q?eXtyI}XuQ^Lw!ODm z-{`hwx6_a&P3+I5K#=6@@28S!mR&pCP4))fuUP+3tk3~wE8hYv&!CqJ2R$4Tph+() zft3U(%R$9OW#wm(qr2Y?D0WS-y{GH*xfD(DXLw9d{T~_R4$XdO{&iY<=N~9P9%kg4 z;vK?QNIrr+r54l6+TNtOZ6!MQ`vdbv61JyeCnxLv-7PUEAXDXnO}O6iF5@xJ}&A?F6*V4H5VLe7WO3^U5D1uy~U_gmCS36c?l8A(RI)q zjHx^Q?@A?KwQXkRr+yy%?lIJ+JWxkD&%CoY9u7>_o4StP2htclJc8ql zEv;7$f~Isx4fjW+|LWjzvcbgd0UhegEj*sx_IH_}Zt-ZV&%B%8G|ejf-Q;KY`7HCY z$;IhZ?s_8&wPVgyix=u+w7k;#KT>%4bZH`@U5BNxgHP|RKRl)lb#b4C->3$j;6~V1 z!d0aUaRD4Y6FltV#?I}6S9W}W&vjJeI?~oWbPXnI3OX?~0>Tw*0#Q`3-R4*t>cw6J znYZJyp6|)`crZ@8=ZWEoc-HyGuksn>R=AoyZ3@~VuJb$7Rfz=84KErk{gQ&`l?Nqo zUk{t8NPG#(c>M+bP$l9CI65T^f8!4O{|UqoiUH?a-=Ht9|4H8-r_W3BrC&9-YdcsO zC)?oK*^N0QV9k)qY`wMEstmX5Mp;k{CneP}uUM24i`1xO&OdP;FQ!_Rbj@)#`-xEINWg673f(tQ`G4?r%L3HX}2?c&zd z3rLbE)%56BSM9E&r4=q(T`6zFki-q*F`8b)jvE{`D=_&j2%fPnZi0VRXo0v&_$x}t z9JN6p2)i)3ynd}3>WK7D?}zs=4i);PTQXzzZRp6%w7_ml?D9AUQJWzQZ}=U@iwh#( zxtySUWO-5bl2n#bxVrAGAnPaTDMdo`3MPO*-1QE(@zLhal%J`fdbqVpGIqeI;s^>= zh2ckT_pxD=pW{(Tm#e%2*C*o43|>c8tSsr|>^XdZOqg_pCem>xSIYQ#Bo2naWPFL8 zMpm9NNd?aSjo-*gvb>JW;?q~gzgh{$vR4*G3-tn`%^_#^e{G}Jx|fZx2~}} z&!4to9qULsUXx1Akj#EhnZOJGA3NTgiea=6c;7n7aZ`WsQ>PFWS1LKIWo$;~Dq2}D z^t9*W`;SRjc+X?>GXK^gjFkw2`Wr!Z-P=j_7SWb})88>cQ2mlQ2D+dSaw3$zQ7o^# zPBYfKC>C=+H5QestOY+3iiE)^8|?$=n;h?9`h;ChbRKmSPSG(N1ay*Qv1EbY%U~MF zPK`N)yPZfNRmo}$q(~7+5z}=`=CQ`yC#Cx57uD_3&FY<#&SRI{v4Rc6i={Bq1JON% z@@-*8`-}jsj&&%XVwpysUTlnD(JJPGq@pZ)koWm$G}^mE+zVQDKQpf58$lqe{;{LW8cKO%$}eG)8+Xo(N- zRw{ifkEc+&29aa!^kU-mH*TdCwaUj-(5S*g^)`oppx6#n&y*c-a$88-hG5IVA~47+ zO8y*bA@fqp!l^EogV$)Ht&MN1wEyvJgm(%sa(9YrNmvofi~pMV<3LbwMd{*q#XcpB zL!M&nkzg}~Y9)q59ke?6Hl&0KBd8pJLs3}Of=Y)p}<6NMzTSZ$6wzUO2^eFP7RgJvKvW!VvM4Xzm znq+v#I&L|P^!(<9PbM;swc}W>`CdX$3x_SJo8#ch3X+4XSaLKy9E;>aI4uH3+sXHK zleD;yzIpLy!GqWnfM_Al8aUgxE>thVi1Q$Cz?~84UgQ~=!BZy{3~!YB56mv3%!uMDiYjHZZNajGV3!j2;}Ue zg7isgYJG#R4f((e@pa>!!!X<7Wqx0TqK(d_5YT*}FvlA#dlLlkeQ-?k2u?skkFAXKLXjl`7Kz?RO^rj7X0C zA|=>sj6W&4*f3N<<2XHGjQ+$biN3`Ger#_lMtXvGRNHt(M5?rU0AGzROel2Ju$+UMhsenm@;LRjJ&pz&!U~(<0amJ< zgM=XaPxYk9-e77V$O^i%dkT-6D`K4;q}D;g1S=Q>CjK*lIO@SB7h`jM1a zDsmwWm>0k6Un7}he>0c=A~hefR(42F&NPs?W*9jePvuVr<%y<9x#V+KCu`SBZASUL z?UdCO*0Mu2dimF2z%ggrRQz#cIZD3mGt5 zBKFe8C@gHMs)Sc-?*@S!X$D@VHOw)9)v>J>14y{MSM&eTQ8UwAy11mGrfVcc`>5$j zEM~Fb?oMIG2BJ4Bl0x5=y2?+s13aFL_GEFOC+pP@R^%-f;;L`O;AR>)|GK%J2+)7< z{`PJx@gI{5TYvjgbW?oBcspVf>fMj1K4CH|rM8(=9RK7vRUrkda)4bf^3!zM=yCLr zA3hQ~YBK6&wg8^{H|vk+f0EU%|Ca^e^I*B?27Q|Vxk??A#QU_}n8g8EV)v6Po|p(( zk}!O2d#76{tm5uL0jOmX^2>aMUH;NL(qYfBXO@4C?5!KAcS!|wbMN?>n@iH=51^Jc zkD-F8eq$6^JM*)wXM!_2GS;);XaKn~2z|!qt}w341{4LXvQAAyRTg+PeG|?1WOpa& z{ob|zByeBr+$1v3*CswAA=vHr*8K9J@*OSsSCYtQhB_a{nXUe7vFLe^8Vb_M+xEyR z`Fq+HRE~JGk>?Mo8~{>+v&oZ$*vUQQK!$roZnjO!%z@`hT4T9S~%4|k$} z61rxC67*R~o{c$78dP18q*p_ekL8REu?tMz;t-zbuAgutCVA4l$U6%8Re%c>Hk1%a zJ5aKg2I~I7)X9(w7Owo~`8F%bXTWbZya=mugIavA>DV6u>0L1 z3V5a}96%_iuo(|w5DZ`rh`evEm2P2H^qlKnNG!>-DGfB6xZtlMn+Kp1sv|s-f+1r} zD6|5*8v7tZ#k==nd_VqCI9ptR5fmFXzbaT{w*j8eE@WZ8g7xRe+v!FAdAP3ssig`3 zIzS$QRLrO>o#5_yTWwQdvQMD-mA_Nr!I$(Y12rx{UjxuJ*u2|f4`NI3e!kvHz6zz! zucRNzdiLi5X_kp;gZwvYcCG>y#}rRD|VI5b-kyYm4rN%XWYd*(mvj_{z; z-p#Q?)qhH%1QfvoqSiVOR{}ABvUB|fiLi#!H}1Mz9-Ru)+A!~716ExkQFV7;0d+b- zy?4R)2&R3P1khU>5cSh*a(0u{47gTk%t}3TJ-qs+p2vh@J24h$(TxPBT9`bThJs%7 zO}^%QKelbr``Xi^e3_o z`EcxyhDMhj-lslMU6Js!TSoVrvcc|ZdABt;KQVYS^j+{|LWM(K&QShg{2Ny6_3egj zDSZu)BV2dBm+j7as;tV9Up{2tkP{#kJ9JuabH|@-_|KATndEd%%XKFP60LX$P~~#j z%LrC)f<_>m;muWo>eY&_;)^)(@D2X)Tmo_skreOwX6KTmKPbuTuPHYc(^F2|Nf>@n zFlS$I_e17?lC-S}*D4rd+~iUa{0B^Z_zr%~Vn#(9o<{!tPr@CU0FQSlIs|7rj;!1o z&!_)K@R>Zc!zSyTT>k!-vkJr0OkLuw^>5Rgf^dpC<>YtI@3Ckxl-jpTsq`H zZDEPn6{wX-;$7cKMFUR^yDb0Xn>(Ba>~~0(BW8yqKCr-V^1=K+8T|4efBYYF?0Nww zZU5ZlnDrE+avxc1*?or7+O731TcE7-t|pZ}*1O$oTb+Om%TfeX6g#WNN zgKN4bS^0h+)(!*INA@z){|B&c?mx%SwOWtA8>(|!@#i2<;<5K#ZB#lm%Irg1LMn<+ zz1?sx|5F4Z# z{e7gn-kAP>K`XOvWz@DxIH92HXK)gLiT|ooi;(@FHvAiBVQpg60`()w3r-Ow1*z|s z%lSYUoLBu0IieDj6ND2}qH6BBar-Ow{JZ|DT;Cgz(0}*RqW_x^B^VCJc#H(gh9hS+ z^&P&)1Cb`avHdy~s1wj#w4_|jB5gH!l+yGrwZhz6-X7;?gngoAIiLZFM`X+z6b7az zooJ~pljw)pV0=@6p1b94y+9~G11@EIb8buy~; zGtZ(qa*2zrlUCbR8d5J&VN&0)+yZOJo#8US>-)^`KkgIfYdAP$y#!yVXqjFaEc}_I zuC;}ydf~u?uy*?gs2hSD>x)Rn-PqrTHYSdeqC}A(nYu&(OXizocv`1bE=O`!G_{}~OnM{SKj#YM2beVBRK3~Ng5Ef_Z&#%@-@hN}=jRJs5v7T^$fRhTe z`bhbSjZP6W*7*je@I!gz#-1xSSbsKra)5|_ZmU7P`hsfK1#x^L`8fcEgD7VHJVw^t zUOMc>@j&4oF1ZDHUH9!D|4rqQ(uT$%ODaw&b8xYKHAieT8;k zx+es|E8B+F>W>{_fESZqS(;4F{cZSn zf}|sMR8ymGr?~xmy!V_dcdIIk2(7;ts}h3*K4WaMq2~<-F*I>tz5Bb;=53XThJYQb zZ|4pJ-f7c+Wsn)l&@+ za8$yW)k2cr%L^)^FtI9PK-dMW!z~nm-;u7&*%c!IYHvhN`ASjyS|dH1OR>U>-wB4N zIVi8#qf+o$Nn1+eaS9++elAHq9dh1EjJe*56DpGbB?YX-6oPbw>!05{RLdKyRmppV{k@dHM>w#!Y>+72ga; zjF!9>dFxPY+pK|@g@cy{lEd3Im5mU!=c2e*%|?*PU$_7=OMB+#NqT~CLMuPDJqVi; znmY((<;;fLXW0Wwae>258MDr*XxAQgsq$}7l=;(G#%dOW3%UiE7hnAra4c7SD=&#u z(g9ze?^BgA<^R1l-yUrHnC^Gno*SHR8kKU3d7zB~ssM&N0zw&LHtg@Y*vfu}2y?q^ zV`rr!ReD!Q{8=pImFSrkE1wrbHMDP3#Vbf}6=ELtosDY z{}9Im;d~peO+Rq8BuQsW|PFpTcA#94#SAHy?TxZJ`>4qG>tPNtrE4# z@?gPc$oAySy%`?v%3Az#>*-HiLP`77<5o|KApHv~aQA^NTFU5^=TZ#PWpny) zffjfqZ{u*HFHCOn$jCUQ5+5rC;;O${sq+S zpdlp-;ZQ9^(c4_ucSNFRIZ7N>7-<{K&ipQsGH+CLA8Yx-B#`|0kd9w}CFOlx4zjg$vamtI9J~ zuEb4`7+oEeC-Dm>2T7}dz>k7=hKt}omgm(|Lk~kJzWJ*};68hF*Xg^VgM+H68L)Fz zY|C_6^uUE>#!iy(dYLcu58yOCS?eVcr}KCwM5?h*spM~PDyPlCU&ATl@fVQuy zz)QH3sP}H=SVh<-1zKWk-S;AOjd+si8Q&m!lRlEZ^V~lk9>5mZL1)5u{K1JRMVxg9 z^VkJ>;+c*GUR>Va(?8~lKwHHJZ29QeRh4a5TZhFA%oT19n?_-$=Eej}hr~qILUWO` z@B?`;OUnvc-mlw#Wfmc4BxY}|cRc3uF~Yya(GJ8T^jzKL;v|iIsZ-MGc3lVAwtOgI zyp$H0`(qt|GkF+f_~IS8zMHkI=5+84@A$X`<64l&Uc>9fU-HVgWJo@y7#Y~f4zFA( zbNrY|C8QcKo_y zQdbgd+)xFC;e|BKtFPg^r=Y8rye8)3d74QcemtZC!7bG zjf^~clLl(S6}R_fMSYyAF<4qi<6kyM>^NhwdhsfJrui%G$KFG7TM`jHWqo5XYXH^PKX z6hT$~QYj&1qbOc9MMBHpRDWH*Pl)BUHhL+r9a|lJ&jwUH_n>(%A4z#Y|E~%fY_#XC z&QT}D6wqZ&+dz$)l57%xu8J@`re8x`ZrfwTxr*b()ON}KdnC8bSQUlRX+J62-T4`S z%c-Ed*KymDF`NDnZbD=-pwBQ{utao|o%h9i|0hi`ekt%_JrJLE_t+}yahP7QVH95< z@n?(%L~iWl4yHK86fwkr_>V=A+r296RPO{r%WH?#U9`10a&PbnThOC-{m38JRlX(5 z*4R;DVwv?4KCsVgs9&iBJVq_v3mn`mRRZrV0e_{n&PNUfkTs&V(;f}n!JD{nOl6{xgaWUf-*ILEIWCGvUbwWGA)SRDG)9dx0gaX<)rH-knQ(5VaR=-@PNPl*UVt#Y_Fz$rKpboz^lL$&cQ(uRT(I zYV^YU+N3k=D4M=M;evYmZ}pSUaHPPQ;0kv;Z)6~T;>Ef8p>gxB!}W(cY%x8IdTHnW z<+XFdQ=yrTm%X21H2S|iBeo`51Wroy-I%p7L!df%%ji<#zs+(U z6{Gqocn#%15xz@t*VLjBEhY6555x`ErLm3I$6(d4dsUHm!q}xWt~D!>nQDEYYGB5N zrV*dl$Ahetd+o33fQ=m0pR51wxW?0!3-qJH4J70|VmH332~4rWEYA}g6% z`#WL#h%iaFA@Gsqw zQlT{wQfrQm?lJWW-E?L+cW=ozh8_#ghFc?xlSWOw7>FCPR5MFhe78rn{l z_rF+f8%1%db<-ZHV)hRqMvr$~A9tJIsxGaaEr<<(aiJ{~%Zv|%8c-V6mv5!%e z|5O({xEFrCV6IU|Xv-3CeXBwA0Bf91^GJ^KfCUUFtJspv>bo>jisHva*1FyUgX^t| z%!^pOu;SRbE>J9s;-2{%w}wLm3#n&*g_c<7RCd;{l}~@%S3~PVt5sT8gGtEgd5qq~ zZBV)D`Pq7Fzcna-FWwB{Ddv@pQ3#kiO2j++7X@#vA?U_K+92YLl%oYTEvBS7XI>feA}9Owj%bnwj=n!#np!}q!moH?DwhN81$u_Ww+(F!A_1L>fA*|czX^(4VdqbWsm*x zG(&Hj@BX6KeT=WZpv`t1lfL#Fj>-s8moD;#XcbE$psrNjIqwE?Ln&BUuQUTB1T<;{ z40x|WURrf@sD;R&xXW>ZU#Uan>{{3*k?-0Tgz7OA`xq77Bh#S5?ic=Mt7d*tc-P;r zUUu?<(|tp;6-AFa2wC-uNHcyPh&#^|nML+nN)N`%Q&Xe~6sV{Olv!C05LoQ_c~X%- z&pqPGB@$31Lk)>%H1-t6Z+;^YTTv8|pJudodE=RZHrGc~XNE|?buH^Nsna`R*~b9( zv)7$X^a#eD<0n6*(ut?rX_PldDRO!Nw#e}X(mvFhhM(Dl#7YJcrT&_0sq*)4lce1m zcvAnHLy@}U7u(zTvPvVg{cM6+)~;QH{TufpK&vIIZ;DzbLxrRQq0SsP#zz#*(t{NT z6OKKHu}-31qDzI( z*j^b%)I>G+V2+jZ{AdE#Jw!IdCd$$z2u_3ISU&^B?$ps!?w*ejz)a0Ik4W{#+KBI5 zjmObGmN8sY$ZX6tFSPSO%Z8&+e~*`qxEBY@bAKe=QpYL0Nv0kXz*gDBD`bwlo#w%tr8HZya%iQvE3=RycZ@Qb`kYmt^JF^2kIc~kNKz~W zN|e5br^)@$AgbR&>}L0)I&_^ok5HG`10iw9fiY%^fwwe5gSeCk?lrTpQm9%4Er_?~ z2GlD$uQqYA)d(Ql^9aoH`=5$TpKOmAhY=~P6BUykw-J$#LhOF%=k4dyC0?^kkLc6D zxCVZyqJo#gnOLFLkRPLEI@k*Y9T^Y5l~W9*VhWT!)ULfu#9FOKb&_uRNi$%^xF9{p zPib$aN*)HZSh}~;(V3Kvd%fEG%0;Hr;y&=9Q*(p21msbg(OOT3*RDcVm^TlTgdVpx zag>n4?Oj*0EUZ26EN?**hNCh;2I3RM{o&R`xs`|ABsfIYjn0j-l5B{0CliMP2g-ln z`F{vTq@zQ(P5!Ln&YV-FAU5XoyMvSf+y<{fgJg&PYaHGN*$MG_l%2(7Oqgxk>BO_0|EA$?sil8`WN1jj0Y5#{=yWGxtX^4Xtc;oWBnW z43!EdJOmRaJU*(?+;u{_xUV_{G3&pr`#d);sW=mLqsFvv*zM?gx>n*SqhZVQ#5SVs zA`v^;)Cw0#Ij<{u?(S$nK#Azh+IkK7Urb%H1uQP&*?*Iafz`E%@1b5H#;-eE8~XO-r~4S3zkb-@SOssBC|=G zN`XP90vrNI+CWRDWQ`JhHL0dFC(&<6$l3H3!=ZLfn7`9?Xl`rgsg<&+?;=i9dd`#WQr)l zi}y7{@+iG&i<-pr3uZRRluqkPwAWBFkBS-sAI;cH zv(3P0^~N_;D2Fx4oO*!z8>J`Sq6%bGpy`BtaVb0SY{vS~x#{1pol}RzezDjPq@LJ9 zZRmZ0l0E9FZn)gt)2jA-%pk(9{%%ZUT?Kw(lS*!b{Umz%<(Tm(-6yQ799scoq7yzI zTSp0Bf)%+0!jDLH63RJBJTKH+5;{(5ZtLZ9yGnToE5_D;>&eDK6Tbm~7PY(sq2n}9 zzoKkpldJj7J_X^<*z`B!^eUCi!%~KaD3UR0`KwsN9LQbIbn+8Ypqj_L$=rfH_@^4D zAMS4{y|CsMW^$;$tJ3YF<<2CxJmsIa|GB9V#xi}Xfp(|P1uorvz3%|5iQZFBeiMFj zal+g?X-pDG_y7B(GpdG8rd5bE7szNrk6wBtn=5PT&(%<~XwG_>@=GSuZSM4<()#H^4fj@BZSk*_(_m+EKC<*#{N@Eg0j z2l7dh+lffI2@6!~7e`gWV1GQlz0TibYmZfrRiOaM>-67kC203=$z@E9`Y9M!Sh}w6 zHmC)vzl5;07K=9#GJOc{dLPu=#rK+vf)#n02|leNM;|!P1QUoly9Ssv_gj;+ME_EP zmRWikc{0@@1xPuhj#H$Go$UCK?R22@l3yAF$SXtcc4Hq2@d@tg0r>2mKV?4#m&885UjD3%`Z|h@qj7Pa%dHdIc9pwpW z2eo+>hfDg&{Fn;ocM};WckNvISMU#6V#s@!CzCcGW`iP< zvw~9lg%1$B-suw7rH-27e(hpNDDMA($lhTr#`}vZT5>^ zA29sYW6?}v5B#zz2^8azL}rS46+a0AOwcIh;|%)a<-^&2XnW280lYk<;( zCGaa)hxTaF<}OxzSwX{cx_!kgZlg=1uMOAg1>A_l3Uo?Z?YrgpKP*76$Ajn~2gXYf zcA@K%j+Wa-wVyG<0X70jLh1^}yc)?bQ>%XY)F}_> zTX8CsHo7y5YuGGaQaNi@&u@`C4bGKx@6!~KsI!c^LkgbVa=r=M)}WsLC2%;lm6Qn3 z+U(#@>o4^~>hJ(3$h6hLm)3>(U7K~cQ+@^X%R~*!jCKoi|Gii?+3W?0O8O_Wf1)iK zau^4yG>b}w;zfM`G3eedH61R$;jce8oheKAJzDF)k*H1P{+G&zjc2Z7UAD27G4#Y z?15^h1z)2jd182$~My;j~ zT&52`Hk)nJks)mA+y$#7GOKsV=g3A~CBQ(rrcLkz=^fi8Cdiunj<<;sF3*0sw;t&dERB^?|AY1q|>Ff%kSjsE78soz`=OTs#F+ivPrL}VY*isb7k0jQj zWo9~j{d?)Rgq<=`RpZ4WMjX`j^9`VbJL&2F*V)Ptkl#A$W^0|I+MXwYBs=-4GdS> z#+M6*vuhiNDx7UQIZIp$`gGQ-=okbZKeLiT>Ml67fXK8Z9>AsDM>gfWFUv=UV=k3? z<^*^880^3zoWDf*{TRDp>-*b>AKL|m`(bhgHxp;mS9#MH^LO1T)$#Q{X;~s4h0s#H z(R*Qj`WfHKD2w(mwu|U=|5U|u2(o)ZlyI3S1qeX;$~gUu*pNWdwvs9gJr>`l087wUwNqCPv5)Mm_%XI8ol@4!zoet`Wo`w z&O!cdmNk&Dnc(_Ri`X;L$83kI&X%kM74Ak{c3@qLlOh`HpYdJ3 zO%g6pF5W+aPczYI9(+G4_?WriWet8W3-VCjPQN=GM!XREoa$q7?JyxD!!pK)`dc&k z{)LNvx%jHl`o6wvkLbFI3htQ5UBK#+v*e35>(PFET&`bJ$y)DPej4Wm{Runt6?pFy zwP9vWSBa?#pu2uY4xzI(P7tt(Ovd0o7Dz>1XYU4i4s~UO>ST@H5K@B`y@t_P;y9+3 zQ@qB8NfzSMtJDlxxia+h^VKl927kD2h;u6KsWyH#JJ``y;u^&9R!E$N0c(>*`1UGB zRELW+@Psd1WWp2sH-ySm@gr3g7e#(>uLL|3_%XiB=))c0{y{JAD*6vb0XHqK+2JLH zr0gXMJZ>24dIr|WwN59}T5hnJ z6LOv)v6s|ixbkw)V+0be5fiEuF5>d((Khsr8RHGsFgy4S3Op(t%f0-YilaGpdr;-# zhdgdpK5VNb^b#ns^~g0Hbe&AH(5j)iM_4P@UGGf*BR^k!2g(wRxRC{r!kqlv*t_o4 z*OFrYe~ab;8y_b=5h-z~(aIC1)Z!^{3O_e{;V1%TpWQe+SiR`Wbc>JD<|yPx=tkO@ zcE5Hj85Rdo^#p{8(xg%U%~y*dNu1q1rV)WhXP@;-HcEbc>xmuy4Bz(t`a4$7gW+cn zW-d+H3R-Lw$8m`P*4xsV@&fca!y@cGaW(}Uukk48(#E%)DCy2FBV=x@5oW0a7!^)h z+Nrju7cCf1g~IRlQ=1RY?Qqnps&?ui%;z+W0p_20wMZY=pV7Hrlbx`@-+TX)47*ZYcdWs~_q^^O-IS)|FAi|T8 zF8nBbTA`3p)_(g_V8rOTynThlxtHzad896-*X?t6>olUjeJO{~0Pe*8YPzZ$Rw$g5 z2!#lf<_z30roL%tyZe;fjl#YUHn!kS0b?x=(jvCE%K#rouFTHu#mfp*n zAwMxE(KQ4Gu8~G~jLKy69Q^5a*-$^bYyJ=-zFw-51aGCV!nTe;HoEM}j2F)d%Mq!c z%#@I))sybA{qTUQzY4F(oEQ%|7T8AdB!))}zEUJ$8RMiL6*TmWzA)8d+&NFa$QXE6 znTIRrY~!yR#!%g!Q;S_nrxtVY_(0uQI~Y7j5!WNoFLgXck${(y$tv)WKoI3V3ZyT46`L$bEVEW;@J42~yGN-Zv^4x~#F zy#nS{jU?E0Xli-4EP3DNt zSTZeHuj@og9h)nN9l+bJ5h@=BIG&ESh#&e)99jvH=*H|%rjiy&ehMH&uW1gPkKE7n z;YoVn#XT8DqPGr*o59_wrE}f{dCCU0<$BB|B!l(qH3t+Olo=&|0rsYT1arO8!7;Qg zZTYgN-AH^;6R$0*>x2F2)OSny z2U$4M+zA?9=(iV;atDi*A0DoKm+u6A8$f@%HNqdu3j$mZuY)HDFVaUQ%zyVxOy=AS zI2^47Q&>A&kG5x&{xjCKGP*3b7a+CxVJM6(A$Zqdpkp;ut|M|{^dN@6Htz(U4|ziA z2W|73i?4`lkMwW!D@PzkQ?f$4e>2j8hH_-h2$EyEc2}%c3KjSr7$g5Eb&7O^@d==&E zNpErScU;c@r~uz!0)AA#tRXcxQ6WuZK|DR1~`f?7Sv$gi*Hn& zUK9NgC*d^xKvABj{h!(UHNL*o1J$QV}3+_O|G(H)&PmbMK9f#rqVd4M}q+IL)RZsYQ zNvHhu6gAig8$S-0X1GbK{0car4{$PSn_Sq1lA;H`-hPAcuCV5Rjq}uH%hveTQZa=C zFN_3!dHMX-pfq5u*a)R-?7*@>!n76B6HKklFG$S}2z9`a1om5}GT>R{pimxqR(*d3 zB!a@p{Tet1rA*ZRzWf>!v8S=>#yVg&_Z}#iQ-(`J?GYgk)+4oBm|Tr9tni8ohuXH( z3$S3D6%Hx?=!SWs-f^yE|IKf}nL*(YHNvGOxe%dJX_<1Zq!;>k250i^oh`|8u zP~<$(XunOHdpf=_0B={Bx?132*E4catV1A&YXy|WDB#)+JsmdN`mWW4F^|TRpKE-M zH{#oGHpLHCASE@776ppNQpDFE`?3>q6Ce7qE5r^^)`I=UQJHUUz}nV(vMO_l3#2n* z&B-vi&$r#Uy#{!=`m}44aJ}c)q#4c>B}4n{Z)(Dm?;=@eUR>Z9p$op)cO3`@$P;AfzpeC-M{&vv!49AY#|3CZ2wnF*|;{5 z!KF@M*5`|I(F+1F&&k&pXw(w-ym0`{jYV{b#Y%R<+ z9l2-X;7GN2wHB;NIjVh=dtuS%erTda>?e%7aT@{#jFYJT#S#v6xY4OY;wf%jU_!cX zE0iDV8Tj6lNo5mr$qKAZ6y9^>K|Jpb2WEarwJ$7YbElG3nUXDvx$k~&pC7GxVaxnc zLz7s5jQKS|qhs)C^J^PeBIyoQV+;G~Z5e41`L7u|>& z`XF~Tt3u`TM@^fLJ6_}(SenYJF;_iwjP!+s4vnk)$4yp_4DqTM^FIGtDEOIU! z#e&pB^>Tgajdb9fFMzC)#7Vw7>Cp;oEzpZ-K1x~Tf(Du}?G`wlmD0MuPji=WIEB03mjTT#91?(q(%4OTC{k#K#E|=H0NVG5*Ae7Pc~+;8Q9#~h~I07qT3>OP_di@-sU!evL-G!3V1E|CtP2va0Ht2`!p`7ZHXXc2GGILy88ATGM8VqTv3ZI9`%YE37p5;BGgT3ZS zB7T_oniPZp!H&+y>IIFwJk@#pa@2e@@cmrweRBkTYG3%URq7Mv@t&arkW|4*S~G(Q z0TVzl@H?zWh@pK96a=+;o@GLD&rm<6rF}P<6g9zaJf=kjn(bxu#-)rB_CH_?}M1WgA>cbyt*qB1M7d}D)qLcZ&zS@Mz|A> zt+kd-6d6o80w<*%{7nR2&ndE0#w{ovi~!1+88aE7u=i~&7J!xdX9lZ1rfkqhiDyk;={b9ADkkH zdCEGeb&N$*XbZ_EKQ{kmW#FaNU^v!w1u(!}n%KqHG~OD+3VqEMs+)&(hlS%w0`<_y z!@Ey~wIp&O(8%!(EKV)Rgl>m=RX*?cGk265nIj$j2Zqd`LoRNYr6!Nyd(*Y@2+85?|$T4j3P8@ z1AAoM8Q$@}%8~nfNa+ks>dAgN+1+-uKu%Rt5o$}=Cadn#KpE`_2X&7U7aGB4$)@LG zGJ@8rZ)xb$9yhA38r$uAHZ*{EwnK}k=AQJKur3eLWgZDUI9}B1K6Yjg)q20~Nq3g0e$Kb*sG|=mf4k;G_l63)Am8|!# znabK5vz{g=PgY6Y8458O8PiKRb4PI}K7w6(iTVL7YjfO;SMvny3wd`{+YY{^aeC21 z?1buIu2V&UOC`AAf@GdOI3`a41DdRyJna~|nk3F8eXVcx3P`riF|{>*g%+NQxL==I zS_V}fb?T(<3Rj5EQp_EWhjz+p6!H=AfUPf3LD?Vr{aA_J_p~ot?61 zLe5QhyL6im3FyaK=NGFwUsfco(?p2-0o#a&Wn5V-KB&W z?AL;Vs6@QXBbEqf2kaE6{;P`^bqdUwxTYrJT4dpy@rhYy>H}0;8ScW?aJIMp;vaoJ zlSu7@fSw)E%S^)SZ*0UvOp)=^2o9Em{R&bf#itfCACw<%n(TL3y+|-*MwaBtwt;gm zuz`Jx9~n-1Kljg%NksOU8!gHfqzxrbCYdbd(k>OG$^NN=Sw*i$-3fID9LwCV?qlsS z>ImnQkk5QE8Aa37+qL}~%JqLaTGx88=YwQeF9qE53udn70$l9hKwC<4du}gWbMPZ( zjzh6Ki8|jjy-dGe`ialAl4Hv2Q}hO4!5k>Mp>oajLPgB~v}>-dzivTQvEQMq^Y;wo z&;5EhQ++F*^RTNm$ck3T$K*>*(`;ETnO} z{kVA7-5%oxBpLG+@P5o*;mzus%x>xb*FZwT9Abk=Z>bJ3TqxTjDp7|mxbf}_>V;d| z!s7m12K@?`*Uxc(2KxI>K4uWnDGO3fo~3mi&($McBBNms86`~u*~I0St+N}w^Y*6T zPb`0|hRtKeRyO(m`9o8yqE65|Za=GxxyjbDy`4yj%+|Vym z%lVAW@#fCJ9Qyj}J_KUGwS>TTtHmKVdq{{4?gTx_y$*`cO{UwjbiA6iPVAL>H7y2< z*Ha3WRbaXQ`vu(e>-Ix@d}4N@Rk_-qIqSB4!~Z zE>F&sohUa0(rE5{=spfs#<~9#|BCLdpHJwg&8M-p%hT$$lYjUj^XbRo)eg7TT%BM2 zlqG{U`Iu|C7S91lAkw;U;ws^NcWFt_ypl@QtVWThozma3@3LfrucKTN!$SBPQTpuF ziQRpGua(j4&^Xx^af3At%}BLSZ%tH5y~woD{tUa~(S4@NaFFOU@{|~4W@m*)lNiaH zj&LdyxJKEQO4t>YNfo^Fe#emTp1V_h8`?Wr{)=nD`|rslX6LQp8?(K@TJXPnZlh!V zmn5}%Jbo^l`|!zX5|jCTr0pIa=SP+)1iI7*{BfA}|8``Y#L*{AYc8NyXXTFggc$lgaz;gYk;Ua#iw~5L^O&%@Wtbry`pD26= zsMYWO5Rl`pqlSm+P+F{`A{t`UV%|RUlrc4;6tAWp zq5}?TjK2W5dUhUk;DivIT>x&pPj?>b44)_Jrl<=fQ3^+toRAd{NpJN8HMU=dzZPa* zpWnM`-6-WIC9V~C`r{*`0@%>}6#d&Z5be$>xSngEQOM`I>iK*$En9j7Zu}bEhM>E0 z?0rEk>Tq5SHT^hw-7~_;(G$E>m?)MXX7J7~!#dW3&}~#R*I+Ww;JLCvxa$uzcD+}B zVY+`KMjN2NR;Q*W0Fy!eG0{;I+KqCld&w{9cdBiRd}%g5ZRidV*(h*G=9 zF0?(XPr2{ND;PewKum;=B%=hmyc7xNf5uAK4IXmG=b+t1$EjBkpac=3LV1YEtI~^D zD(=i@X9k3%cqbp4`+%yC z@cL#k5{Yt`g8DE?O67`qPbWDH_tC<-TcAIXWD0v0m^Mf>UX>;B>DC%kbC+pbHYf@? zUvZrRPCG~7HCWj4mayr{Ec-D~x>rg*$s0#YA?YV;<7f(Ae>Pd5pa{WR_cSMg5k-;Dnp#hJoM`Mb-qM zD7y;%5Zhoj$MX+y?S2lN1VC;0Mvjw_>-~T(Q}tw$+dad`7WB`wU-SA0ddu0&Bt^Qw zH-M4_R&Tr=tf2SjyxC`CsOsHfypAnQCl{C-3Q+1iyL4CoX<`KqieE zG7j_ciR_kHzes-BT4U^x?-X^kizD(5CssY*4H^UhvCGDurRa=gAq02Hd41vyz$dwg zqqoVJn^O{vIMUBSa)j_&?xH$vU1dv#SeHo~uBL?D{shU%>|1J(16}%$M_2?bBK{$e z@h$@MX&sENH*fE|{Xl|k6NJC7cs0ntcD>-+WZ4BR5Vmm#dd6 z&>Xj$Ydcu1z}G663~uoh1#Yvbu_AX*`Q9usUGpRAPsvnrb>$`*v?EIFJD|Va)MQ<> zliE31;D|0sQa#`D>sQn#Fa1$#?R>K-F>Vi z(w76r(<4G?WB018)7S=T@wa25iiCF3DMztOt?tRe#o1$~RlDs~o)Ah?OnfO*Hoh6W zWrTJRKaH_eP?V3oD^;EsU=&X>s3?%EEJ%qKi=i_AzEuY;ZLqM5L`j*)b<$bhPIC_B zSI)?H5k=+k3K~L1y-MG@AQvPXRu@!<0?x>`sPmfHrC)K{20=Vh&pYfaoIT57evqFI z(sU!1?7zPq9QE#-t#)KRymDdbF;$4yz~{r@`-n^r0YQHPYFTgbgT3H!>Ji?)s!vB9 zJ7=S0X+lsQp#(3KvodNTTWQX~@6S`HrKwqT>{2&_fiT-ctez)w#+5n!=+!oK z&?d6{{Wqk)d=mtqH=UalMbhc=YckL6+ z0?!1yr|y*Og}>NgSqtf@pC7TEi%F#AhLXpq*i$kl>eo!zk~B8SYlha8T$pq6+}YJe zc<3zII0)f?0Zqwfi6N{xr-m3>+|tmuQ-ap-qQ0n(BL|8jM?DF!m&_nCewZapkY9%l zI}$J$*jVBJaP%C zbP{#cSQRc+hN*(-UeSpJWn-Wh?f+K-9a6Z8($*l8%_m(Zu(6cu~A@#pa7 zNhf;36h`2Y=FEo;-^6a?x}DFwKAmzAOTVnq{TB~I+ACwv;Bs7X?r84hjuwTnZmX3*?CONS=yRrZ9kcWF{q_uU#hez`Qsi?u$lJu&CTSse%|(?6 z_ku=OdN=ZnkK+c}hap3mMh%SH&nHY%)^xuDWuWIy4G2FL5>SegbuAhAju6=e zHbGDP;JeUz_xo80!yhm34B#j)ZwFo}_0&|~uKnS^aH4Dy8%d;xTF5le(b#cmJWDu8 z$_d$A26;Y!-K*po`|ExU$<{%tH>jZXpK0XY)hsbtTzSdxPjnJ6C0Yc{EnMasbPbHS zARR#^XeE*gZ2V8NQ^)aljp$AlWcuatv(=XQU#4KJSU(Ey>-C!A2*0J^%_x6=xCZ8dA#&iT#&6+$^;v2eh^ut{&GINUio7AX5u<Vhx9RvLS8j9m{Sr707;W*JwwiJEx(uAWK;q@LT`H?sLks zu#b?#*oH4XncbQ`v;P}YF3o@cDSFrmV6~GDilWCVwI)fMrJ(aqtH!0Wj^wEHA4bE< zN12tt=u*%W>@vwFHOF(R7>t65)RXpq@6{F7`w94f^%2AqDL`TDCdQK797p1tPC+<8HL$vf7}WtGbM<+OT2+FM`@r7_T$>M_-#VJ;Z-rZFs5-36NN_(~{ zd9_I0sKb*Qu{H=T(2*HSqVNJ_R*>@Vx9>Y9Sr<5_d#Jzty58=id9-jxs{6V#PZr#= z2!3=sQM1nxZGwck{30|&BCT?&EL0V_F;{O&O$PzHgclDgw9@lLV&%$2Nm6Tn2WQ0Z zyJ+N(Xu*bg6XiLN;O@yKU_ zWsY3C!$7-dIC@Y5;D2J`&edCjkzc z&-$7Wm^^X%L4^Pz2T#qNe>@L>_fI!lORK!d*L#fiY!G2m9!IH6Bx}mm4L{|>-|f>8 z=KGsC=8?-NcW^HXktuovT9;k{_z|LtqGV%b81aaq@NLfnd{T+dC#Xl^Fy48#AR1U; z!w(H54FIeO8sL9g@>u-TJ52Fnx05h-;r9p}Hf0*$qk`D*=+rY{NNQ^yT#!-HIpsrbijEJ*!Nqbi`UJiW+UM*$Tzz;Qn<&5YvLZ% zar4XpZs~R+v>3Q}#K`)Dma|Y)=2B$PE0Pu@GcYP}BRhC+DXMCyAbweL9ZKqUTbGP| z??@0KCmJH9BqW~SP!1BWH1MURQ-8?Kx!EjLB*1>M;>7VTGSSOmmX>q4_L&E>|7^_T zx_N1U88ex5(>(=H4MjXU{bj}RY6KPrfdk`Ii6RGQV^pUou>RQpEl~eh2%p73RYeGV zNtP1&j_)muoWz4S<93N+O#pSXjP1NLOsdt%P|no@=JCPn@TYZmc)<2pcsr5|Cuve^ ztDH6Wom5P=s6@Nazlg~&0nlvQm50405f&ew;nxYu-AI3v9XH#c zz!00HTg&Qs(0Mg+IHexNvgmpGR&-$qQ$z?2AfiT?j%*y}%6$s=jVrC<{0>TW`NmI} zrDt%P8)=7eUS^5wVWS>*L+SJ>S~+*8YofG6vY=&Oqk=$`fEKvpt+4bJ!lynKg_tfu zJgtQ+jzxLp3_lNI^&Y#o%yP;VkLyr6H}L6sbK1*B_KX_woU%;Oet6lj$vTyW8Uy>f zAZZr59Gbob8;g5UxgRvJRZs8VH=>F!l%PVrp;O0lK2sn-*(^(o^A`!X zBA0_N-mTuP)x+a6K|qoVG5VkTtD-enn|aBS^pjA;vbi{rBAN{@Jv@*Wh=-h2_CyV9 z34#_>9WFAg4_4~bo05(e zdsVw;QaP!&VY9^^UDoN{n#~**k)ucjJ%`BN$b|L_H1lkKoRrAICT!q5U(<}JrR?5v z?~{;(!#;B8Aj^klUnYawjLE5O;}HbX;beR4qH3qpigXr06Jv!8)d{szZ(S#E#& zi(*EDunpEFO|o3j6}_}0eqnJ7Os93C%q)Ry3&EIJS1M;Ib|C|miS(m*TGme=zx^y2 znsU1v&eK2KsxSrp>SPrnh?YD22F|eP#R4V8v&A*qhESJ|&_GAYU*MYYfMkcR8rT9A ze{f|vh9wKdWT*Iiw*5AN<)jX;9?9|*#4e)yP%g$Qtd|^tsZMF2eFG>e&ER66n( zF_Kr<%(>>Ql|uKD{O1R528a6tL05_=>S@!f#3-4*xa>_$q&ZZAcOCfPwaE zcJzE|G{l_5huT>pQ`};e5S;ID^u}(0`pzbOYYd=l9Xp=fuO$}gmTZ)e=iyn7MjuB3 zaR+-aiRJ29Ymg(OLUtDvji&61zgnz892g>Z4Kv%5t~FaZg~aXB*><^p*ggi?2(8D= z#ti8ABpVyP(hdC_2y>3h@k94o z($9IQMQ~@D;WK`?g-iP4-x>yF=JaOb!l;E568@SAX(lVDl;=g?tgX5ntX{^6@T)oV zFbM1o9bmnCAouZ3JoDcSi}*TOY!l|@l+|HgtA{%!yJRf6kl`W}?^Jqw#$9(6$bTNw zbFt0yh0-Jz@xA{?r>xJqu_YzT;nX#+bojabprg3oaywiG@%~$zB`-5Vv*yL9RQ#Gr z>bogmfb6hA?uJb)HF-gTS!iy~E-!H0=H?arJ|^$H3xCwl2*`NK^8z6)CBEzv!I9$U zrU=TLYN{T#FYBk=#%9rEt9St|c)_(RO4g+fbqRT_nwcWb%{A{lG}+wWW}v9RnC+Zg zGuZ~Wj=M+G&n}y;Ri@!qG^P~N9p2@EOKA%c(5o)FKYtO8?L(7G+DgdH-$bPAWGCT_ zxnaaHgmNO#P&C8VA|aQhpFEIcqu)3pAEGTB#eRK3qOj30E7h$BUet|C| z)IZt{BE#`j^>56vnQqN#3Hc!<`*Q^Rsz2`dKHsl&FF%StJjezEKIrDjbH_Ybr2Vtgi5i z;jPMqFpr*HLgQ-|vT*z(!tGt1`Y-hy+ZG*f-|X){6K8qk2X;_Dt;T%zpNW@vQ@ZGX zKm#j`P^la4arl}u*6PsX28!(ibx#OUTMj54^F}rRdmjwAkCXTLX6#xWYTd=oGHGAF z9rw+&Hy$!ut!8AF?eO~iu<-ABgQ&S*U%XD?0~2qWX{B6k^+I?33fuJw?VFWN?Eq5; zKfChFU4AkDkE14WtpHQ@QVgq2&~^er?a>DE zW9uA5YvJj3t{s1brEzZOs-^$t^!P?oKYcVZm7Sxasym*ikNQzTc$oG3i>C4m)Xr6~ z+(y$6S;6&R+2Bvrg9D22UTP1QCZoc%PEUi_K8JtTR^P9sb$l%C3f*)!aelJzo)D(4 z@6qtcXkH(l5U=~9Qqd#b;?0I0b*NQ`YQ>BUiJl9Zc62Oe}57=ei3=PHaKg1&0oQOw8kq` zDjqGjV)o~V^Jnqg1P$aC$>=o&#BYZJi;RD{7WPdSWXEV+e^}5m_j4nELJLt)xWC;C zIF31Xc|r82mc;m*iM=Pu_t$UUTsQX!WFDI_tHsQxe8TT8nYAy`AhbCA zBA=<${W`v(pUbk8qhYgGX(}|*S{!L2rw%UJ-9JD-w+Gb>#E^@JvcxTgxO@(MSCb+~ z(H)eSbBA7tZ9E>hRPot=$u|?(W8Y`KAl9Lt_AQ+|o4=unh6*JBGte4ex)`IKphS&u z5_OE{8qHA&-&LSNV3&jVSyUHh?Jga;6mHG%bnvmbx(6j z3t2_B7&Ydc&8){RODzy5Z>~0UEj;r`b}zaRgS`$p+YKeX0%L|`FH{$AuGh?Ql?;Jh zN$3OnTF91pyhbYs86=FTv?w4h^n)hP#eAN!ZV1LV!V%ZIucPgE&BVm)zNF8Q#~wbA zB*c)U0L{vpsd6Vwh~Mr=XJhc^68TBEXhOHGvx zyf*euo4irYGWZ1=t*y}JQz1{&tYoID4umcuOaf?Lodo({II@(pYDw+BrsI>7-dD3@ zt5U+Sxha2{qs9=6`sivXDSysFp;UH{89(Pl#f~u)z}8}Fsza5B5#Qn8oCB+qv^_uR zM|`S419EX;a7BHDLG14>NU#YQL_mxs;$MqCNDcS*JM~9QqhtXLi*UWV2e)xF=4|I$ zCb!mJOM9HQ!m?3x%whX9z8_Qv=wLafWu!@6rbRSLocMz@#nP;B0pT2h6%2<|;fQho z-mg$Fet02Xp!N$HBYO!tRbf50IG`Q}ojNd;i&Zs3@}vB7(oZksec_9o-%N`#zym^E zxbH{4&VL=)WCvOaXeZic4{nps5o|TpKO=OQ^h8mFfV$%Qg(>J9en%8>5`SrWeCy(gfx zlWkR9F4YT#;KhSYOZ2Q76rcA3y`fgN5o17~5jj^3{;ye*lj2(^-vZR!0(Hc%rZ7A$ z)+5}m%{IU+pBaXi-$L67-kjw_16|gQ^EuA^W3)IfQ3Gt&HbUcgIq)O|%tk`hzJGA_ zLO(=}4kuf)N#%FzT=CBz{sWFUrDW#72f-9{(OHLuMckBt@W~R^uM%PjX*fO5&LU`AP=V_R@8C@%s+@>2&ma-*z*; zMq$ZqZoe5Sbgp#cI3_Ux!;f!4%X@*HnK!LkWSauZ1|G3}(KyYco?*IFhG&0l=76-6 zY6Y{`&~`XE3vA@w#=JpApoK;q4=!6&dpg29mv5(X(teHw7p-hR^!6&dz6kE&PStZD z`Tj}i8%a*f*gf6KBF#uDG&ZZBW@z0Mu#PKz%n8j+ThYW@RYA=!i%;Gg=~ z(EN7Q!MbKo&80;l+y;)I_C6U1ic9<+z2k|E8p6B6iHVxkDdUi;JJuz+LIwfWsh6wy z6156?_WEeB{`u%42xjSIlcRynOZ}?oxH*k}loL(>Is(sZY*MRn&~9X~(WLvRp}8&J^@n zS-?vYL1)j?s5Ff>jSJO}pA*R7`Z5o`5n6f6+P_IaO-i>w7TBt)f;vTGr09+*KTsts z{RzL*S=;&fuCowVHU4Y@`)~@?PDO*3RUciSl^`JDdoHj}R8j83RviiNbIEJ#&KL5U z2xqOE6r{IMiz^DoQ7n zt1^Q(0#ps^n-YcCWhtQ*@aLszz7E!Zf=o7Xnnlrin+OeX|1Ry}s&c;%E-5nvDiss! zeoKY!ZGtqF@q@l4X^C(MSE*J~$41E7|AomPHt+}ligWW6f`miG6i3ix>J|PPfeU_E zV2##fE+NUHmRAgJc5F&_-E&t&V|WxMX3j~Mlr8##d^1yOcj6}y!qlnOaTSJOZFjJJdHD6}obj|!{C zE3REXz5);m{wUuhJ@r9oHRjc%WZT}~#!qrFJ5wOwsb@Z~uv%p=(Flk)?kA7Htn|JbPp=~VwILCFU z)4WOMt<_!DLII_n#f0kHvGPjaFt~C@DB$_r_WMg1x+AbEtKyxUY^8+6Uq7CT?c+l< zLa_nMnwM6!i(6o5GVJNQ}NTG^kGzC zpk#(j2Er!etqo+$VBe1PiKp1KC__>gz!$Ccb4)0gPw)r7plEbco63R52d80*8Inrp z4%yv`l`G<%JFMD)>-2)AvA0#%mNTX5Z+CD4yMa5fFHB2CY;ZQX0vXJsZnj!3zX7iWcs>TzoQ{-i?K~9{Tn7BFiR3B$bUUgFruZuSn(nJYTokp>3et9+n2$g>@&?z1Uq#M{5LnQ*D4hl zE8f4}khWSHhB&fdkn;I=tGzBbz;luH=@`aMJTQ#H-l^@*iY(|D>`dq!s#g07!?NEf z5^Hnj7X{~yQxh$vTDpJ$F*&uTo2A=l&kUQ-wJmvT=6km=L`py5n5<5y_R4#V*x8Gx zyscU^PS;nBw~lADZvXefr`6o5Wy(7y;JI3-{tvFad`_%*dJ9N7JG@H7_+gZ^RBi3` zY~YjO91D3`r~6Rqj_dwnJv}}t8h<|q(YZA(`_;bqy~WUra_>Wy+m%Y)HLP!h61(DJ zG+qMqvlxAh)=qeO&<6)N!!D@lf1G&h+>%#(T?-ET;Jz&Rg zb6F=p|Izr(O(*Q77fbIOW2Fmlm7lpaA?kGY*S;<0Vr)mh8TdIZ?fyokz%!8U?^ccd z2kwPJIz~NJF5)r05WSEFNsG{j|L!6W``QxR#?U-zJGrovRag-yCIY3lKU^w8C1f|$ z{!76}Wh<+yNUI&^fav>Y^u}L7<0-vgEE7EF(%_N`Qhho1+5~DFIaPeJtUH$_{&Vk5 zga>W`({~pu3I}NrX*lOUeRz0UM3c=3Z&{BERKbcnTO4!>L7Qe2=&^nFM*t};pIN%7~ufh>r*q@NbzT{O|u zz%kMD)Uf)#b^2xu6^4o}-inG2f|^69-Se|1&}=Ak?#Ho-S${Tf3TPfbc^TWDM&<0+7elLD>v}+)$ISfY$9;|+w_yT+ zy57Db5F658XwR#EIO~v~k})w3pts;TJS-wJ8$&qzYDX*1iyEziYp#Z?`tHXkF#*T9 z)HQq$$8`&{SfR@|$7>sQfny@i$@pod7$J1$#nLef3M34Ih%?IK$54pdfHd4;e~1*t zM%Kf@oI|7#nzmEs2g80-Tua9H(Ke}AhiGeD#94g;4A(xb@^hfM#Bwj2x+&jDM;JK-SNa_3}l0NJu~SX&Obv{A*?&iuJL>Sh8k?#a)$KMo+ebryY%EvVmvPgxnyQZ0G;+$Ra zLmCSS5e|wGI1)A5wMn!u`HRSv3;C|P5m3nnlum?EAV5Z2B-RlgRB?|;EMg7y5CkP; zF5=90Zx)b9tpSDN6a)>O?K<-(Zb_XTv#E!EijpT$O~4V7XFCfD7xA#tAX1AN=EOi2 zk*s}$utFKSW|9=H6m~psh*2sK)hInp#b_Vm)4_md!=r1beB?MFb(cjHh$aAF0SYx` zKz<8n)_TDKQgh%^-xH$>Yb0hGntH!y!%{phMjjSs44xS|E zN+p65uOqM%s}EL@5w+x2VbzX!OxE=KAQ^^TrD1(I+dW}j_wC$OV+TS9*`Oa~IR<^v zox^;vO$2n26Uk3guY6hlz*L#kU)AXVyO#bzh_GzY((uQu;B=a)csXvT%<$tYn>J** zzb>Q6$?(YEXe>+V;g2vLS_!ys@yDCT3z^8GV?^a4CUKq^`53M=Wd1QXW;aO1BGwez zk@;IDU&srV^z%eF8;whhh2pN?#Ysc(Wr;y-1M&UDuq_EkcjA(QXI3AQ!vzU#3e5Uq zUwCe_Rtwh7Ux-(6D8`0g!#7V0CS*%4`lK-&7-pu(L$CNTr3PrlCrN)&Qw-A5$VU|1 zcsATAa24d7|3Kyj5$)N71$NK&eYjeg>-}J5!<@G9QK~{?i=kdpMhBhD=d2-znf~?N z`G<&iuaqx(5MzCUJhzw&Dkv$A_GGm^`3{qAz~76bp2w|O)0T@VkF_sH98M^L&Avao zYe#IR>(a9)mkwJ?^KTh29Hv!O-wmJ`98TBqPiN`cIpr9BNL!zfhD~wcDwkMWsUF0H zHEJZM@l1V;C^VC5G#e1>pd+55jVVW~`bwq>iqNMDR_jx<5Wv-RX*+kOxwBe;3G@hDZHdbPq{PBIq1j}0!Q(X z_274f9%0?m-0DGq__KO5i59VC30`dH3WxYQP~|dV4eQQnIv%JQmEh`U(Azj12jzTW z1>9b2BoZ+#@$T8qvA8c$F=vl-k07(=p->DnGr0^yeG#cuEV3_!0G^;5Q8BduV~p=M z!;ps-yg)ef`1klMuTftl1PxinxmZs25d1o0g;Ijg_O*D9-;m zP)Qhag%wf!u#=PdT-W?wBs3j6K9KLBLT9!LITgcRfd_SYMP*{zLg%Z{XM3!MWrrVM zngFP>)t39xL=NI&#omQ2YcJZR0W@*pJ=RO1r4#*T$~8wj*B+d{e-E~KBO(FphAku~d0=*7dCP#9_IAxq1wCW(m^#(nhw{GIp*{DK_Q9K7)@cT;JU@`*i0h-? z<|*9otNdtp`n=Bz24WtL_6HEeg+>D6RN21GPjK(E9$XliT#^YQPC-uT6W73K}uJ2X0+QQLN7EKP9lmLZGF_j zB>H+~05JdKTAhvWfts*LrH*(CAPqw}J~@1oGMp-VhzA+V5u^LcJ}@A<0Py zJgql%mK3FV6VF}{t+XD-g?Iq`RWbi-)#PR*VCZWTKRksF4sQFW^tGuDJh5F{raGN= zWJRZ;)?sv}{)*UvR>DdH{2nZrMN1PbkN4zCze=mMHhL^@j2)^(b<6>A5_iKg9u*<} z^D5F@Z{R)G*g<;!ARhxo!J9Ssx_c?ar7nYdVoJPQ6Jv^UYrf&UhcQXL4*ybAfj5w=mx3h&k{-njQ&@#!pL&ykd z2QIK|wIblw;*R?ClDCV((J=rIyd55EA}(iMAOXXZ5`{ZUO@p^GfidOQq<$Qgv|MIM zp`se>vR~{^nxGv%a~cAP-vM^B_L*Q}zC}yE>`-EhY?58jqX#_Oz33S8VHO_YCNlsJ zR~0_ns`;H##p}C%QN*}P@}JFRuTLA$^1jZi2e!Z%rNHM!k1sEF;_^6jN_Gh`vwm{e z7}Ho^xGQBIk)?~*8%1qsB%4UDiS$Bp>e$oVtV4hdCYZVL4d0T4U}N-e*Os6+S*)m< z2V8ZhFVU3zE4H6UYyTCeY|u8?Fi|>r0IXPUGQ5AgN4ffkfWT#_#!XOc@Hmh7RYldQ zKY`FI(x~x_xnm$3p%eXJ{UK&c>pl`{r@}+Pod9+zDiSH^8 zmBA~VL^dnj6KB}6w>{oo4PXWSqW@_4g4azXbXq=VvL05(w&<-W8bZn42yDHa)4rkoAH@pPtL!<(-9)}0E|o+DUh4<=!F4T%qFh-QfiGg&bz~&_p%|DPJZ_;o2+yY6oX>th zZ^&388|>diTR+=A2>7|Tss-+{)Fk>x4yU2$z6(OWpkG;8w`Mr+{p-a4nw_UV{fltn z*Lo_u?NJd0hjjNmc+zfc610)%+Yf%iq1^KavRF$nF#KFo+lste>3tNIGm2c)Vlb`p0jKb-eH@NHVpClilNtCnF0^imP3vjKIjEZ zL7P9?&fhcW(%ByVsUOS*V<__H6Nk26sxdBlu~tkTgFpXiauq9&YI#XRDPdl)LpEvoowoR#xNrq|K%|d08Sc0T z#9(hrsQ9=s7Q@()We;yaCr8+E9R{yF1}ha3B+urbtsYc-I!qQT-jJU?wW41R{|Cdt ziJ$j{66v=@7QcW0-TLdLKe)~^_vPmYr?-FH3;O*}3B&rMMk=tEBAE|_dN96jt9z}& z^vUh&QaP5-54e|x{VVLyLoAmjYBiq@YrYnPHr28!$Q$Cb$nX)pBL<`@Q~*9>@1cX5 zY=b2J3HdJYONp3RO=P}~G32P?Ux^|MTs3Ji=t3=Sd=YbtUb$4B3T+AK$LF+Ibct(Z4C8wg( zyvsm|Z>uIZk%=aOwl~(zzh#0%!aq+8xM>wYdm<<$TqYf;xuqveQL4qJL4{GCLhNh> z8OXj`rV+=FC&^nlD^`zq;(}14zd}o~pSn&s7F1SX;wlk6^=9*gxG?Ms;0zO}B}k3Z zWKH~kFWugIrkej_ct=3G4vRT!yq*ydLBWWb(IcLD4G0YkbHK{yxo3*yX6n@!q%&hp ziJBIH%*~tKIW64B1v@qS$%hj*?09YQ40HfIrc`}zas3kD7TktHq9@IGSs3pxuTC%E zIzAT%Nnn~jYY&wx(NDpf#8iGC!h$PRkp}`vODwprk@%fbhSrEnM#k_!)V(`5q!2Dn z1*YR)4?BV(isecQdfdZLv3y9y{9Y=KKPc;|1YFw+VoxF5~**QHP?hLht`V z!SEw>)MfDCL|a9#bBgfRV{1evIc#ND=7u4SDoJF#DGHvi?K?X@Y zNt!kU*Q1@$4ngK(=OjrwZxQOAO9$s+ds1Zl)+0Q*LlZUV4q?GNQJ z!rvETNJ+>sw9iYLBG}!U-|QC&#EI7RhYWu=^Gu9VJeWKdOXvP;IT6UdCkz%q!$!VG zNva{bYWdV8!6XkH3Ay?m*6=GdHrwL;H-goePOIke^{ZnpEzFLrGh7P=IW89whxb~T z6d$3S<>i^0JoFF+EL&_jJ~CPKr&vH!<&qdgHm!IIO6;0<=){qwB8T!ClnCgbB zLn>@!Ce$1%P&H&0we2!*1lbSO{^QJg zBZxIyjo1FKlf7|$2nJ|IHi}$h42zj#_{m{gD&Xf%75V3%^jcms2satB0+qH%&x&jm zlVb>|w9`74ZXplzf>;g1g=r!C+z(0SBa#SCYE)GpiV&nL)M^!OEGT%QFg$aOLs^dR^Y#|D{N z;Iz@>NF-CDCrfNI_Wr8=P(W1h3{QT+DcuX65X&W4IbCu;C%?99wvwIvDbj2V}e%AQFw{Q zwYf@T00jhdVjkw(Z5;1SnAWV9_Dg#ZPu`rt;)Uu(>tI?xHC|u?=9LB5RO#vj2k$Pr zzem%P)RUm1GFG|;K57m8y10Jaaquq3U2DUXw<)Hfwg-;-XuSEi!j(pGgYFd&TiQ70 z&SQ-<_;l9l2iqrAYh;t(ew%ina|f(Iy#(jpidZt-FKjvu3QL8=@djwafEUWaF)kk2 z3G3A1G4U_L>M9b{o2k`;HuIe72P#X_g2e4LSULHSFMpFQrnK|-dibuxmdSs7>EVj} z8RbbEi5@+*AxV!rO*r{})IjS!p^?SGYZslA4p?E#0m(j-u0${bk7Y!vQEw!5k>aVI zIlF2T$(@b5sJhtKO&<;mSjG5>QoVIT+$8H~2~JJ>i6n=3xZ4us6 zKtOv7=alKMBAPRRd#}K)f9eefrVtmeEat++hv<^RBIbC&rVx*LV-y@(s?3C|{C_{F zEz#E*aE@ibl)E$iWuj#LSe;Az8kMNNl~8i&@W%Hs#CRTAXD)s*(F>8>>%5^=?!9>i z)_2;PoAti;dDjh8m!cQ+D6=Cm+ixs9KFr9Err%uE$Co#zous-)WTJ=9S7lO`(5%NP zw5MX{RA}__#WAKDEPv3kdr%!EXF9aGywG+jj{1oBr1!yZyPtUUgLW?!&mkVDQ~@5Hz4X{M%lu zC3C3nAcDFK=#IcD-(QjX8U=jF2CCip3U`6B#a5nq@6Ag!g&>hA{<;<=NC|2oowV2w zH9J*(Y4!G7{|RvwGX{@RPWFhzYEqZWB{Yi4l|H$| z2fbh4i?;FzNKeDtB65A8kmDB=(*y{~XI{5iy^h49K*UT1a?~MEUh#VSo(nYIEx*v) z*%7fA%Ed`m=S03)3$FrUE}3)7LiO$1jKjmd4#Aw4-ic;>Wk))%#JZf;M~qD=hE=xi z7y)ns-;PtR^m$${V52hxFmC=S^~`uF((l(lWW6DbRKSVpnkcNc=e7M4%zI5CV`uaq z*KcPoyzj#VCCH*;1W(cej=IW#eF~nLhOu{Sq)PoA{qHFHO{ap(cUGR8ckBpe0iu+< zcEJ4cof86cI&Qfvk_agdO1`>tI?>y5a$*{)nVsDxs{QCDxEs*Qnuu3InjYzh7s`jw z5MNxVcU*wo&{C^I^^5aA>wIVieg~m|cpwXQCFkz!9QKZ8EVbpOLjF}ah_9QY8OAZ! zJ-Lcm2aM^XWBLPvh7f&xn=FZ;N!!dJdfypX@*GF9Uj)oxH#_#62eUR@VDM4%rNboS zQslF4L6Q&Q4N7}N0Oeog_qnmgVe**XXx=Cw`SQ!5teGA`9X^zuH}`IJgM#3=s}>O7 zJL7+@$7yJ{nGxX#vb7g|EC%Tei!PEnKosR!Z*Nq8Ct6dK-$CVZaHZUD+hyp<(4Xsd z$&6gc5K{GK!&jxHy5geg@3F%tWkeOoaYBA|m0>b`N94OocPH<5QPGYKD*XlX{GO5R ziy^(r>{;x1=tE4m9{K%$$>eg@NI$5@@ZD3Sy|ufg1)j;|I)FX;_+x^R4nf@xP^GR5 z%UmDU7VE0dS*tvNEQv+c-4*90rx-_A+57~<4a??7{+8CZMVreREXv!oe=a^F2jRbX z;if-V&Fk|1XDkq)wT|2aW0lT-=Y7*<=w+ZI%Fyno6&+~*KVRU>4*)KN&+o+Tf(0NiF{o4R!NkrIJ)I|N#<;**9W~s z%?$@~{(N7e-rf^`SdR)7#iN&d5%oZwq2}T1p+4{pp&K1406X{T(Z;uU!)9K93$c+M z#OwZJSWo|E%yg3+Et9E$^ZW=g3|c9PVa=yDL=TvwaGKTa$zHy4V&gyz(CD z2cknA_`UUxJTs2;ye7TVymep?Ro(mc8&fZzYYFSMkGZfV%FaaOg8N<~gv2~x93j}R zk{r2qyIQD)$Hg{Aic>kxj~dr8hi^fcuO+A{eV?JWA2ipdCHaWxL&INZd$=_ocJI7V zR6+~&iV@(c45ov^$88j(wfi^HEb3G0JDe|PF-BvQL}F&_zF-5aSd(<_5492L)uKL$ zT>gm#JjRDj^lgD@2PpB|oDIfT)FL}8@pk@ap(h{#U`;Ff0bYX4n6_W6#s=dFH83g?D8yA0-DH;Vu7WI^zcf1Wx zPMOC$hIS!LGieOVfSxx8QIc43ieb*W$XG5Xo)?akM<52ktEpwCkW?vTv>4B8W&)RD z?oPn2Y*qs0BgpL6J)|kQ@tCHVB6TZH-9Yg3Y>Hr|Bf%{3mzY&}QQUs>0~cTf5z}pk ziSw|2#r8#)>!T3&j8RZWkwz2}JFv!vTgCNDiNaDYMNnHPZ=m7kYUPGpWn1*$Lj>jF zNBb>l?67zQ`T)b@mD0o&06ks-PVQ*E0~8{CO3TcWqe5$X4>;0qWiOM5f3@LaiY)1d zY?a_@87bJ_%aD)az*DD67iM1y7pMLz3y%p$d6JWK3n>n9GvlRTauVQp#$uKfdU`zR zdfDU;tL}8J;z-ep*UMYWDadX}0;{{UFWgccc@=nW{lf zV+*nRLk7<&Om?%eD`(?oxzjNOPJk0Bn`&|*$`|@vzn>(j?CwznEPT~3mLvbPA9euG zk>t`Pe;Jv4HEyW81{%F5Qp@7}`~KMW$yZoCSta0cVxh@+7h^R`3= zd_PI6qjd^l!Za~`SL&0Rldt`@gFTN$Z0GgxZ>8zI1rSkP3Yj3K^@P`+FReRc!!T39_ z9`q-Dd3hP9_e9l2*jy-_Bizf$WuJe&)kyHb_I&3)V{He8n($T%J$Tl| z$nJvO%th14(N&R`L-}Fs`jY7a_fpG@sU8tzV**_-=z!d+Eb+zL(IvqRV{t8ekj`}I zguqKR`5FHugz(4K#MqdkG2+W}^BWMyFCwzVTQrbjOxb39>YIxf$64|9ie1U#i~C{u z<5Exr;hnRi7JoE$qE!$X)+6#0^6bu`H>#D9S(0h`6*|E-?kUGwUp~ie{EX_9y#*O) z>d2j9Y&rVgg#PqK>%&hWV-OX(QBcnCyMZ;>lEB1y}nqtr}Cq_F^Lde9Im+~K}pQi6g zi{$5QzA2xk)KA5afxd2{Vkv$7F*SV@M%Piu0>~0QqKdIZDM8C3wYq+lZIZGBi>qOb zTAzwh-SmRp8U~tTp6G58Cr&cBOrm@#>j|M{_&#txD9|0-xtH;=lv>y%!u8SBh1E0F zR)VPA9`I|x7bxHDz8j@><6C`}2WpNGCyI$>(qim0zO!K06j&B7UEiE&FEHNu`s!S2 z1Og6 zhwHy%2sIBjiYEPBvE>$C^sx)kU-7_}$kJmcl^&{;`62}eE|nzY3JoXPcA;&ZnypNdx5|imtC0=%S_NJKW~x_H!wZk3`88B1Os{ zE6&JOBvum5^ZhIE7P-MxQtZBcjRgvP=_gJU$}ht$pECywlCuj#hu_Ir25Vy6gs z#J6uDc;BWYWo4zTwP`4c1;E0>f1*5N3Wo&a5{iK{mY)MRt>zcQ4RfL*vbp_j#U7X==Zo9&XCoD*e@UHvP|qj`FWX z&2#TDizJJhQe3D5d9z+cbu(=fXwFGO3bLW%_&ihzUJ%hpf3ha?If|^HFd5E`MO;H; zQL66M%uuIDgM6}C2U+489b=AJ^ev$JZlK@*xI>dM>Er$44V*fD!kub_!yKcBXcjP1MM`t&K%jyevmLM)G~?p*t$vTcr;@w?tSPl?~IW8eJz>zKey)yU2h*6keuRCc1A z>ST11fkdfD$m^KP{vbq)Jm9jr!u^@T=(@Zhv6pE0`e3+>p7iWdwn4sV^2&*cPnG=> z1yd;q%wvL`%MPl=LQ5pTxY!mJa`vjP%>)IewRr9TkuHO2zpK7rLe#OA%N3p!)~Q!& z7k+%ix?Xsw0bJu=qy4oNCSHVhd{3!GOrFTM< z5kv9OUCGo2=Kp#1R;|3sjde>PIAR{lS7*E_qn6vi+OTrfwGsF|dfihY&8MtuZ}Dl! zVrMoKsuC~@R^ME;{EajAy5?C;LY>i&+P`}rU90x`ViwRkxy;(tQ6Pc(IjI>#;~waS{AC_!uvCW)i~Y$Bg`0%)5iOA zqer4MJ3PsE^8}g0!LHGe)i~e&W47+^uETO;@$D_mlSb{PCz<>cU|5_%j-zVHq}KH6 zf2`Snql&MLm86{d3$>IcMvH5f+m)XBaw&)WJ=A(z3zkcvoD3D|&Qs$ZxO-HnofgX`TE5 zGfq2o;@!Upwd4xtyUhH%Wj=yb$i3SOmcgI?eXQ)f)ZxAn*?wt8T7#pVz5aI=fBGi^ zXUDGly5`9rZQvg^yOp0*wY*mxga7qn^|$Tcd;cD3Z5bS?vL=ib07xJ`=aGt;1Xy(6 z)l~lEbG!WO&<{(+ct0y|ux)>0`34s@?VgT&GWsi#Lm}J4pET-_*R-PXnvA8`!kp zQhz}+?@!%Z2a(DB*6su#0|#%r#-)FR?4LV$hxebSUyvp05ZbT`jkhKdw+_C5E%xmAWddNuXuZ;faoeZbjg)+Jx z(&v${cv5sD1=mVbnW>Zs*HeZZhZv_!uU(E54>tSWh+G2CK}eF30VnN-XLskFPwGs! zw#RP_y42Zm@HjslTIw`^`;=z{7q@;R7ry>pe7>_^-0nP z6$8QA|{<6D~a zU$Mi9d;ugiWT_uOILgLVbu`>*1HjEHcRWpE5)E56`6H@t6)r6eyr3moA}8YewAq76 zfFRBmf{}#Qnk?KoSdmTA=vputP4QP7oN1EZH+q*M32xW#7pb~N_3XvW>K1lCBiQ;2 z>>Ka}n~A9herb^CWwoP`R1QeW%@jFC5MqDeX@nDszfeJ;hU<5S|0v9V(a*txPooSV z3=FAKz}sg*X0GyJa8uFDH=#gA&pKutbKfsimdlS2pZunK9Q_4648S!W18TI%7Gg+3 zR=>k_&_qJ}xr)Fq)#TgTwTgcu;hdH2?U)VVs@o$f`hVhQAdnD6{_$E0+=$Gx`ZG=nU=;UL!ORcVwTz z-CBh%B+MSowZ=q-Q;xbQibiF^!t#B0xIrWjc?ICT0_rU)04e;t6g-%Se+?ES3P8-F z8X;eQPX(W!bd01hAa(UX=@$MnGuWVoz!|x+OnJBZo8m!ctkG>7FCUp}8Lr0a-%l)R zW$em(2PZ@*#-FQK3lwno`}*u>!`g~%lV?f7AE7PU*)+WJdGzYxb{1e>YhZ`E7Iw^t z62^miiXi*Dh?vXjQDnmqo9Qby_(~lvZY<5j%&>WyOgM@Igz|F2k)7->i zC2)qs-H+GjOfe`75t1T*%gqgwHoqm58y3^{S?A( zExKdwVSsJsfYPcT#U7n~@2Z&dnT~@LJEXTPbIbI5pC+b z$RZJcl7HK@>mOZRaj>^_3<~s1G4_|7Xp8PXvYyV~^L6S?zgFq~VOBakABGYh`|eNI zX}#+Yv<%{b=g-Ewz(baI-kD=L#S$OGo~%5DS7{rx=HiN1{2ncD;6&IIh`S~6f^r17 zfQ-yHHjVB-k~OrjH4?l$D0jbzCHw2b0bnH;pXPgowRaJ{F~G|$&`c7aw0OT?Q$&yl zEIFNWS9pgoBA#9(nJ^LsUYv!xf1l3idJ(Gi?!|D*bt^pXDc0#;OzQfMQ%RL@=*^{i zmH^(G!MAQteULUbo7sn1$-J31ECslgMEb{s38})kjx>)kA2A>Cl4~10`pe$-ob__u zWwvdrA&|)bOK9Vv_aDh+un5Den<>(f&iwFL@>j;GQ}BA3(MwkaL1uQHRb{Ll>8yj* zGv40&pXWFinL!`>b{Hbu((~}iar=m>1)%UQ)o+l1b`=6(ZEuPO28P9M?tDyvkqw0i4OH9;gBqk`W0~c&U?=RAr^moy_zNN@N0jS>_gU=`~pqDTO~dC42$V>%@DhD z!@RtmFH3QDAXDD|j8*k)7N+*wdP4h1;u>>mSQi{=QwFl~x3jSp%23=tsDqFBnXk8?s1WzvpGC>34f z^(rBQAC%(n)K3e`+Y6hiSGVtEZzeT)lW6Rrzt`xBai3U32raRVQT&*^zZ5fVIjm7( z%vI5(Vu89Wio)|{_NO%27@2cuf74#jl(}A1$bE|s3qe104HN$OLXu0^rO{!ij1BoM;YNxm&9()L(P7t|tWT4pI%`f9-=#d~pX3|1;PXz4+wz6D_ z<^v+NpLj~?z-kdpWB8(TESK2A3<0TKOko`0Fe!C|MDiOmLJAcn(F}{+MCR-Ul+iOP zevwhN0;bRF#Q9YXq?JNxe>W#=i(ah zuDJG)%`C&*bs2fLhxnWYg&vYpOYX``UC4pmPI_e3ko|0E@Ux3!RfOQKq$OFJ&3znRpFRd^I>du!U#ECJpbZtn3I-WoJmnI*GQ8c)cSc-Dm)j1mD++LL2Ya|510`m6Ji{d4=Yf`RM5B z_uG#@CE+8cdd&t*mS7ix$D+x@jcJ=vkAgpyhF;Acq91&<98zj(JpJTSMw}iA!uxFP z8uimSCT*MARr`3aQqqxc=an)_vcEA@{f*{Hhv5Xgp^x@-Z&`<`pP8m|%8O0ORlwj76YL2rsIJ4SIqf^Pu+Ar>xXLm5yc~Dd z`hVz!8a{Y&!4minSt={69UK2MmPj9i9cTp9v01h5*%|%By|v7<{W;;F6~{ZhdYOlm zdd5<4SHrNns}2S~V)%(|9QBd^&biSy{!l+DTE(a(AT+RS;eb>%d;P|IXOT41M>@r+ z>fc2k^4Gv`_)>4QyT_NV5c++*9A9R9viQe5y-ay?k)ZFfcLa|olM>501zu+`3_CK6yu&-Sd}C<47$@YjYG95`ADQqLj-jtGdw zJx9<_B~q@MVr9=C{xB>DYnTq>WivQ^sVXG$WmNRN(_@dJ;?cYe*x?QPW1=_G6;*WU9TVD#eOKtR$md5FQV+yI$JwUYaW2~h#1K`aQ8L2gv49mIGJ(K`|Q z(B~HG6e9MOfhu{>;@D^~I~@L00$(dl2`qXgzHZe()frMBa%D0>%)v109!07<-kuD% zX<8e>*=l63p5Xm<&~FpII7vL5|IrrlFjSsCLNo?Jp3LLI;df(+98hUnHWnGLMpj@NRO%$Mi z9(U7XU}WKV?qKBg{=*SoWtq#QSr0clIpIcOC((bLy6TvqnqH3uB?Yr@`F@QcnS^6x zSk-;>fA2&98TKcmRp<2$O_k-%7=lE8T&E%le@Q(lCWTbrhg`4ZjJegi z$q?J0)$Hh=x}zKup~Fx)Gcu$bLP;87>uxTT1ovBG)KM&t&k^p22HuJ z4+Hw)8Z?pt6bLM15@-|n^0+0K$X_nRq+mH)OwDz3zj`cDWza}&#uuq2LW3~+jR<$d z83s}vB|XjO4g%pOgh9~=D!;XXCLG-4z8@1>Q2Jta9;AveQH^6Gk22zTrWEi6XhvP< z3>W383MZ3JRh8NtYZ_;77T`3>>5ruQC=V(oEfM~s=AK9WiERA?3cWh8t%sA(p`Xo} z7W^RoY6A8TF+r0oyXin#WH=mi>yA~F(dd%V4WRywcEopBzSRGqI~3vz+SZCH(PpiI z&t-mxk9fVSNs6(vSB;z`CjqYl#!~QJ0C~XKp2^czaKFPBp$}-wfMZ}|9Yc`F#a*smL z(fcUvMCc+bO8b=>RaE{^98dsz%C<-sEh$Rim~u{K!olPCe*rCc!g>z7YsuVn?VQW8 zPhNUhA-REOzek|-aC#Vj_OTxKSIsTTWTG(^(wujM1~9Beon-l$Ad4;Nv*LZ>wLR$g z*mwUGc(H~kgmy5Nej(}2Kq7+Q;mOhS!B%7~UnSdBrsNUM#o12#=v-WA;o}|?`61OI zb5K)_!U5tKd(E(g)QvB>=VwDm_^9$z>PZ(Vv_k{s=tLn{&0M2~q~XjgK8LT(uJ0~| z{l?{WrqqVFud($>O7=z8iEwJg8=+2hS~U2G<^7%na+oSU3`)a(&gV~<0_W}vu6 z)q6pY*kSjbs%<8ufe`U{Y-bh!c?=lmDo#0TR&Tt`F;|TC5#O;ms%De(&wlT+p>*UX zON5|ercsJjXEb!0+c+OIote$YNFs*SF9T#$_`wQi1w={;YvO`fE~Uv9e?<{EurL%l z!^OfqD6XP?7Tt?Sz0&GbOgk$hL=3>CGKfexUlfiV9SOXxtypYAw{M74=) zZ9kFIHJxmODV`6ph05U|hC{4S(;13Cw_XT|r6Ih!-qXNU11&SCUcxqqaYctBmO4a0 z6pb@}o9r26!}QkD)>#gtH~k4&0_6-2W1RXM@9Dp?ulf*w_Ly~VoM)mjTGZ_f-~M42 ztBviY5$MyG9)NP}aDJ^}+_L@G$!l|hV3lJ6Qy2YS*TTZYA@rZ0?t3GJyyPb{?eaGCr zCt-X7lxZ&MmM>Z%R}0QKabPn{$NJgqA;3RC{bF;e?L=qG1NAaKow3V#_TpwYFECjo z;`gXBrkZs3)Xbd}!*nV)0 ztjryIfAi8OBPbSsx67EVc_H?fbhJVIN6ILIe2$yS&sEbcd7{dDtP?7VPWlpw%YB@g(kTX16MB1ETO`rs~V;=pTYnHKTyXyKD8y^4Vk zW~Bh(8e|l4i}a3V7v5@B2q{(Ka&3suQ5Sv+4$!v;@`!U@R3x2MXW+jV=6E?IuW^CZ z##Z@v%0?gvI?5e-uVI9tyQJSspM*sL-tyBE-ETOh0?mQgFw8i2N#NK64coZ+zLJf) z?a_rsyL$6b*nTm=yi)=PXD8m)u$mB$n&m!AGA)yYYw-JoMf&+;3uB@qZQ%uf`tXw7 zl-1cUlDlGSb{77k{39XYu9dLUcB9-)SV-&v`kglysOw`Fo7iV7t1x1h{XFKqLHSaJzmSq?NXrqiCp|`1beY1%P3w{$Zv)J&D38 zk4bkO0#vrm)|zp$3J>Pm%$T6%x7e_QP%@rZ*KP`~^8#Pacve5o$tQ*w{qyW~3VmGp}a2IMuX z&ehQ*`x@2bHQ@PDfaqTwMYRj}V9oU>Z3#~09Y9ciZk42#=Q*7<4Io==e+}-8JdtB56J=WwxXyR1kv~0M?c7a zNVc^i;Az?^JN^CCjAiDB%!6S^mnjBt#tdzB2W#HCW_4#I4cZ#pRVt~vq9fhVa`jOK z`Qf$a-!EMb#M`C+A5&)?6;=DaeLAF@p{1Ll8A?F9K}3*dNI|+wQb2~Tp}Ub(x??~Z zkw&_E00AlA;rXuLTJQhoths0A#J;ZUv-fS7=E8X{04Otr9{F%?P`#L9@|lXb?*Of% zt&~6wv$wE?U4FA1(?ownaw}h zf1sI7ekRco?owM2wO|EPq_-lbMmze^Q2%FK(p1Vj?wH%SU~KzGN2O!VFuF|5H%+v; ztLW>_@%gIKOx2Q(-%%0507_eurS9KR_d5oW2I(Q5{z*^zf}ax|Rj9k!wy4%m!bOJO z?fktE<*nbtAK=~U{2GsPh9W{8&}E=D+WUU5$uVPPciv4Hwim3_xfghl`4ygxuuR+7dT30KGX}@R zNLL`7I3fP`w%WqlQ}_4n*ygfFoNpIOHp_n=ygr)~jcIGCiQq+UZKi9)K3 zB+FZ+F!y)QazYCFH1RuI;Jx8kmkr|eUtU|b>Lz56`$K>=Lnq#@2g+UU4P%a2D zOC}uRLYnbnYyzt@a@VcQbhhI6$+w%5NZB}2TtP##L+i>Llq{w{)kdGVU9}*&9jg<2 zy^oXTYUpfAdzfFflfrzW6$gTnBBo;IDkuJ2zR53GyIg|*BxpI+pFIUie~8mkmgK!H znqxIGI&eGrU)C{+YHJ>_whs13ZKT0BY||x)5$@=6d^x&EB<)sa9t&_tGaIX|BB>+D z5o)%l+8n1$A8lC~AT^gLWFNZ161y|uOzXL|KuBMM12=jnfFh?WJ~9>N>tf>B!CL=` z`(@z@#f~@^$?k}{o_eKoux&MWl!QaR%DDxK@jA5|H+6Kr`GHjB^kudrM0?X3O-vTq zC!C*96~e6MG+&{5i*+u&j^6uf?5p)(9~42^eScw*b9?~3u#fQhYtU1}AIo-Itx2xh z?%-ykb*7t4gVZQ8a4XW*b7@j;kt=x#+*PrFTN`_TYL5#h371Y9(V$?K^V-9$)z{X& zj|QbQ#TZi#G&x^4NQpIthN3a}lEtv08o@Bqt<6(5{#>CU5i(!SEgu*r(*6RLFiLpU zs={qtXpaSo>}PADP(z2@_vpc~L_Hdy5K#GVrfSzKI48feDuW(9vNVhK+lL#2FHD=I zOh8ZbJfI1v}DW9_+SW(jj}Ri&&lOxT99& zRbBTHpY?rTRyp+xJ~U^Q+y0*r2c`6Gh>7qxMi;v5$L8+{_g-`NgvI zRd7}An(Ug!Swqe-nEZEP1}_N`k!CjQ7OC95wNrpHosYq$w~eHgrBqy`JBY4w0IChT zHC8CK5*)kCUF;EZr{S^_(kh~PqyCEvlBe-y$SgLRMlrSr)c<2^8@PZX}(FkrdOI1r<>eJK!W2p;hwGcaYa@3pTF7}vhnt^&e>bWsj7}^u z7IHnSu4=xv{mUizB&KSs$h~}gXt|ktN63_-oHD9$&6x=G$J9C=HP}aFwHmo&jM1N% zjbGJZN;fv&6ZS_lVwjYntoVHKwJ}#ugj&K#6*;~HC*9T&e$v#n6SwI4$kR^o{n{X5 z+Dq<%c-eKsKgHK;WM%`aA!=Yc@u;i_%tm`ZgKyFzM?ysfa@Im>3(Sc5W)&N!lV}Ez z^f2bZ;p8VbS+%7R7ZD&m#X|)%G9d@__fQU-GOWcO@3lnsEg1BotTYi6#UOoqp?$Og zD`Kqf!kxo^ZSkkZ@%RIK3oRv2N1%PXCcIA0vL?S35pTRo+B2D{0Vu%fLoY+RX`F(# z5f4&(-CPdC#G|SLSMWN+*eS%CDM^h?}Uqstc* z^S|kK3b?gFTgmtUj=eKVV4&k#Bu#UTaIOkF_2hZs$&%OLLy16y82&OdcBFn zmGrWsZJ>ttPpBNzIMGzKnouxw;b!|W%(HVFvEGb<)G_wSNE%7X$9MVju(woqwl*iA zjPZb9o1rU%{;XLWq`R9tl(&u_Hdmx%{2(W&?}Xl75abbZg&+jP=`6 zB7+HO3FyFC8j`l7KV@l#-lj<5)7o^W*X zgYg8UxR+57E483u+!r*cG;BlaB#qW%@?#h_nXcIbxFdJNtX?n&6V!s50KN0q>%6_# znh#wNoM5NuEUSlQ(ahs{GT&HCcAaoH0ogmRBmkQN@=7!=WU(t4j&;s1o6tbyvqCJw zYu587a;am&qedS@BUaO$DI>1MrOYy?Qawuk_m4r%Sp}=rfhz6W>J4J^f?fqmLtl{= z+;|_Y+Ay$G2V+fhh&Eg84GaVGsMGefx9E|RU;4?4HU8XseK`rhc!+>%o_ScS>19(U zxJa~V{6B(9_~jPIvy71sNpA^%GcJ~joH4+G+cD3_NH>7kJlfk-GSrTt-+{)sK>J1- zb>*{xq0!JGyrapg!|It>+4i*ttpB^g3QYPLa4J0=^po#k@!`WRd%sFgGzJ^CrifU^ z)VxM*>N3_zdSni~4nRN#iFBLsDQwfM&%8*P%kGbeiotRhZ?f2E8Qp6wS<0)})gEiG zcGK$m{ATPKff^PYg1j5_0`s}>ZN8(tX$kjt>IhfD|K4=Akvq)TPJD~x!U_A`Gv6+5 zSpUkM@g}WB1kPi_9UBmV*>StF^8V@4e0A-8!~5EE*dL5q8}kP0vv+}hy#{VQ3Cr2_dPLoP z-4ne95Fp?d|Dj0$9Of1IgTfu{Vq;nBFxP)#q(tpBl@HM{QCF-v_W(h>y(JeCPO zDV=w(L7lU>Okf`rbDwoq&L}-qKpYVCkI!iD^5jtCyq{~l>O0|96k!@?Cv*sHf9fm}px)S2bW_W7XIVBS3xfs9AZG@P>CjImt#>Vm_k!Ae@kHT;- zWN9s75FZCiCfO8+WPcu7zuVH@(kwphHEHNpHIcf78OmmyHkxi`HwpP8eT|`{Vea|I zPf`T&^UjYM$oFNXnOS-h+(6w9!lS)WhX_kZ=(?8Mdg#PkN~9Yu5uVT4SsCD#5~#7c zwsSj_m`zgu>4Cw;S1tLsTMv$eVyoYG)00@E5WEarXO&tq|4^xtx^Oorp7p1Gs4AKu zQN9yXND|sY>_YT(u1XfIv#0WXN_c4m-xkm~)i-b7BVN$pG>7LJ8F4}zLHb5YN z&Pr<^6PfnSp>=?)r^+bv7?FC}GDnk?b-lLBB*+uf3DkCIWTRYXcbvw~}QB}8ur!72HKMoO3tR`0*ng~2~Lw+xG?KT}kF#%f}; zu2e4KE>tcU78{<(^@cEvus@-A0E6bvn6cTv9Bk1YcnCmj)No*XN^HtGDe2y!w^^cn zr@8@o>`@#jvXNxcXqe4t` zPz=?TbE6|u$pC2?RWjJMdmu1s?bj?^ri6lpgcbRIEXJHXwz)P>tI`4-zSDCKhH zEjQ}^NO{cE@+~Io()z!2nSbzq!knm|6nz%77rekJp<#*cKpkX*{a^^ngCh!ZwGC0I z2v(Y%1%2E(Qp|dlTb(`LJyHdY1|#9+`lOJs-eyw?^!C;pjlAb)VsH$1#0G2#%I6;t z{2f~%pIYoJF$`iHJgdN-68Srnj^`dV$%@7i@q-u!4xKhli`7pLvygbxk7$%dLf2XSN$Z?fkLndxd5O@ z8)I{{D2bG*_V#ajZ)Yf4uQKi(dgm>Y3F)twrC{|`=rN5T=^7@Wb9a#u5fqg%ivS!M zH!MbfwoAy4gwPxTVz}Q|Wz?iK`BL<@{L+E^S-=^8B_~bH}?R#xTgz=w> zkQ=thWgH}DoLaoMRDVZoMLGfH1^cDErBOhdPyeJr)5as{HG)|{Dys;mUia>a`Dv~a zF%Yvzqwvm3PF6_1?!v_~cngbgQHaC1l_?@k7Hy??y@9G}V!Y12Md3$`^UR;!RvS_0 zNTkc$*eI<(R~NAbk2nz`znoj|PoG1D#aO$|Hlw%gg8lyz4L*yp=63ea4XGN;_*Izb zh0^geaKquydY>^MWgi~0Q?skqW>O*+!3`VEJNB7{VJqv5LdG|^tP*xtKmfSGmz5+a zmyv%E@P;%$Fc~{PfdiM%X#}Uq$j;qSD`Y_$tHB@F#&Rs?abMBAs<&2Z#reG5=P~QW zuhjmW$X0J6hHBtj;LASg8~sUgB45XZt1&~g6Te}Do^vYvNEaG0I~QR>G>bU-+(LkY zd|oRm-qz-*^DV2!D+l>`30E|KMm-XXih3QTMU_)wwFFlUl>F5#FUWNRmB+1{HT;~C(}KG67_FX&DWydLU$y32;aI#9Km?ps`<6PMpw9vanr8l`U#dor`gLz zr}H;z*9tUf{Z8BG;K*afDMjWl`mmx0f_(yqU$R=ZM<^2z_p>XTi(7ffgVYIkEI%`>PX|m^f4<^V=p)E{5Uv^MjMFvAvnx^(=kRq*r0nx3qqqPg$WkHcZd&Ixv_bLVk zrsrqMEj+n|LRmh(-`f!Vs?p>_Z#G2NcttmBm5YDFlk}eIi=xPkmj2@TDh{j4_O{qk z1Uyz0i6FCHF1M`SCH^(}VUYQ{AScNy!a)K`Vci31mDe5fiOD#h1hu4^)+{$%0wNy~ zJsiQ|4E8FxUreoVzt}+Id9vAUphVf6S0ptWydy+OKBm7G79jte*}jI64*hx!nmO_y zE;u0J{#C%h>TCCH%6rW^Kpmzj$(K1Of+NXRkG|y_hQH^_?P{S8ViMo!drb6D?|xWN z`vAvula}a7TK23Ymd5X(@F9dF3MGUmSd*%@^j&Xrl-PTl=93G1Un_a-v?Q_g@&CB$ zpcd($i3uKYRc|QW5o2mJbXYCMtk0pp=yrN8JdW+TysrfzF% z^_6@rMe%hu#Zh|fV=t7AAHf1a(gj^!716`>#A|;*Voe>#`tGPR9gSE>_&>qag`U+8V@D zzLg_3dwbBH@{$sI=EI440>kgK{l3Z_z%~kdX1EZ{&b)u-Ce0{19E30!BfvWsF@HTh zX)i*?5tY7?=}^WC_tweRLPU2e)aVX0)m-9D)&u;w!{M5YSnq$r8&42j;D{}lvCawO zA_M6On!9G(xc)3vg1$9Adk7&oqzuOg@3-i}+GoDQwsIcz$2Zb9tgI+&na5IpD=5zW z9_Jf!r#F{;MrQvb<*|%q?cM~<56m0!*839-OFJV{GA+R=b*Og()vfMPK#&h`SrE}; zQ8;-)As~$}xjyh+l()`|w)&C2TB!Lz1;W=n);#(4SvOpM6epOZjX)WSy%CN>;FV_9 z9hD_Nc*~zfgMHUq+s#|gO|idO6w6GhyjsF95$VLc!mpkofgK33z*_A4T{>NE=5-`-Unm1j+>C{r|A1x6Ow_dj@Cg5b7+)z-Re@SVv6gyLVsJo<&5- zvycz6gbj}FEuVnfPDCCtH&<$$G-)SMXI840Z5z|Ytr{9VA9}M8eHtJC z7iG-+32okvO&&U8l)xgPqoQ6!dMGaWk@>7Km_y}0y>wMLLb=cTPZO<_c8j*uBeJ9`w~Wh^v@CAUftN;%U?OHHAY=Mr?nofm4J3* zgd5{K`EI-gSvl)@zpM7M0aoHo;Y^I@XZ*z@i^PCI@b`svJgW?ghOOFQ!74 zh*x0soIhOe5e7w||8E1~`&2#d#Oq5m3Zz!q-~vVm=a!XROoN{_=|~j5uD+y+bJ`}7 zO_Rfnl&D z8$YTH%$+=_=4G%PU82ERsJ3ON_1~{qBSn#n)!qjunMT|f?`(v!TruMu(#@<0^xKT@ z5!7GX6u>M&4Eo~@q1D9_!NveF)@`@<{-{{LeEB<4Wmt!)}*YTSBaO%tramCmx&)nCD$ zC4-dURD_t#1x5bY`Lvv2(NG0Ia{e2{YTbxR$P%_Bk1A6H8NTh+cCu1;6#)+Y!c?|G zT8#0v8B?NhhJ}Ti5t_&UalHqjq;?}G_9v#Yg>k8fxRI|v8Wu+N_b>}Y8DmqC_w)&~ z_iXm%4bvc%|CWuBDZPEcs9bv`HGm3zNgwPWTWPW38)n*KalvwK${LC$h&I*9ry?dF zSD(kXLjN+}9%DVe;31G0)tyEUBN&&@ZR(5#YDA?38yF3FN7U2&D%CX-J>hWu;~+mq zv@xul=!y;htnWy1D$jGcj8MVs+LUr)a4jYddjh=6eyWl1GI3mt71@(c0D)CNtzkOw z)(9-qQ?3(iHvu;hmxognvgOGr0Y3GW#d2xqutI`$$&9k7#AYO}$susd8UtTH3GCAa z+WxX;pKbRHO+nnBD=H6?7mHv(TRyH6Rti$2e=v2a9OOAHF}Sh+2^S{INcuCzX$2B- z7)#?BDd!}b}GESqq0Q}=u!w1z&saL0FX6IYJ`L71JGmq8na-z(kGORXi}knjtq zo>8eQWJkkoLYX%eP}KR_6lIp9IIj@=1nL8=VBvhx-uw| z4t3-G`nHlxa6QHBY|6968Hbp?2n$K<2Q}T%?vjrdZxu+GCJCnp?w#I(bGA6wYeOmw zQt*#K3Q>fMA(EJm{R@_Lu?$;_yEIy4gZeCvkGm|0?g`IPgl$eEoCtdoFMXf;!$uaL zD5Pq`8+t62yydz^xg#b^M@0AT)k@R&LIslO3FELsTZk#&h0U>0(JQ)7=zwV71_9EI zHWEf854rGv8Uxb|h?HdV8efVc8rOLpkC=YR>cG}KIA+~cLa(5cNyE`W2ZcKFIzu!8 z^Gq&_6E2tb@}*30;CmH`e$w?(!w^v7A9M1%5y|4vbf+*CdPU14&#oTdj$;iqbr-81L;;%pyM_-_QiYs=(2 zfvC2pfU#f>VAVsWtz~88mW$9!8^d6ZFD`2y`}G1?BX(0S_XV_wlsHvK-y?~MGRDE6 z_Apo7487?otV1mZtci|#NiOLeIo#(&f`v>2x(M*5_5RbiE7l*~jI$c%dKKj8HpW71 z-|lVa4?#N1#zr6;DFoeG!bLi{??cyXEkurmd zb~0(d0No>>PE+;~liqyAQ?R?UY};=_t(UJ0a%;3r8$ zfeFie#b!XJ3WOQgjJZN!!MbVch{qHOb&G#@;h4s!3DUJfq70)Gj|XQwhTs@p!D0V zSlnD(Z3kKJO+w*@q%re+Gs?qN^@E26Z{??9V)6Kr8=jzB^81v*hHig6Kh*~i(n|f* zTyp5DMgG{vpC1rL>8{Vfnp9A@;=Vkgb%cn0xt*>KAPNnq5Muy8j8+FY6{b9vptUbT zfpmi*bpUs?=wOst7ThM9L{+wCM3DiA!!2kChP>E{(Q1u-AjB^`BY^rp!5u>B8}EE3 zMr?grx(H!)cSq0{2^zz`P{bg@*ItKY<44;-E(wo@)ux zrkt3w@n0?DG_HB!L$Qj-OB!O=7^_TNv;05?-+eZSv-%g5V2&t1$N_P3ktB0H!=&HH zz*Y|{fWQVd929Zv%(t6x;W6*~#c(JNRhX^Om@s+nRsRp)NTR=E$+t$5X1(80-)EkeF5svqZg@+6Zv_ zvYFn{#ybxEMxY_PM08YcQu`Wc7vMYfXBbI~1SqQr>-%$s4Cod}oS0d5-WbtVIn%B$ zDa5V5x~!RcoM3N*+Dx(7QG5e9vW~*)!%yhHsZZYdqc1v$K<>$N%ib zEk%eoYF>uBXdWdO(UJk81hYl@6xM>`qkg`qlIu(xciFDihooS?dCs^7erZaN@l!Sd z-6Lh7nu?Il#@wiBcrMJF!s#?#WpqA7^Y@TTdQ4Onq5e_g37yZ2c!11M()RS$7zS z$#$ww_BT6w)(9_TauaSXMsDHC7~IDdpcp-UPg1r-JVNYf4i#E+0T>sy^H*F;Fg|0V zGu10-{&2z1l~k%daWSSJ6{C;Yiu*H5AqGrC9|jJw^z&}9wBoM7oHpbBdiG5&?`il) z2h;(3N$Hn~-!T87J&o* zrh1s~9445m3lo=zLscg)lNB8I(KF%IB{6Hed!@S6=n58o}fYaPh zMQRD0yKWR*l-zY+HUy1oH_%`x6LP+e+1%(@C4NGG58 zR!fRF4?~M(N1GNq^%xfYaAv8?>gB)QAp#RmMF-mVt4r7w}HuNNNgH@ z;g=YKpn?L!+7zFk>qR&pPK?67|CU31B0WkMP0Wl_p8XLH?WD}FsbYWhx3R*;24kqz zcw8RU4G${k5fR_7|H=&s63z-AagwaXgC{y4U)%>4YyqMWiy~RiR@uqc;a2Gk2Emw5JqR>CR&;c6L zO0!ZBo$KNt{;I!s@gP2RXYFFv3YnEeQDKUYZ1#s9rrk4 zSgbQUYs?5Pji!=w`^9Ts((4w}dNap$9N$kgx>1M*y+yL<+Z>Gj-t_g=+A_UIDCsL6 z{WtTLZ%~*!FmBP#Uy!^K-om*@0nGEv<6a8kOaMM8kC{813gi$2Mu~KoZB_(EpN#jR zcZhMEAI46h7o?E46l6LB?B>;xZa5f4-~gaDWtO1Hw-q-qt|dg?*RnWOu$5BH$LU^Z zV(E2`jFBbze5yLeDX>T?<7zEpA(b-uIN{vpxXwJhW%T}>cF!(e0kd!x)YhOF<35mP ztwc(+=GJ;5Y0mt*y3M+63SveT;3fO@(Wqbxl#tYR`8UPu3~ zSIb{UThw#8NG`8Qg7=s+$Los)Z2oSD@jscT1cOSkC;A2Pwj|}+7g4pq)fjZB`c+{= zYTD5oGaX8)bNZ%7gQTERN<=BBX{T0#jS-NW?fYec0~~U+t%kE|WAuXJZ$X7c1#iMu zdryTx7gRiRl47ek<1bh0(yt$pWDpC{tlOT@jO)?Iz_R6pLBR~Gq)x$!6fv@`@>8-{ z$iO8cY4&NG4<9{fa;l4G0iZr%0C8@m&!?Z7B;v(X^u6h8nfn*TCInpZU8H+E0PB-c zYf!k|vF|tSgxu}SE;4@1EjdB)&K81}{&e@7lk}yyjkp6BZIk3x`}4Q?x|>@#4u)bY zo``&d52-}OTS4mMgdW8%6Kv`AP}k? z7=jw9vw`}{6&HxSRX$J$LiNB}BA(gP`CZY@D8N)=zLG9TGnRq>`7Lpn-#$MEP3Vk1 z`;PkMuIUCSX^;OICfwvR<>xti{`10TMcAlIxX z`xuQ6Q&}NkL|}{rHdtti(}%ns-)EY}khBMf7b@U~XkKH42uRXK!o@QlbX5AtS@5)&D8-sm6h8562PtW_p8mqC+ zsVhT!gA|w1y_E{tjp$eI6~PY_pO^Xu&8UegHHI)0V9_{a0fO60iY;5l!Wuy*UI_h& zB#qc51fRa<(bOh!PQ{oUiQt>qCjEFrnsK?OcLnDT`(#|L?5#w>*;n+U8GoM_lg$zoF4Nru@52<}FN4eL+0Vm!vd;xT^J!ZC(*gk z(U_h@Q0l&4GaTWqGHearY~Nm>A30a>g|OmR)7XVJOxr%5!QbWB!(MS+*}`bTk-znB zaTHy*3t#I#?fpHgGG3fE;k%#-bM06+fMA3269KcPdZ2PW=l-n#mX*jr-m#47ECx+T zzWb0~S04B%WjeQK=k9YDU>SY6eLPocnF;KFyb$D;nSPg**I9c(b}jO-Y6ifO+CA>a z@Fp~k)4cqK!V?Ji;GJc^he~zxS>o6_p9dNN4+_(Qy3%iF*m}!Y`wS6FczLApe}Qt6 zq*k1FRSb()p6gMj4CQ`dx5ORNMO@W%U*U1`zHF67g|)7+!Z@L(iw@8T{|Y1 zBfk z_&IG~)AUHOkG2fA)sEU#ELV4Dqm4M=V@he8odF!A5)wF3wtx82&$+gWQ!(hA_?^PD zGptxt$8Nv2S1ZqSXJ-U*pl&mav=e1)XPzj>eVvK$L!xXattokjf4A;8(Mr7kns<_w zM(CqzO?>MVJ);)ump*CQZ#G3pJM3pzkL>L;9*=b}zx>9(Nsdk=waWb!tNaT5w&Ft- z0-6dmIRn!+FmZEKpyIhATh|fzH0I~6*lszEaTwC8N}%!%l7IM9@~2A z|4$Zw?tiZMdl;t_BEu)cZGFhjzuPhXb1w&1|9;eR325f`agG{b_Pfz>j6_38qZHUv zzcCrOyyzf-$M@(1{&hI8z2Z=GZ=+7H?2y`IBF;l;g2F43>2~9u#>R8zt7k0Xg6jsL zn)hP;X#{}-kMrNhGp#lSG3JrFl>&l(*0we-s872Go0TDb0gBNf<}$GWqv_0hav4&j zLy!fUlEajX7qh8`U~;>>Lfo?|^2Xa6c)Px+y~RT4j?5WsiLt)xDQk753pKyB?embL zS7j2D4@~F}=w&wDOvM)J*FW26B;Nwh=fkDb6?g|f`b;G4Q9(qZ^^5&E#B1GO=jf=5 z-|#cHeW<7$Wz_Trl1&~^z6qJZPQYb?YA#tS^zZDy$KRP&{^4ttJzhDO`( zX0Q&ChH^ZmSix~ZXE7Ym9GDCO9q=5~Kt-?1R{qGSBTo=_OqdHu`MUELXf`d%wVS65 zOkaH-vy5)~kqlw52JM;>Lto+O{K(OwS-lS1QiWQlX@&segd>1gVDw zAdN%8CQT6G`%3yVCQP5sfeT&y^Yi_%adB3rQl`~7xQ%(CtUfYv9_tkulE+ICGA{M< z;>3~;(8dg2=@}@!$2_9Vjx%+cB^K?ZXw^r&z^Q|_z6p(qI-@Np8s@E_J_N-ZV}*Er zMGqnz3ix-;bv)R+y7%zcjoNgQI?4C<*~^Z12$O!a_(hOu)V1zUn@8_;9*kG&fPZy+ zVkaA=ch-K&akDrM$Ndp;)(CA-nY_IawY6!PNAkW|{gX3nEfun)6i3|MP0_hG-aOuL zk3*}aBKt?fZ)#u*$7V_6e@cNhkn&a@{FU}oPpTScRE=37+=QbE86i2oR!qTDgnT$d zSicw}1cS<8{s7X!yWNa$=4l@}JtR?eehUOnLf#3_EnUeC>FTPm;ME*vd17p0haHjs zTKX8)deX)kxM=RgI#@C2c$=;L`5)3lLH*pS;l2+>AzJ7awe0V{_xG~TQh+M+%D#7K z+})4A+jegDQw7s)?16}=@#m;hgzr{C$gXcxPExJpBtO$|nu)l0zn8mm;FsA||@Wc;&?n}E~z z%u;%%Sl{;KqcAYHdjZO_wiq!faClKn6`VNGlOCcQ}Otm|q$ zy7@KQurPOW4l0Q>_ltE#K`avbW~?Cac>;h-(+@fnzum9}E8%pGF$lhO=#9m3IBD;v zeQjxHROJ%O%VJ#ihj=t+Yt`fPy($tEwaTeg6FAx5jq&tRx^oA$McQfM93By$q7~BIsl9)YrZNc9K-O5&p_C;%@jetGSk-DZ-Bi|6dP_BvC{ozEpoE>=F#b%sV6g^V(j>*<|OOU2tVb4CAK3$6+t z3i-s#qJ*pNem3ozxD~771}E#$2~8hsSu)m6n+R3YKKqRb`;u zK8D(`0cc8O32{ec@opPSHj=Ss=O_Wi9#YL!So z+TQZ6Siy42AXFV_3reNC43%Ots(D@A7^Tl=8UeKchH3Blqix||u7G}lZ9O&o$^^U8 zpxI{g1`ap4J5Ts*<0ciZHDQ9>!O6T$NO@wshS`F2KFXGFIY+_GV@*vPUrv@vGVS6r zda~tK-bH2|p6aHi!U2%1V1GdX)tB$4t|z)Cn>1@LgLR*}>OaGtnx=OVH;xA~h3}RL zJ^~hJJTG3imEMi(J;WKtbl6rGLcWLf&S9u|ShqP4kL% z+_WOC?UB+cQ}O>UE~gU*zuuHRBuR*BHpj>*!Mq|0LV)^5p*mLSa%+0z`@rc4BBuBC z11U2zR0_T2y1lsH)fF=U9F~kA7~z;H6B~@Z5Jd}6DAzmCJtmt$0L+d8;(tUDT@W?l zYdkZz0!)M?4$iPJfniQ^?YC%Q0=?pbK@khATh@RRUYkaO-IC>O9E^6?FJ6+g(&J6b zeBa}q-@h}iDRO3mI@^!Tiocb9M6TI%rV$JrH{QVIMhAF~K8gGbvz>ig-O;?3k4-I# zf3hHodL%P?Ie#Qr6BKZx{cEk|y25?(#Mn$^Ln7~S=^tG@Kdq|=iW~^)t&$Z@U=H~M zoXdZ28G!PdP7Ucb1htaCa@v&jQY!oH~*|F*Vh~7epLA zRowi_82l4G9h7^J6uG~Kioix5QKgJH$zcU=sYzVt4V5o}!6Kfj-`EtLCB_ykVP*}M z9bwIuj@O&7a_Xa@dwQ^mY`|GpFuD7?O2*j8RNEbCd5_t6EHe_qnwufk>14FCElOpqNf3T%{!0#6 zT#W+TmLPkT-riyk z$124XA4?oPI=upjGb%Ya`rw?U%`LPH^lF6exdg04?-exvXrEkH8kACm2hI-da_cUJ zk7z5Ms#>T<+ysehkTzec^coKc3_jR;b1f@p5uC6CcDV^|IV;=l<1Y$$k!f&y%s3_I~<4r;$u zfv(Qa8n|A|)M|u_r6SvoeFn~YL`ptx(N9BNtxLV(h_lfxh7{0l6zMu1mM#XFf%iYH z5r)`}?dYT@ne<>QT`VPhQt$%sk3GWh^+y+E*5X#nPewM#)VMPXK>5A@4N1Q*a<5vD zBXY7o^JV|ne3W4FxVp`_oR#~$pa^Zaq3Ebb7}j^<@l|? zHW4FXA+P3r<)IGICp-ijtZx1t>%75)8-qO%tS6}wd-a@^&WuJ*Ct=4WMi+4S@i!{fL{o6@cPq+2f!9*!po&e z&U8a3T>K^v%hw=23l2Tngd5o`&xK+Hws0bU0}UOJ=Vl4wPH3}Zj#^`Bu^z;DhS&E; z<%+mtVn2+;c(&U9j`1uu@OB&coOqp0R#f9Ox8DGrx6I}os)%|+n_ZcJO0lGWp49t3 ztc+0WE~-oy_NLj`iTbWFzID_?b%eh^W>JM6Oy#pOKui-uF}7ZxC^?^R;JKxn+MMQE z=v%sxVd2t+GF8&%Uoy4Urm(59u4Pl*Z%`E_+};E?<`3Obr2%{>>k}NLM!+7Zd(7QcSRb2Sy~qXn^g)KUplnWA)}J`6 z##sK$Ju3&^b#*~rC1Ye`^?iasqP+GBm>a4NYN!?Ltn*fdbF=%- zNQugE+^F*1Ak3D36;+ZE4v!E#DUcfwSV36ee7L!$+79y+;%Oo5a4X**10@K}!1rwQ z>#Y?NAm?!czQ@zdiXO19TMt~pGQ7+Rwm3NUT{yb&*=G4>@F+z^=a#~sg~3{-QEAM$ z5AchRLcyU43tp^hel+7dY#|+8{_+}?bgG9w|2U3o&D=It9wD)=`Z=5DY(te3;h?S+ zJ0qRZIx@)rHmP(YljNxXRzJ6kH|K>@@Y%+Mx1Oe@VIfxcFzXLbw0Ej4=qnVjz{$As zLS*O+7_@8vKI8pQq`2ic=bB~RW}yq73_WKkl@340F+QdLaPh0BDv?1!Y7LGIiGxwC z8mj_97r*M%Z8xANgVh7Zlc)q1+@6+;U%xk%PVuLGYernEV)KKx>MOxMeG<|hMzN1= zQ?98(KB}x40qH=zE7VxwCZF=_**du)&fQu<3ZiwiJ(4j$zl_emFX(tm!}sL&mrB~0 zzuYFuL$(5A1s&fOfHQB(f5JtczCcASIuem6Dlkkj^i@{qd&AiD&u@v+g}4o0llZRKT)>LGgDh9dw%eCZnADxez_0Xswh#3&gV~4q5K%5}(p2H5A{ZjbmQ)IA4*JO*8{5PcV}~Hj8SAW8Bl?w1CMb18JkrDlc|E8Vf zJ$3{t?(aSr|N8N}2SEIeJKLUsLcBDw`i}Jxxuvmw?#VNMxvkBxXvm5^X0&32io+UU ziyvv5&4Pj9mI9*85fmkYGyy|e-uIrnWHSg*W>LP>Bf>r7yu{Uj$#iQZiwAoNE-}N9 zt)sq&rjJMQdqESl#xTc1RYCv~%*+c1xO`eTgy3Uhs~lTVA^_&s#VFo2m1XwnMd{3I zq8rTMVwDu#iDOZ6aTLc_8y1ooG2d=@_qfjN*`^^NSXo)!YePJbMU2(?|55eUQBi+k*Eiir3PX1&NDVQB zfV9%mQbTu1OLq+@-5`P>&CoHx0K?EF64D{vptSN1zx#gPXFY$iW{5R>&pG?r`*W^q z<_IqFo;1$-J@DCV{ypgd$#2)LN7tYZjSU)|{R; z-`^2j7vdd1PfSHk6&dj=qG`dTAQKZFZ!DygD3#Y1k`4i$YJ>ghb$q%1lFo@ZR3PYS zLgdk;Wq7R4+%JJM{4;G-XF+i~SWKpdPAyLcg0FrM^N1)_7j-T@f38!EAs}n2tDudh zfc#V+7||oupp8bahw}`AAAchQDkU2=$Xx#!`6p}J{^JQPgiH2WvOuQOBC1NGwDiIl z!n6JGW;RMC=}qyX!UUNbaSTck%f||4^<0`2*b(IbYK?uJsqQ6+c?Gf60?|?@ATNP~ z%C7(X_g%p zi|+Zm`C_6>lU%TJvhze-o=DYJFr~AB=bQ(q#x$>kh!5~$8)9ztq2|*>ela425u0r& zkGe`#mMvK|X^aQ{iq~k4=w6FfqvCGiL-;EvXC=|OB0M^Vn zng0ZUaC;y-1gL{JKiOoeg6@_Y<>&*=z#nLey4xz9IbC$eE1ZQwRa9|YXvG^^urU^U@BHh~0 zuIs)7$qq`8xd<%~FN{r>$NDI6DJffeF>y&h2r7-Q$)v&;=?fZZY@}tgG@8NsIUK)h z;~7)05wll?koU8M(3sC7pFm}bgBa3LhD23S_NXDk7W71PErp~d?KnU6;U=8 zb;rgtFrHT)VBPqP1P|36w|tVbMPozATb{xGs5g=C0A00_ZmR}X=El6w{#Dm3BzmA9 z{rzn9QUKq{4_!&+w5tdEA6Bk>gaR2bPb1C`Xbya6Xceh8$p~>}C-Rc7!Sq54ykWxJfQuH+!rY!?dN{Mcxk2_fPI@Q40wQ!c#b;Y2 z6+-{>i!gN1*0D6xF$ZuMw)Lk7a6|e$U zew!l~A}ifEj#Zp85kX&m@9Ek*q_QPpPcAFpv;XXMKyimA+fCh-r}MIw8r}&>AsS8K z_Zm(7x3&sHH|2wi!I{`-eXc;CH!vb+;MBUjKht{)j8Bz>$}v*UAi1OylADW+?PC=A z^Dhq2Ll5z->UbrG>(^5xHN^NQVE-V zC{=V`w6x=HfBZ(TRb$2Flnf>RtZ<&i>6m1+ltZe+U*in0Y4n0#Z72|0^^42@%af|Z zK9fS)_9)po_cpvvB95OIZco_h795edBeIo25fu&AffTKHXYz{oI?$ZZ+3HE_kyAa$ zPn-nHO{+&r<6q#_qp6p8-OcHmc9!^KD$p5(yt^%K};a~OI8Na(8ci*yI zt$S;=AVkm9BN!X!ry&4RLJCIS`C4M6f*3Eui;qcR_NUYk>ahz}q&XHpXtRIbPjGRF z@ae$CcNOu~zuG9B^CfRi(!(QV(Nhqeyklf-E>`b-Rnmyx>7}ZR{canZYz*F~U94uo zQM5SB@*<;Yc4;)&$4Q*OP#|M^E2$r@RvZ*HIJ?P{`TZ-0wY9!k7QVZab zQWgA+i-$p$9H%VXuX?R1@*E&%yl2!i%~{avw?O06=~n@rZDtrfe&06dXFJlGGFdy% zX}AaJ*Wm5?I%@{_RV>9Sa$=S^hJX#P&2XAUojFF#f%BgK8TLRZbjT%by1_OXxeBs$ z$8XtOk8NJdm$qH)who>t^>_ho$rkGPt?qllQE_@-Vf`rtMJOQPLrwl%&L$CXTpO1K5isPBpOe5>(GSQ9U8}b2*n(=1;ELdE6zbsd zDp3T*+k|mvS9Y2vFZP#5l-p!t*dQ8K>!Y zzD@5~34ds*o0Zo6&uZVwu_&;mX`q^&um6wQ5!<5z`%ro;yvSS}mmBc>meZh8Tv2(A ziDXM`^3i+r?rV%o=lnOx5PJQN*KfbCalZz@cweh!sjH|3X?*z!R*bP{tmx@Yd7|#E zF0r_l3#SWZ@}E#nVEAY7_TyvPkWXeVY{iIVh$Ufku3stj>-UV$x0~TT-(0h|bIxAIb@(1_a#1F zw^#pZH&+m9+yk+oE-;+jAmZ=)RW4#hei{lqCbiz8xQ?=lp^itjZws8Y_ee4{J*+sj z-rSrw{f1xVNmX9eo^ud(g9SwJ>wW0@z)jJsD&dFvB!``I!~kks_iDgm253cx1~6ja z$rV<5P&mgLHYA2fpIg!@D~TtieZqE)5%P7*rt13gYjcOz8G}lY zEC(M}QYpzd1(bpPHI7KW62%FM*5u6j3HF04=ygbS!gTPJUIt-s_#9gwfg1<*GY?p$ z9@4YOg44k4FB!B6b+y?~bHx)V^$gBDAi3D;KPf#?likhutkuM`6kOlGL|P-P!~Jht zt($l)<)1KHASL<_8!6{l$8n@*4V_l$A%5F6x{5!BY~YKbJotZq9@s3o6m%5FNeRq* ze?mR|F%aX>7f)79a|Xpg3!369l``LHNcg@%?NFVI5mmbzC7PVF+@62YEzgFw?(2mu z{2p>z4AVVwLU8|4*`tPLmnKiH`f#_`7`dHp;KBjG8Z#}cE5`HY%V>?NOphz~-@xTo z-K}b5An@O-jh(LWgD1Gaf?L~smNV=K9&FXOWFeAEvgLUW?~fk>V{t;g1!up20aG4KMFO%u*5@)IBvE%*Hhjo zQT=FS-SV1!|I+Sgrk32qzGKWbAfpXSYRbI$HresthuD;&``Lh&RTqr$!3gijVjuj# zaMy?>78$yL52w#P04HXKp$8Uqf1Xa~@DyBzN+zipszs3=lxhXtRhL}A!h5Z^iU2O|z zh*{$2H2NzvE;x|RXluOdd+>WhnnG2`DB~X7{8A>itf(X<{v9fI%h96Q*AeFyr};h} zb(=y`I;(vJc*1Oz2js=&*4$@MW?4CTnGdKOCCdh!5ZehV8!7l#p}_=-)xOY&$9X;R z({`Sui{v~u^PEV#9NKt-cfy$GdVE|82sqS8+W5-n-knkK<2u$#GsK$%u;DWmFz%5~Nq; zl-tA&7m5)m&kh1kk^T&4>F$R7?NpRzNe<_sVQq5B$B5*`pl*N2}aj zE?^{nxt7fGmiopPHM)%BX3+vcZu&Z4hF5CB^mix;y;2zpW`M?~^_Wv0Cw%_(vl$EP z8`>r5khssj|9McTw8FX*XcevYD(9w}cKi@yd9QbySh_mX;=Xx}yJwals;SMGC zE&BmRb4T3s#Ar#IPB2eCRl&5DbV4J9aJ1FDfI&914QrSUM(ttU7!b?g^&weM6;6QU zQ@FY}^=~dUiRGee7=akt9C}UW9ODV1oYl?Gw+y}j1e?P zzDKX+@Fvu=hNl)(#<)u_e9#uX%ewH^``_ z=KAi{T9mt&VMBK680SQdDym6L8*$5SZO4!odXUXfHw7|t07N{|lgdGN285Kv281H~ zA~tRC1>l}?DLcLxFRk{)y;mEAns;Q;+q$v&6_A&r6UaUrMuX+|`CvinArEL=LZ~Oc z%O{j`D2MVkickQ^S+elMhSrQ`D2g7LGg4-kwG4UmZAK6QWK3`nli}tXqj<%ZKizuP z9EMD+RaeN}(@RU14VZ0I65ohBXVNsb-JoX^^`sBtJ)x!5K3W=#yd1>NdEo_PxR8DfGym0nV13DP(+4J593Us_6*F_t| zIiv-3ON;M%b+EOgA)({VrZWd|^Y)9`$W{m;{+~7J9X)!!KWi!R%Hr4QJ-QtJ4}cx= z+k>m&tB+uBL5#U1N)FHPab*)Q5*z>Y1oT<)G?WGfkq=XZ^q)k3smg9p(bjuP{SM7; z45u{f3>G7Kwgj!q(2H_5Hf@koE~^im#{gT3Z2(iB+w*Qq|B!!#r~xq8=h+qWT|=BN z?B<8r-7Z&*;`uq7v*UGqpckJ{G6;3U!crO4r~U#t-1A*Tiedn zHAzCps&lwgrY@d{@SY5|n|)Q&qc@v^WAJ}rZWK%2!WO*pUG4^z3DjVQSp7l?(O~DK zb8L~zr2l0!68CexMBH=z`OE}H7->db=3Yz(*{az)tb6yHFp8ompZ8Vi*R#FZmqY(U zZST=WM2-7RSBqR${;wd^SUcp~JY+&0x+qpymm_kgEL0K&o=5-B%TA&j$9?!{7-|ep zC@xZzx=^Wfz_FZ}-39>#P_Ps|Km3k3!+)X^g`+e@B{h_ME|I#WVu?EfqF}%VVXcts z-F92kz5XjaC2=Mb(DX6mG2k}!2S4<~9N)i|tb?8i&Y}I>HvH>uc!bC3D&=#QE}2L3 z+`0|mkxYZ)F}xb!ZedRWl^a5gQuLz(mtUi8I~6xH)?T0ZFRDab{yWz=f}CSm|rp*?lW91N%s{zQ?M6zH+us9l$G3# z4vLrlOy1!GZ8tn1?Ef5$#vv4&7=Xc1Z&O9HA2($1LeEB*B zIAvwx3^Uw;G;w8IcokCc$(auggiWBU4%eGV&L7Rgd=}H;{<67X4)+-To#USUITfUK zh#EJO%#@*%IUVFE<45t$#g?ckqFj39AdE17Q!egVWW5b)GSF$Ae{iR#*hgZ$kYE2l zUSb2w1-G9H)louQVc|AxGzeXL)WKmq)=E52J^{@KQu-$m)XQ;L zx9Rp-_4D_@AbKUCpbjCp-MBp7}xjo!x)_;}&2y zCnwhz(FU55`O?P?!6O%u^e@Kek1^Sgu}_Sc`e9n@hSS-$27;FqW{K|2kY9FIT<$!^8OU zW}yuB_4evJKlz`EzNnBi+?%&zJud_`Ct^CY*F7I{Kgr_bVX8t-CAlH#gx{oyW@ zdcaQaU1nJ&!Kdm~S)l8DMY(a5~wH3DEB z4s8*F6R5Cvjk!W0W}C#x^UvlkoC79YzrXy9_ZZFmp`U&w55Reiq6!PZ^uJH~I#2T6 zfAYAoRCmcty#LI* zxAo@ZcjQ2qu@ygYe;1Bw5TI6br7tZ+s0WMxA*c=$)!53AVu0?RXtPT$x5m6fHxo2) zg~z%7@OIP_RO9qr*Ns*%d|9KAV( ziS0&rNB#X~*!$EE%f)=5Y^Ql^7ymSFqcmAb$n$qYPw~DxuQVm9$K2&5pf2O6DdX;B z3BDN0Z)XofSck0+8`>1ad{4Sl{?OJ`mP8qf2>an)t6?yD7j_Ve>h-}r;RBh&$i@ui62oy1a;ow2^< zd&?y0bjDVLEARBPFaD!_&~c9pgdkiWl8(cpR@L4#J4<=`>5T-Dci)@Dz5O+HAwJ9% zj6B6%>YyKM(sAa9r&Z6x3f|B@8S5~x>fD)WlPIRp!Lm!mJcaup76M6){uh1w>(Wxv zySHzfsL?}1mX`>kzUGN~&xs8KBiU9i>gY*en3@k||Az(m0-2G=)=@dGeizq5zGk$E z@6yxZ!CUZ~hmlWMcIQ7-SDL_t#0$SGMX*bMw7?V-CCGyL?9C0GPI$a{F{e;0K~l?i zjEZ9rR|8A)fqK@&puy*Q>?OI(&E3WLm^?wq1Uae{7F{!BRPI~Pwu}SpvQe#TA z#-EWNM6gNF^!8(9{r@PjZZ%H4%$_kGezLG z#ZuTcn59S7Kkk7VpHH-v6hv#UD8(}1cp>$xpIIHC|&tAY0#01HJKnJj{@b5&o__R}v!h&8e!%0Hv0Tw1l$n1=mOt zMMfDNY?RNDE%XdFN!H8pLaB45O#NYqzFB*piTcaWY zPTG9!6SOdA!y>Enb@k3;7eBIAYN#JO`d{+UtE>OxdIo+=<-5(X&c;n2R4<6ibI`&_ z9(={20(E6hJ)mevf553H59xF-eHqBTDE?{xWQvDZF_F4~*cOd!gACHox4qM1W)VU^ zc)5dm$aQcZcsHj352j|wKOAfDNk>gKazrkE>QZ~63Tb8j*;+VlfDgCjxBm)RQOhUD zC|j=&9)&m{Cdnz9Xs$F(GUXk@!EBsdwF*wUSI)6HFK}Ai@u@nFQJ{W23PT zV%`eXrvj!UT8lqQs8B(R__JofwA55@FLp*;#6#TB6l2(IY&wa`!i7rm7YVyxy?hF?r4JO?df)%VhSsVQl5l#!2#U-NV+CbPL^

){3aqi1iNuBL@$*o*AoBU2!Q`^&#R4{jlMi}5fRtd=ouO2HTygPE;N ze<(7)nzbQ&=d(>8Ba{Q0zj+cPmSc#FpYqgiSD8&K{%&!=UA%10yBMOQ>QWr(Dj$7{ zWc2`=T;G{NP*=VHxP>F6k~Z{S_x3CFzqCrNJU(Mvb>EnI3J=Xg%}p#N!(_^6#?F=S zJp3<`n|D?f;lWN^?}dB2Jm?VlM*$E&NS;dMd!VhwlC4MZD+C=k0)k|=_k?h6{9KSp z8VB&O&(h?9#7UXbJmTWA0=r+z9h?R6gpD%~r)G=)2zpjNQy6AdK~P;MIib^~6=Z3o zCM@`Rh0=>0or{$deIPPdWPQ%OFx_t!qabzDD6VNaAJgPrn|0R5&SRIJ>!`^Ul1(P+XF2$$mp(jU<_>=9pM6t$|Kh;5)(~Yyz{= zYC|=d*UUb~U%}WD?R0L}7LgJ8Om^+^AKw5~{X8YZV6?7K@9~@G&naQQU02BPLB;|z z5Kq)i&O01BfecKNA!y*8kN)K>{S_n(vEJqbeZL~gCsJ%8u)M~xCVq1nu-Y`vYP^sS zO{>+)Sh4=ja-N+Nwj-#Yd-0{M+?gBQA|Ew3_aQhRQV7(5ttuf>&kug0#$DSY!XzgO zd|0;UM9In|K>cfe2rxvtx+PO=bcuCS4`}wukEpeK=qw~8#~~5Tlj^{bkXvYzT!Cy7 z*U-k244rU#$gi3!d--$Nlr1McT;YVF&d$_ZhTBQvb~GLE(fy&U6^b2JzpO z-s?=nmplMrfNHR%TgjjM2r^onxHD7>FGOc64b-EM9_Cya}#B(SoHNEP7=r`Ga;! z`_=12*A_HAs(Iy9235Of)#;>6)x7nKk6(b&w7jB!CG*W0NF-|<8MJ?L=>8z{wdsT2 z2C{S^a&Y%}N&|1Z<#^jr}k&zVkXf~(Q!1WP*u39(8~HgU3&yqdi#3O@ z^F2*k!KKTYhkg?B4%Pn%)U+wee7wJVX_6C2y|h7^UJzFC{yg)FuBRPK^Dsbai}kI8 zLg9aenOnSj<)tz^fP^DMER>O*H2hNk?(hO%SYf0{r_Jp43Ay%A1Il|%y`#Us3&OrOr&!H4w|+X5R3@hVwroUQH_=GLY=Pq}VEsTcblUh!-b(Ih?sHno zKHTj!IV@ zw=@#TG;;ad!S>YNt+k~&hdP^zz;psm$O4N$3w_lYXLCW|;$3fbUBHle6-a*FAuhdWx_Xr&Vd{h$v@+k1e$~GoZA@tRykQ8g z!)qRlP@<>~k;xKQ2!OCIysta@_-j5Uq2uM^i85Vr-0WzZaUsFR5?+iT4_Qt9AZyH0 zDYcG%tp%UbD{cW12DkX@aKv)9Ngff+2NDiduTt@U6KnDpgh%7YAmy87TDpV_>IfYh z6H`5K$o?*L0hOt%ARWd3dA=%oxp4cnMj!|D!^zYJFr}wN5fgu;#STFY;?Dn=)ZqwD z*epZMtQ2gJpeL^-FX}54LrYRIF6s-yll9Lc#8tBdp2DzUfbBOTI7(%a64-+D`NR1ns|U@ep^CPF zD{&8k#mj%N$u?aWwjXQ+n+H6f{Po{D+z#Earz&1Oc3yEnFRM4e`okWmeqq})EL)`u ze}kwWmb>!}u#%yDRy!?8ud51qnx_ABVYU4tkV93NeBc)xaI*GGR?QWt?}i$>&A&Of zdqHZx+MMstAOZy~aF@^M;mEi-TWi^2xA4$X28oZ)&mPE!r;bguK&(#w+BZaPGvT9a zC>nPDU4^AV{&aos@S-Qv&-s>bZe4h|ci}6B+RTXz^^EL2+xN4cJ|!@dj?tvO$FdhJ zw)`zWdNO_k-EdUI*#b6VD=8!!BQLD&l3(GyscXA+!gb0mFNfF!Rxr`>3oR< zt?ZejCEeZ&a0rA?vRCjQTG`WKuArF>v?SE3!uaOt;Rk%Z2Q^V+aJo&#^*^Kc7ynGU z3~$7d<+gcTS+-q1)&kN4JNPssq&%3LVKqW-CqzfWp8&+aS{ABJamcNhe$5oG(>^Po zinAR>A3l93n*juoQG_K5{aZ0@yXc>Z|1A@}Np8D+`1E54mvmtRHuM!TN484s7clYN z_;mU0&&S^u#0r}h*I-%GMLdI-U(+kDN1ZeE5e`c;QhZ!}XU)$k_$%#eb#f%a4>e>m z4~t&;Km^|{DQow@d0>LNilg^=!t`2>k$;`UP0EMF7C-}OKL9n`{mn0v=WCZ0G|lCU ztIo6n9k1G8V+iKn5_lH(Dvmm3p1pwZ60gOV7OG7naCL-T+So#Yp?S7xvBy*>P554{ zTwqPXgw6r6cx-3vhNI0D!=Q(e2XX|24(jQ_$Ds&4yB1}Hg1k?(o^ZJ!4IQ;K^ZLtkTGEPqb?Oz^ zUW~s6aFNmS;A^;g%Pc*SO6cD=+p>+74ScOyp}r<~1ar34=R1i*$xO<3L7>E|u1SbqTq z#BnMyn3IkQZmP#IDZb0f6kK0amDqDCO^|kz*lQ`J*n1!Jm16Hl@K?g@%SvCJX2asA zbv@#ID&E!KiSAMbb5uNp7!rxfWhIt(feb@LG)ataob+(+qeHLs$LnlNy_ez%u<6Fv z8Nv1?Q4MeX>pgrDk%|y5EYC`Uqg(5NX__|&y5U)N8((e|ecb9d_lUkWwNrp>S~eSH z#u|~RH)s#L|eV}{i7Hl9CzgWS|fHxBaa1%b2nmobO{_OJOG@0N#(MT2uMqymap=KBAhLPpO(vS@xEc=O zyjI#X9vY$RO8V8R=k-lPN!7(^v%9pAT$}rPN1VbD6P|+lcb&@aAy`VKxgPHv693U{ zE{1u$@}=9L$F~uY&_kY#g0xSokuLXDVuUeVt^0iH@3p&PuJMq4oLzy;WM?%ct?z!y z-%c7BS&Jy|Qai9#aR23C4G+Y?NC3)4VEAgiMJqIIYo*H|3~o zDxG?^`hQYQ^q|ysvv>c4XwPAXuoU?zBPxVY1J|v21CN2<++4S73TTz-;f5QQFqIo8 zz!lpnuJpoaCs^i8-kh0jmIq8`Y2k%;)g-bY`Kde-JC7wiJalZcTw}cR`gav?mc|6 z$1VQ$%C5q{A&+EzOl$?sk&G}Glj@-e?!!1FSo@!fzo+3JMcK=8cj{u11w{;LOXdGw z@!1V|)Ib`D$I+wLu+{am{S1-kv775{Ko?Vk{FcC?TSP+}H)TXOCI9gxhb`xxLT?uK zJUNz$s9W^QjKeGmxf{7Zadu~fpVdxzGW-6Rx>#f23X2`RpN{+fu9NN>ILS}?AYMDT zFA*@hBIi)OLUNA*;JfY`Sua~Y6aPcGp7*EULh{0bSxmU4?dA90!tL>Tu~Y^tUk{s3 z96K?fHaZ11g}NF72F5E|OQq>xF92HQ(;rw@VHS`;yo(!tej?jfaeLz^vb;tGj(pX> zOCLNnQ|OO+0x33U1rLDO|yL&{7-fVqSzx0Q-O= zb&Noc{n#Px7=$*&OJEo6^+8R&fH#Em$tSnzg&!B+gwrNIvFLGE>xgXp5EO?sbllRR z%E|GQ2@(NmJEfUs7n4P@_2UQ{^+D34ZX?k-12b!W2Iq$)fO@EygUY0tRb2Cg&W!yR z7%Wh;OU367jAcP-wWLnw6L zn{(QUzv z$?kv_xDgnQgI>%Yjmd`Hhxq`);D0;+p{i59Zfeb&f{v0_IqNLGhm&xAkXe+eiUDs- zh!0EJ=`Zoqc zjksfom_WZ$rZ-^NTQGWE{jU$))$^gpCOzsh(9ZICjlNkoI!c8YlG=R(Mq|12A_d~C z!mQ2?g4ucpnvsrfn2CVD9Jg6#L>?L3Yl;vtjCtpcrr0y2o9(HR?NQBN)E+M+Q0R-W zAlQ%smQGa^#y}~dRb`%msM0N{EvhICU?ISI44?wAVatyJwh#grb0c`nEi*Oh*Z=l7 zFXp1eQt;;4tvnHDZ*P(lNV#F6ZD>W|<4g59J^KF{4 zwL}thT5Qeivyz@op@K=i0#H`=tLVRvRWPm*1nEJ)(aJ2G*%<0UK9DMqLJB?<QYbLwzK#Ln6qjp;3 zM>((#E}2f0o=zV9w9YM8|NY%D0whw<=V01q2rARC!Z-sUkJ7PyybTz{XwrVzH`D0t zF@H9HSNULvZ2X)({kCl~c-)eK4ofNtDm-&yz#($`i6%rj5LQ3<&-{Pn$~!cZFQLAA zV|D5%Q=vF*wHo~lR2kZojy*ccK4H6yR|NcfC&$v9aE71c#-?w<`}9W#eMV{hXVnTV zlWN#~U=3#16X&Oa#TApmg@>&|Uc_IUo?``L5(#YbT-XWJinT1>QPKc()beoiqBRMY z%CdwD#xVD?Mh)H;Q($gR0JvV?``Q%!W&J7WjcxFw+$|%EHnO)PfS}g+>BlUn*FPf0 zqp`VNX%+o<1DRnbs-qtnN9;ZrZ>R=6Z)lC7!eN|BS9p^!p$;{6hJA{!0e(ere9_Km^JSTxK$yijyb3>r+#K6ae&5aEYF(ok%o z6v9M-zz6W>s6~r^pt>DsCn(U;lYT0e43{=6tHoFe@Q$#>TzcPQN#^e}rCrE^{X;V& zp-b3-0RvR~B%(?C_{DJ%+2SRYQwmOR9KF8Kc*kxE$Rc$E!-cr=MF;FD#W(@Q;1lrrk;>7{zmL&|C;X-V{%Ib&VpHj{HMj=g$-I&+fsqAsceLM>yJ?yymOdUJXDkh*vcnul-C>quG-N|fP; zw229T2h2cvLnwF3 zlFkJ$uF%r~5aA$BGfTmnss~aV2PKp0&HoCUkYHD&9z%Y|<5A^f3mo3agJdl!{SbuO zQp&@ekss`;@WD+K2Mvi_NeD`IVZ^maog6xo=2lL8!IwsTewOVc!T4n7adIVPdJ1~A zx=?&h)N+fjyd?2mej=6N_XJh-jbr?sNfgZ0C#;m?EL_?uT8fv-5qU; z@@Icq{bx4cqg}I~^6#{|_NW9MG;<=4T#iz3uJt2Be z7hp+wEe(&N8W#XCIM3b2kl&?I{Q>Uv3#+={eIQ#3EgThnI~JEn!XnZ0HR4pl@_ z^*RA9o#VtQu>zl7mncMd2G&T4X8#~#iMqf)__sku(k6{)k zeBt+O_Ki=HSzBCG&<~@ba@aDi4_o6G-^%$XQjA5S}EB%5fMO? z$?+;L83E9o-}wn#ISa~%vP0O>Xe8C02X-2^C9LX(KE@D4=w|C806UE6bh_(bG?tsSzLg% zzJk&*=XwxaqWw*+=>Q}HK3M209cxW zLxVC;1#XRaef{A_*Sc-)nJu|yE)*GOSD!dTBfrDW_VcixXk^&3)pG?t1JS+~Ptsm1 zRE5CjY{Qs3y14xWN%=v3f}zx#+f1nz!DiY;Yw4b#a=pJlh`_SX0idS_Jd)iqOz>+~ zchS1H?$h)1|MJSmUV`>YYP0#2(Dq7Jb2Lgu{-kS^=-j3ASufPCs5?}55u;SWBqxVt z29c>I(w;R66^AXUP;?0JRrA(G4JC2OM@J-Uh~26w3&}?pCul(qJ=Tg)T3y9}QIeAC z+E@Z_H*;q9qmZq_nyDwDiziB5aQ{zoXa%U`v2%a@oPPne>WDmlfYWrT=1)=>H0@N_ zV+Z>8UcUIZkZ$s5ty_MjsdZgMDwgvi^xjqaVyfB%LMz~|8a`4qZwtS_%LgN)K;v9% z7;)ORhwqbO@LJ71j`bKx>Xn*_MsDFZ65q67IlFk^$);4|h_;=>a zbF@mCrg)HhqT<3zg4RZ{QT6m0r>qTK7Tc`rLYKuGSGU4xydAJKX5bj)2=1$7r<3lW z*^#;7xJA4t@2Vr}kM&E*^4HLycajvu1bFWLYj}_lvZTe#KliIe=ej+6)r^&&d1-tQ z`<%2bYn6om(^RmwtUPB9wxnP)YcsP?E_9^FHR1(%2j0AkWoF#6kPmtX8+ym)1^}oe zKJX0gfOEsy+#0GEyQN^H>rFNi(0A3`^0rIP=tJsjmr-m@?0PiPK|cmR#9Fi9$c?I^ z;&#B|(^1z+xIK{Ki3Rr*R+W04WJt2@KovxZdzTwIn_W{bO6@X&D5r zO7(lSA-~{#&YHy9MfvJaiAA<5286b%IlYy#fTqm#S)|##MI9= zq@m*ffd8%%mkbw~NZI?t3)7TRCjQ(_9#^ER5Kol)WGy5;NS zEQKt5u?8s+qH^_C4zG^s3w~onSk&k98tJ3dAW;MCcQFH{D zx@qJivA&S|74{@9(%$$4L?LS{rkL{2oTXxNCB6^r#ZDQ5V-X?^i&VN( zLAs=*7K`rgkVXWg8)e@-@4NTe_nmRV4_4gsnq!RroEP9?oEdiTT(neR-1Sa3Y-j;$ zB0S_)xr4M7kNZz!e|#YRt+1B4o{e(~m0dJTo6cX(Xw=YjCCpjCBx-5j5ibJWvxW-G zx<~bq?=ODzJd3&nDgfOe14*4#aA@ZgwFgx~>f#|aPQ~j13}wLVbwgdfS?M2HrgjhG zXBy!JZoULF3_!sACUB@7SmMz_^dE7~UGNS>Cs`6(j6{&|RTo)&q=H9eO{sUZ_$TiX?Z@y}G7r1B2C?NF9il_!jC=lZLiZP}{=Ua%-0*ez#YMR4 zKC#bMNY(w%S8O054f$rS=!U&|_Bw_Vc~O^m#q9?}b1!e1y1il_XP6&?)UTbp;EGt3 zXuYKx zW?j><{oZTCTA-NjubXi1s6d$@-1@}JQc1fK)F%=5O!guk={<&axvzOKe!79!K{RBe z9vnb$HJ@iFwr(v>(5$y#o6>g*akghP6Zj!$95No&tzhHgxEj^8d!}rs-tEQMCo+E5 zu}Ssx;7_!}*=H5M$`D>Ikt}IVpD}h%RT=?)vbiDt{L`f_AZa^H>ZUDZ;kb?BNdw~U zxAdAsMO;nDppT4Pug0v=H_ad)<>mgaWi@jxd(gyJ9tnImOeGIOA)~)@mV4qzY56HR z^Uj>#G#+l|UAJJKQpOQ`o>JKjyXnw(^Uj=PBTj+(l7=D4{9_QGw*+|!gosJ?!5Jx* z4YT^q^102BJI~CaLcyVu-H`j0mVO!L>pvtxKPm}vRgSJG`xF@x8v`yGe{Z4ni_jvQ zxww2OY>6AEj(tfBrr?6=nImX^q|8wKMcZ*Y5Ee^I!Hca-%P5#+2zx(GXYy$zuF}>g zoBsUOc6*xqP3KGUGU9Zt=HD~mc!J+Q@@Y%yKWTYeb7QC4%N#oZEEWxjxBVRQcwpwT znoQ~V-~pJbv6NCm1$U2SH3W-8pMsQ~1m@%Y_X)4N)|ZBobebmhfuKuGl^0N^mq-T) zA3{!In2G9Us8kve{;2F7wN$B-B6MfCPk8iy#xO1=AjXdEnj1@n+X&wY3R;yyTf*Q# z{KITv2;2-4U=6STu6o1vOruc5YAoB>VvYmS>rzKo`p3kF4g8%BX(Y>RS@kjwL&Iq(P>^~=O&~WeUg>PBF())Rb9A2 za@{vAXPvr)_SrgRjfftkXS=S0r~x{ma(pb+^P^-!0Q!>z&^`v5+Lcm>q{v$8YU%fC z&HzUw-6w7#25+DXWMRX=yvhre6&NQ%@Dt@B>u$LDo$o8H6ixcd|?Eik8)BVa% zL4XHk1iv4%v0xivgB*%pG~B<6LWyjQ@0R_UlN&sX`YZgGBJ>r+WtDwDSeU8~+d<)& zQJ?~@nX)f;$qA28AbUDqgXklrgN#c{NG6pr*7k%0Rw4S%dxQ;N1s!kF1bl{k44Kht zOsjf{ofiIgF&GeL;yQwQJ_Png3V%mG$pecqzH_>uo<&NsTV)PUktco~I1lg&iCHsW zDjBWoObjWi5n|N`1a6hSn-$!#`fkgk=Pz`%i+QC%JjSvm_G7d>xHSUaRn+2f5h zmi14B(Q_#879G`@axs)IgcRv$tX>l52*;jAt3l4*D0kK7N){j!Y@UA&Jt~PNr!9C; zyE6b}?DC6S+yG-W|0a3v!j-&3z|Vyo^*_>EBuNJ$gKu=L*ze zh357LxG};C80iU~(<)$6k7SsXO`PMYw{s?a@T$yjhVB#<)tK!T9ZVQExnp!fPvZ?I zl4icJ>2a8Rmtz;3Aj) z#Dt3i{_3if^L&ddXGDGXHwZ{0_1Ze)!b z>r(Zmfe9?4Rs!c4uu0DQMbw%=?SY&aA=?hfxxyScZ@nW6!^-&eHHAjJW6b4PCWQ26 zUGdKDO15g`I|Di27s;1*G5UaqEx?9TrJ>=q$?J2%&DZ?@8ks%C#HER1UL0)V8z+R~>Sj#0X9~qW0xuqV?pLhNT z8M(QLJuy%%{NZF{+z|;FImX)b4sul?*&w>--PE$M?E~BF%8KV4&U)h(vHs!=6AblO zenJQ=3W{v7GA8%>bbjms=H*k0w>PdPHH1DeflJHwQI-GbejK&q8nA^XSf^h$m7Ewk z-adub6LxofKs{TV=6S}WaFB@d2(%3~%{vDF2%mbjW$a|78;Di*(l$SnDNGS$%abvL zmV^1ngQ4BFHd#2FfRhW0yL&t^bcw~Wk!^7L4wSrcgc{i(GBB|FpB$(YE8Vy)ZjO19 zNq6Ym{Au#OD!38txOQ(j{eH$p;$m_0X(&xV>urFQ(&fI4T z_|$@lN}2LVMff34&M)Q(O`Yv=c*ly~`<4GtCFneK@mxger<=>}L6+dMYzp4r43GRi z0SgSXUt-X>##*dCW#lRs$l2y;*{X50n4L${#RIO*lr*+GQTDrIv0EI;pH7&N8}<%g z0u)A17rHn#Yle>8;mSW|fLH6nArncSG5m`#HlhQ5jmcwmDcb+c{pWf^05-z_wTLqQf!7DqeD{6}m&CV`A{d6Y2e++yI3NY?;7>Eih_hoB=}7*N z_#EmUc)a3A4^KINAK+ZF7G6_ipw@Do2iXF8%EWAl<5KnmQ)NMXLA7M8-=Y20Fe63;??m>uw zy?x`GWuMx^G2nxoP3^A(#cPG~>RPoTL@^{{$A9+3>L-g8k~?0syXAyd-qp|0Afh9f z>EtFD;+w_UHP#D#41WLJ6vtsR6~mtc@Wd#fWwt>`=9Pkz(?qhbyN%mr~bb#<9}M_b0(_*z?M%r2J_hnlO1}O zOuk^L!lJB|T9NV3>8*toLo~lDcA^j-MnjYuJzUvHU84~mR6=vuFi+Tl1b{zv?zb}v zF$yW*siFdQh2l#t^c+Nig>vfK0W=&0`y30quQn|=7e-{-fquq2>OVN{AT(2?7BjXp zS^hsZVh%3Fs95!|8eNQhCLExza_Ku3gDijEL($*HZGMJ=qCg~qG|J5N8DHoP9XV-x z?sz46w@?!jfbI%Z@Bo~+`cGND{sl4;zAtJL!Vx7P1kKg zCRZpKr$?pN+9&0(JcIe)Hsn48wW5kzZjP8K(vH3~sjO$)_UH9>u%V~%zX@RD(^?WYxOn4uPpJrVsof`5_*wc0w z{ei-U5(`g`2Zg=?>tQ&~a3B6J9x$?ahCGY7a<6X%?#XBBTP3N}DJFMg#OqyR!G?yHixPaPr?(5)i%mt4)DE^f37Jq0wZa3f>)& z1MnKcg3s4F9U#!bOS<&3c(d)d>>*izQ7VX9Yy+7P7_5ep^<3*Ak7?Zatd|1U&QaWv z40JP+2#Wl1XjdS`=rkoI`>80NkjdXYl&>@)HstZK9QT~PDdi8-HF<|&X%(elQPFtJ@2PT1xM~X8;i|{^! z3XHZLrH6FDgL&IXMv=g~M33dcv($&zQ-4>`GeoIOhSl@@{VVUv%=f14?AZaF?!ODZ zlxkE>xxoRmwKY$N43(w9b=~B$j8U6voW_@L&X~4+;)P&8e_|!DnqkHZ5ucTAcQ_7E zO4R#`|F8Jt7%G5|@69Qci~;S(e~sp=9Q{Nm>!hP!`HUZgAzV~;q4(0g^?gIwkj2e3 z@tt$nb|@(Uc-yQ-P>SEN#e4g{8Q9uI5_u3I8T*b9R}Q7NPsayg<==vmG5iulBb{*E z@r?j=-uD3v5M^bn!r#6tNWt#nMK**!mU5mB@xJtGpm?3JOoYH-0ug^|qvzo%{}(wW z719;wg1io1~J>~8@eDRvt#1w+XCsZapdcuI+z63wjlQaQ8HEMk=j+bW!)~?f|dKPoO z|9ett4fBae_)SO=8N)7ZG+h*Cq9FICRBor2I$Aa&1J`F}Zi^PikOSL}FfbZap$RlSrFkIR3LE2i$@sL zR1qS@7}(h$@iKNHqK3uv`=EZ8%mrV)S1X=WBWSt7g2=TaI3LJjXJrY2BWd&fl8e%8G^QBSMiy%?sFs zm=BD{)icr9tGzHB*KN~)8xFbj_o}`)P)B@-%5fp75&&_62t(71DgE~yh-80STM=1{ zL*De>P)u)*+YfAFV-p_pPI_8?T&7BpgOYz3i~C1IYgWtL*mC-P*}|uFlA_0n^q{eRsj5pU%Tf+p1@-fh9yrA^m@|R?Y znN|KU#1Mu5%=%34@YAA^StUL%??n6#Kv~qZCfT0)HQ>9=HAsH``77RMA4E$I zQ!!o6&*0WA0FfNn0oKSBBOsz(UG_~0fNOC^kH~GJt)8z@uFp;Ws4w1MVVNoxe+0vY zFMHgH+>mYWMbK#!*UF?`X9Ydi0IPg!m{3l5-(n3m9J>{^QTop=H1B7j6E4QozuxE@ z?R1>z>`VoWb0cA?G3z!mVM)u)R40Fq|MIwVEdT~8qZE%lUuC+}VO#idi}L^NdSn0% zrB1v7zv#`O%1eyG3MAP3;Qq}gT@vYuPyhZO&GCy-6{%x(Qx#eDaKz^8|6ti@e`?si zYk1Flq(~bkNV4wSh9!NyVvGTX33PMLX}oepK9;^$^;M#_y)mVrfz%Ozv<#uBI{sSa z-_>d5p4JP!gNrzoe8uyMzUyO#;IfQl>CL|X@DjuTgJdWm_$oJ-FPjdkuA`r*{%16& zLx_l03bz1E0yjxdlU&b%fIGo%p~lt{IJ_S#dOhwD^lrc)BqNktmt@6sIFViUAgfc3 zkRh=RDzM4?flBC0PN5n&DWIjtkib4N5|;rE6-ZKsz(|9!C#(L)H%TisUr>U`l%0IO z_5h-WYxBaJ;ExkGz_rh8=az*y?yvrvMIV>rNvBWGs`m!eo3eh`InY2hvRl+_dTt&8 z^10WhZ(8T2w>7kKs{FFfe->$zM96efs?8g0n4q5KL0jxQ)@!n{N-#hA+qcQ4Gp0+f0(-o}7f!|k*kFjs&!p$sJYNKgX zDFy$59rGl7IPoigM3hh^UN)NXa|Ve^*H# zB$#$!#CJsn3FD?B9b#6%l@^YF6=V`;T@)W_O}pQd|A!KIR@{_mJ#!j{8D0qyFmQ9B zSng(j&fsZ8i#LIYzgm>b$0UouY(Y22L~E&+*e3};>ree~Zig3bEmVhGKN@exJQnW~ zv;~r!qAf6RHcLL2e?FJ}^j}uW{h8^t;f`r9ZW}^ZAjyEO_#&~0R zSD(k-7ZD(+lM_39f3g)4MbL%jCD%HvZ$V8i3vvCL#`E(&>}M-g*Jl<2cJrdDCH(=s zRYfv~AW-Yt4^0xBR|G^}9pt92NA`gob=dn4pe zlEk%X%h)3c0_X2H<6`zu7O$96qTbkvkizkXe+`r8QICZ=x!1NXOL8$+|U0B1)W1{w-1UwVy|T?D=eJsjYLuqj~6d(mOw?o z^=?8!X#bZ5m=eRTXn9{IskiSJh@3ob2>TUd9TtvG!qd}-bRTSa)KxUL#CVQy76!S- z0QdC!^Rma0DsWj_yX6$9+rOOKNdHK8_~HjSCrs?c9pS?XiWRslK0%~mQrmIkijB{i zD@g@^$pTbXWxRSw_?w67BRSr@e-?TfJWfjbA$t4#D8g^Jg#JiDB8@!9_9wQ9?Nf-h zvGezCXL%)=iW{dux1;wbo;eGyErHI}Bm^cu);27hiN_G8Tk9$;s$(%Lk1OATQpR!* zZU^tx`6B8V8M7i!AFs0wn1*fkvx2(4x(>t-{3Q$2yj)X^-12U5R5BhE2$^?^Khy4|Iz)4=52JzjiX%_thU>Hj@#zpV2oDGACHSrp{Me51Z#xOGgeN@2v@$oc zH=S~!k3Pb@O%xXBnqNoadNw#NZ+(M;Ca}a2rv%aX;~IB!POg7MMmoJQnJ|doLS;FP zj0~imOtyW0Zqzm1S3XUlKv>q>skhR0gVx3-4tJ%%(tMUO*l1%NI5?9&N2vk@ryjW@ z09S#ev*}heI6McNsq8nYo3(AAi?fc*=?MOaKUNgrOCyWS5jv4JB!ADgwYcBRIa~3) zeU8V(U8X#LXvaO&3ookh`f}M6$`-0uQAN;OQP-gC1WHr#-#^?FU10I*`((#iP$2P+ zWI(i3=XIH!nD?Ktx)2^+OBNVjgr(Mfi0g)|bLe&JhfcxYSvs+nJ}g5&QXp3QX-7s{ z`E1#Yk?$X(wnI8R|H7Z?X>lc$br$IC<@;xAWhh8BU6K59D@tlL{@8TYGi98%WtQK~ zD;7$Y#f*BtP{#~XOvJcluj)P9TPCy(Ztv=ug;pkH!;eAd*-}}atbCh0 z=5r5*ITy(hKElzsoKl!hYChOQky*N@jk;(n&u@UghEEU>jV*x~m2auS&2aTynR{oV zF&}J)k0Bwk6Z7`UD~5jrt@xN3Y7BbwtxhF%9id%s*>XNF#Sz|D;?3v0gxcqOOz+ev z)}B3^Ke2kXkj2|a!_epue6+?RCx4az^BYxWzb+iSYN6CtqjgC;=0cpi42-ytk407e zb>^x66!#R9NJ1vR^sHe}Toh066r-Q3X)h5RPbf&yl5`V|&71j@Kjpmb(i-@-N-Gwl zO@VeXHHLn1^PTO4rfRRsTJ`&;xXA`_apW!~`aVj zk5UjXfNZa)Y+aPT^Fj$ZX%4PcKTzBPi{iGBLq{}Y4hZ^rJOavZa4=+hVRbBokRs*3 zx1X&+(UhYLadkAHvUEW-XGEW>JP~={CcStyv?p`KFY=gA3>}~1eJCaC8Or1k*ME2v zvF#8KpqpTNOB=?un$52m<=-xnNUBXQsnS;j2NAit!VU5wZL}n%oo~$Mqp4QUtTAPAcpIH7C zjF4K3(9JoKUOOmCQ^23HX5WNa9wcMZb1CexeZL<17hzPBq}!9jJC#F!*ayl*zk2d$Mk~{x!!QWB$i$Q*^vI5%zmBFO7 z7+;Pn_eU~6M6C-R2XB^Da9~AdQcNPB&#L%*N7sx=X3#88e|GxK|7VA=$PA=J9!>a{ zMwP*`$igjsx$|mDRPu1#k!c5G%#ThNT{nv3vLKW3$ofv-C@Easq_^{7VN_^w zZh~hb{sc-CsHlY{Oq(5M#(qq=_bQeil=!CMS3G}-F!{9t37VqjO^o{z3?Cn-gi6aY zi6uJWE0fDFMxHU}IqFbn&3_qW>1boPnCvr7B5N&#kC?S7nmK=Wj6Uy>Dd*x|UDIr5 zs|LwJGTkS|$G^SXbDy1oIrHSg*6E@#d6}I4Nr_IcHdw zDF)a!f)8Y&5>Ts>AVIBLW4p0M%<2o4k=Ia$P|@J2^zkZAOQ)|ls^vQYxmpwB!r}R8 z#bZ4@Ex-qc(H-sbBRNPfm;+{68N~0!`ce7&zEgqqxtxR|h6!U-eMNk~puO!T#dk@# zjl>w$n6sPBuT>J$^^>gAZ!@?|SYc{VPNx;w96Z8#&G`}^}vFppkYFTxN@2{Ege}lZNVwCpVs9N-@ z7{*1GiSIr&{S)1si$SA^OvB=}`IbxvX2Rzw+z^0e;bLt%q_m<9X5xa6W;rp88TJw3 zEj4)h($lla9u)}33jyLaed_MXVMe!4%)tF|xJN-li#s3HMHVl0LYVF-^sNy7Z(VBi&*nAe^57UAds4M@wUhf5v&rRCk8Pz!L?7{`l_T7r4%>4v zY14gkZK6E=+Vbnhv{;&5RJ0uN&E&qNU$j}!}tdZMDf2mB~y=9fWH?Vo__upJjAP3 zIdf$ZV@Y8b1DkT-RX<%2`n^SqS!KXH(8fgn%_&0g@uuE#;yr<@BbEQ25mr3QM7p!_ zKiBPo!><9=ydAG#o$`i!{0rxD-zE>|csDZzcc=HG!X1ZB<%GjT8D!%}naOO6G2k~V z@pXC$V{3s*BGN+tv=;d96kC1gv)mHqZQpY(X%XBWiA6h0qiW30CL8r^<5GY6G3~pX zW0!j^%80eAqlrZo#xY!cCN|w~ds4=;at~javIqCs0z6ze2Y6Aw0dxovzALh42sM3B z6N^f|>$|nKJyE^fcb8(8dpDrDnKgq7M^x+<%phvA$TM%y-2x$@tzO_Dfre`3%%9RI z6?(xNlp4)nUzI@-)d38-65(+1X0&v?8)+0A?QbQR1#<@ zb+Kkw>@~Pcry8d6?}qy^*ikt7ADs_3@Rx?R!0WI#*;mX&<9!H~cKXFU^47nv3nqUPOoM2JgiiyI{4~Y%<0($YeJV^JEKW&bNwNkqc*rk z0$Wu)<&bs5>~|XdTp@>cW?7U7M3QDd)xjx)2FuBbTPI>#Yp~Ufhw>CGcf*?k(=63~ zT){KUhbWOu5!+T%>=%t;-)!%J$N2MXxC0n#>^NcPNtPklCrt|u^eq{C{cXgSMQ?4% zMv})_7MX7ZDrTv1ZN3@Pc5-NHQU|@1%LRm8`%F|AB)^vT_3V(-Gh{29zCZIfz-wTtn8}0!Ou27Zg zIRBzBYwn|5Ef?{DK48yH7am2#_c*>ywHw=KMs*I!eX{wB~cWE4VI|fh5<~2XH zGR<;1d#$PCG*&k$)fjpF_X5c4;(27_+)|UQsDbDGT&WbZQ|j~8xk%%1<^90S7i6aDJt(@kuD=u0F9p-hB2F z?O(5Fs#WcdIb(rc0S6r4e_cVcpV z!fHdO*~BRXo?6`2KHu$5EW%s)Befc)848XdLS9v^8wpGc2MX3`72|-AIY=#wSmIE) z_BuhN9VEa<=*#?5drJ(;|2Fg#=LD!XZ*OaID`E5b;4{J2uxh-sbd0#Z2A=*i&p;w1 zf1C|qwOK>@WFADGEdhg@Vf;x9-z@e3Hu~h*X}IM^AJoF40^C&tR#(`#6per@fDn9K z#T>ir|5@z5eLqUPQIN;^?AsB&Zu~XRIahc)y!8k=Sy_4iz5`PVs8oMK8OCJEUZ+#W zF^$fE2Ium34Sq>fi0kHZcB=pTb;nq1@{D??{kGM{F1>>`j!c|xxGbbn{$8si=8b@S za5+u`%ujAe)}QcB;hfQ*Zo%WekG3sMG#772vxbC@a)@yR=}0#+Ql066M%`YTPXG?Q z%}E;L&O7&W0vYS`0I1h9bq^l2L4`Onpg>~Dyqm=(gUWHp=6%*DIV*o?flUrNy_NaF zMlF6m>HX3c!0Kg^)I3HMNC?_aBQ}y^Jjr_Tn~r%0{z|$mrRa}tnMQwe{gW@vpY!R6 z((3P%-l}IYlc5Q}rqF4T57h2e4By*GQ_w%9Pu&Q{M(u`RqqNc-iUIWa!Sw+I%T!x5 zFAcy9>XzYd9&tmiLHb97*F{~~Hgu>7`ewI7yo-RlMG+NTB>42(8(U;0Y=~Dr(`wVJ z0t-n}`>PDrvBprFW0%?VkusLFY9q>ku|L_Y~| z4$mpEhMlZV!7Whn24HF|I=?RwWWKUpI&nNJ4Vau>c~U!X3PI=TpJY={8H+`H)gdT9 zd`h5fkqC!uPst2VeCa!j-w&>X2wy2~>RY6u< zmJKS-RD?n(S0tb@L)Ph!8`ATj>b%Da%dgYd(GaUNU-4*dAu>F%rH<$T^+|E%w*=rq zj2EWGGi9qVwpgbAW5XJ}K##zzi$_6W__7_}msp5|Pk~uY`}zjN&E=GLRuTY9!uRO< z8@QZ500_4g6{%5ibG zrt2Vh(;kBu!LP~Zz0HmUJqIGkRg$Q_tjFV5_b_W>Wm`4lKja4)horhJHN*jo*=LL8 ze4V<1l)X}+ultuhosGLUv``|ZXe~on$lv^y{PWKuk@!kV0ldBx^@x8NQ;KASInwlz zOp;))ruf}OH**|+tu8n0%y^S+bCMOdNFa@Ony7uULI*w2yT{EBsA~kGglbg(!FOD$WdE1@m0V1J=-Iovkekjjn|at5H7#hk{RgX2gH` z_Yj^PIJ=$H5I=$KU!E?}0J2d-3J?>x;N8D`3 zWoNwObN}IMwr?K~jID&hnK6_XjdaRlp@|ekh~I4ha*XhE-uw$13-?kMnEHxo5bI8O zMxJ}#&sB(J>uMxw+uf~>^WD#+toJ*cnvf-mQYP;={u|*5qo#KZVXr!JT%uCVP6i@D zrQgIBto!G)xU@6vBfAH~r=@q7sLKYkdUM2s;g^22WH;3xCpqe-P!FHX-)2D? zSn!=gg0^$QJWpu#2Uz1tEeR%AE<&I)O6vFCP97f!a>9fJUVqQ%QH!s&4rz4!HZNjb zlW_8G=gH+u_cqwyyQ9s1mrQQIFuJ!&dBA9SUla7TXS~UzG`~KA&0yP8on7ynz(`z? zfSLN-26L_cgSrLEl%Zu8i-z9m!D;XZwWAc(hwNc1q))03)x&ZPx#q)id^Q~UsQgIc@d#*7Ogr1gBGcWq&>>8chN0#GVoyXj|hxnT!uu) zHts!E->>--Kg2-2^(6IjIcuBty;_+6t3z$2hy_C%(?Nkq057 z=x2w;=oedY0c;1pMd%rO=jZ_dy_`Zlw^z#t3+sX#YJAcJd>+`4Q z%Y|VL#KjnQ6|HoR7$4P>Nc&@c4d-7JNmejs>wt1IXDse-7yZjAUxZ0`!H+^o@Wu&S ziH3xG1@$pIHoIxgxSQP}+=yawcUy(8iSi)yypn1uV&)6>Xa?Yf@SV^&_wnXuBsO9;ja$K$@G#^RPNMB6g;IhN_iH*u2nKSh z(01GX)&|>2&?{9VydTJE>P2`N=<$lJNMv-H)@itEA$kP+4D56C-iq&Je?`m~rU~Hx zfTz}+!T+(d5R#`(7vU7iP)zl9DcTcl>yzl#qOONbiYd|$x+|Tp{BSV%)N5!oG|+M{ zPq$Z!P-|C8%OR>zCne!6k|8B03jh1AM68H=N!W?7S8oAop!Q6<4CYJC5*=;Y5cVUi zX$y=-UpMCjkWGDM1U1Bny7+<0}IWdaE;@v6vmCvnYn}M&nP7FI(wy)ouQh~$ReJY zi-frjkGJrf{PGu=@;Mfy%Jy|r2eBdMp207k$jKOfVw!0FA%E#DLrObW`Z!a8$QGI> zc-QU&a)u{Q{dA5*5778N@D`dF_kLsvBDT+d1OdR7)rXD?wkz@awF+3ZF#OefC_l@` z%8f}CwG&J=?)m9~vk#jjn+3&BGgtf1$&ODWfV|~eAHv@Y-sIaf$4Dx}`1o%3M`Vgt z-CO=%OUc#LL%Blcy@s?q^PH>hJ% z3XCbTS}siH(nniea%JPK@Y{e96#mW=u2quq5b(Lf6h1g))+#!rJAAam5X)}I-A!@Ud8FY(2&&NZP%Hqfo_sffa2{$oO1gHuG%)R`{%T+v< zzRkJ=Y>97rv*Mo+Tb_e0Res-{0!}Hb^g}jJXWx`cs@d-`mPh(4=|gtc?q(sbMZ8Xw zN@B}0wpDk3O+WJ`E>~{X9F|o?*u?BO{J#D#Kl%IH#B^!q3i(m?MH;psgH&$TD$T7f zAdXo+?C=fzWL$b+(Q1$?4z0N8wgR^bt89qm9gJ5_wQJfTN&(KrX|wuwW^m_$4_eeI z-CAfJ&gc%=#-&_KAe@BmFUX8>M1I8;j9lSr7sUIA0X$F!;wpHY zj3@R!#FVw^*meBL)U53WZ!eg*D=dfbspBgOp{85##mBdP#DB8$UfWg^AF*}@w4uv|TD3p#%8egP&9y!+T;U>fbOQ24~3*T(9>sFxI z6usFtf~|2pP1=E_a~_=r(YKCkO+I;Sn0-9lxg%lC0!41I9iAtaSXo;;tj9_ZJ&GBbOWv8CBcJ0j5SE2X; zB7>iKs4Ekx015Dqu2Lx`8aAHr$coZG)5k;qJ~J3afNOy;*Gjuhm= zYEW{G_p)HULOv|pbBoM*Z443zA?G&gy|~}MkEP&fH1KJXqMKy-{(n20AJSX(%gYxf zpuz3gH+Kqz=&Hey8x_j$d<0p$zLjW*r~Ge%v4ePBoRSpF*W{4=RNj=|Ql}hFnRF%& z^N(n&xKp_Q)|B7gc^;cZibx4_RCPI3yI$xcT=qw~v-4*L7zOWG;Lu?U!YhTlI*jT#%N7F4}hZlM%i@IlDnNu#c9%ynkT+p*dBY&a?W zA~;KRjHmYQ*P39bg)&7kJh*|D?4GVPuQ(PXwPrhfqZu0 zl1Vh5Wr10joSVmN%jnf>D{(qaf4TA)TiKMwxqE7SN%Pd#8iQ_Xb$+RV`-G;E2JoVs;l}MMrW4PROsQHY+lqGf^N3;#F(2oqij(l zV{1pjomWLCdTV$>An+wpbV?8AO{Aow;uk6qsZL?RV;L1|$&xOO_5nYj@D3ZupQyx0iHXat&~g?j1DnccPZRQf#huy+T(myIo0=(jSzR1Dk=e)rii6lSP{`^ zkD{B+Y1UMPpLuyHwW{r_qLRMQsGaQ4iKqv=d(qT{>emDU)?H=}y+PE>uui?SXdP^g zW<^O`g|@_c_mq~>A1L;pv_B>a*<*2V=r*2vy2{>BxaNZ8w^|-6vvM5TqFCxv13d=+ zYLL);5I5HE6Ky8^eA|KZ`IVu57CjICV(ZPDR~5O;u=E@8?x1bdQzJ=btP;%$lnE_n z6i*UtEBPFEY+YK6s``-?qR~H^7$tQ!I}_#Jn?9-bykiokT4mrKexXkJv|9KKL>0L^ zHI_7c!fMI?l9lQmN%l2{DYY$b_`PW`&+~BYlx0PbDBI+BR4|RD`n4n*g*kg^#u2DQ zJjA^cZFT-a=`EN(AA9V-Xk<;e=lg0%;#=~Of|(gs6}$Qgri;YugK#%de6g1@eK4WE zscZ2q(lQ@jes@9Q_f|X78x|KhNtrvPG;Da=@Y1?1UAdG$K)IFvh3_pBAW=0liY5_C zQ*rgS^KoM`gl4->gMw0F4xV-=;zklhQvbAzrM3ybYIlS*lxt(9&gw`c{ zQ!Vyq=1+0$|G2ck;zYZr8VMQe)#ns|h~js!EXGC3ZvB_vY|w1dS)bZXB7$BeR&>b^%~k+eBxpu1%45>6gxbb}NjVcDC% zOt=)lw2K)Ow2ki8eZi@>5!c_PDbQvckcb~#=8g!PwcIk+P)*h2{2=+CIl^87>F}g3 za?in+tR1;;74IqNjoO|Ssi`lt2=&E`Y@1`*sdBG}3KzD+a5e=)Bk6S&D8=(2FK#Eu zUO#s9AaNi|8Oi-J9XE6j>ZzChcwNg`@;USxuJGerS1(*Hn(Y_Gi&mzEN2&di^tr6v z^dsHSpX^lvuoHR1hMMaQ)2E&JwZHgexIyj0#{bIBtpP=Gr^Wd<;S=k~t5oUV5yL1u zaxSP|R~{>e`9lBZ*DWXiBRL-BVJ{;9*!C4!%FmB!Z-Q#x+ zUx3nFHQPtFiF7xC>r9x8AZ5)aCPFvdZ#fpK?-9k|u0O;i70ck) zLb0CRFl=F7==K~QzlKezSH*6cBM!`*D41W&xNBjpyFmZzx>_a;D5Hc=%MO2`o%_!t zRw%qaIm^_R@NWuKcabWIienPXvL7Zn{PB3cz! zS3i>=`%(}oiSS`=MzIeaR&pi(D~>SKt)p~>p+*6z=?gqL8azHuWdlvGvE}GYs(R}9 z4+Tk=pMD3k8@mQhKQ*yGsD6?LJ;Z*3x){?_f| z&AFU*HLzo z@34i5aM&~WHQ}&8@N3L}cfNO_5p| zWcFp8joc_udbqoj8)9F4hW{sohmq+x z=Q-N|m<=cl>t^-;z5{KT?tjM5e;mRj;sO5th};|gVfICQs8#CM`Nw;gumW>_q<lUjpnE}a zmfgf5g=GR;K}Zt%#ws)Du1UiEoXP1bE>HG zVxkG=5=O=0bCHbpqmgd)efb@tCntD}B3tE9X_x-1RNJ|gVLH3dTFvz<4s)MyL|iBR zLL3~Ti@bO}nXNy-hNQ<5{RG0&=m@D-LGX9_ItjJ*qPO~v2MmHH)8D@FtH#GcE=R5x zp%V0Kx~Z=*S1y~3Qx1tmmsncB+inI3ibQ5e`*Y|Y??^>9!kO_8oDZXmltKP&sVn1Ibl#O({C!~2K}SDZDUXR}!W4PEQlw%~bF-gQ06zim%h181Nse*822p)eET5w*an7_w zC?IePfPLj>H8GD)VI3cepFRGA6Y}CiUdz6~Bd?;cUNRy)ak_WsT?Tx3GkQm-_Jv;< zyrF`!1*(13X6^*S@t$C*WPX}#O)25YxuiQjCKc>nkThom~4@8EXhg3_F0>u;@6 z0$C4d5eG!+vXqy;rsvEyLc9=BxeZE4oqDjk^HGn-KrBkTmCZ@bhj${z#=|SY&2#ix zbW;kMX$L9znY1^h{>_9V*UO7?CM~TvBM$YF2UG41Yi3FfwwF)*m#VyN#t=eWek+uk zNAInN_U$WGFJT_XWzc0cf5waHAlc_mxeE-Ku)~(2%k;TlNB$38XBib`7rlMDJBRL2 za%hl{R%uD4J4L!XgpmP6kPZRq98kJrXprt4LZrLpy?Op`e0smJ7Bj42&bjy5`*&Su zZzSr!(!g+2asn(5SuvV|7hOt`0-?TYROqbCjn)$C5mhMKAr5O*7QUr+HQceTb|V)5 z$ykSEwgKW8w#?^0sQ*ow?DJIA|1~8 z`vmX2W}h)|=wvJFp67K?OQ|Z3dG*L*^rrb=M1ZN$`vZu>(QL6#*DlUC6Qm>J0 zog_)cH3u8H4(a3f76R_qDz@)h(y$ayag=te_+Ng*bG_hs2u1$8MNTB(BGlRw+xJsQ0Yr1w;3*tQ z?smml$3vHvn~Qj1L!&d#IC!fwbbDDjWcL9;h2SJyfX$a0^i3G$T`6||P5Xn5sxYA0 z{f_fd!-&2aqrP&t8)ow@L3o%VvLei|FWPSv*PnUY&(q#1P8so~1*a9)dgjDo7Wh+% zoIra%9iN}U>-frHJmnGVTs8=ZAXeK&O8e`h*dr!~Cty}TXcAR@>Q{mNenfR7p zAFVVVI1}NYez{<%(Fn`s3xhu)z2}>0GhVZfwAGy_0y{yc>3wT8zumi4_PVq`7e&B3 zqe`r2cB8FVv`UR9jq%S9Iy3+cThD)3^la!HC1MxHw1aNUP1nYT*V2T0M8CzaS6c56 zRm2L#ZSjQ0(%hE9TBP(}RW?8OpL!};STA(uAv8l?r8TJGWjwI+4t}JRdZ+nX8GRP=fYk5xcTUBwPsL`Vse|CmUe=YI8Z;O3D#~t7_{!pe1Ad)T~;I(KKbt} zab5hsx_I!+zK{4uy|z3rT3sn6EkoRW81jK%>}_t85*59oGqdtTxeBR~?KTw9`&Q%nbaRy`isC z_`6F~7=8LKv;RUpB1I>S67P5)@LN;~n{eHxu5Xt-&`gWiOdL0sbfr%J^uZ&p2G1*SOMRw7dXpQqo+@t zK~x{7#teDhp}gy06JyEh1@zW$)6?7<5rLhF;3p`Bg@%)C9xD23pU1vsHHT}LLea*m- z@H zPEb^8&4Z_ePE8RZNE+>=+l{KUQu&S*wCa{fpI+#9mX0RV?)IOs%JuTSLv$JG&Hd?# ztgcOxz+3zjm2|*YCBGhn-?~q(}#zY{7#Z3Jvegjivy#_|(Q~DTSX;^hz*6ztR*V z2%8Mk?}W|NYVR5-7)&b=iP>K~C@O#NfA9F}moNn>x7+Kw0;;Es%C%tf8Xlu7pSp6p zp;<@5Qx#7lWOhUA&tjbu3(>m@e$>J7qPah2dIU|3Vo&P4s@ziV!* zBL(}R7!WQ|#Iq-?+-~eNyvdQgWMJ(;a0*VB+6P!J-%4KS->z}Fot zlZ$IKQOfmIFq5>3EI4zM>o*F%KWCl@W0E4ulQ$T!b235x5i`NWTsPj|!c6xE=>mVa z$i^g>R!NM6xX=mW8>zOA;Eft56&lEv?{)>mp(!0w&2pM=?f|Apab98`H15FfkdAcI z%2vVG9yhr;MSxbzwXH*6T05i;CiV)n%3;R16?GUlu%8fWW!Db2Fwq$#y|Ss=H`d#1UNrl~lc$S}JBPxY^9_$2j?1egfwiM&=7SFppd73x&{lvM zu5K==`%(uxrkY%I%uiULkh=Ttj6>;14M2ZIf(0Op2E|^cpXSJ?zTo_(Phx+cZjzfq z8)a9~T36x}3`}9A>Q_pU zX?#&gi^wp{B1XZ9RpqFJrx8fT^V_;Sw}zb0tFQv~(3kO0JmGUJ^Z|Zqwo=>v>g?kd zEUIiDEvw2L+3t()^r2t6WQ|q~T654{yOf@35lVg^WDmV~?u0Z0v5p1Je0uvXvES3V z2q27Je->g-IK?|`A^*y`&ID3m4dNEw{~?&%afK(x*Q|>=h*!x-8hxE)si~fN>)_8q z{JZ%Hi<2XtErqVi8J|@{3$K6U_L|};Q?j;uK;SGZy0U1Mq+qAjGjHF zikSAvcHaSR;v5=_@o^h*c14yNak?NotG~zRMoliR2Cm+-&hI3SKSk9*x^9%@T3zuz zES3tlI@{+G{r+<%YaiC=B7<{VNbycDpX}`Isvou1?fx=y0!>ymeVWgA6=5hPNzI8c&?QaY3(20a~u&<3p`2OU%1*xa=K{nsF zp5W_iWCH{#4%~&z7d&Anx!68S^~Pgp&B>99YtUfnt_4d}?~{u~W)q;F)zwY^dIsFx=@4jgHI~hPJb@`;B!5frv^VUTrg%d8x%}@?M3EC+KIxS8 zQhARGOZfurpZ(RDlckbAHIBK)vW`Z0YPzS1m?~2b#iAs-cAY)z*xR_QP%&HxpW39> z1I1Y*IsXIn;J~_kv{4p>&t}6f+w5E(G4jwy?Gm+fpa_4uO<>27LbER6d2_-Q>S0FS z6=Pt66;Yi2R9=Ybk$eAcdm+kOhe5(T&VFH|AycT88OT%{-x9YYp@qDQ=wv| zPH*hU^a-|N1S7Z-56~|crKHp&FdFoS2}P@VFb7U!X}h@3;$^Ncp(Hg9SpCojJQm&L zMtpL}gSH{zrAg7J1}9d&fSo#PfE8%fUIRjA1zNQWByjKO3nZu_^lR4QO;28%q)A7+ zXt>r{!6hhi>bn1jZFm-TROdOR5$zcO)q{e7@t+6C55ONP^u(|Xx@p(6nW21xU$-hQ zmH^A6ksLSKdiRu$^BXIea#isSALlA>Hmgh=z$khhi*E(HSc#qOMi9#@s##^I+HVbT z%GFd5a0Ti1(?KE3^(y9oGQh@3vgh+2TDqxsY#Ta2QK?}?Y*;lH_^g_jXl)XrBeach z7f2^zj9wtCLf0cD{;HpRv^wSp?DT~>rDf?SZ?Ko>r0xxqCRf)L22XB3AJ!`;z~}Xb z__K?m_-a+<_7248_uL8@z%B!xu>fMXsGb6~oB&eUXuyV=E3@;*l6BKsj=|*Q7QIfI zbPMlO9`ZI+NmMe{#FzTzoPa)XgQFDrjZ2{crvXKblAqI&I2om?|M@ z>)q=K``;I^7?l|fBP7aNkcM+V*;*_oEm3Uh{t5nm-|_xa-T9g5laj$B(=O*>41TBq&O&zLX%1{JWk z$e{mi@ZTmApE9WmemcCPbU{Qs*Z*MLkP@TBVeMmHzOyE* z*2c@wtYe`iDb`Z~B%{!9i#f+NGdfz;D#XiG(K*VY7M=fWx*trmAB9)qP05RK3{Avc zLT0y@*rOID;@F`dr6bEQ%P3n30Dn5Eu*z8R@3Qi(T9e5^@s2*uGhH8Xq^i+D3v1?K z(Wi`LmUoHOr4}dAW#oYYX$z++oe|ei#p!#+@nw7w7SJvF`33cmqE^JL*0#A1Tjro6 z#Bb!>-crZ0toJgNaBEP2p)a_8YNxZQ6a?Y( z3pn5(mv&h=7$ig8hwZH;gcz4-ttDVIoEK^w>D#~!OINX%^+`y}@=Q(Wc*{H$2dt8 zWpGcBV<`O+Tl%EIHrpm549|}B`;4hnXRlJ8PiwTu57#N&A_zwvh$sD%t>!p=n7y?0 zNrWwDeGg|MV0QX!&_@cWn}8|$km8#C%ctW-muThe2CcfR{g02wQ8Hv0D4|E^hs({d z>naU0PfySNmDal-N~Blc92U$Qu+{~*jF@`7$B=I-_3g?@#-Tf9XGe z?0yZg?q5)1RqKE!J7Kbg%v)F18IpKX+)(G{zuXmp;VsVW`5IEiPyeHuZ$H~g%b%50&TJfhe2}D zvdP44+Vc6UiB~WB60T7FiTuHr=`j6jL+Sg&9uq46*VSdhQLQqW&L5F=_$Fl1U8_`F z-m!0OdMaL6EL&wONv5zVPB^4+iNaF+L)uZjSlW!dYo(Uzc@EM`{m3aOPl8zwJFmZ+ zWr+tR+pUYIs4#uDFi?6eP+0KFZczfQe#mF1i8w5G0=dicC&OHonUbzO+->dO)Z?#T zZfghi^TCC8<d=A|vJ@iy}c$aB&MZb#<61(>*$p5bw zplV}Z>YSok!;8nOQp(LDPfl9r8B^RH^|N2f;;tsI>I2%YBy=wZxp*vIb%8cW@gP+4 zXx+nLoopr>yaX`Wm$Tkk9GyH&Fs&ZW(E)sbdBHd7Y= zbYhN{H~$$pcGxvD9$~~c zDlEp}D*JgZC}T}6+!Le9$1m0wT;VKQDva$EI1pd%^L7DS-B z>KC6JD4~HtJo||IC2CcMk38Iw-9*$UzanJz&Yjod;;otscA>9pMyFcDQU@i^=FIR> z$^GNP*5HTbZaY%MFnF|64C+doI#~|Z!Yh4m|5Uh`d3%1 zA-Y7%#94rElSejDaNFOqvw8Z@a_h^2ibkl2Mx>|`4U`xfyCFId_}glgSMJ`1w0a&o z^7&Gp)Kz4A3nrfBZZ{e+wIts;O>ruTp?u*nH0)FQ>sw!tOU8%2y*ir#+Pu`iNgyMR zF;A_PftPYi#RDR=%tsQMLBIoAJ@FQ>t%pf?q?i} zfS#UQJ+xm(yBSBl=KIhL~oz<>*jS}fYYPzBynX>z` zM{{e{;#anzf&L$%(k~K*zp|;==53^#QU@4p5NT{QQvQuXKl`tX>TWsafwy%>#(JlwY$n&JIgTw zO^)dV{@e;!UM}rkPCmUxpjkFiQV2=8b%&I2wAwRpxsdyv-)CUir-RtpNL0a=I7~Np zKq)q_6~?)Z6HdA5d-9uj#-`>*K`ngH>OK}S#-b@ejcnP_eF2~6b*=4ZdXq7P3A`13-qm$r<6-fFqzl14bjBV4?VZ@qQr z64Q3>qu>6^mHa7QE!c)pnv0SB#+xSR(7zy08AR|@TGhfcuCNmPF%==u$uOf< z@7sFPRy0U=CM>}bRh6z4Zm`=+S>v8Myz><_WEaZOxzQ`L~PT zwFKZCW-Y$J^Bi@#2>L3AzrhI?fzm~{b_Chds&){c{Txi#G5dZ+mI017GXeL@!y<1U zpQY(5$PpHpOHQaydOzW)%F$|H7&f1>ibWN?^ z(IS9u`-CRtqX~Yd0~r!8syUs(>r!DX1cq)=)n`_pL|SFl!dLiC#?>EYc_AFGlIxP~ zRA;n~6M>mkrTXQ?sU_oALDadA0$l;yq8J)tCp{0}>hh}==EO(QSkY8Mquebdzmn+{ z8|PUZm5?ocZU|+}^m_%&PUZS;zv7{1{dvvffJFBiO|-v(-c>mFl>~Bmr-4njZ2+%^ zx2=&NUFvl42?@i9&Lrf=D=lWxXd+*&zfh8+XI?Yrpir%Hg4*Z}b(vLJp?E1Q+8#S4 zS_RskIML58E*&(O7ICO;v8bPG+p8=Zr{nEhxN~rzCo9^aT1>@apZP+; z)7&1<@@}PhihCj-gn&yAZF(4n>&WDF^5)18FX5752W|8Oa*!6@uUxh1TPIgki0cmT zYuJuuw~`|bl+pmRs|aQ94&H|SMg*<-_K>ceTqoEh7j=ty>F0l{r($^7!f=8tH!S7L z6-Peisv$sb)nzzT2)8g%a3|Zqr7+?O0{p=;%#mFrFl^}6XBn-4} zLz>Zo@H}gAh?{)?o4m+sydMT+atefRxPITJyL&JLX&J+~nP>=Dy7Lu>l0V2AZU=Rf z+yZSy2rCAiijOzhb5$o2Wh~%0bw`r$yE;pCI7?vVg6 z-B}EfAvILQj>AAKCrSRGEvOqL0hAw_5Yez6l2r5yxjE!RhdOD7wNoN&8l7phVr0bW z#WbP<*rGoCrU@tH(43!L#z(^A)9Dx$=oC}B3#LE*wU(OrqGG;Hrm>8ch)5VB!($oz zDmUkG&*vMAbhJrij<=vpq`NxnOh$ZpehJ!7u>8n8y5f#eeWiN)J-s*m^Nwg(^N#KU zYSG>OKcx|7;q>)wy@gn$Y5a7IfWGftJu-c`*GeC!UMg-Qvkm6sDKpQ6ivX%;yycfp(zAr&2zWS9D&E-yyxLNkY7T4UWuQR`6f=&Om z=^CczqC#lz`Cl{3a@qge5=rxXo{n zI`z5!?g_Cg$5A3yf<-nc5;LU~8<@+m-#e4NCi9w3w&NLBjb>sHKzygf%*s#OY}gVv ziwiuZeYvl^FJnXds;?#H1*HQB%-$nOiguI;?tI6e#5g>jxWMZlauIexp~_~WA!g#e zanbZ*Cr@3-<`k3K#;%(}a;GQCeAFB)xI_BFn4g&D)VqD{TLAKdA zM%T|ADTnA4mAThI)oEs`)!66>PDgWJ2x)E?jacc5fra9C#(2&$86E)4=foh5fp4Cv zy2ZNf$l(hr`woN3%xJZo^SWZdpe>5i?YFavQK3B16(B=vCy_Z$n0R09O$Tw^4@7!v z^Xv4VScOc5$OU1`6mD;mQB)?xi+EKYEk|h^Kj^!KLQ9N|y*X3U&y!>|lMi!CO(MgG zK#DDayaLFUC>AK@gfgBVuaTWB3+V`>_ z)fi&%%-}Tvmmp701z*Y20c|Gj1i#RtU&q9D@0;#;D@eWJD>-j^@l{p=N85WBCtqmjLB*YHL!csU?rx>)1&Fq;!?u=SzZ)Rpo$gcEXOig$=iorM@8T(aW3 z^lToD0Ftis{sQ{c=O_naMy64CQ+#>RW4XUZiswx_Nh#Sh=h+v6M z*)#|>APy%d)LB>nLPJ;IjcNF6_MqUyk-F-t_}q4ZqSxYvhK&jqK!Y?~iw?zzA9Y1| z$>|1{K*b=Han)F+)xFr0*fHKBHtVgNAlu|70Pdg|656k6%yn0N+pB@7t*MB6qcI6zA}$qSuk(N(atgzn)Q)a&}nfJIUnCh9{=`C zv-O&$`>({Y40xH1jgh#S8V$@xRDRVIPa5GkLsc$p*?Lv(=w2Qmnj5)DBg{`&nX;pY z+Y7P8?%hzsP{~SNO<^7l>})1O$x^K+(uO0l^L0qF$^$TLTnYC#2o$nq*hD#f0BTp z27Cq%)#s^pl3J^hz#3*OHca&hM>~d=pmj#FV2ll3S9IcbeD>hueb|>H-|9>K+cTXo zFuWBZw^;!iW7Naa+w6On5VzN<-g}zEigou3sRHdJ1}zuMzR?UlZYzqg=5MR!edgA1 z>g12ik-i2Jg$3#8)SO$o9Q& zn2?hR@)WAvM1FzBl?lu|!pT{i2P&lO6=zc*%SEdv*-#Zlt}**l%Q$;|G}V%>ZaHy* zhMdzHW{aOKV7a@L;lq?Q*0-zKYOv)~DF7z#(;Z(?p|76onyVd#+7gJ=3M}`8j3)7_ za$KUs+)jAp0YOh5Q}g#%W%FU}^h{-Xj=00TMyvA|O30e8IKvo_jX&?R?R>`66yk`m ze4QA*X#{?j&N~*G>dLq-w&p&c0|85h03bvtTi%yBnoRu_F-O*SM(P)FX3tZ81n&Q7 zsf_N7Q^3ub6z{WFPjsvM>5|qdOv2FFknXZfOD1W(Vb7Nx*JqHuyHWg0MJMysvDDgR z*rS*D{qF82;eQapSCzFh(#GiTxRtaZJ9*E0`z}FA zik;7QA8T7}@6x5htZIXLUD!bE`Ad>4{7P%jL_u+uP)ZhN_ogY&mt5<$OAeixW*J=u z?f7%NV_xJnt)kEj|MUf=tRs18<;d?gCIt^IqO0vd<`)@>H#A_I*KuQUxFlz zOFAW?%R_V$R`kL`duBE@!k0Vr$R4CpjHPr1HEUmqn%#@hxidC}Ben-}SD$^1*8=4* zMx)ClT5NdbUH7=cAX7JP4n`<*^x<^aeWBf$^NTch7*|5}nku+lp`w2a1z9F{D1>91 zh+sIW2`(*EXZKt#F=nA`*WHO!9p1e!X5Je2)EtwgYNe8ly)of3t|(i}f|YmKEzvv^ zbJ$SqB!S{*S-xBLU7iy9E7H>)mZKv%R9>5m3> z$1*h)O}dxbQcGAH7kHD{tB(nvpPjtG|26cjtTl6SK*!>ZhmmrKeyFEHAqi^l$68^^ z<-RBUVvv-sWiw-5Z521M87OJ3U_%n|P{`CWX*Pfgj8^_)*0;RM1rrsZp4)SqOF_)n zSEU6?nIp~h2CYVgEKM!N))~=1b_y-(>sGbobq1)y=`ch|hf&)Y&LmwP@%(F>7rmNv z`1E}9z72?rs|oD?{qyyg<)%B5>rcs8Rx*Yx>GgAtG53rF23yAeio#6XSLRYW>`Cs z1t29w=23ExK6B+O2t$kWF&ClQsnCU@v#o~U8Q3_96oJ6mCP~BsS43e`CyiZw*sIBe z{(oWKE%Ct%XVN9Hs)^)FPyd>8+IRVoAXT;S%Zw9!_oBt%3s1uuD{-ncq2IO~U*A3b zI3072y>lJc!zlP~Ui@F{3ljeSq777h^rVl(pY>l|UdYjvV#39|K$#X|>&7do;p9ip zV+OEAr)Li&NNso~@TeYDT~vd9O9sF2{`BEs&nt^pD{MZ;G637I`?^nlB%ogAGx^ed zF--kl3TTnfb}VX{W33ge3NLZ~?TN99B#m_+PxUC^-Bj`C>Ak>y&Y0_Vf>x1;wEmN# zK>PzX!bsq99RL6`o(M|{c$7r;dM@p>r}Gl~dEB08j{+2XT%O>& zndG`z#Z~zkI=2S9p|0p3-tdo9Efy|)^Ed~#;-1?=&uk5GcYaY4qswj$M1+mfg^{zH z^Z;7*D70#{6%yRf{xVyt1Wt-E$zQ0{J9+>o?f5E4ES}Z)YNrRv!C$uv5-q3=(e)mG zjdv_I3CRS-pZDb@rl~!L{Hi8C8EMKm*jqkHe+tNrVHy_qq`5wKFCYPJ3A|kxKy0Eo z;XDp|e{E1`+$@ZLi@WCT`AuZqm|-bOAy1Y|_5N%raflnAE?sI3IB`oafc{iT$*pl*Yc_fK_Uo(6#Qvg)`gmPTABOoD~4 zpcpU9IY@FT%lUnnmQ^F-_o|@rsnM_ZpQiJ~fv|p3m0wykx|`EFINNy61Td@U15-y? z3G11iyRZ3=>(*RthdJOZ#t`^4ufB7DOm}9On9D>&7YBMo_e%d=$X5W45Z%U@DUFx( zw-+h&mi;B?qVDN+GcxbA+Yawg08UB<*b;P$gbz+zHgx90V%&HCS6L`EppxIUQJgpB zno$-FDeQXZBTs5;g}_+)%J9e3`5z>+UCJX3u}o zWRjyTFfOk89zyweCh=lIR5_`j-u{Rsj#3-H(6%HnFx5S7JuA%P;K6?aiAOgiuKzpp ze9=`h@%!W}cHx+FBKWT;0@tATRlRIwCaMJx8MdAn6ELD}+a_p^!5!)!^MXcLWV`Vd zTro@~(>1r}1}%J1Z_V258)OT+&pn)^WiG@09(WdAum?3dH5xGP{I}Jotw0aUaQlB#( zpQO4@KTIBcTk#pwIkcbnUYDQ5LEDY5GytA3Yv{3Kxut=!mfLH~bW@m#!bN%xFJT5w zf|f-P9w~eEFU~rme+a@Kp_jGN%f^l&R;udR31ILf>nN z0|~fXY%(#YaJ@V!-fMi$FKiBR6CzAcc;#~9FWXRQlR%HcE85ph68vnAvv1Z-vdr%{ z=SGs6MxqjNZL&ke#xU9;%JZ*K^lWa5-E<4dQ*H26JJ!Ow^u7<3vrmz3xGmzh#t#|}Y8#lrS+TLU*u(vtI zX`pDZ&vY<^9&)5(k}2 zKxI-vuT~m zq7nBe&AKj8_CsS*4+3uxjN#YEXq)6S#)zpH#_UcuAh-k_r~i}&3e!R(GuzA~{Y%Qm z4N~3b7$1QLi6eTW5dcq16%67KNN%7`1*Q4%$a9~;wQVgXo)kbk(PSe14A;P)8bO)41F5zK zY0D{lG|nHVIx^7^nfY@3Ghq+~bhwx=+-t#G4QUZuX($6v#KP$mu0-NQ%_&moZuC5{ z#H9SxAS{N&1t!Q#W~9(RFvzi)(~8om*(J$^KyOJMaNloRtHsq#!c5FU;0RVGHG~l* z#-lpoWnUaa&m>nEJWEz${nLet3%>1bHcms|g!$e{o2~C|quJ~l3IL--wV_A?z$nqg z{-iyw#Qq=uxU~B(O?Q<&!=>#tgMspKI%vr0N#IOcV0*64Du%UWq;HQOxSY-XPF;x| z|9l=|mCXHaCH9Fdtez=S1(Q7N`jeaiN@rE}f#WLJH2=))#!(i(S_|&2dM~!zqoN-9 zSFvdj+KyR?njX>!3HVpvjy+fq{rVpZKLvt#Eh;Mg-P|e(>XFI!i8@d)H)0Iw^?f|# zXlCSR2gRTN;{~Yx1|&F>*4vg%{k_+i;f5h<(M@$?g#Xq=7H4KZyx?KY_?4>h<{saL z$wC}{b$WJ_^G}a8P$LoJSKV<@Saaxlm?9YAFA@QF>Uy1gB>|Lu-$GP|8+3s4nvH^l z)KXz!N6bXPXTV>tKKj=KkHLSrJo6#OHjzkAd(a=E$CXw1AUEBVWTC5ATexdkCn0Gz zpQKp#<+*3`3KwuLLSDcl6Z+Q`!e4JUaFa|D%Kd`BKPx|ji+qQ#k(iC<$_EJEE$`7V zC)5*C2lPX^Sa~tw{a=uM>e3oC;y5sUOa|GfJqfd7IneY;d%725IX1F;i{2|3On$#Y z)nJ^dmnbZXvGf1va)t7(ZqtRP(_@4EWfOUqKqtEcmPjs1AF3htD^T zxXCW=gQEyeKJGHs{HG_!hJ6tKF#L+=<=)Zo`yXTd*Z*?m$qM&CqEFQ9z0V-yEdJJD zwh5*(I-^Wi1I6`F)0;aljkeWY&E@a*7+1(UZzMTSX6JpaY<~0FEi$P~QxP4PlEIf0 zkW~bvs9L=m-F~IGzeszd$}}t!M%-nO)3Y*Ny#66OUO~}VFa+Eo4eitL=AC3{@DF`s zXrbyB2cc&dM>l^h0hP$W{zS4jf~m!2TfTQ-@nAJB3je?^tpv2Ck>Oi0;6GwtTroTl zr(4nDE<^P6j52{XWj`lGJmK5{xp@kotyUq*LxLw0g9j2ik1v@QTSTUV$vU0&HWhY~ zWs(XW*pe~91uBR94-(6TBHJS066;!S%qUJ4Nv}fu&6h@uJP6@(i2K8bEtvPBcVnv->KRmphxk?={p>Sto~1Y=Y@+kMV*Ndu}A)Gv`T~$C#^wB7wtXDh`!-I+BCF?%poGkAmSGEOWo~&ScbQWpLwS+RoGJv0iPb}qkFrAYCF#`up)Ud9`7%o;DzBp$DLV zLVPd~=Hm2+lJV(49l-O!$UJ+G9JnIDjFm%A#4YH9)2EHP!9Dh)!2yt2KW?}Y8%LSb z(qYjmmJ1>3!&aNnh8R*i_a4Uk8=jbaOv6M^5!POoJ2P_2G|65jY{*^iq}Q8LV6TgF zgRaXD=PaMhwbgjul`l4-ye=Vu#InWmr|)wYDCG7RPFH$kCYh`6IIl(XbXf6$7qlXw zVVI)lvTd-nxmL^4veRYb`P!SVD@n>ZY)Kj_x{7{blUJDF*~9O^KXfhm&txMWt%^qS z8EAe$GY{QIuyHlb=q^4eIi*%{=bd`g4>OyI`+c#K8M55fB$%}hC7*i;|E!bfe}bm1 z>}vVEX7c2E+zoYBO5YxdX=&Nd;G@0EOq^PV$wmmR^pRPe0+$q{$70SCV2u3$jYmg? zoDuDis8aLhbys@}R=>CS6|U=69*4g^oqfn$Bl-*(NQpG?+Ry`jR!-3G#m#0ueH>*f9Do*?gR+S`_&?%#^5a=XNOpsj zh@`ubpJ`As*|aQ1f!!$KybRk*{+YIha{FF!Sr4$40uI2Uu)fy0WD9qqS`}X!rd%Cy zDF$kyuYJE8Y>UM|QRBsr4rr3fOF?T~feWVP zX&bzF1v%w!BM890)+&!}K5QR}^SZig>E_?C`eaLYHfT=EFsACZv~;?xinMS#pWM_Q z)b|#DAhwnUf$*IC5ai9^_)&ARIG!bl>3XW=&7H4l{f?^GfbjS?tsYK6=a)Vb=hQ}& zeEu^^#I}Btwba7B{thDzsCEh0B|Y^FndW<==fWB(#h3TWB!qgBeap5rmpQ)_C^z9eqzWoKpOFWE8kV7BNT_(}lK1>Yu{oZHh^B?$!@qv}QySz*kr8bU zXh&XB6R`S#=d+gTxD^$RMr%+F@oOux+C@f7>FlT--5Tz!Spq<`=l3{i1<)r}I?-F?9_I(bJRErdpu=CJ3;he4#haauSS3D+!@@i!{J7lNKLCE`k zVo3Y?=iZbL&f^urIjFk=rZU98&V;9S1aw_0!mv-QBaT)jI;*ly_7uWaJx22-(|pxe z`0IMT1d0nn-mZ3a`~WMQXEFSNhT{0!7j(Srd|4a!h>A)a&i@80e(!Gpnj9Wu95VB# z1crw`Qil~UDyLr9bc`CS0jayws}80k`_VJnzYyQ|!3g8iU+h05e@dCgnBC4fvx7gT zR~(gHUa`5SC)M77^wV9-)+{l0NVj%hbHA#v1h&n}ngIOACWA-7jHWaEy7&-B?qJ%) z44_Y0LLB`=i0OZN-OCJikGw>q2|W?7hVLai(PUwCRi0jCa}L#wT$4BX**p&wqjmL- zfN&D`%fAVsyoHBo z+;4k-^xK|(A|ZoPHF*#l-Z{`#FU42o-hO8ySpP=96p;2)hFC3(xLt`|m|Vc-S?EkM zHopY*d|`0OGR%%9)xi=K%u>p-r5>^#1-XhLvM$N#|AX>BE6{7$SkO&pin|$BS-8Df z_Tmp!Nwd`1Jlk{18Gr0&4IEJgqx7>r%&0PJS5~PqC*D@6GA#xdFihj$7Iyw@dei(9 z@QW4L4p6I|YuoV66s*(=*ciDqp{KvAIT!hV*h$wRrC5x3haTFDonfl+dWxLvxVBb} z_dipKDTXxaCRPyg@LoJY8{oo1g}0)~hjglnGMKm$=X@*fOvQ0} zIjqtVf1A-iYaC0x^7p3QW*B9Z{C=iK{`1L@2RU4Vcsj;|9_|$W0t@0Aiy`xIWPO}L zwKgztxotAnFQHNd=!cYpvVnmM{x{2Dx!w{#zuxA&S^}Voxi#iW)PG_EDB@V$FNfoM zeYrElQrT3V!tT#4S1s=72i6e|UK9*v!ub$`a7+AbU9p*SCE~yHZzsPC$Z5^yAnj$H z6krxEhDkf?CD(oj$P`l>DjBLf;1}_}T?`P?E;g<-YLCJViE#zi>lu@*ox=GSd0@IZ z-RQNxFZ~!h)`gUo+;|jGJ8l4VLil=!NcglgD3(Wb>~zj$=7+z`DuWm~0=w6~yt!8- z>yI#V=RZ?aKGxHlKmOp{CS1UqQ@q)|a+U~;J&%XBi1uG!w(MU1It+UFFNKaALk&h3 z$~f`1JWZXQg}6RBWjDAn-jBFz2a{rm6AQ-(laFa{Q)N{4=}dmFN<;N9DmY6TMB z1*qQ|&rY%58oNJ?WA#WUt@TxkKO&<;7$g(Jc76IFxIgkFstOjxbmb3>x0}4CR@r1T zNUyY5UzT+U^_@T>K)A`RA29X&okBS~B-yPrDaGdP6zUY}@%WAfGpYV56L<(v@;JgA z!@(VIFdZyjQwVo2_s@9 z^$HvB_5yV{Glagn#EIS}Cd~PVio0*tnf5lirdj~zw%pA~kMg^CED?!0c33w}v*r57 z3U-`CX67HD_Z}o9R9yoRs7SaQ0u>;2*}0yO?hczyC9`}||9HWwKXNU;NWUFaqy5=4 z8d8a_GGCoPh+1YyI)Z0jl_y%p(pefy97X~g11%-B0n3s(SCf=Fp(0G;plMha1kC(>)yYvfSK3 z*Un~5Zj~iUR*7-mhEHb9*KLyo*@Y8#FuM6i!I`T~qjDhMQS4QXsmzZ@4riW(+AJ@<$ItD7^qy8wYZgF?;5Z_XKFEPS!nL(&Ot~%lF=lkYL)-! zpE}v7q*FM<2h7r3a4*s-%NALpGzSqx2qmUvp7^0yD(*;yD?!@@#mKJNZF)gGWSDa! zZk!#SS|s=6a_RxewM!+Fg)Z5()yA6D)c-HO-YPE2K583Px}_OHx_jvE?i7?77(zl2 zK^UZ@85p{TR#K%wQkr3C5KurGh7hC%kPyK=Jn#2@`)KbIejMI&$NFFEinX3PPJslR zwVdPgNX>t%SZtG^6Rh@Xxco%GZ|C62*n3jH;9VpH z?x1IIpe7-pYHd|b@%J0z*Hd+G+Zhu&CLHxZbh|pVmSvP*KdH^Cyv8(-P z#Yz6ABXnh=kXUjYcJ>zI5K_R1VP_G9{(#~aS&#{s73tilb>T4B(inq3uy9ql1Hsc(H zA76aCCWHV?Hf<48vwq)AY${E%qOSyt!kA|DB=agGaygRBL2q!B0uddM6w zr0~TLzy7w1HQ`y84vQp;tzT*I_`BsIqn+ZB-NeHVDR%j^k!>LLxR0@ANa$+P!O!Hj zXNFPs8VdG-O}9UObU*PC_xz~EJISz)$v8-T5m_Xs&!pyyqa5Ue(sM!dws_Mjw;q@L z)B-w&=&p7oyT#l#M!7O&%EZgWZ;&XJkRRK+BOfVv0e!zR;fKPoX?NG(t4mzA?79Eu zU^pPUf+2PZgOCE_ZEMY^rK`2OAD@=}i$bffM|A9k-1&F&V4594hVh!T2R9Pyq*TgA zGW*O0-ZpP)zptocgeu}V6I##hML60Q*F2p~Y%bs0-Ki^ZtGM@T1<7K}s=S{Xl|7Y@ zjWg5x6Zi;TU@rR2_*wgH+*98Ublp8$G4GerH^h#*5d)R?iICh~V%pGPS{Cz^v}K+> zXZ|$mXw1^?{JgWXUjMmraP8<1QB1*DN-;?vCT$27(aS*J4u`yx*(c5b{`&?9CmcE+ zD}NQADxJT`!;EtwAO_W0wT;B)zQ}hAzb3kH(=({w0VatLNix?0Q6B49DtIEnS3=3( zjjAt-T7|@T(@o(8IlS;4L#Z|sE#}P!PARe>=ht*!9a$G>hFG^=yu_m7pz@J7PIS^K zd3&<**wLvC28=&_UZ;gaH8_t`=h&Hm{$zZzC_B|4Yd-lj@FgZR(33Uve6x^*GxF^j zuK$5AJZp+3!u}0QVJRsT((wW`Zc`=OBDG)sfRY?`GsIVn*zh2Ag{>_(mnM?=H5hI zJSyA_0|SHHVsu;%?ynAj$DZzlzUSdo754xCIqke}Sa zU6?4yr{ymu*V;+O!&hFMVL8};k?VAXsOh^@je@P@a)$IJWF;^xCv}}dTaZE_J!2sK ze{@2mxyufFVFozF>_m56Z(UT2!^u|=xq0U=h(VyVAK78i&KJ<=8{FtSP!sI6Q8jtB zp%q2!kCZ*z;(>VzOFVtWkoP^g1}=O5HP=ktoTz_nMMJ(;EB-dK^M|99@Ma4RotF)l zwh5?b>v&W#(>w#Cl-4W;h^W%rue z!|GIPj2CmtEkkfBSvdVe-NRFgU%>2Kbf%w#e^I`c*4GqlV??akZ+oeSx&K$r@g?3k z3#LVF*rIxRKsCZ) zZ@)DxcQ19z?u!Nu6vqMo?g2^`Ch~2?dF&6y`({*(f^n%ioy7gLfJCFK?!A@sFAfQf zT6;TN=QclbKZ{=yt!3w|?jaDQ5j-60FTlu;Ni5FQT=3{cFn~(78zN*{T^XfCiPRdr{^EkBdtj7RXbfzD*6~#Ax-jg zSmOB>JhSI)9TlB92x*^q%rbmpb9aGots1s|lJy@FNR)S^K` z_}cxq`#1++E8I4|ZWaUN5$Wi*((eoD53=_se6kXr|F|YhBg#&AkdRj|Ps4f$u;xwa zsH#vWLz%*_MXl-NI_Mw&xond#G6$bf&1`}apER!vH-ms3s0iIDt1r@jd1B3s&x3ew zR8;(fG>_ACJIPpk*Dn#~upZRru)XT6Yx7_13ugKmH-ZsH*!Z)%vf!lEmq}#*&0Eo& zCE2o3$_dh9e<=p-#a_NC&6ucd_t}I{KAEI!v_8Ij48;c|4{S+AC?y9lK!i$ zP9%X&nc}hfBfy+6x=YSa6^7W;}-6auRh`NwTCFIvUZ01 z(nWqUIuGxb1YSZbtTa1?)`(>j9(=BNy&`V}cc2DQQ*I8}4Sr6}&k3YODdj?kH=+&< zZ|&zKJ{Ta^;8&dy3gd-V?t#T4=m6>FBspa^SFB=eBGDcBwz|60noo?spHi)9|Mgs% zxEM4KU9HwKL>E01$FLQS3jDtRI`{s5l6H#4d@Uwl^-S~Cyex|-Rnue>a5TvhI1|cP zN2mTxt>zDD2NhkeuKg-XOMO7t0DlZ?=mT`35S|Q6eXhO*HI_yULu7c>R5#z;*Jh<( zbj;3nE4p_S6v-L>kyDx3n!PN0Rq*X0cB6}cQ767ZCoAoeAXbCOGxF!T?cv8Pm*O)z zI;<))I!@iiQz4&|T#wv}cH3Kjb%gbhYmx9=tJrnT|tfugs zy?jDbN^9z=>k&fSywcUG_r%jcEH0}zw0CU?dE&O4j{W8Qsa*o9Tj%eM5i1=!k6wB3 zY9!&hrRhuEcRGa*EslJraoO3sygpY|7ZRxpD?iwzOjVlMv*Mp>OiIcV^<_4pC4%RP z8r)pFGdyI@*$Smt+o^8t)NQn}Hzro{;|Lw`Sb_MGN7!1Uz-fd;5cfl>@nI{`?B{r* z@q6d(I&wUmMtN+k#pL z-)Ym|e1lC$2Ktu4nG9w+OzI({f|&%^EHM6vX;@19omgt<#JmS zrSY?|2$27>57Y^lGNTKe9#o+fdd!K7DjJEtUH7Nz=TLd=+}(-apq)v-`0*j&Gz9$h0vo;vIYJHulnzrzi9=IT&x1@fB1!z8-Vi%ncT(` z#uZ&DCI_N_^6?M^#rtrC8Nym$Cj^RhIV|UAD%4RZ^&J9QwI%0S*nZ|7NMDsp+b2Wm z@Mo0tvX6l9b4mO}ieAu+&tn6U>|dUuK=_}!K1@1b-$COwkEF`TDDK68K`W2`ak^w4 z;GLjN<+fON+pCC)asPWu8e^3EyD1~iCg+h?Yzh{&)3Su!(P&(R_QdnkP26=irICGN z3JU9s&RVl{ky-oCj!Dq(hRKaAldZALa)hXDVjV@c6i-s<9Zr^IcetP|PRk}(^R|WKe+JhELxKsJ2%zhRmnP-h&HQeBk zNybD$oV-|~7AFNalT}L8cdu8NR6(J+?Wg5Pwc3Pno?5Q>Aq+Rdpjb|eW=_5wH{VOr zW6G*JY7V9M^hY!{cMQtk^+o;|?-^Qugx{FDH8`36yJHd-uDQ&KS_*3at1I=f^It=o zS`b?6E{^Hn3Sx= z=NU!Hi|*vP2_s2y`X*`DAJf;JH-A8bw)@0L$AI3_zC4>oYFHMwstU(+GGQC(ou8f3 z4((c=v<{;?5r6)?=}r~;to)+ux2#&^pI-purv)rEa5sGM6(seeYD-6Z@*h`onCDB^ zb#0$mJPU*G*1eqqcWz{a+y*Bel&^+NiBmx56o?ImnqF?RFJ*pgIma0+PoSZFMTGu3 z8go&Kc`pjLX%ddzw3(WtYy4gM(eb<9`Q z;ZSC_J|%!fpc9_i{i8HBIO^A7k1uSQc5yuY2C)1Q`7SZ1F4NsBa`-LQ4uLB-Clld)Sv!kN`IU0BUM%xWu*Sj$CrdsSGIz=lFsq2 z|LX;CZW{!66m5tl2qLgz>8YKl*Xg+dJFt=`j(9*bBmwcIk+$k&06Z=Ax!O01gsT0C z4-^GBM!Mg$Hi;{#?^aoTN8cGGQ%(92X?JmbXtiYk8-7b+)Cx6T)=#PXo{E&Q(zS)c zp>1ZEk;w@qm4%!KBVO8GbY3a+ET1_Srk9+~A7#5+3oi>z@dyFFrg%QSeC)aJ!KeS* zGNpEUn06>D!M7ZmYd%XD*?}?iUjX$@a7az8gk0^( zdjfyC7fA8F5+TF*{cnKP$&d<`r0qv_-?@4ZtYHG%xiP*pFLBvuvnVN)D_9|C5l^oY z(0$ho9%Y!o88t^YNR_vK24OylF6G%>nrmwQG1#`UF121t=@+qq<5-l$ha%h!La7<_ zimB?!5NX>Bs@}P8nu;zC&`keUSVb%h^YU|Li*!srQg$;{+?8=D0aB*z)2Pm5?nT2y z$erk)&SH2zwGq7SD|Ofzl9~>gFe1k7XrN($Nv;vOb9<(ZjM;;Fpo&Cin_aFJj0fUF zt879{o#duTM{wiwGMQENZHCACuVP}l{}JuxvZ09j{~kvUw&rAdb~K+nh6QtWFL8Fy zIcPRCIk%fE5~{RJs776Z^F&|g{RDT&SS6sMgMOl$pfN+*zE`#gwWf2$vC(rLN{3b% ztMf|h{dUUjl8`6$05G#^!HxFn8H$PrB0Jk~u08+US)Xinn`2|B<#uil2NnCRqk?(y z;%OoJy~0u#_~vqFsi^3=exB~8b075?=2YV#P&b4!^ErOt+z49}Djj`CWV+2{$s8cb z{c+zI?CSgRlsFDJ2P0esBx1%eKoDH7VA?P`Tc`IvzuI=ZS2HhRr0n=?pieF^4&fv`9(-p~#7?hC zMl?%m?0%C+i88+R)}a##XBU&N8Tc@09#{IL2u16p+HA`7;YpF)?gw0tP#B8vgW_vg zUJ<-X&_UShHL-)(75=-yb-GAnEc4+0vda)YVM}kvhs9E*8YhJ7*dQ1E0-D_MOY27a z6u@7BlRyEwh54zAzk@XV3DW4d>lEv9@61kCGzwS(E@keafp}(rg@P7RA;!Lsx?cdG zVLghOb)@4=rg|0nUc>bB&@+{J^k@e8Ag`t!b!j!tH~Me7GJdwnZ4sieOh`1=CVir* zX)p{G%J#LV+8_{HIrRkK@Jx0s%(vy=({5Yu~a?|Qo(psC@Pst`$`Y88z4HP;k}DMu!z6m6hI zf$hukz6nmKRYZUNcp~0;Yo!0O?6!MgH&43_vq&J8eBu=+DTy(e7Ksi~@>BAQTk?f% z1axjn?$2KvlC6Lmq^zuipYf zPU_AMzg~yjML`E?M#o;bJ~K0*GH6N-%((;PT%3dPzEJu`a&8kye=SVQYt*Pg# za|nqD>1W@{p42~H@>~0l5mzy)?Ub1{ol^mB9feQv9y##MF3?U5ZMO{|4x@tt(j~xz z%F#JZV9;fdf07pWrh!2}j+=q;@199G^LDMBo=q5i*>+7(!$4n{?UfSVjq#g{^Gb+n z_Jv@O7OrqgF2wZ>-DzCXT)|T0Pj~I{1;GW6B0VM>oko{;+s(h-n5({?RG5$Vwy7aW zqUhu4O@*CDx4Q5a)SM64FpeCXo}RZWQL@T4&QY(@!_56^sONr~N(i*8)c zY2Xx5ZXZ?}_wsBymx|JL@T&(rB;mfD>qCIryYZ-^KK^46#4w0=gXyn3zGFlqddv%r zpX+U$y~^b&0aU>p*v8n;+IzzUX76L4UL+O&J2}L-q1qOexgNG2My#2x{+1LVGJF-3 z2-yxHrC|}A9YcDM{XQCg>%A}tym|M0Ll%$hTwcU<{d6G8~s;&U1 z%{_3k@bZBz!wZ59<&_CeUy_{l=g({a;rcqAp=ySImFc3sZoSiJ{Nw(uw-DZ0DV3@BBX z=O!-(;f+dnap6ycU_q2*qeVjh30LXZLzs@roqN<0Zn0f+ z@2L26a*@;Cn?szt*V|Y(O9ri6giMl%R0CpZ96adnl8)U!TQhK%dWp_B|wJ0}c(gWATA) z{L%aNo!nnZ?Q`5%Bx$0hRE*mTaD$VoJJGO0Vms=L$GunOs_oKq1&I_cda$uXS-d7( zzmh302FHo7kqaEeH>8nzZeHGzHQ0kH9j%zkeOIrh#4N7F0aWJK^Ts2CPqPAHAe>bG zf)`c*XFhepq2#0Z*RCToX`5!-DZC)Om=QvWrU z^rXqxb1F#Pji%=TQts#upWuKynfm>PzH;*}(5R-W7xX_@Fbw(9B|60SuAvm9(LsKh z>S~mkKnm#&U?U*D9fPl4`0?2e5&(t(>n$C@x?W^?18@|Gf*=Z@F zpGoCnd=9UD0FJ+L9&55pv3?RITZGzwPEg#8B#ikuQNUib1u|Dss)Xu0+p^u~6r_FI z*Iz}xWQe|l&=Ik7;e8PekOy1MEHv*kU%0)Q@(GIBwA8H#a7=y8)wl3aZf{^FhWkk< z=Dx{g`_B?m74yXNSmr_a`SiXt?IfQv?F?Uipl>A~=W(S*%r@PR*?7e!rSnv4=AMDV5p)Z4;DG;2`dHHa^+odOVibkP*5 zD>-=fHp0k&=achaw>f`yeeOL3;(154VQSpT7kzi}kccK29dM!8tK`!c-?MuNWnR#Z zC(ST!2_G=z5i3^dB<|!`Fo0cd8d_8&iYj(K$$|UE&|7I}y|z-RYS++HkcJu3Len&3 zUyHT;)+p+mdCiZ!qGM%)gnY*e{-fp~uAdz-xkeD=apvL)H^2 z@i1GPF@41sa;A-{vQV(?CL(%Rr{o0_nPa(D*EuKN?w~; z^@r4WmVaYn{ayq(Xr&EsHIrz#FQ=t|3@_Kui9nIT4Rr(YQDVug$q95*M~s_ z;K~arIik#ppSILrh*4vitN}yTyN$2^6u>OwFDKB~eNTK$PCKhL$xE0KyTiZDQ}f3bUtATOb*AZO-DcGy7t^% z;6+td?JOO;mKf?6&1#$}JV&A^sYvWI(NhA)E`}ACQ`yz?RwUg*C=siP)}Dj?p!?RB z`c+P!dan-_#_qU&?M~S;2rD`NC2FVAz4Ds(v;+bg>iX;7;nTY`(kvs`H$Ay&gL%ja zRK^}I(dJ3d}>+3GXa;$i}Tho-Y&~ClqSSba3Zem&g=ySiV8UO4F)KzdxmQ>GB z$Qgm#f41*lRG25OO?ma9j)TCTo3Mhv2Tw|~qT1)TMe=hDj@M3k*UQ6q0!--S)u3MI zRiOsJdI1srQvh7|ST0T<Teib7gqNk7kMIE9`wZ;@|u4{@#zLi*A>%h(QTl#xdUj5%b^i-j5Dj5_`j zLLL*An6dWSu9T6tTlL2VyWClEFy9`iF_p$lic=><>H5>tMQgL#J0#`8}d3n>sV96xue zh*>@ma9^T&@i2g>1$(KW!LD9%&R`oQQ`nla<2NW=Jig5NXq6myHDy*BZrcp^iOMck4IMU?O|x_3Z8EC6P? zcNDbmRVXPp9%de_H70&>o9OcE_f2G7UBT4C0rSi{&;NmmOD=zJaw+*5o%clkUy$fy z()dh0lO17FYRlwetmtNM~?aOa@qiiMrIaGU zK|#}h=cS4s1-#5r2y`@%MrB@h?!b!mJ3qOuG7X`u7Mp&2!| zT{@M{%}7qvGS|@Kopw^x8#RhO?{ymbI@AwxIAxa zjN?~X(o(!5vByG<1G(Nl*@Cx);_+$~(GtJjUIGK)m1gxn=(95H-SmAfLfs=jhwJLh z+>I?hd*Vu^j?bM~{Qb%r=7aT!Xbu7X+sbp?@X4T6KtK4NM}Ku4EY93_o?AS6Gm#DpO5uKG_V^^-Xr?GF| zM-82LX1d$;0p2nO`i^Wlj<#G=g5s_eMCoqRPs;3w zy)c79hMx32$$9r`#w0+nXN)pew*PJb1EvEd#eUG|$ilNJdwD_%@eE38MBCXYaYZAC z^@LxNqi}=nz;NC%qFT2-0a~jMyp?J6tC0_5sAj(h99B5AN|Mu?^cvB1ADtEzj=E_N zHM{a(u*2PuSRnqFYA1ef)lVWDi;5nJggrrleO<9~H2aBiG*kAXBWo;2QJw-EIM?|cl(EPW9}QK)g=rt8 zf=Qiz#{j0C6NctJbkqx`E1?o)&<9jFj5DNGtcD<4q%T5=PJ?ludVoBrmmo-(!ax!p z3yf(|Lve!wwK<5O{JS3}jT=Qu&j?1C!;(ihbB~-1#HU;$-FM*Jz@*eK>6ErU4+8jL zB3}$Gzz32IJQSsQOc!Oyob9pgPu@E%m{@D;TWHOE>h4EN;=}DDDfB%(j9vyIZJ&pZ zC*Li5C#7QhFx8YRad1=E5%500`JPC2~xaTx?m}>j{B$GYSwn@H{FTe&g$l&-u zmrh1;srhg9hasmqZ=xh-p=;b*&s+?78qaO?q5X;9w>vG1|}=Usr={fc}!b zW&%g=L)B&|wyQ-j>g}0DK1wCg%^_l8?P+mOo0=xt)%(1tovfB>`K>Q*s(?D}D*~$M zATN*AMVtebkhkb=dKL&uor&cgAF?Yy z$;R!oj5n3;&SsyLW9r0!wkS6qm`fN4L^6WeQBe&zO?kkQ-+^Gcpxja%)$aqCSrO`y z>XElQGS0eWUzjc=hh!yEUzwSC2Ahkrq&`BD(~_`j+2jXlR5{`}Ce1fIqIpRo6YEPY z6I)XEay+u_+%yXN6;lHs&NIcgtSZcZPwtiv=|FIV=|cJ6?EbuwPO*FrVW)t}f7|%` zptOD##-T+yY3bHK@w;r&ct0e1h=M11I1(C77e^_?L{EVlzCNlEd|DSr()~EM@n6oJ zN5EHy33lO3u3!G;ehOR|fl^(7c5$&Nd@)2 z9b<0!&$%#KWYjdnRoeNPl4P7ZwqgrYu51YQ73E3EWytT~#Ohaja*DC&l%4hxk@?SK zIb)V9{VT4StV;R|=2z0`Av{#=?q6M5*E03P{2wcMBoA?hZNhfVfH| zyTubuwl)C!iX4K7zBmRL`IaL|2CqMxuox3BXS_Mt?s&0P0-oAWE#fMryHdu z;xWFsxwq#kBE!ICB#UZ;BApA&v)^&gsiCeBLy7t{0{oi{#amKLm}ov1obJs#N{Hd6 z<$ALv@r$MQ?z={@iQh$(;>-`6099N?wixQdd}^;ES7RP8;mm8Oy~VTMSrp^C)B1{V*5GlD6 zB*%y?Bh74Ang*4j%9swT>x(9h8QQP$u6lBSSEy z-t{)VN-`(zq1awpQ6H|6b3gGIwPv?z$}Hyzs#Y6d%x~i|6xhP+x8Ie5=8%qN1Sy0A z^Mz<~_@9^{WX=qd4c4O^HK;jQw-$^_LXF(S+2(rY)xxZsp&s<#jV!KZz7OPmoZNvv zVqzAYt+$TcLt76=WwkA<*`Lxx+y1h!UsLM8J?j>48Cy7_^lI`w7*9^5)B4rf+6Qc>Vj{V|`B;He?YWi05L4$F1I@!v{h21_Q4& z3!$44f`2o%HyuU)H=6q=l55JHeN&h!5G#-pi`Wp5Pww-;2dUswV5~ZwzAG`EzPzeB zUXBaVMhe6y0T-@Ta9i5(AAPj4{!=ZSg%TD&!c#Jm$+p;>`$buok4oaJGySm^wSC`R zMSYrGqtYdq>sTB70ETXvd>RJxv``X`CLcj%dRJ;YNz2?AE><~ z8v5j=_;Xrs{37Nteg9zoRXklQ9K{izLLOQ7;0vde%#fDCu>=p~2LICLHC}!`*Vx;Q z_pg#Bb;a+;klN-qhwtCfm$yNkoz@tRmiTR!NlYP^;1%USrny4C=ghrlx^ zi^bsTHfqcEeXi?@QJC>hahyN$3_FjN(g3Hk@v@W-_RU|z-U$E0oM=I^NwyqAq>+pi z(r{lx3xgG$PW;Z8t7edSBC4?38r4og=whEkokFkRRU%6X{v-}DHxWkb{iR$T=ElO4 zgByk50kXvkQ&As_gqf8YF)G$;s4}`}FO;8m70Mefi2Qf(ORaCyY>&>`pjE9rWwQ7lVG;h{n?Q-6+F?&luo zLhr$=;3yk0_oDReaq1lYo_BBC3+eSioleLxUF*xP>lU8b7hNV8=|uoASf1@{l=l%K zgri!1#F^9 zsc$mTuD)6Q;ftaEEq{tVZjINNe=H(g|G2edZdNT+euk)dXXXi0TP)|l+(U;Z=Y;cq zCOVqL8`hJVAV(vMf`X1Co5W1i!AX&|?J^fU&RT_hXMv4Zn%9TgrOW+^<^Sl0i33EhKmz2oEh#Uy;y*#_{OWs#Vw-TXMRJyc z1*F&89khUK+`iN(O{k<{(LW}Go!4Um)O8+?)l^g@+z=o$8~}wGd)zW;u*^&lFhoQ} zdbnYn_D-ppj+EE5IKfB|Ov_d;*l{-C79MrW_Z}1#I*C@T&`2}`C+g#Yg`w`WPTe__ zM0Gr~_Vs6?s#i`aeazyYwtxI`q8{-pT|fF6zM2D(!&AOK!jb}2WU83ylWE#h%kffE z=k;5`*kKez%EtAqO!88cl8mvINX zN{pR^A&F_Jf!sUvKR)W1%=a5&*!#w0)}o)JubfHLVU4Vvj5`M#_ zJW&}AmhtSFYkwZ*7HX3dc}+_Q44|$$(w#ono^$V(E|R=jp&>qSc(W-ft{X^7%AVE& zjXs;nN;`f!L1N~V`_a!F^Nw}{!b{)>%DEW8!n5yr{miH57$lk4W8>r#vXH4 zpkSH!r%3*%-oHbk6^VUn`)mE*;rZW|T*pA_9K*`9GbU(YU{Gx-r0<)R?AJoc#Tl_s z`i9Zqqq|l1;E(vqMKCkWaX-SLfcKZ?B>`Id-f}`d_d6!WOB&roLwr~jI$d-x-AbZe z5LUnnY)0IFOe_Qc+Eahs*~0WXL{}9v*n;Ib0-$)}v6O!*OjRCl+A+~k9$%JSdt-6i&PGE>|#;vh)*trN!)Bc*h?AogSZ4HK?;vi}>M5?W4M9Ub~ zsM0&V_9OfCXOT&0G{0ym@0i0?dtQ=ge$d0&SgShQbWYqQkz^O=&bpnv;3 z%O4Hj1lF*yoiO0U&v%9Hx*|J6ff6s$(smWE3kM4#6sWHEighb}cUz{oQ(jILCCw`F zh#LhxH~3d=u%To~PhQA(SFk6ES^91%gFsJz?wDR8EFL68ECEEooiiAB(^(f?$=?#E z^+3*AicS~gGlgRiECV=zATgq=P$UWgZDJoo)-Z$M%(ET|BNe3Mof3!I5Kuz9Ezj3u zI{l0{H%rTs8J~B0%a4aXujT7bMMWiZQ$D_Mtw4TQ41pI!s(BB!t@Zin8Bj9mC5fn? zT3;T1IndA|Yh&@#!iKgim<*jw$FtAITQI*}9OrbZ@0niso*}8mRV68rHt+&)nSUk0 z)*X&1KvA!Jsz+AAyGA_h|D-8T3)i^C4govYF5&Yz!(uNX_do+tL;FhRxc7=THKS+< zitZm2JBDC594R?&I57~505dQz?CzSK!bv-~ITWWv=9f-FnC_&IQl3pg5Sjd!Ho(>kwX^v;Z)g44ZX2F&O`NCD z*4M#t87@;@>kN$7om3VK34C{$>$b=E|3khJjAUo}K0vot(Jm^xcE~<`Q(Qfbc(Ao0 zwsL^@)eFPmuBdxkUUm}@j`!z4L+oDG1pRnsh-{l>Y=yVcqvX_PzEZ%X&3CAJ^LH8Q zZ5oZNtcEk+ zr~qUWuFHD}8{(JfY)Jbx(PsBjJCFPs)`Ah{Z*}f`QRiB+^XEP{kZ;VXlhC;2lu+an z0U_CJiSjX3C$5(mss@g#x#zuLk{5zy8qQr;@qI~nez^1GM?+M-buOJTyM=&GFrn0? zoAlW%<;z*zOTln#^Wd4w4FTOQhsFJv1uzR-aQ(Xn$kITzMS z3^}kRkd9LH^f>&pLSheXjLp_l`AF+SWx?H*@$)X zqE~2#!j;#YH`8||C3Bry5R#K^&)yI3^7k(@fqD?MFd=UKiH0mdzSVeBlwzPpR2+s> z8P*+YeOuluUD-Lw;t-!|^nbY6G#P7&N1gO-oNq?M`m}hYMjL?mtHWh73o01lRgoZM z4big>5ur5fVg!&Dh(aEt6EOQCxr6ZkE0*JmX?uvuhz-73Xf|!wGF^qQso7oJiOC0712`63d zc@<%ov)A%K@M&dTF4_t+>5gvq0>@PKPwQKk^WL_XY?+zvPblxSJtn=A>q0N>Z(egR zrf>V3-B?qe-CJGXcKU+}cdgfoFE=~xNw=!}HZelKhWaU*Lt@g>Tl;-XABx8D`MrDF zvC3*mvOmbg!QV^g_x5RY1CQ#b2g>75V~JfEVYEzQD6Xi}J|~SCJ2~-mR?9YeScy5- zWaK5Df*W)n)E|6kD< z%=Iw!rHn?20wouz3R43Fg?jBlkLs5|DH_cn5#Yt3;`c81H!r2I6X9Uz8S%b8i~E!q zZmA*35Fid!iHjOUubPKRzB?K^DOARxK(TR7}ru#hE|u3upBY=@fWKQ9RJl zME?%cvlr=$p-EhM9>-))@zx$E-BukrhKDBw+g0D+akCI2G#@5nd^LZf`=t_+=bB>xFH}V}F1!YxOlt>^G+MTS;wVK8rUq@8Yq27B zR}-jVXXSHD&0NrnJ<7TNNJ@cJL+5ZXcM)GCA)dK2?0u<8?ujcTI%5N;5ri|H1+j=^ zHL#3o&Qt%U>97B$OJThbMPd%Lu z9Dx4lHJ~>q6*kR(`+=wWvTre$&QX=u$H6%PqViIuel4A8aF`9ri@;eYLVS0xc*R4J zCARvy{)hZ(5~EFV!BEjE0|$ngRxWv~oQc+scL*{)?b3YmgYh_vOF#SQKO0fJxSZXI z3|GLM(N7sl4GzS6)MI;YF0X=TmCXrOm2=*=Pun`Apc}?f>AOt zmQm3u94>lKBxj#>>1!qB+|;F~3xA9q$2~Z0A1!q@Jf5=0zsYbiwmqnG2Tiqag(y9F zzX5gS4xWO58ktar2I&A}QTrkgvg~uapbC|vSGClFNa>;izO#iqxGpMG!u-39Z|oD* zzM~Zz@N=L3hwddCv?~s7l&i4dH=JQ7S2XudZKb- z-x;uBKex7xu!c&8OxFPzU*5SQ)7kVT<&aZ5(`!wpu@9{0a(3=WM!czNYmmdFg}hv2 zNc(bkJ1iZX2{W~pq3h*6j(i947w%VgUn>?4C@wqf{H)~6q(c`6yj{h0e2ivs z{ChC?0#|>|lldgN&w?sEXBfq}SG+g#`V9$+Wx{VTL9?Y*dI>|Q`gK(zU?L9*p)5hx z6jSdJAc>B#k$s4B|44J%GL@v~DUQR>+5zU|M6Tb!Rqw4U8m$%hi8oBR(e++hY?LPe@PwTjNp4FzDfXZqMd*{HmQZweZ7Zb3wj& zfBl!rB>)}4i!m39QG2$ zR312qaY97IpZOd^MGR(;G}{t66{$TMIH6`G8V6Fwcuq5!a|&kx34Nh4ccKTo#3BRL zo;4X-@0d-E;mT#*j~51Vsp*G4%;I>y`fcV%+`mzmTf*dSUO!4TZf^eWVpJ2!R=Ri0lD$icY7ty*6; z8^3CT+%o)PQXE&elh*A{$#Q6z~T&-{oD3%+H zsQnXFKDBR_D6Tx}XQMM*vxJkWU)>Hj+%OMz;hZs0Fp^IF`Ml-L6KrTkks_U3^6Q*$ zokQyxktv!lNO$Q*E6Fx?69j{ezaa-;uSRx3+a+q#6? z^Kc6@NgqLJaqiZYe)e9Us`w(dHA6SWD*E*?utf19S=RDD%L>0Ir|8R|dsp?A7++Q* z!*;O|55U__*P2H?jv*po$0f;Y${u?c11C-sV}Y9JmTSJ`k@yjuvroF8rPaJ1e8RCL z3m^($56A<@Atvu?!@t{PR?p-3{HL7NrnTXrJo=d<-`e%c1CBR?v`>se62utNjbb1~)j zPUU~Ba4yTjzW9A68~pu$U-b03`dF|_Awj6J`5!YYvI9{r4B4pmK3MzouSr~2?eOk* z^GBX$gdoaRE#!lFY`?e5!@k#cFhht`&`_OUUQp{=0!;T}_?atYCp8MX=)Z=}TgGs$WapwKoCe8X?n|tw9xHP!&eOC|b`Ulc@e@gb+vP2(v z*S{ItHe6T8oE|OmTogB#Eu`n$%W$0hX1-3n2@8JF5FT^H_&xXE!47OF8t8Zh*JWB{eu1Fdt>6h6}>*!%>!%6sQ~B3m8Xp))XWZ5Y`>jc z$AM#!ZBv$Ft`EiCsifqR8w{Ni`=nqmltwN#P8~0P>w7W9pkH6TRuQnvfi< zYD*iS;mD6+PA5axG#nh9)5K8h^+QA?6{cgHYhyewxxCLun*yiBYLIi|3?Cl) z+VGG%7UJaRXm&FL9P@5A(h`pPR{c*A#=roK=V@_%|F-Vt*Z;WkF}Eke8xusGrKQKU zJ`mJ8XVj!=mJZkI7S`uNIA3P(uh7)y54tP^t#(i-{jTh;xst@cXUCsAazFVaq~zR! zz~gev=Yj57X3`o1d#Qt=`BScx#jV0@Uoh?F^S@wUpKY&}A@oxqBlOXLRaDit;QmQ= zIenw7K)50Z?x~CAu|keT)qr%GX3M^DzA&jz4}1*c+Fka*?B^xKHj{)de3U$j%C=H+ z;!JmLUH408dRd@2yOR~mvGv6SkJnBrgTk@2y=y+Mg0WB;_Ei)eY${7VbqguPW5u#_3J z@n>uR6%Zx}Acc*VC!&2vG|si#6Elu(;6>BISdT8jv5{uP8)jMn$s=X{V%EwG+CX-ue4pCpadTE9TyzSh64DLC47He3aYBD+#dY!Fn3qw{%MbGx~U)t~VI z{a3LWg$hrF{n&4Q`}k2-P0SoB5c)=VU{pZM???J_*&`2_Y535%BybiVAM0v<&b`RW zEQ1fKLPnQCegGDad+_X$?@?B|3CgjzwCk;4ds7nU71<*GmvJnN_9R?;O_{dvs&$fu zC;;~g^Bem87$_7JYh{LuFUYv)({$61XvN6S-BygFPGW;l#0ja@_i%i1MpaD>&N>m6Ymn?<+->6C>Ky_BuCTw zAj#9#Ka2SzPr4BDkFr75lKi4Db19Ld_m^1SWw4=CykU3@`3rSeR1G!EkadzqiJS!n zIGNY8Dqw9sDKhVhNLx+5Ro>PFGhvnhQ(D5osu5$h2ts(+H_s>F+uHjk&H3RQE;{`a zni&5l`f1C=e?#1bjrwPdva)gjWfSievH*(b-H>p}Nf{n7rs@o?3=P#47EBwOqs-fE zJJ}y!Y}%vUJa+=yxTnWN@P;xvx)s7GVA?T3%{id@D<9X5P4IJUBk;3#`Lf zR5Y2aM}(rSb6m`Z;ejiOwL(DRWz*7z0D;v>JVGbrudV1|AgFHy9NTKqIu_P(g%QBn zEd%a|jfnI;l0j#fK_w3eN{x`PNp9K(zBCXg-e|rm!$hNdnhNK&1Vv!B3G(8Nw z6T;gIHn2728Sis{7nhR7f^$A_3psAic)HERAv@D8uWKBYnUPnGMCQ}=KTCsdYPh^) zlq#CVlP?FN6QcKlfi6o{UU3|K>Q+5l{xh|LoxLJz4`Wk-a*@>W9suz@3i%+_N*bM9 zfj=CYiA?3$e33tQd<-}Lb)9|K%vx7_G;FtZ$S&yTcT}dHzr1?VGON828H@FMB6BS? zPh`5yPrqI~x!6O970tED$IQV^mc>DhZ8aT;=a;M{QyH}pA7c;$>?1;7C3m*yYMP8$ zdzsCP@@Vap(>q_j>e9&N+_d+``6y$v?es4v4bCc!1!IcCuuQ-wp=&kb!K z$*o_%F7MRVCvd3?A4JzGer7L+z8JfqPj=DX*oc86NC6keJNjQ&6bV?38A_pE9MtV=u!+WF>hhmM9CoX&q=Ak3E>M0{$p5;nQA;)R{o!{)`T;x;-E^EC25M-Z?I| zHqmx9hc}51hQ9LPC5y-hxuuHMr3ocEb!T3XE)}GK=%iq;%^y-CcPQzY9%h*gmvUM7(=CQGc@xZP#W3?;_mM603VnEI5LtU_x!y!g5>9351 zwY|lptBj^A)2`*as>|x@$6!U2IZMGLF2*tS&(VE(Px1@a z$~13OeU78FPl2IQzAfOEBPt0lx!35QiGO=CzS4JhqE3Fjbb1N9;R5l_CyY({N@OcV34-I0KmrTHe^s>0CNu})6-12#xZ<$%q?L_Hqct( zr$LOTqkksT3u?jNvf(!!?mqcCzfb{pKD_)>N1>rX?qR}QsR81B4_WlxwR}6(jBl#& z99XOtY23pskE#eLHvRiiR={r{Tb>{>4X??q{trbfS;BroAud)3fiS^H z#*FHYzLo~Ts^xgJ2Q&3i`mIH`uU0dsb?sUsBdaq%&kcPZau3#E)+l>&{K2{wvI7yC z-*=0XGSP;D#d)rFwW$SoksIq2pU2jNmgg4k2iiFOb_9tv$|!?^X|wfB{dT@dcBrL~ zyEOxSR92XLzxMFS@`b$EWZ`>4_Z{;y^+Bhia^T&IcCq&k+sa=>SQ|6JZ5Y8qkaGvNp^3)YZUbM6JM6dlQbzs z-}NJd_+-DP*Rn3274>d*Q+7Xr7oO7_^9K9T(-SAY&AfEWgy!3>0JDpJt29hn zz<_>Ns8T6z@&yd&5Qf&AWMaxodOf119p~O&jqt&|QSi@I4^AV`QH4R7OC0uV;3}OP z3&e+35712u_wtA`=kOy3ecaTBfsEfkQ;c6@FTDA_eIPKR?9pb94m*xr=GB|jUtd6> zLc<4A$x>aQQw?)t?xoKUUfy`*tmd0HdQ_$w&>Or0W^mJsAqBJ57iWB(Mvk$(yWY5`q?gZwB>9_Cs z6b28PQhh&NYfwr;UJm2tzL9+XP+~ky>DVw1t>)6Y^<|cKUZnT=L*0q@iOKfw>J$g{ zs&Q!>Q>P}+bNj}1Xz|+)U0ptOajb^`e$h}VXGg1LYhI*m`(Z95q7}O{I$1goZUYow zi$jX!M1lj(HFHRUq`a&kmYsdn~NY6`+Rr&lML^QNm zvU9^k45R4kii3n00o899f4PMLS{EjqR=*ocj^zvn-pdq;Q=+|jJ9?7qC!ReIoq^fC z`-VcwNIVJ{^(sJDb^R*tgL00wEAr^BiN-l@PngFCO4w^C*_0B=AqI{&m~5^XtTD`; zY7fm|@3KJiFr|54@S0gt!;EpxyB9BnwYo3`Fg4qd%0Oy`w|)_1d+`Y({B!f(m#^8C z&5C|SIb~C3D{~chg+0pNAxR*agzNEFud_k3RCtUWkb}WnOyc*%C7ezqVx_VrP%yCq zvtZeo_?<}{KfAw%aX7MR3Y4Vx#*Wpa?V}B*qKf|ZL5drY?!_Qa5mG6V4z9Y)CyPgL zmVYQI)Q?I-Iv<)H2}%zWW-GF=2v2MEq{;he)FsFCawm{+%Wp=6IwR{vo{%qoU42!= zQtqpD5n>aTPnM*H(bgCaE}uu!ApV;u5ufjJ(~x{oYtFjlD0AYR!LOmVaf^y^B><&) zZQHo)^H3usyRsm@i5l7amw9DlY|7FG}ZNs?n*qPWlkIoU} z8JKOq6DWU@csfO)K*wWv#cifB%Uw=2K?Tig*z4Q9LE6kmBb0-I)pUNH3)~GL|HLFr zz*slFsOQB{MZ8>$iSJLF%bI^AeKXT;y&gRyV(jHZCgI)gyX&CF&hnu@EiSTkBx%~jHsL&m~@OuQuhKQBNIo>{+mh%arAAozT2|DwdP$nUB5 z^cP5Hu4e69)5jDsKY|I0m3&qBYK`OvyC2V;!76D_xU+!j|NbHQ4 zC+mcj(^gWxHGgXm+m${o6`fhtv_F+|Y0p3PCjuVydNO)S)suRpMf=TQe_SVNolS!A zbO7rqm+jAAZyCYyzGnWcKJix$gYOUS*@jEcJHm?{YukpFGGq0qoKg%uzn45x9#0EV zRgF(m$bh(ZtxOnnSF|=*H9xbpvhUC6M#1TN+jj+eq@RskDF;uQ>C?`RI!8z>^&Tw^ zQE{ilj2x(s>tJORK@-rfk0y>uNxOTH458V5-PmJdDT%2)=cHNt4=H;-)(-_m)B`R~ zA(I6(e;zzw1L(PEU5-UJ4}H2H6;9H z{yq@Hh-JmkLx2x`52xpU4Io+t<+B27eV-84n93OURCOZtM%*1+b&rCI>|~!?S2V~e z#s-Yl1xvF@R=+@8oz+YT49K2TPcjm+!RD4tgsu9iv+>{?3PuCZ7ZH%wC zxn7!ZS(}pH6itl!?B|8A8gup->hfe93x3LnhK7HyxO@5Xvr$%lBs!3HAkObcvR!zV zR_r1N?S)6(Px|^J45&l6&MBL?9r{;^yv`MwK6|iIDQF1wuXs3|usEbf7@ntfwlX8Y zt$A@*@Q3W}iAA+|`ffH$sVcI&C<`BVp<1jTE;!(V`UOs_l-%f1-S;0Ai|-GU4I8p=j5Wu&|{R#U$1tDNP+Als60J3ktT~%e4H|)`Ww9 zrWK?W$v3Wg2%VXfe%Goaw8}sNt#-r#3?R~`7oUja{WFH2l+fsqWQ){1WDsp&0aJ}g zCmuOSaLPl&A3@9?-G|a)gKqTZrOt;BjdIkVa?;Szc(Nbfv!pSP+zMt3WZ%^cl>|Pg zi!C+0f0k0bZEC!l^lfIUsnhunWI7~$2rFHlGrIiuS-WD%kZ0)x0pt1b>zcUF#qkU1 zr_3aE(jk2nsNs*2eUxT?3lue%i?d>aOz#Hsv3yxJO?2EIKFIzR@AgAkU#H!~^Pp1g zr4-3VVmG{W&iMSw$B-wli$V3q2$=+hx*YY&ii&3f8K}gkKsD5_&_D1&pmCvI74}M! zDow1!ieJiqglXN?__IqvUu>TQ7G#@V+v=QaOxVhcS#kg@w(o*AXW{zRm1L{j58sYT zDM6R&_7{V<8&$5PvJT(vhfIqvRIk-J^cOOAE|`2x&>-YgSFQ^{rFPKL)Od=q8du;y zbn&uQzJLki`;LL2eD8KS9&=Oj5N~9PvRdp?nD?t(d7&> zCX&T0h-Xvw?{=kEcEL8?PH;I(V9Tz7T8!5SsZ$zu5PN zTaU6bKAzul9Wmy_;aXB|65>9ueWWG~CIkb5^hw@&-RIrU@MdJ>~#eNetr+fsnAWKCS2P19 zTN1sQHcrr0_eKCoc|Q>!6Fd%!%^i4Xa=VF55;r++^9Q+hxB8x{YCckkOp^n2D2(=f z=JsWsGWqib*E`WIyAt>a#k$`5kDhC^fU$+POPSz6hD3IMocL(geP$@-aQ&(zhq5If zdBngYYJt+r(X=%uMY7GE)vY?%Ricj=;wT+|^Z#1*8L+ZPMRR#ZgcD@B6z;aJfQ~dS zU{3vbj}&Sfeqhc3GmK;AAIBW0qu6$Ehrpa1k9)J6lC3Gdc}Ivxys0q{D0Chkvf@GbtFHoeyi!D=+<{zRT9}9^)xAN-sp>gl} z@s0o!2;VK1U8Dem#9+Ko2QYsuvpfL83_j=TzkRK^)fj&~kHD~_Y$QHpZ&J^Y^)@7! z7BONMVU~4t8Xxybo+U?OZ9iO;o7bj1xeg;afIrDM^Z#uBItEsgexaBam(YzKwY9($ zPP9minlpIA#-FPOu+S8myBnphx;n$$)BzJ%|Gq9z`*L$1#tart`=KFSUxSL?cXog} z@k|GnP5`db))9c{eoX~n^I+eHg+>l2BeRA1M5no42#X`{L*kVuhFfCoU3+dA$z9~j zx=JNXzX!|U@B@SC_y%u){BKMH0lv)Ho6GD)7yfv2LwvlD<CZx8Xj7 z)FYwR)^EKC-3SLLV-ZOYwnFnpDtk|Y$lg2KFJsH#M9%FaZgCc{ql&T|K-E|7QDDUf zF%18iO5)`*UtUHgikzf?;pVq5Z|Y*0B=z+`0)3Q!Le^!}1Dh6WKMFj?0(G-AVI~PL zEvUt*@9li|@r~KC*1rbfkb~ZP8 ztShVboTJZfEsdQTYm-%sw>VHybILQ90Z*#Je^q+rU61<@bCO5(v(ma(a=EuxIm*{L zJqobvMXQ;GN}qewybdDxghs%HxOS%#-gSHWM99C0p{cE4pj#!7#h}E5Ov_7I{^lm= zWl-yO-OsS|SVgM6v%CQm-0Aha>pT?_*KwIXT>^vUca-#tHBwqOKGE6IU--X`mdn2V z*2T7FEc?K)ye=jes+fnG!xYbBOTi&aGBUNfu4H?pl2DUm{VIsnTvl9*UX(jJiw4i` zP8{);!h-rG|;qat(5PR?pdP`+TGVZX-=9KcXMo!+0x@vF=HaMA;7Lv<4w=*N?dnHE8hfRaxsmjyxjI{X)>P^M+!>Xaxd{m0q>DyF@?89bL zW0QOPGM_eOXYpbj+P%%g<(1&o`>o#vA594I7)77;hJ9<|P*51Z@f#_%EZx39y|dvL zmGH!CG4m#_0pKFXoS_>VT+mB=U7bMei_kqI;-@(KI2J24;m0pIBs70U7XG1!7Y9B$ z&DVJ%z6=wkx%F=-*6Xj%z2~9!I#VNhxN8B2^q!AiHMWbVc5Zxd)JL6Y4RgEa2$l8j z^5JAv!A{was-Qf;B%P%N#oG^2ka?Csvtr>4+Xwt08Yb>jw=v-8L;}nahy`>nSVhZ?3@W36)XwP8(RJ8sEc~ zyzml@YR5ghDSyIwLtsOOEk_9f%2JelEhatkMk|>Y7RZt94~s|Dfa~zM7sF~&ii*oz zaC`cb6*wWXMZLyQs7JYtF4}#?o^{Lh3>h%7vEWzgfuj_@?|geEhX=BZAAC&Tm&j99K!)6}7<;5xg0SnKFfA{kcUr{G;8< z3$duYTvl7*83|Y9$33y%XzNaL4T@7Z0G4QFlF4KQqbZ-{v@2+kdu1PO9tOnG;2_~R zilUJBBfm(@euGxjqp}{k?u(mRi|h4%-p#h;cjhyv zfn2i3QPTl6jZ39gqhj`q_>pIprjl0ioWn7EZPr?< z5#R{}b32<@J^QsUr_L|1669o=Fa1zBnUQE9e|VZ}yxK#YjP}12am>?+l2XZ|uWQE_sN|!F~OSJ05PG$5>$u#MNipgO$BZr?vg3+ z-K9a9Ulm;rGY83X3GTTd+cV+u*0TYI$tv}uR3i+7L)g&2m1w*~q#{Ys9hK6je_Au9l>2=YPu%y6?MqN=({p|M z;G6sYAG@tk`^NI!+@qgh(AE;Jwia3p3jT=4XV#vcJhZhAbct3qh0MffXP8~+1Sf*B z3l>jOLr_fG{3BL_#eOF+UotusK?U;bW7I2^BQ+7z4&dEUdC|2GQQ<<<_>=eN=VrLy znAc_m@ij6H+6nC_7CtJs+C#n8*Hs^A-Elt)x^+{72G9cg3{IQKXCjpyME5nb#O$y!YNfn9Rp^bS{sD0{`jBw!b; zvatFv!||-wI{oV?{mil(iz4fR7kBMoTkyGWj%(hj{TIK=yG+yi(a!K|Qvj4>>%16= zvIDkf$ZWLXbs>&y#}7$(RV9#!KIt<}J=WbKhy3l@Vm)6v1?WV4j55k97tzF&Wg@GK z_R;>zb+yNkU@zYuHYFcjMhuc#;)R9n>hi_wO1vc@t%U~cu4g48cuQ0r2(O0r2Ods7 zBzIKFUw{(}NXm{qK3~(JU>P>^rO6MZs@j{@sRM=iS!vQSefz?F+C8n)H(x~Nvf-GP zoIMNsNVU3~ttk|eiC+<1k)uDsPCnK!{1Yi7Tfgp~;!&z;tTK%+e5zq@z}Sc_f5U_} zlc&6vPbtUjCu#p27fp_dL_4Sufp%_06`$vAqBq(LjR8Q}MeOH=rB+i^_u^DJOta+Z?8X$UN!^X@{<+x()L4^bG?ArN-l z+{$2WAnj2tO(2HO0MgdiID62A-mGImx+Rw-7R1NEOmarO_n|Yg$EpOkhrG#favh8j zXC-fC$WKZij9N;*b=@SqThgk- znN?hpmuKzQd62|wW*$s@SI$rvrWNY^PbrC~yfQoNtn@2n>M-6BB3e@H8apMYa&WLM zC4;K#YSAM2oY)R`oUNgBYCSJ5x?yjngvQOe{1OqF*}d}v7pNRV3o}}#!I4oDpf7|h zEk_o^NPt__=xAlwK<#|_AETnky7)qAkkW{qcE;5w5!L}+ZUgh@!KK9mwz+;+^RDm{Yfw7;vEy(G~jv z5Nw0cE4q-|SnS>+@&s|B`XQIC=mFvPUY!pG4t@PKB%69)xQr>kL7ehFu&owVP9SWjl zTw^O++Q?}7Z{*HbygMAXP+#_lN}`L)Abko^+pM_4?<_d1>p_IcTI%3&al|?R#?oo% z8cyfWv-?2D_Vc6{|3pqs5(Qh1D@#0>l6qh$;n!+@I6(GeQ$#Ysdy@PB1yGs1RV}%> zDN%MXLcjImJZJ68o{MR(wo1B5!R!NXVwV@MfmyXZY>f1X4$3Jwn`pvc)) z(P$%2BIawtBsWV*Q|rE6_{KaS`i)rhnddNT?U@J@xdKt7r~*%@gjQ&Ao}f~Pd}h%Y z&~&5oFignrO&nS#+HX}?rtC8Ql(O%)*qJU(E0Ff;D$YjLf&<(B(1(jQtVe%@Sm}Pm zKcNPkkP6wca2$PlPC9*Km||52OxXD+X6qau5X+wEv`2d^f`76;8Q5v>C5noB>Gs2Y z6FK;7p2;m4&Sdy02t#(nmka#|A&H9+pv~o+`LYiV34}6?^hNR? zcLVDCyDVzMyiX})p93N2kzPjz5wusl?V+rC(>7EzN&X24z4wg~tOMg3CwN@8${PpP zjC)l!{V?6_=+r(#AWk{{yH=5M;OfrO7IiQ2anr_4otsif4H*vykVnPsx{sG)UFa9) z!@m8lGQB0U)-2e*c3I4u`+-Ypyb*51F930$-}ZL54$DnSm&gXS@TCWR{0~!eP*zw^}z(24FQ}mmJqD|Ws%$uy9 ze_O9Uc06u`J8PNxCCaBAC>GKv@22aUrWww1+glh_HeeDXuW%U@yerQ~L5x&y#QbIs zDRr2bQjl8To+ZZoc5SbzSea^-jy_#!6S;mP+lx{hI^9haQEE!10fJbIE7b#jxXaWb zXMt^EUt)}4CD}xNra|S41@J+Pti`z}c)>q6=^;C*ak~FByF$A-5oaY1;SrQq7r-1F z%z-_PI4fH!0F@dDVk0V&p%$GsWqB*>!ofe`4jAdETY>)Iut!DXyVLQYN`#DI0a=K# zAbY76mj5o+{KK4l>ypXP<@m)cPw9AqXzI+)n>W)e*MBlfa9@j8ezMC(_h`A%$-bOZ zlnwWg(B{@THTIS4O4e=tA+gw<21?;Oyx}NwF_n0L`^9bDqE)v4{rNLGO1m2ye5;d! z5{_71rW7sKF*N+!b>Egpps@T~umXCvZ2{5~1Kr{S-0AQrck6d``yEMQ$g|+tKr9Ut z^s9Rvxh3M&(99pk&RqA7NDoivLMq9a)?b;#rcxvd?FFTV%JmlrdpIDb<0>eOJOj!( z)z9Joc`4d7>i(hmZ!zhyK6I-u!&pw}Nxs=&hPLVRn)aW6pdWM8lK3#TwX{!JgovzW zxWRy}%%-Zke3u=5gvilQ?R?_qCR^)PBab!7c$3njM$GNwdDfR(G08GT6se0mQ>Vr!l#2l%8e!ZE6V$!_Cp#_C7Jo~SYKaMoB_SDorGL~i9we|;A-yy7;lG2M!7SE+mXj$_bOJ&Qg#~sxb6s^h#l{pn@ zIHuFo{IvDz^`UX66g%jVR+}U&^qS)6m{?FEQ#pOy9RDB~-oT`jqHKHt{4U%?O7^nf zNTPEVsjB@Z2qEF*vTz2@d{jm=$G(?L?8h=bW4ITCRoP2C`n*8y& z9k`beZ%GMzU5x&ObVQUG6YXH{9d`$%z_^oCB4B|@NXDi^p%MyK4Kha!jfvXN-n{-iW0M8>`WEtwBW=hX{CB~A0)@Qf?Z(X~TZuB09Y-!%>vFOlI@bm| zqcD60ZOq$!J5cj7Krvv+o|~&kA`|w1WxM3i$MaFX^4=^at(Op0sJeMm4+lZ>g1NGs zs$!B~a$ojWLP}4F4=N`{Vtla-5xBSa*3}eZYZKmc+|=le-22nTCsm2Ten?K5ck`Zn zVh}!h^`dH{>f`xWp9;Q%^5JeO7TXaWhhnJ$yit_KO65FKJuGrw^aG&3%WNQlfL3qO`$?1rEPq0v-8!BNy-e1C1|3xK1tbc&nsE1+GxnU%2-irx zVbES^Y7@`^O&;CG9XI17opQ;I4t;+`@e|Q4LJ40Hb5{H0Vpxp(()}$hd!Eil@k$)F z;ms?>DDf97iLO!m2!xEulI|Af)yWo4BsXQ8B-aTT(qo6Uk%0D#oVGI;on$TmQ{}LvXZy+jYF6D6%Q2IXMIz?5LQ7ovV zeE5$hMU1>Lo<*2NRI$ETvua2iGOs?D%*X&CZ`h8W$;o9v7++XLZ8t8pyNNNQw~k47 zPpUA;(4A}>V6~VcOP2PLaeDH(YQOwN6b{$Kt&fSUcWulM5rW#XRlS{}QpBCofTwsr zpK3LBJm%vVZg|SIHU)0{K0zeV`ieS&-r2ex;Uq}^l=0WjHc$~pCbo2wZ#*^&#GH6_ zax+*mKgH{gmiB~<@rb%nyhwpIbSz=2W9&w_z#vwz-?ER>!ZSyk`yWWE8v_>#!&%Nl zx@ojNx5{2>{=rP+`#&#$#t@0C46N+f@yG?%CQ*k_$914mA`>ipu-D_fiAcNIA5v~R zi$=w#NoW~)E3GN$G%2n-cBT$D?l3VO1u{eNdzi>z2FSIJ#y`%Q6EHHxJwa|ml*d?8 zWsI58;b|Y2N`ZV&lTa7TV2-UJgyoK)y7BivCae<7&^?Y&K!%!sJ`0`91?}EwKqpW$ zZ31U|3U@?DcjJsS4o`MVW6k<~36&|b$U^3(dQPRzN9JzzqyiABYdo)aMxE%3LGkRllIJE>fAjpwcPA`H!I|+8SLtuZhCkhHX@xA_uAcaO9gNu z;{e7jd666`Jn#}TveCenQ5_VSmLiYXk$}WxIQcoHdJi`vB~{6m#8P0Wo@Psx+xXza zp%`zu_@A`=(&=B;tk!x<^}Rjp;>|-X{NJlDD$NUff_uWyj&iSq@HIa_@z<=pLuCKK zye)i@RV&zUv~s8zrpFZi`a7s3SfBCA$!sKr#YY#kog+g-7%1K{ zl>6@=55FEhpJooG*fK>~uO{-H0+YD~1_*eNN2A=}rhOMK>^b|ndT(}RbUe25Vy%)Q zD`JYE`z7pf(Ue;vc3OUm>4!8i23|f8@-!wlCmH-cO>9Z~dwlrox3?(lWBdS|)^YNB z!gI{?E8mYfc=>_afB~k*3GW z5k`ap(h=im8@`Ne1Fl1K1*po_Z|PUsb|sn+e}Gr)U9aVzXnt;kF1e^L{8>`qxTi>d zhnm$2wuA86q|rL#O(F9*pc>PzYz@(sNQ4#hA8TZ3x(QwuNVCc2$7=AoWT%=dzb1?4;KE=eqlQz`@k#PE$ky_iO)D z>r2Y5?u`XOWg%qYK+@A(2c`Vky-5wq8;kOAMsOjnmK8AyQo~(=6HkS~|1sM* zL*DCh+aX-D5Pk9obfhA?UsP@D=SzWpch{l?N08~DbtRWXa!VkC|s?pPaA zbTHExuLOIaLi8{nMh!MwXo9Vhp9-01EJjbSwk$)xRmv75#G<+%dDN~2;Cp)3y2!G8 zQ)zM|2yuX6tnW2dHA=W#Gc+S$^3NC_TVP5^mbt7S5YA1`ZPA|R8n|c68%K_me`6D_ zvvx_@tn^~7Mh<%aOWsUZ1%ubKy;_D%fX7}?R&<)cqxRiPaG-!N@Y_zzs>w&J8I z(4>_aV1DO$nN!>Ac~oPz#>)OiMoadsDTg2a#kJ3o!zJ|W{Fa(CPuZm7^{U}2k4Ko{ zZ-&fEt9C1o9rQvK8?vY92AK9*QxR2xr(r6!jj|}tuG=Ea{la_3$BAcKhArM zY8ZLmm4;MKj`oAxni$l*%}Qy_OMKo+E*;@ZvV}?tJ~7Ss3hU!i`<3Gq&dMthUws&4w-VH^9{bZrzJJ0;}Z@aq$fW6M?r(N$Zs`6!dL-Cb^QJeVWY5NSv` zht>AXZ`oEcLY&On*s}**J!wt{du2*ONtIHr^4au%ksE$km3%h@+-jm+;h8ejda z8j&4)JGEkoZ^;aCuuq0phEj*On)18Cz@mV!fk@5*tw<{^$-|RxKnWRjd{MyHHWMQl z-AB%)6Iq}rP&#_?e$>1jS;by40PvnSG(n*Le|`V$`@uhxdB}3qp5aS=y&%qQ=U5CN zi$#aHo;Wm2Rzf6CpyzrV0L;bi?E_b#R{?L<8$h7EdQEr~@VZpz7 zkXpLgY2*R&&Nn$+C3Tf`tNSwl*^=PX(tT~dd7@~ZmdreIJbf6sFxyyIMasd)9_d*8 zWTFO9`}8f60$s!NxP(XC94fL2pJ^jQ`F?3vs291+<+zn4f4PiX0*mjcx5&CR zs3bbnk5sCeqxQNyYo~&n*NWeXOaY^J+|n0>WX91ri`Tm>9|Wtu=LTRvBg9?F7wlka z%%+_b20;ikH<~Bw=0nGXx|c9z{CPosD7ox5=zNDgS{RG^V;)T|lHIH2V2@3X^9P7t zj!Rki+J^ey8gKDvp24oD;vP;O9$Pm~j|V!)kbTxxhH9Dp6oiYSBgV0HRJJhXF}CKk*iy~}4fRF{(>&4iOfgVH%;*c!x^}qG zoM2zMF-B5sAty7(XC9-%SCkb#WcH+}#z#f`mT z3To39SfZ&4p4$jAvQD;O(gmfEY=%7W1ATU-^HS+)mYek<#qxuml+{)}yO(bErp31r zo>z#G8GJafzy~ZsN(b&WH!XQWBznSa%`v#fV*fl@=SH(c$nZT zJ}wbA73A`nXmn5{l*yw3wrBb?SFO}Zy%iDVh5~LPd&n>`0^cLRNfpD`Q2gKMr|*8w zZL5uQ|G=_JxLLX{aZ3b`v){L>#G0MIqPNjTFIoJ3k?N>#(2L{?^v86}VeISmrtOxB zL){AjLhHV0;;)O=5Z*S72$3`Q|F;R(!;XFCL>Qf!k!FTR&wp$TtZp z5l&!4{$AK3aKN0qz!q4ji_{QkdoOzb_0S;djso^ul@JDG`{!I|X zKVs`IRc7g`2;^(pjM-_6M7&CMCSoNBi!0&HcZ8SKcqo7pn|@e04Ooh5p*b9J|K(7Z5;(m0tAyDql&Pvpt4ls$(k~JS=?WOo$VvSS>Ofzxr z`ak_MZH154cJ{^b{)h%}u0>pon+ftR1wDIQ(09O>O|psjTFH<2l*RbIrr%H4kFa;J zaf31^-!+hDxG^wP8xY*T-WHqL0e_<;w$_@x>E-tuWHTH0o4aK~cGVa-MTG?a0pvE( z8s93D$VuV()?R+0y<;v^!Z-Xi7msdWyf^Cut#w0gZP`-fR3t&Gy{&*hsE|;DO-t@a ztj9lp_S6cQ-%i=TPJs)DQ4LBD+})8Zr`m2P2fFVf6-p?JSm6mrii@Ivt*A5hgl>WE zKZE3e)q8gt_+|FhsK9`F1cF&3ahJ0r{wr%oU*3x}O$BCO^WT`%hk}>85pA?6e${qf?;X7rkyLcZB_y*D}sLu7^0>&$FG@JqpuZ z<_5CW%?A96106Ev&7X+=fU7gp87>J38bon~4sp9#1jxky{Eug}dwq9-FbR9H7~~PD zX>jx#a2UiIl-K&cNx!`EUbn_|;X%A}Y#^C%Kx?h}8-!r%z!Qqwq#Lt%iOB$Jz- z5g=zRj+EE0Fu+V1oVvbk@bb=BBQu<&Y9=KVR@khfz=1ke%j*0ej9GcGs8Bv}MPlI7u2 z@o9mbfZ-TqBTjl0X1DZvXJM+lC5kq2(_An954wreOh_zc$RQ2u_kp~H(42pz&ZfL@ z2+BhfaKe`FVM(5gDt=%;!$L5HsJ7<=SnNRUjSK23xY#Egb$p>v?NQEJ`RN+NCugD7 zD?ccxec4lD=?rho8@;^`Dn@vUbb_Wwv>V8_UKBTP^8k&T=fg5xdnytHJC@cUYBg3J zBiKByBzv9ry=Z_#LzmT-DJR`nP;9_hOH%FguWm;^Q=thp)4%|Fvl@n3q?s|VgjyoVlA8-!;@dFnf6Jq_zH+T>fI31gB(8Kunv zKAY2rF-3=}uE;5yPta-(f(Yf9-e7f#Wvk!**HW>PVe_#i$8~KCq7fxx%i6M*RPF%_ zL-eO;l-+2!RB~}WP_05={@DG!>p=1edpFnZMKSAjYR`4R*xLL;Cw!qSSI4buyT3FA z`MsOK>7pZKk1wh{Ic9xV5ZK^XW6RbbQ_{Ppgn1~r$J-giK=-Ju+8TuNK+kr_xq_xdgRjw#dTt zJ)%8d153mjk2etui%cI@*()82*zBbS6?tCg0jdZzSxAmrk!g4b$%&`d=>g+1>!FnP zA8U*CUREa<$`5p#YvL~OWU=Wuz&N`(ZCCi9b?``!s(yK#x$6}w&Q*_9W8Zvu10%MB z+e_ovv4a;muK&Z=S4On~ZC&C{aR|kVyIY{RLvbs`3GM_9?jEGLL!oFXQlLn22^1~G zDWyPKLh%5_ODDXyzF9LrX8vU@LXvfJbMHQT@3YS&*JT+wABIVR<+F{wZvLp!IW1F+<7J*YH4oxrqxbM0M!((V^q-FUf zdGaj#)cvrSG(t@|$@#88-Pl}X+PBbok*INvO2uy?t9yX}Qp3FNqd1|@v~?((13P{m zur)_0@)ZH<@Ty;&tLslj8+^_k-w})e{*F~VzawU3=H1=?JuM5tk$6%!LuMSG|m|yD;O54D?MJg?YnX|8LkSRVW(}C z*}jg0CX#X!hMTj4Bi?kyfb)coyFDr?Ml^HG_72|R;Q%mo*h6(1anf&ap7!d!?RbY` zTzN+&KcyBPi)iQ94%07$J6JQ#*z;g5;GY+)F7}frVEz6`G4vp0PRftNp8|^?43?R3 z)l22AaC9rm6O?oKjw$be=5mxlcEvMdG%KtOlTo67BO?+m_-mhIhZGiF%CYXyUIbR$ ziPS<3qg2}QT%B1!w#x)|;VPew@_2`Yy zrwrnDhWE*oN8B!g7wtdz1{b{a5cyO-M`v z62dRnLI+On?u91dm!`Tv++Rrh8h3sJ!J+#u?;WWq&0EsH1oBsO7r|o#K^N-q?QXWp z&f`}h`O0$U3kKE2>cIr7KV^fa#cS=y4NRz<>XO2ulp)v(aiR^qwO=iXp!!itW@s90 zN4>)_%=aEnr>vTx95||@M}2b@delwvSoG0V<6%*1T^J!E+#!BokG}KFP5aYip!cEG zr_NPE&4JQB4hgzxF}nSt##D6nX$BW*>=Y3OH#gAg&O;C^;2prD$XfGdlOiWVnS^PP zVRIGt?ezKV_iu-EFZy)axao%BBKJL8&cd6C87JFdx?)#`Kpddqw~oL}gh z%#d!1lPjOe?k@tI%Q`2u&QiNdy;o72hxAOC5n3=Cs9M-hEf5J<_lN}hUwhEIaG%*9 zp&HF1$SJ4ZVj-O14XK9Azld$=sl7u>_|GOcOe z#DGK4sCjU{Ks4N0z%S|NHq^|<%Zgrr1%J58sI3PfEkq*dAUxQg7{9rBwuO7qtA`}} zZS2~$1$&J{u+g=#hLX+-hQLF~l=K!?#1Sp@Fs`bsbr!jH?IY7H~rWYlW z!W>o8Lo;B;uWB3!SJtHE!e?JmgJf@#a>uvcbQa7fT}uszpAyE*9e;OIZ~AlIY%IF# zq%*VNX1g!bS8OZsZGTLYW~DC#EQ0MRF-zDjBZ-1l*sPw70$jGGDzY$h&VAX&R??MM z%4jsrPWxaw7Bn_#K6LLCY8vS4xe%8Z&My6%8CLL!B^6hcHxLbiRyR3I#+wG&*IIVj z3|F91g+1Mo!A8{S`D&5|I4zFt{&Mevq%$pl$HeOqm(cK{Xy=6eQdrUXQ6m~D-_u+3 zi~R?ov2KY4FiY!vQE8XrSJq~zLdWd2tJJXwm=k@N9Q_{wJsJJ0?VEgetGQ`j!2*Ij zp)OqbEF^3(9VsXp%^pZ^(n{z2%h7IO`%j2KIy3Z{x#qKlH}X&9$D1jl^hQ=(=B|b$ z6S9Pj?NW%f3^GuxEW}zlNsm1^Cz%CfwPI{owr{LrX2ca#r&3>gqqZ;T9J@$i^N!+R zIKM{@ejtRSF?>Da!4>zjB8p_ax?>nV`WcuFIDdaI@=on z$7}LhvzfyCr=ix}O_paX(^RAi0ymwzS-#cbzp{Mm|4mY%oC}W6J_j)zM)SdF63I)IRI5 z@nex~C4}=JJVD3TBL=PV*_R4Qa)Ji(kqqI{SI{=B3B|UISYtq~QTi^sUQXtrtX|8< zilpMCRZ`9nPX!ML5slXjQ3t|RYpDxP=<8@=aNyBcVYIb*eoxE4c}yPE7)^%4dQFd4 zp3Kh+J)yQeUy1023ZwRcJu?z!`zFZ49}k`^g#FM=67 zQLh*veh@aQ<}FrW<_)r<|7oGF@u6udWD2lNUn&k(gT12Vhv+_6C*+p_CsD7wu0k}LhLnFx6y!C!=z?g18r$2W z_5F&o0)J#BX_l^4P1MK+NMt~;g&30KHP8>6{i8{DLlUNCy58$|T^cu-s8bY?A5y$) zakADN5Fg*Wnrgw&Yj&EArLdtkY{{xr0=s73!4*OI;ctwK5KNyEcgF-$Hv0AAsdB@J z=JCS(mB|J==(n6-zN@LyDo=K4;iCK)3=gE}wA;{5vbuPdPMBT{R@zzZf`57;>s_FO zNr%oPAV>e_umM(m66E$>oa8|Csk#=vyNn@6>X~ocXC(U3XoqEJ+qOKME!-_pgZT| zk7dE@UtdvO>7D%9x#DYFxChrG=Dgm%J&s>&$7t$AdlwZE>&>CMbucg+lz$M`_q*;Z ze^oE=(-+Bit1_7Pq(B^ci{q;u-lf^vc4{Wuct(j&0IfW6YFc%%DIlt++xKf~w!nP1&7fyKql{9vwXrMiE>E8=Joj=izSNngsyC zB&R&0YNT@xbT9eTF$+)@7(>}Gjbho}?^}#RbkUWEEbeJwmyxvHLgjj-MU=TFiNefJA;^ zrW2W!a{TTtU{}*?*$%Hu@hs5!O<5d7Djem zY|L*nLqlm(NUjWBH4Z(ZL^HlG()W=6F6OTFCft{4cuY;d%!|O~XkhSnn9LQ-fJpa2 zc}tPDTrX9A0?VjcXBWdot>v>Vh22Kp9)=IBVuTLylh%h@?NntmTdSID3ZwBo2Q*`{ zCj2kykW0VSb~oX?UApc$`ZF5ZBVf-N&Oq?5fFn2Q2LA&z6MI#=2zbnE!wx9VRMCNk z@hhT~q;Y?fX^D@qjHnz0^&t(Z!t;yK-OpB7fbYSavl;3of{pO|UrmS?Ga~{bQ9WXd zcE(@azhnSLQ7M0QuZY$N2jf60$xs%WU8`z^*5n+IJSh{vf>V@1tQ`|9;rj=OoWSh% zo=PuTJ4ek~Jvd}JZ{ANl82|Y|#hE{uqkZ}Zf1%;#i!zb6Q+*({V+~r`V4YG9#qFku z3bvZ#{dx6t(jDIJ2xgKZtq7N}!5cKtGrT|l;{|Z$%>wwPGhvRiUR$pt53d35x%YS} z!zD4aeO}L;Imc&NI^-}l^E%MwN>Y9amPHH?F2awtBQd||llhKX2aU){7j6AG%+l{mnfH|ju( z^nYJoNF1->$W`d-nd4I~pxJcis-JY|9w}hES$Kz59L8{kIf7NEz2{E#Q1<<@seK@P zuOh-6mQQxF?pH1w5uok?&J~ZmXWyDaB~p}cI&n5#_ysb2O^nKz03ZC?S*D10zU14z(yP@3;JwU+Em{PyMRng{?Z2WZq3y02!}xpHkwR7O?WSVrUSi zSVGEv_)4jO4sFYuX3~!L&EP5n$dBE$}9zL_Q2_gV&Tmg2rrDo77r-~%b&jf zdQnmdgxyFEqUPNlpl&Dos*CP6RJ)v!Lq#%@4(19-qq1iN>5%OvI{TC-SJJgFoD z8(K6j|L7qP{5t6C%QO~qCk#zUl_#@bB4dPM=Oi*!B#?9;E4>i8$`$7Irs=he3g}pC z=MT*oser`dEKasUUSS})_7Pb73q`$}iI2uQ*rQ&k1=t z#dyP0Om^#9lTdx!XJ7$AJ3iy_YQJE?(QZ`)Ud8Q`9U$u$_C5c~g<9askCE>2AFlSP z-5K3)kM4{=RHppNv-6x>eP(ZUD7;`RY!>5FMox@gOBvbU;92VuEBrtm%JVaqJVvRhVRv=Ay3~JS)U> zCNBCFquA>w=1d1+Pv+NcOipXbvVDosV>Y!IwXdq!>>=71!=f9x<3(roR#~(v5M=w?x<_4@iMqWO3!uLHMGLQ&C4f*NYKU zTJ1u*kz-Xy;^7ZdOU}Cfp~^KZTdeaDcQ&NzyED*T?XI@-)k@Y;rbAj{{T!Crh?<{W zImc|SnKB+FM+)9&qnS9Bj$L5Vj~!?maGhX5OwjSu)RSk=?H6*`dVRumaben;gUTfi z=BE&D!fPhkib?}BrfRdq)g&_}TtYgbWeQu$wdi4kExs=?V70O~WJE_%)pr&5n#_;Y zd<{iT*FoJ8Pd<>pXuIpd+TTh0n9w}mZ%HhG>e<$6hifj?eidU5ME@6!EDrs+`q14U zc_){f)9f(AH`wT*JOie@J$rld0!I2)YVB04_H1Qw$sJ)7(xG~f4V#M2aL=g;i`hLh zK<#QZ?E5FDbbv?%t6a-lc&qBy^eP_R3?JTfi)3_4a>0*ZB-!k%$VAKXA&kRqQe}F{ z2qsj0N!T4u!mud#`TE7y8s$AA{-J-&6i#DO`1#Zj(KSQyjPg~&3fWFOltLHfJ`RE< z>v?XE`U;IaR)X_Vm+0Ojs~??H!vk9T?;bDSyj^1QAlhCs_!6o?h@V^!Qx6_o;~f<_ zWis;KV=pe&Cetht$URO0VVq0Ql?l@ig20Ob@&nGPf8mB+SC$uF?D|x9^rG@L4g;|7 zXO#*{2L9Des;S?EqWZmXoiGFVaswF`y$g^-vKF53%5Vg;tjDP)z4y9bv#cL~dB;KK z1Mg`q`KN`BFdt#^n;?c|%p`g2rw(CXY0f^SqIXU>>WEGc6t__OTSc)yEjNjt1-nZa z57RfNtRP^~h|e)v7gv6V=0tk=v5cs%nQS~YjH~enmInvr_rGj*9_aWA%uy-nth&;0 z6+NbZ5q&>I1u-<^g1tW+=Z6!)@Kv7}JsYAp-wfuXUhCJZpVYE`O=*a~iA5=ZdwzvF zUdoL7UVxivz126Axs2U$`;%5Pkk!@cqCaz2!d%SJ0}aJwqzx!G?iv2k6(hN zMp|+%_Z-hFqN*rV#M^M&SLjphSoqIYP(sE&^G0f{RJhPBQNl5nZG1Pt_;uwcm$>7B zuJST>*R~V+h7WI;Ck?qL`2ayp7oaqX0N=*EI#ILax~!^Um0%BB6Av|JW|({*#J5KV z)U!u&jLjyOQL*FShrXE6XYWj$vQSsPp~lOT1{vxu*5@5QTIM z6^!};``PC@g~LD+8hJAAw^y#6s^k~ZU#FMmpQs}4w z{O-?dlNoa4hT3%{Rj^cZ@5aE&%@GEipovuveZ?d}5;Ev2kMnf_*(fQj06Kwg{g#Np zF=y2wVl-|Vux#w2k5N<5b(xG#LVX)gs9Hvt&jaz?Xf~t*zsu-SMKQ^#psHF6y!bDf zQF+_yz9mZjU1%c!{UYJuh9vao0vBL>F&C%0CW&2Yxw9JI<;4 zma!lU@{jZ?{$q7~&)5FQ!`x^si!#m?W=T;tVp==c=@y1ZGAP~y#*;_8Tv~}*^RhX1 z-e-^V{}f}py0{h>r3Foc9#oe9-l<8Y2V0fybj)Q?+*Z{P|JZ^rj5j?`Z&+1r)bYj0 z>aAhYAu2+VJsIF{4FN~Hzq7zk z=A)}d)Q4Pl)RKmF1K|4~{Jy2mEDK_f#?n?m{0iZ-OB2u6Hb*yno_y=cL+dPP0%KQ< z2))UmeJ$*?g*E$3XHTAo4_Z|-;`w1o8I9+HHAE;x`vOumjv-bhdBcznMsQuwmiWCD zsr)kJHgV;l+NL&(D?-Yt}1f0wV;G^=A#4{ zDOKW?BOjnE*7oXws-W#erc%cNmHbyr8-y;e3dnEAPp6gPM^5{uB=_D$@t6WlRa%Cj zS~9@0 z8F5OhX!Hg${&}S{p3rL0h5u%`&6mcFloRV4=)uTz`s!`vmbS$rG-UaVe$BIgATj+w zHZZpi`HJf8IyaptPh+N`O!b-ZHdiheSS?qHPEfdRkV|h+3?~gdsj>=0Yg?A}fVJ3v0k> zXJk3Qco5iRHRUhG`?T{ODEOh*;H* z%-2ZlbQD~b?==1<{Blex>;yN0WKZSZ31i&lu`1x|s3&5t;@&rOe>4IBpx{IN!H1ps?;g^4L^i1%s zVBHC@Hh20--?*;8a{q3Cy$iy~+;)ysQP0-NZsK{mzTj_qZhPs?5ErWu3*yz+vQpQWzavO3>OzZ7C<9;xoLrs9yNN zK#Bgt^EHaJ}Sc?rmcFl{Mhh6ouydc|bfrhxdp#Kj+2Y zmrbaQQU1O_#;=j0*QNb(Zhq{wT+Q8&v}bzzc}1Yq_;_e&{iNUpB0!cq-|ONg+5r__ zlDo3wdM8)SGi6pKMyJ#GQX48U=0jkQnXP(En)MPzXVB6*pO%aPQ^C?aKRp7Y{{2-q zk&w}j^+R8^ZQ0za0c^IEot9XAnHO*gLE{!R?a^!pFc*i;8Pf1*m?q+bgy; zPBz12(|oJ9eMH)bA3S+HsWhzCzSlMTJ?*Q8XFpC zRv?#btqRvztiZ{{&;erb!4{}atj$kQ(i$Zv@zT92YWYUY?~|eISzN<7ff?s&lrw+& zAL^z#Higb~eWBMbIX=4PSTj$gDQERUwfv!><_oI+#}T}xFYMMISqoZcWob~U7HH;Mrm>|yc)**L%OpX;$SPm zkZaBF`wRDSI}CsySaM=au+4mtpJMQjd}d#{D%pj%+edTGaYVDaIW#|>3z0m%mq&$; zZuePSAN+DT4yxLJGZIof>ZRB!D%TR48Xi&K=~^$==WYA75lE*mn&R>rJiG<@sCg1b z<$EOaHlHrcTHkJm=4!*)rYK|1YBq&1&r5Rd$af=QRa;0SFfQg4f&ckpoGqP-=De?3 zNM!Yq>ZCfvJeHWttLAEq0~Cl%GLQ#tcM&3Sl%o9xh9t@6t|@KkW=_*A`PwxrD8OVh z&!fuGtTS7g=HQ{7XVXn1_ugB%^-rxo022PKG}Lf(@2;E?0+_H(3$L>`BOYA(iS-`g zo+8|PdX)pt5ZbvqbaQ|2KChhkM<995ldBRUygQMW*v=8dgco@7-EAPEqnzT3FcMz| z?|!-L{iXVOXRfIG3UgnA(8nG^__-ExJ4_h4i$P%RAjO*sO6gx*ODU+g=<$RiLazGr-?z z6i?Da!C$L`y_g4OQ>zPi-_I(MiK1JVG`_R;$mvpemdv}9Gu*Fveua1aaw};|Lz&Fx zGmSl8uTxZ1Z=ulg10%9qW94*iWu%L{xmTbzF}+R~-mB>|mopp+=fzP^0=9$}ms;%~ z^->=J8ybe~OjW%qfnMybuYfIIKSU(f+|P|EB>sjWvgL6X&R4Ol$iC-Q*4mbo-H4sL zqH6U3+;UuHg~HGt4;s0X zM53OUE_1%4HuRE)C`0k1OpMuq=v3bX=?YXvJo|UbB%5`pX z@(e+hV2e41GUghZlSceit9NMiLRDCLtsNDaptoq@ zq3((?d~&sY32H~ex(0i{rWWWI{faV8xR-vqCr^un>8n%n(IzB6KH#(8pixXS5ZO!r z%P$IDM{+XSRzb!CL~4(v9JQ@k{CfEi5$V)6JXOG#p$4U?;lA48)Ig)$p@z~3({j$C z)so4V6+FkP>dvmm(3QKCIQWh#HB53FCxND#jmD!q`Dj5ML(1Y-wS0ycz(%h_vMdjjLbT z4)+{8-+-H)s46kC=|u0Ds8-=&NUgFk^r=fbn!&2w3&ulRC^KYM_z8y1T;l|awf}*=Z7a|TA zw=9=C5t{7URV1|RUEkFle&Alc@VJ&eX!8R>vGlRX1jK$(B|+%NnG+=5y(?2FqMUd% z=(BKfFbita0KIRln@CIYsm-?tz)3D4~qra=(+Zc%TGCwa0S}D;GX{%0eCMBf=@?XdPm&= zol_EMp65&dUpim|y;qIER%%#!xNFF7u+t%o?%LEwP`=;=y4TlbAIe&h9JV9RnqXUz zlX4uf>9T(_{*e>Qjyh9qL-C@8d7OT|YwOE@>Pl_&rPy<7RaMz|b}WnB6yv3MrpLo` zif=o+el$FjafEviyo7Jf_~H{bRJ~fMb8r9Jq9-hK^x2xH0M3b- z885M?_Qj~D=LBw@7ZWUV$aV-Qi%0;J%>DUkm3ZMeS}1$9mVR?Pjnaf-Z!tv~X_=hQ zotawl-rYbM)J;r8lG3ORW2#m~x&SdynkA>4!dh*$T$MMpykx4#f*ShQfiNxn5rb%q zRdg=3w_r-TF02BgE=ZrHNQqT-ehg9JxDT{woKOTn8w>V^7IVf|QF5t6S*3|1>b|7k zVkT{wY684H$?h+kH7=Ct$Y`UfgX*G(% zrMA4;9|Gr0@8&N$M>|w-NhJ$cKitXPbq0Scn{pX9>S1R9mv2QtCDG$!>~-lg!L}ok zkidGsfIzwG4r;J7yM*`PrP$FJ-C>SvD-yu}yW`;uGEX~%R+JkQSaqWy=>MK0sG(?*walQ=aK4H8=F0h)edww|&Ov@eb6 z_Qqsh&Zei+6RPl(s2WplQ*67r?x>YAQFm{8pKL>*R7!;?!=IKy-_WQa8x2U)B=+n{ z*|mIb{j!1k2Fot|rW*ODd(F0#NEyn)m#*i?n@q+jUin>n**Yj2`_6i@=&Uy;x=S>| z+$Y0tL$Ecyaf97k=5@1rZ!fAE*9?~GECxH5pl+Grq9e^AGD7uMjSu9b9gvC8YC4dPPxCIOzWmg(F5MHt#&{4831ir@oVM z*^&O*6njggHi7~mdDWYFC_$3^*Vq5a&N?%d0c|1(awkvFK+5~8+f-^hwJ^8uZX)q&Ho+h@AhMd$Lf@;5_vBe4jBTsXYZ z5B8Mypd`Mc9ve9Lv^dVtfu@HT_9gQPHbL+wa;|un>L}Cl%7FSTcN9Vw2U}Pij7rlV z!2hm2YfZ3yn$2aemPj%-%0QiRZh>9OMY;RD%3Y{3fLj|xclAyz+ez7Du)hpTg{-M+ zDej;>z5d8+1FD-G7=LtfTDeqVR5@noKRLe~8U67_Lbo)PBkSw~1w(fKxSoRb(}E)4 zb9P#9)2I=0wmFWK*WHIto-p%D|~sp zw;kIvLKlg(;pxLhfqYlq{iDnx=>)aN^(j=1S1=u?4UeJT3n#p0_GOXo<7LcVv|d{u z*obSzE7%$ac(;|m9YH}C^C$~cVT%=BN73pL%0bxGo(1za{?`kmJ_7;3&*gS7QL>TM zi$1F<&E)xJnqp$FDU9L2Y;SC-l*&)-$+^UM4w|WcwyqYn2p5a14 zd#toUOC#|>`DWs`e3ZSDjOR|Fo@WRA#i#1?=21L-*r#Y3^xCLqv=i$4t3HdPxqRQd zCKZ%?_LS(oM_nRcM_;oz`rF0e1W+>nYYjC_?DdAfObD0=>9ZKX2t$zFhOm~1Wx zZtvYDO87VY(-U{59dUcu?mKM4engTfmBTgemg8XLX4}$}nG;jpr6$gf*OUXe_vEL< z&iA*qA6HkX&z}3~EZk1s;knbr;@Hs8zlLyFO-be(3ERtXKniI)M@HdeapE&_C@q6t zncku?bX#ff(V7D8o#173*1;I~FmC>RP&3Bh6p4jlMvnY@;CWPuVtE_{^q)Ig$)Iau zC8=HZECO~KUlBDCS1h880spXdZ3M?i7N&o6k}Wsh689GlS_OKy+P~;4m5h1B^Hug6 z{Bz%CR+W8du4X4BK?`Lv5Zu$A zO-?Rby%syvQ<)1Z?6H|V{Ub8==3T+sz5nv1MDbe0&%Mi7qHc2QG-OnAIp?U?bK)ng zmo!vJ9kdjVW4Lj-t3%4u!?KgM1%|blaM) zQgw8x9t6MbwYxyKdz^n;9sA||+>C~x!F83=C$j+=`D!u&^*7^uErn~hYlYg7XJ|IJ zcwgXP+D#&6HjP)n@oM16V z=_8XN9Z)?=nlp>@0FrXFaE@-}6uS#i1ix++3x{t!WktE>Ea-!78|uUJn(7y88QHfy z)hmUXaJcmv*fV>3bkK?y#a(GL;S!S#s-ya=8vHnBHA`@Nuu5lvG{Lhp)xekk0%rNI zLOra{YhizR82pSW6|mDMC+hswa>*6q3|v!YmN3IAQfwD3rEnMi2oJCOG1-+Zy0?D* zAQ_S+43X*I3#87NXAMy^^0(2PuCCW?x(P6@mO<&8OOOU_<4=_CRYdPf37@egKc!tl zM&wc~Lu;qsVEK|J0}dVEa*&48xF-oY?^9h!@1-Ha{tD~A@dlO0u3f}+%h28us@j0| z7W|EWrz=iYl`$L%{Erua1r_Ob+v1svQ@v>f;@)JQo5PGG_jab$cT+1=iH}Drb7ya* zlRG_S)m_39qRjY%gM~>Q72SsuPL4ThtEiGekEu%p0r;zRUJ*Hn5K+>I3Vo*xLNQ#Q zz^1y>hz~@WPSKpRVk7d{d#>D9ncZu`w{w>vqi<(v;7psM4WDxeezB&F{f->;Vv zLI$Ep?`RGF10kwC6txE^p8+e_B>wT+ITdJC3db-9OTy5S?ScXCp1=}*VLDx0kM?dX zG*kBB#6H1cRY&FX_aEEgJ3aM$G)B- zpkR+7pn0fe!%=BO)55dQJ`HhFaQrC3c2M-@yH3BvE!p21G-lzdL`}0%g|7oyb{g>) z(gtsnqreVa8y{YFtcmQ5;0&&%&z@1{ItW~ z>mbc9H)GuQHN|Tv(Hk8H$_fJ$h5BLOAN8aN(FEHM&76%kmk?p6GOv6mvofz_LIEAU zb-xIYxa~f9_rK3c_Q#xLIFXNNN$&&M$@9h~_)g!TAf_a18T!MDCDAmEg^rG|v-K1m z==4^Q6fyJpnlpLe_QLdT*5l+m^6mbDYgtxZ6214`bl>H@lGj0OVn?My@8%XGD*8%p zqGGE~^fDt2`Ew~oclX7DZ^|*Ymx#St*$L^{X2!)8a@qs_u~g6XeeyT5PBLF>FV3I6 zT>yo9rHwMw&?>Gd?+D-20D<)Lez`7-qf$fM$xPDl z&`n_L#(74dO#Q8KN)Y;U{O%&osJW0i)V19v!1fIsCHlw9oq#- z#vu8D*+WFH7>BD2>y0ipR z@xX`hAzDNfq1?k7JwjOE?PxGA%|2mw%f_;kujb>D=Cm%WE=s9~9~v3bAPm_eME+RH z)G(m0Q=yTU0^W11JEHsvDC-Ms>(CJL6Q${LRP`MLP_bm_zw;X)y56+Rb?)|Of}(*D z+^D(67R@+k4wY64oqAH>{7$}Gj_f^vL4mF{SP?bvT%gkL?}9(Slj6l?xR%Mw7U{D^ zxEZg3H>?MkED~(32UMpR+jJs&fqI+qp??A~U=^BH?%0Y2Lx28DIaz;|0H_hCz48Zn z7G2UmjW9DEpxy#uGAgmpl?MHIVSDG?QH`eTN%F@{bm?==)L{O0l&T<$!^F;(6sem| zA{fZ@u!l~SmXrqcy7Zxd&EQBnM>p;liox*{D$<>jMF(jqIp5ILCd$l6n#YVPCkA{P zEywJfx*l~IRrhMQZz=hM@+|0pIxALbnO6J83#8k8Ya8pA_O>Ct&6mfDz=W?{ zdbIuv+LXKF=|DYATrYK$?rPInPw;2Zk@Va5gNn{Fr}g}oqf241S=Mz2+9zmZPmXOg zlBSxJ&GGL^wg&L6g^wz|hv`)fzO20t zPmNh9OO;7>AQHwqMixMD--Ubfe`+FbiRa^<@K2oqP4jWQ4IFe8w^w=EiwD)Z)XMjel8{ls7smj$X|1EIFZ8D)${nG^(V@ zPVM59ARoxr*Z7JwA)PL zQ&p1aGNTEF%7Zw##g4sF68EwhNXKN(6p=%{X<0z; z)!qTi%C8_yebj_^TTx|FC!iMu3Wb6xl#`gD=ukyl{jziJJt&kh+0Us&Z~95w%$2DF zFtS_f?(s6>s+4AJSm165BU%y~4i+(BD9?ARnDiLl>Psn1bChKkSfnU+)CEkK3y~2u zTcH_u5rtEJc`l)3v%V1Yek(7CNnf?KE)d(;#yC?;2r_K^C zuz{1|Q28Ic5?W0&rP|P5|g6lC7tl4=Y$wiu&;uTCVCb4#5=SyB0YG zR^5+ue7t$oVC@o~Qt7+P0azx?;tfz;=!=D|JX3MK39dL1A_+SF6wtW4Xfi2S$v7s& zXIBGL^=xRdz^BP6_5_LscY<*D3LZRXjd|@}yVV%$1kKi!VUmjY(pknN*MGB*SY1JD zsQ)zDZ%NdUtfME0{Z8|C3+1rygr1s8eSC3m8ODgRGX~QjukF7bj+270IlY~A6v-q% zx20#gw{Iqg#9N|#=R{3fS!t<$gtO$@SVdI6{?dlrw^+2n)6a7V64tX5R8ojjpv0CN zS2}?0agOo#0ui#ZdNteb?TGy_(PsJ_hvy{c6+`71;UaP^L8%Oud(EErl{{3fachy_W~{PS*{-b?O~(#{42e^eIWvMrq%W z;|SR+c^@V$=F_7YN|oRAosJors~%-!^vsJUxKutZTJMNP@xnh~3WJ z?*2oWtDpOj8IcRX7yUxmK}bMv!bk#!Za4H(+DkGw4nDvVA-iBEWYLEed(Z555p0L- ztpVb+8pEEAgDZ4)u%X$$_n%n$z0=PHBt!)PwVVyk&t6Wewf*NB;;w)uok9A|(2ZFp z`BAmy*nun+X@pu1uO-RnA5-0NuX|}n@Q_v-7EYFVRl_u!b<8+)P(r z@_jGTs()KF+}u9e>e9}rDtLHy0@^&)zpl(-WtHITOA{)H&>2e8m55rzbi=#ZyC|{HmuU2b{8p*)F7q>z|e$yihu+us{2eC*z5?Pq&0*V(5nIvn*cA zgVK>!O_RKHGFqmg>wmDV@D)QFVFpUV%tI)05uHDAVI0FDCY9^aa*9a7)Yn;vkvXh9^uo;D8UcUy2spAM^Igp0? zLM@`CG79He)z!%Q@<3lw898xsc4Jg8c*js~DOt(UEe|QWN7%zM=RI-VvV~3mFW{u_ zaxv@>-lTks;bUaO)EshON-g_e2G~!AOPB-M$qlzBEF|$4e{^aU5^i|zAn@Hy0#NZ_ zKdR{?|J8>ch34Nut@PYjxzq7PX3syy3+;QN^uu!;>v)89EI-!X3j!nqbOa}Hg$DVj zx@Sd9{Bvnf>`XnSHw;3tqZ4N@6?I)C)xR(MZ{x=tY8u@f>~F(o%2PvVegTC0O^ux> z^X^V`_8>m3WHAJP$2;{l_?qIxQf})2ks~JfUu2GIKeBpf1jiB(tZUk2gRO%>d_wzF51+$}jx+8-vr)}F&6$%h zRH>NT$W=QVA5gGF{s$cH=4o1L%V75&9J291|K_qMwj~{~Z>T(DZ^1JtxqgYVtfuza zym)`bWU{sj=paKm*l<#bXVRpZ=!z}s(yZ*&JOej4O$EWkHMCYS5}YvXci57ey~D#Y zC-PB|l=QA#JG?8Qp}l0{_Q&>eKaNw{QG`HlZm-gtMP3XTVIC=SidVEryDS~oF1v8m4tUwz;z#cRy;B_Vdsm^$8AQbAH8Puy zNyRf?34LB7Jc#=o09**MlLvcQ_bzW>mZ+msZjS}i#IlN%op1UL<$@nXgT76Gj;_+0 zXk|h;Zr5FXZp0ThrE4$C=ASbH9+VeE_u@3W zXQ}p@Je z=D3o@I&XMF!4Il@)=#01vcMeEAHiK4xs=1P+;>#kL!5`g#?zF#&KJ_wo|_X3H5s?XDA!M<3rZGrf zO)K0#%GnwTJ;rVr3I-WHq}~fYjlE=ND*2=Z0p&dUH^zq=}*JAx)R|$JEI+J98Mz~QK2Xgxwq9p1mD|7 zAF%w~)CY3p3CA>Z0_l%jctLR4EW0woMy_r}{j|EvHk{o@4JN-6d><06i|Rb~^5d3E zS>=EXZw<^j3qe+x!||>$w=z(#NHVvAuul8W>WsHQOHob|1oeLCBfiu+r$2pEL700Krh>8)JD?ybZaqSDy3^W}q%*7u+^he7Pgp*DysP?sGmSf5ddsyF~4wiCd zGrwfZDBspw)a35#Z&>3c7-FAkIrEBxhpI0gs~4d4PfP_6h21|dR%j%-C_EXN5v+@s zUJQ4r$%L;cZx22?kIW`|97+Y*+ERa24gG!Sk4eIn5n0zaODGzy z&A!)ihcPyk5@yDI{ckPwoa77M2gG7AYNNAkD=hLLU zfH~~=)N8cZ?xgz=;DFL*>!{kvr)-(mL@;G?inSdaxrZf)aIlmKYVJm2?Aoq3MYn8$ z@!O*S0l6AW>HOHi!Lpww3}}7s}VxDJHl#Rd#w zRmO;$_6bDV>DmqiqAtFNY`*LmMx`r@psg?Q_K6uiTMwvnvoxE3hoqYSx8a`JR z%kYNFvPY1_*k4!%XqqYu(<=}J0I*{7@TZd1fUIxh#{l9+bDOV#QXJxV9VrAJlm!7X zt<|;7bn#CbGy;7|7g<^Aa0OygN=8A4pBP6x;bpnwqD)hEtjMvv8{<}{Tzk*c2Y1#^ zs}3}z6g_>M&MJ91zA+-Dd8@{nIjB|T>wl!`%`o!G@+CRi@0Sj=8aqKkyJj>D2z?4# zodwgSR_qogm0JwYxNTG*!`-|?P$=7!^O2NLbF-%b^yph8fdWZUTjt18po4diu3Yf+ zWnUt{W#1)QGF(%_k+Yl~($$^?h_HP$SP@MgWtYf=2$LVaV$=$twZ>vDiiNW{`r8QA z)LQze{Mo^FF03gQ^Aa?R*q?WTd^S+j6EyS~b`sEPg0e$1mbaQ2O>GvdQ}OydF-{0c zVA+Gw=c6DDMrzw>G&eSyPcNvf+nL@Tn4^#|h}G=>N@Ew%Xwq_;D)(6c90d=Ea|kQ@ za9)+yj$frG&75^fO}3FnG{syl>PAIcuMX+2x6ufJtF(LiaS{(QXEHDI((DGPQm8Pi z`|r}^2)}qY-&%iLk9JB>{5?T=_}bg;vhL!cm{BZy)>RkuT^z2)e} z9|^AHi*H`zP9glj$ytaBTCLl(5hFEPjnbg>Yur6h6y8k*xxF^7bs8r+hJz~yWa4@X zZ6%Le`_h&xw^x(3S*!w*>>$B|=+Rsvl(NF)P3rr6jE=2l>O>yk*!%Y@tR z;Y{7!y~M=8Aqi|gLwDTijA2wM%|X*0kmM#_jX?w9-DYVqC4>@q*tkh!HXef%wZmI; zz{fV@{b{r!J9mU)q5Oyd2~JQp1X};0)$}VJ_N@w3nsvQ;%XHK~`}NI{BH}ic?GaFL zP0GMDL@i|l3(-4Us^)z6Q1Dbm1L-1zzaP>vJ81iubL+2yi)a78;FawZ5&Go^%hx^ng?_wM#INsIqTl<>Z=b7z->mf(Q5p@l zct4_y2iAU!JH|$W4M_KPpWQ8XIwe;qP2Mv1&ct$SP}9>?`b&sGwbjjUqYZNN9Wu*( zNuwSA?1W4;^S4YV2dWPD_i3Q_7!r${Z%X6;#-)SL0QL_(7mc)>?r;l`cPgTa3;{UmPmDDtM6O<4PKPv zGIULO^6Mk%Zpa7$JsIuS=&cdnUr;7J>N(0=OJlpCgnq=7u5mYAKE%Zv5C9zD|j%~^kvyylN-s4d{=I zzWFu9`}bb!WBC=fIGTee>j|vGdcdIu7Fn$)db5ivZ4?K*(OHdSwojYHPmzlxw&;t) zM!zH(IBvh@vHEkRrnFAOB{`x`RunN~;pN{eMl{NNWj^+cPlVI*hY!}+e+Q^9s4aWufagV!R%}ZgdG9$n z@@LdULdG)uwaaQB^w$>0#Zw!+*k|lufr)!MAl|7HJ)$O&nKIm5Sh?z`0ft_CL-ArY zT8MnfmDMXzlyR+eDllUdGoZ9tT@OR1uPb2?Xz|z9op|%9VO7FS{jx@F;FA1A31_$S zRZicPal4Ym+hS}jB@)cR{?c>oG->*cI8`WZR`bD5QWpAClo4&uaQ9xPz zG5yZnFM$~ZZa9@As;X>+RQ29`DeZ5wg$t)6sfE^-#)-tO1YEm9<)d3^KFqlv?r{dE zy283R+X>5Mm@I)G%E(Hm#!(blX8B)YiX|uI?W`nXE}5tvixz1D8AQ$@4v$R<9}Usv zj6NdA^(II=F|Q|Y4^Afjbfim_w|x0`4QF5rkw&Gv23Ym>``6wM`^@rvHw2c%kHj!V zirdr4+fN&9XSNILzM&fd+D7aJ3`6Hwe4Ez&Kku)jk8;sQ!aa~C*|&cE|9we3ef8e* zt8bx;nb|EZtg{`%nrv@1RM|*xn=YPa+#fr;KS1TIIYCLfBfBKi#bV7%yVw3~?PC4i znI=$L10)`13EQ&bnoc;z_W306S9#Z$|Kz$QIJj~V^F8hSv#QhS^Jz6b!j9Wnt`W{8 zN%(sclK8Z=cMr|SzQ#=`Oov}1K6M2z$*=xSnqsEUB{zG%H>9z=_>`xT_3RPdF<+<| z80u#tbws+ff$d|$wMp`6-UG|h1{N)`)#tC^S@Gj?irYOpMV4*6=?6_N!KQ*ScDQau zG(4fXZ%Ha7H{blnrA3X@W4L%3X`OGfD{CF4xhpE~x%a>~Jyc`}&q$Zod_M_a^4|9M z5VPMyc!htvxbmAQc1YMDZK?bNw2ZhA+DlkMI=^cBd^%ge@X&Z}xW>%czD_@rzzd6W zfR^FJrwl8<6Qhp;q5ixqe_bvh2Cgc8bki;Ln^X}Zrx=IKvE<3 z^Pt+uA2woro#xplndo_uByUmwqq6QtY4}V~77SXYX8heW&TnLf6T9sy3aN9Q`L}8- z@El8NbbOan){>qDCB0)Wh}@PGNZqgXee8qiyG5x`k0Ti*I@l;GlF7F zFcY|`94$g%N3a8gVcJ;?X&V-dn=jD}P6A#62Cr?MzGmzUZx+@*%ummb62>!#+xzH}LIZ95Ns?nxgq*ew@uIu&Nem z5@7pt^Jb+_Y&|Cvs;WWF4cvB6Ofu<|$83U)+xxy4gauLxmX6b00_xv(m zQ#b1$Y*|t`-puRzss0|1!^rk&KRL>!O3i6f2G8G=|0PEBd1XKjrUrAeUa^=QOAc;` zF(h~bvv16nMTsTPI-Yn<=mVH*D%>QT)0j4jh9C%>6<?U5=cy zG@T41{$S*E&CvE!9y2C;;n2b=w^^DhHBM_UyfVFD@zEfl|+5~sl%`&?^;chP% z@cbd83ha9QqN-9%>sVisPIG?8d1!8z%!Q}4)`^RJ-=+ntmL%EOLopW<{yT%T!R+;p zD_LTMY_zL5$)r>i z*(`KQG0g?mVQP+xH|>Nk6@#S#ME085X(Z+H2R`6-OFQFM-J( zo6T;PoY^Na@$?sV$&0O?H=v#NkH5YX zKR?_pt`JEVCF7P%F3c!LWGKv+6>ku@S8zw#A4R-Kf0BqyTE(?e+gh4>s+2KY8j>+L z%4#6Jb*I%MKl+@2%b;G0oo_b~#6AwrDpP00B@+t3qKd?HL;n4Tq~4Xvc!W$hgR|3o z{)1xD5mDOc^$PoEPOYqM%KSNCgyicL)={9bbS+~r#Vk$M|*8)$(XKqu z_gI;>{?AGYJIzKqsX^k2EDnU~4rdqR7_^mo*nh^R)jXS9q_*AjJKPslI=Q??`3@CN zXwCYVjuIfy!{eoYmKGCus~;d~&U4=v+9Evf*@5Sl=GBof1`i!d?|bWD&eT}20%;>b zClh3WMQ}u*PoCFH?G5Yawd>m+a{WTPketeyB8A#$rPU241r>x<4rOKx`i(8&jMh1d zIG$b_n6r2mM7SNd_)IxBHinr5Q^1ZfaAeKEn?vV)XT;dmisP9Dqr35&Z=Bi+Fkaxk zNS8y_j5YiX3Rn-+;9D0;>~9a|0_0DQ)L zAoHYirJyrqs?sIkUlUNq9+*nIvH$B2OdMNM3hncEMpDH#{b+^sn`;*Pza*ch;`=I8 z&*E=pgTQNr$cn2_&AEwlb(Y%noXKH2XmxzXMQW&wvj(-PX-ZKCtd1#R@5iP_f%C<&QO=5dRp`pn7hOJ_Lw#dzM;5FTt4A zn{chHs>+OAOzqt_MMbS)dtPk$(xThDn7XL@&|;|X-fL*MMs%R#80>oEu+}k)&|Mfd zq7d{-a2i3S6F%QPG5hUkcyC@+b!gs_A%1@-^Ywpf@hZqn{=)*Cba7-N>sl&n%`X>o z@S&Y#Qv*$PgDD)srL&8`uu9`_FHqC{74xqT z%MGU|U4)zPQ4w6T35y=+D1TkGhJC{!e7QCKn+07LP)=NqQ+65h_3SmreL4PBr^7v8 zM)qwDWAiNQTI$U>;Y&^tvn;AzqzgpTKd@{j+Sj2*>B@N7{508W$<<-7JGWtHS?4_t z-v^rC!-2d9V@22wSAkyNQp)Rjiak0s==|smPj1O2=QuYK?C4;DWER#OO_NE6bp@Tti3+>ZvXNVx+<&|8@@wU(L&9_jgyGwZR`AmcMR$* zi?WThN5#k~nF2;JtgCeFJ?pCHrHC!Y=E~={PVth} zE6TRuZx7+TYVzKP>3!)hEHk=4))S7`JZq4oS`~=+Yr-H{Q)*rRyyWt3=W7=``Pod2 zUlX}}8Y)Cx`q7@L5?bQ2+9rM#@#In~5V{5J1W6(Eq`u`G&6?_VcnS1x-=dlRKqLK@iRlUx7#7zaW}h`!?Mu*j)Zophe%=(hMfzp(cA}K} z^0!3M4gO!O+s-e!?o{|_CUtb!K7iXr@x_@bLGf z<6}~vd@hTT+u&>Z*`RUcY*Ji!ujaN9a){-5SRZJ-OBem86XlTx>@~J@{#~^n@%}jV zb*N9%F{>oS@EYmBqE679-0SWX%K{ zT_Mwl@{w-UMGMS7nW%dle>AN;abo8?;@xm`VX?*L*(pl_p18uf747I~(gD87I*vYj z!)ByYN&K7k{rWdL{pfcRg}Fox`Yz!n{nNcA>sMbR8=r#}Gu3QKbB@0FmF_=fejPn^ zU({5D%)OKF=s%~F@JKCLl;Fcj7K58GSR*Sb(^oKKF};o*=eHHZZgX>^+KIE`x(@dK zKdBE*SATtn&Zr%E55ISS0i0Wh(x5t2lO^Fc@ziA3UsoJp4p1(+xAstKb?z*48fGdD zJ~LaIY1sPy7To^W+YNj7fdopDfGf9EU_FmVdiitwzf0|p7@rFK3?p3YHloT1YQvwqpD~%eiO^D#Z!tNP}fE-KTjf z7D(*@Z(dksYB!~v2Vz=VNcMm4h_ZGQEY$H5F35>TiRpkDpbv*O4Ya$|EjM=T8v-$^ zgV&SGH!(fUJ_0q^soyr!%yWhVOdG@y#;Dj}zt|DM{u*ymJ3KHO6(d1Br-BP80!%{q z`4WqAN5|J|TsP32D(5oY65cVw#kRlVm}G-M^{{~YcjGT?SQ%+}r|x%^{8-XG(iQJ2 zU)+`i^hVukK=ODiiE2q(Nc>6b{6M5tY&HEN%!du11E$R{3w1TfcCnP;53>DfQRkvB zaxws;(0a_l7iGJriW=&HcFO^ZJR|mpfI1Ceeu4e2E|9@(qdYc4lb2-*_Eqc>nt)Ir zKi$idB;t-aBtYw?pUlcSOCE~paOP;(gkE1<4Iu<62yy^IBhd=7a+ES|JR}Ztps7lt z;qx;m3?BlA8%%Dw*H}%bY>E-Z3Iv=ZPKQ7P9u}&gE!(=gS#x(QHh@A*Yj7jv%ZKBM zn)e~af6CB^Khs{cT^5BZ>=prgJCI=MrnmV>6{TT-1-d0-m;)sI@;6-C09Qg+{9Tr# zX6WXV*`4UXZgA7`4d!kCm;Nsj8Dn6ba88M9087Hi!z-d;3MLul;pHcj6s&|HD6KHM zbHj8dz~&w9bU5?&z=z8T(|uGYo-d-j7g(D^X#)EZ}yMUfS65@2MEp7m$f!l7#nTAy=^&v$R& zP2hMAD0aVY;VjAE2O%7xdAG7oQ&t4wQ4%#B@e9x=x)?U|!Wf#l7`yAZW&F{;n*aSH|N-Vnix zzg|d(7BF;*w^_J5noBILOe&$ z_j=de><~c(i0b1wA0f=mh;}9zS$9FUXgBF$6Z0$V$LDJR)YD*`H2Y&n}_Gc@`qj!zs#qK7o<^iqfTRJx6Hi!(G~VIN4X) z<)m?_3S%ANf3;=_a0l8%S0jy!E;CP8+O0?QvrMDKi)rucPPNikaWjeZKpF~f$|bY$ zyHAa%%ZvvJV&SFKN_lBsv)h79y;o^bbLaP0c$)3bn)zBmA)L;#pm*afyem;vX;zZ> z%Vv1+mm7Sg|I1@l?rw1pz3j?Q%}O1*9SF%iUQ;_aF|d$88X_+4Ns7P#dp9JD|7qr) zzm1aL^e=LmmgpUYy=^1D|E?1?(&S&wO%MN(j-ub2)(j7KkYyUR!lL{8yU^GBedxDv zfl@v)$F7nsg|N!gD6L-*AtaFMdHjd3B1U{uoWWQQwxi|VipYF0ugWn~vo8uWw34P$ z4iwul`?t+hCI};()QW_JR(HR>&()7!ZKHs%JM7A=s#-#htzM8Vmc>%^UGH=QzHY1V z+rt_}uy|0Gu<hc>UX6`u`>m5h^;^njKsT3M-|5 z(;Ye2^k*?i@8W8YHY8!Da|e81_2goJd{wpltnV=j>&xR@J7141s^>#%DGb)? z)Ah{P#OT&4pZ!Xw%Ks0pJ-tCx&7<+_O|a(_&mR%)5Gex#-#Sw@x)5JRlYfUZSnx)& zj|;+r)1Rt~Uz5q{O72j%l1+Vq9KH#e2p8`vy3H=m{)^WhwZwHNKoa zZ~OE}R4B$B*F6$**A3LA+Tw-Axpf3ts~J&}>+bpRAS*Irb2zt17W z)M|_JjU*%?n6@i6KT@qTqjH>rz;ICGp5iTmPnuV6Bkcj*H+uE(kPj`C_8 zi(WsH9*R;PpD>6Of_GDAj2$7si;$fG79i;U_ ziafH)PWWrP5fwV@&6eB~c~GBS7A7{$(SQ z?iF6*qXK3TAxLAWXQ8z~ytEQo9wlrrN+yA7|=-k1kWB&vF&uX@jW&Thi3rv)K*mc=^{043dY<@}%tPhZ?Od0aly56j*IT0`F#0dNSrk+hg z2B{@AqV7t~2CJd^8=grD6l5Tr9VOh)y8CUCYYpcR>GS_~F`E=_o;}k`x77dX&|Pui z*Ai#XHncy~o0}8{9N&Fe)Hn}_Y7=d|(-r3DTKGqof+oVWak_eBcVSs)Y5!QYm%F%* zkC!gO?>9rW89?V$ks3&0N^kmK-YCuQ%c{z>$LRC}x4&I93?I(W53?rEx%>D~M(iJV zHz)o~$I$ydpmwiqg^;t^yPdMwyo}G8saWU(AB`n-F2o#wkc6SDZO+T?p7HY_fxd>hW&NxKzUfkhlGhe#srYjXlkASp-djlaDXmWs%P?PEu~#jm4oX8lf|*_ zyASM?xe<%6WXI)Fm!%DvzKqr5DL&?gdqvfgC*AVd5Stkoq`UmDpd_9B6IszOq?#mc zK%VL~xFxkXL{P#bYid3;Bb&Mjg#_ZPqHfH$fB*2W;e|3JJE*sz9}kBP{156d#a4Ou zk4=m*tS%ic_3@wi;N&%(6Tuyx>~ymDVRz}w<)f8Z)`PefIt!RnFiZI!rK}-K##9|Z z7$y=4PK_^)1VC(S3<++M1iG@G29Wi-W_LnsFyV3OTaxCS5~0OHg0tx=YwJw5A%{KZ zw=WnYfn=nE@nE@b00lG~aBVvc)fu2)Gj>Sf1iOG7l4ZF;{CmLadPg6yU1RM-nvck= zxPg|^uJiRyX!MYUmf0)4&f!8GmlJyRpf%i}qswd(1lXI@0p#FG3O7lhvNMS#k@tpv zGcLGwgL2_I6cTdECw3_LZPhEfpc%6exwD(*%_KXWD+=IYJ-m@o1#!72+;CL8PKtx-GXYtz1k5*rgZaoq)V!y8F?@%Ck`ye-pkPgWW zffU=Np}!q1q9nWowm9r(Q%smnZO91B{SLK8t-#bK&XS#EJXfq0$de!>O>z($_2do=S{cx`8s}=nXSm&<7}yIbZF0NfbtQ(UJXR7uCHlR zjQ3-sY$m?&GC|R2pGPrd3SICFu$^wDMnKpJRTG(^eq$6ZE#er903FJ_~5|d;u$z`b&$v*4gqoPEQ{KqUIus@b8rasT}7-Cry0W1OIbkf*Y0Edqz5hO%l26iJkoK z_|gA~u<$Y1fMW+g4TspiWgnos_}N>j%=? zDeMG~u$HN9E6#bj*Ag$~eHhV}P$XSk?xFyw9KF2dgwYJ?Z;5_VqZs-6#Pn1FEMy<| zdY(ffB;BQ=CwGUFQGwNDA30!0e6hguKXF$t1pfYjJ~sy;<48KBJ(!MH*>2X?Zh=wK ztSJ0`NFuQ_vnpxp?;Cf)DY`x-T-fPcyi%Ofa#!A+Na8{=`XPB2(Xz{#C8MlF^7)G3 zo(J+7&+nR^S`LsorFtZUJq^k~j(7b2n07qYi+%7)$jmSzD(GF4Bi|M6)SG{cjMX4J zl%}h_fBQH(00B7Ti&O&jL^%#Yjg-ypkf4h1czBQ|P60@iS@aOf5@VX2=lVE<+zKV7 zhxyQY?atmx_?`4DSQ@XA8u>ONdt?_g@s7_JW!eQL=c*3%gPIQKik7sH;?Vr$CmTs7 zjtk%D_O>PP+zs-Gy3oN3+KJZ%=D5aV$eXMUS6DokjJ~lSIyTl9FcNt>^bDi$nvbQAmh&tjFQ7sf2P|owe(V}L zL`C?*IS1V}#67UqdC6w4Aor&`_{9Oc9D(PDTQ1m>1MTXQWsi;pewNu=uT2s3dPW!# zGyOG;rQ=G!k>HOtG?9Y<*9BvE#}``%ZQ$Qg`t0JlNBKu-r&ZYT{Lcg1-fJ zyKaL5)0DI&PEmc;-9KD`n);w-0<#y>!$+({&Bm%>zPIS0dSK;9^9_1P)ST3i)t_$% zGuy+?O(?vTY6oU`=ud7Q5awb+Ej5kgjCrTlG-2TJ3)7Hg8mA@z147cB&C46e`gs;qkvh$)I`zuQ)ooBXSF4j7r|5sI& zqxSz+lbCAUBa5JyKbPAvuny7R=w$*xG38pxk-&W>FKse1UTQm1M0c2l%c3(H|q%dxU|Ay^nT~G-hQM@rs zqXW4EH~Y@!YtHSZqIeTW=xPz<|b+ z+bwk1^PDqwjp|YuxHWwEln2ngU!Ua$vVmkn_f%88($$GG?K@DT#^eGOmtTIzc_zty zCI5E%mKg(2pF25%@OW9`$r%=kvH!ZiB3u_CG!wq}KTeD=z5qy|q+|OEVf2Bn5Q0~T z$f?gF?eax4id=0J2zvWwf+_tOAL-IHnj>|e+!?lkZf~%4%t~KU23{OB3ew}1Ga@#t zM0&B!lH(q~Ak;`cOi0%6`q$*sH<(x`m4BGJ{oS?JyVm-etAN^Q2T6Du#$OsEc;acj z?R#50@Jg{@pCrCE6%q)gfxqIv_NU_sqpuDtHYA=}UyTRC!dkpVS=a*{t z69{XgjFLPJ)UH1ls}ngFj$xf}#r>f>#ncmd-Y!C4|7(|~nw?4J>oN9SRsR8U?PP&G znc({DhG2a9X+W4Cf3w@m*osI0Js@S*%murYcIbWXDU znmsh&hNm@*QyQ+TJJYvv{(?*-h0Q%ZoJ}z{;L0{i`)dzllxmjaC$UYyCr9-7mr<(m z9Nw5cjd?{sE)6np+&Py%qol?Exbm=e2$jG=_J^;~xwGNR)5JHBfXMg&r#3x9Sl{G3#?V)LxYC3r`=t_&!D;^rnO4XAWR$abT(i%}=7tNT;- z@|`#I7dIEgRmaX7)KYBt$}9!?Tec5%3s{JUwf2a5z{F)Wy(ZT_;RVXre??;y|zs{0|>?J1NI(m&3oh{QaP?drdJD zfoCbR=Q{e2Zx5g@yL(z} zoCZ!mi2*WMA4z~EtyoUVl_degOR!8sNJ(8Cvx}$Z7ua#w^S$`men1^C?WSG~Y)zy? z@deJJz_#A+u#jqr9=eRgq7PZ^t{`@#S0PD4F$N4z56Ua}hr3(4)FGafj#uVQovhnH zJLQZzDCyT5Xtw;tyrNydHzd2`RHw4|_jrNtjJck| zan2m~UzT#iXW1LHxM8w_1zc+d&sADJK=4*Mt;k5@H;Jutp)152S+P}4jFNMLml*xZ zC?&&hlobUTJVpk#U>9u-DKmA-UeNClJpUQyB4+A9qFnHS&8w)zEIW|vTrgpYp>@NI zfbiB|A2za`ug2k@13WA5;*0t*{WZ#=$pPx=2BF71D2nW0*k_f4aBI*>OQ9gVLqE@( zvpkiyTyG@2en;K6z;Gdz^Edjs%^5aE)P@z3R+nm;EpJKv0IJK>;OLU`ECm|bxGA`4 z$J6|71l74Aem5EyG(5BQ;rCTEqJWLR3kE2FY>H1Au-KU^ta0q*3cT?93UGmB4g_DA z3z1HEaL0fONHN2z^=IxF-b){16bW}q7+3mgWz7U13ctMNwn7q7i1G_=>O{kgGyXCj zS{91$(G4guAkRqJ9b-sDZg5xVS5LyGUbD1c&HWXTs3+DEnczsVr8KH2N?0tM5=B`r zy3rU#E?yRqr98}%jlwOX$7Ls@LJQA`MLCAKR+%#T#^!Xw#ISi96|8Yj^whjBRnSo zz%4qi0Pn)`@Wk|d6CAb}kbM@Z0wG8n`cCh+Ya$lgorUqezd|IBD(O6@nQV-q-`*EX zW3(uRMAfN(ykfn%DOC~oESm{>j*~(23bl}cbae^b-w;*lwpo65Sv&;bi&q%~$2)#~ zmy^(9o$|jdMSwzzI*mw8^siIhUwJaGZEB0MQ4nq)uB$Z**zu*SIiePTEzy4hcRC7{ zS+1Dapd!JKCLbbjKY8+Z#fT}%h0FdVw~mz)^s*6~GkHzC8HX4j&-w#$AF%m}JN*Go z8^j{}#nRuAl|-FMc9KLq1Y#U5j1euLHMK}OLcs4rD4|GLU_6*-^a6Xo1vPC1 zkw_ik_9t|kxs7>;F53DaLN}1voM>H^ux>rh-VRpK7)UAjBhZf}G%v;O(iztg7Dwhk zp$hBS?6#^`CkrJ%FX?-YjJ6cTd9*Mcc~a{r{00v{LHUCg=KGe;kEfabt~kmx^JX28 z6e)tv$5PWR%`VzZ>M*v}TalFE9YuQznqr5FkgQIA!aG;k@`J@wCB3lZz9otd;EM)t z>4+5=yRbYXG3%DSI|5|J%ToHs%LfCN?`rZ8812MQ!>+vS4y5!~JQR&;Hz_`VVqeto zlOtmx+?!!H!OB$tl#n@WM;>n1r<3533tx-(&LwlbCEFimJlYGbSF%2QNX)$C7#VETJmc< zkSNm~^LR2*4)=+D__Wg0g<|`1$NE?;(QhNyd^iszf{ow>8|I5Gzs~F0vr0?v(JoR6 zpR!`B(=?(p97hsn63AutdH6x}hX>cFG=DSVhxbu)Sl#^hKYv}~hTNf*PnL%8SWLZ& zsZFc1@x*VA1*3VxqnP>t7UhMW>G(%3XNz(17Ok(A8q?#*4ubxYQ-;alnAtme2A zx2%Cp7$MPNDl^v~R*>3ol*QDrBhy*aN-I|t*UBeT?y6QR?s7WpE8zBryI`Fv)3yIC ze1nz4*zD}CWor+07fcTis?mS^uV{nUARSmiCE}J2ESE2z*ld{C%;bnHQ`ioFIlw%r zd=&&vWmRXqa8~|M17RkaAEii=Ru%cqTjHJiXu=rxs=>2PCZ<~iV%rf}g(Uf32LyU! ze)}2ut1D*WlsBp_OJa=zeVzaE&Rg^i<;!d~$Xl8bN87I};k!4RNL3tClZnpfYHckx z&V>AOH$y46k$f8`%1e8n?1M?@6~&2;b9V&>&i7BUFZD5W2(SxG0z zF7&tA0YCn=h?h_4=OzHO$aZ7$M8~jB6~;bzzWzX7Od||AowQH+Fh9cwS3f34r^yAH zCkM4SiGJ7>cx$e?_oY}2m9w-TukRc~^HnBzkPdrce*1tc-d9C6vq(?4dgGV|Q^vxB_$y#b!Wk8NQRc4oLb>f|fm=>ud5dF)imE%Yr|)rho@Tyo{oo)XQ$O<3kj z(?GFeF%EGyrk_r5t9fwjtDZv%$0}LKST)k2sCNI(LLhW#J4K?m3t<@KT{`6|RE5(U zIcBb&b_UKa!r1gN`O!O`Eweq`h@lA$D(FqwUd_jDQQ6gsXhRFj|9Q7n)gM+Z|C;C^ zKXRilPyksD2Hn{UiH5#KV&aDzg3l8}BdjMhz@37-)PU0-tE9PPBk>V#P~H1o7oZV( zJxZMeyDTyY2}_h+bbtH7vOh0i^zzANJ9rvNvkWg>QuEabwJUnoCb)tvNuKR#Zz+)p za*t0&> zdHW%ua6KgPX+tiokPVBe)plLx;O38Au<)nnRW9`qANYc&4=u*H7-<% zL$4hqEpqF_3~X< zaG_{c2NqUeNtWBz1dp-XI^fnh=hpo{J#)1Z#O$Iykn^VyN&YIMZ=u*l8rrQVWp-bm4f%QJdx~|f_D7}l947ksxq%M&KF<< zu+Q=iP*o@iK>#)`th;}H10aZmp2x)$_kbY4m^CG-{HKB+SpG@%JNaMM9c)fOJh%L? zC{~FBvdN$9PVaFiFiU_8)-N0c%|PD&JNoufI`O7POzu?3E-}>KVm+VLqQNc>|Lf;S{pT+q()r>*c;>BQC-lW-GoEP) z?#b_`pW*yjFk}djXuF zPC}X{>l3MHz%V!#kdRUd7E=_MRwIFt6;fn^3_0tp*KAsrD4jGUYcpnlTR4@EJ7vu9 zP9X({k-nnh8qFiZ9Xi?`iag9C5_beM!ID}BuCO=Z^Tr@CDffao?_za6Oc_H1s=C)V z)f`@r5!)}e8B(J^Zum7xw#_1h3Z=Y_C-n5@xs*D~Dz!+dyPSMK%T7nnP>w*7NRMYc zr3Gv}Ku(O!bV<=S?%EiC$IF3?3jTjCWL&h*u>8IEmCxp_1r?)y{k|=ox+b@I<*mxJ z=r}Hc?oFVgj$cM*Cr7fmEpfdU%jXz@O6dV00ul_I@m`S-%MkP48jRc&_hx~^dq5P# zaLW5i&IDWm7#Oze|JA7AoL>L|9K7czL(HCg3wqL9o_9wQq#b-W;ouVlvIJ0Ilif?aBk9C~f(v0yT_nlpFKRh*c1 zl0v6!K2?%ef&LNneT;V-IuAQ_*UTZ(aXnFt2*}ScQq>O){GffK#Kz7VOQuvf(DF-2 zlm{RJHg$o^&6X5aH4yBi8rIMd^n;YyX0_dk_X(cI|{ zFz;{NBw5v?a1v1}8MvGQ+F%InALy$RDiV^ke?dWYYX)5My=g%G`Dy@o#(Ek4Uxqps zoW3ij<%5k3soo^OVELJ@4fIaN=5Hhc$5fUqsZA6amY5jc`RdP~FO6Sv?>nc$H{#i$ zVI+C2C_c(0*P`kL;`mE!N(ZhOBnKdL`q7?(j}EJ4y6y5Wjo^+2$N;NJockaz2^%5v{!5xCXiEp05f%h8!Bc z4lEw&ez0i?n9@>tlwewf;|iQ`&tCvD%jYDvu>M+4Q9c~wKh;2H>MXpcET?kmx}*o# z>e!$j^m4(WtBqk|&=x=1X{4_tL9i|IvkR(W5Jc!TE3OFMCLR259ctNxzj}duWLQ^K zLA}K*>vvso9T13FktzuP1U7)M4-{nMZiBF)=WYHK`+` z9)_E+rdW_tO?tQql*;?;vCyM+j(C+vVo4P4LbN0vlV#&@!Ce+!jvRp{@|~s~iH#Ng zM*BdHz)i_w9ys1dSAJDWa=n3l{Y~Euy%kk5eq{U{C^BKS;n$f|I0Z(44tvyLFwz67 zjAz{+MV(HQ`RU!MOm5=C5ZAXoY1t}Nv=%)wnPT6rpOJC*J6;xuY{cp7wyFkn%+%G2 z1t0q#sT;{9qLyFUSKyssi|;I!nz5fIXA6ervNdN<{(G}Z z<~Q}Fvi)_k6EEpo|B2;&=M`%XzB)-OZ09xiKy>?~@eEnJyKY}`X$OYCncsn1l@N>cBTu&^t3*$o9G?}+MF zdo`zcLVamFi6N2n07H+r8ErvcAAvW-b)_uPUO`%^@Rx#81Kfc&pPD{L#j}Cece6f8CurlTJx`ULuYrQ;G1gN``hsez& z$clZqAh+u(t7tc*eps%l3rtxAZ*lG~Fp5YEK0hNWS_9dBg#`H|sQK&ZY4jh#^|aK2 zXSQX8rX2r1zMwIIZJ2wxyv^J44)t+~|H1i$ubsu0kM|W6R+tm9TYIsR^QT@+)Bme^ zD_QvL<>j&|jBtOi!QvBQ@6xw^ZE@CljcoKm_pCl;|JGQLK6LXr3h{>frQiFH&DPIH zP&@zRA6~C&y?%dtm)x?ZVdmb_GTV~#C}f0>V=aW7wPdf&_|uZpoO55l@cI37i^OV= z#mR%m?wcWoQ2Vy33Q2w=2<1|UueU~wt%^p>t?i+R0kwAy#k+En1b9UY4Pf^J0mkHFFiH845)pK9=Tzw;rTs9DVlY>Y6q6_`flMW^ZY z5e4a~Q=}#>mUPd@VzN~vR^B_1Hgrn*_u%>RCp70e%w*}~8Ru5_FQ49hO@-7yycfq> z5j)~v%B!tK6};BtNt1skE@w?5`~JAIsNH|p*e1~5`*#9PZ*x8-Yn~t1Z#v7KfcjyN zSBa^hjgCcmrgy&hLYo)@g>sTfHx@jHp^N2`65=qg_X3~VG|S)Ldn<9flC4?6C2)p! zUxTHc-DQQY+E4ALde(zvoiFs)DW?b7H)$-FAVZ(KQW*&R%L+;WTfP0zFv4O% zz2QuI(*-l^25Lf2?=li1ffBl9gKbk5d46AN8j4KIO8UR$EQtg_u5Y7HUsdkElkvYJ zZ=kX#rwVwqsW_~RtcIqW3%o@}S&6Ek;~0UM3x&&UtXE#lv8zsjPo(DdIc;Mb=>(vf z*Pvg2q{EorLWhc-`Na#|yw^(oZ}s*o8SPl`nHZjV!QfXroM+~n-}oyu9m8poa)O+o zf+MZMr#ee3D0kdAJ=NOYB)gUe4!?dNxV-Nv2()# z(a>qH7^O+7F`rVmxFJLkK`WDY+S!?G%Rb64u3yICQ|kvaJ2p8m;%l;KT$JBfh*R=c zQedt%4+r7zOk7;lMEhU!AkkZf`)R@`F1POR1L72Wrrb1|^MP;i>%^?0?pz7bd@2ky z5H7Ib{GX!k0`EZU2kNP7(2|}@ua3N{S`KE1wK~Xd{{HvzGwcl=oEBORamik zF|@1}D}3y4479K8T;J>HvNOy1Y=%K1y>0a3{+D(1vA5UuWj@@?G8(aG1DW7doO`ge zkyyds@JQh=$h=bu*{3Kh&8*?HWRb>_`m{n=VgXLl;bap7*Cc<5l0zd&ZrJjdpYz*(Px&W6 z?7IrZ{&8LUu=$mq76`!U{f8C+FX+%I`!1qamaYfqajW|1Ui>* z-D?8gHGAm41Sr2`+{wR(cG~?*>Y+EeTJZWSQJV1Z9U#cXS`Xi2HA6+lat97!QX49Q zOmQ7&Dt?r5@uFFt4swW+9tWZPHCwEL2ABdHe;s(p*n9k1zxv_$$_X1Bx# zd@%=6&I;v^r`=15moPq*ZGJrgK(IUWtu)tP$T0H_zej2hUa-0f@4RHM=Fd-vgjxjT zdy$j>9W0>6nc*7b38&M<2o@*fI+pf)t9uhhP{r6yt&hx=%+&=*_*a>P%cyg&&3-;t z7k!;rxu47xMN=qvwX?NcQUT&f6X=!<5w#cizMi5 z!!^iLAjwc_vJDFLZ#QPq*bDrPQ3BoDUUpEm`FKcb^lOf%0x$KK!!^V*4Fmp_mA)>C zIZ14pVPNMYi^tE$BdOF7kaB^2z$FMx_>=Dkj1=~h1&IRh8NiD&kJ8pcCgnt z#;<10W%uFvtDJSi@YoB}5#0kc$Ibfzyq(a&$<89=VL#IzTf?(wH>44Lw8M@nDqe#@ zqeQ}LMLQr`6%RHU`zT5ADmjW}eQ!nKbn5AMyUqX^aW0v#CYDP49=`Nt?9?dK| z085gdcj?aXx5%DE{J7<}UFWYY&D*n|xWO383%9okUULc#E?LVL6N(_o*KWXyetA}# z+LUm6hVQTzXWI`IyO!$TLbp(-D^tUnHPS3-iT(QfUcy}9H@@_bYTvIbFg!JL`;L!- zME6`6|Az(emVIG1MrX0+?9Q=8BY`c++;pGYa3)eya$?5wUsZT3auJvyf&Z7d`;+^- zyKBLI>>{_+t-4PUV!8dK9NCYR1(Lo@S2(NmbF$@dOX-rTjM6wcdvXfKrYKDhiFsG5 z2y18rm7_V;G0rV{nJiZlkvo5Qv`6q4=UG0z$L&yalNgb`P!sbqccq7{`(TubS!KTv#4v6ra2r;)$UyQ zL2|+*A}9BQ7grQ+Qxq~F&zfn8G4kmyBGmaIthg|hd{HkcKUk^<6*>Zxr_LVrOk*9J z(pE-3*<`nTR5{c6|4NaG!oTT^ok)%^l#2m+bOWLU_uH~OFu|(^>x>eoyTe|sgi8kh z^#u7Q8c(@380d|;52l9c25R>v8YUW#OHSI~o=xa`-1^oJhqCCp?Y?xsTIo8Q$JD5G zAC`}q?#y^0eMfk|=y|GT`o18+U`}?U@J-vof1kLpxb6KcU8kZTcTFQPi{IPy3tQP9 zrOV(V1}9$mtTdWaEL%M}QBEn=kE!+uT`a0w-s-(biR}9{VjKF;KJv=R*-$yb0uD@+ zkaU!u1Rc7=G?0^!s)R6qSB6|avM=LXnzVdnJ2MOjrJR|zBxD}oav|igEIH+6&5YNk ziLn@=h{~bFjY-8D+vmKEo~6kUVa>?;vDyAJ-c}ogm4vCf)nVfJGlGx^zoy*)l01|< zA9um_8Z41wBnVtFM^Bt_h^tHNuW(?+Oon?I#O`{u`b|>9sldLh;6i`%2-bm1J4hvXYHfbq4eQ60MCow$EiO|0P$aH2p_R_Gmln z$K$7vZmb=@2*WqQJoYYO?&&=pYv0;d^t8<4UgkHUOy30#1Oi_ylHteAb)g;Fy~f{jn9V4gB9>^tzo%F))!wo>EKhNNwCN zOZj?pT|1X^qgKgaK4egzhB}lae_XoQ^T-K}}7a zH+N=^tD(QL6Wy}?f9Zs*&xHPZZ%uSIg>1Oyl5X?rf-bdejxj7WHw(*i1(X3RaS?`U z!L^$=bn6v>RXgDGeUq^d93UBT0@q{*u`6oGS$k?#5a zI%gRIg!R$r(Aw}Eniu%4nH^tnP(PgnVIaDxjxBv2~b@amzJ_AzwQPt%O?F;<(|F~LoEHfFrf7SDK+Y&|>uOZ8@ zowgYci;y3SD31lS`;@i?n>0+at+9Df!A)`C@3m0wBSt=Q7s()rhWD=;zAh^?lN2i{ zEKZ<Gs&NO0@i-XX#(ZTLn$w zkFO(A_CsG&TovF|1)5ei++QCFov#tN@b3sSR$A7#5H(rqnh zaWEIXjA-HNf7xxnB35Cp>d0P zaBP%@$4Zp|yCMgP=>!+&D0M*G1mF=z=3oU90F!nbASinZx*36-AY(z+!E}?G;|tt# zlOs_!3^#(qDzhizhf|x(>$9IIlJXAWO72Q+bWn%;ZNwERes7l}(5~o@e}y&FL&ti| zk`^K<5Hh{V%wI9V8IbK==;#JzgX?Kb7^RRF=A_`xO=9daEZ4zQW`AuRYNzz#3uh$$ zb@;rd5dQujJo1`85_TnvK76GJd<~}8Jy1zu%jU$=ZKk$dgC<~C0u|J0CKPqYxgv9H zx!Pck482i~WCGGwf)TCN9yM|8FI>=dqWExqE4iL;cTO9#G!efFi-+OYj*)@+1MZv> zah0|eQVhACB~@aJ7)-t84in_bJ&R;WD&=UoN)^!+WsC=}AALg{P;8k(sK`*~rSSPI zn%bY5!jkesF361){bI#ccf8N7Ja)??A5CS#WMTnP;&v`eLtt1S7s(X;ozp10J=&~r zM&>$ubewZ2^iJ=hK{t12x7rBY=7r!;w?Na1~u;;)2R@alJ@<=18jhsN(#S~~W{(F;w1bu=iR?+aS+>`4hr z3K0gL-9ryMF3IwI2}sKrA04%rw&6ZO6s~XmY{b-3rKi>ZugTHKt0qR-gpvU?>(1NLJ%%4=vnZSsZ`1%xu(op+4QC$jy>W z2Nh|&T_PxXHfizj6>Qljf6Qz-bJn4zAk&Qo`=IWKZpT{=B~bBf8B-&DkTwF&d?nhJ zLnO@Kub0bf5jmgZI8%5wA_u|jBjt9rgUwTxudG6ih7LJeO32Q$@a;kz1e!&wWi?=o zYb@#m`GZ?3-P#})1}iEKnIeLMndfHFxqC-`z>p-T30*hEY0|;;@QS$9uRbk_@OGad z3&RW6IUF>M*Ok-7goT{>1?Kk%hhx2aAhWX=H3UnEs{4q~l6NZ)A*-0MuDVc(6uYA65{ z2_EnhdpWK5vLniJky^KIlQ0EvB1y4k_22aD5;0=e{SICP&AM&fn;Lg;_Te5V_C+zw z^*>ecTP?h}y**v6Wbiy=g**GXv^1b06T+^&(qV|XG1CvV`XLiD(o)v$A?*h~<4qO< zEn0qnFl+bZ1esc&bGIpWndkq?0NZZ78(XL;hSrPV?zcOz+otvV>pv$ztbC8t*CH!_ zo24>i{;i{#fu;$gh;kO+8HIao9sX0MN>5o9t#CvYE6GTxR9Sg{jtE~Y>e+Bd9RCzdZn_6 z|Awf)1I8!W^1Zi__P&V*IUL3fQCbx9h>?5&S|oEK65c#oUE=rq6-X}n8QUnnbBvF) z1XTbofVbfIKP57v8+T`+pTMr0W;z+TM6&XZ;D#P%^W=yenZe~KZuWC(PkXMz7k%eD z)?T|u$Ei(rknZRVQABqoj)(hPJb9}#HQd+^SwUHbAmrWI{YjlPafb4tlbqVFk}r1Fy1C*AFN7%4Q}JUeV;Bdiv}J8VR+!6_zV zY6}@zm6c+FOw$B;&VYjv&-iOsd+XY~g`Jk_Y1ZkjLR>zx_@=yaJ-g4T9t{b8WY*Fw zz#_2dX7VqI)31Z$Jw@+dStz7B^<20>104KF?=lA?AKB^a_5+TCQT%uXhwuNIPIR>5 zOlUhyIh&~1J=+@{NWTFFnGBr-F3m_ket`8z2>&D)@8Nsj>QiB& zfff?P{PTZ$3j@;wgUa+Oa3z2Tedr)h)4rO+S#j`QMLyz+r!?`y-B}#_sMz6KPT%Ro z6MoTtdAU=aV5llgQAX_!M3sCwc#!q!t!53BLS9=ffGeGHiuwEAt}@YuMmi;`_|U*i zxw`kyZZ&gr^V;8|y8lv2$)e85n`N7zrQ^6R&71C`ZO6|Xm-j z%R;EjL{;~>*z{G8g1BDAh;4=3FU)=5uVO{-4Y3O?zj@yGT5t$6Mtx(L)LuLD=8ls^ zHF_vf`#|1Qm-8#P{TU$PE7e|o#<>nFCbEd0El2Tw8~1srs9qbL4)xI^Pg%B4-|CU) z)f5SdjvQuSJTk>8tV^=I9=E(%gZAfDe3!i?=w1AhR+6(5eQ{}Mp@S7I*{V6++u7h( zIh-meS04*F?4ey5q+EN=@BJqGlTGRgtHe+`vY(ZpKIgD&`L$fp!Ko%Guy8{Zz=}`c3vM@ z>k0Zi^?lv`vt|-{=?&$ZRz6)VQ+uyMA=^&z)_YbJsQYKZ5my!K}2$rk+v^NaxM zCOR#58W1=l75r>QRamI@UrCFZN( zYL&#~g%2zX*+qr*W``sYm;dTt`WWrUHyrZ3_}HbiO%$;7$NwH!bz8VjE)FyoQ3$)`=Oc&O-xD?%zbt4yNqDnhAb9G9%eR^8y1n@; ztG!;C!Mq87j*D>7eiRroxr=H=N%O$qzoo$Ph^dszPzPQ|PGj$lNF-Wb*JXGOfL2*am2R^u9ulDGwi|U%qlgLI!hkh-jJm;M&vT$pabaTw* zdn5+EAQ&df_Sg&t614g_*&cA`s&(Ua5Q?TCI$#m1FKElzGd5D-vL}T`7|0B* z?E9|QbtGN=q+&wn>|3w zD4Q#OH**A?a=7|gHnY!9{MwgxlKsmoHVoY#n=r*JoWX2Gs1oGF5jxc0{bqvGa+gh< zpbON+GWz+`9}gIIFQn8n9-lgBc1&|nOng&m z@q?GVtm{>OZUWuS&_!`zHmx+Pb3T|$IDue0jJbUhWuiL#^~W5^W%BsXbEt72}f z?6~Zn{NmV4qu-(PHT>)vK566RC`j9(wBQHYK`tP|7e^dl9DIjy{ z@$UQYmEYt73jd^Y4xM(sq=6C<*T)P4ISsKPiYe})WASbyr=j@TBv7%WoqX+c`g|~% z*Q}F<-8^6vf+=>Imf#u{$*ef85SM^LZBB@}dkDRCMtZuX&8iulN>I3ShXUze)5sAk z3fSArd+y37$#C)5)}yvC3AARSu8qdD6UyQciAhkaGXuEnc(T>BmhKrK88Zgsvv2M? zijRk)X~{^*rhu1)2`0%2Q=07i4Sht&J^LcemNY9HQjp+-8{m;eQ=8tTxlQT}B%PW} zNVxUruaf(Ybuo<-rGmkd|C3c#raDsaO2wzq3QzYQ#FyjjvY~+-czgLRh(nz+V9zd~K%!(`Fo| zWX2AKtHDJ43>n07_F25!Wm?63wWige%OMb%soX2P; zQx<)nu0oW)|0TODqeAavG!CuqdUh)f+oX=v#@p%I0>A|2;XusE=S2XYO))|ICdLMU zU(`90Hy^V_&Uyw`JYY0;N+%VMH1Qi{lqRt&v((IN6ixeKy@wNGk~sXdP(@mdw=UUi zr*1VGcfxH&=pfxsm+MtT)=vV!yFGr!#E6mRN8{x2eXapgC{9|ADNLfe)K#Csg>bY+ zrL+jrn8+}OF8Sf%Wt9DDo~5Q%>#HgNNuzEm8Qo+OcuaKyPPk}gJ&F+C5;kseId`Gn zmRlnr^ou1ycodWitNEgs&?<$+CWTZsm;ZeX0OxnM6?rlBapT99_kFJa8r8OGV2=_a zKRL33idIa1t?<`Q*<^-cxkznv`mMH)OI@?4SUuzn;c0f8!&f8Z?AHRtZ^f@q=L|8z zy1mjL1FpW+-Cxotm`ApsuGtJ8>@rf$WWM$Z*}iS>mq7paYA$JKFz{NR{HAw!deDcmvDWlGbQ?-!gF-+zgIVL@HZglwDJW-CqyKas z3@2d@-m!vyQ$L1v7@Ua@hz~D?Pt)KZI0rwO9h@K+BF_2#QJa&Zp%Y0<)a2mk%0#8? z5^W*GtIaRjL|!wnr6sDHDV_O8o|rcLnnSyrH0srGEpP9${=U9n?3qD*yyPM7sp9Nj zwdUOM=wgKC>1U6+t*J!Eip4pCHGskTf*)aqwXI~6}6hx`n ztc4#4femX})~O~M+|(n=qJ!F86XYre3RqCJ>@m9*w9u<;zF#pd5LCuYAL@%#{W0q9bNMNMM*jP?NE?Kr- zy_)lz&fJkgC4$HAo|Brc^HaBI@3969sFvqAMC)yz6H`y*57qy}P-JS|Oq#=$x z6RlG4uL}q<1fWe$PLOC#$YUKIb1}Dn!2St;>>>m&eg-=!m2ev2TeS8+dk4Y)zr6#& z$=rsx|9OeVRmA_*85pRa1sI$)733YaX9b0=I320C=3?GmDSrL0(Lhp22KC5wnbiqk zIMMzsiE0`Q+q%DpQ@e%7m^J&CJs^R(&I&IbOe}^8Re?e#M8P{Hc7zRYcXw%7*GFG? zzbSDbD@z5)84V67mEz^mO=>AS@>h?N>UcVf1_~=-|3`70+RKV1^4byu&k9j20cG)E z%aTUEC|4VqJhZMl+y))ye~gqyO9UL7iiZ(O4zhOj(-axgZ5`VOS5W7-)+ z;b@iV1Khc*iZ3;Yqvmlj2_cveiwyp%sMNl6d!G9OH7JN}AsuMM8 zAI-n4(6ZED`s)QdW(am~+yyl~UQVh_W4NcUizd^}->(oMRf`PL7^D)%fkvnNVY5fr zr()zEa_#?ej{H-!SH_T+PklIZv~}m~@xzBl@;w@;PkF|F41|3yzP|~MvsXhIGu{ho zn-Fa=`q##SQv@WIa^3Z;W4y1wCwU?%sh{~p0;>Jat$MVbduE}(YI+j(2p@5d*&iL|l~Ccg=QhP6S;9v7^ieS3d* zY}%2DSanCvZ0LudT1whV)1*oe`jiJh%B$B0TN?EU2s{*1w_C0yb`)5W>R~)-!?TFB z0ui^(j&uK2xP3)Y@zcm%a2wC;-{uprd3wczBAIt7zGNiA-EXXH+($F^>NjCj7~UG= z4ofpvpHEi>gkh~Lg=^#)&jo$G8IpeDeA)H>-e>1`WGwQnS_MtU)^vzoS=igpstyM^ za*JEY=65W;XX!EMk_h;$XbrsSM?!XaB$$2rDS5u@ws9X^4jX=(J4}hR7@m5j^rbD! z2*YJ$Oa+p!PnH(;Zw>8SFbY983vt3fsiu%g7`aH?@pOX6?Q5qcPI#q2BRYKN0GG8T z#Hf?Xu9GRov=NZme0j^qz4aa1!`H^VUKiy3iS+M)7YCd!`t%MP4k1n55_NA& z>u$?bR={e3m9K3L_ju$Vq7$N~ViQ7B5x2q*R|5+=FGk?K7dD7JI~5qVFHbH^v(S=$ z6}540Otx*kh_VWdck3E#n=5^A_>t%_2;IZ`1-_#0F|S;o(uGmf6FX#&8OGTrB25Xg zF=x+4gF@6vipk5q25R4TU_>2!EYY(7ah==TK-$G-ziENT5jJX-wLPCN30YAz3S&p(7)8bK~M30y~ zv(Rq+bp>{4ffhf@f62>1zlQ!ej8}c^gKali8YM4+Zx0*qG-3DSMWj~ zIDPQNEDf%8psi4(^R7PqWer!B@qj)uS-yUtgB(c_vwtg$g;7TfeI=3OMtakxqCV_7 zOYh;FKPc#w@x*bUEF8XzMj1Du6i$^1craAIiB_RnnQVzN9*(2#xoA+b4$Co5H7@!& zFx1nzaU6|dNrN|9OgXvTgT)|_&j#Yi=gDm^T7h;b2Q%2d#mAGSVsyK(-Y5NnF?Z)7 z0LNF}1G4P_x8udeaA+H7c2oc)`aM-lcj!`6huVMyn-C8_L8n83GPTmIw4fP`%M)EX z1=jT2d(HsCSzYk)k4*fM0}uv7OK6&v&i@ivDX5ohDj?RuHI8 zE{QMt#`?*C{!l8SBdGrWumBpe-^pQSwvq$#$~Z_1QQWgnTtha|XHZ-nj%wU61zJAV z5=GHd_gUJNvt6A2bZMwhblW9b$*fdUHQCXShZYQWuMf zqkr;zHgIM#%5R^JvMKbOTE5}EH(rxG%D5N~5YvC5v8J5zPVdv~(AjSB{+IojA4sR# z1UW|V>#*pb-s!DjWm<*#0*Pb Md2%Tboc;fuqxuPeZj;0;a`cL7Wf&Fs2^cpSwA z`6mYo;Phf(IDcVvySSiZmmTzj&imN;*1OH3)v~8hhAV-|S>y2-@UT+{Hr>FBSfY@4 z0d)`4*v?uv$3OO^f7rcsAggBSVg;ObkBYRbU!}{8u!NUsi{}9xST?T=(xaEdmJODL zso?!L_gv19#sjp5XTlyak&KRarK7$uR>%Rd2>h}ECP6$vJXi+hyf9R23} z#(=x}^D_5Q6CwS=Dc;mWPyIM6d-U)1_O*T-mB~$lVetC!{q;@gWzaulLWF%q*}y+< zqB(}XUv^X5M!dK}2hw6YMaT(IZ~NN){Nixg@{=^GB-6-r;keM<`=Ebgxd@0|_vB_J z`F@9SijVL}U+4(?{gn0kX~?}#E7=BC+Ku`YLamkBqLGjgmwvVLd+Zd;o-^u8~5SpBw9ahR;7}`!LqJ z$wR&)-!|Qsv$WG`2$zU3jZbq*_|;t4Ctl=r_$tW9-1?ykshurS{ftz6lwPH%Y&bJ+&*2NrSW$0+J^7Cn+q^Mb)EU+jKtWV=6Mw zEuwWz7Ux^+d-x6y@>Ok5etN15uhw6l)aKug3zPIi2ZAAr+dvXZrk(7l5Ay;a{gv$` zfMQu8m%~-aDWHVumT$niBV4LqAAR(@Jptjo)5GP+h85qd>(I7VQRFi0b3-bF2b?Za zB0_{@fBYSpq@6qCm-E}^FMVcpE7G-V7jqAd&{eQ2mMh!8jcM#yg4h~;>1JT#P^J|H zp3vP(3e1m^kD2_%p#8<85~lgDFJ-qdv8U~imeBCJeR7lu5Dp;{wOW}xwWgCl+cI=Y zl5|$_!)zTcc-e+ST{ApthTiw5l6Xp25{IQChO{UX%+Nr1!wZD;_MmyNQ%wTab~t~Ow3aeJjAC&Dni9OFeAiDct-(%F>;{cUhCTH= z(Dy7i)%9y-=KpKk(7?|r_lh9qQ$pEcSx%2!U!<5q7$uO6^~=A!Sw65V=ag$XH*6?$ zf*Qi5E)IbQRcF3c@CT4pqydtVBzNU4b`5q>>suy{7EWOojGAl+@Q2M>Xd7JZzrV#g z@GU;OeJcJjaZ=!mvqUl&1zzqE8EFWd;v*Hm?xP1agdL7E+`$$A2f+#86W~H|xVRm# zr#22DAXJ_Tk5?*3(TiX{>*usPBZ!gT3$-VQM7{}=tO%v#RnOCo)*jkgaQ@Kpo!F9mWdjgU-l1KH zAeSD{{d2(6rlHjV4;gSE7%NbMYl^_^?tMF1WG4DuIHIbDqoDx+lFFIIeC>bIX3iR$ z$tWfqB>LYinVnRp+%pbX9f#Ve8p_g&t)P?SK#4hK=qJo-qd$rl|NW69#`#eCR5;rn z-P;dR`Pc=%;pxwEKD+}w_*Dw{j$Hoj1FW||(jQNBPW^aRp1!jm4z+9w^bhLq zq#xW%B0HY|nSp!OP`;->ek1Ukxw#x&rT(p`{^>l#dYte|m}_V#5^Aj#kxtyvuhg~d z^JxgxfpcgfzLM{3(Y-jarwW8&T~|R?z$D2n)pkbQPiwG{c%r{Z$ki>p?*8A7#Y12{ zyx<}!;qOMnJ6TEAn;{`O7l{|5D@YkcfcY1x|44IW+Y{_ z3JOIZea$(55{0%PStLfKl#1+{-X0&^1-wl##ddzBzqyJ`U_|WRh-wv%TW7=|g^zRp z!#g=jt`fg9kdt(SGr7@vpJhfVLe z%T}bH`TJB0W3ROY|8Ft!0fQ7JWM%=w(5u7kF6I|lcMaf<^QUUyC31u?q;P+w<_&d-+=8p%{ z`@^*fI5T>URpd;i!qXwzX*U6AcH{XA!P0z}sZ&2UUPE4-blR>@wi$#Y=T^z%@T`un2?3;al9J@32ySJc>6o?_p zArmmwcgWueltAb)fr{SjLlz?%Ya2UTsbi;Vp%ZSTo(pE0cDX=^z81^nw z9NuDs-DTrCnC{*?zlS&%Q2;+B2M-g$lT-fmci6E*Xq8qpML8`gABGFdjBDh3mDnOl zQS((ZCaWx=_L!afoaJ1fSglY;GDPg^l)sckjSYjI{v$|W7K@c)ydoF^d}6#K&FceQ z14P)oB|Z`o^s7VKsGlF%pk@1FP9Ce&uSxcD2Xi5Pld=W6;oOvw&G`U2iGrJkX|Lc= zo^RBEjGP#IuiXjI1O6suk95CT*S63ajyJA2vAJ)cJ3#4rXKwOKCiRzV|AVTbP;TH_ zT)-_kY(8LMD4J?#DjNaMz!*GE^J2Zjwv3x_=-wFcn<>Gjb)TuTBsA}TGqZhPNqKJf z8TVFO2roR9I;y(Z4*ps43){q)fEv=5ifWGEDWR-_W}Wt9WpQ+Mj28}5(Mz|Ijqi9} z<{*_*bX-IyA>})&9fG(1kEPS8)cP@qukt{9H=2AwtuFKf+jb1|R?VD)Y&s;HAAUk;U5IH;=W+d2HI3dd%$wfv%CXi|Q1-$3X znZ@#H>}P`;K|-DIjW9uTW^G_T@4n=0bI$$m_hfu<>FYh)|` zqBuh+?xM+|+tLql4p(x~SR~a027Um7N8+hi`n5TfoeD{^?019FC=L|nDGQFsrtF(h z9GW#h9SE#cr%u;xIb;U4A}1Cs>Hjnm|C&+JRci~*M$AH#8x)!LPkoHCO|M?I{CcXD zNxjdHc)hQ{q*=~yMaWM*>0!sSHu6bh!ao}tV6=4&Cl~4-*S<_NL^`mEM*i->$|)-g zpmmD<;lXVArKvCZcFB4H=$1!t{$l?|fO6k#!6EV81qxJ*iUS5PzM+VSdh|(n5^Nr|-u>nQfB)RfN%;?HV0Yz`WREneHa;y} zTrqO?eQDe>gPOMl3)L1OwR;twRwN69JKL^@(M#PHFE+Bd^)t$T;&i0v(e3kRqY$UoQBjXypz z?XMrr-RBgpm$S4E9^T=P*3+;du_*F{o!yA=3j3xAR*j2!d&`X z_(Iw@l}@VQQIbW)_gQ*93SlK5GW8tlgB9k>9w0jV27-5nvgs5x{YKK?hvV4?d@6#3 z`D@`z=zZ+KH?w!`fPU5rX}?c9aIjeid%? zDumn8`Gd^CSZ(kH?qgK*&b>Nm?}5P6&L5lHw1%6Vxd4j}+>Va`QwL1h6tw9V-2ht5Lc`J1 zXK9?ckWU9Pp+v7WMZ$O&qu-Bu=7;A+=mK0=E9A0yFeC z*OeHrpGDeiGxqK#^IiG(HZBJsORhhEep~f-c0OU^3jG{L=e@K}HkMkSW$<#m3ttDu zNiYcmFZi9%JHCp5sM*~qJ()GxkrCJFLuT>7_B=T7HFU&(TQL*Q3WXd@xpcxorhS#- z$fjOPgH49uYWRqUOZq=rh=s+-|L>)Q z_%qE)<@JjPkKvAg@)t3V&W;O6F@z-&t0Y2|=|FV2Z~j5Z|!R z6*zk;|6x1akWL58s4YlE>VW2`SZ8y_;QM2V`X8X?yo_+kK5Ay{ikmW`t>F?S1Zm9J-w$v zMOK3L=hHu8>C^eE*(=^CZIey{k`FPONkH8WBI%qv5gWa}uxxM(G(mwtt3PJ|FNve} zMzV}MPEy@kPvOp#e22e!S8v?50+~ch)D43dp7<>})^A|y#?R{QO3z~&02MgdJZ`*> zjNtggYi}T=TGEC6>C-i=;TWa4q#xKnk|+tW63b5jb))_;s@Dq#h~(H3)eKdcK<%tW zw;^Z{Mb~})ADX4PL|-^V-%ZUpL#KARARiCkVqHY9aRo5>ELiGLljUSPwN+)Rs(;FZ z%Df;R$va(iXM?bAeit5Y;to}Xs@6I`zle=u=qr6Ue(8uSBU~_IOG?Yb%tzdi3szQt z)`YyJV6PqaZ~O4a2|%Pos!bh>ccc7bd&Z-ea-|iKn*dJ7+^`F zNC7T^;&@h5R{bb7AxUTOm)faO$zOlcCWzr@8KYH~Q}-IDZM0@(OD2B=>c0-lcEeub z5w%Ie+4A8gavwzevXtW63Lmc{L0L3C?VsrS~C_)qI^MF23G6OT8@paeYuYg ztD1~>s~j;KxKkDM18r69}HZKo(_@(!9-yd&JG zltIjQCxXI;yKYk}*I!k8cG58I?E@018%VoXHpSQ0YH=Rwp!Xz1%7`3Wf}&rH+jFvx z)07rI;z?_+-%PW(&!)+|w?B2{tQbdV9xpds@~=B@)AbvI)_d%eLhL%958g8@;hDmh zvE06vInqAo!oHE5@@x_yGw+m>j#-GqC9YhWRt?uUzq@|Riet4H-G(b|COkfm6xLl8 zW&K`#8IC3XY{xt{3SLKMRX@V&&2dxTjTmAWa-V-e>G;wie6rk7gcVACvmj-9LS?Y_ zguz`*ul>-sj}g}w*sCys+o<>^hB1<1U{Yh%GNE?3M3-Q9`keEH}-}| zwqmeS1QrPq=1vV6S@51Z4Yd1_x30$Cj11MVor#q2k!uCJF#kDivjzjm1tdz=I=`ID z2@gABx{S@AY@uCIwDF2gk_e}oK6QZ5A?O6?DQRQHvdP%!dwF(dFFa0W^bIT3zWH(m zABfj~oQ_*!Y1@>YkHf$M|K)IZe+3|#vh^V!v?#(Id|W{%Lb*rBf)HI7xR!k!PVB)Q zTpj3$AdG_9XwLAWnp#G8n9Wl0Sg);GF^U>wyYuR!Q=$s6+hy@1PX4Sdpk~7^`^V2v z4MgO_qso(m16%ud>ot2QfwXJb_{{VMo4iB4e^`rt(`@_rF!$^g3uoj#V8bW-UxfRd z1U2-VKZ;%RcK5Bd8UBQa#^SN~I)mhk*MxU`s`{}By@1>kR+BqnpO~*`i$#X>xw(9g z;CmdHR1~>G$@%OO6Q&#(1On_Dq3;Juu3ibiA*@7%u@0*0ts2Hk8Yp z>3%fheiqIb{Yo$^Dg|8pY+!#fD3FY`Byy1PuI1m;pywEgm@=6Ijo>ckZu36ETqKrA zZ?6+T2HeR(=t@1 zh)e70Esp_@V1~NHJi3VrQCD4SW?6Ii|KjSa0-6BVzsb>E8{H`}K6V^! z43ut_l14g4mw=?ykPs=UA@$93&j04S;ff1l@B2Q_FNF)$X4TJKWu!d=3u8ysElaD& zonc)bxN9#j$!K3N&k$8xb3|zVrb|m++vys?;}ONveCt23Dx=keZC zf3Ce2kcf&IG#Qyn&$|tB6eW^WavZtq|=F(S!J|b&# zd&0JG+|?k{BkRK3TiuUn^MLt3n@;mBwrC<1MZ-6n`IPH@Fj~WO#X0Q9f){LmC-=9c znaPW>NQYcNvoVd$jq|$P_&(NLvoZV4V(x?c3zhv@a)os?P@TzKvZS&0je4vWV%p&J zTqq6!^-q;!lf1AZmep3HZ2v*`(RT!3C;2_bBn`nAKzCWfDuLd%&B&43@BDuZ_4?-f zz_d!|_>WT3Ea&(LmO#yKLVy|JV4y_i&Dp7Fd4F($D#TnNQNy9VcyXsRtx>uYXW#j( zBV4$z_**AZ6uc5IZ%FxmV`$uMt@6xYZ4vTH@s}e+xd;!rZ1y`VrDK6>BiV%RoS9S8 z9HN5h4{@R-DJ!eeH(r?Y^iOA?8Z-hXz6E!bX7|qsI4fcu33Kgn5|=U+c^!>af3%Ti zz>1a+`4(!Pvy5TRe6Ah+arf}U4E`UKpP~$tvp5T9&lhX-$eteY-sz#d_)HLjj&;^N zv!9ikUlq|Thu5Ew|K3Xg%e?v96Z}Ys5jSrYg_=B+4^6u~&%w_FR}5aO+G*GftZ&v9 zh;tJ9m`&-L1A3R2+LCq`KtZ6^5r8q66)uwMmQwC!;q~?knJ;-@U_Vq$jxL1=Q*w-= z_alB8Hz!|?#j<7h(Vkf)oKV3kz~RuAL3CwRvzKqYSKO4He5zjyNTQQl#3B}Mxx2Sj ze#rS}>*6mYapkr8FMHtxNxRturNz>jQ{a4uyz+}2W|knBqY$5*IkqH&59s@g3(P>$ zz@aUY{V^No@sT)cbWf<@5E0r$n(ETR3GP znRezfjq3gPlckj3>$e@c< zNH0WdNH8LxXM{Q6_tMc6LMm}`>-vY;ahcOsjVj%>>yKW}QdILhn0<~h$qtV~Ki_-q z1!8Xl3q$@YkP~5vn*U~@mP7`uosIpjt)pZw8EqR46rKs<#`p!|q^8kh;LF-4r@AY} z>qk}O?IQ_|KrT9ZHT=r9yAmdOEVZQZGMA<_`}l5amRIlazx1oRXDut(mq7^FpAwf7 z8o93A?EZFmdvzz>oMP`lA$9;|f)s^#JNir?$cL&gqjM6Tt%nt>nR^3fk!DdE2{R^J zgW0$dp_N;+Bd9FmTc8OPWS*k&EB%*o9 zLW=jgfWNV*&U#FqInRt4B|2_uRlxX`Mpa)?t$w7s@RN#BI=rDumPtiWH zp$t`Ttu7qTq$=ccdQOek(?aE>SAG2K6G6;P77f#W@@=%UvSNR9o3fBDCGN!sX*Psg z%w7JOk(4*<&FZ9@5A+1k9|=NF&~U_OiQ5gwe~^{=v&^jq(FwwT%@*=`D(gtVPJpFe zs4&I$8^nncatM;#6L35{#k+VGLOuDpm9OhlORX7^%K|li_D}<}eB)5V&*R`Ho9KOB zid#~;LNfWu2Xn#?())R+i_A`FW%++Jv-wo+V&$%~S%J@ExFjX^EyI3;S33wF0SZ%Zlcn|&>lKjxr^dqNkx~{W0(N7=w z*$|YRBqKfjdZBdJ()6RSu6@?V?Eka?o#LR{3cRoYrWFGt3;#vrmjcfpzOv|Hw(V?j zLcr;F=~?Xu*0}44o`(=**5hOZG5;4URsV~(x6}gi#U(0aWwCS33HH#$;z*D^t8*-< zdk(Jz%iTpN7#f4Ap00ivRWnaeyWFAm(3o0cXfKMnrcB0Y&6y^Pwa1R(OV-9TiGJ$a zl!o@UL7&6{ov2bPKPb{-?v4rUP>5}iY>AMh7!D-X>!@}B=`lHVF}XfGsMoS{T~7tL zwG+kpg{niTeh`|ejD(|>mmZ{M==3MT6a+1xt{gbVYeV*`w#<3_>TG0bA8X*xm9j|< z+`!UeV+*S9Qd%SQtJAiegQ(YO8f5OqwQPYGjqy?sNf8H;bi1T$pC!%rsZ-m~@d*E|f{G52$^Q_%I@MyN*1sCiQ{u zrZCElG4#{J8HT^fd-P5C&b}Lv?C+;}4AY|4zfj@9r~@M``$-@&xd?_prl)cTeVQiq zJHB1R^O)pB_Y}I``r^P2&Pot^ zVIMMx`%EiK=Fs(GrYKz+ToY5amvM1EQ$*rn4UM(|)$8V&lTI_l~h2Rf5 zp<}*}KMR-ESpIWE{X1s$NNgvGlaI>W6XuXG5jo*Kh+5q3`L}gTM@;}1l*;`_CFk6E zxes17RopaR&fvM(wD_hdXU3$sz)HL0`SiuJed^t~1Hh7X*V_&^hbqut`RIDxoo$DH zsr`gjh6Oz5b61GlRC2IY5|tP|rKGcW(a;0>PQ3(PoSw~vmEG^)GFmO9yE)JRMobF&Xb4&Mgd|I~FI==8FG*nb4xispfqyV; zI@wy`ckxqDHxu93zenuX+TDNY|2h@8bi#Wb6?@wKVCg}aZnfIIxY6S-LwMjg5h^DOY=_WiPrvo4PL0yUN3Cwn5e3;SNQ7M(z$iBIv@2=8D6*>v~mgeOxWN8%eQMOaDy(jUQY zZZP!`eikGO2vm<7L05>Egv%~Op`af>>^J9H{$8pKyZU+k-E0yyvkJ2%4Q1?))Bv?D zt;j-M#lwM5On!}rwp6-YEoF`Wh?Y@7@X?P|a>!D7>EBv})M-}#{+i;|#OL>4#f3~U zh<$ne_OJpRKoQ|1N5AKq)+g(xeJHHim_;TubS&ej1|qnDchm&Z;oPSaIrINscLTd> z_P=Ujm(|10lr=+r)@vwhKmzS_8hug5ez*vQ5a5+#4~Y_*z3;_s5~Rdhe=lkzw~Z+U zIETyO8}aj-QmE&(L~^y-!X&gG$}AY8g9m#}NWk1eT&-N~P-+8uCt2m<`HbeL8yc3< zR9-~t&K>cfEKw0-@%}baqQtAY`?udj*K&e z6S@x1WC9zzxAU;QjikHwpmXz7oYV{>d(1YZ@3Z2|N$1!E#RH~z;!*N6g<)}7mM^V| z<2%;;B9)vdRvd!w_=U0lk_wTdP>49tsvS+O3_u35AR$yj<=&Cw?rT}hd3E^Bfq(V; zUTwBoEvdL?o|7TM$KisH5`^O7m+3_fp-W8Jh1E@5Ng7~yX_{XY+I#X26!^=%ts|=U zjV>EvhaY$L%#cn|TS+z%YYFNtmBI`A(LixBtyGOamx;cFInM`Q#aRb!m8wIOL}`v^fEIx4wOb2KMg)1$9AzoGjojz`lmb*avWud%OWqyfHU zSJ)UVMuIZwBWY1d%%$W zna2>eDl(`Goy?Ryp2yf){Ac52{#=5mvx0ytI3t!+qs7^zm{|u+knCu8q=M)mcaH2{ z@>Hk%L$M^=x0{B)d}-(dqZ-Y-updleh1(tIdV;2o!sq81=yJ^VQN$0%`e<46EzT8w z;Z;duum~%GndbiJiJ9kVmSjI?ct!Rvg`r%Sl`~G9e{RbyzLL`iVbYA}p>t<7F+tI} zyc_!dVy5~Z?%UoG%(G%+!UAoW(I-udDg7A8n9At=qQ%Y_u|7vyk&*$)zQ;CK+DM}` zp&0Y#54OlQ2|5z|Vy`TnY2g(cQe{{7?6DHO{{Xgf)5lxgtBpjpP2koE9ynW-7b+gsr-}b*MN# z?fbh%f~#WV`ijjvJcKgM=RInHcorzLTrlj}@8H^|AC+~T+|6OV8>EoUY(!|` z1;5N?a0sdONce;BS$Jse`CULEW4(RJMsQmlA;?N|t4z_sJMhMEtt+YZM5H}R@y+t? zQA<6xXD@QVT6bOTgwux+FL&)Lt$jJTxNEV5g=lo?ohgD&|87x+SU)dnd?=&F?Y_rL z3_#n&l5~dAmGm?4Iz{)`zb86~P+otv6@R^MeN%LB)kd%DRekZRx$Q|SiV9WBF7%f= z$e{NhzISA9wEO#+;|8}+gbNwb`nj*$$#T6BN&xC+Qo2a!8M{R1>I@PE%AT|7;Yc;d z>te^S+>D z5csLhnwu8esPTUAiTmym)!DexG)&jqo2_9CLNK=sv|Z&XCP-QCI}bq@^M+v53&RhA zVy-Zqt!jv!$u1D2wRl8JHzxY#%h4j;UCRc9LHRyQQu>PX%*tRV#p%6X=s%c`{Yc{G zZN+u?Xt2-=Vu@?j`w)|vo#&=a0$9fwgetW+Rl#RI!kG76zq;Co2WJxwVGbNYDf9q`po#Vwxh*Wi?(`V7p7+ivvoQ`-?_d_Ly}qf zz{bkO{682(IXB?7Fjw0*^tlrx8W3?pt2&ZACT$koVW>tB`pm9?&NxC7vOwHK2{ig+ z*g(06eU${A@5nZ1 z!Jh9K-@o0r7%mj_PJjM4aDN{pvEE0*!tqXDr7Q|8{N>2@t3B8187S_>#Ed>ahu75= zhM1~R{XKd41-a||cj2+R-23``UC&m)O|Y6&J_(W!2ELO^#@*MPih+k@?*Erb$uaQ6OhoAV_s`znz*5pUT@{Y%L zC)QXZ?jZFC>Q^|9F_Z6d{U<`z>7WA|GVEL_Mc|52C`ga}BZ(`Mz+6yQG+4=6T$cBf zp45w}-NcNBwqt|M(crj6+fmZbrEpOKc=0?iztetj1Ds!)26J-Y}f}7JerI2 zL+OFuFQ+Mp53@n+>vii=2X#Ycy;^a-fX8YBBVR}`4?dUR0?rm^28v#<60aciuimAL zzChL%Gv1U0E(JSpxI3C;F`)8i11PUDb!edoLGRobD597I(g1L~=C zQBwW)q&M`l*&PVIEnlHGCmXgA!L4hrE1Quhko-|cRwa$Ekkgy3r|Z(${*nU7XE2%~@v=UyMdQ-8sK%Tc0{cdTGt(vE9?_6w(COL8YE zf=~hkHEfC4N-xpt!vt*iA0)YAVrlD{_T(CK6!{JzdDkX*qAckwR#Z7O^XfkE_qL)F zHFkqv(Tmpc^&#e2oL~31iQfyVUas971^bB(-aG@ibRN?`2=y1)>;ggpytbzl|NKb_ zxg>;a!jg5z$pNxT^Fu|a8?IjFE)qz1>4oHg$fO)NnSxsQ%R79&HcRAV7(l%~@a?8Y z1Cp^GHKp-Gp)kpXk8=Hs@ypq1EoaufP)qNME&l+|mKZ#%i|^=v9~mE6&bT2@j%OG9 znTNxz-M?t4cT9yu1}N?sJ=0bIYNMi;{k+%9HHfa`8`q{pH(p;4;kxG{KX@Z$<1vW< z=f!A5-0)9TG=cLyO3kzbEIwC~dbCF9=j|XOWq1jS)w`YTdCXlC>~?LRZr`*ayu65_ zmfhz(7(GEFNA5fNZS}~@!PGPvg$TI>_&pN1l_Rdyosr0t$M32(%M!1~hYzzh$U?gs zft{BZM|TY%^qRD51#a1NyVum%gT^)oAlua=E_F#>DGo;=yJtj@D`Ds%WvIVDd&@(y zC9!WEm3e9)9sRs0#HXmg-+A5t%T0qtK^G-$6>lK^t_|kN%ilB!p{;J(%ZrJxkEA-g z$lICTmC>9dg{hHYqyZM!C=o%OH?GJ(_GYIvvL+ATEQSOR9~VF@|EK*bGEq*_v4gKq z7S$zVggrTM4`oFDy+k&Zk7OoIQ~vwbrE_IH;uxBI8p6zHWTRw}j9Yt~6n^m45_?XW zq*JSBSShFaB$;j%#^!V)kb)Q0aN-(DLdf_}>l$`jT<82ej*2p)t(ZyjeH1KBkr2qV?E8~9An z=ZtEQ=xA8_Dp`_RZWcFgOyh*^o>4)`q|sw_J(Y7}$;F|G5NY^$98eKwA8s_M6No73 zda%V;iwxS#&Cg&ca?vwwV{3@D{)SJIXHc94GvWgJD+cqHk@y9ZYezy<@=y>^-tFQP z-6RL2NgKLYoq&B&o|GBYg(3Jt?A$&1?C-blSoL;l>^Y^9p{jNsk{};-RwMD_<7U-dp4wQWHBZ~>5v^wIxm0EfK)dNk>Q9%(V zFWUiBb374}T|whDwFjqR_VWMgKcK+J`-`-gIEezw=2Eacuzk@8l6U(PbUY~2();iL zOh3seHea1b>Y0q_uGOHj(@Ee=;Djy!jmK0&%z-v9|7$t z2&A_w)}nv?E2)62+DzY)XE(&Q3X8wyheu`%DW-gjewExZmgLA3*kZsSZ;t`<49} zX7dFx0iPU^-pmfw;Z#YLqbi z^N1|A8mH{~G4v*s$k8ft^X~)ibuQ2C6IIwu*eWzPNCg(r?U(%UJ0t9_z0ixTwLEO8 z7SWS^`gNdxA{fC?<;Uy2CTCIo!HCf^c96|7YO_ch;?oPd$!mYQX*-)8a2rcO?*yH5 zBxpJEZoFm&jz|!?c(;yaQ+BAH36ecw!&M6%p$7%Msh?_dh!Fc>+Ja zUX$uf?4u*i>p%Y5wyHey<~=S2;6cv(b8{W@7ct7n+7AB-#mQc;_gD|O-q5r@Je*GN zkKfI{64qP>BI_E&)X|XQ_4OexEUGd`99m`y(Or^|m?VHx#l>G$;O4`QD zuZb+tEIPE)vcVg$>(#Dr>#8fB{R+(0eU8e=4rWhKCxxn9#gQeca|_rAxTJr?RATE< zi^?_L%|2{O!KD{ypMk_!jE>*d?og{0i@1q(i72HiR(*(mvtd7;OG{y{y^sUHn|TPN z^W!IMtGCX=WQ!SZa>iD&&E0mE<#alRk_E` zU(OO^kfI(mBBA>rK{bB0_c75_j!S1dzg=);V|CcX&-x~#h(!B#L<1ECTwMjaNdt$c z!+v==;v2`7#8z^NDp)h-m6B`6N7-kA$!&(5IoR-<+Q(j2vFmQSwg-*a3$oPUuum~O z2hHOo2+(z7hoM!xTqZSmUVVK9Zu)?8i##L^22Rx^K=t8IED0r=X^GpfyvN8LIrG{G zDuiiBU zU2eGpdi+kTr#96quZiPT9`c1+K^Z^-0b;TbENoz^k%q{o57k;^j_R*GWQSh{jstB~ zVfq4x;eyp($7H6vopfu9j8u=6l<&>obv_Qd>N9ysEEyMWfRQc$X zI6sH%G1~EeGl7~ew=ZUbMK`ue<<-y`a)dA>Q7>&qP`iPFL^~r<{Bfkcuaf!s)gey( zw4DkJFL?bV4T(M*TRR%l?Hjj^enT<`-zNf*DRRJj-m?=Vx!L6O)dH`j!Mnrae*Qe9 z6JRxP9{b?G1)?N3+QPJqm%!uUyim9T(aWsC?M6_4xSydWs-ImTM^&PtscT6p|9_i5 z;8f^bsE@%>!&62lYTHlIL+|t!fW^=F1;meH_U(5uXCIIH2>(Rjr2=N9#Pv~C)D3!X zr_-m00hf~vWExgjXSx0!H{{dHXl?Ae7wwGQ<%IX$Ln4!i5Rla%;x0JZ>oZ328zr_C z53G)i4@Vd>kue-~NV^h!_RV2^>A9aCS?HnrWVV-BH9-Ys{YVL!+1XunOrP?v^j_ns zfc#%uTGLW>(w2(>2C2GQ@(0IA?N0wjpGkk-{+bpFed z;oQm7ZOS??^6j4t>#kPjE??VDm(0{d8$2R~PJbZQ3u%tAa_*jxG_gqJsmUH&dc~=o zOe^v?Iv9}YLGnfmXjoH-@C&!4rJ|dlo;J=8;cFvT1I9Z~YDYs_iinQI%UgFYit9%& z(xvw?Y?kljS=SVQF*Q7;EUlDrT!^h*bJLj4T=4Ga6ILsrhDTv)Cqgf7i8kz&wK`+e z4vqs{ETrK1#O<9@Bgt;w%i2Cg(s6+*XNv=)?Eh6>=^3p5sr$O9_sJWl_O?=-&O3Pm zDp5t9F!E{%l+mwAPUPghoFDorgzog?CqJ`)lD(->qNJ36V;z6Bt!z7mC{oyPQD@^!^&tKUK0QocFwR~E(UkeHc> z@Z=`}&le(h9r&VgJ}NtP%Y!4*ND6)P7Bjnv1LU3q@@N4*1EGTh-6tpE1zgfExL42n z`d=6DP4WXwOdx)=P|{<>98~g+p`JBvYPLaH^$P7-54V`PB$0ZKBh(#V(7$r8W*V{h zvMFv_)X?U;Y!W)f`R5lXXx}lvxg|l(^5;(n z^QzAi_p#I&ndu|4KycFZzPAg2AmOQ!OWx#Wdj-5^+qYSEvKW|HqzZWYtnua;*hyKu z+KHu`pTnL3)b+*tD9aE5-e0Wouza3jwsKmN2;@N!Ra2Z?c5yi)#SU4j8@*o?@IgO; zObJPE^BOe?HIEFeRZ5p6mHYifX>kRfiLjl{{kf$msN7Y37|k5>TkDX>OQPWju7_`$ zIxdhR9A0!=;Wcc9O?jjL))fSstmChbD5Q+0zb{p0;4ipQ%X!Qkdn(fXqCgbgfGgTp z`hfj%EXzXi{VrXiGvSxCzd)#vm{;#uv=&mp^sQ>@g83smd+Eq04pvz7OuRB%A*|X~ zf2`)?fC3(SuoJXo5*wz%^ChK^Q%Q`BCThdnT|j2(?pxPJk*`s(?xTiQKHgt^?mt&H zY;-Y&mlkygP=?L!#jxJJAo-5lMo%2meu5J}h&c(#D0*?iH%lLtk(FLI5^Q@)aK~+D z7G@lkivye{E6uyOL{PH(+Ks>mt! zT(_hztqYAj@c*;`xBgwvsu}sd$Z{opxors{mSL~3SDm*@1KH0388hY~`{*WSZ092&FpyBq?f&hR_|7V#-^*?jT#%{`>54`ca`{t?rDW3Dd%lDK z<9oWEjy0pGb%_?p1#o4dmO+3z;RuvNOn4q3M*G#$C6>kVmnQk4k zHmXvRxT&#ns7vq`+qnhKh_svcM1+fZ!pxk}0x=M+5HFfgvzp+qfrvHJ4soA98`sj_HGL*Mhk6I`~#;OP3VQ; zzt~P@q!i#)E*?9_hl2Dl=3k&P|8KX*+kTga}9WaJI? zKJ4hn-)-VR8SiWe(Sl!i%}C%oP{@?%o5THfcP`QX*6xq^MCWCWzq3xWpU@ksOl)sz z1g4gItRmdcxEF(boIFEF)R=smLW>?9`qUehz0zgY!ZM}8zZCUC-yG{Arv1&claKJj ziQxu)0q}+v{`Wo%J55;~5jR)Y3%;lRYvJ7n-dJbKGe_GV1xxRcx|!yMt*@o+uq{_K ze)d0MeHD`)m=rvl`4BGv;-$M!eLwn43vjqLUYOc3s0bthmX2bi=i;DpbhdxB?+4U+-$hS{N8Hjh(*J z#2S_wM6=FyspJ2z1nq%Mt5CCV?2B6$`~tDG9aM>T`jm^A#`W`xD$LZl%C~jF#0(fl zf3LFz2&x-_QzGIy3(@MCju3>D1M0Z7)Ic5AbA=oF`cD-Ld3TZRAb575I~)}fwja{7 z=%>*ZZcgP8#XxS(fL5Q|{+4|0h3In9`qzxm8#0&1)nUz;M}q}EKEQ|H3teJf8`2N! zT_RW?EaiUeyrei%0@Y`ri#>uZ^;R&|KG;y)rcd?Be%98RfWO}J?+H`D>axq4a(fJp z4DV+wrJb}Y`Zal{_hXoozKKTAiig*TXRW3yfxx*jI9Y7bhw<;{+rZjw@HiJ5+1%0F zktSJmV+Oy%)bk%0e1rR|Ud+;X>+f4cUyn?^`MnYzVNn~#`yqttui;z5)FkL1?{)D2}(+>kzXUYA-(J(4I8 zj;N*Z->(iH*M(*7qLQIw2D^djZ&y#cLj^9Dv7pITo3>$Lc< zCh9-jgC=q;SzDetQ->uahV#s6z0MSf3CBY!wleZy)~XqY{22|aufVp(kD)S?6xjSF zhgtgTeVMm@K|89MvijNG;&9#KbD){BHwu%+m?F`*Kn(D?lju%8OdY5Y8l! znQVfF1Uj<87Wp<`ghzi5lokg3s4YyyjbQ_hF%OaeUQSzI?$!rIl0fEOn*#^{iqS@s zSBDDTIg)f$T z4>r@kt;2VAeP`n-SdU+`xANy8#%iLFnQ~Yl3csdGJd$`YA&Qk#UU`}EUS4dRiiAu_ z`m#M|yp3R-AkffWUtqmZX8txa<73?UZokbswi6VdtRrDCoP5U-g~MPvDU;G1=(1DKkM_o070}B11YwG!uzXo_uB~ z!?#0Kba`=gD1xH;pW~Xp3ycC8aSTd{qAMM9d@3lKRZ$D=Rjd<&kFfQKNEu)uodl>` z_3DxhPM^Xq)LT79!fUCzqMUFFkauVOa|F47Crs=2hHa7Y`TiT(eCB%%0nhY33pM*4 z-ip3%4MbPsKCkJnr!bpz7_tQYhw2?tp!#LoriUxAXR4RV8Kt*_HjOPWLcQT~wJ!FX zUow@U!d5Pl#eJ%Jpc?aBn_;l+(kZA!fqA?mW#DN;EcJcG+!Q=7loDB0He6j2s%7gZ z^#;PFV`5x=w(N0-1CWX~I(V#@d9qKfV%=~cPPohhS`Vruwj}4dwa{6G%(`uh-nV|j zmJ&H|6zdi>?XwH!y=%I?shQ~b=<`MK&&69Ge1h=pH>iP$ z@tMr0s^gNj2ymaS^9!p5_d#A71K?x>AFOqQ`!+l*=2Vy3h1i2j%h#eh;!bYFzj%Xym zpPNcyOI^c4&qRL~jYctnGe#?3es22e{ER-Sy=P<~Srmc7BVvn{dV`1cQi0Z&Nl4^* z&fvJLx{AUD!VTruFrjur7Up=#2pXGjbWn&2N=gEaF*?36qx_}PftnH=z5Os$rf1Gz z=)!0|HCs&~kLFs)N%}{YjUm)JIdViiVye)1@vWC*%eexNvjUN6?Jf|5+C zNnMf*_yo6iZ2b?kaNoWsh2H|vHLNPv75|=I;+#dgYlA(;g`M6itr<5KX?W8&8_rXzT+)ouI zIwGg=O?v!gnu=GRvz@SA>@uef_f##3Z9$Z7qAH;j#qw;lhG?~;Xp%<1-vc1(3deSy z2;b(CCHUuUMDpI}ygB{y#F+9@g=E=z1+Khzd$M9HYf7{|x&!sw6oy2S#;S_aIck$2 zV^f+0%tD@dl!SE0=#4D9PI|O3%IYoR4}waHrS?jxx01Rkr6N(qlng|kCe}{oZb$;X z&K=Wk-(0g5utAEiXR zmukif)_i0|Sfm|yuD*ITfAxB3=Nngbms`hPkDTd#vOYVG}T_OyY2TWDii6-LptOz5n7~Aycl&U-WtS9qZf93n7G#Y zXFl9p30pjJ>t0d(yD%yw8=Zrh`Pu)+n^aF`?|21A@4J)Q>p8vio(mLG7dqK!rPrTP zDP!~sh#7rMU}aUoygf*L=|vyAL#S3H75qGIe|WUQ(LC}Lj{oKI;k3E`?H1=5@Qin> z8l-Hu`|AEw+2w2~N7Urf ztn1L+na#8N@k3!vw;I0J-O{qLfiEsBV?3q9!*-xbM$iZ>!K%)?V4(uN5wPpzoxC6H2(o+^HD4SB)w#K_cZe+q*MIvS2X*y z9MXPi7Wrd}^u0`Iw^Z1`Q^_Z!%=Z7Y1o-=Vx{9G^8$h>jc4Eg09RH}P&I*)8IfEt@ zL^2b`UJsl_>keiHB`GJ0c@HN}E||6--jNpu{+`9sdPG*L=T)^Niww7SF@B}A{=(+i z1mSYiX~AtWDR8Yqy+^97w7Nf}J6abTl-9GxCE^du77gn&G8~8?1E%uvZ;|Pry;pfb zqzUOs(GQKZP;|*TJ9a6U&+=e%UJSP`sr91doaYNR@FLnm8SOL)noxmv%5?bgdR2IF zFN$wkG5J{9=9(*hdL%{Q%L#08LSt}R%DgY^KK5QT@fDH`0B`7cOQdiBzhh*g{sJ0w z_(ae_MO`FsHYw{1%iEVfTyh(4b&nC^nt0;eEUC;T7`!JR*3^1R1GxS@}Oc9C8|p=7g5J~hkH5nD2M9=+62Gt}LEK+uJ>xFl9c9N!BZoUc)bB^H z2P28yxy#Pgf2;5K2*zbf!k5Xs>{7F|QEJ%U2+pd*nmI`sUF5&KdX8=L2E@HXE3p1)&Wcd!(= z>V21bfkh|u#qU!Ak&EBPR_e1e%|xq>rp55nP_KC&3q1U3Jo$4TVj~nIfe1;#XexB2 zAp_jdsVz9^jNZ=do-$&Cr-s;i2{oH=-<@xgUibW$fkuqK5dkvDii1~<({}fjt7N$4 zo&DI!@(h&#AO>-@-p-e|YZa5K2P4@WLfX0KpcmO8o{hOP!|n(J@hn@Hh@wr2U9 zT8OMJzuH`>f5JmFD2)9`S@yp*LIfPQR;|g@w>f|q25m4dD(nd{X3*f(KnePS1pAVeNbrFB@e7X#JE zjfAkWIqPz%&)S-0*=$8pYb(J>m+D7kc590;>6w!GbE1Q-k4%L^aBbm2{4)jecut># z6Pn+%d7mRI(!<;uuY<1KCBl%7?*Yl&Y6NM+?$^1=}QQ&AiYRzk(|*k^G5 z3)0l=U;0L99qnnkw}!0&zi79R~z3Z}RTFn{6A~t_>cf$pPM- z1F4-l&?zT+pS)Jvu!?gZ^cvR=KYoHAHyf)j&;t@`C9sh$i=oU)j{}odUGKdEgq(k- zFHhkE@;ZKDDw9Z(>;D?#Bjw53NazFU%OuqTz!hB-%Lq~@W<=Hw9DXkUd`V$9M=jm+ zd19)Sz!|9TpkOc&sryBiT}N~87n|Sw6+S24GtMbD&`)ef zPs(tmjz;!U+EHzHH}#_g-$+c7(iPgoGKA}2kh%)-H{Z!;D_#=9(FfKUP5Fa7A|@jX z!WOA6R=%OqU+ZM?1wJL5i3WLUb7-gjxlcy9!uA)U#&A`zMFVCbJ^-6A;!a<3HHExA*oZI&#a`QI>EP(OWr678l|35hrm3rh;<8=X|^FwUp&ciN+ft41(EW?!_h@2`p+-ivw|qH2x@ET9x%{c9)}sJjHn5j#D$1EQ67E=B)%nOBPB)pK zT9&lVu?M>N%B62%YZw(LCy%7-<1sL1sA?)bxZk6j;d(1+lxoJAunJWxl1$p5kyjc{ z(P`Y6NAC2j-J5kjQJ$JTB0pL${ch|;yF>o?a-S?cT29?;6(d!<>7!GpG?;yBpCu~4;B}hM+6qffqB6!cHf6E2wjVq1>Dk=IwSHxnSeZBM;v?=`zgC$ zb}`{oSbhZMZVjU04mmTZrs|o2p2JzUGav7JR{EI085LjAie<+XR2YFWgi*MJL}t_< z3CW@xx5CzNf>O4Py&Jw8zx9FOkd<+HIjy6S2}7$B&QnPAl-(5nc?bn2VT>X!FWS}V ztKNrrnNQyvU%#rHa->Dupc>ZV+8;UT@b4k{+wr~N#>Jv+s1lRCKbH%YJ0H+b|2~wL zgNE+KNZ@dIYd%^g{zp9dttqRW*o*AUFCO*5006>5NctK4h69G!-=8n3n! zgmy2kw%+ETBE}$^9SVx1BXZ7#L@27M^G_w;Ul;OT_qH}cj_|?;*-*)dHe(z5dWQ0jHsg4Cq<$Q+m@~60_;`83+vy)aEsi)12I_fA*bm0g7BB`9PK> zrc1rIvY5~CPlP)9{IgfqGRo%}G#chd`o@0i7zjbayFj`rz{NUZ*!CGmBpf&rMV0{H zyFKGzP2p(xHK9Z6wID|MS1i2FkG6I56RN+^XTV?u#3qPtv;nfs8259gcF$v^AC8nttXJ1kzv_;cmF>90R?EMw;yodv5+8U+)z(Lk z^xoU(MD!lfqxarxv}mKZ(Gt;n7ePet1cNY!Xi=iqAPl05ck+Lp=e+Bjv)1`ySw7rr zSsq zU4=5v#j7R(Y;P@E2Qx8M?CgaSYJKg0Z8NlFR4({+ao-sy9)TL%TNRe zrJ2_(j@4?1u7iM`~axm(bO88b87oBXCiG%=Rc>biu^Kz z_rC{&HSYffgCCK>;OZx-z-0v3GsDM9#4-?08FCfsrLDSeMK?W+S%XyEF*k;hDHyW- z5HqP?&Y~?@o|lD@_WzFjuXF2E8G5ZOQq;V9CqIu9TAX9B3m&+}8ndd&XZH+*3`lc1 z3(6CAvBu@1n-DaA7jCbyn68{+vTzr%IkhGGmTYMG18H?rq4X`o9`#(+-ZyEq|h zcgUu?FY*RIBnBkgE=UL4k(M`%B>-CwV$b!NbdrHA-)aLFb9phV>Zr(?sSb+A0o)%B zn7-GI2@YAhcxqvLg_R|=4LhC9Q!?WBOhmBs&YWlNm-yh#gk0jk7R zk}8diCw{B|HR-IuDQ)*wj;TYf{%@^EU=29zywU!_E%Ax68+l{MT9@yKbT52Fw(*&T(QKc5nv1d9?Q_vbex>n@IYFmq;Izj=DMq8V+f zJTnr`K9h|K(!-UDL{tbBNf-^JU>M!-K#EtIM}A}VdmRA0vhpvj((;J}Oi_B4Rqm1x zr|w%COt-}LO2~w6@CU;{=c?DMwgRWim1oDTJqhb+gW_U%^jtJ6f43<^Y76~Og5-)n zAnbT$0s`-AB*|)(9Xx|B7Lks`XKmeS&l&V3>G!*%Ue#lH1y4B?_sm-w`-WT}Qtc`~ zTtFGIKuP!DqsbrBPI9UOvI&I|Djw#?P9{MM1mwRuIk%1U#Zd+3Q(MMJTZOwA1}a*q?O51te**rQSpTI zQ{BNe!m8fkt=l#hq%`iJ?dSxW$jt@6xp^3RA!vWA>q4eJAJnBl)oWt^nW;;YpaqJ} z@+S8wM6hdcP!8OOV=)NOYI?smo6}t^583dEJGA|6DN`*A5@6p%e0I@~Qo(R^7Ocm! zL#^5(pLIGv?#z+Lr+@kIZlllnp$hqv)6`I%dKEl$qp*LT(BT_=@|M@?3K2)pk)QD&I8*aK=B2 zy!Mystj~Lr&3h>c+imUNqAZE7q<~8P9j=@kt?feu_HX%pC%}&5#_uDTHr_LV(-|lwWHI%_w zfq6CJFZn{&GBKkc*&DVJRfN&=au4y35<0e&pcLJaQu)q73At~FD4;5gwpV^1XIaS} zG8J{Qb413L}EX_0@e2}ac- z1n+hbm;Q3a*3;Hw(i}*4clyCl&zK%X^6E-hz&MuxfPw2%$cACbSEhUI@v+-}dK8($b5{@K&W6eG0cevUvvB($2&p6uZII0lict4wQ^PdI?o-U(Touo_JKNjs-jE!OL^6&9*^bfHe0P%ZJjl8h1y&OU8S5RIeu~~dtqlJd2jZ&16#tti z3P^@l4BI^bnk73i8JB<;Euj6fhdJ#DVv6=!#FrgM z(>QSk3j!;!F0;c~pW%^z<>%1B3os&HBA*TE1YRDAQe8)9nRB4262}`mqlBfNQ!VS- z{5C-mPokA2JF*q(^W6KBfr1PyV62a_LzpYf8z~jHSY{-;Ow*eR@BJNOdd~}TpZ{KS zeLBtMZ!S-rstj0dbaRk?R}`78mnyM54>Qwt_#1%ior~&yi93=q8(HF69+HvQ<|(r5 zMmi<6HCLBi6Fy?Zi`x2y95D=Yno?RQWGW>wNg{+2L!`eJnEFI9JLszY_ z@u9~;_FLj4D}rl`K8zSL^kUwpuE1F;B)7y1#WV9}5i5TOE(5#0G--Nz=GBCtpqi`t zPbH7wPd1PCDcm^SzW#taEPfVn?mT(>?M3^K2_8PL|I%dI3hGFV)QgUU^lsZcG5?Bkdmy=aF;Ypht7rRGlX9<_4$Cg6)5IhwaU<5UqC2N3Wq>o34 z*{AHsei0ta%b$J$$BUvQ;S0m@V4G-k5*huE7f-AH`L6`73R9(|%(@;gxu({-Db^XY z9p;bj87szf1(dfbeE!vz`eDCXTVhR*bev$Q>Y_??W4I#3!n!$_Wyw zX{$U8!sOPQNx(;EWt{u({-3LLCW4su%&Mp%r(U&eK@67J_oQd9qmjA_pT)3MQL@i> z(>bK}T$7imhS!y)fQcdXIo(LsmI~LR~>8-pGcSe zaEshzj_8hCGVzta7rig&{9C9^Uy9#N$$j~E=6?>ZDWBKNKs1fVSdu`jPy;o+=1$Ne^wM2jAZ6A z`OM(e`~nbGo8F17?MtmCi!V3f`wg+RJKiEdb|@MR%3Zd3!8W<*jv1s;1NvaZ8H-h^ zqB6jl55Te2$+{W>Kv(n{clM}#jg@DLl32%Vq;2ZF5GEAPgik1ByUu0x%yoh8*@3E{47vf|xqi1-Q)9uY$JW^_TO z=ggY~MB%ph+O}0AS$ zBIDtzJYkK3cpp0Gx4Rq%>3YBjDy(PuL6-)buT~i5*qM!Tt)ejv%D{CJ1XY;aP1GKt zKw{X3$&_AIup( zpt@ki@kf$u`yqH#?fk(7WDUN3I4O@k9Qe%_a2D$2)V+M09{0!94Uqi&u)R=TJr;mx?>$L5uF?y|F4>8} zDZ6nDyS#xI(VTRUMXIL7Ilzu8X=z8#6h&YuiJ_Y#5{^s1wmL#31(&QVj}^oQ^9pfh z?CN}>6pY>}0pWYDtrAVjGlg*gWjOqfzcTt0XV_$dQGr=m?WEK0lDknknz%<(DvWvg zm*N=}xLDIt*zY&@mVqki=|Hv%<2IMwoBfX;U9e6;m#fkZMb#&+av0O8!KRmS;qJu}S%{4bfOB;+^=?<(C6 zGOxicnh!O%iR=Y7AtoA~iE#wqZ^zIX#m}$RhcQ@8JRcqBD(4mxx-dWDj_HhEJa@F8 z1Q^7QZoZmSvXiVg!-SK+_U*Z}K8o(-4r6 zfWx^a0FHY z#$Uw{mk2H}$7fCmi94#PSW8^iS`l#rweAgf=qZ8)9rgx@jEb8(|psJ-CSBHjR+B-|<++^mdqSediVIs6Um&guMRZqJd0p_Tj8DJ%M{ zV0QBNcloUa87`&o&vmnMR`QFVHxC54+h$U&z}$ZHY2SnYAXDrwoJgZhaK=1d@ZWTse2ooDX?39Qccb53UawlJNv%$jY7iWzjYAD;%VF8=9idaP8GdG9Xapq zjz|0>l)PI;5@w!$`WBi&{g867UA@&>pSG;qSrhr`<0&$;d0Ld;dy0I@XJk9Akk;M) zL~mUh_-n$%w4Y(kk6&v)+1<-Lf)k@Bcl(C}{M5f+TZ#0C=dVQ4WUjCNen21x-f+u_ zCnxWhG=AdZ=>6b*{=$N6I}yzt-Oz7n{ryNt@~h`7)2Wn+ZszZOCwK;ag3is50*7`3 zw98b}tkH?Tc#k{u_?~Wq(R&)AYAA%gh9tdg%CC`+yapI;NJ<$YA*?^#&~mbLg~UI? z&zwG(d!zWEY|~H%hhFntt-2m>o4)3eL%WfIJj+*$e3KV#1TJPI&`$1A#3sNdcsYp6mvBa49HG&tiH{jefvqxo^$?2gGi_zk+?wn__ zwcDNE$Q1<+XT1vr)!zl-ZTU{0k>dW_x5f-;N3aJ>KYfX@AO`WjD9A5 z(StB=roCj%x|I4R$c`X~QWG<+SUWE#i6{nuTE#bSq{2}dlG-1X4a`QZD^A#5zCjwj6T2n9ut<0 z$^GrHjoFa!#onLD=$pUw7Ih3S{V$RhkpVY-Ec9{on>DKgw_0KBqf zHLoJ%9L<+{=mYE^4HqZFTFPNq?q%Te__;V@v^i(d9F0s6Y7TO1Im8BtL8$=&C|MKrsjJ4n_euo?Rj(XeELS zQ%$x_K^nvP$`JB>&Oy?TwTwNSI7OQK->=(I(i6rpbaHV0sSR*+$4cs0f2GI?q?=T5 z$g5!Su?$odgS4> z`Hnrp+7i_k*amM)p?50Q(Zg?d-36O620RA%u=GjOIEIS;O!G?rvat8DOV}1lHFHB` zP_Y)KgGeD6&X8d&mfZoh`s57l@Bv5o5>dZGi(fJS#HR4TpQwo7Ys&D(_mH=q{>Y#V z1443R=F^n++P_BoL9_X$$>*Kq9Xk@jLX%rOCY>yyz#X7O%S<6>x-p$g`J#yLx+dWqHlREERLPKGY4=%0~ZsMo)jTp3)h zL;lsd6P;R-M|{47(C#zDZO-5#aT>R`U>#z&5{0t5{8@yh*VN0Nkhbjm5cW<~A7cv z`(n*``E{Ke`}XJI5trN$q+$FS-*w^1z5kElUA}wZEBD4X7o+ps@Gok<5vBpSK?-O2 zl_?L|H$sbCXN;a}9jnHrsW)>)`6ojs$FmBR;3omwhn1EhJ*lGNRV2KV|KWkzI+12p zrZ)kx53^0z=ls6>w?r(r1IoO}>in%6{BpK94UY)RM<+5mH|SWigc=$5^bXDv-;ET{ z4-(#j0ldB@8z+CQa@pX5RKJp@8<`ylq;@E}yCe+gsi#nHdt~Bg+4l!z=Qk}e=VLaG zqLSw4u2WhgkM<#_DAI3sMv>lRBkZwT2q@Smle{B;iFPjMQy5ZuLeJ`pb>pBc&di3sMHP zu&GxAM?Pn#+0VnKVoQtH8v-N%+wOilo)5)LiXAV3(lTT&g!7D|JPss4^u3^$BKYM-L9x#lT`O zgC9>CV6Il`15#<|clUNVwCp!j2obQMpfnf1UEaNxn`Zo0U|BWWn$EEA+wT+K;hqr7 zIYV9_pW7Z4MbGrYe44jv8lO?ce^d$nfWB)A&l^=^-(>=Z+k52DH?+KP`Vx~cs!3uH zJ+{k!Pbl9q(2_{}c-Jt2!xd10Ay&Vowcad8FU`*j6lDv!BJZ!;P`UauH%eZ$P4Uvt z-WL$Y)_dwDsp@y?vF10V0Vh5gx2u-S01vrl4xqmFJ8({~$sJvYhQtBcC{%x*e%ZBu zYnju{vx_>Wq>if3YAkdiK2)aIi{Jcbc1A%?-eztM#We~j%v?6}(2LF(leZBAkRNRC zq>NEc2j&j!AQ;xY#?WFog@n1u?|+>%7OZ7U`cHpd?Mt8B*3ah;;Oj_xSP~w;{xgCR zD!ILSwDn`lF$y$@_mD$FcxzHep;F{1QsxX0;SJtHXP?1|{PNIk;$7p7syg;AQG@Gy zPwMhFJ{Mg?0iAviov_NTs{QJNR3RH!z5$1FEP*(M_m3L|K47|1O|msbh(7-}Q5h}z zPp)da+oM(#9@ZR%I$l)Vr0|vlal2oRoda$@_G4x1JX-~a&OaZ1jAm-H(93Maxrslg;q4+qhpy^_m5y>@?E0$t^~NFW3VskLVm=dvppOTdJd zr8SQdLWOG_w}M(H?S1~@jSVfWHu}}RjuQHmne3}auQBWXCY(qk4HA)h<00G^)TXJb zt(**Oq+E2YyLEN5oMRq!OsG8V^ke^2FR9~)bp?BOexovv)Mq@C@@t+y z{F)yRHP%;dB|Ro5dREWtx(4+-eJ);@9WMne_S^M`lOd9MWCZS|4S$wY?C$A8n%>=% zKDEr#dj-;DeZPwLS03wRN?OtDnLjMe4&e3Fb8Di+MrM z=*d2z2;lz}0$8E;(K_8O>s_4vo24N=E15nY20xG*F|8#b-ah;go6HvfP-G@16eu9+ zdZr{&lo=#5pi1&b+HT^X=LK%Rz7U0ETEVA@v#WZ>lLf^{I+dU!5`u@ew3Pn1^^4AV zPNG5IHu9s&gHq>atZ7AkSijC7t%t*h?u-9z39_AZ_XcLX@<1=_G2F)(Y3>vqY)&d z!sfk`90<1?M}CR<_N>{H14IGp(1r2@UHreo)aC3dxRAIp=hmqjZbU)jpD zn&F>8J*f68PudRlP4M#&^qK2Ju?4s{Sgxp$!pM{n(NrV0mx> znizSf9Y{}2nLOWlBgm+7SScV!1C**h(-uG0bB?cT3T6)~wK6Z5w zoywcXFOoel(z85|38s^u47&Me*SuX@P{35;5SaPNIYU-=`9Z@Vfk27jh$uJOZ~wU(5?YhZ_eUc{| zIPB_ZKO_X{RcZY{y(-8T9#+eVW%1FuyVW^M`5he<*Fw?Dpf>}9j2@J(9L>Sh1HgRffKj}`%SnU9!d;{ z)O;jJk6Axs$AFcDT_3!3*`7DZs!})>!%Qjkv2%vb_haS(mhY|sS`OL^TmsOXW~O^& z07@7;H*=wzwh-^8@*O5dB^`x&oc^J7$|e?|JW49OAvD688%Phafx$&G^$Arb(Lo85 zX!5@Ll)mQx08Wq|$3)9M8!6igraU=2!$$1203N%RMvgg#p*2wSmt5{r&iiUH+u!s` z?aYoUYa)9>cbJcZq@gNBBGtBLk9oY-B99*KcOBLX!>kzDqecJY1%OtRP+M!(qhQv2 z8x+{ajS*r30e>3XK+*8ZNLgB?^`;=co|g`uS$?Dhwlj8XGQ?%h;uF#0l(a{juDKCV zK9}L=tVqjd@jx-PbP`D>3nUz`BXK61;QQON;gQmo!jbzA5N8!c#juO8ikS`d;oBmR zfOIYwnC2BS+EgL9lK^C?#1b}%Ub?Vh_HJu^l=r~fdd3<~a053fj4%YeSV#VM_`D-z z`rJp}GoTJdB3`+_Fi}WR#A?%67x@fISK3+TP>|zZvuHSCDwl-`3dHGISLoW=4*-HI zDaBjLk#1xntBHP*8_^9W9)xzly0t*j>B(Es!=YyfKWBna5GNW_9@Tz@0(j+|a^&ah zn>tAfuY1%GILb4nJvh4FnL?^!vR|+HW1{|gguDitj?&mg^C)ic>GlAFk_Yo6Qx5G! zH%`H)If#~Feb9N!aG*?ZUGL}BbEJG;oQ2@p=tZ(!jI^C-0%fXvrKhf6nm;ptZ|OC1 z>Y@swmq%iD1p_XA98#OFHEBNwYonwMkHLF?*M;6Mxdmr*Zhy{)yRQn`n zVgzOVDY5=asrw$&`+omV8}C^$sKIg2?;Ru?3DC^`H#rST=W#I4PCD@%DCV*h+D<07 zP85TLB|9i1U!HkfZiMB7OfE}N2ErcoLxQAL=RRdfaHj)*Q_;79x0Y^_Ml22QI+y`Q zti)3^XIECL(r(bw1LY}gyrPof(tx`hBxj}BGhtD=Ls~@)*#K<(iJI_f{xgvqBICY+ zxe2!pg%8^#4gui9W1HjZeJflC2Q}rwi(e%xrC%)a6=+M1><8z0Jl8yWZllv2jrSspr|!3Jhut2dBM8H(EwhJ z3$HU-VOXG8*bs|;hPU?2K5A4rXw3RaB(z)a9PRPH#C##_E;7ARSukdNfjH_RSTdcJ zXUhS08goe}UZtdLu8z@sNvGQ;*T1UNA1{n5*`Y2Ii`w3~8OFbgu?8_eN7P^vh!18v zQ{P6X8NoT@_2Q-rN^e~RoTenG$wV(YsZpE1P+CVvw0X)1*iybf?0|#k&fw$T`mSU` zFCC9mSoPS6HO-^)OX^3NsPsu$bRkYzC8R1;8T=@F1J~1z56y%W2&IU|%Qe&RVof8I zGGx%4XKdHegAL!aM?kkt(l|l&b9kuj;0kY@ET;Lh%kHC<$y3%ZQO4-DsYQdy$1yBWZKHGyz#29m ziW<84)u!&~RXx@d9?i!G@gz08F%=z^k!rC;yy5-bVNPe??Fbp4^izP~(j`O0^Yn~}$UCQ3&6SY)C#4dw-~F|%VY z0hCvSG-}~6f^WFrb%inxFTu1gC+hIG zpznQ?wSeuE?O-;2RA^EtIMYqY5voM4KS)|2Jkl8rdbdAm4;0>&D#zS7QoMHa7JN6~ zT|11y*F>$DMMBVZE@FrS{mi@|a)p)&#paXae0iT7+@L`<9?Dtxoq3=AWv9ki=mS2C zHfuHmUAiY_u5`)KS6Y=(oMAuxFI|O5z?pyXH-D4SO%4B~0xm1>qAQN&)pG)D&D;me zn8bGvrug`lPW(O&zSmp-GP1|g6cVPyQ zkyHr*k_n*~1>^MFKQtNMvVq~0A1S^~yNczUf7$~QQnDjAxBjMO4jRX6`q+6p6AO*< z>m(8$IM%a{OVmv*d}-{8&@>Ye*0g8*$`~1$74D{ED>#4xmHQS+?MTFG-lG*Y(e7Nf zE1D=vFMzhhC5z#OuZ*m{j0o|x4vka1Nv`Ym(Hwxlr1=v;U_ikGn z!oL%2e?YvL9dprV%)gD>eI4_N~+wpG3|DcEGy(y76I1?5)zB6H%y49WvpH z>c7Wl*WX6A)SRd7=1aVL@Vmb4uR(wJh2QcI&Wj-|aWu2Do^-Mb$qAJE-^;G5{~Tvm zrdOzq@LxTT23NuN(aZK*)XB)vgzH)gIv(|a{(!tNJqU5Y(RQ};wPXDXyESp_^FZB7@q5uWn6=U1>>oHjetl>iI~)or z{(7WFFM>EcX8zkDZ20TI+?j-NP;_#4YE^ZLq4?;bvN>~hL92IKy=2A#Ozh_;KC#nE zmyf(CpT^FcLxy`~gMat-C~jdz(_k#>%k^&9M8`LiKI6v{Hr4nqU-qeci9H3@CwVo| z%wdshnjIvb;STgo_Z7=+8D$gi3`MxlCf8y?{NaLr+}kIqTH60h;(TR3N_)KfoHWf^nwmMH?Vd8E;itnIvZ8yTf2oKI$otwkW-D+`bn?r13=# z=#*tNvTN8F)fkj!HV*@&%pBDaR+S<5x!`2HNKPe^|KVgFPLGHMqBZb#~~i$(wO{OBS*Kd6VPVRyg{PfW|e>sJ9g|9tgy z^;rwwQ~HF{kN>CR`RDxct9$mdaqyEuCx&9>YVxSV8=mj_fNk;jXe^4gKi(DsnI5}i zKwuil%gU`~PqqP6%TQB|*sT*vHE}SO=M)JnVSIAnmBWKDP)_JGsFO*{46ZcZ!leqy zLFa`Eo}<|L(!}bbD6638ZIzzEmGL!6x$QO6zjdjPemP~ z*mvG%;L2fjfSMymtdHIE@rGFBUcwaj=o$7s{6&H$Dm2hNW+Ycg@1K&0C%g zO87k{Qe7oE=U&rv*4V2sDlDgdk1fay?}Hi6n$Ml0As2A{?2UyN{J!Efg3Os3`{Tu` zolr2b4aJqAaAisQbj6+To8ktXsSfA}wnf+`{|xMFKb)_idv;j=ZRwfj+|lYAu}LW} z*^=Ms&53V?L#?a#W%I&U21j8DHY zX`y5tGmoW!;4cPS`Tyq6YHfD1&uq;}#k^sz6w4=}YKkcZf!IEeXys2*XN15sW+F## z@20YykvF3Eg(rF|7?M@0+xDhZ`A11>$Y^ztnZEog!068ak2q$a%fupG{Wc z8qx_=fY9c(jRoy>M>uj~x~${r4akejB9u?{3G{rJ`ll8pI~<3q<=agy?kKlTq_Da9 z&bEEM*(O7_Ia2{wF373!{^*Sp))Rl>s`8@U+2@ku?)x9#0MZDdE^3=zk#S(qoJ9jxt;NBkoGOJY{ib+!h7_cS(Zq znELtfzq}f@t7y8c5*QG+At&!K_tJ!-->cP*nYuKw`pZcD{&{tbLonLdmbRxh|baWj}8LgDN6Iql_41bU&(?nJo~bO5zx zFF~7xyq?OM%1x27p`c7grm^ijb|!q|7+$6HAz95eD`VGZk*$X4TiDeSN+a-v{=y{R zPGCRrYcfK45j%}=J|rZ8#U4otyW>+9fAh)O0P&ZrLZ*i!=*d#cF^!~i@V!!du$gOH zwmz6bz@OIe9nJ0Y;oz*Br{?S5x>**1Vf*{-@UXe=kCj=bd}d$xR;*d0t%Qi$Xh-pT z2W=McV61|y3Vd$1A;HFiF}ykB3OoeOLc9u&-dNG@t%H%gRgszyk6t=VyCuP_hlC7o z+HMclPBT~kz+Q%HpR2&XHz#4I^}l}o{`kw)zwS+++w1Fk{p%)p=lyXr-0LZP{h0;+ z8*&q&au#e;UX!?R%;hHgnGy=f2&WW@p+X8-rig*}*Kcor(_AE(yH7)O@V#-N34@;@ z>ccvw`tXZrpVebuwP_q8UblCf&&>dCa8}_i-ImGz^${e4T`=nm=w%GXA7WDf>_^7M2IEy+m_;dc4~oXyo!filjLiyqJj#!=BHf z-PRMnf(|&4X6Mq#Te+TnxqRAnJT|d|EMcZnOY_9@(~64EgwqGfP{Z>Op-a0zwwU3? z@YR%0E2oRHVmBUx?+0&A7o%QyhA1hP4k<_9nrETX9p&3weI36@dtE~GJVi2~dOXky zLR_vv)pkW^0Fs${M)JdHi(&Jz1)5v4LXo-bnr1#er@>7aCE}G6V=VuGRPD8>nm?8@}5tnt+_@7e+vsW4w>6E1uilp z7o>b$%a_^i&kf?GPGh3aFWyJU{>3$$Ix)rVVSgJwX|1(zT6%djl5UPf7%>z-CLQ!)UcDv@&#}BX0+YXUnRSd-j>W&@vwd2J0dmdXYvU$QmsIMGj2 z$RqhomK*aoH|K~hL{o~nF!yUIv-~v7|5W;`tN0|ji(&?J+>z<{9_KQ966HvGX`lVy+xIViljx8 z5&@;z(wgdNvSV5td&Av*A+YFf?FIx*jX1i5Lw&LFxWC@s;=u>YdV{!y5OeQNay$~< zc++eq;csn?!u2%eFga4l#97Z?Httm(KnpZCl36}8vR%?C;K|DV_LtP>p5i@!tLXcn zZ>FEACzK2=oyXiOVMk%b-}%8>g|)`k%H#98Nc%~+-c3IpaF2#EPrY3$MN4}YyrME&BKsZRIxeH}^pP*pNjge#!YAOzR8GFvMGpq_Q zDoItO6+^=W7>us!uz&O-Cv83?uyii54`l+Tq{X*6=-L5EG>Zav+EbOMB zYiaD2mGt|?rrTJLb!nB_OBL9vd8wMpQ!7fQjxY|YYb8Vf9XtNAxb1nd|FZo|YhoGY zf!_BfFuAinsY1yth4LBe6gXck=UweHLEAW6`(X&0Ux~W+P>g$tq%zW_mCM@APb^3P ziof9xhg7pBY(AhL$@2jy3oUgla0fP-ZiDuICfue%H0E9eYRtCfgB8!mxgiaMQS%Pz-r=VO`f>_n`3wk_i{oeC|etZ+zNa&C!};-xjS^4X#ELQH?^Rg}n}D9U}$If6W(HKqrR;8H-Vb zVdT65=Ky#CTd2{!(FQ@=zu@Ko0i047Jx25JAlFn!mGO+daYp#=DbDi8t zZV-b@o(7@qUy)@aE*r#9T{3YTqC7-C-_4!l;8ThS&je3>!uAgg~6D$h=EJIlv5xAe* zlkNH2ZNn8m&qsbUt+eoh@FY1pIA1Er}cD2#ODuzxD@s4K?~%4VJ1r z8)ZlSmBDA05Yy3wr$PygW~bqPX8Ioop=ElN_$IQCV3nh-c!Gw}h&9M)SHJ6)K8DQg zxxm>j3}EV^%+O;5^R#EBVKqJ^-uq%diS~z){axfm1yJ5L8^{id4ShARpwPJ3KxiDL z;66ppwB^%E3L51?nM(No$a=@{IKQy%H@0oF;lxH`HfUqpw$Y@)#J1JgXf(mZZfvJb zV|&m4+3)l25BuAETE~6Ntb5kFuJdCy)uuDM0&uCtUaVfY1!t%MK<-c4cTz`FrZ1qykgdVn-q_qa| z>1|=Css=Ifb4Sd#k&1BMOw#=2DbTSLk!R4Ev#tsn->?4mOR3hkljeo41bni#WI*qOJG~rm8fRw<*vn+f(*e{a&Zg zr)O0{s#>VTGVrD_3=MbU4jNK?*7d|5;y(fM-KE7)e$&fnY?z^6x-2g}6@vZSFwf@nDdbTFWj zVq|6eKTljGYC}YvT3^h+QGD_L=)-~(t10TvVF{>Ql$tVBdbh62FaX)&PHHRdAW!5! zWT;2rD=u}VD^pDpWB3SW@*mB8TB$^Nx5R9Mr3^4ipnB}hfS&%3c;Eon&PY8b3`#%{ ze(^Ck77Q=)u0*uoUuWOVZg#{KG}D}E*gs>1q;aa3kwZK|a>E{myr1PwaH!}KJ$fT^ zsNlr6f$yDWrTaNzB?)IM2+YA@0fyT!07+r9E+cP+{f186;H;$v?c`MlrO$57g-(BA zE%8bp{??knmB`Xn7RD!V6VTAknd=feHR_K3sWIuaMmk0)oUodt(|olI@E0Zp$(4`; zZRs1b*Hq(aEB==Sm|Q+>@y@0`{IXdc9W9?!kJ~tGQ!87NA$53D;Yv&}Ir2!fAes_h zL~^?y@5v3uL(E^NTo}Q+3pI$o17CA1TnE54i!oIxGsaG;!Qp(TJGc>arTM2XO6N!@!Ptk_*v;7uy<#X-U3?)vKVksUZVz|8Unk>KZL z?OQ&?-Z;UqL?8c#H8KN_rLuu8zN@?QSbkVBJqQ^xE4aXk!=sf9musQhn?J{y5c2vs zOd#?~1neGG(s)30`8wj%dfeW;`GR5R6Oj9{0DKsKoPA~eaQKDB{yz^U^RI01F#Jg$ zEjyj%%?Sdzxwk(b7d>;v1e`NxWfQuTqAAbJTy8`_omJlM&Gv?WVqoz7u|t{ph`iHu zTfyYI8LIyeHOIH_4f8}ByHA8)&Ybq`^4|ZBk^0h{>wU!EsR=gcspcU_ZyOi2H)?wj zwcz+SG+MmkYZ|e!@=b%W;)6y`EOGS5S-$>1oj?7aQs7K?ZsQw@b} zg^Y)tr3H$niic(VyfajOVNUPAU6G~7o>>EuzP)RtfP%?XE6`H|id zHXOd>9v^*MqaJ^O63BJxiW`>Q@pu3T8talzbi8bU3WTbbQ{- z9J4wHm?kE4Y$)h+*_UAvW0qJOl;+%pERbh&_L4!F1FxOMg!N;9i7F3+>968xX*bLn zS6!k~z>2%Wd6*HnFSvpZq0X5$s7Kd&=HF#vTfT8BmEr5Bt zf<^$>J&J7jQ z-u|Bq1%6845=Nc-$ZuC9Gs5vxbgWW{ZJ$+rwH0nnVZU9JZu-9!7UaWvt)!GZjMQp3 zEjWKnTy!)7009jZ5R%3fEGt5JM{y4sUrn&3MjU$2Co;9-1D?nw2SCV(uh17gsDXq=r>oQH4)LEggf#D1U|; zhK-AUhmOc_S$s9-5x{5mSg;6x1W$hReVL#alLb~`ghe{NmJUBRA z<8qIMKSKr8+XjnQ=HwE-)QzB1<|RkKL4z-ss(V?XG~}sKyvjHtK*55e@%PZJ7?){ z_`}cDu#A!Z!zk@hpRDMNu?`KFPSC{Fz#kEYR4WmdE40g+9b(PrZ6AXDELBj_T|dh4 zXK&HsHBEZ$`NN-yzzg_gqHgjIo1H2-wEU<&HNI|4a0<73K;SQB`11heJD*(2#E$r& z(3^+dk#i*QF=Qg1$QG+_v7w7Y-shDXgWEHP)UlqLhY<^dvagdY`|W(@=M5hVei1Ov zV4oC_eyDvYHBImXgu9vupXq_TGl`%X-JLVnhzsFMbH2W$na4kfJbDSQTUq_*5PI$d zYquH^QdAxl|63QUorno@-rZiTpP9P)sA+d@7cDL-9uDug;`W)lNa@#B4nV(>{x!Ya zwnljYdDLqn@q|ZSci5H%QgdWFF|Qr1Ux6yZ6$2>s#+tA1La#!A*hhPK3ONX-u+Qx_!^>ZK|+@d#k4l1)efrdmy9vxao}z%So6t9oK*GjEEf%S z@}aIGB?qMju~K;TyPcFo)ESpxt;g=^{TG{D2IuBp0h&RQ84|3QKx#mR)Y1`k<3<84aiq`0$%yf`K6IlE9T!mk zvTU(;+F-*^fa$Q6dZ27K5hwRr`53UApix*R&w~W_z24oz)87?ay~~|HA_A`Z^6h8J zG8&YibPr)WpL$Admv+MSo4v`vV$0+P1-{HN{IRz z0kR%v-zGk5Lc82R*%l>jp6eFN37$D^37^qLH6S9Jn18}{7d+YP{ZGUevRrv63TniZUn_)(a>ZK60a%mhI z?g-st1>Z==PuL(9A?5wf$T^}4DYU}!P~hj5K6!C-3FPTVFs+sI4{6&KN}Z{ z9~)FhpW==hdZ?qpU6P6&o{%*)zx*1xWK^*HInAw){9k=|pr?xX)J`oZsFOUfX(;NC z5LTKgs?$!2p}-e!M-PYZcXg-sal(hcP7=|iPXY@n;_IC&u3NQ`;oxj*M*OvGF>)>g zFR#QtX+RN(c$dh2WOpy}$+?#lB?8ZBA&JxjD0h-tGIq{Ly^$soYJ4}_A$~3?wab9k zg@h0pH&{5tiBT~6l0$T@k(nZyPX(vxNcHeJ03LbmXy6ROx@ zCM%d08rJMasy>Wq3tWKA5!%{ZW;0%FN@kp_edXXlBRxU;gw4xvp`?HY-x4Z080q&7 zub@xe43nD9 zwwN;|{1YVSQ=oYf;93}$U<-*dT!-4j#sab@F`b68E4r)6M2|%LLSVrbib^x7k#B*E z&CKCUzHl{F1#^Klh_jfLtIAEhLv<@=EmlBqzYb@)#`H|4iL%+J{z{-a(3K{o zpDCZ8FTQO13uc`T=w{%E^9U=p-z>(S)uOVD_y*8K27?-d@fg*h6SYdDqXn8rwe9fj zZGrrC!^0;)V{Sq2_rIT6kyd1F*vWGiP&vR@-i@VJV307&v7Cj@h^8i z-;D)annjzk%FiJuA+#}6FXDcK%=;&j1pK|Lx<`%3xs9NL`eqc5mkdi|o%2v%KZEzj`X5OSB#^`HIeQC&>TXysYlZ?`bp9oZr1ui`Isb*(M#zWC z=iIkvcwh6niEGw9UH4WS9)hEUIZwTEM|5h!biC_nyIifVqxB5{!crl>Ug6hF*E_+E zgxV@WMWZ=jk(us1yY3*wqrve1ui!Ns`v!t6|Cs&6D!59sm@>korKiS)<1g6vR5I32e|G~a)b%GZ6!G0VHIKg%?{$M zy0Lw@dxNg|5eh($Gcq}d7eNVZ=zJ&2cS$)_ad`hoYGMx#S|j6@oFs$a?8*pf6{%+K z_M~B#>r&jAHM?y%3+B82MSE`97`{*Ui+IlMphn4+Ty;JPis^6OKoM(#mU%?_qKuR~y{FB9IrXGIY)+H{^U@f>A#lM0@I0qHdPB>P>3Ft> zy%lhvq-}22BLmtSfip6U<^q}D$jUJFlHKz|592clg5mWfBJ5XBYe>e-!jp^IHXI2} z22-{FBiH;-RpIze7?KuI5d!4}NsCaOSN&rwtRQR)8J+bLT<=~FX+2|xvYdCWzMnri zDV3or;oI!N%)P(dQSYR)yeD5&$@iprW&i&Ko3FNvfBvV(nQa+YL3`cqb5Q zQpUKYdr7xSl*L0^3bW|PK8~>zuEUeOs)?SdIM$$fUHoUvqOuWxRECtJ>%8165v4Bt zdvZ~)LrNsx7+w*2%VcbcwuYPI#1PD^x(SIo;pDE>+eFn4Z8o7f;SpFmBKb^>lO#qO zh(Ke4=abx;mF%l)!J14(Rjj(r>A^Dg1Ipc}=$QtCc9g-YZ0K_c4av>Xw!Kp1WJ-O> z23{qdMr9#xK(JD{9*pd73p|D}Nhw)13#JZ*--#O`rZy^j=UQl=RTX#A7|*;Q9Vidi z{Ysn?mJ*(JC}#YIog;;ajmMwS>L}TuDY{4(+C*wewkWIbk-j<2ru|mQaT6YszoLAz zq=>LsnE$vNfFH5}<)hwk#)>XU$?{1%OuRIPufiEH=C;9+8Z=(qa41g~xYF6MBi`J| zho|(i?bwbmUX96o(APKlsLwr4dtLRZ1(0}g-Ka( z;bJ5#bCyUBYGEo{od}5^KViHXYbd{+B9itH_{^VEj3N58rXh%6#}TPcHcT zA+9K`)-aRs^8r9Lz+Vb0%9GdY4;JmONP%Z#>!p`wm4D<6zfq?|S{t^uzdYrm%6-wN zE1KADS;q)|TKVZ%-{r)Smo}g8`|rfo_+{MNX!Uq^M!RF`E(PE52 z+FDZVzVVm7j@mdMS#ZkH@Wqc}0qHm?#JYB=ryc|l9+CDK8BHiGz0u&`&*y)BFAavf z5P-1%lJ#D@2UK)Leid34%A5Pf?q;BG5gfAz2ARFY3N%+a1y7$J4~)6b@WMY@b9HAI z?CN~W)v^8MxnAL^i|uo)2TK^%o5EZS=S6Cg_Z9*Dw6^a3^}=%5{Gx z6k@OmeqO1)KX`JqEF-Kw50FohiA~%e259^qlD^G6#tX6JhQASTH1e?Otvj9w+2}wwXjo68Bq$KD+5NmTA6(sm-OwSun^JX`6uF(um1CXf z8KhAz54#yK(Mdv(rOhIXGlPrHHW7Gi%O*owS7zu2i7XM$Uq}&ua&YPmygwQr`!1|Y ze{8YnIKhUSO5Kwqa`cx{jVetv#U=|84K@i#x026ip%YGOC>I_Di}l^lYL5C&NjIiv zenht8u8|WSWxdV|n%U_*M4<={m4JdW{=hTALMN_Wy!5^BeO+zgXM34Igyd4^ELwQv z4hE+VXcsHg;S;&vu{^pC3i1}(*yP$tY2Wg~vnmT+$ancuRi^{d)aRefq_$5&ifkW- zG+3OSoft><=+@@NTWOtw%4#v9zv6r%9WsvW@sQG8Dt)V3re0ey0&?c4#IL!q~&Y((GEh0xX3@gcr_~v4p;Q&R@QjIA)C`lx3etAk};||}%Dbk)t zDiD#!W6(?uBBXw>EB3fjXIV{_X7-R0-)&iJ+KB{#xhFgi-;#Mms zz@h%})n$|MLlAxPYdhj~U*d0M$ZLN$gqJ;TK&^D>8IzOgA=iNs@sguJsqJ7qBgQZC;Sb+To$8hb-3UCT7rx`p7q=%JoGbT-b zVAN3UUxg{XzN?4uSZHgTX$MV_AQoCA%o})Ax!&~bFlGIL49?WOenr& zcLvdZc9)#ifb%L$drsU5E77PC4WaflH*7cmF2x2G)E<83OW*tutF;-JIcfRXmiO*z zg?!w6^XRQ^#!t7DIqf`qvLAn{GQWSp51$F27rN06wVCW&7vmiAH^nk(Yiv|d?`@j;mw!~ z!(|&Na@{t7NqE(nJmwZtYd3ywgG!B=duXdv{*bN5HIhp`$Ve`~Dmxk3@5Zc!0?;RM zw3|GB9E6zh{{6q5TSs%6>~I!EbFL_4;*v1+o6c*W@f*_N%mI~$$g9&iq98+JYjZ(~ z-nLzFZrkk)7O^?Zg>0_fWrFsfH=!%i{uDL(Thd!mOu! zC|t=pV6IAtz98;vbLOAK?BDT?7_*MNLAq(3I{SN)3+@wEr{U$B)?r?BL=gd--PW9{ z@(llA!5fH9ErT4lL0W6sK@Z-+5ByXAVrsj+oKCLCivJDGP2c2b%$G0za<6yQLq-c*>~=d#mFgc z!1e1GV1?Nie$_PLY_b8(toTcnd+O0XdU-!`yns;TYt#>;du@^4Ig#Xbin*^gR}4cr zoMJY;(^)C^UCYW0d!O?X)Y17I}TnGe!t@Z9=RMB-pcvQaa#%Foz^~L(+?A z4tqq1fs9txzHYyuRhZ>26G9+rJ*3;%C@#GI@LJ{13!q_Vfz2@c2Uub0;5mHx2kOA1 zoM5-S3)Da+QxX4xEeFWQ7qNHwJ+!Mq#zrdgaCLen;DAiByAzYriW1<_1^5cqU@K1d zfe*dlcdZcQJRl|u0+^a9woQ{U9WFI)<<;0sWb*D4CE=1r$N;?r-;4BXJ?CF`TPe=^ zrO6q-nv293N-9fdB2l#GH1taY^9fmry?!4yl7|k5%_IFA$kcMKr^y5fWuuTK$6+BS<{P$ycz}7dRkFFcQVyrds zY3)QiQSGA5&Vy|Pjb?fg0`pPg`99b0qR6u2sH<)Q4n%yuhAontKhqzQ$eGw4lgp_D znsJM0v)}+jvEkhEw53CI0-BZu{8zi3seV#)2G0D9$7-z3_V40jP@e>dWue|4Z`OQJ zZ}+F|_t~DD!vTaRQb}K6@cOALUmQ$EPo+>_p)8k~H{Bq0Vr~LmwZg2n z1X?>CXL9yIWB%gY?WBZljkPwLt!*+Ov^zkfd<}1xDvAiE8Bp#ypL%Lqg}_W%t(S3F zJTcxG1(?am$8jj$-m zPg}+A$t7w{BLQ%kzL&seHnMbh%boH}pNPWmX5ih{pUQ*{C3M}9Qlj|cxW6v+_-tZ} zF&rJGi^}Bp4-CSDQ>?_IvJdV*WF6 zBI<|M{~tsqM7XB#o-GUy*O2n6@15+W__3z2rm(-Ps?Hmfr@wh06&XV?L;QLz=iK)3 z63|{TA5n$^arT^4oG%Wk?brg1dyW}i;{LIG zN)sEWtc4CFecIHWyP0}pw7&^^+{)6an^H5$b335Q`TlTtDJS){Cmk!3al-2|?4<1L zZjT983F)aZkg*s6#BKG8p2Qbgci@5)&4q`Tnz=zyU1w2d>4c+2$m1gQgIaRx^^xcD z!=3uY3MZ%;0bN5or0w+s=F6uGhVU4h*(9t`Rke!_d^gzdejzv|6tr`NStwgMNBvQz zG%{f%ztJKOW$r~6lH(|XnwY<--t&}WgJ9f!elYr^J*lYo2=xN(NClueUT2n|=B;8fk)jKFiB-WQVQG zr2~}xh1IO?v1r2AV!KQm+uA>06*Dtk8i>d%A~bGM0{)7~V4qYquR)zn_)mqV{6M0} z0GJ-k)nK;SI18*B0(5h(q5cLEhYJpW1*W4cXwcj%BfFE7oc`ud0Hwj*R0daDiY6ElfqiBpzlIgrlY1cV8aT$Jp+hn67G{YlwKg?Lfr8!W<`L!QW?6P+Am$z}N_l4hG zS6bUoTDf=^2fz3ATFR&8V4AC&Ths-mfb+IF`-Tu_(}2|-C4wh6?8obi4GYFl?*BSG zuQWzZ^vhIr=^dZwD&fG@moxvU@~5$ox%2TvB;%yCgW@j&jtzM}j~#lvwMw&p8Mb-~ ztSdEk*#yTnVx~ahSYae_3Xo|(g0-gG6**J_FO7JAB_*{1iu%=%fHHtkfJG7jB+W%f z1{q%KH{6CRz+}b)YL9I4#S_D%5FC{Aht8TANk=C*yh+0+6XLfw(*@&TsOw{ZHSoBr z+%o~j8LOpyr%kdRtVxA!fViuF0hZ&r{nvJm{*EuVDEZo z${qK^-@gMLMqo_Xi-C)gc#{C|P%sL7K_?`s$*`$8V@uPoHs@`1KeB-dp+B5D}hhO4*3!Ob}%lCv2*}Hwil*9MBSIO z94}Bz6w93bVED|ag~CP}KmqiFDjp=0UAU??1?q3Fc#k#_H<^YtiWn2}u;sjU4XXt^ z?OLJg1A4?-Hx3>)4$LgE!q6RvUw^;y^KT+1uR=OV0rZ;N8&PD(ZAP&)<(!W(`GPB6 zvNe7Fl-Z%Gh)a8hS4TxX6PZbL6*$JQGPX=>a%kORq(1y>^?e~)b< z)y(5_)V!!$N)Vbqcf)=PBpBIAFYHOgm;rBd63!j>%n2reBLxjazXpmc{KZU>Ae{vu zBhX=(moHz>yM50iVsg>(XX#-;KxE=)W@eKVqs23w%Ivm6n<1ePDTg(GF66R!iO|@V zw|2=vXj{!bw(%4daeZ9pw+*sKzpdvFS6rrm zVnHgBs%6otp-S}x*T@K`wn$Bx`&bs%WfDvmCby7&7SiJyq_4JIp~ z#ORDB1ScED8 zC1P62K4Y+E?h;4HY7L(;4QpN$lxr1r)%)_53Wb`=XA{`kY zC&;XD>9K~W#CwUK)7FR<5VPm6P~ZG9`}VP{pfyYTshOwsnjN7kpCrfKuWYvJG=h5N zq?cjXHl(Z5z~@|1_#hN8O;WlbmdP-TyBp_N7_mD;7yTqcqsvcs-yVR!Z|dQ;e|sJQ zPj5=gMIp&AIU+WhIr96)U*6==K)C{ce^wI{jIb59$1*76=u0N3KSC*>#3-8DyOQ^f zE=+-ztyUW)cg3fb-%am+DH;Va*NrSk{zz!b7<+@zUg^_gCK#O_SYW|!M6IqLfQx-{ z?k>Rd2BS~BRF<2&qBFaCeg-a9Q^>)C3@@c%r73d%;m*_=0u+G+rdnInw(um99%$F? z2FDSSm13??-skAvESxX~XEmPerQU#L(x^Y{RL9vvu2%iufh0Cum%Fd+_Z~IaF*Y; z=-9%@n`-p0`cE7ISFETU;K2BQ9xIz$A>Y9PSw@L+)$y)yyI?lh1(|@G$Yfm&_8=+D z=6@RN#S1uHyV1xn_k7eZUpM(z{&k^u^|yRlE_1HQNB_-XY+m#3rW(m|bYn(x7xx=+ zYI5v}BlOP`asImec74m+^QfHIb!}2oQZ*RdmfH4OygV=fqokztW9wz>q1Vsl#s6YK zW$saQ$7~vEg=-%(`t?O?XNKQR^d$??LnefuX3GLhO238FjUr(-4MYYNWL?SN5)4m- zyQb}sJY$6uT=Ib3V?5wd!0ge>I>F>-Bm!_E$Rd#ZD3tsTNWaUv1Pa(ZcZT`bEj9pU zrMllAW5XsP?{DYDORATry@3%!6fE){79vG~SGR78H9wLI`3)(>a!6_KwP(TD{Zs!KPJECGI`lABWKyKIK& zS+cfX9t*a%Sx_Fei)&cb7o^CAp2w?BJ1^2_HTmr(M@t*w{+Lp_}ll zvUTwy*GOUxA)uv%bWB7-4v`X76m$3(o)pmqh}Ims5PaS1A+mOT8Th++ecPfbQ%OCuQQLjEg?= z(#q&)96JUuTTVVHgv#`@zYE;IRY+2PScD}#@-F~Liw?V>szx^EDPsQswW!0y_@M3TzT#mOe)CfXf`i6OjvcK!_sRIf7Ue*KeIg-UgV}ECZIm)*ih90Gn1C{AFqlr zZRIBQU35I+0TVcQ2CR`1!ZGZ;3AWy*ULFxX4$*0GM-Px|dU+&aW15h;mKx>gn~e#O zpco=4=PX0ddlt$+#i5^)UM+Ki5trkO>$BjV-#*o2@|i%L^a7Ckw$Dd60~|dl_606; zhtTp-J868`OA9RE-cNAR#P8E+62R1?mL9U3f^O`d#H3O!ZshDE$5+QR~uSOrWEl~8uB<_l~)*8blT;&y&k^?G@OnJOd? z5;l_3qWQcG(PK#ZykdS{oo?8D1g`zKl0z|Y-H{az=v~+RGoS&V-2vq>^7dQ+->1RX zdHt~E$bI}v6k?%i|Nkp8RrAy8d=I0@nXP;Tv8f?BIGo|8G0a)QoXN>v{s`oPS^V_( zs*ej0tt`~WV(`fZxUbOXnZl?rL6ioIW9Kk6TFb$|_1DV2)*w@bD^mb9yjqp(%0|h9 zb(W@!`3KM|gv)QB;oyj%tb0^8<_+db8l$p8`Yf{Zsvk=>k@TKFjIlVOgB%8TjNJ5V z4u6atY%Eu?%#mwJb%Y0$UX(^C&KxM^Bg1m5jfpi;c@IsuG(FgZCIm=NZ6K=$54_sO1_X?<0UYd z%fxb2I?Cw4P)VUbhYOCgu~b5se8P+C!3~z`3k*g_lAKBsKJgvQ+VxDV`tM2a7709t zn3E%#h)!Z->Mthj2Qnz6{5v;he!K9vvKG+%x_XM`f-D`#qdr_79BA(lG|ECvEx||t zd-Nz+Ry433cMQ&w?#+>QrBPjCjLhjTclez$a{5%lNOxiNXbU7=Y7BYxXqY08$tvtb)|_1e)tos8+r!jL z-eZ|X!2g4mb*xq<}BaFDve z?OX0hCZ-v*x!BoY7!0a9t4Z6n_GSd@P?^k%dCrpyTR zkLvpXPA(0Dz_6WpfQ}|ptNIkj|w~Eis^4L z1~OcK`8yEy?`~&)@a<*Y0Y8qvT((m(|;1sE(k_mY2aFfAAj4o9-a?cb0o4`U!kJ(2QBVb%Z@`?esoE6Rp zzVQyZvS}Z*7JH|7fheY@PxCL7bD0EH)v7&)KEUZUWj)Cgd<#qxnP0jNhJOhUm6WsY zs4AtXZ}-FKQjpOJuBlxydnUQW|=l7~IMY}_z79kKv$pl7j)L^@7k|wy4sQCWdx@@$c*ol0H zmJhM@1OHaMno1T!Dp`MF-99feP*;jhOL zome`aA5Ml=B%49P@obG9*d?iuGRQ%*y5Dg$l|9x+FYGW2T0g^u_Fm zK?Uvp;lv&t!BV*Zmj)Hjqswru=+DeVix=5=k)XVQ}5`Dri@Fm009DTyAW9cVK_)nF;go!?>z+Ysle>}#^~ zbUGk7|B^d>Np4aiJC(MyOyyJO5;Cj?L?i9i1iwt~Hzd$dsNDRyL;KZ^BWw?gioo{7 z>o`|PE=h2rGmfh!ORneu&RFXJAr0V$TeJ3ypy+n0PIV&;5g*gK4GS!xl)?nBDdYQo4jGy_cFg zY3^9d(fqRtN-Oavl*p1}Yh}stEFARYCk6?i^4iDD)-S|$uSL(^g6+)H#)9L2DY*xU z->Im?)Rf|8#pGLxNR*@8dMrs>TlzDv& z7B&%ka^^VTjd025T?AvFc!Fx2Nj>l^3-Z3es|jVfiCc!5U}TBlqF)ItXz582@3@u@ z=i<_sM<-iy^Kt+F^0=nBFj?K1K2O=?+jh0>P}!vG(y?HgJqn~jrRF53U0^P-5UOQk z%gj{pmHBZ+)@}RRoyjO=kkv7htE}`$WKSEHw%IVKB8nhg_iaa?_4*gVqYsSjx!nmi ztvxov0{w(FELC9d>GaFpBKCQjPtwl)e@!r0p9R>iZtly= zODA!Ll0m%GczXgpSRl9ic_vvfVu+i-XKAQeU4&FfB-YjJ2`=^+6~1S7+`eAsK%VyE zFe;iBK<5&0U{}NCCJ3H32>*mA3ofSTMiKc@4O6jj7`=!a@NOo~kP#EK&mXj(l+k-z z#_@K|@o~N28~}AUN}F(bQj(x0i!1(WM4rtRM7-}6;NiRGBgY)HYgpf2u>Sta_V6>a z56ID+T;Dp%QhbFH9voKi0c8wFAsa9UbVV~DrKu0ItA!<2BJedZ8{6RVUfWUJa4G8F zpD(};;36sjCI!QZ&2c>acr$qD-tXu&+}rZt_@ED{ar+9vB_P8wVLD*M3D%2_^!qcg zzF_-gk7lr5dH^AdbBy`Ox(v`1VfE;^Fy-ui4U88kR*=f274Qgnv7yV^v(Su@A&y8Sg$4JdMIb#)0-!9sK-w0&?`Rf!XlBeo@UV5K*`)Yf{skNTJ>f4e-{hD=>O7(8I z|IQrm*~YNpk*PlB8Pkojzu2FVG>HR;nR(TZDn7JL_S;{XyRDVoN@$^K=~GTux`(-Z zBvU@^+g-o5?v7BvxuCQN^CJ*mOzt4IV^xU{^}_U9{%o$~veMp9SDl3&-jVifK)t)V zJNmkcZNP^;-TrcSTaCw5nRl%sF#P!AQO|^y!H$BFIcJ%D%tAUzUHviJj5T1hUc1SP zRC4>DB}2@gH&4{tRIad>C_9V&tv>9N!6{dgu_8QwuZ@FGTkrn`wY7e$ z)~eNOwOjnTc%zLNUGJ*~gu=k-yQBJ3m}`uvfLQe*#ANqUk6OK+aEcl7^vk(v`P^Gy z&oIC)j^SR{TeNce7(vAB^5vp?EXc2Kec|U~#H?i3Ts!R8|5^6`tnW#kRwS&lVu&qB zr#`eIFA_0`Jnglz;~AE7Ft$gDa#@7NJgB2Kgo4;g0fS`_KX_`*T554b@|QDh5=A*Z zS!YHPr%aIO=O+iRU<3{)vGq54sE>3sRE!p)eVO^3qgm$3(Dy$qTrJ;)qKwEkQJvCF ztuiIJgqWH8a@IB^(K91p>${?YxHvNR(WqyB1%$GZ(LrLIi&o+Id`S3HR+OQriO~+Q zYSp) z*NO!m!~dVWhrEdluBMQ%`~b^4;k+B^7dxPTsD0@XVeoa%uYLh=)QXc-mWFCa1J0z8-# zw-7f)5Z;NzZFDDbCvm9Agtd}=Z2~IPK)N}{&2%!E*xoI3N$(SbL0Y4g8NQATD{}+E z!Md)=7`P_ga0$VDDd^ZrUvSL&UmxACx1b;hB^F)acYJ!L{qRcx0u}kG<;g7zXx;jl zQX5fy*$IZ;i{LUcaY4uM>Z-YFLlS`(2@SvR!=hzmz2umDgv`ZXgfTWS+^cejcREW$ z9wxt7PTnIXEc1!ZA^h%0{QB}v`Su%P4(tlPPhPSyb6(`h7VwB_hxs75NSS#IvH%~O zA3SL8&S*m$Lw9FBi(SibzpL+=?wF@T6d{IjY2L(lNF>rRrb0rd5RTT>dtcJeFQWEMcqVjSkj!I58Jbi_E)z{Ox-cox!+ zso0$(4d@L#Yps^97()3vvl?Us==8(kSbcTYZ!$?n4MLp!mih`2iT2b@R^)Bt{fhM# zjvd2Codj8Jc8hiwp2vaN#NNJXAp5J2y20a^U{nz*AF6xbN?zAa7dyO4tDA(2esoQi zn*_HQ@t|dU2VsGiZqMV9-)y}nH)BnMzdQE(ZCEx(@e5hAxC=hasxI|7Nnu1~g#Pq? z&c4AfEe_;Ht2WbZPTz^p;0+edwc6~={MbNk7A@x;^Kp)!p4@`@G!IS-8$>< zL!+R9))q$A(kWm0ns}1QwBXPx7k}(qQ|3&ufQ6yy4F1w4e$Hc#2%;=t`Tjh>Jbc;o z753{Jz;jlOPK_D8jQ|{;W&nCZ^(P&es8|(Hh#Kr4_?gK0{fH{V8~~^K3PrX_*mLJyQTS&g zr=(Lrom@b3-w-3L2%ggW2KZG$P-Z6Pd1EQDDjr}DHb8zu(}YG!n&3vFOMlO%m$F8^ zWy19tmOT4W)7$H(xU3wKl{tyRI;*g(_YSNhmI;ed)g|X==(2TnvQ9GZJ+i_GCDGd0 zogW8n(hz$wjcf!?=FiB9i^uU6lYXf<{vnw*CK)}W;GK)g%r0OfW=ZTamzsn0Wk9Jr z;ms~O!#qHA&t>g=KdKK#EFaBlsqL&9=3NWLK|06bM`VrautNBcHw4ek=fd*x<+m-} z7&8&W97>CDx=NJ=)A_F;eveEJiLZel!=PsOxHE!Opvxy(&uwoXcpT>8$An;Ph}u*@kOJ3em|!uxL}@(7z4|NCVr@% zk{+9PBu`0Zb7p+&?yECl#qTCi^FUI%^-ejcKfiSSd6^pT0<~ z8i#CpvY*J-h;4O}z!q46y_rZQs6yqjw%olKGQ5^s1YlPZ(&#G_Bm5l6@q`+|t1PVX zkE-pn;ICI+TsY}}FCkX=^a$*WaC!oFEaiD|#gO797S_SI=;p?n|+KRh& zkGs3OmqLO=aV_pvCFx`=iSPUP*0<1Q#*66|btW)vxShi;|rnxcw zP8?F%k5I(VK6@pD5blg6J_ABJ6x?nU+%@wTuma35PJXE9*h6K%uMzg|<(SsPXdJ`j zR08xxUUsjr2hSF`xmYr9}vTy zszW7*d5}?xyiV&jvM9+RsL5XEE?}B4?BHiyE zyQaKm_ceF>L(RQ&56ya9`KbYY%rj^kEFWARO2MY6csX&%v?BHt(cVUbNs|RN(=H|a zovQpC6_;HtW6PiNBbUBxLM|@8i&oT`>L+9+p6yf|%erK5S zy8M0*Oep}H8SgkJlv_%?eIi~j$lz?ko8&sh;olq07!T`qzM!A>mbMrVpLBDJn!d0=O5b9B` zB-T70dgGoam~k0kOPIqUn?%&9xc2`At@_7ny`aw`pTx;8bBFcNXQeWslo4_p?!|fr zkf;s${=~++&4F{W%5a7YZES$5-Iga+;y9GWGz!+Bc>WQaHj2REaOd8s7X%1i;0F0p zP5t0w5W(+lF65gQ_M#ux<$FAK*RKcob z42l%ywU8oEVGHFfj^G&?Yo>`AfIb`L2R<}Mvz@K+8%aUfmHJv-#xVOzJ>SSRbA(Oe zt*T9Btz`9);>_I#Y>B{exS6)f$HpsF@8lBv**xq}e7^Vbc6|qkg3i0X1dF8|IKzQv z&1s4BihdHijEQkk$EaKx(#{@flTJ*Uja|fV%U;L0Me1LzLu2gaeZ5?i54GIjn3Dzp zHo@U53;f;Bqa-ztnAZ5RaaMfu$fY+STFB~VEdEiyT>F|ys#^u4IizDJ>>n?Xd7F4Q z49GnV)(_@|=mhBt6S>0X3{#7DMRZlnSw`r3$nkIb|f%Yz+N74(?ySHkl zwsOK@YxS*`+(bFy{tSs`497oGoqb4`y;9zaa}g9{OM8pW=NU9sQPn{@!5d|D_+$pzjmRJVQA^#HpOZjECF4G*}kFe zA=YSnuHJ{7fAQPMDExmKhyPUgSyfng##gx{uoMh_M-tN#f}L22SQ>9`YO}Y-#3~M6 z;@{l|ePBJVR{8%poVk1dw}EKtR27T3@Fz^D@){h!9r9}`(k?^)5$u}pfSmY$oeu3! z4ozpVJ9Wbg;olVEW0d?0SnlJzVV~QtM8^qa{e7c;%SZkqMf;MVR%o^gQ|Am&GU>*5 z1)EJkpYD{5T?rtLcK7tI%yKv`SEre9ea|UzlS}CY7A1SX}$BZJ?PBaFwq=XM`?VjDcN`g-TrT{`uxAq zCy`5P3|L92Jth4ErEY7@dr?>-FkybE|Gah2*W^Z%;P>#h%=GRi*wZ+7fG{8(ES4*V z;E?QYNtr?5X$K>4#-jIz&b!Qr==M|JR=f8{Xx(321P0|$C%Bln5^<%tRsia#xe4}2O#mW=Y0u*8A3@$IQku#K$S-h_nFQY(PFwq_&qRG zAUO(ucO!Z43a^?;k6Z7%)EVE{qL$fIo0=Op;g51fTe5PN>cYgBJdmAjx$A)KSNbDw z%!XelzFuXdoh%p8cPo9JBE|iylcDy$YMMW`tz``<;TEKwzD3%gv~_JPvBZ+LrM9Xe zw!xenT(1)c6pf9uLIW6CJ-CR3wWF9Pkg%Kv;e`r^Mzt;pyYJC9%)3Un-z;*MiOxyR zFS-8|J(E4Yi^N9uz_`#u5nl40RBdnKO<(k0bzk?Tc5wJ$a(!;Gt3Rkt|dNz4@GM9&PVk*Tl@# zrgH~faRuqXZ19d;B&@J7g-S|;*FN|m$+@hg0j>yV852JPDm&J_Xv?6eBJ3&>jMqli8?zK>aD~IseJW>)l0!b79mS_<= z5{pyk7kvbDPF{~!3_l9E&Jd)EQftDvh`S|)9_belJzJg~??wVYjf_tBM=X!Sq@1N&x4+w}y1%|MTTPIBd0sMNXGpxEzC-Vhy&zy{w}8DE%L& z)ZtyJnZ>6Nv}I*~>n#M32^siSGvd>WFIWB%zAJ5vY3L5-Vkw!&C{@C4l)9ND%5@d0 z0M9)LE9@2UD-vpnr2+xr+XT(Hy#hCiBp7+*0wh%a6X!V}F?Dz~#K5xQANgU6yiqAa zo#w+vehtHlRl+``+XNV%KXt)ju^D!qWk4gGp=rQaT*eA99Ek7KUD3n21ylRMN4PX( zW!+Do(F4czroZC`_m-GONC*45>YaY!cXYCU=4%%G6$mL?_=-$sshl6_QuiRpohkIy zmt({U_RZj1i{zE3vmsS()OgVz_ZVA-ypFO%Ixo)}{@h|EZ12d^sG2RlL4FrNy0Z6v zf@Y1T8Sh>W|4o(k^kqEb1mD|7_*26Y@v5KU_u+eE71726tTtFPVc$y*7(P<+lifc2TmJRl8791|C% z;iO=?)yLY9_fF)4w5RYNmNk5jEq3hUXxDuTGWDPH{-PGs8{p^6t4Vmgx>P5-7THAi2 zcx1wm?5(b}x(`t%S@_m%om5m9sEOZZMiK0WmWdGY9dBcIV1g67#v$4?_>%wYoE~!Or)S>iAD8>`A;;)wV^zgi- zJ2T^I?`1g50%j!gK*8p_6OWA^Ne^ zT&H!@gf?W{hfz`n2^F@xqPGGE!o&NMaB_6l+o9Cm3K7YqaGZK<2x?dWsdrl0krVY;pN{-jDOU}b$gP60} zrpmL?CSVN%QItF8!e>-DvgrJxo4^r~RPAK<>m-PMl;u4a=N4Mom1Bqpq)ROIKDn=# z$isue^Zqmc#h>;LDu))`nXB(kg!GkbCbx;Ng?wEt*2~LHRL<~e2SYYNDnV0~s z{ympxNAGpP0owJl`$Z>_{(T+9BdeF12s$L{<%v);h4p(sO(n8z`|tj`lM4_$-J!tS zH77Wn$e!0ppWVqeWMw?xzxiO~XLOEp8M&)hyroW>%i<+$*yJ&UyUHmjg92ej21&$E1 zkzYNzsglSgPFq#n25hvFjx@*bw^|NokJP<=R%KIx7vGT9zYH`LJ|DjCTPOF?8-V9# ze7mvZUq-9=l=Z{jyR)(}@rb-7VF4D_xa>8T6g%yH!(nBJd8x+yzv{YnS+w^5M_w=b zuvX;Hy0!P@Tlsjiu())vK6Us|2vsz5+@73#NwzL-3ug~$j%Zf*mjliI&zb);_SRIl zJ?f)#flEy$KQ@t@vUXsn^N%R8I|GL{<2o05P6)@-SR8kR$&ksrHUTz^2uT{fGzeF& z)JK^m)Mg|a#SQ5xdVrLf!f$@nkW+G3$KassNE{Qs2o<*J97MQX7(R+!A_3CbJ$4op zLc^(b=Z*`)5{{)f0Uk6@SaB<(QJ~6i*kKm#Z3)TUNdq_n*G#)E5@f&ayiSa_eV1$y zyNgt~IvYD_M#k6FZh^$8-)#cIz8~1qv!s~`OT>}vn}5iETt84kt5Yom{`m=yR4Qi4 zqKXtts|H6IiR*VNP&@I%o6(*nP=Yq!W#npyhpQ%S<1;;8A1vo0sz5c=h{%j0@zF>L zl!E4lK#3@{8%AsS?brbjYqT$cQvh*#Y-F^D;Nj;oBw~mM#0vh?yT?cVz{@mhz#|>7 zkrw!Wi%OPc!#Re-ol+!7GV(fsbfa06%Roi@BI#gr(ryra;D@jSVYi{6Ci;y9aT+xg zFQS72Fd%wL5s|o#`DNqL+n$c-q9;O`J7pVGuPi9-hY5zSu^3Q*Kug{-P+DRP&LRXc zIt!RlaDN6^3%htD`tGt^fJW4&<@)6GQrXw^X(K$KSG&79__a!q}r4E0qnL8evMNeDgwn&np`;CzM3Z4c+SfstXf`O+622nF3`pSS~>+IHT@t$1w3 zaN0rVGCFsw?$med{%`rZKI>J!b6fC!vk?Dqff4;RImXvnh)sY^$r&r|eclE)6ID~! z9s||jeYuS2hwRM@_x6F5+xvGSXRe|k-tL4*Q;+bsZOJxG!ahsw(2Mb&R#a}3tDt*I z8eXsyvUJ7!WC!Tv$mQpUxT8{y6&jBUQhs<&1Rcy*jbV??EdC|q&*xzuZ^8cCxuFtq zR^%=ix#at@sqbS1Bdrwg=5h2RXuGZ9xS0wWcgJG5G4D{D>0k?`4i`Qk%`|s2;bmdC z#^q(~%F;HsSY#8sm2`9N8O5(gh#9ibfXnK%VzFlv%?0SqxYqP;z-hgBBS=ab;#OGI zaWJTh0x22nDE#`X(pa`V+e;)qUQbo7yv`?H36W z{@O$XbdXhj{QyzIFe5n7lkCG|ueZ$n5bqSnV-gonTS)5MDp&pcv9}K}7>5_&o0-Q; zN|OkUmWvayPg9nooEMWCZfdcZR0h#M7D`#I_!bFll zB_sCNsrI5xnBnj-ung=Bn(+v`tUF!lbT@**vnB2TvxJ(04#k8-n5eb0H2SO$R-LrP zaB}Ws;sx0yuUUChWt-`|dbd8jR)^8X4zpnd@GC0_-CdCPF7RRMYfM(jOT5Y0jzJ(Z zK(c2!(VIqo?N9s_3NH$XI?t}8ycP(OVWfon4tyFL+N!#SG+8HQ&jjlOHek z;4+=PGHQ`Z2eeIHU_I#H)p?6EOb~K zJ{6PDORM&goh3~|dn*>@J4>qa$tfo8z$*h&N;<;V>pUgP=XQKCAeoI-kC12rK6c37N1{nq5_{Pq{ zM$iVkhYE3*o-T&<-yy~%?}Y$O#O^NfFV$-g z@n1B3gUWnR$S=y;c}(CtjgAaS=YWaz9b7$Ccj|DLdmf``*@~J-HKZmq{QZvHF^}Yx z+BF3HgtoD;Wi_8rY*Va`NgC78c3)w{8S_ij+vC90;0HrYF9%;W^qHf@!YORuobQAQ zQg|{43x9;g&+jc9Oizi)nTQ);jR~8EUx0La>1Fa`g>IGNWWO?|;sD<&5htsJhzksv zg!Sc1Ra0$Y;BRhpa_lB0)Un?GIP_c?bm-R4oxZFGYy9ySg`?UT0EH>YP!|_uPbAjE`DB#LCbU z?=sN5tp2#$L`@`>d0k_gj2m80<4_&Ldg$?kd|SI7Y^^l7T!4X2zccSnbS@izb&iU9 zx860$;>VpI$cbGo%2lrez#07GqX7dV|*sImy?mSeL#Bpla+OWlhUNyKdei)Q9=&EgTx@d)r%R)LBPB=*@ zBmHPdE!%9FCj2N~sULR%Wh1b(Q z>(cK-&thtSHJ49C2G9xG$<;EzG*-Mx&|<=dyah`lk61%V5|CkoKPHg3kMz!hA~xGV z7@y9!z-HP<*@P@-<`yVKG^2OQo;>g!SmChUTt5un+1@g}n7`19q77E)Q+Rmg6_|OYz_8 z&s<`Nx1EGNvL68B{vvYqu*a%{4`_Xa&41O2JDY^VpbJLU;eu`Z;N2jjkxk8UBr|_idHK4MhCi zpj`(M*2NrG<@aXTW>^o@HDrH7XyWLl8vl9G+hEM?^=o6}|HezcNtf-~eqn?Adrl;Uv{0#(}$Z{Hasb0}mdTX~IuJQKQC*rmL*U8W_`7>JU2{x~TuOG!dzqsmvh|`$A$AbGG;=5mVlkTg| zRfTaA0N#C|GN^QaW(rA+;R641`}s{H)>C!LBwm6PhO02RptIkVfIBn;q$Gnp?;gl1 zV=<0GqIn6o*%3*F<$G8Fmkh$HI{q8__&GPDcHO&(b$f~PTMXS>Dy@5oWTP!YmV!$i zc5jkv`*v^A8oD(-Ot|-aSL9V9C^a`ej94XDj6{-4$1y21{uN6ltxJPe)WUUVCw@SX zOyy^z0K@bhx6(FR8kxW#NV6TQKwyMKCQ>KS%W`7#^W#Uyk@!+x zNujfq2$}0i(;IWGm+u(DczWey<=B^J%tBm}0W@HRyd;{2q9;uHO@tJ*4vK9L9nfWu z-k91YxUM{V#VniTF75tH$RyjP{?SFtKgLfZ4B<2qPrU6Iz54CgxMDNxd*R#2A#jjF)7!)y9+c9 znY+GI7z_2QwjD;GBVxzgPsijY7ElAdGmk$_o>Kw%x$^vg9TRw*U*<)TM={~fZ_W5|gPh`|Zr5%i>=+Yb? zz`|cnA?a4hLSmqh>n%||)D>lIF9*S3*K*NgFog}?r{TptNN0rcmqN-~47kt(DgES$ z+u2@J!Td%vV?qo+W+vQ_0o>(T+VRW?(Ba|j_3R_M)!5xF1g9_LO!Kxs@#^b1xc&AB zL9_T>;zyoy70wjT?UXt}o#O0;Sv_(*9eAxHp_RP!YiZFhbpx{_P){B(MM4oU8$#$4 ziC`T6KmurI4nx|e?P={FL1=*JNcBpY#kd;rn^3`IDeFYlzcq05u6ImX=RU~f{-V;_ zyOQb%93nUK;di9;6Bfe~rn$%_eqr=?;@jGwh#QY{F>Gv623mZIvEdvTwy7a43LVz7 zyIEn79tdpVd&u4uEq&o@`ZLdeJk5N3jQ;f&URg5?z2H4aGo{DJGypzK60QgX2Of?V zHXNy$HkdVdz&bcBLAYaC9yp$m%W2Y0BBL!^saI@Tq#`#R^3a#;`39s9ZyjfXw;J1O z$S@m4VcZIu$>_{(=_@@WJ=a^(^AkqeUZiCy4r(sOHGqn2dgkoFu5JYpna;h`!36II z5!TApkggc=^&+L}Ezd(yLcA5G1}@VN5X?ye9xs)peuzoZ?iQIIT4}e&+M>K>C{t=F zoY%qQ2E}5U05x^e&0N|t&8f4ucY&Ag z_KmxijjcnjP@8DZn@(li0Q7n=TA4l7BZCyv_ zzQNtU^IMU(Ozgk?)jJB7aoXJ3Roon~Q{YTvYvH*k!2w(}(c|nNw zxf?R_vyB4BF@eH2;dM~7AzS9n5#%lH;` zBRPO27EzXb)%YgPT98?QM3BtLkM4gKwvQn9{d=ndA(cc*G7j70vWcnl@EByM%~g4c z(@argA~0a-N8Us09Qo43_q$r!<-I~d*`2p4e7Rd8Wad5GfXTFlnW9m+4E1mNe^Sip z1>=6aH_^^mh_q@udS3w{$DEfTbXmlTHw+xXu@|?a6GTlw7#L7ML1i(>J1vIpAz;sc zXL3~H)|o9E_-8SHfz-6-{M9*wbkpQYIHNLc($3V3W9JV+%9y>N)#kmzGT=UQ^9_+ z?=yU5e-;^KJ5_b|3Kr1<$N$4j^uvIm+-)x+wbLkgIALtkH2J ztPCf;%e{-5zS|a`c^om0Q2`PUU{nEuOJ(-p-qPsh&4Kw*HBZ>iIDWb4cR@sL`>~($ za^I-w6D30ThK?;J)Ja{oh0_XYk%x2X_P9?%aR==NZ;AzZ>QhMGsnNt5Z0w!AsyuBB zudS0Q3-{#5i9YUUtUvE^c5eCk=FoM2P>&B!9#IiXTkm|z8AUELnJH&>YWRPPpX&^_O1S3&;7ji1ZJ=3z@LbZGOZz2_N}#%ae`lYN3C|L(EK48 ztjejot{hv6XC4JHD!2N3c~JGPig+dF!i~w#$@824TifK1R+Qu`JZCChg1YwUs;Y|! z#3L@|YMd6OK+)_4US5tg)b6bfJoMd`2^Qx*xUdX6<-c2BON`$x18R=LaAWO3&Y<yFw7+qmuF!+{m5zDt$CMhrR0#|W2df5yWP_#1DC9dmVrh) z-wGpx3`5Q3vYUEJ*|k}wf^Q|geL~@j8i(j*f(DqERgKZ5#>_wOemdFvsh&zbN%@~@ z39dA)lpWB!7{1?Hrf(C1y{p2t1^Ea>V5eUsBnK-Igr^!t3)zl0JgCJfH<5Fvl9%!* z8@=n56q8Oux>;WMNZ$Y(0<^M^Q%-f{Q6`_zO*&F8#Uz++6QEvDRxHG{TIHS`E+e6| z<<_xE)$HNRk4weShKsTu%P?WA2vjEF1#Id8IuJeFcwS2$YCO@lCNZc;_l+sOX$*?&8i!vnBEKA^&F&O2|v#lz{TtUD`^%Z6mFNqW)l?yW%AV#%>m7gF|v%^o14k? z?$+ZHia#-Z)hl$!rF!>Eq=G}GK^Fh17>Z24;Tt+lDt~?PYbt<(4JH3iut8%wPOP}4 zJ77652XWVYWfiycJT~Ka_{H9!OuqfXZ~V4T73Ph;+IFDRz-agMB`9bGdNmg=h{$H5 zx5AQ4Vg69Ljw_8ufE!cj$bxH+@6w4%B{Y;j=ttrrDy72(zAt?tv?k~yqfppD%maQy zi+8!`cJ=C%N#!boiT_*|nHTn=3x}+Ot=-$M(cS2PSb&;j;`|N`W6V0hG@+4w(Fo#K ziIZlWYdFDZYq%Z}ZT^J7|hfB%{?87G67RarQ&^C*Eo6x$PBvhS_|hFM~zh=J}T2*=;;6xRL9F_ zNg*I5M6_uUx4;!urA)9cfn2#edqzi z8;EyF;sOKLSs8*66}XDmNknad0jBPu+twlbMLvZVU7yTdT`-T)_Q(kN`WMN2<`591(atSr^B4^QVU^9T8nN4SnW{D;+o6}vpev{ zCVkKjFiAJqeh-H0kKj?gw1NRoXVTg&Aj+aD;JbK_@A=GSYOhV;0+J>ak;@;1+dk6N zNB|nQ!EeBTNWnSFg0to2dP-48;1|YmRAw_%U;gRjzTZp|t0+OF`DQ#QJ!Dtg3D9Bt za%Qt^Z~7paI?n#a)tM8QQt`n11NUQVXVE2Yv20S9X^EJ-dqbCW^ePFs&)e%Q()jTX z$Qdd|L`RrkR7y}TROw{qVh&SN)rL&Wi)DoRn(-g2 zwlx^C?vfv}Pd|R0YTQ3JIeq4;fACv5zari6jd%(Ryfd<860VrgOkDk%>Ck__hxA6_ z0X!$&xC_4UUhs*)Zj#Ne;E?&x{fFM++eKX$Gd|#E^6uB?iU}o8NcP~ar&9Ldrss3k z;Hqa^*5IP2ZPwtdC&elZ>nW1DFtKJyQZL>lZn8&XeBZb}-}(*N^3qf-e0fq9wc6xD zV-CIA+JbrbfDB#3aTs}qrkjAl=BPPd_6PNn8ix7uZp4CsmQ-u| z%=BEECwt}O!^&4fA^kySWA6jFH|6tD&ciF?#?DUObdL~KvD=nGQRkC5ABqc+%%{Yi zNiM@ZK?ev44nJGpa;vJ<;M)vn5;n9giaosPku;wFa!W2I3?yJIk)xmK& zQL9U}8N!Ikw0;#1e|JgBa8t(g_-ejv9!yt-yMZWcl(@QCOjd>1ZxrU|Oja(y}x~8B+N+K_L!=QJU@0YAswVsYi$kigb}cil-+xWnVa=qc930M6<&M_xN%CD zcP3*RfNIIL?Hn87Yx(rtfzU$a4q+=t-d1lzmEje%vcu`cc%{&CJza%I!G`3p(=wY&q5$^V@N|R7biA@e5Vltv*AOuiV4X zi$)>Kj zN!&KS(Llo4zYzLQJNS?K_&{W7>vr0@1xu+p%uin_w-Run&}Qt5w?(^>x%Y$EFQU_G zfz;riNc5ccqhfZ6bCoSB4&@}0%IfgRoZt2z zo{j0D9FMn#FFyF1gQmoaf_`Ne)k+{be+ z8#sjYdA*DCX8j7^-*GF3zoQ=dD;WG^H&^`MUgBcc&TaT1{Y_+TQC*lw3-Z^RRbQ7n zb|fo%dAenlzsMkw$x{q>y-Vs`3;B#1%OkF<9N(V?SIHEpGcb?UECUbvwxJzO*gP_Q zgsNw5T86=X8*WSWL^5h8DO0AX{jfyw?Ygj>18Xhaf-OqlE%loT-?ii>oJFvpVZqpP zT-vvXBLyaVR5c!(gxFkWmoEvR5ek;y^7)Z;5`$=@B3Bpj@b9(SiMD^!Q@aSXHG>0b z_%&ht-+SO6y>>mfzczdAuVFn>NFtE z2`u8Vv*o;l0S5k1baCNN!(&-u>e9HeB;iVJji7Zk=ql`DIz2XxKMfq%&IAXL@RiH? zTn!2Q+IPQna-WrGDPSg;lzwBviI*uw9UdT(8U%k=mv0t zd_D~j2Wj|&AlvSFMvsPwXPUd@cEDU>nePG6lnIK;t*y)s-p3-OW`17;k?nwjYb{kQ z3uVqN(0Y64UNVE`%*Ng9M=tY7Say}`tdT)!!Ae4w#Fm)w3E?nLCL~|)g7>5be5A(Z zf4SGHPxi>VqIf4Nm_8PJsbGbbe}(S8v7ho%IydDuqTBj(h4N<)AZl{XPm(i!w!9W@ zkGzHeWa5Dlkkt=cVrPzxm@)UYOZMITU}TxJpimYq$@={XGr|C1WImun;ExA+V!7{i z@0ibCI^%0xGH8Ej?$Fsxp_HW`_!T`W_!_Ib6bp2P-iPY!eLFkya5{sU_0O|ax((JY zguHz^m*);Q{{zrt$wbvoJ}>TvsB;nGbK^crTqnXxAQqJ??W|nS?&%D)g$?Ldk#XEc+*DHR^Hr?e!@JuC8Y9DwJ*> zMoEUqj3f|beq-SNzCZolm7_SorlCfr0UO=Q{_Lt(%9C1yw=;`wvfZwS0?Y|f<}cnO zCV$0EJ$xveg8X<`q5FArqmfr_!J}ZMqW?yjhaw#WM~ScSfJZs%O`Jtjj^T%)@jPQ` z=O*maX=+3qddYBMin*QrO*pKKt&oFXe+5#+Bv%g1@y(DS1UF8LO3Q^{ivaYz4h+eRd>eoU0 zL(iVM(b{SUv80qOf9*}6F)SLD(HzzC!=dq#g!oc@i4vp`%RC?hQ@mT$gGEv_MGgw%VJt=Y6BHaRLCtEv0v}#7 zgtH1zpcCZ@5Ku^qsDg|(6-y%B#OJh^cVz8 zqvSyte%w*C@)EOr7CmzEcTQac4O+DkBEep^*j@G8FK! zXtC+!D@L#%OvlyFArC&lx4U-B^C|OB_`U;uRql$fV0(WXp1-otT+dxOzwccc+nv3C z-d)y_eEy$tGLE770AZJTH9gi@VT0e9kpfdk76E*=Y12gr3!;=u(p_fUK8)|w*0x|4 zW5)zvABiRWJJ4Y4=bntw(c15f^ zFg(~iG7x$7zg-iZs4VTc^Y>p6wWPWPz#>Q=!kfNm+f_6+RD2W<4n$zMSz0cx=$B;b zL!NDHI=NZW$(mm)U6?OIYotYe{<%a}{t0;q14EV(x1QzFrmRUj9*r&HW47h)*q@`T zCvb(!gsA0&Jkv0PC0E^Ahph8$@6x)M-yJ-czx2Zgy{GfD90six%tNulDO6 zMj?3_vGN?YdGVSx)>i=i4O4JfiZGrG{YMnR`~jz^Gl4pJApfd0g&^s=HKDG&Gbs0H1! zKS3t%1$C#u?|sp-iSWa_xU@Xt(C+kXD(^pz30NwG2ARP1`$2G2N!}JgoxDnX=})|p z@lfB`_Q2SpjBU|8GYy7|)638y?el zWLz-Ymerg$In>@pVx=?hHW@7p13XyIXNU#{&ia~Hg`3WnMi&f}ZHUOoWpCKA_qGJ7 z2NfCoMj%d+zs!85JUjGGwkplo6H-}^23+~HQ|Kpn!Gg5m`+;xqi-9#Wr0%w#%-2tx zizB7!5Y z#J@b-hk!AQ6B7^JT}goXuH0ibpM$`0e6vfA;BG}L3`>-{dsf=1C!-4W1dmBU2Zath z$wCS3b~M#FJ173{u&0*9h6&yzRD~U+Aip>s_g>s#gWTzQ%yODPPsw>+>+M1+Ddq}{ zFeY8SxeK>h!5+c>SB?g6CujFD+IugTGgyOPdaUb;;v9W{o!C%J_zkwM^uAEZSj*z; z8vEXG)71aLBI(?v(Df7$iwd&{ZK|RsH(~^^U4P?Fp(7HE z+u_}Um&2CL0o6!j=M5rWM9{z->*F!IXAtkC<5cJ2rXo%iwl*gPO$A*|?Zb5C@;7SM zGJ)Br6xH`>R}gsvpIT{ydNfzkLf?o^iReifH`0~y)Vwtj$|`K@c$|d4=*Bd?zSj6I zGB~fdy=97lxtJi2eXhpIb2t>aw52NyrWO)rlY>W1P7cUhVInY0hE7?C7iBa<#39_} zHRPIToA)~2aV+I!Fq-O_6*uiBl2}Q5kt9Wb1?Ph9al7n;spXHqnn?P-JkSCIdx!ba zdk4Q7h0-vsv2AZ)ma3c8l!$8LT&8oxeqkTj`obrvR+mXCIQ zC$Pxg&Ng_>gQm-QI|9l<8@#2}-WLeUC$Sg(5bA^Nt5Mkok72DVH{QQ2`jf7~f%ER( zD3ir)b08RiGQa*8LTT9Z?%$S=ZcxovQb8t4GB!pz#=Jg?Y=F;f=A!o@$D)=-Z^fDe zFEq9A1!*i+ZF`C)cbEi#wxx`FnCC}k%7~9JRoLFO*3-Vq5JHWf#gnf=z>E9a>>0NC z{DUqkQhI~kC=}>J9&;oy_w+&?cuxp}oaWA6iQWY>au98f*!_cMdx1W55rd1{>*uZu zc|T{gELsOsL_Q7G7jf0-MMdn;R-vfz}2NRe<>T! zMawOMqh)H=iOXNHmTrA-0jy*NCq+})>&hO;LpCp#%68s=wfENni_}jV)igS*Uy`EQ zcTIETM}LXei1mGXbYl2g7E(0Ai2YWHlLco*g`$}SuqD(eS5K*r^M-JFv zg-G91-NyWk;eq~wW&t9?1R_ibN8RZZ{>CQ5DD0+)5jB;857K`+l_>|x{*V#!nz);q zbT?i1{1_K1nl5}>h1mbK7k|KD)+<7~n7o9P-$T8@5i?!dLUzuZVBtf){TdzoRiB|3 zpxF@^F&1jGCTxZkKPV&NkQ7>@Vj`}_QVhtpSTmvR#D9DWs!5F7!YSn-Y1Bb=Q&b-F zi~7xPEOC4z0eTK_p{=5s1QU$`wtF8=xbsc3@nYA0!^(EPZ2Mb;L{m33~>sF)#Hp3;J1&YN=A=kfoG zt+x(pbM2x>i@OCVF2x;!2Q3te6e-1v6Wpb^TOlPtDeeVMX(v?wG^0-TmF|BzL>QCj5b%tq^3g98o5q;~9WKuqA z$mcb??rT*7o{xjZd^59M*NF0I6C7CVxq}TTlgYqOHL=q|e1(#Y0rtLj$ESm<-an+@ z_re(=IH}i*%A+MI)}1fKgm=aC3~8Hx>x&V+yJ33BSE6+_5lcHpwc)=dfwjPf)EaP= zS-Mo&@#rXDeee3dL%)HcKi10+1$w@kyjKix$@K-ODyv@0tI&;oU+yYXFI5ytJII~MP;gIZqmg!ojq>a zpC;07`U;i}clQZ4t@*rY!PADn_H%UC=yD)i=_mGA)xF`dc^Us`0M7 zw400o$*qYhbjkKetT)xSY<>qMUkdqT&AsTcrzEU3CdLAOJ+c*7wr=@3N&XQjeAB^3 z%^w`s5jJ!qh8?5cxYjOUK0R{RW}DUeIxp(+POh_QhuK+ z{Li)PxoMYnR(}iciJUKz)8DEYsWEKvVO)i##nwRAdsP3B@Hz(t`7Qlt zqW@hL&B9Ki8qFpf+|WnIbudXYp(lH8<{8fgv@yOei92iFiu36plcquH4_;cC8O`1; zB)b;Zg{y4ZmhL$(be z8oq1CP+6K-w+`9>n`raNM3y|gB+55SUM3W@t#U;-E4n9nbA`@n#uk2)VdylP%#BwP z*T?TcJ+LW1zKWLp@oZVf%6X*4^AV?#`VIE3Oa=z>tUQzGXHHYG{tVB_l?;OOt&eK0 zp{$bgW%hs8PBoB}_L(M+wTVO@1DPL4zE{H|eXi@F!)ic#MO6*X>#$Kav3yAQkVw!l z%vLxb6l|tVW=@6k*v_xcz7)#c<0TqAqNgk!U92p9LE6Adm~TohKR~5QJ}e^li8U3F zg_9Z}wo+n}$WPd=w(Xmkmd}8znIu^0_s>)D1<=Y#C4j;T0*g0hsQOPkAQa&5|Hixw+$Dp%=`l9GVOvw>C7=Z&Ji(O%E! z${LrxQpH^+DY*Wg)|a3-yp(uM)09_Y6Z%q=o^4<6%jYItmfyPsdQd$9&M6GNgf@Qx zHKpNVA)ZIsrN-{DJM1sA=Wx9WB^|I+H4JD-`b$2VMcnfDgunS zB39C_Z%I+7hOW_QHkX1v<(%t9K_X^o6&21E;Zof+!$S&8n5_^;&Vtl;)dm)z6*|PQ z^sX!H#%B`5+z4{emn%5u$A4%vn|AI}f5zxFtCR=FG}~@6#T1_n9~lyNr!&cO?^U5X z=^u^?{et&B`x{gv@o+*~RHaufm4VXU(N45OBG!}Kj_`0%VJZ&wlNPq;oV!x^afz|Y zU5lkR?p;?+GwbLCkv68JLQ{bzIn=|}9H6At|Kld?d6h>sbRoXey-mRf|ql3^aN-b_n6>`yb?bWhQON9a-WeDY8 z=nxa>W{B*1#O#kav}zyp*zq@qz#;J2svVG@-qsjDJ=ZjPJIPjB4Fs7vqSmukVuL|U zt}?Fum8f)TgemVD_!@4U_@lz%v|s8>P^dJOVJi`V-|&_W>2m5U0g1{5M<^{fdE`=n z7mY)vv%W~4P0)wzvbBDrweI$yQGJG!Mx~`WQdeg9tdbA$;m+Z>)aQbX0LufH(djnocL4|68fn<}jtlVB{( z9O_XKcx2bbhVAxAKc2P_2q^NzKQ<>39@D(8 zM%JlR>Oy1ECsaX5IN733Jm4}L01!WGtMn(4q8#b+fkDB9tRmYduSx#1&l8k;sO7@_8$Vs`+F%}y}oy5f%V(6tX%m=T3e!8=#aE{ z_$5<^p!ph&mUU*D`RfiAkFfDEg|pwEhcn0F#ZVT~X~^y-YSX1|ns)5vMIUY0KWq3=Ua|R|rOCUr>9x9uUP&7s7F_$2MkNw7z#n z+9P$`P!%L)Onak#Nr*KXx0w-ddC~#sYfWg!wyKsN8qxpYnsCBTD}QEl+6zn~-2#q3 z6LIh&w7sYEhJuIr9lovue@JU4uA4H-f&vIOh++7way1pPlG?(>ubG;?tfsXz%0yhM zhIn1BFiP31A`nKyap%?1PgJWc@{u_lw1M_5EnWSB9I2TUJ0Il^c1a$~_5>w10!}rx zHy2+vL`6sIy#|FV>IWi(Hv-AS$KLWpw0!d z+PHdgU3I1_*|eXl?DNM^zy|!JcDz1S04MvqpjQo3z4yqaor zZ?jz0t!ald@B4=m#c5aUCl~Ku_u_H44#JCcb&hvq=1vtQt=y#iWt*;)sd$8Sbb=W# zNBr2Ysa6lQtlHJ0L^jEbXXHC-v5yj(e<2;qr6xql~i z2)4aT2w!_xKP)5YW)_~M1M!S{6_PYSsv9o9eUMsoJL0pB{Gn0A>o9LqtNT*oXi@+C z`5!t?U6C;iFPQk}c-B{Ma_OFDhg!bcFZ3%u5a|Koj8hZ+;4c#?r#qRkBe+;5s)JEX zVvD+@)sl2K=hFR-K`Z(BGd-G;bDIr6WxcvitRT{$JmMC9%@*VGpxX#YAAa%cYFkrT`Hiy;z}`ssF_0vtPa|JWfJ3{6J??VyTUXy* z)~aa6g7O)`8u?+=?6x32naVhwF1fi-9wD2CM3h_U>pA1+5##-QLY`GMSte8&uM(x- z+yykUa(!}EG`yS3a%6RQDfZMUk@sE4Pao4J^S<6%mm#w9baBD?AIC9YILli}X3d|@ zD5^1P$^|Q{rk*<#m$hZn3%(^4Wp;ko+*HK1MQi>~_u zlQ?ZywHue;DBpOS zPSi_sPeoe~rmcZ`phcp6`sBKpWm>oW@i+TVpnV@r;idaF@(zfcYTq!^Xlpk-)P~10 z`A}|k--d~9NfK?Cd98S6QtSDJ;X!uUhc)!>9&Tb&lBfa=uGUg?vkmrp*VU~rmK z)e~(H{&bVcCJHvc)G@u)Ide3rY|2;uuBZ5-PTK*+h>xSM66FeV#1(jjTo}d}dUt5m z>po`@dnT#65<0yoPfy6XqFC+MB}tZ+Je}^>LQHaXevu^gdMEKHu0y$C!Gtlqd_KBA z#bsZFW>lm4r4A}5=urtra`q|g=jR|m5P533aAI`KixFu$6t?nr^gtR+IpW)HC`<2k zO*yGJDqEP|6C3%-8}csBl@Vqqh)d~%4dZLf_A<%%9^{!PyC61hmg6BJx->#jMo>wc zg|!R8DiYGN7Zz%ZtUoKF(+$0fK%xLbJosOJymeWyD&G`gv2w{A{j1=LT6_ z@-4^FfYajrs*?=rwP#0|S2~MRp2r|#PrJYGO;XLbZ3i6)<-1+sCcH>843@Tkb<(u9 zIiXv%!R4GEdmB@W_pg&bSGUC4`7`jQk$6klO5Kd1j=99KDwgqmyAJz_xbrHHzAW{8 zeE7|m^TMB-NVs+PH+;An2?=Y3_APedWi> z+@581eYGFqxpBtwg3(oV!ssImyW2DE6%sZi6(8hVU#pmnG}5|bekZR zQ3e6iu8VcbE`IOmX71`DIovJXI(4yAJe{kZ)^kQZl_f7wewL68PNlBS>(|iUepFg1 z!d2oB7;Rk_6b!aJ5LaHBRfw^VbFJ^I3{zM$SsSLRu0xf;nuu1XlRB&4#}ypKK{Fa@ z4HMrx)+>Lmn`{#Fz|PkDkZM{yW?ABv{2|V~mizY1WaMM1p3^|INznIzIhB;M0Am(k zj{Wm2bkmm_8%iab|2R#E7k%F7(W$vL>%;a^ zQLmkT7Ze(2oz~hkBL^?g7MC-Vl?hHj%>?1zA6p)E z%OM-RaeEDcn{w{Zs2KTHZK?VI$vgCZ084o-u}`j!g^wC0Ji>dlWrFJA^mth|9aNVP zIVpUP8K1g+>D+osqO>8;DY_hFM|OK~4xG1}U9{8g$btK?jly?-zYKUqJj1$bi^7LqSb9s)u+avpJz z#``tzXbpjklh?UMal)fSaCgJ4Kht%&+HN*hTyjZ{0RG?Z#$Otg?Q0(1Fe-vv@3ux$ zn*15Y#5zx+LbSOt;1k*hZALex7}}Y1*}Ublb(3EW)Cv5*&5=}+fQtNw>?NfR5@dPz z(q?j()>}&7MD)9REJ#9#BD+>{@L{2Rs5AjBlhtZBvI`L?VQXR^?m48{-Zkev;yAVN zRcxez&IE!gly46*&gJofzIXFVe-e!`-Y!{V>r_qr(W>3>?z4~!K*0l`Szb&SCXWy` z1qYFSkH&BYga$>^y4-(w%wZuo~vV{=ztdKt(2IcysLBXqE+~*mR|QqUapl- z*Rc=hw1zZX56y&p63Lujf1PTaYxmBG+a&n|b^QSbkhcb5B~__UpO|;}iO9bs5A82u zy@YAwu}WE`lyPZ|gK+tej8KXQ`um~f}&H9&hv~`PKmk@fR z5Kp)YNqw?`ApY1lN(};AYmeaJ@p*)v*c<+xvx+CzuM&Fj_kXhzPT^U>Q%Cm_+X+<%;jQ`B&5vVNe4gPMpu{<_3K=;t(Xg4V#c-zZFh zYB*nB?}`nI(H(Mj0N0OOYP_EUpT`{rurfDm*m1_(`4}WQz?9duUL)>1es|3K_~50S zCFw>y&f*Td#5(!M)744+pxE~k2a*xJjw_6tIi<>G?N*$q@+J}89cmF6g_(eDNsiuF zcfksxfroUR2Y?%gW~A1z{FH~Gq!&O~e2lZ(1&89D28?Ee_6$_IJ!=|h4k{@+^Wy#M z2RLZ4`4f74Kq3Tb{*bjXfo;!cL@M;Jtf>^ouDY1Lg9NlX$V>gHom z4qceb!olTFfm4R;r-ES`2<&}du8gVsVzyszV9OgMGiG~P?!8cpH#=F4k{eG(`U-tK z+Pu7M?tEaL47V)s=`xzJa8GTA(mSeSX`Q_xi<2w=;=|Ul_|Apzj|NTmD#tw;`$&nU zC2YmE&ICcYlrM6x^J20C?ydt6=~9DL(@C&L)u1H~;PUL+NBkS%oF=(is>bcZCI{sD zH4w@?@nmGM9i0d_lDZTkrEua(DAoloY)v^y{KCJhXjQhXU?N>vD!#z>2GEkMXop*MLIc*Mcer`(~Z9{pUdWTWa z#K<9XVQ$(bGAt=OU28ie(cVX}GXTQI@V4>G>kU<0eu9WDC!5<59auIUI8SJG*VjHY zpaeEsHJB-gypjMDKz)%Rb7Vk&TIhQ1ew*Pr8madm$1OSiHN~?qKR*f~>13l#n=zG1 zs`;l)%$p|{stNa54qbMRMU`I+&Nvq`nP%*xX-rBxgZux&1uAU7iyYnS+!*!`%Z6q~ zb5kCDKH~pB=DEMAREeVGWvSb{BAM4cr|{cN>kF&4Cn*@a&rd00tmYcxi*%GtAaOrJ zgMWU0Yxm#9(M4iI?AbFPvU|PbN-dd4gM9uIu^eLHeT|g(s~5d zYROPtXagYZa|BBJp%opUZAi%&SNZHdTO~VFC$mrXP0+LKLFi!VV5VSDk*cSs$E_WC zaHws0vjqQW>44St>PnZu*=X-{dnFmc)mU#%3#D#Y_p8LLk70J#h4EUZ}mPpOH zA;$b;U21{}8f~rN2>T~UtwT{Ji4qVAGZ5#HrA4|>+wxjJrv^H^6O-@YQBsQXO<-Hl zkFP}&;88CPRC3~f*P?u1UNd@>5VpuZROZP(X6q<7p71YC8_wt;@LkQSc43dc750-v($va-anbz4!AA6kqAf1@H_ew?_l0SFP4 zbY8mdqV0T8j=Ck}SR1fl-^Ym1h)oDHlbS^7Siz$`JZ^u-KOfTCw=T5{eTC>Hv^}8# zsOU0dKOdnL)b+km6K+h#w1r&tQ8#ai`Ol#bFeq;-r%QT#Szf-1SyCN!Ga`7mJvd}T~ z7BDxl9|$NwTd{vjJ}p0%*7?sAS4#&_Vx{3X^avpL%tjAxlRa~hV;-SrBSYvOm{>LS ze%5q=Sf<|&R%TzmpJaG47tsVU3E^o;46Q6f;+B9z_?LPbOpw<%zitH;Lj)x;u82SK zieSIqdA}y+D?E^j$W!feXxeW2gJ|QD+FRM!AivTCQu}X-o?HzaIHTe*=IT7I&-)IX zJSc|0%BE7RO5b)2!!+H~1HSn_cYi#XU2(hIni7goycifN43&OPshXBBH5UIG4;>@^ zBB*E(v~Rop?NF=bFD#wkk%eAZ6}BC`mh*&3gAuYc?@_AUTx(xGAa@;}E6{s}6!P@F zh^nCvrEVO{Sht-wb!=cOfqbBA{hcob&}teo&aly4bhvSrCjFh{`A*Bb6Qsa{3KO;D z9*bxkGHnDGpQ({9mRNPqB%tJ$?-Jz>wZIIN3%2Om7}7PE=v66!qF=Uy7i?T+7cH~A zA{FtLu4I__V`QHM`xJeGe<=4PV!MU+aHVP2*u;^&OU0O${=>~ZQBV`q7kqG~yv(s| z1C=F4M9xW8)gStUepl)6$rTvj4B!Z4{yjJS|7>%779(~!7P7X(lXrhcudHDXaKPK&V@!I`*Lc8Kh z3xEq!KvUi#mf7l}2(J$nk&3$%#+3|u0LL8F+*nEv++~)ph^!N61%(v@<0My*!qc4c zSp}iZwWheB%;3Dji+-rW;dYURoT!cuUXdJA(+Mpeg^JUxq}F|5>X(jar%5QBba)Gv zOM*-Ks#eTo%3-8yHRueZFBe9!5JIju4<01O=5WaSj@viiqK4>67$Z&I5t5^9iP5n> zNPu`RDb3S373S<^OG9VN`7Y~Y^jQ0>ts@mrxfQ>s(e^#z&DCT~Cg^eV5$~()4XYds zz+9f0?hTQ^v))P^}poy{(uQgU>jCoJwif(W25;IR`MiMew*>33gAs%w!P>E}_GD9}Modn$c_0KUJq9z`9 z_xd*EkfGUi0L~#SZsKgqiO8$U3iVRCzywFv{VERyPIC4Y3i9uVTeH`C?;D*7FfE%e zvpJe`m=tM$s9~ARikjo_K$pmxg-cD@J;z|%dkWRH8mwvt`VS#njN!!|T^jTUf|yddkM3=gj8gl5Mx5wn!)+Ua8t-BQ zJEe$S^%i?xL^XC>+0h-c%$LamJ@Ru`^;yioONSocAS$d)8d9XmTl%7l&bC9#JjTEh zDNjpxE40}RQCYoAyEra%`@kQ<6oKDSI)~zr@kR2xGnSpX3h_MI2E$zA&-B+t1F(vg zI^G$-pkKlb`Wz8df6zKNiYw-={iwLU zOR#2}!Zb$N#ow}|US^##aFWK8 zum`{L=y>EUWP7#7(Pe8BdQCPm6GbZuR-@O?{2L1W+qd}NOLk4@A)`@FVB3Y;fxiHR zvM7lCTEzGZ{lgHvT0W$;dajNG&__ur_Wle6eBU?B6rh*>|9n}UBbi@Me3w%FK_rkr z3o~L5ZV@y0jj}I9s-}MBFF^j4Ig!(3i7--7xw2;W&KZwGbgv?cXY{yu zI(hr>1?VtgRUn3b-0UwebDeW<(H^QFczb!GlEaxP0q-#^79JvWzysMI(km~Hid;QL zVuEu_OSNFOD!O+Kkz@?|8makYZUHj1Q|CToj zitr2Pz&HOaN>#m-=J*q1Pg)Br(nw&7(he;T!4DMYGO{XT(2R9?o%ohT9OXcwt_dI5 zaoL$}@V!U!OQPU1#=&8m&XeXY4@JyyhRb~^w}~+WXhjtDaJPyz(q%5Z68Ylqe`m{l zVv5hkIVmdaQ#%j!#W@saSl2|{MFV5%I#TAUt!&!cn2ti(&b{YpA9A@i*zaGi%9C}z z|GuksN)0o~eN!k+(drPlkA+xe+3h=3(e@4(H@VV|Y2HwDSh}WI$f!O+s!@e4F+VJx zU+Wbpa2l~05maN|+geBVp*vDRFp~k_ImC;-qu6!8$p;>TaXT(CQ=2%stX$Mipzed6 zmq9ZF6x7#`AleVHAeHqdhOk982HywNFpiIDR`#|~d9Qar!kbERY8QJuaJi|?zn>}; zpD#@)SzU+KEh5t4UvZ6>S@*$O2DP~^%EHJvE~PzhGIDu&M)Rlnul~@J(!5&We}4KP zgF>?j^c{I0Ud1@&rm1s0#-FaKwTNL4u7Sx4b(v0cj1R(-8Rc%2K3UUJPQY=|ekNJ+mT}~m4YA^tP`Kwg zyMkoL)#Ec}uiGlPeRq+Ysr%u+zm{(XznY)3P&IC5E()PdzE!Bem;n*Fk?N zxV(w;V1I;~KSAvZ)p`2McEaa3kN0JGD~>+oMuAoxMYtjha1Z-@cQ+ERo_}51VE(_u z;7Gt%In&y)Wg*zjFs)fX+Xcgc(H}*`*mU)NJYRl=Nc_5u*um3|2`H2E-m}%0e*;BF zL$_`l(qqf2qM4gV;y>i_YOrLrJGyqRe0C=O>vD1=Q~Vg0>ysM~^NDOU%TT?`f-}O> zzd3CJG+3m8ML?8{b;zI^r$daLI56?A73k&lNotXvo01bigp0G%5QHjOWz3Y5+k z&<{9uzMfNiSWj#KIhA*@!D7sHlB>6b>zmQ4Iyfi9@y&s5EX1^rsRzGe+QW06D%Q@y z!=nzZ(V{f-Yp?h-%)A5Ly4Z6r%rKNN{1H=upn>?LbgaX@&18v@aD)+s7RHTCWu6GQ z4lYc$x4wl<$rZ^yn9B2RuWtaPHm~Lizv*if?s3?eT?W0Bq6A@5F$(LjC8UJmv|Nz4 zf9sp6IWH9O>+qsGD7E+Ng+Ayaqy+lFr+GcA94zeFQ+9-Y&WKKyTP?@2>_18} z9sKjdq#;F=aVeH=4;Yo$CJ}j-Y-4JXo5L(2hyNCV4Q4%&CL!zx#Qtkh-~iFcs$E2j zXdWEB{u#Qn|EBMd*VLH^iea|Dv9|8#*2tgl=PxY#eMefJ7E;rCrUi~I^N>--E_E$4 zS*c@oLMW4XL>33E*Q-!65wUt0sU)8qSV#d<5ly!oL(Y#>N z5hYX?!*el|BH$ko6(r{Wgd}UYI%_m6iPN=X%_%x8{%!c3`^!$Dw{>_-=vRP*f!-Jh z9D^XjS{5WJge`>^y^vhlOzc$n=&4~20wf#LflXAoO_9cQeX34i!Y-0cbN$&7& z&(zX73Kbir7Kk9XOo#DyD?mb`BH%MQpw4e7<++9ZK+6A^3C@q41a$p^3jpI9CkdpB z`+e>w9i9HXLhs3JL$gffuBDi?k9LEipG8Wk8jS(I*hJTI+X^5}N$8da$lMlTk4{^7 zuUae7lvR=Hh~{Rinj?xZ6;bl$bNeP})Jcl@8Y!0fvc&ZEAof||E2_GGE9(CtMYc+H z>$Ybm?^4WWk-$H`! z?e7u}(l2X4o%`~4(Y>SNo`v@_Ag#&qB8aMV@b}L(P39$I&~O#9WJ@Y2>m&Rjn!bn& z6Z1{gqRH6HB<2#6u8-6BbJ^qUarc|6TF6=IH6&@{!|(KOVGJ7k(ba*~8{wa=Us_wk zq+!o)&3W2Xv&?BR2OE3%-%=(~51#eY*U{pz6S-OjXaP&RP6jg{9=|m4f9jG(n_x9B zmqL>%)U=_^*L}}3wdC=>S7`dlHg`%E_?q=F@DVp6Z2W1r6a$}hpGO=)+ZpvJc=3{x zP8c@hnp|}(H+z05Vk5|fH$g1*2w7M9by=_iXqD0nq)#@_-2$7Fr?d^(A{Bpdz$n}5Uvd^Ghc4h3_+mO+rhW)|f` zc_FSN%z9K?i@&fVckecP>C5iS0Hv znfB+ToRlvTheS)qZlb*+$d4>DGq%o1ka6KbxaQ<{LVfm$B#&*0SA5Az)`;KD<(?yuGa9_08FXM zr7}m4wwbqWOw*~a#I|zwidodGj6PX4Zbqu6G3gdT!yQjGPO-wuY717cb5~+iy4XD& zPciPkcwkZ}r2I05G=^z&RXgc`5q@W1HOFatY4NzUpkS?jS}B|!Dq*f+VDe0SKX_pq zBi;tz@qN&b6OEsaKPk2OuZgcaOx%(=6F6T+Y<$Zd+Dkb*m9Cxkm;Xtm3zFo1`!+`f zb>dd7m>c+dNTHC6Mz!Q8dTREh=X^D18nT13Z#R#)_V$M!3Qe zz%*l)!~=J`AKgr+Y>no6ou(bG6*^_U&&FA8Uo=K8g(ODbie@t0QrDs(i3~h%BjWJ4 z+n*L`z6yV0xoMRcaah3hifosk6TN^u-xHH2GoZpM!z~wEEM9PN1=+}P^Sf?5Q$2}1 zC02i=!amdHJ$Vh3*VE5WslyGdfQO(7lZY3Ctu)=hu&0NK{Y{jOb>P0yckk_2qd?>< z$}ZfFb(jV-+78|1^vFF8^)Eg<8{=L*3B{`gJE?a)e79OxbucHqeM{%b#5j&6st~`4 z5UltE`GY!i(-Ls94HJK}K5`u^jKY8jS22uhe}Yy>S~@N5{%cds)H{+*qoMmIApoQ6 z58D5QfCt(r0^o&$2CtqIlt=##_sW=WQK*KHNBmrB<$d8onaCh@(?1@k@Ic?}w* zp;AjFi&%6tPo^+y9$hoJUDS3q$Lm@({5bcMMZnQ%)`Y@zekhH1a#s1EEg=2j#h8e>?d)_s7G^>W}!2wu`przPgzCUN%e4LyM?N@ ze!0>hVQ!X`s5gBd(B3woTy0RJ`xe@%`VVH&-1`9?WGU3AscUI*>oPIe@su?FIQYtO z1W{+1Z+`3cvZU9%Sg6e6X>DNc%ep$^No`V*o}jV%77yMd^B7047D1=`>Ktv5c3}Ib z+fQ0jt@7p8)yo~JE2b{hooN{IKaam}l8?K>u(H3<2huS|Q$!LUmSB9QseeyZ&L%e{ zvO#5FzE_*^g(p{7x-=Rr94V(?_TC`1lnxrRp{-_HuMOctP~;Mad^fZK=_%-0s2Dg5hZqMyhgN*POo*BH6gf2 zg}QD!8a2dBoH9ewFOWU(d&k^&?^ro!#=#*DqZRWD^m`mq8IZZoX zK)Ti1!Q1CnK{qma1CtWlH-TW;8;%rZmI^etW$cSRvB_EXZfG&rvO^$Sk*HonW>;-F zE5Av@3-olLojnQHDaO$;kf*fK1_0eMg(fF2Mx0F=D zP(Q5EKiI_QN-UH#t?W_z%qvYwA#8y!q;?L-`NwMY9kbjwO~MM}hcd;SzpYFRA)?P;aS+!mM!0 z`=`}$^yZ=ul%~~in){7AYwQHIRhp9{=BSX9lMnJ8y|@XAn1oJWqxhus7iyJG-oDxc z-0pn?d<|3F?f>0a@vS6UH?QtBVqe~3zT<$8LFQDxAkQ>6k6LTZWOugFHNxk5`*Tq^ zf=*4I!|wIXfNuDYG+l+OwVlZd?sbAMOO;tU;{>;wG3Mjv!Mi!oGv*f~bLrtO33FQW zu_zP{*@;y6ZFodQle32id?_ywuU0IQ;m*8JHWU35a()UlfR~P|Roy4#WZ=pn+K2Nv zmmBS05^d#r^+VAKp79j|D{PKnt)y%-L12rBWCJcx()$f;=iR zxV`P4+1UIt4->aPi_S+|-xPW+aOINL*fD&69NPe=J^aK!E8v9!-%-$JeqJuU%qa-Y zStW6fr!g(6=Uo#O4x5{Gsg&Oi<{H`=33hktzzdW=dhu}tK5gc*-%gMvSz$g`PASSR z=ZaVtobVY|3FmN{uQVPA)bcVkOA3?N4$gm}42~B{Ymt%|hPWEdHfT(X zQIMD};DvTIB0RL(9&hIVd*i<2c8Du`uo7;JYB~UFp_BBIFHtD|$)}kacZYO9vPGsI zJ=MIBo~Dv|w6mMV)jH9kXVb%VU%UW3srV%8g`U!*nEeNnZbs61>1z`@D&p6n1}|-A ztP{4Ri#4#LfF)aPPuWE96X;!2@ZS;hi3~!1P@H4jIedIi^_C9Xo6-xLSL{^+G0IQP z#ze%<7N1>l=8d{YENyLF?1EB^5+q!y28UR=BUHUcN%yw>0&5K_ucXd`f%U3`6iAMJ znn&CJX`9>bV<1o4{vU<5X$$+-(p#qF#4?M)*e;|D#G#}%WsD>?^i30Kg03>ys3z+Y z51NL}LXvoe$HEcj_S^ByC8j-6Eb2laFm~+bp8~9khqrw1^#AegHGtA?8>oL$;WMB* zB8Ov;(HfR2JwpsdHPheHw^-Toh-?gsz|FDr6=t5Wgi^(^Q{gHyR?A0{hXAqnRP_>K zRMel+u%&O+vs!xWg|nW&j*JwFi^X`e3C)KVQbA*%-1LhuKJ|2nEPnHJ2}aL7iGFHq zg--B!G?HHCQl1D{7sBNd!#4qxpW^WoveDY`1fyi^nD7wFZjjKCetyemY?5s^>{oU@hFYVyQ%5ps(c8e9d;*jTM_Yt8PNspV+bGF!9BH z072GH*_Sr|Pa8%)nNU?gVpN>UX0uN>89FbtCsOC@E}?rF{y#kM)wi19Do7=|tcF}P z{hoFFQ0-V^$(=QWcb`dwJj(0v(yIGZ>Fa}k!oh-#=Z+fFt88aXZ3FO|*RFdw|DuE489qY4 zYSQ2ES7XceC+~(_``?XIGyI694JFF7j|vq6M;%QrqZe4q9!)M=KYJ7Kd_b07(}W>h zXnZPpQnAm)e8HsgKTMc6IBU}WT1niOdrsz<%}`c?l-qtHpp_&Mkg3k=q6q+sK7OU( zpK6OaNSL`KOspi*N7zFSC5-z=O_<)07Phq>TI$S76-8%=^XW4MHO?*{8=+Z$O$A5z zE!bWcHuj{X;$tSoNA3tc5!$CqGe2%{=%1<=S=TP#%j2>`t3DF3W8X zzsIGPub~tB1z?X}rJ~{uwtV&2Hrngh7{pGH5{dvWX1z1D^$&S?DmwN9L-q`%|W71T3%FB|UPNp>&&$<5W!|{sx)!0TT z?JEUrUY785GI>6H*>};&2+ZWK)_V=tBG7PB+BLg;>@|Tk0_ajoI2YeyA>O!Tr}a(O zLsP`Of0tJti^Jueokw0W7wZpr$N1*{OAHDyjC_0(Z1Xg>?(=d`;Amt5j5s9mtusY_ zj%JTx~zARljQe|rx( zXTp?Zof;zuI zyWSq65_V@c%QcwZ<63U4J_3`DepRqd99?Wg-uLZ#UrHo;y;F*h&lJZ2m>g~$rMm~4 zrp?BR4>KxTHfk`-BBdGy8!R-Y#WN~rOT_d+3W?r0N5VbM_doJpw}XqlD@Gk+rG{GQ z(I+U0Ei*%8=Un#j28=e#K5RJPbhSk`*y~ZEgU2uRXgN~6(b#pTu>E==dsp`K)<(LB z$H10XuU17pl=(5(kMO&dYNK{(kZxz_E|KnT>F)0C zkZuHqR#3XTLBb)WLFq<7KoIE?q~q+-_dE4t{t$Cb?6uZi>)E?~>W692hS~)R)piR0 zE*|SY9_9{CiMhg$d^lMd1wmfH12YST9sDq4q4*g2Rf<^oO5rP(foPOpNz1|`*Ph{j zfFkt(C?P$!IRSz7RWMaao^tk^c{7k)QzG5F|+#0gwO3s~wC;iMF5b0P2;J-C)N3JMk@5+#%92*gNt z9MQwX<-(X>5>5Fo<>JGmHb-yXc%ghxsCCx2H0y0gZES2njnCHFVMm=3erI_xkRQFv z{A{?7LUmbI&#URp%_zU~ROcFg1dleSG6NbDKhp$+i_~e^M3wNDIz%3iH%HDROwN4l zy~WKU7xtMv{B|rR-)(zRC>D+^t~h@j0_WILb;Y8Go_Q2VGy)G29BUD2nm}D7k&UZyT_Yq3nn%XG2MC}NrdO4UJgpDA5gdFq>8j9g1>RrtEZyt;I zqyhu`tE{|iIo6!+eCDx?oUai&#+N*RwE3m+xzc}iIji(w``vkHSjuWTcmC3T=8tl8 z^!P3D=@wAcLVJcu<+m?|=tn%B4Gl&p#dc4^-=kd2Gz;?1iLn*X#v~`ZCNnQ_I~Ml>oBrE+tar|(qVt^ z0suEjpjXiCx>h%4l{k5@Df}_=u6q-tzOOmK40bZcwAx~}OGn(O@%#;3d{RCudf zD@&UB(Pcnr@<Dtq5y{XL3;EDA0xm^) zhN6`5Ji272=p9)m2X>f58lFtOKSHkREE^DD+0flaI>c$=8_Vj@P8 zEJ>`0Dsi`kt38Z^^0J_!?G^SkEvMy>n0W?bl<3cXt}zhTF1@wDSi>aB7b3`Uud&^Dhp4+wW+9XmyZ93E&>tGxhpcSr z3RlUoAws~8dP~<$86%7w%TknI9V>>zl3$&KID*FuH&%GfP1P=9DFZK|e~}rs+Y4$9 zLQ4hCry@f-#OUAkqM}4ddosqwWRYE$7mxHx=*|J<#3dHHE|+YIZRK;UVRyoq=bOf` zSnUyj(7gf>3v;`v+#WP6)*qRgY;vb3f0h6{R^Vm7TiNnuoktVf`)OuBJAlnn?*$B< z7eK7~|Mnq4RCkq_U)BQ$=vlAwr3oc&1*Y~=yONX7dI=&1W#Ge$dkK0LU?jP(RLEC5 z&&r5<*)P)1h@0_e?@Id0hNRw42Av1nuCas{v8Ji?5~bkJQmdqWT}VLFYBFOqF3Yym zb(#Aj8E0c_41q@MlI^O|w+5KcA9@7GPQLt4yDH_m*@D3HztCc)cy9b% z*Xl@Nacfnk7KTNr*SW6cloB5RcCY+gg)$_m6*R9n^g^p7CkR zENs+bbchn#7?&BI3Q0bD&oTVDYd2eDH#8o*z@h8c&I~IaYvSa1SJYYI+URv_%v)u0 z3RVwupCd&boih^1ASfO;9dQyd0Fy%Y5Hpb+K!ExCcj|25MQ?jmhM#2I#LtLHJCm5) z%W=*!5MCRNB&n~SP|y7<<#7?L>_5Z_p+ub>wL@aL-lD10V&$il6bQKFS_~9_JZBq#)tvr!yTNz9ql=$Ap##h7BE$ zxM95q%OIFSpt@yN+nP1& z2DT`#lbS|1;19eM99OHF-fuySlk~o~^mV6uixNzy%zxtiSUZ2&4YaDi?}2+3i%+OsMC$K81o>b(H%B=|LC&!i5 z#XXj=DBgbPCr2kepA4_~puizRxBzz(J#LlUR&L(r8c!ljyGu`5MTNpce2mNMnG}MJ zSDZ*BLx>J{7bA=W|IjATV9|UQdf~Z2$a)p&$;rpl{k}d0v z%S}tM`y2Y!lN4WN31B+zq-${L%P_;!SK=w2QzL-r0jWvu2fSqSI6JbU^0eoTdieEu z0S}ca!!jlFOEeG@JPQ?enve)0ZVc~sKWZ#O=GZPy@oAMf?ikL7F!dqkKvNuI-q`MB z3_RYz9g(FuPX?8WI5py+^hG)1t*vAK;4>td9QYh%!UpZJLIj$k(1!sF+?%jiDr>bz zUS`Z#d2rzGddW%CM>__${Qaieg5L2c+Y=!Uzc)K`Q!$K3T}Or65M3-8YRiQ|8UWm zH_#&qV^&$Wh&L*G{H~TAS5mx9CfdGCPZf6H?UesIkK^50cAxnp;M-icHTs{4#2BuL}0M38{SqX1Fc6H6z-x>ru9|D0H zuOE0Qzg2f-F}2R2ssbjT{M-WWI)ugL+S#-m^48nL_10-*-(TiOjT<~0@~!fH406yn z)q?)d>rmKR)BZS86c$n1BS@Gh9zG#RjWaRF`D0dNHeeiQ))>>6#p>B9I+ctF%4)L5 zlf+2mQ~PQ=PIp;mxqtS|XR^(CO>gXP8#D!qr=%O%D8ggAB7ZC>&b=az+veP+nLk*) zMIbgBkt&KVmhG91_>Lk>_j&?v{r6GPKkbv-NIGUM42pV|31A>WKnal!syPh=UA5@0 z@B&nei1+m_eN+wsNj>KoNx~u=#%6YC;u#b&OiwZFSJRS}e@zzg0O+!%T&*?ms!iZ4F7og^o%n~kjYX$N}v5{CAkC6()`zw zUa_r%z*OsGz=H~S(1AB`qa)cpHprZFSJnm=AXOO15ry@#x|8>;A!O@A?+1 z;Pv>phG~Z{|GHo9*CpwoB&SU;$2O96U&Wc%kknUXuZS=jNSm!S9SizehmOQhf#$$? zcQMMktV|*Opu{%|?RSXnV5i^TX+h`(N*uA%={UX|Ryac(mXtSF+VWwV%Fs2mE ze7Qu`MlY^>a%5kV8PHsQCDfGz`a(Fz38ii?VFneDa~ng@yU3v{^5$REZfIH8WLJOGaMS zz9gK5ARKv2E7oF6hp<)snKj*4thi@PqbHxD1|%hK%&Qv1D%;2&{Uard8p4@=QWxl1 zqU~~mAc$d}v0WZibEdTDC|rQn^{ijuf_bf8-r(W}SK>rIjv8xP3!lq#piu1{ud7AN zKzUfXRPm1q$H0q*6Y)1HR8*Fxz1@2XxNlNLW28}J%ySq3so^Vv7~!w$Z_enk8LZ>u z=y^i<|PeKeqKEa#2V)yVW*QG8&Y7y{hikDn}Lkfc}Ao4N(;?B;Mn*BxA#THWr0h%q$!u ztL?Cfk~7t`)c3TRX47*ohYtgHSfk-u;dY#@U~g=!#U)TfvI(~Dr3ClSz1Wx)caxla9%L;WfD2)sLtlHxWvhud(wy8 z5H~g%ZV}}D^*SCXk;%VQY^-WLz~k$6_r~Ok;~@qN3{5+Z?2q;k+2$M!vt!r(rJO;_ z3G-a8CwrT=IOSfhzkz0?futh8kg)CroU>~|y8hTZTbaUNYv3xb z&|X$aMe+P@rw28xeBAGqQj3d9I~#u&Z>^pI+c-LSaY(YJu*ggQKr!wnYmz(jyU0}V zZCkhWBxUqDUOY(nIr?cZgd8Oobk(}BbV9(&jrSkeY1%bD+r0zl4K0NO`#VV=Y=Ty@ z#oEvIKNq6E*c93D0X>I%j+^)dB0S_ft3Vdv;Th-;SzG$cYTCY)Qdj%Je}Z>1to9#P zzE<_0WgxmD$sY4_m`1DrZ6zL4?@(POC+AlR#()fEc9Z$hYvdQY4qOp7kTwb%7@h~`+^r9RbqB^|?u|9fS@(CEGQ%UOj7er=1v zdxUFyr^H~Iy#U~L2PyMc9NlY%E|j3qY*ZDp(&+JkdgLG~Gy$h^qDyUHBBVEyeyR*| zPoW@qVd&_h1)xzGXt7*&#-<$AsiWax zS_(vIqNwclXZ9|E$q2tT1KRF8v@N->CLW0z=ho)UjbgYGz7r$xKS>XV7q5~^ivAEq z^Z4~Y?3FsCb5+_gO%iDpQY)sF(WDoPxTHmC^z@S@07tiwe+_#lKvtt-FMfrohB5N+CC-J zIvVm4gb0L3>jQ;a#o<~v4V41+RaDk2hHR9qL>vVvqLR2TQ*rQ^D2l{=x$erOxdK+1 ztgzhMWRw)1ov1qIS8-6$JVzE!%g`_c;o_l;jmBghJ;#MVk6pvjQKq7zc@o07%xHW? z9f*!dqZ$}%hwZyDT$LDL!!j63)z@=f+`@ZlmU_xFF60q*zSYwO%&iY42Ved#;^oUT z#2aabFov2(BmRLxfoIplTIx=okvG>l{TLu#z-ZMq3gKn=G1oIL?}vG@B36CWCx z))waAh~6aXM{}=U4VGSZlsM(8z=|bK@H3SkuuSCa#%O70e<(k>6Tau3FhMT|>HttpKBj3S1xno45Zk{q4{G$TT&D2Hj(^^!bi{zZ?qZ?mq8mV#sKi%l!D zP|P%tGschO-jw>M1J481cDeK%4=YAC)I7%PL@*A>8wK9rqBHBwtYinvn|6XX_u&Zwx|n$;(4x3DZv9`~Ir1@yv3vUtLVB`IRd zoL4;SyAHj7kD2Soe|;mC`49Ru&8lQ;uadfF_hR9nI8?W&0d|{pZ1&g_se2nl37}RT zfJXiu)+#eLb&yywEeaEn)l0(JHdZ3sP%S?txQ&;cmH$PFYPGz&S>7+%JijyKf{^az z+zpHpU6k4>o&)+1C&byPwu^tyuq;&obDy@yp@}o-n@Uo2O$fW68Nlosj2I{>MdpK1B)cE0}4r$t4W(Un1l zqt!-|6GC;+3d*hEkS8s9R&>yp;>pcrTSCO1j^oWio0z!vX_cyYSHey9eo7-F^62@7 zdx=WYD?&5 zBScADWL}teEAs3n_uYR+)}UY$-osgAnnDELgi*e=B7j#rH!j49JH9jS#bG=uI&eosur2;; zmPYP+`S>{1eh-9R<(7oSMs~RkAw`M?OAMXA_5h zZB5td$)nRLa8&-50B<6m{}$MI@g%~V+A+#93PL8ATgM@zX>Q@njE zN!TRBtGlwtw|*@cm_Vlv3_l9<84xCx;#k z+~44)Xi@&+eCj?f%l3y?f7*cS+G&R zVJ>02r?N*Z@)c4pg~-n#C&T)WZ!w<}N599-O%Iiy0!PHZ{JyGU!v|^3U@qtcx%dYc^}({^(q2A>D;E#{3%`AYHP_Q; zMU7UJ#_D4`fB*+vo`O3`#sGPlw7G_W^G|QMT-zO%ie#glQ~jQl9b!FM2gljP*!^fY z)>buL#8uiEc5FWaVWoTZnK4o)FQl==Sg1BpC>s^wx|EpR6 z8h8qJqs_scxYjmK0u`(6eiYEfk@~|5M!3Sy>>dral7?V~oo;DB#&(8cj=gD--~--T z?^bvDtN?VGgaf|4fgUK27=J6KALo?QX+u6~c7WWZ4GJq?Bigm}|2W=++q*f5z4(hR zGZ5yjB90Awf^@igI-#dWGtdfFE2`yRp7}%bJE7MW-+LU)Qxa}sOI9gk^c*xy#P#=$ z1dYNR6c-O1|4b}0i7nmSS~4?)2?-wMa#K81uYQzqQspxuZd0d*qS7G><@U17Dgfzi z>vXcj_F+B8PZSM7)=>Lcj)$Y)^O|7A&QsntIL4Lh>~VoaSa8qKxWuE$lzvN?dFzmO z{_+8E1>Z*3~6}FW)$Ntw+DDb(t^W z^LL<$O9kt?py-uE`+v)NzW~TS6DmYl21lG*A3iu5rFy@Fb)8fh1ZDl11kstKtXa{WBs8|l zc~T^&eLPO3y-hk-HP9fM;he>4)R9X|J_F&{_|%d?CV>4t714-`R>W`}88)_gfc{|= zRYJe}OJhoD@xcu3MY$YkH$M`9**AX#`KeWmbYzpbq`vkMdJ$n!uuE&Bu{>jHV)|*3 z2jK#Haj?*_yhMjEZH@F(1wcq5eFuNwAle@4tR9j!E)InK?!|>iMCn4`OUe#E!H~K% z$O<=>@P+FN2kCpg@gd*z$jv_644*kkIa4i=k#iE-Xyw&g(o$IDTd7^H&?}n>qQcJc zLplqmbr{Ll1Kp>fXZjXQ#ZY0t-Z+h<{FR6ioPkJ4F6m&^i=$!n^dLn!Ry2C!(#5>I zs6mGAU9b_8)>zJQ@dGfzfUJ)6tKT{EZVRO2*HK`0%)#>LM5B|s)-~z%S@MzVFf6HDhZdB0sC&|ZKqm6p5p{KL5TGw`aSjSw#3TkS};#a+D zBp%iT#>@+r>t=AZ&Fb3h;P@+{q%XjKEz}rr(+)3_71ouNl|?2&9F|JF(5{6z$a)US z0|<(sYp)AfIrbNHSAZ#=)(oVue&%hG!EOJmr-f*MfBbAT=jzG zPk!K=Amq_X1oBkC?Gk!ldN+N)aw(4nyr@A>*0@LsVnlXSxv&$sT#&FAV4IWfe5hNl zNS$?H!!uSUWIgkwYTj-8#>T{{qLMBzTB8qTbJakvA(oU-zH(myjCgE(k6{R`WdOV=x+ z_M2#fh|;e!&j1Gl2r~ubWGe#Sl;F@2AVyaLDpD-a=eVvz*9gaf87dqCB&&EnCkRSA zDDMdjSVYD3$S3pBNAq~ZMkcg{TX;0x&=d_R*w`XjfUu@MRon!ztmlAei-Rg6i=rF3 zzG89lE&RNe|AQdigInZlTp|5Q(zTg6SYCCCd~qS3GYYS0dOL6&^lqq*dlxIQu)w?v z{vxRagdX!u$!pqYFRUBpr)bQbtd?|GME?2{_i-~!P*Dr-S3iYJCh{0YaX}1Mq+$ZP z40woaVD);3OGfAZ%3!E4Qm;L>PvbVMOC~fu7$l1FJ?i4iF5)E`O62Yi+kgaG7s_`A zls?Qm9+^p8%v(vDoup(KAvI5ti~NkFIs|3pa5d@}qfl#a&HR~#J;-2L>gKX*eH)>+9-@-x-U$yH#?MYmLLhj`m?9kOir1$6a(Vh9U2+@Azlb*!gtCMcnK8T(X5VfJQak&H>cIb&w}L@ zdyzVAiy*|5rohyJ=WU&8E5ArI=rVGzE)W$}E{^f0%!Cz6$na|!Sr5+VK_QSMC14&_R7%@z7s*xR z){go$@l(Pyzg1-deq1B_A)3fiz@kN{&nNUI@h+QjKI2%ms;@JtY7!7MBvtXU?cYG2iQw^rEVVZ35SOfqqEs(GVxtaoE8EEFuCp+oXm$+%Sj!PVys<3p zC6Yk#8yi4DSh#x~bZeA5|AKDcdJd1bF@Sg}p|P$b9(x_t2R2Kedas#^CJMNp|E?2G zUm;Lf+|CgW;&;`$*`N|f=$+d+;0!Jkz^-OsW+h9h?2Zz7U&b;nTc`j#fI{WkNn&+rCZOQBURnGZsH z?Z$J)k2}(=$`En<&T#vnP43u9EIX(bLzEMrwGU}S1z>Q&Qo#;m`$D~TMo!MEK+;eC zfjHNa`g0$&q-D94(PYwFeX&m4hF%SB1^5FWSW38BtePI>3XrE^2oN0F0VqC&(KQrs zT($G8zZG~Uj_Mnw*Rci{0rd^|ByDJbkm3Ka)&Qvoh-G!8DTo3)hb3}~mCbkv+*MNj zXvG_-q!>Up5JViUorwq1M%M%pp(|u-B)x_ImBFMr_p^mio|*-oqbdwej+B71(zOU> z@F5mH0f_w>@&>}e(mUajZ!R)ru@WJ!hka-^7swp3pbtxS@aTiUUgV)dZ!9F-I4gvd zPOoJ5(YMCDK9tg(yBCIRb!7ZWsx+zJ17eeH8ZC?U7;kY-il9s(j*f%@(^mwmx}xY! zn^^P&#iGwUAEiZpQgGkW1wbBcJ0Mw*D`smoGK6WyUAYUiTg-r$=Jg3;a=Ti1CbEK; z$g&syh^9NX(LgaKh>XsooS>K@12^1jZMCts+uu0?+_pMXE&%#z$}K0bcv|;`{Z7-s zk52n_RoRzPMTI_@g`wfDYpyXHy!lXzTZOP`lfa|y5hZDeC?PJ>i>=>WPj3-^hTkia z@FXb`cQ)!rDr&6(RU^bMwExUXnf87?{oSr+)|A{*_6vqiC&-Z~-{k(72f(Q_xWuTo z0ybWSdyM{babi5l5NJ?hFaKN>G;+kA!Q(}U6328Ap~ysmL-OI=Ej5ljb7!Q<;(DzPc;y@9Mnx+RCK8;s#`6M>*M0O;ws7o`{FKh&|mZ{gyuQ zv(^7IpCO3WAK=*;9ut1UWo80D`zps}9NWkh#;?$+eo7jNJrIEP)+Mm(51mQ5aKJx# z2vX4x#a)V@W^ODj$*8}9V)!<1q7*-&<-FWVYKZ-O?$tY?LWyP2MF1U7XzDb`&E6+z zYL`B}@TPL^}oyv9~v8i4cicp6l zHvN744wfx1IZ)KxV#uuuOGa2ku@{*!noUIF%c4TP7sn=aSO}bH$e`6TTfx>gm_r_t-v71!NIPkdAXV{A#h^NRhoDE@NEr9s-#PQS12 z+qLiZUsX0o*mLpqew1=jGL5Pv`G(h{dD+%+{q3Tnsv*Wc*4+0O` zt&Z^%%5UzO-9V0iaCEc|773lap(!`~49h>mZQ`U)Vy}kvAj$<()lT zs~ire9wMF`Yg>KkOh#pZjG=Jv-9O!b6Ns?Cu5{9K3<1CIqDOM5P{gsYU_tjs+e(S) z$*9KdFG@iLCOWb%s6_$;Rd|zN@PN%Gz1!cI6oP61X+3ly_z$PBBiS+7$8yvYZ*yB~1Y5t^922adIEsLQQk`*6D@7 zPFdUSxM6}vd@uUOaL-PAhd~oezo1CYcS}=~P;iXW94y3vIpf59SD>EhBTek+vH-exC3$oKNkou~&xNGyeT98qQSv-}g9A-&^ zXdBN%6ec0gbiQzAa7_h^JVS0h^^7%_v)ZhbQE{M5262C#8%9V^|%XNJhtz)X(^a4_uJ z_3boPLJ}@qqyltbI_dx0g-F!-eAd*;PMY2tNkH~bSBl=B-lh$ z1SF)(AHLNCmK8Z^byI*WC>O^Nawb%?aYi12RY~~N{R=&i1qc^T$4`oO^=>HkmfB** zY?_*z2o3TF8GjJggfXu6uuq8j&AVjRF~o%Dg6s9}uKP}ZeV9DB*TBw>4@|}k=W$(F zu?d<^s5Y!RdI58k|3<0*-{mO9cD9|INc*+^DO|HOeQFOYquLfg+Uey1q~{!c)ErFX zSwpLDB~FT(os)jFrxqIy;1kE{)^S+h=^nyVM5R*^LKDrPg!&R>ib+dg65(G_0I`ZZ9Dd{a zb9gxcZXI5T^K}_Q>)n}8y519(j`~3LxIUe}vpYOTzCHG%ug#&%A@<;FoD?XuWM4==o#v|F197k}-aXIN zi-nYV7nJnYxuw3Hc0kO*p8cDK841N`ZJpN-23#zDqItVN^pPKdRwfNdLV$%O3OWHg zPwQX*JU!?C3dAuGX)?dn95Kc~BjkE6Zy-TWL(9bISZB!BJ?;KzH~1-Aqa;NT1TMNO zg^+YpLMV#h74C5RLBTy#Q*Im_-DeG8X$f|~&CVa}#kP>2C@_*k^Uh2`)&R+5SmJ~w zHhi*2%59Ekd(u2vod&N%Mb-z}8Z7*~Azri zezFrL>Lqvm-8(}WUoHAxY2zgP30o!=RYh&=FY)z6b;mk=TyPZQBtT&%XU8&l;62qq zX1yv%vML8Q(853CYJZwvY6Ubn*wvsU1w*8Q#Dl#AFbg>tB^gad$<27uv z&jL7`bud;5Vww!Ufk%LY+aL(2z)=|miBw)xo3fZP7(54mIu8h zSpAKkCOj!FObmIf^b;E;&l8BX7gV=vz?7$^=+#dj^_VnyahM6X)3d|C#Y&3#n;(TA zUYyUvOR3fcR+g*1f4A-)Wlv*(6kaZD`=Il-#?<9BWx#IP@u=%>M&$o@hy-_j>$=S; z^%I&Qs-jCj{sdeoi5XsU^PbSRTU850m*=o@4%Sr)U%^u4KKr71#wq^c1iQ>4 zb%I)!e3NAZbHh#|5bes38~Uvn7Tn8--||wwiM|g;!P)LdpE>t8A8+H!@vdz$fNf2g zj8ylfD2+j7HfaC_@q14sJ`R)lU3}b+056jP)NYKnd!FMPOXyVG7>Bfe*7 z@*5^@S8Wg>8B=+Pxr@2;;lha%h>*p;!lY;=@L&BD`meg%iggz2X1=nlg+q}?;GPO3 z9~+PUETnq75VSaED@Hs`u64!e>E!P{g^D|!kWtaW_cqNesFoWBYSzSUz+=+EH>x_> z3%|rL_RD{4Kdag=DjGP`WDV48yWH5(9Te}b=}dZF>i{D zn)-|B)k$&-zcWZ(!eaZhv+l+7cg|l_`b=*QTf`39Q1u-*mEtZl&4hgj61$WAt-l&m zF4LW{tGvI=g`SheWf4DoLHNL*w(@CnVv}Z`xiswa4cY0BVusRsIGseI%MZ||1f&+` zE~C?P?=0V%47Vq8Ukd(@^CjN(U^SjJqoZ!IV_5>!3Zc>y673yu`I@oo!j}$C_r}!QAcn3I&HA86WA=@5H{amC6pC^~%i%q%Yk_rIHkqDYoz4AUPDzQ9+n= zB|_k2zghJ6_!Ynv>r*RmD{>+bq)OpsXej=A8XQ55W93f!184PY7ilKeH9@jyGbV)l z7D<@%wf=}i2D3lME*Jx)0Akj$DW4B|mDk$s3-c|CR1zn&{B zMc47$mEn?}NkvKljUGM?O_8-g#*#+ea(OG59=9vMLc&(+mrLktT%zF%d~&q_q%MX4 zRE_I z2B{x*|7cyiMp)AJEdj%NRbG5CDH@B7uQ#`O4=wEVx8x7&CgT zHH-@qAHIm#1-eqGQR->mCc5m%uu2k~cM+nO*J5Cj9%Eps_|C9oJ#{=N&9+#iOSBEy z6GY~+%bHGJ+Lfg*HhKu4e_Ebwvo)si`_x<66Q9|#x!(}hp*!|*0_xQ+?X~TwLL#po z-3WJ$YA&)VnV{37M*8CLX^?C>5!dH{hd1}v0kBmTh@AiX$Dau-t7)GvG4y$^HO)#} zNn6HsS!qd9_ll=Gc@)2H*KVF(3geob>YI1g7p~?d2&Z~Y*yw!P)#P@Sy?>iB8sp_4 zZ5uZKNhQd5=+BogK>@5daHavD9>sDuo=A)>r<6y^Nq&7>fO@t4aBxs8SJM9CCw^+X z!3-8>w6@VgCVgn{+tvG|s5Nt={A!HKYaC7su)V!5y@QJ*mradi5jdX_z$Oum$Ptdgc`gMSD zUa(xOrBPU>J`WK7r;(Uq@G_IrU&r%3on-Pu+r~Y z45r*1(aW9@>dhy8;q0(#fSqN{TYHEb1g-3IO%zUwpKIP#<08psIn4I3^LV>V{GFJj zRE4OO>X?;QQbiF5ZjxVj$p-ipt?`AIV|H&kDa&DWu;@TM19s0$nkvo@yxw^gqSs!l z{yC&|Ra&o4RXZYAtHn%wxZA83BUn3k5ldAQE zgbP!cl_hu=50ko`PKsNoLHP?Jro}}RH6qGNlXNrzaA4E~M@hN}N@}n-W5R{X`Q8Oq z@&uNd&w;iONb?;bJvuXXYMOqQCYZqYy{yb|o~5h}UTWIi2&zCiudXs zv3K@#;;xLh4F+{Y*qXZc*Ik9UH4YWG?p?78y)$;3c0XU~Jx)2fi!~tm<@U-AsF;ZI+$9d287xCS^IY^B5-i;%MjtUt}=#mgmvJpzT3zHB&C4dcmo0BG(xKrM)Aw(X;T+ zV6FpCmE!{R9sUBM7Jg(-hjX|~Jgfo$h16Z+v+0-G;2a_pjk72)cNoHkFUkS#!D|%f zQ>ixEa<A44fBMR~#}1j(B}-lg;NWctCfs2zhxv$g&e*(cGa9Bxn3xnvW`|dWGwr!9mCTN| z|C6s$tmTuf+DJ`oU594^M;9BtQ^QqUTe#XfkULGDRb`v_g1Hn^1KAio4Iw#GU*VlF z$*-jotE64Iuos3tNstq84#sMp>N%LQYJ2sxxmk9*@GTc-b>U11*q34lZvOx{80{c5eoG(2nR%*EeX zw(LyVIQb5X6K*jjdfcp?n^P`BrUULo4wCrymRc)xWN)Z5H`rnMNSiX9}1@_ zqMQXBxIdFSUGeJjzTj+((y|!?;B~I7ck-+H-ZJM#88!YZtR3D2VXl1&UDInCx5=~= z<^JE>c#zmmK-%7dOmcga)& zNQIFoFTVBkzfw{BJaPE^NqN;Ex?{g3%Za+S(Bt^!cB|mAh^uwA%RDJv9$Er;bo3}3 zxWP|6gQ)_K_oL}R)G@`xpI)DdBQqaG46G1uPxv=~nw*)AMPfF$oU|Kg3)VM2Mx%Fd zAB#)~UO66$qVWpbFCj4C$sxXJii}oKUJe}L5TslgPWe$B8~ueW*7=+CQ%DTv4yKxD z7?2hyMLPB_6R3b4+^}`)-+F!;#0wk3#|0NMBPFZU6K%sadZ5i9o|M(e@}(zS zyJA|jy%CB~BywACrV?5U?~>FDyczL7@Ok7;q|CWqF}8E*;!)m*hN(75Z;=r%TvjBn zeh9_rn$>Sq?v3$#v=n6%P~aK!w}eq9&UxV#OZvo@Sp``L5UX~|A>+k#wvPBy`24JU z>1j4em%RDL#_roj?|m0>OBIt@5au<_l*7=XT0jblS#c+yDZRN^M3-tFJK)+6tF>GB&-f5S!IWIXlP>`p z;Wcq&1ON`AbPifO^MOp6(y?R&mx$J%gnVR&2S&cTVo*7HWOzFxo_lkKp^mVi4RFHi zNInA6^z`!#9B&U=$>6St+F3#AqOk&HjWc)n&1c9pay94}_GX-;w_6iJAGCR2Xc&GK zZdwQK+ljyRF_L@Co^hN+-1pbVOBTwEXN0y&Z!wo=-qaXzjtXr}?3o(H8|tLtG!c11 z!08CX@M?-RO=0s}vo(LtU1_y+n(zk)l^F|wQ-L?2CgRz_eg%Q_@8(OOWLsw8#VSFc zs$<*&+giQ))l?K+dZLCr%kDhBW1+S%2TPwm0rJ>3kamHdV>0^G3h_qSLMp9-soK3< zuPcp8nfF9OkaF118p{-&5`Nb?d1 z_NNh$>0)4b($fdwT_X&A9P+%gU(Ljpb%|eN+tN@v{SYm9c?T4!$vH6v54nZe zgxVgi44C%P9y=bc0@Vi9;HYLCY|oimjKe(`J5Zjr_>|zUvb}&0wA9sIEnsTwv})y$ z^Eo4?;ioV%DOkr~qY@Ili{YH6GE=9^2pee%Q-~Fbd`6w{$v#zzIR!PXr_Q3ko(^l& zx}oELvH;$xVAh1`mmtgnr3M147#ViUsiN=-V48;?*~&8hpEWkF9CDnj<)qb8L= zk9@8K$u#{+%dh>Wiqo>^R=Cp+Da773A?r$I*VG-hS`lnYsjXqEQYif*0bX&Gt@XzC zh%wt3B*iZ@g}B4i5GdhHIT~5n$FCmb-dxYsO}AO}JjeQln9cFHt&YLyxk%Vn>fc{U zWhqeelDK{b;_n|sbj`TIAK{e6;vAflDVMshtCI!A%ZR;R{gQ2PY(o)KR%NiIsCW&3 znjFi{t9x48__}GPu)=k^)b<{s!l|Yq8hW0ftE43)8kN{H2|(mH==on)A`wZiW_mi@ z<88rMg5rjC!J>I;!And7pHY!O*5e$jFEC90Cg&~r??xw(hzR5Ld&v&43!~@=?c?%7 zB9c!vPY6@;xhJ}7nN8d~e)Q!rd#8-i`iJ|zw>mJ?fY?b}j{7qdi?9z`-q>dvCtMxB zE*4ic0f%&t!d^wv@^MfyiZ#XKnTDi6{sxdF;^pZ1PU{nTrmqLI(fS?tJlXZd(Qtl* z(6=6pmh*E6A>b1gI6oQLJ1hHCSJtgM?Kf?V+YD1*Gu%){{u)BR^Mm30;}6Zdf1YhA zY~;MXjdX^+POL^OjRk#&tAX5M!RN^@^qe$>6n?0`^B}RboMBRqKa=T?!icQ6E{sZ% zN_YkujO`n%Cy0$MQRAUCqm~89e!KE8Kd3+Ift#NCAz6UBWYM5C^#(-fO)%vK9Mel7 z`vx~RA~)(#9T$rXJ0avFPI^+$uWI99@*&A<$0LIpnm1ccr zgM?n~KeOIh4PWUEh*B!tK)c&Uo#r)G7CQq= zNQQhf#S5Vx0dgP+f@;M$?ZMgs8~`u>qNJad<>c!J&o4`OG6#(my(!4v(ZJD1?J?0H zH1wrBvLbd)nWskCi-c>8j((Z{K$rwU*JWF@ z=L)`W-E;x0ZN%TyBupYcVHxvkP6lJ6w!CaN9P&l3MS1!ujcR7#qPUJ5q-d$DRVoVd z&6}=bC`C6X+8j-Mf5{F^0vMbmbpR9r#gsB-_2>+YwA-mOzay)#zQG<1iR50}fuSjT zcJ#I<0CI63cTRM@qxU_4%JkfTFv9$Mtb5OGojL4j$FrjSTX}(gGyYElxMRUjX`Gf? zzLPyTIq5Il*T1Yp>yZxaWnEui?L0<-5;U(jqRt|Y~upb*ww8{I#>sogD zIKsP;y4*3Zjx+*tN*dbD`vG!5`1%2$i06O%!kCXO>wAx2wdaf1hNFV~&N7HaViu<^ z8x$MT{Wk$q0NYJJ%g5Imzjl{y`;O;ZCZJtE|BU$eOCYPot`hXIaOUyFu`ydnOKm{p zKxr&X0{CaniJ)LUacC{a?cCxEzguHfEgt*etCkQy*s%qzjfVOhIk4yWkktLkc8pGl zk`y6XshPByK3e}XjGqbaM%V!N5=Xv$rR)A;sNm>prPe+siwnRC5@BjVZaNUQ?Q8tJM&%EzUej`J?8nvOE?P?7 zzlW9gDxW~4ty8GC85tlFitD%S(Fg#_OvBK9Fql-c8=PzS9o)`o0jc6}FmZe;FTk&9 zrTf`WKw3~&#KhjR{mgQx#oD;C=fM%SNI#m2?c27yrW z{Sa619~1{>{n7k#kGMg+vnsNE@}2fr2o~^%gG)9F7tcnm*XRm*0WgYEfL|2acr{u_b zc>J?{KJPt8^(DeSEyjK3?Y>n17txUA|X62f;vux z_Zy!u3&OFP@Nnm*=E3TCb-hu;YjMYID#s~S_L?;VPd)ADhYCNLy7u7?t^F-0ScotP3VRz z#jEblcGx!cZd=QIeu4`L4)=%Sp*KW-LqgKzH^h06ELKdZ3@e#sw>Z334dUcyqxR>A z0J-vZuQ7w^ei|ocpw4nNGkoCjy)yq~N$7X{lCU8(WCZ!KlTUZ?qn?6OW;T1J^T&ol zXu+u1ZWD}QMWa*T{pLHpOcOr;dKZMbHT6j*CxTVP=1*3?3?LMwc{z&D@n45op@(4a z5t*;(+q6Lo#)n*06D)ys4+VPMrwk3yab{(<(ahGf%oaY0a1#Pj1Qqo6BF4$ag<78V zzon8F>ke3FUq75jEE0ZSe0(+&)5upa{b1+ysQH~ekyg#SoLqo^5#&hlJ>d#Vxrx2~5&x`EZhG zg1|kEVspDwp&^MFcLe4n@f=t`;dmI_F~Lxn&f9+8VZ`IpcaO~Si+2stS5?q-WU^#u z?K+pF79!f(_?dkR@DPN!Ix+230AW(*n3G$#U@nX-|EsahF0{a2blkkqy$Q*~HQTN) zSt6P8_DPp$z;55%arh80JNQPw&8eK6@+GG`d)vy^)Yj^AowT{X**9JaWnYI2cC^2& z)-Jx=nEqesVJgwL0}*shW0*^={3_?e=W-`wFF&V!X;l2*G_vMnkFi+}M?P?;YXh^_ zVj)ZX1E6aPNvfZxsp}Ve`4aj3Tmwz{owky$4G z$S-M{cV})8ErQ{5gh(%bn?|uULmAj3mxd{7k|&0*EMt-7F0y@PRr=vV_qX;e{4%j= zdh1ImxnOdYP{A!r9Z5QTa;}#hFT`z}WGSiryl251lVL7r*Y~QU&`dCcD^%=lWZd^? zy;x(seyyZdNonK|xKkr=7%i=L^E%O+8~qA>hZBnp-wm1h&2bL)qiMcjid&{?cl&q! zeF&-oy)(R7J8u}r`eBU|pv`C#2+}LYHtWg2sn6`#Tf|`^M4vkUP#^okE#c7ustZ~M z8m9IC9QY_eUFWy+BjXl_)mnixpOHTAh zQGu%m3ccSw{l5ljl2L6iL{DHRilJ2G0!tO{k!uO6%ziH00it2TFJ19BBiU}Y!aApe z2a|i43N(VoFCs5NB>^M#f7@aDoOq20p)%ferjouZOFzN$%V}y?N^Gdn+U? z@)m%KznRr{P96rd!|n;`!*Tur^oqPj0itU-jsb+@v(V?<)#7DMkel~|RRnEJu{WDd z$gNxeR7kY{%5^7)$J85bgyxVibta#I+r-FWgso6JuP43X zquWL%SnRhFw|}_}=gMhX_!H;R+z3ke+?P z>$>b=k5C?803Bvz8-K2fkNJ^B?*Oj{Of+l8C4QKdHmrZg>0+Sso^N1K>8*LVmv9QI zB>JnAB|M~8CyVNKPu@#(z715+nnLGxgfd+4M6>~U$yWJZ758k!lUo^9!+}DcXes1> z@S3TLfjujL^`vy8m3JeS@j*I%Vr?3ec@4Ka%Sl*sOi|AWx7vuiB_f-#)2Qm$W@jJS zAr=}OF&lNXc<`B=tw@ufy;2kkG8woUgoy5TT|L?}4Jl?4wMduS)lZvYOM52)Y63@D~haH$?8ke zZ?r)|;}WA3R>KYug2kuu0b&3s^-aL32Y2M~Z9t zY|L(&rHBBegqZPbU!THt^0VvEJQp5(k-KAJuyMU&uG7zjqSN~Fp8klf5m z0+*F)!pLqdWNYA!LD`+|usuq3%`?yruGCPBvl_bzBsexVw3!~HnjNZn)01k3TA6vn zJ{#U1c69u6J%nq+ToR}`(%50?H{N<>p*(<$eORfvuNUdTVQo2YZbs?gYQ| z;GD+}zDDukdy|TGbI~MrwFu}7jP>OP9-mUii8IvmaU>m2e83qN7Ozeo;!0Ei8^k6q zCyv}fAAuEd1)F9f{f|4~6*|bQQzQdENFHxQGa)=F+7xOzA+d;*#|+LY>F0-@?~>vq zg<0wg)x1lizSf!joEucd=P_Y$#{!M?)D1SGtGL@q-LLr6Davg$np2#~elv8ootg9x zL@X7DbKOR@tUsxo%TF~xOvLXi&|OU;$B_*n%ZdWDZ(>ddpdG6+#n;kmhRsRmoRjx2 z_2Gx%``{n-;M;^IKlKge&-AFlUVYE8u0NQUn>p953HfxMZo6W9cZGIyDxm#KY0KnB zAu$r8(8)US}-j4T|A?FzB|q<(5~Zw0T3(=G!yDR--rlkT^7H* zHmy>1CO^4?Vn|%?(CjJ^-fQR0i69m7Zn-^{`W|n5Y5A2GhYZ9MTHBkc;>*|yXg+%& z1{|DW+*<&xYNb%AmYqGaI0A|ARk$v>5)+w+v)W{Kk<*^%yTL)Ycr-GeXYZczk$L1K z+stl-qt~CXNrWFkaEerlG3{de{XpCTLBwvt-;(wOm$YQV$grh<3(V58?9r9>S%>%L z{hSvoe&Hv!3w_%YE8{p$?~N*xm)(;5VR{&$U;1%GDn^Q-Nq>*q7<=@l+!6@@_yYoV>CP8UGZ&!gn7`x^Q{IEpOD`G(DWgYB+f!+u1Ep5-KVK zd+1UqcuyfGGWJmRMq^Y#>(-EVhNoDbJ5ob+&=T4FKYzk_)%SkVVP zgeioLhu+;>^n!$NR}TVvjW7C85ATP;Qz70hu)(ZXBo3mRB{YYbC2du{pb z7`YcH@P&yI(@qAV74fy<_YvK`@B)8!|M`qR^Z+8^%=SC|nF1#y8|N*ggvF4sVJ!Cf zu;Y{F#iw`3UMNcV93c$q#9AuF`wiwyge9+f8d%j^ANWqC0KAKAUOQY??Vq83~928e;jIY10xzN_04ovW5O`?cWg zLgw8nKh-aq=QKTrR2)d!MI2T{AmDD3g$`NDrlUBY78j2CHx#UE^wss_vw(L^?(1vX*7tK#qUgo zT*j5X?FAq=CejG8Jt!&b>2-weJQamtp!BZTOTIb@>sB4>h%!o>V<`HujS#QA$&yy) zdO5|r{mvJ%o*YdobUd;goZ{tY9q1S5rl};)#T?j z?;F~%Rk&HNPlO35G6TonXoLl0SV1^NjDq5+=;E!obNd4h1rnZs-Xvl#87*;6o`qI& zsY9kbgyR4nw~%?q7QVDd!A_?~@Qy2DNoutx+X-)hW4WiCAe8JO7%QZ0g2HwBlL2i` z@=;GO2LF!PGC|yXt=3y*x80-~m`R>9!AG&t`T`+rF;>nY8q)hxDb5fEQEyO=$(a;Zx_He%JDgA!}tYQ7=f#S%GJL0I}~1&E6V z|KHx3#`a!YAFGKkP%uyBY|`)e>xxQ*hM@0rAiyBtbU<3$`@-%5@K5p(w+Q+}ihujV zy+T^Zc5<$4`5Q0tLBbf;%=jQw(ZD@+T@iKyi*81QO-)siiEj$*Uje9}5@}u8+#MQ9 z;yrn$c5krSkx!}qYoSW8;O7ez8K=qy9-ylwy1!r0nOvR1AWrFSk+axd(cUFZL!lsg# z#dZjOqpo2|GH>m^t-07dnzgC71$96U{z)y!Zc6mm_m3w5hj))i6M}qEPQ1PJ?;*vy z=z!__WB^da{-aYB{6my+9kOgEoX`gpH;8zcl;D;AKevK>p8v1#6lxOU9Aryz7q|8K ztNr~S^nI-J{~-k`n6eopz8kZtyP;d$w3rp%rBQSE>w_Cp-@zZ_shIaW_T1iz{da< zR)}~4X(*`+@8rv35EY=5rV}-T!aty);QLiwbx+m z{f6+V3p{Go5%}LR_Qh-uI3l+}EF$AJy(H z?d6bU(YoUTbfM?>0a7Hjgx*QC%aL)s$-uSeYt`rdLhNiu-pzlyzfcGyp8i%=(My0+EaM$pEmyK=I0VM~US_TGvFSLHJZIbfvg!i>}hbB--j>#x?S z-+o9MSBRHIqsZ`Xu@Tae>D^y5RjYc5LE9qiA`U*KdE5l1Hquv^Z_-8p8=T*HRgeZH z;iw-kc!9#t1%?2rwJoKCM*SyMJE{8MmTY|%?oY4Zo{zVIqF?`65NS#~&*J#4Q#S$y zgo`ReN}eKCU#Z0aBoY$D>Y+6tI0&9-Jkl=??k~iDg+54v{A!f8^r2k6hVkdfKaD`F zO}+eCJttZ=Z9FodP=v{^GTQ;(?QwmfJ&+xc)HkYID2+g}R~#bvjiMGltWm>cozWLV z+X28I47-^ATfh|chl_HMB#Zxq-uO!-g8hH80LO!qugJ%Pn_PA8_%{pxuggFKFDz)d z#QG#CvOU1xnAk;!as$f2tcvODiK3el@Nc1v6{F3mE#+jGCGn-88$@We@A!#Sa~r7e zLJlEZSYqdyfmg;bn*sFH<$UuhT`F4&hYEJB4eGy|keqP{XgNP?172eb#}Z&8F;PUQ z=q%4lMcvX7%HnJh;<;WTC|B99v6dLyM%vS&4&}6+@|-)1N4%dftC#bCCe9bc8>Eqw zywjbWLQMkfNx5LRR{25KBMn&s9`++wZC|a3=~D>0?PAg1q4ge{BBIn)CfBdqybW?j z3IyuI5`ZM21^q&ll*oMH)Hw?jd{|iWOX2WaSt8?>1-9o2rw$r)Ow$M~^k+zfaSLL| zC}m`Uk*Tln-xe*=y|86amex)W9G3}y7A4D*GlvRx@3)4thy+#uFa_a9Irv&*F$CEk zqFJ-fD2-S<`7+)`g-cTwtEi%!qwF6}+Cea_@+rl<$DJ*eta^0bc5HsG#-*6!Vi@c~6txCV&d10QYY&-zO?eFH4;Nf$_m9b=G zQpDZ6#l4f!Kf&f~H~M!pogJQ8mxIV5-&Udxp$Sjm=6rHmqxcxTq)QO$ABoqY!yoxWdyET{`V)*l9l^^QcaP$i)7(Fo2Q&pl z43LA@pDct{1W-az%W^`l&I2t@R&<3#%+kj5uq zW|pKsEh$&K|HC1*mcYXAqI)N?p)=SgX!vdM$zw1~oAa17p4WCS1WAndn|>?ykA^BZ zpT@vK9Y8B%4#uS!<{wBB7#P;nNVP{vjaL;@7{QG2Qq1E^LP-T2`3G5A05@+DPi=^ymY1Ku!+#E9>%y6)^?FluOE{0IOO;xzFV5Ac`a12=do=N%z-Jj#&$^`#ZN{|n=GS8;p#?EkJ$MaV-#>2v#T9nWVYv*v4FD!mLz_voMjc7`7yipS(> zh)q94dMT(nteH9h$k@5%qw0P$LGQmJVGUA_@gOg|SL$4b;d(fIM% z_8S=w>OR~$9aTBVazwVO!v@MMB-|0n4C@;+ENpk))clGU2p#Nvb461_)&>X2&p5zW z4_BBR4Ce$KIciS=(HrSXsQuTLU$rmQSqG67%eKOZSEIaM=&l|_T`R{v;hmAg3Ak2d zMP|lncvt-DyMK{{pV`NBUs``*6J#-bMrfHPk!>OqjqAYhOCmQwR2e<<$T0!P%IdWXQh%+MfbC8sNkaD9 z^{L?i`x#6=aovT3^TPYy($luvzn3C`Nr~>Wz5;J5_x>Esm8*4e9BZhI5!Z@~;jP0- zGc`)T+tB+LYTCg`z6(MQlZrh@tHjvoAz(f36s7=}%G@{DZ#fC;kk%v77}+`GcYZ7> zEP9*~jg2ysC^Bt<+fPFrpT*+H6&Jgv8N_8S{}T&f=`Xum=|zjhgFy`e2lafk3yN1` zBtyxU^|QuJFMC)}B*ZxI1QhIY`#Th`GjQR<;99e1-EFr(c{e?OyFCA)1Z)*r=dXN- zo5lHO(S+foyr%eEAh`u@GwT)Gq`(mX3#iRLkP_$gZJ|RjSr#x1SyNj$^Xx46hJ8`1 zIyEbJ2Q>zfEViKi~7#%Ac=&iZ-y4!r(69@!*^KG zKR$?;y`cEQTJG7h{`azv%c9yph8`C&0Z7BC!0_1coS_9leAgVjhb7MF`}B=6*=|vyv(2J_Q4z7ub{HJ*I3mJD zA&S1;Ms;S1roSaqirb{4qkT5X7WEAM1Dwt)_$|<5FvG0!EJN`JqFadKIM&OsGAsw! zJ-P*o2Zff_UH#!;9P0{sKkJKZzVN*<981*B&nfWW_iq~&8U!?EJ_trdM_sTW`rU+6 z?m}Z0E9q?cXZc=PU0LA4QwL{!IphZE>eG0&V=`F!q#D%QC6(QhK|?l7Hc-)xkE3Fe zYC2;xL|PJY$;=V+aY~Wa0r&h8P#6<|JaZd!Y6v<2bR9PG5_ekJkIey>LQQ4##*vVg z_z%S?s9Y_W7x6Bw*sM=n8#R0v6}&9N*#?k9idq-F zPSplcJW{Uu7OSEEs>~6LOUJA8Q*M^DIYV%wP?6j+H@IozMJ2yT)pVaIt<`CqBH0Sh z298<|mXIBhQ4+#m-(s`7iw2f$X^=I!h~k=2Vm_I06FJW9BM98``7c^zj!gQ42q_8R zDKj%x{tgy=9jX94lsVlsHXR3T7SY1J+%SCxM7LY#Z|yEDL}`YgXYCqeyNG z5A~%}1TKHGS2k1Va05wHNO-~`nV9H^+bqfaqhfzAOAJ;(#!MuKbw zxz+Fg;b)T_vz1S#4b4zMP2(yFOnjhu%6Fhf{B^2n0Mr#$oc|}}R0Bj-fw04rSezQw zd2G9mw*96|494w*Cs*M3vY8)OgD||1oqh6eg99O(qQV#BH=HL%gP#&JTKSL7k3Si~ zLLq$f=#~6BO8PZ-*`N%hnzM5=#(5ZK;vbC$QVXQ;74QmVxQGY#f4sF{T|5-2SpEZP zFUP=+1fd@C8(wUkN!0Q8hWg(Mw=^m0rD8}Zh#~sL_jI&G{|2NS3YP`$xBy$za)jJL zBg(>~0)Mjco52V}BQxjrj~|_NzW-`X2Vg~~wx@(AaDH2PBR(q@5sPK2QL42%k@-%1 zfY;|Cj6%m*8QD{qZqR|Q45_LL_vGN+-8E%Goq4UQ0{T>@SL+7VhGcOdpHv*`q|=Mo z)y0)@1t2|RHQ}Z5_FqKG47oWpbM!TnrceTb$3`;K4qK^ z5|OBh^z<+z?uJ8f+Rke5^exaSCy0Qgif{UteJ$&k_7OYOQ!Bx<>qgu|kQ9Ak-$qGC1EV;Z1C#%6PsH7!hH3#vHqVycY8 zx;uC%V)WbAI;w+@pW`ZJZ8@RF#h>Fu*gP+U!;ar$Ey^ zkt`UoN#o_XZd=)!7Q?;Jz!xPFW#Ou8F)$ixOm%`E7-!I3;G4qUp2W-Vid`TalV6wd z?u9tIyz4a}>T$wVkP5om}*ey3|ZHiy(*4i>movenIt zIfT&Yymdn8)i-hSA1-j^u(ck$7! zY{wdis;UK3bQCVP8*Dj$KGBjUCpJy0;rcfzduB$P>o?A{4#A>E03o6_ckWq3pCH|) zCxH_SMSWhK(D@M;h#-hrl&;goFGEaZaZj?rESSr9@xdNuP7=0BzgFLWfB_+GA9dWEK{7u_C z<|0_kT99y`K9Y}$7C_{LC-^q!71^r;>+c5{U!COn6FaKlZGNM&AcmzHA0*?V7P=a_ znj1w*f`=eh_{5k>3MBJ49y~de-{Kct*j0O9Dx;rNk{8yEv;}WY?W}6+n^xeWy|Je! zy%#d|7vyyQvZTnG7qP1~_43iPyVb(5UO=HTQ&dS?*TC9;5cVDf5ieHrh7%LWS*O>I zw0#AFRoV8hb4fl=hx;QIR&zGwZBF@0re|>k_@RV3o^Tbv-dcBY+X)_cop`PNsZ_^A zjw2|hcV*~V(rB?MrL(OM1Gai4wNQKHEHiLQR_;1XXx zn_cGMtKzxjw206+m4-@VgjszP>-xbwVN2kpQ;C}Ob{9$ED&X(2Xk-PWp)sw73-=GR zGlpxGEshd7DCT5jr0}F_`AUM0+e#bs0yGFTzeYEHWcawf$PfJQ4$R|8^TkRX>Vk>A zHg~)YRS-4`Hn}Q=yT!{cJMe8Qk;vW!ovNja%+L-59imQlz-;Jvr7e*CH*7#v=Mz5^ z{KLFBG6fS9&-@talyp%Tp$UQF9j~v9*;UuIybN(ht)B}DeZEObO}`b2EBi+mS&T<5 zr26AbFEGbV`n}#5Hw;bjN4$J>vc$Bko_R$dpRp2zIRmqX4e-SGo>kAMGyPcxCmU?9 zgwamjW8D{nz995)L5$eXj`9G2<^JrMS&2V0;-f6&u-{KbWGS8{2sM>O9(qZwOi_x$ zo=3LmPv-2h+{PFl9*}iLo5EP zeW{PG=sRBV9FE@DHi!2gan03k3DrPMAHfxzmYO!AD zr}Wl?Lpqx&?+KBos{>0$Z`Ia~8usB|l?_HnGei^QZpdl%>fSaJGz?`4XTIB;pEZXB3&92*fMRew6aO(|Wb}u*Jju8*k_KvO94ep7 zgj1z4goKt~+LN<(aWn$B)V#5u84?^Jds5nuNTx~B(8!R?`f&df1wm#C3#VtD6|_v& zj2Ec5=;DV)Be-O(JfKP$I5;hVZDlW%n=)a|VoNf6S!6EojkpQfE~<#$4dMFsvaP>% z`jig0QPe)MaY zKv{EQMw<&UMoFGn7FQQkOlSXNiDc;h$6)z!a81;be?Nq!7>Q1n5_H6mIf{NFjS z4iP=W5`3wBbE?vXWQ?D1`*Ds)z{&rn)G@w~CTnV=}pB|Ptm5xH&1W7a#=+nIU-seX@sr*}^1Ma)FO z6HAQ6VT`6kiXN=91o4@NOk8XH`}sb@&>!i_ah0Nxm7<#sYK)wB*O-v2$1?oyIg-B< zaK3-47UIrPHhe*`yr7gM=Rn3g2G)7|(gc#N4dxwT5+bu;SOHVf&0D8im&%n78e@*6 zllA||l5K&rh!e&PFev5_V(Lk7vN6e%%PL|P;_dkkHk4zfcO$z;DnL3!@7l-W4-{e? zT}#61{Ik0vc5O&i78wVk`a>45jg0>=cHd2BYi(v)vCksy4qb;=1z8zGCf|5H+_1aP z>@(fQ!ey!+3VEp;iHqR=RH8yO7&V>LO|8%7n=YQDF9hDZSimqb2HK}0f5AZn58Mjk zR-xhc$}fP=V5DYzIS-5QK)hy2Gw(UW2!CgA|Go=Bo8w`Hh#>z@+j+G?FEgz}_WI8z^ZxA>1oe1mDp? z=V0hON&)y$B`N~*#hVp<@KbQ_Gb(|BP|)d@TfWdewyLi?4k7BE+)(NZPX!=fybJSG z^nuFRN`B2j*XI&Zn+QY$yVVXZ13^6G=9W6v*TV(70qh?Qul8m`*1`7t?(VKXVhoH- zjQ}&&2dAiAD-gvXQe#jEc-*Vo1*kQa#S2n3nh4qlf!pN2-Td-2ZfmYFBz+6*L-1jC ze?eGi(mV4g0&trnj;eX|NF@hOc}}DzygXjR*Zw~DFGzurcAz{|1k{$B@^>zrC@b9Z zO}MVY-dDPQur%}P zylO^C3VWuLYnk)cj0GB3ZT|_*s;|z@@VgZYw&rl#2zGH-f2186mN$O9XUek*&8Qvt z!I%9np6Tw%VOBwP$;&9njXxpOp5i1tVh9e#rbtsg?sEHZ6en?DX3(k38jb!lJ6lDc z(~F`3*NK0N1{7>+=6tp5iD))zA#MOa&t)ynKnmQQ%jMIyp%aA~5z9pLk$uD2sygTp z=s0XqD;yYyz+da7ty}RM5jg|d&tcVssz*TjJ<2bjKHRl$VF{L9-eH{#(QQoZJSn~H zAM8|1pe*8n%1}*%+pC>{&^{XrK^@bIFp?1IaC47QzvDgjs`;Zh@R)pX*s4jAqH51t z!c8KxXtizc!?Cue_vDv0B)+udJy0bh_w19varnM$flylfg(rA2*W{f=wxZ2F@_*3 zO9AjVU{t^Yq7_v@f5^LJZ<_@!VDZCmm2fki9{) zA-Vti4Z5^u= znTBo$(eCWT>}W6X*@lD)CShyAchH!RlEEy;-2mH4+nP{T?lfOoMeg5($KI9p_Zz*Y~o(pR@^%u)4ps~NyysFwU&cEq;}RQ~05wcFeU zYLWE_VX>!lo_6-VwaF4$!NHje2ir(QF}96z(kVoONXppg$2B9(S(|`lTiY&IF;8ew zB4{UlqIE~4exv=kRSz`Zl}=F=m@WkogRqtM^6=;4O**3=U(&zuJaS1qP;*SOc6TA$ z5iE8+nj}bMaylf@lo@X`vP=4v6v3QGLFw!LhRz{YxlU<_Ankc=8(c2v4N2|*r||uw zHH=OIdqBcjO`H)OQ(wkx*jlrk(C9{|5hTK|t`N?(!@AE}gNH?*k8Y2Bh3bZm?r!O4 z4dI*fc6hZW<^xeiG_h&xPPsZjLU}#*VPjub5D}N2W-La<-O{OmuYyLnu5MOhZho01 z+seQi8(3d(JVu#uWzM>SCsV`OQV&RTa;gOw;ilkggP$uNTT=olPmnc09_pW5iU#Qz z018Pxrt})V_uadiSejNP!tsS)tGwHCplL(mZ+*c3@Ay#OuC+)OA~HKUxRc;!wHk<1 z=5OtsvTaW84_~N3EDaXm|xoT*ZK2O z0oGFJ7-IKc!tVkfZW;jh;yLiWVQ@A-LKL58sCK`3e#s52j**yH zVgqJ&O4edtS7ka80ZcAsgJe=b{_>jEQ;Q5+2)CF&?(i{cYTrjf znIz@A8`H_wO<34`**6Eoho>Ky zr#kG8+KCkvc~Fx;^`STmIKJJ-fyNX^Z+%;iev|=??@TmQbrny~vTkFUd_tfE>r`&T zexriqYyglJxQ;^xhF&L9d|g&WKY0OBjTAyZ%^;4x@?2ex$=wv+fnVoshZNDHi>w)1 zo54T{mqm$~97Gdh!tbt$d9!(T3yl5OMI4v73bKsf@Ieju-L)vED>4f`zI*Lbpv50t z5JyehgjDjcKe7T$#lWkePVk0DKw9UW2QcCE&)}h^2AX6)`1Zqy$TPTdxRnS~0hg%o z*N^#b*6dF(S=uFg@_(`b_|16DeB5yS;YX1UQ2^dx92)4||2$N6Ey}1P>zkhgrgcQA zc_>4ewJz=el3>*&#L+Oy{SJscdD#d2;$lh}5f~wyKxx98Mx(%@=$!A^tq5%8IIcOa z?JBoq^^2Y8H^$;bfgb;*L9NkpXqXb&#lb1N45}Es$5$c~nB2n}`VRTXn`Tv??+Pds zduzP_$pn)Re3BKLrR)FQ(t0Mv1M)sTVyjvV#!qH=tZSM9=07FfJyqQ*-IZ4@Oq^(w zB&JXG%`2+0-SJ;xgR23S45S``(h{(1M0)V|U7&b9UWO=*)=eai1*3VWF zX@M`OZCNl)rQikrk;h{Rh{uq`v+MUgdG}pGT05B&=_+E)FRWWy9#yKFJM7bOR4wEy zU_0N^hQgnuzBv?4-Be62rmRX?NpTrm9&{QUMIWbEC%@IVJCzfE{o2s&Hy8McK84I1 zAox}}O8IqD?=M6kf@$dQ8|s?~eM#Y%_YU*kYD%pqsH>>s`nqgoX>W(&Kb^II1NJla zHq6xv2zj&R1iPvz1G?Kh=TcXV0;3ZxR1e;V{R%gMp&hO?EDeEy<_tcBg z1OP{ZEEJ)_G}W0THIF?gUsa#|^jon?z-Mc9`-mO_*FBrMQp>-nr&|k#Q0&VC?I@rw z)WNx=L&*&Sfh{$GR8QijhJD0jqQtnYo^FK|{CsLo{?Q`i>TJ5H$O(ARs2byFMdhq_ zpvkEi=;x{XlCPjiX~O)|v7HkB7a77%sX+m9oAtnVEe>z_Tv1!*5^de#a$h!~0b|aV zS6OHvw#cfUYjj0KoATp6nQ%5T*7G}?zdhH8JZP=gYpB_}f3>Lps_sU&G)nFwa&0Z% zOR>^%%qsZt8ys3Iw+^Vxn!0@QnNSBn}Co3G+;(K+xv zvs$vl2Pp3=+>J(#AC&N_`gfgK8wSE!^L@Pb|58=|=DS40V8FQw!R)5{j4fyHdQn&E zg{{oTi_vbex$seb1<$|rNAauXxnRGuACQ~$!C+)p&5*99nd2mhl@taOFY1KJ8-7n= zC^gC1r+E2b$z!J|9oQ$MeC`FVhx;DM)A~tw=h`cFK_VMIfZ_RBBeBuayq9Bq!As^# zeK;eN=axhAD@6XKA3nAi?(j={KtIQanEjW<5c9v_s-ADbBPokfnWh(CysZR%Mf#%8 zX`O(3MV<|tMB1m{%~2Xq!t((M;~yzV7Kb}vE~o5$@Vd2KA@{cw3Ay!h@Z2|&^df%{ zK1QeL4zRs>!ts0)@<66ive-rnMKaP!A0lN!z8W@ezC!7ve@$|knSj@13}vwHB&UvJ zkyH5G?i1K6MeeWV@1(xyRE$i7poD@Mj$}&+{RrH(`gh+pSo#=zeALk?wxO4H>MmGe-6 z%(9r`^^HD}sg4M1)siNHf^@_}goW4sdg3XCf72HZ6h7R%ldB+SRtR;Q8vZ53ukc6e zL`>jYczu4loWZU60Z1ZG!h8Iepl0#2*EnpXOUO0-#zG9ErZTaT4Y!}dBg*_6Yze&e z>}i`LuHj+=P)bI@*etn*+s$96{~m^ErMg0Ez6gz|M_}=c(R{OPR^F7Y0#^Gh7G7tm zJu4EM9a6Sp{qfYj^C>y6vcf4kSRCMYXLmc2`cXjT?>2w*2lcWT5CryGw}O{Z096+> z#UV^y^MZm>YqDs0njDu?>FXGoL}oLQ_j~J3>&|{L$n&D{jkZWGhgYhfGkdrskCjjm zUpUu3DnP%CApmn%B&f`v?vQ7%?X*@+%w1x1A$krWEez|A633E=s$R8^-@sN3XCd$3 zNqkc~xRB~M0J%>Y_by#gkKW^q7lSrUAC|xzs@})eZh1cLyw9o@l?NBb5IDqAue2O>U{b^Va#LlWoh)~D}6T%xAv zB7`T2k&NW4;9p

!}Y1h(O7H0EtRV&u8KF8Ltas1CHR&Xiee*BU*1~J(8FFAUFl5#hyn`v>-Q7XY!(0NuHn0A7Z$+w7$3W5^rHRgw4% z5%!}FoHrmo3AF4s+XyKN|8jaZ_RAaelZcn8%TMMH^?%lZ1ki`!y*lWoi$Cz{MP!A4 zipy1`aD_41Y`ad8#;}rEIg}K*NrzV_{g2$-i$X5?j-)=sP0!HUU)~$Fr8hOGU;`v=0|G zvPPl)*|j@icbh3~hz$XZ2*AC#M}3W4bM+x2Y9LiPQPY=~){gJQNbz8%HP={);;#kY z`WsSUkU$s^zkLsW9*`NqCe53Qj*%`%Z~nD{*Rvhhws2#SEarqqek-;mv?Z-{|RF^vnz zUVJ}0uay8a&%{fP%xuhjq;8i6{8=Ij%5LM$n~pl25^-_SMX-tOU+W>l@SeC~UVsYG z=K@4J15oIYb`sTA7KX$K0;_C6%d&>+3^=JZRmM&$fJvN`1eh{X>!V$1DGBdf=>b~? zjvPWWNZ8ZIF-k*Y85rF|<`0Aio}>W@Dwycw4y3;Dvfl-fJ1Tb#I#@G8p)YasP|ke{ zm|ZVPK`G>90(hi|znOFMF7rW`9~$Z5uY;?8LcC!FLW6e_Yz}J1D#s_5c7Xp5`5oa< zWKt|PVcT4fOMUZHAJekJd5lPwG+_Wd*4Vw|Imuu473YwO=h%Ubmwr-7Dis zIL~_ZO1RQ$5AAGZ)j4oy0MQIfBFE z<>BMDrtDuZNOD-J36-ba{0ZoV3zx3x9U}dph-?BfRyB>mY<9kPmHJMpN^LLTSWfOX z5q(rOLl%q##mkVpc9WR+3QD6nf?5>W_PjU4OA?ba3aO-)|VA+bPU%1 zfD6%P*-z6)w!iw0t=7n$OxFRb67CDOQs=B6+jajNDlV}E1W*5Tf6ak|2(9y@biI`@qglgAV8s~E+NjDP;k5?FrD#re7q6nfr>zLUrW~M>?dt zAa^SJ=8Y+g|I@;MCtKA2X{NcFlT?-(#HAcUDyq5J3Jwo@ybcKlbeQ84A_ES)L#LlC zKcXB$;If$l=D=2?H}+pcavvl=L-c?@Y*#$T-4j&obK4A3!@8n77TJ;}Jh*OYwEvos z2^KqU(C#+W;~M2ep3uS`?@Mu_J@o@)$FYEZwtyt}?xPt0DI;}3^*+}m^aBZG*OY=6 zZ)*Tj5*9D^Q33;o!zE$_?laUba2j7JNY?%HBtp@u{?i#7jJ>m1SP8Z%G>lp@-Nk2f z)x%{FDD7XVy?xaLk`y2VQ2sH3I}}uaJLE3hW!bh zqI#Z5pl1AC+k9*dt)5Z8{wsAIn)MRt)WYHK`*2KL)KeIMfrVkqjV!J zjdV+Qmvo49NT;-Pm-G;VbOzW1*CudX%Bn&&zD z?ER_D*yD_PPBrhTYg+l7a)w1vyg$iw#R%Y-9B_iDtx6o%M~i_N>FE+ncp+kVfnVHk z-BdtPA!IahmUcncGd0WY`lG%jF-5>%mB{)JX$aI@N%^4gFSSbZ?nPLCu^jpCKHsiz zueLP~?Ar{UxUjZTEpKx17b`u=b_ApNbkb^b={hc#Zm%Sq#rMxEUGq#2S=pl3Gawc; zs(~tbQ+>4$OsypRtmu3uo~3*Tq<_yC%c;wF`5W0pjfpMdWkqRR0bnU!Ccm_`c>&>u)DzF$ zCzFGqHxQXrT<*G-_CN9{Pujfvrtb5)i`)ryp8te#o=<|%ExyyC(Y8^oLIKOEKEjWL z);elQddDY4=wxS6rINSHXB^+*8kdpV0E2<)5=;@W&Y^evQCJ(X5i63y5`!zf@u^&< ze*p_Pyeq^Rmgm^MGA>HPG%z1DBfY>Nx2;@N=n_>*02o*=QS- zNR#=Omu&vQNY>f2W-4Ww?4@}iw}rU1M6b-3iVuD-jgqY89)y)@p#kN9%S18HpAe)~ zs1YEMevYhh_Grc+((j@A#niJlb-F8&yL5CEyT4+0&k!(u{D|H_?jz{8Z}W*kN?HO* zzFZsgpzO8HAov#_?+Qv#RwDd~-0r#Fca^IWwN*rnnI2Eb<5>KipEJVKzwI5Pz=fh!or7otA>>^{Q}GzaU&lrwYt$ZG}=CxL$-L7i%D5McbMX0NLSI0(LZ z*(V7zm@<5Q7zL~(2u%3|P=!>wvC}bQR>bJV(rDWXXGN+K(?Gt(u-Ku@NHf83nf&+*K6Ht?x;dkG2E| zuG`0e=JW!BHOBD)F#-zYZAB>?SZ_(a_+)P{*ZsrG$cwXo5Q6x|#Xqoz$PxK#{5Wnw zX3(*pyf=Lw83-pLxHqk^eE1xlcXW+6V+9358J`Qij1aP-o)rF;j58z*CY;n0dQ#rfA{R50>9RL^D!fveJ zVeo=~n3P=8pWLxzT4S)^|NZi*lq^NjY}PmD_Jr^X_QnUm%_hEq5w(1oEC=)rJK?Xb zm70%Wr{tZdWB_b1`?Cl2BVEek^YeE+yn0L%G;#Tf=^xb4=8+r=N%D$($@0?8rhr>G zP3l;Lcn*2;HO1 zc4;xh>@|1K;ca5nVZ4ZX_p>_PItih$K(j7sa&OI32WBn{m7160}`1zZ5g8SP; zx!e?g`Zev3B?MnQOVC4OF+lfIL0Cj~=f6|Uv*08kdEukihD1)fDVg;Z z)+`%)H77_36{O`tfai}xXzK}$RR)tYad%#VKnhWRtxoN2VsyEeJt*{%voCZr@Xme> zqk~{s!8X(ymv8S=v>kvf7RKGLCFF*o`_mJlC=>EE3C@OkXph>UUtZ}yadD7`pYO}3~QV`g>YM<=y zJ2RavJq}OV`47vW3esTVW)>BC{xGOZkmdN#%q#U5Y9dQb6MlWUr#tLs@AQJw!G40s zK6Hly0tj*&UsKL3>1P=ITI3zn-O+0TI$7nEwWWjzXS4$Rf@t7sFJuL3-vNaHya1X2 zZZ{OOYye%?$M_AHBVaLD-4Z0cad!gM-1wnmf$Kq#2d#>skM`m|TpQDtXC;LyHy!(;Y(pfq&46Jcr@=?D% z#ERy4p@|<2JtxMWll)`s41I}UcZFxt0xD`@mbgs(5;C|@`YY|2$wuTEIM#d&}t@g#b1 zA@Uv(nG)edN!pS;VdkU1_n2Qd=4SP_ruvPy_H470D$)EA3k5agI(4WMoyY>XJ|)fj z{h#@y^~VuCAlD?9a;|HTOip~gJ_oW~@dMMzX1vAs2{4S1ZgH>bM&6&9bahgBw=vk7 zbn<8?egR9HQW?5*O`tnrliP!@+zf+SlFEoJb(a2q$`Cw%=|LghV*hEFAepmRrS9zq zC>7{IvJnSndT1$%AG^gTFwzZVu{_p)Qma9#!(h zBp)vpGYBS`K2VnoK*)r$dSalOl;o77NUUI=Zt7omtn~UxOy%~~Uv~|SLlHf%a9;@L zK5^ZB-3(RR9RyDTjyy)<-Zv+K)o16 zUVAszP6(<{+kXv+8?>#${sfyLL6oK5M0}6W0}8_0wyCz2@!$8{)vC2MC?4<`zv2v0 zFHihs$Yqu3@tlSRP-#uoNj3?*$l_1}66~A)2cqJq>j)Hj_tPyhe4M5|00zI1%}d+tU9gqG6fkFQO03;J1cA5Pnu{&&nOkdHN>@QiRIJCciN z?EZf19Ujc%?+Lnsr66Mn`{z4if`mfYd0*C|O~f+h#mP;yJ8J}Y&8 z6e&&QKV7nWAv_%NJ;xncP;-=U6ipi=9ZEt$P1b-tYi!`8)1U7L=KyNMw>gDv%h?14 z!;zm?Fa)Wz=Lea(JOcKEqU9^eNuFN*MlQn0i*!g>=Sv#v;+?#c#fpngfMV=sMi5TK z8fb~Mfi+IDMpb}?btY|tEB~ien>DrSj?cL^{I7-hsNY)Aa}KpD^?so9^UD^-3q<>2 zJ}8-iz3j-RwGs*xbKPiD3G3A|4+9qA^>R|rV5^GP^G(6Fh`Mb|&K!7}$b|^V#&fjK z&n#LT+Kag4#I0h!!$f@8JYhq*1*=Dz_t-1GCd&n;tSBp`w{q?dpDv#+HY*b=BP$wm1`F%wo9rP6%~ylFrwk`3 zyf_vjv)CP)je$OK2~Vw|JS6R}VB_OFesm)Y@VmCtF(09QX*x6xEqYV&R(mUQ;7+{p zQEX%JB|AbkLz1H)s#mRJ-ADaOr2r4Id%EjkOearBrowI~`nzM|1ZQDoc5uEKFDjx+ ziC}K%+rFn@0}Bj26eD5eNiWP&)=CO@kkx=jUcc1q{XpMj-N73Z4E}VH@Wbr_YWEBB z%fI)P{>sLl-dF0V8Ql;gRf23=&y3+#9|eR+7kJln|KFyf_x(#_3j{OlNPRDBsjOSG z`~aJzOs*O78mns+6*;wNMWWCawn6kjV70mAOxui0*3!3(Wp!L62k=2?@UKud^l+hr z{>TmnF?YZP*f92_vfQY{#+Wiff?8yj&F4(a@7 zNZ-K7Dt*TC{JB_mT7P0}k52REg>6PLgY{zToq*?^q(Hxm@b~o5Cs0@1p&dzfiwTXrrooAe*Qm~obwh29at)gY6?jA6z#y@S=&lD-QIWrGkEwF$o)=Mm z#5?43D4UM$VxM)b>%qjv*8zsWqSrmaq;5~f6uIfC5^oqm2m`(}gNxDq`PV?To$?qI z>H&y#3PgbfH&QS{ni${VTby#IWhK>Yjr+t|BV7%jEm0{U1+tWljqelvA9tP5WM}K$ z5auntPgy#4`$OB|Ik1j{=mYg@5ws3d}XSnWdzN8{cE8TAjhGx2biNG{J1&V zLM{71>r9~~Ky_U(Uq2%$^njns;P9nJqh<4VID=9KN}gcboaYwf0h) z2dQpui{JeDzTYwSL-*m~Tt_CGxP0d3%RXn#rQx{c#P~XeXlS9!og@J<-|D_Cm;8_q zfbVto>OSmg`gK&zl5)G+^Xl6la@%ABbPeVffqM08$$3Z*%9nJJB$M!NH(E4_@iCjr+1AWS8;(uCz z*qqdw$((Jpa4s)=&my>5bmo$?{*}-dzy3mx_Zs*%ydtYX2_*bC1L;=_3(`b;_W)KW z9?zQt1Q7mEQSI@!^CM>|n!s3r)P;S8@7avt-Oap5>oKan?ceU@A2?e5_PjRDteI59 zG4`lyXUiD5qc$9=62XsF3zfw=ti-9Rzun5NnJieiKOf4k^baOO9YuhX8l-Pyr<76O z^n-B$*H{|C?wv}X{iP&*oy3pp#W87GM+g7C%pi*GWbyKgq2-s&l(I@{A(_tnzzPQ8 zq=f0h4z#LA-Fg4*SIboB$I{TuA81{u6+U3>mdd zD6C_zqX;Ho1YBE`@?*8cp`8ZJZNop>Ro^f^R4aj?0Moj2kD*d1(sA&-@gDV4%o+sJ zFvOt4kTe<~%SU+tK`|t0`11-g5SkQ)QM26OFL+bicTccuc}l_lN2eNy&7N~8WAi^m ztE*^$)}#ROB?YJ*;>yzdLjbz~GO3iz{~x*1`tzZ0_mz&E_`Z+RtEDUt0vOF!vHI>* z#al1jQo_~gQ9O5=MAQ~wC1J=Ne-{ysWO1@Vj+!Bx`hX^p+DAfqRC)9dElkH}Y=@sx z>wW|B>h3T~Fw6RTMN{xy;@ZW`Y(&yCtP6|BwAtDN6B~oljvL}bdEqJ z77jHye=(Q|9U6LYF)?0?vS;R~HKtB!u>6}XyrZ?jXSuM2QI!`SE6VTu8w<%z^TQ&yJ`UtSk7#>LrmqP)WwZBRP@1vieQXHuVYdkPRMB}>J$pnPZfW3@397*O zlNrg^pN-9OJ!bk4;|92kbNHq1Nm-a!g_HOfMV7udrL=|Z6V}y!%G9`OtCh@C|D%so zg>hqPAG!3`Pj)$tBhMHC!quz6LY<$6I00H6`>|=|Emrcmb-MSz5%McOZKq-*>LYZb z#9>C*ODYr|V5iaz?4!mX+?DGJoWE?Rc z5+?CGpfK#`{7;SXI+(8IKcwG&R2|u9}~T|F}Tmg z*;G1Z`ivP{VPVh5=G`$as+#JOljHnvF_-)%zc#H)mx1YvXl4P4Lg!wedipgvA%hZk zrNwx&BpjR-475nsjjpcnMK)rN;>;J4BbVm^`}?ZeVn$8g8;h^MTz3(sT2+w=ZM$0+ zzILQFZ_7+4r6R?VL9z2EGq$e6RoMMdWDgv1-#dd1lGWYa?ei!<&dCN;jm3vek2&pc z>~vK&YA0NU@Qj9B%U~B^ci?=pg|E0wWhX0_4ile zTUs>DrvhK;K%{KaOw=nFMk%(JqgFyF>#kI1S(U{Ro;$G+ChT2h63D;?WDZ7ig8@h> z8FPTJt+luN9eITMT86DJ+QsyBqb`h{nftz6BJ-~)GW2Udd>H2v5soq+u}6S?UebND zCAluVIcvw3?Whh6fs21=D6EH5`bd+CSibxdf{Wh)wDveG;Fr!HD~P%c?9)0*yg;> z>@FCB9PBIqJ`(K8RrM^l6eR0D3<||;`S2!Mt$Dm2s9V1py{evS9yNY-Pt59}xP+@O=048;2g+LY4ox5V!OAEj(gxZ9VYVI@ z(JyP?<$bMF?S65H*erg1koQ@j`|8$KtG7e3`_=-{%807o;E^sE%fY8`)IeE^1IdFF~hYX(`ck8r}$x^y3U1% zI5lW{SwX4hJhO;moj~%<8I|)Mv4?Qn3Nbry3 zn-bctn|U3B8Y9Cq2}j4+HBA;Of#*1B7+_)_HFmLCN@vW&{4OKt|IIve>iu|Hu3SAN z7kU6SEVf7!02{A{yJ~HcS&0v=djMR73?ss?4<3XUO&I6non5btxEhV>F6sJcy@~zQ zbYxBPfQ1U?N0&x_@w8NTzugYgpSQ@iwx8nbb#9Hiv%bn8OO%4(I^mA&Vv1L4A5Jvc zO~;b|!>XAzLI=m;A|8|z>|KRF#&Iodgr^v9 zoJ>QyeER@qa_Bo!q-#-Y%O|7YV{tzVql1o{*-DXN2;X{%IbkalNtm??k)d|$%K{)@L8mY zsMbeZnMV#$x=<%vaRw|g{udc|$_(1~X*~GmAtcO)ZJjQ8@5O8+VTOHN#JpxuKu&$= zsdQeoN3l3&sNAb!EURP*vtoE>^re9uNdLuf_3~&Fe?5BxH3Qm`r!^KOFALR_-?e8e z8<%S`+6lo_t+>;E9LqTPyeRE2mCuzVn@~{YLJr1uHi$q^OT$7J$D|}K(r6Ul_3ZxG z*-04XMA*X38N1nb?T*Xve17iq>&V=1w(kJF|1zV9PBefzq$t%_g3DMMRT`QVxEx+d zzY?)=zQ*72hq|iJyC!_3k?8i5Rb-DBhJTEwSwr;gane+f(cH7-dsF(uEf`|TbvS3b zZbbeUF7KI|t;$k#C}xI@(dWFRtOCbLi5>|ALGu04G$}wg?b>*p6wDzxDg2pE zU!XkEafDl>6R%R#l|u;Yx4fRB*5TuzKVYCzzr~uMcT%MrSn3*|J+&VXep(gro0W%^ zlY+00RUQ@A25p(qc!rtX%7H&dOio4Wki!1}rJ=2h7mtd#P$=j?>Gox--->y{XZJ4) zYF4P=tZzJ2b#_HjSKuG8Voj4sL*w*bCvv7@D~z184IAyUuTiKF5bW=-;#FGQ2i^JA*obRibTEP~6cp3wDgM zZYYQZ&0_?>5?BK(PCw1p2JarM`@#0E~N6SdNgo{P_ihs%}PaH=1G0V=Asa`s*+Hilo zkMV%n6nDYFvlebaataBIVEgca8|XnIeA9%7jv{H`_B|H}>-oGLX7{NJ$-U}rzh4=> z==ZCCkQ0+}B1^H%q%*92T^U zhZkK^nNCH^3%D#+wpK!Wu0JboEPPfjnrg0jpy=QQ0~;qWJ|+fTzq3+q=l7}`3*2-O za1kRw)tMpXAKBPYS}zw8GIN!aGSbtm54SMasQ@4TJ1wXW+j)If{YyP&$5zegKhFaptMr7$NvMEklq+X_b3T3?)T{1{WeUNRV7o-h93MD$7Y!QD9WbDy{52 z(XnUSF#SCftjSQ-7RpP7$!D;89Bn$EXD1D?4(2UPuigR+AZ=?+RJ_ulDrKv+s>Nv( zmfqh}fx{Kfc#7qn z=5Md)%ScRoI;r!pqQ9Z;HEd(xjuZ*eWcWD7jsZiiwOzEIkju*qqbmt-;Vjdo_3V+y zPiEj$qQWzB?DhpAoV@PO z?{WV5r2P1?UY}5S7gfmcleVcox2UN|W9VbU+CU6Z>^#)fuQwfg1xa6{f(pr@sS!zd z_x;!RQ$t%vi@D2)NkoyEB0kigdaue!oa(n)m=x9ue1X*Fc!jXLtNZP{@g6|F2q#lb zFAr-zs;vbs9~IZn#_lkW0Xy$h%T({bv~MZS&FKe2+@^Eur~BGi9tmA;B`kaWQYTwu z5wm0YuK#^!fEP(d*I3L#L4}eq+tG zIf^cX^7G34I{tv+cv+h=~J8TL~x{|mlj{evVO&@cReIwKxe=c z=2v218l}L%Bf`s|kcSeIDDuUUJjX-sWr@wFKwiTEM)$C|IMOubMvmg|eKOHc8MYhV zS2?x!P*VgGdE`wJ$8HPG+9FH#riIEwyZCxi>XJL>=C+UIQ^v(-BvXp%ZI~I!nFuHz zH9Gn5Ve(=PlPaMxNZM_qns(BE76&~h=a%misv5pG<}0Xjf}SoEPqvc8Ix88=Dy&uQ z3Hgjl6<0Ro(;paGI_SU(tGg@BYpcd*&LBNMNZhzvdr`Wc3VxmL2mg_iKQ-a%MY~U+ zq{!Z#J^oWg!_nAfbn@br=GlZs@)u z_@rc&f5`=I@;8MyBKu#^3b7%;{b#SZN+}^f=Bfg{l2jUH(N}n{ zGiC}pN3yV2NrE#pjvFqOAXWUxCe%vzTnUNbg4JOrW0*=vMpcg@Q9Kt}qBUL%$2ihh zMrduB+R+3g+$>2}n%6KCs*QhquN2tU(+^d(YVJXe_bsXS^T*u^sojAeG_53Dqc))M z7HxL76*ZG(CXgbdFLf6^dl$x6h`9$glV&b14hx~Eqn_!P+ieF@c0c0Q0WC+;m*$if z?|Tjg1~^UT(06?9NZOe#WgjzYe@F}f-YDPO>#l{5c%Dr#6D((!?|!xZco&*u%t{B+I7xvE zY%cfsSfpO+~Mv57MP5i-M39=Q>bOsr!g zr6%X?eqU!vsCOA6976E^nf_s!$hcH7`+f+#Z}e%Y0R9`w$yX8Og%71ZZR2PROp`7 zM&&3TL?x2#S>g_8$tbr0S|Yu#rKGEsummj2U8RVU>rXH9RL^GQu6R@$IoX+|zk1Za zpA8Nu^?cMR4mjbf2V-AaEO9OFinKN6I zJzrdscDR6(zDCxh@rigaYAokad|h%$mR)>8h*b+%aH@zOYm3KZ_uk6M3W8-F-}AVX zxFkd{RvnL_E$!UXG(jZ4jGvjv$}WG9bsh;lg7Okg5<5_Fp9;GPgJHqmHEUKgkGvtn zRpvm(;%F84;E%iLIOD}4-M<`T2I!y@VcV)m49O^%`tRAb^D=@%xs}?MNHBVam-f)u zc4fLAtkD@s4f=AWoUGb-Fa!O8w2HTzZoJr#Z+X5)s-oI(_5EbXAy=>?oVAMNH*)TA1oiu za#l@#aPj~&K@fJUC`giEZ?_Cy!Dr;&ZZIJ5AfN%NX2i;u>-FNJG^&=T!>?FhJZ9t9er#dp+6|G+@OJn707~#*7jx7Q z{8^^6fq6#vt&g=!%v>7$Gw@4?#u$dAXByixUITwPmee=8)O>cgfqpO8b~9SC1AHl( z&)b^k7muJaJx?R+r3gnlUtDfhfDhdF9nZ>1@#0^3Qfl(RgKBZF4Axoe`bjxI=NW@u z!f+WcN-UBGBb|X9NofMJiwmxs-eTZo8<)`sdN#OXm_0JL5EmrPsBaGADMx9A z=0m?KDe~kq=fx(*xfj^G)yMk%n*#8I5a6t~V2U;j6Lv<(ikXOUW?P`pNDh9eN6H_2 zl;ypxT=C`upC8aHP#?ujFx`JEBoePKG>$QjQcjrZ=z#17C4s(y+OpD(sUL0XI4-2j zq7Zn3YHQJvcB)pu!9N7ShN4*!d%CW>dmxPwk2y@fKJm-zd^LBB`Rn*XoUf!j-urU9 zZGrx=MQuOyww~GXyr?}ObEcBQ7&!zW0AZxyoKF)Ew0pxO@UfDqpCxU(s4&e~`5faUZx7mZST**j5wHGk z!+(b8Y+U)^r2Eo!IjvRDXDsh$khY^yc`^~EbAgVKw)TKSI5f_Qe_KR zlm>b>j}Yfx)EEDPm0omG%|e1|rO-v$Vy4c6en!cHqCV=yo- zPU;Nqk>qZ>{fSUdE+s)qzNwE7@-rSqFa2YOSIVjl3(qz(D3>S9Pd}#{LQd z3rh_@Ebw+G{9{4rRc9NU@X{Kp`g!!nz+*!G-P4ZkGI{Xq%zYMl1|6FyGov&j-JouA zzLqj+r3KrNEP}ykFj#+TL12ia_1X1-}I_cDv>XN6PF6-sYGBTkgd|e zPrGUa>Rv6?gf!&Z+{e$951|kvQYFC$3K@VNw!4t02E2SH`Gkz45XYRAU1=08*6}1l zghJ?ye*5Mfc=yfnlF0b3-OxpV8B{`WI?uTI?W_nO7iekY*oz4FeP$x6w}tS-kUefa z5eN`$p}# z-Z(+aQXF=qu!8ZQ3(@v&L#;fy8}HfpYfgM?<>eX@zh6CB`HWT|niebWSmWQ$Ay~Ze z_4}g}bA(JYS`UH5hG7-(tU8#UXLp5!RaaT);f3LuGwW(ehR&C%^#n3dRcm`?$c`Q)1F3M=;*uxr6=gNdu*hh7{KU1YN2!jcwr9;Xve* zi!g9rT)(WKVq_3Ga&cyg;Zh)5!8A$&K9`2>rlRj}4v9-iKbE=aa+p;AwJkV~myC@; zLP)|tE@T^}WC5lM<|3gHQn5s~uME_ouhX|`hYf#g3X0@;+55gkYyyimc+@E~MYj6= ze_8;BGvSr5!YoZ74=ox1E`=Tp{<*qFPwmJ6D#L~7>!x5&0T;>e;0l37NM>x^-v74M zffR<{7y~P7CY{S#4yp>X6w+-{|L!nqdz)0&%#RhxHdP1DvI#!hEC(d_)~iCnj}p2P#j1Vo!X8-m>qP%dU;FLotz*6K zDRl>2kpKXPg|xczeeII&+r06QeX6iZjw7PtH}@V@B2*Lw-YP~8litXDshg$g!I2A7 z;#aid)!A<+jOBqtSv6B124}lZX#3faJhwrZ^b@fN|_?OuFD!PTJ9AuuFl=K?CLTdra@Z zM!~?@FN(*!PgzhgDd|rdtU3t@sY5ukw_3)zdHB!R`A~DvUPQ%dEz+Vbx*?zPbdCD; z=YQ+Wh$hVlec?o~fdQlgX;LZe*N*KTLsxj?0=6O`_pS?$&uWNV z{Q9+Vq$qfQxWx5(m)WDQRK{0|9X(;?kDzI$T0QOk0e(Y|nC#j!< zXq8OTKw*zvhehbxTL&!?#JjwuKXh1hBWt@k|CD-dMwxnE=^Mnj#$aWlRsRqo`Nhhx zUYR6wolgGi?tPivOS=;;%d$Odb6O~R*S+;1g?`RZW#vzl1S~%jmv3k*Ey=a?0S|Ry zVA0DiHkdCNug=;vKlQo$vgc~ze|Y}Sw@?aRdyDtG53WLSCRe<(X`!t4v7!0)?!AWT zuIedPNtTaS?m5b`3=n?35lBFD9U1-^lkYH_zxT^~ufQ8sjetxE zA~mYmaT*mLK`Xwqefj&>_Fwz}#EpOZ7@QA{9a4=^vJe_5yjkFe%ZvLsOuN?Ky!8os zAhI`lCh(cRiSJKfmOWz7P;t1SmEfoJ%!F)3Sj*AE{9O{a!QR$mOx!JDaR|n8$o&A~ zgX27#o0;(LR0L>NTv(giG7b5JY%WX@D`>zolQzyBW(~G#0#p`3)&8kPG=GFYST88I z)^=FhJ?haiKJb2IOMQl@O5hs?Z2A6leZVPo29Q$z(g^H52RSW2OqXzp1;0L;xnn*1 zN?{2s4wOVP{2g(OS-iKJ-!Rp7|9Zc@)-fuH7w9L6PemR`=cw&5PO9f2@=Og6#f+O9fo@1RVgnSUCOXeiZz3M{)->#F&FfQxL*G~>HIniD(AI%KZ zkW@W}Hq7TX3GYHsO$^?o^EP_(pMK{em6_^$p#2*sAi&+sOaU}F)UGXWs z_9omR3z&vDvJ|}x5aBCQqtYR0EV;guXZ&iUhoinIU|HoZb=e#sA){zC)n`3WVlU!b z^}-D-4a(}IaM?%x09r8;0S-P`9G^I0#&RATwKL|;gn+MCyrd48#e!EycNZrg z7fq=U`g0Y(_baakp*dDUqGcs>D`CZN%3_kTpITpn^)SYn!cHB&Ab~7KiB0fYtnSC> zR}OJ2%@nxL5)qce)r;mS2^Jh2u;jk8Z^f(C+)TJvBKXql(sxp+pL2|Oaq{|28j;%z zQA0D#*VNnOg50JR1xso$mi}2jI~wFYLH=>80xRxGbo$oZcH98US?>CN$QaZCLLQZt zJsRNk_uBOV7Im2U)v#V0<-yRlHtR`$G7ETLc-XD7;ohJ6{ag^w9>L>Whr~8hqnGdt zVNtNM({rj&JhP!tmVtTpOd!SL;1HfGQTxRb;~%HE?|HnGepLvyup$7Saf}nIZG*vk zBa0Y*`5^sLIa2wq{F#zTXUnXxtT}K6rc!heC4PxGwoV zj5lqa8d$C>9WUz1Rv(e@#@T3~G+B4#Y}>h5Ugi3aw-)(X$-l54rng)3<&7VFrO;s@ z^R1e`w32z{F^HEzyag%%UW)ZE2l$&edNztAOBQnTIrQbS-pi?Pd~c^9T#;z7=L!9v z`lo@<{KgePqtPNYb?=3&iEU_+e^lfS;oMq;Ia-K$1(0!Q84Qk5=tVrh!#@9${1IUr z=&ZQY?zjuQG57R!tACgvsTXc&SWAh#$n1r2!e;-O*5RtIZSY1W>%Y|z_JDZYuglP| zCq?a7x*WDpsUmudG6^R?!E>DvdS>jxwUNV5mV=|oM)fump(u!8O(WPo2Iih zpCJGk9Dj(|hAOE8jyn$nr)b~{&7QG|v|!AO!0gBmRr0I9f$G;r5G>He2N1Zb?g5(G z^u@&Mo}YxM9Z{p`AMh!*?1Yw|*qH(O^|HK4Gz`-j2R$aN8xpPY)Lc2gLqiyXyI#r;5t2=d{`5D|@479epkii+rs4^KZN&bG*Io z2BA+-XPNijaFevDSve_gV?8rhurpOhhrMz}Dmq_4QD0_9F}ToMW$ET~>>kn_bY@_E zKcnj^c=hvl2{zh8l4xh>7m4(%9Xa-_Z9~2Td^pGkC{GSQiAq=&1P4dFl#leIK&`C` zDlb(PR`QS7IiVnD%RP?vr{{Kp{iRQ$f8VdhPDb*hmWnVYr*i3~nZB4QarC`h)EOfc z4@VP=M4et8HI`hL5joRL^{)jwfiEaB1sq#ve7OpCJ-w{E_fU41^Vf@Bk2Peqd~B0_ zn299w&CQ}`L7k-m9vLYD`Tno0%&4dt)+c6s^)yX`3z59T)>bUYqMQ!bTrVn&9}_6T z?-QiZi9`Mp>s%!M3t5DqapveBxG+AYsjP{@O47Moq$(6lAW-`YPXs5AWTNq7%)6|o z*1u?1%lqzSp#)N4JFI)fgt5fF!(S0E4!T+_8F;^7m0Muz%1 ztC6&{hhZ;^Bux=IpANJ!;>u@$@iXmgVQH=EV_^ffNK z7nHqdienV4{7)`57-Ov=a(Jk*lz5pGkuP7jdMsPhJ*$Olk$B|Q>(!~$%|Px)-&Z(^ zts8(8Lg}KVi9I-bc&4_6>s98qhn-_im~Y9ANvSsaLtonc3bHS27Boe+6&!%@v%=WD zC66{n3zLqY`96qj^O>)lhR+}ab7z=xOh_*-8zbVKab7irQ$zg( zYbtmeguOQYxcxeAqdUt=s5QzqHdqY2`1nDY#nSbi=Kj+@!oeyxR${1wyO7@rN)zG)Pl z#?y{9G`7zJzP8;s0C|d*-}8z`ikl#MU27R__r6fhk$#l%!#ta@!EXL1n=CIl@eR(?7H>TEt6MN;ZNo zFWM~dQ1A-u{v~h{G+sFFcq*L{7phgVH&}HE6w?erJj+~8Xjv>Ii(O{|AT1geS%XkT zVt2W&ctZ^ZyEGus-YsjPu2xoXW>OqdN z?^}W3&oZc2T%I4`BI%28`-;vt9Tt0{{2HF(FcvvOhqFZ-g{+y;1^^G!yuZI(BKVn^ zoO6v)kcX8Dg#zgd{cc7*4|2EV6Qz%@7k-Q1$(^92edo|PJ7D!>oeaqy!#G7Hh+T=a zVIZpx%>(n`^gko$wp%8nlh{>$!j$vw8Wu40d*v)7G9R593RSC8c?fiN&RH zP&lHVE5-a8i^sQ!afWDFB|1$SGD_kDS7D5Oh2gIxVFeVsDr~4k&^pDtpAuyT% zxgBdCEADKg3;EbcOAfI3eNu)g4;n&2r zcUsW20Y~yP4Z%s2ainpf9J#;Oft*04W-3J>6%+7eU!M^^^jPY9_6$`)l15;s4DKSU zSZ&iR9msXI(yv#)Ww0&jv%h2RrJ}#z)&6vpn>02rSk-uo>_K= z8|{I*m(5?^Je0O!Mwvp6{M@=tTKjxAx)C}5;^?D)NUnTQ6c4&IE%>$l)u&3w1q4!i86N@>(Vs_?^%r2cx%@ms{smJ3J!jOO+W6yxTtvBh=N`z$UmgS{qZ0k zO)l;zo5blX+T!%fweCBW48EwG!CN6=yb7UJb^6G9a~m(Wdf~ppYFRFz=Iaxdhngpd zMw;TDdlmFgUOx&{cVxJs<1IKNIm+5vvrB)FcaTjn(g1JEPXc*Q-pA#KuZ9V4Wj(iM zX=FB{Z&Ne_J5yf17g#l=XO{T#5Yqjgqv1y%&6m5n)EdqCKXL;joQEDx1h9#^_L$%h z`X5lEJ5B;@ib5wQ2R@esHKj`(i~aztdKo^tKbv;fQzJlLF4%ta26Q{oLNSRLla@F% zOac9nc6_R+h>QO0IUsauJ9ThZSNvGYprFUkqdba~f_lOz!d^V2FwH9Ay!~AoUZaCx zhq=A12{X0LtDLZm@73YkR?92q6!*kQoVXd434LH%BbF}#F&h~XI~1p?ReZ)j$$3s` z0W`~b;04c6lJzc>dqdgHGWOh3cI)Xc|IJXGGd98D1fIj&yxPvz$PccWU10sOT%O=n zt3CWqW@U-)EYrC590UbRsgw$oVKaPFgOI$Mxxc`Ri2SEEAO0iU4>yxbpwEopeF&r~ zz~laQGw7lfdde+9aFq-M7PbbNF#gIWYNM`Ux;uw%q`Rb~ zJ4Ct%hLT3QOL`DQx&;N4mhM4d5b2PPkwFk?kP?OWp!f6so-h7qf-~prYwfkx-b;KF z0&4_Tb+MTl#dmeZ`OE+2md_gXw{oW1$@O^=SICB>FJsBo1OpK*{pBD!J_luWfwY_R z*1x3qM8~>NpFxLW{&cpJh<(P-)+b4aq6_Q!ZEAqykfK22!_!rZ;-jM-MPk5Sw#0@f zB}eg!fRh*eq{0R0$KV z*r3wQto*5|;#VppLH@+V&_3{D8 zMin}HA`aSh{tLTiMyIGt`BLMC0X{=o7K@urlA~ZkX^E~_RgvCY?%Bj-VHF%Jb3^+_ zk@a^MU0g3g!z(FL0SXmjO71N>c^C~@>;-U+#eH;O7~kj07oQb_4ZW=I$OOn*gy`_9 z3=?%ytI)p*`u-S`R9Pl?O~3A5PWKc7?kv{6C>pG@s6Ld87;#QdUHVBcsuC}NMWJ{3 z2MPZl@M!RC-5PLB6E&h-$$Hbn4_LzPvROl!58cCysP*VAg0*}}9$}qE*AqU+uOhB2 zvnhdHF(nyk{gu4ou%U&`uQiyrEE$%NI-^c=OACL#SSHm{X=>6@gSB6`}|N zUGcMwx;ZVy2ayw5QM!p4u-Gd9<~U}COS&ZkG4vgUdz$xM`llUDMP-j9AT?O_@Ke?o zx8nXMN&4rP__v}=qq;HMuq!|RmvYqiHcmt%^V>$MQ$eRpHVKrwsg;ERrgwj7zANGB zhXp0LDipmSM!RNpOQP?K`M* zF8?`aGl(rfS-%5h+5lQQoH<_!;*mSB-23d{T;Xx6MY*od!9{Ri`geM5?Bkk23#dP? zi}bw*&UZDk_&-0Jwc}9UOr|Wj3&9fGLbexhw5=Gam!y7K5Idc_c=*1zyOK}-Yu>6U66JR&qanw9rK9svD$XU%OXiqQttn0{L9K~qoWCmwZtHbf zSZ5ynI@etY7ZSGZ|1)o2P;SYoL3oU!7%axy50ADA+FYFmD00i_kA6h2!Zxm_OrjTt3lFQS$a_rz;~V}n>df5IaP=_n3y)qsPq z>wWjG{XmiIiMAHn7n5RFy37_*ST4%lb6;FttoajA3zQ(1!0^kmB~!VtPu@lqX_864 zkd4dJuOE6_HLPsv&#{P&saJrIsbI;@WEPxHx_%i8;td7qRy4uc+|fbQLnLfT666e@ zO9&1nAhtNQYEFr5fR>Yys7$H6)!cOS{CuBQgOt<~@>XJ|VKdqD=<;wJSD z5P)S-!kZ}dN!aO9&*qGr_U~gX2LYr543A9OG0X~lo1v><)~&wm%tauUn=TPh)|5nf zqIpsBPR_*mPM$r#^!)2_`)!NBhnbTBsl1Wsze(=;M|U;#5F>Lw;iRom%)LhuJa@Y6LQ0uU$rdh*w^ORd0`%|FEsj@8%h zD35TIUvTtG+2a4p>H9PN`-`;P%WV;SuFPCis1TAPZd&LH*6w>hnFQn>hTIoBdZc?( z8?Z7I?UjgEM0FUe*n9x!a?QjcbW?lpSM29+v}No}dUQE76ll)qMTyvstC(W(4_9}T zKm2O@&(&ZZTaH1EsvJcXi%oj(F~@1I>?0QUOIWBKtePrqSRrZ55k6F{5rx!JTb^5= z(TTGz>AfzC&QOI(m4({|+Sd>b<-g^)2M{oC$ z>%Esj=af?PbM!_*d);4q@xsebz#dHWI&3_LIgF>hrgEb;P(Ykt=m{eOTz0IY7Ql`Z zLbASh{Ed~!iHDE>XUJlb?hPTERnVwD}I-csjAF^c)2vt8n{PK5~^jks?#!W6{8Q zM9(Sf*lJ#fh-luxk#~47l?w_jJ1r4a+AlM$1xmp$jqJHP6pO-`Qh8O=o1zLmgRxFE zT!IZdn>D`7Jm$3oJ^i@cpN2jW4odaEQwfcIJ-b?uMoVVjQcw6Fhj>uGS1nd$PG9gD zA*Fp{2MkOMlX}x{N+GKB68dm!u;=mTv5%Ep#5k9OBSvLvjxK$bGAK=jwPq&(sHV3p`GaK-ul&<3F@1n+^N3xLs$_6-XTh|H|cq$eRnPl4M%|}|57NLdy z=Od*_8AH-sSq{M{w)-P$P8{OW+#H@*0v!4KSq={PHUs zy#7fM`XlMVzMS}vb#ahV_U&D9fxk1Va`4^Gd6oI)I+pSqx?o-h-;axhS|5tiw+(21 z^B+>zuYX^rWtisd#R!XbLDhanoY0CoI&PK>dhKF3uK`y1RqYEKrh|EQxpC?0zT$Z2;PAnrVzozzKu$bp-;E^QtPB7(8{GAZf#q_ zzEt>aOEc_cRmb#b;)*ERXRpb&z9DNHFB7BMG@3BFc8nmkP1{!qz6%PrIsyJIdiaPP z7!AlV$)xvTWOff}ptYQxXA3;xF=jJ6RDW!;trA)H?h%)HP3%W@TLakqY1obC>iIvF ztL+gUZx%@8IW9x$Ys?*#*cm!|SK%MA={McMv#?i0O>%N1hBLZBoM`H3+%w~88j@de zo6HWPQ4jxES(dXcD_4w2G39DC+qBV`J$+mmbwieL`bmMQ?Z+PAQV4q+M@|_>pu^%S zaBepU9ntUY>Ig z)5km1nQ#raEX4$U1q>3$d|`5Am(R`T)`Y*b4qCpAWjI5j_7}s(Y{fsshYqo~uUvNd z)%$(A)P)%(-9*uaPpq9|zkQ2mBb_oFweuN&|3mwp&rQX5Pe;*2^{BRt1RopQKVimC z%3mo}Wr8@k>bQVZ8f(A?2fn{jPiU-&!%|(mex(uNT|f0&$6kE5?S*2Au~GABXCb`9 zAbiB0fr|6G5ITvjNrOKS(0k-2c&YExLZqq#EQ=Jzm!dTjY+NlhsWmda_lDOsJ!-Gh zOAwP3?Jonbb5o_JFyM8k29ar}y-Wt;<3f24LvCU-LdD+n6ulb%G?WXKN_bHLEh8;2 z{uwsk>LJG0x!O8x;mu?OJliY@-uYxYN-`fg;>izsB3BVCgRu^ek01uvCOgA@gYACG zW3$nU3cS;~hc6zkwMGs1kXHQjGI-i%)|jZ>P^rzpy<^LT)wH2RGk5m%+H-w`r8JGx zQ21l9{OLrO<|z1uPB9bLp6>dCPY4K%Wp_XVJr!n=_>lk&a*)kgY~$DQ)}FVQDX&ds zz=8})9P?cs21*6#&w0H@3U`fwb$^|7nl!|-r&7)ay%tPslUZ08vn;c#)htFa$);X> zG-y2;#cF=?tT*;5zW>}2^CG2Pn>KOgk6;8gy*=Fd^XWnF-)fV+t0HP*KbNh)gBMv8 z5Xv7?+yy#8FZ;v)2-|a)|Ewi)AwBGHwIios>1dP7sh$H{@jc<3T&Nt%WgS76`xs? z;Gc34?ab4yLJ}&EwyBJl_c73n{kP znIGt6K)B<<1TR0~GOMRU6n|}0nFmUwL)2cV5KZ4*zKL^boHT)Yh`mwy72tf?Nrl)x!e}}J6t=k;8A2RYUXOW!NEb;64Wix z#&qLIyu67aHaA9>Bs}u)!!?cR?a%y@OQW^Ah0c*uu|rm?qZUC_QqFig2h`Z5uBgQE z!~@Xy5pLq5HE7xsjWr|TG{kmI1;`}?z}Ut3s$+hxNS#o7A(zTY!B$^KgYNkBMO{iHnpyBSXxnH*3PkWVvNK-18i~W@kfsct)TjE# z!Q=}h{PH(Xt542Qd(1UHY`O{zT#=@u|1N!(RPuAUZyY!f_{O&SIP_j!RVLG1RJOY< z+j4MlyoIIuEGRyEEH<&Be=u2?{r6Vg>#D1n?l)&KRD$prh+fSmO3c)}^kHI<A9D zf5@F-FjE~BUsb7#+o~9NAWh5Og1V<6$s-IIny;1pO1HLJoN2W8Ju^4M(_Ml=iYQ2O z4O%5HX2MR4jIf=Zy7ZUzV&-J40PA3gMC-<2#Zr=;W2dNx`XbfZBBe1cbu}eJN7*ds zTE-DyU-aF?Dl`5ZRy+a*u(w8Q!)gqLmV#B>yh>19FZ6Ch#P$A%yY*&q7?g+cRLkZFf>umF%sGTVljI{b^5^ zlZD~f+k>Uh1vv)S&EW&{-=%_pSoQA9OV^zg*g33=GvejTP3OMuPZGn{mbS)5)zkA6 ze6cAQOxS1$Tykw3Gb@Rr;qL3tx4ag0U$gB$pjDV@2*7DnLQy5{Y82+Q#n_2=?3j+$ zBa32WpVktzWf&{aHHbXm3_X`x~dubn)1q`B?cmX#p0xesBa z5X7Em=pDZE@}5tQ*kcM49?=I0A_yjeI&R*EIG+WvslR2i0LUYhWM?E$miHZwyKr6g zKbIK#B28hI&*rx@Yj!cnDLBpKn^$~Ca7%jStQf2s{ihjwbpJz{>mN8Xu~b)OKBZj`?bcKmhCq-}4g_cSZOCh`vz zasKy`PHyH+??vRzOdYn$b9bVc?|#II|A6qCqh9JW<@V2m-(UtX3-XkY1ouf}aG(n5 z*VWII2BzwNYX4k{vdGz}0k5Z`T7>v4EKvJ*>h`63x?Hu>w6(#k(WPa-qL10UFDJw8 zMF}HX^xOmnejvvlA4+)@>&eOpZQ}2Cc_#Y6po~vNjg3cB?I&e|&*s<*BD#S<(oG zj*LxA;er452`{wTq!Vy*E=*4X*r7MvQX#w2z#@a8K7#Dq^J{a zPQEn+cE3sAbe1{hqpdo?uMTZ|pSI zKjsBQuAciD+r7ndc0Mx{-TvI}zhdHP=GV~z2VPcp2P_0C?$?hZ=b(ybk-WG#Ni1{K z6~7Wb7DfnYKT|d@?x6~_zHz+}VW7qcn^wU!D6cPJUvB?G7wfm?{616kQ!W-ot}rcA;CVOUatrHp+=$w_AnaLP&_0_iPdbe$Xzvf9dF2h<~a3ErG{~ zeeN<%zD9zAhJh3YD;)#}KE+V!AEvrPsD1aSF`+uL-~~AGr)j4_;HyC)#1q5@rhdU< z8HS~1Bfp(k3!N?vs;*pzkShT1Ql9zx3U+PhyM_GVS+%j~2@%Kt%0>fZ?S{Rf`+JhZea z-KAbN;c|(cJS{^sV<8saQS_Zn3a(YVbi`YJ%2E)Xz8bVZOb|d`dp%p0^mWaoi_gSB zHPvd?{B5%73>-Jh?QVOuT2y-tLL)m4R>TgUt8kwDwp`KyA{Ul7pFDXh{0?J7odPdA zeXHaK2?wwz&&#Vg@N_F@vJ7_PC5L>@LQ|)7<+s1+4J$iXTdYPrHVwZ5OUQV$T!AZS ztW*zP(j*dm-1_b!04O;@_s7@|udq2Xoy=UELZUDV4Ky!26YMFHkC4|c?U4A|v=;CJ z?|AL}6-hZvHow%|`va&L=NPI7!2ch9;cs z_Aq$~8HrMjy}Z8pcuA~89*{|iVuI8wIm4+wl<~*j9F8?fLIl1XlvSCO$5I3*$BdjN zeuUTz1i?yMTe9BvzT>rt%hGai79D}6U{G8Bl)b@fAZRrEzs-^$uSEs7Qy6xx>*E5E z-VUJ+#ur@zJDop%&=%1oX2Hfz(W+l`F}4LJXFtuLxrBuE$Zi0GHFDPf-)^q%PCG&T zH%czo6~AWh(#itvxJ_LnF0kxvs+8&^a@1+j&}X5g-bwJw$VgQE=XSIpgW~}Y-QSgI zfBd2yOcwyL`IMj8b`#hs?Nc577O#r-oFpw+G(TK2@SUCphZOG`BAiTSM_K}{TF8XQ z!8mv5hfIZqZ_Ut!&w}aG$4x$3IF)u=Xyi-5p?z^?sV7za<+UC)7mXF+fgY(ZH2P^+ z3ZHKB_2(%_G!U9$)?k=$lGXh5&M%hqN{Vk`2YF2+<#SxD!erAin^E@?FZ{(c#2g$? zo=*<^H|H2&{EzHWq#Gc70SEC5(*jSItJP|U*RoToK?5$()Tw3OMq<(NR-AlPAfV;r zH$I+GQM1S(CwcH3j+;oX3muZmcG=g3X~U$U&LolI$UJ659&p~o2Svu-zD71ZBM}n# zBgF_TXquQDO^+ZTKbW+Qy>Ag~EzMUSf+Jjn{UtvgkQwt_(N%oav1)tVYj;@YYO^J8#WC*MXyTi592 zwpiVReGkK8;E1zFwNqvC zHwzYGRbtSdr@*A${`yjtrTc@@hdAZ40b)O>R!GNjA-+7|vsV7@6U7wx_S|>wqy%7L zzh~PzSLjGAXGq$YYSSigKic+WNgvXfrAXvlSd^~Y+V9{8xkOF_&s=l{giZpuF%*9oNxh-3;&FYpP1O&`idy_J5Z1Mw%xJwWw2G) zq2uq^S8$)Mx5h1WKaBp{5YgcP@Zi&g-TQuH7zeCBF$j09BW+NgNuIQQ zy}|05ehMm6q!IghQQ>(Ad|X0IUEeFU-uwG$=@`H$Qr4Xd@i2B%4_ZLyuY+LdDIqx@wK(Dl z>|#`k6^jv8%uUD$(W>*uu~(E|T$@`&M-i<3!3tgdc>Niz61OV_;)h*+h{3?5`HBU+ zUIQC&+8_XMtPQMcyP}b5b(= zM-}87OyHO5j;AuV8*PDg@4qC7EKAv@Q)5_h`4AjS!%GNV(Hq+Z>oE5S>#Ap2#>aJp z*r*{Qo3aS+GT{+t4ioU)P43n$Z_OM+Io?}~B*P80Qge&!V0r>2e=JCrqFT2`FHwDG zvUvw0&@ssa{8{1a!g#6JbWx!Rv=;zv*GCkz2+evv=d}i>-FUR(I}=(pTp)$%lROBl zTVl>XLJPu03gQKSMrdlEZq1L&?p*?-yZ7LjsB8)r0HTS9ia;nf&H6P&)lkc$%B5e3 zLqfT1!~jDQAsL;JP3B@c!IBV;O|O4N%i!h8pw~JXq1!09`J-Q=qL_g23m4rzfK+Nl znQRh$4)FljjErs35TmR{-aKQPq(3XPLA8@%B+#F5ub7d!>wf?7>VC_LjB8_Oj(%9{b6($Ql?0_rcezsUb05}e zh}d;8J_!qIAMlyHm%p?)3feMX^P3YG$|#e=A1lT4fVqS)gpJ@+3Ivn{jyntKdUuBt z5@6nG>=S+<)3BLM0L6wFaY3>!2GQnf#ei=!4`pxbv^o&J-Bl1D;e9{f5`A*?M(VYD zMNb%WU6Ux#TFC`ai#1lyJi!#ywWkNpk|nGi6bQ2aTheQp@UoqAmMDj4h%kl(YE+@xBV0V&uEc&Hw_LGy6T4Y z)Q=CfM_0d5d+>J9Hfj@p414{ncOjx_YwDac>1pJgHz-!gN2e|n^9fuvi>HJ8Yh`*Fqa-mxS1APv6B5zPf6T3&Vy;d0V=YZ1h0hdn9$W zuGhHaC6Ak-gf#+G0#%?~-Q_=_1@pC!IoOJoCH5}cz(&3Z`)2t@gE)UtcWUs^3V0@t z*dHz_aVBzwu@)W5FAiEeitd*LT>7pT!q1buVJdXN2c(Hx-QBEc5pstxx~-*bld#gP8V89-Zc-B zH8KI0$W1LADU$aLuVd)$Pjqw8&S&(Sb53MPS#EB}i5}cqr=681p}GjhaBk0WN$U8d zVp=(-r)va6#50K{?zfXAUve_D5`ffl<$HV;FbL2;B-*%L{FH1FWma;RfP~_VTjM5z z&PnQjp*;V0Nc5`~)fR9g+)#IL1+rk9uor9dXm#a`v!Y;X}xq0RU*OcuP#Xudjj2j}tpc_t-^U6t?wMR`$-%Ev3tb zIuAI(Fsw*EV#35?*`gL?lpZLxJKOd4Py`mC|D{-VglHhyNu!DRCN()`o~YXStxu4; zu&#E-bouHEcxn^0eygWkMc7)E2j6p29^aTadI_MUMwl#Znd3mX z#=?BTJ?3#mT0zZWsw$z^HkgNse0q*PX_7^|`IAQ6&gni{l|FAYVF?-u)T34EV$V0D zWt*(;%`Te)jJTD!};Qg30uK6261SH z%_ta!V_fv)n`YB`h}Y}>;!sQiIs5Ww18!^q-Ri=+yxH`fb|yLI9~ zea5gn>=46vY~7!XH?(4nZL%)*D9g%IgZt8snEY0r-sr~$Wvb>hU0pbs^oGJ~5&_>_ zLp2pt{5oCM&&8b{^R7e&vsi{r=ly%&|5)Dl0a~Zrq5|ZF*l#c{F^&`F*&|QYtk=o` zT%heN@&#HAY_Y~dZ-IHuePrSlX!Q`zS*(0Rr)TXcgbfinj_FrYqRJj`&Oz4IFTAYz z&M3gVrHwTk?L2;Ej=y@n7Z&>9@RX>zx>`&?<8d;VSe5Z7(_c@@UtHeHGVxBmZgA7+ zJ4qLkg(1op%as4SM>&53uyHsWTNFv%exfBKDrZY81dM8P3Gn25VaF+(=mI1UTUMiHOL^Z`)MSghCH_Qu@RevItd-=L}@ZIyV3?I^Te0O+NmRW|5 zccAThCa|2to;VmWPVv`q;@krOm1^%AZJ^xY5#@pl)uw0c z<_9!OP@r6Bb(MuF%_^rE9mw>`S!Bmbe-|hX8YWibjvz^Nrff5fn1asE%Noh{RyFnJ z1gi(g5CphXM8oGS2LE6Qps!MA_Sz;sd~Y&k^vZgs9?eMPXVf?>v zp;+RcWN;L+5L!jJBu)F>u7gHGL-jm3U0eHvDN<40SrdEpVHHOBbYYXn8~6CIfd#79 zZx#m?M+U_=)j0p?nyll(d7^G8YX0Y@5NzDfKM2B@&Hc!wl-yw=T&BtNtzZ%6{$+*q?SLC=6dd-15 zk6I;8&Q)_(F535g906pLfnp46tXni&^j!|#RX@Y5hxKa9IVO-{A!>%k2e^p#kafdD zJ3n|*o1%7iizN-C*&iod^*A06e~=C3-zMvd!`9tbpBh|0zUMyN?+M!8GwUb8l4}+F zYyzTEXv%0hq3&0I7@fKs{COdvH)@NUv_&aqXtL?FgN{CxrBtSSilR>(uLIVjyKU}! z2%w?&@3IB}fWQ}AyBOAf*%T@mtqgYAmX0vQHrE)5iy zIkql>aEqEfae1LIv|`kGG(s}MmDZEQwAY0094Y>0Jg>N)7iz=URRpH7hIL`epmRL) z77seYTeICq_u}TXTHTXETpbZ49~dJYZ5~`>^yxkG$be(8>_O_puM!3ptm#mwZ!|C! zgwUipr~1G;t+)2u{6eieOFHVK7U9H%orpaxTr74L1tX2+P`pal(cs990Vy1s_d**> zhj^&wXMC+nh)s}B`etOe-Tpc^Aj%{iLALO+@jQQy&(yW?yq`}asBwXLqYI=R}v8@h*{%X`wAv|=IJem)@^DhikY3an$O&yp@k4{>bhGlxE` zR4lLfEG$v~H3=bf$enRHQOTo~qdZ`)u~{M}aoi@svzOsb36GOr9KYaC6ldg_4%a%I zP8VVab`$7sY*(T~P{x8(%le_}N+;eT{pE}p%RK;24@e)veGN(jqAYx3aA9`4%77$I zFpo3OS^72C_;*Y5+()Us|86+{zwQ3?M`4k8{CI78h_~2uetCJ)d>iA?MDG)pW1iy- z8am~m5d_DeS`wimjMuX5GC1l(x@QrTQv#AOXH)S&R6 zX3Kzsu1Ri4x@2-S5^y0{9RL~Ja5Ts`fG`Awvt2v{R8Y(J9BM?(uw}^;{j;~snaaH< z4pQ%VsjbH>?N+GNraEok04mLv(sb`JVg+`G%7{O>Lp9c*4iTu11h7Q>(?qwi_FR{` zA1_p5N(cvg>2F;1vL>D=@E<3S&L!FoVI;x432ITQwj{D6KOHfl8jA&){x<_;RS&=8p z7nm&;p}k3AO8&j^Biby<=V@^7pA!Y^`g?%DDE75;?OkPSvuDVG?cL zD8pK-FKLcz??pnNoYuZ=qo>c&Zc|(!n+t&1#Tn=o9{lfWFjVW3r$+#7nk9_pL`5b_ ze5<9dAsFPLsU}M}X-`n=B#O)WOfT~Mm9kGhO^3=?@(1X#QGwA9l4$#6<6S^6hn8pF z%`?MdOOIa=mQuK6CrSoW>W!0fNJF zt4bzK5P~pU5`Dbl&!0C18PWckoUAs)yY$QzlfO0#uY#XL%iWz_RMZm(g<*hxavEoi*@ntXnTHX4GV+sLL-SE>OC9Lu@zWdWv@pJY29+Kc>5=#=r zBgPAAq1qw2ck~c2&p0f?jh!-4hVdCi+U3L(RReWewgJzB_BP)vx5zDltk5%(oa=~^ z+j>Akd+Lm*R+luQ;x?p=z{Q%fIQc`AFC_Y=FS6uTvGQp5cir;F=T5?*2?{Y^=NhL|AjV)1PM&=4Xo1e)d#C6hImSsb+*} zK=dE+ZL*sTrr$m$Q*NoXga6cY=KFAb~~=r;9y#tCo&;CJl5}NQHG%8 znJ&%7$E)#Do$YgYst>xIfLGwo(P1vS+<(fe75)Ek@{kYUF#i}g6Sn6_yKySGy>}P=lqOd~>Hs8kq22VhBf1S57 zwr`!XK})aav0(Pr)jb3~456nmt){04y?<7}$1bOW=~a8GZ(Y~; zeb?E>Aur%#3(m}@T#WTuI9I$si(FO{x$f!4^V2Y3B&@Tu3}6A4l)2bljYLV!?2gMx ztIhTy&eOSuKXf@YxAJ^Y?ODMw@hFEc4Mas=C1A~jbk*_H7_mCzFrfld%L;|KfUJ#o zizRD+%yq2cBtv|6%DO`D+!Jm9TwckSDIoP`^$=%oY5&MR6S^`{w>2Xd0UG zOhOB*jYPSy*gRH41)Glj9Nzp5a{b}L+P&IQG{6w;qv>J=5JP}L#4z%&yXdK-z$P!O zpYvAE{oC;E^0FuZsj7^U^=YlxrHF$}fo(Kx#uSUM?hRA`MVtg82FV6L{={b+xO_JT z5I)VSpp=!l_i#S{)pC}16#8gsIn;{}hzI=x0;g1LLj`s{(YamhZPCasIHX?tP7PxJ z*}tW4lKcwlD(>w<1_TmxM{20*W9c4$#D65j6~{%$ukn&PS$pggIlFE%YF^i$;OPF! z&rXX>7d=2g&0m&ck4`#2h2*iz<}(Brn7_fyUUP`RlGHcp&&Myuv^hcoIVUt_%quON zRG6C!XU@xKz-2Pc%;s72rrIemh-rWB^5im5B%-AO#+cI8yIuhRWi!|gX$~4)l&xc{ zXe6`8vW_HcS3g1<<`nDY<*_-Tnq$dxxO}00BBDFcj=yNXdHR9o!U#|_BuKVTfxzzY z+WJ^*-M>Ekj$VWu;n(uxDA6ba@T=0-<-&e|m7uqI{_}Y^Fk>OvEVK^AO*97Lc%+Y;VRso7y{HaSiLp|;1hPWUxwfs~W<&D{{FNWLcZ zyUzwFSxuByc%G*}-^1&q?2b@shbZ%})o6q%YL+A?d$J+)ew?J^o*?Q!Puz>r8H{-x z7Wq{tRPJ#3SHV3)_Y(0cQ5&-o)lw+i?9&~_fzf1%;}P5%Vw+_X7?OsFlYn%ltz3El zjC7qBasXF&eQ;!%1}4uM{s|vcP5FU`gcwtOO6ZDIvadlR+T>%SMYO&$8TMFSJ4S~re1wMbH zJ$gk3HO=5&98l+ zReX7w8?_D-E$L2+{pwrH?uE)~3j^0*${|(|-4??}7>Ug$^6vZSTsjwj9021~8_ZnVW6^ z{PG}|nGsq^CNy_>1Xm}3AgsLFGW6{S4+A4;2lsT03q=jpi>`)jF5kd1+lvt3IOuwu z^&YtLh+tj`p#a8H#**2k2lq{4{=g!|mi=@PC;S~uu{&_Woe;jP!pple`9ad2zfg7fWN$>mNVUlgulfRTdHAR;El zKl*7(8DC7%gqSsaIvPXNb!GSGLV$FU+xD-DqUt8W11Xb~sDQ>IxU?a@Qp}uRbh1|Z z&>#aUsmfz!JMCu^JLfk@Uo;jh9G0(J?3c*SXO1_(e%7X~t-{M^eeXlh&YYZ|MieHL zO@YH)begLgx8qdKLT-}sbLY{%#N@j}$`j)M8P68v#%iAksDrX8g;;4s=AdU3n1e+n zc*%5%6lOx1knnsIBD5ovuBf)?K;c&M53|s~m~@6v;s)f2{>s;;@S>3X&>U9UkHyoND@7{c2O>8~xa}thNZF!6J`N*|nTE zT4U|`9}-Z@&5xj=0ro=QU5UOY)LOEbKOZ<;l$l@Hce?%H-Zll++C9n7?~-xZjE3_a zUQV4&7+SpkswvDNP920lZ8gsbeh5eU-@FU^Jv*PfEh1_&B4Vuz!$W*yV`*Y4aP;4; z8)?xu==gARj+|kJJA!gBrvaLrEC+2#CHm5m{e3KAvA9=NbU*f|$@-r+{4Qm+^_F)v zOCz*7&9VpYUU+B+668xQ9W3oTv>|s3w~aPR^h#AMb7r$Io~JkOGX;373hm#zSJRTDUVeeyRvt_gU zzB_gjbguBL{qR$MR{4s+o+$l+83aBFLDj!HNKbgQ#z2zv;d6^Wqt+Pdqu zTNU=LHX?CzVBBN`^VzqcG4AJV?esV{IcvrVsQu=LGr$T&ZhIph-MxC3a{Bo_MPyfW zANsA@W*gO$?(Y&S`G=h$16DT9n7UX0GZ8d?7@-9j04HhH=wXUVZmqMDNiMs;S2@<rLYG6w6in=_5WJ|MncF)&Dty zrEiblmwHWcm+V~E$+t<#slZ1@Xy1iI1NLOYFSxsl*B|mEYycqvE=N34tNS{9+r2sS zy2`5YcbG(;S(|sopQoLByQ$kI@0jOd7GTT&!_{9$MfrZ;<1pO~!q7b+J#;rnBO%>G zBi-FGv?!f|fJ#eugGft*gbX1KA_7vs8-2Z>&v!lluv`m)f%}?s?X&kj`nET@6|kLE(T#1b4EFj+ zt?V>SUI`qPhS)mgEc@rIfbm{}ht>PDd&+K>LAyoFk(%9jc6Fu7nX|H@pwKMS^62_c z_ce@;a4o1M38)4nkl?ygrH1ACZ>?8#IV+ofVTUKV1~DUtMOd$!tYQ=o6*Q{Xt(X8d zk4W^4KrAdD<&fZzU!gFZ8nQ^PSqtx7Y7(Mes9<4Z)Aw0x&C}d$*@%FA-~j~o`6b!? zE(b!Z=j`w4Cw5*zn$p!9%-jGoHnh1I@c&54%*33;K*1tRx!ujism;6U}T}vNwro4RAk1&gb^UuX!AGjBf?%R77^7$VI=+G3$ynJ#i zMgE{U6q*#2!CiPnrlPR@<+yON9%(S=%3hz#{$Q*KHgj$28^GltY5J@Hs469;*UU!uaDJGA8HaNP> z=Hq&1I(Z?i^OS(<#*yx?Z(owy?L(Ow&+gEBKzviic!DT5JqFq zTFeen`1|xyt-PKuUNwBtAst}QLmqeVw`cMCz@8mlt?SZLZ8^2(!@2bF_ zQaK&^kWVi^yH1G^5i>S{!k}@pFf_CTxH>6PQ6C3*oc4r-? zov&7#d}Nw?8CDs&T0aPxiuX#w%GX zwj9v9bP(2J+|}=5@>_A89J5Txs{0Wp&v0&JGLSeUyqk3O%U88ly!=wX(jgS(veNlR z4P=j$n4R7))?AuWqH`Kh9ji&-w6kgWj%8f^$L31rLmW=m1s<$JR<$HoghT%Km`O&3 z@O>&yxiV%f+#zDrfGs5To`VLAoQZLpP9Z5#zCm{W2%fg8T-S5b^A^kjLGng4frw?0 z?nwnaT@BOqUj^aPNw0n}|0*8`W&`05`%V-Y8Fr3APSNLNHr@iD^MfS+3DN@Lg}E{UrBd`*tVrcgf|F{9YqlgQ3J2jWczwzJWQaLKecGDM4-|Q+t3FgwXz0$sTypt>zj^%%XxQyoS$R`ll49!m#dGWyYn)gd zMHk_mbi5XSVrM&(Yer!tOrU4KP4vE{f|Sq;z$Y0}V!4ydEN$QFFS<*F(9|1lm-b?w zH9pah;k1LQt?oAbYph(g+w=_816vqu)zY$1)R4H)KZOOOImy+LLY-MZ z(&jrDe>JK-$cX>)WK=9uE5kY{VH|A%NlqvBkVF@~*yuSis1aYYys25h=Ah~k{FK8+ znI(~?W98`ykbRK25$3|{Cgi<+ov98)ZP$2l@gks?!TWHN;v`Z^48OI3W%;y5bbRex z7(C|KZ@gEJ7p$r#qoyHnr;1dgQrTy4WXZSpqC*?1Icr=%6?{d zmiAC1DYnD4@WZdC>cdb~GlIKCC#)2O!%%qjsAW}?dfTL7d4 zdWizi8bW?+k@(By0I=|-XlW2R6eWm`s0a`LAeTHYgrdtr+_7PqL=6PzE{5Hkq~Wwi zgs~H50=s~xKgjtYAB+Q84U#y9p&JM_e}r9zSKD=wDXbFlk+9@Ig#n402xz5vA{2Q< z(&`{>O3m5{N|Jv(&4NGhfGJZaQ&DhwL6(58d)7kO$_=A`9Hi2)>*ZGQnwG)nq(NuX z6v>CqC;KdUqmyon`qN_LsqNb68%Ukn3*Bl-)ayjdBnYX;+v3KjWPQ`NwZS^Ef=DX_ zxsWw}KR%LNWWRd)jd5D_=E%J^JPBpTnln(emX6t83%HZaqtf@~uP%MSgUM%AkNR?A zV&{cx-*Mgn=JAKw)F?l-Q}iBvvhmsn4PW)_9|bD74mjD+Ar@G~6tV^C=CJpL`1Mu! zkz0=H7>2@jJg#u;Gzl+PG3VE`3cL zb9)m14W|G?QtZxi6h2#I&oJ2y;P``Ct7cnxw(5EBNm?-8qlRRu{X||LAbZNLQ+pHu1cZ~EJ?jbV!Iy)FKPy{V z*{iOpxOmqCyB_uGM4~~B$v)G^E?^pdYen+$~q(Y=wJmBTf!6RO*9v7usePbkdcOE zs+O<;n?0AK-5}UhNNfbp6P5pYY?W}Yc+JnSl6WA55ON4Alqj{ouKN;zC3gY}e@JR( zv*&eB6BAaA~bu3ktDYHvwsy-+M@5Pe^MUT+^OhPJW8< zTFB-)XZN-2=lTCMji+Skfh1?vzW zgbEL@DSIxFSBy);-nZ^#&C&-FHbzj?|M2X9U10Al7Br9^|GP@i+I>HuF>NL)#UrBi zLlm<>1cIT|Qec&ZW(B4xI6O5m4nq$v?fe!$iYB z-8k-`;T2d=RRo&|_~x}0kazftx~i^o*Pm_e&2Im((TDIeloX0Fp0lI#Lb$P=XYbst zO0deNT|^B>f#v$%;rZmRB3ShwO5kH0x_aJ~-Tw$tfa|i3&pgoH_^o?7U`^+6YCMp} zlTeyazO=)inNo}!& zgrS_qTfFW?Bc~)zdihIHv9q6g^i3fYNF|pS{sW9($(>5dCn0?#1X`UCKhegl#?Z6I zgC^iMWB+VtG8)E+-2#3h>5fqMb~`w9jl%4B5B^@_v3f)*Q+%G+_=uFi!@G6)@@3#JB2QCO4u(Q7Zgkj^L|0i}*n9v>D>6^1aPy#N)*m zP_3Wn!nM{1U7^C&24t<1O~Rnrl|yzpVff7n%&UM_eajZ<~sm=*^3CRI4zXKPpPjW zravISu){o!sk-n1E2?cRsvl(?C&pq1e^cVE#EH*kBdAlW993QVh9bM+qCQzrNn{ne z^3^yJtl@3Oa${&WJG(|srIux zWzF`apeljethy%qOcNYWI??cOG)EnS(4J{R{y5%w4p zX&U!@ZM)MAcpdgS*SPdsQTR%@7;ahat5gFQMSoeLj z*t1kxjw~D3vi7cO-42sXqn>pJN$d{BD-9PsY(D4d;aineraI8)XSdF#66;cwlqP|2 z6SKhTnZ0>;2Fd@qTyEX~=#FzlNtJg^792Aq5BQbe0%#fQBd#M#;~Ho!U+G{t4GD`7 zE;8TZ1OOSCB=Sb0Idw$tKUdn5z7a7l#$Fd zd)swl7_V<1#hhIk_7n_8)+fHJIvFsCHsI7UHJ?0}l=Ad>lFmNgEk(=(uph)~h(Km9 zL@&24o@tbH;?vPybz?cZze)+m#INUL$^y~jXlDF%Z^D?dU2RNV1Gze!U=yQXHl2D_ zfn3IJp}3PkM#6;`@$6pdy=~Qtq44BKR`Uq005OIJv$d)HPCZl4(F9|gh!K@J!ETWl zApS)%0pH{Yx;1Io#(58G5z*O6g6(q6SJRab-wZ#5h*(u`aEC+U%GGZB`wW}F0Q;l@ zFfz^yp0CME<1~>@kW+Hb?xJUos=O8!o*Y-|c5}GPC0M{Jbh-l+tkVCF1A$sjdYI7d z#17M4Qs^@3u@@~{iJy#r*R1x7RwO8+IDXb_L+>Us-C{<3Dyo?v3qdqzgFe zoB>qleBR$V#WmxLPPL5uJ^|-b$KMl1-{{cVS(_xHafwqf5qem%4HUJ~zr^T3?ojx( zw$G`Gs+{FFI*cc(@0lgfIz&m*gmDSN-YUg&qCVF8OTqrZU))E0J0U_g&dqdry4$mk ze3F~h4ba}A<2K%6|B>|-jT@Orbvs?GpbBF3+x=M2!~9=*Dboc{WNU#Z8op(TmA-PyECPTv-NIU?AgQ zSA|QU1v3bdTt}32-89CwGcp8}BQD??6f2ivbQ}C^0(~pR_?mGwyz(~$J3+7W{+}rg{ zO@rVZRkil7DoNOKlI&0#9-{YxP#M3d!rxmfcE=t`$>f&=(au?k&xn(5Rl%HSj~a<( zUU%Brf^^luF4<&*UHdQIz+RKJJv4Q%kvzTcEIUj?69LDsvJcN53je{N#`Rkp(RC{| z3^_1HH80%J0%v-8vJ=P$3m`uT$G!0GIK(Y6HC8FqdytP{&&mD$j$&LB;SZwnfF5~c z_6vZl`+>`70LS3`e{wM-4g^AoK?z0a=u0#j8f=sf4*7)1$sIM!ZcD`tzcn**{ z%l(Ub--#E91dJZsPCw(EH+~^M>|)FJ+`=Fp%i_qga%0qr43CVvz*FIlR`Q9Y>=g;g!2uqk$hA{pjo0bEj z>gy%(yT3i3=wt?aQV}PK30latYpZ^4^0pA9)Np^vIBok6 ze&Sbz>I0XWJ)oFn_Fkd@qh3GeX|b0n3`+8(LP`r|~VrQ0Wo zdY)NPtOG6I5@lhM(nNl8Ryx48`mgEiV!j!Hs6Bdu}9!pz3L2AA`0zvKVTh zam=&X6KJMT^NE?t0vr1oVk9!e#FB)89s*Vh9s&*4)uuAWQFBIM3%hrXj+r?x-Ipu6&BPA8wdPa$)uUTWn2NEfJm*`HQ#PIn40&xZg@a zLh}PcWMg%5d)4guk5_{Irj@D(#0@fpGBEeS?I~dXCc`zuu{14)37D>`TDYWR{h=C2 zbN3*2|AT;{jD`?JAI#$c`NXkB6)BA9FRjKvOK9;6U9A{_jt9#cM1MDqfpRTh|D^F$!D9lP1Z6NeBwyGdsv3^N!%|4{J`LgOE z?5OLq(r$mY2&Oh`8VR0=nZez5Ta5)8rR8sIPX;LbFs}HAkf^^q*_DQ8Su>~KvYetO zrYX!Eq363dQRC(aQwFSfD*HbELqkluw=v~E3mf2&Y!-6OMnfMOMxBWWThSg@@PXbg zTi8GuHEpyRFORK5O1a*&tXec}K&8Wgsc-pBvIM*3ioNPOF?Ik8MJzQCioVM2e+Y5? zNUh`vb9kXwX0dYd&Dt%KyfCeH7V6Zyxp(`qTu`M0n*Gxgc?U5R6$dFK<7w`6?&{r} zp%}zV=r^QWVVvtPjP);l^-VG+x4o;V#e7c3yB`Ecq=KZWa&sjkv=in^qW4)$IwW}$ zE<5T{|6PK^>>=9zGF(tONSDHSSw(o4G*X?qVwFr%ks#XKqs>4lrmcyjW(q^+m$0@p zy_NVh+Gm9K$Y$t{FeLPko}Py5E5msKZDQc|>{gL&~t~sMV`9<$dmhNsmqX$Ter(VIR0wot?-vi@lfcaws)m6A)DPG?Z2eXV0 zoC`s1!QmOOO`MZQoT!)x%^(ZbSzUU)jB=^90k&XsdqUSM8fiyzs`lF8NS(fIe)S0j zZQsiQszl0h;RpjxgXP(Q$-vPLxBWANmqQCoXvk6t3KRuki1lgIbbchGj=p!bLi{DX!Q+ikv?cNf-N583RR1PaukB6V52QPz_C z35)ecsDTPwfJRq+=sF0&H@0|f;}s~#w-;w6`*>NyCZrUs5`=lh;ij}{N9y)ay!TtX z&FO#xU>h$^CZkAuiFCqDEC3-rGF{o={M{T+(o~ zieKCrra;Qb43(E#(3LCWDcW;fK!vmI^~6_izWl21Zp#MnbIw>LoaE8U4H&2PO9(%m z2S#}X>CLc^1do7RQFvifzXOK^;}hT!$^vqdDhb*UNC9pXsS_K-`kVnzAp7*;znwOG z3`-r`IPo?RCHhEC>r{&@Bs4}eN?>&v23k4N(uA`&9?(cdURrlJS)~jF0zH&sps}xU zns07ehwl|ndvImv%_F75Zv)vuks)FX_uHRB8xX6CWI_=ev5H0iE(k#a@CFAj#*Lt4t%xfuk{8cLppIK45g8k7s1tjPkoijcU@QX( znZ)g8)7aS=08(t1x{gZF&k8<=BHyjzBAA7L-=-ooVXf8LuMX%DuW(p6eO>%?Me6hC zU}g;nRT8&nShZ=vJ1v6!W;d*6NJI~li%V1BJJPq?_F%ubjO%{I3J5%;`Fq#?Q}UPJ zWrzW$XzzbPL;z{1;pzEm*0xWIE{CZKH3LI$e&Nj6Jj?gbBXmiElv$1;?jWGXjbj<8 ze1eZ@7ev?rpI4?!I`E{60Dv1twV~S zzb{M%jD{FF4l4U`AR|wyiry%iz*Ng}QAfFmdYDl+EbBA6Xft%oLw=OmGhvd)$1X30@+-(N^d{@mWPCiU6;JehRp{B#|CA$k`OM3C$=6> z-U+72%Y@Hy_Nz@8_m4{YEO-h?4M%CoRiC|uOm7%j*zc$2qXGB!$~UzMT4ISuK4^Wo z1r1s}z?7&gpQ}qp0X20RGQu{@B{*nf9BU!WlIQ1YCxaUfcw!k4 z3l$i@VS{TtOpk~aX;r}?fOylY~s6nzq+vB@1iN>CAgGCz0TolQ_{ z++m`_(^Y^q?1$`ERGo~v+L`UYH?vP06QsDAAP*m(v*o~`xOUgP>JH{NKq_N!VKBlD zNG3l~5@$S1jMn9B8*eIWpRfM_$Vr^BEgYn~6fh@F3dWXrR^3g6QwA%}p=IkH?3A@W zN{PE*t!E8*xcKtGpycqp;{15Xbqi{EeorwD*MM z4TP+O14|8VIY%mXtN&20ciAJ0C6@V}AJT_}ri8--;(|uO5E=f^fMkBr@KnqhQpp@5 z_+6#IGEad1M+H;Ng_WD!M9)`Y=fFaOe&oQZxB^YC;kq8ebq z4m&(Wx^1$eEIMGaiCXgXMQ#y1nD}a56Ri_~(6E5Ic@kzA(TH`u%vgUYv{!wg_DF1P zYZsxQo`Fz#u?SG(`vxb3K(am8Z$XZ3lEXtaz4o#luC?4G=r|N(_S(PNcTQu2is&vx z=Jjx^s2H#~E1ofF)8k`C{vk-tatFCTFP<)@i&cz#SH#t3fcI|SF-;hOK-%=HQckIc z90|o+VarV(+`B|MZ$xGD(I0Jnw>E8Nh}{T2gH~gEm^Veo6<ZueqGJpZD?Acy5=$?JUX>=>rqO|m5B{G7Z99f`Ptfw_{m7Na0Fi)p-4(H3;Tl_e z&7&y@F_c3KC5S{g5g53;x(~?ky;T2V>UH&FMv)P11XQ@5H%_1@?Fx#G#C#1 ztM*mb)TgIET@0ZPWrbJt;Kt3_-X2^#8KhxiC!YX>!lC{2ls>@$a?8p0?BB9>`Q49T zCwa`_QM)8^S7aIt^Wo^A?TaN-%=h}S!86a^=F@3JuDDSP)lOW-KTh-k92-_0bjaN@H z3Gd9WpGS7Ymg^kkuJdU=>S98~C_)%6bXades8K!a5xZ)@h{NH1fFtkQIw#HNkH*a` ztRV3Vcg!gaac&?s*8F6Bvc5Bz=6wapKjRu?C+muFBd9kJEj^A|q?O}jr1u1HQ>=A` zuY`5Wn4}n}_egQKrI+4|pG*vN*icZRbYKPrPUGC{0x}fw<2MPB>_(@!i3$33Z#bWN zoP+TH^jQD6oUOcrdzH++Vrzg{dOC&fM+G+rl*r7lCd*I9tF&D@!Y3_*M4sT?vXeh_ zUFos4ogb7xn(fSobtCCo>x&nV55I?lMjD zeOexFa}%Bf%Eb|kqR;j4T$+8oF6EO>97Uyu@aIvyj-z@MuT>c-gR0K<99%jal!q9x zn1>n&*UsKb!(Kw+ax+JrUi1HHQqLOJx~+KfQVA`45S-RViH=OkrO_{ISgpAY597#A zn}m?YU(#Zw@hF0Do+TmcEn?#}i{-OHK2#>;Ig)MALzWu)dw= zn2FQ!2UKrgWXU@oe*|OrL3=ryq=FZEL>7QQKl}Wy36=-tQw%6c6oVA_licUw&jKYW zbmj~z#fqD)M8P;eG2`exI4DY3NW#hQjPrtN7(xVVQjDUo8lJnld1<;}DDx%blVOOw zWBswgn&1+75I0|N!gChbE1C#@V2KaF7Iv9*#X#qLSGPSG5!SEl{;qR@nFou6=AfIi zMAKr6rW1z{G=1cp${k0Ds)zzYMRS)gpv(Oc8X}XB($q(r2BxriR-=mZ*#W+Yaw=I% zt7SJNso;ry!Ml&MPjF#-i2NHHPnil&7LTAr*(y|<=?~LVC|!c0dHGR5PMXRc`R0wZ zLW%pcGKrxR;O6dvaB0S$p~2;UW!tL@%75prd4-jRu=f0OZd8YRFLuY#3FWuFpG7b; z5dU}HLSV>2O*#4=rKQlGpvenRO3Ny^Jwr)kbY(IHn77JdSPFbQI7^d<+{VTXz)u3OGdm*1btxJ{7`39!BzbbHtR(*(um{ zdJgLu^M>Y_UuJ5w@>$Pg6ZYs9+r%Y9)5rvksa!CDOgL6P&WUHow0mlYD%FI|65($yB_$mS*Fjdw- z8__krlG@q%C8L(&L_k70?(h8ZCS(f?gh!jo+lQ*P|Dqcgpa)YvJpl}UFm$o@WVR1e zLgC#ATt6?d>|8>kL+DyKN#QxD&5KQ53x65j|EH6a06YZZ7f4rv)E^ zyclyP?L(ZvYZ>(Eoh%vhdAL;(0-P)^)R@1&K-1HKMZmXJaoDmtQHs$q^&yWup}ziF zxlC|?`w=43&|)GHnfdC^zC`$#f#4-Fv= zA!dGIZD8HX7XLMvYD!6+CR@4w6XMBF>`z#*V3Q>A4fSQ zJ>@;c8mge5hrq%zu__&+_CMOJxHcX78+auj8&4-2*Nhk-zr^=94IZ>$0 zerqiSYX_?KrLKb7k?NjJo4uCc^~tUiQ~SiiGE@-jV&m%y()q#pldv;DSYW!JkCLa%B{*3%@SO_h?@D?<`n(5(KpfA*^l+Fe8+CKrJWQYXTc4^EglWTYTN6_&3! zjj6UR25KclUP@fDwwErJ4r|yR{EAjujerlt1xJ#XDl$8*R%n(9OUC|cFWHai{N`&R zG+ZXX^c8-r{h=I2Nr8Q01KulVMA-8!iUC-J^dGE0DAOG}>w3FdEQ^-YL9=*~tCl@C zJ?LdWJn7c-dkXrM*DlZWc9-=4b2YKyZF8^5hB>!Ezfjwa)8Xb53QH?1$Iy8{3x-E! z@Yn4f7|=JS4`zGbuj&u8r-Ux2?NzQ^Z~)4^3^5ln(D4nY>)HDe(V(~t`*C1*{haa& ztYPP_w{E?sf``CZa*=j?-ic%bRgxC?64Ctswu=+|8QJbTlBJesAU@QYa0hu@0$&7nwMq;k@lK26BW2h0RUL=u7?!~!lyAu` zn4d{2Ay+n_Ph0;i0W&s_*1SZ9#7P95uz&$>lGFMtX+18$I1f--e2G# zm~$%-+iocb@Z@`>jn{18k*_1gFy2$bX(!)(Pkcmf$HL{0ZZQ8{-aN3PK@S29@x!1a zqZ$su^kol5F)qrPo}D|&qH4nrKW;=Z6tT$EPTt>aSmNsyshtq0E3d`Lrt#t)CB{D` z7;KMMgz?wB=E(2OtQF}OXNK(xp6fv`(StZDR$Hn1nl~IxRL`fBN|VI6mG-92(sK%V z%&X|md`4RzSdvrL(;iW<)jCC?*S7?02Mtqk6iahRfX}~2RVGgzyL_pdU+-w*`D6E& zTQQc!s%6hZ12-!6PYW0r+Ode}dB4wo?%cvD175Vtno_XzW*$oKc?37khazXln=|we~T=5~~;1pRUu{(*2$f9S+Vo z`?noD1>9T&UzioKR7fXlS-t}6ovLrx%-#~pD8Y(TW3a=_Rlk{=Pja^hLZct83Dvvc z4b=}k)%iUsvi}@j4qPWuJ9Pa)Iff$f*BuXLOxO3=0CVkWaP^xk zTOM5KCwbZp)5LXpK&N#4UR8Op=Ok>DJW3$IMw?sf+46Jd4|llF z!)78_v7V)v#c)I}0l!jD>Rxy0-bqF7Esby|6<8vF#&1i7oYrF;mkDvqb=^htD`gD) z6<80vd1RC3{hY-hL@qaW{X_9rRDtT5M9}g)HPgFP- zIS7O-2Vsq)5XXY#0+^=Y8Oe}-`9bWn53TB+=%d_N#xayfr)H(L zUyEXuOP(uN*9vr zUMtjG9#7G{=%QdU#BK9A42Z36aH%ULsH0^>oJCGTLzfe_8nTqd!=xA!M&QTX$4QF| zM&T#a=7zcwc=RCc_cNh?Qdo^_uB!pq1-l%vjHgnniSdKvoIrXg249RN4g`V&eLrB4 z99qd7zG{1jCYicuS1ZN;JA3ijxm{ghSg>;4~!X>-LLr{!ux~3b4c?b@-k4VsGExz30w#gw0EF18CrjZRJ4eTaeRG^x|~w2g`Q> zKDq9~B*yA5`xn7bF)MupF}bsX=tHI7Hkp%8gnf5Z*af(rhM)l<%J+SHzt6oEyr@Rv z*+G;&jl5ubaO0xy6C_uampqGfi=aM5{BmEr1ax)3si;xu)w-veWlulMQVrb6V|v?o zd*Ax%0APodd<^sw{Xf~ytmLl*m1RF<9qAAuh2Wu0>8S_o zk(4bk{0l1P)wBS%{RY=$wL?S~i2jSF)Pj>5EOBr7KDzt(GnbG4Hb|jmPaoZXae_&m z%x4X#97(wEip!(f8x~Aez0CAT3uQ?xzhN9A13|1IGJ>NkMoMWPj9!8sR3j&pLwCOFilzuBago>ES=2*)w>^+OP@q)M}N|E#QqpX>vTbNLXLyOY~k+9+y@au}W zwRPmbvj@uvj(w@iWnpCP=fcqkEt@RqWLvy~B=Ds7t?3F$CpnZR)U--S0%zd)z$v#K zpbT&vSsqSXM5Mw<-PAwsL5a1V`wBeg)H?c(l3lLAI64yXlr*{)AB-jDr*8FRXdk32 zC7y4zE)U>r#4VkHX>bMfbOXjE)U47fgRH{?^s-D^a%rp5s1H(st~Ath*=q-qC)Hnj z=;$pWkz?W%;v3`vZbE{7D!v}Y!VbeOI0k!HLn9+?74^sDF3F!J#@h@HN80jNc6}~; z!>Gmfjz90sto9Cl9@6`UTOd7z#$*d2=dqo#k9_y>#P{LK=dD%k3bMBHsf5$qN7^CV(h(q z5b@RX;$?=eZjZOlqZd~p#OY1~Y`FNyDTq*9vsVU^)v1M-+t>Ft0yzg8mc;l-%xH~7 zqs0AJ3ZY-f0^ch}{-j#4+lEdICmtA-pBX=r%1e{ed!PseVS|Eg3m|0TXhr{?5tI#txLkTv+E0mFHk^~qiNa4WC&(+m+lGeg3eFb6$acVg}cPyS&xL-Pb zK!3Bjo5c-IvhOor5gf7SeK=w4(UN&huI|CloLJ^1Kl8EuQ0b&=Mw;uxd%ck9=R;{$ z3_Qygv;Gkg9&MKucmtMv6x*eB&v^Tg()gS5H>C-be{qn#RvxI!HuRfDkS5!l8nh;o zNnLE$t)B0hMNniLuT^?u`6io{7>5j}{>o08oQGb#1&J@ETiaB7#<6`ADDvZ(c>)<6&`tc{_FD_fjETN(G*J;28FBYY_y-Zy z7#VtK!<6Lb?LZ8aYLY)zUDJ#L6q#YhOfG3Hkb+F=h{@n}t6D-RpF@)u(;~&hO1KG; zJh2Qv;g8r~mu2F?(O>2$ex%(-Cq7u$jt}@2w5$mJp8ZYpVY(&iD!S;K{9t_h(Yn;p z3EH&$I(-}%DKn2Q=ikHsdj{AufUnQ`0{^WvHZ1h*EG^1F+_IMIRk0xd_@7_mx+OCH zn}U(3J$F~KA5w74h=EnUtMSo#nQ+VBBD{TgRF|VI_~tJIu;4bZ-89UQ)>{pykqcqZ zUf_2igRR3#iO<7c_fYiCRFMAsxvd-3QK{&eU-C7GNK<9AJh;>C;VlL37qU>KTb3f? ztDErTlVH+TwXD$t!|GX)Dm8lfKCPVO1R5SiJ2F{TuEZYJL6(xFt-kA<1X8)r_VIb4 zlDSH38jKTpobfHMOEPC5Z2vpgLWU+4Y1S;SdDS-|U?}gjL3bJhdP*{0XBg+zaLK*DB#07grcd>0YM{M=Bb$V6>9^cIwgpMZt${ z0p6J>a%0+q#CMDW&T=;XSY>PTx>J#BU5j3{R?hUhPg{hBvarfP z#xTD3#x$=u-_R*TTWF7{KiLqW)ssMoA3D_$eb=Gx)@2LGhKtYC2-+DP$jx|gplehJ)fa%)pb-7f%j?f)rGEvFBoaWzQhNt7QHdi09) zHs{`*4gFN`;V(x%dZt@F{jQ;o0M51Hbk*0>*^@xTty~%UlSZsyMeDZ&Y4`i5m}j^H zcRk{C%vZj|4>4z(Ulf{H7NBFOs%BICd^89&J(?J_^1AJDp`Cxc1WK2LY zPpK_BdPng>X6L``cP%4qi3v~?c--ofhoT$`!MTl%t`;<3t5NLy49MUqzt{sRjqJk2 zi)-cTK9&u<7xFNeHaRm<=_^((`KOZZ4JZ?mWM%zDb}NA)*TxZR12T8oFx}rM6)-!ftE?#s-j5p`+Hix)S+6bUs7xz(?Q}{4jCH( z#6la`1U2X}sZVDiYZ*{alC$IiF`4I6p>esIlSzrjc`b8^#%Bt94tx|$YXg1~`Bv~) z+OGsTXuqg{lUH1N?I0v=i_$ylebxV*rNVSCJiY{}h3(0P#Dt zk&O9M4jw7QgOGr5G;m+gFROWx(rvn+vj2 zE@LPY%_8jOzrH$L^sCdbz^`4kD7SdVHdH810rMBOqymX0X^E&|S{vM>sFSJtSUv<-_9kc?%`H>VY69u($n3F&< zzKjnzyGo34!VJO`BHXE;GZa&YU&-WC;hm?1W2aVrig`r@o#B~J^sqp3^PXpHpT5J~ zKyX8F@3D{?LQD`&J=~Jkyhz5*Q&njEnUL^Qe_%jK&BIDNZ$*eaOWwEIp0ZZo3SZKv zmL;MyPJ;b-$Bm%$w>bWs{qt~WTBPzTh}O`6!5;`AC}px6IaEywg$fOioGMLNZGe6N z@|Eg9&4Xb!?}FpW+!tEjH(y!R9lmH$Tzj5AC%g7+aMx3Tkd)xCBF9WqqmR>VyxWMn zhVNkVX)q*<_{%6TX}n|90B=Oz1|?rAT)VueN<*LI!OU{tp@yPap$+l3*#L>GXfSHh zIz|tEFJ^lV6?YyJUlSu5lakFo6mvoj9(V40zfcnRIzhM6o3o!kDXS`khJFG-y5ZRv zFJ#z4gCna8uZ7KQ3&9GT@MLo_EpBmnRu*cWzkrQWZJp6sB*Ghllo*#dsL9c=8{o8( zULi2G4IzUT3)4o8Z7!er33sj;#~ydvsF85(^x*%LtZ;Jz)@g|G$93$*(yoTT_cQ_EbBDs3YnktQ5kL$W}j1)g9u~%H=N(*}v-jF-t$W@34xcsBn8a4P^R$zR(wg}{h-S=+eZ{7MEi6ZOp~w*VQ|C70KyiZ5O1uVdp0D;hvyW*+PJx~w zN)VB`o}e(ZpgvJOQT?MiD``+U|hfZ8n` z=I$YFVYU}mS!cw%iu}s4iTX#4{?peLVF#Eis2{q^YTrMa6nk_S`f$y)`#YBVcA5W` zhFh9Z%M*X#cG_a=?nVl8UGdINTTd$;G}B|n;YxcE#-=~#ffYb3P?XvpArc4U?k5#4 z%@kCz#{DtMq`S&C@jX0;SlTRNfBkfx!Wx{HP;pVm#a=39^RfH674Fl7L{~fs#(Ao4 zpFupf0h>UW0Ny|5n?1f}LZ)htuPvc5p02u55>-To$68lR#L`l8w_@z{W;KdPD03`b zm68^Wm~67wd9xVT4hu^s(druJAUQ77j%n|rFErwOxmOz_yDHb@ zTW(faR~5vrVu2KVVoeOpbRoWlJ!BM4P!~Z9B%scjj42WvDiREOag#NqJ+v!>Fo3Yy zZE>ci>*Duvrh?x?gp{ce9uhp|oHFjBboSXvZ7{{7@a`vl&v3E(S&qY*b&Mj``N|}Y z_YRFOpFu;xmAI#^u!AYBbU_lqUMLk3W-JG8!=FbL!SPY9DH49t3-~h|C6r1liuWju z`oImmrr9+|;D%thTE=`eavWFder%|_jVk-B2>hVmg?VcL>?)HeM5dkz=&gV_zq#%& z8ucpZe&-*gc}4c|F)k%E=YHA4Z74%y{8*AVOotB}B4t}f0dIy8oCPsm&)#%CK4(@F zoXxTc{${kiH1s9?7cB+OZ+6)!)-RupS`Fnf$(4!la+`;jE|_-%yesV`{cwzM-%-zK z@ap2PQ?%RlwbFht`=sXt3gbsB)MOOOi!N)1P}6YJqi~pxmDlyn{>VNj`u{;{oQ;&`{39u0cjbQFp+vZN z#1bU2Z#JVgWN+7na8yz*ttK z`{!w`oNOoN={vokC)tF>2of#xhOl?w6mwcspwGtv^AJReCLyZn_TTl-zg@LZ2j;s! z)vLTtu`ZPm6b@t%vazQvmmscPio zcB=TX$qBMrNz$Tofm@{HdmmPq9m1?F+lu}6u=CMQ&v4wYumEVZcWnHsd&i-^UZwIA z!Rcubg-w;@7EoCxUD+%*CDVIbuBq^YB#u|zEijBt;8jCO28WRqBItVg1+||V0?VtS z-%nEHSDQ%CVo)k%JI1JejeqH2{8SszFF|ogefS~DRXE2K=Joi~89E8zwA`Vm8dpQK zagcv=29Vd%VS)O`#~5ImjMpaf)ps*!L7@qHY%DUDDsc!IVv4s+5Z?#zWPl>Ql{S9o z1B|a*?$O-H^-0(aHke4#E?qJ^ig`@6_Bzh*^4ZsrGmONlue=aks)y@YZK5#0w3yJn zxRbn(CTz>Q8zy$1=kOQD+SPK3E{4iElC!>>$3vSljIRdcs9ml3rD!@~aTJ1T3N#j7 zizqWsX2{4-#vUHjoGr#n_&)C_W*QSTPJkF6w`(nmPhamv_z66re!*9Rpe1Y{KmE_c z%!ZU`YC)lp6SQTbW9yul^D#(XEaK=QL`=xbQfEYHtp%@>VZ2MzuzUNtsI>^9rI{dE zFE4L=jOWjx{6AHtu?4tI8a+=*lvwm|@!tzRKi(bb-P`LN4*Rsz(J`_TmKu@Du4A2z zp#uX?NhX+XgdV^LIR^*5DLAS^;!+F91&{nCvd*!K2vi4`&%Hav5R-h#D4`7AGb=G9 z@kF$2C)Fe#zoE6A)rb}TzvoSY4nm1HWd*H3c?&u9fL2+Axc1>>%)A3pJn@y{l7ax^ z0*io<*eYzpDn&)B&WN2!z@MI2U?D0mb(v@08DSxLrm;7PLVZ;Sm6*7?H{&k2h6-a= zf5r%%GRF$R4Z1vn7H_#*`$+A~<~xyZ04nSp511BV>wd<4VBrMm(iTtL~a z3n5QpAVQ_E#Ps<7?ICZ}c!lBd-Z1&#O#KD9~tg;KzpFf zg5a^Q&@A&WDJx#N*T(!-)CpAVTLUlxGfm%ppr?ymxJk-S+{wl1)k|MTEC!t44*~Hg zUmWwDju(zBz3`vHBDtHJ7r#i?4AwOPPS*ogFV?N~ZM#le@I0r*lE{H%E`h7b>b zV4sb(JS z)_2nda%vWZ%~u587b7H#;Yex^7CA&C+4}1hzLm;Z@+M2JC)D8Z-5g@y_3aE*R5c7y z`?gH=`j89RCh`8>YekvM2sckeWLGE(Vy%SaE_U64=Wr{hgEX$ntTLQ`P<*5R3(5fY zQgS&YzqBNNu4mbk(c|X;xnZ%&hdxhSD)hQ2vfARpr`BEmJ+YsTLdz(6hq>WSP+^BC zGWhsfL*H6#eGjghevhLDhh+S^)`fE$L#*X}RRP#`y946mdwdi>zm@Law8qMDh-y=M5B0Zy|wG*s%0!+Qda z#`%>~6t1&G(4TU9|E+&w=nEGTIgE%}GKz3p6hD|uA|g{(4d%|fe5(HA^I%Z56D$r! z5%*ANRAPKh;nMY_;uT}RQpcXrb(<e%s}%Us-mU#@2e9g=E3Q`GhoTnq;{3l2QEU4GWix)G)>p|l6`%X>UkZ6#-rOE% z_h$lnxH!*Uqm`X0&-mG&%Vr5I<8UNPH$fLaiTuw`g;-%j>Cba@PQQ0quSl&h9;LoH zo;itXVkwK1PQ;!oZ)RNE;$%q!ZS~c{Y$D>ZcG<-6iD^1R6JKuxv{}A`Vu-Rlg~GKi z4$FBhHp=tI@+~Hk!deC0Yi=~4D)y{}dT=f5dO(x>7{!l2eS=-_;I52?1ejhNwd zq4W{9F!2Lm+@#BOJ&E$K|1IOw4R;v}fLpFGRn;au6+WOc>gNB~epGsoJ9RW&$5xsX=f{>Fr4f>R<^!kWA@ zn&pASEAu@(?ViB&xLAeOQvo$}mY)YI0Xl^CO@4Lzq}WyOE+@?DTyj*4r=hxCeh?sK zNG3mm7mc^3@;$uWHjWkAo?QF6Br0z0qAB%dHL~_!Idzy!3#Za0RhA%b9n@HXUtIzcl?KIl7pv>LH`CergH( zuC9AmGVveijf-CD!O;Q3^abD(j1pH@WHTvp1 zpz{WbNABJ$uK5eCX<+^l16)_$cj{cf^APhDw=F_>0q(@Oh!mFDS>FqqQkfubeoXQHgp`5>&NVEck#*tFm_ z?0$KJx?eo9#B@VYm_Nk$b~H%qp6Q2oJR2Lh*G@~==$o{cOkJf*>8r_$;f97A&Vsd@ zQ!DrKy0s;v@?mKtJCR6xXoip)T~`LZ+H)N+;l9&>BVWIG!+6q+K-F ztyWRY!f2JD46;c|^-^WS8XN`w1`*!I;bG1+qc2mO9{gv#b@ZiBhyvHN4ZvUq7?OA} zRbTK_3o+`XBT+mbpU4}GV;;)Ew5kG`Sl9ux{gB`fD3xFMlhRewPgZ3REa*O#H1DVn zO?StpxXBAbHHK#Ry*c1)U8gBL4aaYT+G2G;f=d<78AC$nAH#jD%7lF?T89%hUM+@? ztCoTbsJ!Zng}si!-}$Y?Rof*63e?NyDXH84xc(=Bo5!xtVg4gsbA#C|c?vFoK+)Os z?n7J(1qGs_Or?4B5pz5H@18bg+sM2Lah2 zw?4&B!+$8{c^+2jfnNfbYUiP^V>pKa#iW7RO+UwQxvr_kRw}<_1zox{k>Pp0I9Hi z4sW;T#X7)}L;DCp_P_UCh+a%MSOY5d1@_l&*Z#|d*(pe>qmhp)E(1}1J3;p*wn$9I zAnWHRi&%>hiM1#$*kU-dG;OnU=gGRg!1wtEU*!Gp)2y{G#D33k;egm-iY*o3e<{)g(cP^-|Su-}A<6_Yi^ zf=hNAL`3Vy%Rl^t*=>U@xmIMa&l@cfA#l04`K$wL_W=jojaV;M$N z08S+m4-|LX5{ZqMO>e zi1hDDSXla3(;=C^<6&Hq+*pX9%JO7|)eojy3IikPm*4N8g>d;vu?kvdOBny=5)N_i zQ@onX{WbY2ySz`d-qky_0WXxmKKk7*aa2ZPx)*pVcdTSBR$H5l?XD_vg z1l7gPf@WF7)MtRf^?%8L-@yM?*k4$xLP={YpM;3iPXiX%0@80=0QxE<@r?*Nz3jNzSfrw8OvIQ{ zkUc7eXN?`t0>vedl3N07w402*9(t;%F~ODVHQ*_P6{Hoe%XE8v3zj6KAiadWj^h#P ziLJ+!Ke?lb4f%Ik1tj**mFLs3t2`(j66}L=A*1E>!zYiexq?uq-K-L=s;L6`taZ5u zI~b|HctU7cb-b<9y0yA_NrVLv>o%rb@W;Z`>$Kfik7WUQ8k`ec(ERfR(A1DMYj$}2 zp}o3RZ@)y@>LCpi3u`!C1YOq{#-1aPux>uzz4{j&;3wCWu&KJpUeP;d)*guCc=Q?& zsY7LQ*({g*z+MAsdK5vjFvO`A)qSshv8_|7Xr>XRXXH)4zxV|)Y}J|&$W3=w>d8E0 zh9xG}(~-?kRiw`+(IT=6k~g=vS6{bsSI1R9Acq~BB5wlo;F?&wGlSpm3AkC}>GU&$ zlAQ_HMdvkLOuVpB`)khkLgXjfmMdWQ#-IeT5TtLX&|j$#wNbZ5VfgTFBR;aYvZ z)x-lNSjuA#Gmgulho2jdet7(#!7=l{FP%Rhp|gL^-0@P?```=pPAKNBXg|02K4^r`uF!jq@CducrK{-R?&#Q~CdKCzhTo#7$bzg&I z1gyQkQNHxcQ07ghWTA8mS*G_~a?e9a$VhahB@43h7=ZSUfhFFrt^AyBV>s{+$kQUs zI?`U;%xd=S6dU?U{@r`EbC`uP9v*y{?Wol?DU7)7puB3!zL&HER;pZsUyG?YC><=W z1?Aih&a|#x|Y~_L%`sv ziYpW$P0i;-?elzx6Dt_YtQR4ucuOl!OKFFQ;RO?P)f$mEGWdT$uQ`qToecbMAz;Bx zdo2`p9K>>1$VohUNnBu+7q*JD6rAp>88T@EdYcglKr2sw~olfj#uW< z#kHm?a7={N64Z{u4NuBVfdETz?!Lj_>WV0Vm#`=uGMBA)U8M?nv7oRL#E&((0q&bZ}FYNAt0{RpoG7^i@CvqSL*VJBZ%y7UibLIW>!L z&u|YAMN^2@qQw$J$r7X{cA{48?CbCdpO)qgv0x#2;wIF;*xcnI*Ado0cU;B%You0A zVC}0%?*EBJ0J**NfmgXASuv7GEaT}T5`Rn-u=R?Lu+Njdo_RYWY17Pk8fr{$U~7|j zmk0&ns`=gNj%5?wCeUp9~ao9Gd4kPxiRo zOQfMu&sS31-=t25q(}shbqn3HhXcR#Xevc2A0SGd!Gu7aC`F<-hcfO+=b@9gVqANGQH9TMX!IrylWd!e z;w7nug;_FN1*Jxi`D>yvl(Iom+ME|IwtxKvJluqoYy`NpGQ+08ishe;SAS|$iRGJZ zufaY(4CNwZr_n0>Qlo-ID{r^odv8;HuL#9s=j-p2Xg{QJHevyHySYBqNuqQJmarUJ zI)tZ%)gLFSM5`G^=ed_s`>FE1`3+YG334=BfVCUuXR+Sq#srys)JO1JalP%fyY4mh z<4nm2XCkjKNxwmLIiPL3o7@Tykv677o!hZYxa~O-p6Kw`=yWrzI;=#h<~v=}>d-w+ zoSb;S(pW|@KbTF36uLKGqe;PWR&t2_u6<-FTVdkSl4nMxPBT$cZc@@goL-`1E_zqEKR7I zhWvF7p0c?e@RY{ZUSJYzURB%okcq7CRTY!o*k6e^BT7DzFN_CxT>+fnT&C5qo>m5f z7c1HhgW%%g8j0;|6qxY#9Kvf}v`coJ-;Lg76!|%v!Pn<_y2DTYJcpX#khIh0=nJ43 z38C8rA5BgC z&f|nKuEnf4Ht||NjZG~ea?Ae=Bztp=#KLSuK)5!v+XuUJ$crYHlc|38 z6&w%Ji##9@+lEH?`%m-IraE9zO~T6?DAh8-_E1Pxb0RtdKE5!zINc=(jYL{_9X_Fj zG859!YS3K0_%S%y!Hd#C3)I_$$Uw6YaLgx2)?pTBVhKah4tZ$tQK%PocyPpxy#@Cw z@t$s)$Bsq?AK^yyM{X50H@i2&s(7mFYhLPbBcP&q)SpeXee+8Y&J-uX3VyU6)?FY% zJ4Aw=F0gUa;kgL7H{Q1VO44|o@m4qqDFd9~1g2!YH7gv%Bd=R3N^6j^#ne-4MA#`D zpFxdh0wO_^*ckJWt!`WK+Xw?XibvrB^BYc(Wi@_SP=eF3|1LvB4CrL-PTG4P`w}c+HYq=7dXt%}u%gIM z17Liv3v+KB_2}!P8i+gw7M_L3@$Y8EkdTs0lyo49R5Jg@(b081cggWp?Qef`?Fj9N zbVI&6_dmbS(89-iS)4_9HH63nwG+7PI~0tqai78(cdla2K})G%5HU6?2&jx<;E%Fe zl}=Xx;T#pS#Acw6D4(_qI!!FC1+IIv=Z&zCa%@W>p5+(K*oqU{>Wg3AN_p~zG@gB6g?%K<~+u+BoSvo)lNM}%yu z;98N!#M6-nank;od#u~EhoqQyT{tN(&3fFuk|)C zN%{C(_67Rp|K_@ymsjMv)5EW|w7x?Bu#3smCPjDr&M~~t$HqCEWtzq`+oZAg{Vxk( zVcpa%>doO!ht`A&bdtO;XTTvS@Bm!m>~SSgY7qs}GG)OBu^#VGl$bfmNohzmk9T99 z4cDWLHb2+E@6Z97sBe)}Y=Xtrp1q_zMuu$Sb|E#dBS~ zAYamU&MP($t%LL2_NpN_dYr` zn~CBNdAy!VB(AZDv53EjfsbZFu;h8v+MQ+oWN9aHssjpQnqHK5laR*_*q;~v+1M2Ud;0xPefHXjhR$A9GnRql$8L$(m+5`mRCCKCS z5Kv+N~G5y9em zJf7-Qo~sVR5(G#&`w+yAI2ruMUwbE!hL*UELm)}w&AKcx?XO=}clQ$E1QlI&bj{@b zhOdwiK`)!CHQ@dvP}1e8MP~`BT4QX}dzpmwZrO3F+0v5J#?!v#Te~5pedWGt6#Buu zLT7PgD;#~y!}aY%WtT#BT;A|gcbTrf+Y^Lpg5a^BJFkUQ3K4^y zWn=?7w&2-1&G2FBJO$Mi+gVgwt3rP0eX;$q3N*p0qI;fqVZq3%0q}OhIK8x_xg14m z#f9^TyO%hhtnU!Cof~hX@rZLJrfO;Qdbg=tb9W>jid?tLcfG}urrQ&l51*%(T%xN_ zmVJ33_z3B323!cR6TEG7=QuBI|60RXQW|hWlkLde2{Zs5Nig{c2?}mk&!DZmr6{n}+?r4wrWQNM;cV{*>exJyVY^o4TS+=5knS9N&(1kAA>o=mv zjl+HN+FnT?G-;9qAn`cmCrNf;V89jNPCu{x$iWH1}#D+Xo(Yuzx$lJ(3!nBKz3uDQH&>U$jOn~%r z>LfkH=fc0vUgfw`<%^1lX{?y$MB1->*_gxs5-Vm^|4M)h#IY4vD$_gsw7(Q+2?=7+ zRyNrjnAywvo(q?v>0?fh9tywci_1X;Bu^~VoX|%#!93?;kI>&KohXIRT&d**W}iTX zHNANr$%SO5i^&?K+9TgX%*W4@l`Ocj%u~c7uGqK5tA~k6F;P|ISyIJa5?YKU=Y`kr z z{@y*5Lh`j8SrHu(9cljUtnsw$NWae;={z4ml6&ACbwFQrC+3+sx^D#pZR@v~*nN;W zV7jds-5DBS!^J~d$~X6Z3v}iEF}E$g7DX(+=7l!h<H$PIWM9ueoK!nZ=agkZtNpjeOqsRf^w@nC_!auu-B06Tmu@A&v56x2u{09)V# z5|A9k(kHaiO4CDb_YF|R^LVTqYYurYq=|qI2mM9<6=1%kP4z|;v0lm#^j1gwh{olS zi@e6YiZ&ae+f)7+3RjjipMhG6d6I4mcrKZ*SF=Fg@IU9}lKbAmb}D1d*=8e>5Qt6E z1NgdL1Siou%6Ahtobh>h0(IX=C-6mv=bq&VO)8TPvn;ms;6wsNN+~=?+&@&|9X$Z; zc;|s%A45b1#sJ|17gPx`M+2}kY!nO1bR-?KLRc;$$6+4 zBqCDCIw#>fotb2J?U%gog1Bau#KGfB1yMC;4YW7R8GerwG79iqaKrmaz|?15T~ z4p${MJ---#>qX-jhSCUAMqjxw`0>hn-RHdJ^P%UMSMK(mr3LP8n}cZ0tWrCbGl=>~ z#HxY`_9ShieZNqV{wW7SGLjG?ru@aLAwJ&Aej2ycT5h#*6O#V?{gdgWr~n6-p6Qjy zRW%UGgX1?J+de~?zJ(Fe?zdc8L}hlLCG#GR&B>T=NGa8+SrkYaD2p0@WHTJDrPf=A zV)?%keDy$8Syb!L)IYx;>ITutC)w$ic)KIyI4U6(*Y6m2L9UrD>;7@TS3h0579sO` ztd^Z9-o49_k#eVk?f0mc8QK_S!-FwY2h44=fk=59t}&IOCUx7F^}f}MKXvu8d}f9s z7LtIbf?1UK7%XVxn`3pINI4}?wY0Np7DSB7fxx7`u!OU3Fwyhi@CVOah`4ibw6>6& zkWIbJXX`}`n1Cia+87!~*m}%oyX++JwW)N)pO1U*)HkH;2dT6bUXHMP%6LBA%|;R* zVbstA9ohOeM>+0?HF2k36BLhjP=g8Pqkw_V(t8w`$lE(2M* ze*H7M%|&MfJ)9zpXa$p_LpW_~pSd={#Y3VG7~~j$S4v8tz^AWD{0LV!5cKWnx7BYe zC>ob?va%$CJAcUvT^}`4FCP<3T%>|{Lc*6;XgA{J!)4h|T%Vn&xv2EW`HG;YV-T(X z!QAPbc3bUMe_K0@n29A>os}4(%>3VDE3%q?HdZrz9;Q<}*sBVSkI^P)zY!C9k0Gf8 zyOw@W$(5~`&7|^)!eI{32D0q^`~LbW>)Q(}aP2PbF<^w_>i76JH|fH~vbv9oGtG)? zf_71NxzyLUlQ}G&eJx*KADid4iHkHP7HrB!?ZY_AU3iBYMeF_vwvP8BY&B9S4j6mh zwU2S^5oXve=+L$)+n>F@?UwzS;uV^aetqmP&jo47l;4`0V&T-Iqi8Dk6@MG$YwrT~ zms>Og1I-I7_TBb)Dsz$~xer!IF~AC5ZFp_zf;yJ8D_UA-3Chf;PxR|GhPgjz_;zvCWpr-uSKNNq9VNZ4ONa_fQ6k z4mt-W$EXC?_>)7)*S!SUnYydZ>Z^m0>EZf8D`)0c9S@q{bFJ2*;#>sHed5~xqj3MP z8rG$0dGf~a`A3V_O_0PWZxDJ4R67bITdtzY2)g;wV{?Ifh;sIuXI-TeC zxfXh?pPK-uXJ--BcPr19cn^y+mV`kt2ACC7t)nHUhLQg${^j}*~h%~u;1qG^KIch&^k~BR&+Uh2Y1GL`^?G0eBkPLZREEt*}&}e zmyidLyM9_r9_9UKwjus|`L_=tYO1p0{4*^*7uM&fH+f^oj}*T9-<{;M5)T)>o_-E+ zOmifaX>~6P4wdT=Cx(zlo4;-36&(wXVP829d$%HrYvp(JGQ(*W1!~iVA0*uvi;m~o z0X}DPt>ev8yCy7H4t#K&(tR4)+jeqI;kse+d3E^8z`{Bx2w~)4Sk%7uz`~L@8tsdv z0eUW93o^Fb5SoZ?H^}{x7F%t!$ENmp)^e}rK(Xn{B!wYTOH0tJG*(>ry}MX~goA3F zctQ*7t#W3X<2%W|kzg)u;gY4U=kdPs6GEn1;+cA(D6D~dWV0*tS13mAVs#20*Q=cJ{&J-msu{djY(UjK^C?ABG`vRSCGE~ohWdcS z_K6lNulCgdhU?tb;%wvA;0y=+juVZq$v)pJvv`Lmy=i?c8X zj%4+fAH3nyl~-x#Z(g7J`*&Ckzlb>3N>vHaC+Jb0CB)*Q1TO$B)>LaFi1?JMrX$|8*3 z0uJ9?}P@+!-Le zBIM^kPiNvy;SAEt4xEQwz1z~S9bm6B^1BXe3h*-m;;W)-YFmC)&9K9e37rWS9qX2^ zlE;;b6P}Iv2*tOcJWWb-zi3PwEMuxZc0-unhY5fDb37YTc`|Q>1{As&AFl?#BAZ&R zwY?Ang0xLH$pgW0F{t!|gsz+jaW6>Hg7vN42b>9&e~A3wgEYllz`4=OMFcO-v(NIS zv8G4A=wMJe=!ir5@XKtZ{}42_hWp02RoFlKoRN&-%D3Ej5hkH@6GE5OitI&%C1clO2c zahhwOd+Yc*(D2$Nn2W<&@LbL2@MX!kj>nhbliej`L$~=GN%V(p1lK%AEKr8(E293i zUo!Jw*?&4O^4HQGKSG#?sa^9R;_PVyF6*zonPLYIfY&xdc}K9;seKTsh7p=pwH1h` ztsv$3T0P`6wd?L?MCWQ5_eZYcG4iqOPT#VP%*hDh)u#*O*bnUAWRcYzQA?e7zX_#9 z8J1}v%3JBB_9a6@Epsb8T@+!PF$^zd@-kPXb!BbaqukcbWST6UH<7ZD*qFe8n}|@9 z+&oan-9DX9?SyN#a$Ud0CZT|w`;q_3`kUJ25J)E-{Z?1w2;Rl7mz9)sn`e^vze_jQ ziV+u+inl+!l$9VqN615U&IbE&ypEIH*@@QF`Z3hf11whGt_HsWpPY&~91JHNZaPv8 zo*Xjc1PC zNjSAijv7lp|I{YZ_mOv|w19p01J*0hFWQ-b^0e|=#xb+e=X8b%nhFAsD;lvUd5Y#- zezk}Pm`9Hti?ri$^S`D`84;W_iIx)nB|BpR!udclBUQviv~Ho@EVku^>WJOSCN;Vv zvSY|RwNLBn>1~$SSa~{F)oZfFZuC>RJz`Q*HaGf7Q9762Z3dS5jY3>X_VD$$Z=~L4 zCk+TA#f_q=nTn~YXNKfu#+VfthC@aVDujjuwP$cX@-6CqbO?e{{5EMW`;8_`X`Xsc zrke=m&nx*Xq2hk`=!f8;`_DQ6vKAynb!McC3=8d_snfqA?k$q)xp`%98;JR1Y)1n> zp>@RZRMjEHeaWd%R$r@Mv4Sp9x$4Ckz2W6=wvYNwAA{2jK9Gu@%ve7kHnP(|a6WY& zM85eDfExB7zdu69P3^>2x=?c>zUT+7Y=#Kk3nlUM;8&JnLM3+cpDzNkL!rvJJt?A@ zVLe&e8|wTi+QgQaa*sJL{l)^%_@Wf6`YpfiFP%oi^Y*_i-)<{5v0aQ>QWQTUxenm{ z2<3h5Ifn^n;3lQW!R#m#(KX*ytO0mAr&lhuzoB%wF4~XOs#XmB*jGJWo@CR~88~(1 zv^{li6ifxD%|RS6+=M*TF(b|ZxwnoC<5N;XirYb0pi(v^YG0O+tci><6b@F4em|D~ z2n${9Bx~Li7SIBWo5M&Fki{uJZI%I>ToU@mF z8R#_m#F_xP(DKDd0E~xl?c$3W?TW{UOf?gFDe$;?msK@RhGTS6NN{X$o4z=>_Tax= z*Zg4JhLWN8tr{M4l#`XB$J9zQ6$h)1Rdx+&KgE<}!g1$chFddBb`9u ze#`#si}L*#fUJK4O3eiQbfBdNJJ(;{dm;4uM%-}heM7n1=b=R-l#=2JM6+?fbtvPto3Xbop zB!rrLWUhOWB`fezDr?K4+eerlgBs(9{dFo_la0#4%(1ox_<&;}nRm8;E;@X)b$J`h zyX?2+=tn5HEX9{_38OV}6a9s<0>IKX7Ij{)RE#qLP1X_@E)}}l8Nu!tpf4HN@ zNL{p`#d|+4+3scj;-F+!hi!gZZSqT=-LQIM?2+TC2}bPdzCW+Wv$&rLWYyOY*knPz zgnxf?#Kzi4dbP{QAlTdrIul2y&+@5oF>N=>veNOG=+)IPf{+45*#}xA# zkLDsBRRdJc+CCJHpzM0qBC{1%c}uGvMS(-O{%&|q=jjCPrFw8Qa)Mpa0y_*RLY)tb zPj2r}KZg8S!`@XzBZUjgKe|xGBs|LO*;2>Q#knR#kS|lZi5S|sV^k&TMgNUJTG|Ru z0?1YOen$9lFWGnw7t`g!SeDZ^-d~<+_V}J>LTpl_x=92+aHp0secCt|rPg{rYAyG4 z_&Fb&*3Hs>1fk|FJ7vuo`aahVjI)4mY}L}Vqs?-&M5TgBDaW^>Ti>B(HlMuTMBo?i zOi$Wo`zX3O2HzJSVX4!oub6b6*);U|y8(&8Dsq&PEF>g60FaT7FdL%rko3kpnT~0j zGt_uDb^?y<@>kA-%B{3%YOxTX#_$UV1f?ydkhX^&8wXe~ZB5yq<8f=2d^lGD`hku_ z2BJDsub%TUiJ3fnH|}?(qMRNvsF&FDx=Pr$y>}Wjo2E^{cdt{8IjZD?ao=!y{S+@R z>p8wd#WRV1=dfQg>jl*O;u7dPqr!~8>OJmuGDR372pzmjp}C(juv-AVRHETHLLE;y z>t8#Y?AWGYQ@7C&^_FQQ^+|SS_V957FGX1=z*5XBeE`<>sW(L|Gc3wREP4Guy)=Rp zP!L2cqc77_+um8z7Kdym8Isu{A>D)BOg{W?T<8D9iWNh}wQ2n>L$0c$+;mw}iar>B zsPjC~j-~2AfuacD-Cy_enS>=b>Kkf_O>Lq;T%P_?*w3wQXfAJ*3%Iq!B zWTe)1e0lW9UFJ@O=3?{g>Hl#9?(tU6@s%OinC+|1j4rw6RtidFj0w6vW~$_6IQe7j z!XJ;-_%EjOf6&lrPMR_0-P<$gwdCUglCxP30N^45tYo`gn8X*PRY6CNy%KSNSGxr_ zK6E@K$qqb2ZA}}x4Y-FRY8qPL2Fld#cS)_a2*1p} z7(*9(UK5Xu`Ag=U+)i`(C_gi~VTo~Q>Oei7dh}qPLe?oc-fhDDVo8>lUQ*!AU3OKy zXkglJo(^ovIOejVd92Q@#7Q5jzb4grcuhl^OW1%K=>hxQ%>(QzEnsbc{D#Vx`5C>1SHTymiQc zPF+V78f)>Sp_a6T>d|jdP!o-Cvd5jmaS|q-FarjiFH{29)}b@)gI1)4_XrOB5{gun zI$_LeMXfz@E0wxmB1E-jyu6usX7U?aPVd+3BPMsWA*(y1Z~R_7sr$uvWZ{7jDEvhvUqmHVp7oGfd+$oQcmh*G@yb9Z!>JFHC`ckR^ZiHO z?O9$IrA1eSEXFAtwzpMVf}hgbfah_l(W0LnG0C~EhKu+-Ka#JfZs;M! z6u9;NtlNIMk{FH^8JcwLFdmeazV_O~sRp1tB?t*74ESNxI>O&Ph$Z zHa*vRYd8M*$FBn8LcOD%j-0a_=Zj!q_0cEq9iuP)T~JB--m z7e>N2e0@kC?4dW?SzBo=gjbw;aRZvQ*+OL_%!EiM*~&xFdD-T$_6Gh%<2aY(kdV;R zhiT@5B4q(;e7g24UhAt|BJ;Ph49^&HuLfwhG#-<@Tfr&Q*&oV6*QQ`|vytQKWoHW9 z7P@~<97CGG;R}CoY-|H(fBAr76rN2wZWQedu5wBKR8Mn_5K((IEAO!V#XLSp0fa*f zvQdCAy)iz?v_TmU)1{wIxIM;4U+n6tKmWEPa}c4v@v#O#unTL$61q<#`g}%QHt(SZ zV;qG`lJTDy$68~DF*BHO^3K>ImV#9uUFwKbTxzBEEC(-5=bZfJWv!pu%~3o1gjFu6 zMyJ|a{OEIeZ@Jx&gmtMuoN|Jofu&WjH6>uuO<1bEOnCDre{1-e#6epVusgi{sb2GM zh|OwLq}hlTBB%%et~x^$GE8%_B=r&qz|l-(%v|~~f74feo8L=AH>tqv$yQ1=5#+I6 z_0_B@3fU2DF036>Xgv3)+YIXk>z1l;LUp6r(hDjTNQ<5)ZA)jNpzQy$0BxOK{m-S8 zuEgmZZZDQP)Heb+mVu0S7udTU6+w*-#m<^)Gs0 zqGGO%94rwE5<$93h!OYYP76pB#Rd_O0%XrVw-+@ z`3I?feelrp-#2Ft0K#uvZXKh4`?dPAn+5A@3`53x%bIluFq$CQ3#LC~vg1*uGGkpK z!l_n~R67D?7U>Uu0$iq#RYXjIp=AF%tBl5m(OH6n8{;*hoBmFh4vPDrA37LLb$4DL zi>fkSzSxTiG92`LsqB#_i~gxgI#~{`RG80H1AgB2h_!}ekW1%migi5&koHD^@vMbw z!auBydl7SFgB1}^P8*D3(=@3}aP8Ze7K*T2h`?n~X+BEbpa^A`QK*R2 zg?LwO6syG1%Z1ZIx1(XB!}qo8D1Jdb!%idTh7 z4@!iI3e-Jtno-O^lxNl`HuEdY9+ObihZM(VLX@5$*7axP{3e;G*c5U4W@aBxC;r>H z_K)j+RO`9dOxC%;=XYKfb*uK&rF~%j{&I!XV`znR?VXulmEPFiRT}|?BMXcV6r6~F5Y#-rTOnGzm{Ti2O6p@I2vp@(LLN$9Sgn2+z@}!N6FQ+BVfjgTY-`PyYNq{0pxqdr8 z3z&Fc<0oYo5fR$5%@_b$Wc{j}^=g(cdVR+5ZM!pQUT4meK zh`aNqXPfm4W4ld3JVO@LtnUKFRkj zpBSWuQj{*S4Mq(pQ;lv{;UD+hrCLsaCY(UKI9p2KkL;&wcKOk*qW!0mUh;!FNCVcx zIi20K{5i=XeuQ}MZOA_qatlFu<{}$iKppCN^Wz;%Jf&NI7Ij3AB6vl(mB~ z521z}ML8>slhUZB@Lh@0kC%HB?V><<;!&k8T=cpi5zoL*nxxoYTp{v+$% zzvJ7)aBLJ(gWQ$DjvBPjK^+2b*EC#>Nr~0ZiTyNeZ~OHo{sbu*R8Vl=+Wc;|Y2{4Q z%OS-P_&Wk!*OSVkq2O>Qc3Fc(n;~C~^Cnx1q~Ef+k0-J?Go93Q4i^BonhRaEG} zYa+iOa7xh@*~G}_qnFUI7k&2Hq^aRv=+&h5DsK33ytUQ?lTsTA^e^O(gvl&Y%``1_ zB1#;?RKm=MK8^aLPmSBZl%A}HokAbUd^&bTg?Qy~=ktn?c`sUSjS&-~ zw-4z&ct={vY9>Nzaou+Mh;1(K&-GOyE9x(MU5iqBD_S|584O{p-y+NfKQi}%HIysc zD?fNO1nYAwaAY5EM?+4+NapPPJ0*F-V;9x=g^tn|PrOo*d#%ZPdywFx#i(rLEBB|v zHx-8U8P*W*NJjbCDUx)hL;GO!MM~B}1B7l2?@8ag7BwzDl*$v<5@c+2wPn*``XJj6 zn17ca75a9Bz)i8&l^DVl2kd1Q`BAs+hyS{uZhUV@huEjLc*&pDPd^7=F>vh2gvBDyrOcMu}=J+27W-ryr7aHE8jB7 zAb`D}2tq^05Qt-IIoEI1+b_UPP$WiilcXNJ( z`sQC#CV4-w`po^-BZ>j3?1XkTnLkM>%p8(kVSDoP9c9RagpRLaJ$oUfly9U5UeO->$ zD-(|v05kb|&ef%iue2Kajs^J$1mj^63wfsW>;5?O^&86@ul;GaLX8#g>BC2Bb#UxV zo{N@gM%B^xd{L)bA-vtNA(A4ZFPQ=LdO1aXDCyi6waj5oCQ*Q_iGT%hjeeY`de@U> z;i#3&J?+o9&A^uljPmzq&aTZS;+)%Ko~rG}_o zGr27zbv{I}Az|eiG777W)O!U6ct%gCv>G6t8gtJ6L#le}904NmwWtD@a;lWjryzS@ z-%lIbj|1?#8Lls*?}VN(_yV7N7BZ|^kP}%tH{z6bq+Qmuas)~Id+B~PNS zQHg3o_OlXN+fU_12skcwJLBB)P%+p~(k}Q0tcmU+6L=GIMWR4$x_MOV^qi282lHuj zjwmdwXL22=r_y~vGTd?vbfOxc$bs!?-(X~{aj`&8K7h zUja34*MFMv+-t`0%;d!clt=aS$>p_$rnquo#y=bT6aKFd;Ytg38jv+Kbh{$P+x(1H z&HpAO(YC~$@OC!xdHXHcag$_3G~Xz}t%iZzYy=xhn5m8E9npX;r);<0oBN!WqMAkk z#Hp^F<(A>TrtXH>_PsZM9eT+fa*|&hbeVgC5;WYqixJVEls+cLJblrFWJswe_T`_} z2j2jL=8I1Ty7N=9v(7D{3gHXpv#cpLMGHCDPt^ZF9oH-jM?tm~vNIslw8cu;L|gR@ z_cKdQA#@Pe44M#jP%~9ZVT;L`bQ+pZ%P~vJH1B?s=#L*%%tYvF`g}(ooAqoIISp94 zz@OBHZ`J8Les)60y6MB#S7`LR2;=FEr;9M3BDogs{%1m1PATFx_-dNXav#)(7cJHs zn#Rbbm>|XD?s(BWEm>Fym_NJ_CI3|ji31fIEZUVst$-kqg1~*5I`)@62fg?JJm-B2 zd1Rh)y~mu~MMdA>8>~Ek8?B7}!o!f5>O{twWa6N<=W;ow3%ECR%s;G*>XhC}<#Gz{^G;!Emt6?PUom4B@1HE+?TiCJM~W*JWF zy3X~Nw3Q4a)|CwJi*^_~Z>kIl3_oN=3KDaH9;lyx-ViT$gN)qKsip;NnC$9Tax^T` zdfBSkq%8hsge;<4kUX7)l{rW~zC2!ql=@nHoCf?`<(k|JUzyWayu?vE{3{EbD+idf zLo3Gq81O~*IF2wEV2~Tq!?bx1{j%-u4j!=A1K67c`1K#O7E!KL%2K7OW>X$yXC~ch z>_SpL+&#(O6aZ@)EZv-z69qlO@cQ3FY4{&ys_wnO?CrD7+X0;3%t|Qmjil$td%hpc zaUN6w%Yg~qKlGQLY05UQGZsPJNvt72Zp8IP-JPOH53*uNn>=IVWrGh=*uk;T;HH19 z%!(cKkhk@kZI*k^PA-*H?AkEVDdRR5u%dbWL!0=ca98b*x9yjF1%Xu}#WTMg-zWN* zI6s8;DX9`R^M?4$&_>a#So4$s{#~GWe+9m_pJRf0lkd?wAYO&L8CFgxQ1!J|;wGpA zJNW{5T8cI1ZBb?sSVGXJ-4*dkA;Gmxq#z>$gaPSL3)1dJCPyie(j+Z{{ZSgBr(D!7 zjy>VhufE%g7C1cjQR;+{CcDFo!p~M z0f1jbSBwybFhB1B3KMdTMEoZsa@|7;L(sW2BUberzG<`MS9^6 z0Gd`O&XX;(c}cUX&*-Dfupw4aeeW=EbHNdNF!AoqpuE3M7QZyJHaI7PC}Ey0_LMgh;m3-tFfz zC=@QhNqNZBla8}hhp~>c-q?xd5VApvZ_R2y2YX)^_`xa&jH=zk-`;ETz}W;)1a9>1 z{4%=3y?Jjpm{R#8>N4_Z7|mQA47_?DpI$Y-0~$#ViE{a+H_y;`-~@BZw*k!;uf)!c za?aJl8J6TUV+Zk0H4z< zyB3JS;}zK%)})SBfASg|F&^n|Zn(ujN!|Kk0toYYGv)sA%cx(hHq;`!n4Yf79(`!( z@x5gtAk9)5)+5d02j#bjt#Z7>n7BgOJ>98W+W+m2FyuMC4dYIGI>bd-jkE|0DRz(KHJ_DKj5sS8@pq?=+)!bSP0;rs?BXYKSd$Mi^um!P+3jpdQ7wa6e`2 zaAWqp=4R8sWX9K9uImgDIAl;to5F%j>9k`7<&Wx~+Y4xm{U*7~QKXStODBr?i`v+; zshU+*XcS?@UVic6jD6MC`2UT2gh|mz@n`hZ!ISQGZZTnnQTZX<-KkUu1>*pN-lhE9 zx5tZPd)E3BGOL}Ed$_TfmiUb<+_}x8XlDXMNANeF7xja`TQ8aI@#Eu_^a7)gS7<2? zZ0*F{kWKFk@fVIo2_ysIMrByfAe-jq*UYo~a(^0nQ>9X3JIv$2xcBY5&UN%WNgFir1Y2aF~|$DN4&oPSLfN%)RwBlEt2u4+E)pj zD)SH03&3hG;|~~&ataM`XQs|`m{laT<~k2d3g+$i3tUl)`<=JP@^83W^pGtCNviig zEV98yf$x2t)I3yjW&6Y?0Ml`UrrZHvjLQpz=)j{zKAQauxBPubWroU42v5w%6Uy4jG8vAmAu$lS+@c zSN?-$DaAi?gtlLn!K!bmyX(`Ml=KM0lD%7R6`wWoASN}j+?6HwzRAW%vxQ2%KQ^AS zZiW`iVR zvlBcmFX21L^ghBBZCQbQc_GLtK8`OXMLl3YbXa5|Vi*<)DZS2kvefWRjo8xl2=TgSCf|Eg}+R^d)1wuYYZVTqo>Hr|xZ%9n5A z^I43#~r=VfdEwt zTYPX^RLuj?M`x^5;dByH3OFgsMCGGv6FoxOPgs$PF#@j5>ad>Zh>@HAK$@>g+%g;S zZWnB>bcNiKJwpHV8yooOHj&3Ox50Mq%FyI8uidHm;JBb*G%^fomZc9%>sqq1ms#^;hY(F4XW!_ zU~&BF=Xc~cr6*)L1lhJqH-5|QJt?}|wHV=16553i9f{a`0_01a5Z3=J4~yK!gf>RU zUDA%c(9mfcX(q!$`EQ&{*w(=bKgZ94{_lS_SyUgGzB3gE83}gd(&7wQsqX|Nezlq{ z0#^tb_QKL&F1X)W3yQZb#f*Np73V|us_4DY0dR?`L+D?5afTMF}crL zK3~s8dOLGwBX4%~Kpbi1el@pAEG-DDOCKj-Yb<4{dnqD|x{gWaSA?S+#iG!Xof8QB z`Q?9yhGH3?n{Jmg-Cl$}lUlYfX&ED>oSII=0SUeeiYU_$Q%dS0=p^1dyXmBlKW=}m z53=-p@$2Zg@7KENI%yEWb<)4QJ0nA~GLppTe9SDLL0u) z8L?cVc>k51f}3L@h81HTZ$$K?SDY(Opi#ZTgmbEX%DVb;G!hon_Lell$xKv%;`&@}6$Z?H0j%=r+(Wu6?s(USk3ML87(nU>>3kzLHI5f!dKeFI zU~q+6k;1~KSuA7E1Lpu)-dJN zWX^Zrrw^wNXDWOFzgDF5w^zAhRH+Zm4N8tq>fZD!`Q9sCTdVL<)0$vFY<+nfCs+C!Us1XLlG8Y;46iCd?sTz~EC+VEnXi%fm@-~hDBV_ila~pnb7Zsm}Hx`uLq`MC6Cy8r!vsH)aL8xisbG z1C?2oW}92v&EiVa;$0&%cxhl$IyHT@8xiq~1F;2i*w)k|Xo?p_3nW^E@x);f2ZrUm zmdhG&Ar#Xq5rNa*2A!>>spK#$m#=V#G)j8+3 z0&f~m+XTRCgZ!_vQZ9Q7CVA(ozDIus>fpJYZ7@JvLaw6LLH8z_-O|DKgimBI?dIP^ zsvKh?j3#e{-IQRs!BFI5i$it!2}~cn^)U>+qzTyp#*=K#dXbOvcPQT$&_|0l#Pe<* zsJ#yL;1k@IBE5R9m?r3h1vVkwTzBK9=;v2JHSlIg#{6R{jpv?&sc#2fS!Mgb+x?)c z4te9?|E!j=lF_V*KB7j;?AmWDbss`FUX@8sj@-GYJ^xOxs797UE(Pr})E!5XLe)+} zMLWwTD}9ZPfrvF>McR>i0h|NZn%C5&4(m=fvHeI*G|nik7G9HP7eB@NU&w|rUjyhQ zeYvKYx~ASG9vBZL4@pp|xqvy-GeyrlwT$mnVKia=s|=6y9yL83883Uv`+dP=-$lzF z=&q@di~zt6b8Jqy{&3I(Nt$?J0$lU^)4mF=wHg&>Qb_hiYCY8uS&hwm$yC;-s>aBr z`~6CFY0Bsn>nrqpponu!@y7{iJbxeC{BkHEijkn()}MgSSYB1;Wh5WVyu$UWhUOw% zuam`3hnK_TH4MZO0V!~P5UL1*7`;_Rm0n@+$&fkV&>EWw@E>cdUMZ_V*LWL}dgTUf z4QDBlr(>xw^@lg-LT;BZb#@kgvFl0!9%5T-T?6AM)~_woDj{X8#zy{WOlCH+vu|9# z$cnYYhTL>&m>Ea!Qj6*D=MOJv*AISMd$PKxU6hXA1hR%!dH5V;fv=t8-Is4tzS%;k zL$xcRcnSZzZ!DbNilS6IpQ!FV5mX8!1{Gh|xZY1*GTb%fhP-;EUp>F``Rw{1Q>S>< zH5YlpHOQ!llQ~D8`t%y{fJ0GNfDWpbw4!*}16~yVhi^>^>#9}F^*^*g7rRKUAWmND z{lPC{@id4jK^6ZUSO;mSjjny&b(S~m+Hegh^Q7Q`wY+Ht)tp~nw1&P8U*E~Pmr%Vq$83$vnz}?g+O4RGw zo_6{z?4F0uVRI!%1jB^$Is3eH9K9bAChs&4d}C+cfYX44m>0%~5A=!XE76`E0PLrsZzH1CQ{9>!ENz{cF4#KMQs+$P9`WVBq(EQf zpKXvO`V7|1qKQr=F!9cf3;BcN`BfJu|9`9|1IE7?^U1s~ZoL{AyXV#A1zReaAM z@X-`6zXbl_C6{wj98voUIXs0R-a@Up=PO+IISMXwa^)DTJ%;f z2-jdk=sy$Mf1t>-fw7h<>DN}orMtfmvbrYZ!| zQoriaCaCO_B!)(9+}raNXih$osO9O%4CsNh8!KN}EO$J&QdliGOmXt&meUZe?YpaC z#V0O1fc>_h6E-xiAL>ao7l{f@lbDC8&U+;3a~-ETa23SE;GOwu?GM>0RVTt#f-kbl+xz6ovR|mbkZ?(B zSF~XpBTMV&G`(y9vftVuohIzClW%ZsJxaqRYg>hun>B*eov1aFC3@$|XtIuup65Q2 z`_L7>c|J-s8t}et&*ML7T`Je}o$o5^9DvvBjF2mPK1?v98JwGc+V`tPStv47NyiXY9pjXxbCzQfaj+E5#C%84sh`~DD z!zDwdd%tgS3QR+tPz0R0@&m7(AXyLk6GgxLm%0$#?E@5@S(h$w@ot?KjdY$wUS&?1 zPKk9b@3#{2&lXUj9uj@S-6MiXUFkSp^mG@JOy9uwpzcYMRN9N@< zt+*WtfSTXCx}(-fqruPrxC2g20bHmVcPiq#Lcv*#hPOH zD&>u4wkd|EVudm0REb9?-UX5{#X$(hIN%ekJ3RHbZPTc2&Yj|1RW&Iw2=i-2`s!e9 zsQPlekbrO(bE6hk)cnd`NlhQeOStNJ3Uxs`%W}h>_!ZnZf*nxa2>8i`*A7-4c><#HzV| z62>c1;$iiw>V^rw`4h5Y$ zZsSAV0>>v7Uh5($_&0vyj(iNA?_IG{uy2*O?#rN?}Z)Wb(*LPJaR?HTgn(rfc&;q%0$LFDPT>*eSL5IuMsY$A$TN`F$Yh z4if{F3L_rtlzT`$CKqPUM3C-%(tqXN2y4$z^lKg<3!gSKURDJH;DZcRed)tD?bOYp zqRjCrVbNDv;BVm3a%AB2_dL$@wR=wUoQJ`Nue><{P)##H3Ak#3s9IXg33o09PGCjT7|}l9}+#m8uSk=gU3r`5UhAfX7JI z{Fin6pFiJeo+Ac+t5?kIMVJ2Fqi*;- zov;qOQDM)=xi*!smAs^Ce=A*cJJeGWcF1-pCh0jebG>t<&b-s0Ig(rXxxZWHGizp> zms%)(;HIzhY`#ew>ZXElpQ!VX4Khs2;jZF06X_qBro8Znd(Zj9g~gXEk2&EFXmG8^ z#^S%5L=i2!v+4(dPo$T`Rtolc!)nSM$eEbbFDJus#d)jDb#;?7pVvqZJd@HE!Cs-H zu{0nK18SX_6peU}53>`P4rSd;NmYJipOIq`l7O+|K^~h*KGg8TXd`-?1X- zNVRe5GOTV)1hKI_z7p6(M<7!Q0coATS86RNAj@%EQIvO<+RR#z-kW47bpH~=6qj2R zVui}JDL(JF*!=v}qh{;J*J`(siI`ZFA?c#nAPZRA>IL5$`+HB4#4cdE$x%>U#tTX2 z&3--z9EIpeoM%Rfr95<#Z*eD-B64;hL~;(Lh@=nS&9mI(m*2@5tOXl9H>9^6xOQEu z6DgLs;wtnO#x7hg`HFb}*Nc9rn(2=$bi;9GyJmvNy0qL<5rr-aEHI}35?TXG-_Pn= zJ(bBp0jLA+(Z1Sg@S4lJ+th?>{gyK55?*Ip&ahtz^oAKzl1Zl6?lQ`_7sd|qrEtko zw|$SA{HV(q%Gylo6IzAJE*jE8YM*Tdwr?2}%C!?t7#}WJBEotei2-BtgN!Szix7Ta zl=|LO-5qLyr-waR`{`U_usfLyadr~;0A3))$~vC;I?Qo874s&*yiulc3(HDr2zJEe z?O0Fs!IU2!^wa3uYD5>4Bl4e>2VF6&NWPSQQXA%(mCrXGTGIzMr@(|4l2girQFYkD zuK`{!J2L8_E1&lsvb>MCk?K~7u@Rak2&i{_Ib1NCg&CBM5)PRPjar^_D@K(H#rB3i zU55@r^41*gIdM_)Z;&Xqts>}sW$uraly4M`MnP4MlpIEsbWBYn0M+!4i+i%7H6qn+ z?Ug%pKeNJO$W7|BU({LCE=3MyM-~~!`0~!Nm5jzyo}A92Kf1_#h#2H9{TAv>Hl1Co z8OQw6@H6MKarf&6uMq?J9@8=EgA(rY>O*wM6=Y%TL$84kPJMhjph(am&YaAq8Km%& z(97io?ORGt3`}wmIGL6KaoR4wu4Ixw+wc6YPT^;Z&1R1bG+}`i(@(!CCC%g^X?5Yl z2qSLhgE`~)R3Ep%U)@5gMzwL-r+MG8Weh$<9hPX3_kf_*UGxCZHf-J zIayR^C`9gi?~9sA@3i|9$!p16;UiYI-F~c`^K(HJ^dlVojLQ1qT7;JhJsJnSV>BQ$mN&3U;a zS%o3ku{r%7Paa7W@4`erdV6_mcYzs2Tsl#~;i}dq*3gY4BcEAwlcfc%TVzHWMUBwf zzd0ChvGG|PYwQjMMp8m|(79FL@z>n?iKFU~FhObL?UL_@)7s>#W`uGn4s-q6l+^Vd$m*`r%b(`$181-HCH<$w1Y z=Ip%$aQZ5w%$1mnA6G&(VzakmVSv#|BifW;lUpX-0Thko?kA~PH4m-Q-n z4@+tRDWF;4AdmuljX%B;;y?^>^6Tj=9DvNL2`s{jkedH$NkfpOmn>@7TPGbGqYX!Z zr#?EUHn)4(K7#LmXr6;5Kz=dr>0mK2uvI+!3h1ef+sz`pJ(Fi%Hom=f!H=TzuMcpj z^GkEa$=b`H9K~z)U(fC58t|x=u*6KyAI*VM{)P_3UQaG8^dh6=m`*tIO38dhNOWwq zBY@iTJ@Z|+r3l-pWNhH>+%)o__5I(TJgQ8~^XUP(8JkB6HmpV3z#SxR7m2Nzrc+9W zLTN|Yjw|2Azo>_)?Z3G@t|g-smb*qK3$Vv@(Y#>^V_sr1mzHZ12Sg(iJ`1F9tB~Bs zUofz_CV_-7aG+{nfZ4mdQ~o1+4@SPbEu6l(XwuQCKiZe%u9Xbf7*h99nyKpqZH&>d zZF4QEfDBH*V69!dxeurhzo|{#H9FfFi@KQR<{ydTl%`~)?4CcbJLlCS1D2vj+sZ|A zwV72u1)HMVy!1EwZD9;Ar$kP} z1oA<0G%ZqZy?5z&K6kU$Li)$w&_$(-F}ce!OsCPLuYIdoO}KW(`dnlLSA%Czj!Nq( zLgmY^s;q{v(0wZ!d=RkB{4DN>341TPTs8ehU^$o3w z>_hlhdtMvqyE3~Z2)lXMSKzxjD^V(;Kdis^ohQc z8fd7ivn^KALRYi-n2IUc@KXs+o@9J?${s)M30HTW|66<$?|^i~7l7FGo%FlSMy#}o zhs;!^DhnX-6`P!FjKE>7WCjYT;!McgY)WcRgxxH{?SV+>IR>Gy-1O7g ziOES|UPnnGZ-q3#>)Fq10rf%UvEP%KEa|%mMW8Q8P?`P0A~D~Yn2K7T1=e>TzV#IE zetP5;^r5R$*v%^g4IaGbB|C%F)EE@?qekG7OmPdu8Ao?HyBC$lr}~FeSpwBRTRix# zt92=_aP`+m4fNxDoa9BO0v^QRIi zry^{*OM|W81}YRGOV-VSd*SR9wNVR{=Ev;RD|5>rRX^y9&;9|;G?1BfHG`p8(g4*3 z*^*d|TMzfmIJA%{dSFKni;!a6= z{tktM!2EO0LH?3nx?Ky4iAJB5DDSe~NYaT|I);u$I;ZsjoL%9ZO?vdCa81&|Ct)7B z28(USIHgGhR&g-|v-GnqMDlEiAUmLT(uXpZk=sXcVI^;@r-&pfd567(C!||~3wpk- z>%9dJ|8ae|*VPlDvJ>_dJTdw!@W$L8V?Em2re1Dl4{!@TaG1&sC0Cq=4DGWO zhsdl>PpdM9Ti<=;2R|@BGLDl1-AbUJanvk+H+64CUW4hnliwXw2J^45C_q~Hj5)dQ ztT3jg&vD&s+%RG{4*on_`^K^<2sM^@De+Gh{%{d8Jq-%z#izqF(9X-3r>0K_(h|z%R40qf|*S>PUcT#Q*5o#Qbc2(

!r5xVaF(ifuytsipxy%?AM%qyw zkuf9sPX{blGyTGwK2WCd zU@D@|c+kM~?|iq{`tD{i_Q%%=@?>|qTpQ^k@_~Sj50eeAFMc_Cl2ue^-~6rR1W`Gx z4ET`S3NBlGt{3{`Ju6AycNeKs#6J6@F35xW#I;ztmsDjkQMVs4>@SjZ__OkU8i748 z7M^Qziu02+kG&iJ5DZUF!e#}SwYXbuH@#bMpMBE@*^D!6d;&Lt>IXfs-mS4MxLx|A zUBBdD+OjlNowZ#V69yd>7=><4Je^_^DYZjb+kE>CyEB3Y9>gNC(lZUb4xP&)} zr*G5qa!x>W*Zi<5K}bVV$_OU%06 z$m*dnpkZ(B*V*lmmdKR2(fe*H;bptOBm0It`AVWr__t=TDL1>TcUR-d%gOUsQTl1N zPt{A^D2>WIlioNFJp)SN|CMR;*6?obCDJeu(48WErt_xc+a!OLl-k>U<*k24;SJAo zCozVU5t;#)H~rvbN%5%FeqEdS2P>IfqvlX2@o8M*BOtdZFQ}JiN$C{xK(>NjmLh1( zGLgz?fDepBmQ5G(1m=k+xsOkIT8zM@)(!-W)`1?pC%piE%bU=_dwRw(p49oEZSTH> zCC34lO}F`aI678=sU@-7+i7xK8f6z$rr68k#2GkEx@>kU(w_tGNJFo)wCsr0!s87wLKk}I|PBba6<}L+HgPa>i2*|HEnCo`= z9%te2Id>27#>4-ahzx*m@kCaBYl?Tfiq%hNRnp;oDfV_3VdOOIawIayEATV_PLMm@ z+lSDy$t1Vrd-cuvp-clxdpBfgKNntmwlX`)rj&)N$xT0`r;MKv@@WFqnkjas*N_TK z)O{WBbtfP6rkdtBCRy$e8l-sM(^=J9^r&QtEbE4He-mq>(K(~z=Bp>i#;ocZC2XZ% zx@oHqm1|g==tOUPo3-da2Kmvwu-9mpXph2NO1Ly!T;YqyWF-HKFO+HQ^++|U`fd&W zUM|{U!nTF&3LHjPAD%W#35JL806V)5%u|mdm&$_XOVK6nFWAb+8aGTToc+StgC9?IpA9meAK$DwxC2RAUYdYbcrHyO+ z8cclF|MM?4C_FUVBJ=U3iQ+P68y}$g!eecm+Q#ZvM)%Y&37|lO8}LsF4ogH-)3rRS zcbwE*ZK)x+L1IT_*A-%*WY@yD@M$mMuJan%m|vdO=QKUizNC%jl#|A)wbQW3>ee5h zOWo}iK7Y8ETJJ>e>sgRdq3(F_W4xd$caZ0vV|g#@b#Mp7%c+X3a~Y%)5X-fZRF>K9 z7+*$teVL(4IlvI9A2!`=EuZ%9U3_;vNd5iG!SA_!#D1RNiMDkNA zx@EB}lcc(42|jt}rDI##loBQ{P|f$pvN`4L^C!lNmH8E@vdsYG!=x`^l@%w;SnHJ+ zMB)?FUCpAsru(6~qc3^N>|Z97xl?v?WAJUxJC@FuQ4WdG#)@UjEa}k7lOebn(VuYy zxZh3!6d19p=uub6N@@0Y+lQl#u!$c*F@Eq&+11F{Ts=WsG)WtKGnpXeqY^2-i^h0I zowZUDWtNq)pR>+Av|qn%N*_x+`Z)isyYW-3$C1Ya8T>X!Bd*N zy0EC&u{tYW^x71u5M9eK-N(t%3A1I@>7TCpcVFaEz}fSV-Q)7OkY-n3EZnCfHHj)# zGhq5DZ8`clxJ2i%n-iSpKwdb+Qx%x8nL%R)rqEetKp@;t%}r8bjo z3N%I6snjWljU1)r34z3<%T;0$yr@sPs1FqN*LO9TGU^x=GIn~@r{>g}@W;$gJ41Bl zcT%tSr9U)^7J=QbK^%?UcnHl!)YXuylzs<3!j1cTu^4nV=}}|kbYNw8J~Q51YPZEU zQ~ImQBzGaVxS@|D7nifnowZX!^#a6|(BWWY zJI3h9_$T5`Hy9pg#k2s*Oh}!fl;udBs-?V9cpb!sw-gN-1nGzHZ1(5v>`Xhn9CyYA zLgrlaesAl4!agd%>;6COj2~UF9%0=TAw$HtCOCQm(szVBB?R#j7rS=MT&|bArkT(t ze+%lY)MP$=@-}g$YPu2@7c&V2`i;@5ES@IgyAQ;xe)yda5d=0_jXrpVxbQzf3nilU z3P$Tw;5Au}7oCHi#Y;a$2Z4Pe{S6q7cq?8qr!sK7Y_N^wcF8qh(F$ZB55`0yP(e~r zgwR1jJrL#NnEXDLPalAOgtm7nhQtI5dye0S86HBS#QD$^8QUgo*`@u z3s&R-t>zjM zFPPV&6mO6N{(J4d+JV4?J#O{ndulH-a48=jUxuL8L=;r8HaGNmwn`k-6<9eq-tHjo zquz=Y5yg6psxD|cX#WU*yRcw3)-maO#R;XkBuFejQM8c7_%NxZt~@FmYH}NH-t>>v z+mO6b@9Et~$;UFjXD2^E0sjh3tjMtM{w>IE2>cRQr=YDIj*~#2M+Tpt!GESYk|~Bl zyl}3XpsqB@W>OV64w1qz+kg}ZLBU|s-928Y1+mqgU&{c_>O`V{)cyRE_MY{Rgd*7M zKDij!>+FCXBfCkD(efdN%ySBOKuow+Lf+QdhTF!Vm&}(3si4UM8%a6&y+Wb1KK+nq z?6fj;SL)<(!w>Klu}^k~+V&v%icbvdyzKTDWGP`y;SN-U*4%^h{8Yr-BilUM;D3~N zQ^4f%T#$&*-u9mNi{2IDdrwzp4>(^A4OHij%nk1DF$Oc>3%0IJ8<3kTNr#N5PC5?eWP*^nXA` zRIOp?Nb3~6Zh^tyf1mEixFUn?He7#6p!bw6V!?lFF^@|cW-gbXwQTO4e!}oj+6CaY zUX_$;IR%abgu06{Senu!kDk*H2VD#~O$lFL6t7w4R5=v2SY06+*yBT<#i+ysEJdZ;G-Ns8uDhd=uOOB1JzNGIiZ*R`?ScndW_Ur)5fpO=Rx zywMf%BLY;byinIav(%kys<;2sF7P^M{VBZ<+B;D;Wr4KDm4IqY_viF2vXKpIYANz4 zTM)_*DnWeXWyr=923?_!=kN?{4kX}X+z6zA86|7oW_w(7RI>Uy1fVI6o~KmcuwVe);J>uGOXSp5%JK$U~DY<~o@uJWl%W^c`Di zIo}s7XRmUUXC7}Qq~XV?e>GM{y*UgB|B}=cVcQel@+x{{ck3W@#tjSTu6H8Rk-=m+ zyZatI0d;3#y>Zg#gpX#4ZXShR9%ynkyd2ZzD zdT{7cNqz93Gc1Re_p7DffYtW6x5}2}@uaI-Bih$-Ef|K*iGRvuaigik*mq#H0HUiT zuoaN?aCnZ3By}Z>Q#-yH8v{N8wSrI_Wii7H-RGelA#I-0qN4jm*)Teap#KN6lBip7S~xQ$Oc-`^E|JTsJylhs#M% zr{WZX(&BK(V!6L$U0r*@J^z~p7$S!gy|D07(|dgTK85-c8%de)0DDn3%oA1X zfe;?Uj7O9V%hzXL&AcdP`C*(jRbh++<4op4@Y0DquDIRE;QWoMebjDQP{`}HDZpLm zw_gBb&lZo{O^?RW5}$tM7T+!z6CsY4KE9~fte1Izcq&+}Y8+Dspg~H)4u;vmtd*U$ zI)n=#UA_uUPsORw2NxjNwz)fkyAVh=hMAm@Mx*l!Htr9<@7pb50|%mQh%Q?+h2zknX3CrK& z|5!QeKAUfbddv2Q8Q69Bcx$`CmD~MU>hI571ES%pAMZJf@hS^_b$x_;wJc4QGGImN zruamIZ3vED4P|ITusc0Z%q!CSo$!!ttG1mgR2U)ui`w?1lYwXgt|Q7ETUz)iReQJ^ zTwZ>fclvc|v?2LG@BeLS8J5qeSh(s_?$w5UO-w=M`bt{KRbql=!?f49pKXNY9P~%f zyXI-{B*EKLKK@Fmcin*m)W1&Pc;7I^g2_u{{|VC3R`-!XD#0b8RYyv=FYL$%h6I1( zjzU|9gI`}mQL%!Fy2*tNR+>w5O`Ol)w1^)pfjlrY$&MHr=>%ghGji(2VI+s3!iRee zqL_zNj?7lDF5tMegpCj2z=e3nndaa9g;M(?Sq%>%fj1XgivD4b|5?OScnHmGc18ss zY+pI9pbHNZg|Zt>1Q(1%XjD<6*{8?%o%{5X_zEFHiBBn0`B;pfTl98F*d8`hVOY35 z7T*M42YF8QgfK3O0CII+Gen|aPftGbQ~K{FikZNb@2xHddZwVXJ$ada#SFKA($oT) zCf7V&ns>lFjXr#+$Q6K7P`$;iP?wKtiQiVsLbpHC_nUOO1>HGSwqNdlbn(dBKZB3> zgVy`kQy{eZ*SQhuNN@C-P@w#6VD+wW=x4~^X}6VxV4_IxXgN|&ygqqtSRn>IV0bBZ z9s3~cYFrQWtFk38l?@S@F9y{!df>p_v87a`XeMGJx0zo(10*Q2dA4nieVKU%bjciY3y3q|TD{zi$}1pw9obLx3GR9#|$>OegD z!!Mof6zsuQ0hv{`-ANhr6qpC;Ds>~vtyHNbVC|%^s@#ruymMwY2>Upej-c&so~JtP zdM>(#$JD4mH`bp!QE?CZ0V#;&33rDfpnfWTHqBe41;7ID8gR3Ch!mNO zg~$1#zirjlG+=J!f=y7~yI#-*)@33#A8#r*Pex6{m0NqW6^u1wYt4x3C7rc5EmEYE zem*1l@`Qd~tRclg8c2S?^jW9HX!~}OLTQ^+AM>=0y{$rXqQPq+dH^#Xv&C1eHBV0hlWwufWRE?>}!3l|Jf6g#J9isF*eA)qMt zvu6ta#nG#|)uV4F=CelnB*pzh(u+uSU*;m?!;(1YDRE+@y%hca@5qGEkvK5P!_6Ik zXVR>|IQ!0ocyXNvPLrB2`ycag2SVetq|D>yJMh85009yI(clxa@Zin)PxDY4mEP_@QK& z)J>PP({o?aqK!1nVj%HP6vc(b11|JXPeR3W%I4j`eSs!csde#HiH~V33-5kCF(i%1 zltX(e9 z%Pinh>n0!I>HhI8S;AVr!6={7GRZQVlK(^1TSrCtMs1_gH8jEujYudp!_Xmk z3`mE{(A@*5DBUO^A|b7G4ALMVNW)OlLkLoyhu?d?_k3ru7Jsp3EuOibd+#guwQ~nu z`jztX?MHd^85lrcq31mQtj`5ltuy}mDt253d{pS@F(h4hLJtY0)8unm|he^+Ui6f`!%1jl80B@a20Hv z&}Wh4HC4FcJ;9PQ@#92g#d};KdgR>6{&|3|?uE(1Pyq2T5frKPz*KQa)b_!A_C}*= zcc)Fh)I#2NWpzF7pErAi8<&#iUy5R@tVxGcyfxjyDt8QgsT1WkZ_&r0knWw)fBkdNQ&GNBI_V$*~R9CH!&RNn)B%cN1E$RT>xC0Q{!Js z;=a~TN*g+|i@{bJnGVDWi~U?7#_^+%*juT6e1OBAI1vD z=EEFQe<7K25-7AYo(*{S6!-LvYcgbq#|?BAjz<+IAqSaqMG$E0puUH+vv#RY;*+)~;nNK?6R*kCC8}xr->kx-3`> z=9Huq{@o#mVK1%eg)q*$h{-!;eZRLC5+o~L8k09AGf=IcONo-Ob0w6paaEn;pQcG9 zc3-vNI*{^I_Uu>Y?16OL^8-xlUMpxcyoqYK9$9_nw-^mmg$~R`=b7u+GPu0@kaW>A zq$a?6VTu^@7L+0pgdSK`eB}S>Q*)$bolExNtwvi`eIK&((oH#u4R z-tZW=ekcFZZ^pNSfKVL4-_M_4h1R#Xa&4p2wu_LpZLMMVphWw->Sc(6C5tMgP7@rT zK;4oa2fBA=PRMKd#?KgX7<{zl0Y1NiO`*>CgARCjZCViASrbJgDDBFaN3p)1p)(6a zrfUdV7$kSQY;*G_ndKsa-*D>&b#8sC(~fJv>=E>HxQI^BnV0t%ae#KCwdcBPNszlw`x2x)BRc`VRKOWJwIY?p1VmGy<+`53;_Ot?k9xji$L-3|eS z5&TI6+{7_3DowN$_LUsBXp$VjvR7b`}K%o>S+h%XH}GoX*GtVHW3dR2qqai%3ONt!@BbfSG3&}+z0?J3E96q zd*@QbvyT_Mik9&&w1KY`b8}~N1yf>yc{3&GECTLq>)FxPy0SPr9_4ezO=nTg0n&lO<^2Vt=A z^(J5Yb}TG^03A|HbAL>`w5u8Ka&$>Nj-y_#Qb+4RH_czG3eZb6=L#8TSEq^R=qe@M zxh$w(_E@{!A_DRrpx9LSI^4Qf< zxSITAZDr89*gLiYk^Y1?5pRq^F{F8)@a*)uEj%Onxy}*$?T=ewb@k@AOX=|MU}EJB z7`yJ+qiG4ay=x4k$qk>3^sQmtj$=PFC>*7pcUMfdz5<#eC(Gyjx*4W2*+rq7Ck3rj z`)E0Uj2uw@uF{b|5O5B+E^bWzMyg=2%SFRvhp(VH$}>f#@I+kMrdNy$?NBC97;bZE zk&vr}^+t0u50@^dcaLwTfAB`W!2m3tL7GDePsP2L9D3KQggvGjd93ruW5+P>aD^!L z83kohRWg1qf1)6meKGZ>3PWLu8Hd1WhC|-(`_PQ2elm=<)*005<1Kn{3bFWK>B>4X zA468H!A{jvLG14tF5Js$fb{j|<1dX!%3zIZItomn+UK`JsJJ=?Or{G z|M@iX812{^AdKF1v`l!cDJHA-nWxx5`*LQbBWSAz(r?N3wx!7R^OA39cyCw}4TwvK zH12z9+E!F%7}T9Wof1QeZ5;apvm6GWVA4HAd0}Q^mydkchjCQ{%U#lVuy)l+; zIm#YzuH+HCh^v%6qt*@V4!(8p{pdV$X(Y^2cfmuqe2d(g7vQS`j*S0OEM0jAE`7Y% znRc!;SULR9h53KU7&AAts7RvXO|5#K>D$+6up+!fwIm^H-){Nf^Q8$ zEa?j+7gf^gHpMsTjvqb$isI0=WMuqdx9qxiYJqYsgfllke<0XB#574>E@)&rNLX+H z3rp{dcZpoxfkdqwX(128VJ-zulm&X>9a5O`)4}e}+7$(5b$OB@*MDcGfw~FzACP|q zO4k3Xg?4T@3Ch_i*y6)hh9f(R^(=Q`Ow~L9MNPGwc><0_?&hw|6ec=*bMO4kx+-s*p27}{hKDxF@mTd~i6t;BUD-36Drr(fI@{TPO8ACUtxUeA z;=iXmmJr6DE10SOivQ8unvFuw)uR2ib%w# zdZoC8^)W~B(Lwk`xHd&6)w+vY19Wi;mMHaD?hh?VAHEG6$++~=kHZ_A(yom;XlF&xR>^B6?bd%cNNlSD_ip*dL5xVH zR_ofiASE85Ck~NyOmCUDYMuD!3-sp6!=51nM*+yd?EJ;+keoBK55w1nHLZdF+4shq zh0js|{^(yY;MPStNf>@4Zyy8F9Z zdy;$Fi>T@R16y@La{V{9mIS{`$3M?BhmW#E_lOl#FLN21oeqSgTc1`QTuojs_@DXB z-}hp|kZ4~bLGef65-2YjQeKkgPYnqbfg%j65pGNwyox--eGnbGk`VB~A z^Kt`LlCD9oRg4qJe*V9d>H@EzAi@6K!2tWg-%8C=>62x^uL!Kf0Et<3K= ztu47Rj^8zM^yU;*1VOJu&lVg{_TvxrJm7 zv3eMy`^v?6od3gB_RU-Ef(C@jj*(H>l%jlI2d3xzLF@Ov7gCLnYm6eP8f`9T9QA0% zsuVV#kPCWHQ5G1PaKUq#u#C08uwZOt@CA9i`th>wI(pL_YU_7DM+kET!n!!jr9I46 z*?FB#(^8SJ(9FMlPZ?^Q)I!&SJbw5V7SBsQ7Fhq@lk(l~E`rOHT78$gT6vb&S#*o;W+$0%$)12w;#2H5Y2mgl;@KWYrEDH8A_7?1A_ z#Spm>&WZk8nNvvfQ3+4o)$gyw9#1~On*ArFVfD5`-;C&|mdG*T6_0cUqPu&% zzK14+dDRAqEMZ4%+i62u4=%VUQcdHCBderVe4}oB9hxV#nL|-|=sx)RilZ#WJI$H; z?kB)4IcFpCA)4DGhrwrj^oax4=wRMQJo9tT@L05KYaM0;j^7TG z;$xoQLqBH);{FC4}HIda8;(r#B@rt?^ zUf3Ao0tI22iOT^pkZ+lo7dIDXqv-qmI0ut$TY5-duzHrP%voBjrT)b67wKH11jTk- zudaK;KV;n$&ilU`r|-x&+~9=S*Sb7TcV&x5;(F)7W$V%vF#qS+e{^PWI^8j8)iy8$ zSQ)-|v)#DAGq6|H4-8cVvy&dlKWP`dipG=0CjX_W&ChJ2ekOnd~+ljwI zN7N}-UsaWU6>R>bQN_!9h`;B`8O<0Ie|Zg>coTm!4&4|I5-j)se_%Q-)pDfN7o%SoVQ2L= zG+1@av3R$j!oWF1I9@$|FsqKqv`M-Y56$iDqpeiUrBui~-6rg6SRL&(hKl*b9Jr_Y2&a>PMy3}V8Y3H&qSy`h4xrc zc#Zvl-9%Jq{C#24@W7;MUc(agj~20gUBJ_W{<48O&e_JKa^t@rS4 zo)r8o(|H-}q_{z3>tmVel3Lymt6)q4x-jjc^^%Mo;MGOJZ_s?&n;yyn(XTBfjvsmR zrF8aE$9(X#AIz7}z0Za%lHM(bGH-|x^!%N5U?9VJ8kr<|D+PN%DudrninX|gSp4NgI&2=iL zj6CXyjQ}v516qn=030LhD4oe%zo_8T>)`V`&Q*$cQDu}-8AQ^jWiJGO_kuM$I?p1$ zYIQpUunT`$Zk$Y*wQC#LZFfV?{WNmnP-*5xO`;>fmG^o-O(94hnp1bUMFzbfSw3-My>XR6zq$XMrX7ax;LD!=hSC2MPQzLzFS>AlYEfY7>>Ak)xpiF!@ok+y zNCEnM1Hr@np|f(d$i$~hrLAPmyTTmFJL5uh97d$hXH`*uPv~QVh%YQsnAra{<^Xg! z;dGPrZ2B4yavOzHT4D@0y;$r!E2dv8`+2tDoC|-sHznb6C_;FeiBstIe?SbUv#ef` zCjg?poSXN8h9H$zWw<|n_?z{j9-BYDD-%}ytp0bSf22a5+l|lt5iA$6kG_WZ%)W*E zaU3A-EjGJ+E;Nw_ba7N6@reu5cJ37mFS+eZFp0!jWXx$D^@{YitiIuTF|zI}rII@7 zUWSZ+rhe{w-Wf_Hys@Q94t%X2S$u*=mt|UdlFsGy{>g#+4brJFOBKCV$ir~MZ&|A^ z!oGL8>D5x>0MO;28ZlWVv*4g46;>YH~Oz%v1nz{gu$Cz>zyCX{Jv)S z`A@ueEl8S=;g{J=LcCUxn+IR{Fdr=8CLKn%i#WhXR|b}X6GTE9+M}_yd|1MHUu~!@ zlx>8?tKVQCuqE4Z?oiAuDHB=hTbuq6o3fn@;Q#4&+=?5HZY4D{q~WaqD1Tn0sL+?M+lE}6w|>y|9C1J8Z!SK_DoZu0~00aY0t zyTRwFN39#OAC$6>+`+G67p zV=1@0nRNctQaH`<1_*aQgw0Cc(%j8!%rOzX7Fp1}wR>?N9@lrhhyMpc_6Y%y*?vx{UcQFd-EdwFTVZ$gi>qwgc%|H z-B#)7iBYAkRb+r|qGkbm&1mc&{H#=9VkSr+jB0n*Ob|XQ{6M1j0i#}Z=S$@B?Tt^0 zLem%r<{C`uY^#41oXM^oP)_{){Y^Glw+A~D>p9~cl$4Fa$@e3^O>mEJTN`x0qR6HtYGl|y zmGLq$tF#~7o1R+Y5N%4s@W<}BzC{vJ6N$W%3>ydc((+O2_<0R_XLtH|W2ACbpTw0* zmwZdH8|PoTC#!!b!SMtSWW!JsodZ_SW;0OBPkyH&@P%f%kAE)fRk~OyVgje-55!U0 z**(U*hujWyx__jutuDWjama@5Ej@H{`#)ZQSLuBdwJA3baG=AC>WdWo(XO)cPvCLd zeZFbioYo=Eby+nI>S4JBCjT1aJQGu1Ps+T}pJle0qS!J{u%$LHl(r_lLz)*ML|D^G z=@#-PDmdv@uLEm`4`DAXLXx)E%#!slAc>pg2tBp{0WRtW7g((_xbF?Jpc}#N^$Nuf z?d^EJ^Y7nIO90w_Drn>MZ;tuo>04w~?S$Vsl)?oWJvnC?q*s2J1i-(nJXO_ajXP9jyw~TFO5&nwpd& z1E)tcL_2mJ*%S1jN7l*ztl%g%Z0rcCMQphGecm^zKkSCTPb3*!1WU+L?bC6Uv44{DF&>++r=l4BP-Yo^NvAXQ$m`EBov&jVl7w20TI zrPo2HvuVOp!NAN@dy$CKrSi%Cg^&JhZQJE*pfoN%`>d(vAFAKs))lqp7$lS&pl zsmYeNvrrkfZ0qiuG#fT+3jVgJ18!q7Lrbif(B55Ut@QJfqOTMmU=3ck3c$Xh>U79w ziPxWqj-Oh=W{;u-C|cAk2}11ni8VK(IOv)w8=Io=2M))E8!*o<;`_S zofV0Ht+wVlTdMPL8nzkO^b$nv@+{S#!2FHX?{mayutOFxBxe9Tz}l4x*TTfgVWrdu z;X8@85o5WYZ)_u$OBFe|Cg`F~=b?V=>FN`(;!QHN9w;_ep2Ogfi@#H4Udb}oEU)xm zN9F9qZADH=Xv{YIbCZn@bq-w2G_`u=ct*jqII*{{@e_on!)!=yQ(4q)Md~8 zqhH@4Ej(jA8}&7b$6j+qkYiBGCy}tE5{};dZl`7{hN<)5&XeF*?;>o;y*vFByTU)7 zWp^|)J*CJyf%16{(ubE72g&scMVg2Y=@0p=mnZve>kZ8emOx{-6D9-aejeU4-_rj% z|1zl6-P3l#z3OrL$d^`o0o0q%zcm3)XeHZHE$ioiI&(R%96Wo|U2-aKqw98j4U8S@DptzM z2Pz-ji_nhU&%|c5DqP!3`@DC_iD|1~OZ91BJx$*bMxWBe>y;3S$a+0YQt{(h3_d3? zn%}$vWT`lcwQ5Ik*gn502e;aaklkpE*g9>*8)YxvnkwidA9xG)0D|GiLJ|s(yzDyK z9GBfmH_bPMhiC|YzEEXn^7e`Nie`i&$cePk(NVm+Wv8pc?-%QD$6qu_Zt>bD-49jO z<^fFX=kht4rr&3dZc`%F)g1ai3knW?>_Q>a!*7+1d<-Zbj6%eog0l2^h4C|&o2iSP z8J|Sgup=@SB9~y13CPgf!mdhHX%aN8l|2j(#GGA}e5+}QaE3{I#{7*h2t?u+Syt7` zpbzv-i1pMdlYI*#ifI1@|76j=wXL_i&B;<2B%j3bzf~N7!zR?*l%Ef9t(~#;EbCRA za^~7l%Ct{m-0|Ptg?x~ot471+MLx+{JJb>)wxGFj`nojKC!~=Wp$P?bBO1!Yio^5b zxRsFn<$T5-;6)KjHabozI#N=eBv@u)%`BEV6JU&>Dx*6@roh+V%`A5wUjH)F)r;rl z$}i_CdW1m7&gWA{k3<_rsW>Sh13}7^Pyv}Vj?&T8`dKWU!dzSF9uLKzT4wyr`mj2& z=OkTnPzpkDPp4lhY@;#a(UO#dj&_3WK^=)Y+L2Gn-(w zru4VfX&#&r1#epeeJ~Y9+eewEhc;r0u(E_RUb6(cc(S4s;Y+?Jh8t!dpQl=JvgLHe zdmJGm7*mf(|>)%s&cV&qo9jfc&!LbL-U5Y%1Y(p;7Qj)b$Z0<0E+2AqFcL1 zV(h^lB}5T=R^MU$26xINd%80mB_q$}nGgY9=vUtLBbTxu6k$LpKW1$e$8P%9@ug+W zUx-6xnAi7u0@9k8nx*VK0sGogdbhr4(qD<*$`f3V48dJ@hw5O* zU$@Ajn0xy`yaTtB-scvKMyO-{GWs*7x|YP;~~iyy%utDuI8@ACT53 z1d@8*k4V2x=quq^Jx+u++?eRQdurbNv5}70csjTdAWkA#UH^OAK|F8qT(oXmyh_{) zfg4pip&o>e3IpN?#|S4hy2KiKxA2$u0S%b;m|J}?9QTEY@|p(NLb53feK3mm83TeQ zIN6ACMpwp`!I5F6QB|wY;OkK4!wI4qaLsUfC+rhrO;BNL=CuM4jQIu=@WCqns1^RR zWY?;E+e(_#Mrpid@Kp7OkF|7s{;O12W|xx@a^g@8*+H*9rH3*sICVtRD2Ru_9yfY? zXw8K9<14XF6jrn?u#opkT~CzAMAOsY3VTl0@cX1X4Xm^HcwFoE`ImzjlNiB7&Pjc5rw=2ws? zY6oq04=6U#sG#JuP$e#UK);EtUVFo5WoYT95LhD{K`Lwr@JJ)1YaPNk&pCQ$(~T4% zn3SMSW=mJFAK*pvQp9bOxcO-v4MR2bCk5i0+Oo%j!9ad)=i<#3>m~FiocCu(BAo;d zP*U^4{*5g~08;8=w3_m|MkrZC1f8yZ*5BkQ^RTPe8z*h}|8nTt4*!zuR7(1X(0!s; zi}^;|R>CMsorqp0#0uBDrC&q45wxt+45xeHM9R(wcy`LTh z-WZ9QbgE06Ejsu8nYdFQome`@i*|0U#}8CH7mBp2m7L=X@LagF6?%PKIV-HPdOx4$ zeJ%&`>pCbna4TpumMC2UA9q41@R(o|g%1re5UeOjzaH#Vu+UD^!|PO(?5P;Jn+oh} zAXWSRP?Auko+j9qF@6WXTF=mr*H-EO!jct4e*#qyM@OL3Q`nQ(z-;hI5+0N42(}vM0`!L#q%7j##KNyi z-JT5I)L-fknz+*8uta_OLFsg%$Q*L6kuEH7pQgJuClbIgB&PnBLvsk04@zPP3%x|@f^U&>>vD^2-t+gm9A;P8XJ2$t`$&9lx+_eg2G_K*B^=48t{Z?wbXb675OTys z)Fw`h5G9Zus0X^H#BITcIGX3Aux%HB={mK3!ssnFfuF-8#@;ygD;Z#18Pp_T%3 zv6fQC6Ks}Qr`n1=z=+;Qz2_--P_Bqg9~QN*5fLxV`&IiLbgLj7 z4D01wz9thA(_y46=*hN|r?eMW8t<-^My@`~)ZaBtqimy2l&yIHm#Aw9$l`Ml6Wu(P z&@Fz^3Y_3NTn536=%TF)?Zai(hNWNkdnLLh!gX+rh3Z8yKJCwz7%+E%WT8hL8BW5! zWgy4v0|nV5WLt6f`EPNT=NMr**+8h1AU;`ee9zElp(V=Lb@a;nZE?5Al!f%>6WQ#? z#gC08IYM-bB9a=;zz>P8l@qgku_fG0v_(S3B z&OqaYArD_#kk=w+<$UCedLu;3Xq)vK7{GQ%SoPHPVoAj3oN-ig9wZA~s2GTcF%Vkd zXRQG!95L;RcY-$)Ij9WJmQUQ(zil|Ydy&+z;mL%tgaxixM*cNqIivNA1uKlbyxiqj zbcC~f9Z$>9l`k0@J`-7M?CqX!w?q#19Z7;k$gTL@R?O38H0ywdckJ{~vz>47Y@?lK zC14$e896Gs2p(rnTO*ox0*2x6tQc8Cwt_E)5*L7pr~thW2yH5S^NCe?rVFcm0KUDZ zz5WczOT}FzGXJ|jxlbRLumPYZU+o2t1Er;@Q0u$LqL&dJ*6FyRz+4Zv6EgMm5^)b^I}<%P!64S!&!UeFPL`IqPg2? zfqZY&keo(f!j!~H(B*{BOg3Z|JLeKZ->@|O(PlG5z?MDOXC$u{uoe^%r^tuB>V4-m zkxMBHa{tLc$(?WtC=tAQ`9#MyqV8basLnVXcCJR{XHDb-->^?8gT zbJX%5iF=ctow;tG$sxot3RChh(I8Fc-`iemenqvBVP|v4XLaCh!;G zrHL3O;`ZBzNPxS+65teYJIu+hlm6I)-zh?9A~Ur@Ug(3;Xxoq~eY>d*RZ)C;M>wn{ zoc;MvNR5?YO@2%kkuw$2b5MQWTs|m-r{aaeMfQERktGX^NnX)n*DGpX?A1C10}C(V zKt$%x?lYlfz;DJppzF3!=U=@6m(;vJ{oTW_pDQ>Yvk-P&McXjLL`u!i28XzvMUl8c z<_Q?H3F)g>rG2pNfkA~UyiXN>%i~-!d#RnL8^Ep(AoB!R8tfGb{S}#oF^eU*lPU`) z2=0ONBBp`;uU(_!sg`{uDv>h}xv#S%oKX7Wz;L7ysldlO%;XC+Tyx#}LUGUX;PVh0 znVdA^qz~(demnXwgw2QiSGUhS&dGxB4xH3H7#shh^)OZvsad#Ha8F}i#@@cRg|9bV zoU6kXd5m~VVc^9G>eAp5bwmd&+fhGIH<=RRjvmr~{nb|XYFkcDdRb;RY3diR*AAjU z!zp^n369J(x0vM9c%on$Ok*@O_|x@^2+Q=BsPBtgBcBt`iPoj`T!#uJY`R!zAy z|A?SricpiYIjh+Hk(Gs7_T&%lnsFi9bTj(nRAS1sDfTKfa5_|&3ORTuHjp@Sp9h9UN`rb~_kn1ClKvy;7h zSN-bhe?xBqlGUJ#*I$-0f=+Qm+qQO>2NW}EF#*uM_#v|WI}D9{L^0V?tBFi3FRUKZ zr{74%e>N=%d!l+eCOd_U%v^s{Hr_IMIp*Ls+S5ZQY*C}cBv3trBQZH=zs0am5Q)_q z3DCc6oqqXj^WmvS`8S&8;IBc=cWa3r!$GaTf=8hrT;8UpQ#sXWQ-_K|AJm>E{)4(I@230kvGVIJsr%8k!c=t z5x&4}h{@b45=KZ#Txm&xpU{|7YT&KD3hx_@1x8!BDD2AgZMuP6IWESme?l6QXh<9+ zpG!X>EE68p*l&aBLi2f=qSML3!YLJJzyRzt@9D(;S7ba)=Eer7a(YxNs<}QLYKM#G!0wSMbh`!Q8aOJO* zL-_6j$`S)gXdm0_LX-jsmnk=gq&1j0o>=fPsK0mH!h^sFw5LzH2Z5EEI6c3&m5PlV zS*6*g&=O|;5^rWtNr9XrpGu%Hq}@)6f;9LP=xZu%nhH3h>BK$6E@rhhX46{@BkKQq zfxe{YRoEZAWK)GAAz8=9$tpCVYD*`8k;n4Vf%rf}% z^yVDK>3P;-zOY6X7+rw=)tddxW&AqAy5ZwM$SQzM5(iaCCiiFNRvFNnc9b^X;ve9T zB%y?w-yKy(8K`p05Fxtn8G!DGra-jTlRgFkyr0K8g=Tr*-W4;rDQ>qG8{oFH6o}}| z5p?f%!&kITd=MYRVRz_1dTCWz&Y&JP9ao)l)WvT`NI!ufF44+v_xeE+(VuddEtn>a z>y9a}=MvduzDuOv{FkA3EF?3=f`xumK7X72|rE6IKvy9jEUK5DMtSYhvILCQU7yw+w3 z)IA7?h{*l5y@uJVMpVz0^ySVGCrl)LDX`E4yJ?9vL zSAY#dTDjwHy|`_mr5$C{3U&I#ZviSQzBEZ59wAR`tC~u6xDoM%>c;E#SUy%=;(!}K zvs*L4`toDg(GM$!{dE5Gwy<6cv*rWYO+PWpajG3R zoyfdyUJTb1aytJF3&M2b8-;pKkuJFzl4*|v-kUFXH4NT&mSu8T=rx_?aLt4+mS!O^ zByNwip)ODk?bC1mXI41@4Iy*-;;>5eFRF>R@Q|Y99uJ0_o)>O6`V=e}r!U9do^L~n z80_Xu>L{!XqY)On17jwLBqrN<<`v+&=18FYuhSJ2SV}*T%9!b6%bT5 zeyD|YYRoR%M|{nI=M0YtbOG&3POj~HOQZ$VUb<@mh^6R6+j@Yq9Mf%B<(vx^9j0w2 zy3&buAL2aL9lUq3;ByNOHsB0pzoB3 zf(E2~m`uwc-E(T6SUh83au94nqn-zxz9vr*oyX8 zn_iTz-wq^~d?a|&)Rsf~{i0qc>GubcO5*rLk3k6*m950X*SeFQ>hc_pQ)3Nht`Wt$0S z>IP0AD+g&?aHz8Z=8yJoM%Ag&iZ|6P+(DpJAdbP?Lboe%&^I620$$sToehJ2+ zF_&@U9g{Hg_pb2Vug01!X3$aR=cJj=p~QvU2?dm4WnuA6yq%g{*<8_Dbrk>JpIQDm zQ06U*WGmZPmSG?6DeVxB)AT+TTZ8<2O{T>dFdGWSQDem?dz(E4OwPu!@ktzkL_GzEd;TV;i*w zNy!9lBy&`(qS!cq243~ysQN9?+GYHzH+NF?Q@1ri$}iqvp|~%VR0>zkd&dW49VLQb zyr3!85sU4Ox!$~Sr=Bxu_#WdN;vhJD^b6%>3p$M^CL6cQw_h_Qf%3fxT=Yt;0q{eO z0chjSHYifvAkCLay|>v@tpH${|ib*WgehJJ>$i zgn@A|{qRwLlU%&~5l-`Z zGrRBkShWG0)KM+HX-!MsKT{%=a9o6H#2mSx4-i_N8-Q=t`~MTv##Y@m#Z2ewsSG+&V#mRb zLg^H_c*A#eut4%|jSzMaemcX#a=1b#a5!C)x%qaQ3lYOKn^WD@^^(4UKV6d%@3tlU zK79SX&0Vr=Xu2V4kq_?mbywQ7%yYeu+MAc?iA7F1Ja#ouWzxy>mkaqUivoOG`VW%1 z%j#3$dT9M>?yOw%(*q;)ENJ2J<}RQI`nP1;%$$Gi*k(@xv%Xj{(O?zWXwC((7&(p% z-1i;+G63;K;ar!AjpOhFih|XixF!!{NxlfhD3P zmb4$IIN<+vN@Q0N zfaD5iIsyX*DP873or5xXu>d8!9` z^1u!B>w9e7WB?H2OaHUWxk+vozEAM4FK%BNH_yjj8)9}Yrx|`XzE@-rx7e|=)PJ4h zH~fFR07u~y@k^b&mrFxiCnm_@8W;UdWaGXBV`a!o0?8JsW-(Ot-1PA{Ea$s1FX;{Tvkn*s39V-O152`{waSF}?S`4tic+GL4* zfhF!h`3&cCrSl%I{G>z{K62FVxb<>Dby9lW8@AthI@FB*<(=i+2fMhSHamLE(V)8G zUA-Z|Jcxb_G(M-t(!EtS-}CQ`G%6AGa@wgDXau86XRGqL_sriXg7R7vIs=ihN4>5C zFzwB($|p{owq+V!`a%khNW-ABogq3<_C}HLH+Q>*v<#z!=(-Huuise`>dx5()3++w z?lUwX+}M76k*5|dHrn!~(fZ85Z}>H?rf*=oe{|d6wI8pMjASS+TARwfe;KLT7PUQH zYBPvd=%x`si-2UvZC9JnNlKd085&^HW(dzwI{FL9r?5~j*<8e}Q@n=0S43Km2}L3f zm?ksH{yMR`V+=1%6PFn}5(u3S&pJ&k)VU*)PPGh*=hNVBZZjLmj7MDPxDNmb5JDK< z7IlFkAv(EU5Tu=Qv@~Llg6ZPR7pEWA@mIQQ)7+CxDyHQBa>7a}*zV3XEZ|g?5=R5{ z)naJ`@59U3y(yFwwExmvhK|LzFtJhOmGI(x7o3($k)wTVC&R2mTnLFEVWSe#H9Y=v z4;%eb6%NL5_CYYF*TwGG`M$q*ybtjM`7lakwLAOyPIjkwU_MJ3!Ev@C1P2p-Te_S{ zA_uGD8fKXVyU~w(EpFlb=iWL>T)XM-Q*p_wyXz%i%+oygti8>_O)oATxO{>2Hgu2K zM#%t-^aEe5sgXz*_>KyAunk z5;FOYr*LK*TrQ$ix^x4Y;-IyW*Q59ukb4u30LK6vFb>G*l7H< z8qj{6zhNw55Ay&pZP7k<3Z(E16T&@4+$xAdE?)iVT${U+Ownj7&P&0ub<^w0+x)xw z!t&Wujy^4!pK~tpOupk=SW$akSvUQ~UR@VUO9)f{{{RJU>cWw4LyaV7kj@ti^ zCS6Q)w{=O>$xSh{NG|7lSU{=|-1d5re5HK$wnRnmqDCW$YTi*;8g4sO<537k-W6ne zRi!1>>D@s(5Pe6GDRz`Ty6VKiIp8$2?faD17z0pGEHLQ;*e|?1@9el6!N+5ub_n(` zU7EFENvoQlx#5MrO%!DK!gE$y^fraDSuM@aZ~3%cXZ|8;7FiqEyxY0*%k^@$_>1Q^6Eu;OT^r`e2;p-5N<$o?w ziVVjR+~Q<~L&Swq6qFitKEwJcPI#1%8mdf%*mg6z@mNR`=j90Nx?F$3o!*DK4}YsN zJdF955cf1w|EFlC^*qS;nF{%HD66`8p}o3E8~qj1UX(TWP2t}w@{6ZCv(6V{liw5{ zbg{DKjXNdla zvOFER>G!%5JAS;FS`eSAYc)tCHZ!Rt>+3w-(mqZPtL#|89p2~imv<>K*a#{S9=EW1 z20JC;D9C*74}>)I{tx@8mg^==sPFnR$z0A=$u&tmC5tGFQliFWe}Q-yNEX!TnRSHm z@&H52@1$}Xq~#@he@%q?pHyuK%)C9VrmQxw%kr7KQ%yPj2+Fre8}es(cLtgL+VKhI zo@4f(mG>QxIQk51t<4uBtl^KFk~^M#V#LUjFvzX*!=?YePN5A{Gb81LR}v3><~viK z*p<(bw_aIAgh_@XVi7R(N_q!uLu$s=%YKTB*B}w$m&yz$@WlsQPQ&53pW^_3_R|RC zL8+Y{+sCX6r%G1eaxq`2Lo8)Qaqe+Ic)R8b6X`PFt*7wT{pAbPbuM~evaH!#$oiY_ zzOjS^M&#j~Kx6NcaoB6rXMa5G2c0Yrg(H1gFIe)wj|Bb+^#8=|Br)^tEOgfR*Qmv- z=I8P`vT0emA=+)5iEZ8(kHBk%fcnON1(jQQ4m=8fCW8J{R!;bY0Numoa?nfU@2h~^ zaox2f74W}hU?LFCbl&*w)Wya=GQol~`QQ1E$RK679NQ0Og@5AHH` zy|NO;_9Sg=voH#B{VEdi1hQhR9D%HQg(XKa#LA;3z}+Fxtyw1{V!d^`=9p*TP@HTo zxS`W6YfP2`gxA_q_l6e71+$um&eAHh$UT#jR6)N>BMk*KvuioQ5ns&SQF59?QDW)g(A7#jY)?EIuGl6^VCr0 zwzV$?(T}34j~-Dh$Mwo<$#}VL+yW9@^-AwRMXgCGvX?HG+E-ewhO<6Nj~IHSM@#au zJk<%oAyV7=M7GP8a1qRVgVl8iS6D9)k0OPLQQq8osXSj)8U{MK{=9^a@}Ih^M*2zW z_Y&IX2c$$M7jBIj9d7+CaC<;<(H|!0BN=qMA;8J z_idU)7l-UOjb8V({3$3S>%d2lAYS!Y;^y`ASB0rEnc|uoB&sHx*22fs2tu}f|MO%D zgCmG)f=%YEXgaMHOKo#0;|z(?yz+==%cv}W(Ym*p6ws=-jFk_<#Vw0ZkWuSA75H}p zc0Qpuc+O>ch$n34REZGZLw4jF;h|3!~I z(P?>@9%>}kp(NzTI#L&P=oi}!zh2y9v`8qv*?TJtGmMp4n=qUmpbFwN z6AA{e6DHer3?bQ)fg*)P2+cRC8(wqZ`OaDXt0_YAni*cqmsK@5Tv}KW=}*su_2MC4 zo}S6?VwX1ZrTb9_vBt}>!Ylh|PobWTaaxp3_GkW*TejtEFPd6VMcGj3iwV10F=;hI z35#j31xDufMex&gUm=I19eMzvL(DpnGU7yw-oPpmFXSmM+wy+UmLz51J3!b2}8@>4QN>m?>k)!c0rfAY@FrDuNoA8;J+MRX)}rB=IN+Cs-B#PYQ6Fe0F;b ze3_MnIve4H)l*fnZc!ZcUZ~=>knb?k#8?cUCEu*-q5i(qW7&(f=FdNp{M4f}8P%S{ z&LheNT)+I7=(JHsxeuk#qX=ZAu~^Wd-f zWI0Y~5N2UaKxs44F83z-aDw&8njN3Fcd-Md7bwe>PcX|rhZYm*49XQEx7aGvA-m9N zvGARX31m&O(Sl2nNoxL%X{{p_pMoS%Z>gTV+aA{5;gQxW6QO(KFmU+?74uC!oakm2 zpZn=QCR#1xH`SAMZ&|0xchkVjyXhNwTPgPaDL=kfKfg1}LVIb5)4+f`fV`h*Bak3I zZUuq0T@q#il5s#h`V)BkOf^zinlti^#X;1on9ij}1z2uhSSSk|BG zpy=}#!G&m@7`Gq=+|SG@q!DhYrCf z7@P2P#q7Jrq{J>f@e<+w{Dg3#RL_J-e!AzCbzQe|DoWh7(wbf zbeplVR{Zeyz#mE$u27r0a%~W;BCkq3nr1jyo~e1lmmOs_)`YRp^aBR$kxqw-q)qzV z5ml)1Mx4U-2cb=?Q(c0x;er=Lj@ayf-jC#S{f;8mph?|2vx#CYB$V&r1B(2w;6~<| zWJ0<^M83<#cwj?k`M?T zpq&Kq5ZtiY14r-|IXY-?=~Xzi>zN@({ajhvD)Dot*2&S-t$LZ##vU*^w_}P}F;Gyw zTA>3eA+649IyE;wPY#hZj%wvNN%tl2@7ryiXb&9r-ZFVCaLk_hqYBZhx=p%F)q)*S ztD;+}!U&*Kjsxbg#zBh z=ro5n8lf(+12dX)XxeJ&)&-!lOPLnyyx)Ah_Cok^A>aDW-0{P>3pNf2IXs7^tJc`!36ewB|q4<7}bHKaT${LTC!74pyGy*TtiZ5395Y z%9Bn#&<0^tY22fLXZ;C9V$tPoKwEBu28f1V)>7yNk~61nk+hYXn{U@*oF8% zx9Q*U_sDpFo@&V2Oxj0(3x*6;{W^ z_)B1y6LV*?BUdg6pU_xvM9;asvCBsrkrc_*-X;&G}bcOH^Z zeT_!_qi}qWhurNg17q+;p(p{%my+qj43nRv-^ zh#r)29GJ!W0Jv(VS$pSV?zd6s?aF#_lwad$lIoF$=;T<9KQZrH_A);f<9K)lzkEfr z=D(rneP#u-9ye%w$?lqFohIE53ZnHjxohEbO=V3)lS@5e4QFD}fM>3FBet-Pnn^SN zjEJ*%yl|gKe32;mvA|1UNp2{nW>srvu!@$*nz*45LIY#n6#q;p^23u#=5gxyD(kB`eYWGQ59$}=ezG^JGNMDOAin%^tpNx;) z3>+M@B58-^S(KhTR_1|)(f0?a*?ugZXhpxin{)3xrgQ52CZqwX?%ND;W{)W5KOoEC z7||PtsAZC%liOy;$Z0kiXYa0!Wzd~mq1e^H;D1m4a%#)+dsDd4{+olh!iS73P`w*= zIDy&6*jU&@cl;#tn6l3Jf_<&2UXp{woasWDANWY&$c_knWC_pvf5`XRW!7wK0S@1% zR!n|nvD&a$+p9Z1pabA0w8=2n6;fBXxf{x>Erb}p`@KUlf0rT^7h91qE?fF)NJu;l zyqUK_k4ncSe8#APrFhc*wnMxW3_m$T0>1zg;C1~GnZa_s@BL&R(3P17gx5Q&DH@B_ zpgc-&G)gCrN zaLQ^A6QZB*)C|Ya;4zeAbneU98(Z!RDRF=6^IW;ewn(vlqyt7@y1{X9 zx&iKB2B#_Y78a3ECP&HJMz!o%a|%7EcYc;&;U7ylR`_3I{J3ryfy$w-EZBtYY{u{j5|0SmJ;fZ;3^c44s z$ODLEM|`9an034}b2R*)>|%7wRrebi%g{=Y>?y3WDE*6h47uO0sZk)D3nOF08`vLH zA2tsu@{!v6R>LXL>2E=)mfG4l*i5VyLsLq2U=KH3o&#;;E&?r`sdc8ni+}+T?k@H> zrKNAJIi>l>SLubc$aJEA1+4ueAD?e>XY>c8YhPH4 zZ~f>18{(#5De?&4R}SfRwd|CZgSK2UzI%+YbUY{itIR@{Uy_VYlPIesr~FYly`ALe zti3onV!&@%x&r>Ekbd$WY+T>SoCas7jxehNa+i4RWXG>P2 z{LBkZhAtOIo+ahJFrC^*t>A1XyupLN`e1J^Q2j|+D^h~vH@7A9yA_2?Ww(U2=|?Zc zkiMo8Tz*D&Q`R}w=TVVPTCI$luUgOHae?w~;JFDW&snu^dlj(g@9I2w&fOSCjnzOMmbM;`H zdPzM*tF9V*N>72WI(qY$(uU&}ik`t-8f3!xVn%(Ny+7qR}HX3`4B*wV6Oxd^81P$hW^$9t(aLcqnlglrsSI$7npo#2fVO-f3t$hFF zjZweE`&*o)qqymKB5uPfRTpxVCRir+}8wz2vzQet$3upQRWBQ;uYI9fFYleN4+Dc$eo&Q)D<++N}!eJLkxtMQ1CM5_DP2ARBw7XlDSV@I1BV{ zE;sy$oPhF)i@tVlK7ODSNi@G#PLBLAk+J&WBQ+-(gw{KNnGlc_b{(M&GdBu-SfB~UFj&Tjj{>JY`3w}``;5hecQoP~HY@3G& zyPJK?!o(=ns1Mkvk)Eu}0z7#J{4LhrCakS@(msF6t!bu0SN1Ir1J*>G&|E0;QRlT^ z6J1&~vE%Y4mkASV*AK0Q$y_??$k=bnD=}fNMNYtY@J2zRXDrw`pT#K2=$hA((bVkB z%t|;mU*3GgWV<{U4tCQT5{kE$y^tTzNcWMLxz4^W>#kh04^m8$slYSb&TSzcb!pG*l2)M(1d;_&)I`H&Kd0W)B*$DQB28yYY%#L=#zD!|{;?^(D3Xg~ zTien1Vud?M<4oYyJHypFuk8mcdq)ESeo*2riQ2qhykg4fYKL>&L> z|0Of}`U#V(YYiG#|BKVMSi1VRV|c`c9oL6 z?`&roAFCK`UrdKdZRXfHjxs9_=@t(zCx~xq{tqAW`h?O0LjUw}TpXrIT?EM{ZCMiL zN*(&%^j{SIGqvQ-bqimu;bC(NUU?4tsz{(T!9O~eOOGGe{~LjgZ(f(t_+v7$;nqI@ zegC3Ha6<+g5(1p(4%%v{(T!y9X`wsnBBJ%&d?3r@^ zZ!dcbZR9qEhu8+AXNMHv&u&a`k1rXr*cK z$n_aP(pJ_8F&8G&Z&$vg^5P%kq;CcXSRX$eb1}Mp$dRA+ba6e*u^O^)P4p zN%vAsc6d%1f`*q?B?L?{Mo%%&GYa!l49+GY=8iy}AN|4x2iMON>OK`tyO?F1eaad0 z%OoZPcD)Rh=ZR7!9Xzm!{q}U^2}$aDijF9V{>9|?USMxXHa;9AUuI~@^4|Ijsc4;K z0nKH(O#v0%-X?E^<8L4{y`_BXThy@=N(}Z}vSMG;n~l>dnlqNrNaN_VV}KL)iFgDv zi6xM#F@T6uba;f~q0$%rr%Y)vJ4)s&AWhuh^lfqjYs5vdQSK5w%iJmVAHV-( znDEcgQTMPwaV2XDdv|nMZh;#}vhE8Pe;U75V-s!}>2VjL(BNl582i&OmquQm>U&|Y zI&MPT-it6AsQ!tJBV4y7cD7(gg|Pl3!CGfVnHO~VmG0|;WD$qo1s_;x2ieJ~`(SB$ zhj$U9zM>`|;$_}Cnt5k9DhXp}^U9NFi*C0u)YCTm6xIMN%@OBBX4BZ6WTzst$0cz7 z-Hgm`U(8(mAG6YF;=$&;amU=rn)iS$eHPi$=sbB7LFaUcP6X*^AzX4=_|TlVG)_U%B;t2+T(@P2z(Y&+Ap@dxKl zi%X>D4mH~Y8VFh<&4&|h6Yy(bT<%@&y`|SJPVRI~mSxg@OYlm24Tfr?gMCb}9h~!R zfS=#z;EV0(s>v{mgvkHn1!y5o2f?OPsw*$WQ0V}o_3Peh%|ik>e2L3tt% z3#?xSzi}UlwSGr`%5HJHjB~K>c)N#p(`L4D0p#$Ig1fw5Z16z%ihO()DWj(Gx37?? z`8r(F(T#gG3CT%%G~i1ScW*I?W^7AXR#@zcwiQBAbk802QasTg`Fowj{hiEEqZ8rB z*4RWE^Nlcc@)khH`)yaJs=2yq9Gt{5ApKiAZR_Y>{&EKLx+$oPgKQWnZCzIJo_9k8 zc*miSeqceIL&nJ+J`npR+apmYw{vdHV#UYDWd}d8EJE3L$X=8557&CbK^2RkDD(~7 z_r{D0?z;o*hTSe@sBt8}Xo9?q{^f*7BW&k$TzV6jR!MQw^$P7yRKemv;XU+DK}vef z=D9KWuZgz7EZq&`=$$u-VCUowdInwizeise<1|Zig0=ZdWfb|!x|LMfG`V^m_y*UA zrl`=3XiKlG^MJEjaoFluahqZ;p9f^c7lDX|d|{d`vRn-VZ+?*<9vb467RBK;o_5Pf z@0t9P&JC65wHi+U8mr&=V?ZqjestKf;C0U|G)FYE_i{aa-DzpNV~8}>SLOr^d^&?u zx`?n*v(%ZGh};dH3y?8N20IIXt#(1~pBtYBK57#=XWHl#MwJ7g>&axDO8JeeIgOXY zR~X;>F0q)g7}VMW$s-2?br;JZuSg&VM+a7mU(Er9Vws$kL)6;wjwd3NUUvi6Ym(Hn z>tfd5)x&EU=g~HK8*Le+#@ zs$YXW@SFJS^X9ORVSKhM+ibJF>6DBn9NU&?^KVshrNj3CXL-Qc3A!`V{=CIi?APIp zZ{bSI76ua-RkzcUyRe19&$B7SkLt2qXyt1&R1gf2_+AliUyQbU-d~sG zEel`gql!ewzg1tdJ%&E2G7J66W8d^4IafzJ)_{#j#id$zL@i z;{(Oegi6?rJ#JsxT@|e-1v}kV6io=AIf2bCrv9qml?Zm26Zidi>q<{duU%&?WU`eI zG&jCEU5Xjison5-eL798ZEw2d6*N=3ALxjq5Yc5FTzS2$X0J2%E-;JZ>QZg!!j%P^ zX6y+8dGc6#{C#t*qg?kvH!>YmmlyU8p!W4GOOlPyznAbwN9qrGinNy^&IOexI@N<1 z#KidYDpLbTGVf|+-1(ADdP~pLV|@&_Ze7VnFc|%Ro8Nw`@E~OJf7K#>q8S>EJBTqf z;_FM+Rr^V5naN*4DhG+xXVn^$EQzg7^LW>Ad$49ch0!qD zD;Hc(MzBpRTiPZ!w8XxuNgD9Ls*taOcgL{aatDpIbGxApPNse$_}`a&TTRb{MOUO1 zp7MlfmfW`1^rO7U03-n&dymY#HUQEqXo+PekL5(bZ77omA?n4f;qI+^OA=V#aMh?~ z7f&S*)Z&q{B0;N31b?J4Iks&7`tjL*eM1gpLK17$t6b+82_-Y~hcc?gpjG-yS)siS z;Eh!dZAM4<}eOJejAMXlrClXlxX{R~>Aim+vE8z8mzJJj>^s z;L|`mhSBWiSnpbF)9Z*bjlBKeFE7|xBoQfm(SY5rkLUoZD+d72#W(4+fJf0D>0mZZ zKAJ`;Yb6g;eX_r$*P(pxN2d6dq`p6y6totNvKq_$C;^c1l`akyQ-paRE0Q-vL*hZO zN~!*9<|rQkyg~%3uFbsGvhhh5&syN+7XUmyB5jbnQj8kkX_R>VH^_wLtrgZ!N<&Ko z)f2&APSi1BGg}6puZ^Sq9$tXUy z3qYG?y*o)_@-30c1NBzEbwx`R+BS+WR}kEBpw{oTAJomCE3>PD`fX>Y64t;TVr9eg2eJ<%jo0*B(`8jJ9KY7n3V9BCr z8z16#f~$hx_Q&Pda&VYJhlYDR0&u$g74kVi=Pp?D4>w;J%jqz&`6pkI$T#9c70*8G zY^rDbjc%v%e^yl0lLC*s2(BU$#D4m+Zg_{!VaTDmtSog5_=F<4qO^c(gPs9?nMY=B zD(C-N)gs(QKMH~8wrsOO3|&HUAh|F##eG-(&07H~$TS5(w4`1NCQMfj;8lS7aU+eU z++UplYd#UtXyPB8XRLR?L<|mDHSrd6(1|^FV!&beMPEvg99^j4?I}3+F~$ABoZr2j z{c3vM|Da{|_MGX?nxXefV5x?u?`zzNm~yy}K{%S+MZ}?dqT5r)FebTxT$!mLCe0l_ z#>5xP&wP)MJ1>}KZw-Yq5`KoVE;f2a_+)IUV##55q)li#Jz2wi_yz6eU9ZSpaucu^ zwKn0<-B@{lBWRXSt{mPSaHS|Z+n%H;lmDsl~F#q1%q;f+v#|Gt-KfX9~p68z#R zmTcqA6@M+_)x|e}7@0!%YUoLLglsQkZ>`=CchvDnI#RE94S9_NJ<38Q$naow+#LsL zRH>S6g|hB0HOA&N1ziB}*YU{3X!bvQBtw!SWiJ>dZ~Sqs%XPvG%y8fMVhuSQeV`h0 zSldW3ma}90Hl$&32(IR&mIzw@@ykg^3c(yn+bZ5whD|?hoP9N#Tj$|Q+NSV=zVH>Y zL0rGRrK|CP~$bMc4#5M(kgVFx%Sj z8YjfgO2>!8mz}#3z48?YA)z38Js#cb$+*sEVV zgX6bgZZ$_GB1@w&K{O^%{?TdU7ftV~>_2DpG0|c-IIPT4&e|o*y9?vEW`aY*R)0ur z4%fn@66}o=@KS_vGDk*81cPNpl5DC8No1}vBcgfUVoYCwpd7Mx~rOc!XRm#&Ae`Tz<)1+7J_`A@L*e4$r| zkPl^x0dA>*YxW#-owQ_z#;0ATowx6r4l8E9378J1OcQ(1YRBL(tI?weOZ&_ zE`^@aAWZSMmWd5f?%MH3$7jQ31djUU-R5}VsbSamg!$uOe#7^mQb_$OshS>iYN&3) zdm{rI&>9wx( zyl51{*XWk23^nL?_?qh(aB$&b2mRh6LlVWe-Am@2Ai}J*Ll^7KOhkf(swF$Z-&pOe6KbUYN8}V?v+j)dcT7AlNB&0b@vuX(MogPZMuU&sHBV4!O)5q*M z1}s0j7GuGFhForn+AP{zdSbO|T88|TE^NP^u6F-W9b`&>>jw@s>`CVtcstdAxXGv* z71CSkQ@Du#@jrd;oAA4d0ZI2`u#4-A?+BDBK4*7qpn~h9Yg5lOoh2gLdx_p*QoxFZ$f0J>;d>BIGbs zz$rJSLo@L*>mN6w;NaB6gS{>ouTSc}%4v7mP`Dlb-v+&GNFShazM+eY|H9T8jY?bJ zq=z(D&>7$QJDU|VP!zjYkCeR#5!zhV!iPq@L}+CEo9!nW-*=vSgj1VJE_q;s`hEuVx1bb+F)<3@;XB)>~7f_)F z|F{g|S5!pQ@#{XqJfd@=k!vc(^p(z%`%_0%PbD$%JsCb(=oMjyfYkyR3$&C;w<}$G zXmd@kWuiRZo0$F*g&gd+7%bP#Di6i8Coa4n|mV@iIyaHD<>iX2=kIDX@E75QwP z`bQ&ZMPx6+!j~!1X$PEs{!*OWTXcN`tQYxo;@%(oJ9hN{pe(_R5%?CXrv0A2W}SFX zS(Cdhq0XDjL_Xzb^zS^XpA&LpDiE^b$C3#-0u{?+Sn#$}`tYmxdb-mg1h~D#I@ru5 z>aD<81PD;@tGgT`_U5NMKXlwFKk`XdZS;LfuB@(~nW4m6V&wrHX8?%fA z5oqg19L+qRYZAl|=25oDznZbnOh3`e1luT>gDano_`Cwy$QKGx5PwMz z{hoU_xoMq3*`RdJlX@&6xB-6Cwi_t-b~R%!GMaJDz5?F$23p-q?}77ryor)jsOz(Q z0m^6#rG~dsb^JZXajw4<7c@w$J_25lcbiyzQ*R9vdOb=4AmuCr#`4=e^DD#wIAi)H zXb@d&EVPVV2JozuSnbdgvrrBP42iuveu01MZdD`QV!h8Akl2D;YH=&{4|1ayhskO- z_)29C@&g4{W7g|Y^?K4aX9>CG+dgdrxyN|FsXr8oWb5Cxho~nYqmSy4bH{w9l>b2e z=m{|n>aHcfuarAZevS*;IL0Fl(!{sx&tQw}rM#3sU(yFXHvi+{<=Cs21DaNM;+C#^ zn8%#J;Ei?7IjgTh+hvXde19oy@1!@jLRNZCIUaITx8&}|G?!Xxj@!R+3|!uC0iZhu zh3I#ic1KMXCgXFD(-gb8KG_E8{`2sq*4r4E^_TC zQu*gqgId{uKkfndS;Q-0g07ou|9$$NdsPtxpfw?E>3G@JJqzJ26!e^h+0o#SjmFbN zKb?PqDACFFNm3JKS$B~ek6u|sz)Y@r?)V(1T zd*Vckq$!N}SY{qRQ~l6AxD>HA+De1O=Iroz=NC3576!ON{YjmInWQQQiD{P9_eq__ ztfj1^;KT#O3Z$wxEsKxTAna@rq_b&_T)4+|`J<<{CtEo+4qVrMf z_L3xgY%*=6ja?glmWq4y7cL)_hWmWF(+Y#L$#hp$ye1Ly=+2;$^xu34|Z?tqo z-skPzy|N_Ae_-+DG%Z~xeltYZE5X4oT}Ql<7umGe&iUs=$amLkzZRv$v5Zpx|&e249(4wHC#Ny1vG)=1|ScyT| zEzUJ5Hm}^AX%U^M$mx}Dr=!ec_TW;v09BIIS;ltt6m^PZz}~X!Wz%-`Xwte5dk9a4 z{W;6pfZMZhlAb|KH&lZg`BT5#+CsR8w^xqrOg}l?wO;wNl{8zqe(p841$O<%wf>cT zHXQXzoX;{>lqA;DF@CZ-h1}!)(MJsyoq*_z6V7wGur){q7CHt~g2=-tp9M14;-H|N z%T|v0-P>3?{K z67eF>0}c{?VrcH@jGeM3E!#bw8#imN32Yc(9z8*&c{~?kT;)>6&6WPjM?i4*kp^Y- z*4!8>v~R!)P~D(`+7XCfEZu%!p%ee#?)}#MwXU+B`cU2xfkMPrcX=2YO;o=T4W=Tt zh$$(R?{*6tZaIGC=T=tdZYt^_J;$tXECt`6X(^^W$K1oGZ#A46nIY98f@Udzm6-Vh z2A9<1QN{&rqTUehqkhlIEs24x=RWRH0i5Ff5}U6FNr^QZxcWR_u~c}$bh7Ne#yp9p z(^fMkatS>|BSLcmIV+Pcm2ut`xGZM6ryR#aAjW+4d!=s>Cie#l255vaZIcolnyQTy zJDBebTM%$bj+i}lkt?jPPx{^Iry{`oXP9l@7oT)r;n)^yTq(~T(UtL%mInGn+U04G zq8R$G=m{WNHlKukz$6}$nST2>;>p2vIWOh^tu@S!6;oQ*t7!`jxcBksd|6nu-+ZQ}pLP}S--b#df%#*x}-yikm7J1I}x{nDv4 z>v>i#QFTAlHfB#K=#2|U7>Ju#oKnF zX8*c=32(o;eq0r(V6zDbvOM<7(-vDiT09EU*)~Yfr+1@$7W0@8%6O$w8jqXn-1@L;VYfOUYr5#`mJw|Tp z7F!Z?iv#lsCE$53dhr6Q_dKY4ysFQEjNX>}{qqL{jFCs))b12i_vj%AC|Q?k?@MUI zrbN8Qs|`Z;RLRmT_ENVZ=13H19uxO}?GYb~ItI>Rx4bbpYPL%8^z|{$e(}tO=YMKQU(&ib0@3}s74HfL9XggqExN-3`DVTcY`peM zcD!>Cer^%;pw2ur6@9scGke~Y`)k~H+`0n#*7$ip^bsB}mT{G4IGrI+aq_6rf1NaZ zb#}(~xQ`N#tOq-71n1~JuRKz%YWc2OA2Y^YLOPN`0w98ba8lkAubJz|YWlIqZb*rDagQ4?1oR*LcH^I= zybcP!J)*bMt@*mStw z11IPFhU6P{XxYlyaE~bQ2SMbQ=mwx&)oiw;|A&(V$T_;oKkGIu)xqb@w zeB+yuk|vdT)c{tY7lqfRDgiGb4#Q8UEfX6C=Dx>^=zXnSgjSidN6=Sa*rfA z0^Cysnd~*4#uM3)42qBQXz3+XnTn5XG`G|iU;`Ub3dbpz3~i>5A|popY8fT_fn802 z!1Y1LxB4V+zAaBgzbdu z==HL}N*dg&xSd8SdK*P2O@}jmeqo^%?eT;dLn)*5_QWehvRzm|pm5#f##RGW+Y<)U z4tTRuf^r((&1@M(HEoFnG%D}a(pyv@Zli8_v>N=hJP^#nB;v!L`IAmQi8{$=(R4!g z^@tSkI1x*UVZAa>csw-~d^A8BB{sR0fKCy2RL22!R3Wl1V^Fa<$eeY2EWDvHjd7GK zB3rxUl@|lc-yHN%!k>cptj8j|lQ;t-p*xv%hLR-JU+L(Z@jp+ZR(9PxyC6y_Oq?eA^SNBmPi)%)x9njJ!1@HKvzayp5dW5t z$>C}EAzG$#-#4NZG;Dc__y?Sn9w@LCM3uW|jUdpyBkuTEUIFhA^4Usv&#!WfwtwC- z*Lx^mLbBpg<>fn$VvwGLF9Pp>tN)VP^q&2Ak!iFEl9u)~8W>tU$ihbrU4$5Aui zsq-z=w37cw!X7R__RFE$YU8wp@K}{c9Ta%Secv%q81Z|oz&II)U^my* z-TM9Ak0x_zUxdSoM*O8UN`(#Vk-}R$L5(#z6F(p`cDP}IXZ@nVp)3Cg+j6!;+Pvc&U=u3K>G!AW2J2Wle)V z)5aszRT^5ohg<0#i!5n$DM`}#RVINTiFAgZnP-DI8fQqUb?TWlq367-@jeBymID=> zcYTuU)Wf*>UpGK(&24e=&f`aPy?NX*bsJq33iUiRCEDzGmJ|)Tec)}pp%)5`7c0f< zv@7dCJ+R)qg`QSQ^Ukw?Gpna@GU)CgJ(YFcfYF@-PxB2(v)=neiCF%r`#K50-)yD- zeY%@|$anFY`4utFRV>s$BD@c91qkkaC?JOHPF5MCiu+3bkwQQ%kKT{5u$7`xlR3Gx z#E2nnW886PF5nLTlT%{AYp`|Ql}diA`xumF&5AtT3k&H8=C&R|>_3;=x|i0OTij+( z{zhixbc^>o9@C!yQ(!(w!AsUIedZj*<6(pq+BtZSM$LPS^X60Vx9E&`k)J>RA>;EO zD1oYUZPXn<;!SvH0VFx>lWH!736?S;p#WR6@k9IWE$vOHrcGeXqcE} z3;P%~%yUzs`v|yodUKS5d?=)?#g=k{$*j(^*G)-Wd~YBa(im_Rx_IFdKE2xP3;@0k zWd&Ntc*cM|vrjjm($>`o(*>(aH?ggE!MD5bP^Gm5;$~!>l(L^%M>6kF`x+ea`$;dW z9Y}+$k86yaFlY(h5+w*Nd5p|+ehY@je5ml8* z-fv^ECIsewRawRV^s-sZmLk%)E29;StGm?~!sx8P_3rFGPToju@x)uKF3&4F7r&IW zZzao*><8sDz9xcXVke?d6mlSCL}jJ7fDf=bJ3A3ZGQJ$ zd@iUJl}Q+ezO*KJB}AfXmLM1Wn^CHBG3cM(_eGo;$=X8~ax{Fk@h3`yUXravdokm` z**^^K%gU2}mEp1R>E3(Fuj>#c4|rlT8SRL$)XJNerz~H@gJ(Piev(fFVDfQ(fo+;InoidpTTf}A^(iadznhECzduNL-)SBY*658P69KmAvPh5O1V{B^o< z$7L<>J~KzCE)!D8*pK^@XMX{^*15d}D6n^Upu{5a4}6YFB(kNF*8BEf_T90hLUM?` zZ!~-dya_DHq;{Zzw-vWB@G5IS-^$n-G#O=A83u1=X7ib3FMkir9xlFYc?xy}Ia*D( zAJ>pEvSxQn8T#dzFyFbt$&mQn$tSC8iPFeOu(>3>X6A@9`G+ap*S+;fyZ7vTpCY|& z7ew59w?CgBwaVmtcx)nFtlX9K@k)>adI>n03IHuU)R(}pxq6|rKE)&_N=O%Ee#WEv z2Y~+kLV|pBSBD{+ddzC&(?Cq*&9|yI!X7@9zEPv@Cmx(&^3mjEhYv^eNXN$TB{Cw( zk_(;5_kn`5OKN9#Qn9H2y{glz5tL>K+AE0tU?k`k$XjHbNnh~!rBi=-SM_X9KyQo~ z;dqRY8j1~WLdmYR_A+Lpr@Z=m^XLQ1Wi{6Q*0pfMLV%c)cqi?o+(i&Fu&U~*aJc<5 z;6>VBXv^Ltlp|k*&%V&=O3~kJ-adWkrP>>7A->H_l?CcOY#YKd+GWI2Fq6l6hd`0H zdwKHP1^=e%L^+brqe%ycj^DYJ>$5u!iogbU5FB;}vgyE6!kOn%|QS~bEY zIWDm5Tjv@P!l8UOtyQ){HLV6zq1pR4-9D&PF}wlX3oLd~ z&%&76(my<9X!-xY@F zhfwSP9Z~#vJDWf+>_LMn7ngtiuU#lEYsdvdBhd%C{oi)qYZ{y!`yyU;_9JTeYmF$t ztV5;5M=b)TDHtY^w@Hq9h6qJlddj;ZR7_rwrU;{KKoUcZ>n%dZ@8^IV8Kq#)=^jcj zc|^WTT1R2}?>EZf5Lt1B)I>Z{vX+Q>lFg-IGFBucQ%cMGk#K8q{0P@q@+rqQ z5k;#n#W=wfxbXF5GJ4Lr^ehD}f+y;|8Qg0^w8p7BA#s9fdm*W<#f9K#BPeHYRdWf! zPd}g#%(`47u_=2m?}UTByp3Y4T?|>_wZzOB^2N8SI@8arz^ARhBtz*YD89<4fkc-z z!#Xc0+WNsUQ91|F{(T~g9MGJ5cGPXTM9Crgc(IDU1-7>C&+iAE*MZ@Xd{4EPt=Wv1 z)h56>0K)rWf~+Od4AaB&whPSX)d&8}EV5!jE=%D}J}~}?D}7HgarGmSNzuLz`#i?? zjoJUjS0jTT;d3?#q528xO`l~+!oN&+TE}}mxy1L(7dVo_;>*IbZ4e39jtvrOrkIV2 z=B11&E~tI#dK3~wXxEFoyP>{FM0ShBW(-yMM4x!0g05>zQ^H{SxF6aeJ;`>xa}v4n3vOuqq#EeX7|k!8HCvF6!!#w? zNsqZ0V_AKHN6+M`c9##GJou9cY6yR@H6BA#dq=!2(q7sNrV!b36k=k`uDZuHzqFq* zoxO%oem$O#eWHtG(|Mtg5V!+ zQb~}*KD45#$|9Vhb^d_zEVP_0P><&qe(hX_5LOki;G_RqW8VI}I#KB6=w=Pqlzvxp zKj=qqz~R~S;-LJ);a@mvV}m8)85$~25&NWapl-(@QRc=n%fcl%Z5Y)(-`62DgbqKq z_9HZ)Oa+Am^cY<=K%h~`rB!KUNak+#x%h@MJ*P5m;+Il9VB!PN`Qr`g%!6V$NEUxx zZzDp&oU*Y%)Mq}jr?n;BLp9rC8(;RxgE6eT%Y|YM-PeOZ>KWxed_F;;M?or^7jyCe zZ0)mbq0mDkH1^$-94Wlfh$spd3QHE(m|GulJ7^KwdvvKBV~1LLH@puNO|VoblP8pL zhk2ONPw6TW>*MXT!X(_4vZ9*n(l~BMz-?^8Ry%gzl8fiQ+bFWeggS?vu;-K2OpXgB zf8g_c)K0kiT!7s#T;85nwIeXNX>Y%lWc@vFQ>K4R`vp|VdLjSnYV+dGN3}h7Hca(f zs~5tkugNnE@>4Qpvom?8LK?Yg&r+gO=Gn0#43-Ct=5QCJcG{?E|60}+l+YTS)|FJn4W&D|!E>$G*BxdMOxwSZ(8V(+!u{h2T}4Ege7Cp;FkHl;&^%_O5CeEye)*o+&$|Rc>%wAaF?kbe%!)+b0 zKBY$~h#9?LBbejrzdI-s-Qy z*;DDwm&>$+q5UJ(9nThb31a-tl`of#BJKskW#>lZjsf%sq6kFMmfHj)D6l#H{wKnS z5<3O`pICQc#Dbx2f==*UA4~+tnX)cunk-Cch6G*Al6;W4Eq)d{U26!`lE)Gy?m97g zTy#XZi75GSHhG8(qBc8G&4Oa3u6uG1v<}uKV2Ui2)ZMkafbT>cmW}GCTu@b zw-H4Gqp_bVmM_Dq9qb{Dj;YbZv~Wi5?8^Bug6B-oP(tuJ(>WHn6J? z=x`v6r+v{-4zAH`+6(F9So(ps8j5unpAkax(&xHz{72;3{VN-pgj*HSFdXFbMsv@V zrHXQADzro-8=2<~0t0;mSzB*fe-qOU;FvgL=k90^S#EVjG`L?r(rf-I61={si0<$} zKfF8nkX2jxB58_jhUH7HfRb+kXE$aAsz1=UDj@jmZ6ZByR1JONPr+1rXnc9o@aHM4 z39XYm13St*Fk95Cdk62-{fzLi}CiTk1JHd1EyEuzD>q%O|NMIGT0~R>;>?E&vGwrd+ zm@>(5x9rB!1qK^$Mh$n}CJcvw?z!QgwlmlcvM>HIxFp7Fm{9=;1z=P~k!zA&{D|8+ zOat>oWq`{e%Ld0N-^jwhg`sT)jmL70ll(oePCuS$RH`Zthd$=dBktfZ6WM=n`8=_{ z*s@jncZ_Y*+0C(K^DgOI1eaCSBTT$xg6Xu(GT~#$n$m0VLgRxxO(le5gJdrx;f6F( zPF+nD+^);7?F&uTaYS{CX@5r9)5ZNd5 z0Qe%S9;aTpZaTc>&}_GgSJ{@Rj86l_F6=)&7G$Cai8`IuRkapS8fdlh3QXx`l)q@b ze$OGKw*RPjsYmVJwpATKj^$!FsI@4{Bl-r{u0CAf%;`QMBH6+7_uvtWSuLUTnSaDm z*gQ&Y5qMt+C2$@JKS%U44>EV^19^q-As&oTCNzN>-ic={bcsV99%*qBpx{uDra0Ck z$|WBZLGPfZO@4 zw@B}z)VBZ81EyPJ%*!_JG3y$LWcvP*dtCw{`};x3 zGttbS9;JMaRcIy& zO$XYQTFM5yC3iLgveC`n{H4r3+qA*33)MG5yNI%TcSYga;VGG9aXJ={?|e?fLOSs;*Rc7h;9cf6ZQO#9EvYp zI@W2C<;(C>E7ue#p>~*3pL4r9x}0u5gy=l@bgnk5Wh)h`u9naXHcSj2H!@37l_^7vd7slSB$)mW;DE|!{S$= zLjwgKK?6IIyw%5#wt49s1DpP6T{bo5Jc^9&hWDZ4MneO@53D@p7zPKeSX@N_1Ir_( zdE({f;@0Bmdfg|I;14}UiP97(=gu5@2AWKB#$Ct`SMK4v%HW~@6L>w+0PuTs@#dCmS3n^~JKg%x|6y3bT47yJjP)BZv!7Uwg`a9;7-RVZ`$9s>~IjnFWZ%IdER>Tg+V)@VmCWP@h ziywjskPvvGzLWmu$N@Xv9o9@?vzJ~Gx#tW~*dQ4Pta!K0Su9{@`M zqHDyu>w^mO}wz%&Hx zTZDX;_<&F65K^_xGjtu>&j?CRYI zGc+N=)rt@QEBPZ{L5p-b_L(h)`}Ycp5QLn(OM+Lb7#RAle`;0x#eV6Il80G4O}ywY zFb$C`q=IjmhedDVM@8%{av$l%gc$P5AGMwM%p1j{|F*dQ`SrRm&CA?- zKe2ErrC7weFW|n=zGS%WtB%$hl?n=>V$Cc)6mWo*_@Om{we3}1sN{B)gasqz^o!ka(d7qM)xr zGbMv;A!~e0RZD+JTsVr&4BGKhA2^*uuqw#o2>aO-$gn5d^Bd`*Zkbb;N;nhLN+a^k z123)c`3@|{NfC=!m_P^AJ4Bs-M2}vL_`&{UOd)wbd1g~&ff=$2Z29LghDMR;DU6Vq zbQ0c`6L@r5My=z7nt3K%dvYkPAMI38hXTANqD+{`%`v;w00$)`J-qtm;xa!2g)9GE z#7-0Mx7BC)28D2&LMy4=Kh&!0$6$1pGgQ`(kvsEp07#47vB7P%kvhO5t%yIcH1-(_ zd5|kC(ht_bX9;UY6gufCcGTcPcc_Re%e^DCYYum{77andy4gq4bPoCG*P$%zS(IUh zF|zo)LiugleQp1;?W>)Lx_tT1bTsf9A7bv_=z6xdn&uJ%6DLKH-CPVp+v*njtp`yW zA(X7=&5a2N3yQzciah;bY~c9v^Z1BIf*ej|R3h~=6012*boakvS1&QB1kOSnfam&U z0c9EakPmJfx8gN1rjCRt)9PAA1kA2B)uzve|22^@^Fnew5Z?dD$p#tevg@fo z7y8@SB|bCFCWiAj>xw-Iw(a((g?^ppy$KPU1Bn(sUZ%B^a~G-}$2X%u08f7o%ol^U4r^dGd)^)xmvxnhx(l=k+g z-AO}87j5muy3V}}5nWl?iIv=r$7n)wYkr6ri)r_=h<(ZP;g?zuH+?ZnK;ms`cweDNn-xEzWGYk6&L&xKyJuRHh=Tz^+uYsb8UTL$+ z0o(3mw1AR0*26+?vW~FUOxZauXa>?-t9DFjbKj&tmlBq6!H z*H81pt-Cpq@VgldEE>ayA&TXxBo(c9wLkVHvWe&(hn3Wg-2IyuR8!OaUL{7^t6E#{ zK88i9Bf;tO*JPml-nCp4S?yCN$yyAbYmQdWsWco|1A=8ewcr0EVfY`Kk0I*`loc+v z@2rgXBsK`^lRNMh$gUEXMi)beww3??t;>j{tP>%Y2mQ>zCsD~-Bi z&({>+bpac?$QWc7I~jAl*@l^NeX z3NBE-I4bFh%PcPW)K=nU*1xG6>JRmG=HG3q>w4BDsKJQ%LU4h_jdS1hB^*maHbXEJ z)ADm<3l`n?P;UWAIVuCzWm@`~q1b$^c52NEmYmklgvf;W{@84v9Jn_IG7T2yNXBPx zpG!e1x=o2a$Y(wQU3=no^4nI`8D)D1mP?LL3k%db`kd*!AMPmehF z_V;{K9lvgUwZ!#CLkBXR8?>QoLs8d)l@gmxK`V4vbgG)BGy8&J6o@ruP^*=ce;kIR z)3h(i(mI-a^~Os%yWc5RGR$+tL+L#EsiRTGAhG7qwI}LN`tR`%<;6j}kyLU!?a|}k z3BJrnl+5pn%{LK7(4nH>3v&i4qeMQNhfTRjqsvD+f$2ht5{r3bKy*`YMcsmMy?UrW zE()3Cp0*J(2*L=3qPlcu|5DEIJfye2d0Ome+G`f?V$N?1epgQu>$^DbW(UzdIDGfj z7@=&bMlYNNjrrqzhnx#06za(AsIV9X$#oo(XDk(KF{T~-{)bfGuOmJi3xXr1Z%L}v zEjxu~5rZaMSHe{KY@2;v8`~w7t?ax9u_@CPPKeLnHO_UQX^SX#_1oIt^zeKk+$Y5B z#3Os8etWC8Y|n9x=uh6RHqxZ+WeB7^d71e_p!u|xn45aqtg)QWCE;_BmE*8>@J592 z_e1Uf>&72^q!z5#ki2DHVHx~u0juqgnUlGNZ#6X5KIV2g}ApbfiSiK`~ z-~=+F!_xNs$F9~z9RL4HC5D{6@Pifm2CRT^UQx%nd90GUZ%ZcTxkPAk?55#ZNb?OY zv!^nnV%~9@X?zcK$C*yCXo5Lys%noI<&??5ph;4-Nvb*z=5p*ThS-cYMdCS^6kfi) zDyu>_wS@S%u5?{y>h9Kol;X|Y@#(e*0F>@Vfp4-zDW;zy$79((e%6L(G(fh`D4< z+F7zOpKb1d2{9xiT(Qbn7uEe$Zw$|3t41&LBxxGQhYbWC^!+9)o~+`P zrQeP#*Z$sW=|SKzU%OhP0;J|8o<9ojTOw^V&y^ih>&1#47W(k~iUYUKhexBAO8A%9 zxkOyz2iQA%9M<-9#)`$ut323y0l5-ijc)3%c)jS1$$b9j9W_k)7gL4#UJVhVDL|C6 z7xojm$>Lj;L&svr5OCsxOG6J?l=P}?zb*6w&}+(x@b?HwL302iF^^G%vcQ;_nF~$? zShX|3Q)qn=EK1X_xXHXFy46MlzzK3A`CXUJ-bw)HKE6;pB(M{;F+MwxW{&6ywJ6&E zP=HFmtF~2=EPj%t;*JFE>1&E+cqzqd{@2Mh7dftvu2Z z+`k&bruvm(q2QKe+x^N_^G=q`xR`EJh3mxSsMkbWU1Pr>had8*9Fc_;0 z|Ca?IIl#76Z>+Ol_c?NzsWT7(e!ySfcNi~wTi(Vq)nwr{U74=yoH?Z~YrC_+GoaxZ zf=WZ`+`_X`YBz1WNAs%lXhb~#06MmM--^4eF12NC5u02%PgL=NqrTRlnyWN z=d)Xm66Hv!`(V)-f-5>)>|r|yO?V3$AkC&jQtDUq%;r_)5u_%cUEkcd;aUB91t`-T z$qAD14S+|kNA_28r3-AnF5F&INP<@zJKBcS1IdZ9afxyq87f&h`h3!2;eYE)0jbHf$4q^6&@ za>O!h@ajmTG%`z*6DoA`54Yc-JA~$bSAuKePZ|g2ej^W+F@Lo#)Xu=*bu2&#J3L|g zZu)&DFO(`UWS8P8v|r{`cK@x1{OBbGl+{i}`mgcH_whc>gDyaD!&{3~m<-~-0{wga zh3dV^^{K#PbPsPIJzYh_?f1b|aG9Ie1>&`KocfqqVbX-9I5Dk9$Jcx7TadC$qa zsai7mj6q2b>1Q7XS6z}X;66 zkvRd=Jwd;y!p+vUVhCm8Arb4d-BM)R!LZsa>B%_H*Gnv*q5_L-!$gT13i=OT=UCs# zlH8YD+ZB`O&{wTCXK9ZcCVk45>pmhW(&a@g0(j`hH$;AnYYr#L#Nffn=lPQDnjeE5Hk_^KC_7H7?1(5)>QT5dI`P|5m-EaNOb|&uvH9`kX zIiMpYJ8w5ytaC?_pR-LRV<)@>bm!CJo~GdZ8i&8grFv5f;^t?_gIZ)4zkRFG4-o2E zQ?_@dG+(al{obK$;o81hi}fXIP}t1O|CT^VMtAZxJ#lCc#80voNBb6)?mddZoA1$9 z6y5#M81@~u&vTmKoxZ?x+vc1V`aII&0*tP33nJP_pptc&m7ghCE$@Oy+ zjAf}q*CFAmm|#GxUCzYjW^yDITz;!J>Z{fu2xfq_v}9wgiDu61QcVUDMthPPB)f4 zzdp09Mts_<>>Hw@n%L^I=nOF+U*C8nsiek-wo8!``R*g^X?mM<1uBvhEryz_r^F41{fLK27!)8-%ep))JYhc0V%6%eanG&TRy8Ge#FxmvDf-4wY+Jc= zSA#Xm(!ul1leu{JHrOrIqN?oq7+=yd&y~6)f{2%HL)9LWbtJ&29wOAnV!30(!^8e}9Dd~GZyJmv z@9ozte@tPzd`tFt8z~yuECDm*6V?=({W>AeImM5278S^x$F&{z;fD>QZ1n+vQobDH zSYXuh8uuW29(P!YdUwptGB7I_p5se@4ICJ9vL34BBYaI^5)#AvR|gN(JPGKUVPj7 zpxHU!=`;Bt^EwD|FA0hZ@htIv=@2v$@VtSzsfDzgKLl@4JW-#v#rC}mHa@uvcxcHp zF8HKbo^HM+GInt$wM@ZNRqgRObYpn;b6OntQ5?1jKlyR9vg;xF=$8XJV~q8s5ALOw zp(YNTBQ%HI>Ogs~v7gs8pBhbDr=I?Wn*TZ-l3w?X%Pmcby*%R6MN!F7c5;*~9$%O} zw>jXxlu-`2*dKn46h%=Myw+tT1SB9Og=OPy(0EWq^y>rPxWCDi>jQ%ZKMTG^U5eCZ z>jBs=w|6CTyeTch5_scM$uhwY(pSMjA7DgjiQiju?;t7)iOcn5tRpBkDF29G_OaRQ z_jtEt-FYWbQE=*IX+Y5u&xs}c3l&W}^fFAqNW4)@@^2fSTH=&be?YtvhqX#Ym>bDg z*}4ioB#q_O?B8s~3qUmA{wPL5d;zXZF8wtT>}9~ayj>Y=7?xWNr+9XRDPS0*#KQs~ z6*05|6CFI6RW29y#->9Xf*)$dCvQ|@1mTA)fihelJGP@w&`#?df^j>Ea4VFPe$TEY zI2KUDLuo>@p=qiAj(1MHVn>!0Or39<5XWXHn{+gtz&(B;IWrMf7egP)VHMVmTTuR< zM>-e2KlyFu*zE=G&w0$arzId2x)bDwwR6T4tbueaY7uB0&TUuaH=(pK_3n+Evh&?< z!g*aBx;T~}K=q5!0r@Frs2_6kW_f;!sN*JK!Nd=egfMcjRICg=A0Bt!*A9bQKf z!wp=eMaNfeDD5+_$r!M4hmebIqxV?c@^9RmqScqa|S{83md&WT+C#k^srMW!cA>MWdhzQ9Fe<*(buy5Z345 zfARGJPvbM-l}DkYg|oW}K*fU&I%?{JwKf*dOnih?3gHXWw}1bmz8}YTG3f6WvAAGJ zI=n5E%?yR{qLq;zTOd~xeY0l76A=YnW>5ZDcN8)_z*vpSSan+{b=}K)ykI z!-wh^nOfp*V|EPLI6Bl-HK5x805SCUo4~Wm=7?fX8eLFY(2f7i%~_e?cT;zH7}gz< z@%zo^Uyz)rfIF!fAkE-GArlnQ)K!~<)9ts;3?(Pp0ZTw=J?0X~y<;16!PCh(QzlI# z^)HU!&l>bME9YY1nnl4~`!njteq8M-q{S# z)pB$fa5Ay}(b6H&`j^cZ&K`V!oxs07LUAhz8bNXiHfbf8O9trp52q_7(gXQ2+J5b$ z_M@qv*O?2&*m;-iA zfm7_v@?{F6_C>ebh@wAQhFdEF%tW3ujc8;4^Ws+J`K+Q_qHr${Ec6Fd zwycCV2C-3E!Z94Rxhy<-MK|c*r8%!&|9iK=^zye~3AD1q{uo0OR zY?P}Ynw=WaGSp%ZkxK7VlieB?J?l20=Chlm&gwFeH?V1Mb`12ZUSzsti1B-LSmjTm z!->R`9nN}T>S_5j?3aY8WfM3Gz;6-Ek?RZ+jJ=k6Ea2bz^E@t7m%3Oq>~Hv0Jh@O> z6~B}cFehM2nZTaBN{w?q3PAL6-hrCv#-CC=XFpE41IShc)30HTawrq;1jAe~jm}!x zxlHKrl>V+_U%l~sP$Hj_V+*J7!E_nL=h-57?M&sYayhzCli8HKg^Ro69y*+z%poLL zWA$wIHH2dH0Lj4><9OL9ZQ5=|w25N81d!f2;-&5WQ?iD7ReuMM5?x2sb}QzJCe=U1 zTAF%$@6`yhq; zi!g~s{@7|S(M7;#>x^d$_2?GK1Pj~)61wZt^k3fh1=|ltAj>;5WpiA8!?*p@E6jOXg~}UgndJK2 zO=5ZbihaP4IsSVo*`SZb67qsOrg}VFl;;Y}nbPSF5 zN$$!TG{=uCrSmuX8v`{53an?ndyT}-EPWXlbExz1{cm!x(g@99Z5CW%ih6{J_HTc{ zA>+gML1MCx{k75?j4AMrSTO#xeiUk}XR?g-jmb!`rc`BVSAWRMGve-K zq!4mQDCq8dzB_I7R)^R;a5nGEM5AH^ky20 zE7qIuw|`x*;5*8i@z1)Jqzd%VRGS38F#A(lDirG(Sz&5Q&eAt5>P4As{L->m zKuv1wp-o-9PZ_^1avg9}i108mD$CJRJaSGGJ;2WgQEq~-x^_Wt53`9=3G{|i8d{yH zKZ1j@fA4s`g8MEG zTuB+G=Pgis<}usLiAleu4NlYAouV+-^F1QKxl=MXNK-1H(Ia@=MImNEt=9_j`UIw@ zwfLsRQ0^s+_3X}k6zoLuxM9)IB7ptOrnqC9b^b44+H~-LR+Ie%aHfDtmx0Fz-tz~m zmx>J?>eiX?`J2|Hw;$W$8_gDftt=F?pB-o; zV`R4ex^l$JE^{C_Lh(SrhB*c!MF{*mpcK!D<;$P+_g3Qxex9R4)5zN%B(VYu4?9-pM+y#48=Z;%M+e)2dU>y+Uiy z<#Smhi2IA_C!16*KLa1wM}nuB66;+K@S8g4p3}hJ&=OM%3{y1w2W%L2VYS8KqOieP zp^N2Rh1eo<6=~A+fN(Cu8Mw`cxZLwM;2>KLVYxS${timE4)v9?qxJ@~C&hn&XkYW%oX~csdml)`aa)W*R z?KJ1z&OT~3WBPjpnNJI6MvFMciETj3J_#5PIq&e<&BO56R@2r{8y}bT22mO^L}Tx5luhOZ2OHvMF@}Oq}FAu0%s-7i34XT%$;h_ zt|HL29)Ah6R_@%r5ex1`4&02va(N0tdVYPX92_t6)Zx2`-;I$s6{PWK*B!!eyYyq^ zwlK=0wI+^0`k6N1oL;8S?DFT%B@r|PAR19CbDh%RfS6oK1?-{*5Hp`v-aJusr8?%( z1{=w2LG3t&qK4{LiPeO_@B}@< z>P!$lc!?B-E$Q&YzZP&FG^c*?MgsuzqN$gE(~M8GmyT*moCX>PgfQN|?>qYwoW@)2 zc9w(4xYm$xPh43p?0ph_xq|KB_51!=o+3DojpnVte3eiYX;EL*@ytyi^;9j%iD2t? z;OFmi;d&c z;IaJ-1Uic4Q|V_gXhd&sx@TYh1}WZk-<5zP~|7cup%pG=lH(!;xBeFUaJ-1hWJV&RzOvMu$F99yi z4+YKJoxN;J&5xGuyJvahg|!xi+m8HtK$%TDZ_>8J31a+J=_Qx(r&E@|%UYvBHa`D) zGONA;Cj-DLXq1nl(gj40WPY~yS}G#HC|u4g_oUAIb)Qk9(@@{&e?nR-nXZ$Bj=Eh@ z@gH!Fy&=C{k}c^wgX;OqTt$Ip`W*}q9~?|ASUvy^tvYqr8WgK4qdl5lwRf>`Ojgj) zT6h+p)O6Pa=s977$Q*~B>m|31og`Wbl;+I-m)e? zHRec^Kdq?c+=r8meDpjFl4n=vf8<4c-2Scvhhx(|X9xFEB;%MR8*nChTxu|N%bYiw zCEQXcJ=9{K#Kv#qrAbmZ2-=`u`Y%6x&1*P0x$gW|Jm{U{Bklr{GT~>!y>53O*9}=a znFiB_$^HtHQ`-G^&hqc;BgL{@-3EvQiBN`xa(knXBD!B!SVXEhHIfuOalKfL7RXIJu0Z2>o`O z5WWtr3nRi*Hu>S|I@2CP-49r&UMf+-d!q4rDVcx2o$HoFTjb4VoGG{$QbLluj9p@t zw*PJQ667H86@M78t_%LAhp}AVwk<`5V+Iof?39xU;|n_o)@h%j7y)`wA%B=)Gc%zmglWVdQ-dJj!Eiq9-(8PDM1wgn>64#CHhSzBfmdvK`P1~lkdk- zb2}VX>&Ky(1FmRuLn48FffX>KzE4|qK61+hQ687K1!ZT zOVr=U5DZ-bmsliULb`7fS)D=H!5E5qT#1~eGh3(&Kou(&v3XveVeeHyXTlt26r~di zO1K5~YG1uLh!!+Aw);{KQ`iToNg=J2KToNbdb66nD4(F~OzhhwS!mK`_e39|NI#*&9H{wko&#RjuU28~;|6TrN8HR&+(hQsT;w8B@U*D6fIzW#~pNf=>9kfOHsI9xo3Yk623gOIH!Y`M7 zml9~m)yjGUdIKYzG4D)M2S?EQC=<3Lo}^7h25h}e{^rBC2(qWVD*L|i8t_kilT=-; zKkWY)U0SAU%QYyLZ_~Trdaqx0`Be4dKHUlE1VPL_z~&@E`j}g5Xy7)R+89tLjN#;q zyam_W-6H1L-WGL+S&|1A^$|YbS=_rXY(lvZZF=sSWGJY<_h+ z#)HM9*szBX`mZ-%xc9`V22C)Zv>a|Xd$na|<|0JkVHQ@VV?GWoY!7NUPrpaF!xf(r zUV4CSwsJOcJEln;lChZEW+3}GnfiF;)-s&n_aEc)jqChMg!qA>aN+3#(4Jhs()?OnFU=4}v4$VnG?Tghn@@x57hGx?bvuwvP72`wY4&8{u7;nn^cWMmSz+onBL$+t#U#yB&rG^{ z%!BsJj()i=QHM$Oc=SJQLy#cV{TB{V|AX;A(tN}(9gLsg}v-u4k;t(VwPb_+9@<@CDr_jm~H zpvd6KUEVEwXGhvuKFJ9VKIyess~&ecG6R1kkJG->wW4*$i0${Vx9yc8 z(;bu4?T)CIb>;}>C({K_{M)CB#>J&)hsP#_)! zeE}}kH9jL3BDCPm`$H*Tt5;L>ff%Q+7FBhZ+vvlgV=9QzQs`Sf;FN_$zAf{YbhkA5(NGG$t+Wq7N@Y-2|oPMUnP9U7l-_{vYPwV-4F2T!%%;eB`w6A)! za=U##AE8BM3p==Kz$y8Xbkp_suf4!@Ir;_w#^KUOG%7eiWDMJ(`!2(0s z-W)Ywt4OE+jvf<9qtbb1pv%@0f8Unv%8pqMmHRW6c!B%a)n?{X{LnY8=1$4bDbK>P zI#;7I)_PhQ7yYE~*rQe*nIr3#Ba$?J;)+NPUjEEZij3Q(Ctu)5h^aZk-Ip~*1(UCh`WQ`jnk5dLUN#nOw?H|Rvdi^g&ApI**>1U!{)fo z408zbi)@78cwI}c7JGbn+BAAg1oeIWSRA!AE`5p@Co^zs1u(x~@xAz-9r@uu!u)?f ze3uaqQcCp9Dq^{m8mw}|`?PkAz2?e_}v+omN3B|rhY|J z!Or$$G5mWL)+TVC1LUevpQL07Yy+OSQ5BV5S43FG<_bF2m~$6XO-F`(!7Mdp#F09% zIs{ryFYWTNG}N4d-|_iFIrh|Vl#=VSdu8rnV}`B8mr!)wYB*B2IKoRpMo&Xit3pqV`t=Vr{;@kfd> znJL%Alk!%K0PeQ{m7)osDZ8C~T=}={AFV!fNOA%C5QxfmnHLY#EQq;l_PwT^@bNbbP+=^!jV&b_#5v zjnrmyuX;Iv_dI4k6!UVQ@Lt$7B1t~XYmh>UItwBWERmD|W??4p4%KH~PZ93u_CKYX z@RZ3*YF#d*AEUa%k``Kh!&HCA(sLeMPw!2?-&rL)o+x3vkCCVQwwU*B;PfTMCj#2C zho)L23I*fz`yh38>6&W{POu_&P_uRP%*W(pN z7Vvco0eO0_!XP)c?U=*^&uy8!y{|s}Z3e(oVP7?*3luI?xmb&at<5;=o$H*f#4_Gy z8t9pj?I?eN-*}XqSjB+!nqNGmaH4p=0T0~OsnuD*RPL#x>feg%%`KUXf}IsQ{<3om za?5f!lgN53L{G*SSh^Z~$(^Ub^F?!sn7wVvp(nL%WQ=`3OXZ@2q?=yk!hAHxu=sZ~ zN0^T`OSkru=I-PswQ@T=wgIWo9Y%DASs2RLZ5honzj0SAj1?NMik`;AGu#Va{}!jZ zie|64(eh4Q&s9XWk5{UwO$7mf25cdgir3il1UH4(-&A5Eh7?}5A0d&yOxeut@#B(Z zC)}ZK--Y6cnzgTNqskzx4k0Lpq$E9rKC@gV6w(c)D<5^b2|Gbq8@Nr1JMo9~tfOIs zH2m?~xLI@ZzF-lll0sr@?G|xE58Xt`n?}KZ&J|c?hp@WS)s-NHb~z;{y3yTIo?hqz z`>H1qghm7j%&}ug*d7F8?vfDGfcKE{N_a-M6n+HNhT|4qf zle}rhTxVA`vx8Myw+}X!%N504{DB71Q4 z=Duz7k3>oYuI(gIq!r6O_{$X}9%XD0PGifSG1@LioFVm@#L#X=p{CTK61|r^@x6ty zK7XiI0Pgs29C68^CiYm;SrYPHOLNIT;!z7zg}s?clyDhX5DSCpkrWWw0>~`utlWPq zhrX)q8O}kHdj0gNx4~pykm(<2znRVy4u#gb2Op5Bn+ z#<}T7-Y6T&s>?tyTVHoDMaCda3WzlvGd(gM{rfi5_TI}iv$BdHEBx5NY@tF@I;V(_ z&RZy0lS*(;*YovB@RwPts7{-n!MtDZ)(F6##xFr3i@xbDg1vY8@_m9IBWT9;mDEj~ z&ZUU$AzRC6AUGQz%ja|vk)IRU@)3R=(Zm8k4ThaI<|0ytK)o~+|A=_$v-xW2RB9}Y zkM$8RXBf6U2k$yN4S#0QhmOCvwH~CRLVtpAUlO{=vG4Yuy`%)lwlNeyDq7_O^>xF3;<7y3QcrNrlVrqo} zeJXMv^Qupwvj$9Rjp6W&Eu7Yqx&x}}-h>u0xohc9-W1vuChTh09fPZ*q7G_~;z4Q0 zQP_h6!9+Wo5?*C0;`fdF^8`)`oBY&UK+OjGEQ`*|uC!LP#mIuAOr}JR9HRGaNSbg4|GJ)A6eB#IB_Sox8 zBPs9w837SX8Kl5l&wFhG0$lX6S300FSuS%V=r`YasCk$ET>8~Vzxiw-HtU+%eYe1i zF>;v)_W6@zr_IYh3Iw#~8Bbv%9ow5-cOloFZ5UriVrV6wd(V@zKUcA_HN}1kED`FO zcNon>0f9}YPSrLeDgKu9SkAKEc{7ivpCO<6Aj*;}GtjLs|MO^1-i^_tV(vQPHva!V zt*QURCPB$6-QqJ~1=<4s-WfdcQ&ub|4vG=?VHMkP5jObBVyB%VV*Fq#n*WkVI0iBt8tji&Nz| zS`{K9@KnLDwQx^Nk4P)3$5YmHM_H7mRbDI6{5Fr%uS5sFNQf9DUy~Z~7vAa+Q;FJ# zk5r=j>z2r0pZx)&4a!EI-VS+JD&{bb=;nPk722j+(^$E7+K};hsIh&}M+%61`4C5Q zm?_yQ+flGs{Z>dU$jfi+y95XTOygjQBuz{w)|;zt<9&zcpzI?iNRloJTMViQmS|f^ z_CX22#l>dvNjZ6AXoyjbfL27s`+B?S2O4DGGzgL_@j9KDy_|WM@p2HtKrYzDYcSG z2N`e2(|gS+Y=r}ZCEk!RP$1)=?eQz{N3t<*AyXGM8kE;)1+FSUqO30QCw17|PcrKn z3Ji)n<>Ge+T3h5c3z zM{8U~TUVdGxyv#HSLwlWwo`xQiB{=Bm-r^Al4Pz_dfHyb;r-|i?A=i%^xCfCDZRdP z#4MBoG{sBNZddqM`^Xo1C8Tr@Obu2PoO0Z zGWHI$Jr_{=F(ceClu>u=`6c}%z_Y$9_4v>HVl6T{d=jOoQ*hgb?A{pV(;LlsjOmDt z1@B$(owcAL%_pC_Ic^8ROhKHYJt@!dV8Jl^3t1Mv*ItTI*$r>j$Rt*EuYfFTtf9C`G^c;H&x~ zVtIp?HC2~wVjd>$oAF)b)PoSxtNCBLA!Xv8e>5MVIUQf=AZo06lLdEu)MbNMIC&?L zaW>|DYLG`qrNlmoS8$hp?4*Wp@*FzpFLqHZcJsU!9mXz64+S#6R&0h)&?Mu3!~Mco%UN)acy_U=A1wUz&f0=F2EAqXcdi)mG*e5FOE z<{O%%-Kj1D`kc6;F%QTeYPvZPrS&ta6@r_-=o(w4Z+VkzfqU6AxCYjwwLV&%^>RI~ zt_3s)z&Y1iS6u=_?goSHe|SEZlvKOrQH30xk3RW^gq$h=osJq$Fc)8a9_d;fyzk61 z>Pz$X{Kr?VJpyZe&}x<2d)5RR%k~e`)UN0Z3Zz^wOZR!saJ!8$Z3PJu3R_u zKX}WkwD?Ax&Dp!}A|}{MHxlE7BM(A*X1ZrU>1VviKra6c>e1mT%25Y?tE#R@5QQfh zJ;A)AS$cl2X@BWvJ5&GNkOfn-;a-4m97`m6*3=6qh4tZ+ zZ}6AvBYe@;j767Y%>9Y3%SE&84;D8q#XZ9NJD+SRwvi<)(D~2|1iRe~?X$`(kobPn zVdZWA;okC%1ShtjeOR|xUhoDKn5SEnz1=W6MYS*>k0Ez%0}1bYRAnI-%VGQVkbUvy z`*G^*SLC$$QS4oZGzpS9N?m{uU6bxNODTVZ<{tiGX(b|w=| zY#SZhwr$%paWb)O+cqW>8y(}{zxRIke)s*auU6GsPjy#y*Q(WBXFvPweNKx-6oK<< zOL0bv(Y-Duvfi*;jBe6$1UD_ejWxnCuFJlUPz^?x@c9$jByPrU>l`;WowPdB;ZSt} zoeO-q_Rrfb^(~2i=mGWR3E>s=$M}`Ib4q`PD)%OWdeA+)9X06G=Yi_k$~bi%bsHnz zkhxsVxgB;J!`*0_$pT0EhkpLQ%WJ`gztsWO@tg$ldsxxR*6DsLx{2B6&0?8KP0!MZ z(o!J^0boh#w=Io0!kqcPj7so3@$hj28{@oh@Y%NGuU9dXz=Tmh^+%t`{>V%}wfsxH zgv3Mt|5(m;T}~0S7VacpAe(_Ox)LPW-ff02cvAW00X5E1Ef!7^ zu6sb84Z8aDKvB_y`WVEVoa@-v!!}>)K?>%2a{B2)>UH$fW7!g%iVUeb_;@1XjDAg~ zs__I>GD?0#KcZo07r?33hxvqK4iTOlyJ-1KJq16-O1ZRcUA+X@%WH!E-b=D7DvK8e zJ#fVnoal<*BLN=teb|8SCbW4_G_iB-ZBh;7frUX<`&pbp3%D#ZhW`=x zI;syrQEfgV;n*csdw)}}#&|<@~WgoJ-+|HmCh>!CZ;)JtI__93I22BPl z>MFd>Jt|tvurBsi)#z#VgZo=ar{kzF)hNLVTo~Im8lO3d5*>~R7rHNk83Y-Qdh1^+ zvwlsMul0drU>UefcnDAy+kS$q{mo(VduFB!kp?tBE75rQn-Rh$k7ZI=kw@skfG<$V z0cc8Dg-6ETCrNO1d#3jU=cCB$d3Nj!@;|m6zW#Zd|Dnzp^gem~M^l606y4>z^2+Kf zGWu-U*KANgW%WIeIc&sz5jeoOdtW^&>sOrGA0N*c&5Ql=*P=}tAODs4i!t;x-dTm} zh+IMDh51n#1~Os@im0Xv(C^f=Sskms-? z=UV|*jlbQ1VCkSB|F{VqX=KpI9kPlz5;wo924>u1FuT*P4)^78Wbx<}Oq-QyC&IV4 zx?nFI?kctf;k}MFB-uFX`Z;Uvt1NsV5P!>1kkiw}O?Rr42{;g9ul+_NCYU^!3q zuN*RUniw{%NgQ!iax;flJu6ltLHg4?K+CCFlR0dLXMP#1mm?Xrv_G38Y~cKDPz**4 zQVh6;TkCBpd6@lI^Hh!A7ppybBLIm?w7jGLL(!od4Wj z9&LgfXbA>E9V7{o0Ym3KdxCiWujKw`)hC2#wWM!^{75(RroouO6Z|p3dY9h;&x;C< z&t`a0IX=Qew-D~0j%uP{(0|!P6d!4iFvzbFVw_*Sy1bLD+IX#dz)G zj=FCCP;U=KbH2RtzJ+JC&~As^s7G?*cS3uRg9{o8uEg|+gYyUOb2E4IpFO_-1M~#m zVm<<~bGrjYK0q}zx)i#j>mS$gSBL54TZ|F)m$yNt3e1MPO^sgbfR!u+e@Z^DGZXhr@e(2v-!uOPzpvJ1hrl#n%4WP{ zZt!d8ja9$zonNFkF7%VjBp|i_sY^_<7B`f4fmOkT6Rf`k*EZ5EMq?d^{-iFlxrSF< zhbcBSr`1P$FgeNhzJb9Oo8eC;a~6XnLn}*I!!cj-GVs3H4Pr0 z)A{>Sn&n1|0V)~hn$eDW_;prTX)=}4m0AB#M^0f&JKn!9IC8UGlm9W9#7(nwaK~B? zw&k;jvmd*M`K^Cd%s_abVwb1MXfjacKNy;nlovT>&S2=rG|V#a0}#Ue94%Z8PI5HN zwLqJ8nD*Ps%N3-gnci0$zMTZ5A5+g7{p?tk_LO1zxOhBir{!4S(&dm1`$v!lwsco~ zJgZ3lk+bAEvgi5Ds6YzBCGPMP@%HX3mIFq|G@rPlq-hQgPK>Eejk3HH=C&rGg8WhH zNa&4@3K%;W*N7E6@DhC_Ep?ibZhyd0kJ}G9dwPyBv=a4UZKvcLzVne@^_}sGk%2!Y z3FJB9c*1hkHw(F|E~4b+UMYi|v!9RE$wK<#{suA3ovaymz^~?c6?A{T=X)^3IWQ?~ z9rHE`%ZrWl6F9GkN|3}54tdu_a~C?d5eg|=xa1N2ix$Key`hD4I zf+^y87XMPqrKeKmY}TZi@!B1nraS=kAsIV|olnuUOkr=R&`wiH+L`!k*1q)axC==z zFNw2_6#$Yor==0^6_VUn3878aIu*D)ze=6zp&ivW^R-v4f+efLL|n5SHsw^Y8H1>X zdwj#_=ePfj0nXA+rgOx3NZv26J}z5`e6IUo^zX7(Hcv&`s(@AYzR^dy{vXfC{!arf zOW3J`=vN*iKQgjAa=bD%sz3fJd=xcwb-h~?KaWbt=khZ?cJ&N|Q}`t-`mkH>ekkcA7sbQP{sVb#i7xbMQmV70`IMmM)*8F}s%>k8sl8_}`dG<(sYhCmSLyx(}Q zvg<>#f!6|Lb*LpamcXRT!%)$)D={zVa82Hr{73*i^FEr(dy+v^_fTl43s1 zSYk9PZcd);VG8Taft&=K@MXhEO@}0fj(_|%qrK}L^jQ!Ckid!y&LZG6QDr4NM;I{Z zwAhgxq28eBXvua5Y7^ZY3obfQ#h4^4q`m_<5<(AJ*f?hqFk)rFq!DJn4w0Xs$Efr6 zRsOan8u~MuWDsyd*%>oG=;n}>XRoMbv+?J>(;RCZ9(q5oI#@1-sNiVeB^!N)-anBcc3io%42&OjlPeghVE91kw~r5c`wXvjWj^DxEmJd=gOD7$eJ@2+{gx?%4kvT07$WL&w zTr&!SHHb~xppp~&;~G(G6~=?KW!l zDosF|-?>UIFuK8{ph!m+W~^vOUc11p*HuCT!a6KOla;{lDgi2@5t7;0+LhULVdh%| zpqcHmLuH%ovi^zf3@AyT_3OZ)aHxLJkUCAqag{8Ftd9=E5c8`cW;m$xpm+cV4*eH; zy~Zhv>^icUDDL$`OK;=i<2im-iPyXl>g~@Itdf}hURGy<*xfMWUe=fn@{~U~4%iMR z=NE*#L4BUM%$Wsn?T$hYdO6YR4pOFohbIxYXA%LKe>r*ZG48!P1v7`fPo{4a_RA#+pXAs$^yv+Z#sED z_mZ!g5ISrhMP`n%P2QY&AFqG_2AtYU$v0{4DdNuk?08?=mCFm=7HbeXQ2a;6%Jp{2P?$E)@2x?)Nm+6NmpNPW!IyBnwzok1o?;Y-M`1e z1g?yGq6rwsaiQmy;$r&Qi~2}`7t*#bR#*E)&eVa1+op!U2t9LK}!sv@W2bkmsG^~lAFEJ7}z`5DF*fn zB8CJSGR1*RPw)|VB@URQzr^pf%SkN1X_aT}8KYBGuJFe-aJnk{iQ9a(?4RdmsS-}*Qz-;7b2UU~sCq?jq+~F(bu4Jq0gHa)+5M={xJwjY* zNH?9ty$)a%huf+nxBEbLwmAL3Y_2&c+LhkbQ*ic7JC9}`PM_S+flfsK1~j~qIgfrd z!~k&ILr@iiA|`)TqcOS-@kVy|2CGa~d&g?=xG-MC22cmvC|K1DssKw}h+<8PnRyT5 z2rTjF@n>o-RcvOWh<<`bSVz~@-=rN)&KH8`2qAa!EI7=mv;nxCG`f?{*J17jXQA;_ z!<2iQXX3RwmZ<%gVp3q=Tq^stvVPo>s!QHU^TiOt;1?frA7>=QL_@p0$o>k3~M=O4I4>nA&eRhp#sHUsB8eKSMu09`(;02ZKX70zq)ipnV4?Llnux z_vcdPJfvPB6?X9BImD_#<*d7jcK0?Q*WjGhu`}pPIcJ>1a8jjPv)M8`987Q6&=If_FgWoXb2IN>MGhbrR zgTGO*&q|BGiAGm>GN@*A+9CK(lXC}dzYF##88ZYUw}t|0f%JnWPMSpeIlF_&zCVC(hQfrSY3 za&jDe%@8g2RsCLNmSK|C1IlD>D6CDxd0;`-`!>I4e3bYomH@*26tb)l#c{zkZ&r$p zMvnJj+8=MZlrLu|1>r1N+yhI@H zW;-XI^WmSh%E~+|S$!C7>9Y$nGzZFHP-i(vonY49R9SGVksl9IE2cSvGCJRj5ij z3r!2aGlCrNfWrykaadp1dHeFJ>}T)#3~aUI;-G_@<)8J}eE$hRO;c|!hS$Gpzlk` z_*sOjC2U161Ur=RR&;ZpmSN?Ei)L<)+5Vin=Ec+1gyz4Dmky}AKf|XGNipysXwxXu ze$`>@kxeX$1ds|=t4~_cXN*+iG9abvf6%F`0mIO^6ForDzE;Ni0A&880n}Wb1WiTj2R3$hjnSuc;PI4PLH&l=s z0!I8MN+A!%E&o>$LxN!2?9e6mtb6I@_PVNEORd8y*SB3^#%0Dwz@P+F7UVKr&AO`m z<(>TZ+`~{X$8@$kayAiA08Yced+ z8(s&2*ADL<6X?#^P^He|aqV7YjBWUFZMx3lz!vzYz-kZcrU`9@0=fI=orNybz6$a^ za;2w;etK~J@@x2O)LjY7OKP!Q@7`R5&iwHf=DwL;bt08y4*P{dPmaI=smrk!< ziK4$X`92T`IZsg6j#(ekDk=W?*VJSW%;eqA*#e9^qH6q)3f#uWeyX9h6ll=!wlILt zKK;*WfsYmbk5d_9p!;LwRU!jyjnsZek;&)cY z`xODzDtn7K-A`<~Nu}!Gt%;a2eJA7}#PO|d`i_A>XaNil?cEM|`-od}yeAd457|(6 z_3P=Yw-_D2Lu)S`9Y@uELs$Z}mBSZ2Tcf??($0WuVR%j+WiFKD?V6oJd5TC|N*e!& zPy*lF-t1m|6i=AFK!C$DB;wDoB$(gkyid2kO^^8pe%+NZpImks%SVk$sWHn1YE!G} zs-`64aFtP9!BeYUf5!r7>i*!2tTYFB4AV-T*U+9zg)X3QS5bUet*ooW{>19H#FTv> z7uff%>7u%cv`_i{bEA=-BlN@-lBnF!4wh}lh1d!GA^^tXMW$S_GY~WYhTex~LR#BK zF2;E*zi>96cz2ZT*p~L#W_LID`8AIqs_0N(F`r#YY>3ykk=_$ECtD!_a8&A zKld>oXI1T+%$uA@Ka;(}q(RLj(5|wteRB@u0jsJF3JfL<-Qj5=w?(g>1!}c*d@$-+ zKXMacL+L0<%FiR9iA3v+`AI}W>(<{Lve7johV~bH^-hIO?GwRPtbn+Sm$rHpC{XHJ zp;Ou&Mu}K9IYF7ftwy?m*)-8SPkHUcSQ*mrj&X`#4B^fzLWQ$+^l`&oVj^l4#THoA z(aWtRwZI}}Rk<-vS#X6i%A4a7NgjOkx3H8AQ;0WQEmjMm;rQrG-_w(fcz8rA1u8t! zA0t*IrA*ujFHzLa642#lWN8FL+IpoiQ+pwPa7rh-e5|ph;$^?q8;$&7V7wOI;{nXt z%0BALKs3<&l!+`5RoY%A3yoW4xdI!Fx^v1(V}w3UQTYQ?hdkj(Fyh(#JS4C;s0E5z@&x>)WhZKg+j11B_f6i)+}?x-xe;`&{?M7Fo`z z!f7{m!sZQV$6Dsax02w87xlAbIEmgpf`M)LSk>CbS3 zq6A6P3v}FX8*R-!{y^-fxB`8l$0|9skyyvh)r}rex8y-!kkus zl7uAkHTy&^;qQ1-M`9bK=>VWX2fw2+-+35Vtd|zZ!7A}}K7bmZiIbqjaDok|^d`d) zkA(tOcHfS$#1LVDt|uo|kaeWZ`ej^D*O6csI#eW3B$hz354=B+j#`LY-Hd;W*afx%M^+t-vp~eL}RZ{)o$FlyGBZ;X#x8sk+YB*23EZ~Hf z3PXmagQ_AJN{1ZmfVIZ}Yi_!0!?S;1ML*pQx{^!hu0Z`~kzaaoPl~QKQoEwNlw`~! z32{}Y9zp3Sei+M8r?C_|+?3ZP{q74lPUR09+0Z^MUw?M99m2TJi9hvUosBt7j$r6v zc}S(kllsJrPFQN{7t=ap0Ro1zVRuxYs%h*C9ypD+dHur$dMvg5PGz)y5?q&Ky?Lne z=U+QoLeP|ZbK6&h>b(JD>GMSEhW~u#k6(S+`-~k&rnoh08+r7<)qfw(ed_SuxNE(- z_WgKtVZL;_;`Gz%_FtKJV7OhYIqu@x6UpE0uJn+CtckczFaBF&(HCESOS+o__+cIc z-DO7xKUm5j2B4{gNI^yE;E+?MQQvX3Dyv07_=Xu;_V?;ivuCZX7a4PVwzoy1zhxpx zWtR=m#`7gk^1u-jC-LLQw}aUhsauasdL^b88cUP&&d|&A&cz zOQ1$Tc`?qR2!S$cMDRc1bi`Y~28QEtlLJ-(DAVfwngJ8fQPCYp+FqQ`=Nk9hjRr-= z!_obh%$SKHYVgv-tgG%z?{7K~nLurYGN^-oM|gX?%N`Bz?byGp$d1)ex11L>{L*-V zMwF~QU}6$lla92rNDGKa&{SIbk&>Kk1BK*^wQo zYgNCmnU@Cb2G;-8qFPq?wbQ^XFgbLVo6_|9>A8V%*&L6Q;~_w}xvAlfolhV#S$7Rg zNt_l=XU<}q`7^)Heo`WF6B%zs5f7MN(Bj8)-YZ6WtR3lT7@~4+ogEJbL z(O67Re#aewg?(nlF949Gbp1bU#H6?P%X_g~(BW~}mDF_(W zn$(7%M;*3u4TKg>kW_>vO(ia#VunaoHJ{~i=o4lfw%S+CKVMi(PuhX;M$0D*jzCk3 zs4}f3d2U2i-i0`OJeqIs%9c+nU1J<#H>Us1fH9cX3Qt}4IY#&>#b}XZuN4VQw$KWb zAt~8EqvJbMq?MTFW;oR8Ze(Mffy(j{R4^|mUv?Q;rfV1q7OT+!R$q8E?7 z_TaG=9Tz#M-sg(j=ap&)dV9R_@NahK=!1m(?S6b)8%vLSTb^I;%UTtX@%!KA8{hf6 z{yFyF>s{ln5IUd7?4TQHdyTL0e?PlBJ3I4#n&^3(sL7|xeK*!C_*)1;Eam~dS6Kc= z8Q4?MA72Dx1}=%5858-Yp#R4GJoMyN?<2)v=yx2!dpK zjX3tjpI!!u;$G&5(;5&DfAE>+(Pfv@kVJKm#Zv0Cp8Yn8319TRO{XK=81(uYjVSCa zan|kEI$9bigE)?$Yo@F&F#cX?ytNTLRB6<(;vdqB=f$^7Xo`y=#Q0oWPZhU<5ZQWv zyh;;=A`LzYys!R--WiFkO2+80Y!h&>rR_?s6SYCyugC$JOXwCgHE~RWQd|? z<$g=nphP*IxJ*;^hRv3AhE?s$AZ*FpM+XJlbg)&UfrRucL1?|C5v`hA#oi!=vC5K`pmNXK&z`5w zriiyKRD88SdS&QZ*a$kIA|!LT@{mUTG}WUNxL9@AeT@1#>3kt_2vZjDSt!apQHVN_ zkSJLPvzG!60n@ZRP`Hs};{5t=Fr9Rr^Hg(%>Ky3_`h~Ss(xywd)kX4eKEOVes%7q@ z(aQT9NH*te8zLCBM5xt=4~wuKXhk`$Mk!Fyo!lF2MIT+SY{)dfID(;Gt`m|VRY+C= zv0YYz$@pZ9`U6OFQnmqv&K-+_Nmgs9IijrCdHcZz_`*G%T(rS|8D@BBG}N>!W5~c- z;p`^Ng!wR6g1BWn;wBnRPEk=vtCC;V@Br1mRRJ+HKX_-ooNQ-(=o*KawM1G;&_2%3 zOgV-@->7XqCK}tDRTSI|Rgd?32}$Ju!ggF`YA`mE&1F5VoOe-aLH(@x7t=6<-;ueA ziuaP^WsLqy`Q_EXN5QTj=$VIg-i*Dc7!qu8^yw_M+#Y<*JC3oJLjwc9fZ@eD^uZ4{ zT+h^fWgOY0K_)k=K}k$Nn<9k!o5P~-qPS}o>oKR;>*8yxdPLx&x+R3h5nh`WaKi%L zIaPKwD|A@hR7Q_D5%cIEC3TXP+G@WN7+e%E7wRw?;oUcW>KjWy4Gzo!fsGNU2Z(ce zf)b8beyTn`DF~fpRpdf|N5ARI71`KtX4Gm`&j^Q{v`^`fg+=vtVJ_zL$BJU7HtpN% zcQm~R&@GuS z$j`D{MM_`n6@Pp<^OgQJ+iJ+FU33pP1TQYs0}3-COeugLMCYiNw^`UN)%6z7tSA>| zQvy7y{C6iU*x!Yi_8;pzX;bfMkQ1JrGZO6A_3*?>Pq5eZG&Kf+xXiyzD*zBXVxEwD z%mG(mJ6L-^SZ{wVMcM1?-*u64KlFThzmONQ3dCLS3q8BTzV#b`*~bCv7y|u^oIiw? z^se0>?M4c_2Ob|k%-^jKGCuWosZl>#m_I7t?vu5KAEQoxB96-_d4BJ@dZ>pb7WY)z z<(4~$>Fu(}7sG#zP~M4xU~Sr}Xg|#O_$bEh7hx#%kY5roFziR)72FeC_ic;Pg_%K} zR;pG7P&&HKF?@khOy?94dNcr6H8+}IQ8A^&I_3d)8$2cSwgSgXihV>m@P@Dlvll;@ z0^0!rrKr&5N-7`s4U#)6f0R{P^>a7KqM+Kstf0br6x#YL75yE%=IQLep%*N)2dW`w z7Vj-;Yu>*?0)I#OQn6Hw?>P;APh30Z_IuKch!nW{&bQqqdaL+Hah>Prkz1KYnK5fI zVs=wtb%0`$)GW10J`!zAA$%!O=Z*uUr}h;=)vIs?$KN(U?Kv8P zOX=(A(BNk}?fD*ffNI}%SsYD2S-)wm^9?EcMQ{1L2Ho9?ztET0t`^cOjaIA@!>sjN znPJjUYnNAaiZkTVE9QfDSjOkyY-J|*r0k@(TdzWMGgC zGVIpw=C+?0NLULzda92?qKu>p^_@RX)O7m4Ys)`%AqlIADC{l(yyN|eaF|luuMd|KS65204E&*Fkdn775Q*dT6 z2#{FR#e~}h3gDrJIhUAoVAWUbUX}!dYR7XeBu8AFKdC~MUE)FmP;R};v>!w^DJk8m zYA;GtjPkJy6o;BMe2J1`3pG8ZoU$iqp3w9W!OMFk z5KjM%J^uUrJBCD2_v|m3S2h?2jYXx91Y(4K;QYtKg7H&Aq=GR7 z5nmBtlVMG+#duCUJ!^p-U&A3*AsWSM`0jRSRMu!VVQO7B?i2d|pUvqRdv-a5$0>LcIJ};#Qk~cw3G!yr$U~`Viwu&Fz9YI^#q_5e+sw6pQ8aF0v4a z*MswhK}maIB<3?l?11wEU1j0u3s^k_=ik#SX!lXVk$ zoT9%`@<2hg1U}gysl*%X+hzwl{JZZYS6lHpS8H_BKseY!S1)ZWr5>Mnihmz&R4Bs|mSu$EN zn!Fi2+fvcU{L44O8zIUc<3px2k{SuU4aEIQW+NzIMn)kSzNmBRyJ00H4W>ve9lJjS3Iah>-3q`AR-psUn+f2y!Bxw;a%!J%!5jvidb zQ`1WV0;_d9#IWn$IL6ev?L236$pSH#%h!9xAV0u-ZgZEUF zR~8hLktGTa<+p(MKZYI4HE*4=M!N+^^^AD1uL((f{+5R<&2?AfNY1iA;fi+XC$?;K>bNQ`gP ze9EmYA}{N498kvkeBCqMr3{HjJ?jyW?jZDr_fcU?`6HKj&)GQ^VIK$Tat~A(zjfAM zQgLz4bq}ZM*H(I-(aXHm7PzhP+yA@)G5bdxSD=2kSz(+XwjVj-AM|z3{fg5)pr?<+ zK0UhGihNa!vf(U5fGzXPNW#2)-oP*;XW?`}>#)po79l-DSG;iB70 ztte99Nz364A}l9)G#&6NYDi+r03~mvC}=6V?AN_=hY;%!+^itfT~#@GS=7vQH$Hl( z2eAxsLxL1BV& zo>C*yL}kV&YqdzpJ7aFSLWS9N_~{s|)=k?5_h9UH@L2^i6rLjjfF(M+S0E5~{R2rS zPf^O6(jgV^hftnkhlC48c5AJ)XxkBFv{m!objNUAW1QqKUm%5 zteksj#{krZgfjHP+FsVs#Gr~V`N{;25pH2$i0zU=TU(xv);koKfg#{oEf*uT1X6HJ zLs~a@zg7jvWUIff1@fMwMby1({vbQ3rtoYsLM@r%8}0P(`H9wInad4A16PFq{G0^< z&95j-?y!Y9wU67gP$Z`>4Zp;e;?9jgXuwN##`IT(!4<^--J1$)cQA zpnQNJZt*+A{(3`jUr&(sNyBzkr=q@{ZQchr=nR!INJ_one6%9#*;!HnpSmXX#g)BA*h!({>8K_&$(l@DGo`dNAh1!z(EtTfTBgDT_$5U}N&B#rb*QD` zL3e=VK6sfaJq+wtRfI*HXf$^A9_Rx)^lc1MZ%qBvGig6`TR-D9lqiZ#ly(XNYYko1 zcM97~&6!4tV+WE%HX6jz*0Ra<5?QbLr0PegsUX^%`^wQE|R3F8&0|zu*AWHTDX)3-LP^|uY?5fMT z0Jw6kTqYy-iBIfmmYN~Cnqpj09%0f`{w05@ zoQcaoI-g_dWsw?ntJ?uPoKe$rNxq=Sbs{T?RZ^CfUdpX&q-2_9Hql-PkzEEi$Z_G% z?;jj{gsFe)Uz@_+c{hAObZt#SNnFFGAzFjAm41LGr$Hh8z~J8ppvWPfH&hm3okF~e zb4X*&yR|T}<=@|tgtvJ#^bH;LNACMx+t_~|St1E+=VYz2K(*iugw)9L$u}bz+K=2& zsvA|(Xnsol2(aM8P}H=dP9cY?o{;x2(#J)OZYC&ISa&o<8^;Z z#g%`+>pC)wW7H)G1eQS|89Vd;N`SCP(s846$df}UU9!*iI=6-Db{-NP&Iqs!Ya*>4 zg6IToqtjxrqF7MsS=FX$R{FL3lCT)P5Qef)aI#84>p)kGa*|&q@%ai+zQ#Bsh?BJk zxn*qFq@_(=SmiM+d)HAV{CJZ2CYGzhDS0TWnGun_;=OSI!9N_fec#S~Ix)CpHtuvT z?s(~t%bOb|u?$eT<26@9;hk}BNEiSyPrZsG>hV_Q9uzbX^F} zA9P*cFCpn)*cl{sUSVww)eY0xdBK0;k?=|IwAFJnZ0~nE!vAope+!Di#@X&q-Pf;P zY{WM^us&gdY-iB|^a_nRbBNKn(3dqS#BkS1>yG!G{oxQkuzM&6f~mh2dtCSHZBG{U z3~dvvD`!sVdetzdMRs{khTV-!h^rv0A5|pRk+6->ZV+3#6O0DRYLwEjJ=>{4LpaQ2(8gAv^ONCcoC!`B$!mUe5>}i9M|> zAfp(qnqusESZ^z)(`<_EhEDQ^sV>@~IVsKxlo@T_5gvL&Zj=)t{NX{=0Sya%s4}^X zl9?9TKvB+>lB#e%2J2EdbP0eGEivCkc?a(fHjC9gVK!!<#t`k5;bDfPM@ zOWw@&fNFAFI2TJ)T5d;*ysvV=*?7!V35C5LzF(}dwu&BgywoBwt`jz0YrQ?R*OjHu zLJ7t&yd-wPcBZtJ{K8FQ>xgz9$xHEorD&fI*-VoCA`_Ufan^cK_ zfDh~yGo{2vkSPt)Pq%s}F@{Q|J6Evzv69@9Pz}1j>*8CQnLK55pKP+Ep+%;xm_odu05ry-w=Zafle=F z7v!?>G^=`Z1l|Hcf)7-RsZCAfi!HC79h6_XlBhQ*;eW^z{6#>q&&xfoCb?~Wj zD26;9`#X#xYXHY44yF2I#NhObQq~j0lsSdwbr7r)V@NlAD$P>d^Dl+~(kPTWFtw_e z-5_Q{g5bCzrirqmg(kws3jYs6H+z3(xg;;gF?}l*W@KX@dj0BX(^0vS$ zl3yQ08Ap!~?Y_-P!r}Eh+JF9nrSEGloozk0vVpxO9z z+YEJ)ykB&5D?$Zy5-t}w?-b?86M<>W!39-N=bsPdxCt+XSu3>K#k+SOO7g7eqEg{` zH^<*M+rL6!Y$M#Fv`00OK!UaBA6WXF#MA&J*)Ev1!H>Z}sJ`Kq4~&cxhOsEGKxG-*9V{iXfj; zM%884)OAWv11V70TTe$nd5{+U1XR!hsfN>~sA8|V=0R+u!0!TIoyX|UB}Mj1ox&|K zy-KHBIy13&yS{qEdH$;@hde*>N#?dOn|On@4AIV~n$^@5B_y5DRE{BKd8Wp=EdK1NpqwyTL|wL5$$|R; z?$&V>4BL@PqL8W!@i=?fiAj@i=%WBpcIhQI2FW1%Qz;%jUvS}D^U@sIdAQDcam;rF zWyt}BU{wKhCvH=Cc^dYyy7}~2nkrmH)ds`zv7LUnEYWR|-nXoTdXdhYApTyP zRF8FEMbS8z@Xe^byO++SkEmQnb%3r?wEj%v+}@j}GNBok>eUfT*x#F~_n`b3k;@Po z`O*ALOof}$t$2Ck_Jw&Avr&wln8NR*qTRpNrdna8pIsKe>_qU#K8@9x*Ao2tY%hh$ z%5EuCV4)jjr7pD|x+t7+KI5;bekGPb7miHVITg+XNW;o@s#>jz{gE7}f|{7)G~|A- zHO2cBgp9WqzGk;+VoQp?H5ThYPssk?X`@mmeAk7{unJx!n5i&ryGv-Kg zBAR9rsu~ju@U(=P=#Ij)D9p%I;6RiT4trEi^?e2suLPmG1ukLy<$&lJ@G-gKVy^1c z7)215GEn*x>VT!+FhC@PTnz~mNsLSB09wiKE0-#LIx;kp%8vzxY0I*mC%AD!E)j0E zWHbFQd&+yNW*$V2@-Om%za7#PZIQGqBaQt*LW*axC}#WbA^nSK5WpR^Dg9*SEmFCFd`GN*{{jPb}3^! zDf+`P`6(PK)rnUJ#v4(k5_OAV(&RL?Rs8MNhddi+^C_3%~D5R(k}Xx@)cpL+#^3uBxQF+q503WthwY(}nw_ zz?su2XHY$eJdhAtxYeJy`g5h@qE_%K=r02`)< zfN56Bt_82FuZzGsHCg^p{X+JjyDh2O z-EY`XSbH?u#qn&-tYcw_LJPxoC>)8h0q5fO?zM83)KTeFHHOv1%Fl*wer-M@4OuNNJE`L2yXpt1Y+@7T11(1u*22p(R-4BNcrBG1cY68spFWh8CI7m)h;S$`iKQ zE%ebJ)*pEBPT41Brkds&pMPBWpwp*k8?(x(G%h`g!rxmg7s5-Frcqp6y?H2%{JejF zlTz?M-fEygKdK<3RWz;!o{|?OBsYqC5??8YWYUF7uE#FR1L$PSUE#;sw0dT_HYQBz z?y~NNs?~%-mCSo$gB#-$EKF6qBjFi3zY)7uvZS6*$Msg9l0)aiy7{#rt6FC_nbmfG z!+&;io8*Nu!d#Cd6sR(gMm19gR(!{dSbhgp8bYvr{MA%6aq`m0A@m(2Li4*g@-&cW-RA;z83Tcmj>pHBTzXu1E*kao)7}Oe)(75> z#02>a=jquy#uFm@&wCdS?)JVp>j_qNJuI`9W`cp49rpYt>u>maewFqOmm^nQClHb* z#?Tg}Oq{BbG5A*LYmMdCeV2FK-^#%XO62sBE0U%-uQ(M3#Otphz7^YbGzG<;4oT*> zW~qt4zRXsbf(pY)G~KL(okP*8P0YIM%cf{@pJs}mR!sKX22lQQ&_Zz3H5^QJnV_NX z>w3{)?|Y_w_2RS{2HFLd=?}XHKTf!L^i+obcYff%#?uR;NjTdWD7VWUbqv!DQ&gHF z(+REl6I6*J(^O@k@h+*x_TPf=G!4OZf21hlMn;O`WI>u3y0)BNNx90#!o;!+g0kL2 z*76T|@;FhDV(a%+v{m3>h~H8z^f*Rx2?Ry~)c;q@SBAyWH0{E&1lSEO!Gi}08iMQM z8Ul+$kl-F5B*ATiySuyV;t(`A!JXi?K=1$o4!OSX$@9E&&c8E%rs|&Vp1Edvy1KjW zDn&fpNILg00xjZ@+$&V(cQqK8%s#P(;%L#mC~C%Ka%a;fU#|kjjwMaTfd^R4L6jH? zbDNK3K_Qi87gRQhM6((rM23^6xmKEwcqL`RIsNEj3U}rTlYnJW`ip$DIy8@q?q{-v z?O$r!9o4!@S8S3jls1=XvNl@C@h$kh9Jj}(8U^Mvr!_LZt)(i9SD5TwVli zGO>O)d<7`c$uzBQ`PG6s`>9TCci0%uESN)_X>!s(j>B|O;DhZs#3;K)r#PEo-I_IG zwy_R{m6L)-@#VsMCM{#dm#tX`Y^`3)s8Ji%{qYKQ9?6*LYHZ_Ca8H%5zyOy!6Jz1LsAz?2h%I|ssV!q2#k}y#mt^ql&EBESM14-P z`t_!X9p#ETHC{Oyw2L3T6f2FMo3R|kXPo(>2)}C0J%g;o+*W(i{khccqK+uCotL1loBjf})h7F&&gmV5r}Rp;{ol!l1gR zNP!MSw5HxHu*PV}7L6K4Y7qyBBcfJdi4 z6&ffbu8cV0nMtZi1ys3YSHC%e5WeTDmBdbr^fI6TJU%Gj>)9u>5d-4hZwU``+zA>2 z9H6)17>i|hxYK)p;!Z#3Qau{IV3^D=Cb{n=oivGZOD$87v9C~A8WhVzGWM0lcaABy zblRXQS}kNQv!Ijk4na~T`*2#@$jLIQfdKD&jr?D0n;Ul<`NurRg-5S!1(#z!ite)& zT>Yj(EaTo|46JB^dFFyg@1pLkaNa;SrM~m~OT?lOy7+P_-#(8ubxM_coiJSHYW_-1 zPc9&o+b?JOPzzgIufXyskg0y*1^fpYpX??S{>?eh2mG2%y%DD&wgc9QIzTgZ z$*sj=#STDDpXh+n1OQzssUFyoia-WHP9Xs`l@qG;WIxcft~;5vb?Q})ENiZT(fh#~ z=uE9Q+RZ541+J9hI6LyUuXIyk1y-A7*^4=i&P0rTOI)?fkDJ=sCAFl>ZUncW@AX%? zY&8j+r)8r%*~crZ+R}k+s0_u=36wEHs|>T_WUUllin}2j$vhv+0bby8>s-CSO@s=* zLb*9_(l%J4B#NC7;Hqt|p1)&z5>ek;7B3bu;_@2G>&aS}1rOi=^L)BhQ?<8zmg~=Pzaqd5cVQ@qYpzH?I_IE$>gice<_aXQAm7x z>ZB9?p3_Myfq7eX%cgDk%v7wmB`>g1vvU!b!{Es2c0rWh4|)25jMq~*@Z`>WJ>^l# zku$*ThM{h)VQ0BZr+^}NL87uP*?58j2v#Q3i~owQ4KA)I+{^bsl#DOr6Rx6b8@PnY zM*7&!KJC`!BsR|M^m&XHNm*n19#M~srk>aSAyvsqucAh@FdqsxD%N)P^DdT?-9vlZ z>V?@Le~>nb5yeitJ&#FJoI+5`t~nCBlQsL?xeHz4t6%eR+fwEt$Z`#yQCiQ|9h9_vcKx}*gBIIBMJ+&z?7 zDfqLI{~vSH%r$bYa`P9uvof;B1!Q;Yu_kZIU2&M zAKvSFfp|vjCN%gjlNQ5)3|2-YImB}np4h13yMgktw2G0MS9w@;Pg*RZe`q{aYT@f& ztaxjo(0WM9*=Rz)k(hrqA~$Yt>(6>hhc?<*hH7OgG?{Cy|4Ev@p%|hF1)S31ryAo2 zStvkMVZ<9N7(}IGasIK!<2_w_U?m#f{tZq*iTv{CNykQYR>N9{&nVZ`BHT9x+Rd-= zRLiM5lc}WLOnA<}j8ROByvpS7o$ehp@gv*hs=ZAuGevOFwU4%Y$qzA7W2oz9!|QNx z#qjy?8nA9kd{c^f1+$XOE@9MlNigEJzHQfs6cS(~*a#RJn zhVody;^pN66?e#A$A2qd;4j&8@>VAxDvrHsEV3kq5hguWRO)UHj$-T#7DGh2XmHJ` z<9$q*AJvfUJD>q=BWvKs`#cxQC1rD<5QK0AJrCx#@sI1JBW589@Lif7kajT%fJqXS zD!LLW+8HD~5sx$l;fZN85BW`<>dahd{FJ_>U)N|IA5eU)|71&!0d3OkDZ&~A9{_b0 znE=}9%GfO8Ik$vg8D3Nd|Vjn%EpI zxVEhG`N0Hz6skPbR9Y^nr9YvFQ80|5TdEtv9{7;7S#dij*n!fB)R1VE8GW5Ni57?p zsamt45B0^th>cy82m)Sk{Ir;roOqRn|YW z;v(zc2P%;%?A<2pl}ud}53ZXCu_-Xt@cyW-9`EewrW?sUQ8Ho(W@E)!FRr9c_?Fww z$qcTFjHmBxK_AND()_3!+aB2giM57-0eR(o3Z~oKM5$buP;4`CymS@LJ~PCVbp%<~%F?MRnhIMf1#lT-spVd4-97jbeTK$-@=(tEG1R zdi|?7p7RvdxQ7@JQLBL=T(Fc>To5|FTyKTOGPsB}$~F#C%9{1yB>)*yB!WzkOL((F zO~u4??MrM@n3%@GTo;(C=9Iq-2o-sbgfkUAo0|;N5!E1UnZ`ZcseN%Vev-G=GJgUKOK^oKZ=Qyc5&sX7^7G(CGXNn$D?fd9kM0@))uAep?AUPwn{g4%ZxJ#e|(>p3e z=6C9M!Vm~z*}{GnIm(p$GJqmfL+=TTtDpY>w$t(Tvpilz$6u`TzwK6|u8>9Nf5QJj zwlRJ@*y~$J_$5=u{pawIqn9TsgA|>Gw1pV-&#t!1Rb(F`p=cikmkx%#-H@Gz{d`98 z`g<}$3xL{bG)Vlmv!}jNCb4ijJ7c`f7;So^fB%F!=6;beXg?+hZqk4CffwvV;JV2k zcE+0V;X4=j$fE5Do60ndUGCA$i0r_ruBql)% zLTgp+^jXyf$ZzI4vDuh*6T}Ge0$5VK?#TtC+3Pq`9~QnXm;4tSqKKH#15?$5mjnd3E-V;tVy#1HeL_t<+eM(PwYY{DlmtUo(@=n}qqt}5z;s2v>D))kl_#P; z^{7=>(A%zAzjEL2*=R;I^dyU7?g*z{YMaq!H0?(t0Bfl^o za+G#CbCQ|i>9ivO9%Jvwel1=$h|KI_vydgJ#I)4Z-MLND4&>DS(wO{&v6NfyLt^y{ z4-&1da-_=3)WWt=x?b%{<@ON%>Gdto^(>{5tE@0CzGS0(JM?NNOut&*bqc5H|Q+S{hcXkT@%1_tujm4;DCe!a{0eV4;of-ie z{I=wh>T=U1K!}gamRXPiRsp|nMqu)za+eRL*C-s&YcuKz2Z>3RMJU7yb(oTvv}Q0F zz*BJ=4)+H^QQ+Y7b8QTB>e87o(;mP6Vh_axwY7aOwdw0sk;vb(bVFgriim8@v?Y#* z*iXcLHoM4xai~1QF~h2RKpF6s#KXszm!|dh$gdC!4bMKg&#+zZNYSpHl7{?U$hlz( zk~bD^_=XF0rP^8iIsaz$ho;W)1s=A088bA}ZC+h1kB(}bKhEye?4+bQ^opTFmB<^=V%b%R8@wh- z0|#;JzBXd&Noivnf1M-HQ#qa{tYP=kag`wYFaE!6zd$r4A)~g3tX{}J_DU+I@3&SS zcG^~SZpsDiddBRpoUga$(v+XVNiJ@`j(Pg5dNf#OESoi5RT9FlY%M(MDW?B1QvN-v z{x5jw``{Q=(88~3y?yh1aH8A1J^M0W>LzJv-#3TDZZK;a!Uv?Thnd4vCHZWI#fU?k zJGqcz-I(`BK`gh%%&@lyQ7Iv{2`rf8z&H9aJ1H9o2iuRtL5>wN%1bQN3ds1@T&2`- zDE<9(xT@vX9_=lZvoXO8Gh+#Wq-4W*BAr~7@Fzl|as24ltg5qA)xiTO7=EfnPE%ht zcQMJ3BRjBnFeVGV0>B%O-VtPWrZ%ui*FM!fRU@RV?e0g(dEAfRjHdx>BpPlB$S0F` zZfO$#5%=+3#_5dbp0xfv{^kpViS?zy1#1&?pD4v-oJd0Q&?mQRU-;HI*eRsx1@m+` zvtlPJ877BA`ve-}DAYYQ=!J0m&+|W=UoTHJ?NU@8atGwA z9n-B`>G-!sfttxs671G?v1(keiGFo95DMerw4anN7nCa8*nT>zOLNE^G&r?L7?)iEUG6XQ1bCXO| zaec%cmeCSUqo;t-n=k!^4l2p2Z}WXb5-*UzfsMjt9ah@u?Jn?$yF>mZxU2;;;-kiy z-e_{=NFSpD;RWg;{jpn0x@p-SPOH|=bfC?G1za@-bAdN2N;QLNK5CG?iM0z)SHK0+lMjk@K0*r{STv>tt9#BqDSt@N(KsNsvctjq8D*m|t{t8p(7Q0~$GY_z zU2|Y7())L$V~PYIa40_{-P%Zm!u0OJMQS^<@ZbKrZIu3+OTZU3`MVB_^Twk~CG0%A z8}B`yuC2i_-WA(~RX_O^p54Q)EDzU(U6=c|VS9Me|84*Lf7amPyY;?x%V-D#*A28Y@hV0Vwd0 z>|AerNRl;Ee7a$L*74`90<9g{6?+==1qF9hqg)7e6cv0i z-D)Oe$TC#YHeNxoxW%RHb)*cgC5tRNunb@tD|fKERH=?S_7O}{Mn&U~o|B?ngh`Em zkdb@y0yfy4hW)(rTbG~a_Tq^nvd#IMnfwoM$~c)%PZ2y5bDtfBFd_)KR)s`_#f9Od z@6{TQZd@?q?syyn4))A+5igc-l$}HRZ9uib9bN7XGHKepVp$&&(~s2~q?2qxON-nG zDf6BZIr5aP{0d{^M^AihgbZh5@ zqX_xX*lOz1a}8j86Se=j24f8lkHTqy)`Ri1X;16&?crNKoP9_-E#!Xia!$bczs$LR zcivQUFm`f-L=*OBm-c4M)IO4O_E}?Hp+LhlnI(oRi2)DnU&}r9Z6$99{##f7V`;Xv z*Wh0AW@9YNr{BX1QnMl>*&bq$zkTM2NTqQsY?As4tIRpx`t(E|mo;@=ngC0p;nT9D zOFeFGasMnl8Qx*EXx!Sf<>n;ot!e{${xBpueC#&^IX9m#kj~lNulN>qEbCjXWcZ7V z*l{&1N8_oUNZ%icQ}@`}zyMMof#6-%PE(z)TZXZM&xCsON9*5ZoP7wC0U0$O$Xea+ z<_x`>5p~hDcSw$4+#Q*zsAJ^~Xj^pkTzEuh+d8aA_2#ve0n#Wdj#R(oQp6XM2(?gj zmPXijO&BU1M;AP#ZcojEHPn!n>B=D7C1YexWoXLa^XXii_WnE3Y4tlp@h@KFGQX|^ zR(`hM`EQF{blMhFVM-jSs~@>8ZE~*+@3uHxcxBu>UG*n~r>`Gb^?PBtuhsj!oQO_< zrrhrEJ*E4fmC>g1#?60h%>7NoeT7fSee7RI`3nIio9)g=(|CGrq_I6`XmRiI)Z~H+ zPV*|y^3gkllqX*AWz5xaIPhU>Z27k=lm{Y%$M?i!!P#@QMYf0AEJlg;AEBT zj*7SeuVY=&XQHKTcl`$U=enacuJGcUyD8h1CAavilY%^;=aZjHGjAq-^uGEL0=j4V zp$V5uZ6F$0x&HL&Xpru|KKozb;p2zCN_)7MHJN4UTyT{2z*Xj<5MA=P7ypDb|Nrct z4=rpbNl1Ey2__6S6F-#QzPCTRQ%?zAZTDIXKh8T^O^L1EO0h7a5$ji6vm>t{_YNcFltTboBau#kJtc$ z^w(iXZe@y=sr5~2=F}D0MU|U0tdlG7&FJBVz&7SzWqzNbP`k~KPst* zyls2;{AkZ~%)YV+*#^J{eqX?Q;5Iv&UZ3%{;OOSlmJsrvN=QiFRdP|ZG>+jBxW{LP zqRY0d`2%sp&M9BWq{XEO&D+x1a}98-NO4Od>Q6WIBFyUuUO7sZF3Gj`QKJ88g_ubS zU&48QbM#_6ZTf?ojN6r1#gXv-{AuotFln#ndlpiXGu{#WKjj|;;v{n3%ggosY2$1D z@b>-pX7-WVt=UJT0?q2Mq>8YcT`HRRJC8p#yqR(>0DrXK0^ihi>sb-v@!ue0vUgT; zN=iszpmfe_E3CgS{EL(ylZ`=~ZHJ0K@a$jkzZGI=8RBp4-=s6?Z@_VvzQ&tR2sz!lM9Uj_|Q&PrL6*Fcg7TZ2sqL|8S^Dz3GLkKG3kxiQ1G(2KE`MtL q77VWwm-Y<^&42z2`u|tS{AzIYa>r+TDIVqbjpU@1CCed(zW)cf#2kMB literal 0 HcmV?d00001 diff --git a/doc/html/_me_auriga_8h_source.html b/doc/html/_me_auriga_8h_source.html new file mode 100644 index 00000000..92df5ef4 --- /dev/null +++ b/doc/html/_me_auriga_8h_source.html @@ -0,0 +1,220 @@ + + + + + + + +MakeBlock Drive Updated: src/MeAuriga.h Source File + + + + + + + + + + + + + +

+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeAuriga.h
+
+
+Go to the documentation of this file.
1
+
36#ifndef MeAuriga_H
+
37#define MeAuriga_H
+
38
+
39#include <Arduino.h>
+
40#include <Wire.h>
+
41#include "MeConfig.h"
+
42
+
43// Supported Modules drive needs to be added here
+
44#include "Me7SegmentDisplay.h"
+
45#include "MeUltrasonicSensor.h"
+
46#include "MeDCMotor.h"
+
47#include "MeRGBLed.h"
+
48#include "Me4Button.h"
+
49#include "MePotentiometer.h"
+
50#include "MeJoystick.h"
+
51#include "MePIRMotionSensor.h"
+
52#include "MeShutter.h"
+
53#include "MeLineFollower.h"
+
54#include "MeSoundSensor.h"
+
55#include "MeLimitSwitch.h"
+
56#include "MeLightSensor.h"
+
57#include "MeSerial.h"
+
58#include "MeBluetooth.h"
+
59#include "MeWifi.h"
+
60#include "MeTemperature.h"
+
61#include "MeGyro.h"
+
62#include "MeInfraredReceiver.h"
+
63#include "MeCompass.h"
+
64#include "MeUSBHost.h"
+
65#include "MeTouchSensor.h"
+
66#include "MeStepper.h"
+
67#include "MeEncoderMotor.h"
+
68#include "MeEncoderNew.h"
+
69#include "MeBuzzer.h"
+
70#include "MeLEDMatrix.h"
+
71#include "MeHumitureSensor.h"
+
72#include "MeFlameSensor.h"
+
73#include "MeGasSensor.h"
+
74#include "MeEncoderOnBoard.h"
+
75#include "MeOnBoardTemp.h"
+
76#include "MeSmartServo.h"
+
77#include "MePS2.h"
+
78#include "MePm25Sensor.h"
+
79#include "MeColorSensor.h"
+
80/********************* Auriga Board GPIO Map *********************************/
+
81// struct defined in MeAuriga.h
+
82 MePort_Sig mePort[17] =
+
83 {
+
84 { NC, NC }, { 5, 4 }, { 3, 2 }, { 7, 6 }, { 9, 8 },
+
85 { 16, 17 }, { A10, A15 }, { A9, A14 }, { A8, A13 }, { A7, A12 },
+
86 // LIGHT2 LIGHT1 TEMP SOUND
+
87 { A6,A11 }, { NC, A2 }, { NC, A3 }, { NC, A0 }, { NC, A1 },
+
88 { NC, NC }, { NC, NC },
+
89 };
+
90
+
91Encoder_port_type encoder_Port[6] =
+
92{
+
93 { NC, NC, NC, NC, NC},
+
94 //ENA A ENA B PWMA DIR A2 DIR A1
+
95 { 19, 42, 11, 49, 48},
+
96 //ENB A ENB B PWMB DIR B1 DIR B2
+
97 { 18, 43, 10, 47, 46},
+
98 { NC, NC, NC, NC, NC},
+
99 { NC, NC, NC, NC, NC},
+
100};
+
101
+
102#define buzzerOn() pinMode(45,OUTPUT),digitalWrite(45, HIGH)
+
103#define buzzerOff() pinMode(45,OUTPUT),digitalWrite(45, LOW)
+
104
+
105#endif // MeAuriga_H
+
Header for Me4Button.cpp module.
+
Header file for Me7SegmentDisplay.cpp.
+
Header for MeBluetooth.cpp module.
+
Header for MeBuzzer.cpp module.
+
Header for MeColorSensor.cpp module.
+
Header for MeCompass.cpp module.
+
Configuration file of library.
+
Header for MeDCMotor.cpp module.
+
Header for MeEncoderMotor.cpp module.
+
Header for MeEncoderNew.cpp module.
+
Header for MeEncoderOnBoard.cpp module.
+
Header for MeFlameSensor.cpp module.
+
Header for MeGasSensor.cpp module.
+
Header for MeGyro.cpp module.
+
Header for for MeHumitureSensor.cpp module.
+
Header for for MeInfraredReceiver.cpp module.
+
Header for MeJoystick.cpp module.
+
Header for MeLEDMatrix.cpp module.
+
Header file for Me-Light Sensor.cpp.
+
Header for MeLimitSwitch.cpp.
+
Header for for MeLineFollower.cpp module.
+
Header for MeOnBoardTemp.cpp module.
+
Header for MePIRMotionSensor.cpp.
+
Header for MePS2.cpp module.
+
Header for for MePm25Sensor.cpp module.
+
Header for MePotentiometer.cpp.
+
Header for MeRGBLed.cpp module.
+
Header for for MeSerial.cpp module.
+
Header for MeShutter.cpp module.
+
Header for for MeSmartServo.cpp module.
+
Header for MeStepper.cpp module.
+
Header for MeTemperature.cpp module.
+
Header for for MeTouchSensor.cpp module.
+
Header for MeUSBHost.cpp module.
+
Header for for MeUltrasonicSensor.cpp module.
+
Header for for MeWifi.cpp module.
+
Definition MeEncoderOnBoard.h:122
+
Definition MePort.h:71
+
+
+ + + + diff --git a/doc/html/_me_base_board_8h.html b/doc/html/_me_base_board_8h.html new file mode 100644 index 00000000..c8be27f6 --- /dev/null +++ b/doc/html/_me_base_board_8h.html @@ -0,0 +1,461 @@ + + + + + + + +MakeBlock Drive Updated: src/MeBaseBoard.h File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeBaseBoard.h File Reference
+
+
+ +

Driver for BaseBoard. +More...

+
#include <Arduino.h>
+#include "MeConfig.h"
+#include "Me7SegmentDisplay.h"
+#include "MeUltrasonicSensor.h"
+#include "MeDCMotor.h"
+#include "MeRGBLed.h"
+#include "Me4Button.h"
+#include "MePotentiometer.h"
+#include "MeJoystick.h"
+#include "MePIRMotionSensor.h"
+#include "MeShutter.h"
+#include "MeLineFollower.h"
+#include "MeSoundSensor.h"
+#include "MeLimitSwitch.h"
+#include "MeLightSensor.h"
+#include "MeSerial.h"
+#include "MeBluetooth.h"
+#include "MeWifi.h"
+#include "MeTemperature.h"
+#include "MeGyro.h"
+#include "MeInfraredReceiver.h"
+#include "MeCompass.h"
+#include "MeUSBHost.h"
+#include "MeTouchSensor.h"
+#include "MeStepper.h"
+#include "MeEncoderMotor.h"
+#include "MeEncoderNew.h"
+#include "MeBuzzer.h"
+#include "MeLEDMatrix.h"
+#include "MeHumitureSensor.h"
+#include "MeFlameSensor.h"
+#include "MeGasSensor.h"
+
+Include dependency graph for MeBaseBoard.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + + +

+Macros

+#define buzzerOn()   DDRE |= 0x04,PORTE |= B00000100
 
+#define buzzerOff()   DDRE |= 0x04,PORTE &= B11111011
 
+ + + +

+Variables

MePort_Sig mePort [17]
 
+

Detailed Description

+

Driver for BaseBoard.

+
Copyright (C), 2012-2016, MakeBlock
+
Author
MakeBlock
+
Version
V1.0.2
+
Date
2016/09/20
+

Driver for BaseBoard.

+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is Hardware adaptation layer between BaseBoard board and all MakeBlock drives
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan         2015/09/01         1.0.0            Rebuild the old lib.
+Scott wang       2016/09/18         1.0.1            Add the PORT[15].
+Scott            2016/09/20         1.0.2            Add the PORT[16].
+
+

Variable Documentation

+ +

◆ mePort

+ +
+
+ + + + +
MePort_Sig mePort[17]
+
+Initial value:
=
+
{
+
{ NC, NC }, { 11, A8 }, { 13, A11 }, { A10, A9 }, { 1, 0 },
+
{ MISO, SCK }, { A0, A1 }, { A2, A3 }, { A4, A5 }, { 6, 7 },
+
{ 5, 4 }, { NC, NC }, { NC, NC }, { NC, NC }, { NC, NC },
+
{ NC, NC },{ NC, NC },
+
}
+
+
+
+
+
+ + + + diff --git a/doc/html/_me_base_board_8h__incl.map b/doc/html/_me_base_board_8h__incl.map new file mode 100644 index 00000000..7d0ad21e --- /dev/null +++ b/doc/html/_me_base_board_8h__incl.map @@ -0,0 +1,250 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_base_board_8h__incl.md5 b/doc/html/_me_base_board_8h__incl.md5 new file mode 100644 index 00000000..a12ce33b --- /dev/null +++ b/doc/html/_me_base_board_8h__incl.md5 @@ -0,0 +1 @@ +c14ae602891d7e71ac8c86588ab03448 \ No newline at end of file diff --git a/doc/html/_me_base_board_8h__incl.png b/doc/html/_me_base_board_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..5fcb791ec934b1e2a221bdf60c44aa4841baf006 GIT binary patch literal 780350 zcmdS9cT`hbw?0ho1Q3KEp$ICXv``az2L(Yz={?e<6M8QS2qB0lgkA-eE=aEe2}&Ro z>Ai;Dd;K`??f0BJ#_!*6WsIzyIg&l*T61TvXFl_J_f%V*mg*K20RaK+BMp`31OzwT z2nYxlDafuZ?B@P8*AtnQrn(Bj)nBiy#)1R_0xp6_DvB?B($*(65&WZp_@k{W6}bm% zrrkCP)xYv(7FsxP>yCuqEfJyUkoS>^!e(D;fr>ySkICtI%;T7T8eOBsU=prAK852|Y zDK4t>3pOgjP_l`T`~NqC6XZWc&GnD&at4+*ovsE0VF4?KLXiPA7dxC+J8U>VR+Ybx z&D^~r7KOjtuPt(?R*0)l$rnQvW`L7k-S(G%|CZbbCbydm|1jbU=8lh1LV+uqI6v@$ z^776+=6r!y-ghYG_TOE0cbPR53W@rE9i5TM+$Dd%%l~B=e)>=xx7v{D8 zIfC)F>z^bWe1ekN2D|W~jU&0k4g6}+$kOSmZzI(T)xL(aOz{Wf&ac){;F|dy;+dZE ztF@~W{o{@+-^_ZUA~MBN>NivOmQOcag8khl1H*GuHwV&&O!H6jsv9?8H7gS1C8fgy z30lVg<QWrbK)w&FJp>LS zlbGp!&Ns3pG3TVEQ6rrSr?`5@U~__|S+Cng=FF0pcdFn8?GoCTMr51je!lL*QERWo z_6yh`K0%_U9VOph zImtS&#bGsOgXKnCPYO2?G2|%{K{htv zEP-}!&5|vj&_6MMIzx>r*qJt)h`oe5o9r|wkiwH?*&Kc`G_q_(*wwB7GPL`k&rvzt zV^Sa|PYszQb-a4MONG!DjLT0I*jy7!ni7b-$1d}yI%Y;q%vJKS=mT#W%tVwPInTfw z+mlQb-1;^tXKumSJW0j=mo!zGUTpuWE3XhAAl4u+oD|!7tIq&VQDvg}mQ__t-yp+` z_s!zBLyci#=GB*sV9mA9Wgh-r55+GGdxF5-r~Xpm(irn>c8S1)LH*1}od=JWYU{9t zJAc+Vrj=!fQm=!sBXq$de3>k6j@hv79@AuQk(vI+0Q4evXgAz*czd2wY_6#qB!{nO zoZpq`y1T8m@S{nvad&90lx!0T^MJvF8He*z@4=2wKc7^knuE2Y<+mnm{Jl93)E2WH z&u`1!9X}M(Q65~hq$+8dy?s8_?DP8J(v3}aI=S&vY`u2$_>@r3nidu~y;Y(^|JbYN zoFi^9W2QVsbjM$Ai1(e6e}nSG2vBNb_0y}+@=1w%?8z9xr0QDxFWZ~vhdZ0N^Y?qh zW)6^*D@Gz5DFN%`@g(49{{M;xC5Y z#O6vdQ7XK`#J0}8Zkrgk%J!e4h)L;d9cz8+4IpNU+0v!2WT%~^7wsM}yl9Rk9E+o! z`PO9f@&`x$I5S}KR{6NAD$>xbY|1+Zf@jMY2|b8PVpTS#w5??;RMYI&F_hjOwBAqo=+L@5%Nm}X8kgNPrO&%uTwhE*`NMVRNyeQqqv@l3 z`-vq99eDDlba5orNRR=;;?MD^2-yE24urpT? zGp;Xkckym2&T41<;f(*tJeD+z?H)Umk+gYH9I_yYp0HED%bsuZFwo8RhQ1(msM~%0 z!*ujZt+VWKJ35bmw-pYO?R_rY%PGYOymLL!zBybp}>KJC`>TB%5D53>;?#%m*LkTBT%o?+IdFcC;XJwOjE#`-Pp_!g6fs;q=S8ZYq8~ z`vPTj>u9E($<`Gks=ZAq57$%A2HaZaYZH~%ETrF2exDg!i8eD%KSL>Q(L4_TKZnE& zcd~!8uu$WQe35!YO)q&geJr@5mIQ!%s{!=^ zqVS&etCJGqt8GA>H-mvw(3P0;nOKsgF3Aty)TIl_Cl2G4nM(m%-?dWnYd1~{*b`~x zuZCYV?{dCfs;C=eG9!C4nf3e0?0&!Yv?CzL*^(X>9WEu@TDGi3OQH4-#_%{CscdgQ zeuKZmC|7yfSwPtqZEqPQa#042>Fq^a# z!gx$trtpm7U|Nq_O>yymSVHXb+`-mh&9A~eOV`;(;&#peX z><-U?2wCGv4kydrxQwc5Ny^ZlwHLVd*=Hm464UPE#^mq1fivF6$t{-xb6E0;?X;+% zn2Uu~N(zbXxuq!Aq}2J=>L^n65ue@I{2xb6g%c>&hv2;*Y+$f)u=#l1uf!wV!vWS} zvZ3J#*Rc08>2PO?qm<&UEu)0(VqOJ%Y{ZTFpo>v~p-gDPH~7Wr+DntMfD>Phfir!? z)cLnb2?~M#fk88caWhwme+S8(>eZ1bL>=}@L)U_`m%73|5O4d zYpP+nWRU>X%c`}hs0|=_BC%ki(g*UG6V@~ST+@xtuRrEY2_bd(2Q}KFe+B_1z@)M$ zzZYncV^&>65qph$#Aes=J62J>Ic}S@TA_Kf!rA^OmW*^J{ZYlv(TQ)OE528!ITyS# z`Pj9h7dW?OUX>aq%IVO2CM&HIaf!TnS1_@Bma z3+3Lew%pF6e`QwPmu|;r@giPH8!oyO;{VE7?GsPsK!=|s8p0k<1zYMBN2wMND8=WG zd-A-W`@_ynOca=vRGln&S%d}Fi{5rBw8>kxpi*E}PV@EXS#?Ti?X--5t66Bj0us&t zP6nFLC;P|kxnn(WHQ(gA7T20zvni_+m|vX^Ps>1|C&hminn&h4yX6PRJFuVthV854 z=1WrgiRBM-?xrP_^Q<4is%YE1KsSVa+sdXzsGzp%@&d#o)A(H8*ZYBH_VWT~|9rc9 zC*J`x&K{3KhXlRH^^%-TZoODS?4nP&bzrC@OUDRbKUpu=l91oDbiV%aNmN9ir2Ut$ zGQE2mNkmGoBqOc8-Rd?y%Eib;fdrEcnO`y1ljlc0yHx^22BHgzMEPla1RbYbHJ2EKZ>C zu&_3wgNb8@qsNR4-jS5Fld~`RnwXl?2Z}$fzi|a03cJc}xFX_`N;tJ8QLxyIO<*7~ zjuR+BCIzBhc?B_>=`Dkt0Ui0NdLdCV4TCrViR42deMxio>LXK$+9z5g2tv0rrwQO2 zw*1*10%ug*bVEZ>+jsuNBjzqfX9JES{b_DiuT**8~2X zZ!ugi9-c0EtQ{u~L_gY`@y*y!h)|T~KloUglYcB?HHMIcw)aNegPJTJGcWmg^e`W3 zf}?EgvRPeUcW~#xZJ;5m!W}i=N*|`d>Gq`C3riGpDu-A?=;*-61S9;pvp$1=f9d}V(6*Q*W>hiON5K3YsOm}#G3 zh-ZOmtYw$WX@@XMUl|_NUY#`un=$B*F8oCf9judF{m@_2aA(&NuOj&@Kq_9!-@$1M zxr>$|A0XD|br}z9Yq6li3vUruB@YMF=4Y6t_OXk?HY1GN_e2hax!yMTLt7ef8&zNQ z^Fr4C3`htNiH1MOZ~TSL+Gfh%Sb)5qCW;vFT$c9W-{5s&j4RfNAK~kHDJuxaPh{P3 zb&fZD^GvuzX3{yMw0^fzr=EyP)F$I+t*N&l<$6T4y+_#14L3*Rr{Vd2Wu5HZ64o=a zbRd-KX^j9k-n4Xtj&!LkuAtNl)A+*7<)+$LbolIx*sqWk=!gEMlQ)FE>E4?nr9%M% zv6cc(F$2Isi0#Q9`(oF1AkKD42+49myCp98!~%7#>e6uARzAv=AWt8$mM_wlUZd8B zljhZZtKUD9dYmm~R!O65M9TmaybMGPo z=FggpP2`cVe(UMzweWpaEbN0r`{0F^vM^HCnKjj5t)hWBQn{+TI*=&$W$}g0nscb> zNP~7s%&t_-QBi88&d49L9>L1CU0Ti;GMDefwOzme@^qUV3=AF^qx|$5aCZpEBi3;c z=q~{5)6dz9vG;=&)!09C68PSnW<9?*FeD~9f#KQ9vABTux4gt=E=qiIZIa9ucdns$ z5qx@c{22J(DFivB+?y+Q{r^oWsK~twIwKGA0qQPW{Kc#o*hX}4t48tPc%W&C0o6$n zY%2);vD8>LM$)51x2^BnF(?an5o)xgx4ld}2gP(H-Z}nKU#69KI9_3QJhB?w#Kf#*hDmj31^LyV=;zAG!D<-!2=i|) zW}Y*SgKod4OP3Nhfp!$(@cz0=>u#Xfi>Gd=`2t)$gD?`yx}Y(^)lwoINFkbR z@9cpc1ygM9gQY?i4LI_EMpU_X{i{_ z@06|qaO)-@I1KZ$R@cw~O(QE(!IYh9r6nr@AmxeFSm?KW75cT!cNQTlyxWPec~uF> zUZ602C^7bHSoL0YEV5}g;s`)DdIZ2&_B4?mvLDL0Yt6J+on}-9L+*6g9J*_55&##r zw{G)URCrIGyDwWK;A+tzBypNF!WErSm7bIbT%)%|ZNXV*xXI9DJl;KcINBdQc&2aC zaPqRSBy~&q1Wnh-hVud7p-1~S^)Au-gRzWoxwku@RGt~#=RohBVf`kd%hKRW9i51) zCC&$P4^m}<&QY1?=O0%&ue_(>KCS)mvY^S$mIH8!)R?{6qINr2Qt7(jHqK4cO}o9~ zDa}o4Yzu_PeI(l?6y=>^vhk4Fp!3F#bai=|GBvjYXA!RVNb(_~2ypy^xPb?nXUGRq zZ*KzQ6{ysX8jyCZ? zDvt6(ZQ7TtAlI{&6%vT4%GXEZ=c=d_P&&YVx|c>*noqCM-u#(b!}47Ehn*tL`@a`a zO~}|3FxU5aG#5~Mvx|}S&laJ~bUre2C|>kPPs<}ytm;t`)PGp+l2*|pygwUj{_uHP zjR>(0?j>EsY&&Y&8%UyAZY-ldIsu&E0Zh|G0pJTYa!@7vyd&y9Xa&=E_F7S673Els zi%afimaoAa#q@?V{65j0iKG=$1V#t%N`prw)G!&J^{2L5_v*W{CMz)^W#>&NY2S(? z9M|v$7l9Wh#sOQ!3ARN|Mm(AdHE8?Sv_7HcW(X)4Z}0)HaMz;xawPuVkduAI@E zMQ-V(X&$-0HvqWO9V0u$%}}%#;gHT$xm-z+IQNfYu#Hj3qu|7*;H&7qRP!I!6MEN8 z2;suB`TW5^_(1-Jhm&XUWM$o!v(aQ+b;(}r*|1nQ?b*?iSar9HfLXI;hVgv;+I(pK z;YgPFz(!p7c)G_@crVDfQph}Zbu4kb1R?!8o;Ilzsr>rke0&H0`22^V-D2%}ac#ro zL$q%R+2N>ggrOX&!yx}rU*Lan=<#$cswV$Ejr=Qr$SF4M1WpSeF6|SEW{jp(s_ zBEel5d}4S$P`9(MA5Ay~&_9t{egCZKqW3ugbs8Ljx(c)*j6*vJ+jx8V=H!>{waqb&Xtf_@Wd2*^7o~rEsx}h!1e+aixEdbX*eqcy$l2_!4H+AOE}2z!ne*^N8ot+`A+UL=XFca49GvabQ8b4N?Ccxl4|lk z2a(kBRvJ&nBPj^4bVCgfd}d_(afKZb3ngz}H)zOoglo!+uKU3Gnp{;IA`Jzq(c zcKIvGm%Kt%`S@sh_rma(X89c4CIH!~d6>I(VT)@#OS)>}F8Tgz9us%+ODE{(T4{5W z=eVIft`HntFfhN@60;f5ioiXKj7*0akm$IK9jRoA6>tlC+GZSyF7>+Q+BS)&_$gAo z%J^V~N^1G^nPPMeQwR1M-W0#A$R(XgIi(`e()mr9KvpS}|aUSo2r5 z`SZbW(Kzi&1UAmKY%Fqgk?X6Qp0J?WcOHW5{d(3#s*ZZS3GkEe>m!Ug7LYp1%5RndK zEmC{6MgP8dSe<>mPO$Dr56b@*CsyFC@c^8gG=OKtR(G-dxwV=lU$0T~)`Jj>h}r>M zZi6h1JN9raYnS=P`I~-r`L+Z<`*lkjM$$W?un!||w#GDv2 z&$s^IN`o&QoaGL36$_La%hpo4Zh`}wEYSQPi!TLWAbVTmv=TmWRy7Fjs_+05k(oY}xoFC7@#=CERUJe`9!)^(>Kp}KH;-g zx!V)?!@eycC{J1*es-z-4=un%=O;YsH+PAO^sBj^+5i$_%7Ui^#H_(ANo$b+41 zI>E2}08@GtC1v1RR~YvkZa3TPE=Fd|%Q5%wjbC$L%I zz99TU8sZPIQ4=EX4f{O&5))$Qv0<Fk2?-_An*I3e!- z=I3vlpRx+g1vI(KxolG$6ZOOZGs)$2q!A*7K{hT|ni*%3R|82*Zl9hwGrBbvPM@({ zrb%a3h2e`A;#tm(nNNte?~|Dc<8||n*9iH>;HejO_ULw=1ewkB8Zg~cG?U<#LA2ZE zhnznSinsfHj>}tNdRJ0y2EwAiXJEIs?y_YM;&sEZ{LPxrKnDl^GMZp#DzV|AYFbYc zX0;`R?8fjt1x13mkFED7-X-P~`R6s)Ln}?y;YT64pv>vTr6Ztdf7NB$zL|xiYYIO2 zCQt7Bxk~s$)KhR5tl~G(XZ4Bay^V-?B3tjpz&`E|V^qUc#9!5iiwX}8^h()u)&zdO zD#t>{?0WLdO2O&;bCpQCn`rw%OOwpr*^TrerA>{2SC`Vk-CJeh!BZseJ4EJ!_Hnu zjNTLb`MuaKwK}}ASivdCiGOpL;?L5CspxrCjXC>o=P4I3yX_4n9``k^Z`zklZa>*V z{=LgKNS_`R)v2xx$37pw^~(uinWBdg{W0i9TZB1cNh(FanFqEHd`po2MtkET8)YIJ zpLU+=`a4#lj)xKqKzojHzSB$%lX6YpiV+nSZNCV1H;iC{2GU>xM^JEU#EPjjvjesQ zdatmc8JHx%QX?)$>~j?zbKNK?eqZumsfYg`8X%kxQ|CBRb2z%g&8kUVSJzS)Kn5IN z>cB(gG6bG15@hMlxpMR#z9GvZX>~LZ zR)flx!DqcNZR5IBR?4l04=zh;AiKiwal7#Qx6aM4*OMxhC`HzrHjo&8&|M z2Fc__dY95W83jqY!drIh-1)Dh4d&0Jzi9ORfoiMH{N}!kCKYZyz8mlM#@uLz%2vZD zQaSuPpx_4U4OBh6_SX1r^hr-zSC?SL)@5Dn=J|*`l{ zl!E6fbhB_>=4UN+au%ws|g9PBf2XC zzT*}nIw^`ijp}Y~GsYOuP9f3K{&$}R(UKI!^CHKPJ8+EYsJ;%)(hXtm@KNJe^dKGOUA~S2e+&x+Ou^=Ks{fRU|12y zI+MinpqyHnylv}6H5vwZ8&y`c$0X1oBMBNlX#KjO^tIr?69(LmMF&#-*Z~_yaj66g znow@3DFM{b-4yzAl+r?=PUx;_zX*GzHPgZUxY#3&aZHdIdb|N&sKNWC=67~qg{sLP zD7A2`@K2zTpNw*UlSdew<1bp89wKTxN2;F=W=Rjc7kvEP)Jz(0e2P8_tQJ1yv8@)( z;w)JAl-kdM0})7dB)HCIeRzx7-StO|n@Ofvs7Kg`M)cVN@$;60H~V`s4VKSdd!BoT ziFN>`UnB~~BWAR(RueO);yZacrfNU-MMM^y=9mI>(G9zcG;H^iV?GzM8~-i#2x= zlrwoFyHQZ#O#O<_79}qKn4Ws@$Se*6Z8-zU+k%9Sy(aU_3yOFI;uwb63_N*|$N!&wo84bIQHB4NZ2s*^=4JB*vAhg|DM9c|uh$f$ zu(GbUEEL8F&AXND(o>>{8z77_^*-!gwgAmAkwx}V+JIOM0R4(m$9*AzHTneomTogs z6t+VYr3wJjIstBxKYgF1$exiKtlFc%#ww(t1T3GP8Ag{Q2>z-?+NAH!=e&CUud;fK zoc*`@ltZbn&yoH>=uc1jucB>M@fpp6n6m@PcK0SUEWey8%z0S2vOgno1u#F$ zS!`|geDRf4v+jtni41&86pl^rr;*eo$L4pKpW9Zx7tBu(q6Q}Berp|8w${PwzVXbc z@`1ZW?FFsKFJIB=Nyl8s8_gEEsK$>{e=PHz>3J`9Q4kN3ZeH`7?#D_JYsXL2dj zDEuYcOJ<=&@?ZE+sE9jNI+yOq_ey>Tp*$3$kz76A-W|0{RC-GaslxQOOjz-x9=AS zHEG+UxR|&z+^RNsh{-aL!3Wvh*Tgm-196dV&;=H}obm8MpIwWGY;@+!1J=l=I6aSF zxN`U|!~lhe;)I(tOwP}!D`Cb3Ez)Ez>UhlUNF!Nuy~E?Rtp-P1Hrtv|?h^NOI_36* zl2s=aR}N?cs+ulN_)>e`^MF+{L)1Lxmx|8WX4!3kJZ^l(T*XHcqD=QO5v?Vf6|Fs- zwWWqjyHH!$A8i7MI7ii@Cf`fzWsA+AO>W6lsUH2u_j5$HkmJ&4~4(t+?n;OHy`jOw5<( z7lw+jrV)ZG@DOb+@T4<%sh4G&gNUb8o#!8|T<7xJi+y6EPj!brkqv3O`cF16{(TN^rA|R;;eIOS+?UH@=$MASb1RPjB0*UxXajn7@J@$&eQa0! zhcdgZgdcyKi^EPOuQ2b1d=^rw;6z*=P69E`ptEM>h2wAN5P}^rxct0f8P9!IF7$p1 zd0B|M3zo-~dDs5+<9Y5kGI6YJ=_onPDK^|d7U-bMbWO7;5AOFv?!^tk-Xo$e z4MN&SE`h-9)gjg*md;;-- zN&6Au4c;3NNpmtve$vOCgzV;^yhNV6WG}Uno?$eiurNt>l-|#isW)H3adH{|#;-Mb zuk=KF(A$3L->bY9U%po|fYdWnM7eLUWtE&)smMdO(p{(F+j;oJ24KPF% zG9jHvg$0+$kT#TPJo_3Y+Cf3K2Le-`C_HVWfRHg|BtqYZ-HGV?1@1vAZfkT7fFpkn z$ZsB8b<$XoR96OkBA<|9Z&?)<=e7E1fc!c{o-PHaIbx!E5-0RlHS9C}v+c_66^nft z_RjkGUe8xNbUssANYda9zCb zhdojpm#a3MR#T0B^F)>%D3gN}{~Ydub6v{#X~hUfgWYcu$v)qAk_4K<4`s^2;RGPx zXw~$ZJw9Vu1?eYOvf<{C2I>a72J(ir9wDp`j=Py(`doyJ<0|ed3PX4E==6*4A}wbc z$Q?wDg#7}C&eIPJOSP=_l#^<^BH57w8=7m)soV>qI`NsJGc9z2>yaO zs-NB?-r9YR@!=zr!*73pW@3C8@YMYC-+!=f1A278LD73vY{85O?}=kRc#t1>F1_I9 z`-_X}fMB`V>BZnPm&@^l&2!1WN=^>>Ags>iQo+ZoUstZjyjSfJlGF3K*2dd|u`J!b zQ!{rZ< z<2@jUr#b%I27_ydVn{fYPuIZaWO0+e6SQd=X4_p$hx66JGm*rQqM5RgwvpN12gnHs z04nEv^3e6;v~kA!!*F$e;IE^#q@5HH+C=1K+RG=9Q;K0`OIY+(-WO+f7o*T z0BES81vp3J*3&qX7Hw&1V$fQK5;?zSEpHX8dtCB~$|ds23hZH=ABf76pbgUKnq3reIr?S~l+RJx457(ApQCY< zjAPwm)jya&;Tqhcvqfhg@hNpY`b#++4I1+tp$;`efLQk*;UZ=Go8#U=+l?`ny00Wm zb)+>aRoT6ZFnhKTMp3j`q<(t#XPjC-fQOo?73E*+FnYsX28U3(JL7CUw1%%y=@K^J(8w41TEi`(?zhGK>q zMc3KO^Z?&i{h6PGgKgqw9fXVnMcA&%{&-^tQU>H|sVZ?Wx+bO65(0X2XA_7O4P>OPC~LU@gj z+!$*6QS4@u;Uzm%RPY1nlK<8a0VVu~b3b{Xx%D3^hE7b}-x)W$FLDY+a>7M&z#=({ zBDw8CxtT(_-a@$=2jeJWBXSp7y)clsY*eu9?>>k|@I2w^1_Xl&NOd4)XGb3pK9izf zg|+|1kMWu59zgHMB5@;pRAie_qBKx4BgOjC``5!sJGqPmk%2Oidc^gfG7xk9$cRT%q{c8pTg)qp z$!1?8z6E&=l`ra`z1Ch=GY$#$i~=3a-#`Wep$}U4r9P1^LGJRE+ydL=ovB2MVAM2q zvW@sVbaM+r9+3GjdB~KhQ^{{lIZ-BCL4>`x-z$B&jcap%F24BAkzue=Q1FMvQ$H%j zq!aK<1}lwcqH*ySEBJw(%6{oYr5e-zY2$8ke3-(c1sY?LWHcEgBD>%uGk)lTl<$uR zDFTb~UHD04?a?Fi7t2x@U4DSte<0}8)4tMuIy@Q{$lNe4MQdw>oI%;?c~O8h(rIoS5!BFfEwiT$XF(>df}a9bbAi zH$6VtI4)?F`&6N*q&b%LSl185+#)}fswm`V;Hk`uBbw21X_WYA{cC%9`u63RB*7H; zxX|wWev5fWXB=v$R1WDj{N%4cXQY3F1v=O6`i+__&Q)$B6nDe7Z#JG)sEmU~;L&`) z#x2bQz1&iOsOS{Nmkw_lel+2e*$EAehbGv)XpMR?6FSB1)95RGW;hflYd~#QiWE;7 zAMwr148&VYk5_32;e`TlHXs&K_4KfLDx}f^#3;H+2|2BX+l?CroJQi+oP zO}aCh>J2SGKYVN}W*hOGR06!pr2TE7h>COKT!vrd5@J1V+Z}uZDWYC2!!M*4F4>D^C>;i(B0#E$M zEkI}Pj?sg>(WH9lkM@UC$3=M;XBJtW&$}agL9m~GUnDLvqd#{*m|6zTb__4?`EhvX z*GrT*ARZA;)KK|K^|^KN*1SC&`2(shYbd#7hg}59s*(0Sa{3SK%yG?%{U-KVm+iPutJa6Q$>$6<1+^sb zd`mL5nZEF3lkIrPk862-2bf4cRU8pU=p0Q-TtpVmR&HTHN4E7HYUY#R1p&68AX@y5 z9Qn>4$#mg$&e#bzM6xQ8a2o}487fEgvofaNNh%|Mn3k{qy1~=V^mHTPr${|e79kt{ zGf)8GnLzcW%cj=lv4!{@WAlNgB5vVUzV0tF>>m2@FcXfi{4<2VDVBt3d*7*9YbP-| zup6Xo3fdbdSoMejY8oQKjg7A2nF!!Is&4$*McXu~H0q^0>leF%@Y&285V zU_m&@eLkL+e9?}9TX z==1$UyKxmiAnEZw`Q+!}EYg^~4kx}l#{Q97MuCw5o z_on9w6^G z`eDIb^S`??nvADr}ioIwF9ZBN&=q8M23`dDYZ?f?J-oN`T>KlkLUp)RbOHDid zia1i##|G@)Wzch4v=5^7^-3wHF4shBho?uS?;HwR@an6zQSbN*-WIgNrqnF3Cuz;j zi3%EK#u$Fm!6Ab+$H-vmZM`<^9fczjsq5 zQxtOVSpzWP2CZm*`7uySZN)a6OKj8*WJS8nHTG<7R827>x=(QjoD1uf(7~`dfu6Wa z-OPOwH{^BLfy?NBvn4Xrjp~%q_2p7Z4aeCz|bvIFqKYPtV0J3mA82{!qYb1Cyl?c5PpWU22$;eKFJlS(3#Uot=a z3ne8wOT&tH&KiXcmKAslj_`%^fBakxj3IM+3;PXF z9I3EEryY4v^OcZ}Y8L`wYswDXu*IaUiW7&i+IQ`#?{jpBff5;%PZ9P?pn?et6UHpy zIDdw@d=q6h{n+~)yQc^^k)%ZtTviz)$9Gekc%;b3$fP+Z^FrTJ(v4+t<80YWnxv{}UvzJb{RYOH%i;`?l5K2r z4e@gaG*rfD$v0tnpU)C@9o|;eK#&YnN!lOf3S}bm9-o|77W;16ynCHmlre3_QxJ>6 zM0eHBJ?1uk%dNrDB4f&lwjj8_RMbBFb{;>7b7brZ4PX9xA5B0*1tU`J>uS{vl=798 z(Py}De5=@3`r$dR=r@uek+k2P-A8qd}; z9BQyRhXsOoz+tQS!5E|aDfhKvqG->M zllzx*-c5`(&tqZsu4fTHR1CGt%{~}fex-jFu$e37QiXMWh)nON=vpt70{D!;<}5yz zbI`Agmg7KYcMr?-gez&%7}Ls?uvB=;oS~R7YB_v>0PIj9J%)F);EN#{>G4j50zim=sonn4YxkhtRBzYI3{WZS0ET)Xp zON#R_l-~>!Xl2DKF(N;pEcZJ3_8C!eqYF~g#zbP?{qxVoal>fO0xF{}lft4Oqf2q6 z`XBt)KdL?GYA{9zwgk4+Q(R>STe<#j`^w`Pw9y_oB!B2RnGU^_m~$bPSBi3Ida(0W zC}_m2X2{y-m^DygjwN(U`MmUmLjLOWSyAn%KSzL3rucDzh}>ZZ`TE-M>7>K^^=#V{ z$*42zaXf~jOuqScW<4^~*C<$=5%cOC-vS7qrVprfI5%=L+1(cPQ<>W$cDY*_YCV%` zCL<;FlW}-2HDKBP!t~u0mi370Qe;-XoHT%KKCTh}ftbXfW-4??-(X`LcPjwHHto61 zzIEb^+c{hDc`cx>^G#yZB8l;glsu=!<0{K#x7=K0)5^(Yf_RL1u04Z5^fmJx`vfC@ zt&Ml(RIXF)P(%z6--u6RWl68$a;s|o*}!J&*cft1mF*pX3M?LOL(Nyz{~Hd|9l7`|pHf^{}IyoWaV__>EwjCQHP&gi|R z#A33j`hYEVFe$ly24pL&f4O^15K^F zHou7mXord+oBVU=?u7t{IAf+E7gy}}w`G+9MecdO-;T=$$-6!Nv`4LV2%5j3%DoBx zgx4}aqpnG#AHDa`xhg(PIZ^ru2BcyE#q*SBKMl}&bCXYN?zgYRD3C8(@ZUh+Hxgma z&2n{iHLhGhd1u@Or8o7J>>GabW0pI5mZHvS`wF#Qb>CUn`C)sG#M*dQosxug--h1W zi>H;TcM*%?8@4t3UX%uA(@3)BNP!|kTv*-o7UIOzX{Y9Z ziM#lzmLUHgx8gD2wpx5vq-wk#KY|Gt!-RSKkjbiaaL%2hkH{7IS%#^EoBE>qC`acm zMa?-?OfJ>*Np0NdglCb?e;fcA?v5!jMe~Ja-7D>9J52;413CTyFt9YD1MNeQh`5BhtW_4g7BaJA75`77uDBy536){4BcJBfTSQur${%<&|T6Y z14s?ssRDx19a2(5gMf51l!SDL&v;+I>#pZ>|6d+nojIJn*7~ls_SqlT>-09R*1B_{ z`0qU092oh~tEEPbq%l2gDePDA`!GoUJIpUpCie>ecPjXw*xySPFJ1D>EFpV3bL18_ zM0oq$R4E zhi0aB28o9^N+#@P;Y1&OPewCTq{mTy5mg+HOD^zDKH&Ye!L{iH&)8k`VF&g(Dl;?& zr*@P_<(UIzB_S&5z9EZ&yqL1#3`o|Hy!wS6t4PEbmV28!InFPD72F#Jc?G(iZV$2O z7!a4)&y$~{TCooUzG}M*YHC0Fc8PoIT4X92O66s@zo0*G0$$ft$2GF+l5q>_@kC{O zLl27X=zcyv`uZRe)k;fr8&y}%MuEJKpX?(a(7{;MT#vMuFZM(N+fa5E7Az#X#fHm# zm7fiIZAZYEg}(=-Du{vLYT0@!YsrupL(wdvu#KDR|C_i-z>qIDb&t|0G0{iyZ*+ha%X zmNMkGhD(S@wru>qDPe^;#I{Bg*Sny>L(iCOyYi^@n?T~4*)zVJ2*+r{wOad%qUkM@ z;B!QyZ>-+M`(p*d`t+Mk?QE)1-!h6L0bdFDizbyBBe#uIuBx{;GSPQuly+J&Rew2CG zoRc&o8#TGa2+{4j@P__QR!@XAXRLXZE}xOxd69x`vE8{OC=K>LVMCt;6s16_FEo;w zG&5jsOUWl4`Qu2KQ?B~NNMNUcfvowU8Sr=Hxk9lNhu2C@;a(K5ONWL%kLg}$ zRZ|we&P92anCbE9oo>s(Tm?c7xZS=Q6kHG2vS-Hn z#B(b3I#|yZjmFw8px-Ywq<232>yG|40*x{#oBR*r`H#E(H}N#TqQoSmL3Ajn2T@V# zlB9&mnLrj`rM;;zA{^Ow%5n{a7?iNDN+WoJ;Y=;hG0_`~F-CG~IL2cD>S$lB6t&j$ zl^)OspA|$T_0L|OlvN4$Cr4W!WtFH@5%6Xtbx!noy9&kU|JL1KQNGn;!u}Ljs+2x&ASf=IMA^Yb#amhR-m-S$Gt<*03S}O!q1H1e>_hFcXX~t0 z$IZ}8p{v&-pJH&71%na>t49!JKPi>S5Ijk#N$fFT*d{vK(a-;YDVo~(Ukc7TCzNSH;-WOBsQ&WkaIQbn{?zAd&B=NSdk zFc|=8Xl|PL7P?FovI~nRmR4Y|+MvH_ki8{mu?C?I9{Rg`FnZ(|^Xr1-TZ~ha(~2DG zl=l9?$Zi6Y&Ww$`e9W!BuGe$(=MF#5skORfhS82E$>0 z!?HD6wv~8yktQW1pPU!f{<43J>Ae$JiM?i!`RC zc%A;q2eSJX66veC$iuIPZCAGW6P6_WRDlQ_g5xHa_lZ|?vu}ND?&*$m%zfV#Hp$-J z4WwlM(iP(xF9EKoUVpfoUP4YMK|dZz*FKdrp!iZ=2YkOGd?W$&^1x?_G_A<;gU(TA zzU5obzdX3@2{&ktxPB$p5wUYshi%(l^4?eC7=P{1rtJlMSwQZ$(XX>Z33ZMjiE8!v zeWIBd9(}cup@LLFnvek+GKLh}AsFp$w$No|3n(qn$r{Vma^4_{y4bu6)2k6>0=K}a`a?yx*3M~0zEP75U zHfA>j)td2t6eX5o5cO<eP&H0>Qoi${QY+));2+GBQd$|i>Q z;_@7*LZ2DhdGlA55*JvaxQtKh-RoJ5Z0fNlhl&FUdyEoWBX&Hq4db>iF7>S|<*}*z z_t?lT*R6ilX5CjR6Z&{z?$3AG84<2~2a@)PE8^I#|FY1+H~yq;ZsT$!nnyipW3D*V zc?Dh?qyhD1rbIZ4gTX)h`yn;?1q2-MR2xhPpEY1uK(@HGvWa=)0cp z1CB2NMOJnuZTh1>_$wfUwe%z2fL~2gVJP zQ4W{5r~IhKC~-gtPuWJe+GEAOSz_oi6)gNJ`kT6M_-w2$ybuy3E=XRMAJNV~`E4qJ z0%`DEoP4!K+D|x$dHIuu0#}sppkHy=__ltq!5B}>cNSdagQarwSN=D8uii5{koTEt z)tdoGt#LjWDs5G5naIk30s~1M=U*ymex0*Ome99pGTVyNh3&7uP{S z*$q-d``6TBzyD#Pf8o9jOSI#^hM@mBSp4fsKms=sVpFlWK3i?}5 zwVPxo-GcX-JjygBgt|B>*ZUj;dc10-u1*b@N%%ir30Zsbs#%!}?A|ie?5d0qu=U20 z$LGtm5^96JMs}a^cEt#iJBppn6kh$E!$udvqxTWLoVsKD0){M626PKX`5?>q(lGaE zBjsBGY#3>+dDu4!h|N!MYXy}W2c|X~R&p^Xt|Flc<)UlGlgyf;#MfGw3bC8&uLk|*}H zU&gUKXpRWaju$PoGq87$K+en#7jVk_I90s*B7OBH_AM93ZGe{^Qdvev-f=i7yN z#aR88wEg;FeUHxe^;NzW*MYzsqR-4zh{x6_9?OqvI}=@j6;22dRZxQw7JZ_|0i$`? z;cz86A^m%LHB6xP?xX54fGA7!ukN~+bE*|-D+Nl0we2DM{7mT8@M z1D4;Mzez^L&;pazR%W#SY~}g<=yON&;_C!lG*Wjxks?x!23A|sLwUy&MRirHhbgQ` z7}0LCK@+d9o_n@2jXSmtC>buO7J1gMVc&Z(SM&LR2YV4ycJbn&kLoE0U(_gebkc_R z=-L4uSzdc6C0kys>l<;ASA;7S84b=H{mV*{`tx0ViboAA6=pj*qtV)>ZA;dj zpm>8ZB0!`%O|m51Kyt;d-_ucJ;uX6p#MhiKnrBuKPgKHUb2au{nD>Fd;+pLP%t4E0&m}l z0P_V9H~mrrO|IeLm)hfYZF@J2pcSmJVRNS59nYvEaND~RiS)C(4uw&Vm735cVZ}Bc zL@W9#QQ$0K)xP2SH{wI}=Y7)|5fHn^*V9SKfc=PrY0mK?20neomLcJ^H!I^a!?0QWV27pxO`#nPrM zS(CLE#JnzL61Ew{Ewgn|ZmcC>Q+UCR{n@EHKH`ffrE#C8YWOoceU(F3u!-@(c)`oD z+qcCm9K17r>ROq{*_JhT@AsuRZfp61P54}j+4|RS_2Yf{Vwd7Oliv9z7ul4YCiQgdrHOo38S4+p0RBsnhzyq3dE00 z2uUUS+a%9K#fd8sd2d=rpLf|fH&}WHrVA! z4yhL;XkGkWmzXStIe&VdaZu0%{cP)c&3I7ib_IuI@;}nKxrP+2_o+wHg`$2e)wjS= z6PSIKfVUkSRVscIE~fZo1!VcjO%xgHjNtA(d^C79%|pt|wPE#6X8q*)1*U#>EGlkH zk~x8Vk_ktQV7PU5!Z_oE$NPi`O6a}rdC_&p8{D|e{*61#qchoJgZi$t75$jcv^?ja zZ%=~k;`k96a4jyU{Qr{iK2pjX+5dI<-+d&coEO0(2-Zy@Q*4(W(qU{q2eW|`z~JqA z8B+n7#FCkITmQsBPO5S?eGMYE&zi)^XCfrbPcZFjxvCB@zwyPq0g^+AL&jk(vf&(% ziLMw5bvc4Uh}OZZ$in8if~OJEB4YnFayaO(4Aom)WFTtJMKvK$Oic-iWP7X}QmTBu z?&F+%^bK`2E;&Fox}DIxP78c=TeOmv8~md1O_ctOD@JtIMf4AAd(_W|b!;c|Gft6Z zhJRWd4X#?s40k+;&uX+Ce(F&k>Qjz-+HirJV0jt`+6IsIBoggFz}DE5JALGXqYjbq zM_IzyZ)I865Cu&pcFbixE3Z7;E{u84NCvE5;)T40j$kdB#swdR@c@O9BxOej7VTaaEEHf=aOcg)qEVSevk& zi{%Q|H+=qHmC)b`IT0A^>BnilpBTBK|Hx5L z(hRk{m8XOU(pcYhpYy|i8ky&Au<>!N8chr#1GOr%KodpDMc1Itz1YwNjRD#gd~%KL zP8X=xrO&TP7UbhhgU0zh4`dIB4}di|5DK_PFCX-Y7ll4s#|73#uc3t=c!q|8u#Syy zFjE*&0HBz*ZIm85$oO5iW!#qC#M@KU+_Pzqen(c+oHN)E6MO<&JMhn%@lP_S8v7-p zU9ifm=}=718amdjxIwq}t}8e?Kp@`jbI}beECbb6Jy&M^x$YQ^Uub7@-reD%){N11 z*UsC7;TCBX-G{~G&h8zku`mHko{Azp>)&dhZFMj`aq^0xQAJM`7;u9sI8J4o=? zU+GJD_CXMl@>2ddH=5tJ_2vS}EM}yL$7Vo3Q3#G53P1Nf-PMzwP}~2~^IF4KYx=^< zar8?s5B&9xdD%Ny`d(*AD>r$`RYR^*Xw644pjyfKQ{=$Bu0>1E=!nsy^9ApL)!`<1&E$MuZBPJ zLik8{B`fIaDah^GiSFhPF||dA2s8Ti8o3zitWPpO$!^p#Oapx?I(slWO9vM)3zuQh zBcQY$7+5Bd8)yW(%A)K8Zoinqha;Y6zM<5omshh;>$_Na4W;HxSoac0R~x}GqEtQQ z$(~59u>%jn*z)BqCa9fvvW{ZW^ld+NjF@yJ+_1b?XCba)Pmufyc!vhm1APAd!cZQ$ z^(O0Fp)UgJiFoqY?Aef1Ni|hRiQ?$yimt`n5zUizl60^*`9tsI=5pqMGn;1k z6JLZUa-l0wbYK7UNW&V2-cNs1Gk$;eejNkoG93tuh!rz@XCXP(#2Bw^l?sM{xC~&? z^2=Z#e?=aFXaqP(oqE8fianigw}(NBj?_V*A1bH6W=aISZ zlpaz+0y!ZIGRtCYr@2^VubXo1O$e(L{N(a#)us#7gfZ`_%CYIFPa2F_-@VEtZHL+^ z+ONiRnJ^j(+Xd7(31}+eo4d#BC0)D37k3Ac-zv1)lv{CoO``5BMj|xrctCr7y}|o} z71)4$1vWtfZI7QcFbd^rs5?%|X$gy<=Lkb?mym)k7@Ei<5rbz{no>?S<^*Sw5fr7D zZ|9YBQJ8w=qOcgKWYEB2Dquk972B(a#u$cSbb4M3yOHJC(>I_Y{hb+y0 zX~_i~eYJ%3AHI%d`bH&S=0t#2BbS6L>B5-gi~dF7MmA|gpzcvZNx}*qV-aXdC$naM=FZ`=FZvj0Z;BiZ@QV_j(;j^gP53B9P1`2f)#K10s-l=`5o*mBzSZp!b0< zo`)??0`Pu7@XMAAHmF5o#F)JE`JAuW)a#Qnm>6@663wu&ib{b~Q*BtR@{If4aaM_r z`IqXc=!es#FgzBstJH8apPn_5X*9m4w!d}65PE;df_)`*4hgXi<9ijfv z%h=VyTzP<7 z?Ht7u+b_qHNicnvBHVKuk9#rofbpxP%Gw!dXuWRRIE+3+6mx_+Q2V$IFiw9Tt~XG4@1wjr)*%d}$X_{QnOeDla{e#PWyrSbEjr)7~r1eXTWi+O{2| z^gD%QrL0!pGi+7pUIz#Ur!$-e5g`(IqGm#H1$vQ! ze@^Kj;8pt6b?960Y!gwiv}13j)J{(4DN(C0G9j5|@;RKn)<{NMHi^&Ic@FBMbEP@X z4;vFzOZ-UxCh?N~NqqICs11>C+OhN*xg0?f zgdt!j*L@`xM7~*No9ZsL?-`$4hnzyln`-!S`pF{Nyw5Vh_@b?bl9q08YFpQ7;MiaE zenGG?YckU8RB^8x@$L-@(H1`R+S?#04h?#KQQOPvX(H&Zj5^QlHcyiwz-POW95$R` zWb!SoW3_h z!-ga|%MEvn>h!}JWsLL1Fb-)JvL=30AC?vdF{Ac{owU4-_}ECij?ep~p}mHU;}4w( zy(6}~uwFmQ&JaRPvDBnlJ6;-zdtk~BfhyYC`A&mhTKx(2TO{)lL=d{Yz80Y;G%4t5 zGJl+ONFV=1?|1++V|K9NV8&4@#&{nNIL7nc5_SfqmP#nyx=BQV5*;=t508Q9Y%R1V zid{cSLVz06N`m;I!1YQh7xG5gB`rFgW+hm)Y?|NVxhf$f~^zhQXABygK^`tH-* z+(#vpm)kuipeOW@O%FBa*ZmP!H^6rpkM7{5m(!MCL|GUPx_T+Y=sgACv0FUBh7Cn&!4A!jSb(cz{Hvc zW5o(~GJRc8Y3fT(qq_pPE=a3!BbHgH<>LX|w_ zB21>b9jok&%erAil^W&WxMECZXGRQ8Ws1a=HuxKw7z~%oNBfE%4;x$KdeL&6sp&tX zFV68v7;u-(KVH7Rcka8OJzX>=vm;-$jFPKcv9|Y4x||+RY~=Q&Y|J9w$} zof?%Tr;z|4=q$R*ma$94(|?F`1LHE;qxcuxCHQP)Fqc`Q!WX0psWZmOh9!zRd2lSe zJwBJaUq3F$O08RV(IoeeOkfCx#b6BzNHPz7SuYIigJ#M{B(mODvT-CgMos}tQI08Hh(B?K&>h?^zO=M0^q9zWa)+ypK1Zt9{# zBbs;V%I7FuLOFP!_=D_MwmXr#8CQnK znA_^(vptYQ>V1}_73FJ9p2}H5*7*!fj~X}U5u?Bn#re5?PV!cgzj53kdaFvoc7V=+ zAtdCb-5<2!D3CSK(S30ZX1@KWmE;d~Bcr3~)5n90^agUt>vDX9u>iEIoD)W5K6BSNA3JEY{N8~6QNX!FHW1`0_6$raG!vOZmP1a94Y3EqukKQ2Xo z2sr4u{MisV6J|aeFmm0A``F(vW%Z{A&+MnV*keKI4bLC;YLTk5O8#ZrQRAD3p6e`I zues<>97)_jf@9OQVZC+Lgk{&AgnS)mhvW|e2w&2UM?idt`iBhbwqaNTN$}3U<$OC) zcatSeh{n`|RES^R+{NL^FJbVk8C;|zu+tP;eR!viPmt6aEWLisIcVxif-FVYZ_&si zJ*Jm#$oUF@VaX7@tn05zAj0<$n#H6_6 zTgEt)^v0Vx#`wc;bi}mnkN3R$N|8QTQEe|@S#@k~dkZ8Z+LW?&a~=Yxv&gW>h-Hp>SRySuC(2 zDD{e}9!Jb|+KzwLZguz1Un6a7b=Yeh_&e^T%+Lowf=*InH;s#nt&fCem|q{T%Yem& z4zeO^*{rw3heLdZ?rdEz2;?7cs}eLv#sv~+Uy%U35jS${8Tq7VjGlZad}wFz$#aPW zgBW1U+2sB>yUX;fYwyesc~1-IwWMuhmzcsk;T-_tronQD>gnIkQImM3=0EavNlfxu zSA7P=Rr==8M(xQD+erYKN9jsmKPirIIr#-T5MW)a8`BR{zTr04ZxbPx!`Lw4DZ~!z zFE)@E3l`=f+)m!)z_y6<>z@1bl9ak1?7xpKMq0H`vMn$O1DDscCWsguD>Oy5x9@6y zLU`yLM$DQW(lq@iZl1td|L??f18?MnLU(iwI3ZkIi(M$ilBcc;V}e@=;ljbSfj!-j zLM=)G4JGd!Cba_Eh|p?RZX%nM#MH)c`A`NPOQ92mV_b$lBS)95o8 zq;>A>-uPm0v()eOd)xVIufNn;>R!;efthVB_Z}Hgmqq^Bl*UgtHLm&;Dgns*v;1FO zsE3)Pzbr?fyTzHA$am_NO20;lw;T0^aMJ ztX%(y0cp9x2Mx0l*Pv`a+K>jO*uO!daNid$q`N)hr{D=$=xUDq2BMw_I1V;NCxFg4i}(KO$N`S@U^JnR6CqR;?1 zY};gw`_QvZzsz2KobFWY*YY~3%t$G6uv5d~ZAW;!JSx|+9?+L7M$STxCoWHq#ltl~ zFK)&o3en0JlhceZ-*9W$%_1aI2>fvCA9~1kno_~i;fTuNhzdu3?(1XukbfcSXP&{z zgEcU*Mw^%@GIss!Q`>2@<1#G9gury8kh%2nX)|TnVraJ5AcJLaR>mRGYCE9q@^gaQ zqlSuj$fok>IXBHfSfHKs^F%E=!jl>f2Ww}V23f+eF~igldB#gXmm$u^C(w%Moj+!Y z3%k?>46aBkaYiShYuPkB&xu2^gK(ZROwKwi`nj!Q!o>$wW#hA4f9^I9sFNBp%-eb6 zn6H`;(w*+IoW0WWx547C`&-L!tWED{AVnFLpQGGpR7TXPglF4kT%Gy-$2`CGnJopk zl0hSk;fMOmosA%^h1;iVyx$ADLUXs;*Qfk+k8B}l7jyjXfM9~_Lhl@c zRgFI=1k!~*{@3-d&ahV-}a1%95*F z=UV@hSAir5EKq*PL0I6O4g3j`Y1Y$kf6)> z__6w4n79>K3wzAkYW|+zhe~=AxIL+%fSBLk*G%sCt;x3KvPHo(QFd4~Y~#;5#(x13 zOVf>Mh3skSM-~|u^V3%cLxSGJbr?9O`du!t_Hfbq=H^L7U!=5Va;wo{SSx^?;qzs> zCrQ=$eWC?kl-0`_5nMF-)}AMZyD!PUg2#>H=AJIjrQ$G z*6|_Un44s~0`L6cVG*b^SI{RjuwS*P>DBolY}p|IGwdlLUk^N8PI89Aq%j%O`wQxG zTRxF(2eNIKbgw%Hj#!If`5>2U%toDNj%bTnL8qmvHhxOM=fXv=C(LFpm8~mXLQ-QD z(d^IEd0lD^jd>FMTnY`QY@9s~z2}NvPgxkJ#>7R|ApKWY_%y{K@D=+1gtT{7$pVLSHgi8lAgkc_4=6N$@BX-!kw76N1+yEnu_tP z(SBjx`E{FnJm;T;YkMaP>6`j;nzM+Lkd*puw$MhHjh7%<2N}{MH#>}GCVn9*N@gZs zi~ITrUE#Wsl}t+j@b)v@Zad46--MRUycz%Ii92mZXk}PDMG#0*#tyxk zbKnhk6qmwu)LYj%da!xB&tN{-w}p$@n)JF~dM7fp)1_LASf3pF zuTQT1LBoIcw*wDwe=i%{sweoOgrP+&rE8ugy+aCF(T_6T=Gzh7c%e8V3U+H+8%UIT z`CUww{y4jo3j1)Bv-Bc$UdXRe;Qva{enu6{p* z?)1OtY){iU-c_DvW4}oRNpW6NzDCRMzZS_t%({AqT>Y562!@%XuCO6IJK)ma7M|f* z$9H~lkQ#P<5>N}H_j_@-ADKT%u*277T$LT}_?Zflt4}`Ig^cwd= zJJL>_e{F92x4~2==9Wu%_W@`3nh8O@9XG#r8tN7h{gAsmQJFwLI$!b=Ilc9HXmJKpXIf((8nYy=$C)L!pjmX#@oK&wy z2T=yF;)4%_5g#c6czaW)w(u>e>sJC*FqWVhfnIB z*%ch|3>9R;X+T5D_;O@j_T=e~zAMGX%VFQci+G=^D2dr&DOGnn<dt(Wqj}}@{iDU4LU@fTkYL0(Q7n>4FaBoETcT!drA@{dP@y(53_2&`8JSC`5P?Y@uQlk_ZTZ6kT3nP~Q)0+twpgPTrIMc)*uLo4J z)MU$AozUn+9F77xwC`6d8OUpVJNTkX$gMwRuCKM#Ow_%8U88v2`3vHO8YD>@wq#6b zAXZpGQ$@wQ+LN$dpAMh6fZhD3Nt~mVFD+7@i1Pgwj89GGLD}}a!zNZ1zdEja`xT|x zz|-a!Fn;wi6#pgA6&OeKpC-q_|D#u8!i;p~vykpAHDU}XqqIlY4|0kBDw~Q0>u33j zWwEsJz%fE&t4k%y!`WeBR&6I!yg~zrxZYQjh%xY4S_4!f zxbZ{4T|`A_{#!dK>EN$25-%Lf-EYw?TD8^Ae!HW@T2A%LmD-KsY8^E?llM(8+V=Xn#Li44n?6tQ(T9mHi70??D0ni;kF;??fm%oK(ZR6}je zBz>3aTwRGVX$pl*X1Tj#OrTWj;9HjDWlT^Tt^F&%&TQLxNys+T>1|%%+qlib=1d@O zg`X28w|hV%)~u(T+PXf)*wSw#(%c=> zq}Pl?zc_XRFdzkZ0)%z>M7bi(PjZFbpCSqiZOID)}Ebiwbh2CrE*IDQBqnnFXCN3VU%J68FYN8Uaay)0kJjy8Wu zBka4fR`=mgV$hDi^wp=53y$Ly{1s1TsUv^CV?fYkZ)dmfE)KyQh56Cee3Yj2r?6?R z52*1^T~QwC*J9hT|Lo;cWCmQk2qZmOeR}k?gZ0`Rsf{oGR?auVmmH7QBUyfnG@Bno z-Z6GWpM(R(rT=!$%TRyxf0!a#-7ypUEx&|wFTm*MjdqPf(us3l=@)!;M!&8Z$vcb8 zR)mXv_X%6}&6$*d0pCAVW=OKP>>myyC&fc^no4ofYw>}*^&@lSfd*Q6f6N>tue==;} zfMvnmTa;H~Y%X#}fpwy{(3rQHU94z+EZ7wgIph%(oSZ}2D%h9jB$ceJ3#y6~sMe}Q zRZ!(HL4~Z>xQ>%BW&R=2p>0kP+LW1(xr@p-hbGk$S;J6SrHsk+urb9CCu`-`4R4GZye+2} ztaP<>$o>iZ<{6$FvKU+WSvEENFk@Lr zbU_La7c>}s$>&2Dzou8nqwUH}aESfBbVX70RO*JKF|RZqZ;pFd78beZ41PlFjS*Bw ziU&*up9(TMauFNvQ8cxB^XD}gv+xnJKq_|jbOvs{?N>*wPUbKtTf$<&&2IOdv0DWv z$`%G+?Zzk-26t$fHG^TZu3M}7+13^CtJL-B3V#>L)B01dQyHA@8J&f_&_BqO`DC<( zE#zie)97u*+5LfXJ3l1Q2+ogkgxX=d;V9Lwt+`^`BVzqZ&+WQiCCl$o_;?lD%x7bk z{!e(GNrIpB>DvbpN^?QPRKlw3pWqkUEp(E|KjFixp8n}0A(%6Fy}WHB`w*bv6ELm? z3dY(cm2}CMe!q#YQf3A(rJnZfc4~?2y z*z)x|6SwB!R3$2zW!$#38U!C1F`oDEfphykwcvgv6lgmGzzq0VV`RlXEyndWT|pfF06E534T$AkY_OL^WovDmJ+5JzJ6in`)CT~m2pdR$hc zec4Pvt=EAQ^P&a!=`Lu`TmW00!^%VEelOWwHsaYEG~?thau#er zUPR~T4U_cZNv=AIPwHGeSRUNmXe~C;LKLNRrDI=iaZ~0EOAkKPPFG_5?GCp9<2%Yt zwwZ#4l8gs_WMr|I@!YUksc(Xq5Ge+Do}_JVdvY+HtWB91nv*-t3U}6Vx61PYV zuHuoK&khMyTfkwGXOy7u0{%Mke0>eepLnG!Q$i5p9%e4$w>z1{BZw^b`1#^Y&wNh7 zpVSJ|V%d3~YR@H3s9#(X{ex)Hf$R0RLh5{J18>-OXo9xg)s11?9NBJAsHat1iQRkE zyA9%p*r3y*@k&Bh(24&h8--LPWW8rB33)dASx zW&_W9Ug5@z(W0mzltMPm7b%vd6Bb=>1(!3eJ7zNhIhHQmWahE|SPxFT1--)mN2S8a zFuvpC#u81?JWr6-0D_aXE5MH=h|(|m&Ax3IG_oLKt;5T|Z0}h6yAU{=0ho(!Bj6B) zE#NFr!LapZz1xM`bB(kO;KTMwCeW#%u0D=z87~r*iXBZt5ahao@TvcK< zvhmgOXPfPFD%O)qT|22028&@hYY6b3x0fLd|rG4cb_%2q)vCv zZ}8Dg-+xj|k#WTxqV&p_v3Ln*s2;Y6v>5nUblDGwMilkDmvyTn8Y?mEcAu^px)j3N z85v}G{Y^ost%{RnC4)#fj7wpZ9qSgLWiOkC+fYd}EqxoM-Y|B4Z2uPc>MOJA*Y#ih zT7nY^9D~VMjO(@Z9DsB7+2~+B&F|$zR!>u2iY1|@D$j5dp{YG1v$uD6{`LGq%djOr zX~4$gAaiNp#lcy=kKc&~4!GS1(Dv#We-d?zVX*lLE=mcmY}fklP)Ds%hA;iK>fi-^Zd=r zu!ks=?dDft0@a{eu{GS|Vt_5n80Jdijyk~A`(W*U2w428KW#8$4(&j=rlg@-hKXP~ ztR~~fmE)mA0?F-&EgA*hST@>3SyvPZbAb8Ar2mm)=V`9@^S*et12tq<70wsEj4nac zD&S2LgHcbePV5GtMB~e9jskKubGQ$7S<_^YlQ)Y>4DZfLIpgfNtnBwOk2`!91~`bL zj{;f7KZ4NPDLvw8iNnHypJlo}MqF{<9ZY?1?#hhR3UenxP!>``eE9}}Ht`cSc{ThY z(3*;+46)l>ru_7aF&T(Cl&@t zt3>7;{#BG?(q<$1Poti8dXq37AM2-|4Kg9o-hGHlnI94Zdx(nJ^SdHMpHzRZ9tT51 zy0@XBg}eNsm;2i;v%5<}vvcR^Aki2YQf9I|L!K56O2`>~?ImUc*G?SpWkm~?Utx&F zsalz`RlqMKNJ8;v701OE6^u%jgF|<@Vh3^xwF@GTN7^0Z%JkUJop*>pEaS1G(0Y}1 zKS%9+W!q~xBV9!q@_ks=c~-5-wKREtZ*p!B{l1^NSrX==~ z?nVP$G*iSl_8({p+3boUXmSgg*0B(}vCj-;mz<^|MTf+8G8@o^t-tQmKBW?l%)X6HI$M>l^ZoZ=3Qgt!|Rd6BIadvM)E>3|Sr&{|)Tm@5}G;#sq6fUI;yC~8my63>!*<7>< z)elj;>)KoectsuEh!DA5Xwhd;M1nA(oZRtP9Aj&0*Hmwhe0jj^-bTg?XPX8NAs`gi zkay5$(MwJ7{4Sf$aAU&ur}?=1YhI`xER6RVLPs2%_Y}hfb;L(VvI z!p^lSNJM$e8pjv%bI)d4M3Mw-_6SS2Tpp>jlpNXkflpWj za);)XW5_chzKw$fowv$mm5t>yvRHh-jIZTRvw0l(E&u#~e7$8H4 zr#?*zWm2d1wqEhzN1Q<-vT58DABU8WVa;C{ zJ5yRH>PNa61a#ePXb>Ie*d#E2AVb&*dxOtm2}x+846ReG|S8Yp}XOo_-O6a+S`u3&q zPdc#TbG1D!V`e1ip4(|@1mrJLW_Xk7+u7ggB(cO#mS~9n89sTH1Y)S);?UCKqP$mn zgA+OmqB$i^2H?~T4tmP5p>LP9;E_PL8BG8#Sh7 zn?7Capb~Mw17D?3IkPC@A+FsUEcBAg~ps=$>n*rVXan z{;Cz62SIHzeC$Aq(4TD!QKi2<9QtC=&Pi5u{g45{HY7|=M6q7uWG!+FSv2bY*)skt z{cjxGo-1w^&BLeYm;>H3a{T!7u-)C|;ov@Y(Y9K7HEb|k-SPqC{;%Kt|5XWwiif%1 zuqgSb?0d1ej-Tb8wsI zxVN8HnnHc!Zjlm9#?{eX3T3r&{w(xx7@qG@I3LhDkns*`rAaejDnj+bY@=fYc4dpx zXsxX#GSqI&rwF->Q#q6o>LqG%j3s7Kyx>~_V$|Sfl{ptjVtTMD*>5& zVH)w;Fk=!Q=!slE==PD6(?dL&FCo1r}w-j8j}vXc%`H{8X%bv&NbomVXdv zUIoexqM+SLLb8;j-TAv(C4Vlx@MTdUk*1C6PG($5FW#TYQ<;C_X0VAHjdvUiy28rt zh`foGY=QqAU-@3N4@gAft}yd0Eb124tKQvMm)1ePB+im>75hSbG#)s7(ow%Q2we9> zMC@9yi4TZ+hGWpo;xIj9#BN750H!6j38jpeXg2bPewL4HVCG!*|PIZjNw4hW}t0YS%m zfVHb<%9%8tsHGEgpI*Q7HUdL-j!*#auyf7S*|HuWdCakv%D(!IsChONMPC;o;Ph|n z6$|J5_53%vQqv-iP8sK_ZubH|0E(g#xG6(?e7;HfUZ9H-l<_d3$mtwZ9Xs z72?_qk|g2e|8?~=&K5M&)0#If8zY_rbHgokUw)l3P{S9EbWIZ`8uaw`ks!MpI6qLZ zHMWiFKL{#{3X%q}@jGrZkle!bDg(UkKAhhFhW-s{o$UE~3)em11S0i`LVR@oTeNd* z2r`$l$csx)XXfzz4}zxN#r3d06|*N?XFfADQ=+??_1ci$7TPtRO^usf{k_NUa(EqF zD~r2b>0{k{A@le(J3BSDI!Py7)%-&GKIOr8VIpLn`WZJPjW`yFX3vk>Pq##7Mr?GmQTWF8#>5Nj)=EL7$#;CfPG5IqON69p8VX z6Zmvn<%EZPY&U&3N5%JvDdcyIMAUl~rZs0=PQn;M`a5QLd-W7G*9{+CN*`A31bY6W z?ShXRddifUzS^13!V1$a;JZ$>=Cd5;fa(l2?HR{cJ$Ja!;#KrmM0&-o{^asKdO6Dp zdR|I$mqc&dXBq)5#uCQ5!u@?a>Uv7IKHS1Q z;c+M02tSed7)e+)H+D7)X?$u;1Py@4{aKKuq97`~-Yh>3i>e0Sb+zy+!M{}wpGRjX zzu_b}$i^30bQJs)LKUC$wT>PX0V6&2l^zwmK<&tzel;$H?rV8P=^D<_^Db>OVV)`` z7ttDNs}VIkV={vJoezQp`N-RDienkqjZls9L-#@1H+W)*b(!N( zVfpKQLcjP(?tfK-mouQ%?B7tej}ny0MZt7zN#PPIKMWHnz9D}`kc!5}hl>i|en^!& ztX9NHnkx;KPjcXwk_|7T3GF7z%OcV6w%etjE&hh4p){@Ol{{9HUM?vx*!&~wW45+O zt7Ktzl-7r&PwJy0N^PIYHv?H*jdb;z14=Agm4-a~E$y3cKpdIcc2I@BCCi~X75ZdV z_s7UAn!YybppoeJ;PyLF|*EBbXl&nDEVH-o3ZIf(bU__Wb z;3!tSJ2ve&D62{5hwe7Gg2xNl1j9(}(Pyb~tDUuEEUY-GY9`&~jA)}qQHg`IY_9u$ zBwR7u0g|aNv~YML;A$%1+ijFom5Q6SX56&X^sPb>QaL8+7Nk8XozFT}hhyxuko)dvlcPBZ*Y~-aEO(h^1mxd`E2%2*&l*SE3)9ec) zoEdVGc-2(e3ajG)*(s)KFiNYrW8RK>#L#VZLj;IpBaGV%#-fn3e_LB&`->!R=)Xyr zl1n-zLeM34V+x*-f6oFP2@qp!u9FnQWHr!2Mzr0T+toop-{msE#Vz zRfxd>eV>?f*WeA|rrzwKP5FAy67GF;ow5;V{A*yiq8tE$-cuqQ$Mz9g2ik|ecQ_w( z6B=kG=ETEt;jm^XbmW2Rlt;Q$7NoGO7NGYKMUdZcTeOQ6VYZ3sabFy!@w6&41A!iy`iXrF?IFA*>I!7lovC8{fr+0Dus$r-n+qSr=yv=(~shn$G!z7}&+(>A`zg zbewv5YsbK!&{ZJ?rK=PfN|8T7)#<>b?@k@`-iy&X+ukLM{U%10medSw=QWihMwNXS z?NU?8iA(}eTL~5Qc-l&U!sX3Yu*BPlXXb0snfhqCuz7eVBx62rSnuC{#`#&B*Uj;z zBq9X`)`*?(twIqxVItVAG@J9?eXRNrY`An5To-!eE!|V zgTQyu7D8sV5VBxZhgc75kq-8;q}zD0Ueq;hKu<@WnUA$L)Li&BKIPWK!0P40>cIEo z<-d#vgW}p}>cV-c^Y_R73&W{fzOi5#g~8hLeXMkUWk}OuZq8afXUQ+g%!9T7#!-hv z(p#Jp!Wf%fgs$nCkr0n>&zjya{dDoO}2D21H#sll+K}Q9QusM^oO)U`X)^%3WNweDg*uo8d#N%gbx{Rt$zB~L zVv>D~c8rsD_7?cOs?mbBBaN86eC|*53a$p((7`S8^TWJ9;%{5E1MU}iRQTdqK!)~# zKM`UwekSd`fr79ifx_m3BiN%Es$%dUQtn3J%LR1a0W=bZTH+FIS!8nuNB^x_#&0qG z8$A;zch787JMi~)N50!kVs^>{8V|*`4Py9kQ*fP3%X@SA_GKY0Ghp<9@bf?F7fYRy zzs|z%;(P|tAh_oJpau}UDG^8Y*>7rTQVtpmNPicG07|2`^@JLPWA-Ea^6z3!-T`+| z{=XK8hDFI}`~OH1|6Pi1Kqd(gmolMS3ztAZ0V?!o;U;encPZdJ770<)^4sbpbj_ znKq}SG!bIxLJ((YF_UD zOT(T>Yg}Dnr=DqXB-lezG` z1;3D_L*rRQd>!boMI019aAS}8rj3+_jc89KRw7*JoP(Vw37qHF5ktv|x)8+Y^sCR7 ztmV51rWw%R32uEI6bFSxg~1_D=A{JzKLa={7Glj137kRR962GV+I!c-WKEe$ODQ}q zzuZ11;QTS7Ow^+-ke5vk40EslEyXVt;1|$RY z7lwkhfVW#xVH)VumnQe&-7ZDrzIWk{<2!eIeKsNFh&@i5-mpClWS70hP{uA(Fj7nP zg8m)%$+~(h-~Z3-To>WE-?m-=!ktDx8}L4uw3l$ajnMx@;MqQUE$w_g`F4383et07 z(;}sv-Fsz(7;gy)P59bCcQ#^QqSr1_pHB3Lz^@POk)8ZwBE?@c)2MWIfSm%yncUms61ob%gyU+a^KJ*nT0) zdaSGEZ}x&4`=X*7Ij1rKiO`*AxtGKYvLgQaMm1Bx8klb1wwT8uhT!gjKVmgIy;I4! zU2;;%eMoYCtgG)Q+^ie75BMZzoR)0~BPY117tA26g9#wYLClR8Tf~CCA^G+hZgvDi zFkpZS1w;!ot7iIBfR%US!jk}cE}p*6{7}MRyw#9s+UhB{g{pZ%i8)2}BR16kDF7f9 zwu1aN}yp*9EbC2+N;p1d>pW?9X{>fLkF83cOywH9f;5WYxGENKg1qJr@KU{h5yPG+% zrw@91!5RUigayR=X(EWJQKE7PrM}|)2uq~9>aE2;LjO)3eNKyOmq9g1HH{5dkB8G} ztJoc_=QN>DAJ1*Ev8L5!!B3N@$K-RG?B{j%-6nAk_;q)i|a=NvU9kBZ+9YN!+vhpDSW0|)I7WM`a$Ug4^^QBH%*VMUN+ zW_O{uQMPlKG7K#tS}peeW3P?!ec*J*p3qI9C&U%OWq}jLua`QvOT=8)Eetpo!zshW z4jYp%{*K>MIimKK5k)-S$_o5wc;R)Z$*ca;>nhyWKQcs`KMiprjV`zp8xCZI{b85h zSEV0x!ownVM_t$W%~@E5$dI$`Ikc(9fZ>4*hAlZI+cGLi8ZJY4t!9iXf)@I zor%?KYEt)p3$k37NYPvCc$JstEl+u5r&s~vrVgX$j`17Ph_#>QU!EqvY0VvOJS&Sc zk0jAQq@^@}gAOaj@;*PymG^BJ=Z)ck4>X{^!|N&0PA{XdH;2B=r_e`Xwd<`489=~z z!xLTmHt1%X?s({07ZP_i;^vEa?$;Mc7?k7jwEJp7WVduBKLlIdeOnI-+zfm?b((W^ zL`fp`iLWJE!SFweMm(0u?v_6qdR=6v&SEcwL9f=~CJ)yOmbl%6&@aZ`pz7x@pH*zx zb@qxvA1AyMob%e@gun17j$S-XuB_FhzMrVt9yocwIp_~&deN-9QvOZ3ziDCeM&WdcWUV~bKLNl(^Lkl7kO*L?ndzgB}{u!IH!lGDA|De|v3rL8 z$f1fCOL3;$@Wi1m-wX7;dfhdn%B`4#wMx^Nb+8sXoRNIt3lS_aCOYx`UtrTi)IbVR z3VrmO*zpR0BBi#Ku~*1t(3xEJ z+Wx0*LJ}YSdk2hXY*=hqAZ{3O-3|7Sx!VAyy;SOJ6?8Baz?b)Ga)bX#1Q${(PWZq)0Sk{fKdHS%?ZvMs(_vs56aQOqk-s6IOi| z2$Q4P^u%eT-L+KAqQPFoFYk2QIJG_2>uQntcMPlrh3RqafFA&iGEFX2)4A$|e~vFU zalC51YOhTjPIQ$5%5(LmglAlR4u;1=WBDZdJzs+5a%xx0))=(`DzcD{Qj-!4!fjA&EHO(< zuydXxw*+T5F81yYA+=IoD--q+A`;9jQ&Q7pnL;sDESe625i1~t2C@y10`YI<3=(p& zQn3nHxEF-Q9#I+!`AUc=4Zq8`YE`hpt%J=Up$G3#ntC-T>Bzz$g~qs;8nQd0sB1@@ zN@H2<0=&$-RxP_M2)0_mKJ?g&jIZ;|CeF)mO9bH*t7~{L7vP0euHlzVY_A*9I)%^ZFXR zCsr|#t8~H4mu;y@X?n+$7}_kapSvY&T2_tskyo~`s?vang~FIx7(-FQ=8`F}eCXNY@IS7Ogk(F3>6 zAOBouw@;Y(C<`5JT7?CbY5JH7#hksW!##Z_L|0av{&(8K7y&2n-8xDy@Xq1RweFG5 ztAL@qYP$&0?!2{=|2c`^Oa7T}tbTSZFMsbh=SgB4L0h&ecOT{eU=7YV(VM0->~v-S z+0+2qq-yuq^z!ZESsXK8!?n-09=h)S`|b|~Zw7^eg;ek2X%-bp`7O>m*3k#+K=aOM zUaV(J>48(UwO*u4Na`4jsa>=)0bqc_(iZ~?P(CPO^@twHgg~lxo*}ne?R9;&jx=&T z_JAmZy1hL|>xt_TE$B9RB{rhxIO;kG(|6j%Vz==)k~mnASot|P^>!{iyCBU;t2l!2 zE=B6m7Op0368qjIxUEVq?-Zzet8YUVv2C1E>zj_~9U8)zV#`=MzbN0EYnqS7AVA*n}+U_q3@`zl?MxJ9p5IG8IFS~oOm zHU>=mMv>zCPg-?3d0M!1^#s0y_&2U$ZqK)(Wy#g(P%n3({p-9!_yci0hy`jR#E!5TAkN__JRR>zO2kqcrpNu>wi!bMyG>NNwiM|Aa)2-3AP zyAc_~#TpnX#VzCpiC%bZrGL?_y~VT9%#OF)BT2U4(roP%rr7z%@>Ww%P9mX^93`ZI z7jW;@@K$jJHb@dFeO!BDY-DLwOtwzxrZ?cnNL5PdR%=PvHge=J} z2Fuoy2#aVT!XP3;2q4*Jf)iweO?ed3Ywa&Y8zMusoCwvT#-=XFth~uLe@ES#ccoLj zAH#h3Qj7Ysx{eq{p0V|r`@VlGzsZfbyGJJfSKhZRio7t+cY-de&Y1W^Qg4u0OTlvM z9w4*m`O%AA=@>ictWB@v`Y!#ho_<{q_X8Z^>?cEpqdY`fUCOYpJ2`8Np=DmKfg<56 ziGM~blICt)Yqe;q8KlFYY2gaTSD&wpH)s;oqiwhyauQieT?6njQqSGg^B|8 z+1(S_Ly3FM^TI)}Pm_Px&P`S;ZqZ+vGU3*qm9WDZ^4E|NvnSOvdljH*siWl!M*fUx z&6EuMZRR<}Mve!vH<=4n^3HuV{iw(j!BXz%Me=U@GO-u&iUPnXL*j`}z?fq?R$$nq zX5OWD%;#koXuG{RK z&L5YH=Aw1E`yO%&L5K?AX+d^r;vba)k=-sEqxm~v>l+<1A8pvx#$}RDq~!*UOOOGFTysGq6OI^+Eb8o6VN32y45>so{An2B!m?X8At zPhpZRK1{1NWJ0vJyDA(R zi)b|DOJzSF6cwdMC9+eO6#tYZ3KJ+8k4s+&Ge>REVp+MROlsUfib2sQ?`VtQSpR`v z`@NCbF+Sge5s4qs%EBU(v;n&#nfvKQ1LCz`34SCFuJ2&_G)lfZVlWqfhw6@HsqG{2 z_r^}DMZ+%qu`WyCTX%*6bv+k?8*uOvT7}B3OyqD`Bh?4G0dbdWGBe&QR2PkER*xF` z=l!Qw{35eHD&6S*MV_PE)z(4Mk6ci?N9O*`=&iLo>I11Y?_+?NT~lkbA?{OLs3GQ)F#n4 zx|Fohfi!CPC(nrmKCh42oHdodIt?&SvEV{II@cASj{5JN-xc7}I7xeLkn>P85 zs5FyL5Itv%b5IXX@hfDeS;kr&4)_#9%}9mCv<*JYm1vS@xp>t=w-$}bHGbBXS3nt^&nS#Bb$o+5*9gF`S0 zY>nbHpliz@lv)W;1ST40`8YeKiwd-aLt;S+Q52#!$uoqHBHB|gr}F) zXF<~M)R{0x0MN(=LKz(=WTK6pJRBZ4qQ}NVS`_5jt7LN80o~7WU7!Ulp#TQ-M&Fus zg?&FYd=nTBZGWPBCSucdh=2EDfw43pUA^}&9r6~EJLN`q#v1KqPSQkCtT-)m32m$M zcBjyLMtFeK2yKlyv7b|5>f&XS%+x8n=Q)qJQIB@i_Rshh_JLIFx_RS}Tw?W5p|h2T zoc$4y4;igB*;PvJsQGd+dC4rE-0cjwK8$O;rh5aCT{BQ|3C}d^fq^{*B5N9rswZD zqA|uV#X%Tvy`UWkYBRk@g?hHu4ITyWRE`+X4Wv#U^08vF#Q>il^47H)&$1$P$o=|Q ztL6nITYxeq+BIssH(C#lUJcab)$gaWIF5&$D-C;#!h&>bAG2RAJ$J;`c7#^Sck2t# zjSS|!{ehm7s)Wims^uMdu$Row>WC2y4Qbf6U(ZS5-hPNCV zoUfIJ#KOs)&^yaHV_E!!Pdtb~GlaO9F~#&br9h=mk$KCy_P(#$Y1GHnhUZU>T9Dt$#l&Ai z{y`B(;2-nv`dbJ_*q4LN(Nzd-4bXmFHBl-Cw9Wctbg5(J>6<@sHy5-A6^C9v{98V> z{2&0`E>n|E#xs(w1{bqB`}zHs5n^197++$6{ntzA%8mM8QlujWu26UXFrC3ls&`s7sVKa38CE!yXIMV1?F zjILG^-trO7D=D+L(wJdc^h`}&i^5ihcYMGBOISuDnu=ES&}aEqMcs)Fb}^p9+@r9U z5c}if?6zJzwJq;6+Ov*aPBmtd6#)+P1nkGUX_YMc@eFF)OU2xaRp6KbPv(;#cK_|n z3rUY+%bw&AF)9LhWL^AwNMi3;mn0^MA(;PjTTYiTn4fOC#3Ai6*Ms%BpYGF32d{3! zbU;{coR6n<<8j&oOZ@<78R^%7S9ZODIh{D9&ijPRLVJ_bS&iKe4vT3s2~@91oiOU0 zC;;JA-v>lX&P_pq@G6aeKdWmVbPIDzDT}bCw0|qcUmHZe^@tF38h0vi_ZYCYJBgnB ztl)Wt+sa2AUHq$Uc3rvO2mw(qDM#^*D4g*CfR|(C3N6{}uCG-fsOabs>K}XZEdDq{ z%S462M|C}-#IrIVA=hx5um$0?w>HR;$H&L==o~+3 zE{r*SxR%lO+U;q5)TC|+YRBB{LZgloJU+d+mepyp2GG?BY42OFf>pJ({};4cU|_z{ zQd8=xX}oZ4_uMuaG}*a=LGs2LttaB{8=vvSyYqCu%RuHtZy=06(FoNGn?PQLmUkc% z-UdH3A{&@9E&s$T-f;<4^#0CD({_{lC}U*aaSaAN57Hg4efsI@#4FQNGhi)j3tqx+S0sPNfN>sL;9F#0Hv&x(+Z8jJrrkl}bf_YoIUPIa* zMbyJ4raPJV#8vnyliQ5v<(#Ik6lsdg`AKWe?DxV8oYlhkyCE)I5E@8`OX!_9Xj>@E z3?iQ0Wr>W{OR%6~}!1+jx7@?_y+Q zzIQ6rdQOGB`2#%|PF$7xI*r*NX{TQLYH;RzVR5vzb#jS)C9eHP^?~}7A5*l8)CQe$ zD4E3#+0~<(CA1cumNBl!xejSlQ#G-iG&4E# z3NS}8-7VWyk(U!T%P%dG6Hih)tda9_GQcS;Q)%9RX4qLXvR6J$Q069|OP6L0DO3oB zYtjzS(*0V4vK7Vs`!6>7j`VdO@A*m~i z+N2|CTY>h}Mt{!&mquTC)xIsAB0evr5uc>}0(CoU&FtgUV1Q0+h5s`iry3#QHFp$U zQ5_29dwJ=Cw*|3v$B98up*hDy;D}jlQvJ!D7@NEi%V6;H?N4;O8`-By- zQHX(78)2Iiby^E!E4v4XOk4oQzY2_13eDA!Fi848bx(47)2!VdkL#yH17$ORO{&l9 z8zkA2%{&Fhs<1I);&T^>&SF#os+%iVz+3u<~V2u)xXMYwDq}! z6LxfQ+{4xpi9_WrxHaBoq4o|oP2n%VvZSX{djf(`ibPq|_?>km929dXYuKUzOpmes0sv>{m z8+iMx&Y~9>eeqeW5@k(U;AO}#maVn7B0p}YW6l5E<$l=h{ZCCK!#Q%e1xKrp-9K z)LWWTFiYCsP(^ImfD~8EO)llO7B1&^#C7`Ls1qxZTOSI8G(yihFbWjDBC62EJ8E^{ z3XVtQIXNZ1_~;f3m@V=6{P5i}->^R*S!sgNr~m!VH_84&vba4Vyl*~Mueer+w??gr zHFl?cbj6A);1f&HUulzk%oynAWNIVKnI17g>=}Me<58qywHd}@s}3=4kpY=pN>H;6 zUIR>6A(}72i4>vcKAZQ$`1=OSk)@0uzb?!1_p`;r4FyZ{j|qwfEcY7LA%jIk(&zQZTD0(W0wLnRRGB$bZJgC6#EGE5 z1Hmq>Hqr>NDbI6e){(IyX>CO-P#0;IC9xnhzh?}w>XVO<$I`|`Dc6Ddg)&YfTob*< zm#o>7;UbZzMu zA7e)wfWCD7kNpkCQS>T!q&{uymFL-|*pd7ai^IM!RIR|Oz_L60NufEg{fVX^Usxj# zd+^yzqH88fY>H`MilcBWs*in4Hpwr9lL~8~0+gb}?$9p(dJESO>Y7&!{qL{XsBx_N zsf1!J8QB`9{Ehc)dOJ7j*mFP39sB&$#w=BD72$sDrJT8iQ<#acfNkB?VFVAuXUUX>Hr)GNI?O?aHzcL$7cEQe zI_dXO4_)d6C7aOX=3h#=KAgi0`KM|NYlahgjYp+;T?ixG+scnfFIWU{RoEQDYNl-! zeIx2<2w9#hG0Ekk8yU@!bt);Y_1q7f@mihasVD7*tM&!eN=Bz)maMoVZ_w2wVday* zlvKgQ5lPabhlgLGVW#>|d<6&h1taN21g0>9Dde?N`a>=1s>E)X(NeTHPEfcBkO919 zgI@xe@h~0D8O0o7MzHDbAnJ4RlELyZ@%D*`!U3wYR`A+F(?qAbG~Wxy7{9`s;mM^rUhaBSQeHx5NK=2*!ao@MD@N9QGm120W^N(>Ze6-k;_Suj@Qfxd zs72blL+z{^ZbDC@zM*PG7<4)Ld1u0~$!Tv{KaJd)#fLWq$x0MjKV87cr=xtPku4YO znh}qQU$l%`UTU6EQWf=KQKha?o+_6}$ijT!h=b}bZL-Gd%#F%ZMJYc-1SR+4Xl>bd zKUe!T`R~Z<)6rCqA%t9$&7oG&UD;BkH5HQJ@YjG{B5;)XS$&i>QRr$~G2P0~egcj3 z@La~x8s@IU+h%6_uoUM6NBM5-x5D?F$}N)VG2Y%{#SnBMl4$bpGkJevl>~qKbf_Gd zC?mNLeL>up!T6W(?&V~7r}^mlS!ckhw-Cd710$G?@`)fMsKY*%B>Two*jwvJEwIA5 zt2v201i(qtJg`-V)W$$Ly{+ZvwJNta-LmQt$uCenMb7z?iNE!5O z8?-iy$YaFY{~je<$~%eu<_98)*dlQWe;oi0xnA=bRe3S|3={mJLK6!`tUKbOgTR{xn$+@hx&GZls?1MRzD6JDk(wL!*H|%&vy8+D5TZ?N)&>#Z9gwuIvls316dcKb5bcKSsD2t^vhmmcoVi{_ta;< zh^FuWs>z>sb{qp@X{vW@Ok-bB^g;r|t9%<0-z(%f$P>1y?MW;z{q%4soVsTRDo_Qa z78WMEs-2H+2Yv$t7u@m6CiK0td&>IgJvnq6!HJ+Twr<{5^AEahT`Y9SRC11&b*U_G;|1`W-et;&wzspkxHS;GU-Uy+j?q!RWzgw*ov#>$i#n0{%*#=_SXh)JMJ z#4&n6acj^=P`)~RxcPkLMiIm=f?<zw z6X^VAIU9zKY>&vQE6TTMM`sU7?Q!Si6Ta3^Mp4dTwrGF>(ahrfgyZm?aLNKI=}5V3 z4h6S%NzeI9rA(D$x?wiWjP_Aha7dGPcfc;*_TCt0<5bqr@UIHt#$RztR0_K!MfBrQL$3H;4sSnWC8ZY4lre8d<4j+QXPECUuO=$ZROY^vx(q@EwMQs zmi#>lHhFxJGJn^u5>Pivy$;&*1*16&B~Z?kYr~U#qwR&&8FRyfbnEZ(Gcl*2&L>~% z{FbsUhIQgTr9L65F6Xx|+m8m@$A-;Y@=%WWi3Rs=zHjZr9TVc;eIbMGxciUeb0S1q zwc9ceEj)DwL`h8Tdy1Zy)Z#Wx=%Kw-8u9Pgu9|wpPvcg<{Dw~4iX**AxXH~;7`A$5 zFIN(?-D|H93dD)YrgwP0RFqy*Zigy)3A2}VA1@^i9)3zn`qqniwcN*#C+)NT0%tTv zn?w)y)9zh?om%by>FfgeDNl|z*$P=@UynL5#?MIDHqnRYMD&eYlibB+A7Kt;Ww%DW zS(5r9@2k-iD%oJSv{sXkqi6vVHz;?Hp7z z!#OIlV4KmM%3p8i^ovQG{t3B1JA@eFO7#qqb^l1USsUi4d8LTPf91r+N zmz?*TInhV|#-GX^BDWBt3}9`NsQ}$8@2bie{Pizd_y4?aq4?Ao>Ew`?DyR4oV2>Ya zmCfJPx7`8p<*{M(k{{It$iu~ckrZ^;zq10E=|<$x4-oaz#+#W?(8X_PN}e3U4Ja@q zUbwceP?r(Hu(2v6F@b$BEYflO)i|c^ot{69PVQW=xqJ3hTWtjtOO<^gu?4>*BOGpp z_cjeqYYlWGd2ngT#KV6vTOM3S1SEO;;X0AiZU0RC03afyYW*2z-qLJeBKo1DFf%uMrRn@l${}X zsu;)?@0ju~2K$PksPmd9-lTl{D|B}J_Q|^R(I>6a8fHwvSIg4WRlsDap`rGq2Elft zdZqWw$Tt(5>+3AT}JM{Uby&^y9(mR(O^?8W34 zHioeEwCW-36$Y#=)W+fDO%EoO37MN6k%qrm%+TGdrhaj8-y*~|TNuzo9M9BKtVbxL zzpt=;o|2SKyt0WYVT6})WEimpMGSzR-tF;8~b2 zI4FY0Sa(yg2HVf=4&$kq3X*@3&;0u2Qi5(aw=Tl&9cH0*BL>_{k6=&JqneK&aG8@p z_%dd-2uzH!_WL>G>BPU)2Dn&nk}r905$e4zf(5J{3upW*5OX)@MV9JSJMSg>%4Ttd z3+wd4>5!kn!1Xs{tM~jhhN#OJ9~*JKWl6IK-9*8#aP^vBz(O#!0`E{OjhMZ2 zNy5;Ff5s`Mk5U)ToNVqW*T_-r6XL|PX}*0al{3ih*uwap;mTd{z3MxCoxW+RL=lp` zrY$w-)6dkWM|N?ErCNC%L(NJYnSA_x=Gc9O)YGC#*burbZC8=PtE*ZwOGgQcY!Mr)Hh_gD)J0hqc&`g^*t8zw{52S!9SG z)qG_~)M=*Ws;Pt46@$|s*1FX_E?h|EX(aFp0AhoDXJ2zN0fe-3j3&2$42YGZ5`Pz7{M`PsI|hzMKW z{5VLF*L^QjJ%0eBO$jH4i>!NOjT3;Kl;nyTt37ZtiiPT$Oo0St^lDa;RFUJffS0*i z4p7w80gA5VKQ{zJ$W{!0n48aPrGz~~4QE`sWpIr~?tuWn{f0fntxSOfV8+`o*)f>V23J>M#8_6PcFkPox)=DN_$2~9Uo>gfK3!d5z)hi1_kBfd=tw?~2 z_7%D)N4rX_^MjFHa?bLSbvnD{rI5Lz%oU`X1-{bBCD7vkEOd`88bB2(8o1KiEHz^` z>gh3=7u+FB@sqsE`Rqp>WlbgF683@WNg}N2I)IHNi>UxSMQ$JGd!pV(JpG%|Upr;` zv+UO9|1M0S zje{Sk%#M7&ZKBgzsSd#~sk?*TxqzoG=f8|6G%LT6k+-TID7`0MW}UrX3N$kQCQM&P zXoUkN2ywR6Yh0Db>D3xP+Sc^Ifiam>i%4QKz+06gqwQ|Ke zua&$v3K5mL8M`AM!7H!W{?|r4x7_PO9+3>tf{)Ct*d{{Rz&d&2iPYxV$ zQjUKMv=szQ#JrKb*?WFrLLOe^H_*d-6$Mr^F!Z*qMvVO6-uZ0QjT*&eeze!{dP@K3 z0iINDlM-nyb5`(2@60Q2FBA`dPcNeigaP6YCtkwGPk2!F5Ds5_qpqD)WV7ZIh)>5g zje3+2N%_(Js3XtKPP~H{@(+i1s?a8r-M;NavOHb|g_V9%W@VZ%8Wd;2Dmp9$4z*Xkkn^di%9JcNm z$Legw|5Q|vRE}(bcB-HbbXOk!0OL;q@Y=2hTIbK&;eYfmcF=(#H|^fH@Y;NKRz3q! zXsZ>|hG~6HUKzCwCMH8uKqQCg|G=t1QjKvdEl6>92~MF% zarXv_Lvac2?ykkHc!2_?xI3lA+HUCke!Ks-yEDu%!$1;}^IYe$`#dUMg1qi63(AZR zsT1^=@lb{$lc}4>=IyW|@Vl|54H74cvPH0E*CKo>U%+nj8Lu`CLIeA-$^J2wFY8dUn11FYdbBG)=;G_aY^Mz6LXj(QE!;^rtu= ze_=J_x}a%X#%IhP;CK01NwC^Q3);`zK*JNpiIsebF+!a%ZjLn8^?~oji;9L>pakZx z%rCYN+l^?4TD@vKkh7F+oaoPB^q&*lt8mKA@t~=8u_&G~&Y}r)KWJ4(E?$NYhPc ztTxuDZoum(zu+;QH)6M?mN`<}t&W;fqO)8&Q8s3pxVyPKX6N~%fL@*ePjyzXC;@wt z9fVzGchOL2otG)jv!C<}KbT}In90QK*L$9sK0~zYrq|#(e;ps0P0=o@;_3pO9@Lxi&E0QhLW*_4DY)bF>1@l9y$!gzSI|9{6CyB|OA4bv*b)Om72Z;I?UR(ul42`6lT)@2iN`vCdNjW@Ki6zFyxvw9*9J|3UNB>NN-uHE z&qCjm&kWSAq1>o`hVE}`-p+QV3>7RV=e%_wGvtLa9!}uSfSB0`CRqxKVl*Esb^}~% z=+RCWn3j#321E>#_h#Xa>_KM)7X2h)gg;6~$2sLJE_Qi>O53wzhR5=lgL-tjN85Va><%3#A&mo0-$g>>`TX{=Uc-!M;b8IQ zxPK^1gNyGEn;HuB4?jR6*V?|Kul z=!fh0<-DvTtA{hmA}mZO7+nSa!IWonh+zb_I;%JB5(&v}7cmygi-^ks>Twt?l{&%& z#06L-BDGq^=sHETQO1-+mF!)M-cc@U;v}VD8g(=s=KW?VX_@{3!xT+GL}*hb)HR;( zcpM$7J4zPXBmvY1Z^lv|#G-dRKikeoKFpN<`D-yjUxP`h2NJa}62{&bPZLwUeAgnx zQk;9)rsYc8Zx6B@OMKI=?u;MC@Lrbe`f5if_{!v9kO8?2e5XW8V5o{idzkGa*fXc>xrZMZ@tycpW}@`7;6JY*iJg7*k>o z_#TTs+SeyH4Lv**Z zp=XY9nxz+MK`O}p?Ea7d&+)f{HiI_RHl0Ccfe1nf-H4PRp;OH6`*{Lh7mjbf9lu@x z$aM_gnNT)YhGCfW^Hs)!Lw5)d`&}I?&}QN&Vl1T}u>un;g&&b7Dl8Qp8ZrWZ+8$-} zl^7U3Co0#2)u{;H1?!4M+0ub`5QGoQ{&HNNZa>F7&&l%*(Ojf9F;uQk5-`y+=_2!*jZw#XtOpMBFH;Ygg*8-cBNVU7s z4b<^+7#mv`@QQ1hN0H*Ib~3a@YQ4nVd;eaTTvl;DMy}1}jVLxRKrsX4=vLFi4O)Xz zOaqFy9?`SmE}+!fl-Y41rt~)^$>ZQU>Lv`c7=~hfmH=J#c;3z$b7ONDO)=7xk*Cj{ z!EB2~i^G7~op`(uD}RE8m~Hsj819hyG7y(iA8QXA3^ku9H!(P_$7IGAM0m5Z6*s0;nMXXS1GS7IxEmWTLHkVIGo?*B?p083j z)+iwTFOrSK%{=dZj?v9|G#sEndT9hUCHe5?Aq0bzW+nD_J?(d?yyAik%A}Lim5H9Y z)g*p_p^mr==Fq4U#PB^bPc3=WX`ZHdA1xPPdy3D%Aiu>C7Ws&Kj|M5Nh&0zmLshY6 zrnDbDY;9B4<~ zYQ{Qaej|#N8GD=j<*IT?SvJ`Zh8%LxA(pLGHj@|@RWwzT0FIXk-|-Q^4}^XIlp#Kv z_}`$=P=@r#Qr5K}bGyJSXrnxgYa8wqDCRSO`#2z;#?X~OoI?aZ%}&`v-2!E?9`K=`;79fVERpisVHeolYrybJ2S_D)=Dv&1E#p$_xLk1dW71e65ARR9ac@*ku1#n}LJA9=V5uF4dc1_p?sR0H~l2i!6bdwR=hES>5q# zLcj!aj6TVbTbX>MGSbmG%T{>}6RMg#~F*G^sre7MZM@Vu28;NoK@~n6kg(yBZ zNpEs`t}BwNck`WhNikP@8Ehq@y+C^}u&r_8K$&;p`smQXNE=DlH9WU9a&O*{o4{BS z!f+BIt0B@8f-;2Pzr9U1ZWVeC(}Yjs1a5v{Vq18Z%*JKC(gei7!c$$K2+2vu^}_Da zyR7(;!2n%){;FB#*+YvKDJ!w}Ez#UF2J8VGcr#|S9u@Pb9!kuND;2rDI?=V!=nvKX zV}vso3(+^TG%UP?c3O5CuMo*eya>tB`))_>^q#tMX*f3(gup-OzSDkZ{T@?B@|@lT zKWd^77p(`=HhCtH#Oe2}(x8A29LMG23EIO&tid_YB^AFBDGoOp{v z1Dh_YLqj}1boceEGB>Zd5Nty8I$?}KV>$?_2y5n3_Oi-!4p93NsIaL^spUbNrbsWJ*iOO*eGH=-OGb z<0eDyme`1w@LuF$m~S&2j4G~1DrB7R&oUEC7SZ7GUkxyJ{MPfi^3n*sP1{Y|&n~!* za7JjUh6K}aOu9!z=vp-4K_p=WsMp*y0K}x%ci-*hiDeppJTJuVemB8s3~Ehd=6WE0 zn*XaDX0q^RJk&W6a{jSVUZhajhILfHbXAh>VJcofwY4Ou%*QWOZQ^jP#qeQ2NbwoE zt+wiGOxeC7-8Sj&)9Y-j5J0MLukM9D4JSA6aI-v85~3$q!5^9f?U5sZuhbv~Pr`0p z!7`j2v1S9$^kpoGj4RPq6R#26Y+8y`J*>5)HKz-HN8^oW6KM@I@|9DhU9lbvCXU74 z)%MR?s#cpa|4RkkcKDTKOE!)7TD5WT_|?=1#+qKrDlCO3?_BAEFPUSY)ABJ#Ef#^?$JBhC=X z)S(S>rxC)~Ok+Tr=!^9-7wU-~v^=`Vai)-;L>ojt>RSg07d>|wSPXyi=&6KlT0rhe zF0$-<8r$w1`~+bV%8!)`(^bQYD-wm0T4@ytGvm3&fb*!eG*k(Y5Pk08vCk-p&rJ!F zwKI9D#exel@;p>M#k0$!!tp-3?i-n*Xkp4R@->(65hQJy{I29~!231HjrsLVj7xB=a5D zys)(Y-MT>P!Rwd3&Qr42*+A+^(^S#dq`{P^67oX)hUFjKGh8=}ncd$!!&B2XnS5=SVSGyvTEluMNnpy^xUp zW-0zYXq7%36O({n1U+f_&U=lLgx8UA>cm>+14>C$@ydbD z){G4UH4o)zty+}-4yhS>;k%%^@A^70&7JTE-RUgrm_3m*HrY#)l8&9fay}m<^5HCv zu$SZO>uKJWUexI54IH%ZOmc4nWxasv-?XwP1)m9>)s-d4;4gS$?f5-c0r65l6yQaJ zw?H4+GqjAG0U0~y^T(aLwrxzUD4`F>Hz5gmL zV8+5MfK1yC-S95mdn}jqfiryk=H&hX=)fq#D?E`)51yZ@al23{=&iEYZI@m4FXt0q{uXdxxu)H9yZ}D_;ZlF|qkQR1 zK|BF|#{=HOB^J&1VR(8(p@-{x4WXS=LzJ}R-~5@@S+5ZxkRu^sNyXgWOd4$^g`k_S zo$FFlIwx25ivh6FuD*DBUFmUXqebL@VR(h-D_5S&d?7cBGyUEvXAk<$PN(vgnHiYGqYrxTNKgW3>;;jZRM6$*ro^_p$vXNK|mWQbKyAF!x1#(^PlEGv2!jqx&s_ zzg0og*{e=gR;wbvml%$OHbo*Y@gX(XS8EvkENFoVvUqiX(d&4tZ)@!DZrYGg`k#}( z12uHZn#WMlP|*y0_l)*4?P8e4u}sn-6AoilMUE)PmLJE}HNYfWE&mi+9a#QHK`a|X zI5eGq7_&=Ic{HHy!tG0kK3_QR?^m1D%pQ@~T;KqcAnrV;)vL;lr){h2E4jLh>mDu`Fjp{9NA~4B}1A)!cJ?IoSbM|XH)#-XwW=o)nA zSpqFEaDi>Xyu=ObV{fos{?mS92I+iQ5AH_=%HBlq!>kTGVWTwBxcVyYJUu zRg}i3^9it5Pk?OH{Te&ov#>d`Q9fMHoWnw`!pE^hJzu#%d%(4rV6WI6R#6=_{+2ID zrfgUV6F{1t9I6nX`pZNeC7Il~x!h``MHmgKhaHs- ze<)I59l-9+w5eG4!f~iq#)-3y-(2ZHkv@5)9^uF|gpR-*9chzN!P}(MIc-`^1 zro6YqkYe_`UI`Nmc4-2+Ld0lGboyLl)#x0S?+S^pJ^c$tw~!)a?J)fi^NUQJ@3l8 z1A$ajQtg6j-+OZK6tea2NcRFExX^3B#OTf*rD5c_f*{6PaQSCvGLGJU*0SoWdLxKH za%iIxA8mUdtc~}ep+*ZO6gt|1XscmB=Xur6SJ?w^TEw28FYdX8qT3YKoFG@Nrr^)8 z18IIRm}YH&3aGp(MVEH1-7Ojkp#`7_5ZB`uSAUTmJ5H63A|{6k;x;CoHIzvd6a|f{fB9l%eKUKKEH!1A*T$zE{mtlOP{@ zEAsta{1?LDN8Jmv)+Vgf`gmy2tkMZJ*zOLR@%Ye^NCsw<2#UQF|Iw z#1;12E=&URIwMzSW-4sSI3!i>4{t;SBZ1SxETZpBAX%6X*bTtY7d#O8;C^ny_MZoC|Gnu2L!ra z->D#k%+ZPjU+R+eL4P=j=C=v$VHS$zUxpBz$0a0}g?fjyX>72_cKa_-P__isH)tp# z1)jE%kgHB5i}_^c>v zpExfiW4JM%f|P~34vf!lo|DL}L;3skF6tfJq;DUmfBE@K-?N2ZTm-2Ec}uLd8hX6D5T}`#D_0R3ka_BlsS=GuJ#A@Suk+WbtQ^R8uJwBF z)?1JbDC!byOQR*?M}hOn2uwur4(z_Sxyijr1bW3H|F&MwQa)e3<@jLc+ztuhf29Rc zJ7VTgIiRHG@``%6H6IZ!jj^e7K;KD1PuEAgWc$wkLt^@NyAe_+ZPJle(a`{z#P2PA zBWyD;aWeSa9BT@b2WD*xg`=eCGOM;%_=LA78X+#k{87V;=KV?VBOM+W@hWKXA{-3x zo6P^SW?URBk@mKr5hl#E55}4KH|>(>dzprA`0+&EX)-Vq^h2O{Yos{=aHxAe=k$uwT#EVD%x)Ah>vqPS%f z^WRtRS}aK2!~dsQXcg}hl&1&l2Luiw7K*_I&esmRWsj&J6R0VEBcN&cOZSdIv zKTI-ZQgRBBo8rlWSq$0*j%r&gl()NG?-BbZce!Atj2h7@2!&`EC z4Mo}rFM{2xc^4!c#4!FF+@ZWVZIIo!2`vGjVjE<9Q2{~Vn9ju9+6?y zdvV(L2VGA31Ji9SQ@Gcjy1yCfK`Ft4yc2z<%)B38Jl?ilp6W>>{q``q<1nMC^yo&% z%9Hq%e)bS->(yP!1@|ZC9ctfA2IXq6SsuPk8z}SL#f6_rkVEg9P~PcEU0+lq#i8rv z=L<2$_e$TIYD^u9TzliMu{ZTL`=T#Z)A!X6_{a`n1{r7eCLsJ1Pz>hAogm`mpT=oX zwgZsdMSs2-Nxw>b&xH<~ePW9I5sw&LFrhAcHy)EPK6ZR%#-$ZOsH-VxH zvvsXZ*sbWaZ;%Q4qYSrl<6@!fLjl zz6hxL-x>g`K}l|ePaxC$tZhm}JGT>`#Z;@$v_{m<3nV|?!(qOV*_hd~S!#4~0G2QDejGVU6Xl}SbufSK#zXH@&4Jr@Mj4D?|69)sJc4^ydn^S96WeK-3i!ZQoia(0O&;SM{OIc~2D$0z%+C{%&LWI>yel?tWN9s&^M@R9Bs1316*+s#B%GkxLFC$G)hb9kX;mL)M$Ly^ppqm$e*c z<1Tbr4SxjC=syXDE-=#_ld0SJsf81yb>;T zVb_Y^OWlDjf5e+snrA*}^X!=(k{DH0&j zIuMUlCV5K#5ROEmt%?b+L7p-HCx$SbpG$=;?`QAtLs=~|S#|tf1IQFQmZY+urstlQ zVqB4!eA!KLIEUAqu8cpZb&F*{G;;zgn!_%5ZHT82$;H(~qH+X>5Vr>uqs0>3m z3fX3O&DA4ABALxp6!u@~=nhw2N49J<$mb)MFr+oNA~>Kun##@fnbOe5dnziRoT{8_ zKF}BXTZV092PyTvz%Apm3Ug&Aw(`>wok}!;iV+`r#V3$t?H1{{6^O8?^}GTBfe`cK zgiIxQ$y11oGZYu>qcv@M=KU6?MNF~Vc2oV4&O;SHF8h^+^{NAqAk-`Y^p}EJ+jPk- zWD%|mFv+6(xnYE+Hd8J+?E|JxhjdK{%R9X!oET3A1xBed4G6h25x%Jtr;K2|G^SpkNaE zc2pfilggcUVhGN_RopMKCv}yQCZDviugv_MkouVS9f4kE8Hq(Ba$R{@67yg_7LT;KK-KNX&qkq=&r=^wYR)xbmz)PjA~}gakXY)UzMqj>%Dy_ zgQNhXHiKDVI|b3TP6ngWZz=Za&AU^-h>_+}K5p32Rq{uw!>MH>j;tPR9x>N1Bfu>l zs332xNe4F;xkmO?T%7-^Bz1>gj-$#Ibh>Z={)$W?m4EoJ!PLTm>m2UV#EJ`_~$4RuFB5@*l z5ZH5wEl0es^jPxLFfWk8b_eW7@y@W`$TB1C7f#7!piT`d8opn^_CP4p?9@Rit}c@m zt^uVRbs|h24SA^DLsF`CVgy8X4$z|!nPpk}wF)B;LP4RHEri<-wWJw5r$+~_ii|n! zyEQK%YAHB?RcvVELpI%k87&4q~=?QhU!ttNl4ehL)LA2L$HX4l!N{JK5T$^cBM(1LWS zg_RF*%;J9~*E9lT5v?NFoy5#Z%+d1@L`C-)L3N1HQ|MBXJN1dTYS~I(WrOjpff`(C zC_MZgKW8t$s!y(Et|oX}EjVM_PFrX4tXrlU$GJ4Iwr$qtA@n0)_fs&}!M`oPw8a7k zJN7i2p8fgrB*Ag2@BCLShZwt9z7wN~B53Kwpp@|?*o*reB3RaWIkIyVI|X~eJ)~CW zQd$Z|Zr>ASkLHrUE+m(9AtOMJnB9pcklbW_)>tJ825;W@@`S98F1tE*AJ7Xf+kvYS zL}6VSHji6cX!CaWfIA9~;o!~7Y0Te7W66s0M8B|z$QU%qwXew)$AhpuThj%9wG0ng zyT?sO-8L<owzJYJ#F>d&j)pdTY+qe|}-2Yi-rngH}wWph92Dk;xv$H;=gEGAJe|RDqiFJ-P#v6bF-g5vb${LY3eC51 zgB?b+Y%hoDQ^P0Ra4vY!QsdU(9qA(qr^i=6jzA3onvhqaWU$aAye`>g6}-gbe*f2l@&q@wd!h zDmk*n+nIE=e`IAt)~m2!m|#WOt3^*K-Ev#Dr2SGX>qOE~qR#Z5ml8Xi0o zMhjf{81|Zt6sk;}n1N&RDEDYYJZs>aN6*(zu?z{dN{)oY%GAXuhqy%$GrmaNEX7n9 z)<~b)g5>RVq(mc%7|ZA{YJ}s5hga-cm<+g}%UEIK3-MScqjA8_5s0g7CRHwqoAarO z;js~wkxiY0vKJgW@L+fAQ7i=%j zmhA8E2_dv{QlYHKn$@cT`81tGQSE(OwPy=QdWU!Z$PCkc~^+xE6xy!!4F1q`@?e4?uULDqlaP{F1oE268N1CL5$4}O!1 z2B*7l02lkon0NdmlLY4(nR6u*W`$7U)vh72(f~TxHEJrRXbs5`B$RfABxEuu7ufRbwe2>%~ zbJ@yjx=CLxf7BSUAb$ipL=YKFR3mT^QJHVC6ET(8+B_ypGPeParl_mwuCm$f# zVLsY@M<{7{{rsDWNy+wF_mzo>8SW_zYtBx4Ly27Yyk|+J+US_i9Sj z^<(`&ti8&Vom%XPB4g)fUwozkC%kfXMA>6HPwE8)z>&F7HACLZq$IKDE<&oi>{Uk0&N6W`HrDhe_r*CM~stq>2+CE>m5 z=-Xq-QRJlNpCE_$6E1DyYpfE*qfzSYX_T%WWOf$s8@>8)yFOd*k9RS!!E-rBt6#Z=n>Z#*SwB&v@(RfF$1(e;ulk`Z*uC;CGgP^m*Lo4znMxR zR}xj$H9Z->RNABZ)w_W=awnkK3a?0%Tc6e!VEJzGbtg>C(mj5EXL(NmIDb{nJD^V; zECrtS=#sZO0sr#c4Ce8mLNNJ&3;)|=%c6ICSdXsBw~rGSR9V;o^?CS42!g!!u1WSJ zd$R$tS_A(o9{5JvT{^&Z;U{JE&HnLBH_LzSl5Kl;`U3F{Q7={Ys5he$z9($C?ss*V zrnYE)SoMdO7LKid1vz#kgvO7cX)WXKVAxvsED8+UjGJz8K#DALx;M~9r*n61FM^B) zrdl`nK2)p}-8jZ(^HkSQu%-|Jt1Y>0_b4y3&?KAEtkCK*Nb791t0zjolA8!7hw}{L zSFsZrR8D9C(zdtVwUE8=rQQvo1Jug*AOJObnd6LU* zuJ*%dXtUE^aux{l&Li1UR_JHxLGR4Cdc=ASiufLq*%z%ny2D|dMf1ai7K&U^#l1-k z8~rL)bM!m}X1lP(r2VV@$#HkLyyiqAQKfnCZzB%uUSFEp6c z3OxrPi#a_CJ!aNFeZ;;@kmN2s^@f1*rLb;vSl}>ZGv9OLT5ui@RSVIc#9D9x!U!6- z@kKk4)GB7f=NTsKiD02De}tOf(REmBgH7Zit0`Kh(YiGanbUrKSv<3?Dv1f8?DmN) z>(@^c+wzs71t+RK17ZW^igu)FWV8|?cpDa(@GfGZaAh9{c##lW7}YYWKR?LDgkA^w zovrBA+z2QND+!N$Wn;$|Y-P8xLvW^6!USP*k~JeM^VNPca*7?fd3|&_{^w%43vJjL zp*H5FYCb<8a08$?T&?vgwzDy0#F60r+tnIjciRRr$Y;bt4uiNy&JX~k0)0?@MCqvu zcAZzaZoEY}m%4{@VXLQ1uV2EX)b){r=r?p*rt0_J=6l2s|M}q~Mvzyf;uX$(C6tQC zW5g3WJKJ+&)r_5vBL zv6Ki|))9_$i6lk!u1W1wX`bP0Spk=Hkhn9eQtOvQiA|D@it(i}?wP(It%tkeoqF#<(y0lEkF||u3Ilmn;z3_m0)ck?O^FzH9WOqU1 zc_wu?XPwwt+8%qAoZjVE8~IF<)RI!kd)n~ynAc;IRSI1u`q?VGSqG}n>Z~1HW4Xj? z?xWgcKGAk=sASKW$@&$R%A;r5%So$9)~WvR+~-g~nxaYP#f*_v{>n(A#~Fz&sXMqWjb=A0;cO|* z{p6sWX};k6DO32p@6oX0dwQp?pWedn9Q+c!PT$9{3~L<7Me55BQ{|Moig!9s|ECME zU!_r~^nq1Qp1FbBEMKQUW4+VMFE(m>q@}_D@>0`?UxXUTC~n@!Ed%Ep^>QwZa8W3` zqJ>+sv5q$ zs~&xci(<@YVqDZxsbGgvK|`skphR2Mpaei?1GFWg$zVE*^tI~Pm)|CxO`g~*|00&# z7n34iX-QZ&aBvq~P*;us% zTM*r2*_?hFz|PRK-LU^-VCPCj;2GEbWH1!D&9H7l5Okxl2+M^OtJ;hE5TGdnuUC|z zgRnHRVxD2P#KkC|pg^0$G_-)N8A@E>e&8p}xA7>XyKA2jo~<{ zS2@(uRZ(DJK6mN8vJtsTS`@+)PjhzSkK(<>;TVsH;;pGh`!=;~;bh)WWK!Zttx~n= zPB;{#8pQEXV0VpD5i5thot|rgoE=Zv5AOUD_Gy+p8lO1Lf3$4u3)VNt6LJPAUTQ}9 zL?zPsR0Yzh#8|2jer24RUYBA2BFhA|3qf{)2pdZS)(I{1%mJ-@EVM#ZQGgoU=y0b$ zwov9_QIH~s(--JwvrS)GWFxr^Lp=tQLl2OL5) z{gWNNBhk6JhR$4s8`7Y9LpMGt`0RX(<4+*$ZRC7b9vS)EAp;sL@+?xBTpF{ zt|4yTvt@Kg=}WV*yY1AbGf#jHG~)ti{q>Q$X0GmCn>AD>NNwD`=J}0ZG)Y4paBE>F zvFHf5*&floDf&bxc;E|y5WEpC7(l0kD(t&#M?LO3?*Hg_@6cJYtA^bY6QmbqwrKrD&H6ZW+Q7os%0YZe@%$~Vh1$0CPzq%jHq1f$$q2XTr z?W2)ezal3W%0p(($(>K@j|GD!n>-2niR5;xpK7CA=ub=2x7RIK_J&^du$_aYLk!&! zE-3K8?~Ch~nXh#WjK!dEGgMoe0CmvsgLu@vO96*VBCThd?Ch*>Q`2u0{=Zq+IE|p{ zYgR>5?e5pYz0_}gIg`ur4p^-W>|J+!A#0>56s;_a(QJjD>>;a;L1s=cU#GS!-e#m; z1+uqUtE<})`Z3IgR-?|vWRqhPd(+3a|uZ7ySwJJcvawtEFDYQC^*1$C*; zvx6RG*+#exzdUbjR#U3!Ojaypc(FLdU$Sv!qPwsN!_|nw)FkT=>>fKxSk?|IMku%f zZvS$hoy-8oy7_h4{!_4pmrAD1*9_-Yv?kpgI6d~JVeUyITM7#`C8U_H)||nya0LI* zrs(9}La44Fm6-DPCbZX|<>eZ%Uk|&zRB&mvMtS{9p#HCL%XPGUMs#0sOodKQGR&&j zMqVQ}=GWYB?Z*5n0P(gCJSs40$58u!+$xy!p)d^3fhqGFaiC1&9LY~^rR-7%xM|M? zytL+fb{I0uqmbC+7(>$Y*`*Cd*b^I3%VV6Gw4@&xi{nA$u)87C^R^ODCA=PJ>X5%F z&O-p~XD5OL2qSsb1@P%gqLPLbjmoh7qcEjVT`)>83$*jU%4_LC)YxB;ip=DdoOI=- z{l5A(SuqUby?p4k>gq`vs>;8~ReUm&e>4Ye@@sNSC{-z{r(J%$BZz+H{XFlr@HOXS z>SeXjxi!spc5N$eOC(J2wJAmzzJE|E{~i^%GyP2MWT6aizTP<-Xl<%uF)A>Ha27(O zQbYj9)mkJ{+4Ms9EAscgBVP2%FxYpu{Kc*+`THUz04nmMA|KOA==aKKF_XJL_e+?= z_z`NjPB`!e@;N;@Klle_T|x`@Z2@aeszdt%vjg6_rUBwE{DCG|Q-(vy39cofF1^U= zzE7NL=1vo~0rxl&qPXs(Dt!nCSuuk$6ST}tuR`uIkP*TMb2nnx5ayKVt%wRtQ?+4Q z7rsnIp$q#k+Eo3(U^-OibnYlBL^Ld<>+>}&q|4=cMPid-a};BSfq*i|t*ANn^Pe8A zR-F@kf<`?HjtRu}p&u_H?+`xg`S>j(&SxEY`7z?cv^Lk_YeS{^i7^Byy+#7TN9tvT z71oHIaZ;wdc6C3##ef-q>t{0!tlj~sRwDRac778=uT+FFI{z-MEd1$|0$0gQo+58p z>>+l;BK+-+b@8_^4PXiXj+tNU5p6^0J>m}wCza=2v{O6%)&NF*oum2LOXkZz z2t2yKdGLC3KP>}@{5`;=2W=r-@MplMwp=PNTW#7Hr^oN!y7yeMP)dyRra|T>PcW6) zefHz-fKTgNV3U2@{uFfhE&7v$b1hI}qBQ#YcpCe<*VPfMrvZbQBhKGwchMN%guV@? zf1A8->QQp%A`coy>noYykg6G2o^-n(jmm;P{lm}9ENajwT&)^$%q1ssX-0mJbJwL# z!<5`q?k6YmPaGwtn5sq<4j5eCwd^ngt?PvF?^Dl#X49wn#9b680@mlvC)8;(HcO>fo2}Ek*+;S zfgHrEs+qjtlaWzufsK(uRbFtwTUfSG(f1CN-#^4cJQ<*iQP`e3Q2sXB^_OP<>`Z5n zNvydj==}f-z-aMTtuEG?bdncn^~t;EUx$4N#t?H}y5ro#>~)=Mz_n~fsoL*6E~Q?9 zb8t}};Mx^`1wlT&-wW|;IYCeKoK-$Lv7k!H4%KYH_KV;FesH#y8W)$J+*CmW_QN*x`#gh!^{4`wa933 z5w6%Pd&msj&rRarzw21lb0lZr&4$PLh{~(y46GE$6w@M;J8>||%~{?_kJHX#L3M=e zH;ajm5rkMK#z&WwjsH?B6HL~4J2Bq~1Ona}6v6_+d_q!Y4JJ?Md(3i{A>{rUh2UPa zw^j4u^PyWhN-5U)s^Ods9;+eRl^!OC1(U%S@m#pNN7dc1!xr39kkK$hdClQ#gGu1{ z7IKpa3uJQon_d)B|}X+{2MVkk&O7nZt&!KDG&5z}bd^$d_wc9KT5;Nt?N2K!a* zVfn*eF*!Ns_t|5TtGZZN`qcK7oo*b1ZJmAq1FGW4!Y#PU9yK3HKnB&=YlpcJF2Jd+ zJ8S%CT^Nt>iH3O_C>yxlW)NdK9)GUO=ze8lFh)u`!}y#-szwWp57b6H;zc+wE3qYB0%(|6l{7gt;x138Z{2Lyy{su$TJ5IptV3Vdoqh}tKj3LiN9>-;tCY5i%yKbS}vkAsl-6I5n0K_}*b}L)? z)#?6EU)VW%(;UB4 zf#S(YD7e06A78Y0pedLVkiWsEY)P{^n9&v`s|CojVv(5AeVsBlQIk|^Li5xUvfV7# zJ&x3DJ1K%f9rIc)hMxCgT84B5aE_xZi%d)`80f3|qOCDRp6kZPTb}(%xY=hH8!PSw zDUdAnBPhaY$eu$~q2~{0dqAtc{rMU^!;%&&ER+~R!_;Ng_3RtGmGP5~SO7Lx8W%b0 z7Qoz$2))qK{@IjI%T1Z3+ac3x^vnVvp6zIgDh;4g1*oCDl5joO_!@2#dM{}9Gm@s{$?!3SNX$M zkT?4gQhl;h&DvkoQvZQRWCiA_S1YdubqG7X=q1^EO$yf7yU(~Bu)@6@(J^BB?!)-s zDl(Vl6N!U|ycu;Kf&^j!7L%CY1ll*@wZY#od-8#A4FtRVuAVnDLt-mKU_Ge?&&y74 zga)YH0yrP%dFI>mr*yv}K<%O5C4uSYIZ+17gwki0!EShYPmCd#6RQgW>S7S?M=EJT#kJ|T+ z$dAS9F$7sTNXLM5_F@nn?Wd~{;=HLuGOCTDk}JwIgh|=2;`NRhDt+o(#b};V;z~tm zw-A0(nRn^`i>G8y3F%G|knYAsU=fg%?hsIV zDM1jvgU|E6|Nr~VH*eGpZ^gTbz$}HSzs&DWO64#T79MAf&tCU)PAZUPC7BA6L0LQfkw(rJv3A< zW`(XUy>aX?tujFP2V+-8`Bv@;|MZsYPzqrxy;hiDWk9ch9Rz(EzqEN)!mv5k4GZ@~6hVWq_cy`IKO zgTV6PjWKyGP{Pia142Ulbvw)=1g69njgTe`nMLcev0~RBo2eb*XicL%NrwZCtA+Hj zeZ_1@={DoVGN8tM$izQfqD8N}d^m$V!9SUr_Q^8}F(P!9=|D9IjaO7caAE1TkI>ig z6?nI?Gt4jf2k?4TF@Sxh;aH=gRxG2TJ5bLl>pj#pZ6EA51^9=CZadjTjX`<{zW%{V zUb6fK7VXEzml1<B}25Eg}TA-)kX~0-80o6sNKFxr6 zRc+WS8avVdRm!RkVsqMe;gD7zPTU~Q<9(m^%Gf&3d3ne{o`Wg6EV8ddw8JzaA4sq%5uhDCFiakBdV@Y`_*Bl);nX*}FDr>Mwl|XiXY^-th zGpd&-o zmNn#A-wIWN#8aRjtr9_Jvr1-rF)4M)Nhx)*z3s+XcRvJEY$~bBsEWnnG{j2Z-RVXg zv#1|I2s;Jdi;;ACSiIGM2@w1P@Ur(jZZA5;N0mvPTR%G?d6%ptvN6pecO!HcjbP86 zg_&)i`S3>nPh!GGxp9Z0XBpJ`@r+FxZ$vWmumGJt?Xs4OX# z+b{wuz_!jotcs1o&mG9szbPFg<5PR7Q(mpf=$0ANb|}^SZ;1}OHngT)*UYE@*$7-{ zjWk9##+`Ho4TFczaqR8;Uxuyy+i;vlfP1Tk9VikvePC4G<>NP};e7R#Qe|3nYUo4Z zdU>SMC}jkGl`Hwkt()vSyp17f5^B(jN8&SLr8K>Nu*XoNR;0#8M3W6cf$q*v1L!Ns zVcJ`tx1ZLm)9VfcLd+;M;PU%9{ESY@RO@R4MaI@&E|u(!N#o%kgXR=G$K5Z-%qYjzst3~RC&uqcHQB*B3v6_S>o;z8U*6m{z5|HED(w0Rj+w4d z7$~g+s|Gvxt1QwQWQCgvqW`LDV0-eiK4X*@R~H zLVKR#V|7CBt7BA@9q!Lh2|s#^Lse3>ruANzHtYtiWwxGt3Ngy`HAx4k_tL~#B?H<= zzy_(YS`_n7vIL}ijN#iv8 zmD6;EJE{vhna?ePVl{iZmDX4vc;^-O-a4YulV!N*G*%<;ycZze{E-B?JuO@ZEk zv@^l;moh{6zmYCZ|HP|d!Qh{NG2PzMqY$$+?8LfKc`9R^IDy;VGL06x$8op7BDK&^ zp#MiaV~9`kf5Q(SaQ-fv9S8&p(^5Lv$x}%-gd_t%A}tb&8_s(@I{B7(!HF8hc3U zQE!za)ODBKO6JrFfqcVNRxulaXnc@rCO%TO4^Yaw4N?XfURT!>nA2%8$z~gp(X&I9 zN}#bm%Y>AnOzdMAxF!6U{EX~srYRB)u_-G+7bP)p1i$NKXdP_7-D)12Kwu69+8O-} z+lPGs@Aac9wY4RL|KPaWq zsgP5zox%#$_1S0TwA>JpDW+8nmm**{wkJ<_;@MJ%M_wM*uruInv`CF%>5lm&n|a3=ILtru=P|3X)kO~W9%o^TH@AK&1gFBT(OC493BMxE7CO{}(iZ2`99wk{0@O~Mv8*g!e>#`B8J_Jn z<<~!VOIt@ih6R2K>S50e{`%o^>faz1mc!uK3CT8=>7n8x@xX%A>&Sbv>M4qzz!k=N zGH-vW<0UvSgGScV@u^h6A#%zW+ZTLLD+q_btH-V-z4vOTz7*T3QzQYS=4J!+CVp>+ zx_ZJ+kT37hE@eLP!H%H7N}{`%tC;!-1@btu6zLALy-#*>Axh+(BX5B}@KEeay?p(( z-Z-6#P_Jl(<+B< zmJ49-J46M(MWMgyW^%c zldUCx(W}cGpoVE4dSEVnpEEIO@#Hy?R^K^aNgiwm&Dfo||EH!%%}92HyEW^?j_=O_YL^&8V&Ac6(Km?D=F~(>L&gqWu{|fq{65bhTNTNqWhiH- z`@)i?*+g8WiG0DAiSzXz(=0(m)u**~>Kir?bCp@nr*AeoV5lKm;w&idFGODK zs~A?|q_Zac8Rk&t`TqNRge8W);UU413BGo=f>DN^iNC2pPKte|jZWJpx<4GUCagEl z0krFwQK&}t=|qtl~0C383ap$E-)kK69HXpp3@n_{4xXqs++|TBluH6 zD2|Dg4YPe{1pp+oMB;Bzo}x*js-g#NN$E4Allr#^ z+uZ~bK9#SRiyfd3csnF|)8`-91F+L&2LtP8q1rjZmZaf@_~Fwyn^~cym2js;nf*Yw zEV#|z&qDU;`KfM%u(I)HnaP3GC26Iq8ib3d=zXTcvYEE!~P1V~$vMOY8xDDJl!l9VhzEPJ&85|#t%J&6y^ z=ZC3~+7Z0y|6~Ey^Hu4OYWy$NH+-dar8jazH-9l581O%<7|G~yB;4c*vBPkSH0hcf zZdDa>Dmm{6^fO63O_&g_{eYN_b=cJ!66A)#do0x9M=yF~y4-PxC(so0WMPfwh{SbK9 zz(ph=qGZMTf)X=Ap{Qz$^`65TJI*N#s1BdEQBy{jF@n zZxhjv@f%iE?sxy%fda~Kv5T=7qP3YE4L_-y`(d2N=wn1$a?t=txkj74UeoQDu$>EL z_+XfpFymy{G^AK5oy-m1q&6Hvw#Dx|bpR@6T`nl&UQ{$E(2Q#bX*}v(^=UYH{+z9d z2!v~TWvJe@EisdL{6@tlFLLB?)J)=$4`v%a%0`{3zhXCoNRJh7Fu0NRU9apm{Ke+s zC1yf!9~d5&+rReZBeI%!{~j<(+eGd@vVIE1mXxYE^UNZ02Xj`00=Ly`QBIsa+E!!IAp=~Dyg z5hxix6ZxUN(*6u(Un>#F7>+m~QmcK3XJj6kiU|gr#jEBS4Z2gE_WtmC#))}Ef6AvD zWRJszeaC;eGh6vvBgV-U(S3ZG6Le|BgJRNro%6_O?3d}IGXhS ziEF-e0@k_`iujHczQp$MV>A+WrW<HDe>zajD6Hfm+QU-we%L^fs3|It zU%h2w?6Fqx#pmj@D*`58k1*l2d|DIpvmrl(XW`(*Bjs3!S~@<51_FG zFRS**f~q&8uS8$D-_W1lwx3*tc5rK@=q>a*^aOak-*X1?VSIHqh{F{{5skcRLGOq> znY1XQW4P#jM*&MK;MX^z#L+~*H434q-@h!bRnl&Lrl^yytz9C_Cy?3Z5>b}DsnIfj zr`sMzf+i&8M!i{Kzzpa4-0;X(W_KhOp{=YvD!9R1nn4t2bBH)Ach`O*ejLjgcCAO> z2FdPALlt#9Xh+s7PA`XP50}m$wS=2Vp-C7zrFZ2|sJ^GGwmDQUw(37S59m9xS&GHv&~CB68TG}xR95_$(|CRQIhq8H+0KY$uGmIW z3|$}D&52I{mxS#HLzo{GAD^(>XO%w{R+e7>D^CTt#@erA8-4VQ#e7X=;$J&Rs`pd+ z`kizO&tX1}JG_CGF`;RMHDXpFe*=)YiEToOaWcCUh|ZmE-zMowa`vBDqoiQ1(%N~jy*Qc`-6%*S32Z_T!(3vkNjg6 zd%d_%u2 z{LK;hN(?fv5Hf2$RjTezE{2aGAGCtn)Y+!|I3_8jmvxMr{!>eE7)jYc24^oA&2VnC zy1^f9{bPxg%p(I{!8(ux_#RWJCTdU_}^wqD0U^0{$+T~V!(n9 z&*tkeiqP0__jE?d(YYp10~*h$2H%QY67vC^NdF&s>aXmj%KCW!iM5MA*CF!}^fJ>u zcnpQR3x9J0(9U+hEn?M666&834*iURtL-0ut@el0$^Rg;ZINBRX?lB&Qd>Fr&sGs< z@GyQULi7bVnqNd)lCwf0aQrd_0X-(n`P=uG01C(^)+)!UWSAa(NwCk9(oDpN@wzM# z&Noe{@yd zsL;@PLh}#Y$tVDvo}500KZ2p9dcslKRMJO_9^I1ZQW{ci8g=p5zhc~77-+kZnO*#F zuk|;;1g_lQ=wpE0LwW_9=8_=)*AdB9(*)GwkuV2}y6lpd%7D!FJ)1`28Wr;r$tJ*fg9|A849msQ%!16oYCAvQPiQXUs+m!AtX998a8Zy^@FBsE~HPx z8@@pu47%56wVr1Q4pXhF|H$jTI00zPv^R#y8}MPx3%60z9*vEp5CIHbq)(qL^JlC( zP3FT!lm*nh;Y=grMIlnbk38vZ?gylIwAU{3*Zofpz8CVX7C1gisA_)#uy-8f_FiT2Dl-7^oFITY!N8nP^ z)0+7=l3;iHU`{KP!l;L>vlpS`-?yUqxD$_O#jyll!^^#vPvzup7*Sa1E|y6)uUd@s zQ8W51{V~@kqU@;oRL1@)tpjTdlT>~|-F=@O%y%tSWo0}+oJ3Zg~ZSHFZw~qv7 z zBTm2VJ#F6oHIx<4h9LRy`id9C{w2L9r8BJZ_AEre7CIouQ;bjs%EBk%ZvJgcBuu)x zq^XXWk70sk^Rlbb)!Gnm^{mnDZSCF!o(jb)5;!pVvpoyqj}1 z-@_!_mn~EGsPx~G6v^!~IW?yH>!Q?8Q#unGL^dLsi)bcd>uBExUmc70j+~7@JREow zrlLmHKSRMFFqUD9)6;RR`hcR@YXV!ad-CLKXvNXQPt|h&^7Ri#&9f(Of9I>Wy;JM5 z4USYV=fGmlB6DhS-q6OxcnQobCX<&=W7z9mTbDW(BjB!P5_w&_x9ui{Ve==?qtGMY zzoYgSX=F&XkO7xvzQ~+4Q8i6|KWwCmBXyR1@l-cDZp8KwTj^sA1irNl zAEi@m@Qg5Ad%D7$mg+7f`bxLMc(@Y{hI}I6!{tgi6*3o4L}-xUBXg=BPM+iLv*vvv zCM@qMj=v|_jw^w-eug0I)=y$)@X=)jGPF9mf{HF+@EIj zTD%IEox6_s#ydvETD4E!jOB~9Ro|QlyI$)J2!$frGj_KyQt&=GByJspcoH3iUJ@M; z2jARB`yTB`@(Wz!W#$_=e6rk8@l2#xN0VGS^R5yIZ5WP~rOo`2wTlKO)eJY-ky9Hd zm^16%Do_cd72ZE7oA>PY`n}NS?-7k>k9BrtT%vFKDtW!?`IiZN;*O5QH^=4@^0=tu zO0*HrF>nmTgFgnc7+tnS>!h#QY*mF3ZHVw4uQf%Rc}L^zHC4ThBwk0Tl@~uA&_B+1 zPAZrTw3#?gLG<+c4Hb7+pO~WZJPI0T#0XTHmB+SOyg%M6|r z3B25ArJ==q`MccreAh{2&S`{C>rlKG@s0ZPRf8s}s*-D1Xh8dE4tOR*%yl{O-+bZ#<&T4(0N_xT>w~07j@k0=l@R zMK*--S>c;V{6YKGYWw_Rrg43!FyC7E%i`_CY)nE-Y#)A-!Vd3`64s@;V{skc{48rfgVFQCPm>_aQ8^V0z6%M#DLH%?rX(;?_xAt<@?3S43qU_Gq z@mMyQYe8%i&p2_O!&F4fSRk91Wwm@Y%plxA{!7ly{Nk?T+}ffJ`&`inV;B?lU|56P zAH1B*&tyWY3e6f1jo_ZxOPR1s^Z`Gq;qR5X9mY2u2@t$N+dkXyDeB(5sjb~Ef?Sl` zoZH|p4RjH>x4*R3pIq^Xg^NAad5B_=w)<^V>?RsGF+#=02ck(di{w*`zXrUsPDXo^YHJ-tzJ zzAiCwE)E+W4@F^(8c z@2wWvVF#rlhq|Lpf#AHs$1{j3Se1o!Dj5@l3e&DN1D<|gzP)lQe2}>6PThWC{O^C6 zIPd0k(o2_QfirH{Z`kqmlH+_AlI;F`-reecK!mG~hJ$Gy)5kqnTxg9m2%_g%C>c*i z7ADzR(0;~&Y&z(ih!G&L;B@MT;ZKaYhKGE$8`Vwm{VW4N)M@px3NUA`iBSATFOlMg z$^>KoIN5rjx)3S_UNMRvm)R%16%)No!PUj!bq$^?sA<&h%NV6#bW7Y=K^WKK|8Zzs z68aed7wQM*s7KUtKx~nD>156&csu^nM1N8Ca(_9~O&!w4B7BAfrq(iGg9i246IWSP zV?#XEtJm8yJ$nOxMMfvVaEu>h6tF4&B`Y=4C9BK zfJpJHSiZVuLq@kI=i)=Zg$j)sJa5oGMLLyrC#d=pv_{v)K6jdDtgMy>3zb8TL1W`Y zeyRn1hW%k-?oiLS-H6P=M;*@$#hN%$>wcX((_e#Oa5PeUD#1e^p-XXu zR;OiHtx1=C@I@(2g2Y*89O=mL;np^qSvt>L#CHBIMnz~CDotZxjYQDn1@eWM?}Dr? zK#8)bID=X-Zc!Bd`NI7r!*qszPkcxhq6Ue>LCXwYphNBk0d6m{-G*;2uX_Ehu+x9c zN5_-8)(i+(t7iO&tQfp5-I!3n``K&P`h2;ip!&56zY^>SM1xF;`_y&o9`%*)oeyGj zlg)%FKNuQ91%pt0lbQ8n-cAr&D{5`c5b@XrrIbytfMKgdrEjwGrOmh~>Xd+Sb#rZV zi8t%B<0oI%8;m{*a4!zbf4ydidJ(NAdZ|ut39}r}%H*~`tbiaR4d_?uS#fxmfLT2dlAI5>E5Fkja*ayTvM zyz=Fs?$iB2M(Dm%Wl2d1FBjKI)%H*l{?azQ=gMOPil|p-n(+R7Z#>_~qkDO1k8&5t zr11o<@%z6w!Af=X%6UG1P3>B`AMQ1>||S>h!Kr33?CuNhsd&lV)p#Q zsiS^&%(l)-r(8J4hJAb@qB^PqQU1K@vkWkMuGFmQgmZfSEBjbZ`i;fZb`=GM&jVb< zn7!{KNmIWb>XVxVxOL6`@Wh*tyk$?36!bn`iB#+wW6rGdenCvW)gEJu)EO(cN0bWX z1V?UA48*;Mf6c3Gt+D)gB0iE?$xX0_v?nY)Kj3Q(iAUa~&EfV=D1t#|!zlL*Jl1st zz4yHCbkaC<>cV;<0z7lE4WL12Hku7_!S7(c)N?ypW;goT;=B z(EEG*ep#y$aKpgO1GW$zIpVv-9Zg%eXIehCHQ;axs_zTQ+=AT=nTG4pMMqzaYwz;f zShQ2L#s|&ohNid2+FyD)kD$uO^N((sq@BHzXj1-## zF$fC7AUud8A#AyP(8LsdpU~6o%bR?eKmyJA$uGNG>5d0@xBMnkN4k{LB)oYj&s-t= zmhIp-)E9idOcs|y9`<)&VY*0Aq@4L_ zf6UdB=v*Gz68-qD9>i{>8N|9T3l^F*!lr!-XBnmU_di?Pw#^dud<%eMK79Ql^o=-(f6M!0kw0+Xq6m_-IAsKv z$Oyo^)xDBS_Iyo^*o-RV9!xLvp$HVn^|o_b&85QY`LG71Z0t%$husH0=Zh0=yj%|oP1Xr>xQ?h)X_zr`VIXn~}j8CN857Gh$+)bn&VGl`fYgfd9mg6c-m|%>_GI#7AUM2T7sp-{v5hWd;_Y!H|>Th zGi)%t07e|?S)g*^8~%e&2fG^0o}eYP;deq$_jf5F6Qdn>#sk?n_BY)kOsrsP3t$Sn z3z99;oaIbbJQ^VyY=2Xu5r$9nvm1EKCkNyPgiB5?D#?by@pUc&^BOS|Kd*aSKqz;RjCnZ|H97B4i2Hk=B%ns(bJ9Kk52a!Whp9(`ai^(J;KS;1x0gr>Bpo=}1&V{^n$c`ODrm zQ5$h&WHs9E_Z^;xH)zoD0tx@AfmmXf_M_J2r5e4HnHqzJunv#CElKwYPu^ZsRpH2J zw{j76F+w!HsAI&ssEQ6W+3W9hn zJpZPw^;+j?6;Nq`Zn2x9!fCh7+7<18+!3A5rr+uibFk4D{^`2z;dhzLpFgM>p~k1BEAHXoEZ=JP<1YvT}DwCk~rl*c-t zFj{}5rM&KXVi0AJ_p;G(9NkGHW7JW9XO^`UhYzQgygTVf9_(DYWgwiHw?k2b$D#6G z{qz-t7<1g2*Ss-&d4+2^Cpw6t`sR=R34pk-*uNd100g6TJF30)k%l$LH(41!=gID$ zP;nxz#u-pXt$s_Vu_m_a)vEX>-(;|V|A5*CmTH?w3~Bp8{RdRC-GmE83pTwP(5co` z-^Eo(DHi6Adji295RSEgOi^PstXOMq%hgb{j0HZ4+H088puIX?g%|x6+RnP1D6`%rE!9!zE7aPB>TWbfhe`T&`E zS>v1`cFYOr|LFaO)#dbfPmrDHv6R=B?w*wR=A+J7yDz%Zr$+i6ZO3?VW8n(K5e`yg z5juGl-E_^}bulcUIWj68_0BII-fp(kWvolYEDc|ak+)>KGDR0YNQNw6IX(j)yjz#D zaWp!WX}t;5_!oGtwtK{$T`^Pq$N^>HfPO$ip&L*T%aAl58WtK-c+CBiubay?V^>IG zJYLF&ybF;FWfdBG<8n~W$U|)?r$BvA3ueP#cp08O`c_XifbF>ON)f&AllRB`ukR}h z=AY%;4mtnxzaD>%b_zG|p6n-ZQRboE=^?gF6k4z~n&j^JK9yd{eyiV|mzJARK}$Hz z{AIiOJqyMQKcld3U#E;TrJ;6cRmkLW1B*Ki^4*771YdubUXB@m%{LQMc4Jh(%U&@bv01)gSWjkr~ao6ggwhV{5+Q_XotsI7$E{E z0gA?F>Yf-KO2Z0P3nD%Ua_>1BxAnl=5N0NY0E)QGe3;j@#R23P#-ROuKl#!W&gipTu8Tab~#j zOo35C6iSLdl&WEnP-6%a3m3cc)Olzh|CEuT2@1Y(qPrhTnzrK&Z<)dT+2ty81+``}vq}9};bfr4hye0}H zZejiE?*40pTb5x0a9(sgv<&sM_L&WB3O+(JY^0ZEEr>uHVv`+;Gwm^0Bo0H`4x(n; z-YN2q=u#kdUW4$!LT5Efc+%%aC08z8;d`}$rg$EEL_0?lfDZ;ygm^?Fv8%)&nN_+J zJ#W#u@ncqJeLEb!MHIgDQVN^wEDf{iDqtk8Ok{&+X81UQ4}%J zB`%(@I-2UoM!i@s-Ss3H2u%$NZ24r_5>8N9sHRB*wcTU+4Djt{TiM;8ZmzarI3y&K z$;wrxCF2lL;#?jG} z$76#H2N4aG`z4H^?|OGMPq@d|kbE>;#}L>0Fb>(w8_Vm<0%?p1s4H*595yc9{ehwD zs(YL>80a?uV#7SnwKxc+a;cfN3cb!Q9_si{7Qh*SZ6wp4Ga+Cuy2yWR>V`o7zZI_T zTUE7=W-x`&oRB7kcV4%Yd4P|4Wl!4C5&#sJl*L^eP0%&QjcbE?t`uL(o2T5Vo@qj> zcrR28-sVFBI{N#~G-4KLP^b^N*%}m;s6zw@c3J%bH#OHT=oJ5=Mbp4rUUe-XYn7>vbG)1xmXxpyf;DX60n0ENv_z@IAA@nn^$Ak`*-XMidm&VzHAH3;W3F{H zrwha}9rKH#;3xITNUq^P7y`rxs&l5j5783DJ(VzL(5fj!LZZ2|QJjr$Hyt>? zSao!h=kZ|~ZQ~mNt-Oga@3mky=Ls5Ph97AJc2C2FFaHVX2g1kI#5ePI48nIajQ5g;r_0F^k?zlZ3*Vn zTx4T>mK<7#GHL-CX#9A^YwkgHAJ_K1{FwIq8_RBlXr?Cu+sYKFp%Z9`FQ_OnUfI^>itpHjHji-zt-?#!P6Tu&gOe zh7UYxc#8Mx@j*&1p?yMhiP@q@SC)(#ne82$?#5nl#y{vrK z-~bi8>%N0d7g-Z|qMT=?DUG(z_eNVqcb*8o zXa`aP1w9AZ!F$84gBpwH_Y8f|KFSI9kqS*z6hPB;sC?kc_NYHa5^{ODshOBmWS zh@xd%x8b*;8s3Y5iaLa+f7Lhd^z8olXcu%)?O5!0Nde{NB|(lv>wiO%!-K;!Rx}xF zj>gZFMALjYpZ^bu^lsdeZ;cdpU_ zc}z>K39XrJSgjO?84b%M59DgLL}ykgU+dV{@!s|vk7nam=b*xd$dVLn4J{lWoW4tk3L2!AOI z4wc)WjzyVdFmO>w5ZT4HN3y(J(bl_74nHmhie(+Yt2zcT4-=Y2-p6(fPz>SL0=uOr z?XebggxY8Sld_Xy>%moG-JSRT3r_MJ9zs0MZ32+vE0TrZE<{PpeBxp@Q9bE9DgN){ z21PkizgzItlBm|YfE#6`z;%7!n1Z$-L+ajli|F1@&3s$pIQntqUW42t`#vI=r(NQ77}*Jf4yL{qUW<2oifCg~r(IVwD8ruw8%<_JpabRdK{r9Qf z#KAtHh=pV%*wxDBf)x1s*z(Wf1&8WGJ?e5mJ}f3P{82?!jdBA4s5fal0Fp$H zw)+O?{es~1jk*|JpuS`q+jsT{$r{CkFBT+b_OF|NMue%{GAL-ESsYpf2$jui zNONp>UIGoKhzITie!=R;GlNcpTJvL%k`RI=(hvw6bTDARH!iR(+UJVNegZbS;H^h& z=mUpCaMhFquj_xd5~A-2y8P;W0f^yCu{finR%sq2mEz1xEy^ z-CGOQA)?`G=22>Duw7xuj05@*_F)fDgi{lFLP1B=mR~{PAmji8i)I;9>WZ0UWrrrP zB?1*H6(JS!!W#;~@oe)h(Thk=OSd0zt!3p94Nm+al(K2AIIKtXO zt3vi^!CNcOuL4>R&L00(xBd0wG^pz4Y_~!!vedp?E zY!Gy!3oVOL32j0|Zq0&2s6QpcA)}V^8dUF>vLCrgIipYEMj%n@i}nFp^a|{O!hCoc z3Q$6<3)=zVLhi1Hf`+kw5$Xk5AHAOYNf&%*zu8vVjE3-Vym1mL6-7sU+%<0c)yu?m z!dlIx1GTJ`!~jbR<1RyiGc5}Omkf764Ge`KigrIlDB(;fteP_DmYoxR8_VK!V+31^ zZw@38BdY8MC6jl~x+K17%76pVRb79Bf4`|? ztt%bKH_sdzl>r+4q#X2GH3T1Y+L_-Nxj);6Z|0iFg~*1KCG4HkLb)`R{{HDS3u?gY zk`>5h*jb=|$2!g4Mfb7gy^eoRx8XPT{?v}Ga-beG0F*{i+?(3q)y?qEZ|4`t&xs2K z+9lHG>WE-%dufJk*nvsw%e&k~T`rY#&^)GE!Zc8T;a05<>9Udog@qgaaAPh1yXn}N z7oUR=?@EAnMtV_(qQ!LWrH&`1TGp~OK<^>W{Y%s+^T=p+? zXl`KFjNn#asQ%UtSIw&RKL8`ThEK~DhC)p<2+Ds+zz{Q^yRg*V`?Vrrxy$K${j3Jr zWYAV%&U^@IjmdhW$p8z}@8kT~tT3(bv`XVs^Tnt$Xoy_iZGnA`xA563rg|n*!^=cZ za!m{zVq+KA3^_z<9K$uW8Lv64)@H{6p&T4|tILSf@i3cMMoq-RW_rqo=lMOg47==J$u z;nUB*@o_wt$jy-3nDSdx{3^n@k+^c|Eenl|}FMPTe-dA!A`? zM$iYy9k#|>9alvoHjM*?4Jkxs79;N2d$DB!UsDIxx>lTMB;#JQ*OlOJWe^P}pF%#S z+;&P~WQ^F)TZ-0AYXu+vdW{_zLpU}8IBuNvD)q+6Bct{0Mqbhxj(Rys6>)Wg#0Gbw z5ouCS_j{<|k|{LJOW}jX)RI~K2VNuJI+wt;;ADyi;WNzRpC50v#(?Y8g25+ZmT_9M z;gu5pStm)}zNWvLfh%~W+ldHw{ln0U7Etr7Pzq1`1~B*jyw^Ys#twK+BCun}!E?QP zS9$eTaqio@tlbFUE&djVjH_aS}& z1?a$}So-Fz%PyKKG@-dbljre~ zg{8(S6vQBR`MuXa0>0-@GnuM6E zqa&NCa4S$Se3AYb2MpRv-}NMi3L>@s4q3bMmh1A#0_;|EbouNM9%vR6bOeT=cB8}T zAbboMF94N=cmcyPZ2^Shm}dC`gX-#}bgk}Ft9P|0`jnSzsTN5D$#XDC99ei(2t6c} zXdv`YSE#65K9V3>iFyfVh+2lZrN)~2)xRxt{LeQhu6lBVVEQ&LqYBf&-&0Zq{V0({ ze{iFK(LYl(AS(+Zg<>#9G6t$Sk+vP;AzCY)7jeCAJ%?-beTJp?=Y>BRrINK{k1csE z9cWg~cix@QvzvyEzBAT8;Pt1H^Tf;r7v0bP7x=T7eUSAC_$FeFG(o`adr#sozU=vT ziO;t_uEP&ZOel!NDCCr?6)s@$WCvG-h7rgfK{_BZxdN3aM5nH>f7MJO>Zd+}AhUpTe zj(wT150!v^-5Hs%doOpoDazA7Kmch$`y?<_^Q>U^XYJFkUhF$|=?0|U!|evA$s*R{ zxy}<-U7U{~=fIIwkA=A@)ddvr)Sx;FH2lA)I*>aM4cji`-$=R97R zVfeh;*)gc{4^~j-pxlz-m#V6s;o4_%3-2QjE!S3QfrPk>akWT! zzEykjd~L!JFTUe1I=9=Rl!@&tXFOKcZOCuVpd({WVb496Sx(()Tvnwvxb)xnMaq_z z>YHEXwt^5KiF4z{S~Em|4`$DKw2$383g%1y=vN-m;(?=n7^{Cm8h0wdA=Zk!w#a&s z{BH-g7N1-FT%n;y-8x4--qwC|))+Z*qz`?qsLFY3H&CA}jG|ht2UQ*zfmZw^ZQMuy zRzqi0SJotIc)bMNLVQYLbYbQY59&N}P$q^muW&xj`)NO1IMI~Iwg6^D1A{|A@^z&H z$5&8^(%Sk6Jpo(DcM2TKtK4*-|J zB-~6G!ipAH7VR?X)RW7AIyeq)0;hs4X$3_WzEe|eV|H{43hog(APEkPiUBDiyAg97 zSQY^+EB;>4@}nG&f=rk&SfnNaMD?{n1{MWfCo`r(qTl0qMm#6xdEA)ZnfYL+Ah7=ry!@RsRoPZyD8A+qG-sw8f#gyKB(kh2m0* zyIaxV6pFTml;Ccmg#yLhy#)8-PVpjz;LaEB`+45I-yh!|{9p_gjFp77<~7gbJg+rB ziT091Fj-KDy5l^lE zMo14(bV$zCEj{^~RHW&kdXp$qlLMmZmo1zslHav{Yy8DS;Yqm~My$~H&a-E(!$C^+Eg`(BOCNu9 zU+GxkOGk$@0}-|;j_CaA*7i_rU9@}c&Oywfo8rML&7lZ|=yuRfeC(`V9nDygl!pCv z;Bb!JWm2JcIvAZ;^=v)s&&<0YY5`HPUA$-{qh`f#?E}f-yQLhGF9NL*xfXs(Z|~YG zzw`fNMNnrQ4E~Q3F$dZE`w~L-_<(p;Rxa$Hq29q}vx( zhCP~0Um4%K(x}@zbOZB7f3-I>TrIs)Z@t4tFtu}4nza|?`f2=z>uyXMs=8H)wGUx% z1EgSoYdp?%{39CfAiRv#?r=M)@81TPNaH(n9ZBK?i)_vc)bc~_)o*olQ}#^*;* zaQw>m#g(fn$lwYK?h$E2JPq-RK~xndcN%w|-bW9S9b&im8DMV6Y+a<#s6i_K z%*~tFdQh#5O(g38E;(gnmB1*%CGB zXGU2bBpn}I+vMh7F(c->He!)8lSPv;M}?W;l&5If#3d?qmU6UlR}tj)SP)s|!Fo;l z3a$X_byZ@318$>v76%`j&T6V2yR3-D(Jr!A2W51)ArVIF7H^(p%D`szZ$uU$8ux>i zq*7}eXzJ_MQ@X3QOUVgHHY(oRMTX^vw=PF!ucY-=*WXASTNp9vTYgp2!unTLJpGjS z_D21`&A8bZKJDr}32)z__0_=E-tu_oc;{2@t_z>Yp3Q>KiqD+~f!!;+@UaPT2@%St zAu`O=yl0Nxug3z@s>Q;X&PT}^OVc`_)$}i7?LU{nDp(jBOxeL9_Dl7L1!@$|mT=<|K>_@H!hE~H5bSWY z3glS2c806&Fvoh~MQe0PXl+;%oR4}ltH?Nr$8V*#FOML#Ia2&7TC%uL?6v~T#e2cE_>{Rb` z@T?|v?=AXWChRu!9f0Rh*IidFWrvpkBB)!%RVn7C6z>N8oK2_)eY%t9g*W>S7L8 z)aZ?qswwkk3!@jTeh%E)!AiKWKvGBJ_Q5w|>}PvhVDZnf~^c5w10irjZ3=V!Pi^Bp^Gq!aE$^Z##)vCl&v1P9%{``Y{jYH4T*0)JY_ z%Arc9CC|7~-?i>4KkSB|#T+izhcExRtSFgXC5HXBP+k9oFgx0Rb&3g;BgjbOWLF3A z%Q)ry^Ds!?2;6|7`$P=jtnX8DB=Pi4(aq3lT-!_k4OGabIrNGm)IcD*C?f<#vEjKM z#ndysTd+!Ox0>hI7zh8xEnPrriFtK=6+A!!p(kN3WY%2a|8XzLgtiU1e>{gwyB%yX z2h-e4^$>AYAXs88Hm@LAMF=QzpHGTbCa8RU?bYl3Zio?NTIJ1#obRGWYxcEsD^(8hktnY?jgO)`hf^SggMR6Y1hMR=v^~27F(qod@_AM ze*CiDDXMP;>}7+-}l0x{V5c&BansNBis6y zsW+1ikf+3u?%-$N>2wNYQZ94jT-2v(eUE5lW@hM-dm`B}tV4q=kq&?t@0Spq;l4id zU%fp$4@*3u_Fj)?e9DK|C%pX3hs`Fq8~ZvKH7`V&>=TBZEtyQ~m?u&d@f?e_h?Ud$ zx*K93*j&beVp|SX7lOmx8uE?ItTf3duDrOaBI;1(p6(dV88m%pteGYHUy7g`;VNA= zas*lNJ#Uo8z7AX>UwD!ftvp`?(_g5o3HHg`tCdD@J|hpAu&IRpKs~jRRj&r`+#^-~ zeM;jNsFLSAYeZ?JvL+-S1!;vG0Rd3iKt?_&VqF;X-ma8B+I`Z!WG9Fy8ZW#ZfAnWR zS*bi%Lx`IgVx}GQ$1=_|ghm}uC{IXxk;Kr8>Xr`w(Pip!2ilx$UBmp`DqfT780I;Q zCWVYGe}|k#E_kx&4>%}0(3`DCNNkF$baJsy@6$peO#(9Wbpymcz0|J==mvk%M3Wgw!>o13-9wXK`Gd19s9AeZuINU|)W zFKW)Hk2(@o?uX<)L^1V%@G=Ia7O$hH>@A)ap6o+~*S77MFDNRX8R!@miPxKq{*w|F zpm`?8Ri~qA#U-5ge&r?f5cf!n3hf-QW?xh6jiDZ>*2{`bQ=TJ#Us@aFN-v!qkX<(9 zQwH6k=2;mn1*eK3`1dHRkr0#*CWMH0Qz1ku#uZktb!6X;W*rg5)T%bD3uWYJOLl8W zC(=5r%P$<atT)r7bkhx40=&gUz;n+{rU4eDJbziitWdu%bBh2#V zQ<@@U&BMMb4*&W!q+sgp^pL?aRRJZLP{2jy!lkmGFJca{$yA{Kzd^lz*gje>x>m^U z<16es>?zG$`s5i52!*`M>HC2ZTNf&Z^}5i!4{l$R@y)EWz?|q?7;OUx9gg~4cd-?k zA@|(0pJO$(#hQwfsn+?M$1S#nyk{p;q zeNZZ_oaGK8A4~o^JpXSNV7WZxupI0%AmKCIl0v=wTLKYgGSeiWwN@S}{-qs8TTtA{ zS7osEkoJ9c^6LK%3UoiU;iptNiEw73U>u8IOO6+6|Do?kyD`|#LTMkZ@#EsFMsr6u zSK|!+oET2%q7t_f=|6~{)2CvMG`{6)qA6GEM6!@x_b1ogzA7e)T|$J~>{`r@rk-Lm zpG?@<_^mz21aSM6T9NKBHsJD|IS9IYVbh{_6o-f*VbU{)5mKaa>=NO{ln7tFHI4&iPMxphjSe`7P_;(JRaxLE5*l&2VLH(8*L$?Np+ zxI2-D*Wxnt*wA`kMRP0vH@J4ktt=%^avMD5$st629=C67Cwb0iO*-_E%e>eV<*E^4oU}GnRI7&~ zttklV$Qg&n#W>VxZu%Jy?Hf5=#`r8I`o~yPKZ@%G1Z`Sp4{t#GZxaqL+G@bvhUOSS zFW^lp53wa!uKvf~Y7jH;{e;N2 znLG=GK~|a=xHO&Gz&rd^Ivyv5No!nUW4NMt*|$uP6*`Eai&!x6Ob z#R~_O{5mtM^GEBW&-8QU*YlW9Kz8@Diw;oqA!cQTl5MOif)P~0@ zpfM)RKq2v%VLqV2-4UZaX-9=zKV!$1>_~@;wRFJdYnfa`NOo8uHZ;Yr*Vcc}L8RrU z+wO3j^NtpJ;?Zh>;fD_<@dGD>FqE|yFx8Mu=5nMAGx{fHV#Xur(?7I^}<-+-$li^MaPWH>7kJs zaF4k^1ssUY0!MMsP(uFZ`CiKE(@GteIUYDtyJ7?}H z1V=!s_Cg`Zz5e3v!;XS!f;8;CeXGWLw^Qo;s=9YJOE~H) zu8$I-xs!#=Jg@%VuXal(^U`J#QdgcAO&Kft*F-WnTCvq=O{ad$?_xs!?>_us(eqlA z?F~DPI-dRu^O6BYO~FUMln=QblWOwWz12%_NQtn-jCZzU>F(4BOFITtEw-D9XP%_k zv^NE>ukW6E{MGlK%V=r2yOoUmyQ7+OXjQ^w8!lONRei^FNMz;yA=&Pc+w4g1hGw@q(CRqT}htM@N0T{6$fdKCcm~Z4pZMnt? z_F2^?s!Tx3QjMFHCChr9T`R^$U1tRL_SVVx%s0tSO`AKkG0n}Zfe)%>PQ^2pEb!@k zpDcr7Jr+IV^F|LKY^c@XV^t@lr<0qIcEsj~lPk+=yht&aCNxd*e>u$Tjy=}O?1uF}3W+4T?T>dbLQ$YBF^mDg6A5CV zpHvOg;V5sy*t5S&#iun;POkMYn}Ln^26Q0CUR%QSVY*uH-Aap8c7j%lmf;$4kAvnr zt&2}&kIxJ4M6M18Cv;(7qe2^y9|y!T;D}E^7S{gC*p8ijx0zW__l7dfkHco(mdm^% zqgRi|*ZmU_R-1u?)i?46B`!e+I`gFSzZgNU8H`8{zEHKq(Ee`14=4Z6{hcmHZdLF2#(k{s`yW3n46)KB-X2p5cq)vHOJ|>#rZtZVG-Pww#aqYyan(>>h7=U@Q)ukRkhXtHTmh8WSP(JNh;HLNau!v;@MD=~x}Ql* zN9U=Z8?Q9Zdaq}=uWxZxuP1k}cV}H^-DWz@89hy^AKI03^hQ;%!MhIV!UBdy#HH&m zh8;i7-b?~Fma*5J{N$^oOHMIIRFXeqU%l}Ydn)We4Ogy7+!_9W+?31#ZQeW{^46aL zK|_#ziPm1Lq7&`TJi=gY>pKQFd5k#Q(Ls%oBE5pkDQyl~Gk!iiFkQFC-%B z#Op9gBSRvwdo@djn9!<&mOsOO`7nC``ftaZM{V{z8CfV$3*}c;k~X_bb|f&`djZVl zS)gK!g}9#7REcs@t^|)Q?9v`<-_H*>Lk+47XRQO5q8c)aSgKpAro4;GD+)H?6TBonq-+J%84n`@v z%JQc4*oxh8((T!kbI<(AFB3|HGFT|7yh}~GJ3F8KODw=$5lm96GXt`~TJ$RZMBAY~ z%ER54`nO5S^1j9)+`i6lJs!b-Kvu>?^H@6_((=N!ar+C^!= zrUSQmEQk$VvyJK7c7etb7$HGm1iH~*O@5n&daFm$tPD=?%R$%i8Stl8lOW+BQDvB6?LA|0v2mkx@qMvQD znl^q!tPoay(ZA7&?Y=$?v6PGAY(tZj({Ecb256D1&rmg|U2Z z0gQpXBRox&%l8o3$Lc`iD3fj_+b?1N+H|0hQL>zFo%>k=Iu`cIvsTUV&Gir7XmiOc z`rC6K&e+6Xwa%xr{&8P_&0#Z(k5zH1*a(rp%Bn)DLh3^S=SOnd3X03l)?wGV%&del zO+l6;m$&CkwYw+nCtE81`~<_kI(C(GSwUV$G85{P3nuVBQYRb$j^^V>PNLESAH^n> z7TU50?9p^>+OV?V9AIAyu6{oU*U$C1-g%pW88`RmiU)zmB>Q4DPQ?FhOw?!w+TMt` z|I`RNS||XD4EsNILa5t7{;_V8u6&jiq~TMma>gL{Wp5V`7aUCN3oKmxC|kU*HllqG z*W?#j`$s@TPi4Vi@FD83d57LqB*`*w?09!MyZLY>|02AoT%V3_9u4gDPuKNtE5z~% z(R%pcoDh7a_FEvIjfmj>w-LfQ`m19-dI|)Tf8N|MWI_VT9DgJ-PuT!xShlCOKEumG zEnWB_Ce`O1CW1OkU*6k~GKL}@2PemrZmj*BlU)+}{Hfb$E&R67$fjy4rTU=`MEq;S zLq44Lwb!5Z?`?ZORTL*329m?<1XW%YPFUpA6B$_?w4r8T;TQ=9tp z6db9@RLea!zugFpOTfCvy(e-)^mXvO@{8;&2IlvX8%3i`O`CJ2T^nE`)c~{|dROA5 z_n-GY3yO#Z$*{2`*24!bYeJT64)%#GM^X=R&TQ2NW7nq!bDnjrIe0{BbKiQ^kJ-2_ zcBcPE&D054YV3iC=l<}+U9#z=#r-K~Zfe(8SR1CTW*lKwY_M|U(l11F$o!RYH>_2JuFX7`-{kw2%S@aN%mrl^5-wuSBP zjyU_H)0fYZnSOo8>HK`*vs`l--Kt>)?jj^Nk7X!zsiEnfbLgEB5`k}|b3ABl^5Y@l zE!Dl&w}WM~{5@L_=LDWHhGTxNxvQ|rMB_;NV(*<;1sNzFOLv}}3LL=szT%NJgZH*j z`q4%*oL0L{!Mq-oBIL89ZxiVAULM#$qnaq;(mZ*?qth8O-;-@?ZO}$^V4!+04ZVpy zH(;kJXJrp4ji_@j#lo~z2&Sc6G~VdI+MctjVjLPnj>4}vCh2%}4oiq2rv9R@{VdLq z3&u^te4y#`$|InPLNi$?I#yTi6rEJDL(BucOaK zzwd8Xeeq)^QR2c_iG~wCpIuUGcd5DfF8@^=ZE>JFV3~07L$5wd=iclhU#0jpWUV~H z8^qH0%AW*iKxa*Vtg=Q;Mykvw8mZ^=t^>x?#Y5DB<1;X)n`mzzDW2uWfmT8JVzr@R z$h$3cDCxI~y$SnRa_3OUqw4w#fQJ^E3-x=%ULT0P+5uY7mcRiOzIaFT*-}tnK!I3% z>1DY~@eocmANPn))vovR-Yvp(pnlSuLmr}wF9`Y8_Sfa^R_#Ok{|KtA$XmBcWGm$T zpkfnEQa|59ihaa0POwSodCq%Zv+%@kSi$l;_d`|rGXCkf5GwONL;mcYyG*Z?L;&cZ z;VOOdp>F8lINe|t(JrM81a2M9w7tu7{o+x2X*D!B()?j$q~7sK$f>c&u2cNCTq5M$ zb9;m`Xm*P8?zCD1q)wkm+r1sP{8v<_U-&fb1SOUT#5mcQgg0Wq2jz#aC63*~FtgzX z!LSWw58E}aHE4tmOR0oe#Lz3%8}Xc-1nk!5h_2izS9HDy852#K5%H$nt%w;lt%6WEuj&-GwFf3SR&~A3_Nug4`+eNVl%KxpBUVAx}NFkg@V@{Ex zm6H{)$_eKPcSDLL{w1!qwN+#lRC98|yhpv&oitRouk~*3N5mKSfP3BdX|SEZYu;pr z^uz&7mRz2^=gt~+2a`pUYRS83>j6=cv&Sq{L$@$m1Fq_zmm5UsmNX_GGO086fEq$2 z!o^+o*J*1+ogLy;2P>Ino`~8xoi%zC1VlWUoS_d_XGhJYq*BukBX2;ZFtN0*(_r7L z_`LjOmqx?6^knJoI1Yh?L+@9S6_3@ox4(5}9ZL~EBLqC4fVkIhxBV6~Y%j`+%4fak zvN8*y>D73>0TmJ{)pjRBPe&>^MfO$69#2Q3Z?;hz=GzhV7TkD5vWUFof7yMLC2&^+ zOKrxuHZU%HFy0Pq2U6$cs}mm{ZnHl(YIon!%g&+PE(>GEpiQ_6G-k#8Gfo2QRZHP6 zajVVKHaXN@f5>!ZJ^pjy^TF;)=B$`px&~8Ac)YsKw>5P>#2lnc=XC2 z8xk#E2jM)iKMvJA@!B-qqG7vTyQvC)jy+2E2`d!OeLFVt2q^Ob!&TZtj^$%wy_G5t zI%=#EET>5;MS5Twq)^YFN%RTpj?2$i*0HEiO7Ig^8sB-t<3KTNp#BV5l6XM>i+2ec z8h`=KN!85}GU0Ai0(hlns{PNQ!Qc@VsWN^v%hU-z2y=#91CQ? z6Aq8U_f(9GQ8a8xEUS%{?fk$1a<8Jolw*zLMc$?OSRa!J-3<`)myqGjQ}&M{rZ5)s zsdiK#_)Q|;$}w%n`3~KP&xpC4&yV}qES$>UVSgOSU6kOF=A!+|my|WC2ET2) zc-DVvE>>$@B&&a;xGzMBO4nzzWX~D;pw`YMg&9JlC^)%s{1<^ASYvqag0>p*oZlY8 zDR}6|P{PqWQ2-=JM=*nrKWGPIc+$=YI@AX7)bI!Hw><~!o#q=6cn6%ODMb*PaxqJb z!g~o-!x?yZ%Vkh+lOtx`7f%CSaBs=}Gnz8yNXV|M>v(}FTvRXJhjPkwX7vsH32bwn zJs?*9S)$hamuiF$a!ZK0@vssbX`7-b+24GW(9WjO zy~Was51A|TLj7$5?GyEe2u(CEoE11KV_`?gRQ?}^_Vg`{PfxPk#48dHOA1ROp5LtD zeUYTl^!bY?(6;8hUGDPEJG^xTyx#`$CT$()@(;6wjoAj0!W+o_)>rZmIuE|5BTc3w zI#3!3GeQuqIK>Bb_R!(iNnkbGsR3y;Lu z+TatH&J6P-e_Zu@2*^S7Ljg6&)JJ;MgOw76&0-n0Rh`(?GPT10%+)KL3dO*a6 zTo|Ztn`EXSQi1*n;pBZ^Otk;C0eHb2)+H7t6B~QQmpW3Z;{1GZPUI#!={T< zM!^zNp68Tx)>Y2wArRRUkS!?1UH zN||Qi{;-lzeOB*1y>~(3uBxmW6w9`+1DZqszVaU4)o9?fqteRyZunz}K$W>#k7d?y zti2;_sKh0VpWiHg$VSDymyZE!;dzTV-(emL4SEJ%L=cKMp(3o7ta?ZE>UQm4dWzVTbVd3uC)1xTDSmL zyC4Cv(zneXYmh$@`*B<45q0<)pDRPukcvNvS~U08F2gV_mMi8$&v3a;lNqpnB|qrRK@q%@1naH>f%ph?pM57bIY& z%tdu#SjYvm{GGp5Fk`KPS%4uGiUc$DhOw5;g4X*PnOAVNfQHn_kL~DzPS@}63%6NT zcs4YM9;v8v3(Ms2p3@jKB)MrscpJByrHkPRk^%?bLT4a_z0x&*bkkWypdL;3ds!cV zJ2&vG!or(CsXs0YdBKmz839M8(vDc7LxxStsW;diF2{?J4M1Zf1Q~M^4t6S+PJR1gkP<&x7xUKk zWu{t5YJ8Bi-%oTksp6!=UgAL=?7l}suAY|$$#ufvt%UG0(sF}J)T04|){*>1YYQS# z)fccYW=68}tM)7n!hhX;$xxpI$attIzr613MiSVB(CaL@%5n7c%D;AWx(guFa4Bj{ znC&LfTy?9WYOK%QShh52%^qR&+-xhS(bTq-ICONd<7U!6xXljHdGsHn-)c>MQmdb;iy+ zX)KURIHZrU=!Y!Bs`ZB5w;kg^P(-Z1+~4e7@A-*|g91xpXgw}9@d03twQ5W(=o36k zHudcgfFIvh(UnvhQW0C+=T5zs#~SIO!gRUOlBh|JPX9xKSFsg)V~d3Z^%2=R2GhuB z7eQ$OWMfF0SkOT~=pQ1@F)u^7+GbS49Nn?a3A^?6d)o}krm1T18nGD%f+gqM-Pr>u zp6IJ}X9b^6#@zF}!KiGZ82bmyqWc@Q3hn=r0={IXYoK`I*bf9iyD2zL8{#`n!2Lwh z|Bpk{*0b6MW6o9)5=jM$5Kze+__`zY1@ZdWugT;TaxUqkqlDIEUr=(z*5;Na=8>73 z&$Bn!72Qwj%yQzVVgGMuhUn)P+_qj?t8DU$xT_i{%>xik4)OOgbbM8%?@h!W87eev zJoQoa0sWjviJ(r%5xo>ATt4q=g4C_5YinOux-b+NLLAGNT2{=Nl==ifMGqv;nY!(! zHdHrkrdn*Wbg&CBJ9W%r-kxS84{{Cfv(aiqS19I#4CX!dLYvEF6(r_0Fo$EGebP^+ zyW`Nh=6L8vf;>Z^CFi4MjXh%p^M87Uk?{Sq)oY0X-`=UjqVGIQ%Hr&tcEsNMp7?4^#*b^j*e|`s-kn#Nj*Ybm|ug{U?V{SihPTm)Cu6BIib|8jw)Ek>NwBd>4% z!Vc$4s>LG@A*#h;zhtu=FomabYktNPYbogwc4nR$wVT`%zH zdh zccO1QY&`}%exJ6jJ}N6F812}~(hv{K751&Y*0f*DIWW7{Sy&sqT}$@~EJZXQdR`96 zdaty>9Y++Kc`np9&YF1UcvXzk$~J|XOgaBg z9PLu8u~Wbdt^}c0()(W=V|LQgtt`(B&;ZXKU$nO)thWRCt(Q=1yqPyS@Zl7#9m(_U zwCKX}V~A1i%FEc)p5Vm5qsYg;wCp8uQmD`vP41L(3bIG1ZbRp&B8$sn*1Hz5_(PYi zrYoHke(347AJh%{0~c_37sOM!O|pn3krvpvZ)utZx=XPDlOH8qd3ge^5!3*Cba|9D z@uIR=-i_)24LE6DI+yFuQtksSX#>@Pbvv&;HVMY!YJ~_juYfetv-P(&lNXgd`YEqj z%+Om2{qimN-&lio8ph}l8xohqf_|Ugt*f<1sQP|1j2;~2FZm`>Mo!rV@xsht{o12L z@1@S$t+l}cR49i97!hi5rqpk+fW$w=h+>UIfFWJZDA>C)MBSoq*iG*jZ@+~6bUguxZ_(3 zwo7Go>pvvhjdS!8vye}mktn{j?VOI{?Rk}LkWu<}HTRG5$Z?92Ju#N_WDhnmQ&o@e z-vJ-NZdIERt?(bIs`av5#?)vx#JBRXlvJc=>7oitzXiVxMZfhHWtrfO;7Z|U?9X7` zhe+k$sGlp0CfvJ#c77FMF}=eV!;874%6I&^vvCeIl5wXs1j8h@h(m0RLg9Rn2Tk2Y2=rZe72m~FWfkJG1 zVga~(rZbTznk1Bj`d;$bYp-KHYulFZz#qR}N_?O1u3GaB?Xn_|!WW?ooTJ3?)*~cD z77sa$TppbReUB*odHvZZ{Tm3C1E2tueUf(F*U5o}yHFP+AZ$Budin(#O9mb2DU$G? z6LmUPA{!uwOb`m3R55iH6 z0uyxBUSd9yZi`rxkc=IDQbmbDj?=QQn&N>9>&B29LJD+rDY&1nlT29-C#Kn2>3K!o z`1vrvEC{)ROcYk+8Lh-Bm#}Y2U#6Kv3iC42lCUXEq|SVkXK#E@CTjOGyfZfMEt0rG zLn&h0TU7YQhJUmfvEX~C(m1Nut)Jn2r;L`tJF58gDO9lK&idN>^(`7X&|0(DW>371 zpZr!Y$ynOeDRk~OvFv2cE48zY8OjX8}#2Z7`mhIP_F7q$CS81@-ne1 zr{}=tzF8k4;LWWSpVLXzY-fE4uscF|vE2mOh7%TlvRYov85{We|DvfAD z-K7*bb3a{4Rn1dHe@R@}_&C>iIQpVm0sc_K7AyO*X3WeNAt}!se`j zmD!!2pf_LN(g9a~SH*~DUl$f@BvvhfmsYd~iu;nIaN(9m*QIN4uDf0@(w>U<^4wam z+YmftPc*z{?2eWT1xk96G`5uv^_tJ08|lKZveUx(`(RXE=&+n7LQ?DDDgzmj5W`W!X4c+^sV4UaNutB!KPKkc8p|wJ9Z;9U(`MWH zvNE|xhvOb`;Xm=1Zs~>y9+SSm?1H!N=@B>x@g5nuyB^f|@UW{jgONT2_O}4HDKSX6 zxXnritoH9SrI2yO!_V1%E(q`QL!#}RO+AUEp}3cS5nkFxspUJ2{j@`QZYTzC1|YXr z4iJM8zQC3{O~*RNbd?{TI^@>@j;-_FZCv{iP6MWZC|J?!!RLKtYmEepnO$fVR=$$1 z?@S6bhtiX-l3uD{(_e7@b$3Dn>G17BtZ8Dz$ZJNM5B<3NtCRCVW7`w)T-Kcj<3s<1Q}WJY+>vP5`Ir3i2J%1&0NM9)qMqhV zXK7HvWA9I2^r{kKSotwIz|J0n+;x9kBZIVkmZVToIf9Fb`U!X;p2&DmSZb$*O|O%?_I zl+f|%M>0QTH=(NAqD4Yn;27qWLR28`TK2t~Q6EQZ=c_QK>d`*K5AJ8LYToRBn^Bx% z$oREB9+o5+zcuQi457j}nMz}1jrSavVGufx$pUB5h4%v)_Y<#&`x!i7ua-0X;G4wK zi^l^kvCjyeSKE;>U`|oglI+>`1SkCd(umOmce16?LUq52%&nMVO{9>zn0R5+KF8Xq zDp>vfzH8t%tNJRcR&7=xFugccDOpErRYha1Q`73K*w^5%VqgS0D#dG^4A==VkdT)Y zlJdQs`J2PH2i=eP%F7rpQ!{(|ZcX_N*z`ZA^AAztkW8SMJTsx&K!JTCS;cw@bvq|( zrGq3d@2nRBF} z0%DLhm#5EseJIrzYw!z9A_Y`%qnP*n0!riHM$?;_NV(3zZED^3#_X+!&GlC?i2amp zei_!0zeVW^8?zXHGzx1nWRd^;k=lsghyv$@KIIJ378(+r0{}CH1-|IDVn%rP4l8O0qBJ`_o+&p+wUAfM9Xjghf{iHY|g*?O@2s}r>=kSm2?|u zjcf%a_2l1Xp54IWH_E>X>L^Q;6-JDyM(TU`dEU4d(iJ4#33!TJ<#F>OjHd!Dr__Z) zJs+j8+Xdj(3{PEf)*cWYg-H2-#c|e>45y1q7~n!M-N?sQSMriVxiF84lh6@`q8n~Rg(H(brJ-UY z%74ywEl&Ils|QU61Cw2nKU$@$f<4t#AYeH1t7D$IGM|G$F&XR~_?eKRN!F9OZ-2#La-IP###E(CI?OcqEO95OMrZ+-%!Y&Jitf(q%U6!O)$57?kk^;CPh6;ZOKPUV2j6fmU=JrJG%_2pXMG+b z;w~O~qpeH~6^)ljms)n6lGREx!cxwZQx5u~@|-|Q&ahg&Y8l^v{SXz5459gI*qa=Q zt{gVP&&I+`(ja%5)RdMIrRsLQS$CN?ZXUOrbYqIb=c6h(Ba@d|kUq92( zIrgnd(ehyTL~m%LauyhjeR${*P`*{x8Nuf&G{!@oQ#McoRMry}iFba@8ti&(zIB~B z6x81*cS|dp`QyXc(FNY}8R^m4IN6pMZ>D8=*Qb?91_$Adz^}RrL{@qps}pfdK{FOp zNaQ`r-+HuLn1$z_Ik@t$G=r~<0!05fTO#Gr^0SFrGKkqDw(?b!W|Bd)vbD3#e{9oHo&Wg#~^q*>*S7lvHZ2^p2+Vn;A4Jn|~Fex|xnH zXlWAJ*!gv(8$AHS4?PA*^damNf7M{(n^Cx$SEO3fr!eQbxZlPpTvU(Tu*!7}4h$R& zVp`e{o%}?7eDC?qj&m2+(mbhB=2Fk8AoBX7o_Ah<=l{0f{>?Y>I(Kww`L{vr{xb63 z+AC71Q#C|7^N}oADEmlK&vp7Wwx{MxxGWv#hE$jNYQt1>ukp;ud9fQXwh0?B_M|CU zQNA>FN}D z_;oSh+U<*7ZBZVObr$QE{A^j0vB&^qZE1S=ubAy$0oF7NnxzU~F#rNqO*79^aiyLI z7B!_yn@xNhySzAF^GY^XM@*TnrZc?$nQiPHz9{Z)R|Kz zIlonSNvur{VGLb46ejpvh!8d=c71>~=K6Dc=Ze^?ttUpsZk%2dH*qnBXmlp&&9-|O z!h6V~@EgeQz!7TjhX2VtrQv$aZr_>k57MyCh zM1Ttek=~+@rQ7rN%66GyDuQf|$@E_SOtF%M6foIMSSmZK09p8BOb3`e7Pf7mH@TaD z2OeT-0V(Vl=9t;mp4;hkem2^^dvdBicN9y|T?CBoXC@=7ImCQ;gN$%0gVl{>$T873 z-H>_R1X~T8{jXa4^S;VZ#@x~M7|{M?HoBp6^~fv!0)V=wY(hpt%FLh&NSLFvfRJB( z>qbA=W17pM*TCRl9J!M@VR~;7^qsZgF3NzRm_VDVh(VqE=uC;7Hh5dq)TDNo*aiB0{<^0A(SjB!gfm}|d9zgIhgXQwCwPBw!d{b8#X_3Z zz9l;Jxu4+HK;N$Sm#?8uRnJhZj5ZS9%7MC?6Qq~O+s6O)IH!s#q{8U z%S5Zs#_2u$az73zV^s9((aSPV=kGp*4eL&5Fu%U&@-A6NB_5OQphd;9deF9yakKBw zJuc(NKJ*EYrI@X4(W{sPjzL1y(d1NOTkQ==)H*r1dobgD-m-{3;z1+-C!wayMMuzz z5{117Aa~e*BU0I-cD(mbL~H`8^*{P>hhyN}SETYot)re~Zpv>u3n7Hacqf;L^eA|`HoUr=~ zoPwi|mqx95G1Q_Fm2`!D73k&TGQYq(lsICES!xh=X28 zu+3#;cl+vftbEqg)BDych6DPk)SpxJ7#$1xr( z%rrnYP&>N5>AFs!p3)jX*yHo9)PzOmvr+zts0#a8J0`Jh0c-L%iq;4yq%2}1}TjIVTHhS=7q#QGB8kx>+F{JF8Lk!;E2Eik?q!xKlgD*8NKi^kllma#3TwttePs~N z)-*;gynD&#pz_xZ!Wd?TDQVWaMzy?xka0=`n0z+^3cj1W<E(5no)&%)#2Iu;jwZmNRnXjk6PRcsh9&8k|N&<6lvmhk*~GLif|ChQ^=k9s`bW= zVLuu>4p2#N#a|)Im8{%=3tv^?kyKN#fw%4PLu4iH?Wp*7;p6tbTCj={P-lP{-|oQA zP|H57Xn!+o@Wm525uG)tdVLy+cwW9sSQ!aOmEk-yrF7x@r)z9l9jLCr`>d;+rpOLX zuLrG0+yOs3#VUw5Pp`Ra9iHZm8T^u0IL{u4(T=U)# z|K^e1OW6NM)?Y@o6)0W6Fi@blOK^AB;uI~e#VLgZDNdk3aHmKL6nBahXmN_W1$T;j zuof@wZ+h=@*ZRKqogX=Wvd+mmNzTmPvu96_L70oUSJu9Ev@JU7s?yN+lI3QIzg+E- zU$_FuxoWAAqt!LI(Fg7w;tk+_;br+y*DYK1&X%c25Fr4yP5g;}%|>VF^a~{x61#yO z<~Mp{K2I-=m~5bdx+)W{w>*;tQY?L*0j&~osc_K+-@J2o6f#nB^OQSuh+9u7b#>V_ zUbcPIh+`wrw%&+Vr-cvwUSSx}ppO>djGCrp_wNM8?rws>r5g^!^T;PjrAHp5TRH>8 z!`0G@d5CeL=w5_SHwJV2pNMDv6pN3HiW}X611{aQLtEaQ(SaCdioRii;SqNx+ueT* zL>HV!&FRz*i-^2WgJ+e*;YC2C&TZVnCc3z;VQ&J~DNDi>ffIYyr6 zk|p;YAV5`S&X+HPW(;e@l&7<-IlYanXK%#0EA>qyP3AHJHZ}4vBx9ckiX?0KqBYfX zu;~P2;f^Go+EmIast+Y$aw$MDxX+efdK>u*Er<`)i5lDC>|W>PSIS7|1P0<4KJh<> z1m=5F(2Z2gQMmgc9BL9@;^6*QSzsjXM$0OScdS<&$JRA9^x{0u818Bf+PCvR`KL+E z_6$~@&TOj%1>7>ld3j7e4@LjA$tVVvV~u$2jEL%m&Rl#XHBz-LKEb*Uvbm=wB6jN; zBDCo@yPc<7SEf{VPneT^R~1dhtcR+}#=$+hr9^9zxF2k_`_| z9(0%in-wBGX3LHQ zFo7VpCUT)Q+Ax_~sSs_Icu-VWZV(+7}Ug=Nz1we1)zj`916|G=u&|JBj3euP98WzYCU+dJ6$HSJCzgB(9%9zrO7rv7L~y_etpb*?Kh zxJ&K!oq$*!geY$7b-Tl~Bnu{F=rrMNa@G|+qlsF0X4EmW6xqwc6xCyP^i?u6Z!-16 zf}bl|aiIP#mBLrVFTGOHmUcEjz+Y3N+@+X_yNj}|mM?rq+is@iVl{7z6C?9#?7j|} zNIz>=r`us;INMoaW;t!6g-i5l67h7&#THlOVNTEeRxm9HFc-EyC_@{(Q4Bu<>k@Sx zB@@}S-aO!KNb}f^B3szHrSy>!)yJ^>y2qh4pe~hx?s<+kNl5gSAh@0Ew}t7|Uzoi} z60u`Kwj)FtUksUuVOH{?&8CI6sZXu-d-aIlZ4-BUZkpq-u^fd>_c(zk+1%gmiDmv| zvPbqdp!iN7-|wtbjPt9u`0M>r2=HErXBmo6ku3Bs=QQEMHM+yxH?Ssa{J; zAxsAxFBNbJF@TE@VCnK+Y|86Nu!;Bl=V@1|@(tb3N>8SJ- zhOYw~{B9~RnGHlnviZmrIM*Tj;w9so>j%11e~2hG1}YM7K(ffY`P!b|brjdEKX=)@ zKhl=;yK)c{tP_$0Z2V92!#w_`S(oH9CcAe}&Y8vV?MRQGyPus5g{fwh3m8~T96Xf` z3o`WfY(B>*vGVlgL zVO2I#dq9&hv@Rt8Ht}!m_>DByKz8_jmzCXxBH^Q9Z}5(|p4rG`nrk&kgLuicT51yW zV?*OXfM4aNrfnNd)4MJ0Wr?3}3VNyWZN^JLjA&+ijNgAsp`qxjsPVSoZ7pDt*C@h> z`bvZ-p7I*BEWYZmi!L~9-Cy(89qF4LWK2XZ^As?b`y&zMU(xf$Z#bB9d-WUdr^tXheNtOz<3n<8< zNvb6~MQM`JJeY*kNsu|_)!)B0c%@7Z|EC3Ltd$U=DPeQ;Ow?LY4qm-to;uPI;t*LIy4Iz_^$DVfWNij0S#m0^!_|CR9RLb#xTr>_r0}*b_@EQ zhGDKgLGQ0X2Z!cwfj3hWtaMvOxWi3=5|S7*GM%jO>HTE<&?zxmcYxAM$9z&^Y%!AJ zbmhEoq5VYNZ#-A^Jli6Mwm6NUh~-FjVwDmhd!#-7IT$sKN?{{5A7PByWD!Ng=vAsX zAZla_5jcfi+n*VFACbactDf*t0L&Cz6@jj=8W!WJ|NdCOz%S$k%3Udb-|6s?Syf$Z znRaHbsKV{l=uKrb@NHpGrt0jz9FKTKS^e`*XK#8~Ry#FlwuPr}iWCFBM;qZe{(?77 z@NE*(7s}Zs-k0}cYzNlPwaXbOX7f(x+3^Z(u;Zod{)}?S6~8?*tiwiwfz!Fht4top zOVY&u-CUc|GIJ??Tdi@6;lo?YkYaj5QXnf1RK~cW-!@~ZxjMIQzV>v~Vu_*koT8)5uV8U5Nr|z@^ z3w6rv)fR9=aIdNImQcjB^B|*lT2X@-%Z|}>`dgG&dsnUZsRwbsAVD%d5Q~HcrYW-h~4>7||@CbK3 z?P{DmW9sLdsx8aq%o&ZtYLtPWgAFWd{_jHnj^hQ34_{q`C-y=l zV3*e}KV7M>RmBm(_9gyE&$WteC=@3k@j98m1uUixdd+?z@rJQ~_`D!WWTuqp~0)^x?UHnW;gGYkTnxDiixyKs)TeFR0>$_DF1%Sd#!WPD8~@a>kw z#v?l2*KU*WM=M!a7+!-B@zYZ*)#2rii|hE`>VVc2?2|ptXnf@P7xStYNN<=sj-f$T zxE&qv-m6s`mp`?2w_K(MTI{ourrm1}lX-w$=^Ox!&^YqyxNc$zLBA#7Livl=;+wOw zW;dDF462qepRd?xi=4`QRvB_6jx$6>Wcd`zIZAA$nsMK+ki2xiOuZ(_`NEFT)ehB# z8U-`FtU^}Nu#$`Xd=_d1A&m{`0xyaMM{}4bJKODHd}`YgAJErMtaeE)!qrI!3JXk^ zxm-jXIHzZ`fR|}2(iWKEIJ;SN;DHyEr3SZ-meO%lC(To|7XQB0Z2Lac9DyG2pYUclGVUyNjl}m|v<&f{KEmc6 zVd#9oQVDB9RUv=_Nae4KMl3&XOn;k~zA|Xb=a$9o%`p9Yt(ZWf@XW@lG8ArIV;hA` zn-tOd32vBUx~R`fC2R-ZDMwazm?RJ;5W!DEXVTIbPIqINa_H-giY9~>YPD_ARF%Zd zXPLy>m*@P``=&L{0l#A^o0)(==D#LhZ&9f92Y25B$kPF*a*Ulzmbh*q_#Tpv=$N>f zi@V`K;U7RSi%?{Mx&tHmxPEq>ju|X zot|kjpW!DB$8$X1>rSnyt(t6M6YId2A@5t9<7MER>%fQpR5@C^#z5~H!TItJDqihf z)BK$$N>xHwe=kOK-6xNJac3@av8!BwNXGWR?0=lh*C?Va5fRI3T5wUcw4uml3tcg-N|t2Y&pX zRaTt)X1P+@*{xa*mV@3IdGpQEF0uOh82@Zrt<#n|Nscb2aeYam^ao4e95heKNj?7W zQmXV_Odqeq;aCJa;+B%@{_!Puo4-18=dN_6_~l;Bh$86f{x z`i%f&NDp*?g?8Xvk(?U3JmNzf4SsPCuNZ20B3n+_pk9MekJGl7y{eNK1sd8IXn6G^VUj0^@8w{Q4S0E-?TJ{*?&N{DEMC*7%M1viDa+ zcI#Ab;Inylh0!W6T~|Pz=&-q73-L<(#eH+tKNBAdcnfY-eis-<=tYtRI&8x4w5HHjtLqVyNuc_s@b?Ietgk$fZ zR6w?8XP8wu;?vRwcj|KhZu-hO@P~@UfQ*5I&@`4f)8t>kS$?%|-^xYpJM8h@H8;5d z@6;5;>`0XCI@W6I=+olzJY;nPsjyGvjT>bHVdG!<{BlI2UDXv2taQ37a=tt16~GrFjj#?OxO#$2kfrSMg$!6ZR-AKMPr(b5N*?u z+~Y+Y)zR|EYI%0{D|ue<*wFt^i1TJ0>z6gAtq+_#c0Ip4^Zzs9QZu#VVuZ+me-qKv zX!%rXDd@`#gNuN{)~wnryxx76@&u-A1uq=Y^Dkc*#!izvzD^VlTSlQ>3M(pV=o)P3 zBulL2QpSON)KJBF6*f}4G02VNZ0lxiZa0oJG#N+0+?@BNZD}K;d$;NXsZHQY^Z~|@ z!aRcnP8>Tb^r@q-cXcahTkhIUv@yWo8BbUZM6Yrt>05S=uOSFLU9ciOQ#iVotc`s1ICBR=l z@IBl}y+ETAI_1nT<)k_4s_Z#mP$lb5L086CX+QR$5~a zAf%h$l^zzYEPn}^z8h=xeCM!&oehG~c)R{=C3_y*-p-b4IC?w(u5oEQs}`)jmOO@d z6#9Y`r?0~7gO4$+3AcukdF-Q(GLiY!->TLTSj zK>AYzP?O|6>-m?XfH;&`U7^T!yIM_u0mdn}IKmT z4$?lynfShCyFmM@ao)Mxua;rmRq79Gsd5%p@wAGE8dy>g&O!0xwGWGacSp+|-@Wg` z^ZIY{aAo8uI&I=gR1R}wWz#lc`TWlJ09n->DPX{B`w}+&zPRH0_2h=f*Ig4;1n?&>j%*Q|4>d8re zesg%g!(4gR%?ka7^H)>0#C7$@`81^wGiKU|M+DRpV8qCaPB6=lx9LMWP{(RZOcbfNKajE?!+;iSuD3E zEVGv)r0}AWArP9u%OouLD(3mDKVWZ;r*BLI1N3*+a`yhzh#}4eRV7DY>4T1k4Qp-s zekkbg7&Iv7h;#POL%SU0P%q5YG+(9?Q(A2E4j z>gR@E1-P9NP2A%&HjW*Zy4jo`EQPTL*=?lmH42Oyd^#EcfBq=x=6)C7rdG<^!le{c z8+XG3lN2wA(t+&1^l}sf==hK^l`;3-1R4r690}LnvlTFjO7xvX4)_HF&5U_Ej)c@! zFF+B6pb~1_ED){d`B+fpVqutaAt5?2NuRF)<_2BZVKU zkj6S+M+pkzo49{8yFB8)vG4iHDiBhd0g~UeC)S#^X5i2QQVTH0Cbk(Z9HQpE)B=Oe7>J2h2q*eUASQadp1tcI$dFFt*+a2$j3Jh7{;p-r6c~KEV&jD zmd7s9daMKJL>>YJhUG*g(1zEhh3{!cm=`g~m5hJVtYfod7zp?d6`AOkW-5u3AyZme zop(_lSvcUkMd)&1bl>A34RJL=zYu^ZoN zc8;G@cbcZBd$AUBRu1iic|5njIy+TcI2jif4O041KDyg`+DSi$;gtbz@pJk4DgOCT zD1OYZeva}1m*1kw<4F2efSqlRr_clm4V~Q$(@l#cG52V*yl?7A|1M{Wt?55Z*X-LsF_r>2Hx$LdIBZ!}sRH@_6tpV{f31kd9A*}YW zmoa@&zMcRn zo^hU{Yyn^gVsWIF1q_u!H>H;K(VYo!Aw)7~Tl+r2wKvNkEO>ab#5$ z_I#b2b-3W($g?-9fEGAIDRt|gqKza;cHd^h4iis!XEdlRuV-t9Mu)$J5~U_hnr&0#4-RX`TftxH3}`)uY(AQ^{Ac@_ zthT<>h)V!5$nHGz7gpZM+L_fo?$x?CtnPf9r)4PI|W%Ym&+JN{|Gl^jEWQqUzdE%_3%wi;uJ;^SoE zhNuc;X=ATodi~qvt<1ec{9RD$)^&jGWl$zi-jolZJG08;fWQs zq7;YNhJJ2#`o`}WRdjKMK!4K&8dv*j!(2KqSSt=<2}>y0-n>GNK#8VX%z7(f;}?6p z1iGa%zD#%zN_woIO_#zVaI~C)wSKz+@S_c1oR|!2+6$RJ+oOEQkholaY$c|4b|qJc z9PXvSJ-`_ix=bO&cU04)5r6-|ar^>cVHwIjJ6}rZF47Zd$%EWLLF#|Q!X?+m+=GKf z1PV8XGQyI5P?N2N3EVNYW<1UMjYr9;--S{Ze2A+hW+z$osEJ+Y;5Gq-X_WV+ynFK5VWcKyqm?UkdDg! zD|k=jo_QE;X!Zs7-tWZ1d8u~y3xe%@8~MCy4M0g6YX5$_H+H9kB1EW7K2-N}!dtyd zSW`5oT(T?_q$g)7!~w3MIAIwa&jp{R__Do6v~@rB2-QsY2j;DmnYRu}-ZABBStUxk4S0U7*DBXIZAXeP(#wt$?%-A9r@QBQA#nkEr4FY!@ zV%S$E$e)fuNPhR*>92_$pU=`&{LLGVrfw-8j%bYDckK2yt_R*TuFH>`4Lv>HFM^-x zKOa0_#*T|=7w|i~3WWoNAgWt_fcRku?F8lCjjmMMh#2`)4$I(J7h9E-$?ag*b?e{r zKf^YA<2i?cTl*uIKV;5cg?hT1+a9SF@^E$$63d<G8+~a2AYri1sJeTYYEAl>C zr~yrZiI=a-PKQx{ye%?T-{&Yw_D?8C)}Ko0JHTHQd0C~CuCJTTxG!)vi}_mmV*XKZtm`8n=m3SMimK@MbuXbz#hZsw>C_?S2r(e#Z>m zI1`J^NzexT_4KzJ9)x^Z0>%)oh?e53Jj5a3=GyGd(S+;IAmbjtVG|S~)Y3+jJ>otk zd`2%;G+L=&M8z)4g_pE4z-qbEr0~GO!Y+&Mwb&8=_V%ha=lF3~u{Gx{Y1TE|HuY*+ z_LPwtlcUZS?bQss8`6~}v1rdov z=FxLs_E$FP%I`@8@z_ZikI-U>q|t4t-&uQ5R}`EFoZTHF^^cry^Yk(!_OLw#YFlc<5JpIQW-I>S!a;Oy|RCtGuwUL zn0T{wKevz-i4}Ke+~oXW+z(tr#g&&KFQOF2#l)nB^+y6$9&cnkKWa^4@=t|u{d}Y) z(yk)eVzB-=`00}9%S}TYpZ)G3B4y}@GHpUGN)2uT?^)SvX* zYEYrDQk{Tp55IXoSI_`!O{mlrhP9AvB%O~!#bFN!!yYb(!0k5(~R2#0E z;a|UXOXb(7(70)MqvYjZ$4=SloaV|1sR34h67BnfShncRBWORM^>Bw0hE{{Dzl|#J zJ4~Je5q>CO3WhQT5mLd* zlqS3zdrMpf@TD&F6F;rY43SF1k&%E;Ms7yD9dhfrjDTAC-n(4A3+Is;^d0#x1)pk( zS>#V$r%IA{*u@K(b%~Ob=q=b8)S?6hf-7$U$+&6&7UE*=({TzkDHaMFxuMX6vY&nN z%qm|MMbPg(Et65-q1yu0V2)j}fQca?i8s}&;Qlh97e}d#ABKHAnmy8niR1G4n@rqd zBak)(gsyyRmVLa||BJduO;8e@*Lv&mWH{k_!PuzU$k&o*JFTt_C*0n|6V?rfQL|KzP;c<>=`>VQH0i08IimJ55GfKxM4A*R6(pdB z{zhyQ5ww;MoekBf(^Baw1uG&CCD()eFD* zPc;EwVTOBckcF0BsH1!5MMtFlL$&5#WLV^GGMi3~lx1V&7uZ8sh&yADp>^r%4kUf) z3Iu&_;oYTQcI&$Bat*nMc;Qcf?1I~G2@OviEuY}DfT*jitUTF zl0OMihy+0nU^Se1LWYd%g$p6pEs_lL2U3hiR23CR&mT~-5@`k6Uwh+6qU*sQbItRV z(YEbmj{}UoP>exXA46q=f5z=P9>|kO@*9P}ayQpR42XF*f>VJv0%LkHG* zkoVyDa`mq{=YSIWo~0ajMZ&&s+hY%L(ImWUq$?qM&qkwp@A)`SFK2&X;Ob7I$o?R( zFvedx@Y?yH?=nTSS{P3~WxO*8X|6O>R#iOV(uY@&1z{ ztDME>SBMVulf|4bh-Zs4)EdO&mfsz0t0ov`T!976I?E&n;jy*@ykJH0?i+5dJN@+m zDdev*ToVX7xb$OU*Bd$dIaa)#uQhYSA?qc~i*QKxLf6>JU?Zn2%L$ODPC5H76bG4z#iafM0Au#nqxXIk@UM+U zbzUs~;r2jzIuUHuO_xIDe^p0UlMk1^{%E({;OuJLRw)0{kX>OX`R^SMrRw`NM5<%O zn8&`myZI{h3J#&$60{U?o=1j1y%#|gN2^qP47uKM3LO5O#(O%Mr@nf2#`yk!we;^? zwR{Vcwl2W48lyVk5HJI{+_o-gm(vS)$)TcF7iTr|DnWzpU~CFKZU&uHqSyCammP#% zZ`A?j48IngziC(y**o}22SVoNh@ALZ_>5-G@DV{SZmRI9YyX{yakRyJVpybO1x>}{ zBdw?0kQKxUkQJjAqL*3rQLM#U5hn^*%kKgVV~nB+extjQ~l6%Z$j0(}LZ){P0*?pLc8wDW0}!JEC{!IplqJFMoSPAN(HKZ8ts8 z6YZ1Fenqg0iH~_jdB{_II5vRE7B5LV*>yGtR(9=g!h$E2%(Q8 zH-UeAVB%}1+llJpF0Ev-^Fzz2Iit?auNruw1F=I}vH5wG%~7)1+yJD+d{`EOVxec$ zFpnsu9Dd;Fj^1ALx;yjTn4y2A^QY)vfFB^)U8xOo)9FD%dF1Rg0SlNIW$}j@{&bym zSs4$4-d%|LeeD>8Uwew0e7I?{ub-Az5WWRD6q2|4Opf{q7cc9q?NcvV#|R53&Z?@o zbDsMNQa0fTC{&j=w1dwScg#(xa&nm%wgu#2O_Z2xgw>-Tu*^}E4?ysFes7l7ym|9- z{Rx2+{l%9%vJojU=SS;)Y3hF8)R%YOmokH_WBbVfH{~~E^R8G2gZq7-JflWvz|tUk zvOlB1ySjs_*luDtGPk*zIAv^{=4djX#KdH|u@2~iAx=COA%+dsUFHTGI%em74l%q79a1rFZOq64< z1khN1Z0j93&a_8zASygwTq`%>JXr!X3l;W+k|{Ek33_pkzS`UVPn7>R!&5r8HO+Px zGY(qVKei_rzTd|<#W@Y=6GERDgnYBu$l!CSCeD;ZR2(KIPBgQ>5ZhUA&Jnez^T=v$ zc6M>?G#~fQf6w>d*S3DA)#6y|2P2P%sJ^OIkEGT173X1bkAH%ZA~Xp~G>Ho3JSZO2 zg&aj>Sj^Bz8(;Yi&cZ(Wup;u0FuZOgojCV78PgEs0Z@7Z^Q&k9bYYxGR9t8cHxk#6 z1!q`wk3?Z8XRc}(rt7R54%?&(P2p#b@2fCtiz87syPfLaGAV`?TLaw8Oi!q=ml*Q9 z^C6#bJ3{uXym{lZ%QuGNPxOQKP!0K}Pl!hyE=)qtWnv1DU#{xmP}bYZD+n3mvcGtT zl!1!TMe$hs^^bf-%$`8?4`~GnYAU8(b}o$XU#xUPCEi@Qk2Bg6aP_xk_cZQIp=9lgw>9~u$d?3MPyWPzJaup#Shxt-uL4l5n2;J>j!kXHV?o}@09Mb=}@$|tH?j`i-oKi&a_+G0NX=x zbjc6g1~N(G)0(AKTfa(baRx43JOUH{U^>7 z?`$zMy2+G|t|0I!EqLcp^47Xr zFqXHYnM~`wrQWIz6LG-Ad19u%*J1W)$1U}(GK(>|?lT)l|9C%J4K{gfe1+hf0{*=j zRdxC_gch%X0geb60P?`N8m4N!&smevr6Xf4NSz-X03N_G#sUT;k}X znaQKV{8nNCjo-0ZCTQKMJx*Ok4Vzp~150W5_p&uR$4@$@l1}9s&~(~eoVXc(%`)P? zQTMF)VX~`{@UMUqfAp%LV}mlPc}AlKxEUhOzu0`5P`dnLD8nkdv$H2A0NYuc#~E9G zlj-gc=?E_yPB9=86Xvgby9 zexuRbf1#sw%jIf^=A1WIbgTE*y4GhWP25|1Hm7O4&23m4$j}}v|qmoyH9K7VWXP& zo@(=G?YK^KB@Nt8d!Km=@sbYWs7iWw|9;q`P3tuhui@foDD8k_))X=JTfR-3ePwmt zs3oN+JL87~MdW$CT(}^39{8RKhin3k7ik;?o&PnI5X*x`0Y~V3WsS4zLix9>{rPQv zm2Yh&Znp535976hLdrY1#Gp?^BUs@S(ewgeOjc*u*EP{Nlv}!}O_-kM3`Lb`#7LE5 zXrk&q>x@zsMzQyUvR&1h<>jIdpE#KIf)qyI`@_dS;{u60?1KVvrLAr}E#Je3(4iO1ZzrrdPUZi}+uHVM{_6fbH2!3)o-R2EV|;^y z2LTU4!$Mz>h1#vNqXsX{{E?^JZsuf688%uVGSna(K037D_!fz7g2$kXLRbnytTkDUa5{X4d&PW4 zsZ=nD9@}FA!hFnt(DL50e{hSJ4WWC4J3F$}*>ZO9zba>tMV-ApMv= zrGVjf5*6=h)-SaAbXxeU+(AK%e^T@06# zSB3O7F~$rl&Bh#3hS%eqerBbWG$_sG6y=`sLwx9PnW%3#0uDW!D($7F2_I*XGOR3$ zP<>Pw(AUWeix{Kxd(fhR$vtF*c>Da-#mr)aam}=VI)VfVgsT@@$XnnrTJ#4}0b6BF zSTaetiC`Ocq7(NH3lb?HWk4NDE+0BzovByHm=edqiCbvf;Ku*=EPcO=G?i$3&N79| zjTg7_3mEql9#tn0$wDh~h5;)ig3pna+scWqkx&llM}>GWgJJ=a4B3sK1T48m2%xu@j2%6}63%D5r zrLZfL1X5r3vf zCK7oI#h%e;x)hzSRn`J6VDC4ZpVzXE@^@U;&HBIHCzl^*nl)skn*6F>9O~3cKJ!rT zXx|l|=s*AMf0R(TZA2UZhIV_^libPR$?jC)Am&r&j;UQ^l2Mx zRAxUi3)&>tT}`*tDG+zMa1NS7p37UfI55)Kb?KRkEKz@D)H6ByBDAj!ow+VCufo$p zr10D1Nk#@n9>IH|!PkVF_vt=7?T?Z~eI2uAQ4|LDrag&FsF!rHs>Mi`H$K+F+^FrZ zaJCh?{PjbfHqiblAvC)en>5o(Y3dskIigj`J0vsG-GQ7*GktqTJAkyFgF%E|+mJDh z!v4<(wcopHEq8~XC}d`cEgSIuIGiln!uXI4qB~WfvP=)D^8fBH!uEKlg%!=g`mOB+HasyFm7F4*tww^jSvkZA zwTc2!k6j*KuU@sxz__sejS(%*!0D|CqYCSy-=8y0Ak1){6cvE5HFN;=>NhaNc%Ngf z%FHj(AvJ-MND;S?%hb}(UnTRsjdGgYdur^|rT0RTUR=yRkpV1+_!B7F88;0?v}`-g ziF=C~N4e^p@V@4#5#ZlV8{I>{j6Nl@t2Z1f>3EW7p+vcFs5LF$ZrO;#0v@z}eHG#e zKhN!15MIGwx5MnBF4kz+`dm;?njL*o0>abPD6!4X;<>;sVQY$cx{?XSNjrLjRnVqB z1~I7Xf5B28G$&_jc_w5rgn1EI8Gdrbw-9>C7d5_o|C(&4&)HV5$3L;mhCjDswmunm zj#Wz9#C12kdhvvA@aHEoLwjinBZ8vL=h5cTt*1$IZ)9g@T9D7~)C2C)!#z+mGF{o9 z|1-=DRGE^Q)s@~HWMbGu|KuI_)EmQWnn_-h>q^!7liynBlo8Bd30Dp%xY~tR;&p*L0dD7&`=G_Dv3^eUm?u8ou z_J4DBS}*B|HQ>Dl=5+hInmfDU<`1HUFZ_6u4N;7H6LX6H>{Hm@lI<*`zxa<3qHJ3h zpYt(x&HW)z$!KominQJ@W|qC(^d7${sJ7>{Mu5(XL*grU)tG$1HWHU z{n*~?h_sF4C3ZcB`H`SW5`L& zqI7c{UEH7<5&lR{<1!x{Dgx_<_FrEBl5LW=n(TrhpGW$VKY^_KW%^6QtRk8)>^ARD z5_A*3h-v?#>IYz(@<)hSoODIp_A)ZS8cX^47L=m2Ih1OEY_Y9z`lQhGQkeKJD+I=W zOO4}~-UIj?p<04Lw8%iL-<0qvq?8$^V`_<|Z8H_2rpTVKkp8S@5=f*u-7Qj?Tl6(C%yHkJcK2v=tTnF;J~}qCqbdnxk{WBc->s zO{&paZ}QU!@?%s-Yq#+uBkN;pFHQ({pXx?V)~cSn8}u>l$apM>!4<(N)FPNYR5;XgwlW zP-0%ojDN!-h}o&X3y4m8SDnkZ4N?f3aFy&F0iQL{NC*!hL5EKcV!T8surzs2i4gk0 zk*+zpN5|+RR+pxG+xt8BMucduW*ZsyKmFi;jz~^xh1ygPFS{Q-;SC636dD)LUUrK$ z`S}kP3F3*@oaoi`5lMh*g156)1v8T9h+@^UYpW%EBQFFZX+fkGK_Dy^p(}@zA+Q4~ zejD25JXjDVPnH%NL!sb-hIGp~@HaRuJ6kA$o%K7(Zw`5HCg$IlS!m*M*rC}W>=DPQ z`{2pXh1_5Pn0Qp3O?iwvwl;?CI}OGMW`-e1I>EjWqZJ;k011Sp;$KRgV@#07D&}Cz ztfneJM7&0|%F66$SjKCD(ZZviJj#x2gI43f+GufT?h-MXIvhH%3b0=EI?Q>6G}DhY zwmRW!I&w@Ld)uk8r5)Mc+(5vgybmIZzypcDn}K~SguTl9uV!SS_jgT zS8%4#Jb@+@2o3!IVe2cSqKf){XXx%0kZysY8wBYNrE_RWk?sZ=LL`PRDd}z)U;u@o zB&944E{ms?Tkd~?A-FQ0Z3^vQQD!Z9^L}#lhD!EW zXjz;io8FU5KcLwWx{l^JX@JvQ2m9;{!u|O|Tbm}6h_<3323{^R+neW)1#}rQ_t3-z ziT?7RXmZ~mH@nI6c4)I9rM4*GB^fKanVoaPi7&tE8Vhg=!18{zaP=jfZFd97sL;FEg4G?V6o6Og6vU~|dw!7g zRB{|I)entcE=*yV_4?OqKeN&muC^QD4|MFAK|^VyeO`|*3{wiQ zqr3Wl3*1(Jg|!3=?hcYcSQ?jX)6}~MI!Q8lM}<8zSc=SKv-SWj{2bD zNto0SZCsr{*T~LqCO&KiOQvW5j}>+|@Muf$knm|O>0M}4I?R-d?@&&4B>njpi^DMP zr+?V_A*E& zMWMWKvrnXK=Ni*{L$dwGcS^Hf?Isbj4Sv0%4NnW2iskNne_X*RrqR_Gfz+G18k0dv zfvkX#h20^D2sTmHA3&I~>8Ae?bNNzVFZ(7&#}g$X4iW+X5ryXCc&pKs2uabKzM$ae z{nIxKP5Dj?6QqE#*Y5a-^ymP*hzxyU4hp8vmt+miDburUsf+m|Kflt77ID4(YQ`Hz z@ZyJlLR%INm@;YK3>q#<6^s^sVYYA5qcm3#y6@ZS>sYXFVTjeT(XiVq9;SbWv*Qiv zvfAIJOU|pLZVmN)2CV}cpRQ@=PsmmG+52p9wrPZK1;{&GzUOR7F*sNV@~;Jp79^jI z)zwQA9q?o~Yc}GahuP4d*KQRL4r+`KqAjDM59gVa`2;Tgggux5BjI$N=`+*;={9m+ z%aC|S$AIq^(SJOB*UyXj#k`{fJ<|}p;lQfE7CELZ!$18#Sk75~c|Hz3_-4Eg zliZ3#seJH+zM{XP7-j9~zHGgK4T(vrNMCvuPp@U_8+b;)FN}La6t`#Q<4YEe1@;be zH%i%-IL(~&o{waY-E>PlTmIpKv<>y?88xv^xy;E(P1}yceY#&}NXuBp96Rl@eOZaO zd!QT}I6Du)6h`jlRls>UtlpPpP15cazq5^RwCNZ1FuE~$=F1Q$%i~W6#DV$XX+Ctl=lOSY{b4W22ctwv07-QjXfPz;7 zv%X8bZ&;x5IMbNL7BH&PD^ZNq(GF&uL3P&-Ce=)O`-=33M-MK*+B;3q&*{$yM*TsB zR5JP+fv&EFr_@b*im_tq>Fd4`)A(UikRl1=JpZ-czaP%g*FWz> z8@FylqgNxs-%L;5_pnI5dF^r&Mwp@_m{^u8LZdbEQMvOIVxqI|OV8xVgCF;(21-Wv+*|quEA=x$rU<>AIFI2d=_nHkK z$36iVGR8Ja0GEo4-LEAIt0h&aX%Wf-zemBXeD$Y0LWYj?+0b^B>IjqbF2hS(o3(Y? zo*?)A7VS8&Ru?NO8|c>jJ#Xs=K?}-R?ykn}h>Da!I25sB8@MZSod-}WEV&#&C-J%# zKd6~FyZchuuWJFKMe&={$%r=|I2II5HM#;}tf1mp5>7eOUvc0$>L z1(N;oG0xMSIEUhcS#>c;UrxaZs2GzXD|RFto=!iVciX>p2djaV!qa^a0VZCB?4Agz zX_?Vd0by%1JHP57gG%n9pI9I02(AEvL|ZG?6G{O-2T?!i2yT7d1co@{SF8_k_m4fS zPls+l0Pj39kO|74n-|w|$az_^j~Gs#0cq@I@%xj#j!$`XQq*%rgBU)HM#ZEy@?{72 zc}PM(NRE@9as1F1bTiVP_g+_CmK(_%DZM26QkBD;_#Q{{4M_wARyBc>Ue?Ga_sF)? zyJ4l(_{e$80OhZ^ju&wV77Ee)*OZC|?!O9NJNsM-a`GqmUd8wLQBzASZ`Hc?3%nEPq`HP~eJ65f z?viIppBtmK5ifOhbO|zsXS^&PdSEjtMz{CMWvVAB`BB;X$Rh-`q?SP%ef$vrvewwo z6_zZz7h6l6A=No}Ds=1O6L9*wI~p7O)ZX&zio)TCY!k1O?*O`*FG*PCjA>I##aIXe zfre0ez9-_{G4ct;^|E^zo>yibypRUJQ)3~}Xr5sw(7Q}BjPBfVNcIqOOFfZV&`LuF z-(@HU6I`)`%g+IeZdcM(@JVh4OR0*q$v6dRxZ2%qdI^xl5Ot?KyotXXJ>js3iC&GiG?nM;>3NF2U9ub*8R z1=f3UnRjNHh3PoNonJ;76{tq5|J+DwDtpb*l$oA)B8oja_rWC0L#UEu?Rj_mPB}yJp&R z7Bw?oeqR>fk=lOaQXBg8B4ED? z{`iFw%Q$E{lN4eAa{e5^7@%>6kusKfmJyh8{fB^vYJB4Lm}pRr@rmrmua~^N&qiPS zaYvwGuONw@(0AVr``OhU7rA#|0{hOqSs4uPxhwE%p4m~X)DQIH8cmM6Awk+BNmG#u8P>e-LZ^F$ewY&V2BQzYSOU%^ zuzvH*fNg8`fAOCZ6W;St?s)n&#vBFxFt1o`idR0U&s-Wo@zti7BjHkF=4ea zuR@K6rf?kVe;#z&xiRdE<%wC3zVRXfEEZ8oz&Li>ej|gVPdyHn-xP4goRT}gev+Y#GW9Xl^DE_hZPj44dLQzc^L#P423O_6j(sYzz8GgH z4l_m^{CqS$_V=afQ)IZcXp?=4%hQWnqy~3`7#4I`INQ=V>~FLd^}{e~E2rdnTYvb$ z`m252&;oyyWnZV%kmV+Z1r4=1@LvjHVkJSL$nF=jp%3A$6G3@o)I3H%T7MeGix||L z6BfTmnHNroS4Zb5P|MK0%wVSaAEQUrOknNm$sGHh5XuliyGwoA_3dQ!NUT6}e5)qW zsrhNZLeH66{#Ekdq8Oz0K>Ew)% z$tyA}Y3x%WieW)r7=;Iz!cZ!RJ+DAs%Y12gJwBL?_IWOFC28+jv7rGxp{=;cKzz%F z@1#ai4Z_D=OnE>hx9OES9oqgmuPyS^N(A}hQ+ucadF}g1jU{}Mz)7JpW?uk3dj6v7 zk+Slrf((CFWFT6j13R&Hg4d8(C#qm@6Swd!pTp~%*<#FBuaB+fEu^nBLEf3pHt+3f ztDd}TUB>c1`zVq1Q$p3Jhuc`{c7QGH2f4@1 zDE=YviDRzs$M8QuX`nmpNHN+adA7jmX`q{4o zm81W>7zDx(9R5lbB2fa^DXGR?m8B!yL9ABV~LCHks!I)OGV4@gJO5 zE144Y-m*9kxQ-?Swg*p45Y15o6(cj{IP`%JD zPv8a_vsremiePjA)~>g3q3cH(eNg{G18)5dn7l8yVqTgU8V5zm%Pf z=e}DV0yP)ZsNi2h5Szr@N{{i$o_{;KkFlW?%z1bbprdkq5M5hxZe-zbHjv{jxsy7% zeA*Kk&t^J%DCJP^xw(aw7`_JyFLQQes>7@DFiu#iySrnBey%%|L((Vynf8URgDYq@ zDOeu>vw%15r}?PNBn7ZT1$~3#j(1iX4GjO+={6dZazOt=fAeJj7MN+b!%&#)QPmsafd$ zSY5zCzDi6r6LdGp+M%(d%&9~U-#XWA_AqZ-q#inty{QJ&`C0^|TVY`oq@M~B9S&^b z9Y+5l;(}rS2}{8dmM|y8&{1Zr;-z1@wz%&c_y#lMF!bIC%4GNzZteZpU1X8Jf5J*W z@#Y?!I3Rf2lhR@Anf+?h&&Q)rx2M3o&(g&u(|w;wtbhl3j9+aM!3zYJoBX2#3=f2hM96L|Zl?Iuk_zV^IA%!I9%ypxOnqI8hd zlYUa6cdkX|JT`S@6e>+6#eE!TvUf$fVeeG{PX#WK0~(CUY>T4CCIbkjJ0=5aK``)$ z@A;7tIh??ACU5#N~w zu$W@3!9dZ#_Vl6>ED}NWR_31aA91OwyMb|J(@;92J}?|YD)Z6@f*VJOMd2flJE~GP zo8W^3iUOm7*l1cscRFA~RD|W`UAxzO;S6O|U`0{kS9V&yn5gXa_XdGC# z-8KedI-R3L8b=hQRJg-b7rRlv1EIRQ;ElDP?@He0KI+T~k-5{Yks~m(OI-L{NtSdn zg+ER`d8!I7JfgAqe6jOAhaDPOf7@B`0`YnKa`!fJud%M&HtSuOWyz(se~5k=I&OJT zo2YIj7CF*Oq!XqA!HIKeEQoo7CcUQ~alFAL4TcA!JmUQ5j`1?ZLcmf>4!9lp5Pd2w zTjAqqa1D3v>UBUoQ5>KII3_otP6%M{`?>0{&tr=RYo z>^F?yz^9Z7?S6P}`61vD>vjhv&gK;Bk&VTxE3bQHVeub8g>R$Fi4i_+A|%sQI)14G6S#PmGxO1()NR zlGC)>lOHjI36s9ifS6e|xh`W$cgf-}VhUtRZ2?ujg%DZM0koC6_Ew9rL9=b? z=HW*DFRMI90~oKIB^5HLr&daE%Ef-@Vm#Pyy~Izex&~6~XeW_GU?NFDv-7a;dKfB- z07F6(E)o8bm=<>7tVxrUh_5QOR08OodLqZ{7HEMo&hCf`-WIE> z8zI_1_i9BPDFEbRPqjttO6gmv6P7S|f45KUBC14f^??TZEN;9bChaLK?wIkv8;iU) z)mCikOT6m&)OP(QYZZ?!wNUMEBN&yP& z78P6vU8tS0)faGz8z^A$-$(tRj>I^Ia<)=Oag>KK^09ZW zEJF`|n_6=vf4O37VAuqF|H;b}sr3;YO!)QDJOlB89eGj4GFUM2R(SAqEx0BW+_Ku9 z>mmQ~U`tUt|Mhc%Of2awKSC8tY%M07*~?gA2Hml zSli3?Y97enEJ&mq0Swe=vWC*4EK)oyS4n-GAXW9!`LggmT<<6f(UPhXm=bM8BGwl8 zufT{Gvd1=2j$(jN#ko2MGcEMU(}O*tDjW2AU9W;-_O8EIs?(`@=@g3zg}Klb1^eg} zq}?G;pd+t>g`1isbM?Am>L1!-4liJY zKKB6-S&@iJ!4&9z6@7fB*Y^#}Uq@d~oNmI{rQ>L7Ugl`YfRnLy`Ef5r`Gs@w&flpg zsyk_Mtyy0RE?S{@szu#7q47K_tu7p^5oi`@&!D0gv^TCb-8(-24J)GiVWOMMJLJWg zzVIVsqw|h{?9o#y?64d3_D`m8$HOV?E3B;#FwThQ!jBZwr$;>t{e54wrJdUR8`heN zcIIH7b|Dj@x8>6zGleT>4~zysO_G)2?l)_$MVmh!C=V73?^;=(UHZb06f*Nr=f*tM zX5Fxy#2`uNZ&5mkH1)|P5_+{ACeJq_=>y`RX|wqwPJib;+(azMc8ELX!5#5~nlwp4 zNf4Y86vJB!58KTzj&#yb$;CgP2uzF{2}?JySO0-s$=yj)V>n)#sb)C+ZsNKUK?83P z2zv&e`6iVuOG^T>vD15KXRuqHdd|{mdB(S6zMiCCI%YB=i8b$m$n2B@=XS0EL`vFf zQbO6V?2WVzX;@>sqJi_GaX;E>nRyttb_+E}Z?Aq6v7BISn~7XY4Y1)?lsIQjdjS9T z^^P`imCnWw^_o}_apiG+&`YnR-$oEB*7i|t3zCfX(W-SCgDvJPScqdh`mC7|`yZS1 z$J;3fK@JI{q{oN9Qvx$=w7xz9<5yDN3#JT^faAOvJbE~CL`el{jC}nH{cDuo8iVc< zzy}L^$#5SSk__b2u6eO1p?U`@UZAM}*m31HusthE!?vtNF( z`U_!r;?A;TU{rsTA_;Kw6~6fYFd(ht#`q)~i!+r(F7|;r9eLj9qsa+H912{9Xo6RQ z|Ca&zSU|XP**GpW_ymPpO%u|1aw?=K=5s&lM6qIpcj!C1$1c8-rcliEwHSI^ z{fVO&yuv~Y;V2pV%`;v0Z#+637*TvuB1>Ge21N>Kc1_8MfA)U1BV{)5k|Cg5avx1K z-}@@v^P-?`&3c0%^dLQ0 zxC(%|LF~kx1aaY5;&LHb4v4da_$pq~B*o+w$Hlwr9G#`$=XX*B^x0sOT;L}=MRM-l z0t>+j)vA(n>^a+i=&J(mgN+E-x3dJ z6FU*K*0E<$MPp1Qs*4?7A*_7;3uawsR!HwF3}13yM?Tfdc{)L-!GOROrAc^eOzKi3 zvdjko|6SHaz1-1-Hp0n!5*1T*@MB6xWZN$w^%#2gQRA-p_44fA*6o& zpQWr7>QYKiLKMs3#jG7+H9t_@3X_rg*tp7vDiNygI2hx_%t^6%B_zVpoV38t8KX-U zCNdP>W?Wd}ip*7GTw}g$%q<*(+`KsSTLe?mFVfyRy>|$riv~DLq}yH@eLou7iJUkwuz83DyiELkk{=?2`>tpOpmV2ZQ|PG;eV;B zUkQ_50qR+f)Z#^)9=TwMKx{3Ddt<$<dThi_g|P@;pu_A3kb{ z^VAJ3X^i(Sm}6F=Si;94Rrj{2O-21+##de5QQ^*KuTk!_efG!ezK)d-d26jLX8sKG zv94#LHXw#Ar+1}WlS?NLbo5WaPtWwp|4#IqANz~h$z#HOcTvxPM>##3k_p9G$Sx3kg_-l}t<6n|955@B->%3jP+?{9GUm+?qfeBUWU1(3bZ69ov<7!#! z%Quvj$yE8lgDwT$EuDu0Q{?RSCF?=6w2v4al#=oEWf!0FfKrZd|5mwVAkQMn* zz&-SG7!XCI-b-if&nz-2lxSBX3a^Jw%~HaTi>;u>kU6{x zLdP>i`Weqz6!lz!vAve0^LPAK#IBbGS0}-)L84~F(%68eo%IH5%9q>7!4cR3jkOlT z-y@&Xma)a#Df~Lar}D+yZ-!#$yGS}=kb;CH#B#kK&OTcSi5J;Q!?bp+!~*V+1lYSL+Is*b6xoKpG+k`afALjUAGSfN>pkFpUml{ zN3Sn14ELw^F#1Nc^sNBrrl4uWOR7G{OTn9=o6b}=bOZryC&KO=0xV4-+m1b2C=4bF zLn&IV@qe#W4ZvZc~y(w3Y1fghD>lcQr2S{#+ZD^z3jCg z)#UCy;8QTsB&^8d)v~@OG29P&b6zjLaNha@kW(X4+&1QeRT;sd(yapZpJFlw# zW*V&|*ubV&x{sv3!%KjT9@L`;^}+We{PS*;b0otaw9p_YAqu*zk7tGE$JPbap;UM% z{4wq;-e1aT9p1~r(4M2c6iIPr} zAq|;%V;@x~sE;jIq@qyvB}U$EfRYtM{$W+8Z|hv}=;Wf?CcuuuyyZuj zg)L)gLrxr~!sqs7>U^eFZwxQ*DR83KMkazLjms1&p2G@Ra`Y+w3fzN8Ll}J+h?FeP z-@DcGE(!8nMbv*MbjtTSC=z%(rS_oE+}Kt!uw&%Nba>wR+JmJ5XVF~^+S0$NDf{(( zdF!y$e`^8mfB}?)LVdYMT2KgO5bR~aFn9iw>RH0%Of@YD^e@gP^@LFd`QlfTBR=PR z)Q}{p)ZdFVpL3hC+NW6}X)_6a_+&YYa-F_O4cI-XkUD?d{QXAwX~ozDnI;tyEP%m} z$)DN8`sgS?6GD7jC?l|~hd?C*BMa}SCl(J|Ivf9n6^(SA+z2_VPy5PDp!2SumQ#bm z>-S_F^?Gpd`}EHk6;l>ucJw8QR0Fn`eyzK0t{(j=O#Qdz{t&DG9N{MiP}ZR3)7c)+SNq-$*IC zbucjH8?qy_QTehew!{j-95!JriwQj-^1ko50;3yJN(sTc3m z*$Emt^$oPJXOwUq1#kGwOEO-Lz7O8?6mYYunbt<}G=sCa9NtDBu%ca{!?h~tHD93F zW}=`U3?FVCAwFN9iy}$(3Hgo1A(V2+PaNCa&1b;_c=;svpW!zVPKc%%#Pp5Up3mie zg`_tJAU22jOas@D`+K_y9g_JnP=p`N`4VOdcc$NcMFF-%nLZ%#d4V9R=gp>a?R%Hb zW);21XWu@|;ni6z=15eUMnkO`FCgzthML@5C!aYr*+mQSJI z+ZL1;T`16UF(z(q9i5>V+x|%|bO4L4up}r4m;R-U(giAo2rCXJ5UUJHYdjPaILe0Q z?e@V5W(wtf1Eexf7W{c(=52-_H=ARd$(ck?$8Ys?(Ot%2w3nD8QaI+%r=J1q1qPqN zxr1Yut5stb<$Qlbzd_26EW}ODM&Df`KInPUv`oDhvvCYSHEBI- z9-JiG{p}b9+!VDtrYoaVB>x9=!J}LuIbP?zS<^i~C3t+F7~XYC^*HiMqj)7)t(+Q} zqc)-S8MF=mC_|2fW;Xw5nJr)w~^3nL{_4JX#Q=cniIX2+ww$xv;(Io;RH0x)0>{F1F+ftR5oyGDPZ{yL- zSAs<`7@ZUvRDhpAj!a6;Zh8VXjulkIKhzdw7T^8&QC}=+WC0Wjs$JBok502N#_O?_ z*@_1RsvvZp+|QHa{cOIh%ZijNV{O6zPTq@)@9V}DrPC7gg`&y?KMd~)j<{$O*AkjR zY1)hV5P1&rk@mLd*(f`;3}T>yzEgxMp$+ddB^f?0fMefwk=AN^#j)DtO{q@3m&s`9 z8xoJw zl#;<<3+VMHfYJ+`&tjxH{ly^tkd?$Eo1#?M5bMoc_$ zSrtRSeeTXgwN0s4HTmK#t=uoo3HL)Rg;4w$viAKSV6-<_^JtuH8Kr)WQVK`ltAMWG z-MAY73t%rGM0nG9oNd!dI<%cw);il1KgxCJ3(8M1L7JU&?zojcBU2HbZ!TjwQRIsANj)TuVjyDUHrV)lTxi^Z0iR{D+ z5U%r{5IM7iIFU}{rAY0n5f*;F(L4=MKsBji!^x*EoBjiUB%C(Rte`fG%yW0G?u;*S zPG1K+55|W7SOz>It!KQSic0`E#`QP7Ff>$edt&HTh@ImZbIc=qp&G3_@36QOtb6U z?R4LsWo4%c3wY~v21h|)zW-Dm}1EiGTV17pOj^d6IE6Kqdcxi?&ph>$XZ3MzX zyX|BmV>y*%P96%7g?+oR-?ws&_8_a%X#M46nrXDuU35XQ`Z-2VkCE$PS#f#JEpw!! zW9@DJ&sSLOsYM+XY~ubiHr-!wj-_6b9IG6(-@R4u8j@FD1Inz?$*{%y{D1D^6* zKUYpR*bahpNCxC>1#OKvUr&TF1t1_}XCbS!so#hS$I$^d|1aLWL$?Xv zw{0Gyi1^aj1z`3>N;<74>{dOx2(S_BEo!TC&b{Rs89yoE+J|^~aln8IsQMZ8Hy89n z_HQL5SW9Nz-+VTPD?0JlCe!MkaXbeNL4!jaE2wit2+uL6?}i+i5g&vWHhhQcUHcyU zPHgiPIfjpztFPb&k5e{*xl_tGazgD3Q~UZeoyb;PE+UGQdrspg_Dd@^9mVyhdKfmm zi@SH3?@5rB!142YF7na(W*d&VH2sd56v6fs63aL4!urR*6UD5nS9}P}$mSN$3w-H< z9fiP*ZF#<;+g$6b$GA1VDLFby{1*?Oe);ir=i8cGUcbthcy5t`B5RGmbeeeu$`GfZ z>wdn?@{!p|=Cq(g9%k;m{ORFSJ!tT?xF+@O_Ar8CW_+naCc-%7HR%$m&4(Fuia$Ad zlHCh`$oD@4MLhRpg6}g3dZHpaKElh$QVE8^gqxw060{Co?hSp{&jNJ~zH%#V|8eb8 zA#Tt=_G#y=eBsrktR^|wcwvBcG-ns`8@dG@yc8-Fy_GxYe=PVUHTeb4Js)KyI*dpH z@n;7V46=jvh1+bhF3{mVFnpoHL*G>Sy$98~zPYwO{@Ar?!ld`+MRL@CMVLI8|A_dZUOy2e<|g9`NpM7vGRa; zrelU~1K4s+wb543EZ*(f3G=_}Y5}+If3D3e5z-Zbu_4H(-V4J;pqbzeo57(bVOEf* z9dImPGv^m2@-_FR6S=)e(q@%bAUm#iCL4^E{8Xuz`b`|PE5G7)UFo(E`=aXvrQu~s z5JL*@*^M|*fF(SpJ(>%#}LAO{sIv zE7-QRtw^uvcI=EvPgHpwWw^a5&N~P7FJ1;zpWi*wyAXOz1&D$ z9vw-+qYNTkc}L#;KZh-p))xKk9rMc%bVcZo(&YZfJqwTatiL`;PI44}G15{29DW@9 zn5cd_#7br1u=`io=^Oq}S>|>v0D~5Dg}oN-_U!L7E@<-)H=b!DJFW7R>WRO(+3(;> zsEO`+Zj9KuGegLpQiXh)#*T|piGzbR;*AowNCy_0|bG2L+t%Fo%72`AU@Y&bnC$ajmT6)_D}&ga$%tBym=lSr8jJCI9QOxF znN=fDm(8)_VoUsDfk1`c1zp%uBCW<4qKGP0= zR7jLOrG2ZS9;Z5=C}>eG!e`6Gn|@iEA1WRNUn$rfqbO;as^YOm(2&(VtIw9lDn?Ip z1Rmt*UeVhT8Xqnd_eRT-tX1VrLjs*CJslF`NnDRU7n=fQx(&UUcfOjK+>-5Zow1Et zkXx;#FOQVw>pMP$+hcV5vX zE`9QbbJYv5v(j|JPbC(5OBABPfGf}+}hA`=G~y~+w&Cz-B{QH+uM z?l41}W%$Rf^@Mm(RX$znjVJFcoA9Y#0p20e{0p1#r@fO)FX5FF48D zjEOftdr~fYhK+izuNr)iuU#_I`B9Dadm)Vt5l=D z1ba3S7mfevx#9f=q8MFjbLB!z;Qfwx<;KAS`Xpy;u^Ges^NI@SgempS$LDx=1rdX* zz-vTa#`Zn~;%cdtL55|ZYdUHprdmcLknoV8o_#HCb}905Xt{1vw$;6V6v9qCA-nGe z;pT>1wn*lE6-(KC(5X4yXt00##MorqmtiKk10Fif#7IpK+O2|bckh}%*cJcN6%Yt% zjC0|Z1#slke8Ar|z;E05kMLlGM-ddym686m?AaDt|z9k!+zq?DuOZL}vr$hb@DBbzUff1oF`Lt!<)4E^D zlOA8YN(m^^2JNMb<#(+*2{`hu*;kMuF-aqjIdPNPLKk0Wr>x@?=P0iMj@w>UJeFE!<^N_AO-jkB&U3M6a$KCD8j>IOtVP|KQ z$vpO;3_S`d)er)_CP2UOmq1BFJ^<`RV&`XxWWSpqzhkypUetraN}o{K6KQyWWMf z6@}e1X1P4^Ymp3L$Q$iB3P1}{LM&V@%XkhQ?I>iey?V@v*u7psxTE;;0ch%3+;CYe z8Zl^Y;<_PNt2;IO%IGugPyYtZp9;9~saRA56S+lSO9us*vtQ6y4dsUBFXjWhzc`+# zd+e%}#togNb03?GL5^+>W|a zf_-VGE-J|G${#DdOR;0H8f)^MyVY)OXdzeallIL=T4h%i^kIkJf>9Zaj_zH)Sb`iB zJJ#ed4B#4=>f#((eC#>fJuobn=NR!ANZ6pv$_e~!I^d>+NSbg9z5JxO-yfvdjqlz| zL0~|RuTrXxFh(@X^$m$iw*go*O()cf%Xe1Zr10dr6%rruf7fb0k)c8*w!1q zYg0S4Xpj73o&AS~D8{!=dUW1MqNsb)qs3RY1@!2jNSh7F*04B$Oi*YUSt3dTN47fQ z5L1j6I?Xo(TeNTN)PO+}Y#@6TO0a~Y+8y%s1k|q(6LV%O3g2tcc=!H?3^RxLAv`2z zcq$0wE|^EtGQo?;lxf*#4d9$mt$9fU*PpaQ+Ynxk`TR#P^{_TaoJ#9$bBNc|?4;9u zWMEAz!I+Tn+>y7eSsavHAj_`sfeg=k1!>_WqpGz{^9oTWp49kdZLKk>X}%RsR_I`j zT&Q!zdiCS}rPKOrKO)Dr2Dndy=fmqmi`6f#qWpusepxuvV%vTC{-f`rY?Do^o}9n= z7?3YXhRa8z%gzOHk9@!OyCAZ3=_{Hofjq<0{lvh;DB3|hJN}wPQiKZEQLVAWl4V5b z67IxOMq?EvQbaAZC3zJ8AA046Qe*uC6O)Yv<;M3A4x_5RTP_e*q$H2T4x|jF0MmzA z;uoa;fdeg(@J*m~_deAf{69RMm6SAx$GC#$W6FO>Dyo1uMl+y+|;^(FkBRTawt;L=uZb;fwziROhSb~$1O{;b6JAx zRe~?I4p1y0*Bt62CNS{foDz&+hloH($;+mo378zLF?K2HGn@-BXwTO=$ppovN_rcb3U(?Ga^^y-Cpf@U zm>21YQ0+|6&~~quhV6}gz#lx+8<&R z*F=BK4#ji*4zxwVT{cZR3E6On#`cX5H_wv!YJItgjxidt0Q;@%&VcxB!qynB-ZVDJ z-;vDDzi#|US?i3*^aBTu-W^$KG(U?7N{`E(0xWqCFXi5og2prgq)YtpFT)lZO~J#V zZedt{q9k80<6w{v68ichV*9^nSks`)E+5+Q9@2jt?6U3!KFt8o0vNIZ3Aa*E(JlIg zl81EBh1;HaV27V-QQr8Y>9oKvjsl%#1GAh9WjoeFsfR+BO`jOGK8uvmd@-Fh*^tLx zF21Bq>%GWRdbN0TgTB>lf4$g`ZMW?p<|OA_Nld?~>2j}R!ymmGKUCoe6f)i9;8#YXQ)W?tcB;7-PWpr6k-)@{UgYr{kO&rUo%8hFI>Lt8Shht8csRcVY#g$EXU|e;K6Sk8mO=#40@BaY@`K+kFvZVx7<18NlG>&38aN zovis2YrwH_oEk$wWjK{KS{xtMgE>&06kd>VtK$*{cEaa7x0o*={vjS&)U!_&yzkiI zAo~x#LM5Ix(170<6@W2ls0s3%FvhBg9c5Ty3Gf7A4tt0Rpfi~SFD9;pmi)NV0nH)^ z3ry9-1l}0>>y&`06a$)rkYCEdW{_T5AB2pB9J3+cgl$>c_G{=oMQ%a+or@^ZDUIiJ z=qNR2e1Swhdv!R{F{Pghu=4MS_0=X`z+0b%pUff-CC)e4G8jB0;ICv@K4&?zg!@n4 z)^GK|gs;gqAIdC$jdOGU+zWfPFQseLo!R(IoEa zC_Tlw9;h&oa{Dscdf7iI)VpQX(D`BI@?~-*_a^oI9csqh45(Y}c}V*djbGx~XE0>s zI%4sRa5M^l^mg%J9NF7$)*ISGs=}SgAspi-()sM38q4QFJr@+3P6>R_!C5c&ZZY`8vxQMWtLJM-$8nRzYe;Yz#2gFh*JXQAZUi_<&|i zTPqOcR4)#gv{}4+Y4f^99V*$bY2jL8?FV8G`=yk4N*D5Ux7={`t*6)NYdwM80?|EN zSZvt-LP7_?Q}4DOm7z`-`&jNHvxG~rp+;-*bELuUe=+rzacu?N`gYLbE(uUviYK^h z3#E7|P+WpLrMSBVZ-Ju4-HN*hx1z-%MT!(CTJ)bj&pGdT^CkI``DO3So>}W!_uT6q z8j63oxcx=T8EjS~RE5K|_U4bB5pQ#hPkKm~P9rF>Q|Gc{x0_-IrmC((T)Q3<9`1E- z^ZOy}DYw%zA^EWU#80~0zr4Ktb`9B7_8zbTJjKlvVMY@oG7q(YMl!>`?eY-PGv`t7 z#q0iN=KQjnx#}y(kTNo{Ix?=x$^casB4r(Uo`emg)=L&7u5|#Lg3c06QFLk{$(Kip zm-Xe7kL%J`Qrh!XPLc)(PQUyX%jZkfvc(!J$`7;ruO1(zOfvm9C_3o*g*gF=D-$+M zUgB@US`#-J7%)2{ppVS6fIal-yHA~prA`drU#rjYWD7-;~bOcmOr z^p9w=p{scB#S?-=44&^%XH-12S*16@iU^!!I@C^mLaEUg2M`-rNN1=nUZermv*@!w z4iC(pVnN+npG$UQ-6%KbmyVgCme~zcfeT`L48zG)ffP3z@s2&F!aa=N&YTkFVVa2&RD+Yes{2fkx(KY=(>Ff=t zHa#NNsi8mmB`7k@bGasNU1o-kMs6)B=x~GfiTPQH%R+P|S+Y(_eA2Ce34FkuyeFYm zJ}F>RJ-gI#ZMJm4nu_c&1>CK;x$D`||KjMdej-}Hni|@#}4omuot^Szoc>b_^>g# zc!iz%6Y7yx(*Tmq2fP)~Q#c@>!j*Ybdnyen)0utu&o7D`KQ7vRB!^AT?Yrj>Md~;6 zz?`DH#_xh>K>eQW8ithd$Mun-f@l{U=uua%C7R+y(_asU@t1qSvGO=l;xvE-yRX=9 zg>iqh&d@xBU1sNNKAWX{@^C$HW7FoFiY^_5y3I2lQ5R6{8@7HhQW3*wu_wP_nBA<_m74OLdUfnrZHTKxw^Dr9>Ggf! znee)Op!CM^$Y=YuKeqG8Z|sbI=G3kJ_n|GQ(XKw3rE^s;vRk|M%_9msX%7iyaHX-K zxhv?s9sIlA_yQVw=%Z!^{Q?S1cHk>gafX+UOQhqB$1I4M<_Ynt3&wWa8J(Xy$hPB+ zo7U!?g=+gu%8Vl&T`EuA1TcavOX~g>2f6j`-Tkz)!Ha zRV(pK*_~hlyYMIK>}^$BUu-+ZwdpFpVK`85NLSLY%CzIfP{MaA#|Gv%@}$4r%geqK zp_r=j8+vth68Vf$!lMN+` zMKRE-4vii`I#&njP^dnTM(JCfrj@Yvzv3UTxOeFM8l(Af%YV+C!Ctfj?-GmOk%{@3 zLSt6Kb~-dR*ZwLyY!9Th6{D(U@d9oqSd&v8efaJ(OK7A{S5EB)jmL`c7L>PqZ3TA-#lLrVO+`%IlD14U|H!az z3H?Nvfo!`)joni@#UQn^_2aMg^$$^AhhcZ8MzhdW&ZjV>s09oD3_GHh8~9}D6~$fu z<(6(WKZox^qtJkTErizk;+2LBV8F_%#bta{=43637FD2$+Dgz#9hH2b78Dw?l^Sx1 zV-A)};sBDLzw3a&px`oy1NLV*>d)O?2@~F$Q*v){J1z->?1P_p&+ZQuf7hq&wma^< zJx3J^H|cSW^?p=~--4gxTPvh-0bj5zt7=U)JIeTCJ_)>FSk}k!Q?7cT-rDj`w6JeJTj}YBAlxR;W?F;()_BXUeQKG2iDP(z zIzqt#VlhkHLpI3LX$_P)U-|p$XEvVg;u3sMwP@M= zYtWyac)$*h^sI4+mycrNix-(9rg?TobB3*mqb%ZAO<#0qqERO`JU`bu30hP_s$!pS zi*2e3)I4V+mQJc$G)(~Abu1|c`zNeTNar|ePRgs71@djZHT@#W)9dyHl;(pV8Q>eR zoUBtZ*Q1fn2v8G4rE$6!G?q8}0qeINwO2}#e$X*#zHYcpwLyj7?CBZLqCXh?t}6QEq0;@fBJq2v_ucJ!cHARGEG zykQ_1sBuIsLbnJ)DnSVGhxs>Y5Ui|khh(g?3n)k3Kj@G-<%nB>%LqvUlfJ=5B<;&9 zKO`3yO)5OgYeYsqm$j_ZEGip1yGU+b`D84ngyJ0kjSrPvKXcTzK7rpI&GUP&U8tsJ-U@bm8I*=+Mz-%xRl`pSOw%AD)BA2J+zHa{!l zAThh@1YSuqduk1IYWP&P3bI;zmu={2^gO*StDE1v9&CVu67oPaoJHYY&O)%1pyYeo z-H55@0&k~zU%a;oRL@%EB?+?cw=l!VA^|VtiH2n_tzwFE0O(^eF_2weM^G))G!mdG zdkcY-Oleli?k}EPO2gTXClO3&?eS zB5pvO=-m-xkNK^2Gdco}^|6Zr9E}!cesp5qA%V6@4CqbFB=D1zSDKX|w{GtS6i8M~ zIpKt9ery4S#2n^$;0#Tj=)cKK#`3iLTw=q2Gu5$`6)#?_E~0s@aH7&h$KS?0DurIj zC5*7^yOD_u2Xyx%%{uHcYXB)yA-gO%JU(gTno;!3=+T2R(sHIBg=H@28fmrKu^d0x zp)4B&v6H8-2V(U`yb`Bv(%-x>tqA|hn$>`zbtGZ;MOZ?K_t*UkIrB`@h2cg)Dz_Z1 zJ+W|$r5|1+lQQml{OLa=F0sC2)7TUgTbVX+^_baL4f!~$ymvDulSTT-3R(Vch#{<{ z7d`l+vOMQ9teNQnQ;Sm~Riw_{Y5*vN2kdAAg)_ntg|BWpVVa~H{Wm;0oh0omgTf@x zO*s&0C((ty_`G)2A68x`c;5{V+%XLCKE_KAZp`K}Qm2gVOWQtlHR0LrmfiI&NQnQp z2KuDws_bdo92Ru9T_h5E)2e0!qInT6j^{+O>VN|GeYI)Jq6cNP%V7!z`Y$T+KdjUh`vdvn|vi5|=z8I2-lhHI8zfzqXOieCFNVVuy z3@*u9^NeQ@429d5Vpj+Q8LsF`e78%k7fB$@kKjFVMDac}Gwtd5k zJcmK_!zr9TX}ywS0OTLig!So&)r-m(aqlBuq61CrW#&ZRSOtSA>>-#zO5Sj;@pfUm zxSt@M_q1+sKs@AG!3gtbCMaIut?toyNco2yG1aQ&$`87fMmqTh?zbfS5}%jFDLc+O z(dlIA>Yt25aWFzl)YnYJPtGok(Q0^xCfKGA3x5 z-Q9S$gI~{IS9+^CyZ5VlF+xHhj;b8tFMtU1DM6{fNl$+b3vTEU$-y@Hxx}^sC1vxS z`4IOh@#s4qHLIzulWj6CxpWE;D)g>Ov_JtL@Uv~GB^QC6) zQ(hRPPA&2OjEuY}HO#4-q z_DeIn>*a;lzU#nCjlM8vd$AWdwevO_Cn1cTIUmI+6Z;LWUWogW9_O4R5AK#eN-1dru(~#NXf7-b^@bw-7uoAC&_4ZO zOBBA9r9fOjV_o*9om}P@v2tv6hO~p@`d%)j|b-CQEbrU!?aYGp|29TLpA5BI=`%G93i2w`os!-sRMOhQLmsT;)(pJYeH*MgG~%U-Sax{QdLY zxXu4fv-6@@%LD~G?rPcdf+=#0PZ}E`#k>lZe1KV@N zb1!}?llS=I)BE^k%j$ovn#E0LLE66;xhQrO*$7Jw8JvsG=KU&5B-bDRDZ_3#U^iht z_)aCqwr-@Y_;=|4fwzf@eia_B$7d}gT@^+O2$pBk zeilW~MRFabzAPM1TfXrobCrf`*^XM14t--sT$-uaiJJM9yJzLU!BgSy^Xh=1#6r*O zTx`092@KCIjaO=WchQGk84mJF=1e&MOm*DUzwB6J`}C7tyns+$Jf7g>m%Bo{TzCDm z7toJyE(Xk#xn6Q`lKe8i3W`*LhCxzfVXgx$pin*6C<(M5Uay;^uIey}NrBL4V7WJ| zA$0-nx7_ZY%T0>QPoz%i7yy8aOzl{-QHbQ^(%nAJRSqurXGAtfNAia_<<|9QEr*%- zP86%ChP1-e=v|?8&(5Cr=E(KM^2bRAe$1>^+cb_gK@XsPjn@V6Ytl#52VMp}SX6KH zx4y&d6oz(gI`Lm2ex%1p2i{AGOKcpsFE#wOU1NhXX$V3m;N(|?=WE3(_PGmdK=F>f z@ArX-)dT3t$8O48$jw6>=P}|OY3gZREV$CRDk05xmK1lryfNwNOA))^FfTcILmDlt zEMW{5;%cyuYyEyp`EHJQT?BvhPkq=SY19KtsANbd_EFm(@2>X58tH$}=;d*T_BL&( zFS_(I;I=o6ZDOhJ%)g^$$!xPii1XLs)&$NL-!*+e{Ap(#qX$%ib4e4l+uDjptY5E9 zCv-EFsk5xIwSipu#fEODh1^p&_jX!0V0Tzht4K%}{nDFD{bHN3P zv<#`{%rgC+cj?4V;RhEi{ASvcYwK30&J(El!Z!WSr5AbB8A6xUeyoErHW+8*7reMb zX|W@jlAQINKbn%MFo&R`yjTdGq3b=%#yRy=$C}Flyv04wsd7u+0Y>}~%UwwgkG0ka z#66$e;}dZ60DW&TPGYJSf4n29@1LQl_YlaHK+HkL)rD8yXqXoGqlouHl7RJbS` ztx?}=RlAJB-;LIwaf!zeqb=7mKzojIP!T5SMqKT~`tRAZ&!K(WM!L_CXOJTWGln@4`{hu`1>G|H zIF#qsXOhb6aa!T|YC?cQz$-J_7ISb`uT-`sKXi$jT!Nf3wQ9GN%*JQc(C6OX`+4`I zmHuA5NeQSa^D&@u&@)<7z#ioYE|yRm1!=4pun9$E5c86XY1nk z;x;{818kZCqBQeOp9Y39u7&6817bR0B;bYJK{O)SC}O z8&-!^|C|Mv4a^ZTgNLV#-b;mtC^Ln511EZF%dB6raOCsVR z{-HZM;G}N@fg00axAWHO$tbIm$D8BjJb&Um+Z5T$`#i^kqjJp*hmu^XS9|*;AH~#v z$R~h|&`s0{AsWwS;%1If_uIw$a>v4M;j|&wdls@jpd0Tf4QfG!(~l~qFa}IZ*wAt@ z3MoQrmF{D_>j_ABh(5l~C;RNf=yVc9f%4$JI+FeHNK^$XbauhxKCFhcU?V8_oswJl zoc>VN8kiZMQ7eu9=Iov%JU?tUjMb)FE}l$Yio5w;?0ZbP+b-Gqp^+o9W%vJsNdE#H z37dzMgHno?Ihr(bQ@w-M0hltA3z+O@Y!OfyU74F~UtRcYJ_s5ncLMFv91QW3>wV0` zAT+;E@QHge+7?_KoLL?C#JLz=rIqdAsM?r?87QUq*3qr+bK>hCV!!OnCHg?m$k;ge zZDj2~SXw5Avb`xXdMXqvcQn*HHH>c=rA`AO-)IngsQ267z3kH?CxB^QsxCdKQSRNF ziGOP+qvflIAMJwWagV*yL7Vo+C>F&W$4YXbnXSAD%jtKD&9c3|J`*lsClk!KhJc_e z`WQ?jV$5Y(t7?cC)}b24%cK#~E>GwDVt}S9en+qcaTNy+UyNFV8QB!zD^5^!x!fCj z!M?tOnE}K8Qc^&Q-I@&A23E;H?JcO;Mw5R6a(5}G-n{B8( zk;+<`Jyk~Kq-hy#lgW$e+5cwEp7yfIn~A+b11Y5DD<&J({cLNR)vs!_Ge3XyJolif zP`TGK6*bSLQQ!J|0p;{|s-xW4#rgO29kSE8oHF#Tp}Wj)u)q-sT~i)Y$W~km$n~?e zFf>O$NlIev4Jv?Q<`~vBE`Uc&K_1sH?r>2n;J z%ekmmYB@p2*{o}mkc2!WlG?S!R50JNNdFs)Z?tp)j3fmh$uO$Eby{vFXy5*JRasCGRFLlX> zC@FhL8+5`I1e3~enF@&S7NVShY=9?~k*(Tzczokq!V2778wiG^8v7K!SR(_+!jhDV zjx!&Aq_gZKR_%gUJG0Y4Fr9LT1%+ufR{S^DXBbG+}-iJ8)hepBAGeisi{55HC% zmguh!jJPV)KiKB=?0E5dNWA~ z5QPB1%NW0DqqvH?iU-T6TZ^5dl4#Tj++h1YBvm8qGc*L2k`p;`M4@fH_0E}$MV;(k zkSDmp2+*^7lvs0_$yys&Y@R zeu{}#trbs1RR~ozc#eA-P^2J3io3I^Ke8}s){EXJE=NQHg&WF4#<6~ULJ)ZiT1)iw z-istzVN*)<={I@s-?%98=UdP9^()WLLwv`*f?SN;iI(EM_}FV7LiW3ruVzYGXFw+c zUL`P3(#`mko<;nwpK;dy(KT5UPiJjax2nB0&ib~C<9aJdj_wYRaRXc{+FZ6{8>gq~B;S%HKW;V#QAb@Wq^KDB3i^x7f-+K#; zGj35229F60^gv|N$@?o^Y*JJ&AC}q1Qzjg;Nc|_^%?lBt&2KklhZdjK8jg#@ikqaQ zF*`D6imiz3#B)4A5pq$jZVip-pV{IST)fdH?Gs-&SoiL6AC5IlCZG@N7+`Kq09w?n zf6Gchv45t2aA<4^xGfK7#n!u!MNQWfrh>nw>r6Y7Jz%x_ahLoWdmVM~PVnV?C5l$& zfEMK(wDu6a7X=cW)O15PR6xgauBS2#)Z9HI6SSrokwOTt6vaINc#6h+tCe5@-cDdw zPWS}QQwh=oCd@uV66njlWnaRVkY*pO^iA+7)ZQp=rPH-NdWDJkqP%5r%&OzXR4gX% zf+TOipNFeuKcT%uZGVjI!x-l=Be_RurP2m zN*$^l(_K{7l_gj?&8DE&OI_ZMH|!jTzW?E*kMAz58-*bE^?o=m{YBu$z}bAnR>VSO zYjjY5Fk&;J4!&D={lS#MWY4npm59{O-e@5|{>0vA(hjJJQ3H{!Pc3J28j(7$t7O?D z>a952>NO%1s#MOsEf>F+eBK}H!x?{JX{-y-BehVz@#X75jC{KEBy-Md=1RWlvc8^- z=+ceTVB-%44niW*!O-vhz#J$h6NKLM1?CE!J3MJlt4=IZ+cfHvzEYk7^L5~E2EWqP z^xm%u@?ZP~&Bi5*T&rLIF8cZ)APqw>W3q)IgFP4reM;+$}{99 zBaT9_lAy_II5r7%n$5?1Df#9!g)kFBBKb)ElI1o{VZ799s>KcF1=$~nqG2k0_s+Z& zJn7OHn{@A)jVwjYYF=Qj*_lc3XYzN2PhV$+wDU{p ztf0qilgNb(S4M~N)BJ#DDAcx3GxtLwYkW4Ad6QFSfbKSeH6Rf2=J8T4XJ7(ZBb$zF zDnnlN=jC5Yl9JdL7QcE(Bt_b|fgm5OluUngG`R$jB605>`G6sE_@P+M zVF7z+co9rMPXIbnq#1D4aG?*DFJQl$BHwgHKE^!1zPjbV)`b-PB)!F3{+>9na!kYW zRXF4G*qJXUL)*kFm-2o70_JcF4P5N52lNz$sc3`gPrZfo!c6Qu08OFmupFdX;h~NM=wjo-{{6wD6Hf>T$#4}y_ z3(&$JUN?v;f`S0Dj%1>GFW%xrXcPn$16JQ~U5Iu}pMb-=!ijt8NHN_BQ>^f#*h5?? zr+U9dh;q*|_m0!S%HS{Hh3phhJy`iXL(GhV1$urwb|i6b)o!p7J5(LZcgbE|>fx2s ze${X7jvIH~C}X_^Lzud;?vIgR0yz<<2CI=9%1RF%N??a=(Zi%)14Cp>jt#!I>(s}u3T0CE13fM8}kG7UUkC)a1j)G!ILUImpBtdStzDpxxi-{T=3{%5gyB) zfw~c)_{aG*8iV0Q8T%%CZ${(XzD5FLLPO3opMgf8?ktzr7r+&U6O; zH&8+!aAdL3ifbJhV7C9mHtfT3Re0aq<429cI~e_1)?T&>zKBT;X<8cMnZ<)4AzikN z-lnR~+yY*L9lM=9ej*=qHIlIyg_pVKMasPME`Y~Rq^qPU53*j zNa*~IjPJ%ra+3}}HhNU7(|b*B9_luq#Zs?BFH@vB7v&b(s(eZ|mDTRY3$B+J_u3_6 zRsW^LD`R%NQnbOEff5qqxjD)`cR%bNa5)aJoK?2sF<+ytE8x@V*8xrGgtFfbk*_#gpKu{vr=42rDCT{z4>;|cX7adKuvFY%+i;e)$X zPwHCXP<>Ig&spdegbpHSp4MLJkAK8M{$W|oT~)_BLE>6`=#HhDjD`;pOQQZ)NUAyA z>?dWWnt)Z@8P~RGv{AUF-(^y6)3SuHFy$WIQO2Q{WXCH@aB1=mvl7rz|l3AqVwzXAWIno+^I}jJg-S+BJS$XdcM4BcHWZwhN z^}XZ&R|{at@LCs0yA^G$5hC5Nj9OJ?{!Y_N?IJ-9u&$UJP2BH=xJyAI3!k?z0dj;D zER%s0fpgjv6YV;vsQ}k1*xjQ$g_&*y{rF<3y}PwSB@9(Z-4&3 z?caOu6QeC9Zjt1e|JVoRcrTSbgY0}fVlRU)|x3XS;n>T3Tf>gU;>*Ay$^my!L^lF%CIC%?pyx2u7 zPN`0z{KhFa*yhsl514n^OWpV01UZ!tgpx&%`r<5v+0_bZ>Myp?Y{+MV3k>ot!Y)*B zt)gl9--P6Fg$t|QrV<%J%<2b@Sih9fp}@oncr>5cF{q`r;nkbkUXoz&CvK^bVeHZq zlR=Vg0nNxI_4FG&^2-;&NtJvKXdj-E3Kfjl32}CY%?~G+%2a~|VB9!?N|k8%h7wNi zi4cugv%@jeY+O9Pub}oeXJK=z-EL+-243n%9ZHfq&evv9i}2u8A!C;d@ChFxp!Y7A z8cQMixM#1^`VevbW9zS@W%YRxQdIH#_m)(scGy!S!GP}g4IX^M+0g7sWW%uoIIn+` zOkq<)Y3{15oTtorPc~zwCk@AFDU)R=)=C@seiSD)kjV`^5)WbkMG{4F_l)=&f`yai zBI_}uIHFgeK`+HAnqmPn=Q@QSA~IlrkBll3ap8=%VTC0@=H*So7#hA|iHq2|6E`+dTwJqXQyymC`;r}FNxOhWVQ{ER6J;6v7GxxoMwn}Fo})&y7A3^C zOiq6!iGKe6*>usg=W!G1wIoNF+$T+a6)0u_gxjCFtA>~#lR6>%aW3c@CIZpFfKC3m z{KL3-P;z-YaD!8OcOXPN%)ohGfs6)ff&#@ipuD03m#g*@qz6qN3k;9CeT~O~!c&2( zUb&Le8;Z0t5La25uku6d+_Bh519GJnE9opjFnE8C07FCS!R*=sO}? z<)zoWTg!p0_{0pAF`L?bz=^Lg6v`n}8ayv3y*u9f?B2!Cp!bzSzan$q238HbhwNbL zzW%S81Qm~!GoqRy0FS1pj;?MB=5Ksd(9>m~v!h4}4Zi(X5)kV>8M%?*&Nlfpkb^2vKN=Qm7{7ZB>d0$9kmPUNTUM558|G;%1PI`*pz+z_`yg*zuss}6{Uk=NHr?cmLh_Xp^Iq=3O9~6`i#>)Np{eL)Tyl- zI}M!&!R~@{zkzq3vP>gc{3c`bDkaxj`Zu44+1F}@*3jpi!|S`^tSR;L&JT{;7|tp& z768ilkFwiI6)S(o%_Vt_v0^YRo+wWZNCHht&!?FPmy-TEEk-wZR1jc2o($lZlo@_W-48n_kbmgquwQhu$spm9C3j_ZsYg2rv%*G3pd`ql2#Hj zK`}JwO-wl|I1Yh7JB2g{Xnr-oKym$Xfs@vE(p525{LzL{4b z+8FSnK(rQ)>QdYat_>FcIt|70c(9c-aRiT}(BA~zGNj-6V z;6G4h4GqLJUA1v@)atF*DOyb46~c7mFo$%pw-p0nt!)WtXU1Mz3a>L3FzgK?L+6T>0)>uD862pICW(N z&Igm+?LX7`r{~BF9Pe%)tZ=v=6?OXKQco)E?G@WwZPe~6)F{u zhk^Z+@-08YD;E$yVS*V|vP%=U<3-~~7~^t9){;C5fTKrrg2MRVzgP)5k2#2w)~rrv z{gCGRbNR|}u4X^X<18SK__=pJi-m8KzV==Sn?sjWE>Z?Dk^K*Y&4{;1DYdS_RxDTJ zTe3GlKl9SAUD?dEI`UxO@cLhoUsw^Z?sFkvDUk6Uq^N8Q;cLO(|v(=Ur=RXZdjZZ8iKxJc zkp4?cEfJX8bEN+i5`*XRildr!$Bw_6%n;u&u8zi)d~4~)EeH=yI!VM7t{(KjdUaRp z$Hfj#UI41WZ2#Mj$062+Xl(E*t{HW64%0j%7f|OslJZqKye_(OVCII4neHYdq6qw;8DH9DnWCg zty2DAO?A>3DwJ4Hs#W=x2Qn1KYgN-oQ^hTku5@bm581B|b2V$OD=)UuFp(Gh#TRRO zfxCwDeASP#cULSBNq3K(LVWQ9!U0_DXeM&^M&^FINuNDTyH-RNeOzLFeEeQ8mQqRD z;f_^>ll-}0Uw+7*VWYz(qIrli$7H-#n0bk<*zAoX5<_A{f`L1hO_8@rfkQ{Lb-$|c zBIpJEvPwECb0ZdzF%MhS2pj{xXp`ARV}34=sXZ8i`Vwc3D@a`n1E8iIG0y)+q?u8( z*~K^uyoJ$Efl`9=b-pe|Zm1v5hLM0~c!erYxomOT#@#kb{S*nZ4?aoy6UpqL9W13= zFh*k(g6vgqzJU}$@kC3>rpdA?ltc&Uwa}q-KTHShO%-d(C2b>Jk7!wGkpAK-DmMTD zDmX+I?4skMvRO6^2}yT>*M`oNTjyu-y>o$aQ=Bh_8q8^_dFk}AV0#+BHVuBoHnQM| zP)8?JuJlFbfj|9(*pPX=c-2bYSm{|JEHXHGV1qd)@M-_<`0jkI30D>=Y3vk`)9qAA z(EcT;m?qpdKFfl;M@(wOn577A%bwvp6WSyhkO?ci?yK|%*0^L#GP^Fpa_KQ$@rZ-A zkt*sjh=my*6nV6sM1GJel+rG77%8FlWFISY%jU1n#I*HC+v1-P03a1%!q30!i^9je z^ZJjFCF>K&4JRNpa0}OOWq$vyT(g8F>4S(Eo*1(axQ*yJi4g^ydJOY94%FiL*@Aq~ ze$I;ldX{@>T`a3R;^;gD6JbkmstXHWSjid4x8y11>Y1I!`MQ~(Siz2OJNw#h-h*-P^; zz+FgvTtkh?TCsA4c@gNEX&v{1;R@R$9Z}XWz|R&^=Y%X%Ae!Asb38{{#y}^@Ey)@x z=YqYIt`aN8KgZ4?!hex#XdI~96zaWvSc;UY-x$z7`)_KNDk-)p7wqe({N)W+Y*&|4O zQWuIGXRs2>>q(jzIk}+slf~p$KU)LV@Wr)nMwp%d;3TGCIp5jJz2@jaL26Q$VwZMc zlJfF?zEXD^v8vQU!=1Mt>m07?=(LYCW&uC{qcd>LLm{kx;>1WlH0o&&S|skk*+@er znvUi5|6_bd+_PNeg9`l7@SQfRJ9TgL^Wn$Ke}#hbGbz#ENO#;+6lu(+HxjC!pC|bD zaGbA>8#QKHE%+h*D9N5N$?o~58ec7 zj2|fqP;AF{>~0%Z9hsK-DLp&pc>8JZwjANeb7Qy>)DjI|M9m}k+5YFAXs9AY*P2h(6kBMc6miJj+p0VHFLYJ!Dq42mvy>`&VG;JAr90<1*5#VlM6`q?FF zfV7y=`TF+;tT;Ux zSXFXpT(iFvBmkeL4i1~x#S@L)G@z4l0f^YWJ@@7b3y7GIU?M9U+!OGF_Qzk;oYZfL z-c|AdEcb@k5wzQ^FnjDLY?RRzlJdp%$=`p|uZIOaGYCB69`c)s4y3+f?7BT`Ct6|aRH&m=L~p1tXP*4gn&x6V)BS_OO`vO?n%cB=Z^h^N@yqW=x~hv7 z7f10}9J?SCxCJa9U_AJG0zzxwQZALX$8ZtdHV)=m_yY%^2>K5mqsv%gLUO(R)v(CHIxg{WEOSXT|FeF&7R{yV+Q z?ZX+rSCEU49!DyvcSaeiks#`S5&Vw+h0p)sL;3tAa^M)U(FHOYdBOZ-IB|xCG|>p= z;>N4n=nejoJX`&juZG*A0D)xe^~_TE9b?giQa&|~nI}R!qk?ouhPU(K3(MeJH@OJ` z_Yd5CgsDU%*y@;ORm7^#_+{TS3E0(=_vx#H8c;*Sl`!eNd*G8(;?i!aC=D?c*?ahW z)t_ABdbPb$$Li2u4QC~WD>Z7uAQ&$CF{i|S2SKR45=-$jRvM@I77E1KE)s8W#IZ0t z7A!XP@Oi;r>|Ll6`ggB^OxeW|RVAgd8plT2@qM;Y$vi7)nUHf2z^`m$Gk4(5%W zf7XZ^6wkDSl$*@UzZ!uAsHuQ%{ChE%VOSvYWLa@5W^*GI{GK@*qhMCNEo){^(r9v@ z?4#Mmwk_pHstY1HfEe^lSv)`Xl-hX@9qFh}e0zt8!tPs=!5pCz7z&esPC|YThV_<$ z`lGO;iD5C(*fgJYWE?nH_YU+;k-W87@kYWWRyg45jQk4Gy5wBVKf7FV$p$3ErS)?_ zo<~C#dWjZW7m?^#XYYp6%I`h+Xn@V){#Ws54~MQ5A(MY`(vIe6BcngTvc$(*K(>SM z2KYP`(pCg8Wud8|-gKG+Usz#o{6yy!l>ti&Z?5r4Y+IW%{H!PL=%R6zUo|n>z5|*J zo(blD6AVo-bohsr6_gD{aSH{hg{K6V3I&7FLi>-}(`z1d9d%mU69QC-O`l%fqho_ZOL?X9Sx|ydtJJfzfU}gF?nq zl;H;U%?G|c8xH!m-O`J9lb`L8HJCMJuk50{;g1ohh|1}US8N>XZsDM2=&F<1_+Qap z0_B@k`1P{qR5ABq^Zu>C7EiP%^(w}y3~+CqWyvYtQJ3=XK`WlB{x!_$-Kf|mQ`q^P z79VZvE~kUR@Oc?!ERrVVOOKz7-bnTm?CCY1N%^{Wt+v9+-c151tXA`|cp1og8%gi6r2!r&zThkUzQsS=&8>@(o;J31@G0Ei5Clq};H0dn z`1VL)&lN62#eTwryZMv&P77zBRzSq&XVD-eFLwl*(9v$^PI)GIBa@g(6}C{Fy@0sE zip#0e=A1u5Y`wOL%}^%eyndVK%)XDxz&N@UDh?+6PX;%2kboTf)*h~KLXSib&7b_Ou@p_E z?XKBRuE?0jQFbmxiE8ud93|hNU0YeDV^G{l(3SI)qVJ?3cGLY{k-v-O%#pu~yUuqO z$9QxqCDs60ni7?QMK{9Y*3>*4?6CPqH>(AQg#RgE_UhLt%W2p1oAl*Q!e&-*E-$3| zOrJlXms-==ab1%Fav$oP1&ol+&Wphc(;rT)2vE_i@R0Rn7|QvRw68NQ?V|g-ZP!Mt zc6c8F(W;UrpSY{TNajnuZz?_|uk7j(4ZqZynZg;_<9C?(XV>_Zmets@)WlLct@$J! z6a-nH z(66eef!~1_EsJYV!b~QFAp#-bgbQn&e5W3# zd0xD~-?5L0aEjm@Q7TT|hID#GJH{FzyjSxwbmc=$Tw{CWJ_OzhJOl{rqGY__P{MA&y&M%2y ze965C5PGn^d{kbQChyOmDpCZGZ?8k9psQ_WUpn6%pA{Oe6p}1{`oEXbNQ`O>l|lN> z08OZ99nvTZyx@P z&VvWrGImQO#V{AW9$+;;s~bmz7$s=5P`Dx64kTGc?ZA_;1JNpPJZYsMrv;_;U%^db z?3Jh7Iq%1sr#&amciuL8gVy468V779s6S=(uq@y5RG(HRo=I&6 z%HI#utQmhAp59Xcj`(0k9Dsa|7kQ30 zsK~GEyU zq|uxB=y_IOpg7@8-+w;R-j?6>$x`+*jLDu;up_y$aeZOc58t%!+6CAmDD_jib zI2_b%1>B)4E4kMlN&IvO---Q{eZ>nF)f^xETmM9si!U>A`~7`s1Kd4N=BE*q-Q^Nf z#;W*ulk!($U8Y-=-xgbXy5i`XyP|158FiZNaTOLLEIpoz{8QQ4OZH6uA6ai16=l@6 zfdT@Ol9EF=3^{a4cQ?{QmvjzDGr-W@5)vXU(nt&pjVLKdmm=Ni8Q<@Fzje+!`wxF+ z&05U!?7i=+?mP5#-L3Qy2!S9<48L96|9mtlO5Ze2OsQ<& zVSoz^oW7$DRB99=X}U~H`O%vgT4<p&u&T04Ww@RxnJl;GIoyhi+9p8xTamraPluq=c$?TC(D#oCP*?4C(qxX`` z{DS>#<>%FGyP&S7QuyWG{ zE`v@~Cq0vQFt2g4iFW(_pS@=Od~tdDa})?w5tHH)=5TS|Nc_k=EmZtNRgqq^==V)m8o~R;Lu(~>8(c{w@KUC-j6t4%Q^Ly91yL)$ zpNVaH8BJwTED{n^Ni`bM2qXkDT#YVnDO3T9(iZ&~G{^L(rhZX%4E`$UD44M>Hj6g{ z_<7HYRu9IN;QsEJaVlGaOAb&O;wC#Npa;gweG~okY6O)G+xrJzxJWamX@nRPlXfhj zr=Top@E{m1fRY6tt&u(t|Cd^+Cq^zq-$bh9h@4b-%$o1w`*UScWRH2KQ7k1LLO5|n zOBTLPFc*@HPmev#Y|%y89p*{IS#ldX1gH7%t-&GvZm<$r^Bk4%=Mg;)59Q>%L8rF8 z$T>22mSdG$KXjb_>jhZmFfLZ>;M!QZQUZB=tR~>xQ}D;V5(Nin6NFUC)$h4ftuSAs zRm6Q4>!AHKVFEJ8SSlszWjh<>UwS{oqHS#FJCt0Hv9_VY*;d$X4*x6=rJy2{JhL)- zb68O*U$Y`D9F{pqe&6x?yY>f;v9!roEhIvLzfS}=N5;PEk?rFC#@2f@qUV~i<{8}z z%IEivhUuA-E-TzfF8U_RV|y>2%xPA)QV+~z0IK4!H0AFmDb&u?AN9PK_7f%LrPbd$ zKvzov@-@Kw0n;W`UHNC<%YffQ|U9mMK5WHU>B*P4Zb+l6$ zI5_qYRV4=cNvAJBWHvyh?vhliWb9VEqE}Uv61#76$iH11kG*%Wh!eQS{R2N)2+bM# zC7i9NsTc36_J3>a<$Lq5)Inxj6@d%Z$!;Ipb97d^!ZXNCv^e(b%nkTOx042QY-Q~^ zn|4(vbHLO(Y)x)k7FXW?Zc@F`XUlWh90ETXE14>59oiv@ ztRG1qPv(J<)W?vdthgvnrQNrE=q**L-><$F^R8EUmJBRbdSeIl#hox3(f5hQm>)?W z`nD|=Ipd_{V2~^KEuN$qT{nTK6KkL&U>l%F_?q}Dqp!G(D}@F<$W{THoq4l8EIm1f z6|+Z|&t{4uje(9NPaXf@fn)pB4FTito66JkW7i z<2&we8i4bnoMXJ9a2pEj=5cs!<`m3Hf|0_81IUT_i6Y>FpARggTNs@IVk~82vng9J z8r7*r|75N9Dm@29QU$rF3=BmRdMPnD6*lQh{I%pjmkk%!f|==v8rkq!Cz~)1Qz*dW z1^p<>x8;bOX8;)e;qSI>=mlc8IXVb8xoq)be3LG9)3=4sS>}nRy#Agy?p^== z?Qu|d_LY^UBuq~;iRd;Bim4{ZiA7AUT)^|H$7dT|6RJ`+B*u8`EX))&10A89Rk!)e zTP>0{7->Gm>S5p|j)`?YC#^6F^T2+i)E2i0vpk30(3=3woB~m0yG@t{ZLu0!9Cc*1 zxOqD>mXi`HEHnZ*;>H+F+dHp|kmq+u-gz10_yNbu;FxQ_dB_>4e28*a3ZHChCLcXbp_Y<| zsLlbOiq!6d-z%CjB_(-ptpI5sY^iv`Ub=DuiqG^`hst!WM>@Vl(M^JB1SYA(X4Q)VkQ>VrE z6LW3S?T?ru)*H>%s0?t6UGzrsMOSp)T0jF@!~AyOp+Wkn+NoRetxeP;x1Jgxd}nZ^YdDf~JUmn{8SB}KMD@j|zv z!9e}*5Y%`r@0^E16@qj3n4!d@dawtxIS&-@KZtq_Mm-LyCn?NAP*N($(Ehn0F zKI)9}uS3`0#WM+9<%vSQ=#!Vo6#>A+==o0vGT29pjVr4@LnYQ@LPH-8&74@Ifj5o) zaoDIA9_s~tpbmg`j?zdWvm5SErB8ZS`^SOLhRdyAhk!4Enich$P-FCE{Lik@SLZ~` z4ND&sS6k*`Z?U)edNCpI+v3<7T0@uYSg|YrzFwEX@()6c`DEc~2^+ncLw2NsJPL#; zw<5fSQlV0RlSr;ZfAK7v{VVsSjildGGj5eIOE)2lbhB23PixZ$3#4LC8dwW2Up<$| zvc1Zpaq$}Lo`fl?O`%SBsWawb39y0NZarUkiouUKa+05auH}BcJ*Y}Ddylo})$nYY zu%H}onfA8&vT(#w1Djo2ymnNMsxo2uR*8COrx@MPa)^tB~51No(X z6gm3z_^I6JOkRQo8{2}gpZWW6)Sto<%Hg%i#P;x%YlVoz*dv+Pk>G-M_ zTZ$9$-PaBSW)Pwq?07q+vX+LFDW5F)usc;Dq1)7cfPjlRzTYazj#M4(@6cEn?~GmP zE}Ns$Gll@GXQfjpBkJ3eX<5~+^xosaX#q;}8Fn)ASM(WzGLyL@wxR@i%;0d?NBt3E zb~~*)U~!MaTdgb+$TK<|()95S*(@x}G#$o5%~*Z^ub8sjjCwa6>c8m~0*}ar<`Ypp^)M_HSmA`H~|Jmqca*%{$@x(lka>x*1y?l0Qw$JX@z7uoNsf})>3W$#}gaq8;z_v}#tn%oUI-f`}cr2A^FhmAzB^RRC` zWi-Iveo`9`AhgB4=?6ccP-a=>+k#Rmt9uF_h_1{H&D5#}TTYRiMK}N^n`R23mIe6v zQi5Q?*MzJh^6i#XlXSu$uSWxo5h8!Kq@N+_f3MlG(nA0j%z1YtdN*gqBtiRX1=tl8 z(ZhI^Gt9-kJU;ri4zsLe8dtlR z0XF{`zh3HhN#WS}y_=~OAloi^o%tdl{#{CNwBYfqPJ-^VFBEQ1Z>y};nmIq>6?qNB( zxLM@~zPCQojJcVrv35v974z_0bdS`)S^L|=OZCG`7lK1GyG#8$ETyjgH}zJ-B~lN5 zX0}9GF3w}{ZOPejBxaTfmh=&%vg@u|>Yz_j+{hIQ{-`d^WQgpfpHK9HY1|~>+6UXM zIGI>ymHdKD;Bdwk!}=?hBDR2B3nojtN}pITbGJ1-eE_=sIg0023gwuqqQxF2-M@c2 z^k@4X<%Eb$2wDwHN7?s-XMNi=JiH^oEFqU{_v#3}efSH=NvYM`>};0jZhZ#cliG3b zJrky4pi=}hK#oUkW}lg`tGS@_#W6*54<2Vx*GG?o@K@tcJ!H%K!`6eW`GV+lJVuCl zV%O?YfyTYYO2^ldzgS4o@W=F3D$-cuX&nP8Edp(0hS?OO!f;E5;*{2KrQMDb_M37S z0Y4q!P33Js6KUa*6FdC%`X7}YWGyDiEUMPWKcj<^2P4Vx9hg>s!KOo%1pNGuzX`#CWB z^T-Tqxn{92=*JYZwNUwvprSDCzLGDvd`S4GgD;z+*U#vVMh_ofgfyfr_sE?4XNHmk z*HXT_B=czrUl<`Zfreqn>Wkd_Zo_+D{R4zxm7T@=Eackj?dp|yZ2p?F55epYy z!1uHWi^9C;f03yMfLwS;m}RkLdK;eP)#aOBKwdS@T5}8!*cC(AY^y~4?JCc&9l1V- zBL5*=A`!!}pL}FQ^K6{B@Br|i(Sa5#bB8zP6N}@Txx}*5dXcZntQ+MUS(0zxkYH~k zX@-2tlFXZz$eba;iT&|XZf^-IUA)Q7U#1a@`OB*_Hht5^u1{?@(&^{@+yflL_=KljAZB?|wzjS` zTp``?OoneuQBnpaY~A6c++d8~&$LbJsE=j^7~><`{~TNH`>~CiF!=sXA}CDYV~Qm( z9`DZZe5L8h&-{2~qe^*J^<@dM#0|Tt(e>|UD5N8wW17Fkv z{SSo~4W-Gf5;`g})s;=nBHD@C<4=BIh=rNp9{84lLJwJG2&8K$ca`4PA1kbA1kyQR zx%TqP5q9P8#aw{aXKjaA6}dIL-vj;qHkD$6E}Sz9nhl^9AeQ1U`M>j@b{sU{kR&}S z4cq6|Q+azt$ByXkN#Roj(djcO*GA;cSW9n%x@R^4l#(44!c1Hv)Cy2DP$4~6+H<~g zOei0q_+x~P9jP=};!h#wKH3QG@XmH>vBMcD|R}(=PR;eJp$?CH>6Od3mX?FgD(5 zgp*NqTup`(f4NcFJfQC7(w5P?ei&wau+~&(Qk6<>)V=^BTtVimwiDyLqwOmmsP*K2 z);_Puda^=_zy+fC36l22yW(o$7+6?KH!9tdMA?*^red*&0@}`v$knXIFN(;G;ZHpI zVf0PgN#iuOUw1tfwlL|V;AxV)P@Wql_1LY8A9R|vizKP`kE=RZ)p3=4G#Eqi(H67q z?g{>C_f9xzxx6=9-!}Id;Oo!w{FXByZFljPHJM2Zu4JrRSUpi&RblS_uL`qHYrD-| z=J$B!@q86c!2ysNNCtjxyXPk)Su#&iX^!Rk`F9HQywb_Ma`y6uOA6c059X})%8LJ6 zg(S7hLfpxDaOJJFS(zH8mtP zsub0Brzli^2P?@GhfzjRM5$6#ghTOh1OR1Dsp^ryNiuP15o*y$jc@4~UZOInYNqI< zOuRbE=Gngopx#&84m05!%s9JWL<`Z+GV+*r`c)8~2nxwOil*+!X z>BRt^faqDY;&l9O;4tkMIfsoT52gpJ;(E2wn3Vly;-5V|7aBWgYnjZ^B|AN2IOjRU za(z*lYea4$$Royn-gL*NQiF)t>jA;az7n)T{r7Rk{xhB2SNmX^+YGzcEL25l907m* zVn^fN#Zux^n8pKic%c)Z?|A3QWVmwm;K_#h@;PjV&=Lo63t za?v*)I%l$tJEx>r8&fth;BV0Q$n>pDN;NrljHt5oM!RNus|&tA0Jik5qcp@;!At?`CJ{G76}p48Bq`2XN<0~ z>Yat!>=Wo`24fF@NSoY}^`l~Q61_=M1eo^i#DK#c(F)Ij(Ant(In+@~YVKSoVjyUd zb88?H!srT?`}RGFMNm!*gzq%qDY09frsZs@H{Bi-JN|0N^_%<+@F#P5JpHJQ&2TMq zq)j{nV5eg&QZh=1fsBW|Yf%+#gEpw!2XCm9kkxWS{RTeX7j7FqGd|U1A$!AByYWygSK(d&EAlx>VX``h*?IZvJ7JMxJ_4; zYx5=7xY>pd4`Mt+Ryr8T|2tZn4Lc=<=7K))InH5f3_3AQ(0pd71Zy~Mrh3zP7Ao|a zJqe_DeE6DMooJUlCi#;`{`ytgQSD*q`Fcj@jM!6pqZGtr(EI*NtyE>r$Uj|h!aQO0 ze%yq8%b%o#5F)dLm~i+53X33&l@YXr0Yx>k<#GK_%znT)G31(tJtM9SChAt@OcDc$ z7I_wrTo=7K=0z8d^o$UJE!q|Jt0s1`a50IFQJbirtBXJ#|rjX${MJl>G-f>`l%y!&HaMy(aufR6F&jQvMN)thS;E&#dW3aw{tFEYSb(4ZpzaJ7?yhteXWXkl8E4plXh) z|7Zyuo-O3Z!hs^5ufIXa;an7dtxpL0d@#0d8-OhlpjDf(mtgxivlYHK)NDINI)8qH zdvoS7H7v)@JMB*$zn!c*$Z>1h57ukNPnB)OT=a;xvM1(Fwy@{5y(K8kX2i6te7GC% zh}shYwvjk?4`w1~H7W9JR}W!ee^mQqSK6^X8d5GM(3~*xT7xS!K<79KQ$g#ioh|0D z#yi8WsoS;y1~zj+3ZhKHbOzi579wl1US--c+)0uWA`CAel8_X8CHupSal{)}^_^)n zq$!Ubm39O8P`|LaXe(&uldd^@ESP;>(;Dw;F%@&<*@j1SCZJXy#r$kX{@K>*cE_b^ z=GbIH#zAoUDOq6*AQ>`pp4lQ?UnX{=(6MiNc~O-3)p?G@#W!g6&r2!}R@>bGVmOS? z@^*=IoX%_tv?c*6$*VMrEY1^o_XFw=(x->`H1*HWsg4+&9+r+y^ zq|>gDy+8iq!8)B`DN37Pih9QAOhW|W3n8>+os8SlA+yIkb=_(Y*=L#6p<|h#q{B?k z_kxEcqbL_`L8&(`M|sAjtvFMD+B@@Pt5}gV38aeXzUDCYPt~?NvG4aT)+rC_+6y}zuU8Lhs7EZyL0vG z-;Qzr|H5=6C%lwaJ^}LT5krm|Ms1hA&DX{IO%#bI;XdJyyjuO)$>8hMNGKdB0Wx0R!$#3#$C2XWBm%UP2__0%Pl7M8yH*{|Wg%9Ncc*Iz@q zeWf+T^5TB@WyFQxXXC6Yr&=GP3gdoW2C=hEpY`#Unz?d)$8x**7%B|D zDvZc5qZ*FQ7b3}_ZA%>V(wkID40@x*5`u!6V<`+k4{Izs3)>x6iY!VMAa1}Zt_T7A}cW&q}3)PKQeQu zW#?~*cIJ#|$GfVTWfS(Pn8@Vd{`-j=LpU;b?JMkGzllWHC^#|HB&xW|{DVPnkz))# zi8Ap@w1{4&tC*uIw85S2`*}$93w5Q_1cUSVOgwZ3M4eyLO09k9CQz2ytYGvM(Mmp0 zjGtHxEn;qI=+|Z*MIPL%8ym(Gfhha@r;3zsi^=pXq>bFandEA#LYK`o~HQ`Ag5s!8KpX#ZgDJ z5lzV|hnMK-G8c24Z8BXiHJt~+{@Ee+Zm=40rY%go!?<1)oI3U2Jbv=@JZru?=(J2u za_FYJ`MzoycJGo`WqO&JoqOsow(H*g{e@wOq<-4-w%`72y%DEb_~U;-|L|@W7-<0z z7V;Wdzn<5x6CX@O6Wsvv|ZztT|jMm7M7iK-6_mmFJ5p`xwf?=Q`7rO_^zwP zH%}qm)i@?HrflmKrIAG1;l+qW=i%hrwVjw+DRNMj>HVjCbrxjYuQD!>&gSUcZt30r zMUcNm!ma{GPV9H6#T$()kfEz#PeM59h3hN^T`Jpqo^@NC|6{iU=&POV~ZIH z!By<(b*p1CBrCS1r_0>Y*9U@f@`*Y8;zV6~UdP)NdcEeSv^_;Q9eexI74AQ z=b)sVF(nok`)%d(C8avsd`70%-hzrsQPZ^S$YPt5^tnF-S!b&Ed{9jXxX8;u}bsu1&@kDl1* z9x)-DpC>xoMEX6Vw}6wC(|yQcdlkhBP>CP8%jpi&k^Ri-M=Ze;x{j$iRfe*CqLVP> zU90RiOcWmq?Gg2VCL?r%U0gQ(?G46e;l7jw568}rP4k0!R>JE^yUosSpRx6d&E8Q& zg60SJ4~~_TKHdBzVC2{ZD5dv=(u5J?)V6`DgACF_Wo!Foy%84G$KV4%4*e8P7+kPj zbwP3l-w&Lq5}c-}E?LU^70N+o=$gcu6q95wrTINoOO)KS`P>gh1rtu$S_M5c%yu>* z5wua3lon3N_KcTM+Bd$6$vjpSu8aGfKl0P$7qbtj^RoOVF8RL0ySD?yjQN(~Zax#L z6%ARJBZGYhkx@pg9LqCU|MddIN<9Yvl83_VMFqc3MvOt6aFE2k>e7q5i4t>@Rak4T>Syp%?Tmy}2b3A5lF!<11EaA8BE_FqW+>k8MPmJ2oQ#Bx zGej3T=3F+d7vN!%$^||OK)y-!u$RmHGFofMO&ghEqTrw520MMK?POQGpoXvRYobAZ zj;>WIQ$kF0^D)=!f&Z(8vu@676X8f+o*Jk8be5_4$GZ{yQ@w?fO9DK<$l0u- zt~c184t;9B`fcsrwHvqC5_GnmlGoN1j&n zmwdGHC~3F~)KX^bhK%+v_kLROHx7}^NJ6sCgeTOP0cat3PoL(`7Zz;WZ@ruSbDEz- zk5f(L*bVMc8pCz^&cX3C6cSAPlHdLFyN{p9ZqlwH-BgN+B&uc^v5s#TAtmFB5Bf5V zf9CqZk2;0I* zib_@oh-|UTju1W(ASQjfGdBXa#fryLc)4qfztK2A@^n;AzTWLzDYPO4vyeQe$KMbN zlz9&m4=b^pHP!7RT)thj1+gvh_#o&l#RAdx1c)=tK3Ye`=T+kxTvqIgvYRX?u+Hg^ z=7Kw`Ol`3aICHC~scDh&I46)mHu(-5^~PFqOX+6U4mV8Oz#4DGp)?RP9St1yGg6Ak zcj}&2CSRqo`N~-c!Os=`Je-B~g$-mpPHd2XDF6BazU~$EMQd7!jl8zx8xHIX%8T*S zaq8nw7IU=U-`n|hg<;;r$0?@pwC&YO71s<$Y5!K*yAif^d_z~Fva_{7i*)oQLRqM@ zmzO_CWsi=1aL;$O)s1oUCMtze$)!Dby!j*RTl_1~%;E66nGWY^5NICdZ}{l}b@ozQ z{YZvto`Gbeh5HgC9T`w)3pw-dQoIqrNo=gqU7*3I-echyRpu?n72W^Zy7+;}j%&93 zo*)~KO_*jFQUPP7tNrX+nrQlaD0CDO;+x(Woabj00z=Bw)Be>qfw=*BO(u=deV`I$Y*=`(1I2!&n} z=ly{yV1q@|M#v(Fq6aC`t5IWtDsQ&z(1~KJRv;oDLv~1qv!4Stjt$~YUe&@z2BxRj zlzHE+JTys+Zd?;qO!bf{wD079M2#nM#KXZMb7@xsU984cE>XFr(nypW^ILX&_3UyG z9dZ8RN$^wuy{XPv&Bw)x>e2{j2MwRC=+IRR*^+)iLCyoNx2*#6I-Tj?)$S*TpN`i9 z|A-ZHcs-G;XPv^GUyf@>^+gX>t0C10U8 z^vUvM`6P6yTPJt#uY&!G=eGBJzuA+!_`7OzS&{|8%!YetUuN!%Td-s0G+?8)*tr(l zIMnn_d<1*AO{g&s`7rMiQMp*Y> z_l4c!6}r9e6*oH1K6jm#1GG};IE>RP=AE11#8Jou5w2-%d5nu=7W9vHmr{4Yb7~GZ9*&alKjdCjn^-)BXjO@UT%*vLxft_Xn3UaVGA z+Eo9>y-ctBDfgN~zCcmKSfc>+qdWHq0P4=QBx`2%o^Lj=eJE6v@zn5~T^AkZCr(2j z<`3!w_+|lq<`G-y#(JzNEikp2c|D|#C6;JScnxdBQ_}7-$4r5k9V8HV@xlXv!(X!b zOSytE)ycM^MfQohQ2~8kC`}90Art4D!#fY679UkQOy>RAeXOGcHaoP3d!n_D_&1kk z2A~o_PiAZL(vKDS`I5T)>WPV7(q%)EJi__-0#GF}?-##MZN6v`md>MG;uKA}@}EVA z8<$gxy&Fx$nsJNe@O8q_oer96QG<^jCwN+!n5@XG-BS*nu*OcX+akLaBQwWvowIXU z5_tinQBdx}CQuUSwi*>sWrO`2p7GfFMgD_sD6A2i(5A8wmjQ!kQ|gH4M^W zX40hEs;T)f-M5D|NhSToi_%KfYHhSXzb@EhQ|1}na^p&`<>9G$t>i`K>S59wYlz=q zktAQ<8eI+C4~_YCPf|$4G*PtMn&2toAm@D6E{wa1_@$yoB9S_u2MeTFoDu0WMMD-( z!8#}86jq0a8#%l=?chTmdv&&f!c<7EOpeKZ`Z2|V{?Z=}fZ*0kUQ7P1mvE$BX(#sS zl&L#d>~qcBVZH-V%l07P0WScD7Y%WcpJ*Wn00EbGQ3@3kCSJb*0-F#UNP=$ZGc8P4|hK$?;ZO@L|O zcoOw=>j3lz(nW@S&*C>9zbwBn2&yKBBd?FdJtb-`9!vBGz=qfrGPQd}k2L16pRH&) z;W%JgoezUUrQEm@X%~?8wZE1}se2@tC5*`KLeHPX6K)#*L;CIIRYDwU9ms~5`Vh>$ znH;AL4Z~ZvkFO0&NFG^_OyA~6nI4{Mu>6C-=aA>3#4m48=GsFm3XA>++&y3Ewds&D zK0GzZ_-Fib-gH!ENiSBUIA(-obE3)&FS-{?dHb5deaQ8h^CvhSkv3=0Q{44K7g7Qp z&-r~@p}~#x)=79i7g0yfCgQxIw`Nl%U|ag}^xOZjE?Riio{I(ndWF6 z$KIC%ca8J}36Ne?bzao9oTl%R5@p0RH7ed`EiPSTdbX;!4~u{{c0tl(`G;4@Q{JE` z-$O6&Q>3q+jL}1!yvg;yUT2XXnJr%VVn5r6&&n;>k^I=gE+a=qA~w9IjbuJeN#-7< zh`1;;)VETTo0V?#?ogs|ONl@vNy5RXH@S=d>L&Ntuw3Sg4*f`iP= zOwR(N3L}D;3TFB2@Vz6=6%S2mo!0G^es=KT;h_#j2S=Q|<#!uSCD06w)2Zg@<9D;I z2Bxvxb{MzQ=B)5M@W&S6wk3h^vRtto4$Ii2Xbt0VNw2eZLbt@q+Z*&GRkP(UnE)Ep zl~!WNQ|(+$rp23Rfy4Imx_Fcr>n?{NLox2eb1JSd_vqARiPYIFTAdD#povx6yME6lHj$fy1K0I=KW!;Z5zfGMd>>h6kKs?=_(H?JFk!jSYmI(9P$k=5PZsHfD67}RdNtc< zMeN-XIQs5tVbaSN9?0}_ufp5~+5KyG@jOhDZs3NV;r{u_Gll2L$s?zAqbnMqowJrJ zXKpCipZZ}2S<80)BR^UdIlVMh|GV-S|K)vNnov;U_UviCjM=f*bq(sTrwhag#5n!X z?@DW#$awXBs8l~^Zut|%^g_h()zuj;QtT`5zL6<>-!JJmHA9FHw1aiWu>$-8&nUQ? z8%2|6BCGqWl?92(TB$KERpVwIC@lU+lhE$-gLR70N)s0wW9qAN;3H>1NMuI^;4CXcicR2yg>wi|A20kJZ-WqAPF|e-<_5>JQE*XVVqwvc>i%^ zhAgB~0{6@ijyHy8#4knEoXt{Af^C|@g#37m0;7#*H!zc4W0&rl2=QATAhTR{j66>0 zD1FN5n{#dW5XR<}-R*=tB8E@(@eE>}M1$ev3J$ZxmR}l+C|1{@k_~7wSzCti+835X z=f5BJL$DS@(l_@#YHo$ZmOkq{pNlYI1BihA|a4n&QFqYZu8b0 z>30LUoNi-WPNi`Lpdg%-+U*#Ybvdl@BPvpha0l z|HFUU9`{8x5!T=#y<8fbM)Z^gcMLC>ykXenZDx5Ae|!jh$*}a>UpoFYu1|yH?YHj; zI!mq+?kY6b;@Obxn@ZSUpDlrV86-2{n)N@bG)ZFj1qP`P->w;!Uy7vz@SP;G zp%LFEq3R6!W@>FaP!vFE5mo&7*01f-GU2q+AkI+x7m0&pA zHn0Qor#bh_nrF&k-I)$Ab=Eg=khGd;HZT3s3ydDY_ToBvUNQ_D$i z)aGvrczIex>K|IVgiTuvk-i-?8;{%m%YY>jq~th0nqT*ys3wbX=+FDGt7C)d->T<8 zhSWZ5rMyKDX^l{rKGnMbc-;%D{xe>F{bUqOKPpDoX=D*1^j?(fY$z-Nhtb;$YVh zi3YaKi;Y23cs(84g=x3^A2SAFmgeqKVdEqB4m_ zAKV~f?|X(aH`tQ|GVP;Mn?HTo>tpv(s!_;`H#5DVkzP^KIlx-L9h+oV&K%PvyAH@Q zw-(L2$z*}9&jon!jauBGcYiKalse@uG{Ic{%PZv2}lxw!sZ` z1x-c3o#_SAP#Gz`*Sn$HdcImxyOMUe@GGM-@FvVvKZ2zfP8L%8| zii%Zb3211$dN$v%gsxS4ZE;Mz1|xk0kf9m`Ipy= zrQ?r*$|Na*wPkn?c5qT$y@eW_h8@9y)cL%=?QR({MGCp@=Znw(2sKRuLRyB4UzTio zdOw7DIlE=Lc0~Os(@6c|Q0~d2t$Eafg;Ze&_VjH2dIDsRq;fO*yw;#F<1{=>@sIj-b5&OX zQ^&>-HXSTrWboY8671F9Pm0mx%U$Xi;wj_E;>nn*}9;dLG zpZed$7hV14o5`CAKigvK`uL7M!=`FKHwcITzz1$4=O#;7HJkXJp5UaKzoSH}KEMA0 z$&?(3i{HeQcC+V|2&O<(pds3(JRPYe!0Y56Ei7Z_#Baqmes^iU!XNE3M>FyACJ)9l zn=W{0y}4^)4*Pp2{ew^ci(NneB%CzfSxY0EKT5|pO=7wP@&g-?D(W^YyPk@%G|=P* zc>$p2#7IKEeILDn`YNC~^X|r@yx-?Mh=y^zsls`zV}43kqUWpXTceasL%2`TjDs~n ziI4hN$9bTw1PpS~AE)S}@5>E}1#ndhM@1{&J)!$>MZ0q%6+?DWyJWHjL<+AViLsoV zwDw0MRpSKh+&#;6OKTp6nHw6=Jg5Bm^DJDTS&b7!%&-HE?Vy}WIqe;%@j9ux0TYZ$ z)=oCeoSA?49lCOdLLL*A3HFdg)~htx)=2bAw+#8|1WHN{QVLXdjZtB|JWqkbJ`K_@ zaW5x%Wakwml*pV&Dri3KY33ZI-`UrizI(~!TDmX9?Zw%kQavtqC!iGPW2YYMbm(ap z7sb4XtJ$e_f*fKkSNf<5=LD?5?o0~Y)|7Y?7hF8HZ+ZJ1u@%=OBHlt_Zz0W7t3Wqj z?40~q2aAlCi4mCZ09&t#wdcU?eQV=n5I3SH*F+Cj8MuEuOSjZ0tbd7X zGLDn+S{B_B6R;|d#Mqn$&nfhDqkmF#KB9VYuM!Uz!W!eOy-|!>L*2zO+PdjMZlYZ| zgfKuXQFMzb8Z)~*Qd7(AbU4-^|2XvP^ax3Uw5oE+Xy4L!?icr2<1Wm%lH zG=sA+{vol-AbyNo+6HQ^XRKJPChR(sGUn6tJ zi1dNYnIZB5A%5;+w4)r8?6H&D!Hs(-_NGs!f7LgSc5we>%OTRIk>6hr821&JU}*as zx_jkH_AE(f?`PQLN?)<-v>sIkwts!c&^rSI?3?^u(B zw)S>{NVoj0Wlji0jTnX*>oMw?peXeW+neIyG~3um-;#}e1_q`>MVKjQC75G) z^C5wsKSjTNtd%%4V4yuvVWX|TF$7VCJI;;s)&+hQ$E8_#U)ihrJmPOFB;wJ&6ioR- z(9KBqN^}jgo@v~j$yBe%(`HuWK!orw_v?Xe$D>chatNO$vBaBgJl(W@qc?8yZXB6> z&R|`%Hc|X69}gDx-t3k6U5u zr~|L~9EUNFZ;jL>|8DnuuI*!BHD}D0Y*16Xsm2Y8S;k&I71&&n^H?rY`4#*8KL?N0 zil7Q}(D3!?&;&V)x%uj0AcxhTgvDIE2+AMZ1P22H2QJC4H{IRx8;h5D|7u*N#UXRw z-K$#rae)Ze<)zVa`Hnaz!4|u^%FU?7tcc@D^VOZ^7i4Pfd{hfuexDM@%;_*FIlV|X zYWmp)rYQhBm@JW;l8O{_m@Jl=64j~Y6uRKD#kl-b7Z7K-fNYaR`xh3PlFqH-xQ_rz z613>Fq?kssYeUhf%y*>aBMLRE92yej&(7w)ip**5*BlsCgGVVYf;T2-T#GFMJvhya z(r*-YM@e?#x;_peI|7uOXtz_;oK1|0u&S$^h?D$LanBG zj;W{fq_RA-E#;XC39@f?;0;CY0L|YOJhX`mwX>Ie<6;hK6T}mOxtbK~(zv<9eZmz4 zi@Z(biQ3YIud}l$3l>XeYs{rLdk4IvC)+c@g(AbKB!&E1#a<3D64)R`9EJ7`-hAOs zy*T#f0+_I(0ZKx~L#K$$iMN?nTCPMuykTYp3zAv%|tiNEj3(lhuV;$qC(W*g%9?? zyw~aEUARS`fB#fr^_;!4^MS2)dN`dF(4sD7w23T`pK6-da$;1biM>>g!v(_olB0Y; zVpz0%IMLhDK*azx3-e_p4vgyEz&klxJccwgS(S?3f{zVJqF!oF=!fW?d|Kn*UB1SY z<9exm^^olipmNHYslltVz_$2Z{{7npcpq{tiR;mu$a{y_ofI+NZ5o^`)(;5a*s@ySv=tn0V+fiVWt;JpR!Ea3M2) zTH{F(@0ex=iE1BF6qrJ}XAeq=C=8Tv1&mgR9SwVKJ_=JxHJP#W@JZo+X9C9pGBh>L z`8bNv#Ns`RODePxUNp>5o)_@Mv*(1r+}QK0{gbhYTkz|d3%!@;@fz2xb6^&IT0#C| zi-zWE>ffvjb=b4(zcZJVPQmVrs?TL}JIS}!SS;nb(`00+%74HZ<2gy}1=R3AG|}5m zjv7iCP?IuzIICnSu}bFl=8Elc2#krJT2}>&4hTAvuZ@L|z!;;y$7oavcM|qQtJYT$ z_E5NEno`yUHb=ey-G$ei^!~*6&6{DrNwg7jt0UPzKV#47;%r|$iEHZ2rwP6#yj}tSf-+ri(l@NID%Koi+p4BTEdy4H z8i3Ex^qsL!p0Uw2Zp9??Zfu^Jv^a>K-uLZ=zYR#X3i(YNQuo!1rBHP%`2E%O*_*yh zH|#cPpQ_fE;*~Qh;PREHlvD2YY~TFXU!KBgfW8{!15VlP(%(KN*fx>g;9E1EXcK?= zVq4l{xc)U3->dW+evlljgqhUEF`_M;+rf>m>9j`tv&F42YGyw$=M@IpCNGiu@5kuNm!?@5tchvsg&YI`1^lA;rHLrmhw7Y`?Z5;6mx=Y{Sy zONl5GR94P-#kcXO|3xVg8LtGOlJQzu^OB2KZpejZ(4rP64C@E+pL68ovl-P^fQB^o z@?vuBlb4{TeJ`VT^J?Jf#-L7?E0hrYtL=P8$v>);Axd|BvC8>|x@dHlCmC8R3^x>f zv5i-)GwWS}!kzJMlv>9TiT(dBZ}Cmqbt3pQF%^FaIph)Y?DfAZz<5lOw|+bxh0lXo zvLTf>AiQpBF`H&kdSNt5KpGd4@HM*a8|8S(hn8cDWP}8jNwd*)uA^A$fRl-(V=WHN z_nop{)z_MmZEmGPWa8NjDR!5W58Nm3d?1Xb_o^sPPTw+-eKc-vk&tOp4sjk9UtrLH zh%kB3&l1{&i||{5PX8aO-a0I*F6ncv<1@+s=G zDv<69IT`N@MgBQ)T`<=>-SA~ugtp+nwaD&7^36GUVfAaBrH-hcRi*y28$&fjYAAvl zU|4%vAU-xT$ZC3a5 z{XcBXewDM09%v{bXRZM@)X4Z25JTmFD<2X`qY);zFS`E?Q}P?wEU)dIJNkO3pe&Ap z>&q5vXH~@@x383J%(;21GaW&WT(HSV?2x{AWdP+^FK35&DXT6Vg!=7BY5Q^ z>7!T%ScpCu?sACxVvoIWNE;q|FMysA#;-s&3zz?i5%0O?f#bgm(qdh=YeS_I-=>ER z@%*5P!+>p$T34dt&3^ctIkV$O>-EA>t`j1O{s1*Y2@dy>GoD%hYykV4%T6>KUHod= zQNBq`QwZh=zVymId<{SUGTD?^dTIM&2Y=_;g%k`{lZ+Z9G>405FQ-$ zjx&NWgf#ry5t2Kv?=l4cx90=}vs&))Mx-i;ZcBvc=8l3|efn&8o6oD``^DME zvFlRDp~rhs35ZMF(og@CZm?ecF@KH0zqje2Wl5Mk6hwy81671%L`~CKQ^5QNc-Gg< zkEzx&Wu#74A|E$e3CGRhdsuMcbh7dKLao%s_a#ODc+|AxjMD8&WrF{*_fwz?7&M~& zLC3kB_r>odQ)~KGzXDEg!7|RjgLo7F13?6-%&RN#Y+e`E28Z_(M1Vck8-|c%%&z&T z?lq?Ie&;BDl#P6;^NNxp4WyM1;AA~l3gv}T1tHAI4p`t}G6>r$(;m5QaBT&T%ggKZ z*OywKO`Shg1v2+BkU)d^3mUpymW2^f75 z7)Ht4B3A!P%tyGsxH~U+bi-Tb;lnQoT&xd!OhPKhMA#Il#eC3;4V{WlB|2JmMenri zpsWN>SQXqKj`eKx@KRE2HqKZ#qW^fhlL;s6_U*ovZi$;^0=*V?aUX*SikAf|>G%lm zCV@oJ&C-h|r42xG2DF=*iM^kHs>PKXWu`C(WJWl!O1HTqJ5Uj~BE(=~`Oj|1=&UDs z^zva%-%}~R&Rccz)Bf?7f37HY)UPyOHbm4fOcb#zK^TbwCL9ME5+8A=n6wu`pcp6e zJhvwNaKU_viq_RA{?sUZCb9H%e}yiz#vK>RxslZHMcp(Qws$i%WJ$fzM+%mnwT7l& z`m`{jrA1rOyv5c(d8?v}TN?Og-amG+7L3fX( zm?&O76}1Pb6Dg7%%=$A~{Ay;RWaL|y!Jk$p+NiHZ)>tiTAv?I0_UXq*qi0e9j=;Ch zV#h{^#~{Lqo9Kx;G3AGr7HYjsc6S8lxb1}ne12Dlay@>gY>F4n^(=G@o#pU`kS`@( z*Nzka^o)YCt?vV@0~^O;%Km1F?`nB33hL0L^XE$~LN7v)wJ`Wpp?Ju9^sJ%@Fa5=n zkk%WU_VLq^@xx}sD5%TVRHqra2lcr#wBh3elpGxLt)&!>?amAxmR~bfP7QU&MHp}= ztTDm`Uym|VkUL7fThbTr*8Y4to9RFE%PU70p*yw2DJG3$garkGlNGN(yBNy*p9Lzj zaPLy!)sgY)gYnsa8`%w5=pN=grjMA0hmSOZ8zmurzlIXViGC)&rkoxwvTBUuWzJd~ z`sArpeNEhHv-^149p8rCs7%Cm;OgCKT@YJg{{}YDY}bU!DBvG{oWvrqC|Y3bIpKWohFf+Ww`K^jenW^?7zbHrk)$IZPr1 zp%*I*>8j#)=iNU08{%WL@&M*@h`W)+*R;I%6x}$PWitM1QH<%~Y^3dA!Rf^=o5!er ziyvXZ1Mji(zO*icE0c(_yDapMd-~nT+;K%gw`Be+CiJc{s}O4|ClVb)Ig%ImvTOPg zixYm$?BnEvj!%Ao2*@~ol&ziUM>tZ;RonQ)?q!N5n+W`|h}1jw;7-g#Xd)Ws2_B4< zZ-JvT#(>ku)!{Fh1cQxTfwlw%lyr)Yu9NaBBSy?`+WMC^Hgtk2N+e{@w6Gy1apZ!% zfNB1g5;2=QpKZFqM>x2axeJ@Yqyy^oY0D>~K#zpg7g_pu)9_kn_z~0Tw{`i`VDT=I z@x2WEvjLiVCr~!#XwpF8bfCX_BdMT-X949K+b%R>n5AQ_|8@?X2+X@iun|-LQ3Mbo zLC>VwWYQE{NM)71Z8ZF&KLX8X`3?OD18(zXf?Ceb6)2JLeq_AT;o1IhGs>dBO%K@V z?DpqR91~=d$t9-xlBQ3KQ$ONc-Fh?N_5)e78Brh5t(P8u zQ$tkzb+*4wj#|UX%1m=bjGRf2J|$t5X3P{UYwS*oaLl?A0d(uqa4k@jXw*jxz4fY| zL=f-b_iT0S9O-+mgVMXvSNrG4;uf;`@@)F=jAUIl%O~TEJ?B;CFBd(d%$JSvn@O4@ z;R&N%jnoy)i(GGte|#1=^nEQ+s8A_hojm&i_Z1%KGU^P#Efcm`^dqLoq!;>q`b1Ms z@SF=Yt@g&nWq4BP1~{(-y`sg!BquTn)r6EnOp`EL|!RMl(6J z^JUFteAIj$^|=cXADkw?xG(Hdx66#h$Ql5~g)3Qyd=vd`GVSJ@?jgvCBWgI%93S$1 z8Rv|82@mHZT(M}`-?m>)l^R)9_|$ZV7{HDssi@7psf7PNmf`e}!?17XQX|bT2EzyO zUV$h)tP6Z8)cmm|jYg8cWPI2Jiey|RTe~_8VNG)2V*(bqdE2kw!6xX0GMv|NSpTHaBuGSMp+#CzHoYNAHx{34>>U3kEK`{ zt^37PFP6-hz)9u!PCo1FSS%|Y>&g6!A6OM~NwwL+!+xG!@ewuHAOCM(h!0|{sgVN1#_l;YU zB4i&Pa@=peF^IIi>gM?vES9BuP~*!%>a!B8w8u`HZ`Fd1k9w2r5Xt>>yCqix*g({ygcwx19pbPZ$=D%!tLr)dKvjG=6gXiEFJRhdliW*qI`hgq z;PMJWBQ5~;!C-2*CyE8*zHU(S>KU=}9DK&^FIlh-Omr=NoOr20W`xh!=x0?yh9S7# z%RjH0#Y_AsYL)>M?A**G2jd#O=EWKH`{{5!_@#Y+|392Z4Qx>_Cte-W@XP(bylx*J z%{X28J+AFFden-@@@LXTUhYi{nFx7wk$y{d3I_S{K%?n@7P_h`H2RPO-r4jIxCw5# z(s}qZyr*yTYxO;@P}|J=ApF9%ZlvADb=s@jGk80-(Om0&d!;a*JXvt9!Tp4MOyN08KDky$9skMAds`Wwg}j zpPZj;SFQ$Bn?9-qgao2t0l-e4Vyh}CwYhJs!X9E@al0aRAU|zG^xs@>-;u7Rao-!>yQo7cq~45BGP%BTMWHB? zufwt_CVsk^kXg}P)57OWYE#&fWpdR|QhY?RTGPaxiCc=SSKhEQ7{bQm`889#E& z(U@yOL!+^eE=2^E{w27K?umGm1Kvx2f`%ydF}TNUC8JsZ9@MFaXnO4c2xnWigc7e%o4!a8-o{9Uz2%Ic$lEwC?tbf-arC` zu;4b3#?C8i*XAuwj(}nEQ^4$1D`*gsbv4F$3u$0#jDa?HnH)@Kx#*1n^D3v##!g)$bR&R z5vw$&uHaX~Y=kwa9OxYhW-R?hWI?peV3jbp_P2XuF9SIP3dwS?z0JT%^ zxPP`vgWa*rzZye9s*Svj3h8I7BL~im2p%mf43RsYz`tbJUC$mDRq&BA;Y0D6g-2|$ z@zo*BN|wySi|TaFBc~!CU@PGdv8_B-jLjxnlEf9XuZ<1p&!GN z6;Z$o2L+c>VL$OtYK-kZA81Ad%ii*-${LHg_T-!O3E3nRa)*3nLQ-lJdBU6TCJ%KJ zH*#R4=DGd@-7vb#s!5i+{n-qyFX>D0FJNE|Cm86s?l&4LiyM42N3+X+)&P#Sl9FH0S zcp_+zVIVxB#%E7w|0Z{uNlB)RmquqF`BHViu}-Oj7@Zj$yp{hTD{Xu}^dap$)@Yf| z9-d{#J#HCIJU5xCV2H{&eV3|X**ie@M9X|RDr~u-1#9f(AD&g!ugi71)+lQqV9))? zwxR54fRq13F@kxChLyRrXVn{lNOf7Jv!9c_q4g+pQIr-}QJM8Op?!*Pk^D?;f}Y{8 zJitR%rd=*kcMbDs?^iQKsA9s6`j zJX$}S#n0~uL^hOGKYMqEH#HONa{H0iYePAft$PCN^E-j+0RL`kXH*mS>cliElRVyp zd01#1;SR&ce|@qIeQ6`Xf=&Gl-rMuX_|L(Uc$cyM7L@dV%!I-^s33W!HH<&c-;`>z z3Py`Q2*nx|exFZoRNu?8@m^?O^L0OdG(Kp3_w^ccnAE}UTCc@n(Z#yl1DOl2%^(oL zsEmTzeLX(@pr2NjnR;L&b_4% zfEdYJz|X4y${^5c1{dC%vAA47AetXps5r=)FiiwZ`kCgaYz$@9qY%NBfAWoNBeKy5 zy0Gdeil`2EDOQ%N|DxMSK}$+GTH2eVYQ&1(oDAqOLbj@ehBEqi9J>(vP!G=uV< z#%zKOOyISv{p2#qOMF?zAc=RR`2)c*V$sey#UV99eNJ^beV!3Bn98gSG;HLW+=gr; zX(c7%n;Y`cJ+}wBK8mh|;cj#=B6^bbJ7_x(e!WA9=&A4_cvOj&=!;osA!1TW?)bN7 zbMt8=GnLu58@DZ)yNh(qwrA-Fsg$#m&5G7U8K-gi#>tl6dAiPCV7WV#hlCKsWseM1 zk+Z8|#z)VfJsic5kZV4fF8938ncD;YtQY3(`@LIK%fQY+vh+eQi*?t9Lxnn{z-aMd-Vq z-cKt#BU9Qp6&?p!7nTvePm~KJ5{=zu=P0uIikTMSC+vsWoLnX-#!b+*AXl9j6Lr-) zWo6+zW^`DZMsw?wHXA3rx#r$Wv-n=%`E+V|Jw@OteR@w7wnyvjtnA*9golPV# z)>6l5mTU%`BnWZ0(EWCYx|EQHh!X^S#FrF)2Gou~N8C)NY1^aB?IByRBQF!VT13cS zC&`fsVLDKq#pwqM@BD~u;SD|t2oq@6BM1iYbdWcP!I-B2V)yhJ(jti(#4R14uot`( z1|OL^3rMsv(J2t+2RnHJEhhw~)kx>qySN-!&dt@CyM)Z{ne%6MLi!*PvEAVkB!Qz1 z#3R3Du+=sFp2Ptcg>G763RE!k5V;sqxn>a-YE<7BVz`EbFZn_>=X{4sGAAz6mnXW2 zi6J-f|B0u>atS(F7qqrZj12FP zG?E(b?n_hf77xc0y@~-*oEAk9aO5#B->o{ZoAkvXL?W9m4pyPs2WBSNq=$R?q(|A_ z*rGrOHF1fYu7>eDu!QTUhYBG}ZjP6=Kumzkt_w3qe+aE+Vn84kur-fOafz)b83+zG znc@#od~)6=qh~PsTm|?PI2G9*UR-R5(z_1fd7`4VuI`i*zVCl8-IO`IA+ZuLoS34V zCR-3=P+5Ud!BWJ#SI(h{Uw?WHBhm9b^sZ+=Y035LsFf}wcClY~0PD8X zAw~W1etD2ge=zJFyMpU$rH1k!LJyGhJpHZVC&gc-65p)ZkJtR}6xSr0}tBsBmlzMzzg7cn-amI?tr)NPwUlygFGJP*mZ-dYWK4>;9!iM&6G{9^GZ`ZA>r zbF$@e(BJJu&D+C5xGu@|6)Es2V%O>br9+WIBl?K}VhCt!>0CG*q8)oV;UIB^*OJJ^%hUuFT3a*+a?ja8=EP2>C4;1tHJDP*|#dkMc`UR{OfHk*T;Z+ zrEa0o z_o`n0>H97811Lc62>hL!CD$p``{n@7mGPQVb6}<Wn4 zf6mBYYW}S6@T?Lp!tODwT>QxER5qfXrG;-|irAQydilzr_~D2>jF31j2S2^KQOgL@ zz0%ME1ANEjV{1U>{*p;PxzQiFfnR^mfauK3HJt{;TbOPJMK{({sF~;aO2eo}moj6K zV~DY9-|2%vgEUr~F{tfpe9#^G`kPT?pSI60nN4v->i0f(gy*6*Vb<$IIkuN^NXb(c zz2BdeT#(Jp4XRIps+p^Lx3+$2;C_&A!QC+pdXtkXP@1gh8Yr8))Y|j`_k1wxGsi zl6usfJo+5!s*s5>sH2F_@ZZ^~B7Co%#6~^#qv|!5?oeSC`I6_GM0s*^ zy=LBtanWtsniee^foX`-#+8SL-hD^^JMdy-ezlodmjFS@9-71VIwSceUPd|>J3OQC7*TeA-IyC+jA6fg5d0}wy91{5-n&HbNWv67{*lg(4nyS)3o^s2esPv69E-mDmWy~a}@0wQ#@|L3xr zfBx;Fqu%DLETHaw%t&3=lTDUm`u@a^)LAN!AFdPREwmADa`Futj#{+$ci5uNm7>oYp@TbpoiC^>Q@G*0=AO?m>@LrPa z^GyG)s%OrzKH74AYu=%e+7N7N1NCRx9&KX+Vsyxeb5d9MLv1|M8z8XJXYgLWi8h%DL-X z@Z#}Lq}#~iUZJEM3hdl)QQCXm`i*_yEQij5gy^7zpYAV-hy5N0zBZ$xll2(bB&%H4 zNQG?&0{C2OhRyp_=E`KKc)zhP)XCV|s10q8-_S()p}|E&@=ZXAl&oG5v?#m(sJg`q zD*B+-BjiUZa2b9WeAnuvRX`-}TKrfZ(0l2RGi1#+Q;z%nzZelRZulbgV(rTX`2%cA z14vW~rNKI@-o`dfK9sPqqqZCv>ba>^g@S_!fXf4NM z3zOm-*GT~x7-qFyq|IT5=l4z^%=ma4;uKta_4K^utW285XU52AmkVtVBlP~fwhu;1 z9@gmB(8alWDOP;4FR{1>XzybcAKnA@AQ2KBmp|aShUbm;-Rfo26iIy|zm~1}wlJIW z#(t5{*LWo`I0y}mK7nzMf5gs+7DRsR5OKwa_qj(|HLN#NTV~Szo|8i5*x|{82fKbUiPwzK8g#9t2@mPn~Z*zYW zbN@!%N@s?`2H^Xv~DejX0a+;A&45(b= zOAMrJV3e^fTjd=&X5j-aKA`AY%p5JTUPe7jp7u0o;_O|;=N#aD+3g* zr=bYykV@e>5Lj5Reb_hBZnWVV(TQAu#6HDU%WLzi{R1(T(*g$brT;W@LC@kN{8Z7x z@R=gXle*fy1x{%fqNqh))EY3f2#=(z@zgTx>7t=!!~lA){<~8UMf@pQ>6J2n77$_r z(oe>Rv+_V-3F{nGJVa?IZb=ElMQQ4dT-r^*?1{t#FWFruGoQ3mf?`BmN4ExWYHghR zmUbJv&HZm?Ja)&9ycR1 zLU+=lH^UgUBH4~%@i>~qTpyN)lUH$2=5M9a|Dnkg{H9Klhz~9?m@NS|CUi#F0H%Mv zS6uofmh9+jzb<_-EUKrR?B?2ZUbvWv2xx(yhcYh8Q*2U%IVIeTz#Nv!q_N3KuaPah zY%%~oOl?ZwDytAHBGcSjzU{< z;w`#ow?9klIr1sy*g1};&xO!BS>8zWJd2Xf?gh2%>HAoR7lb7wcDZIBv*F>x9XAg> zJ+Y}7XKn7YD)K*UNZm+b4&v}U9^A~2&$^=UsJpYnLP zRu^MKGC~J;cjFrA=oAtBz94tnGgpHs>0Bsu5g_vflKW~F^vg08qP~og)6ubX`3(8L zwc&G815tH9HG$L#zF(FdmeEl^=SagzQTR}s1w;bS9=^ZA0Oqtf)KO2rL0z0Iomul0xx|?|sJV`{TRM8!U$-7L0Z?IX?lf z_!xx^(4!02)CDFEu0%togac0IixtoCg;ly@J|A^1`zNgrUmmR+ne5kDsfk8vb=dPM z8GsQYondCBezWtynO=!<$;%#UE7&WU2F5?@ug5(i`n^xi3dFW-+w&sr%UeITPWY)B zwOq+Nhqg?0OnEN?U!{Z%v$h=U|DgU8w%T=f$YT=|-e(gtgyp$k7u%Y$krzKAR_YH+ zHJa3Bi~?6NRcs&ymq<5zAT0P6_`J3fBP(sfW6H^%m1beu{WKd^wur%{nNE<&>`}BN zi^iF+Cq`pBNyw&`qfHsQlb@imp-%QDc2)%<-{*uSc{Pu)($Qpe#@OQkI|7)2 z6i^_G(}3!xb*$dcRb^<&hE6#h1>{CTQK&ZV{X?wo_W=BJGfuD|Z>5~-%71;-R~AP7 z`f+C>;~MtfiR@do4O^`75zYRY8M-Z+lc>qWlBG2~(6QpZY3+PIzk!^jIUFRtL{&YmW_YHop=#ySUFy4m z$30qV>|0z46s+W;E$1hCTH19Ar4}y^i==Bl%d)jIHlii$XVOKRzS6yJ^*D#Vp9VOD zI*vFV?^hbnl8=T1!~epD+Pm@8&)0u{v);`XP#8 zKhl22z;cajh zt8Y^kEW1k?Ey*6E{s#2TyrhwWX>{WzZqN-Q< zs`BCmE2WGO&W$hw-;tY7nm7xk-y?(Py-CO$hl7NSV#q>r=`Aj4WuWH(0qjQsC-i)p z1lkzPz%lASxBY^M3CFPTE*FqVGFUGrj{^Rn@&zbN|~d-(&)tP0)@ITMSK=l^XnY#hxn2UfT@(?Yo=M7W zrd-^K(X^i@P=;PGkwG$e%&o(t7VQy^2rlv&s;;Oqgg?M=*D}{!_@I^)o{msEJ_;%g ziLr?1Bu9Wwkdl#P)oRGt$GWcgq=KKHQad>29e)m()(JEQx?)GFlTJ==wiUDoWVU zVtnb!pH?48J~S+&EkK+qaRh$iCrS}z7uS2iDKu=eN;)9t84qohKW+03Q)gOu;|>JT z_?CaBBc&XqtwxRQ|BerlP6# zHUzTs5Z}X4d{qPY3-mh@zbSH6LlGw>ERZ7H z9-D~hyUsAig#rsLh$>NUKi+dJnBdgSSR%FmmT8w1A$Isk29H|LVs|;Rv6?R7Yt;MI zum)N?!)vvyYEGhN>NrNXNc!IMhF#D7jSZODVm@J%U9w;0+|*l}@j(-MkJ_D6IWVmLP4Y#PZJ*Q!Ibg3tWW9@$-DV z#Y7^zm0Dx=x=PE-_zp%Q_;?@OUXNvyTwdh9sF8tsDnuJ_znP4_$w5ZjtmkX`l!q!w z*m&O2z7t6Q_$O(aQ~T&AhC+;W7w+iv(0e{uiGYE~YvAO`TjZiKgbFBi8E<#-okPY~ zU%IIz1`I67tcUdiElLEVLfIs#G`|~?9)4Y7Ql9;43@8xQLM&%f(HvppgkK^V3G|X1 zjYS+3?sjv6><#CRsGS_Ir*82Pri_A-*_RTIv_)rW7h1T48`yxLuQqO#hD4|gNQ8-Y zi6l1LcZxMSejhJ0{xiehvFR&Vv!!PaBgV+j$(S62N-_mhs4XtcA2Z`wynxZadkI*3 z=)FPcHJDTGo)H`0b3l6p2d!;Q=0gu=YXV@Sv$BIWP>6j6e-TJde@_F@14(< z?Ey@w_f)ZVOxGVX82!j>G{97;$%%fb1~Y-_uti@Bwy}B>vd2>iTlNv$T5tYx9}|WT z2p1e{A^j90d1AM!0+pV%jhcJNI9KgSuz#tDqO-W!#$|kyV-81# zxj)Pk_H|9(mP#`|rBwzPPHPj3jY!=mz`};lPPevrl*at`Z`<>&s=Oj8nVS8|QnHpg zLn;x3^+beC z>l+pf;b%-Mua0;!+|46u96YLu^bs#j@f=51<3r4g7cWyhNX4sF=_geVzx25N%U$Hp zS|cn-UE&c@Y;aYBeAsmzQC2AI50vI%-In@>B~|l5)IPn!gyME6p(h2uGrEZSB4tt1 zr{}sE8}pwVXi^Vbu~oK@7J^9Rp|t(MgV2M9%H0rzg>5og7+>AL!>MQgC;wc9X_pX| zn=7c57ull8x`4h)21DT_{;ctKWl0^j{sN0>eXSf$p)qaLX?jXj-q|suiWV?zqw#`m zwzJSsC|0h{vHog!ON@V$;kczAx8x{BV2K&-!uJ~*LqYm!bY;?LF1bP$W5}{U=_?AT z4nmuLOBKEL?-50(VD6P`^|v4Q{gTq&6$?o;w<4P?r2Fw#*1oDr&b844yu-eEc3u5n zl-`CCb0*Rt3OxoPds;7YuMtXVZYuAbSYNa;S^9k^!RS1+NE92AE%vr+inF~dfl79!0cPtak)Es z(TB-&r9U<2j##6uuc8$~0>{kV^j4*5L3x>WzBSnr(sdZS$*EW6ph*=QSwoH7VGYcx zD*7xH|KRlf@|#KFEW@>sWktLHrtn+6KNrq{m5irNW?e%+fJ*UPFy;>57*>UVg|D(f zT->CKb`NBH8t8(`pI&L@D>b;z3pk&o6sy|Umv`93^&?^ErSuTZOk2KXVYc5gCEa_G z`<6FP%YCUx9+-QCiiHrv0R4hgZBOwU0Sgp8=;^T3$Ax5YFL}DhFoxb`&1cyu@tocTpv7X@2oLUT9c(` zx-am}?CXTNgrCJ%r44NhVTtJ78ybCK7d<1TlFtJO6?j>Cej=I0mU+D4^yf8be<@>s zTd}9)DbT&kV>3T+A$pkNI2CN^3rtrUFlLsLFz5^5@0KkeS|NR@SiW_=N_u&SOk^{S zJ0NJ7bfDPnCz8j<@-H@^2kA1GM8{00lTr9IBIdx^Q+&EwnZHmnEQyrY15}Wz8~z6c zwlQP4LF^%6Ap00k=Ex(-`E3|%l8DgDdtzZW>?XRgGv?|4yh(TqU6D>8NTPU2e=_Xz z1goWAdwT59xkV|Mgd@`9@XSRK%v9R8>9j`;VYg+xA2VaD&z17>kE{Z!@r{RV2WcJ=jJjh-{Lt8P& zl#MB*EI!R!bgk}R?K(O9mn~7SiA`5htJ1F>DSKuvyOm|Gf9Zy~weph~g7l9)#p5Qr zr(z=7dj#Ln^Gs8ASOM0MHn>o?E_0^Sj-Iw$O>SfT(q@u`eA4?@Y-h>#d(DmP`!3g- z_3tg*ussKSXU$PPPvQ!vD@hEd{#{XJCx+my)pokr?RcagvBCCw$+ki~As=T~h8*#) zr1*ZBgSXQ{U#e;MjcjW++D)DW0nkSg03V&x$99lj!cQY9;wKaIE#1xV4=$%FdU&ye zXQeA;#$xH0N`nZJ=vnVy`pU^1pKWGY5igjHEzzeaCSX{x(+a(`nIMT5qrOZO3{=$E zzcqeAXw|n(BfZrXyB(z6HvnpQT)^KCjmL#-37spmA;Wy*tBsr+dAM0teY;8=80+BPj^@^=w2&Ni? zzSa-d*_vx^xgsUEZ9@Y^&eoJSWa~Pkz@tkg!6InmjN^W^8slu>G_vWKvzhTPB9?cG zV@iVBM!zarO2rnWNOOoP%S5({yM^;Y4{;B9Z_xSfkqlf+!tfgn9NZT@(XfYOiV=NG}-W!&7@dt zR4jwEti@~6Tkx(W>Ka;#X8z z)(4UHEq?$8}e zw*KjJI>Re#+L-K9aoxpT)AN?TA5Q{Rqq^sw#?@=aAb+|K3BaSN7rcii+7U5fM&n zkNG7=fyXMCsSPoH<^9csCy#wbxhl-42D@0?n6#L_fBXHK=)XiW2ltyMeH6FsuMHn7 zfu#RQ#Rl-@Bg;TUnFUeMP)NL?i0z?J4*srNcxAi z9^|DDMKab-?4yFA91FZay;-FC<&OcM>*HUefgucM0=0@;a~$`FRS2OULWb^AreqK!kc#1v{ECWWq3Q|9bgiz2vtz+#1$RmR%yCJ(g7j zJ%svkNJYouJH6pTYged#>t;x+;4_+XJvT^s3^S=ajNi?`Gtm7b(xfq_0&mDQZm;>I z2%;27G^RhD>s$R}M^Rn9{vPP!;cgw|lNDgMz|BJNAWMSNMIFt+_gI3dhDo?`g*D18gfCtIn^fit$v2s#gsKJz(?+=tJL=7d z)szK0V*mhf8mRH=&0VYy>)QMbZdX1TM8;kzw8!`{H?W!ZFNP@}@6*(DeXi%@u5Bvy z$hDv=#_a_@^K}NXq}Av>3ClN={lnv@XUa zYwJqnE{$)O+_1}MhPcn`Jz8a@hfvd)wD)n3yN0h#gR{KJ;JjAGlB*7}URL^Cz}A5s zRs$bdURkDH+D^Fc*=V)ld`Aw!hTif5e?7 z`q8Hlfr$r{-G|k`dd=t8e6@0o7>~$HgahnS8Xdx#>HlW6*fs2Dn;VG{hykDxj6F@? zfJ~iRV3YIv&OCogEd=~Xb)vstM7NmQcB4=nW~;@+8lYoxeKXrJ`O1A@+B1sNoN37w44ZB(70`8VDlC%o7dnY^Yx*td z_@!pu+*Hy{MN7vOrh;D?U1K*MMP?K5lgNDkCy(Q`e@TzejyUewXzC{m_Kcx9!OUiv zV7}B-nV9 zPb%-pZYRxp`&< zJ_jlVG@lc*I@iB+AoAR<+jbysUKUz3X<}|!jeJBDPCm5Cy`Ox*h?!U_P;0O-TfW+l z**DZZlD+NmI+8znTT|1u9>`ezyGw{W){|1-`(m4@+k!04Y40}|hpE$}UwwcV4-;w7 zTUfAtmqk$}X`t*$Am2N~6g$fD!n(4Xn|-{Cnn}wh83h|iItitm1y4=!;~B_Ry$5hf zMK3=sr6q|mmdX`vNZaS4m}3nep&2eSM*NVvP0IUF@o>>3@tSBa`zHnr<>F?ueEaXw zV4j1FB{PgjhLs0sW6CX_TAe47(bNt;T#C%Ny+Nk=fo-c=N@5so5PX=iT3#QJrw zZ>259{Kkf**ZE|wva1Q8&LJdI9ycP_`eOmhh<=!sb5XSV8Fgc7HJKL~AlV&V&cz`8 zZx%pw+|Tpm59X?TFx__zOAeUo%Pzf~(OXy?z9%tjV<2_3QOe1;QDaP)&1zhrdOyc* zH(1-Q5P#A5?T-_|`bCp^REXCr}Q1wQb zN9DS6j_;)zTOd%c@T5=jz!7eb?vzuIf1)>pXe zqs3`;ofJjU@R9zt2s_-J20G6mypgz=F|uDmMu?qB6i2!(nm_z8fhirQ&dy?cCe+8bnv1H zr*V9q?cJcx(7z&zyYIs-lO|sdrHLiqoFH3@YjIwObWuNvTxnFgWW`Ew$cKQpY4ZDD zgduMNud2lh@pd)*fh6j+ZRrrA=%DiMZ(wogJswB@H|Zg=yH076xKqP#W%>R?Ev;Tb zdC4R3KZ;fRh#(e(b}Ku^V)<;0wQ{J^Y~^ z!DZ`$n48tLbdPR|DXrT8|2DveFH`o43$`(^?B^!WnC!c-tB}LQ;C(u@p z3^?V2SiHgR+})Bs5zi0>jqI?Q(f-VuX6U9s_^g^u4J?eiED;b6_9A1vQ{PEI$-%dG<-YsLe_KW3qSXK%kG(8pOnRH56my06z!JkX$P4eJ;`0DR1$?a57^-?`0?1i5F{!$aji+}!i!k^}ar^>lmziw=d$*uA9+_Qd#JIXMQbM*f)^_F2# z{ZYFx-JL^&v?$EbE!_*{^*wBwCv%`eIt{NTo*`#p2~v8@PyfIbFGfI%FVV2Uj4%4!4aRZ4#Z_m9`l( z6+84*c6w|WTJ|>kv*#om;IzqywL|TEc!a#+iQRV3QM-2Y%8Af@Cyd`2OFm23vT!{6 zGe0_UH{|W~u-E#RJh9{$cEhY?6H5IRa~bnNYunH6p`L4O(_vav%4qD6T8N9v{u}1I z4-FH>J7uY^#l4iYnvvW&>5Ap5Ki4HKyC3G0%T@_bSbU{oDo?GKu9R7y?FNPS%b+c5 zH01G~ScuZuo5Ie(*DBMZMY)))H6M8ISV4ZSZR9LFu; z#0pCknX!6M+a{CHEs7H(?Y*DKM=xmi#ZrDJDS#DXh64F{ZqTim&%j^GPq1Q#Y8sU? zVX}PXLL|X=E$(~8-^a(uuXrj8#^Y_^h*)-jsg0Z?IJplhg?<)!aT`|LQulkMA<9Kuwn_{*P$mUxhqVk zKPC65lea2~+&I~@2PAXBBaj%^-0PuuJ$iq&PlEg<+-*c^aHDg^4;P$1!~>v{gM@To zyw-&(HkH7#H-D>=(xmj)r8_S`i3qBPiDfQR%$=jjD%yr|#=7=5d1|gAs#u zxi#*Qa)U_Z>}K;h)^>rvp_r2kEy6Y~Cauil*@LocHnqc z(z5`kP8~;JP6~?^iO(YeP2?P%pXA{t{J5$>V_(((zL?=& z1Y!nHC74PuA-M%Ue?NZkNuNSt7e3{|W)yL*Zn!@I4hXqShoNZvTf1o1nHi0jp~DBK zTSAy9+`Q1%12TAmFY%yucD?kCQ4f37S+?-@6@>VQs3C+qU@Lc_m6kNZ}6DBFL zfE*eINh`p&OA%jHiY@AXR*8C-axEz+-pm zxG8>Cjs3InPcj;D@nq#FeX+ZNKtt==>cpnIt}0(PzY^=dZqE>aeZi1%G<38R*XUhV zo`5Kt3u-&93t^&~dh;vbHVZVK><2ak3Y(T%$1o$`=)h_kgI4Ppl&PDL=l0(I2OE#W z1h4)Q6>wG)MIb*r}C-B{??r z^>7Ym4o;#VvG8ooUV82GxAyL2-;4Z_V$zWK$aBmLQ)qU`jNd(T2oXM{xnQ}CPOI{- zxURezc}-Fw*jatI*S{W$1kqou+*}$r`Efa8#gqJ}@!KVcTd15Jl(5J#Ixs!*!Dw1+ z)G1{3babS2HZGz*kxRi+iudeK)aPUv>{PniZy>$aCFCvd5#Y_8ltz|VzSD+VJr3S_ zz+Rcl7>h-IfvEm;IFukpjo>qYELN63h8atj=^BN($al%lvu(L&YB_qD=CfAxA#`+^ z@{g^y`r@^eZtbHiG$PgtfX*IM)WQVQDNqnIuMMJF=3Ax%VB@Tie|Ccw%6_S52HPjp z^{HLu+Wygwe;1PNaI+2EeA&VR$wD z$kS(+Z(hzj^rjr3F}iV#GJ|J$b0?>r{_IUCh&5vffZv6S;1~g{3%RI?|K&w4=OKjP zTdR{aJO1M7^{nzz!epl{pwK6fW?pLiWhgMC@~{Y3gj(~hodi?V>MLyn5mPx}YdJx! z{BQ~F_nik#iFPgoqvA8?dXP)EqDlKJy~KE$V$?^9*l}YpZvXsOrXP-sPZhWa76#Ek zteY}rA3)ox2uQK3b9{swa@=hbwU z&;o)AdD;FsJyqGv1595AeFV(#YaRJiZFN7w$UH zY_BH7OnMG>kfeC|i(rgWIUAKHO*Qm-M#7*xO#_dr#*#nX^WFNVaL)+9d(ZR{9TX(d zK}H5}o`<`FmIDtl8akFR50TGDrPSvSq6Eb9G1dg61Ra60mm~r)3WbFFIN4yoFW|81 zi;rTe2SYOSwS*g=*DH-g{e{NsqNDMAH;2FG0N4SxoegtnzjW5my8Kqn$?WJ;metw5 z2}1_J$FkU6uJ)HHG8{Y{Trz&C=RM3oF?4u5%}%o~T5cUp`!>&zV_!zQO;MeBn^n=|WBI6e zmS1%kg9~#W^fsWz$!EDq%x@=o7GAMRL-si9A3M3m`j_=QDJTx^J~hFhoAJARgk)s@ zl$AUSdl&q1Z{G8ey0&2=+4y1&HY6QL3R;13cVei?8(7sod;XlZJ%+I7*p`F^K>$-f zcFv(yR^}I8*!a5Dv9rsG$5(3b(e{Bs zjW)Ms!I(GLUH75(p-F#7qaWRe-X^MW+~S-%!hOLVP)n@S^=^R{DPozqpUPzSoGvdO_Wpv?4 zbqtQAmtXkZgdo|~#0 z_M}>VWbZuq=7fLy3+bh~CSV*pdeWwLYoP{~VWeX5OdEq-2&O4C!-Gx@1(Uh@0j7L`H zw#*{i-z3@VE$|s?CFVNm0<=KRMa^=OraSAUh5zQ2Bfj-gWp;;i<8t zoq@k)9rFj!d!w7ko92-tONrQ5EXX1E+AT+gyRl731Y?>GNJ$-HW~Ye+0ipZdgi1PL zlkvxC7}cZ_AYZjZJTza@=6Pr#&6`7)M4=xKWS6*L4>By}%N)Y8?$VE2W#^%Z9?|)hpheXtLy^8<1W!uQN znXo~<*3fH9EBA%f?tye$)=c{FB;p^DeCXyTEo;y!_LCN4F?@+f;|i2^`YuJAjlTG+ zTSju|PTdn-64^N;JYTs<*<*d>A#-SG3};_rd$TJ=QJ5`O*3CE_o5_>VC8=F8*X1mr4u_`sa9!5nWS{}XeQe5v(6GI?;A8TCe{2td5~IPQfzl+1eGG;q^1%bZ zYbrhNN*w6K)$;2bfihYTs``X3%z*=pVbb9bTH)fccU`!s_oP9ft8t%(b$gh_&`^%9 zD+_jvjc4Vle3nD}4IVz_VOIi631|X(u+LWaJ+4(5{?3`?r5>95cwFl>#xBMxe>H+7 z=zZ-@xHgFs<5M**#SSBUc*zVU@h|6ElU`cBD&}4Yr%i<*qq@I4ZITI}gu71G$sbZi z+D~@F3lQQ?Md7tG>~p}%Rn?y(TGEapl+eVpNXw~1NlA-Z#y6f+CTZ`1XecyzBg%S^ zzRKa7u?S8N23QBy_MR2iY}Gc7LiH7`}7{)A>@WhcHOw9 zHE1aru2)>V8;km8>Eh&CjzOW1}B%ZW>1fzMoPTmfbjNRXui$P$x9gtQYN};ZIU*-Sd{Fqap}l z+hkYnXt3?YcY{KdK`+^z2}gIG<)1%1WR!xN?%4Trz`Q>mghw!tW1+?<-?_^4TA!*t zgLSWBU^heUr~L`mgNYjlxbj(kpOig0`vT)*6#P7SOp?#f@Zl8~Ud9VWTYj#E|7ACz zeCS~W^q@2MINsos72=hq@;j#A%_EgMc9PtwVXSg+1JZ!dxVPaS9eOzV7U`$FtUlTq zH$<}_sFA979fP*IfPK|*wyrhode3&v$V7rs8=v*fke(7J8ZwGt1=RJx{)%lR*hUDE zYGmYkm2QKWWo#!;lrjjdD&qVJF*Zjy5X{7!`dxS(GMU(fNlvSUR@pH>qL<=VhZV9q zMRcUSSzpN5Q_&t{F*(_!jQyQ05oTmu37(Z&=LIc*tKp$$!=-J2glS{Xrd}wg`lSP) z8Gr*KIO}sBG5RYsb!#RQneGJ0blTL_G8o(_!>0>DM@`=QrYd9$@)s1(V*mM8ihAsa z(NnNtzGD`tEN6|9GNZH7FpNG{bLEGfU!X7`Rh9V5!*Pr_Za_Mze#GV=Zd5iV53kXF zp5;eN6sF!n0e|PzZ|8%(J{+xxFR*jZab0xQh4)b=OP|^*kOnLfq2NLA}9+)SRbM{ zwn-j4J^d2pQc&vUOW(p4gW`-cra^ZI%zn>qZINS*X7)8Q8{Bjp0&rA?Rpe!&`qB7k zewuYO%+ffWXh~jvT!gO72S4Rbp?)+aqO8LyNX-l#5C_t;X5$^;O`059b8R%Qe{;8J z{N>7IS$Ln_w@rcf*Hd`Y6{|Fpth8wDQwWY0Z{BAiN59XbcnX=A2JHM*4%2oTmUHnjiaP3`qb_T>NMrN%KIvHY2~?I++T!RC$^Y5%3H z&%H(nXunGV-bLmjl>(+ZilPeiAMEx2r}Gq1A(vrx+rHBfKn#m^S%ranXcFX_T1~&~ zUlqN(M=BsQBVDShZfPK@PE=0EKGa`yu7>!%n7ydIxV&v4vVr_ z!m1uA5Mx-k7jIpLG9{JNB3)pmgUaD_5yJr6C$?UY?Yg5$>n{L$63?-NP`u zKSmuo@ZqxmrziguhaSkS8{uyl6~wZ=mMI#+o%BWR!Cb)VnO=5o5?Jg12TSl*?@g0hAQihnz-Q{WZS+V7A_tyrr{Tos#gQ%dsMi+_;=gPGUq84gwU3Ch z?tkqUzx$VnTa_OB??s-QK)ys)4N{e`?h6D8$MJj?gy3Dit#^WE#x7C3eb&vv00A;0 zhr6%-vZ~f}A^xF5;t@l_3eV#j7YjN5@xt2OsecGsZSc{T7HXkhOXG z6qx$*VuSjlAqg=&|KjaogXuHjlnc(t1-1dfdoY_u#4!uxMb=~&9 z#nrQ3YUJyfDhl&Z=Vt^ZIWVpvM@E~MPFE8?|9BDWj7DvLF-mrZM9cq4be&=ZxnR_E z4Gq2Ol^7h`9HB3D8J!}G75u3`LCj0c*qjl6g<$wi{TZ#%k!3RqNWO!U{?G*`(s4e8 zYzGf?Nt0_+)P%i&VZ^PGb||0MUZX}JPlRj^QO5VZI2%pp3|O&Tv!t0@KcHjLFheFN zOeKo4*ai$lSRcc=XdcOu{oX0D6(yweCb}_acz#|K1R*-Te5d~O z{mV_l?aEaY#}kB9GXFyJrjY7^hP!;C&UnUarK|T*c+SV7RFG7Fe`${oHJpKJ5IO)33KY1C+H2r}O z;nc_kVhB=HPLB-Jp0!HYC5<0`VRv^qFr(;{s0y<|is|T`m+AUg&X_!GhKd*HLVHr- z&I$nlPB;nIGr^~;oAQ$>q{#R}SLfr9Dq==yBz$kW z>7BXplEHc1L)l#tG^HiDuSHPLg_~CyMXeyyB6MEbL959*G_Id87*+lq24HJuVw;@`jn*gjNtkVD%&T59J8goWQ*DMs@FNt;SsB09>=GLaB8N5g%Xz94`7XxyBJRuf2 zKN~^8VJ0x`ly+E5g!t;ksj${vAj;B|J&rYn2W_cnIOe!O?H|M|ZFOBFSU6#GQ-S4# zclOn%`uz2@6R|FZCZc9=ruBN4%R11_7zY?@74?nTUP&RYY=*K;OM|{zu|^#!F7BbDw{b!c0$2!d%o| z_`lJvXG<;Tgeg**@BZ(BoV-LNQzJ#LvI4wwq3DbKBe@|!?H?E51wipmkB9Hj{A?pHNw%68Y zIn1ErAF{~Fn~bBBhX%9{6C({p<5uQDq!BwW_52P#E92ghL$M?D0h1(?a;4s~?MH4$ z0KVuaKPC2zTY>TTVt^Pz=aH9!3J}rd`&9{xGwI0DRsE9XFS9dXw>D&m_pe#iCy`*( zKgu)mZ1-Jd=?7kx6`uqRT$N`mssz=^g&+2v@TGa9bIbO#*pE{>*#imn@LO3wYC0ju zRlWqQv9+5F=0`Fh9iQ&L;3RSKTlGt3*oEDn3|dljnqqP&=!_KH3I8C=ZSAQk%9a3Cg6Ks z6UJFOg41}_K{lph7@5){ewL+XlUuk}270D&s6*Is|EX|BIkf80?DR-!q-gJ%oIpR2 zZ!C0Kt|TBY1(`Y}lbH0Z)F@!S7Y4d+6p;XQ9~*AS3CeP?$YwnHEBZV zG%(5md3hGeW0g+YUb58IT5%gMqp?|Io&M1u9$~#EjsKe8bIW^+X zVmPdi4Bh`&OseUMP2;PHaDP(p+I=Ot?do*4{9lS-!Hl~iOY?!SA8BtPogcGBBJiT> zN_4rK*h{nOj!MqVgE$5h1TZf&MrKo+zF#ECW+`xS;lerNcqv3)mvrn+1oRq9bz?|I z&@o+S-r$1zH_4_qp2QGpkO0M&j*JNY3N>YbEm}o*qD)tu&j>eDd%UZ~#O>ykNo@%Y z%^@yyeAZ@de=(_|EJwfADiwM*?JW29;ZA-G^2FDs;94|(&yGjp!tM|@&rHL8unusz zUxmhNYBs@&It=uuZWu0|EmffpA6@Rp7o^)OGM_^0ZFcJ=FuI8{6_kIkGp0F1wBB(R zB4a{$q!gMR#3DNgr2x18J!#XZ@~#tUwcy=S!W#eF=Q?L_!<~nh&i_5+{5}`cCa~B# zq=h2~Oqsv)I>az-DE}>EQRSNpNLqG7EiTS>oy>PIk}NW;`0ogi7(ueCJ zEXb_HHEkPmLfETw{{0!vO}s>+G>ybh_1ENaganJshS9JIHicS*h=zw@j}F6p~TY!&&Wu-7MPw z_EudF>GP3ifW$PvnQ|tPXVBF`KTYizy{(h}@1WP?ui&$38>+287ZWe#S*N{@hj2T{ z2YtVd)Kh1;4Pf7@w@EwQ_qf;O!CUS-3#H?4V`MLV{F*!Ga#3m{a)@t(dP2~Rd0@>b} zra5paJk$7$1?^PPT&INGhg?)ed+OHeGNfo99)(6+RSDTHOTR(wrj;=Xt zM}BipRv6$zQ0odvKv>l!W7)xaK2G1DHQ~TyeD@&+HLisqb`^bmFQTzro+gBqcVuR`^RU*}koub;M&j&TgFl*ZGT6{$o7Z>jwoK0)w z$g0-#qfB0=XoSb(KYwn_gGo&#t5f?y28CsO>h|GLlpF_#O@<>K_xhlF_nU^@Oz``H zT(6nF;N!MIYbg6Jb{PJJG1;tLX!)W0eRp#%Uc>T~c1Ut@kld=Y4!O(?fYF)=W)sX| z1Z@l}FEQgBHn*tjHA7fINe?Asxma#U&dgtBJ0ADgY*AI|eit~_|JvV=2vK4SZ;qF{ zx9y?Y`}A71j`wtw9OHg;re7Q7R8lJsxW4I7JW-IuOrvF~j(@KtKqr4%c81x`pXnp! z+R$lenSC>sC6SgcES2ouJsWb*Q$IJ#&k^A9@D44%_&9J?@60G@|!h{_ik>>1*&J?L@J@iw5p?dhxJjkfwr&&c7SM_aVjxyTUFsT1n zXklU{NAs0BkOU<2alrl$H37yQ8`EN}F)t(n^Dh)XjeLr#)i3D2zuu+%^W?!TyGOcA zdpal+s~=9@9&@Y52E#yDzEr+Us-$TEh$r7Gg^%qpy;)ic@btf{w7K z(8%KGXNvsm>ool|XEs-c*e+VaOVb86$+&*dwa_MJ>vxIT3YJ?w3(Yt*RrK&g-qV+_ z8}?e0RqA*}&PeL=iMJ*x4Kg&BP;W2#XfpZolti?U**unM++k61?Yj08G$RF;yb)PBlB z9hbRiz?(rO;xINoRlKOwo@ra214O=~!4E;iPy7(Bkec+pGSkoh>TC4@9VaRC1jTDQ z$98*ku@zepa#se&23TEyXaponTT3y;eU!@P7X%phL};?_hp4SU8t`*H344wjn0)3+1GZdlXLn$DqJIK&}*sAK)HTR$I^}; zE)|t(D}CoTdd^YiON(c|$wjs9!tK~7G|k|_>&Y_=BTdPz-LgFfu^{Jl4Ig(0IKYx% zUG|?TYh#L?EBz1AhLf3RRjD~zK>t$5qO>6jsPjgb(JohEY3+>@77AyMXe#s9Q-u#5 zH2G}1#z2v4MZS?1#QT+Q??s7n!}kH!A80t$3b;gvBH^PXL(8KpgX(~m9uEJqQr<^E zZh8L=J%YyaDnx5UbX*|m^=ZgD%9P?1mW3PiLa)5zHmRs;{WS27t-14S6wfKZMw)2? zp{c+MlZ}t=rH)^$Wxj#Yz#gPPI|0(^5C_I?LgdT5qV(KC}&@14|4Rzrimju#BQ(N!$bRP!@0)YZ+D zlRD=T0Vp;XkBtcIMEhFgse6f|Qg82zCLxfY*0^mG!gDK%ZT={962APgsC=@A%T!Xs z?BhEVXN@`{{M!OVP=PfN!}HlVWh$=tTMNZrt48of;HEDRuGmZN`UPDwKJ*5rtYO7E zNALI%?@0Ug7oIG#d*@O8Tw&mMFCBh&F{tWhHeUn+m0&(p@0bR_FxEGT8msA)qigDC z1PrxGNkRZFgmGlV!B~q=^sth^<|Vnt*bOzy;|ABJ+RmqHgQssf7o!BA5rC4@(+h15 zBDx}PIjC~R){6Xj3K@8ezE_(j&58krZ3-3-?*pWUz@1CsMwEL(BD&%&iB$_$j0P-P zC1oiBO`kq~?f)vBDORZKnV6J4W)mgt#QhGBR`{MiM|H1Vi!QxZ6gJK8=62h}46(9} zVAvqa6l0JPEI(mp)TsZ`dC*T?O6uSGY)h#_*;VUK(XMiUde0}0aoX@`J!_7OR2Vqo z1kKiXsPFw+^el zTpKDz5UT7rvqv#FMa+K~_1fdee>s)f(=w>(U7a+DU;<1xTv8dfZueHNj1-iQd)uSj z(|lL2O(PYVW5ADmMj)MjLs823MUCjgw5FR|F@e)Yrh~>S6gS90TQ?tY_C{wr39D3+ zd~J;0-tx7$xfDWr0C;9D+qNgr9{jFO#n0UJrCupAlH~tPb|7wVP1&{U=$qI?e8UcK zTUMrq7`@L1%mYhxA^hXekFrh%#l!=J{jGSBFZhkj^-X%qeSP(UETMJUP;RUB9AQ)g z*{(S|AX1dvlL`ioMER5%*@eU~7G?uQM&_1p11Vl}_tmgoZ(x2D`zZN z&JsBQ_ya;<@7xN98YTM;)%S3Ag^wt~BjeHX^Ns`cUIz3D5sH2jnek`d%Btw$u)j7# z_G@~?%_4@PV2uCop^_`rphY8L{U4N;?FloQCINtq<1_B9+L$x`T9J%3g%U2b5(J*4zwGE z+{YvD#y6)VH*t~65fsb_Doxa$HToV3>(HHm-uJnA?WBd}0%y5x8|8GQEHsqox8vxn zF0Xs~xW^o^Q*(HSa%@(2Kt}wh!Hjj+o!{DWCDwTA7P85QM3)=Xg6E+wzHc=IW7Yiu ze%_Z|U8Pu8qCJMR`o-@+qAOJ19I}JX)E|gI#1JZ2LM$~8-r@Z2Y$EIr8Z6i4?`9l& zf1G85>8xx0QB%kf^G!>YYXcETo6&39-Y{#->w0HxY`U1PZo&1ui{&==J@^M2ajE!E zknaO9XrON^x#cyoKp+e8xz?&%$3sZ|svGCemJh$zJ3lE^+`wwqT$@RMj3XF@FXkuQ zm+yST^tCR4ySqm|nh2-%uH6-m-fB$tw(h~}TqtHSME1qu#l{({i)Z|1{QMMU+kTd7 zfkPbJs~UcCXB&A@)h5$mE-96CigEotp}6}NrEvJ_ulu-gQhLN+2RuvUi1OLUtjL1W zws>Y(%jHAw9Kpqp+2ec3C{;u8L`bk_H{3gN4JFdky&=##@N?;I#E;(9-Xk7!HO?C6 zXYbQVD(DJWJZXpIhKg}5PQihaL#;`SD&_`dI@ibahya3TIp~2{9`r+d&ZIzd>+a&o zDGer5bF&&*vH=Xd@Z6%YOY)dCI+7QSl*IEQqz{Dmw0}}D|BY7geZ@u|ZCH0n&nIO< z<2k$0Y5Yd{c07K5GkvurqcujJTk=S?Cpbhy^+He( zWe|ExHj8VKGCPH>v|PPSBc7uKo9Gn2{j)|cwk~yMwpP&Z2lw_)rDcFHvXUrbco7=r z-_+1t_b6(a7@F0|+pb4=(pWd!>V7K<>Aa6`<_|b2p7AG#;J~hVYq%O&=S?%`X*x-a z#yshfAN%Ad7|YAZ9?64ic$-HoX(OF%Godj1gfCLZaeIIzo7p|vre11(n zcv%*)?HuO*50aveAQTe|t}BC`IcQi?JbZ@hjT~V4`H*Vctq=Av!w=umAUD;a5C@&! zCoO)>GSfXw=m$6eWq@BJwH~C$-`Ap2P5dGZCOxZEG|-o&UJfWMVLE{>Wl8ZBkk)J-XTJR?U_Q#wi48_6f^P-^=go=J2tJXUdVOJd_kKTaS|E`_h-6loH z;~@_Hf}m(P=P01}ki*`lT}7jTwm=TZjmV3a>v^>ybX4RQ z4PPN=4xSFjqxDF=Zb&!Vxjn%+s*sTOqaw7+X}6eU$H7W|>}~$a(f)^a9OZo+;NP_G znEtIxHNBO2N0^pP%pLjO3#cqdKL;}A%O;E*3Oz?is&oU$5AT!}aSb8nt!&GLO&eUt z1a4CQ5oWE2=UkQ3bkv!SA$Z??_2f4~=78}hBBG{mWN$qClA~-D(66a2KdyzXXI8_>-fcv&e0mjn zq@ppKBU(WjQZEh9^=FgFuK6a#9b(xyeH}lBG9uH?h**5KI|-@Bz93ab-SO_HYQe2ejGU1vO6eUjZks%d%5Q8FlXMAw_sx9F1gE^oq{yO2no@FV&8QJL?HEk`@fuu0cd z>^!Om{^Tv3ndMNk+(^&^?uWxh`r{W8OWThAJTpYlqAD|IIEHpXBmnA(=RqJl@HH%4 zjNd}Q6R7h!X(pkB)EF_Gn2C7>?&(Lhe-G2rJ-Gu$NqT0v6R0Jfhy#{)C5)}zL}v~V ze66$XTS|iEra(8jpKK?qWal~g)7tB8&i89%htFXXduuP-L;xeUwdtMx{KfCDGDEXN zG%tjcW@j)Ix4NdY(vRx&Ke-hKlezUd!P zE&@oDe07>P@0mY)f^FHz4WgwHe0gUDe2@M&E|0s-D86-_N|x!m+`nSDs$R4XRP>Z< zDK~#Xj%@KHR6@_5}q*q5FEf?pVlsD3iDyJkl zC{ts`A4o3Z1eW29NChoM<8M9+v}zG$79kEdmC*(h!34?Y7Z*VG-&EEzcF8(G9Oda! zi1)GXB;NkoXI9lrwNzd6vuWvF^;L#5_KY3qOL-|KOeuiu&Z_3G$7;4AT6=o`L8^6@ zPOTUdhE70jyF_2}AfBGdhxs3D4Pj0=SZ_M=WbD>WQ{9a!Dg`UhkpR~Vo^^Drg+s)u1L|4A8mwyz2wXx|)FW=WLE~ zDE@0v9heCbinz(6EB8&_4`64PX=i9$)iU`txR?$@``qW#^dF6wpTP_OCy%rb5<}Mb zpCj|q$V=q#43(91?5#nJ33=FUF;>`HbBq59)NU$#OyMEHMpk3FX zj5i=)o#5dWTye|(5Q*|+yAPar=5oqW5-BmSrWyW*{xM)kqa>0uvHhd`XY2+|7R7L@ zd<<7w*cj@+BuRB=ZS@7QF>U=r{& zN|Zm%;3^f{gQSA3d8OnSL-o7vxc<|a`vgeZ#+BT)k~r0Ujb=KZ)v%>&rd#8-VjUHC zF^OL%{#1rN6CasN6|9YIOQzNQq-NUFwwT6*@F6r9!MX6|CK%Xl-kzUyuPtdao1t#u zA2WwZEb6i7cd^8xDvJ`VBxQQyf^g6>oChyb5hDj&N>lOr=i0!$S$#T3wh>Q*dTcVr z)<*g$@0HRyU?9ejcRxP^B?~>f8{U0o^h8KJlP)B&Zh&8dv2w@8$;@#$ew|28>D~Ch z7~U(7m&^a|rYNC>$2Qg;qDB(C^&G3;{d*9wTyl$1-6}u}>v^2x2jV(uCIQx@Q?}!3 z)7e>x)f`LvlML8*PF}4GNv&+r4XErm;NX@`6C)3KjGz84|lyJiXa7v+*wus0-J3%xI*NqR(LW&H&>2(2dgwVc7-2iNVPn$TINt; zo-rb*^HBx1Ge}L!x9u6E*srPO=eov&F6Sy; zH@0&MEUJ^-X~`05B(^TC;TID0u~q{K&jCC)LXDr*Pc6x3I{enG*TyleiBA=nnuOpB z#Ap^##Ze%w_l-vZY6(^i2d`{bj$f#lA%7)u+(kF9in-WR+x23?fo{Gn>CJn;qt*(f z@?+H%tO@)+0*t)%$|tnLwcrOCBL{)~J=pKuMEcTo&)(RG4^P?Cd$2U3oFyQk;q3R? zn5z_mH~nj10$|C|O+Q`nDvT{*1UWo(X`ek`Xamhl$=T&NlyI#={)gxDIT*n&Z3@Jsw>CFd zAY%pxGP4jopo|CNPMqUVtJF_9&FsgX`yh4^K%nHSh4btZ-;;V|Le!!F1e-CUlc2AN z$5o>mzXNRrQ{n6e!6I>QUo4joX*a99>;ODabZTF&XH@ar{-+ryBjXzA?sNvig6B&c zg&C_B&$MgaXHWNyC(U+ogccW0>bog!&(yV=SgQC-Dgkrqx-eq+m;#hYTDS*KDG0)G zIPG)$%yb>>TZ4XRDLpSLiK48)yV+-SW&UL>&89ySR@g^fHTRpUV2l2t%Q7AVRt^ul zogz;};m?aC-v?zG5bWtKbuHtn8k$X-803g14h@ z*x01s=#O!xE1Af5Z$+jDj)E{b*L=5@6oaB&t723X#&O>lv=r1lur* z;lz!qZU0};Q;GPbG*JJdm8r}Ik%k< z6O0d$+8Hbh>Lw)L%c5Rw>A5KQLU4IaMnFlRNProL{%^>C6CAVsz5IE`){2v|Ree!s z8&dOFUbsjL8CXK;fIQ46T)c7>TB#O#>VYvNoPpbdaBnyP92n^l9sm%+($3ghTfeI2 zUP#;f;KQ$EuxqN>eW04TZSq%Pn>sQT3BnY*4_20r*c5IlB31t#ko?OUGaFeanJUx) zU(B0d6vdAGap+B@li1HetvI55&HcTH(=t8*F)d0eidtNR2m01#bdsMIF@uPZKH4}j z*Q>z~KD#}QVm=gzI3-l!eW0^j!+e8?HQoO=dz1gaS%Afh0}Te#r8gNfx`x(5?j#t7 zZ6nJ5yJz&$OWo~?occodk80qX^16iawitMko3u#hs8k`xD9D`f!J-Fmm1}U|PkG`FRsw)F%z)WWi_;Kl+GS8;ZZ&@ISE8ASj(N!( zk?(`oW0npzYo*fmCkhY~H2Q^Y^hBj#$$<5AB(yXu)*quv{GEWo@;XWi(l|0ML;PWr zKzsG~XEy22>1Vy-D<5-nnaSpBuqs-2o6z2nOwgch^FJQid$rJ=bezN?IU(F;%U2znDUU1B}(}LW9b#}vtgTZp_ar7t>Cph+>AW=h7fvG>7_O~@v}}e6OBfMbSgQ} z;L>bC_uxtWy0=mwS<0Wo@2r>Hf>rd?OCfcy_ng6u^1DQqajS)wjpzytk<=K$q>@hSeO|XSx zXT`wfvZLp(KDKqgmR@kvW&eL5WrgCLqqsh9s1nP%rbcf{g)eM4gjFPRSxibLfc-q6+UBozM~9w}ib_BEoHwy%vlWd}ocC>QDjM>H zr}W1MI&&}>v~Js9had1?U33??6iUt-&!5N?BPMuXkr%&eHMy*k;O~ zn|HY6@p?^1X=!N@c2_3`EP;!Ocn%#$Xu@{1`LMdmz4zX2gX?Z)EbHjOX#7(WO8DXzNn%D>~0?yT_MbqT= zLrK_Zn>6o_{Z|bbS=H6mC&Tmgn_Md(Dc*<33*hH~*ZkLexwAUan`jaH@n{KUJ@w`^ zQu4lEy9ddkCR#1*V0CfMe>NDC+%zlgcw6TC_OHd0=v71@?8&$-DKLZbHX=-2qlrX+ zf02I;Q@?EH>8byz`{IVh17%x#1=nqD4&&pt2?INbRCHs+^2hZp;EM;8BejI>|#G+mx8c9K4{T55^+aKAq4NzGvtL0AWG zH6ERZBQA9Y7;74$G@T61fQZ)@7A+}TKL>SYXUYHg|A>0auqdPMdst~fLQ=Y<8w5sD5drDW zA&2hn4w04|y1PTVTUui1PU-G?Z=UD*{ogP1f$L)CzR%fb@3q%j=bTsUISK}?A;<9q zCx28R{cT&LDHA4YI}9&PEO)DBMlhyk#KfyoCym~L+ zA5$-5Ghc-FwrDMkdDu+L-5lV!w6$T*&UweZ#k06{Ye)QYm!bb)y2RIaoo=@^W()D* z6tSo{1xT+&&nGy~iTB&7$ibRJ@CXz1lY2`^7RB-BN&QiN8LzHYac8-A%gyBQREnf@ z$S_|Mps*G)R}$`)7d6^(!338(vf9QdJF?C|J)**hlogM@LdF-cI;)Npzb)gB5^pWn zXx0(J%$_--yKRz@^O~zvNGHq7y#|dLAG`%kh{3Ns(Lf~8uV@LS2S<&PwFrpsO$Z33K_`Fupgg6FnQjZC!~0?Bu8$ZVPqZ7TE-<$Lq0Z(wV+!p27_#(t( zOTTX7=CPL)UukEpP}S)w{Nkwa6SzoJtE5X!Bujoegf9J0=9d6P?d(a)Hxk?5e2g4Z zEbWdK8;4VPZA?la$K3T}NBoOzn+L4*W1zD5J+Hh0x1BWc=ch-dM^0JfvnZd3fZi~I zf(NJ2(9nOd6173y{<+$IG7n}QH8toFr{ZBdyYYdUFH^&YiIzE^cLdP=T%t=WQ$r7q z>}&kh7*P+xNgvC9|DGakPK`5*f*9)P=sZkFu{mwH@Fmq+%y61b4oR zsqEIs=2RRqr=EQYQI&YRg+;DEFzUoGp#AUK#@1X(^w%X;QC4mDc9$;HLtse95azEB z#1Paz&H#%KEkN_n8(-UWj$ANMUcM6hIb*SE+{fpc6@2$OS>VZdUcYa-d znA4ycZ16Uk0|Dgp=`EalB5-|n2GUr{&5G;KPdLF937oYN=jmIa{-@<^6@p)IJDBUyT??|tAz=0VD$Aib_>*W zE*{k7Z-(5VHrqdHYGehReVe_V=kuNyYTNlds9=Z9NH*?6I|op$>*Y^7sm?J_iwMVa zqTTi0H(p1IAU3ysXtjIl6|DGi=!UWE?W3q(r|*2ti0jvGo5ryxJEm_?@Ig6b{)^Pk zB~n4sniR{kAo}_Mx9WB5sr>JRpELKB<#c3K?ff>90STi@EtW_{d9T#gARn;}KLuhL z+y3m)Cc3L(^w?Iz_1f1us+spY_{WuYAne7YSpq>YXK0wAK!cYHS7L>V88p>Zchm)n zHCZey)t6W(`{Jb#`dYoQeN;AhLuTV46lTPH72X?Rm+&7_?5UB4hKAbC3gbRd`%s*6 z!w_+0ZdsOmDwX|edk_LY!WPm0M*ua+_!8}%l+e=8gH zpkLw1uk2}!F}pmHt|oupUMG5#>Vu3YPOIR~%1vs|q$hry;E9hn+YD85!`cWjt!ttOR=G|;pcV^b?@)Kka4}>8t?B}!`{IO{C%{?&z9P>HfHRGDv>d`i10A@{SIKI0ut8gnA zty>Jre9`Mck>{VrHA&GPNKRQ+Rl>s<&#dfU($_y_Qpzauly`{BB4AAg(ZTx z3|)K+3K5PcnD1_OKM;%3B}@&p6BEarU5wvk6oPf6vQo{@znZC1nrh|hQ?|Y594-I1dank^{SJa;1SDjVwpW2&(})c`y9@Pf0mzuLDsH1f##@8&!zs{t zw-M`%CEf8I9n(Pj1(it%pd37y1U{ncN(lRA=toRbMwY6R#%!9)cwSC04&#d?bccA9LOMy{n@L$~#tyiS2lj=hOE2 zezSLr9~x zmyVP-!NEHhmSpd8?a2YdUDJXHk8tiAJ#A8@`TN=h|NBuZ;bv5xDujOcKUmr00hK5s zvTud1^xHywJjiTr*R6y*wHA=Kz+RUyVcVH8jNfw4^%g!(SE9uWE`Tge0Dx|tWk2L} zyMf(rpIC&uccnGw+a)1;v444rTJ1XOjr+m=f2X;Tj^V=;DjSkQwme(d(b!&c(08WM z{dUH2+*B;&4=BU~Iu1GGJ(3|bocNRp`pmJea%4l6k3Q*#3)di*O^*h~jS*t!84;a4e++0HnV`1kESfmj&!;E7#^R?;iEQ`Nf zBWQNDN+P0Mx<&O9cgs57wc9d0OHc!C&mdOnue6~UL;59a2OsFDjoN*5coL>@Z0>mbk}=91m2x4STD!pk3HhyT67oY<^?hSs=w(h zWz)X``MbTn*vfs(N9-^RVF+&TlCnyAz3PZDptqV5W^tL?lcQlE`(1h^ z8K5S#JkNywEu&e=D8!$gpSj|mUau2*)wcXymUhu*v0J&^9oGS%lT{CcOwRcqLqr+R4p$CU zAX;Gn6CnClJ;?}sl>{;b%t)s_ud$KgkPS!IU`vQu&EJTa=S0W;%v|!DxeER1tG_S&vd)ACM z2j~_D2=vb;V*IwAuMhr}XpdmFGC2F`C}&Id5!gLs%) zVa^zU;f-&#KZkZd-8L}<>H1a57ET$7K4yM%+w|ReW1aqmv^H+>&bu$nnk8MKo*qI= zPKP1#)H+mX!xmdp6>p=#6i%T%CHpg6v`T&Jj)uTwJ!Pgtu-Q@U@(E2|>(VBgwkopE z;9w3ytevTAVsOw&`|Ym2e^c2rVAr%&(_$T6JMj2`^q%=62l)m|Nd4w1eu`_sI&q!Q z(&ZA(;t}iiaSt#`0dqp+^xo$H{xFDU+R>?!hxvqr1>gdeY60sg|18dC zOiTOjuJ(PRC@6mPyk+2V-Brp zWmr=E<{18T12(ixBIIQej)({Jr}xsA`)>IYmz1CpfUe}~g%O2|$79yya5KJmnDU#; zBTa#yrZ1jw0kREMjxoTP##>8K7bHFe?@Ip{#pN>q>%eN5`N?_;OWkIqwON< z@+zFnvNhq~H+#I*v|5t-3$;Ik^QR8yXB5DN1O%nQEcz8GSShiWmam9nuV)B9yz;D? z76?3{nSPxpPEzHKys%)3AGa1(OB*Pj(}U#u>om!~pSns`-?M}+nq}{ms!!iG9=azc zXj;zJzE{tpc<20sQh2kWbj5Ie`@x+qozqJPnGta@n;1s$BmI?*|8krD&Bd8$I;I=h z=GypID!FVZqVNvo8A3m?W2~uZ;4>B++bvxUMWPG$NwglGP>Ep+O$H{1Dn$a0!Q2|# zsX|jgLTv07*%txD=&`X$jiF`6$X)YJybeSb+3e$2XYMD&6f0b#KoVb^5c-e1@+Fgu z>foflE@d98zn;(zn;bUD=pm=C6h8c?mIu3ov(@O@AnAmTfUu&Qm%3X3?RNqlWKUAS zMGTNaYwm3<8}2<-LQ}8IG6H|4nrfF&f2tR_Ps z5o1AqM@5{GN$|b2>qg$7u~X|Op(}I0Nl?&j!+G+J__qS_cw$`DmEZ1VTa9qDx=(!L+B(eUTRqp+Q&%N$_D>fA3@6*Geg z@~M_;K}luR9oF#HQZA$~LprHZrZqMR)OVexecP+$o2)7QX_h4?P?3U;p73`UblLl} zo&i*<{^=og)E0E+m@xxPd^!Pq@>5Ro150n^@81VbSq&HL_-N%8tts1}@x9r?85YD7 z+EJ5L${6)#(L|5a;rxA5#dm(5TIom0&PF0xFfm9|_o`1=iHed?mul`yEswToXNuf? z)%n=V?Op+RJpr4!NA?+Uo%h8@ZES3Z7zeWoIp9y-t5OR~c>O4p;S?)tcmZk%6+uKv zTu&leOAnoDx?WBNgz%LWDXwiJz?TufuN~TNtTzaZe>E9Xf1J?s@oz917Qx_8O$=Z* zkl4SnQ+vJ|i&#;?52%r&C)Z~RExxEt7rfCWd?qM@?FO4T1PuMWZTU`JmgU$Kiv1=X zjZiLOWD4v0coRe#@P9(uT=0u)!R^Z9^mgdGxhr+q!i?~+6DRiC;C*!r}8|e0jz`{it>SkG;-vJ|ir|tD;?#X)WA58{} z;1p+*D}Ep^O4IAPR|Bha`6^N#w?f80OmwiM&Bf}z_`C`s$+WPK)vgQt^4<+QYt?8s zDOJ8@tM~CR|4h@qY${(v#my~q6Cw~bH=dYGB*;Tur~R!y0ih2n&HS_PBXZSTc&nxv zuZDRA=|l0Y$1q|O)ffsxAvdFc3eHeIG?_>9R|+{~GL;7tll}ioNDd ze9xWLp##Y0|8M!r7TBSlNH&GpYT7)YXuW-4bc6Rt{3#TE9^dfZSjgmlovD$GaC{j6 z9W~8jGOF#R%zc`I8wi3UnDhVMA=jy)0|j-WnHQPo?&5TnBIGOko%=dgh&Lxj^!Q9q z=jZpQX}?ZMMO*cfI(@Ln6Hi0K=|*;P0@VQy>enCrZ^8eXxt`v};rD|INPsB)1pG)$ zKzRmYIt$aJ6O-)D2T#_X8yiAl0BR}st(+z)YjlJqE$+aULoGgLE5yO0`=681|4x#? zFWN%oIvU1b3F*1W8HDp-U#hL^%Z*L|EcXhhFo9j-$!yr2doRkpNz?v3Y08Fc7S^AA z63TMm;jtsnT`2g;b}Vql>YaAW8E{@idHuIM8DH8s{;WEBUiJS>aV3D16JjR2R;^er zOJ1*60i#En)(QJbHxxYY1EkIWcD^+ZNu1DrGsGFOeNdVhKywPuO1J6Ree?4I{J|vs zW?EZ8s%b|=sgWaNTM6=lD{n)d5m{wi1X+qoHWFF{Sfl$7JGOSqO>E+J&L>U7pE%Qh z_Bon=^J9?&)~dm}t=9V@7$_h(n?t6A{@;y*k4rAFbLH43KMHYUe$TMQn0=wg0zG2b z4M6%7OWb^iB`qB~Kd1K;S8c`<@d0AtP^LWvfYpAt9fx_bPM@iU8~wA4Jr`EOfiGjk3Js0>-T zM_<&qMc2wWnpZpw)pQ!dho_0;+Mr*h?~FzgSCrFz>)D}4YCw46*J-}0y$Wc=BkFj; zDrdKHT@V;xO5rH8DGq4L*ZgEBjN-YJ`ppF`8gZ58ANps1=9L`&SL+4FBoTIk+0BGH zw%5~@bDLw7J@i}&5NV`e6;`}Xh! zowAJ1ciR^(%%KVZO#^z=4kE8A{=Bw_mIt2~{AQA_Ez)pmEmUkL^ z3gMRaY~1`#BN zIZA!#Gc)!a>Y;f*BW9r?DjlWqQ+zOZPHVTkK8F#Yg-=24@d~H{x$fo5oZB7J@h5s8 z^BJ()c_0S4Vg!=m9(sXgk~Ui`#KN;gVZ|Rg*`kVEm7|JazmU(Y++O&d1FVEsnBAnH2*t*o-{(gHI);^r6B;dE3SOR5@r&%k##bDHH^ zh4x(F1Uxf^?A96nGBD;;(vGJRJaffJ1RNm+5#$L;XvV7B3)FzJ{Ncu7*N`+N#34!e z2Y775Ubx31{;SpZrhPlUAEBNpBq6)cgo_#^lM8_SdT|v+=#y23L`!1>I9u3XceDSX z^rktzH~BT@G-L$`tQLUbN{FOOq0P?!*e*3>!xsnZ@%32vm@m!G>yt!y0oIH>+63c!=2pNx z6}#;6>-GuMwdZ%Y8O8s29S&@IAv8e~0|o)7dEWRx@{0q`x;U^SZKtlZzV*dFba^R& zq^yR2(hO*1yj0vxD0X=vQhfxo3oq$NV$tTu4AypaB-tNrJ`Lm>dBiEQD^6h`bN#=m zlBJ^}tR-PsQ{8X|+%SB(015V5#I@o7yZ}3wtHhkvaUjH;cPKPA3;VDO;g=WUOM~CT zAz2LqeHOYWCP5(iY1i?x7jt8yaKAsQeYqwjM|?u{bC&!?7&7W|nIgSEY=R^&+hETx z?w1U85L>9O{Ab*N&_7w;wSS^%%~;k6wASb@{#a{;qyEvr#r>s3k%y>7Z)KJOaanE` zuI|KgIN)gJN@>Z65+}2&=Fe~&8#WQjNE#b%LDm~0FX6->_^9!tW2i$4 z!&1q09FGhSDooY#^CafOEIxtGVoeHEmF1Tg1GB7$mvV~lzDO7KrIq{E=+c8N3~qPS zS#axbEovE>+I}a~_7IvkaAYx^du+rq`eMYMTl9PKFGXL}3*WF7N9_fa+e6fE+Vdsn z_FNjiD3DL$V8786rN_Uy(8G*=^;>z6sY7iqyGb$-Kd^nKc9*bBy8_y!&wwA`XeXv%d)cVnfk^v|{pz=IYa%Hp0QdM=iVABx*#Ot{qsy1TuElfZZHR(*&U zxLX=iFbg@w<8B$56R#1)}I)7se z?)5d_2p|1hS6(&H%UU^o&o!-qt@iTxi5z;TL}?RBJwbwla~(W!4$g54n=?OL_@+_sCU&L{4CoY1%&zYT=QV_!^ooY!h`CceSSH+X|9h-Asm zm}4J#LicT^kUp&S7WN}qOy6ExnH*=f9scU;yZ+tB&j|m#UN7+k9cEjq z&7ul0pRlRT{iu||ZYk8)L2VDQlHtnj-`_GXkK;F21+GVmcW6UhVPxCcyi4>hYZUQ5 zzHDh>UpCs(3C_U9d-u9+$3>veRaR7MRcN)XPfYOnHU}g|YL37v-4P$n)2cBQcTt*R zDZimH%b5z=SPdjqNKS*3)jYH9>D>N>g;a6g&~ajQRjCM{tZsp>Es1s1@7*L875fMv zYz=M&+&Cuk2|`ZVFFCBt%YXUYk;Zc9ygBTjJGE-TS*yE?a92Jjabt+zB{GpBnT>mB zY|*bhB4=C2fg>l_LI|v&#lD#OcIoZs93&j*apN%QIhQht$k}EFd=;xsPQPRDZQ5rK zuN3dPM#-mD7x0$}kk-1Bm3utO4BKL%F6P~%MPImcLJ#caZH#eCtY#+Ud7qccz!JyZ znFQf3jpe_P!29zTrW#{%SVE|!wn1S~6^Y;#JEQ$LCru$)kZRC|?}ohb-}}rXrH%|- zZ<-VN`jbECc-8$YrX%uH3SP+Ux^c0X^e($Sla&C$qt&Eqh>t(cv%EsOUXJlTb*7Xx?^&>--sX7>S<*$Q zF?1x%4Iy65DgXKU{@h+$LwAdfZ7-DkQCVm{-IK`b64l;^)EV zRUIt(ZxPi_Xei^Mj|I@fUm5-GU*d+^Ec86s7k7d_#2cMvM{Z`PN8~px&`IpL%%u~2 zuDnKL+l%r(89I*WNoJ)OCGcfO9jL`3vU{RHt1BPcX478I{AQO1ddX!m#p1BlhEI{qj<|=; zKQ9SRg`KpHG?R)+ndvl(Vs#bnaniPY-IXDg|o z#b2Wr13mS+A)=Q&ae2LO$cm$OyE19Zk7`;Z(<6F*i^Zd-M6DZSjvptAQFVR51=rig zHcZ!=iN=Yo9!xXd`gr%pvZ3+rdG`vE-I@mjr=)zic&jK@TkjDN*nip6IlQ>-Jof-YxxW?=zQ7x2Z=i0zsKrks%YLXb1NmLh1Z}p!tLoHMTjd^q~$F zeT_xNd7~P&pRvuLllN5H@dM)oH>T!~OHZ-9UqS<#?l?wVBN7{?E=6(m~ zuF>I9<$?;%Q*{>K3RCb<#|^1woV@$-KIG*+)Rlx;bPEn6C)|_D)%o9%M3Vde%}=>d z|6lDit*7ma5BBujxuC^S-bnLq4H_@@bY&t?q`j;CmXqu1XeU$J$!P3@-2Ozc*c9J9o`3 zl?%G_zQ+sKsh&x-Zw!b%@}(6G5;8KklxJ7QjyJvW&c!-ng=H%0AG{x5kp8e_%Yu-?|@ zoiY5v=xw}}_M3Sj^GimMy&FlKWCqvlN~twM3jGG&Ur<{_tE+-dt95Xx_Y)o4eR<~~ z(?#2d_$!-L7gYU5vDnP?l}q0FtFZ9as|hB0AIBiYxJJ0G&(P1&{#+BA<<%ceL*#=e zlv(89GeUpw(!KM>cXkDee+D$}B*4OW$ilmShK~86RQwa2jx>V$x{H9`hL0EU7~In| zx@S#9>e>tCx=u|uaqtDjCn;z4I%O7-^_B~> z{rjWpm7-b#SiD;kBpc_CUG4L#w7bWgPQAsGLfCOYp`hc5W#fAWg(E~(yEX6nxOV0Y zmb5k`l2_i~g3%vo*G8CPdZs-0iKtkAQ@zw)<0}JeHnDLcKKjzQ5uU%&+E)X#yXX6fN?` zk9uV~TlMn?*^(ctE2CUnx@trYM1T)h>TGsK0c?XGvbTb*`TjdtYkR;Ux=<*>mL!KF zgsG!k+q0r2bq-0#Dl!JU_a_Z-&bPzvKFxp%)Z3hHSheY|K{PFbrC zhqz9;c1gyY;Kq7O>=h)|fx2Ns3}2N2a`TxzKg!@JhT(VmZ5_8;TRr!5PEJw{HCPMC z=VC)9QYMfb?<@$dluARRb!++*pW5_2shT{POG~FDYPYq6Bi#Q(`LA}1X6F{m7US>W zh!^ZBmef=@y6em2i%GF4ooe%YICkeDl1as+ZolV9c2sH0GZTL6oJFO2@VJ39n=u-l zBw&cZHx>*vL(x*!2(bNDWh^Jusoei{azBcxntKKd5ofsNUj2oub}s& zksSH#5sqsU?{TER9@f{%5kvfY=8MOHqv=p7tM*s>Hj`_k`*Ow7=PUDW9}tOsxBJAL zc*sYBm6HPGX$F~tDnEmR8-k?*d0&rhbN^$mRUSA*$NU$Jz3>UAA-6e&ZRXphRvF$R zR^UF`jLM((J%f4XL0${hy~`4OiTV`|!dST>lcAChRK0IjDQzQmAel^j)1RW3)|o2J zH!}O*s~2WI3o16Nu0Ur;Q3LD4Y>kJ&3GU*eVTyi5?^SrO*`w=_!Y?pt~qF zd`+M}zf+WoEP-4M1-o14=x*{u9RRnS>W)aV;BOV6lq9JB$pHT8f5=SQ7QN+3cq&Zy zkj$^k@VbwX%U#3c5Pr=D?)a2H{G))seZ$HZS0fnQ_m7r;+32tzmUh>*I(ohP<3he3 zZ$GDJ4AkQcHg-_8ZxAxsyGh5%66Ul<=m^O@0pZPy=#6hS$*)zs=^QoW6Yc$7n>gED zUgVRie&pu}l%3$_IRdju5#-8WUBbY z&MpZr(AldpjOua4az^)gg{u`bq1LCz%Y*)~Ab&o%S>reKaWO?@Qd^eI;KZQuN0?Kg z8-BJYYz}N$@dPMM_`jv=92mDEE{yd{q?TcMS@VrgMsH_m(WiAV>X`$)TpG5Bt;wia zZ1^ra_N4cQj#T(#W#*>U+^EUDU=sTt4J*MZx_k?rdn!*`_p@Gw?_1(_?IvxFA`%V{ zgBmKOaKZG~Oh3TW3(^bWmSeAxQ%tgE_}S`}_;y&5(xr^tO9dAN#2D#f&#RR8<|G~s z`KmB4?`@6n+?Nhx$IhF9XK@mUkr5=4>Q^6tHd{$PfpuI;5)_6l@wP+dBhGX`i+tvG zlY@4oR3{h7#cXs4Yc(kN;K|xneYSXX-&-v7E~`}}JL4Ck>x|#C71JOrfMWp=QpLt{ zX4JD$GuZ^`HDSq)#v=_*q|U@_;fl`_edKFdyfqWWt{4evwGyDu?L5R?y*%u5Mt5+{a8$bCXJj=w~7)Mh#EENA#l#} z?nq$M`bp80t?E(=kmZn5Xk$61I`3f8{R9W8Wom8x+zxnJJWkYU9DbeoWBCUnAd`#v z-0u&Vwx)}D6UXWgF=JKpPe!>DNSKSz15aA+TT9(mp<|LFl8Qm;yoj1Ro@&o1*xM@) zz6JM&x(_h7x6Hz@t*SP@=LgXAuu;lKk`mopytq1>$_BAJ%Z9|h^*V&(x*hq+Tq^SZ zu7F+vW#%Gp-hU5d4)4`vS^Efogn2O^O*SrX7o~P%q?+XSN7iX`Hk(kVK+=@AW4~L% z7Z8>oy?t1^I`$bd5*)lz=ZklcV~cDSzq4e2T?jvh>e*3|R3Mer9X%euShkDcCWH+; zMgiO1@wFCZp3#5c<_Xmzhn2i54;Q_B*pxCHVLx*tNgZl)DRe_mwaFs40rD6ux^Psi zfn$b^(7HIT>_Tc!lYH`7bL=#WV>a3BD@^~e_E+)9CY9wB+-oR6o87Fs zw|@3L{A)uQYcXA&s$}zuK4K43hhclbiKI|uR4YmF;P3YLVLL)OX*71+FZ>6CEztic zQjNNBcluBZtT%ajYSccAA2&=W0Qr?5)DGSDcSmin9c$Z_=-iqMco$ToP3P=X^GZFC zQ)w*&u052l!R%JxHU-cwNU+)v7MB4)m&^CPC73QWG*jzS44mY;rs^mI+_7W4+&!t( zbl@@ExQGQEvL-H!TKmSoiy%NqeX;Tj9St@(s|&^gvyWOi&4uI=zft6#(wo;K&}ezE z%stNM9O>vBaV#KbMXE@!U@v06HjNu}CzfWdpOGiPP>SG#C@8mN7LZTNfVcT^65gu7mU%+|c9pS~vx* ziHb_A>RN+0@J}TR(Fi~t$LeA+V^1t;yNVHRrBlt)Gir4Uwz)i%Fvy|wUCG*Lvts=I zX{hBoA(K;m)J*?g(NurdUNkA>v0ysZkk?l0EO?&BD}_4MS24sEPF~E9*6y&zAhPAH zXPHnw6L@O}4pS`KJ!jwk=!Kq91CPL}KVif0sK9?`%iG`Hfjlyl_s;d~8_CgU#0;CC z(Txi2tAQ16rjyf%`JGm`1*gH`l&Ce6f0%*Z367YGBb}nSj8Z+?^Mvw*XnJ>nzeycq z_!XE>V?M2@1Zv$->K?UZz?u8chc&pf>H zbN>9!LPd;&3;syQkEPR(I2il#e3FtH^7LL(89=#I!5&r&hV&Y_8}M`aV(S%jJkpm; z>EjG)Ut#GV8BLhD3;y7nXw=W&z@m=lPQG90+;jkQX*U)V^RQ-+ztD!o;J~wP!*y@2 zaLaykWZ76r?e`6AbGPC3)mFL=PRmIpb+{A6gh_P>Umn#;mC|&cI3Ej62dX(>0fslrn!C>U)Mrr4`cc zPWhkvez9lVE8D2IbSH9pgcr>OaN9pm@chV~9jgk2id~p2arJXr8+dL2j#CuUoZi+L zX0Te<#FMt5N#k-)3SH@;$>O{^6F26XKDY!a^X!-hP35PoMKq@U{SRR>B_H4PzJL}R z>?e=l37KIn*8$o+@8E=DB?wDyaf4NY0wo?^W;wJ z^*`U<>Lh$3LjKTNSW~o2va6yIAj35)lcF;UX}HC>wke08#CX>Ebl1`)C2&=e4jSKY zQ(2dAQ4{a|=&+owxm4-I3fw4(&aLs$YDL9h+f!}AjC|{Iex^6+roE%|$(pEafnVzd zc7G@)jqG0Y?pwR$2!S5T^EjFOhVfU-LzSnUXcuhtQoqKhnKjNyLk~Tx1pz{TA)>Bn zp+9P)LV0gPV)D8QQu-VxU0Q>yu34k_6^D+4db5(r=Jlq$Ly)D&w@ zOiJDa>3%=@IBbM%qAyN|-ofqNbMnL0^5GcWXtTr$O_3N2cK}+ZgAPvfELttNqG94;9;8o7D#FP}}wbP4_+p;Zf@U!mx_B;|5@Ugvg~ z#M0Gyi3RcOJBZ(qT-5Ho5#Gd_i*x{eK-VrjvFiSfC`XCi8>x46IzVp$EY-ECrD7x8 z^Vje4sfU63z=}-K^UY1fBbJXhNN;iil?;9JNvGpMAaZQ0w#u?^Sj@tQIM8k+tL=El zwJl<3M_eJX#21R42YzYOhGx{u$eps}_f6^^Om%Cb!|WdmeIQkBTjr&-DOItaQw7TH z7GAaOXWR*igV*+UBZGTTAN#qh+r~DarUo9=o6tf~Zb|n4^tzx0W$avj`Dp?aQk{y8 zwWAGEYoWQ}nL4Sf^T8d*q~ZRs`&+B$tLM48PH(v_u8O;DxFYzx&jl-AawYZsJILBM zPBeiY=8{8DD*k@YVCr|5WIIH124H4O%4MGA^e7X0xM{u|djyBFkUMN{Pnk0JF#cJw758k9QkI>I_g<`&gfH;X2Wtgud-Zt`11 z(}UdKl_RG+KEYQvjKHo`q1@z9N9*KKSj!y}@%{4=w9O6kYPvvr5OvT#g7&twM(0od zk>P!20HKcj%$EG&uT$M(C*y{v?y$DMcg3q{=J%W=C2B$X4Tl`I&3O);3&4F*Kkq-k zc9)K)e!!r@+r7%r`TccHnpf4Ws;y=D$Lhg?8q4x2!C%la;>NKbmf)(rQZwj?gHK$kT zsZdy6YZ%t#6W2N8&wm0s5mWn5$Fd!cfxFqma6$;64pkMNHxKIZ&CbWhN}QBcZ+ty3 zvl{sl>L9*Td3@zbp^p7u0)|Hkxzq??v3_G=_UmVJitGaj4+)3rR^{p*$)DI3W-Pb2 z>KzTx&g>E9Otoyh!OcV#UQR-8D#GX5k+6!@A*Ti2#j1oQ{yjl0mmH|oLKP7Et`XN~ z<2Lv)B4NDrsQRr&XC$Bf$STNR;f```4r*c5-I9v2epLIDFQIIMed7&jUS6M(%B`Vn z9WWu@o4+`jW^`LTb`=X7pSs2uxff2|X1x9Sp_m0uSgS>h7h#R?e6#HeWNQV<;Ts#- z42V2=qax&Y0?`xsP&@|TPOxGiOMI ziV`2YdRg%j99m`7uhBaFkFU@7W!A}2au02oP}vi0)LspcD%pJZQfD6d1Vu@cl0=iMkIT|vu1K7i-_Q<+44322KHZi z@4CK@;8hPC%U4&~<{XKqj!~ro>1Yns$$@XxnellCs5o|kXnspsWaU@<3DR5pa3>PH zDR-BZD#hn#>sAUuPgolAxbu7$e9IzQPZVf_O~321Yz>>!I1kavDi{TVDly7*@bZ;s zAVSM+f)fuiqf6+_XZ$~vbMIF*iYGDqqdsH@vBn<8?YDg({bG8|Y35Q^?oLPV6-5e3 z65>_zEayj!YsPvAW>(G<5W}(cXLLvy zjir0QC<2lMzxJ?g97J2cse_pyALXEPt76ZVU~o)(OYZi_MaKPyq(p338#h7!#Fb*( z)Ry_~HoBPh{6x zY__LJ5Zfma5H<{1)JzKWyYrE8K_8(Cz|&W z*a~6KJ7wPxVcq&bFNqQ>BEm3!o(Aq;y{ugVuY^Iwc%|0OUj$+$3P7RGB=-K1O`l;? z9-{(~HNdp&E8o63$)@(SGz)r|J5E$oS;@@J{XZ`N(5NYHab}9e2dmsVTF{idtEwsB zkO-7(7`&6tM`x<14J5ZY+6Jv&lLc=V0UGKjk%+EF0AiKdrYiZBTLU6;m7z=s$^+v+ zo8aPRl_4xDxD|_JHV+`TvF{4~o_cN$klBazuKN*`Jhr)}m+Yc#uDfR%Dw(tBE^ zZ;Jn}wS`!M*+|K{4_k}5L%&Pk#@Xa(U;pEhl4uq)T*WHkH6w52(U{f}E}ZhAZnuwP zmhb)kj+57esm0kqWR+O`mc!O}y{GKN^nZ-P=x?G#v)$bagGlxg0VMbir0pw1pf>}#ktQ*@r3~H~=Bj^_)}*UlAo3=+fE7`yhJM3A*EifKLUw#jeG*ePL8X@ECqgal&O;Iy-M(+O8Hg}DOoQ)YPdzx$&*Ea3P z)DkU*G;8jq*M|rj(lHOH?A5XW;g-8IQ>_`DE6$Ks@hn} zb8y(LcO668S#U})LBD#?wDFZ0-xufU{tFU4Bg0l!n)1c zA)Ou$lykpH(ye9y$bQ0}TtTyRjDyLY+udkakXeChOi`p! zv~fi)XQsvhtU@JadME8Z%D7N=*?5LX`QkxPrgEHJc{lFj^4NE8+CkhvMLiNphKYMG zJ;@bx32eE#Jvg`q)T2P&_Fpm&-Weu&4xUyUQ%KAqB`?gn^eU`urf9ty;pXj0Njkf( zF2L(w0qE?b=w&7XIM_a$aYPW~+2L!@!6|>aaw^f}n_gQ##vKL$G-lJXReWZ*{X{3@ zX4!+ib(GZ@>3o~wgaT@X$7VFTcPAgpHv&JQ(wwp*LO;4w_{Abvv&7Yz(4+5P9KHcz zs~^17DoOQ1ELHVw7v`ir;(zdLI;%Dqu`LdCh`I&4n3~T8KrL0bjl7CYvl5_yzfOH=Y2s$X*-&*V>JY z5JHwujXN)A`(2E3y;751ZjB6b^J_D`xuj8-)w2j?F~0qdy(3~bJ8!6rm-O|+Xk=Ai zejZ-+_JLEAent1Ej(VJL%zzhdVe)AEN1xchL-`}_CuCbI1AY@4lJZxwqn8iW9MgTz zoFRCe{s{#3L~l9$`P8 zu(_8U53A^kIjk*M+f!IsL1yx47_-zeW?g_Jbq*32A9UtludBN@aQ0U_UcqP5iKX_*M}bN8AA8rxDY~@%n_o)d zjkZXT<7g;=Xe+WM*?tXxqnnJDjq%0=u3f(7muXA4KA zxDux{dPMCAk3rH1v~R-Y=r>69tGf{VPK)DSZ^7X#dS|@eP#DA-%;NoI!7Goj>Mvrm z-L~0Yd|(^cT72-@Ip+ZG3eF>~rwt*_wKcI~=#nEEYGuxIj%q;sDHY&908O?oY$(b% z>XuZlIEF2ICGp`_6HpISpp1TuK_xi0G9U7$`D!t;*SDq@JvNMWJ^8ac^KMF8crHmxBC;1X7LTS>KceF7Pmb?_!oSns8`y(M& zJafg4aQyODMSmFvg))`&gFA%$NKv)0_(-9ojI9}Am18P=-)6H0h2muU^)u+x-UO4< zEFGX7dV1ruFq!PLFH{*z*pL_$LRQy=Y8*1EdSe=hUKA39_~NMwljtTeVoRXCh*bRI zk&F6n=x;L_xN>-Biec-rIN@7TrQ*FD_ZUVgUwai+RPv4(UqN{z&%dydU_W_K9E|v% zHQtu8GH?dN8$Xpogd?WkJ>&3c)v`l=8pYsa0O^ME4-?GVNxT6lpdpFhyyL(%V~ksP z?T}rY%GcG7-sD9sSwd2Ii;nHW6DHm9Yu|3?`hM+twl4qpvI9Fat|o0QrfZxX-SuXR zKi1S9Y-7!v9DRGa6g}Usyqz}sAeJo7V^su8S{owX<)2o=i}ZxWdtP&^Ry;uW+n8d7 z=u+IH2X`7vDOFPNsj5nw zHK5)D;tIj3ImVLImLg}d+#c0F*o(4tLPJV%vPSwd&`GK1lp3WwRzZi7wgTGXD8HFW2k z9!X|E4H!j`C^7b@BNl-LWOQX>I3FHu@iP zM|#F)CcI%_x%Vh#Dn;`x205=t#Q^M?hcDLyt7!G$@^bVdEuomk=8iW!pYESy%_+Lq zJ(KnqJMN98R@ENn(6|uy7p^Z{NU6|)T$h{#=WfXqN#44&p5K2z5T+UU5e!>=(Jf~_ z*!6K{yKV6!+$vI05CCC0G3!^4efu;V1s+%ub`8C~MxX4IYaa+BB{2NMxk=HK)i&;= zMDu#3yO`Hk;6;qrf3iz&sY%b~RBqU8j&PuFJJIg4uJ@|Qc}Jsua_Sho2% zPri6t8+&74x}(Tkc9J(D8HFCJ*k9?K;)DL41y?CgK|;`!QGReNm1&1%%nX}0xbW%9 z+mV{#q>G``(a5PMgr&&eL@leDa6X0>nS(T0xgtabLD&{U zHmyI{T~U|cB$Fb!db=kyhR^JK;fj4-V>9}drmviAO&1%){gzlNbFuZ@GK4w;QwhBa zF#107y42bwC`zXFcivQFVF|OcedHdO$565MopVP>hFDs{Y4*)v?&mdT3?}57#7K7z@!IE5 zyjEtrpq+|U7tw`f5-D%!g1DZYVNg#!E9X1MBcW_FL0XASC779di!tMhPwU1#kdm~# zghpC%i}i8`Sqt71}3c`XUXo^*kie9N>C7(0zLzKYxGVqB(^q(pM$1fBTuM zDqBI;Y}xg#W;8WTVti(0hlJr z*<%)s;RA1q+I-9L3w8`Fm^C72B&Zf|YXfVVU1d5slS?-I(yb>f3M7FJx@6@=0k?|h zoJ@5@wSe$neqD%fNxlUxqmpNFz zMl_FfUC^@wCT3~c1ThvqDErN#qgOTlOwl#wkaYy=CJ53+p2U~WmpVkAIw^z6nR17( z3>7-GZDR)Gnb{f1Ja!*fNp9Gz=Yp&2OtxQ2+Tj-$h8w8|U@FXR4~z-u`hKw7xPHJ? z$XxW;TSkTYmY*q=aHjvL=RbdW4@cCf$sVpao=<+}uvJT&RiRGxZtIR_KCUCH{?EgJ z1S^P)#Cq^9WEkUGV3Wb2yWDZP^;}_KCR*>#V@jJ->K1bm4aVG)W07{AZ0Jb}lGP0_ z1tuNTg@gxNCW{X3LB5n4k#h(v3|oZth6F#5D~zXKq6aXNLNg5gxiXEE@t=eM=G+jB zar*uL9c*Gx!2T%stqK1B&(C@&cno>r+0joawp??8S{jo+cnWwTk8KnD9ABjO~QgsZ1a#VKLFX6~R^Mk*d@?8_zf?B54G>iU1$d>zj@x2{<+?!JVq&QaP&l|bYFo0CUAxjHE!x9Do%DV zFFs)7%M(8z>oiOT1RnPe2eeR=1q`dVVQOIn$;;Au%zry%Ua5Dc0!Y+^es%2;%i;*N z7;scTUWKkiUEN58TSqX{gX;rU%?(oY#KcjzIhel@e8eM<0S=+)YKc9{vFfp z$i8k?t$uZB3JrDR_1=&QUulh(1W43`OM9dMTtrQDf#_YD*9#>?%{lqAROIOB6PxrA zT{Uj9CzWO^BzQzQ=wcc<*kV^#4kPP+TPr*`;%_iyv%&_>jkDipRCX!Y6Pu z#|Q9>EbRgMHo6)kw=X{tc9BHV6p0Tz#vZjvdn8Q7Yd7Vv^*?>O1Pyh7%!|s2fTG=w zMY>#t0!_oXo-{a}n6f1QYnUhM4wf4siZN#{v)N_ z7(}0lj66%mxH&b(7<%?t0&h{b%WRNmHX%V^lRH0WI5eliXCk$}zae3-F+M{z={uLZ9wpGHv97@kb!AL9svmua}J`ZcE;}GSPw}yXGh%IDk}0dZNVc1Y94# zF>Ot0i6El7!D2ZjH1evJ)XYH#aBR2P?c5x9(*3gQQouIj8Kp}CV6LSrTm<{_!k$Y$ z716HapYKeCUhXE7RcT|2&o+kbkTBfNTQvc?< z?G~b`j+SJCDa_qNsdqa zDfHBZ;1pZS`%wdZp)sq=YekL2s9qfY5U}l>MAVaJAH;|)z~VG(j3O~ES@8T=Ynqp4 zO3vA2e%~KkMg^B${$Wg?sAQ^HvAixQadV^%wzdWXUPeB5C0e`~LUW&1Hsl;$Mnb=8 z%j~s)DZe@?wIzs;2`bs$XC8EYxQE#n=gorBZ)Gyk{izPEwG8DSXj%-$DV$UBsZQwN z*T|#%pfs;KXsRyqUCv2A5}hJ%M665!T$8bglaMJfDDBeh5vJv#4wWa#+S~Py2;mh~ z8j74o2q}M`$+T^9UlDFH6tVVv%hfL*R5lO~hwcdUjhQa1MJ}2P_1~F}sAqg?`8I4^ zQsEL=|Jj&RCYGzSe7cC_9*5GSsv+(Cpy5D0;F;sCtv{80a9HO^X4`;qS~9=<)nD=+>kf`PbspI5<{`ceJpO|%pto4(>TK)pcOZiNW5QB$!N<(fDZ+)qhRqO z8BKsn=AokIx^$}!r34IRp#}D7QlAN<{tMSYX**z2pTS7>+G0*=t3tm5{%1%qf@3%h ze3S#4Ln#eBVitm&c-nUeM=Hh=N{odnq)g@J@JpzE^U$gcBj?g^f9~3%W0;ln3Nu|E z#hmcQV~h~m(Stsgfx6t?sDlIa~;{kR|NNBf!)HXg>+Gs3&->~``k679Oji^jc6@E z7M#*(G1j>75A-Bk!FRcGQ4G+0Ago@Db@Yt-ugZoEt6NHrpVIfmC zqdI@;0$Yw5T^w7H8q~OP(qhKYg}|HCjS~@Q#oDZ`U}JGsgA)rE{w2Yd>uQIz0sRAg zs0%n$c+`uZ(v}y&;!uja^+TayqPj!^P%#g@E&w@5XW0^|-Q}9xIYANN+Ex9TihNEnK#YD~VPPjY`?99%;{k+BIYZsR(Khdo)lb zDFVSv2(ioml$~jYCazPXMKxI=i65au{f|r122CfNOT;DKC_yMZtbx!UEaTjY&dAw_ z+9h66=0kXuatp=;|G$quFen&N>2`&aQbhSf3*`4Y|tHfC61ZQ_48_LcgO;nptBT3 zlOJIAL?y4YA_~n|%E13CTOCb?+~9gNVh}UEg@lEB`3+Bz7x}rUM^p6Jg~4 z@;Y`06eez?CyfsT2mD3*w_;Uc)Wds zO04wc65d`sxF-b~JXB3>sdzYYKvTV~4L~s^QP55{KcMo-*|Z=EyH^bzhf`B3amv`+ z4lL#@RL(P|Bs)eUa4s|*7cA0fpIgY$Cu2m5-6<^PqnF;&#+Zt<04E`x^Zy;s_7=(g zjUfY-DQ)(037Q=mpHV`e!dvAe)0)~cwUPFe+z{8p>SYKy$RpbTPd1(l;1z0JIN*<% zUmP5rl1K!B4tS&S-aD6QA&n1^(^XWlP*dRpTUcVroXB#j9z^{vfiT`JFI`-qG^it& zzbZ$8W>x3FxsQNL)TEZEffr?gV21!2vVW~K?f4!t$tB_*tLn{MsD`4RyhxBa`A;$_%>0TZ{d+>z4kgjL{QHq1#x*YrK<@CL2HiSFx1AWV!6^61{xxTd zBpq`7^3j3HI5k-QP(i!o;G9rX4sr~@rDH3QfvnCwsT}i3tbWS)Ke7meCd7r>&euEU zYzCzSB@ks|B~BTWcGC9{7Hk=Dd`Ww#1&k1uqzJM^2&lcpk6gNuUx6-=B*dGUrr4C} zpOql{)Xho|ycdd)jl)_$6n>rb+Tj{tEr*IyUS{-KSI?&Vr0;$UWpMOhk2lK2n$w;g zi3yoamNA)Y*KLxMSq{7$PBH2fV>gSrtgPU=Vwwv`8h(ZEu+Myt(DAN;>}>i<(R}^@eosmlptKo3r=ysnCtTi=fM-3vs3Y;(?Jc z{O|Ltc^DsL~%IqOGC;uSTn2=y*2J%PHhU9~+23%S@R{ zrUaXqU{p;;jmhIn-!aW9dRe*nC@zg0!(aTAg^si-9(FI%1&bKm?hKB7X>X&DrjTBt zA7z!Z1Pv{QjVV-#9$!1Y&lKB2t?7AeD(5(b_JsA@B#gYWr&|sKaXy}33gra$bEz&c z9t)7dB4m}JN~2DCemzk1QU+3rd9s{elkIsrJ=q)+l>a7Qm=(8&TBPrdDEcuTcVgr3d}?63_jYvHtp0HCs=gGy5($wN^HVWGDV93)?4eob4CKbWc3Q2axg7Tq z3FHYBPf$&f$9Cnoitx1n;2D=a0`V6c@hSQL=LN84+^H0J$dpZG@P&ELW|PxL#oS>E z9U$28E%yoB{Q8F)jPz!U39m0gIHvOW_7Gyf>Gkgk`xBE9C5-ekYPIU5h79PTycTq3 zIe)i(-bj)0%lvz{2+qfbf4$y(ejmI`AH2e7ok?$l(muehO?N1FiGpWT>`AxndNK6W z0-*DDbqJHYcBsoEp+z-WENS=k#|rPwBTWs@M^DeuW@TJRZE}c+HgYIKbED4Ms`wg4 zJCNr_G~2P94btXRP0~Wye-+);eEx(>u<1t_#@W1?#A=ya-u_RO866$#eBS&r)76g?VM`IzxKFa0xrs|ojbLr8=dXlyQk>>T3TfAX_sT1obLE4=>1?ah}jWJ zf9R&VU-Rd_V=*6@MeqKk`!IaBU|9CLvh%@i7JscD>6DQFDG?7hV$$9v##za$hCQM@ zL<3MsA>K7)DHTEC{0ogc#B+&d5FsxMXA*;}0XlV6+^dkI5;lh&;F{!cYI{?ajI0(T zsFWgW2K+r@Jot%mf})B; zz4iC#2f-2qt_+Gh6Vt(3q{pH4hJGjAg+uvaX^l*p>8?yrr4PdN(#2L&EcwUcMA4WN zkMnTim-R(Z80=C;E3u9{BgD|7tDDY?%kJctXsc*vOzLV#5L7T)R~dQpN4t04->Y*5 zlN8nMW}Q#tcRtGmnzBInQF0l+$YDQUNq1aES-A9WG49nq@K~2pOin;nBE}Uo;4-0a z)Jw!{^Dz$BABPp>#SEcr1jqMWcFtgsG8cd!g=IJgdZKvm--g31M3I4U^q&w6 z7hInsO~5oCp;NWK^NXm#_qh+0zJDFbIjR;vsq)=#JeVF%*r)miQ+|#0YsmkQN_-!| ztAsod2H%LF@bmYjywos};LblEP6$E0dU={`g2+2#m>BT>SiXSi@R^^>pBkZF#!(~H z&~+WzNWYk#aS}duq!1ZjsvJ6UjekSNvibvZe;&*zK6F}R2Q+w19#_YU}#z! zLvtHBaKsPZ301m!Q&)u69CLqA;F*4tl_f!Rey@PdB-7y40v2vYEif;eGIN;nBWbr2 zvTBQbM(AeojS%3yQL(P@krVf1-mQ|TyAG$8&P_8mNa7jT55`&`7`h&0jzn>S?LxWk zq;kO#tDtI3M7rM9%i|O_$i}Hmfnewoi;n>TO`uV2S;bXqB_%Q=x>$4qD1;kW?`6-1 zE#Wx4XMTVT^5li(vRMGB55G{pz|!N%hx<;>WUzhN`!4;}*B7`p@yM0`_oFG|Vk*P5 z#$|<{J2=gi)S1Tm31yeJ_obtQPrKgK(;_ap)qEs@TsDPHyWRyF{5jjv^C5vZy*b>8 zWv*?Q@!->7X28ATJ$hCO&Q&Oqrc0`e_=_T(y(#Z~^U4xpm7NkZ3Bc#7V;4PoNyay% zr8)dzq)aiHF8rLiCl?p`2|@~|wyOi#sT=|BOBSj~wK7bER;rSr;S~6i?I%v!lMW}R zr&ngFw=AuMfw5lj@k}(ZBy*Itn9Cw@s$FIv9#4%SFJ;b~A8Rg^)~2Ut>59I-{M|-c zsJlMFvSwTXX<_9d#4x;IA=}7CtWu>^)|Eke1DbQ~>#%dQjXsZaX-&=Wwf8UrazE~v zBR5hX)`WDa%x~oT%w;nWg?%Nv$HrIMd64zX{nbewh;4<(*&KXxvFwK}Un+%AK+LOy z;=N&zt4?_=B=~2zYJp0-wvzfNBgC`681BvlPrq6c-hd9~!*e zRWt~&T1h-xu;Ng6cZV9YNMv&1?&%F$Zojeo1etK@D5;B_qHL-?-bjpVMR-)KXx%hK zG+%gBe241Jzmd0(bVF_deyNr#!d)!PsY&bjR**`ih>{TQ_Ymt7SC~q`mgbod>GfdaRI6DX>&uAY7J9sm|O8)#)MW~Qeh4wh1+lc1KMgJC?& z)X3K4ETL<0>K2Wn!`LV57_2H8W$GC)^oWvEQc|>ki$YnEgD7;LrwAp+Y#Q@Mu1uz;OXD)UDi-XGqllXr9*h<=L}aXPQl4gbo%+XDc# zEVVemDupixd%yx1K)C2pq$3_F3}hSr*Cw5zj}_=J=pej=!GcsK@|DmoJyNel9lZyYF7W67;AE zkLNQB&$>6hN1%8l_?pI}t?PWaBV3v$rTA~?UD6dspJ2Y#eO?wWH;dMJ=%VDUNiSlx zw6cmIJpL#!)u{+vaGyU(<^bev`)u>}+HF$<13gB^nL$yqNPHo|(z~^BBH%@-&qZUJe07gnqbscrqSh#7jW( zX2W$KSd4ywnvC(3Fag4WzNp2S$~iJ0c{t$N2C2ij;vu7Lr2@ELw3%Omn~yHHh8wNs zo=s8+t?z`2Db*;3#TXf4a|T42pLeMtOl+;h<0;R4a15qtaNY0j?9DE$Que&M4LYQr z3Uxe*9AF*3nXrMhuWy+pa~=k(LQ5f0#0o00CZAGLaK;v!=qP0*Z#oF$72x8aF%y_T zgO&ura!FKDt|ky+zaE)Fq-5C4mf$zj3GCl8m__aOu=V~V>Rs&0UFO^b_Q8nVZ*(1st!cRM55GJ;RT!2w)-o<3Zbmr@FeTJp6s8jAqV-uUHbZF!ev?f9LM3D(y z(Qq>4*NZJiVVr0f+m;Q@DTm--3$o!qX>*x}7u3VUyTOtbK0gX&9hUMu$L=%|QWr5K zzTHAaQj1P#)N9J7s|_L6q>nMsU7i(T;zh(lHk`9n(P=LyR<{*pD<%&#KND~CRD_mD z988g_Z6~V3Et~-A2mKPOj_`Km`@3Tu&Ji`2hh_U@dlt=`5kndCw{ci265K2v<;X@c zrEI56^vtVVEH#;dq_UWVzf~jiJ0QPm`YWnhyt!Ccggn=Y86AgmY*1}7!ATfM%e{Rt z#tcy5h4Xiq^j}^yBNC@Zm&H-CkeFJ5332HVD6fIvD7-2A)x z+b0i#N@yQBGC;tOS6&@)h{UEbgjk)u-nq`&XEE$%Wy>>3@ z&HRk=4A!pSl3Ao9!XlRVIFH%vmjfFY2@xPwHb0Bw%NN2j!*$c>?2k40ZF-|)+oorc znAVAHd(%#}^y$6BM~%Da=GLfDM{^^JAGZ&9QMA_VR`+5R$LHU>R7aZcHbmWG%Dig< zJ!JnmYfb+hx)fy@HBpYQaF%s=L|LxE^cUwW*-Q!Y@|WuPAEvvf4HPTDbB5UnCGA3g zroFY^)NYBTBMaA1--3o3*I`2U&hsv! zxs|1nS>`W(>};GynLM0jnIL}zH~YcnE>wE^wF>9{$M_}VP~UuGXg0gSdz+YXQ^=$B z$d`*A|Fiigo;4G_I1B&*@R|um*-k<*@3Zk0e`?I(l2~M|W%pFx%zy&s+B%3_v%Ic5 zq?oX^_;0Br>!O#Mg<6W6qRqtdcHZ~8TEI=n`LPC&NoAy<`-erN^8{K(%<-7FWPSk)6+Y1RPl0&f zE(_cKhSCSdV(qz6`C`nd+h$d*J8koxyd}^4$8@)^^i8VsLJw2e!*-exH3)#B`MX_D z2EmO>%dmh01oXw|fYqf#DAF7&jiP^Eq_eIJ+fOGdaqZv7%F9m$q}yqZGN9Z!PRwb+ z@0i^xgi2&9Xg%Y9M4zY~V9iQoxz>nGW~HcZS6-1~vt8-w)}p5-Pum++n^ zYgUWNEJwbQHt+813=?3AMI-)E2D6UvB@Y}|#fEGP;$m7I+>{P@)a#D&RyUJK4rKZ!8~Wia1yp&g^?aPh=n*sf$O~r#|g9guW`>D;wzM^tzRXSpH`0QD?Jmj8Dpt*B$cxK?XBd8Xm>=j z+;ksz6#DCi$YVRuti)+z0JcU3*#P^Uu&eUZRSZt2LdA?3%e%U8YbOFg;!e!_L~WA0 zN#j9gJ(~H-V>0=Q`*dA|ZJSSR`SZhJ5HP#h!st(><8q4Xvxh0n(9Mp%Kca4mvF?e8 z;df{kHovJ^$OQF;Yy9oCURjJ>Af z03BS48(G-+tmnAaug7*QQE8Tbqt3xrDHnfqWf9FhSgp{yanHrknQaoY0!|Y$kQOWG z*UPcFO_BvZ$hz0bzH>Fh~3Jn+Frq6ie*uWribHupXn+sv;YL4!uptCQ7BFN!xa4+SN-s zHi^~IZ5z#e@lZ>x??R25T1=O66qvg<=%Uk?$tAIzhP_;z(|3>6M>)U|?os~yI94*j zPIaSnI7lqaZM^Bq#1tpGlmJ@^zevK7R<{yXw{0GLXJAu=ttSxNg=a;Aej{Z>xAVdW zf!Tp|D4baUsuY^u>VI~97SRn%M%93#g{=rkwsq7eh`yo#$s_)ma&v_6+FKIBZuX$Imn=uQJaK#+9DPYXR7cK0fu$=b+g3 zZ`SMKw*Jst9X>x!KN*%y-RaS{qT%6;fM%Id&oB2rOAQ;<7)1qhn(;|SitQN~NK;by zQV#i)m7=V*G|e5IvA_D(-q71T{8Z>tkQkvRTX><nqyf;b4Yr@oJwG5HDNPW!IzD-Ors=8y2 zfnQU8EtXg6&Q!-i&+$SF4D)=RJz3gs(m(Dz>#5d#$ctYPU7MvUoh}Q4Ls7QdZdor~ zs&bvU{}jZUoaPL<5gauND+q^U{yDa;(hm|gu>Vc_o&7$Ay4pvi&Rq`**iSV)_qh;_ z)bG*DN=&78$*6F!q7JXA=;bNbdoAL!L_U*abKGD|D}K-Oac9YBP1C4jF=x4M$c#kb z$J8MZyJQ%BOk8y9CXV6hbYasO-A!m)8~A&`qXX^Q$VZ;E)*vR8kZyUlAK?5ss)DQ9 zPxY9IZJ*`rE(17W-y%7%h5OtXeZhnn5@jrIW?v-WFvZCy=K%7&&Y~~OB}{5`o!5*P z##lZb!a341-d#!I>hb&I#akQa|7f8uZf3mkt4^RY-XdYwNsSM0?b645%DWh2>g}i9 z`_5Eij63hJx&&Gfl8|OCt@4H3Mt1yDAKVM;A@7@0{TC#F9(^C!Qx+9-ANwQ*G zY$hrjFk>a>?+QCidLKQ_?r=HA5WJxe2?_k5*)i(j?`$;w=5RUgGZNP0tc zI8O@07Fj+nv?e1@J$kQ@QqhpIU$S=fP33X zi4H!>ulSF};93_4PZ-_LgZtbP}HHR1Z0QaAquUn5&s2GfR+vV`Lz85pLdbA*V=x zFoA;@eYhBBs-2WPn~#ut8)kbN9XXYQ?EeFyMaX3`e`*4L z0JlH{{_Hn!r(&|AM@+ueNUGegP+&^&UOVxur@cdtQbawvJLt-F+j#-|{_UJWF=Z~Q ztjViqFj1(-CGMz9C3$*jyfnj=RMcx$49r!~Qa{vQIR zMH8&ZG5uKIFysEBim5}RrKN9d_~*Rd^jHtfHrXh~~8 zGD_;rUf(L1sfavkVP(8?!cjMvhn-e)uG#CF2nEPOJYCWs2q+-|z~H zFtO)*!x&<#O;*>2@w|8?H)Vilb{J6!zuxssdW_%gx&P%XSI8+`-~H|v<%qwtQa3qB z1ml0X`&lr1@EY@tk4VMPh%ZJt+$m2`>4#Ej3;ZuaOT+Ox{n`biuE7dC+5|@f!gH+` z1uupT0mCJ(VS8qp3d&V~^OH_h%;(1K+(4f`f5h__tI)2vvYTA0e|214C^L1M5t9Pb z=C+fFFXS?r*2&;3R%I<$RUea`?sU}q^gy5)=?k^W^M-i$hW`1Yjp~j?7rX-H;dH4MDux&30<0JaMjo#`*}`H zr*9hyg=d=Fq$+BXG0M?)#w~*pI}S@vNkeZYpvnF)I`Mcb7mb8@;lXVEU=WD)Iw^ub zCZF`|wgpJSAVVY%%P!*fBDxEbhwCssV-f%0aKoSX2B>y2t|^F##UU0i{%9TiF?hF- zcs5eq$H+|UuiwKK9I{97#IEy3023D*6wiXh;Nveis4O%kLTwbe23&xg7HIVfR&VYfw6C-*3Avu4^BhqL$;MG6DbL)!ZAYGI_(O3WV&auj8M)|=)~vwy*H=c95Ajqu;- z3bSwg@SOr*n2_ zV?w5WDTR(p-|y^f&46Kb3P4pU0_ShSTxqgtiaMz{kY0c))(pDP04Ht`2?#SL3Z3Jy zh857nc|t&UW8zwUHTs5WYfUlcCs_s8+(!@BBDF4sm)lM3_;4nDZ$nYDkS&*8GZt~B zJLo@IUd!82i1IHkG66t>RFNbuLeXPu0=g3Q35gpGGf}h*%!*y6puyA*O+)@Ep`OPF3#5ZBTn65ywG-SZ8~rg3mXk zf~o&vkYX5(^(WF#X%tofSI*8MUU4mlX-JO_nT{hDUsr+lI+pRLZS}lKeD5v?^E5u_ zwP?<@)Q{dydoP25sD(jo{#&cXPRvDu*uj17QF?~rp>5FynzK6aQRID|RWfUuI*lYpbN9J#W)xH&R{xdpPPn?dPhD2p0~lD zXu^=s7^L3IFZ%x5z2mfj^FOgNEqF+s+^PjC3UX%tN&KvvCObjiNFup9m!?8y$qrTz z7L!UC7z`ZS_@0QCboEoa@>#RWbv78M{;VXPK}-7Tr}27j3?5m?*AuxYUn!)IIIAhm zr?RY4aY~j25x4gA83B!ZS3*2DO@f0g89sj78YMAllC-S};9}6(%SCYRkJMwNmrrOB*@}z}y4IHHlg>wY^;(Zdk z(kSDKg7d)Gng|H6`VkFYfl|6%7-EW4k@YwRPoWK>%LZ468hV57Oz$|4a;~8psb$XY zxXH0)zj2wUBvGV_sbYulM8l=IhDG{=5~vob!wPTJQFKhtgl%vuIRS0lep@X8Tbtes zS3})u!kj`?z!=#@Oyz)Nus#9xg*6f3WODFg*y-hP*JnP(6B%J(DANxCZiN95g5Hf}K=&O8)7 znS7G4;-N{}SoZ`*|GWTblIeiqJ>fcNTRTy##Cx005s{U@ zpif}DII?9f+ZSlVlUKZS^-np@oQgF#@3@xf?JkarhIcQ578>5iH%A{Cxr6`n;!QBj zfoch~752@TMXmd8?%RJ7;uQM>l_H+F(tAPvR65v(kvB*R$@!IYm(nA=#3xBCWST0Z|S!O z7O>q`Wqf%v!4Et75km=*?i!Tp$1{_2dhV2sD#n~v^PBlf4rlvbE#mZwrAi{Th`>Mk zF)g(18SIN}E#rL<5|du;QPwwpi+wvOR8=qh7-~h|qZQ3L@V?l0y*q{J!NU?Sc-PqbV7;$=LZj#^}@#tLm zlU;UZ)7%RL2n0%VIu#%N$ov$OPEQICKv0C^UozEC;buW*V9}D!*16N8{O`xV>~}t) zMQ{XtaERwbeEIv&saQl_s;~h(OBb7fj?`L(t^HV_9d@q6$3*BauL#%)`IJZ-P}Hl! znzPxJnHpoE$IYK#|7(xsCds6{`_sUp~E)X;Ia+rg{iq_7#Ke8G_BZHx5~hc%Oh)OWn7Wjf~uc1Q}$e0~^$( z_J*1$1~;H$R^iChVw!w^=;Go*@${q&dF@|5OZ}240*Yv8bnJk`^Nm+J%=$Vxr8c1h z3W_uf5ng7HXNbilgIG3!EV?Y9wlP0`iReANX!XvY!UNCNSagXAIWUb}646gksRgB3 zdOox6EY7Vo^Hf8Gu4D$%7 zyIy^F;Soa2CQU~9ef{RjYuZk2)KN(nDoH)^*EAABWM2Hg(aCGt+A4pmF-gqdZ$YnX z{&{*SY|2kOD$OhXTx4||BvytVfs?1Fw5rg_6w=a?81@^N4kHpn451_78P7(B+s#a- zK%hyZX8UQQQu;n!m49i3yfcj>q^>VHy4%~NiU zN-=`I0;5jmJdEh_6%%2akvO1q3C~0ujk!LH|0U}>2st|0IfLTJmzwro=4S<@@^yf> ztV}6z5XefbCd*YUU>m$bwpO+G`>kvoSSc>}=mYnhdxsIePMzCN?1T*`7|Z8Yyq9q; z8LuO)Bi(XO`*9y)7i&#pa%`+~D;Ci+gLrZGtAnm)2nLvD@9MjRMz6d^8|Hv-Dc?T> zLg+9$Lhc>O!WO6W#Z)x66t0oxF)i+LvMc!)*h|1*Ao3BCsdvyl@yX{@4$WJkYQf>N z|EW>NpaG^}%2lu&nU(Cr>8EN5Y#sE|_`(L~$vcm)N^fm3b z!E=g)Sbr9Cy+wTKeubog^PyaH5CboB4x5%#4< zcwbqDsV)AY0WxY?dK<<)YPiD2W>MdK`de1MK#ATU?*mvQ%bcM%llp_)i>n*mz}m#% z$0vr^h||>McrV(r3X;oq2cfh@r#c%TRWmt~gAQO;N?>SF-l;r5K#K!v761uos+@9_ zFr7v;MX23B;oF?+w7Z>XWva48?YL2cScUL9uS7dlzDUPir-l(ZsNS+t=?G|6oqUik zbGC?{jLhDju>Qj#YFmfc>ax)&$MgM2&euR}@26y-y^F-UNV{L!5fnGWl?fJT~+!UIbYD8>SM0KXl4LuMXAJTLA~ z8{rQ#W~D=C5%a?j;pjm>V-5%HD%5NA9EmOwF}Jv0xVyU#RAg42@Zxa>-Qv`&@!*%< zbP%jL?7v=k0_M)XR&{T*UimoxQ>N*%0BFYgrTo%j!T6_WV`iOSSp8b8Ic4i}<6|OV zkmM&@?*bz@YND#~VKS)U#ymJdLk2+RJsTHdbW6!oU#lzmQ4x$?9Ox3_5e3K|*1dSH zSBg22Th{c^FK@xlK2=T0GwEkrZsDftO+Ijs96O$m5pooRGA+R}%s{e20JmNqR-q#b z+;bsxL_{n_?`_a8?hLHe#EB5k22J#-%E_art!&{dni6Pm;fK~*+TLF+uxMRK*7m@) zw_1%QC!bTO)r0Z;gtj-k6lUu0`}tM*)_#U)SUV(olRW$tvlWOi)%M2a2Cd7qh)?Hy z`QwKmqsGTd-}?b?vL)YTZf{1K#q|})NZzm@Yu}B7tF@*i(h}_JL%wy5_feltbz{-! z@A>RU^q%CjzrTu?wwV*465?o+*oPBUM|12s13Ur~CagE@{$?rw$BNjuKcxMic z>jyM`IRh;tRX*&xZl`yW_3$U(WsEpu(Ngc|V=PIYMlGSOMnKnHUcJ8xU@~thcihLC z`%pw;zo%|=lnJN~+sz%7GimqcX+;WugWIL%#4C*pFoj`4*rVeU@8rk#^bWDa{Ke#i zvdePM`-qvd<+*q4@fBQ&ckacPme0U5`Js{jXlp5{I@;nl^nBU9O|*z3C0k=*mLo|i zH|+2@XoPq{`yT(a;~^3h=Fu^At`LzruJv8(5NK91mT|vvliV_OH8Zd$n%KrSpLlMj zXmU-EjD^jNie~|`3G$Dr5duT0A+CrfxdGWEgz>>r|?fsZ=MKT4(9s&b_09!sgyh|goXqXH)S!DA**%-OYk}ge|x>{zCQ}74Kw-V!= zmG;x8I?;rII@#@2BM0?Gw|6!%62qtQz@pUMbM84Z}e{=8ReE$A+KV z-|#6C>BiRt2c7NzTLFP>Q{~VPr~=`oX^rE@$?s*q1NL;(;uk1~BV{@Nt)|PCeBEh`i1(PW1?!- zhv)CSMTjfULyT|FbH~d5C@Tmai~a*4va1+%SZ^6bdX@lohe6UAVnILYCuRYM+eZRg zPF~WQmLB!9WLyvQZ3RN&=7jeWLcD4F=3L)rXhT(DD33tx0is?W2Y3GHh>DM8(ygh! zb+*!aj887%|Bq@3QR{96yh6V+F-6dz%z#|anxCE;tZ7QQXNQ*Y@1l$dc*bJ4K$u{d zps^{U`#;wK7s`m$07@bmW#fW)HwmG=bg}dEcN^G`tB&&13VD0UUUP&BX9)~odG)5I zh_HX|0~8jn=_^Aa<5|?JACgvMIUGL!d@V=b55Lx|2QX&m>FC<)MKHVFi|WxQ+e|#W zL8jywBA0B`Y}CQX-85qRyoV^wR1E>oM6W{TfS~{y7BlqHgkW91got;0IFBh?1u59P z-M}UJVth!ka(kq3bl;ktY`4QEBe+dJ0Q6b0EZQcnfPl3*!Ljzd;g>93aB0*hwhBH& zrup&KiENU4ZT^rBk-=&a#}T&xK^iT~Ro!L;h1-A?_i5fjnyX4heI5@AFBmdGTz>*d ziL`LPsf5R4YX31A4&StCX2}h+!daAc#hu$QtD>wQN+8xLyeQxZ{x14sW0I}UEK+a0 zx?xy2G~pF~LRK~(64}RX^BFoUOwPP)og3%%agCrjnb|Bc{d%f?HxcrGCE9-`Y=X8#GRm2#0CGaZPua+-$=d=` z`HE7r{FEw5Bst2sF#vqeZHg%O-t3^zDEC5PK&%x*1Xg#1WDPRZ?45MnFbY6-{RJ0h zA(jy%UkiTheqic%wob23#NBHpZ46@&!Qd&;ka0PM6WVdi$PWJd`Z zu)pY`pu$Qw$la4C5gfPfm`|LK{fFjH3&|HvR2`ZQMFP%Z7;)U!2xBR*wY$z24eS|z z6C1r|^x(X;V?A+Ol&nD2=UO~Fn2r)9{6YMir~wElec4eU2`hIVAbwe1+Tv6PB6M0F zA+(~J@%@r&I{3PDP0gp)J$znInGa>tQRB0J`f|%Kj4O^kI(us&$?+7U40f=(GVB1=)L(igdiG{|c#|?ydJ&7Pwl)Rvu?5#T z^f!lCaq}4ThBREiej>XkQDExOXxzD8{eTvxj~oZmVB0Gt+X#Fpr}7Afwn@7NLG^f`XtS6 z+f@KQk>R}xag&`Lqg;2U)AV3&mw6MCEt^nRHt6D>%xku^_F8GfJn{>fhk|6GwVf); z#{kwmPd%D{yAhQQ87zO#0LvU*w`yP1|HO|Y0Vo_{7J`TA0`do=fm!6YqIp7vs(j+e z-MWy=3JtBsB<27etsj$k{Vom(b>1*jwvxYgKKIkL@t2DLso{TAT=SHY?7Plck5NW- z1;^bFvlASp$99rzUa-e+AK7UT{6it^5675>+s>8aAHUC*D-3zoNif^1-5_SBM)SnL zxb|S$!0Jl)$4li3*}A6!Fif1Zuw&|=o*-7kOTUQiJp736W1pI+xm5Q*Bs_GgZD!mJTFWkEWOg91qHwYrw-_;Km zjh_;2B=t2NZXLD4=OuTpG3~sNjPfBBn#3IuW7toIMJ7>>21zHVezu4v*UM#{zR(#oufNhHlzkG*Ka*cHS_TvMcVkGkbqh_~Dx*^IELIIDIH$ZSy^)w#1J` zo9F@AF*1_6V*&)Uk=iWD%){<8{XWrLrD5$IDtL0crPyMp1A0f@%!BFki+<~0?|GZ0 zxjGaLp@<&EM{peYN23F7V!~W75o-9m7M~VX!+n7OOS?--P-}C88ce5&%Y34$P*4sv zWEZ%X(CBE%3H-pFl$u24{U>3IXW;KI;+gLOgh-X47hV1`@AjPYALFCd6FAD+mA?VNI6VDtPcDw!Ju{ydO` zE3vK{NUCN#k*V^$w@ZDq`8QVBK6!AO57G*-h;M|giG2)MxY$_8F)cC^9^|w7HWT$= zbyB!T(79n&Uw|@^{@s!#fqH!KIc-dBX7D~>9ooP8St*wEGrMvo-jMX;Hupv83@DWK zg`=4TA=qnIfg`pE4oz1gQc}khu%i!5a{W2TNH4Rw5YdQk7I_*Y`yJ`E7Zjwe<&TnR z>^M}G*pQ5CG>zg%k|}{*Rbsb3AktwwqT})G*neD;`&8q0zzMRxeQ2aET>V-!-w~vH9fnZShP9>Y_iht1=E|jT$v{G@{$t6#QCJg9 zg(#>w@<)t>tH1_Dsdac{*%Gtu=YJ>tVA9(KN97-;JT;tRZ~QJLKGsBWnmbhGQ%IvH z8hCz6HW9n(4C9a6$3J!wIl;1XcYhz9qrEBdpD?{d9Fj7{8Cp4Y{urcWHv_OmJ%$Yh z4^@#rw;uY?l-~`aN#U^IcnOtguCs8FF~+7GeQUXE{+=9onG4Ayjaa0X{p*=em++VL z#jxDn3+sbPvCgV<-xm5uf+f!EouOqb9?CACLd`Uo)TkuHl5C@pA0;3QGyPg>mQ}bq zp*D`;`?Das+mpv85&DvH`!6lu$fP$JW`oc%3*ul+%wtB%Y+KIPEs>^Ec-OMxlV!1Y zmR$!_4|52ZWE;|Zt7?G~zV}J~X%^2(oC4u^(UL#NqXtDBaQ<>=61}%qOK*yyO@9c9 zjS_W>v!9XBf)^Y_K$8f+M4A&tsmpu^CtNDM%gh05px3dv%@R{6bQ&1xpVE>CjZJ$-20_KI|QedeU zea`mf4XsV$FmX&9<-Glqispapx^aWGdg7EEB++HGnDH&gq=vW4%(ak3sxb60t@I=E zxB=4zT}^x3(csHPbH4Fz5hzcZ7pM72No80TN^m>UF1mX@`u;gvO7)JWRFB&G@03nj z*1UHX$QeR;vCaX;u_cfDg8n~TqM{jg{E0PR+z_V*Ia3!ntLT$ir;yy6F&Pfsb^Gkx zDO{@ZR^;UK-NRj0uY!L;B#->>0mLO{pFnhXkHYsicBMuRua(|$UAv+| zR#CMwpl(lq^w~IgQg^{yzh*#l-a<>Pk%e&z+kw z^?VIgl`yxHEqJu9t>aupL+GgYMbOv(MWQOotBa9@x~xn)I{997Wd0*!a|1NtaP;p) z@{3gA!D!QfCtC3}tX2CuSS8EWkqQLVj!McIncS=}a(hJpUS2vq%ZG!!sDv^t?C%?H zU83hEi*NUikFIl23Pbc??xa?sMBuZqbpp%7XNx5TD1QZVA%*{U^tN6^?)HIG-?&w#X)V<&WZ*uxQ5$@i*M<%}hTYX&h{&;>4PJ-kq_CXzWJ1(yiGWa?3 z!rYt7+ZBbmm7ghmfiw1Mt2?J`y8%Vr^HRabU+077@80%U@_9+wb%4^syy7Tql=W&z zIK71vF>upd9ApZ!s2W*>3*#YvR8){jd87ZOG;?yP)_va zb+aFUkvi|Mj%g5iJ8J@QE_NFQex$**BJzpxxG2ap0Pf&u83hKw?L}a} z2i*_(71QX0Cz{k67HrZa=5m~ZIlo;F`1z6g+1=nWqMQ?OBuXsn$WOWXEsj8i+R^J#&PL#NVQ;IF2Fc| zS?k#@LXm4h^8FFt0}TW{lCafu=m!zePI>fsR%j0gP)G}n1LE%lcFWEi1&^&K%MjI9 zZqdsD9mhJpcbW-j-WcSj3+V9GHIxrDcKG+Q;rK@#!K|X{O|54m$Po5{- z)wYRoPc{`1uZT~Rdum-{x;KEhW`R-l?I4wUB$M^S_qZ}97;Iz+)GbjoT0%Qgv)>59VwJ4;|zNmNRsL>JR;sw zr1?(&tLDprPvUUYpdiWhZ^X2-bFiYIQw1Uc@c?z0sS6F_z0vaUhH-9&*HX43h*uq^ z+egs92a1-JO}BMt>d=FjvkCYowo^1=XIX@GPqIP}7s)Lq5D0^8cJbTnou76KBxr_V zo;WAI$IJ)RgNc-|4Jc>-es~}b++OzG!$jWXqcQ@k&=5N$e+qs-)lYL&-S9OuFrV@s zv2{yH7aGvx?nlzKb3whtNBk>@P_I(m(<}15CGR^FZ@`yzS&w@I`0guBdTXBpiqkpfapinB+$ zw$_#bc_GB%uFi+dnt(U>=czscaxC&8Gi$wAS1ROJBr3>+k_z^UJDoum5$d7|+JRK# z4nr7M_!V=@+V!0?{i+NNk)5uwvG1+VnhVamg`(3~0R3ZUUk#2oaVM$)E0N=j3F4yi zqGwVpKQQj*X6;QsZKN7Iquc9^_?3-o{QQmizPe8Z3cv%Ynf79p@5VwweA9f}XI&Rf z?NJv^Z%Bg4u$wS;5D{MLj3NdC!%OxDK~e>%W(nJL5nn-Oi%et*X;l_omxovZGrS}n zD``*mFJ1tO#7_%95*~8x?lbJ;u_XGWtj)%KN10Df{q?pZ3L6;Pr(;hy&Fu<>hqWq& z>$G?NQseqeZgzC!Px>x#+QaP!O&yDU&g+ zK5>rmdUan>Cb`JLDc=JjDey?fC~%ZRAAI7M2Tl~a%yU0cat&eY%<%}>kF1p6Rv%xl z2!KD2d?m@5mt7*{QKUKIkv)ETHDa(P(We#1FWfS6{)MVRY&HKPF-Rv)PDE~8csQCM zd2_+hQXQ?gLcgp#3W&hz#}N@9X<~u6N~XPSxqX`PWO!%=W65}fVy8_R9pi<%S^Y0G zSuHeA1t(BpUgrA868ffHEshxG*iEyB1J&R)evQ6{TMra(M?*)Ea4ZSB3 zvO%f04FnevF7zkgx7N7&bMuMg;90Vay76y_DU3u{rHHTy$+?ia(Ca2eJOSsz9cikN|9Rgf4u;a2)D$E zl~cpIj8%vC0fDN6nd|%K2XEB6IX4HdsO%P;?Ee@V*WYoJI#8K-l^*J1c=8Dwm{q2B%M=TMsTT=08FZ77GGNaB;QFMiUesZb~W z4KG~1f*Qp&$`yhT)l$n18Bp0abbAA3=0A0V`mYCS9qL@p#EZXM)y%L*mPI_%oGg*BW(QK-U;P7t4hpV6#IpSv{^z<-Y3Jg;l z?XE^MzFaRnk{o{XAfI^DZa?tdStO1lU&J!?YH2##OtD5bb^_r6GvPRA=r{j&xhyaf_vlqS;@=ls+8cH3+RV0>38(VaRY%O z#mr~A<84^uG9(7NBOE+Z?rJb{SM{ve7@LD6nLpixh9;6B<@owAmIOCzFbVd*%HThepapZ#PB?R+W9Ax!fqzDTC!7WIU)WKX zY?>3jlhMszUCJYgu9%9811FNb=F25E$NCH$COf218;=WD#n18Lel^VEqh6@WoJkmJ zZBGwq&UKC#5$zQJ^`)@vGr0YHT^`-cu%3|pK~Nw4K6qww7^j1Tuz2t71bZnXH2q|aLze}t^L9XS&(ctD+f}o_7M!)-7C|OBajYlpy%QwjNOvHq zprdZiEd$2KutY1N{D zZpkUwzng8!<1zTc^`_B{4%E<4o8hXCQFraFdMrP|3|BSGt zc#JRj@d;RuLDC6ySbWCxE2{#JYdY2Vwi@coO~NpDZMK4240ej%$mu1+t4!Lc(wI5?bkN#8UU!Ex&)rukNvi%K>W-yR;<>R z*v0G{?OemH!RX+Qi135m0><4ho7Nre^tRl;cmW?Is6&Fo<>V1=(hMBY@APOz`KE&7Qq9_6?%*d^s~Y(!=+wIz&+-w{iu#phbhI==pWL@TppNUz_h`$JA?_PJXAd zG2@_4kiy}EN$R= z;gwlP%dot~vUz>V5IBtzYyfiwG<9W%gYm&n?JQICg@wJo9L#=R=|i<9@T62@E5rl_ zbNCUW%Djf+4;vxx#2r@+5R0a3^D=v4B~~Gr0hNPRDk>o%%*@GR#AB|n))Vl5quM<) zJ4-V4)6MdVmVQpI0>RmFv+xAoW41ZG2LVzCuYW|9UNdqyiUZ+@Y4h2qaq()E^04#28Ob3#npBMZHq~E+CmeF& zj!O4!C*D}0_1dw)${b}eWF-;jiIij6F1C(OGqpGbykOe#FDSMg)1Ocd{%J{^)l?5y za!IsWX&M62aafZbjK>w=CN-2P^c!UO-lq3EX?MNdRSK@?O~ho_mVW1~`gOo(M`evJ zI(mkL^Zxox28Qvt&sS2iy>^WOf$}gC2!ovtmdj*$uX(fOP??&@H>nDkT}$M5tR~_L zE$uJ*gJK)(ol-dT4MLfVc6MdZ!)}f}k{%tNEcj)2cTGw1appwpbuY{XFGfWZBZCW z_K?cq8~_f)A@%X05utIRl78Qt1icT~hI=l_4|d^RhOOoK{uo0z#Ed;^yjS91y=$A( zSJT=Uy$E4n9h;dMscKu|iuk+x3l(Zq)lI&pf+oGH{KqqP3`GPm1|o?OU117lZg9>X@Rxm<|$DP?us4OX#wntwkaklruW(oP%yj_{Gglo zQ70B5N4Z^4S(;1R{(1gH9KfVe=%t7Mz+p5=s>>x+V*y^03DXMu3nbN8GR=kzDRS-? zCLCE-4Nwo$uioSzfTA);8Aw-mEG?FhN)@~RVImtD+V+1LqnT`l{y5D;au{pM=LV+zoJfF3j zZyIM-8M(LtUhOGRBTV*l3Z+vB*ODCY$~DzlL`~IB(<263cnk>bKR_y+ zUXDK?oQO^jx76?^tYQs-8p{=|5RJA&G2$SU6!CS^%)i2gmC1eTQzrFWI5aTg24|iE zjarRduM%=`8TaztRnX$QjytBg93Hr*r)CyV>viok=w%L`)m*EEzF~5~pfO*<)j%Si zpQHDI*CoZdk&_xm&c)UDUL$^eOgZAIQ8f@j?8?y$ zslnh2$b(`;%8+N_Jvc64^hD(7+HH7~Tdj)^4-t(w{*Zbrp?^{s(&jBOazz#8hw)NUSa;h zg6NcI_z>}vu@dz(%ef{@YE4DX#*VJVu$W z7K7Yh4JcJ82~{;I$rLS82vs{5>@_&w7I&-CI!Q1pt?8vP4FR+$9p zr`Ti_AbzdSwRYxRc=$toHx_QOC0* z%`kg5WH#acWO;G^=0zl$?xv?GdU+qc3x@z%LPBCdgLXaK#++xoSx~>r<9O49lcI=fgr_a{n;uWM{SS#z1&6$l)_GNWn<0mo%ydUR2TEC^$gSRWM z-%?COwFQ}yxpbIhI;8?p9H5lPPy6i9@<=voBbzPT-A>7SJcXV#0t(JGK%2~IQ~?X# z#QDy_rd7%iLI|I^9uoqOjB8P$ryK694@cT_k<=2O#)qI^{p2CAJF>^P#spcsno8dE z*#Y>`j#ZS;TfRd$F)JuKP6-fApx<8?X7!Bo7na(%WEkQjSq*~OjIRIJvjkWAgNt}T zRkbbzTLSX~pW^s0p(EU$`GD-(a3RX7+Ic0w_wdJ-IK5l?9Li4z$}euALclT`LrEMU z1O|*3PL!yKKDn1?m)tAX!JyZ*bx)Q@or3m_$U>0;=OLe{27w*`{BoqR|HF=s?9L)W z6hYSMep-H`Xz&oE|88gD`P^=hQ^<=A!+4KixRa65RL@*2o#>M+h^v4jk|OMLbDl1uSkxRrQj9=W?4Gz2FvYQDp;z;k}cwMa_FrG z8o**MiRdV&Q!gwtXy$X&+N|@47}aE-4CjuVelJ1mIIOD53|0tK$fMK*J`p;d8S!Z5RIcfwubQjlVb8s5}b2$w0RQD(V%)VJ3SE&BAT5U zIehDeme&H)E)Hvqa(P`H8y~otbABYj#WRT;K(j60g*ItK}+neg#5de})Er_ZJ=y_jB}kLYme&_^^Ay-v6{ zdjUW^N%^l8Y9P4L&#S+@LIcp=7eQ?P#LpS7QSgLfSTjD{c?&fbmiLt3y1vYKV!8`)oKZg1mYxRzs zYfrW?_^SEtgO`h2wAD|hyO)Nj5sx0cz{T!&FQUc%412|hHPFVik^E2m9)k+yFVd>_ zE~Exu+CHBZXgDVF3!YT|_mA?}N_ln%QuB3>GSVH07bK<*)xVT3`$Sc@Tcgxq+wJ|e z+*(3imW)QYLXc*W!t9I@R0MK0dtO~_Ts@31v9L9cT+VFzap)VA5GmG(-0+c;>Z;cD zM;Ae5FR*_1@A1v$)>>OR)}2$-M1B@AVr|v6(-$}|u^lm9^73sy5~)(`mu|f`yw<}g z-P2BvoW-eGY?7VHLSJJfz^kulO8!cG&Cq~j_Mvf-wGgLH;#M;i>sjWQPC81%+l9?iQx;p(iXHaeo2#4-k>}vI~W43!PlTqh;y38fH0jST0OpW zhXx*`@hJ3jMo4*EvU;JzL}if^z#9Eea|||_^^_Y6aS)mYV>>o<_jb03f=1-pu7Hwh z-A}IZYm5_x7)@3corI+pmo@@8f1u)8Xy22;_u|82E8Cs_r3-3(%j-Io_JlADK`ri7B5)|7K+wg8m1RFiHRpFm% ztDUu&P0tMGHt|=t`+Ouwazw=}_JNMyy;usRCc(IHdk~V6AVzx50DI5m&y(oEhrbbW zIQ7^^5@nOYEi#S64hugrZQ;xFFTU?Kdz?O*cn>{B^FWiA`3vq5HA77zBS;u=XcrG> ztysH-;Pg`0ibF1bVz)R7{qn2saQh0Q8XP~f%Vblu#%>~VL>C#sr01sWr?ELuyI0x( zM}Agzb@OoW@e%2qq!My8?tTy~ym@by4W0O@JU5B4gyrp(y0IA9H+dhSjzQ$_WKNVb za4iBstu!|7KmKAbD)GH-!X_LfCHU5TqccJ0{tqh2Tx7V&ojM96gz;nPtG;-r^t0OZ zldOPEUH`{3%lBS9=yBi=lXmHD6#EmWsj~YM0bsw{q71oU8zt#SZ@Vux?^Bf|0TAh8 zb`9H_L9?dB(yS0)cCH+t|GzE7}jSWOTEzfo92oAKofuYCbyh4K&WWFx{&_B-g67 zjm6#H$bzzJ^N)hI_w8#5DEiSFxm-AHpx59i4G&#K`wh3{h@Vh&+e|fvxM~#zy z2dc~EKNt7cnG$s^4UF^;g*9Hnn2# zj&d?#!*O*G4F__D7Z8bRl-9m#>nd7AxqW3LFOC9-$2F+v46@2iS?4OA}n$EV2;b~0GHoh7-5K<`6G?N*de>!k6 zg>KI=_{9&;PZicb%`;h7m9pqdy!9EpB~ZE~yS0+NX454x22el1?xV*j=6(sbCHnGV zs!-0+Rc~Y1A~bH;^>8$#vO_n`XTt}lbps&)2LM$@PX$;=x77>L2}kqyEOW9<6{>14 zy&6qNJ|;ulF|d2nr;4I1-)~B>4b!UBT3wom6MqeU{ll9o3ktz-8$b1I?~kVLlQbF! zH)7gQDL&_lN&*I8W7a*RknyT*%_g2ag-TfSIXm6y3%=DWs+6Sm%{Cg423#etD@Hj3_9a-L{LC~d_l8h4zJHOc*1dF%*G3T-@vIr4CHs#4y&oe zDruDcR2B7&!D-;lle4J1-A_-;l&mMsY&!Zs02RJ9;=|*IA%&b5L@(rAMunV)FUr;* z2eYkL=Faz3b3%6f?NxbV(%>?xJMHM)stiI226H)S$)tEP3|s2q&80l(B#iye5?;!g z`Gk6Tq$eFFpkX}7KI9FiU3qb_Iz4ssEuR{JU1ETmi*&^ve)@s~LkSn23)eNoTd=6? zLry-FGcpq^h?kic_zK27s1DtYe|l|z5!cqbl$f}mvKb`WNC){KA?`#kxMla&zdU6J z=XH0encV(dPy!z{2k_&e{@&mn`797VdI~wGBp6G5ThBK-%gqLbkNp;%JE$`OyrAD_ zC&4Gl@lxMt=x2dGi+dLLO_*du(!TK7ijSmB_%pfBa{mZ;s-eJTp{W#d*6@rzhQ~2o z16sT&mQ#Dx`V*gc3Eeew=Y^AOu;e$RtFDOcw+yQO8%@Az_M=3LYdg`@?Pd=RbY-r? zmr9RIX&M}FB&tRISQ6PG%PGQ|VHC0)ea;{@K3TO+4D+X%5wh!OFoAv?r`ju6M?|(0 zr`%*_N%qwnVPl0)KP|_ZDEdAVhM6_cwpA`)pYF~naGZXnaNssd6pl2+<&Z}MYmIYb zYj#)8fE;%BqwWHpSP`?H&HlAy9Kf)7!N^w%MD@CK_DDDXO{dBMPhh>kdPOZYAcE>) zuxe8|h!aUH@U4RyZnSD)6Rf*)PMZGjSf2DOSPK$yXNCT~v=s%`ayoAP%yYGP*NViv z=$ON`fy+XfSmcc@Yy^c|qAb3VcN9%*9MoDIt+a_fpKq|G0TA}y@>#1N|9#)NK2f1?=sjrzz<1Ded;)KHk`A+Q*O$b>Pb7R9p0p2P6Y zq3{nZl`g135&5~_f%}w=ehU{ZjlI3S{m)a&42k*BRc-Ib?RrAKNH38}IHxD3Ca9$I zl7u#RIM{PO3s){Lf9bbNPbu6cbfjrVsw&hh7&RG~)Sh@Vtq#DJR|IRF*yF<^@VIe= z9qnfHSgur*m{LvJWR4$eY-F)6Lic~!_$B_l8bU{AVgQ%Ne)KGNK=LR$Ul)4iD4NCF}C zfxqm)1I&@Y1SIWR8O~!7Kj0lo)bMCn^r@(> zoj28fuC>(QS|TTmB4k$lRr7}N{+RVL8AHEqiTCZz4J#$^--3p_sw$_Z}NBmLPvo!3CV6$b`z20|e zVwYQ9(-GysI`Qlp{gHF?4jFBkx$>cyc8s|~fj=&vJ_Yxq*;Pmhys@(*0*r&DycPsf zzymWWC%#G?qxP}bxZ{Wgx+xT1zuwIHYtUznk_0bJ zP`^;mP9A-bh5&k=YRoZr&00uL@K?{gnHQo--&f#6Kb{K4q!98{4>;fs0$9<=6M4&{ z;a>4lp1F%5m=S5zrzkfDG>)IglRszrk!`~Wg(S~0@2XIVjAo2klo$ULU%&{6SNNo8 zRrV=H@PC1EKti>qMnL&A!c- zn_ZBvY970fIAWh%g6uZwKa-0<+zYvx52KyDy`&ncPglb}p;cr%XBsHZ`~1RARm6xE z8iu*b(8Z4J)c^kylu@8wE_dF`KZ_}Rd6b)5Peov4slPk9PAi8jWKtiROg%rTxb7GJ zx&JSf`NmJ;PSr&viM7OaeFPm2_*4N4c|8-pLybM6OQUE_>E-b*oVcdwxwwDa?(T&* zYn-Ds`FH7lb79v5(lup=f`_dB;WEFKa=y>Y1T9>==skXvMmS_+qKUD^{`_59x7<75 zq@H_Q8=>7o`GRkMp*no}7NCk4pMv}`uqhtj!A{|;<~D-)qYv(%=SMKEF$3Lo`?QV1 zmisW{s9u)|U<(!2RKL~#xFVufxDZH|z7Tc#5NF>+zg`%+0A(6EU#-NLGDm3wG$I@f zE+FkAG@qDbZ_YP4(@arVXSrxE0l&{i+xqza*9)Ng zYK7QEIcdJTax%W?z&NcHUa~nvHP7gY59~9J+JUUnENPh-!~Me)-Xyjz`IgBo<1#s* zre#y*n(OyjM&FEEiU_a`Rt~qeVqnwwZIx(45yzY7+<~K{PBP@PNL!~^6miZi@8&{IEya0ppGnC;FM!9 zv2deG2RGoxzVYNA_!c#C2aUz&0A(jn;p=mw{H`m?Ne%kvzhXu;%nLVg@xb#jjM zDLcNBEAGsL%kmpc9eFTgg(}x0G^CMHqriEIP<>A_+AsBlU2D#puA5{NVb}4O-=&Mv zCuur24c|n^G0oFlXYbtZNu96bB)pb`Nur$f28_X+(%J5)2;WgV85ql*21$R)vIiQe zLK3gbuCb%KcR<%bq=Mz(t-`s&NnaFZbPL3szr=czFy!sxt`Mrd6<@fAJwg||=BFh%2e{Jx2Bn>H`Cs4E&e2`klEK&JRm63!O zmUPKV5JGX+oK21sJ!szzp;VodE!*T)57&%xBV=*iAHs8@9OZ`j_mN?;4+5W}L7{*2 zozdyNS<@B)S^*$8>M-UBpc+2e9E9W-2YZeCJ2E!G zFA_o#9o7B|8RfNZA|+1O^_+X|alawwM;On<^fv>_E$$=YqeU+UM$$EUEonw6>t*!b zeo1{%r1R)YwXv7DPzGH8ZG^(mDZS^vd;gDp5%MyFw#Z8x<(i`Os*3;MrR`rhY7ONI zV^Qy=Y-15sEwqh*)AWi)s=^q7Boe7 zI&V(@q+Ab1Zx<82|1Y!cFy6)?If~68tfg zNG`I~NZovd2CtV%-Np_#H6$EUqv#!T8nQT$gx+=gcea7{DeR5MxKOqOOvT!A1DZ3M zF9YQrXfrQI9-Z8w4^l&EIIO)J@EbJ>b*A5an=9;@{`a6|c)n_tMYKodeRlcpKDI;20Wx_1j*-QcQLi>FB&f|9MWd-3r&p0k+ zYWrtXGlI(KwZd~aA9k9DZ-QPbIMMK%K9|nb`+f}_w9?U8lA1Z+Mrp*S+t+%L-}AlB ztq2e1F_&YSQAQs%V$MOKiEo=D;AdcfEYzPG#u(2s^2yz+acUmOA9V^LAqN~lEis}5 zikslFfb#*4Uzfyc2p4u0t9gFeg0j~C2mlrV z#|xXv&u4eBBaa0?H#~+`+yPA~>|o>n`~<$@sNj_(~G5>AF{ zLt6KM2Jf9;vDYJh6MUYi9>Op-`FIo>Yz~fM<(+QO!bfAcxf9@$D(x2~hLlKEzaE$L; zZhrcvxOOd%hMl`NtG>5JYey0EfLM%^vM;(t!k_9sH@x_#2N-g9$*^B)Gn%e>_^^)X$mvvE_V8Veq!hY_HNNGm4NZDeO-oJg=PqoNta7}kwIFy9^A1q`3+Al25AC+kgY);@qx31DM5_dISXF-2eP7N9KJUB|)Dn8s;U@!YXqhiG!|@yM4+^ z!k)YF1PS&d(GMH?smfA@Ea<);C3=uHl{CTTLz5*~sTvets4+eexnr>oLV&z>!+J+O zKdhyH+_})EFRTn0uYj3O9c>uV$NUG^!2R`PNz~M**X=~by6X^u;pc;*Qk?5KX_RY| z`rLDjYVuP8JgEnneYu#4xn9}&iaoQ+@uaJNcfw=-)BJ&-0uSf)C9yIcj?zD`nOtTLwNHCso$hVzJUSpv$B$qRSW8t)_vx+6KbN%(gjhaq z$0MwlN?WL{&!)pBRXNa*D1VI2J|@0SV@lx9(>o4S2S@{Mj23`|2G}$rS$P# zRWvwS4b}xd_s3Nvw_HCyvA}QuRf!GBfTa&6>=y}Mtdmtuz_vDwM$2SZ6QnnGeZ5<_ zBLJf-V9rQXS|Q2SbV5H?mUQQvWow?l(ZzFp+vx5eH#+*~UwGw$)Z>uHv1B*H4{>-A z{aL=??3Tw`wpcSn2Cx1Tb0cE}GKq5=+hS6$-*{{J_X?=~jm?!2hDoyD^=&u17 z0UNvt2_d{pZN^4yt%tOAngqU&KxB2f{#lk{fy#Yt{d|(OhWURrAA0D$k}p#$g3+g1 zX=Pc>++cej30)^_TAS*PUsUcBXYzzO%bRufJ@^zadIon_(A{s{VEKHmomQX?83Y}7 zxP&iDFb@;C04>G?Jl+9q|8s;UnDU~LJu08vVm(Ze7m32ztYw#&qC0o}U&9trX$J0H z&|~E1F_)-XffYfw50UluxAE41NFJ(?7e5Rf3Mea#n5WUIo*u~z+2$9bi-;uvU*CF0s(x)11|Ttb6wSTHu>_La`lSC4S8w6fR{KSN zhT!hn;1npu-Cc_pcL`S9i@Q6;-HH^K;%>o7DPG*6(30RS(#iXs`OR80e?Zoi+!_I~ z=c=-2rJG`;IC-6nzJbs?=ds@vJYoR_#384W$seHa z$r5?ewPUK)Qh4RNEoEs6+Y9G&mug&lKcL^`wP?Px)*{>2*0{KCUX7RVyh!xAC=iGU zW=TBKlPrCcebD62j;3fSj@p-$tCsspvy2#Lonfu;DYRm^j)xPCO8n_)cET^96!%?h ztE)+a2kNiBcigK<25)Yt4Zi(x{$Y!B2QN(ZPiKGSHFq&h_MVBnkcnNQ4Hg}+L2u% z?Ckmfq8u_qUy{H%@)=2Bw3gVx*M}X!f<&=ADO1APE+^jxz#s{O{fx*jPv^>t>Gve} zz8vX*u^uzcqi=5kUD#pm$nP^cix*Lc*s83bILg;RAJw3qm+PCIolQ$7g$GtAeg>Qq zNcQyAv2oakd67H|2q&a17BuCc(FmDq!8%2b2pz{a5AmiT^EmPGXyQZ{J`Q|0x_Jve z6)7PCQk<0z6;R}ioeLrj@$_y7Uz zEMciBxh)pW6Juo8eW%Gj+S%{uMO#x$tOc9{p za?*QBTa8SARv*Q@`^%AGlCFqxXpJXhsg*<_`cfZ21aMA7%enCLTH6gTSLy zV1M_XY;B>~*Kflyd8PwlcJoGW>*E=X&-0v>QDX_S;<$V$N?U;`RYW#K_r2B%ZGZJAb6uRXph7RuhCxQJS-RJg*DK}*{t!^yR?n<#&;J$Dd zPJDwpG?^cLe-!yXqY%b!86S^sSERKxHbxQsD=~x1L+xsNes$gz&xh&HQ;}C00Gf;n z{^T*sN*Rl@Qm}T2%>62|g2Dx*%Q4r9asu=u}m^fm}59L?#HRa9o9RRr26R^bJ*sOe33oAc$ZNFSZd5ey z)6+yM;n0y2dwFe>ClA?9lS=x57=>H*!?)IG-;Wj-ol=NOT4d;%2$gao&MB($1 z;P#DlP2%?uz4Enm=YqR3ByoxNT7^rlwPX0wGGWehl2y3&7pqq z5<~^f7rETwWrRqXNphDXx{Cjd^t3nOdd9oSwkTdrA2;=^oX~sK}D*XejP#=Wc?1SvlH(tm8mUjTT zkESN?g~CGAV&AEW>Hn7((E3k4Oe#VCXKG><`k(z)=e2^K&rmgD9ZUR=-Y@@Wkl-vv z(nsJCbhKWHQPI#$k}ob3JcDy1mG`-SQ>h8_a&dUUJ+ZEo)LJzdqBA7 zvpGKUph?eAHo{OeuZZ~Qn4TCWo(RaTN3(Wk--DkPEJ=>=oE)4~`Wx@|>(Ja#2HYqm zTW$h25a%&%@O^bq&%J2aXQ&>9`^pI+(Zzg06<;VpI{IInDr%r&+a}ki{t3jN(7vOLq>;P>R(_CUXF*{Fkz=WIXCKIY z=e;Q;)97|-I^zfq`2FVF;`eM8LuMQf)6uf9BExrTxUcDPJU#(^G4mugJ~d2zs%&^} zynF^X82tE=4VubkpIN^5zqx2=Xt+1K{2H?Z`_mFU3I7F;pg*}8`O&P0oeB0JB2vuB zZ~2}$Gi!*)E;oz*lky8gs3#=cR{alauvG?SkOsGgc702jJqv&J!Uhq|Hj9GErW$cyu-@RdS z^rZsbK+3X2Qi|WQ*wh#QeHDi=h-2PA(pc7wb_9vR z&G#VR{hApM?vkTZT_hXpwC#Xhyi%$IlWf?Oy3huGmG$FE#e0hQ=)+%5`%u!TuzlAt z=;7LtW#|0`0^t_p3IB^}FitxZM$92-S-AmknV`UK#tE7G)SAZIc3N?pos!?N8ZhFTtV^t@9q{zsWn?azscla#T@x;dtFo-Hnqk^fd^5*&n#e&j? z%Bf<}*jOAKIYrLfeKv%fiV$Iqv(^4C+r>4q)-Tr2($l-nw*qoM(6GJ7g>gf)H1V7M z{d6<&kZvo%urzW09oT(FRvs`1Ek1k`F+@hO`0(+HlZux=q;{(QxEffY!y=cD-y z2eTwy7ondTOlTc7=uh;DCD-Tndq)-KnYpWa!Gq+nLorap)mJ@TSW_FJ&7fW4^v|DN z#1CG40sRlB$9h36ewG3 z0e$)Qw(RpQg<6H+*IH&bToNc@$C7*qesABb2?-%xvoM<4_VO@W*{*wSH1TK?guzXD zZ}|lM^0S(y{C2~qJyy@I9%!zloZx3#u3mn-|BeR88nI)R`rresufd1=<#**~!u!3D z%8MM;fiTg(A<56DbWezJH`zX7-fu8z)no<`aqx~NzJoaw?qx5cd&ZFP1AJV(*O)>( zUWwGjKlorJn&%rguZZrkLqa>qPhP2BIxUvdLtk;bz6Ok+AVJ@WbCbsJ@HGgS=o%SJ z{KI`pA6soh{attlWPHuN>bpzaMt01$-lLCjUmNdoaHy{YaQgN(>NTJtbEw~~v~8{Y zr8cgQGEnM0xWzg!L3Nk69!g5u?H?#auYRN&XG+$@UU7A8D@mpw|ANG(MMpRWP)lXDN2QZPcKB~|() zo_7_cXzP$xO@H73E9Z$`VtufuV)Skc2dq0JHQ`per2KrnrjknV)IEVh9rfHfvzYGT ztyMZYEzG;_zXIbEvR>`iCEH0Q@iQKo^fF)t%Dj+t?IcwvT1`HNWTEYj4$%U7)t@@m z>wbx4d{~XH>h-Oy8Z60Ii=pEC*On9$059OVd65GBc8|DL!m zG9E5+&QDCJ1@3_ylj^bxmP{+4lJ5Y;dNQ%mFC-9zqp0Ojf^V7PD*h~t)_3~Oikh>` ziO#C@$En2=##Tm)$#%Prz@H3$l2r98{z(Vvy>=T@N4f{@?>iGe0|Pk1Gy|z`{DnVQ zV}QA7Ok@ED;Vg`k!WF!TNYj3IJez z-8VPI)Y6GDb>4jL-_p8y+6NN1!nJC;D*VET`xRZI$7*aqz460R%Y@28yBuiM_nSTp z>k(HJ^%?7K#ypaS{blZSEcSl;G<~5C_}o}1`Sx2@=3=O1!-;Bm@*8e@@l!iO5|-OY zjzj*{Jff0m?oB&(KwY&Lh2_EN#jpKIn-%wSW1rq(seD8LDdfc4DH0dIWo-~L*2K7L#o<2kFie)H#|q*D)?)iPc;UVH5h(Q}#?MX=$=J;Uu{sJJxSG<;+&gc7|n28EXXe*<_z$pCZNS zbuk~D$4gvfqj4*rqt;YQVce23>j24HXKmSrzK6%RT{_G~>^*I6i;_EQaCYpl?rWYe z%cv=p=SPU^ljI`njzT31tG}L$9;r1SMb*!-WKZ(=v zt}>~*-@~Cbc-nc%#ie#We$^PJwDXQta?u{vY^mfyIM^`#pe^G&i>S&KY4TT=SSyEnxbZ}j6^ zZ6#tSbi)pkBy>XjJos)xtiN+@8S~lN@3Hs8yzz>}Gq{}B%_GiT?rMzX2`&3jB`1PY z8Si}u0|1@W$({)I_0_$yDaV1=yN83XX+|x$+y@V@Eq1ZIOc~$|AaZ=@1pOMS#3o(>&17ZA z+W2vLUvkkWjAvlZuKXQFFk_T}oyDe7sI!tsS^V&WNSrICTN#0(#X}rTBno3m*Va&rHU-<;YX|w+ zjNB7>FvBt7u^cwe@mn+eSjhk+`dG^wkoh4d;3ngW1TgMnq+kkNhHic>BQD>UWd!|AdN!fH>LOB9w8CSX!vLDDncR%^Hy3pBz6E zgfS2Z{IDX37wN+f?xXjNC>$4*@AAd17`{M`1J8SGCRVVHK^XCjV}i{u8rWe$kki5s zq0kgc)*RSR-i zblec;OD@>RPd9+y=D9AaIX&ZX=!YW{ISDp(gyx;y zsa4LSj`@r-PXF=U#^_Upm|!X#|0aLBCI~u^oryNzsnx_ZU;J*fT2vR@xL&SiMjfim zY6+9LuHW)*`z2-YShBe8gtsqREi(5(!z+KW@R(o0alnB5?Pw~_K~M^8tkXn)<8sy;ku;gxxaHVoJMtg5pg?v_QFoh`t)t)e+VOEk*DZ9*H+WTle{LUk>)>C1Yu|$iiaSJ|p-C=%w<)mek*L=3s-r=s zasJSH5A`-V_NIB)>f^F`oHUqOlm6h>{;-kfyOdJxbMKV*+LWt{2gt|CjFK5@(JZ%L zb|D+$*Rh)$?=Xs7dtYpEwa=F1RM_=>beZRY=)Iu=VNHE`#DqPgyWKmc^}mnZa{Hl# zMD&+qaCwhX7q#ZzHL>h``*hh--N@l53ijZ4rG4S4DyHCd{YQ*p8?zxEz8|mg2IDGa0Bg{C@a+*6?lmsNaf=h;^}I z1nxu@j#1c)FSaNgl->gMznk*Vbzh3Fu>1N}bs_=%L&;@w0(_-JfLE+=1 z;_{$Z?8#x~yCEV<$17;DzyioC*d0VRK<=IG>eYgf z&sTr$IQ!mvsbf}oaJ20g9dAI1yYh0!r9nVE8-Bx}@wZ{KY%jgTIKrB(MprqG-y{H5sTc z+NJD{DOflwJa}pmfC$JyGa|4_Lxk2=x8}m*Z&1%W&p+A(4b%_quV*qD)FYOPy_j4B z@mQrkq622}rm-4^q1zPVPmzw4xbwDz;~gou?qX1XRpd*!L5W7H|}gesDb&sg_>RA#(z%(=G!;&U3Fc& zvR|64QR)lPi${R&!l+zXS@5yElrP|va3p2YU16&MJ)A8HY0%ePT@=PkTs+YU9i4W& zfcxOuI`_UDz@$%i6u5)NPLT=ED2Ca@CF1*5YYLgt+uy?+NbdYe1nHI_+ z(9$`EQx}S#ES8o5rI`Jqp?J1A02YABc>YHP+5FOBS#R5q1;!b#iYpBoS#yRAl59Ay zxURmYtRQ9e!c;Hm9}nS~iwzmB>(--1mb8Z4lD7ssZ?;sgNeW{_ighnt7M%(o#GA*G z@ZF4UKSI3=60$~2sW<5thS{UL6+`#P!#agMM(qtYQmX??&O7SXlQf;u6f%+rDZpxf zZAU=oh`n0(Wr*>EeMtjXcA$eZiz}@^UK~VIz`DK0w;N~{kO$=%w#W0c?Hyf*IWk+v z6Aur#ILC-_;$ChM)_HUV=PYrQc61kxA134VFBQ`CT#oJe_rQd~sf<7myc z7@ZH*R|6Fzc#T$HS1mUEe%$HmyR0ZO;gv6ml9>CZc%y0EYpn{oVyC+7qnGelv4U0XA6&?bIXv5?gQfC7Ov-UBkp zNdbJdhhLH{zlqYt)(~YL)HDMq+4&eNbiyMS8&5Y#cS(<5Z;u2Tbu}Hyrvgb90QN}E zXBZwp#wPfsy!1OPn05~h?#>)RLPtNr=1C!&#P$t2uvw{MfH&gdDys9Cv1U!tnpq7i zG{ee+K-mg%@GI~q@p@E_cHApk1`sU;CXGFkeh!=gTv4X;LAzfZ>2HC7Lpe(r=?p`& z%flmDB$k3jswF7yuI7ZH@K)lu>np=(duV6{b-~Zk!gmd!(u4I;TtEZmAopuWCy@=8 z#;q?gt;9CiSxX|?DYP_<(_sPjHkjkNI&{vY!%ceVHkdzMpfu}+&tgp~H^OO(gcqkHSarP)Z70WG~paj3KaMA=c70G@)0=W+* zqhAI!A(+^J!?CEoq38%Q+oU1Wx&!|=u3$+BJvA!ctG(cx`*!4C5pu#mSbm-u4w})X z!6!J>1?{x^<7@nTCBxy8!v&@>qkgr0z_r=ZX^;;gzyw$K%|l@A{?0i{yT?UMie)bw zB%EH+Kfhej$0`vUDerlf0}M>)TiJXv0BC+tUtuwAsBFkR&6ouxA`j`3fcO zwoa<{dE7VS3PIUd=NK*xI$?~fDT@ODCv2As=CL%N>JkNIkIwh3T@|Y3V#EOFEtceB zF9G}QF74m2bEACdwUAw(nR^r80KG$|{eTyHQd)~YFPTx8eDQmVJeV_uf+P)JjJSB`Ax(T zb_HfsO7kj7)qeguvGfe`d4z>OXD({R-V^xy~pCl~hWSpLyQTq0qdXTY=KaOSuQ2$|%R zd32n2JFH6pa`zi)fNp}kP0`{L7g8Mg=%~(GlQ!3a10;x+ZVH<<_)cC1X(cB`wIY>K z`nwp$?#wfjcp`Qw2PGm)Pk$G1FxR$a!LRMI$@=lo_-CvqKWiD%gh0eOwJEmg-st8t zhSk=`%`p|=Sbd87 z#?Kg5NE}FfAc78U=U<1%e?8)NndM*dP>^K}<14mUObqR{ZmKQ1zJZk{xo1N-9et02F@u6)GEWn+84{NEh$-{$8bb3VM?^;CG@M-WWzg0_kE%&&#vbvN5qlwrF4tkS6BfyA>MZd9vCT7^PG~I@tV3tE>+iAxV1>K+VV(f@Sir zN=aplGP>xq!e@&E{J*?Z|859po3g+Ki4hqIe#It|7kgdWbIM6!M=X{vExcq0M$XMZ za0}&3|Ndnel$Gnl3BBTeJU#$j9U;IYlhA+a^lA8uAIX(7Vs^sMBjC20%Jb4*IVH)v=+d3` z^?#b~1AntQWI}LftOT0<(02CyuVAo}wVP_jmgJ&K-aB=cF`wXqM!0)#{6~Ugg5EGL zXru&?K_EqZaME1o!!lzjUZZ%o~pNS zZZ!E9e@*UA~N6re!zj2FU>Dxvn5;XO<+AwSA3fHoy2fQo_mOk!}9mBt`+fB zzXPhsRYD^7*o-8?-a>f4dfmmk*Lug9mRH?2Y7ouA@9ctyXYYFB|N49Z_IJGOodg$O zbyHp+8(F2OGGzl3RWl4xcq_tE;|nUXQo~zfNrr-{qe`dc62kL7NO4mtuTwYlyt7VD z5+bzJoZuPYXi1iNvE>D%Aa1$dwRBoP$ zH}kxh9>$kyn@-WNqdhmdH6OO0#$wNFjB5K&i`)GZNPPJTj?0J02L?q}+Og*t$^vlM zZ4cMp-%gC}%c2Y)ht+-xQHH-bvH+s-k$&0noDu)vC^OsF(xg>lp$am?spjp{h6Mn* zpDBm&BB@nS@i)C9eTr^X^6eVd%cpxpU$C2t-9eAxT$VwVwpq^?YMs5l)oi9Ct?&J; zP*^w_Niu3U|K?~g)O<^{H&vdNI34Gs6wbtH6*7rdB}$n#?DWriUNi#T`G5J3+cg}u z54qSq;b}!bgxfw`NspwwV=RcUcun>CSj?}Rl8YEYkv@k3Lgzex2D$Kydneh5CqRzA zpbh>fv$CN3w_t0n&Y&7#aCQP(os%q7!>W0Td7+Ej@Xy!cF2&V7fBk+3HFIg`k8?lY z{2)cP`+oS2j|@xS(~;qx&Z_TK7KZ9VP%VXdu&DIk|2UgXw@g{hOu_z3YCha7-sK3j zqZqNt;oSXMR`#9_(O?W*0P9J6hU4x@_xHiPiz8^-;|sX~r75M=djljcJDY*PNy~d~ z_UW|>oL-@S%+TV7IeTE~>dYJ91^0OA>itgjmE?pNjwF^TXO||#BFHuC8RndFu9gK{ z3|0n)Fj_f>CTV#)Y)sQ$JugWLC|boB5Yvf5EyZq@e}wNo|A57L4ix=Ug_O_@xRm=Z&UJ)VZ3q;vTz<1AeL&`u zq+37^s;!P4EK;AUeD#s7*DcKrsp)<8x!{fiRPE%YeCvjL-;AT~7h*z66NZ{!|E>>O zlWl}xg;?hoo{~zr{m!b2T*sFDjT@&p!Cfy7b>CI*-{)$X%`Y?@`-K3Ct|UA3hlXJ)`5Ez zX)CIfMwc>x&>Mo%dRsewUf?H+xNlh!WHPtr;&R#c0jbwd>tP%d-+%n-VLI^38(xm9 z1Mj~aNkft{t}Y-C@ud^H!OR04AKJGBvs}8;1TI1a8+kk=VDE;sb(Nt>=sL7FHSO1N zm!9#K-Im?ak|9&EkL+)?t;*ar7!OoY=;knGO5%wL z-+7J5mw;F>2r_7N0Im6_SKrQBy}P3t=V^MXoSvwW&Be-O>E&O&+NZSM?-416L(1YG zY~H6WP2t?y8aWa}9|=0&N;6V(N1d4Sb@;P>Oi{xkY)1F@sp(AO)pWYAm56>_oKz}y&71;|{bbmzi&ArFd6u~YhU$7B`%{p(IIJ}yS zu6a9f2!=xEh_=T;QZ_Sw%@tvBkr~lr|3mWK2AL#bnKBwhs~>0LeD~Xzkj=OpT#FO$ zg6fD%NDhnX^$W%lD+P|_4JAoX9HxpX#m?jFE9nvuEDEJQiiFbUm(#Zww_0>cZgz3R zq>&)5%td=SHHvqk3`zs^Wm>RNud#({HYHcqy$a#&%Uu&&Oxi1}BK~*CDfL;&xb-*1 zYWfwrdaZ47 zEj?@J1g1Mtfhau8C}?PtAM2z!4#nY7z~o z!qodh7z8)}BbeOEF5B9~6Da}m4ML6t?P#}XKBI%L1PI5BBWt2D77xEFtjC6#la%>0 zYK_B;p3L^6ya+ok&ThXQNNiD_s??s+aQRwo3F*~gQR$Y_7f>QKE7IPazc#niqJB&O zlR=)|0b!ltEhoDEl+S)wiczVrD8+5{Vxb|KtjGl|AO04KoahTzz($nNIB^6?aoDS;QDtJq0;+EY_l{3U^W z4e_OYp}5R?Fm%4&aY{?g`Em1prvb4-RVtJd<`7$(C>^_5y?i1lUPtf?tCYW>{gW<$ zGb0)DC%=yRA@>q)L&evwV^SsXrEwo-BFbdWsQ2+)5jnC&UN%9w6K2kktfAL&iJ0S7 zS7br($Np246uPVVEN5~ug-65rSGdP-Mp=nMOGLOCqopm8J+6`n>L_`xL6}QDM#fSmQs8 zExo=NsM}0_Dv+L2LGTNgl8db{eO$*0scOJsiH~AQrCG>lAIP3>iLAjiEB~64OpfR+ zX2^)Y!ape-2hs~Zk0HyF*kDS;M#?X}1|AR5kgImF<+M4kyr7#3vBspkvpS0S;WsId zYm95^+4fZozrh-9s%JqaBA$P61pXtz3o&P3ZWVpIphBK@OOxOzAhjVyA|KU(7-tB} z-8H4`g@wQAy+Ld!ZAXrV;v4byFy)DPAmrT$1>9@ctHogz_Hp(!scE<>L-z0J-+xge znRgSE3mmbXz5BRpM=fhE5b=;Yk$$DyMtkyM-YdbPB+K~GyXdhq0Stp+ zDc)OESkn@sFH$V-3k-R$QQ5sm2*7rf8=shPy^+2B*e1O+UO>&5#fveH7kV z-mHR7di_C&tOa~6|Nircm_RM^{G=eO(=iWCC*axBLPe)4>c9Ut#Q9%eL>`4$-zmq$ zGLQ1lG}7`k1Uk>S2x-&0?5-UHt*bWpj1=NVXm$h1jbCSq6iFdYSCeO8p>_Jjd%82Y ziIaJ>&945(*J+yEpT9JFBpMu%Lb@xb8Vk-k3X`{2s}$t+zjZ7BEpSzcH1?Wd(=Ue3 zU*g`MwT{6*gVYP$S|9CuB)miieIE5Wpmu-w_*TGAlSD6;i*t98d9JJSSwKD%Azon1 zxxhmi!;;UUy0|DY^rGjneRfRXwaNh3YZMq z8yNBz(P>yzgQZ%4KN;L+KU#-d4vY`^(Mp%7hK+!c`oOFq+@?@Je3z4fveL`)Jj3W@(?ak1fp{O}{0iO?b(l$ZYd5A@C4V0H$S zNp@btL%G)nq*Ycm=E&8|Ripq0!=@!)DV#fgVfKpm&6BbOPGo+v`$)TQ*Q3SX=L5L6 z5Y0|rjA*0sZobZ^q{N}PZ9i_Yv3q+k!6^cMbqwb)Np@bvZi=iAT-{OUTbNtMldD>P zf-%G&*|BGMU|RF+ZBt}@tz4ru6waxsZ(Uzp8O%MPj)AV_ z{|vC|RguqwFzS0JcNr*E=N5$>)i90|%YUjbWGDaH!{3 z+vJM3G@qYki;xR75C$d&@utj!tf4xBCMFbDIgF(swPGb6nwg=B>OjeT5W-qrRA8_n zvAF(Qxam*QE^Eq$;EqjdW{CY9S=RDW+nV^>u-C%+!Y%UFB756dO%;*-@w>?ber~Vh zl9G6_pLO1_!%^Jj-N#DJ_AwxYNxmm%al384_Fu{GlNLwYf|r%LkRq&cvxUbl|wYH#~bE)HPC3#%4G3KwmZXGi8t zkm;JSq&NnCqshS61nk7Q=kzn<*?`a|+dc}WOo2Zj0G7>FA7K|RoD8TOiVj=8Ah39K zE}TgJLD;p$T|Lx{upWsgf3_Dvk)S7wO=#>>A^ka%uD_fX2L-GQb|g*I2|&!w&)@ zPtILC#zylW?aFf({_FS)VD`)*_;3nJ$tBMW32)AgW(0x4GP_L!@%$ezfT=eYJF&T< za!5?t(lbBAHG$4L5_bKCy-$GVv>hWMm@w&GwkXHxt<6ZrKkv3=pn>xyYv*PAX2b(A zVxB~-`x7*~U`N2&cZ^soD_@?T;RLSmP?#luKKM zVl~tmRyrov-~V(PM4Jkgf3v%cWy%FN!81>8(XD0zgXFw)-8X@ z;vc*R{?GZtKD^s4{#hiC6yP%;&^GMBk=3FQC%=@Mx;HCes6W5NrvrP-H zI$tb27uVL0l_d>>ns2$yxei2k19lxF8XiT6@vX$2Q(}919?r1Coqjtk7W6%2-?JCb zgS#vA4E!HxASsB?c@f_qoc|0UWfi8bDLGYMH5go7g@6@R0(8_^+`kNJ)-+bzCG+-Z zgy`>NijCHSnFR;dOTUJWc{#Bg-m*pDI#=^`eA+8G={YrOF$a7Ppj5z|zzRFy^ukfx zHEFOkPY<;uiR+|T5;dE;Iv@CAY%rYI--UHR#nMR9S6D8qjMm%Vg5L5Lxwj|a!5_{? zQ*si@1Bb7hbNjKiBixg0SD8nAOI`GiK{34IxRezmfo!Bf@yW-AKO_6?QLUpzeiAH4 z`47qaXH>HRq|peTDYj6;&M~v34G38XG6CooJ}XTQP*XYo`XaMCB03KP^co%x>Q&}b;$V4gN?7QCWy0*!`j2s zVLcp^{kIH@7mLV0vM*jnW;iJW>!oJkAz%bpUnLdM+{2d=4kUpcVi45%X9FP|5!yh4 z%KZ24S<18NIkaedHr$@Pt%6kMq9kS6DnUf=2iIAZ4`D5oauFfK&%7G>!kBv!+;QoA znhm9772B4@K#WQ3lswdCN^7Zoso90tbjC2>bIhTZ0GVWkn%s!~X0(cY0MTq_NBqO4 zOwbDu2PPjx^Jt2afTNZ;0GYAF zsP%uF)j@(N6V<^0C56H6hs}sij2ZseM9a1-zirjac%&pr{}>E7=`-h$F*=>Jjsz2P zs~uw)8|tIB;DC@k=g1%^9C&_M6X#Ay@_QAl0CeM{aiALY5O33E!5b3Mj{U@*gew=Yrnxp!wrDpd`WW6VJW%3v88_gKzMZP5|B=mJ=L3rALTvW&e4 zJcV)3Q>9+s)!&pUi#TsQo>42RXDO1n7Y5+YK?qk{?C?Lw53PJi2RH}?b`V9}5n?ac z(2Ae)(*HG1P%)Y^>x~0n^oPBJlWJf)8wG6$#(1f^;(Tl}=eLhULx~wi2R00SGBT92 z@x0LtTcjwt0mvzA*t@#{rTO24mVrKmqEE8l0^`7}NFh61rysvHa5vr&Ul2+Nqmle& za7$AcN6o=ZlfVwvjwS^7NETN7{K^sK@qvAi6eTUB6W{%`FLDeW;F%{AIXvRwTwYD` zX^BauWUk>aJ%r0xKiOi_s{CG|kDQH(jRnh?v7ZGP_A#t{B=q(DSXcrUpbEBpCC;Kc z(SzW&X2oTSsE%_r_vP~mmK6&h4Z!7S75ZAS)#i%H(T^X^o$n2=b7*8bDOq4RlN7w8 z1(U2K$xYUu!&E&?(=ovJgz~as!Yg@xro~XBY^97SfjXh!mkf`knrOapRE;VZ95rK9~F`IXkga7Hu93H zE<-KDP3NbFzPDkeZ(si`T%bcVS7*>S;NY+8xs;JtAfX8v{{Rfjz_7x2URpqk4~0(@ zPvyg(S9J6J1WK>*s-YG?2fg=qTWQ@7)qWW{b+GCfOiYC1BmZ+le3|`3UAhl8#VU%u zAOH@rk!#5_9?SZZtpzZqPehiTX+jH-C+Y!nSP>ztS7hsX7oT-2U$)%bw;>e;R7irK zuweSYLw_L{ANfk%wLq)yhooRtVU`%{KM~#y@_)PI`^ZuGu24c z)cYNO`9@IIe+Clcp%~(eI$*MLo;5zbMnQ_=VogL<@^r9{rc?71(a1l|ScpCC*cFn< zjbofY6%b}?5dwQNWBO+;;O-J-zOts+e@gBACa}`4ZCc}>iR+H?*#OkJpu$?(Z&+*$ z!dKmt$cr#}MWd}j-RGwZ_w=w`22s-!vyCVSB=Z*`c( z^%5M1)2$`23Agdkqt?XSpFMz1KH3$6%nyL9Ke|B33fKJ^B*7DJpE%lM{V8Utgx*Rw zq*y-T56d0-Yh;rxt|6R`m_b;6=nwvBc}6tQ9t7KT^N zIgSH)CUCbqzDx~>EdJ`&@=+?-W?Ex_3h`lgKbxMsD&`8f3=W9&LX56dHFj+|LG&d$ zm0!ZT8WC&#p`VyFF64G7gwkT-dKn?h4!?2!U5}s_#wasFLPm>f9pJ6!o+dh!43nDfpy-l_Vi9AwmN=aunXf&gWCj$6L{^GTPv9;;P)zV~W~%@~$8 zYX%{{9LmNNPGx zs%%>i$8T=blk#kKVwd~l{NAh19QTP^rR#68$wf87QMdTPtd53Pc=NlBTgh3+><3>5 z#QCm>mjD})U*4!Zz?|!XFsr4_+)$`UYa>I+QRBAMWX$%Kq#F$-{;=(0$!a-p!LS($ zfnZHVaZgFqw}r|71tiwl|IxwqHJ&{NRG>ea- z=)NC)j+X&DDJRHmqDi96>t-@_RZ=lAVS-+~cd$~lrn3e`ucZD2) zvt#`&U=Z%ZUxlMSdr>;G%R$YfV54Ju@ni)VqvWxBqC|#oUOW}Vf04iOF)dBUN*{l> zm(s*olVDnNqK|U|7{+;MgYc)BLR=v$NgmLxx{DKgPtf^ChZZ7p7fI95;d6|8xYaP@ z8_Of_KG0?Wcl5>mW8gS}!3tZ&uxXJI9_aDu}GLzp>8Wo!zE{R+Zm1c+ou{) ze7HyUQ5u4q^P3^-3Gn5_={3pihkn;s&URp@aaiGCahh~D`WoAs_OCzY@LWVq%JzhL zoMW4Jnfzzokck#c*bgj&GC0r3lvdRQetnIXt1#&l)epI+9`f*Fq%({>pxMTIdQ)uB zx#^sm?D0g(X@xL>DyR*yzN6}iNu)U# zLpq1ThD9es z-m@PO?n~3}!)8Mh>_hqgg2qRkMR$&u{{y&MDXRTl)4T70LqFMo7hLLhtY~fxchBQ%1K<5Kus|jH}Ldig>1X|1g$2nT} z@c19Uk%G=-$(oJhMv2(c?t3Jm^UzESzqp95q@KKc-MrCB)aZi_(fA+zvZH zeP{YTm2FlJr)I=2CaOu~z-gVTc)Da)hhi`hE@iC0ZUNn;hXx=tpH+e#$b&n=w6=uM ztC)ROHI{LXyJd=n@;vygLbg-j)REL0&JsC-o4K%mu|pGKO2iX^zq_Z3#S!k{cMZK3 zGX%6eEyGD*^CtygB#t)v5A@75k~pAw9Qdn6qtAOOfw#jwD56qB zB*x^nA71k6>GMr)4Tc)*Gjw6HJ;8O^C!RsHew=UYmnDSOhP;0{WipxEyO@t@MYU6L z@x?sz+7cSNM_GC)b5C=uMK9jUnZuHXxd;ZiCo;^%jVSiXExMNR3NygDR{tZP0j^2G zy9F3t9Vbk`g(fdEDTD+$8s#|HMg zZMEUa@j%eLBA6tyFQ(-=x)-IlO-?)nVNl~qcMqFembBVSLS@4xiz zXg9FqhNS)czleJ4sHncMZFpwr?idN_mhLX;?v(B>0jZ%uh7f*qg9_3ih~$iPgP=4F z3>^ZJ67r4D`@G-#|6c3tbJkgV-`9P`U8jG-yq)NKQp3~T_|gccW^$Ig{1vBGEoH)H zsc}m)V-_ESk3GL4<~=_q4nr2LUSc&P`5#H1=3#^%R@ct$r<VWv_aPzy9i1`0U zW277+&-<5r<+I`KC#JZd!wY-#UFuAgYjy!w;Lv}+p5o$o$oF}OkI(RkQ?}LcOL9Y& zF>I&CSxrFGQqzxP{D_wric|V8bO}@_s}<+BnDB**vYI0XRKzNVm2-I@Y7^pYx>XXL z+Xn+%8`9S1sxH0qruDOb6tCY3Fo2l?D95*^sJJ&1v(5rj{aXH1pjbk&9`He| zA>hn_k2iS8U*T(v%}Xe6_aTlS!wD`%@iI>QRGP%>Cf%@LNg4|zyEn%%^h!o-Ih}p^ zBh~-tiL;SR&yRb!wd(ZFuId@cAGq4~s3ydj`~ax@x{U!lTe&SYcxxlm_`Bo*tQ<-< zX^hWe%Z)Q5pCB|4U^1`EB{8D22L|DU894oyuV1An{AE@H5D`NkizeTNfW&+FnZdE% zko)oDsY->3OaAEXJSTU!i)29NY*q07yHYUZo@o?{9U95{>j=g=X1{1z!Lki(M^p#l zmg8y?c8n`g=V&bkAtejBJSA2SxT`kO93HZ+aWlrf*h2^&( zOzq5;^2~PEcRfo$wL#bf2rEOBZ$QbCWRtxEnz5Vr#D{P$E?K~7Qj0dES^kbS4J#;# z%lLDn^Zca?;A@xfBquOD7NFAF>2 zs(cJY{z7?Sc*%CgzGuV)Z@V?kEEplHML2S+Q;<$ym1Ak5f6c3Q=t%ByuuC5qL($rJ zGqEGwac2*PP@a*Sr`DU@^C0V;o|_xGcD;|j{Um7 zn=6wWhT>EerWb$<&As^r>P(8Tr0&z&@Va9ZCU`oPWbSaY0(-) zNjg0W-91``31J}3JQth*;tT#~qx|V{Do}IWroWP8ZG!IDdLJ|tpK_2)cA>cZhr;Kz z?6wd5BV3n6N)EXwcdg}&S2=xdzPRm>Y4={$?*0fo9ZzM8R1%M(8erY_cxz8=fXh9x z=Q?2MlO`#R@&Y;vOS+z&Nyi4;duCTHfK%z62SWqV`cK-6Fd@Hg=Qw9~Xsv$-(gbot z>DHVBLDsU}zt|uxbm`LGBx6F&cRyw6^XXH; zi?8BDtR(y7XygTTA>5@*^1s3yFW>KER_U5|hi)qmB}R56WR$UL%Xj3xV-Vv29exZW zQ&uy?4XCBtM&#pvVf;&uQZ@FCU2N!}r}D*b!@ zAJ~OuYM}i`RxcY%|NdpgutWxX7S8CZ4b;!NdkFl^j8WzO5Lz=FVgs_}zV*<-cC6hQ zuc^wMHdkv|S^nu+$}Qu3rD7~BtXIX8N?tup-IlEHg40S4_!&fEX61t}FHkWBS_~J} z^I=rbCa7EqXvU2Z(kaS8;@d-Ja^55-Q}M8{JclOZ-H|*}PtiW^BG1#hZ3J3@-Y%&1H#s=WeCxr2DK-AtbU;c9(OUS|#jY!|(HMVdMjR?-av0pjf%ZjlFdCe<1PAg%b*P-&pmII4mB2@41pbBZIE(#y%AY z9`{<^ALiB=*oG~MY%iXj#zVdMs0-vuCU0bxr)a+w>T9bp36^FMyD|=iD+-qVA-~z! zG(V<17V!fhIebSDc|<|0?5Y?gMR-ThP4refEt@H|jAM={wC~qji(#BdSVW;n82`92 zTghqao>YfLd5_hkZ(k632rY7$RM&9;8G3vE)~D5{=1;B`D@FgvINZ>VdPs&+ngV1d zQtXoo)Qu-ElayYc_bt|*(BR&zQbH-OO-B|;C94h2Szb977eKQ=^ zqWAy$`C8$HCh1>PNB-6|buac)Prym#*dOF7J5mY8N!HgEneCNd-I9voLf29l-|Ptf z;QMpN6x-~VQcJ=#u|01>#FwgkzCC5GU#GPH-HsE~9yhXeNmJE`oV@vhQ1Y4-^=TOw ztbFIb)G)X!VY`*)AEAC^@;E_TYSH&yRvNrhIOV?d(U`6G&DX5QDeRw~b4M(H32xKh zXNu|O^-Yi)(6UQLw|PxoFOBj}haA{5Hn?@i$9ADNGS{t$*-6i=4dx^-+Z4Wa_gZ+2 zS)wU8nHuFCm$97RrY!}nb0AOM$=07d-@?O1-5!dKorNpGlddX41+&n|H1bqFInr=% zE&vsuiHF!Hw$XEDM030IeKzVrgB;F(ZgGa5KXzlCPwxMA*Y5hOa2C_<+_mFh)aO+A zcVIxOtLv+MODgRP8lExdDsd=Y@v}k0L9V z&dE{dB~+1juUCYYcJgP1-#ONwbc2!1@>$7!yhi7n2b}^BSarTfGhj?PUBjE zzx4Ygt6k+wueDz1Pno)PfeL!|OeZ?@8DiNn(t-EI`|8Cj-FZifWj~o>kiHVbhjED2 zT;(c}l;P|k`?RSs_UNg7t2LY=!F?m&K%8g@B?xVDHvjqde_ZP}Y;D z@+I|~ryc$dQ6i%g)DhoTlcodf4$HIB-E6qiQQgVBrPZ=Y?pUG~Q?6>8OL{)mJT6VN zL%WezqmFK|^22iomEN-|9qAw#O6 zA$>A-Y1&}l#eP3_9S(WPbWO6d z)5^EXJ+`mh7)0&T?Bg7;a1^xV0=5!ks`%bNFW?ybx_pG*mk`1XKab)&bBb-W(jQbJ z!?{k$sCa~(cuoE!bP&f$gk*gtEFB&xt6_u*r74}?LpAx~J0=f*eVoOGE*Zf#unSm% zGd+F4>f4My>VenXoB47MXWDSW)1|=X_B4G3uFAcjK_HhK^FmEQ)dBE=pn2zaovkYWRb#jne}x`A8A-4X+pStR|nVwaH8&sf)_sp zM6?&FOb({p_kErkAQft0x{TWSsn2|fM|Jp7JSmAO@jf6L*W$~8&cN`58PB;N!5P(@ zS48i%{tj+2&kIaK8mq)}#RNuXYnU!)G(m7s^Ir59vkh~dsL@Wn8IQO`HQ@L8*mM3f zV>lUDyr_0Nf3$$8Cn9kdHTqr0w-(%|xNlgJ88Sm#n1xHv;}YhvRL;%mE3}pEyozsy zM-F-Z{vw#KSM~>8^<13ht5r8(q#XVMWnpeap-+jA@A6@4O?7EM#UR8qmWIEfoP(Gz zrlgB}d6ekx7$L$v-HpQ@9PruJA6Nuu|&9W${w{|Mw?n6 zubx?HkoAiXx6wBUO{WUJvhPPK6U}hjInN8=*N>u2V@F~>%qO!uN#~zGY#R~j%F&cG z#wBoK03$)lR45;qD-w zG64AmSx7adS8PUqH3ufZ0@Ah3N-9K3fHo?)>q|T? zVI4zA+ap`P0A340Ws}H=1Qqd;?{_Wwy#Uchsh&BYax+qOelZ+K$z-nXw|pwCQY z;A2V`iK?-nqlVR+12Rpa=MfOVmH-mJWKLY?!weaF$-i{8Z?wZ_MQ30gsHws1y{O0Q zK8JU$wozGT`&&MWzvnUHIyo?F$srCgu_0*%l?w_#X|8t7-vbUmG0W>e&t1eg{yh|Y zMA~cfOn9MFyAKjFA!rrWtFE-*ZJ;gNkGp5a);tiuou-MQ$s=#6NfvYkx`&{_6v(C# z;*P%641_y~vn^F|iv}AxkCsY2Knv-~D^hD}I_Jy03?kUHRa}ANM0KtJ(d>w8p$l#_ zo?fdf9~$9!z!>~uJA~j2R|t3g!WgTRjn>z2ID^G6?zQG0z$A^Y9(9*CI}BtO1b zvPXRFF?=|OM}oVS;sBs#k$y_!zwyJB#g@QubxfP#b7X$tSNb#H?9})YAV$P6l~-wM zuU9b+Wl_A8R#^|H6@nJA%Li!X+2(-M8Zc>MYQ+rPEveAX!xJ58c|Zh&z^iSEmuX5> zy8gD3tP;IGt!-?@GwzH`;dhp*w6xUfI(}H^gdkyUDd5$~(AKH|)JEo2;IqK-S!7JlQy}_C>FWyB5_;nq zryg_h zlJ`bQFa#Y0pE9*;#wzgro|yepW68xwhdwXDnk(hJz7M zvCiTuEF^S#))3Orn^oQWt|l{d<_~KZK{9S93*oS%)bNC#2Jmn#Rs8K!J;m09SD+6_e-|rVlfm=8f+o=$>Z%uYpVG`-<(Q-2 zmnhhvv!tpEr7UbY#ONR|Bm<8*X511qP;9qtFYCm08XK0WEl>Jr@Sb3iu-|Vc=t|8osHf8)X%l?vty+C8K*gyLwP8ry|A4C=eTS9GFav{IX2>mY<8og9~wa) zsiCGN_)G7n!CISko3VX-A_XQliwQ?>S}&RQ%f#nY(q2Pzl;PPWB+@4`x;vyLyt!6h zCu~1%c}|DVBa_i!_saz*wS&Xt?BMjUw1w=}B`^vk`3?O#jC-z4Ugv~bO3vkG#JKp= zS6EV)IZfr;YL`G;>q{B~=1muq2kTz#xV`KDz{N4VLXti9-*WQmSlOcYg>|c(zHNM! zE|!tNJ` zxoojvAW)rg+ORP^T`nLc=+)R2yTykyBM1t2aY|E^p^zA*bkP1H`7>$K5)0fDS)0_j zDn)lPI#6|5OclrpP{X|W={(Q=e^w*>PeQe++CCqhU_Q|-x(xZ?<}m#wHRC;R_KcRJ zNmtJMfcl$uT&1JnhX&+o1KvUdmpGKDVhD*xptik z`4^w3a0I;r`61`^qYvVaVDfql1&yF8H9@uO(dV=8GedVgXX{ViSZtBak2F))GzP#-xvFd-YW!&3MD2!UCg z10~u%TK93^uC+T`hD%KKy)Jx}ku*&3s;779?}fh=QgME{p+4rD(Fk<_XJ>HNt1X$Q zc;xN@{q{>YZA~g(?p|{Gc&jn}LNz6A>3_ z$~D=smKML&E5n=ZEFPn$-X0|V@@$o>BOkHvM~!5RrQ>RWMvgT3b-6sA$bMnw>%+_(?dfr0j4T~Z2)&Mlx)(NfrHnZO~C zl(1Tuz(f_QAM=GLAUxsg?!RW)M4l%0Og{6LhXb!Yq5Z2sHQqh7CHCPm1qDR`2s8JH z`6038tG!|z>k>oGz(aot#}e&Rlu>CN|GB_9Jvb`2c>GiwD=`oCJ`4OQmXjCGK6Nd6 zeRMEg)-)!6@!hX_dw5`Q5q3Xh8a*Sfb+hcko`6H#h+Zr9K;!5g6Sc7$UBk+!V>qxO z=UgMX5C`(v1KZ1uW5#UD&StREkP$#s7F75ub#X#?OtJG#C09+Y8;TGpA5cvGm+oS3b6YJ}8 z$`QXe^x{2DbPYA&jv2(@nLE%hzLdV!`f|aUwsf#VWs7LV{8_k^K4KwkC8&779UM$N^!3%hIEI4i zuTKT9Pe8q`y-UBOHm31`VR%;Rp)(#9QJ*l0u{ixiRgSfRELFO{Cmbci>qGSx^bk)u z=O&<#JvW36i!AEZA8$QNwSkZrOZBXPxYPE2TUEC4>vMo<>c78Ke+jmVdm97BV_iQj zQ}Cnbn_d;KdS0+lC?JN(@n1~}ao%@@{aoFGeg6I58E{mGyhl1WucA&~JQHs*WRi1ZC_SD#16CBHIIU!rspk_ME7vslrW%R9m*r!&$MaED@7SMxH4d z9R|L|$sPhG#CLx|_BJHg9_hAX=GWdGKdyBgB{UTpV`?Wm%$rzrDpQWG>VQ^cz&F-C z`uXMrtJ{MoQ|Fk;RG=PbPb$wT_--?)d!5%ph4L!T@T5y|pV-Q;@jrA^AG(5T#t3{{ zF|con(QiG|5l2&t+o_W@-mOZ=h&7SIpj7_{*{ubNnAp<54E>JC^CDJAOTV8lBe z_4bzp*=f07vAtfb_o;aWQupD6*Lrl&Y{y6289r^1-u64iD5Ro8jj`FathkH?NJ+)jbOnzs;3r}Oam>?6*Z-!ObVo&q92y@j{8SpFP zdU6?;kn54d@QY>trk$0}kqmrK-=tWUuTOR#;CWsqX4h9I9f$LF_s$I=GP|p;PkbHU zuwsJRcte_m^Ta4R|2%EuS@8>it4ruKPr$^G5POb~cQ<=>k&MnZJ`ggW>Q?}eKTN&( zs9V9eUKoSHVE|X?ONa3*d`NbuZJjXWq*4g2Q0E^Xh`|=;{s~d&165Be#EGXSV3m;5 zGPhZxhGPmU`ssk!i}%R4-V=?o>GC%2&hH$nPG<^xah{PPG*r;&yAg44KU7+W11U-+ z5siFLB~}p9DxnjKOxF$my@c0R+~bnM71lZ-W7$&1Wa;@;Spf}K{mT>ssYHvie8HfA zCq91`J51q?_GRAe=Ad5y?SCQ55|LbsRV*xTJUrU7sDAfMsd_x0uY)V(?6jbath{Ck zW|%xLYD%{x!RTqE2-RV9ELz%B;-$(MG}+Dlx2OKcb;L(avY`zK%vc%%Z@s4bDK-|q z`(E${MlX`A_Xres6vn%GIL{We;XKJ})MSOym9$i4lmUS00mPQhYysVoEQHM04U9RJsX(i#8D|c4lfESCzd-|ZmRLNBFG(QkB zE>s8SZh|^PNh2fPvEoOP1>W?Z2Uk^3`#}Fn!fzMhv`CIEj?H}W27rqUkoGxo;xv_e z0BR@nBmV47%cvnSiBT_opAxbk?j0A|7f_vF*7m{$V{+7ogh8eHZ8}vULGdgyytow;$M_PXD`|Pd>dyXsMoyW<}^8Rb_$tCZ8gZbFa~<-9<{k;?rY=ZIHE0%+HXFZRdIPy&X`y7Bh% zb-oAe1$f`KfwTmY_YT;4)1JhL%VU_GP%wU^gEoj4cFEOK?U#mMu@18B`HmqTlB(cU zgk_}Sx?G2?TNFXbzXwq18-NhRD%TP(;QUROz}!Cgw*L)9&jRCR)*G}E8p6MUxiic# zg5-@wbCLmXeLiEih#`xqr!&rE(8%Ur9@^BmlIXpE1_*UWU+Q?GS|`iS0bveb%XB&p zN?tejO54%x;RG#B^P9;&x6_DCQlL!^l_dD>PmX<4W19xTdGsg8$K`~MrWB3q@#!kn z^<$F#cqN>Ncj_?jFrO=LFl`2yzrlWkV>>1rN*a)-95cKLsvA?y5G;8nR6|i#Wgh>> z>yL{P3vR~R0BA8tFF}mP{b^kqtPs;*PLeFmEfB{K#f>K6>Iv+Xes@U4;>>Z^Hlhgb z0uG*X#v5Q|SiRfooQ8DAJEBpvoN3{QC3v@=tat=B#JLEfh~v$ zhT<2sZfIY`}VTofV^Wl35V*weKq&%j-giTzZzn#=mD@b~MU|>I>cUrehU?L3 zC9V1eN{{zwsW8AYU16xwhhYN;sSuT9IgX5DQGY2Lj+f*%$$j8||C8a|Zk3x?sV@L} z#@Y_5%F;;q>BFn=^s0Fi&A1j1iS#hyYZ5E<1xLx3IP^pQmPrEA>*Ij9KdV5pQnA~cm_-}w$=>s2AuH4s z`L#9A(szQ@?p3D_@kF{uEGs4+%kFp{a)2lME%+Dput>d>9PW-L|< zXotkjQj;xw#7Q@hvivGx7H!8LQ3dDZlPs@ff-}s~R zcg!~kkk(jF4STw-Wi9UvY0PB2m=Vk4=Q}bxOwG0Jo*f|YJ3eN+WKMm#N6!LSAOhSA z5aL`Hitp26;Wf#L%K={CaOHq?Yt_HxJQS_TG zhWhn3Kl}wBY7v-Z2}oe*Qhl&(LU`WD_v|TM8?=!$Bgq3!CeXoQVB=6)~};N6Nu ze1LU+NIx?*l#zIx&SLuxk^cYbG3U#=?*;XD1mLGexJMPp_1yl)_Xa8<?@b1?-~o zj(=N0E6N|$lY_m?oV>EEOTaQ+KU%bFwLCv@@bCFYuUo9NSq`NUaG!kP8~($m>_*wi zVt3%Ojw)okq;o4==O3p6Hzr)y8cerBQK7|8^Iq4Fs3!Rm3cqzhbftzhtKOKq2#fq^ zu})FH&7$V%83&)<&uiT8I_7$Glb4e=0=xw}Fm736=H}7~UcXs1w+oNp2^n&%aq6N( zI_#bj{}=dTGl+uZBa=fq8A^Us-0U*SEGc$Ppg4(dkcc8-gsCxD^$9pHg+*s?@H#*zt2(y-i5(7#}wb^z@^Y|RfImJ(Na54_r z#a~cj>wMKIm#h6i3$1}79iMURzU&ivHfgpsC_))yvo{zZ$9YaX)DK=1$@iTO`*KLt zGfNm=)m12l8gzN}#~nrKQs{hl#GuS;R!d_GMa>X(!kkWzK2MHE6ys`uXzU?30F?@2 z;>>2mfcdil0|s=T*8n|aiIx(RQ+V#SCN2Bl*z=21_mK(aTLH6BOih!{hA!@#0f#B}#mBt_&@ z#IMrh9unRhGolj{aG>|)#Um;bZVelJz##vRX=x786}da&qD!!>wsfvN-7^ZfKbT0R z>F6pB(vRZeZK+6(3tpV{=&rj}qKWWbFAx8LK;* zj|+lxLZ(TDa@2VQXx{XoR3H!_f_O_07cwkvTf&@-^6tLtM#6UDhTp%nE$f1OA-k)S zfjxpdo~$mqg*ou2i%F)!WXfOsg$+2<7XI8Ax)};f``&4M3cHOXYrLK3y8rbj{GU$4 z)KsX7NeVysYRC!?kuO0VzyazTDqVsmq}f*Jsx-z+l-@8VwT+cExO(SN(E_h60bP$Q z$lG_Mk-J!-?k%)E7QJ(qsv_KuydAyKd|RguD{q#Rc$} zds)fR)4$5-Q9nI(`l&# z23Yys7X!N!08?hV{=HV2n7l71S?2BUU7`m#iKj~QO_OVp{Qz+uf zJhLg9KmE})SnPTCOn{cyKd?S>!8lMDt=hduBp1;Y;m|TJl4G%aMHxGd);IUlGb(Hf z`NgA|wYvp-Dgw>62xDrk(>N;WTuPJMT)5;SDXe{8Wa>PK)C3w_krH&Yecc!H6l=yA zaupwwh(c;F9nefE22v)@{bO_U_d;VrXAkoS7*6L2WnIrcL!bZmO*&U*V9wAl-BB?6 z+X4>pp%{th!ad9KWb;=xyZd;SKcUl<#@8u3>TEFcNi$~>D0_1e;1ylM;kQTx15kYC z6o{v=-Aa-o(7+@4SdF+%!H|F^ejmVcUgd~?lnhuUM%%@MWl?ucVgcd=k4x0bJZt`K z@{#ljw2HZ!?N_7+2^Y<8W{AhbE#RjlhOu5yd-WZ#)rsjccD|Lb+w@Uomj$p)%$lq1 zYms*POWg4Q>L@qOGD0ZD9sJ@5colh|3)af&EmCj+JOsQyF7$4;V@h&Yk^fqMJm4}M zcu_0HWr$*vX0`=+U}lJL{mhp%&9b^DW~oj(KXez#j!03O$G12?68@?Lj?Pj5ak%kK z7$T!L(a{nG=ri|7gswZ{nAOw%B(W)H!MpR6KXU$5Cu96Gf?e1M4h_9yi0K6>*NmyK z6Vhs&1@V>*9c0nwjYtgrgArU!9eTF;sd23(FG#Y*#ML2xr&Pqr!hAo6O)G)LrS%Xq z*+H~23n5?Ity4&m%t>E>Hd=SLGPR7OuyCRa?FpJ1EQjb1$qkCdJP=a7hIeA(J2EoV zXj5muw;>wP8tl>P%xVs-uol~kgVrXSIUwzM$)oe}RT?|3ba`aS*VUt}e_wiiq{51o zo5wC6>VzKVu)om%=8eg$sw5-=CJUa<+rv&%nhF?@BD{;MEbU!OvzZe7;<;c?CPunz z+=%fC--vU9fD0R7GU584inOL`v~R1@dYm1b%Yj?a zuYjL0=3NTnb5YsPGWZnm?}v$tnG_DDsoektoPkIgom zQeWD3o0beg@#I;+sT>cl%YPYC8!(su{obdl;Jy{!}M#Fet$@5ZDi z+&yNtxS9F_oV;97fIWAP;O`cGQC{rn?YVGH{pyPHu9F!U1?q zcF7>SV_5tjT|a|<`!heWjF4%M$#ZA2Q=wVz*($B-#+VV8Etw!awU*0H5C(3Me$2Fy zpCLcf8o$ zLV`}$P&UJ=Xn&-hY224IJse>vwGpV!x5tL0fE?WTH^2GOn;MMHBt9iY0zcf?K>&xc zhL>GbTfO<>+G_5z9*mn`g@)UbOh-Dthu+B?=ODu{b;k`izg>8>h$qBJ*wo`qJ7z2N zlySA!TYL*M7Cc05?38VP(i!ysI5W?yXpmZR8yReMdPRM?CE=BZ%8NfQDe=rHu_~Ez zWRxil|FmPd9MlMBXX!0^aaM@jDHH^E-q%{}3$8j3(Ir{p1pHuz#U^P};7AQIH&l6o zhHam}k!{M$XnMcstnW?}$G;%UCVq^lf*HaX!S_YYa_aj+NcwNAYpWg=v#e=eIsTIN-x zD26&5W{!aQ zJO0~OriSamQa|!=TER-@#5@%zk34Or8EHZRG` z>xW7xeu1Zp!syj$1iJAd6J{vhj1l4o(r1i56N&E{Od8Zm|Hu_ zpSyI!(`Zu`%Pwh$i5i=Aqk#LNewF1GB~y!NT>v+$Z1#(@-UDfuLantfWA2{WU#YoK zZ$3nXp;&}}a7zHeH|5e8r9xKKR%n#9EuMB>f@&g_uL{(kNOIiPqWCc}GV9)hx}PsP z>4$HM&c|E~>&^madR77xscb-hTk4nohM<_DckXTrjbP8?Umv~4hTj)gjVW5Ob_Gi{ zo^92~d@)^(|2SUsfDB%5XcS*2kZYxqAkmoeO(;_1i8{xWLpWX#iY3iKL*~I)Q?c>s;_=V(I-d#R+Vkm&jl;5-ug6qwv>*e`sG|g zFuPc}(qBt3i}u6diQ6o#l9zK4hP7?hy40T58=j|y$1O$1nQh)kIpUu`Cu$?t1p_8s zA5c&A{_mFBS7?Ze>wOYAzolaUDD8jupq|J0k%1^ZQ;RfXgWcZ0#$(yxP(d<$0#vNc7gjyi%PR=G~1_G$KrG?J*4C4YfD z7x8Kr(H**+uteG(sDiRRyqPZM!h*8$EyB}8Xh_1A`gS>f|64_@P#_V;!*a%4K(6lo zl=H#w5?1OccKsvhmj)X*8=4I%QDEkA$w@a4THi-v@+T|BreCJSPe0ct7pBmxq67jnGsCHG@iVgYT`FUlFtO7vnb5iB?K<|= zLIFs1I9bkS7grOXLy@FS)vTs|AnhXI@hl+tp<6!4qOWEr$H^%UzKZF{(z{2SKC<{i z*G6J^1^e2={xi}`t~`>AM0&+<8(Zh&2gE}8v|6AfG6TU$mYBehQqhliPs?tEh{G)^ zf_5gKeS8igLbVH4*zfLgYr4K1)j+E#%sZ$s}rA9Y)xyR z%;Mar7-5(4(ld~Y-hl&y02CA%2FIZx{3Xrk_YEP=Sbh7RiVmipoRyC&X~oPwyiy)K zY0{%Ugyzq)=37W-@x^fIF}54v*8?Y@UeL7Cy(PpDqR-t6LuEF?cxkrpb6cEIY14eU z$ksR*yv>XIWMk-LT)QO!?%D#MwV+0G`BQl zym`*n#guB}84*@_-oVklPWN&6W-0Q2$X&DX?=1bKvE0O_)I8t(;s+EJo5nyYm}r5h z#KA-eYS1Pf?e!2G>bFRXrBl2$5&{4)Y3;Jn*1muVIy3jipUbmNKLyJ&_0vOM1dEg1L9 zIK*qIyWjmBH8Sf<|3GfPV+C-)Z4mN%F@*c=hL-^~kamG4%nIH2Puz3sscomzuLuI~u6rn zxL&R0fX0{cKlC^Mx)b`!Dv^`4XG!93iQdal>WAx7&{f8kjT`L7% zgCWHM`>Q8+c?j#Il@*hvzVx8ge_!F*b|}VhEzhPCCLg7AI$-^oT`l>grJBw;8T=+i zp`OOOtq1u?SK`%)5(i8)b18~}!eubDQzmH&LPP3gcFG|S;@&y=V)eEmQ!BdFRaM>M z-Wg(v>f65a+;-*QX%}h@35a;!PZxpew%Qb#EDBgFN+}x{v&ZgR880yygvrMWyJLV+ zUXL`7!@Wd(>+7z3TYp)m`Kx)`n1jj~!@lDn-fNy{ zZ8@3}(K)mYqA*ZNC^#ShyvsIZ#X1o*grc2x@@Y=2@zAH?t;EATDzPQfaFeKKFOy>4 zF~*pSkZv7DS7IhcXf4O4jD{gHXjNI$YGRON`FfQ`gO8XmA77GiIDnbGz?DBO2ijx& zo*_RZNk!)Zr?F+t?dqO$&v^Zp>a_S#!vEx#nf(@Svgat_5=1!{!`845`id-8o=`Pa zI%uleuqoSA=(T5t7!sPuOGcN(jCoIXYmOP|Ih5XtL1^9JxclMFKj>}J^xm^4&LtRw z`Q%CIh;iVReQ};cW5B~@R^yij!Q8K&7WdWu@j5wa)ajtW9gT16N5l~Gp)w4FSyWs& z7~Z?8UA+)Dqbh2EyF)O>4KUOtLBOkc;um0}%7HsA+YvF_&Cvdr8M;CC!jjXg9l>2N z=tqIOZ8Fpxl{DrwEupVC=Fw)8^N0Hsyk_*xp7=%u&5nW zE{sO)(Mn@kfuwu?KQT-pS-_iCpy#|C;$U3FmkrDj%}7}t{My9wAyo6sec;I;r_kzK z=trbCQJ7{RkkoPO)vPsS?8g&|siGiUOHE*s7XLA47O7H$sd68w#fKs2 zvFt5_4>Y-OMvcAX(uLPx#B3<0EB5T*B;%8ol>uIGpT@HPCiy0zL1JX#O@l`@Od*JA(L{##ZeFg`>2{Mu5G(Ha2<51oDm-UQC^m44eS8W zkF6XkQ>g$}^4_7N=sueHJlD&imOTD)o#>GRiQs#bF?Ygc< zw|&a*Ao|=7r8_cRZn%)$s2tmoGRq^tk)zV&0p_Sn4};zZ3E1mcp`qF8=|NhlRw#bQ zUEh30xP5CC|15hxv`Nso=PR-D6P1qXZ3_u@2nWnM46#oxa_TZOXEjXepPA-UJs$58 z%m1vri^53qR0IsU2*2SIpXLYLvH;Vfw1$8P-*YQ+W-78@-EmC|HwNFjPn&FW2e(t( zwz{Y?0}t#)K1Ut)ztQCM)K$`3+q#;|^B5X$OK*2hX*dJFa@~4~dvi!RrT2rMoFa-GiAZX^%`}LQOPojiIkMuJV;EL>HB{q`CQt zI5XyhM*?Grd-b>kW&pYEWsrO-*!Uoz27siZ%0-k*ON$hV1N4U>RYQVRfFHll=0i#t zAwDG1ZH+m-qo1!(mM8uSo4XzKb%(PQHbPwbEPehELc2N+>(*4ad+i%cHm*^#IG-Mx z+klwq>4-T&UMJj7L4~~-MV^*!K6%G2R?zicbxnT>!o2fwAul`kPfoS#u0y$*ajXu1 zsN36*{sZ^*p^QNO72{&XC>98%3Nc>MXeddRC=IE1TabwnCG)ZA8~YoIf=~JuUD|wV z1IQ5XyqaDcsv7&GBbk#5as_GGCcY@dJ-j39CPF2+8)(SyU=l8`^Ju~pQuWM@{`EP9TwbU*~EV> zP&7%UdMGkBxX!0tR~IEmeCg4CfJS;sBb-B}Wc#tgqW$Q@?w@u<3Bly+C&yeDl{w4$ zl|c5AzGR?Jl&Se>X?oSgmeJfl^A=lwZO@(vbt4;qvn7U|_{nZaZ2R`kD4|*&qAx7! z`y&Z32Qc_5NdNuihJ`R+wGins{7sDNo2aOEArRtJ6rn)t33ekKizc+(Y94I4;Ik;LUP zA5xu8m}&e0m3<)YwH5N!worKAeFR?5a#qtWKdda?TB0csdr_S9gIWw25z`1Hauf;= z?T(?J2EVt!4-|H;6pYrXAg05)kY86CQut7&n9=(Co(=;8YdZ@zDhv}K@I=>oGB{u&Xyp>5}W;__6TUO5IW{*gLgpUyL*+W+;xA9Lv#> z_M(|MgCvR)a4|@X9m2>Q`wb1SIF}Br0MUTBDYw$u#X-4v7BpjNvL+cUFLmHc6106r z9WE2cJruX82c4Y%xPmUOb=-%X0lZ{b*Riy$+^e%W6yP_kcD7@)D_71+{6k3j#$i1a zMu?kaNWDfXGexZj0FC3jRA``bq0(k#$1$=>60o0)Aw|DzPkzAuWn;cc&q{|{Y0ZW z+!c2odYWF(PaF-(cKLf#Z26<`&78AWJB#LelR17u)1oK5-QpEyUfBdX|A@OenzVp= zUIwwVAX0rKPD@b`hmld`1)92A1{%)07j2FNxXn<4b^&V7*i=W4jUQ`2!c5mLrk?Mu z|2jN8%$axp#QJq(@003>Uxzh@!4l)ay{9+yhFXmQ+em)Gd@#7tE`Cf18)HfcCw_7V zm-~(r*vl0`|CWz0(+rB_BD=^^oE)CKO#`Q2t4d3*n+2jW|3EfUrgW{tJl$s#>=Sfv z6<+)LC;#Zup#;6TQ8B(&UWJ+gA4rLD=s~}xX*R@{!p<5@tdX1Tj#Dxd{~uLv8P&$$ zMU4jcq6GrMwYV17qQy#acXxO95~R@L1Z#of?oJ3$f@`q?!HX7(6zR?XdGCAIx*s!{ ztV|{|^E+qnefG{7wsa|4dAx038I%9c|4CH5pD`P;>a%hGfJUun@pAt_kjpw4zgdGz z*y|N+1k(qjnTR0ia>x)Po%RqankuT^;jqdrx!U76>KH%{ktmxSX&FszQ==^lt7)CA z(&!o#lV-Sdw`|{H#>-XPp663jgJ#E&@E1q?xB|@>p0)EWOH$atDUkhdhp#kBywuMj zzxSq&KM77Sk*uA~ISX0UsaI-P9O^?~C|-h6a`(DV+WMx*)heUPu^;n{^49ZrRBBDk zx<=>ftd1ONQp+uZSnFKWi!w4w%9ktt0y8HhWqE5+u)*iWOIZzgmXB4Tl)TkuJN_Md z$qeP-bQr{>KeW4-Z>cB?)m#lQ!iL^+1MBf@duSD`MW%32T~yc$)tcE8YWRmtDHCjF zdm`v1wNE}FP@wTnkc9b=Bc^;mZSzNh3-=^mJKRUuy?aKWxbb2YHGwo<4>^K5QLA0( z$242F*;nMoeqR_zP&itdwr9+s369H7!Qibk)e?epB8a}SgvZXR)?`KqACOC{b-*9$5^9%VT30@)~q-F2Sm$w>0l9m)z z4Z!1#LMzTeR*1fkhZ;!Xe(-gClg_AB@#@ml&1x!`#%l8~hkTD9VGlr3wJDpNBJfci zNV49nk!ywq7o27UCBvJE5F}*#Up`?mgIFkW&RA+(UI3KgKCulVSN)TfW41xRD1N@2 z3aaWBscPcfVPxAELogCjZ0GWhy5bQP1;uu3nJUSLcHvw`zM)h`e;|3c&VYq<>n2eK z!LPk9bYYEN@{CH9cJI)?vYYd!*vV%{JBLAXfurgkaCG}_2Kry>7{x32ltK)7M*Fp0 zQ8tvLlk?jt(s(YXV0xQ(Up?Um-@r*9<+{OA`}ZYax-=}`kn+~wa+4{H=!T zw${Wb`hDr!qhE)?8>&T()QxLUcg2&b+pD<@;}@UL2x^1mjUr<6Z9@mZx48Jz|1ujV zf!&cnb2zHKXihDr&^;LNvUn>AgDnNbo#HGXm+*K3;+p+Iwcir${g zhVU?)m6R2xQFlq?b9HfX@Ht87Ud#yD@h5Zd7}J4Wcm+qT2`Ta&UMMk*_b^0t|3RZ2 z-v0I~O7iQmmSs)Y_VgIZln3sbMEs==m|_Q2W|FcyN+neVlDj{&nM;N*gj4>unLXm1 z4lR{+0A3dRlrp?8>Iz|!-f2h{I|MUbaf*4j!BeI_>DL(OO2xqNg*pO>y6%+-MREf( zheW%Uq3%F8WOEp4DNJPTRVJ4ajNQp~I$nl0o2vFq@Dx0i{LdXWy?6gP(N&0=CaJ~{h7#pz13cOdmYM|4!}V&(~5k8xt58Ck%U?v~(T7 z1NImtNHqvfEjqe`e|K|+U%yw&66btJO-&#h18hy~LWeH{kmWwhz!&j&%kiT!|4(T| z<6|F$Lh)z`~DA2Y7etQJZ6wUIm<3*jCx zsErMFuA;JgE6+jZf=vGci5X-n3OLyN`$KqC1^%k5WDRtnV(a2;2`b~Faz8WK3=D1} zKWeuN0{uow^d*}%PomfWNIX;@iZ5T)F+fWr|G8aY#?7oL^=ln9QD*OSC!P&G=KtV=U2nwa}=TtLs5qZ)%hUNcDA;NV?#-&b*t`@F#v z)-&-USuQ8qvOzc8OZfL$>*WzDe}W-Nv8+5pTrS3wib>6-*^w}?!`(j&Uyhv5CnJHh z(>&nb=-$MqT-1;c2wb-OpC58wd3{bcWZ%YiNt%-!rPRij;+&F~-c_NmJ{&rvuc3QE z{5vmxghmrqdVD2Y9vn;TuTayNne^xk$N9^ z^*onjj*i7Oom|oF@o|dROu=oia%4Vd2vX?y$uJrr5OcrTF(wb9hxf|=+tmadA2OR- zh^f)4o>|vX_BboOn6*mvw-&bOQ%>_&d3z!{ncPWl#m4*ieW;a zAuc8@Q@Ag3>GTgFw-w;ZFx*XvqrA$TE@bLpA3vfh@Gu^uK24u}RW^YP8>H;V`WV1K zC`rzqTRoNDL6(!b?qwGHCq!JveQN=w>P>^LO(bALnbskFuu}boYR>Cb+Tnm`9TfW3 za{wys145%jdB+|1pPq&3tBWqW8Yr@Lv|W_Q5(Uu~--b-UC-Z z*QIaV-GBvedr{$&hw%GJ6JIF^Z(id<^0ck}<>-NY%~R-7)#TsEqZ982zxO;IreY zz{81c`@vq-zJAyg7#YEn#k=7uQ*d%qK)^!(hi9uUi}hh`+6 z1lGUR8No=~ub4{eTGmsN2_{9Jup=V(~xo&|UsIX!aU* z{5zvR3E#h0989t2VvDp$wRRO;c?*ZNwy$iCyB~Zz{_ie1w(9~47UZ0jz4QGPnP^WL zgYmY6avU=`qg>GLXFJgZ4!t*)FQd;#=&5-*WCAhkS>X(}+LkhZvP*3~wpLCXnw7qKXP7~QSwAztDr9kUuF`m4Xt&5qgIDTio znQKoL=6r>gQV)zmL%Px*qK>Dl)c@F1*4 z@-g!Z;>%$(fv9<9acv;N=MU>s9GK7y+h;gM0g(?;MZ~f+ zT5lzD10?-QcbfF_Th|rvX3{RVv+Qop*(Ap((%%CLw+aU&h&@=y_G#(KINT=!`|_t} zq?Kd@`>`DZaZ1kFm+0xKC`h6TD<%g~koeA}H1pYk89P0-K0P<5iIADN$GgAH=mH`5 zD{L!H4LUm=Vyk;j!;WbnH)$;sUAYikTdk$NbEK29fyT9$w25(}`AfePxHsu$g<>@czJkt)Jsf_*!$sr>vg)xFMn)FD`Xn9 z|9pl?fY#X&X6OJdnTtxGiOtID;vlI_6nmbD9~RQ!BcR5uDM9O~xDe|tg9dBXUjRqf zoP5*@3kSz;3*g{fSh=2Ti#3r;=_Q!UUh5N6!9Rb&)l9FRjbgJI`_c_+qZkott}9E; zN4(FEKUOVT*rxBYd9|H;qAodqhvoow1}xh}o-rD&B#T?;UFXO1`N8g0{HWHSroPRG zcp36rjXwplewJ@4XoL<6Ynm2D_VKV>cLzaffzwoyndIpDlv)v9xiqx52kvtOl>Kg= zoG6wT*`1(U2+z7rL-ALl$oFNkj`F=$fVH2Q*~>_MJMUAx;@%GybLT?_RT&Sw9BosV{QZ?R#NHD`A;LP)-VS)e zT*ENo-mzHTw4E-T;+I%6?o`ZHhWy0R$A&}EM5Q;H;Njj?=fboDE~vd>OTg)Z>Bwc| z#oG_`_>Ay7=;~bTtYcmZkHHwYNQsqiqm4Od#n@`c7FS>I^zVFH+ikl6eYBmd?IA=6 z4tyoKwF8Hoxiz6>{;2s(=nC{Vw(bZjiKaPt+bD0H=Nm_{Y-xG`U5s{7T>``gT?uXml3&`QYiWKN1mJIQ zie}N1=Qa{`pf~1t_U#LjxlEFRQT%OAU_S3)(v~vT{XQq0x}L?pwHeVWOw-q*aE*HZ zod^=y_e#E70Gtezayng2lt1#t0C5E9> zjz|xpfP2Y(_)=FYa8p0g#t0LBvnn3AW*3(5QoqHSQN&@6u_aU+wyN2awHw7r&$7X3 zxXOX@`+ztTdDs{obX6C29Mf~`tfR!p)!>}seNV9+PsmA)pFChQ+8YJ_ZmH|c?Zw1j zI3aV(#MWh47)W75b|BQ?68gii=ykhuJRX0{*L_2dMyO>;JbkUx`cl4^EF?Qpin5!) zKfjUF!qPwyqZ=y)kHzE)Ah?%9EMc#dn%kITg_0%l#yTse8r{H<4>G|=a*T8XI?Mh;une$RiqNBo3)o0oB}i+@Nh3wn)Ewi{|H?h@Jsz( zpuiRCNDRIbVuw0XlMEn0L!fQOpR%5?Yx{ZM4h%+Sd= zXx_a4^9qWJ7aQU%PGoaJ{x}u{p>4ymAS?Q9lv<=tx7?%p4+C*Eut;im;W@|GFmqs# zO}UvG%*Eb(K1n%HzvFU*Tt-31+25~_9VQBF)ah9@Uw^2MWrWsI1Apcd`0SebmO@jELej8gfb z0;c3j5?$k!?)p!a3bq+OI-dt*lx5CPzK}~W#c}2-D2zWtFv?~$J$wxfDQFu3j+;y? znU^PA3O$C4lPDI%spI$P{{F9KLwJOwN zV0)*?r6|~-8fiRi&elH-(r9>NN|8Lp{$j{VmqQuO{U~Sqc^#1$>7u8tUQ`&8H51Aa|{r=MMHio(4Y{9bnYo{;HZe2}hFmT1$K|*<+a{9Yl)d$Ru zBtYGB8oEz%Lgd5IK@l&y&U!cP!b>k`JN|KD;B@DU2IFSA<{kWV_1^{_3^k((zYVq- zJg&2Mu}t^3-wS4;`rzAV!3pDoOBo2*DJAGo%%Ll)hS?|CjRw7-R^z{>kX6!2#mvrS zuA$IAP^2U)xY27am5a$oojymd<<%|~4NR07Q3>T|OGQ=#q@!@rQdDIu0gx2Uoo~j! zi+G{i0)R(tIrN${^Prp5YFED}LGh!Jjy9JE!yA{PaA@C-)OTydS8rG^vMMg^gBaU6 zevvH{b2d}2B}5p!X?ju50`{5D405bRRhJxie)I41(6e$TI(ZkLEiwR!KZ%LldyyY2Rr(IeV7OaWm25oHu|w6DuX=Ync0bl!QUZW>;X zXQnZBSu;$;F53o=YY*1QLr2J)i8}B*@LB%7Fp~(g@1eg$jg6SRj8=SfJx%dH)b0QE zsoa;rnM>3~duldRiRzS$x`*y{&MSm5R5ALTI&?eZ?XwkE$Mdm9a4Wc;WS_9ev>SdV zWn*!T?i~IuIq{BZE1Q^5amVI%(^`VHT8iRBo{8|Ai-H)BI=7}YP5%&B^}fbm8*si! z-idJLM%F6=r%B93sL=~xs57#2C|P&Wch}Kd(5i=aFLSp?NUga^S}d+tO`}eRLB1Zi zJg>$TqdWd}vve;y_`{p+GrL|zhgyrwnf*47EZaWAIX7brqr7_M2B{^2dJP&TpY*kNHBiDp2*a!Je+|$7dLMB`;r3(dfjKo=kL-KY(tuaRN%Q%+nsi+AXCMeDA1N9X`D!g9I^OIvfik`xfBV zF!zLEAP>4a@&(}CPoyn;{z+RwYM#ii&xsWp>uvs>ZvXXe|82la+{@PW9_c(jEaW(< z?@u`V?)Up9iHk3PZo>e#S! z!R^aAX@h(~o-!Nz$gk$6HlBXOk&N6!lPJ9D0CQrA!poEB(Li^`gM$FKCAVna;E#T= z(Pf_IdaZ?!qGaP%JvCE!3Qqc-66%0^1&EOTwfdFhXb0`!XO@i%; z1JK6-kn@|teA$pgglxm=b~dL{=(0#a&Z&g2#K0Ob3V^IclXgd955Hn{Nv)AfiO*2{ zl@U>qHv5QzG{{JuRaH?x89G#GDZ4O5Ql#R$<6_DN4CR6!4u2E7z2r9wkE{#vXooPD z?7bFrf5XK_)+S}QgK}^;nu&2;ph3WiO)+l<=r!l|;`aOsq)>x5MEa#p_6|Y z?N<4q3P)X;mBnV0XHZ2w(3qa!!?A^VLA?|bfTyZ*b`qt-pwp3Q7I9qu)2xy(`f`N) z>Rn&8-m*$fx)=3@crlGlH54s3(Sv|oU8@+0Q0JNCsWNcN&(P@k^R zZzHA62YgHUmcxJi4=?nSwb40;R2bpq<_aW+yhmA|K^4F&Kuw}>K1XVboCwlAnO*8(q>ueUC-ZUXaQA#3hBu6knhu z>xwgM$+}^wkXm?63>gTX=90ZO%63RpDDoD3NIu?(K23sG-12Vy<=-E^_^HHLwkOCu zRI${Fk2>nSN}KqZl_EK*v+T1uV2qUU5HR~|&3#{_A}87(PqFk=no<&fQ)1uoRw+Md z)l9vcEv8;YBPy;c}emM=6NR<#w-zF*Z{5G68j73mL*GLl1`LM z?Rx1%;hi3-3%VHFb1?nH!St7p>Rs+sv&vLz7ctYxcx+aIR&bQ9L@|!NPGiqPxiGIs zODmRt{!N$1dOzROeC}xkTWJ$2DF9xd-0~CVU8Z9?_7dTKJ72F+E4U-yX;r=aTQ*Q+ z_I^Z0OQ9y>Kge#ib5|atC)_pP`QdNSIxs<8JaBm-d>HDq7n4VA7bLRNPEyR6n2m0N z-=?qMcqAWV4K}!S)v*tdITyLJi2d{90P$8jqz&+~y3H8}!(G0SKiedvhibVUcdHytDP?~7OM$P#axsr`KdjV4owv0aTCkPZ{ zZt&mkPe5S6e7y(^CGY-V?#i#90VEAHod`gP7DkPVW03K70y|YR>ufsmWVpQ@%he% zF>U+%@nUoB^iUzx|ETvp>I6H4^tyyWR>?U$V@QBp=|uB@9Z9XiQd?61&A8&3%XESW z29|dVNr2{Zae;%xqEYI`7 z?oCavjbg5DuW3~o*vkgBkk59uPk%-O{iw7u14Bsi;b>YDfl$e{=G1fW#EE>-upo7rO87ali zbIC=@aU?39W3C}ZOdwrK?05me^ciNTi4OKrADxdZqn))>>P4k5uemIve@&8O z2tX}=vgA7S^fYXk9^^@)uttahWvVH+9Lux&HZjW`P#^8%DVhr~_+Fr6HxSY{FHpL_ z-n+$4#ZAoI*N(;d%w42RMTR7X)@L@3AernRv(Sod<+FX9hMgfLN= zzP@g!D*g^y1Gx_0*#OSJy&mNn6q1}L65h{oDTPtD^6UbH=#RNdl^|3@IYJsrttmpR z>cW;NSwi&umJFK~7cV>*wIU-4u$wR&!KjdEpgv}>aoPt!uu|5?TXhVuHBjOL7>5X5<53hWCzCA9k#8S^Jo*`I3Mu4G(XJBu2+t zKa8o_Nzc!+@z2$$`bvx@irNp3iH#;Ub~dFEKZQ>bYx%`H@mI~po8;zG927puc!AG&`6G3d^&o|y^ROp_U7%8Vg- z=sd=w7p)d@o(n^(=kHLV5~Ton8FobF2*}Im#$aE}muFw*Gp!F$PqklwM(Z>9I8*dY z52xVNI$jnTxANuNUrVCsB_-5njqRM6X~lZM9*Q8~%l&WZ+ssuo>diB08WcT+0D~$^ z+kZUK-&TkPk$tHwkE{^}7TilzO4-c~BxW|>e5GCe`UvyjPF>(&(|Kp!Mox5Dvc%Ol zeYKCPRZ}-_c1voJQZEU|f(6DUw$Dg4DL5}d#Vzaei`hA|vEseb*SPyx!(}xNoWIO4UhH zhZstGA66v;<-*3fltp*CdKanTune|2`)<&=fk%5-=0^GZ4J6mwi`E0PevS#~83h}# zhLnUvnc+TZ7Xq(TA_qqzie!bb9-h(P&Drf>d%jCWBli)SJYaxl@@;>gRJMZ)P5aiU zL*f$mDEZ>}jkhvFY@sfhp~L4{Ryn*}do;Lh|&mHSo*#B`q z+oO#_(-;0>G|2R>piO zTb~bwrSJAa)MYGga#+J6oIjmqw#FJoHkXUFE|N`3aiJV=LJe2(Uj!j4?*Y7+HxoYC zWusz9*?u+Gnbpky^;O}2l=P22G*jJNE9q1*>0N;-3e#Qiy*V5?3Ia1F zNDIIRBw!={F<5#urLHAs6gh~s+?au2>H$)foS{&T;#^Oya2mwFf)Cp6)~L{I}G!ekNm56j6c<$>Sd2_F}0QHGqRg%l7r9 z@Fkb$Y+YEpxpk=Ks`Q_l2A8>pqi45HlAKP72YHcPqMJi^%0XF1@K%x9<5}0MGjBEC>-$E@27F|jATH5AQQ2k&ENIcjk^~i+ldeQ9t$JhkMB|4!|)g&55*W| zrOPcsKadR-3{P>gHh2Z9bD(ny)16$|b-~>c|N8$iJHEKay++HblBt(xS$1t!O>2VY zwTAVTeGrGJ2oI+wq=|$SVzElY*a=2~$QiNdTSVIHg_K|ao~@cRcHfaZ&-E!M2|QaZ zb?H5L<(-!`(zcFdWsdRE`YS;2N(NvzS?ZUtN zmL##n(;kt7d|QQ+ZlSs~@jUc?2f{4D-T`c>fF zGBviU-GT6e@S^H~*+Uc!C33{oXi%^MFTm_7oeCH7Q}D8yvi2jQ>~_<(o9#NeFb0XQ zFZ%u27H5>KLkq_5lfce4w%5}17M#WjLzcxHiTzqDRV4nQ>F9C&Vzu080)b+tt74JDszT$2K*>l>nOfB!SKrT z3R;^!xzB^zybu(K(5PUbIL&TP*>bT-DN|8JK;G=ta{F934;hg>YVZ-lSg?+1Abzv% zT?^6{@a@S*L<62@8;U&R$;lV&0L+q$rgFGRyUi{Unmw1SDB(2o=nxlKls*wIvorHC z7jx!k@=3YK(^gV|)v0-lgmMDKDeLOqVFTco8OAi#o?-@=#+6YbMd=|ae>!* zL1bw*3J*7!Z(3w&(>i2&!GTcX9A)+H^-!3>Kp;xs+^`nYv>dQkz&;ik6)>VxTmwx3nXmpn7 zM5h$(&~x19{OItw6yfULQfFBI;jj26!J{$i#@}y)6jc9AGgmk!i)lN*+riR zaVeQ{2MU%{GPhXfJSBJ{`;bY8%<3tLVWfl zSIGwnnCMV?>N%E=B-d=2v!){Hs2=gHqy2AD!=xE0l78*p)0Y@-Yn4hy7~vKf z-xu#IrM9yYZLMKHjcSA4D%LDC%HvU%GyC{4PQJKQW;{1Zx>l$c<=$wiT5Uyj?=^fV!v2*w(+I(g6DW2Rsz;YSrpc$p~D7O)?pRw;D)snt)ki0_%%@xAV=}H(&&0Pm$T*SDZk!fmw&X{zS<3>iF_9G*M(rn5d1I!<+yn{>2!=rA}Yn1&ql&-AR zE_Z`p`}9Ap*JSfFI3J0dBxv3~>9-#vQQ;+?<^ZyPq3D%<*j3>`#Y-}bVm*bxKrqvO z?kfbw!QH1I+Wz+O7X|JT6}q%jmavzHFfsv7|=|1UJmX~LN3AzHhmMrjT+=+0o! zr;d1lv&KQtFsy`(N1PV0_v5`a_=bwjJPxsF-m^O7XYwX-`w@h2lGMt-v;kMJ4S9BV z>IuSq;u!0Myy7Sfa=gSEJ~7anKmhR|@hq6;)d{%iqy|1OLZ0)789`w~wL}(UlyC9} zZ=fCN7Q}@ZM*NWJ2r1*}<}~EPC(n?L;Lhp(x{LsLs_)Rlq}g6e} zb(>?~h$-(V0c#zWxmpL$3rkmJ6zoi@v`_gl0_aYC8N0?W@kPB9U{)B18Wq6a=x88@ zLK%Ua`dnE4`^YLb${3K^CR4)fX|aWp`4E;SXD&Kwb7DhZuG=8KJ0%&rHX91NC%Ts| zj;~Vp4Bu%e%!VeEmxLFYQPK@Ku1n!`waj+b*_#ozLT{`3u0^L(Z8%zn+{H)MGEzM{>+ zSTQl}bF~)-;SSCNyBJ!6wnHg@)H<9Tu0|h0c^wisJ2)NH>kYz84bcjKUEnqp=l+JP z*EQ#|ESns)vSzq&2Z7pmf0BI%AEb-a@!v^_k^8p!I7-^Ae8&=A7DFl)$-yEh^;)Yw z>KB!Qw3m?6c_;!AMUn++ey@VSp|25S@Bf(#d%qUtp9GpY0?};FBaq_-g*<@z*x8C4 zo@|D+v5Cw~?QPe?4z{q6m&iP=RLlqpOXckVa)8Q6#KC*YOw0%a0=Q7ltB?GLpJ$6s zep$cM!weU1#GNTaeS=K@LaMH4%e2DjNWnHCAD-)`T}9~^bgl)7fxC9Qm%1D$TFT^g zJ`SZHu7mw!Mw{{gFkjV14}wy1>P9U68eho?l6^o(#$~HuE*eO%OsnLd6je~_*lcyq zbImMmvecsIt|__`q+Xoh@EA3wol>$MP*GhTir;4FWU;Q6_!1mhCZjxNf4 zhgmvEA5&&--4^HKCXNEpx47|9%5^cO#JUMV3d&z96^!8kDLx>I*t8c`)UD zMs{J^W;7nK#v$kfPW)*alFT0seUh&cLzZJM%zcq}6_v7Aw!roEUhU6P)^(t(N&ZnN zDq+2E>T<~R*B9m0rm0^TbbX}~g5J^1)LO1=5L_D>o-0!RunkqcqF1K$Cox}3_{g?< ztP%^7mRpjSF|Ff1O?;|oTH>7|=Y4|dHh1SGz0=LsecOV>DU~7BVSL6$uBjt|JcIm%Uc`#50FqvNU!%y-7ewk91xer} zT%a(Rz-*Gu&29LQ#5Wh|Uuc!CR(x+J%f=AUgr`;EKx)VwhN{E-c+SNsi753yqdHIl>Qo<-YgZSZ7eoKbTk82f> zwuWIvMMGumK@tAv0uN4?zhHn?^8AE9Og9=)#ueAz%gS^!*P$#vulPnK$SF;2QRbv5 za@1CMJI11C4H~eo&;Xx9#~rM24LINr-}Ir2zPL{fBQ~wp~kud@L;06tnmXH zE5)!wz$B!Z{TLSz!p(r>Fo&LVKY_RSb7!AAuqub{o=mYUM3)cd4>I#ax)F?N|5pp( zgaKRD=$Vq=R*joliqVN_#exs|D%n@NEgslx9ctjrlD0wy&fj z4}c;`Qt@c&lNE}Km{`Ylv0E0c6I<*2J- z@7}^N@YDA@h4(dc9OY^3&WJxA{g}T;Oa5$pg|gCr!xoeUZ^)SxbC8xNo06>p$4H>sK4zNPf^ZUp2u=G>{62T_XnFJB)w`FgU3Vw+%G?xu zNrye&9Wq;~s2PS^yi_2U{fP`h6%-R~DLa(Ugr=KQ@ivu8L27$l~||)Je!zEX!v&%55Htj2@)hB1Elex-AIICQ$xitdy^|wQj|gT z=@&N60u5#w6YWRD_y@@~wfa`=VsJ@fE4H}4uCH*tI_WAl4%{u;-RBzcv_JmfxjB5F zfGf!HQZ{NNa{7o&uKB~~bqShx*L zM!uDcKm+XHf;owN-X{OZ?7O44mVq&lKAFhuycsJZD9~ud+w*?h( z3f~wa8}=O(s+VyOn2rsWUuL#S28-oNXOTgSRB%VxZNE=gQ(unl9l6fa4^|5{{ zDR94K=UrCW_VycGcrv&7F8{8r@BOom{#aBOFPEdXk3i(5u_)$z0swZMm?oZ`&`uYXLds}ns_HiRB4xi!-grxX8AIk~~1P&*W>0;d4j>%qTcjjv9BA*sOy!)ZNS{#xqD zb`n{6j4fpWTK?&q&@7LlSBFQr`d2Z=3eYeT51-UgmOADE+cS|%HY9O1?@-NcGtjDu zzjP&;KYoEgT0+-4FPdRSFkM0fI}L8VXZ~Y%buSWF&tP{Ip-^SD^KWUcONv3$YniQ& zZn4jPe9|jyuZ!>^e~!=nPu_o}I#{1O%j2cRGa80K84I;6JLaV6-y(6Wj)$+lz=iOw z@LZ}mu>F*o-P}T6@T%5jgB44!e;mLbp57uKv_;mT&33tA!9C}VNR}7Zh(~0_9#%%u zjjo2DMfCSCS8QkNt?yPMcg?gt(aZ}m!SJ0Fqz4&7YI+rb^=)@;AeBmMo{Z>tK^NDH zH;U^8@0`eAeD%`zGY4BnN#|R46h5F!>%0-uw*nBd6waeQ0x*iRSwPvTX!u{6DDcx}?DtYURt0xuH8r&LAV1!G*n`qyr|K z>;RBX6yIx!eNFV7))o2^N_cP;lG?8w=*NEcG|PNS^REAI2neH*%qD5@{oo#^fr_a! z3_p^2YB8$f4a$Pp7TO(;3(A~9cIc=#eV=6(+0HAs0k4lW1fL!Y1`U5)szxz9D8b(>s+4t6T$#teibi#N`KS`_JWk*X>SSjB;K!8W21LPI-J5)6ojKBJF2N!8rq92*D zzk8I;WW%RX`uazGfl}ZC@zPJHP*0(<`~^vYiUz_=rXOW0)}R;}!7&DLYbFQaYOU-8 z%jey*po*9OL6ICB9dpT?1zumF)sdX)TCNKOJ#@HfGH@WC=*JnI8^ggixW39J&-EHMk36 zcrN_s-v)B_8Eiar2Y*F!A_uEdVYU&M#Xu|!sYG{txK3Gv2hmocb)FIGEt#I(ww@dW zz?eqNAi}sl@8x~|HeTKK6=9DwjUVX_Hgl0o%My0T_xs%-a|o@V0Od!?Cwo!UM1caj zk1ur%0nZiX`9=yDC|^V;;}HC-UWcQHO1_yxWvB`#+$1vOlCG(mL0#An7g){d$x?;< zyOfsy#;?)X(B?n0c#dt$Zjil|AP<#XB=Y>ouwswPCWztFX7!*jvZbt?KkXgb&|u!Q z&;2OA(>%~#CK<3E(oG{Z8&LS(kPt;U&iR;0ORAKWTzI^*(EeSFwsIoNGSTzT#L8An zDigKC>AB}XE?L7U&kcW~x^4FuP2N@R6CETYNOz$ua05g+bmVz7hwv1Aoxp8Te)lb> zYlUCX8xEFgF5sU}HbTl-qs*rnPi!XbY>V=-UXTp@O}GT{k6N9JIl_p6%G~>w()*qs zyvmxKbgz$09ylvu+Iu^@w7+#F%80dIrc#|dHSkfWrg^21nIlSI#ZRAn4L z=#E)-ZSW^jRR8X4a_tV&cfrSk=-?TXvu9GhQ?tLARs}GEu{e&Ta>Z^F`o87nQuVpc zFkez&rtyb2w+#Bp5~qvgRHUGCn<9IlFew>|P#ff}x-UAl@`d9x#!FWbqbm7fTL=A$ z{B~R~HpKEIv@SkEEC*r*{-126)zZlDakiH=t{RV)r@_Wn1_C5F^E&VBk&1M(M6Kzs98E(Y=U%W zeJpby3a(K`!QIG~Rk6YQ^+c&fNNniblyTko&FGEu!aLWwbSfeIUp~Tje~t0%(S>bl zykPI0K_rlhnQK5rt%#xRwrD^4iAHJ=tXSY)B(p}U+-jkd&w={&5^MUJCf-w6g?t~} z3mTq;%s+W8DtXey#jh!*_nBXW_Ip0%8om8$>KH&9PTFgAmXY5SaS}-Ntcra zgv1&zp+RzDanPGw1o}_z38K{HVfquPs`5%FS=@dm(Jx?_XyhxFA3 zR0Ynw)&=Mr;sR-%g6lhN0rQiryV_Q@TCbXejYe&QK*VTc;Cz_c>7LCBl=MAk{x$8O zh~0XRf0A3l*$v!Lg+QZ=u0xtIBVOw9x#j235xSC z&U|qr`Dxz05dN>SSGoBa^)f$2P4riwA$|RNarNFEisw8Iq0B}l7T=WVg{X(v$C%S` z!@C+_k#RG$PiW&b7p(8PV3BwEDu#M#VePh}TS`#8vn9B7ozvh-JEotNdFWZsbcn*9 z;|gQ%%{MZRy8gm+t{yDJ$4rdlykpPpIyV|g6ZTn~pyaoLVWFC^bEa@>;F;);LEktb zTpo;mB~geLYCa3C=^azJC*w~GLIVQoKkncNwAGy)yU{A+4V5>`?3IpIf(E#PR8CWx z!nRwu_Iu`ZaK~YiJpS(*rlkwalwg^(ogn5+E43w?smjmnY8v*koj|)y9YirBzl82Y zrNSpB4$@`^Aj531I!!8y(o9-~U{H7j^J>xy@n>_%T?}7FAzTC1=(7p3ODZJxY&i+7P5RSeOl*2vk>agvAkqLJ#o&x_! z8gycwnLxw(M5(F)qR%mTC^)=I_e(XTMJtd~O3h#v>(s@4qCbC}wmE_R>f3!xh~1U! zShUp$Ep$668Z&I|QT$q0giI^)yRcx^#4^tcTmcc5FUpOEq=- z8RruLSUKM+zV+oOU6w1NFmkvncn9O-{lEo~av>QuszpT?kAp4py%yrh`HB{3Pf7Gz zSdWx`_SCyYc_!7dJyA1z*e>N3(2vF?ba$r9_8!9Cg|IR^lad+sGDD=?P?AwLU&;E| zP#)r%RbWiAI(gRsYiYZf(r$?tKX$0>cmogE#*gkJm!*OA;#x(hu>!(j^bjWK0STOFJxHBA_3!n zMkI-Ea0BS+@bj(^(6>~U<`r=~GV0~YAbiCldy z^1!P-zk;Pv{PXLr#?NBwX%eTcC4WJA$t)4s#QUgLn*{k15`nu4?8iPm&ZsJjd}A)w zqRD(8E?fhMEpB(TV+x-xPD*a7UsC_E7krM`vLB539l9jYl2S0=-6OWH5*V;qQ1@vz z{X&mLq= zr!HUMI4H@KD#SB%Y1rD8flp!(r4(y4CvVf*2Q@7evj6xTsrWcc`_inm*e5-Ci%Z{b zvv+1crUD~)Rxn)!0(md&1^d{hW!MfPR$-5bmlvxI+P7BgRLLWP_KCy)4_9v))K(jI zjRtqupvB#bySufxJ3Kf92~yk%P+UtXl;RR7El^y7yB3E~+?@jLm%it`XU=>-nF%x5 z*|Yb3ExFd3OG;^nLBf&t3R>MJ-aIWO{$UFbC-mWh38UIm5 z!A>~D((&RTnoX06{ej?3^qDu4Brg3_AnSB#Gv-S(_GQx+7DbYY<1dq}@vaj{~T3JyR11rS>hQE-jXc z?E(qsY}n-Wj=~rhF2G`(Fy<>Q)DossvZ|CO&#ju6`1blPOUJQQb*nPkl&uW$AXvN| z;-(N93z1=l>uQCLN!|fFMx-i&;iMFI<8zP7a&4r5c4mPnQWa6$E^L}{>wB>>!&D%lw@5PbN4*#pLP)xm3@2DGx- zL%A3b%u*YljKGB5Fo z+0A7yvuBgB%l_i0$*!P^G7TWyP|)>*kA!!s6b{XJwg5pHK8v^C1(uj<%+tlP%}k@w zsmj-aGIQJULye>{KMpy-56nSkRe2N8v_AQq4AG4nX{(?eZ!wNm5e|1>UYbCm9wD2e zOGm~Of~FSs?Kti^(6XbF_Vpvd*0>#+NwudpEe+M9MzwiAhJuzp@D^J>763!S`Je-^ zkS^?tZTz&vwDuMzNubKfl4inhqw-P79U&474ij%Rtm8{aJJ9-t2z(6#-I%hgs1sAu zpi=*wz6aw;6R3WCeIu&$5v16#Ej{SKPGQiR2ca1xfBPYMSgH7pLi&uEX42v>q?nov zd!rFOAL!+)uZMKL6$-Xc00|uuA-SJY@v`KG2D_OL-9^WibyA8j6OLNLS|wjFJo+ac zFGn@A5IHzoYT3H|Z`P9N>}6eQU*n~LDz4RsQRJ%FuT7@Ozf9xxA#lb2v`!pmuE?`h zUb46p>&`0}?G3;bJO8O14515CW`j9V$$|jWq>X0EfCwZ0J1fs>Uiq{{UPwTn$(mxq zkiTgJP2m3!mZ`i7s@Tm#brS{BVr|y%AgYg7smamC&?OWDM)K>=R z8Gn+O^Y{0qd*k9H4!1VuM|E}6?7A~+t+iyb~|`ABSRvi}b*p>1%30=;MHi_^-XZT{NN@>hI%zAtl z<#r`Ch<#z8nfmU}$_hzI`@5)GrEZ{f%=BCcI#8f@Sfi z4PK#D5dYR0Hq~CDwdG0oC;Am*ci`V+A*7=XIz^P5oe*}|!Em5p8F-L9ktOTz9o$Z; zl6f-yj1m1KWhjB$zHOVi`U#lG*1AIPQ%vGLGa{(hLXGK~_F|l#8%%W=FxLX794lo5i0#h#kogJ_ju`=p z>%Pk{>%tibzG1A~M1K-J!LJ?&?`}?Rc+#>sCtv@vKeun(naixQOvHmMb`h3TqEC1c zoJ;k(z;fpEDqa_=6m5`9=)LycENSQ2EqXYPMbhOh``&%UQH%5I&#MK7`iyi$CKi3G zI)2?-Nvtm)dNUA*kwg2cU>QT5`yyu|-vCRIh}Fs0PwKZlDz|Unbxf9}QoM7I-YbCr z7mY!6e42_F@gZ@?cM}C4MxYar24P<4Uy=1w@dAyrrNSoQ9u437Tf<{RI_FkX*eSXw zv0Zy%WJ6BQMat!!gwsES5yvWxR_j&!UA6#$FzSuIvtPT)cH=zjDkU?@1bmLQb9&u{ z_?!?T9_{~aXU#NF%seBr=)CaZl}L|N!kY-j*a_(|Ou4;-BfiVFt8()nQXgk0d}kV* zk}dF8x|s6>@l#9LEgikvtU0Z_&(3H_&Wdj8;uB30Rl$vi%}gS`tai_uF7kKL z#no=ze~=4L`*+9|3JR?4Egqvdm073R*+Pve2Et=-i%=@qzWmS@l6dqpZ{|!I^g;?( zQfvHE)}r}vMLqLcrWjk!vVkeD>>gQG1bpN0dM(@`x_XRpk_QlIsidX{q&RE$E#tj~ zQAKNNJ^P2SgAx|IAOCP^B+{q_)~`h9k8$zQ-Ks%-Uj3Yc zQsz-YLrOz*$DF)Z5m%@VW}5tpT3_s(wD@mtS+GXMOJ1uh)Uz@xh2Tst)AppI)tdpmrNT{5Rkuj!eR zk%rWnJ&yF;;bJK>9~!@6I(lO0(}!U*wUT>>gxy4~tg%YuYD|?Xs@aeIWfF%t_Jf7( zSc%XNBbV-);W_~S4^Ch6XCfe>u7?Ys|8A@ZwfbZ!x=);D@{URey35_OZMNdjpu!E4p3>t+&~TrO?*l zBrk_B$3YK`6f=wa9&F*nPY>H&FgCjRT8p?xlDpXVp&{sHQzMOGa{R2hCJ{Uq%6$mI3^&*n zKEU39B%5QTK1z{UsmLi<-{rh7%NU(16%Uk-@lD3>}EjDt7NdtcIa!}S)M@6tu zz{s^=sx@N(fUgkR-&<36dZO0*_aj)Z8C@`x{DHKQ3?4|8yUg@}${?Ddc`h7u)?a7V5<68Q@vA|&zXukW4z#%JJo7%rn9-JI((R%Gl zw<{VVe=@}jrCQFKXu9%FCaE=R5ci1-WPOVMPK+BF5)n^y41XiiITKM3DE0X|H100} zblj#nUbms{dj;Zd8<upyn&7h}i)Djj9%LF?X7ZN~spwP2U<1~LTrzWT{F z!6&njTkz5eo#-{<`<7`NvM(P{qz3p+M&KqR)AJU{d6h+ef5Z$h|BhtN{LO(@R&s6m z`QHTDX%PWO2IfloR4K?;&1K#vW4&*q>lsVnJ{dDk1y|`HC-~FbuC1e;2-$zXKVj`D z2=EVVs?ZZ?Vw!34=d7x$n*9dF~wgU8< zs}LtPX#{oMbPaOEg3FLtgmW6gZn^xC^uObQ*yRWckIA`glJ)wSvkVzC_}jw*cbPqp ziRwzql5bP`xjx(ppICjzwUfve3GWiQ$dV=&Od?JU$JkX3_`5!iu)Uw*X2iJ3e-A+t z(kf<*eV1`v&#WsG*k-ltTK^cg0&VLkmc ze*fJ_WZ8WO8j{oK(E&Y}L_}cUy>S{eNG}@=8to{XO>{kH2kC7~3yY0vkK~cSikqYo z9Dzuf*76B6sZ=Oe^O+}>fh_MAc)6cX6!oWc*xGjwGHtP7I*S^W#yJk zK*P_MO?oHM0D#mOwXwLEH3K?fk1djfv?Oqj^+++cx2FHT*c|6fvSMq21E4_1#WLNk zvL(&>=NUqO={(m$kXdX`Q?8%d^t#Ik^F~aih=Kk}OurThCb0=0?0_W*I~*+sialOr zaxhkHE7z(Fg7JQ5?-A`r4o7?d-#sOGQeYqc9-g6y?`u=eM01g_Pqh&!E#!xN=~;lv zjrXUWtAU-c{WQ}8>88OZC*t(3MKt>(q-D}?)?4IRUQ#8}rBr&1hX75B`eM1|nWScU z#y1pVYI##Uxii#>e?5zN+PFi~SY9)8=(UXCR^Z~LSD1-wbe7FRG;o&mw6T?QE4BBO z$9bp zagO8PGLvKL2;;o+^qS8{2OT6uxMVmW5e&oxc>+RV12T+orF??pF2+79mB|t{64ESs zuJHeMI|8-|mZdGP6A=@#Em1kJ5}M}=EC;*ta9GeQa~q7mp)p2zhpzkNy}o2dSvaO; zfSrU^zQ@kiqdR0(L&<`lEp2+=0A}s zG_GVg4_nowv+!>$Q8XL3RU(SNp|cQ_^YTLL%tWhO@3N|(aBjsNDkny;GsHVOL<~zF zHNYu&kSWYl2;sZvo}za?;eFk$x&7r(%B4qvcOpN=;;N-*PL*W1paEGA*6g6z#uBsn zVdNrYx^k!YbBWPVfY(XEq}!3+SKnqGhM^$ANwmrIR%CE;thoF8gI+K`b=243%P6j$ zSmCAB;zQRb#Q036fg`C@Z0ge#M?FraJrv3Rg~#EBPO}#(7o?oXv(r+hA9}0jr<%!| zVZv$;^!@~F2zh89Tw4NXzMPn}*#Ba+EXivCcp=O9v~J9P1{^)H$f&j&zcbv?UE*!o z|I*Ycgsl1t8iAWAw9C`UCh7-PgR(mbvv}CVj=`MFw(_#npwm^&G@snO1VO zUKXx@-~GD)(Jxd5Ey$MyK3L6ZPJ`d#SUcGt7FU9wZf1hh6!qWyx=>e$IBJc{(EdEo z2v$_bqM#eA9(!At<}q!t55{k;fNsc0{?j=Sr@N28@Ft*s@Ved}=<;EPTJw9u(qTSs zxSdM$R)te&aP<~DTUiEb)L6D$72y&|#^N1TSeAmNF6zPH_CY-!=OL&FPNvoFYmrCE z^EUI0aLrJP3)-_4Eog;IrLzZE_~bI^^ubZwvjspIB&ip*%sUjFa7$KvPOrJV;^*R@ zEZA^+sVew~^5HxC*bo~sUeT~wi@NY7pk)vF!ce7du!vzu82fz<2$yCD!A?anR1`4~ zo|t^8Fhb6&Sce28ej6ZMi*pH_K2t6PZF8lHTz?JH4Po)qnx8sz*Dr79IO208H%%%k zd!xsoe}Y{5Z5g8RG4DSCSLP%lL#HebNE%MY?zCA{J`B|tDMFOI)%)`b)>e#;J0a^5 z10{c%JwGrQqI963KJ5!8VbNED-e=`kaEowS@FQyL`13!8rlwQjooe8+GRc>KgS}%~ z(uY%D_iH1!8jpf)Y@%$}lC7fG6W&Fm*CBryN*p(hca1Sc9J|La9pdPsdsQ@3L zD}X++xrF57r3tJd&dJjK!d@!8*{Q0o_~c3V^DiDwf72uE2y2uzl06DFE!o%^^%wi% z>-0w0u#10cq(u&rmjR)^W9cZGPyku!D0TLpsY5E4l!XgpG}O4)!AL6t$yiXvqOBjI z!zXbK`9X_rDI@1EiIK9eQV}&$B1C+;F;kO3H#W04BYzG>m#kf`oXWe5r==|lsND!b z5M9Z^d8%>ZQ0G+fJ<9RSJU4z-7!9%*oD{jpb{VQWPDS`T4%2CN$_U z$#Oh0!xtaY^2KVSbY+KT0R?5A)Uh%tMI$-$3C)02FKTpP*%He@!=ON4F+$0hHLV&d z(*W!wwj6o%5-!s$#W~1u`3}H4)3zBrb-LL(6i_X^zmZUFNOPIkJ)mX(bg#GdCh%Kj zQ^Us^9st7|_L#BwcJd+jKeIfG5F^40`xxBG|9N+YGrZ+&_tu&F-l3TlL2Tv zf84pS{e2JMM@Yy|QIvMcPy}0IH{i^?kv8LbfdV;=nj^;C|A~7pR7Z~cyBQ0Rp?wvK z0v8r^w|-#fqo44=@cOWdU;jX(Ki<+9C>eOpFs|NrJrM1798|0K=IPb4%w{ENiQn}#fVAS*izZ}v zWY~ni%_-7Y+dX;vsb{Y=A@|E_$!m>_I+s0>=qZx=LP;htXWVL}WTX&o7njd{)SIp# zsl2D5IkAW(+a5a@pyT(O;$j!vRyf0leWv1918QOS?BSm?6%a4_H^9HhMUF7%MQ-R1 z1YKo}P_j;`HW(4DPPgjYC>T=z?a0#{>wYV>g&*2e-|$jgqQxrMHB=CaAb);RO&IF9 ztmNCCDFb@xlyq*QxRxf=;QOCE4MZ0#(EFr=EZBX>caS00qBC67F(Y`dtTb&)oH}&! zm~w{&rtEl!S|JRIhrE5AJB9-vCGA(02%!q2e00E}j+d^&Q;PVjzidh9DNm2^!;7bF z#<)9hTu=2#o`lQdM0CxU3-zE$MNksNlZ4Nv<2^yBG!@~f{U<}+O0_3( zzPQ00(%&fc0x*ABfBB@W>n5>44c9DO;dnZc}bN*h_I#8S1yYufnqz0 zreeCNEI*=>NrY1xGIfbV0VRDX+1hKl{q~q3JEuQARM66sn9R)U0~@5{Z3F=7bc$!u zrQ*Tl;K?mYsal19h zG0wG}%}9MkP0^^xhcu^$!Q((nD=}w-Al(m%K|N8Z&otPYs3w{}fFCGdFjWB#Mufln z5v_2k0CMWkJRdn*dIx&%=>eqcuN-!~7f!v83Ezc~-BXwC1UB6|eg;7NpAm<|uO5Ig zWBsjnUF@=h_yrXVKbnqy@$0_eR~=b^6cZQ;iejI3fATG%lPK%A9-w9xGRmBjPCmz> zz8J(ZQvAjrnT0wg6{#g>Ko%x>9`kNVq%Uv1@FXaZWHIsss!hcwhi=Z3wvSPHX)Ljh zxFgMTTNIStui>{QCq6_!hFPY341f-V%2e$b#z?@}O=G0IvVsesMrWlzBajStBKP@ZYvJ9P^M zXBeNU!x(lC6p-4f5(C-*QddNEfJI%JAW{m9R!?GT+$S3BC8onJwS=Grn~`(Ha4N3J zLoDy#Mi4ukr)cU97m#}GTvmjs<<-KR6Oo6q=?XsDTATZar2VY7Gsa4e`dZMm%G+W) z2sTd0`QU%!DoB)JblzVELUHyR)21nY;Ql6Q1+~+gNl%(9V&l*ur`>e(9sQh?a?=hu$!RO3F#r}WfpVHE@bf*kw5}V~m`?!b&|lS|1U@GCG_9*Hd1~DOJ`K z;b)Odga?d&J;EXze0mh|j#cikpTN5t_xsLa%|*8udd;oK-4CYr*4sJm$sJ1KpqVOg zCrTx{?-Uo?V;|V((o!8jyNIG;bS6T%a+tVaE$S=k<}`i6d+SS2gyegUg=TD(e%TRJ zOpOCu`3Wm#;<(97wFkTmW|d!~2UUmqe)LPV1Gel{U8Bn5wr<4y0S{EuTRbfXWm80|YP>>!T?V z`OiLB2A>d{{S35Y2%(L#Zci|N7q^uC%Vq@7Sz$08Bn8Vv*b`R6Xq!1{KU@goo)pt$SPVk%U$TpC6IGY#tA8Dy<}f+!+#zLox!u3e z*m>yCy}HE+Nmf6bAcs}C`_`Ky(zefx` ziY|?A(dEMwOV!|R=>jvvbeL*YpTg*w^MI$Iv%rPE`5x|u6V^jeaa@3yrrwD5SQob9 zJS=4ppB2@1-~1cFeb&&Q>5%@s2$O_EovL1*UA{f0)RSrd-kdbqmOlUIgAzk%CvSMd zP4-oa_q97f2+P6LKZPYKL+Z2hgh`WAq6gJ^8&|=NBzpIfiPv?S;ggOMp4AVSYNZ%)R;a?^`6c3Ls)8C@STi3E?#x z*XRFqb^Kf5|1o?a0LrV@K#$IsLBH>goL^l#M?r(n<%zn;)<&{_Pff_9LdyOx!xt7} z^x0>YS)J*9w#N&}(?Ixr#C?bwaL!E3z3vf83c~V5Kg*&&Ff{?1C@4I+{C7DUc^bq~ zRzf~w1?AtiT{?A}BCjsdSc-f)m~~&f&;RXvXxIS#*>=aK_qVkY;?glgu{IA zz0jy1XcyW$utUPK^&O!&R@Vfnd8Y>*Im^`xNfi7x$=o>FI*$m%rhENhVBgt^_%$Uq zS`e<1r6+K5;B)mr1M8RXR8c?Ah!W4YgFcrff240vr+@qDpL4-{qRqb7GIPLy-wLwj zws9>4a_379`VAH!)ynmBGg9X0m`i5qA&!!7!kJ+l`hx4;9+D_6IWZySikM;R5}qQY z@pIPSdYM=J(4PBbSZDwTtuYTh5#GwN*d+rAz+fAXPHAC5@ps(tG0Lr}Ajk(P%Vks{ zX~Laf1_&z|h*zdc zSBSN~N&SwT`${7N^q7PO7abAc)Qw;_9DxD}aIqC(vvdmPKO*TMI??!2(%7&~BcL=m zm^j*-O(ji;d(!6%Fn6qVdJ9`&HdJ&+UHsdtZ{W+}e=fxv?aap~S|S>x#_9&3RNQG;HmIlF@j~r z2RkQx>$WFjZu8;F{8S9y^WPs)aa(gP?Mu+K?c(ib$LYCXLcdr;FdFhMKM8A|xW$Lm zr+&$3`S~>dAXPf7WbfXQ3eFVTz%Al{8z9%(aA)oTaEp&oP@5-_5>besBBS^E&OacC zMe*tNiC#s4@4R069$#`bk}8{MvZ4BLrIzpVl2edm$_5}AKy9aZA*Zx}lq#U=(=qP{b3;0|w5MA0*v?Yt4uW`lS; zHXEsj%8UvIG7g7gTQ=t*dOXCu=$@VWIz^MghA@%nT)X9817Xqlpz#c6Iv5QJi1_^> zhts%z1ZEnIYCBNA3(D@_e1-fi*HTvg}6V{A)iX*QqfD5~ozQuy) z$R`UWQo>6_XQ~_yWurgDW9wZe~R`&9WcE~)`YgxhtQ%mA2x&|Z!La;^A`<%~^ z|9AL6WQq>5Bv5QP{;e{>`8TcZ=3mc{chxK1|Buy?IPb9zl~OBrOZEeFgPNeeb0$E? z8@IHYv%VKPKJXNQ)`Jg3sP|Lj+aZB}lN{Mrzet)Jh`+Z-DxPE35rz8^Tz_blL!t@h zQ~~x+Od#&emhu1>Wdrc!YG(m6V34RmH-7uS!Tti>af)%U?8Uins1t&Ad>LKn7=sw1 zg68P9#x@>?LUNaDhML~J{j|U{+CkiW(Fka;`;iv(yQ|PcRIXp;9VUEJyCWQNPQd)$ zeSurnm}dpGeB4C)gL|2YS_v|^AE7QVhzEb)3KsHYquAK&5^44s|^>f9TW0a@&dHQ(L2R-`T5uK z(OBi1)FqajI!o70skNz=Qd4VwsK!oQi{|MJlbF(6wfx*~Z+F+?n&T5GjXQG2PZWBb*_qE^J+YN=04o-nCphD9TS zqSHo@`2gk-b(E{2<8b?5vY{QO*LDKNcJ)zh!Jb!Q+Wb=rNFQRI${5TNn_@~WLn3I2 z`6%7rnrNP9FE7kYY*ghn zrdCQu)b$u8?nmwmiWhf28Li4Tb=DYAFDY-*yNG53AGL!{GZbR&igGD-P-kxoqWNe3&9kkivEmBusl^J|kehFo+A z6ps<9gZf-lzt^|g)zr6fRSRSLy!G831ewtoq^=o<9-(5Zy$Zb?g06TPK>Fvoe(zVu zVHwi0(I~9=V2Uo4ViZ#7U$w2ie=}rqn^Efb!d7B1*LLuV^R~>D`^kU)DjyQBy)Cqw zbTTOUnN*jbFx^h|hCfm3@;(;tf}JTVTnviaF`=0OeKK1S;u55CxhRt}Oxu??75q#> z?NT-hzP9J8RFLluy8_M*_NqQ~lpfy(ick&m$iH#YKGXEsgZtjyPTMLls)~uQ_DeFv zjPxA?m128l1+z#&NA@ndost}-3;!{En`fAD%Bh{8U66^;*)K5JwM~zOqDRX>oIAlV zpm`@)#NORegpYQ#-Rm=JlE7$&U34r`2#7Mo%kxc1r@r?PbC;MKdA7c+=d1pGLVA&* z5SCJh?#5xM>>#-rMwud*(3#~E@kb9+(QI$NyDhca6F z->vbUG#--&iva1tQn*Rfm`s!Wg0hMwvy&-lkFN}EE@W;uA8~@lF1tl2By-lEiFu!ndu<56NjI6ytCbHmCx5QwW++~dXHwxN3titDM8pg_tGJozEz)=-$Uurw zrPhsi4~xf5_}?HbFs$DCsu;Pn$!^XFnB(X_pM$S=%;frxGTL>n^GJXCj6p5%cO~~l zljUcqPhSW7`F^wvpA2uT>ZjI&B(IuL4fZ#2W^5W4SwjNZd+dS&nyGfVyXm+a^bot) z<%5L;&B&z;JL_!RUc(x!`|k?gvkIIhV9IoDn?YBGKB$`;wkE@#ZZ9TZ+28VS!Ti-J2U&T7BR(R1F}B||Cn*e z5dD`6qb*(P+?BvDJ1rG&#uhoM>-RPz%AGpgCWu!B*FB;fv^S?3P{weNupXrdY(j+# zwCB>t83<~4Oh+f)da7vCyak%J%4D_}ikH%qu_BciAuV7JD!RQIF{kvxW4D9INSTU< z5+6_G5wQe0!t2p89z&MlSWi;<0*fIpyGXo4`TIsxMQJ{XqV=!!Q^9!fp(r*Y-F(G| z&wvDd5n{|bKp1ZyBHjtcz3b0Gn#~R>U862XA0&r0mO6ZRQ|leh)x@+#&pf0g2O%Ok zEBm>-ooPRVfva|7vi#$a3F5JiXbq&DJV5omDssCx_RV7GIvwcrJ;C6g$(`iUL_avK zD+zR%sYkF+QX5l}s7urxc&%BDo@tSY#FzKsx?U_PWNgrM=Heg8i~)4IgkvLnVXPr< zK#^}z{mB>iV)47eoc`AfFzHjYEBuWJoA;DwSyvSh&6cE@TK;d5rL7>1>KSjF?zc0J z#>0?ezU&^wHsd(Cwh(ibosmo{sa3rmD?NH zg>sHWchEl+0>f8kmXcC_YYNFQT~fQ{uAm^~oGLxVOc|U|CwZ)j$z5kUSyz`?Yb5%^ z1DhG85NpI{&3=?Q!uHl=Ki@&3gTP@v(c#40=H_13AO9`dAZXy(RkXCc%QJW#=8Qr0 zCv^<8@WyW&e;!@Bm;Qm%`aN_7pVE86yLdXqXVrAL+ux3XJGznMDLIP@D?IIB;6nv0 z_^I&FbIibXP^EJU@&jv7+ROT_*XBor7NzxnX;Gi`XrIM_)Jwe3&Em5?nnZ+^&Ai7t zJInjX54c{Tz*Tq~Zx!mh4KE7lKrME@fgzl8#rzK=1;I}P2>Iz3bql-TH+m0~lTYmG zbZe~3U%zb_As}R`5?049{Reo`;cFDyDq{ON`veO(@rI8Sn$XbP2cGJa^L^@`?2YT< z5U-|l?Z84OKVLWH%=$ps-wZM99jioHiFDifA+vu^S?!*n^E2npQp7RltMB+*0z!0( zQW;#^Y)mACx+?37wMmR{SZ57UKClCR$ z9y_gR@F$(~Uq*=1i5bWd05aa~Ft|1=&vSlRgisMI;8&AH6$-0ogvxMN$1#`~;Po?L zGA)dH+su~;P|f5}ep$ss(CV$IH05?HmJqwCAREVH3%d#=R6VYUO(B-QU-rIgR4UQeKYTeZzbsSbP&cF{<2 zWRNfI)pT80S9cU@Bd+ zb44Ya)c*pAt0Nw0M_zP2g#y5c^h+zjFeAa=V&L8gc{W5inAH{0zaUdoH}UKe8S_(}7C_x*W8@2IfP;{z34NLt|}jG7wndD(i@_AZ&rS2YqOFc*sj` z^A417htr`mfG69f63vn^)m628(u7Aw{vn7gU-IL#?3%+%jmW{tvJXaMl#QQ9`sE;u zI_Lu2x=C9FL+MBbXzZa_O$m!lg~+7)xVQh<2+-bl7Tfsho5`z}`b0vweuS2G{e2Ev z-%+Mc@o3YfEx!ZYa_({J-HT;;-cS4**lyQ6$vEVn@J~|Kn;t@$QkP1)G%;Id;V8LO z-y-0q{QI}I^8?Ht(c_9u_!74@b`?soYzu4a`H9-v{&LOw(g)KJaRe*}GMfe^7{TDh?VS6%uB($p0Many1TZTU~gU`G?7P)8LsT2(ywE%Hi zwM7XeDW|XM0|`aR7npqBU_1GApa7Chfj+yZF*+D0B;pM_m9c{&VX2}an{7im-%qAg zvIwx_wt?Pu<~x6^T=ez~ixE%v^*sroUM{AC8)?eqj{t2uwwB0@b_ zR~j!C;yaH-KwtAKCLCRkCuc<#WuA}79RqHBi^X|GaNyAcEPvBFMF}#Gt0z0d-9Au&#$Yg5KfkUH8cRHWh2#zToyc~BwNyj_!vBfr-cria`?sAyMkUn)X4#r8V22gc<`=bX-i;xFV-r$#t{)FuLIE{O8XzK~CK{gx7EVw(vTuE6rLET@R>A)K`0LQx4oHtVwM1>V6_tC2BQ24t7$7} zFH{HlV=k3XqifltOn?`j4;v+=ejIMrq5_i*Np13v;SP?teuGaLcQ}eyUx+)e;;1AO z{l+MJyu$HkDj>GWQiX}dwLPHzXDK>~vG zYL=Rddg?<`8M163LA?6H?_tOU6cXU)#~6KjZcC`u1lr~7D;@0#8l7G-G#~7sq6xPI zI-=*8x{P8Vdb^ zg^hLo*`-!?PQamRly>|N*{9gg^E8hFTPu@jcZr?r;ikD=%=S9_p+9bdC^u{?=Cht8 zqW=c|LVgbbmr78kwkSL7X3?6fNHhmcuea<`!u3sd#vy8uBr~lM>^lX zM)CRZ|7|!4tt87d8hK$x7HSuD`hHrMUWbblA}+%tAw-g5W#^D?EYjt_Tu+psM<&1!{z$y79XxVfq`&>9d% z>w~gG?KJ*&%WnYKN+gLgDn{d&+4kvnoAT%UbdN51nqW6MIAe%su>lD?N;DLRj zrdJ~Vuo*&>MzyB9b*8Wz?+A{9$OOy=Ru<#5yyrp2%i@URf8)MRr#zf-X%vSBN{A={ z>a)#ILc|l|D8-Ox98^ernYbg#Nd^sut>X3HQv;*4EmLdgGSL@Wnnn}# z@blz8EeCAeLd+;+6%HjqQ$ceqCOx@%TR+15=ozQ!Y6slFC1k_3`H$Oii)JoE#q%F} z8ehmM-?Qtxon-&z0n*o0@pri%`g8og2Xq>ix#F|c8$mV*E6D?93xNwB(KkAVKF?sZ zzeHBV0}3=7a{za3If4GF~_DoBtvc?QwIbL}>)05;E!6J>+(gB*QibQPJvGHTI?`(Jw< zm?-2Nu|1R3lnS`9JvzOOg6N8gZv+JOIK6=vfjx6XVf!m+0sBfQW??^)R$x_FCk2Yh zI{j(Cc%meuS`{NDle||!(l;r2)OSt~7sv;2%5YEG$7eh~-;Gu0zoBGfVGrmNqx(u+ zGdd;g*5*`(zg!^Kk#m{0&iFDIQqf>4jG!9;-pDJXv<5!qXMsC3Dggk~kaCq%F(tp4 z`E<&qePS35@oL)n+b4n1xbP`2W3|ncE?iEdPYq_eH{y!LvxLmLZ ze2P|4taVS^hI+>o;=x*+9J#OHU_K7!jdteTY5PO>jrK%(HG}tq#|7Qi_lO_>u{B<# ztd;mCU4HexX_pF!6L`&Ik92`PfJLdO6o#~>xfRJNWjLG?B18Y3%5ONYZn&1v#dsHU z&0slU#zs$x)R6=kc=y>hG%c%NYc1i#2_&k>_Fhs09ZutEVXr_ZP?;vc7{8TfYgf7W zUMl-|r8UF-Fs0+eu(f>=YL-CP8{@tEdyJKvF1!LuZUJ2w7M4|b6!6+%TyeZVh2gQ- z1rtoOj4S22BY-BN>8>KRu{5+dLNhm#brIY<$bb-}eIBe1M0(MML~1)?BnfVJ#-UI6 za&$q+1#WlpH`*x zCIzL;ggsU4Er-s?@=}RiSev_V(!s;_rNF1uuAHgx>vVx8j?&%!@gfa-MRYLmZW9y)9IGD0@tnNl~;K7!z2#jB@)>=7D4q4#(&0n}!iuvE-?n&JO{R zcF?Nae9p78cJP?(76qbrDwG_3C8YRjK;}Au3jO&={1iF)Wsy+q1uH+QCGt`CBBPgb z=tr@8T*_R2zS|O0Wz`YGJg-@KKoe08a%He+!r~`o>b)|@dYGLiSxkwU|rxBT2>0_Tc z^i8immD(1@SzT?0wMgSDS7leR0F!?4?E({sNcXRg-QpUqZFk-rks zL3D^l?-^Ob#up@CgMz?h#o^t2O~6c zuy?Dnl&qx+5b`{L=*l!<7eR_0%;+P_kmI7!{dD=)4BsMqW_TR9I#a3LkbC0sFj$6d zy%~c95n*#89_3_uWUEMlyd9?YrE@}d##u(pxGGC_Z(?c9#B?OQa6swMg*hL?YNU`( zF4WJQ+rR}cBb)jmAfH{eMCd6*(dXhDyZ~^cX-OZ|Eg#u+BdEe z6n}@A4*7sZl=Pk0a|@p$+?1J?rhslr=yQ?K(zMq)r;~V5k~$qdA+8qlcZu zE)h)e;?@=k^A7>qgrC3KJ~lv?Q&`wb2)F)nKh7LCGeF3~EQto{Z{<2K9 zs+;uQ@))_Z&9w@#O^v2ILA%{$N2x8aOD==D>P=zoRmjqainLAnN9;+8_f-j*DsE$1 z+FN#kKIyW^{O>C_~F2nviJ zsz&vE^XX#~JD*ui*H`!(!LY}yTmPPm+kXJA&?}q`&2I(DYtX9#f$sb~Ef%dR3|xr>s3m1PK#vDo8M?IK<7 zkC{nFPO*AaPiD=NdoGTDKMw)s}U$i2Y$GnNX zhTx$(YQ_n_c)EZbx0u`YMxMKgZckB%Y_G3Sw1k`#n_+Eu-7QkTEJeqV0lRztiOg8) z`uvZ&Zb#TkuK-qMu?F!L=Yxo>bZ8Aa4I!#7Zk}i|og4tDNrqUoJB=eljv2VAS9Kvn z6pCoAsK+H)&~(xz^*y5l+wc0mzag~op+9USD$+!C$4B{mA4nE4AvOg^$t(8SI<`z32d%{B4#6WYuQBn zk96s}H!71|jYiG{DN!hqJ$hx40G`QliNxXtHa#2S9Q>wLl~t+oh?sO63yahnLdP6y zP%?8E9gM1f&X2rWZspu1ri#_J`CaBMoE!}eBt6P~<+YQ^Q zxgIGDBh9{ZA!ZT?Tt#KtYAOHnp}+?e8d6SwQQlC_fS_~gVrf@!vbD?wwptOj6lx^< zy6V5M3O0)+=d(=2Qy&o^OmWId_U}55I8*hThRKus6KlGY|Gz$WtfIMam`~g_-_kvf zKz_8b2q37rJyfe{GTxM35-f9Hfi@6iu$fyyvDAckC~`M9pDJ;XL)D@QdR^Vx>n{Ih z;+I`+S{CeME6xDD#;ZI8$kT;B@NVtA?&=Hr?+tbi{Y*c+Ab!5_Jl$`o)C}i`=NAqK zE|@zLYTX2|SNw;qVCWEUkte&Iko$zc^fO>fc&klE)*(x{0+f&~k37VCE~L}DOj(`4 zkFQ04z%&(?ta-8*JwP!!;+|Ea&MfuR&(b+r`$CT}3-NdFU_7&?Fv(>pi&0dW*qY&% z5(fZ0r3oa10iMF{IK*dEo(#1^;CtemXyKcagrRHCxpOh+aVeSCHM6Q=~j-0yD&Q}^yjJ!rxsAdQ$H=i8y0J^{q6YM!@kTtm7yz;*37u0y&XL*y29h+mXy6 zvBhEF8WEGXfOsWT8dJbMR8`;>{ z5E6>_ME|27Ny16>Yqr=o2oQ{yO*6l8&kXf5wFvCm9iHcr;(zip@_55UyntGFn@TWQ! zsuwo>Nq0>CN2gctfAk1P;~@Nt@x}2eN9+1#;z4aLSyhrrs?(q_bzD6OC--!rf72v6rzHVqzT--_;bI@-xN?OAIPjn{Sf|Mdb;uaGeS3nX9uFx4I1!V5;X zV6E+=I$KNGYM<|j40pk;r~uJ@WC^$iW;uNMbDk*K3%~0A(G1$rf!vJ2*8-5r*w&3I z<_wKMNlK}$8A-Tt(l09%L7zHDAXD4)R3Mu=V%*iU3S1 zB$l%Uq_6k~(+`Wl$x4NuL75%BXgUYiR0gx<(S)@o=2oF$A!%P~#%$kkW{lsOoCxeO*!~L4JqK&}v6yr_+-6LJFE8^NQPFTrbYh#CU0!hzy z@H%DYFiLh@{0v3|eldIWHe<=F1*1Q^^}mm*gEcdF-o%qra9ji+>Qzy7?^LX{4?=c*SBwqlMFTAL~u`asz`$#r(0_(Rf_TCiC zU?I7A_;9G?9W0NN1|M#BKCq8fm;`dz5cj*x+&5rs-IZ`l=v;}7|97lNPJnUID6?pM zUw9JDClfcRZl&!G-sGQffE5lxs{n|EvqZ~=2-&k6TTOykTkucqH zq>*qQ=xQX*82s@c`~GlUeCSuw8-uroD{38L*gqU75A3nqyX>)ewvE!E47scc6DA z{XwfFcI8C)L?`y(=^=(yvlr!`l+6-xr-kZ`&q$-pSly2gw+4c<2l{8uucWJR!sFlA z)fO7;gonZm?r-g$-osS=$TV`k);tH0ew=~1#M64t;LFsHc+vk6!{;ICJ^*=ZM8(+2d>>RsrjPGe#=G$BOg8IO)t-}H zs~og zm4q}ukX4ZyHV)Jz_+}L%a@9w&$K~A#ZTF>b2cx-)Vg6bLH7l!}P_;RP0IQOC(RO$B z=CORnBnc3iT2v29F8uUOWyV(23nCb1-(aFPE}m4q;wp`qu*ztJ@jQBO$7R;2daII1 zY5?r>b^XY$&YE+!A(SyVh`jIsUd_*@9qlx?>gds44;v&zH6pJ-UD$_d6v zT>r$D&dJ^83yuXX_bF$w#wNiR7!H`W{$xI*lH)cK@0ps|;o83A{jCAjoi9}LE}2>(Qk_P_;R+Ey94 z%ZZwj;lF+!1B)8lUXUcO3n{TNA?gvb7~#7E?lMzdm%azd_#RP8oHbr9Rga&jM9|{M ziHt>lI1et1Oc^g^K~S?`EhNAu3H=~$mWDRPrsDW~A!FbxUq>1iSNvYG>lYB6juL7l zmHJpe_@@*VR$LymB_(^kU&OsMNFq1eO(3iw=BcKHu0y#UiR6 z-c$cQ+SXu7Q}m)yO##ID$J8{A;^Y4>|b6`zam3DrwH9E{O@ z-K_)SOUA}%s5X==@F)NI=n8uy-S`zZDHkNRDJ#I106p~7w87rkl;*(6_+I%~ z?l%{g2O|4jZuq2JL)vdcP@n;*s-$a3twSN&D`sOFfG!8Ft-~cjIbF`VbF2_Kh$^%g zkT=5#)&5qoi;r{wlYAZ3{_Zjl+H=o=`Cj!l%kY)00GEM|;GS?NhVe8l)hK5P`!v1- z*|yksKdyeEsoS>|u~syD+9JVc0k869Zlo&*2{g4qV|vEztRgx|o>_4Y?a^Btv8NQ) zwm-TX5v|!JC0B>ujlZoi%{^+8*cPqInmhgb#GXB#x4E{>|f>QLkJ2iwbhSYR;1t)-1UJiNc~a$w|>Ow-(#^Q2XM z-x!5t<_?_8jJ?N3Ok1@}*_~^RIJ&C-B-pt}gLVX&BweB?T|!iWCMo5?-tV-w zQ4H?1V!0JdSlb^$A-uV)efKl};xmn(YuQipezmi$`)rceHKsrsf??e3DO^j2PQ_o` z=t))Fa}jTcr}hGAYu;t_IraQBSLVz;WZEGz=v_^tn6*3)o?GY`b=uSJ&7Xa*9e}r7TRiz zdt``tDD^*{k}p<%-`wdrpf=CZsv#tC*C^p(1=^pAd-OOXn}<3zeRU_>YlQ(@a-mq# z{SOHKb0dVrGT3|#4h~$sI&D1gO@4<+uj)wC3_*t1RE~bG5NLw@5B`}pnhdCIeR1GL zbx()G%Rl;$_$D8I{6<){up-=!r*m>Dc@O@eLO@2eNfe(!Q$lu7ccZ2Crt2#(v3HEwcv7e=Il{96`6=Urs*^$7i)ISNU_ zL?neqTN#Dzbcz71y0;phFN>VSO^xUafJ%#XMXcaU zebod2fY^>K%IPa=8xb0*-(u`r;Rz{+qb|^Sw>_3bS3&)+T04>V6L{nxUXX{^R%;>g zOiKjgAbSMKOGUO=9M!k(wOrW4v0=0tW+=lX#Yn|i_N1jF8<|$?0}EfWr*4c}ko_dE z4DMcO%EKwiV#$P}wPv~W1Or-__lj?K$B~Qy(N3ZY?z;m8ufE}kZl1c?q9}^u z2>TeGKhab6G%NCa*193-X)d&Kz%D3Dxyj?ai_-5^_>D5lv1Jnb4e}BKj>byt$MP+V zTSd-e9ekNz9H$=%3o-&W`Hh05xPAPyo&~zc zh>&5;P!nPIiC)4AfbQvD@Zb0x*OV(rbGzQ|{Lq7@as7Op>!i~!FcIw=D()1FkrgNU zZ_13{qQvMvQ8*QAM00Y3Gd8lkupAY92g^jP4jloaBO41>VCqE`_s)xppnS$z+u4|W zLt{~#s6G($PX!M-UG`6osCtMOM0v`p8hTO%M7^Am?2Z@iFJQZnm}Fs#ur7EJPX}Qt zcyy2{ADjo8vo)J_3n5K621Dd(dcxqo)Rn(qj|U z3^I{VA4fkoWlP=~9Q;?xmNaNnEQiNSXww_Kz^u_dAta8vjINeVb8QK(fsyy_qLl@A zg9jpxF(!s@V%rpc4P+EuW0_5ir352YNkrpN4hK*Y_^xun`8`Abz$c=txh?BW->T7+ z4k0H|ZjMRmbXzmLw_a;@l7Rjd!FTHx15%2cSOtpR*N0c&4M!3P!pnH1uyhywLqy^P`z{)$o`>P`;2zH+MgIF;c z+EGEVco1i~jyZoY=tB9k%AXhU8BK!KBg3>EHTTQ*hgUdp*&q)@QF~8t`Rh%clJ$j) zlr*V8Qc7SXsVDq80nZX|)OO*`5qBI z1@r+PZ}xsJha5&B%5~I4N=;6dMwH~l4*s%L5v`J;e*V43>a$IH#GZoY9_IJMi@dgi zq-rDCbEDe#*+rnDX;V2$)tfoE=@Z@=nGH|B39b937Mbqbei0m3uA}Y0QJJK=x8)*Z zR?9qRZ+hM;(5cF&j71JyG_#!L017D>-{3<3-~<1jF056@Tw^Q5475CV_o6C3bPC^T zs#!IC4}wVM4G)fO54t9agSeLl(2h(>g&~_m5?jU8_NZFN}}@*ycuc{ z>7O`sY+mMAq9jgAIbcbe{DI^?WCvk+fta&JJ!H&D?aLOE?e3=B-MYbYkV+BJOT$Z_ zg0*ftPO-ATJ^MNfhM~I?Dy^L(I}^Cy_p03<^n<%lza&e^n+(TB1iCULd)aG+tl>Pn zYQ!oAf`jw~sS4Co-=+uyCeW#jzFTc(67ARgHe`=R!L!9P`B({sfm^vBO-e!}e;4?p z8t5QBR3Yn+Q-jhVZyiKOvQfoq_a>w;@pmtFlW0d@WwFfoo$JV0ilQJ9K=!8gDhjs{ z-K2e4?;(+gPH^(Cv)f&hUhU!LcWZ>rKGNqcnw>x9TQR6L0enVI_$mEVPRL79A$jV7 zUF;&%MFY>Kykf(ohz#KjC_=`Ub5kO+H;{PxgO7q5Ah%CNE7PK~x##eJH^pb`D2Q<} zq5UK;i;RJV=g@QMM)Um!IRB6+TjIlMb?haJZ0Co@ErYUyOA8uM&n7xvnVjDupI`viOYqTg|o;r?Nz@79<`$fVCNlPKe!dJ(qkepKX$L5F&FEYT9W4Bg=;(+l zL@5h$ajG(>%*nOibvO~I{_;F?K9hMXqRK;X;)0Phkio%;S=5@|@6Yxid#JOHdG=^2 zLG8xLzK=gidVygJI;qsEIr#hckItzbqboM=J!;fKjX7{#9x8DlI6HkMO$sO5wCG-q zl|MD_4yPTZ9^7fF$dJ_@(JKJ@)f<#hq3~(o%U`rB3z{MfQ?B~o`4ly?#~@vafuqW2 zIgr{o>A(?qM<|U6$ez><>7j*d!65g7P#q#hrXG<;kE}c2VDbIj;W*SXT%ehujZ&m$H zVKUd!he7ZqP~CX#Lmk%sFmt}KDq?ryID3DPP}s4I(^*ss?HLn= zNS3ojgUJ=DAFYHti`)c$&P%snN;SblfF{ zUUhg7{XN0WcJg$-bG`i}w{9nj;#~PrB&fYze8Hcr?S$uoI*N~L?ZW$E_SuxkDoI6r zVr2250!@b|n};+<$eO;H{Zua^nBY4y?6Y6%BnpE{JLw`u$Plwt#t*)XseobY^ETv6 zmjm!wU?_dtcp<5{e^E)Hb79l~p`*tYWd3~Fcvf78ZsuW1RzWOqCMu;S*Cep$5HYkh z5KtYPxWZb=r0f zf`P3AB6FsVItxQi2%F*Q;=;2+ zUM?Hz?!ioC1H2YB3oO+TTvYkc-^uX%P$BLe_E{oH+1~)goV<7ftH=R=&F-j-C=2xL zNUw=bUom-eQ4C%&1}Dv$K!n>8eCo?zdpsjMKD7T&03C#Dk}{+=x7H+AREIaEmIRx} zlq0y{`K4i((Pq2=4o~hg-pP+|4A;9`d+H!+D83=6aQBA1^%cV@Ujn@HO+9%Lel(q) z1cxT96Rgc7rNfj3UVH@#=Ncs09{M^&xpw-+mbT6Z6l(LcSL>Ye)amJ%H`b{dbcX_yrIxE?E_XNqZei^$!%hT?k zUHO_7Uh|nT6(bc(2pQm=9;($8MN^OBF%fm$cTl^DJ;^QD_YF_qVZE0Jq7$N}0OLZv9*zRU1wF=qg^=}L4 z^*^DKOJmWd%*ToY(;%*iN;Tg2K$)nh)27Tt_N`2!Kg^3Lu0mUXMgy+%1vdUXS}0Sl zml+Df_F`2qXf#sfU6W*R1XrMk{w7{!K@mzS=FXj^vZMjDZv?hZkb1C(-*ALK`{-q4 zySqSse(NjXl=xO(a^J9-Z+INC(jQjsvAYG3rCiyU_U7fVb?1^;#Uw^c#KvOqY(9!| zSmA(u0_dWs6VTN~e52hIwrQ*(G2YWNP2G2iH7d7(dnV23G+YM~9x&FWL-%6;EVl5a zv*G?cTfEVbgXp&ODL-07DyPbvr+3S9fmxdFMw|T+5&2E$|E_}0r zzJ#Hpk}T^Wng?(Av?~~A6S?J`Q&hS8Z)biOV&%JQn(JhoQFHAs^|3v?^Ehm%u-arN zI5&OC_DksKzp7hKYi7$n4ykTXovr)iVqGw3A`-^CrBA9`oH0bZ(g1l#| z9#7h)5%{pU{L*y3cmlf`oMP2>UDf#R=or!OdAS}PeMAYc_~(TGJ=bk7+&O8!Lr5sz z{r7eolZ6270QG&HsJ64)Fnr9HIn*rS(r*|hUucsV= z6ds&b8W+YA)y3wypgzMpl;#gB8UJ{lE1MYlEHOtNa>Y7rN)HxG#aX}GEcOTDD_rZd5Pd}RoLIOR5_KIE zNH(neu1oMDbQUUS|L~GroT02P=%4l$6JRWA`4PsA*hl*Zo9Ie2YM@B@Zw$x;BD71i zUi1esY{0t)2PS|^*%~()|2U$VMZ)S+|419-OUnJ!=PTwOBhFHuW73UuNT~nLZlvu^ zq?--o-~4d-w8yye08e_i-c;)HA@+3V9vwBUCx2U^748102PA+h8RCLO1y-#A%NbKu zQs~_aqSht3mMM%fyK%`a(5t8mO5zgqk4*c$WD?`#8LkOT>d7FKaXVB0z%mB$4BSd@ zM;?*0@GZ4XlfyV&sRjmXlDU*qPUS`=g|(vS@?{liFI zS@Od$J}M3G4(9MmmbuTKuF=S2jgkBNq6S^qu?zN7y<_t_vU-?19<>o-wO0UXjWns> z6b+F*H1RvHm~YR%t{2!%qkG;r|7j^8W~abh)uv%ppKQ#j{()MPEJ{C#z}H2bQx$W% zk-gS#M4f-2tVezTM(}J+E6K{-C1|U@=2U^4&*NbDtBHJtrnf_A%aZy1_0{=$jM=aK zxUW{qq)vm}qPq)IEP{K~8Pk@)Inq5}^CCSqRqKjf&xc$G^A8hz&z}pvyuijw>`uiw zVigvx85D^T5#2|1@v{@;|19BT5i21FcsFSpw<6j2V{i@H92^y^gG4d0S1kKZq8a|? z%?ZD!mwf(fqGrv_8X{#Ws*29u@wkYJ1QQ;_G)5J>T=^{UQpLWm@H^=t%q=>cOIAByqR&f=+!T~el{+9yYhoWxahd4_ zuJxJ*(%LhN%GO7iS3Ej(uC{!32&5veMB57?ZtSh<+A6OC?MPA4?pT8=6|C5b_Vhk@ zpVX)(1!owKN|xKK^>U#l8GT20>dSCRVF!#k)T>N=0($Vh>q-f4B;Xc}&x#Z?!1m9B z?jT&B?YUeSE0iyFeHYL4`1F?AK}VB=4{0{t4L;_fak*+@GZOxJX01Bm39u(`kRjo9 z!;M}21A9aI$n0CXDw8W8yor=qCR1#&J-XQh;zgfdx3_cDg{vgIq^jps!Ans$Tfv9O z?Je1;3>|Uy5}P~S6@u>gDd82StzCQX?v$3AC=u3HjD5*e#Iad}t#g3r)8wrt0?YP? z`E!XkbYUSAp|LJX(8hL9wqghR()oqykKKOoZpy`rogJ5P7)E>M_XY6)OLmWgPl(a3 zb;9Ai#R3vTQe&BL3Gl#B^k|I*1~#6?k*K_?CTH#i(-^XXsk{$oD0z{h;4*WK5tNqn z7tCe6G_p=5#TuYZ;lw^2jp{%%6BJ&1Ao;GzL^F|K3cY~@8c=%pbfKw#7DTJ4;P2jo9E=s2!C!NNe zy{74h{3pqS!peWr{}LpJF-hO|69@Kemd*XZrdMvrf-pFMq^4on=E;Zfn-+9Vm>)S$ z3@#98n0nHl)tN8 zUCOKn7u-}Eo7qBLds~FZ`)G11;`d~DVP2`B;z_Z=sU5Hf~Zrw z!AuZp9|aZ}6;RB@o6VnBL5Am;Ic$jFC(?z^xxCzR7(@I&Q+f;vhg!_9Jggj0cuA>{ zDXuh0X=BDYAt;8&Z$-p-VEun;k!<&=Mh^N46FkJ4;Q2{u+;H3}1fjIFUQ_I5dEtSI zSd+d=jsx94*p9ZpqyE8VIM#);sG&V08aOsF6I+FrHw?`jCep1AYP-_z(R@*vTA*F3 z7GN(pPT5X^X-NsYIwXk8M}xl-3=3cs+*3CG=MhobelJLYT59t!*gMzLe^5vty<~R# z9juG;oRxYzsYN#fSvYTy{y`1L@O+779yG>wJ%bQgj9k78#d|&BcGUge_}+^hVCEsf zq0RpK{NMaVW$hUFKLcQ1vJn0BXV{{;hP+mE3<#L$?mAm3BtIL;Lq4lpi8;D5-ld;>f!`sjvKm4i1B_v*MtqUT^4g58J7(M;rt#AOuY80>BaAcan1_Ma zYS`5eC%oQI8+bD2VPAHQD^}u~3w;Xt@=jm~*JI^^F}qy)XQcJq|Im*AUpt_fC-dg; z_(%UogiNK{C9Og9Jb^5b+T6&0HY5w+bnpe5*6Dxb(8%HQV(LeamDt#=3yWf4a;L*( zlUb?%H%YPt7d^Z0Cgk0U;#s%3p&zv6Un@&eibL>^J?bj{?w8?QmhJ7q9G8P7)?PPV zopV8@P1V*EFk%L- zM$DEo{uIqto5+Qr6s6AIA}AM#@42V9O?U4d#*dhK__5_GVhKX6TmQtUO%6qd5{S49 zc^!&f{PAVPejcFK(G%yzMHd_yRBc1(e<KoliItL`|DU9L9#*fgmI=&9E$N685R}FXle4ctM1p*zoF)hfyLOo}@d=9jCDgvCD`!T+>V9l2 zo18vWHk}+)jc|`qK$ret1X$G>CM;DDFb`_h&uU=T8Whu#Om;IfH3@OL3AU2YWVsad zc*a_ijgUOlic#eXohPJ;la^jjyV`=%w4r(t(n#Lz%%3=Vvry?rZ!08^1cvn@CXqf$ znJ!@-HPx+wnfhKu)bwLbIxW~giO!*AA880iGMDjv2TrY_NiLECli7c}CoIz~&L{CcbNR3~zkcA5@Rebd=Qvon#GijsBrDRCN_VTSNHYR>L zu|4irgFp=@gl3B}PV=f@9mvUz3}iBCZB%PM>D|{d2w*_yZ*CP5e$S_tm!~6 zxTBB>E2r?B^2#S4(hA{)DHa|O`XpSS-=abn%1c){7&U!aYlwb$;xv7v#gxUkR1fxqId~Ab~eQK=uc;4@m^gxdE$STUUX2b)f59 z&3hx9O|3`wq^1#5l!G_K-`xnHe{93#$saB06RBQ`wT4DZ9dX!zGn5Bk4@K#IgO)0; z;9d@popDj0gl_#s>CI+T3XWe$75b_Y&D&5TGo78Thjkf)lj?0JC@?i`R9HMe3hd(~ zMOY6> zwlgcJlvNK35^b~)V~ebw3bFxIoG7t0Q88l-e+UIX$?>4ccM^*to&6Zu&#i$z{O}#) zZ%9u1i43;@3}i1REbn5h2*4F17;y8rki_rVScv%G&C^szOJ&3lPZRj6J7PvUf~hDt zsaxXDhE#+A1mcWnu`aU5RWC~7cfP~aU9szT#2?=>9Ax2d!;;V0)VkJ#RbyE*?gWMiG+kpA=0FdeNU zfG5h!W>ks|jURRGLoy)vETWtZ|8$smf|XO_1wk>*S2!j56aPHC8lWqik76RRTIk)G zZ9%n4z7^Tu%XIkupr`vqV^yA%jCXXzf+bXOm*}i@gT1N;PDX&!=G|GvF`hQ>_S!|w zQG;Yxes4no;(_Zv*e9=r66<_$v>U=qnezD~^p$H6$SgtJ)MfXYg_yRhP)!pnr#MGs zOcM1#Ucdpb7S6jl@J>rktu}j*VVlo2`&Fj+sli{EzGYTVAl2U6?e^%-GD4U#`pL_c zOi1oRbzR%S`geQ>bCXf-1~WU>t|pp5e?T3y14DD?tV4*i z01lmRxTgHu7Czl8HYCRf2(ju1kUWPjQ{TgTPwQap7Vc;J4KBym{dF@s zye(7-C$EOlztn{7ave;~&!YYP)x^D|D))F?-CYEFV*%R=XZ1Yqe-z6MC&WYFzoV_a zGU`9te;Xr5c_Y`qjM6RwiV5egn?aGN-wAOO4}Gz4WN@#SN;*uh-a)%1+3WRvea9c- zEmPL&wE_WK$2p#P{fJ*iKYp2nD*a_@)nii*-JR!T1QitLSpM%!>x{V20Jzv}U&X$D z1GGm;#wP*v?|~3Y7HU>-36usPl~=*6Q5+Zg^qJyV=06En)Nj-?uZ0OL6K%XWyDL=N zXeZk_A%ZVP3w8PqEfit`y^B-?G1hamcA?pbc+Pi?Lb3Y=y)%#i+O3o~Tly$%EO}Zi zBD&itxWDjzsk4DLY`F806UMNFrj1!sYtbfjp<^m!-MUSrW@kcP!Y^F8uQo6EZzkY5 zCFqzAjW6rU;5yjzre9*O>{R4*R|#Ko=y59CWC5V+lP)JbRJ~Mvp-4pzM$_h+Luz!| zcxo&e_i>R@N580ltZNzH-fLnnzT168q4TweF}X*Q{)VQ{uIOsBpt~b7MNh$b$EP9s zTjRIOn>QWz7vLA}jbf3?E5ag?E9qZ0fIk$rXqj%g&sr3A>54IyTBv99g7c30AV>jDa9MGJ$XD4=-AkQc_CvD?h{HKf#>int(aU zP6Njdnl~m%Fk5I__bSy*Z_YAKc3>+j%}j(MVa|RPF_vir8*HE-jb>`EI~bR!OvdXE zw}>TwGg8bNgO$2NW+ zQ@mrFBxX5gn&f6+S;9BPru9fM+;&OVJo5vao*$-53Vw1^5OlR+Pz^sXJ^qpmV0o8Y zo8OH^fOV|fSrCeR=VHS;viMr$PE#y;Bn6^;_1E=i%ER{IhSqW^??Q`jI!$6mG1YsN zb~|IFaD-_R%~z~D^2LtezA-Xl)1P&x<(Vs4D2DNcT)QTLlN|7;%=vQAae~mwDp|Bu|B7wp-meOm~2f z4k8pooLtimVRUAmG$qXonu6BtIho9957Q|tV2w+$FE}8OsCbe(UY5`Y)S-JJ478}J zfOvHetRtSg+SUmlJSCZCCn+Wx`!}1%%kxX};|?A4>W9yYbn~N+kzLD;{c@tKb*Fy{ z$5o`X8%(5e*Zs+IGo9im-@<>{e#h;4ev$gH>fl@KGBX9VBF83_&S>Ei!!nwtvdH{a zb!ou*k`t*N?7d2{83S@E|>gUn8_Cx1uNNYakJh0v4(D}Ygq++h9DDj2wXB5Jr zX6I$+``;;Y>tb!Q)r!NZBov6yIHx2w>9HD?v|o!TZs$+$y@Hm%F)rDv{(0F30Hl=c zU(_08xqK~JE_LHVR@BT=6V0w^OCQ5>u#5j7nw*n(C1BO#vn-{yjaL5BS@@eGx^94E zd>M3Tg!@NF@@9l9;8KkN_db%tqPm~?Prs21{TW7-E{3hk1!sPlzkWGBBBnK-mC&I+ zde8u%36r)YvDT01`|*4zUIeI^z%^5UMHL}@!jXl)SVA7P8oG(?Y0JGfMqST08LYnzJviKoh^LI9ULy+++wiN z-+~rLTmG-C+%TJP)f)73<5n{7eO-~{Yevlb(&FGn0K}vsLiGB9b0Wwl#fxhhbyfvNrj=dxdENpgFJ0aVx zBS)Aq=N7v~;vOae+srx*)Q(u=cxMK;^ylfD_e9-_kAztqR-xU{C(aX*t*1Y0J_}{D z`EF>{{g1KB%23_BWTH;WR>Y4pbm1Av&XTm;4B&~VtW~OIrs82U5gd|6ac7aomSKY# zc@AES{EN(r9wg<4UDoBn9pv84T$!4TNe-YmZVZ)9hy{?#J=39eI(o)HuRr+=G^C#w z*}8>~YWel)@Np-+r*5YV5UCyLO^@I+n_s%&pbx*&=@5(WLZLT_v&s^{w#-jnnk*WL zm_U^u5?+I4<~OPBwrZ&<(fA+u#HPDh*zS${y`|XJ=*$=plxy^Bc$~;=-z(2;WsF_+ z_FC$d858^o85|YikV=i z7puf4I&6#3FXPGmj%WDE&qZDN&!;1&KZjlOwuUX7xn4_&?B>LIQS`sXaMZ|wyn!Cs zV%(@Sub+(tFnK=LwL>z;_18WO9PQ7YRvR5 zk3-Y@!xsLTy6+YKPA%y3Sum5{;sDRF8?BX33CH;zvnQE{!u0BhA83yuOQM^as7c77 z?)JD)KiwOMKUr{b1}qBeB@}drG>cW7)#L|e%f1L+--P-uDmL39{UFz3*p{L=(n1Lo zLzAIYY@R~>sVfnX2o{Odk4srr>R-U~&v~;Oqh?F$v^01j5IbhJu=Jd9vgqRfBXnJ^ z)f7eZ9GtG13&YR zfYxa5MkW!(s^VJ>agr~q?^U8SivUcK^bnb~6R{A1V_8yay*{k;DIt!qK}9Evp#1#b z)kK`2oY@y>=S7r2zRwSIUTnS=hB?Y}<^cs`Eot|c^CR0Z3?ud;di6XPm*fz0ncbZ- z9LiTnJxnMN@79QPn-DCI(tP3-_d;gic*n?rT#y8*| z>m>t)Wu#ilt+%8Ts`|L%K6-{26r#+?(W6i-Q6{~yKC`Mptu!xC~l!Za4TA%Kyi0Tv7UVUoPF<; zzbkoGmdyFu7{lUyNjAL+&Iz-x9PFWgKv&$oeNKy`%1Fjr73?=1DJA*FnvAgX7syYF zmhL+r7fo&bQQu3XJWujRF0r0)NrMuFM`uEdxZ7q|dMddr`q$ylh!{nBmP~|ihdU|a zWRS%VR*LdKz<$7Q0#+;TCYj`q(^j)Hh^{DxrV&l+c$U=wb(qXFE8cm)WfhSe`XB5X z>kC&ZDW%6h*e9Vvia}fmW>_%gtsV8Juq(=G^o2H+>zsO$l-vsbwTh$i;o^#PP zO|U)`a^+l?EX48X<_Gq9Vmy8-G}cWm0D@zqlBPpV&Ah7r`D3_cbopjQt@DZU+5p$%GSD)+yV8A2bkex`uQZC^VWk#-an$U24F1 z#X)r!Vw<-V7-sD{bx{z(q1DcYmVej(Jx&vAaRF86qa>_Nz0*Y>H}67r5ZNhagc#vx zivR&)nJw@3&Y&|B$i$!L`o_(Q%laRTI9C~69TlD=~%umMr~lYaqk^wzGq#zZn=2sqtg6}BQGF>bvOhY*%#!7v^nf~6JLAo zz(ga#OTb>Hf#KNoC>&i(P~vVqcMLEFtgiF_V@64CHsI9#C5a(4u}W%9EH-`rB&XA)oSRY&V2 z?SzfU5CkxhXw33OlwroDY*jKw7;Cr--77`++BmO1c&A*0Tq19_26b3jtkrJA8%N=s z1|4=0VOJ@Ww|kK*-Q4U0lQAu`4BfzAMvSvgFA-G{zd^iSntv|=b4#)o z6UUz!PfV2d@rjNqZ-ag^@3|#ymV*idQ#P=wu--u!#-_mCFQP~Lmi5vFQ8%BM%&ozw zeg7KLJQ3TEZLWtAv6MyCcM_>6YKDr~Y%KIk2~_y-2PP3Ac^mxM@9F~TAlKsP2*e*m zT=RIi3H`Wl)S5%pxWx2aMExmpiJ!U$8;LzX6HonoFv3Y0ov0*%dFDdIDHr-$x~W;| zR~aX#u0PQ74JA@b?$M~EOp#rvn$Q0W%7Q3y+J0DGYvcj5QUXHW2lDr5M}v}y5|=V& zDN$&*n$ye(U;Y^A$a>LSHL9Fyc#UtnD4t|Qx^Q{eF!73=6~WR@jb2>Mzj7V1HIB9E zc540{IsRZ01U04!mVG6W>8V;2}5TP2wflfQ2C0+N23 zmS>+fKx=VLDbH#%KH2%ij%$~UdVJMW)?A8hK{rfYNM!T?4m0t-^_zWRV;m~oe_CJy zBg-#`+!jq8N#XO#2Yt>jdv~(d7)lpsH^+;mC^18Si-_Ise@U3&rnl6iW6-b9XtDQ$3AYtsw;N8yqc4j zb`p;lpGzil1J}yA6Z1rO|L`gOI(T!V?zgQ^wwN$!5JPn`gD;$;^xUUCH?cKqxnla-ws>_p$LC`vRIh_#|20FuI#U zwmpKxVC%%O{J0YdHypV59*$18UgMnh1)gr9}frBonn@dET&G9b=EEXH{ZasZFOKwBA#z(1dx7|4Q*v(EvQ}-FZO(W^^c{ z)MXi&l04if+VxD8@yFBi;(m#GlA%sb z`OT}hP<%v`p;!dICF`uHjrwDm%*2xbJsWr8=)?5oBQI{UWQT)`KnW3Ibl+Pj>8ukfY9l`r|DI!jT( zfQ5|&o@ePIs_w{A$7JJ_twVbjg~hp6D4ufTf5#D;-MM84o=4b>t3E`M>OLjbsdj%( znWpyz%wTRr8_r#O!3^1SYQqH!8$9 zUrWROqgJ=1{ToC)qdZd98KK;96e5*tTb|$C zKZ#-4oxg5ZbgxJ9Jy5iKnQjTgB6cOpp)xQ2JQ}qfokkpj*2VvW9q#SbL*O&UOvR`E z7y@C9$TplKfJ0SI@rO+(kItPUxW5^s{PYFwir)_gHuQwp`sbO7t|ubvF;KqjhpjL= ztBDGcx(3OlWdkS?!q5WdN3L9qfFhVr-bdPUty0n6bm1cb_^5D-t^b<^usPGbB#jS_ z=tZ;eZAk1*lilr^_#W8ygSKh!XnHNCYg4oal&!fpcj(o08ilDw*(H?(q}M;RaSi4^ zdHN0xf!$h3vw0OVzaNv^*g|va@29RgZTWr}!p3sZ5N^aZ`=JkgxwK(4$c}Q$;#CAp z4&679kh+fyDW5RE&GhO9g~W8qBB2l975iU;AcJqA=R%sM8nC+I2tsnZwXVR6I)(C0 zP9miaD@IBL@zk5q`X4VvP2As@15a!~@o5ih2S=F#kH^tO;kpxs4+exA-n>C`YR`Ja zCeJTM_aRp@Rf}1ICrh7i@Q0kFUMJguu1BUhPEu{?RB6c zP;Y`76h0@B6c+>BLXifxxUN7ADaH|96h%w|0~wOcsG=F`Tl=Iiro>_EHG1jCb{@)z+HCx+Nk105ZU-`)ep&!bq+DcPI9^!GYF0YQh)1G+zo-b#Oa9w7p zniXU^sw5B6qUeHy+^+CDzC(w(^LGB(Em^Jh{Nn|P_ZQC=PjOqk zM%DgxH$gx)NDs*i^51XQu=+V`WkRs8DQAcP?;A>LE+*rL!9MNpKw~FiLKcsVM6^hQ zJyMOU95O{m;qA?!+&7=pq##Mxt%{%J}-^>TQe!)P)J_=P_&&L4SL`xy{!l9G@@VyG~Jf=0)&)jmeK? z|5}=e1y|feL@D$Wd*rD6KRLpIkdXBj8nuEEqPR(i6{Kq9WZ%obTc&`r-YTVgz=3G< zbC1foLfcI@!n_PP79}~9V(Sqjo^3O#OK*4f7c3IFYbX>iHX;(lCO_sasDC3}u#)d3 zzQ8R+EL?CD#OgVh^x3l*U~?lE*m^j(62IfvbjlVdn%mtg-Dkath3cN< z&&+(mi(DoM@I~z^G60>@HmI%ErSO<>my6UbnBo5}oxU~P%Yred4&VkS25jrgovUC+ zqhkgA9(?;~SWbu~evW^Sc$~G6bS!s2D(Oyel2X>`a(_r4G>qKamYALrt%;K!P<#-(_U`c$SP6~myxs{yI!&&xdnIGiX8v${f-z`gO-ASFT?R%UX(ng7~V#CgMD8| zk|u>W;WaB+f@gatR1r0D4=C&|u%|s@G;#UHDCgDzN|XMk7l|pWz_%WKjLjy;rsg`x zD@D3~6I_mg#FxCGLK82JxeLl20^kb^S<*>n%El+V-ObHhi|b)rCmjs`@NXvmbg%~7$9$rik8yNol+A&-mf$w51_u_dngay1yA;Fb1BZ9 zBrj42(i9_5% zR+|q?JQ=<(TTGy4i|!y|x717t1CEl^a7{98LLNvJJ$H}47PlQ|PybVm^ejwKN9S(Bv??4d z1tstydaao^5lfkC|JGC5qQ?+&ke)sAgXALGZ2J&fJ`@{-G&Nh@ zG7R_%`4+7pG{S^oB`}B^0sn++Jm#Ktu%4anT%h*N?aWBBf4U+SRix?+IF9TROw z%!2#G-1>{B5umPCQfB;tatkUChtkbS$bim}F$?cY))7HxAd0Z{g&}tr6JR*cvarCt zV+yee9jwR03cuf8#;f|B-hX29AqW`VMfZb*ch(+VC@cRaqC^2q*lA|%Pd3{v05#zn za`dvjF>itSu$2}=h9<<6T&|nt$-No_vGG{;i?@0r_h4*@L_!8EcA=aTjm*O?k8TJddLY#p_Bxu`&+~ zmmrVT2$V^Chg}=D4I_*t0UtOaJi}#Tdy*vY}FwuYd)n} z#mX^MjtPCxLl~}kyBdw`D2%d8i1$c;_xSjCK$nqT)?Inl${tgizZgvy##)`?lt?M6 z?1dXX*G>_K*?P#aWk+%ed1i&ny-iUKg^V5RC-)Ev3fZ~1&O&aZ6h1eT#;qpzl@8j! zU}hLt(z9-}bR(@CP4)Li;l;2;p?F^A8L2Yin3}G`A5}H&H|{W^-CyUw43zKkjfMp4uTV99a>?9HYobNoBiy;~Eauk>rbqWnGS(kk}}-w%M+TVmv3(tHpcN zxZ%0@YOz^|QG4-}DydY)|M${l2IhOk{d?_*M^qdJ+%SVPYI0dn6nEfLE5&rVKt%);e4e6wDSB}yc$mm6yU?PKu`3tPmDqn zI{7t|e?|hi6%@WK&^;;dG51Rp1&~j&JO`Isll<%Xa`^m$Uu=w$XSa70imLl4GHh#y zQ#j;Wd3O_d3RiZyhA&>=^WA&@EUeDt zW9UVhs@ZQ=Srr*Kh;>cuON)p3%MAZ!fJVblGIgU3Usf+W;>VVOkjGjk6$XkkHDuc> z{2W?#Sh0824tm<}Fr4ve8aovk^#o zEZ~5Ho&>0-MicD5Bz*ts$XgB<|EFVWD0wDIPIeOUf`_f^V&M}`!uMVo-nWY<&$t(z ze9SlPB|QjCdG3=S3Z~GcAx$Of#DEMs&gPt&ts+=FI`mdH;U%h@Qi1+i8NbMN@)u!p z)uAoB8PwA~R;ne5%tsKyk5E+j&L==OUMZEBeptmU4D&86;+4)-Mhnj)#hBqs0D;+c zN}(S(Ro`=I30oUl0uE=^M1+Y%^ibpI!wOR$54)ZUQfYz-*|djOzq1^ouqY&=|2ezC z7ri-#>U%_y`m||YT@YOo=0&$(5Md{niOr@-ykx)KJ1HOMf88GTR^h$k>M&(F#~p8Y zll;to6X=wwn}6=i;K-wF;?U>?mQ8ff1XhX~=_|=2Z-LiQO}@fzs`ZoSIPj=XmwmH^ z%Y9)0wmt`N%DP2r35WE54!IY$QKEAm3LRQ@Og2e7=}2-aOS{vf(z`48}Np92?SRAP zXvLYS^c-%bfR@>=xCy&`d)cJwKkE)osoYM*EalGP|LTx~=$-A&|JhGux7$WTHrow> zMBA5d#+W;x>x?g|<#5GSofS5(i(uejjFT#?&lFs+#=C$=9~Suc(Fg%;sqURI%Bw#?!)n#`brA~t>T=W-|g-y>ftpOOzLAD*KM zkTGdGQ<`1dGVyO%eJ;b7M9I;S=47d4bGab)>+d6%mZI{r<&z-=4D+PPLxAXCOmMuB z#Z7}oRXTe#BeC|Ts0Hxi6iS;^dxw@Gz$xdKiJ_H0AqzbhlOMA^J{=U;WZac`77ZaJ z4?P!s*d!h)M1_{~ZvXab5fi)d7VndpiKfp+?ABP=fu~`mEx?`*^@V8c5gEf2?MVXV zCFU~Y^XD%m*L~tA|F)UJxqvS~X%A0#4r8dAbymesQwarj9;qP>du-rG;nxpcgf}v< zPsX!i2jg$vD8nvm!%z7jqXd&k3A5!N286rphdHN~E8qPj;UbLohU!^~++Svqr}K~= zXX79K5PlLcYwGBmz{54(kxR&tBwy)aBVS?d8pCZCA@a}kzRFg)Xz6DCyRZ!XZ#_K$ zHp#E8#5sGucV@)JO?Dxkl_g+lsH3MMFv%E+0it|-x+_l2^0XH}gQg5avTuw+wkNOL z%xuCxuG)S4Y#g5XPRaYOGb-dsZSNSy^vmiAEvTcR1#9L$6iT%$B7IF(*M1?1LIP`3 z1W(i!Af(Y%t>Xv9-Afb&XFTkVe(moJp~K0)p-1%|^{}1kShZnh6 zY{ij(%mH1AZ$Br*D;Y2g17aV=wAE^ntSot7i5ZPzMiF?>|2%!5uCJ{_aBr0C@_5F@Ldb8!*f25VgR1((Tsvr%?4;n&B8k%8nD|FI_ zbk7GjttP6eg=p`RgO1u*D05lI4RO%PM}-j`sw^M8BY25665hTI{btsDqZs=ACBSh5 zs+~h0tN)D(W_7LYSPzj#9D-A(X{{Y_BE)l)JC^i^+;)C%tgM-Nn^oHAjruY|1BGYT zRLe(P?@GII3**~!@xZNW+pA6F0>%BGv{|Z_i>u3eQ^FDnNk8K*R^e1UiI$%1Ha~Uo zMvF9=+4xf?@=P0qLJ8ALo+GCeA^*o#+$ozZL6SbHNT?4s>A+1PE1I&9hNR|C4>2R9 z2(bWMSHjQJKm4KUqZYMv<$^(-&2azl`dK)k$-vr>%eHJ4HNxBy1}NQ=YK=yc z`OQ4SGKYu%`?TP{Pk%mWc6TBlX0)u1G}AM&HIwbB;WohqMMGXTAxWW7d1m16Jrrvq zfuJz+#5Bi_2Y>a8q>6sIFD%IAl|PmcZI&0SHV_qy!vwrUO7s~2qV6T82MWbwV!%32 zv3oRqvM0?wm$5(woyz>rdnO{>R_eBeT#yW>b;-RTT_Q|GIYDcuvPx=5GYAg57+ZIN zc`2+eXaSl4?jFlNzV={|{&UPQmwRqy2*RQ-IadV!_T%^UX=6*k`#?_cr9_HVXI`3i z4MlsWlo$(Nl36?AGXk{1TV@JOe7=9p{TkEu5Yd_!ihB`z{_`nCA#IB~I5>h3?kR80 zErZiMI9H5oaqbs%HEPMB4~(s_XF~x)7tT*(4 zW*13do(^)_{DZ!U(M;~{IFJm4ftvA9o}$q;wfz(0EQk2`Ut*s18&FuyLrQsV0<;RO zU$Tn)2AJ*$qLRQC)f6q4M z-=V+^?N`_gz%ul!cG4njA6e9dy&;M-8nHEmeH5jn7e;4>4TN3a=ZkPCug+VB`7Ugp zV^QuWBdUu55=Eh-41>_jTCeUOxlfq#y3ic{iG6|D6_AYQoocr#%7Ohl zSu|0ao{${T4EHyIVRH0&FGjX9^!j8l#IGKugE_CtQM&>u=YjL2Z+)Q&TSUaOld^TV zx5)zD$d6xVzC@Xjo^K~!i(bEb61khWegN@65)lSCJ(Fm#KKL!D!fi8vOrw*}xWu`a zUvvrwRWhEeO_4=WL%5SnUvgD0hCI_jC{m#Uh{&R`++0qca{<^EB(!SG34#cBdijAN z9a2Lt%W`Rrf?XfnO=6o^^B^lw;i{50@bZLD1_Z=FlHYc_*4P6y?RKYynUI@~=BN5s@VB!4x=u zG)bV0h=}3wW$7t2FMv{R8gnCnm$OHeC>9kC2i+N*64*Y~{1cE+=$vQ}90J4^Xz%TKvO*qB^(zlb!El6f+y%3Uz8Pkvlv`rX|jMn-96$^>#r!D-%j z)c+xgt50Q4E=r$^*aaFOEoZ{Agnlrf4wCv1icnG8vY>6&pXvb6Tf7QDI*&vJ$!|n zoATz0*_)M;)dFCyY$U}=AYfMWeumW-ViTT zt|||d&iwi+!;d=OGN>QnT6fZiDfkd*H}YaR917wuVJY1KoqC2=ZI11Dm;;YZerxCm zXlYY1Y^%vredF#)gx5)xx3^iHrQ;Fl^K|ApfSo2QDgw9EehSjq);jTj9Uv13?~i+- z2K`(^iqWm|!UoPzCCSIF2B&bZUFLILqGZIEFA$JW4~cW|ReS{Ulq(f|aHKis7`FR+#@ZBte|Bb>$_1@0rN^P|UKuVyrKMj8F(0r;|x7rAy+ondDC0g`e z=z}kFG}&rm0~0CwnPF~K{*=^)Fxo6=RJaY$k6-A6#d$0BdBTdU7U3*)e)~)k@m)pR z&#Z{-lBi(nk1q@P*Gu14(H?Q>50iS4zrp2uZBIhcK(bV#)?Wyo&Y-69p0SE@_NJK9TQXJc$sOD^`n5aHJ3;^-h*!1< z6MUI9b8a31QES{E8^nYl?EL%P0~Uwz_@7MIDyeB|*N43?@WOAABZDU3i~V~oI$)f7 zB7=&6T+E@R4_e-IW*plO*RD|l$Ltp|d(@+?q$g?_kYek$uCja=!M4c+uV7{OyqVu5~t8nI$_bAf#|R7I%g`TI9M{ z1n?gl7t`$mZfv+(a!mcMeh@sVfN$h(fhisfn}99e3`*{3u+c-aTsi7o30GsC2o0Uu zk^A<*ao0Y%M~WGW3dtDhe-KIoiE%Cgpig)puqJL^&6R~YCAR{(Q>ha-|vDf+i$kLS+n>5CkcG90_RIdblL7EHo(LGNWuR# zl0GKzE8ubj@T{wQ`@7$1h7P&3H(uU*KrF6#ijvJsJ ziRIQiG9a*OXFQLlVz6D!Yn_-z9fs1Swp$J*J?!3QjnK^Fzvz#S2M@9wsNgwhXIRqs z;*l=7>xOBFzB{MHSFC&l(kubYcLYs>5FcnVzpk4@r&P_q+Vsp0za3r`#{p^Y9=VCB z1STN;GMdPr5i%q;)Fqn5<~YmK*ESU0n0 zaIsWNH2^5UdfjRf_nRYhU9aKwzClZ{00oc_FuxRIxK$^THkkmi<~(sC;n&Fy+%Y)# z_HLou_?g09-Ifm5o2lSeUYh0?d=_=Cd^H4?bs9u4{^9cU2@rb0~VBT6ZLN zE#psOo5h=6O4d&tEroGmDVLK6VoxEs55pZ@3LJx@MND!j(v2LwASdwE*`jN`>_lTz zLO7m0m?+$qon#=-D%kBt1UIp@mQi=de_oyhxeUQW zbJc~28xz8zXLgT^zaZ1yOW=H8)B2WCOZIDtmzTexRQb%C2F+d6mW>hlYMXpp)yz`O z)UBO>(LX!Advxjod+2ya-%3iUchpDxZ8!C!+$mM^UF>Ci*YHhUz{ZyN6pjIdBkXi* z%eqfThcl>HW+S`UMxW&fkXnRxuUC&(10*adFo8}n9jcYEUsesmKR}z1=0bbAwWU+Y zH6aAas9!1K^;bFE&%|E%En~7XHnT+QMd>kL|DhX73;>LBISPTnZZo|E1!4`{X=ijeFJv##t74Ga2cs~sAC!)Yy zVooG=H9KZTB56GYh*dZSOz>%mL50Gg!DGyQh-z8|NpRbEkw*XWE(Q*%x-Vx0ybd_p`7pe#(d$3d|1eAxQreY` z&YUhbDZS~?p=?G9KrGkDkV@W~j&6V}lOP)IHnher!#m4%6J-v zft|=su5}0IC&PFGAC4rAVU!b-6xC@-YG98$>rem<#dr2-V;Iq)1QhJdd>PVPM32~g zmw|28(k$KECW z?Kx|_C1!wYeSc^#FBPr84MeBvooZZ?4IwtW4Yk2 z7SoR@M42FRx*m;8U(G3NWHh1Es*eI`dQ*Kz zU}O;`$U~rLzg96!TS}B+k0QDkjq;dj^Qn7TAV6rlPO(oDtIHk!rvRNEA^TmsJraUG$gV_Nxk$CVYZ(2;ae`YasueR#*3 z;YQ;d_g>9@rcl;I8#+9|-tE8llYIhxjqfi_n-$sVZ9lzcr7&gP z03Ag?);7JAHGzBnBHAQ`vSNsT!&*d{{;@&Jh~HMfmNppNXUgGzm=x7IJzRiI2x~U( zG*kOs*!QiA5T|KKXf>pv0#P*k^n%+`13MJeHcDL0=3N>7f@ICm2uZlh;mOEt| z-%_^BI+ASROT@<{Y`aKR-FiUkM{HN)@l>dyD`jbj=}0`mRKeZ_QvS7|Z%O5_9QilLlfS#d2{ws>+QEfn5h6<6DbUW7Z^9KHm5XJZ zd+&V3+o92NJvIA>xw-7ppkn>+H)Y#!(?=7dQ`8TP2uwN%Lby*lwkdCV{exsWmJEK! z3!l@rvvd`QK{VVX?Ge%8GcS{0C0o@F{aoN{g_imO!FhkvwInGWV9o1tWQvHGcEuAD zUQE5D8ewtCYIf(kCU*!(-z`m-Xd7Rmw zN1haQQpk+;+5W^prfHg5<^rC}7s7y8$1Lo;uP~s6_2WCi=GmTvE*-TH%V*M8x5~C9 zGu-(ih0jt>F&q7gTv@Nu&e)j@=UmxMI$}`qtGG9|w3YtJ>ZlrWFlNTGx61Xt<^1Z- z%8hJkO~=WtYWuBw_o~p<^3=z9^GdRWUa(&G;0*Lc_ioVg6#4b>WAc!uiRyQPV5)?Z zu8GLn284+JS64)faoP=u z;F=5Z1fZYl8MIuGTe4l%|G#-G%ozv57X(bJ)WbDuBk%;^Oc_BXA0&6usYpSpyvSn9 zF9|+2KHuIw8JtzQbd=JD5oxvV^Wegth|#TeBl>T}{Sw9{?~k6@O0Z8-2QFKa$8i(w z2n-XOLW>iI=RRp4K(id>_M$j{wD8jM1EeDrur>B)ME&?a`?>X)ySC#t3G7J^$srQ{ z3C4TI7+~$f((ni?8k)fgbJ!s1JyXm9cKH0qCKP5z1Joj*?c%Z+$yomYo&0mV#&#CI zwuq2qrMHz0aO?q5GlxjAkR8N?_cCl?Kz;APpcJ`x_%7r<_q%b0qbc)w-;FF^wm)CM zVrz%ZE8fH^JOWo%4bZCeD+&h#qwSZ$!MSzs!9xl~Km`lzC)5O{>XJxR_@KKH9XZGG zm;jN24*iYA;tsX5xyOK-hKedEGF|V{c`DXv0NZePXFrN z-?tl4;9Su}(Zs$0Z{*)T^A~>J;K%hdBcRyo)!o~`V1;qJ^5w5p@501?909D?-j-^1 zks|7qO<*)LMwsb!?$%Hs-PZ>?neSD;=RJ1Ohjd_Ko>|<2lMz^Aw6d$IB;=BnX^Rp{ z2z~SK5x?RKf8h?sXqVzzZc@COiZk8Cc@RI*pzF}Tpblb*EQi9odXen?qrK$@(g$Pr z5DYHH_bI~cH7xZ<;i9>q?VuT==^LY+-=L#RQOY3drGtZuo`n&@tUWut77ek68z;H^ z4kgik`^5e`!?e5RK-Z+uW8ExQ7Uy4~K~B4WQLj-)kXG4R!gJ4g)XtWie)Z=S(}^

X_BKF(GC{7zCfUT|PquIS0aeptGQ;8yOo9Tzh^E6|%VJ%;p`rL)PhdN?{oVpl~on{TAo}~e~tbzSWo}|CkR2g;Dr1mPf z1C#jFXlAXU=GP7W`LY6(ABghq@0#C%P4=c;+YyZ;`w``Bh5QN2sF0C~>D}=Ax%teT zFoBh6^o@QZf+Qyxj$xqi$DudH;X)#6LY6aN}VqAWW0@V zjl6rt(jGr-K>b8dMS2tdjEgXVCm;0$1g_7KYUdB~X|W~c;$&|X*fZ!9 z^sy1uBgf;g(_Xy4{9DgvUIgm~xFlty_$IlhWRr$OBJQ|~5IX++N-gJzPWp;gf|F=p zk4#L=&cvq?G2mzIgA+v^ge?~3hE}pkk+?+!zj#ry!FWHpsFF&-I-k3LqQMG@O`a>h z6c{UuvOgg7mPpkUzz9K;q&D$=rYaQ5}0${F9zp*Dw)4#%P)bDup9bI z!bl&neTUOQ-rQiGYns0KrV{v5!LVA^fJ4FH^tkb~%Ep{rtV$+*GN9e3(3vDp$kH0a zsxgFKhU&_U$OPMDX07$vI4q#`oTehw5Rv;MO8WLK;OtNOHq9CboN;ApYOU0>xIcMe z)sM@zS2zAHV}e>xE)M|!t4~-FZ?{jt3a|XNB zfWmBphR?x=zI`xb+IUy6_PA}a!E=M^-xrN0f?Tzns0v5K$t2`NUBQdu5v6$wD~UMR zqYFES3UK0-T7+H*e)is%dUg9n-39)nAv|IKEQ<9;|K-&`O7LJ$TK2}f)1f@ER;&-3 zI!tGMwXyE7!~~1-+N(?-j<+-rwh)e)C%z%RMD`;F+nxJ+NHV`1tZiTY3a+0Y$*jq8 z{YZ;%;7q2u+G;`dYtrwKkPJ;xcrkV-hnEeMLx>%fPk;?hRb_5gxGos&Kt2brMXu4V z{qZ_C?;n3GI6s?#-Gyl_ffQ8B6l7GI!kTjIX`?l7OYs)bKjPq+YimG4Du|bH)HR9m z5OkRU7+#Vz8nHNk6mVWMqzYY}Bl=}`B>s*AmDP|HNKkZ(sOP`nn4`$^lOQRwgOqP? z@AGXWs6m5~fRaW=Nt^J?k-3Os!j}}GtE{SF;b(2?oD$Q>QyAKum~U`)W8Zo1uDzsg zx%#lq9wm3HGrz)3Qzw(ZfuQ5MrWeUu1lo|VBfMp9;GP+yLkGXbuXsBXvTwTM$4)RU+?v~ zxT$07fYi6hI|S|qHwCj@3B%3ox3z!j(MJaDDS*6tNHc!BfDI&SpZ$K0AnlANq7|t$>^c&~8KSF*`&#&ipf5UC9fyQc5 z!RnUv8?R)89bpR(PxzTR<}fBnk0Sm#8LxT`?J$qSr@sditr#4=26u&f4+Njl%`i=+ z4F~UG(-cKrQm^QDgUjg)41YD|5ROO~0_epW93AtnuAyYW57w6 zSA*|oqqnaX$p+j4MDz%kboa5P4M9*LBMO>@!JdqV-=?E`TR*^c%RKUDUL?Rk-RiQr zuzryQ_KMqHcWUPfkWv+=O+x$wXIWs{2fmgLd|#q4LpOhT6Af*J+fsw6f-5B(W#18M+- z&CZ0Cc0}b}=uX-`EihDdj&$s_eZ@fd*_M(<>id^$B5& z6Mhs3aPN{ZEajjd3L&FgqJJgQ1z1*Boj;8jTZA*5p^&u+8rkT5TY z<}n(^c#Aqe3=@^IwlRNIlN=TuC3~72MrjG8p`)&CPG9<_QRE_2{d3;&^H(kA3|=lg zc|`$jr8S2QsKSo|LsTRMV#P+0NBA-7+dDd^haFKQ4CZx4nbZ841uIXYaH?som5{Ek z@u1d(tsCTT!N>_o3`0 z+Y{@^V!f9#wf~Sm5Uk{2{Nl}Gj99tGnu{SKAV}0-*UN70^0r&Xlfz@?av%Rm4@Bg~L__=x z$eYd|#wWu+^vwRuO0?Xae&0Bo9F#~L)BheM?X`xe8)LP?`-RNUN75z2Oa$#`vi{c0Ga z2inj(bll#*Z>jv52b{ewZM8s5t<0v%pE71VlIp@FUzUA`_hrZh2%lN5oLVi<9I2*{ z&T#M#t;6wO1Y;faRK8X%;~l!B!~`ws4#<`}1BB`ULC5qfjM13xe58G-8WO3$30zbk zB%6j7DZ&m%^kc7(~f%H1|fYGs7&?F8zl-!Eygn@7TY?M&5)5ig)=Xit!QK8MPaAJ7~|&eolcQ#C>d^b3iu)`tqk0aoo*5bpYMWH(~pV z(={J9c-}o{+Utu?gVlAUR90(RE8~Qf5bkifEmDOO0u%lU9e(}F3H<=AG)lYtQj|2G ztk0#-?Z&Gdi(x|ov6|DQ{M7XzS7=Ig`V$vnVr@FyRXe$bbkk2P&(#H19t69puwOfu z96CwYU_=!ZvEPAg028D;mw!JW&I{at3M`LmN%Uch(mXFDL&FK~UvI8}#^*;>J?Mh& zKkH2+|G8e<4+XDutmUXb2p3}+FEsw6@f5Mra5^9)*m$1cSd^`4SCjZ4+TAg_#sAAL zSAYJKpBb%ZF>y|#xyuGP*i>Fysx?_hslnA4=CyxlaklFw7X2)ky2iJ> z!}9egkD%8MN@41aTa@k;|FUz2t?oGg;Fz)}8u~KTqZjUM0hJ5JSPVS`}KplPC5CzYnWtocNBoRTJm*0bRZ+PpJH;uFF>KOKw;iC1CnxB!nEbE4kJgUe{z}e~O z?Qz`VxXS4!VLa+8@XNqfyK2job3Cv_m*|6#PHJbi zPJ#IZ#INKY10#i7cRBuM4ho1kszB{_=d8^p^QqXxJq-IkscXa?`k099G5Ud|mSqu& zJXNBrhKrzR!hhCa_np7C23X;D?fz?B(N~pG*{=HSq&uQJqIjIcLd82EGt`V@P=N9- zii2p%k&|#yquSrOjct3lOnpf8LB3C;iV>Y>1+jag<|;+>6^cM^%ZaV@G?+~#zfk~! zstLMjH1(FvU;giZ_A`8f|do9Uu3lm$4D;kx*N#bRN%3%-PzwH{oAOzvPor>H_X zbJ&k5F6pVO#asps?m7Cct`QoK6adUi3)u$tMqj{ABmHBY631msZMzyTj{9gA41`@8 zFt!I0!#!K=XnqKIPR1vFP$&Lp((L1!^tPR8c9}5=pcAUigynaNQO#|U++7C!mB+c( zQdvvA{BfKJ;|^!9%L3o1i+4F}D7Ew^dyE95y&QjR5K&4HE&+=!0$X5LCgJM?LB-78 zI5%5pROxf5AQpss;~Cf&3zsk!>vxT=Mbsui<>#xF;A=)v=M9+01qWYOEP6-eo zw>xu%m&;!HRiyr?5!-DJ%)cb)YG?O@gQvRPp=!$M!VRFk{#YV_c;|{Q>d1`M-R+WJ z52|mWYEA|i0$=Afh&Ul_-zX<7{lyB;iPO|*eq2-VDfaYs?*gxyeU|MHI-Yo%c>b`t z7ev~WCL$m@C{B+F@gh1;li&D?p{7stFGPl8HLEnU;soCo6)p=uepx^GZ-E^~S*6K_ z9YoV5b$Pr#IAs|SCx(%RZi$`cX(|T+yfDdO^z$ViW>`A`fE&;+th+_8(8<;r=UEIM zxUVSF_tcvHm39&`9*5IJAQ9dHdribgvaw;J>lTSm3nbzQhgu;A|QPH}fA z?oy<<7by{H-fc?>uf=4%_%J{cznh6RAfAm zvpGs)CojdB4tQOFb~lN(qjGwnMxj{@pppO_4#P1HGsO`D;V0thkZbbfFp7IFbP0Z| zk<%vE1(og*m@&GEtp!>UaZCEmtsI| zWD4l~9jONYn_}r4k-IW1M8~&OO}9iG zWFl4I5Jh#t?kEOJVb(PXZetG<+Ol_(MSr^|keS@e5|2$91t1!gODI3e_e!(%7b-!x z#zAm3P7yxTG!twmf}w9tG5LZ{n{O(lEncKe^ETn{2?)5PMj2J4iuVe*5?*M4`VCTx z+VKGxoV3I#N^AvaFPQ7F@$y`BY28A8zy;^JobFT}KT`%`i|!Du1`Uh6BD*!vvG23$ zmp;}~iFO+V03pI;c^P2WPEU`dZjY|*e2&((zi*RSD}8^1)l4}PH8 z6u4l#Guj9;FgCgec?y`abiDtyLod=qH!L%3Pi)bnzH5Nc7$7B73zxN(>7cde7Eqsr zG<-D@$Ukw8`aXFPxav*oMW}SKBE2!(y7BWvz`Q!qcl9$UQwmSA#y>w^X8{!G@ zw_YiI-&4J;av__GtZkJL{Kb~JfeFH3{n{=>g3L-+P1A?qfhmU~@2n^!B9hR(TVtT- zWS`IQz0ShKYFdHbqk`-e^SP3=6Bys#9DTM3rSssAL zhN^?D-q%Ke0{Ake3;B;hZ$6ou=0n`{y!ecn=LR0yk& zX9&!IXsY`_$!|(*@XeyZQ?`d{YEBPNbbm)~2xWGDcAYS%AB;@hFjHlndY8^6F9Ew; zyi{a95tYkMW`im?QULOI@MO`5UFs`Z7{u<#&HvJVNAuIReRku}(Xx;H#7bb#_m0_Bo^T z2XFnIWc8~mE*{uBJqyCz7eD;VqHN}g4DrFbE^}4j>l?2nOmUDOPrv>2bC`vI3{YU77PtPr$^}fI z2I#v3t7!q)ZOIT-cy{N>hSeQxlZP90xC)pP-qjV|7q35;+wKYro0swR`zPb=6+ zthQNSR+NUTie~bzMh0TEFNBq$;kUA3Wuinarte|X;Yj{DYWia1W4h1$8?5<^qio2_ zk?j$;6!nXJESfy5ki$*mzZWCd<=>n$CPGwX$v;ixHnN3(AMnicCR<;nSEONq0!Vk2 zMPhdiF*Y$`3Mta38vr*RjR29*=*Do0#$OmelN6E_h+|L*HcACM92AM}SG#VuK7Jr! z%uF4S{thm=PTmv3rSk5dYnymyuIST<7VGbc0dz0;v_X}Y(V73Z16Z(WMA%9DN1c;q zQKR%LkY5T_kCe^?6n#|@eVk#>&2zXkg)(O^t%K?}^o$?VkrOQe^tyBtr)Zlp0_FPC zTn|BimC)4g(HBrxUi_sU+Y#l#H1r3cNb1Mod+{}N$hjKj;ZKbu2Pb1Oe0cAcxFPhu z&CO!&Irjdy0}xL3Z?+U&u`d>f13YXxr8+`f)!VCq z(Y(KbG2hwTNDsD6-IL~-P~|4JN~<(d!RHpWe-KRF6k-1N4SmSGgtn$k=GNVvR^r$p zz61eDv!=$ zquj-w6r>o~^V2)!QnXf`VeEsiD!HhxoZYONrcQR??SFG2XH(U{isP?xQ7dih7@8t_ zjeF!gxjAyBNjPrWnUD{o)FdW1?@Lt>5IYOSXbSt)bZZ)!f-H686P~$lWe|dWRAm#T z+L&n)Wp)u512Pih*^xR*cHiCWenPABs;`=!x&P89Jz9ykfD+x*+Z)~9k zSw?DG5}Qa)sg6T@Lw~G+F~6h^vU_hc*Pe#tWAF?J=)%&RW$nt6??kgkyk3pk(!uQ; z$NF^!CS4Ae@+p4s2e8=f8YSJChL=pXWN~kG{2m~M4l3W*+7J)T8CbWz7IjJWeGoWR zjXq*~veU+X7R`nRBI|gk9cePMf5@ed{sPnR@3GD~rjZ)d{qqK@am{qs(o*@O66_jc ztzYVYUf9w^Fg2l^eGt(+bR+gYCI{8|R|xh>?RKc!@?N~ecy0`Cdi41=Cc4mBW9cu# zd6CVpYo~L0GWx*3!?^R(x+DlE#RCfF|KdzPRNT?tIG?=oPR8o+BYLw=5Aw%PB&!sl z31Js6Oy;=_Sq#v4j*DVHSrGZ6HuK)DWle4xfFOYwWhdb(wz4-xLIDW42qI|b4lrK~ z{<>JVoC>tUZvm5`G%y~DJtZVY=q7un=CE93X?!E~c&JS7O~371_!DaLjVMmne=xSH zz3?mm!F@*)A#ARgxLf{qrFwAHC3CZNDxqU_Hz~(+wtf6p0oiLmo?+e}CJkCd;TfMT z{O0|yXAF&dYCg?{_@@#*4I-!zGb<|(cSfgCC36GS{^hdoy$=e=q@2Hv3DUK$e(_bi z^@uq@Gs*vOv+;VegB@e-_Q7r`#O+7@%|R zpTYc@!}q16)c)CsG1F=1c1Z6y2jpy_mG`=AlzV;a%_7X>|BSCU+Fz3G_!q=7Vkw7- z)I>>uf&5RW%n7Mt3$Ok`y#p<9BTu z(6Gaf*{l3;R=|2aRke@w>h@4C82Hm)o$Vx!XhhVubXkfO+zJlSH<-Cc$SrJ3Sbaqn zFn`03(XF_>w-;HjXB~3?DqlTK)Sl4WWWzk5GfttWehCe_2bVLo#y(R$sqOZm?-7tQ z-N)kIAV%^2kCWy>y#-jD4gMP%$=v+)@9-`y(dFdbuZD7p-?r(n@XK8PIl+*9I}~sd zH09u!Ah*z2Y3ZDw8u_CKN4(Ic>KZEau1cU7y*Oj@P09IXQqQnZCR!A?q9uyBGa^jQ87s-pms8141K~IGmx=fl5h9}L?Y~kX1BYw|D5BRXBY(tAY zCecUE({?EPd<*QBQ-<%@fhgRY`_t9JHCM4*n#2;Fjtdgr*_C~jbrI

|$`(N3em11b z6WOB3P%vooX1aue){MdL4?|eVk5$Pb=?m~mheC?6#D1pq)z4`L-Db)ws3vL&=$Hl7 zXqGs7rhtV?dzKhVj7u?b_H1t%m}>^;CIY>eBmoTsYhPk@qORy%{+v##8m9TUI&*+X zZzvU;R~7TRRbFx(=Xn~24&(I1?B@LOY^G&D|43X}XKk2AZlylb)|Cz@yVa%CE!ZU& z47crjNil+>&>a&GMtd_7*%Mp(Gk6H^^uUn=+CaVMz|rxds|u`%7Zu(uZ^G0$K0PC+ zrt2@#&2HEG)??mhK+Y{vVw>jK9sp+*uh)z0v;vN&0@2ds)!wD!od2Q~gFkKZ4lC~u z;kwpoxfnz_?Yd~tOmGTIOdpnwQckSSIHXd(b5d-y{X69YJ7Get4YctiEOr$8_4Sk{ z#4d8pkwQ%TRtaB@xl%RT&n#-Pxpt3kEGh(fqwcK@F4xjH2M>oP-VySNq@_b__<#;# zY3sn`AffAj1hcKflp!nun}4&sb0qkbEZ*y<@4iO2K0IDO9`$KVejFL3@XUbtVh()8 zw*LZ)5u~f*Jsn8|acKa}(7ZqRh623NfLV9xnAYg1(u=0TvS2TDf+JIc^YS;_kFFYq zIlu@&k^QMhqEu(d?Y~6H_t_|{@U9$ z=%(-{^~y$QLzBQjDmi&+1Og`8wC%9qlC$;|-DFI$L~tz;&4-bJEKe8boyg`mA;WSw z)0PN!d>nzpn<3vfKi~doy!a&>Tu=ZJDW)dL(6Z11Gdd*$2u_`TlWk4EzMU;$FN2dM?Xi&B8;bULS`RhV7d6-Y5eboITe~*bnjt zyFZQzE!FiwtZ@(f;L&i`p`1AUv+}0N??^|tprAwk6e|Y1yJJML@p9peIU$lAmyTHa zIC=PY?C`KJ?|*XPdudNX9-q_$7BUA>g~TiL1LWNT`)&XKK>!9$zIgVtGzk6;Rf^aA zZA@)sX~xQ?^i_6t6Zk0f`ayaY?{5=n@N=MP){5#IAHd-F>HG30b6wxR%Lj8ISAr*y zXu?JZ%1?{Z3VY7h@v9xmryS+VeMk(ffN@o(}*DYqn=SJ+oH7JDNX zGVOpNb;garaTchXQ!)-ZMd$YlLKcJ5cwOm=bYEb4Mkdp&vmZ+XOBb4rbrj>fKnPmn zx_-i-crhyC`}?Zkr`s~>8dNrem}uyxxH6z@XA>d~&ckeob(I#13QDBQu?Iy%Oe#pafM9Y#B%k*Vgu~Ur@Lx`0~{At({07~8jQ;78wKyY zh^`ughcrLkL0~iaZ5%o4FP5J{@TIPqEp1v z|DFBY9cdWpyQD5i93?qHajS{i-Zyg9D(R0-msnI|@Wf$_-zbiyrR6O62NX`^bU+jt zDjK2VFe@jo{DDd*3$1GIAcQlNIW{bV-e`QMD$v69j+DAZ4>MQNJBZ8bD0vJ`8%v$I zcmOhh7#1&v&Y+Y6g1!ip4;j>w94cnZv!>?rjn8nC%qdMMl|tX})axRtclIbhQ&iESJ=W~p4*G{%sVhXYXn37f==ulGbYriqHlRTx zgp2djW%2PWcuT+F5vKfmeZjRa7Ul8B#2r-HL3%wi(krV%E<Z8z=Rf}FW#hCiD3t3PvnpiA2%8BC)8|x~i3%S(ddY&-Aw{?;>avmUn)Bp| z*@sCSEu)Ni-}MP^etyF@GFR{8RmfKO*w^`1)Ye^U;8$ojRk;S&qEW4TDF61RK@0W3 zr;=Y?V#cVj*Lx>e=x@}CVu9Fg*|Qdr2b!0h(bv3@9N1*n>FDp*>~VtkMCoBIm@(%# z1$+GDh}JVH^iaiiO-i*s3NN@4tkRE+>jNo-;c2lrhExqjr(OFI!va%Q0LB}p|a6;46(g2NO7VNiaiY5T%Mxu$$im@i{8cD+K6w? zk5O^SnLMSGgP}_lb!IF-nN0P9iU;2Mt$RVA`0G%Rby}j8FO7j(hnEx26u!1JP1K+a zQ8(F~3$n~`OD&$Ad7b%NAm(L-N>(AWxSna zy_w8rD?tDcOEQz6T-}?7i7o52&#YQEpZDP1znYBj#bo5ea%S-rK>MtZnvuh{jw@=& z9aSIyeT8t8Jypq!UNFlB`d&Unn1&!s{9vY{Y>O!;s$7Za7`6dHM!3oT^(g6(cwKS~ ze#zj={q#N*P@fu$t(&8AOUnn`-wX}L-njO`3?I^R-;u~{6br=b_fYExl)O6{=;nm+ zal!N5b{0l8eh2e#tu~icG{0cF{3@5z^hf&jIcaDJ%i+Oep|Ko46eBW?Ak;;+tudpO z7*j6<)qK&^39RF=iT%3mq9eT2tmXdVTf33h#>ov^1`FGYTnGf-Bxb>WGU6P+l+)CtNz!7ksbw?AQ8hB`1mN_7}7f{u;ahLXSa)5Sp2*+ zaZ4*UGWL1j=@wbwnc8umI(&5=<@CT`RNoof>DnHg7>D zS{gZ{hNTod|K2216Wp+*%H?aMe|gi*--7(>K9eq^KTyIFZ~yB|AN`zQGfMrSLzH*N z+Oam1pwku-&|&xg>opl#7XRmSZQs!hi4a*+5YQKM;jyv5{?B){Wy5Yhyd>I{+_Z?} zxpE#z!(|G{YwFG`lLfKN@qIfYHl3@eNi@lgq#z?MS`M^z7l2oQj@;^-txIN!HRl#5 zBQRt!rSqWLQ@H}6TyEPkwc6Z4U!>=q8}SrXF7F9$vV1G#NRc+<3G*xLp3neN?kb;v zy+Y>;lZ0;x)- zUAi|;-xoz;gee8eH!7wF7SB)b*P%H+=cp7)WE{(!6z^b4-OxzoTr;q=Q29&<`bX?Y z<2Z&>KHtmr@3i*q2{%T&f34?T_$sY$UQvqDAcVUt<2K59yf}0v3f}aFSO@N$p%)(Sr zdP?3~@8u~z>{J{Dzw$pb9~9CyqYafWVPX!UfMKx^$pv5G-Ls7_Zwm>kSx4z#UuTSw zC|E&15Wub4OsRcKP(jJqGa;WDR6t@Igr0)s;mKI`f)n2fOCf1RxzRIL5QCy_+M_?J z(UJ}+7V2F1ZSK{m|NXb@@7IH*AMa_MS%xf5Ol|m0?4r;R2hxhq(g`0PqsqWdfzyN24FcHd~4n6&5SZXFN&aV@JeG3th+l4eFFM+*M{8umJ zPC^T1WGS~L7XE{?XGyD18f=TnQ+EDKZe49uPMUH|^?@V22;}3~uu#)$Rb$np`WcDX zi{e4v?0s^&3;7jIFeWFGuBxeIh3N7(R*a`|s3%gv1oz-g12jDkz1^1|7YIxpvjlMn z0H`rUc&cc2uNLsBKe7cFfOl|x zOJ%_^j7E5UCm4^w9ma)NA_0UfAIdUMD`n9Lo_v$EY>qcbw={qRQiH{4N(DhX)j(ME zb=9sRykYjxsiHGT!RhT{`}tTVDQe-@6I?RRaaAG&J9Gx?^j-7B8G0gBoa9AV3@_2^ zg8_V%FZ5$eSGkk+mNKF4T?$2m-k%AMsyD9nrjhe;?HP zGOsPJO|r0Y_>LHD@3PIJFCrOd;6F93%b6`U7ymkC2aJdH%fbFt5sGkjT?!Sa;R)+M z8k!96cVNBb>*Q$47%K?70UG?11Pc9Oa4ylDVJ|~ncYi1w>RejeG5Y(1#-|SS17;|d z6mw$@_v@IknIjrYE5CxOG*qpQXti;DTOjC_#l5nW!-N``+kRv@gmC;#K3qI0MTA5mp#eWOf2Ynvs~&qoXIPgTJE}Pn>Mc+Q4?~9o%_C zeEEX{-^Xd&PrV3z%c!1yJWU_fXc^6;g4k~&h#K}X^RnVuO(SYxM?!glO^K(GskM=i zEZAKE7G6RWnSeGBiNO=uj!iKM+LOMbYX-305XPH+1<>azpb`FaP36MRCL1cVk4wri zYzqVcKha-bp-4YgLZ{F|glzKh?=iy8M*6YrUr)j!CAyM};##wV^cgACXe11{x;_K~ zXJ40j)pH5?2;%561NRC|)qD(U_}Oa{=S^v?uV|<*eY8ql&w{^&p`z*4#$Rjv6C_w~ z0vQi~dA;OUHh^4o6NL@dJHmYzQd_$q{&vq8o*OYz>g=Cn>07rg{s);dc{{wlT$&F5 z>xyuuDA92`YZ(5aGH%lYV2s=Q{?mMoy z6C{e-DuHziaAqyb$aOZO`-tAF|XzUM$M1%K@px;6Tqs@TLvlY_uc+JQR?Q% z(?8XF*Cy8pUL{2vJX5Q`eb!NiB?ttB`Vvf0ioZqwH{S6P@JK&wYh)Ii`_ph+vBcV5 zrII|`$w-yJrxo8`u~MNjS;Nqqr75Nkc6v`bv~dm!Sdu9qOcV-pn;@9jt!f&dy$E4}-{}Z8aw+7p zA$>6Wnlp%}m~PRyq^NPrH*Mz%uV%`2^>K1{RN0VDrR$#yq1xl8ti3}2dK58ib+^IK zaqjqX0+KqrJ&;eW=Y+;AKl+RH&0i|PM!rj5iF1(Z|zaSVu^*d#~j*yed)0*Y9)jLYf0cio`#o-JI4LrTmt}vE3+^!V`A?F^l0&YqaO>M&ZeF1%6fLo97GWte0t=1> z?t|VB&Cu`Bx>tS|?Nh_vmoBazGyc$Egg+83yw9{OeuIWA^rhZCiDTX_wJsxVOIq5 z_H-yh1R?=!S&KhwJ?2{+J|8n({rm;D=i^qsZ#^NZ24@g^7Y6(q1s}`u2*KkQG)P4 z*Wpj94kBKJH{j$yd~dc>zXaA{r=8UO7U_F^eUnl-C+Y#sYjSGpeljZF&A~0$q>&T5 zy+n3Z@EYm)M2={WUS{vLg+E=sTuN1`pW*mnfZLUs@4A*jX-?!^5Po!ii?G@Pu0#(Rnb2n=wB@$9vj&vU4vcU_MA0O}*`_|HJZRG*+II^L8ia%P6bR~t!gWUK z9y)~RzSM2icw^YpR%sx5lbE3EDY1ZoqxbwZip8E`f6+sZ9f~~f!a8TAt&PDdPmdzJ za{+=qf##btV2a&?D1{har0XBLS*lXvRc|CcRu7n<$~PV5e` z(+soYLJ8=OWt6|+Z*)ToJ-JBoIEl^iET8N@3nv}}s)vf4+$nb74$8BNFx%EtM%7T- z7?MSyu_7ii7-kK;T+!F13x0x(lA?Z<%NuEy74;*~SYcC@fEZ*puco);AD8M!A7R8B zfGe86U;(ZxVJo50D~wq?VYQbGD(HhF;d17YF0Q{S5nIbi-f$4St&ji`0FO4jv`v&H zw;}DONMH@-y|?IFuML;0HG7+@pPluri61am$ zUI4$OR7U^l+-6FbpQUd7 zrMdR%b20fC1UcEX{u2q6>FKf< z;i$RIh_{iQzJ*B_BYLr1>X~oiE`JfWg17UKn-%o5Ete=m^N{FJ5RQA;0>D{bA6(7E z%;KrK@qG1&U^qG7NW-ymI`yD@?$|M(>m@j}K3S`~i+Nn$vaJ!aDhHH`$Lde%(XKcO z08`9RHFw}v$hP4wYaxdJHD`)I%iQ7k@1KZNZNWW`7A&4vpulO2{TVin!Q@JYql?pUi8%x zh2GKj&0j5Pat8vv7;FJ6r9EuJfd--UI>Z@jn}5K?mNIJRi={fJ`KiM3CWM^VoF=$2>{;i(0w>xKZ@=>;T;?!Ws!75 z57aBcRVS;-!&vDpd)I}d>p<0!DB&;)n#`6mdFaY3nj77g)uhIgO+rh;ygy2j;@4Q{cKL3Racow9Q7UQ#=|Z6h@^@7hedSnT z7Yfv+Yx8>f+<%ijG|oSH44ad!+TkR|RLWD<^XiM#B1B`x z1TPx4c)Sp1VdPqY&$lIn{J39D4LezC^XQck=dMvZSXv2~Z99@Th?|bYVIq=e0iyL& z5DEUVs98U}3VAklGx=C+WXx4lYeY18av@P7DIwu}(t2Ya^3_?!O=gW9<;<~XLO7-d z@5h{7$qt8XLd+d~uO*K1CZGfj$)2J_LYFee!zdy)ZYhk)zhADMz+MJc#UOcRmILgb4M-S>dCbe@9> zFrj<)u2~GPkNc>EReIHm(j-Z#gEy{#>gibyCw$`%mQ8ywgQwn$4hE2pbt8bMPyy28 zrpkM#=T9*7o~+NJlz1<7Q(5ZQi|L&{p(PLC$cn0(sUg41lufaqBoW7LELr8H$>ofM z<|G6NSWu#QG zHl&z$kswH!FWQ_K5A>1lGyIQ^X;^GPJS-gBmv?kec-k2uu*d`_qAz6yrPHI1y_5?F z;9`IS08CUXeB&1sk?o+tNPh-@QE=(SD8gIlmn0NIgutEumLfTWWszX|-aC=9+v)*I zdEj$eV*m9eujlU*z}l(T`g{(YIl*T&rlun;)n*g8WW%Dzg-Wr{ZzD+AqT*GXhz2!_ zZT)1870?N$r6SCc1Z%`KWe(A5nOT#qlJ|#2p#XZ%gmBy9iftRMDexXr)-E=#&?E4= zVmCJvokI$!BN=Y8ZknFG7Dx5jM`eSZBijNJYb{u}UqJ_Z3WY0&Xzp0tUc79xiS4EW zlF*eF>v^UsQ|-+kU_uwU6y=P_mXvgWG}cOyrgY}?#PattQLB^(tSxa_fRRJhJh6Wt z(@i4f3Z|*c3e;okK2PqM04lEvyz`ZrHi3Oq_KeqJXfzVJtox(kLM>Xj39gyJxT^8u;0In>DT7_er~(nn$R3(5qLTTBHkss zW>o@6zSUQ=Yd5y@eTkN)eMPs$T#5hH#PTEiU!i>?9lNmE*U?FBh#;$nc$id_&VYx(dB2;tq6*T)cB{N=vDz?b=bNFOSB+HkO2P)rx5y%ju}y=M)J8GwTZ1| zbFNKV0I~db_q(?*d*dmQyV4=SB$)>`FkNZRZF+UGurgxV@hE?N9?}Uh)r=U|@6!tR zME-B{jw-x*zW~QMGSha&&T)<}UW7+*{M^a!j{Ucf)`_W(-iawYtY`g+`Cmn+B|Hfp z9T)7c@`H4bV+-yn(~=YULpAr6Y+b0W7{>M+2}w4!d4z9ACEV( zNLuR5ObSgsi#1YP)s$L*^Pbv6gpG$-}zN;W=5}(OJgl}A-x#)&N1WP zm##sXbO1Ux3%hnL6Uv-=V}sXYtl~M6x7vxBQO=Ha{TE*iBl=J_Q`SsZ>&6IgDmd9! zpXin(249vKWHZ!fRyk@fQtS??UwX^^?tt^<9sAJonorjWu@t}ab}Hv)L9EVp#IiQT z%WUVTrf5gAW*Zr(|L;T9bgbaAf^zMxh5NHx=a?WN?^3DeI0Tw3Wb&fTx$1{B@$@&g zuR`Um-c6QrD~_Bs6-~mY%dqV)x$thopnB4Yf4+&&AD{~u*mHS0FB9g15g|uM%U-oK8s~!Rw$^%Lt%0!&Ex*Zn(&-v7Yoz^{oU4k?s-#8Wz}^$VhBB$ru|Z;lVx< zy?I!T4?q2DxwgK~qE#vF@BR#|v)Mzbw0|@44k-e?7M*O@jXZFlr1vlnfK4RfJ-{$WD~ zc6?G55q}gxvlmyfSGA1k?$)sWc57Rinb#XN)5!1F7=z?W&ljA@+Pw9qmTWEhk#t`} zO6`}D><>+#&V}#)<-Qv*M!lBF1?*bM1N{1tEtNTk~kn+*|Hc z_k#QO*ddJ^MWK_wpNLMVd^+hw3&aw@lc(JD8HY&f#&)r-NHYkXeH@hbanthrAqodS zbO!N~IJ;b4rJpT09>6>lA=7V5*&kVs@gsFvD}Y|(nRfUoiH7IW%d7?8E$US=#_94d z%}tTTkdmssK_QN*?Zze%H}OzR_YhQg@ zrNI@D|7`jQr4zbVI~0Ml+T+`$CCji~BeAL^%gN?;z0u+`IEY)+wccQLh`~mJ1;GLG zFX(t~V{Jo2e0H+jLeLYEtJQtDO|l2F^}1&IOr1E#`v|iXQ|gSTm%}i??lA*6iReN) z{F^k1LSX;-7b7V|9joe*n5`NufUoFZWl?F`G+OeLB2XI3|FE}^lzKeNnx|Ei1R^J0 z{}JV1x)B;<9Y^00x6hGoW_s`;8{!$@0c}ACF!Vbv9TlXshELwK4; zY0Z^&cD4B@mA*cE%_NL*I}ER$yi2ojDY<0if<}*SJ=4>U9~#I&m~yw*;N|Y-W`E$o za$wr|D!Z90|9fvi{I@JatVdyr+4Z~^Q#fP#p2b0^E-UUrR9iJn07_*5x04Y@^XcE& zBVL|9{Fi#=>|GAP$h;_oPck6qLpqvEVQ8coPQsExWdHFXTxpMZDtVVz)~c5#_n-6> zja_7*nFmTUeq^_#lfwyS)LNB*aH+R4oO?r(k~|G9VcbClmW0hl#6pDJ{OFZ*l5^9Tqs?ribjE z-kDq$Kh;UZXAu4rB`IEH-vP)7(~>-PW6ItVY5;?k=rHmX{+Yol2{IBI|C-Va-RjpS z!XsZ>I3q{w0QcPq$eAGWEr4UZDVS0VF`WRxEXVOCif;ylKYYV_h#3=7BK(c_P==Ns zjGh?8N|Qk>4hdOHf)EUkonNjC>{jcf2(r66j0@%w!oaO$r7tm76T#m;z+h0Zgv!yr z8rnlsV89V;mxOfROL^_w}Q}z9^_ZZdYG-R@A4dXz&V!h}t8EksG>B$}jdLf;o_$ z(s6-pJRHApaLcyTCc6fyNPA^RpI$nb;b!x8i^s`!Ghm2}Km zg|BqxdmZxP-1h>ZZw8-WP4&KetzJ;S&Q{p?&V^s=Dbuf>iq z=yJW~?0i9m!&D(EzrB8~d;Qu!b>K)qDA95=P6EH3YF(k(HfH9kqMjZ%@Srr)1^5zd@O6z>gi7>8IO^Lxa}?%4zv2B7nh7ZS>_S zXy<19K3Uil&x0s+nhn^fT@b{^X}J#& z%3Bj_Vt4sGe=kL1L>+wgNjo;RxmmwPPYqV6Ohi}EZjsq%<(klssy1;c|MMA6oGjR$ zG&A#v^REwUA;Jb_l+Xw3BIg_&`c*pl&fQJgRf=g4eW*U5FK>ph%%uC>tG=$@rQ`sG z7sYtk4A)jP+yo{au6*sUu1Tf44Y7JN+_!1Rxwi7M#hrrs%mIv)V?1a}Vs*GU^_Vm^ z2WF=9f0u|NaiXX4$l~E*N-PfuW2;Zvy=Qc*+f{n9|)?o5$EdyXaYf} z7*U1bkb`2BCmDa?)$nYYur19{Kkj27}$kGS&&T$ZPc@c`nIOrG;9Dvr@)Zeb0MUyul$PpYsyEgz>ig z>1FD(ev#2Zd7z65 zWK)_3rC)Eu>tcCTiH+VOU(6HL_OD#Wee@El=9Fk*f#z+3>J;!Z^73Jw>`Ki%)fKYuflI8c)~mN88_7Q zlshI(jIZhQU%q)i*O$$*3}+1xK9{Z`x{t@_$o8d6T@Dx^%GY#5yYFe@VQ@TXWez^N z&r3a^sNbIG#5+Ul3;mmUbQJoO=LpOat}$P&&_$US=4%q88@=GO{PMFim~7OScc{S( z?$+{WpxvuZYFXw^Ozgnm#qr6>ZdQY}^Ah`axT+EByMwJaW|?nA&$c^CJ~MRqPY~Uo z`{f?E=*4n8k0fg%@d3)^&fvr_TMg_0k{VQR-kORG4X*z_s6Ow>FL-Xm|1nwW)ea0| z`$VeUseXEQhi?$VgWgW=7L-|>apvhpw!~ibgNHTSj~^+tbjz!568&)Enrim@%5|_0 z!LnD{w7VZMDt7y1K3&m{Ey~a%^UTg8<#f+7nj>~WD)dC{b%dNG(f^n4_xk>4r-{G~ zx<01cA5^*Up1*uE4qWK+D=bY|)!9u$~*;dTA?9NbIIJeqD-<)|6D^t z|Lg9yTozP5sz=4W8yh!OLuaDF!!{qEOGIxTXu9NvzJXe|wqFER4*o*%M_%PO;*%PK z3rFUvThuIB497&`Xw4enWur zrf|21Zd$rN^3K+Lu7Vn;2kfq&ichCqsAlb9-m3ncJh%g%>=tzZE)2i1eSq57mq8=6 za~{2YGbb;8p|)J#G;f(&^GuS!RLLcq_|ZeGwIbUtQFJwd86TlLqkFn(qK=fd_SC^I zY{!$G&VRk zaDwPks`$rBSQ~`@7M^)g)0=8WHoa)ZxLFQm;#1E#T^4!M! zwfr-xAe|w|Zv>sfYgEN+3O_p}$j6We@;JZTB@PaKf5o1a9nuw;g&baJL}iqZU8+&4 zq2~cyHr#$`jB56Z7-V-~7pZ96RopaN1E4w@a3MYn{KZ?2rW@E*A3)NxOY>2_u=F)& zH*$o5cYUImrbVPc8o{rKh5u2#;woUv zueT3B+Val$wbSzGODkJrNA$)UiU_`R+RBKz+lu`?@J)m&h7V)(l1Gs|C?X8kLoMn9 z^{;&H*HE>%h!~1uMS*@nh@`C~ON4t-LQlW^=?dQpm!0*_>NL}TSFoTWrz z9rzEDFNh?02!T%d#S!<(tcepe-Utp$4ELoX1Ydj)M!R2(>;H#^56ONfB`-!|b%FHw z!(DN}juG`$4M#Jg4@={DP4N`WIM7TKRQtmDmGs+;&=$r7_(*N2W9mq)rTXj)Zq%|F z&JS4weK6iJ)gb7rome9|o>G3o9IC%@uyEVaimg3<2PLs9prNZ6&!i(tH==^MM0;wY z>3hqoj9mb;)9eSTF#5{}_l39`+5B2+10`kDzL;k=EZ<1U6WvQRE)T!H{Tp%u)nfD) zRt>*91@J{QN7VH%3yl4_VZ2QwpTn63dkKyn#Dq0OKnGxN(fhTU1hCDMpQH7$JPMdl zj2)q!fd`^FQJM`6PfZN3E!X5JC|QFNvs(*?E4$020Yfz3(dW*4HqCbgYVT%~fpfy# z*AN+Bjh4J7l~Ml}t5qbveOaZBw%uoK2GOI4X6I2?%F%fdLA(Zl{@`#@RQM=zSLMRK z&Z44PY>Z3fk;HSl{kU!9vL71$Uq>o*fpi$@4<62lQM}NN#wNWAM)W3n7ydp%yrGm* zPY!_Odw5n4@DpNAej>%YjtVT)AJof0oEU}=&!qe_vz==d5H+EQtlg#HaMHqayFK)4 zb1dHyvaBhu&j)kw%f<7trC(tTem-%>U$%VpFYScoi3(0KDi?3Qz7F-S4IG+p)jB+a zYK-2nwO!bJ(NF%9iC`sOL^VJ(j#M1qo{>Wt%BFH)LYl`w;gmO%U<3i&5(Y3!-amdH zttJgDUpp9Cz-2D80E*twszqrs{z<&xAjT3Mnm}cECcD23!Wo$EnwtBVxRKDL!c*sP zJp7F=pE>(fu0b48yYi$A;63r4-DjZW+#6I3UjyF1JbMvcp%J*0)x`H2Qbcc6h(+JJ zS2b*KBqvV#_!`?tT?4|PUk4zpm}uiDet0F~#18(jj_G*lNG&-+cQs ztN{XW5J#bkY%G#uM-zf0Yi5Tr(Dfk_Gg?xO;+q%XH+K;i@`@2xu`>uwvj7**!CUuZ! zcp(<}5Fhh!YVd_xbl_p+El!COvm)g_^B(JAS&B=Ge5rV^MSin8kdftw5}kw?OKhMS zvZX4&O<8$;I|}ecTFr|Ll@nx1aGMCZ%85_2yV*V4Q-Vfx`JrG8#gdb9i( zO%|oG*b6A_&RlQGChAR@=4u}T))=Xw3l@Yz@uSq0f`uhCf|{>+3RjOx>|r20s_=i(6h z5F`g@{Jr#&X#eKHAdUF-)b>%8-%erT!SIn$LJ?hZm zZ6C-}ir!s{tTGdwrEBQa5fgExO1-sg0DRYrV*mh>jSiOe26es`ir5V2cx2t(eo}jwi#{~9#TAhi!e=!Lj4ZUl|BSS{4|4$3R zFnyX-(mryC!ujQWEv^dLE6^WQRr(i{!Vh4E0=sEi-&h>Tm&DFRa!fO*1F?5Wt6xR3 zaT(}jzhI}jtzcJf;^prj$RCsfU!KdodveMrvzamwjOePt@xK?0wg&xkuuH!IoKFKx zM7#`KWwikLfzMD$MOl)!{Kn-c;LX3S@ZBC(lc2E zPDj`FX!J%B`{`mO0i>qW51CUa;$Y#HtYwmqXyU&WecWovZ=i1wZp}_(uy<+kR_82WAy>9_?U#?=c?`zU$vo|h8Sz4)OH&aCH zW28tS+{qOVg&c!3*^gC@UcKJF#%eU#xmvP#`(FKow?c2Cx58|^;~Ru@AUuR+z@1J6 zxmR+y$06QLUoEyd$ZqWHqG9qitleaE#7i)QswDi0V^oin7y*?! z*qvj`2|0!?&A0N_)F8_GtxX%lpQ`KLkIvoyl5~HmGC!6_;(@lw4{eU^$y>x&|6>Yf zyxPGfSD=>NoEreE2lY*((BzK@iXyv0NH1oW!{;bHo6iZR4wFmF=^1_yzNUJ-pk{3AQNR0k0vbWXm5Z~w+(=Z2^M%_t-lQc=@=DEuyi=a@W=P>5Z*k!w9S(AuY_%k9bH?! z)ErCtVv_j%T_+Pc9+csV3qM8~yUluhyKeL8zG$mCZc=%8_|oMY85rh*yI&vnRZg1HUUt5- z%9J|iIygE>#9ifn6-ni4H9y=E5}j##@0wBJP<{0f_K#@l_Y0F4FNU+D7z`bSQIq|b zy}|3j$64fZV>(lv-x9DjrF)Qam-oXj7qi1`{e zEO_h^U{|A|?{W$x&Ax1h!M^IMd5_vDam2g+9~uS4rOXT0Su`w{Cp$(Yp;`nL)HNhH z1*Xa4-Y+4Akti<4eL$U#dR;*;z*LL(0AkjpwEV4oVJNCWph^AnUyBKe-)dlYpJaUE zG3O9=zjG{s%h9Wd@SG=RNv4`4Jrv+lRf9O{zau$y?OqEL-mrgWA+TNvuIt~3e|>w- zFU=Tz=&@R!yJ_W48ZuaHc4nW20M}5j@-0}leYCPnRMHQ}@6I9p(wF5M;xwW*^=f>5 zvKfF7g-zHNo8=AYf#a3bWv-ZXg^y8)nBLV{Tt6zIyuc)IeerTZ6II_C{qJ8mvC27} ziJ&KU#J9rFpJL80P6E6S8Ku`lpUH;i()Z>6UTN|!aHz1ih-!xc{6hJFMps}+8N{x2 ze-kO_RDa!T)sXIiR*{3;UQGJ4#r3lHBd7X=#G!W9mv2c&1of;KbP5hTMD$0TopbzA z@Z3o6tS?Yes^Szi0TdZ$I&SaH4+}lS#JFBl4Cftl7=9RAFLi2}YXG-PDEHxET>%5e z&yS>Zk7k}g)AIjJX2P*@klNKeT3iy$2V7E|>Zs=ru7kpPgz>Ri>ByjM@G^2H*5vWi~3s5f(v^*bwsAyxlYfc>Ym89)POaewFS7 z1Jp?si+2IghzfftDQ3yE4eOr%TjB~UFsf%Ver||Zyo@84o`(8`Hdmh)o==r-$l^R5 zqTtBu1aiI9eS;SV8i)tUGH-TnEvzUI*5WrbIX)cb@#shctZk;mt1yrvTeLXQj|m*l z^lj!idmR@v-Sgf2a9NC$T9m?UP}L&Qt}1~Tt(in26ZwbTKD4h)2-{Dq(vL@+@lf~> zQ=HR9*afG!kd{U~22f5wW=8&$j0gKdLUBsU7^nG*D8e19*qB;G|NC>U9Sr4&@Bump zR-v&l*}mcHrU|bAmJ(_Fdf82ieWI^u%jl5%7iMt$uYF@-@|$)P(TQq!Ez|w{oDSS! z#{cN29ee>3m66M}*B!&X)4G>BesK7IgFh_4;oiui{39RfeMrs; zQ1f4)Qgg75C}{}-Ugy!Ugx5I5%Nt}e&Hd8kLevrYUajy4Mb`EWna6|6n&X42?$2d9 z|MmPsgq-piVj#D_XYVZ(wgicOS#}!R6Z&;8VHY3e^asYk=Y2o~vu?mP(&9#QlJ&`^ zI{neiD%#iYCdZp3)!!WJX6nA60VmAGvuOCCL;AivT4aTcW7AsM^JZh9Dj(0^l`EAAKm`~c5QSQ~hgx#viHKeCs0L_*0Gpn2l zOq`88(LAX3V|*&x6n?^9;)LHR%lM`5p&zI+AYs2FVAS{@iFkV^C7c`+hNg69qC=( zJAo0tj0I&=FaF!Ym6obM@962Z{$+YfjnsbIZZEYyD*D)_@Ws0Rs~kJ zVFd|IcN0l(m!XF&oWg+>2?68ntcA^K@PMv$x_~0%(Y*w$v}7Ae?1-yxmw%l!MS}EW zj;PTSWi6!+Nx6WIIMd?a_&z^rdtyejP%n7dC@3)$24RN37B9^deq0i6d#Z>A z_@fWu_#`B<;w3|)Esyhr#v|ps zNaF&#&(syB5sp*rlMC-lF24_mu{O5gJYP@2?60P-^6^F2k0a;9o6?2P8N!X8+Ga9$$gydxyUj*GpT2!Gxp}6fL)Xk1Nc`U!xe_r#x{X)-V7m)&Ww$K}LlddzkS zOJq`JOV8&!^Vi+?9;R7Yq_8>K54?8Zc{N9zB1_b0To+i&O1N+tJuB%8y3__Ua!oLxk=q%3fj^$bf+yW z2EQoHdg%IUJFD9!e<*m;~@Dnm!L@o$`|;wvbJ_F2_GP*nWHTY$)tw&DLGNuYValkeh} zj^JX?JIf5ET8sS(cy+PO_6GQ4-Nxo5X0WeEsrt-Pdk&k>Ipzy0<&~iFsl;*@LYL!q zKtcw_sTP=Y?!pZlXQuO_&vqJ&`)=6i-9uwlBDk<(6*R@If%AKmd${xDV@1)5fBu}n zoa1aAB<&InMfE#8B;7+SWt{ZT-}vGDl%gw2pSPaVbL?Vc`1sBA3uOS(IYD9YIt|72 z1gP&}=@g=VDr?AnNsx41S=OM_5yo?pJ)HA`4*GUA$v2kF=XUQ~I8#9aBc78@{|7$T z%SMU_JtKIO7uYXKj=SiXqbM<%nwFa4vN$2P(!GUBqFmg|liWBbfZh+2rOu_Up6ci1lI6rmdI>h^26?Ya09|GHZBKE#-vTi#9)S`T*P@vM93W2AvM!J;~%=y zAKmO@v8%n-1D`PH+R>3xROG2wNW|R7kPP4J#P6C7>i0|#tepkT$iA7SAI7NojgyyF zX@-DSHK(Jzhy?`8CFvzxo=6rbyXokb!~ZmHVuqsl7Z>w0UPu|TY){D!^MJU3Tt3BH z%}gug6Wz3L7N`|l+=n>p4TwGpxv0y&WhLS%8^?}{7b1j&j z{y?Mq8vcXNW~Ta!$d+Q{8>}9S#7~>iKhpNnww7uZk=$>gy!X+oBODAg8=Y3W8_8S| zaj23#j%Xi*YKF1Yu@9vfWzXwckz?Ysh`fmdg<>lPOX}UC3FJd2ailIUOd&ZGbMkdl`m?>`#K9c*IO|iKA;MJU3b03<6&Ap1=xFcsv zM|F9bS&anG)k`LiOcRZWJ`19JHBaTImw0(HJ=b%8Ua$Kg*p}^8 z7foO$O`_Hr7K_PaB*ArF-jtl(YJeAFLIF(@y-08327!>ihMO#0OjQd;^X+yl!CZ0k zyo<7&BvwqU2Hp(?`XkUT3i_R=+xHe54QzLxy`uE)UZkN8^lGA^CY6v6R`x{dOl2rp2-n}#)B1ozM^N3~g zez6S@DnpC_VURGkwtjQ-oI2R!zbbVMn?PPyYRduKyS6kc$!W(DsG25$--hDN=s1IF z?NldDe>i6%iZ}$tk;`ux?u)i(j!pE@l7w+-GKQ4MM*st?Bm+*&aRevQj12UOfIm@D zG|J_i>?)+g86Q)xN+H7JB3rP)P4Em%R5>+>Z}w1CNKGE=M1tfo83T*H6i4BJg}#FL zw^*4W@W*WK0IBU+P!URJ@ip2?$V{OBk}7u}HA%5(*J&yOC%DsDflP5=e{1x}VsIoT z?9n#C2bUx-OE`>wCOY#hO>AaQr7eK{?stLMKbdMBBOdiSYCkFn)vG;}5Jlh>S*s#L zDV};p0u5vJPQVe)>^ARceU`2800Er3ei{qR@=&AHsyq(H86s{l0V&EGpf7J>jf*c1o+KKEJ1sH>ps4FW>o>;x4_|NpIpa_ zs^G_%n@aT}O4V@l+X>r+^2_fxN92%!aRDVXNDrhdyS@q?0cNj*P(rBSpmk&@mGy36 zs3B$p4Nl?vvnG(Q6eyKx3rsIh#T+v|_-;*3icwV-?O2}xrVAM}0tBW|{m1ia5-)#m zAAsPNY&{7LEHCr#VcS`rqo5M9LLabHIb0UMaT$zr_i#%pl-o2#XU^b;w9T79o`2Vc zw4v_Cr~IUR6Hs&(HQ8|`BU42WB^g%w_+aT{r>Cvrn>09%#HTK4ndoG{Kz987DZCr^IzlLYMl@aXcc@_l}WDtBR&BY>EZn#G@k)pljLtn^Z03zD zH91B;EqeVvn=V`bRAO|p`4n_6X@3ej09Pdz+6mm06`F3ay*m@1#jzw5{&{95JX)s# z0b;vQM@iWW{WE7UR7;%$o%4 zqGS}9h%oR8dT(D4$|iaLj3^Uk1GP=JY5dgmaS4_WvoRq{M~A=Q3Cud9<=T{*tjF>6 zoMB^^J;ZYp0ChAK*Wji8a6xOSpQiC3$$w*8!R(=S0V+lu(>^2p1A2>^#|~n^u-42% zJMLV7Q4w3}`fB;+mbEfh=R@CvH~GC-q7%OP<1zZ%HcOsNT%7kiDXk9e_uAd`z2lmJ zIDIME4r^#4b0+A(##=u0V*mRq-++xfg`|Z_dGK9mAlXBT8_{T93+*l zzT|;?#|L<|F~&Q>Mm-_BcQjmVdu&$ZW5ZSn*12{`vI-;DN`aBoqiFgmpQ8tj-j7G$ z2sS&q(?3q&Da$bRS=;>%v5~DqkyW}_<^G-Ni(HDv z6@Z~5O6D5#i0upf=td*T&>89J570Q8t;bvI1V;VFm zKrKEDupGPnmNl%Q-EugXWKB&9x@UfJyL4CQfwm0Z{ZGF5QNEXLhLY+&D#H}gxO?q@ z8kK@VE}CnUZC3;hGHPHEOE_K`8Wj8dREi$208}5%c7f%95ivIEhgpiRG%z!;_uuSh zClx}><0V#aBy`o$k3NhnRyQiVj%16@M)p`zgR~%uUQJR>A$6P>5OBvI;bDj$X2jl! zn}AKgs{i`dxeQ@Tteu7}a_i#0sC_np@5<7;lPvNZbI4*q4JN|-l@9`~OTgOnPu#E#dUf7cb z{nj|HPt2jnbYYd^@8Hfz`6$ap?0>mVNHw9-^+7YuBCy%6bIQZZIN4CG>*4{-&1>-& zE2b-Y9<6hswJ^CC%hk1Q$?Jq+8&mDi|4`-q>(ZlI3~_V$5A4|HWUS@)p2j{cP_NE`4pD#RCHAw^ z4m2Sqmya>FBcVU{X}cL_?D3Yp&AKz|`lCS#mpsIUmn3=&NBW=3EGJIpU+vwP!(|i1 zm&P1xqk@E{hm>vkVUpnM+EWrY)MA4qf!j9Qvg-^xrlBZ}OF)K~_rJSBzS!p;A|2}o z1h>J#Btm&jZ^iod2bP364VlauI>%$SGOy9$7Q+wy3R4a6uA2HrWe5B>B*&!W288wK zGu!P7H*C06SmzB{X8iYOD6p8%atWZabiNhIx9^^*Y#+`iO1nS&21@*xf}n zijMzdBQjCY#?(*|)1$)F^=bbL&PU&i#Y?6I z%lePWRsxnaUpk+4lJqS=TSHw%lRHXH9W}bCnNuPakH8>hQjXzN4xf@S&8;y7nP_TW`ywQndaql9caFG)>ZxQ)AIW+bHReXAi&FnAWg|D#^y~NP%pvRBu3tkrWd@hy zn`#IC{($s5y@^u+HW4p>AvALzr4|^gN+Volg=znpqOklA=D!X=ekXlv3T;azoY5I({0n+o3?5bV+0+fifS8t( zEE@;k9O37E0TBIuHjZzy(%_!}*tczsDhW0ukjU5-NM>Gw%C&go#{Hsc6w8qw$CU;z zwDJ0Bq#s*-!l`%#XC)|!2H#fyQidM`L8uv@+P_ytG)|+#)T09Ke4fEq!OL}c_G7#< z8M3m#VQe443^RL9sdnKhTno#^IjLhBbC$vRj=3h%iF>w8r6i;#3EcbP3Vgo6^V=`E z?RYZ}U*8&b5;bRqvikJ+YEx7;{!hkdieZrgWdbUHof}?Wm$}~jz*vS_s&D%h(5Q2e z9>(y7d2hV>B3hpx?t))DyxcYoL2+QRZe?&_rpB2*bH6CTP4!$T*`B1 z`5SW`DcT-5e(4SN6d`tRuGg3U>`-`0VRCq9e_h_8sbP)F)BpDG23VI7KR)!IlI=wc z0iH6U?stdcmo-Sn{r}vEUirI}59HAi6ShpMD5nC6TQ_FY6pgw0dZ3Fano1mpKqq~B zVlcMq|DO@S50wDCE<}!|(AP@kBk-5@ZabXCR#xA*{AWTG+_Q`C^FK2m@j3eB`pWdR z`X`Rb)-c^u$?0#>x??`2uvIKB$Yi{~4dy^!mP$J*1V*04g3AvBKVZpuw`5;Gtp=Z; zbylAr-(A&)ikW8q3LKP3AjBPwp&=8-)j`*g@NzQLj-#;UXFFv7^b?Sv zc@{*Lz8#II*n#~TptZ@~(^i=vCNNQF5W+c==3qLsdKC6#a!1cF@ljy)qy11v!;!_a zXY;GUf1LkZ$Og;x1=p|^vh88QDfa^dZ!FquKGQ8bbtj>q{&4-@UvD=AqlpFt`GKA| zLL$>JLtM{=cnISe9x7HC*UkqhD`DgrH3YEID+{Lg!+~dbri7;0%EzF#^_TIM{qkrr zE(A7RrN^RZZeB8@RKrvsm0f+@G^zg{7BID8B`bY5*=-8Duc7{t2VH@YGU}>oYxiID zMCV2|4I^`?>2boxySadhIdh3+Gz~P zLQBrd71t^3PiqZFN{#NS8LuwxLk_S$`H$oWGEcRV-ZOftp?y8@>Cm+JO1$FGsJh*{ z3@L*35c$iDF|Mr!%ibz#Bx1{DkrTw!bAnQiMGyy|!X(*-34?DXo=eX3vc2P0l3Mjy zg_w5~jiEuqc`BIZX3!!|)nwvCK#9(6g4kI;T!}`nJv-}7`Xv_EvrHtFG$OOmuI?bE z(WkgEMfFHLS}g0kPvEb1?K8%hv8IuvWmbgvFkSrMP|K5N@nm!xqPYFh({2o7ZN(=~ z)NYMnRuo*{noXMcMfes>pql|w|1D|8-@mg4ps;PUP0m+2aF>w=%&>FWBopuC;D)Tz z3pt*X0;BS$RMS7NE*C*vx3MU*T3*hZj+?mdyLni+jNWPIvt`GhIUN55*7t1;%d3_r z@QjMEMov(1-IRX#F5xg~lZ+8@u2_Z%&L%1*En6ryoOMaPv^ic(*e0)ZkrHH;DANEA zat6MfCglNiO|Wy4?|k-#k!os#Q>#A$2VVI=QXj_28F1@!F{{+_m4-iYZpQ7i!oYwE z0Cy5WF znc+Cxi$hSyNvfZr+QmQKl|4GR-aAK5M`q1h}*QoSO zX#{st%rNAqGdqcq(+F9yBjDl=gMU5UEx1OxkIDRRPMq<%FYWN=pyTv{^7AYjk>s`& z@RqD3IvDe6!X!xj(*+l!w9Ts?WBf@ZdhxX1-~BPy`w;%|{C!iB_6k`d&mRUL%srZ% zgC`PuTw$LU<@%CI`x9&1a;3;Ys8B5T#ATpO_Z(BIOw2x>B~_ui4y$Z1bdI?W!n(+! zN2k_|FC7&<31slS2K0FNixlvdi)8F6rhg7?ye(%hx)dFqU(>qFva{So8l8j?Nk2M` zyz+n2uX7#HQnlj)<@v)doJXJ8)xw(o!u*nvFPB1Cmm_TXBO zjcx@aa|h(lk6%=*yq^EQX&1>&^v=cDIbRP+LsP_+&H8X81Kh+jT{tDg80wXX`Y>eJ zpW@B(i|eDiNkdbtt@6*27;am#!UWuGzb~@no-lQ72|Hz>cl39Wmi>&%_1<40Um@zh z&?*<{WIj_jb}0m+lxK7^A()0I=QtuOKAgq~6Y&d!!UGT4@CjPVR<)3gVFA(JG}?(L znIC%zV=6iK7`DlNbU!L0r#K5!5q>nmQ-*W+`QnmWc+#H6783jUp^Ov*L`f^1$6Btn z^$Q?)!{l|Xa^WEp9bJ{&+CCk=akZxrCiN%^W@8%8R{2ew7a2!NJaO$8w~u_vcGMaB zGV}Ma&)uR7JcX0?GsnsP{}=%k-{1H*{ZN;+AlAg3nLj&me0 zj%og#%yMKPoZ0;ACQ`bMg6ePA_B#impT)MzBcP*SvXuJovt3Iz`aVDffEOv87G;Lg zzJ;?a5dWZGaz4e!UCGoiiH7dK&qUI5D)Q{2LVz2g{*sV&q>&9ZU7U=u6zMC=iiL=~ z2-c+Ru6wOuul99cvFboY%FX8Cq#3&OTx5^bUeWp4k_zfPnFzkb#BA}Oh?wpuvc{7a zqPCFTP~vknXlJgV|OH|)Uy|PlAlS&AmPhu&|c~EbEEU1yUI@8KJ>@3 zw(-Z4N-E}69Y2fT3`{Tf1ZFrVEgzX2e{Q_`c8hpr-UF?h&O}IF(Fc$A%MjoXvwSFVQc+cHc(%2!5bFxiIX>DCm& zi(9IOg)EN8CDv&f8pdDzW;H1L0imp!(Qs7SrOk7V?r`*L8032*Z&zr0o^Q+l_H|NX zfc+-;G&!&>uzg)DT`Rw(K>}$Si>o-3i+u29QJ9PtJAY08*bzy3Lzh4pNnRWp*o+~%$Kh@5>wkT2D^V;N%ao7eG?wxE9(5+<^4%~ z_8)pjEnLMN{eD;UGZ(De)JTnT$if%i^||FQ9@PuSD`b^?7P{Pn&LnPPh%Cl1KNl7~ z`&(EpwwPS<4XLL{qwiY7&3+_R+`iv^%kMCq0Uy5|F(_t9_8H~Cv*^}>(P;Ht-)`UN zmmYq9Er)Hv?xt4GTMB~j6_i>bpGp%&9VSq22x0&=pLS(3PTC`rimZF`7}2n7pr~HA z-cPx{I3yEv^Su|(EawUw_KK(7v9eg2D@io%usLygpoY&!EJ{A+W~8XpcYa)88q;k9HbNcGkl^}{m{92S+&Fm zviDlsNo!RpNoOht;~R!a%Lk5R`&5)(mx||BJwQ)y8!AyPe&FA1Ze;Qtjb|+6AIt0q zcc@-?#GpFnkq+Dz+p~qdIFnk-!eP`t-WawBdXlb7ZB?N;7qlv?^1dfO+b5%=4+*=m z2o5Wrs51RTdO)$iKkS@El9+2wDwK_^rEkb-8naE@0rb)A)7w#ir;F*!CRJ!gaq#<7 zZDSJ}c#cjj3INAPqH{`s3r2lzZa2SD(?-400ay>{y@MF;+F8r@$`qIctZikkTsL=t z^sU@j_J0fR+`?m2fGiEeHPWN5^4C5W_`Xc?0^_qoea&WZ6$a$WgiDuFJ5^+!2z?l= zfp0q~B7rvS-ZvoO;U+TUA!7E;LP!p7rCLA_;{FL4(8@@EZzF1{O#`_1L+go-BjOpC zA-nf09to7(Xz)Q~b4+{nJjX9AG8ull2GHifIAVK*RWWe*fn>|gQ*i>!?9|sm8E;QL z?vg9qYZq>a+)3`MVs~!i*u!Rb+mB2V_0puywH+tVgx7iUYM_!i=P$cCP(9+vr_JUL z71?lpqyd_8Xc4)O-2DfiZoOx$>HOUPe1Zx5(d{{3Mv0B4HT(a3INh}jR%d$Kg;jbx zPm^{@rK5oO_dqN!wK8$(u=GmU|GA-?Kl4y{{44KHu=< zj3Lwc{USJx#XxT3h*GzJ!ul0%)KuBg=c20JK(Sv^*Npxe+dbz$9Fxw{Y&Xk*Afo4A zYYhzO@_7&;(W|%-&Q!uIkqr#x$Q4yO_}|0O(2wex;$67{yCZQ z^L$DLvZ&Cz8+=-Hxpv+qXdSwKq|#inA!^bAt=qG?H$jg(^V_)rBrB*{2->NMQYqlT z*i&gxvYR-&q`0if=I^SqZ=KuxGaKKU6e(yKHz#X?7VKs+Kun@i>Oc(!gtHD7%O`(f z=61prtYh|{9sy)09WwctD{AVA1q$7RmkcRWChbZiy|GQPJflI`xFIX_`)m#$K)2le zH|qeNY)4p00O;t^LXotQ*iNW%YgnF1e*N_2@z9Ebxb2prZB8Ui4zt1xfJhcC<4>r# zn;#Ha--bWXoY@H)wMA^?UFy%$`HD+!iitc!@0^73`PfcbXt;&%Xqy5;#90n8J!p;( zNX?g+Fs|qUsPobZeC0zwo$Tg95AjXU1=T$M0zZ#~sgW~C zb)L0kf4Bse=SrwBu1z6uM9>|$sd)BNpJPx+pUG#RKEHO;wtoI}SC^`Q>*dO&#>OH@ z3jA&CAgs3CgAq(%H3VH9ei8rL)AxqN4ht11GDXMW>;#iJIFxoc#@(NckPcRs4n~ts z!7AtF*7VkX5Mdo(^op%w#8s4`7^laMC>%rUWT^sljIn#eQXO-tn~4YN!q znJY)I2ap$2s*w~06d!%Y;L=Evq;VLy{Us#2NBYE0hj z?_51+_LWhLdwB4Po>!~DK2zOfj zX9|MJmG4ice{Dx$XLknbj{m+#VllkIIqyvb8J>#3!tvETF%fmP3(}V zcB~SfIt@*;0=H2%{!3m1CuxUp&Bw3l5V&!Sf$nc&^^0arh8Pj(WtgCbjMJn%AF_o< zR>662F7`|D)$ta+SfEB;8Bi}vsF(xYR4x8 z8B=D(@3KF|``P!i1MXg3x`p=z>(kG@{p=+sy#=Jx|0gzM)@gK7M|?&Hv3r}bNRM!* zG1_RfvcvCc=b+xC^+Oh<0e^?onzdMgYm?|ApJGLncl;b{JqwFa@VHy!kA;=@FdMDu z;M;eYOXM)fVeo{&xS<|!J@2a7Pk54*x^9_(+9wu{hnjT4wv3uhiFH&)am6&%{EKec zIhQ;D*o={6Y_uBA!^ujU<3tu4#R!i!xrXJJW7Pxsh z1CGbw^u<40j=8=mLa_FV&*ra1W$;#2!bOGTf5V7L_fj$dG8_`QO>;vHX1P#7;u2Z; zYSi;be#ebwpZzoIYtwio7C^dn26Q@#X5pN%P=QM2PuSNZpiatyMeZ-^8AHIc6pmjn zt(qXZm#_g3+nI@}sc!%7Dc8GWN6Wumj#|^%5buT+m63t2hllfrEA4 zYpcK>xfaMLJoWcGlTv$Va9gk-+NOHE#}!ZykRpS?Rh9K(rNzmwtVUJk1H94Te37S1 zt>8E9>p!eHnojm3IKHcYr35|Q>K4^(W>udq)64dWB06_7F0F?)3cI7KkBsmw7M=6G zTF#qA;p$*P3oB=9KF5&D!^m9ur5y`hEo`O7xWluHkE2 zr$1`vAl@W z%NXk2zV6jhT~%c&O)>Fs`L)l|%EBTfp7eH`0`apjv02ZRH&@th@8sf2{rc;Rg7eS0 zxw$$WOuty_19vk}x8uKqTnn@y^M!Up-ItnoT>@j(BS$|tOSqMYW-?cC12$Z2m5ey*6598Oiie=TJQ_LVt|W&kitm1a3)N zVaB1pl9cZQ$F}TGo6$N$Ci_6f-s|ZfQ5lI^FQmcV7FrP`y+r^Fak$@bgT3sYY@cAH zqo`_)X5{$QWOl;-(SdDmZrn@aqD;Yz;D-loJ!xHR-L!pQnhLsnqVBwtgoC??*TPn6 z-EKSf(XYFaE_&!m$8Y|^ArCeXUfg49yD~^<7SgHYn&9lJKiZpL)}TZ@(2q|fLhAJn z-f)O=Q?0t}yQXp2#YDr-LGNhxqTem6XASIBJ3M`6|CDK?Gps-hUv@vo3;4#`5skSG zB1<64fi$Xu?!56Pt*>7Yh3nB1AaTt~_ z-3-{qf6r%Y!rAVkno-B}O`gU@z_e}-8^-#2IR2YqA(blU_$0^~NM!f{D5?R|nto4; zwY$fyoX&xHI1-3ea5iyaF*--nq_qB78$r0jGP?ERuSIH*5qdX8PhZ;n{tcB zXzCUFR(k%gH-1y-q=`>H>lnK%VoJog@Gl0fm=-Y6$Uzg?2b-6V@X)dvB~4aEt8~&! ze4rD_-F5aG#Tnqi@Z5WRQ~NJf_5w@CyM_C+K%&zJr}VNvPVh3WYASdArX#p0J}3S; zE@G5wAbQ$l_x<7&;Sa~#C4y8w>SA7QKihYbo35VK!_UEZ0L(a5^_oaCe7?oOnE_v3%Wmt@OQa>cbH{-Pe0>; zJD0zV9Wi1hxZCE1xL!5$rh0~~WVQ&C)7Uj}f<0gLafg!m40`oh;li&R8)5TgFe!La z3Vd+RLO(R61+R}6m|l@3X^yrKuqY!gXYJ)j&OP4u!M~DP1P5o>b4duAw;c;=E))4~ zcsK?o{nmc}OL5z24Nq->=6z{TF|58aCfR7j3bQ>NSQ6nryBDkVjiza^z0OjNTqM{s zG1N=jb$pH{IFa8Xu1AUH8P3(?t#*m9rh?Mv;=YJKRR-OQ>wfKTTGaw5g;jtSqSCJA zzsRqBBr8G8x+m{G41)fslIx*0a4`3>CKwVp*yXFX&nOF%ujGnYi`wCjI;gsh$94*C z6#vK@Rjq&D0To1&qW1kIIyMp>0wU}O#_Q>QI9m?DL?D?*Bf!kYk&Z*>j;1Ss&v5ge zaKSn#H=ySqyWwUK>3+&-nQhLH@6M<4c}!J))5S-ffu|ve1vQJVGp4`EaI;icy>Xa9 z@cSO`$q9Ka4lIlX3vT}$Ub{q?p|&Lww9%TG2>9}@q1BMvr4L*n|Mx>$;Hniin9@2K1Ga|!0-qcDz9f#L>R{m8`O z7m3i#z)N1()0#yL>kKf#DZZp;10mBnR?-6s`eFXO!d90h`#e7fw& zo4VzhUDB|t)v@QOKP-y9h>YM}u~G8ir2G{yiauF0VwU0UBbSaaTY|y24uB5YX|cf| zmozYN4no92E4my9qe0XIM zX2#yHZL?G<>YcsalaY(e;!$7!{txCb*Tc(~sBFFEoLCEI!kQ9Mu zIR8XTNku@G+Ues$R>p6)3xRzkKArj?{#8TKsdD`nzH(tb`;C>L;+2Vxi1$p|Y+S70 z4=#l+?QL0-78~D~6z9K%QhDYadDzoG!_5Wyxq-C1NUSDFv=zR63uGY`-fuK+7viHo z@tVX-AbX_QLm`Y%J$L=)zY1AIp0k|@!HYJ0EQlSz-|z$nz^*oi&j_ zt@3U&qoXK;Y-jPqzrv$K9adNY`0C4K&!31`3*BaB0lgmS`S?BUEvMNiOpQ)*XAiNC zUyrB7;tX@n&a`WC2is!ImMz8#l4BFC8JE;Ui|=}k&LentvIRJMn?vda7)~zfHSw1Z zEk86_z5D-oddsk=zV~~W?(U&Gq(gF~q#Fq->6B(j>1JSPknR?wMLGnA2I=k?q&o!k zKYqT??>R4c!^LpTIcM*^?sczwEy5;dKeX4Z*8-|RQ4h9|l!B4!nhg0CLXTHnU3Y{B z?PrODlJErscV^C65}_by8FajL2l&WCPl#>0WxVpBnGZFPDZ>2wmoYfMYy|%|GyIEy zHH2{nILM5W_nG|mmwMcb8_uU5TL+*JU#O*70kIx^u@&IjP*xQ+`ho7YOPdOSKS77} z$v_jj6**Mn`s5O-LD$5oH*i)(wJbOX%BeN0m_c&Kga#1PF%6J>MN7oe&$*Nu<2?Ol zWjM6+Et_puvDdiw+c&-b47wxLe|5fNY=ef{ge;KT1FDC23zi4~A=%PF#1S?lF^Di~PlYQXH`Jk24nJexMFLhj>MR2;` zhU5AweWF&so)c2K~~ZSiy=Q}xX7&e{|tH1HyOV_f3AOx6zt z@FHL_BymoEIWqdG=U;zP>>&G6TaJ|BybWN$((p;16d(WImk~}Z8|}ja@#v3ak2gm4+H$%loUcZ4m!Snjd%E#@=ixThW9dD&51S?40C$;(w$mV}h+W})ApjWS+ zuC!_$>*4Ty<8+YHF3r#V)|`x$&K3UgxM<&1pA&fxey5V=`uw|NV)_V+*_Eb}i$TCO zXK~YZ_q=j>x3~fI2+UQumD%|Q|CBJk&+64DyUGJZbNjI%qjS6N_Skq2d)4NJ|HZ~@fZn$vM;a_3v zn7VE@AY>^ieNp*$)-5Z**^H^CukiPerTR5xVTmXrRw;lK^+7t4d=l&-6HziwpDu0u zF5<@#7jVENMEeG*PQpK2^#6PT*cH+;OOz~87=olw_CTU6KSOW=MhNmo#=*@p5!=v)Y#c;=W049NW>2$aP131H+mh!lnoktOixM)J?( zA>^1RmX;h7{mVn}`r?N>6Z@&qC=Ce*X$TNa{t6OnVMKyZNrwVuGyk@D*%?(r%q~wt z7*dZYX#pwjsQeS7VlFaqgEVyc20^sVEf=S7@olxAIO+5uQf4uKUimEP^pS);Cm{`h zV*G!dRzeU#1|b$@Y^Xvw8v*{pac~t-&4=zOH^0qWP=O^D|u-;ML{3jA2Q_WThPgxWAd z1#f+EkWQ2ME9{5$3Gkho7Jjihq*@~GHO~6Oie8(I9QH;UA%+IY@YJz@js7S929iN9 z$7%xqJCPWAzxYYNO=AhF(BBd2qM!M+eG<2{LBN{KKnmQ+%0&6_GJE!q6@Qc#-?{d_ z#|{|+M*v6V1X-0JB|fbyL47XaU0IeOe1E<>(J52c6Co?jTwA!+v_Bd#j$V_>ZUABd z$r?&0xv$zz%e%|jA|wF!Ke)<2t1Q?L5Co2U?~FU;GgcBe=s|5&5$ZOYvNZA~-nriu zi?3T-8ur++VP)-_saXEGlen(2T5h!QQO^~+q@GV0*kY-nQ0G+uU z+Y)^h==8cohE@!l{~}4|J!oj7&D|y&Ig+ru34y$f157OHT>GeMyD3I-8ZI{DV5^4y zZbZ`lu9!RYDxJl73KjE?dm6LZ($k2~M;TcXFs5ShG)wkLrQgDr5n#*sgPj1vSJGQ3 zcSM&ofh0YlS{i~Bs@6Qb6y1Qm)*Erh9l?h7VFD{pCq_?sA88v zJ!}OW=s_!1f8S17B|V$nNxVr!wT4s1#08}db;UanZ81KP>wrfcDxt=%JP;^f+f3z< zt%)_20^dg-=)vWd8A+vUGDDf42<3>Kt-6pz9z{LG{v0=k6s-)25eW3F;;Dr)=w&SA%CDyDxA7T|-`#-Me7#Wz*P~9?9dv<_Y$IFwG9m;nJf{pH}qFZkH8c{2b2V{_Bkd-F7ZhSHk5|XMG#DXT0+%`r%nbx!JvhqJ9(SM*^x(2R`&Rzz$~JmP=7tzc;mKV&xj}USIuorPer0dGO82c1 z@|Pb(Q+0-O`;|}fiK7n=DCl8p-v)9y{3e?|)c5~r>s*IxC8T~#Zlf&SAYDBZSe)G9 z)SK3K!(}vR$Q}^u`Qr!9tpdIvA}^2Y%P7qMi4HQ~Zq-B|#D9{dUkzzC6b?F*>*U!r zv;!W_IH|>NeLD|aGD;Zo=7KlcCm%$>g3M=!ylVfQ`0j=R-_J@SoY%uI3;RBm8NT=b z*2RBgd@;EIe;E5KV%5=YzX8_c&4a9r`GjfNu?d>LVv+O~^= zd1t`av(DKtJKzHFM}<#0anM0H0{J^UhEPQoegzPVcV zoxghh!(gJeIijmuPLQThkP^gWVu|$FdI4&ZF~i>T{Gc({*PyED@m&>(4y7yIr^B_OOvjMUP&L*_0SzJnaV9s9mP&D-Dp< z{_EGhD=WVPvkw)xy~gl%LqEN+`_FW%&zG7gOur>&9R8d|Upue5edn%AeLsJE;}_lo z=csl3|D2YKPuyK-4+KC|xq-*Q2KDXLaeu|9C%b?HUiRq)_hP`&JVkMmu_e@9&a6VDrQ=GU`$yIYFRDRQe9xUiKE@JOsRTWjJ?U>CoucZsW!y+Qk3zda<&9^X z_NYOa?mr!CAWeJB6rkfDjq{KL@JO3;52O)?Tob^obPYrkkGdGlOJ%Blc>SzK$@`pp zPQm{JnUxPcN;?ygm8PhTQ5qoNR)mIsinl^ii2HA9ZGxv4F$d!!#apffL>(jFA$SBn zyvp~4c79z&;4>JpPe&`^U*tlyoAD z?jns|LXcjKS0=HGu#<1ILD_+%6r|E^sF|)}h|;q;Gtx}O(~v0Z0%42o3ZS~J5IrSM z_8y$kc2`K1v!b3AuteeBe5(Iu(xXwvL1Be?I1ip~0WbL)m3p1r1yT{7v{8_y@~JahA%Yv;~PP2tMpLiPMHC=jlaK73&u1L-ZcK$ zTZQ>O&*iuzKeQVP`^*Ic;Kf`&A`&u5VLFGykUusJxuwZb{5@O@fHcRuk6aJST&^Q9 zufW@j#OdAsgrG4y@=``HytS# zM{SeuKgm^Wt7%{7sZ-xE8NEC){)+APgzV&yM0ahbB1d`A_veHyp4zs972v=vh6;Uc z!H1F^WJ0NV?HgsHRsHcd%?SGj|Beu^-Z{}7l54dge$putY8}*6+;U~LJ#(!!NptiI z{VNcsWe3RVnt#=@f$5bwYrZBDc8EaVC&8c<(uVdPv9E6tD&HXTwr$N`eAhXA>HdI! za)_%Hq1wwUM*nz#=DqHfH@Ns$tE>tfAawQIAR=k0kTt*=Q-NbDcnHJ^xpmup?6#;- zX!2XJX=X)GEs%zeLp+hL;zEiCep)q~d*YclNgd-8@hg<{xu9a~SQJ$^TqN74W7liJ z_yMekd`ilYGfdQp*T{#j|NL@s47P~)K;&RoO7iv8Ap< za^sf~JwuS6QNpXr=`%{R$FQT$8>PtvCKf`S}MNHzVxglmKh$AGpo4e9CV zr`Q2e+UAm(l^7}?klJ-yH~86gElW#KJRG+D5l6XVxxj?;fk9$&s1}G>AcA%fw_-J` zk|p|d8kba4aFV@e6nQBzAM3ISx;cYXF|%Uoh*S$}z0}^@ZaJ~uF`O+;e$z5eqr2LvKn0>7nFU3hL{I$x{;aMB<9;| zd{!nWS-&7)id1c~(e;lEE>23nzpI%U$b|@{AUoj{(6LtVA$So;>$;(syEL96Zee61 z5r{0;o;;><)ggb9)&@;6*x!ykhS_`d6;`rQcvXRaq4EcdritZuCTPShd@KTt@lT#6 zGMKrx{|d^Zilb5w2;)O*rE^yl%J)y$_g#cHrH9!^Z&s@^W%0}SOS$&Wa|erDUuR@i zMLNRGEws{3D~Ow#sY?nW97e5oZ*c??+0qey8G#MmW@oxMpN*V@7p&k8gMN(=m5eWSr=CNP{H_y(Ajkd+9xmQ+h={ zQcH$+XVV}kBY7r`WZV^LsSR;z;p!OT69TeQS<_&Ad+}< zn>FZZFSXwvE|rFUf7UDtSiCz=CYwfBP3W?(>{%5|FeCwmq!oP$+^{%cO6Os0Xiy06 zO2sbu6-!l{b(#{-4@S?;GOzj$n|Bdcf7V-0=re)g9=~p(pGXYFM>ebZ+USaVaD|Rw zce<=Nk1Qcj{{hK*k$C)3Lu9wp`lMU&BC}6Ha6vOL%`OVL+kaO4!_naT&@sM0*q3Gf zh_#a6WSHP1HX(ha5sRqGC(mvve<@p>{VMFIU$QN+u8&ge6q+!vbr^u;{-frp<{-=5 zKbBrJ!4dA9eCkl=?xZ@L{Qzi>K?P=>n+=k47g8pcP-X+-R5(%3$B)~O-O#ju5(Ouc zU6XOqK3@npD`-LXZ#I8Cb;k9PnEn#>2?K?~8R^OArPH)t1LA(AxFta^CVw=KNgg<7 zbR|&BU!q_^`^y#AW%^)v!Uycf)dw=V%Cm-xMg z6n|+3pC`5t_72kD2Y>VZ`bQUv59fW07kMjwdbt6h&(=X(Lb6=C(FS_D<155sb+TZ9>hjba2h5zqweUHEJB+&*r6#L zeV-49<*pbTX2v!dcs}sEaBSb)s+WQSY zTk+~?+U@%<`*gKpV`NWgf}fA64KKb=PJ({i!j~1uY6zX;ZlzxZDGAqySN8``Z6vK5 zVzn7c$nYG)*5c6xe4nSQPfy2CuTMS1-;wBq4O|m=*Wg(J5^JZU#{;@>Zu{a%)Obf= z3u%BF0zg1B-4O|+6CL8cCf3(9-IvwnvsD^*8<`rv)M)PCBIOkyhZ{)K^s@}YriOi& zfK>cJrp7i;(azyll=WYZh0rdOOA#z+EgCOrA?UaZ{+Eq?_#x%&mK%+nrxO+~SISk# zi&f3NpnL$i^c^W{ejGOiKC-4VQ14Yf#bj}{yrUNwK&2LNt8{=Jx8N96mgRb(-FJ@Y z5FXF=rT-LM9!VuM`VI6MK(3VQz(=(Ulr8e3yex-IXaH>pHJ=bvauOdz5$pZ@x&Hj! z*fNe={Fo1UqR#d5Pj?nSqw)!JxD@}u=}z@CV)yq-^~v_O%PhF&NIWmo$CGmM{A9bSKF9d>HN$h|=qRdK2ipfvB-tCYQyx4uE5gnv7ady`0zgpI4 zL}lKdAZZ|CUv``*2q(bs6oohx4{4wx5259d9a z+64hT8KTxCriT0%%JU_v;2*e8{L1CB1iF~MDZCU~rQzT#Rm&q$BxG?PR|1iUTBQLw zKxzK$0{pUCAGPeY7?dn@>9KI3z7(!1z1a%NNQZjCp&qu>S_rX1Y){`zw`hb^e5vCx z3Xm%u)DTqSDH>!_@3$*tPLLx6y%luOMjdGeB8#h-Sl6kx0)M@06OrmY&(Tg@Tl7Yj zIyu^rkjiyk6_CFWjV%#kX^XtzL8nYN#@WQac!iuIK0aBfn&iz$=E46%vMVf@n*&;L7xsDV`Nyb8lvTis19&TK{aq7FXl(SO`e7vHj?1hrcNSh z9&ZR6owrYl|R>#$eg$w&FbK{X?(kEu=vPlpcxCM;3p1(?lDkb)Uzz|MEm^@8F0okV(FBu_( z-X9ddqk8YKjE1H6NopHD2_Av^JZ7<%x*YIPZLBiY$aOqc1Pn2kYSC}JfYGwkXefb! zO>vm4lHrvM2>L zNMM{zwX|w1wPBaQlZmFLqMrh_XOaHHyemKO#u-+i&83mbR`@q+e`_eMUfvI-DI%^~HO%^T&bBPk&y2eru5v zxFMmAh?COhI%*FhWGr8nnNCJfZnKi@6Gh)e36v=VtxmI-%mXGiW}^<9W11uR8PLiz z(*!$xwt$0@5HB>m4{xZSUqi@eS+hfhL8Ym_=YcWTp}$ZNUa*O#B$lv9V6yuDC(&Hi zdRmrsNuz!SDjOhw5hGTf3kI$Mw52XQsK0eD{l3Wr} znT>j31s zR0v@L?G!A7CiaB>8~^B3b)8^*V=J@k^m~1(f0(xzhODD#ICf|2(w2}Mae^XC5GwFU zb}bfsCz{SB7+O|N?L5RuSHPcwc*tIgLcU>l^#-9$jP6jf8$nSVn)P?&Ir#4BO>OAO zea9kkZRAM?p7;Uj&3Yo99Dt9B8UV>o(T1=OQN&T8%Ms;Kbf|TL8%TXwe6p57it8}t zg+o@uZqPbRa|(o*Fllh;`{mQupjd4!W1Gc)XPLMG93hl;=57MkzITp(ww5%5&!NOJ zzWYzcg`v93wI_MOz(ypW72rCoW8FJk!f(6Xh9Sxns`8iYk_xi3C-#C7&WOY=sk1El zYJ}9bcR>;4>d3rjE!fsiCQDn*-FDx?cHgCe|MftLczmL9OHc5~CKH@>WfIN*;i4L& zn|s%b+Iiz}*d&-6)iXaPsq!BsvohjLvM~fV z;m4C);v2%ZFw(`pH5d3^+ zY;zrD^-{1>m`p5H(PrT_T(QoXy@CygOAPu%lagKP$WSVyQB~&@r5<1ALFpMZ} z-RYAA#+fC(-`{;cn_R$T zR$7vihDKsawDuybTTHw2Rfd}%;%RIDe4G$1DM?6nr?R6~1fVd`5I`g4;wjYH87Rn; zSTK=fQPS(95ey}a@4N2jVE2l7tAVMWDH`WAlTW~xn{|ymapSx%;(F)zGm+x##!$>& zaLjJ#F2;{{ge%_oh&>{^3>mxkA|~dJsu`{(H99zdh<8aK1q1oPw3TA&Bb|BIgyiPA zvXxX)NL=7S*U^u@YQ~kzAL?H*VWeVuMIkSJQ(xb;^Urec6ej>V+dj*pD-hBlNoruo zwqZOhtbID8opjzwOG^u7!Sr?~f%0EbpHeF-cM^)`{`|fb3bz~=^PTHw0_;xX<~)F2 z?NXaEheo*wWnQ;GJuYd@E%G`}o8>&z1L&AhqW>lje0LFF)W`ESRS;;(cy(=p-XqA~ z{Oz*k#)yj6BF!X;pM21M2BQ`)Q@OY}a@*UD^fvOiRJC;J_9 zdMh4Y)xc|(|6OI#Lf`DaZh=5lC%=m(Rn0Qn49?RU=KNW`*`g_wg<9-u`$`Yca)jsn zl$C$s!c76JK!86eMo1ZFUgNRgJ0a#(Rca&b^AZL#zdjAHpEPg6_8) zD02N-hTPeE+jxBplfH}bw|5;ylRB;rojR~gyY9Ylo}I3zW9i{8eyb{|wTB6_JL(0Q zEc!LKcK*Tk-4=_@-;xG-JHwdzPt;J&J2EdxmNKQ?yle=JgsqmOllvF0cLXLdakK%c zAq?k!{LPp?uCt5I?@?2fy6BnLz0D!R+m$3+1C;pqfM(w*XQr-~2O}#s4%jLtaU)%- z=uZd^-`BQ2TIwCAGxG6|)1^zI8$g{d{`oE4uu^t>;HzEJfmjUvHG`?qKI)L4%?5PP z)=5a*!Q5)1f8%&f!=A#Mcb3#a<{P=gyiTg!>&xapU15Wf!B!O|q?Z71O_ z-w)7Ie6LQ#$alq87=Osbcc~v1(h%By={8kA7@SUgSwFRK|yy2X66_w z|LLt&+{O+hE>(GyIJAQhR6P)uuV()7<1|ZeuJ=^Ld4Z!da{ji(0Hlm^S6p-hJR6wQ zk#BE7M;0Q5$f<;~kt1@wH7QVM=;P3Q59FCjIe5#&2L3-SfP=8r#drFVAz3|ng|5~5{71Hy)mv&<($jU=6%fy`1#{uPJ->a=t^{%t%Zy@!Gx zV=Ra2XRjNz>^7$Dgk63$u(iEes!}ORBYk{4=1eZN7N1oP5EZbBD~_@{KD^6u2kMI5 z?y7*Nhu?1B=LjZDxF@CT;j|zrIlV(OThbU}x1zc+p%n1165#cAOM}cZYYd6fx(mrH zJOZI5y{T6~-l5q+t9@$tkfS&uH>!3`B|lTRw$+Hg7flXMag>`{+*NcSfL|}|8%Y`7 zhx2%(d}UEQS!@CLs2;VsU*)GAxWrvrds`-q zYMq*+j&ilBY$|W~RPy;JwST=yKcG04Pe=8eu>av_5~-bfk~k_C2EP$T_^-(##5>qf z+U+$b}z(-*TZEvt7)oU_B_#iv&|`)wKc|yIU$9A9*lo(MdWAR1$nPlBjMTKMe15>)`!+o_CK60(gvcr8SkZ^+Cy-Fd?2#d6Y52vBNUWNP@l1jf9 z3g846jJjuFbEMxx3AB1>j#3nDr`hG`dkM!VDTLp_()=!YIA#V3tUZA4jAO)rll>L%Y2|wG(RFe0J}& z-9AVo4RdwTnPHjbI_t@C*BDX93Y+93XP2EFLPpFiqin~Q3Kq)-jX4dB>}kY3{*`?W zQKs{L$qm~dOr1ESf+xx=rctR3#FIcP5_gInFABf_T3@?dr`ZNR(R}Ui+@)?sfIUWb zk|q+TFTf9bl}zj~=55#d_%I=5xNTCuHmZ64qQB_;K#>5SLHP8mr8$m?=AX4GL%IB{ zk2Siri!5U&L?-~|p3^sF9&_9=0gVZ`BX+2&))~qd2_q zuT+Mw&n-H`=+-T>WB_-Qg!9BpdUD=(&R_9we|;@}r2~*#Ap)Nly)=VTQqdSp4QCw*G zOiFnz+`UdPNFojK6h*e!rJX6n=Jd?;xg zXm#h*2GiV;h14NLE3L^5ki+t=s?jY2Uo=J@bhc(EaPMx5CTEli-5U;a-cHsB z!0}Tx-PbC4SQfw8&g849r#tj4bH=ilZv(3b8cqIapmm86W5HgZ9gl8(qxXO_lTM{? zqzT}Is-_rm{9W}qKW!K_G4l~d-~cf{=W4cMMBjVyWD5mCKM`b^`4`@DoXJ^9e9=zcD_xAQ~ z^dE47x`hDIZ6PBKFa$fbJGYQNnK1AI>3GG>qeFsQt{IA{u;CNO-qzd4!0^nw z#^Eu=O%`{%I$u#+-{eUF^<5q(c~yY_Ks2)?Ds@!mIfQq8$vhF?YvbJ=e(d!;!E9}^qIsU)vO=*=pjQ}NVVf8**oHwwj zN*=e@(o0K%0+|>srJU>qWmrUH=?VTT4vwy}2EF&$51QyY=q1F>?hOe7yQW*;ot-;< znB`p^jcPdgy182iGeCnAb_P#c@K&SHMlI!NmaAJkKpk{++VT&rDx-zMN6M;EcYiE? zB54^j_WHIc%x-PKOBY%5TZ|ea_kqJ>?%WbKI$Y$pWbAX}82P?Z#AxjPdD@ zU2{RVS@8ziS+l7;eJ_i}XnhhkD|Ir{KaZQ6g#g8009azeU2&Dw$mcU@`AJqeS-jxxS0Z?Zks1byJC|0nNd{Vt z$nIin+n{1i%z%6tZ?nH?#s=IVJjahML-qN)Im=E;+w93m(d2@X`EQ{7>uXnKwP8zA;)0 zym14KVY^LevmsWqBUYjCb>=x2%86xMj3+RPvYZ37vIc9(q*+*VCvz)7UNh|uHcX0Y z>?lQShgl5+r?!2K@>K*!QIo+RLq~?iwX5i(IN6e2XQ&#S&cUb+sA9%y1R{GxGL@PU zcz)p1gJFOimcX1gILXU1Ze z;TcSp&y3{BD}Sum6VY4{`_ff`W2LK2$*E`vYY5d=cvvg!)JfW|M8lJzRvx|gMKMJK-O`w`eTDVVZ6p}td=O63qWft(K44F5oGKddOsb`tx%61S6}0as zG+IBQXwA57rOiSpAHw*N7_3ua-K?vzz;P-7{j5~oo?3jWBD!I$PGU{MYzguOiiL{3 z6;S)Zg4{ZqvOmh#2yU(!{lwSJNeJ+P8w2G^tAOfr&w1txMA_OPC`>? zu1-Q$;o$g@Hd+>MRy(aoyXGG)5Ct`;D3)ka?bX-SQx1*a8-{$UBYU$PhNghZ5h=mX zAJx)!?_=KHTQr10F!-f*9~XDcS}z@cnQwG8b@Y9YkMk0T+NlfO*hf^lGg%f#c1MJB z5Mr~z&Ou@EcqS(RD<}oE9@!bGHY451wSjJA=Wv8b$<~|CN+f2l-M>Rn-9M9lqv>>; zXj{MtZgKQEU<;ee1NT!wv`i*pv3xInU%Ot>ZVe*2etws5-*WXCwN@}LR-p!QD zA1Rx;E@q!MC(0l3Cxu|UCVV5B8g80oToBVVrnW|79icUN?BOJdtdKVd25oEYKWFuO<^$ems1q6HE-}MhGkD~l)7 zpIO#e6~h>YpZ`Z++6RhhY~UG!^_e16CP#yQWC^RM6miV$zq8U&ZZYHz+Gmz!f+#l< z`Bm>6l-A2U@6`XzK*&XCdg$&)j|eJ!7<;vxJ(HVBsHC%_Cjw#^%5-sg0hXhAPJGXIv27H){GM{4)T z1l>9K^rRGAy6juQnv)qT8c#5HfFkR6mtr2-_lD@+n_Sd^d3LE7J@2ww?DlTzZF=;t zYhAaS1(O6sH?D(~c09J;Q^a|5EZ*yuv+esq8=PH>p#as_tVdh@y?POM z^NDKDi@6SW_H-@&KQq6X81^KLg#@Qka9SnAJ&fiyo$MD)8f)5roMsF8`}wj*=WLhm zjwFT&mD2bIIehd0&0kY9BdbBzNE#elOB$2CmR}tdnG_xqRU|y3l#a?BXMld_C z_&xL;!*N3JIcaV#Sd7!PX1Ou)_N`b{nM1=yqI+B)zS(UrvY_@SH^ z{%uljV+AE3ivBeX+0_F4UZ(R}0WD<})M9A7CIvUBylf%ptjvMfUJ<>l9XE<>FCQI4 zy|6sgFZ) zgmQ#qz95JC0Wl*qBXi$<#&p*Sz74RlDfJN~I7yTgo~Sx|kR^w)Cm2a{EHo(jo8Cr! zFG&I&eDsx~5d=vQoq&Ka5j$Hb-~-r}(3EYm`o|d-$^z~SjxFL|%0BXg1&||u;=k%x ze`qzO!R4F<<5zz2C1~J>8cmNz_{$yLU?CO18VgF5B(7+}Px4#%dqK>(XAs)@y<(S^ z$G8-e>{5*QJ%XnA?yShdDviIfOGcsIhfoGK!Y~7`I}0qlhM8`NbSQzrHt9gr&Nux4 zo~R#B!%GAb!sBmpGNNX0r)frBUrL4tBWz&R@a;ya=d^kS|MF2%R$fjv982eR+B3(Z zK5GyANSlvx`wI6<8=?Vf4GOJdjR$lz-WiyjaJng#x%@?t#YK@Tp0m}y@L+~@rX2v+ z`T2qi#9F;4g`Vc6YtFyP?po%#KjZu5^~bnP{?=;=?D;Y61l=63 z`fi5jtnsAq%ALmG9r*ZXl8Om>G@R&6`QJ5zY|Eu5KiB6C_L<7Fm7+U(zKJZ?f8n;2 z(N$bl3U*tcE0zeg%b_~Cg0r70Dz3_mJ};CMr1S1G<|Y~H+~R}}WdrvxjV65jo8P}v z;oz^E{BQJwVE(;uf!!3ISN^B|ld@6ZW}irCB2%}Y8|q)+J9Nj%c2%7nB&j~pcRMr5 zK?NuHMB3;6)Fvr%`2nU-B;Ymt^ZcX4gE^kq{uK(rMC6tMc^8GJ*^Nkl-Pa#mEL_LR zOA&;=9U%>TivXva)m*JL&-*q3bc(Le;}K%?P&l5kz@*(_`%HSZ`7?w2ab95}-T08? zOfjGAmrhZ?cROmtY?-^aM8wON09mIC#tSxH{j3I+3!?gLoa%#oo9Za*@OR#-yOuPO zyZ$l6+&D&)jQS()=$6~;Q?B>IeS9{XN~}WNhC80^qjOdmi!-Ve_w;8pF#=u-9yYt* z)^Mo_GC=QK*@PzYx$jRna<{hDW3VxZnsLL(*vM?HjAlM5o@YvGYEOvbHDp>%fVv@{ zARL~`5iRsz+_>Iy^%?-c`&G?!wi{(uB%o@5YubYv=*=eW88K%Rag&kINWWU2BF2xR zRn)%{-}^p$-#@{tX;ghUs2>c^o+j*tZ{^TA4^LQWISuLtMt*NAaRXx*Df;>p-R#JA zV9BKhO(HCqUqk4UQO2Z|^g#^zY!Bpqnwb)Z^F2pje(crWam|w@Pwes0p)NxpSda8H zUhqIG!&d4cQAo|buBd7dCltX(fHB}5sTsYEuBFOXnB{A%)!k{3XmliGG?+#!l7c^=>+sKEuN_=+uVp@ z)itXNoq=!!cQn24O&sqv+I$Rhhl<%_q=*2nEcvl{s0{LA!#tKrJB}2mgVur{b=NkN zG+V|v+Jx_u)kC7`@i+-bK4rxCqvX`n*QZ<{i79d=5=J-}%JCQmpFjlYbAS-eSy6Tr}t5h;bWCIQ|K@KRGhUhG_sFnqv(~BH<7cvZhLeNwcUd z{PO<(C2vWEV9{AaZjg#JB94mmuJ54ONhGZ)k}jg0zkUQ&X4O_Enz6+O z%PA47c?i9+%r~CRd07)_HuP4Y7DTvsu1@Q5$vFSnt}@|Dm-B6WSU}?n)%-yfl)_5u zIQ}E?JjLsXPwpd?9?ny)Tx}y%0gUxuy5OE`l)Imt2Ega^u}X@J{s0^DhtcwGuGC# zvAwITuPeDHJzWf8(!8qdBHtN5)4W{qV!2Wf7o_7ItP4uucRQQZ%yvBl?1|c$%@FSK z=la!1*;HWCvS-3)=)Xq8#;+ry+1!C-cD`2^n^*4|HqzAGeq&t-gU!Sr?*HTp-Azjf zwIo@1Xi!rCqLCFTsI$~!fLhxtRrDrtfh+h}n8OeQM)YRo8V$L+r(AEw_Rcd$K|HDA zvr>_Q0u_^cS@6I&5K-y_wG8dv-8M#Z=4JF5%2&Z4`L;1Zo-1%?rQEQJNF(A87<#>< z;UenLQ%Xyl3?<80=FXM3!+n=lju(T9etMjQ%E7b_E}g&4-x|?jdPCwEkUf7 zM%pbq{s&KXrF-lM|9Wz#pPlN>8ORMr}W)Y#D`LOLZUefp*J=0bRl_%%7 zZV*POZK0?>ON*8ds@y!;__G=<9e-)RSIa3WDV+t~-cJWi#B`BxGJOzo1Ddzw@W>-;mi^ zQ}yOmMs4Rl?%;qiq%FU?!#z=s$SXZIX_fM1`>`QruI*}XRFea@GQOe?>_=^JK3Bbo zha*6Jow299OHHES$jjZOhZ7~tLP_}6rjTeGH9(FTNWO@N-e9R|?=(Ni>hhzNn^JRE ziB3_9z!U9VY#W{x67;Cf-YAhT5SZ~)cba(&&4I(!G_h|&wI zJ`i4tf9Vjpi-(d04s00_FHSma5kHNA#>(Zz@rJMjk6?4FACSAcC#5-MHpH=7z3GQ! z$etoTEd>?G-8)y{qKLupV67}Kl@bM;ps9xWrn8we(F5e({a!+p%LTXt!@Y~-)PiTm z;=gZXJQlD;(<=t2BDbVZQn&x@@d}9tUy1Ahxh%eHMP@q|=3sN>U@*`J;|no!O)AHm zKO>Ibr>f*THd|F142~Y-%19M9ST$$oAfE#wnnIwfW<-k}ax`Js{fkDu+|I^03N1y# zee2%uKcd^eClNR89d~oCc^lW@eY{w~PVAvghH}Ib0?zSE!M;=EX*9pD0*=WEF*NYx zG}hoD!WArMqOpm~5a1XVDsAUJlE1szEU(yP0Si#-MSstJ0tO(LS4*-hrY2UKV>sf& z<15klfOL}gq_Bb^0}qW84_~6ThH8&om-kRKk7knZ8%R>zKKAXvTiKOd{rduv3cgSu z3F!CisRsXOaaTCc6$smr|ME42iE9S~+|QE0w~HaWeqrAJ`(_bSKg$!&#l7`(@gqM4Y>O9*R$Rgshp<%JO~-x-p0N&YKzY z;D)chu`U1lE<-Xbd2*jyTpudXCz5@9dL5`LfS<3Wzz1U z6~c*W^&Zxq`8O9-+r_8rrvi8+K|V4!L4cEzF^((@7e8rqXt#Wt>~b`z0S#MS@P0De z+nnR>WH=oAth*yF1Sj+Q7}8tIOaFJ>gur1txt*U^a14?Fs6mo`ci{kyDn@2ATtz1? zi2I>`4ejYc3&z4y#w*0Lpgno%KkyzVwA6zS6(`nSMH+y?q2haVtGpL^oj6lhs3r@m zg!^UuY>ijt^_+2vz@x&}J)w!vI~L%7y{DMEoK~WTPsUUQ>LuQ2DG94_q4)%hJyNU> zMS?-16&v}qJ11o)(P?UFt(5G7m(B&dRG>}goPUp^zrgxp4;C6M2ds%noP0C%nY^c9 zzF4{8|B>~UL2dnCw0CiLr$BKp5Zo#5R=hYti$igWTOhc5aVQQ&ixvnDh2joDTHFf3 zpY->?cjnGK=Ve|5COId2?ax|!f8D$M%Kd>~``P+@!?d8>r!Jxv^CWT=8wyQM}LN zV57cT5ok%%8(tC&*Mk0`Gkd=8!Mt#wRqip$FnjPt!_nf>a{-XWr(Ne7D@wsE6_4}t=MO$vY{YY;~7N}>; z_bU|2UkIfSkbfjy(X$Rzo$`(m538r6BmOKigDn2-eQE!3t041K?}&$N)*eAW8tKet3>pusNI!k5Z{Xh2zX#pF;C(OA6$+m%Vy}BbaQg*SK>LM; zy5RJu!B1eF(7%LI2rl`neccS7@jpRNzOp5bIMw#q{CKC7Rzg34}s?i9VeDJrtxDEJq06nT=-ycSBfiO=3KTTiED5Ig1*A4<`zfH+V#tqYwlSS1WQG&_pwZX;h+jwkNgG%w`;Cs*g79MU3W8feo0R zV=lf*=iY*n*wI&4uy=}uNvHRVt@X8%8b!jwZk^~B^vo=|QQs<`$gvw}x@+|M^{o*easVndZ_vpWDL0LM-2vM~8t(oHh2uia_O>F8 z<#JK;Mp+hj4zwM?tc+6$OVsU~-$gM|Fo-(QR>pX5G+|PFJ=cF1Eaqjsdq;WhL)eSl z!$XC*FR)RUqm}`p!PSl$=oVhwUM5q3d(Dm~Pz{hbT$;~R@R@o7$h zyM($T0}N|u*Xjlql9m)eGXk3 znvC>XB#YHr6`<4{RW2iQnm%mJ%Hbqr%X3gyGiqfr!RRj+Y1^aUgypBzOI~)~B&Db7 zIhlc6jorFAic38*upC_Q5>+-iX0qMa=w1MM9GqO_Px;aD&4W;EKGcY%ys~-N& z{~;an{txXjD~;L>l&Ag*}4$M(kKx1MBz`w#r^) zpT?gwCG1Jx)aXB`ibU4(Lb>jm4x;NAI7PvwQBU&l=eChoGV}uDhkG}j`POR(sSR}5 zrgD86#Db454Y#<1?Ej36!$4NPRcZ=$-x3nxjlo=e7Q#9d2IM?L2S_26c!J@P>?(Rc z>wygArFF^;X#|R6`kFb;Sa;`&MgGZsAFECZYW|-1F{@%NQ|X@4z2ki!smyoGv>0%F z;H5}}osYcxB{Oy+-ifh=qR7`qqoTY_iq{BTXDM%W=q(clnMJxN+>cYfsq9tO6C``k zvzWL*Hm9rFR#Cn7wzE$HtOGH8yQQ1Ms};w{e{f`c?JUXHw0dMH(%d_o@U453Fx&o~ z%e=tZl^LmQ`{lY(%4fZIl(p!XzJZxbmP=58O zu9AO244el~!~YgHo;(d|EWFL-$>OajfTCUcse-!x{$dQX-#VJaY3*SdpN7YZumDgf z6?BsP0DNIKN1>)x(2+P?IY6FRiNyS#FoaGTS$W|D(GkxA;t`{nJLCg}BXy0=#EMLm zmkoqND9<_9dvwA@31VYv4If`{==(T`=N9Pd8aDPmv|8xU^=liNf9FQ>j|qKhRQMPu zmb+ll^u7b=J9b9e5a%)(-N%YALdgx3YAJwa89!lV=?Q-xQ!fd0s~N98)DqPZm89!B zX5`>|1F&9fyBkkft~uP?-Ghix=k3Ke!xxw1wwpt^FV-YX%4+3PwiYwfF}LRXGx^YF z>b&LxE)c@-%MlG@VcDRo> zyTT18eSzB=ECeM62@w=Xxi+7#IUYz(xgcSja`rHfA8L!3b?uuRWx+a6L6R1tn2<`5&+i^87V2Vp0;mwO(n;P?bM{H z!i155u@LG{Igb`sC`_}YdGt>ReA#yazg+72P=fASlm@Pa(o~h?)wpVxk>#bn0NON z{#KOp;gguw!kWde`+|Ybb`b7Q7Q`3IThKmlqQxF5vQiCI4J$@%ctAV%t+drC)rEAszWUfFTiq9O%85C=FjJc|;Q z`fO<%$3^2(Hx7(Cr_h?dxm^A9n!}GJ)FoPe+d9J#C z&j&f4wZNF>3|>Tgry1jrGx9uEs2DY%@XY1Q@V{V19zpYX@xxnd^Y0+*dI? z8a12`{YMN7&nds*do#%FbL>`r6Gyzy$EKk?=HWm4*|F~8(w7Yw7v!Xab&~tfpQ+O% zJd-stpax;})6NaSN7I4k|1y+r<>Cjq7hGHK2HE=wJ=bPhK?}ODB{8`7Z{&<~ror4> zfZP=VOAyIGiuMy06fxLPTO2IT#HP80sGubVOpmFBM&Ar$RF=Ul{?xqobe{G*AY3&4 z)SB_FND!K?2)%t341xKtGC#XM%V*>^8b&KXe#JEBR4lK{<}Yq*=v3FqcTMwB86UsN zhNJ%4Jsg1AP*#pfuMS4)j35I|IuON59+^Y1^+N6g8Kzoc#n{S+Iz&k;fi-40>`GT|qrqBB_az~oH$v0eMnR3fKw#U(7p318 zdvNr&Q6{lfsKi2{CMk?iI}S-)flhfo7inmh=%Pw<)`QTUemx$A!c%U4^p18o1!*_@ z=L8rN<&R^>7tv)+qob#1e9(xBmK%MBrR^@Eay4OxnswBzG@)a@M?3y2#`j6cXL`rW z9pB@-@K*ED#OXIXxU>smJozF(6ULKE3Q5EP(vc_t6Z~k3^j16%`F?%XS^3?GMm?1U zA~{!MfCr2g;try%(3!IVX$dwc)0n6I9!X`PFC^JxUilog(*CZagSIQZVm1k2ZJh@aX%4BBDAMU9vTviD#_-%GT1Ai*?fo8G1ZfTJo8A( zGcy>h7h6yIuxkfz9o$ZpG@195BrFO z3K*_KGYG~eOoz%4sr=-?=leV;7nR$irxz}|X>q8HRXU4LVoDmymp@;iz4DblBkw@x zBzFP0KzJY>SP%m-uHpQtvY`}Cs2kslIfNF$q+6e8jCty4UAT*)02^UB7lr6+R& zt#jn@DGxap3gTqwq*;xmtI|>CI|!74>++&IA1eqm>td0sH=!*2z4PwZgws zPV<(8!MyIvaEmiIy!#m*Wg>ue^{2z%Z>8Vt6I~)6>-#`4 zslU~m&a{~ylO;E@JlP?YydH-rL@T%zM%!?mho-N1J{tmxX3AY2`xB;MAzD;$&9}AR zDtLN0+S~_s)Z!O;-v|%9J^&B4O8ZQFsQfCEq4O4*a$V&7nvgH!_|eG~@?Ni992$!_ zN9r{7_Hl0Y0N=u&RCBlZo5-Gi$bEm#IKq7@m>|3KdojexR7nFkW&}I~~G}y?RgSY3V=aT0?k1BAY0$UQj2B9aJZ-4EBt1%ki8#ac*(!#xy zeGxKuY2L*%y)80k(hNN}JIzxf^|v1fVAh`9lhiO1JSurm^(|GvuZ~ua%Bx>wH)x=v zQ;5dt$(1ag#JAP!`+&6ri`hl@QU>iEQ7!1lfaab8xPhqymwEp#|91z-Ucy!XW)%MU zmf5xUm4m%PLWb*F2W9pAEx!>4UEw9XBI;k#?X%5)Ax~R2p3d5MBD5m}lS{3w@vs-6 zw*F^3o`vPY38#5ZkYmXAF-(&tZi3cmA~>mnjCEl63Y~ZCqdp}5H<%i&$ZW( zf5#Re-vrU;0>HSx(88|QP`}%_#!bRompE!Fk^$X82irW2tiI!rOk|EcL%QKuPH{Il zXypBwn=&iLZZ*WuKq^IYY$}F=^v2mO_kI;SaWjgmrDw*w!WJ#PNZy{0JM7>) z8$U_$_YW9RIYx1xcszm+BKges<3C2TId9KA;wFoq#A3CfouG>lh@t>&0@Pc-A=KLeQV^Oy4 z-u_@@&o7~3Fs2{>nnFkspWIRh62aw2-ipCg9gMw{;~i5$bxbEI`-&;E%F2j#sDZxt zf}CDMvPp~NDveLZ=(tUmMJKZ^_bFazT)HA}xRjQKZv=nvOJmCDH6aC77@sPm6DoO~ z=caWH9^zR3`Dp9lP#0wunkUGxRmfqMi7k%gM#jX0^D}*op0=U2g(SMIjkI-3y^`ho z8vIqxm_5-DZ|Nz}BspQt!1)x>Z~{=BN;RqI?SStJntNRcX8}6eROO|#y)mve#(``0 zmo@3yFSB1%kgG0fMvx?v$%j9U-i$4wS)OY6TJ*b5Z>EU&?qvDgW)6C}hI1=64gO75 zq}hHBw_7I?(KvBlPL6Nixo<`j!r#62W3R5=E9rBRks8dz1uP#H^cw0Fp>47h_##dkp!+bHZ2_tSN%X*F zaHqA&bTGfr(tW7mI#VsBUjErv<6(Ms-S^)I5;5n5Ig*8kth<5HMsgZ+UrRZYN+wQp zZ_~+Tm6usde$25kzJ0cJ`V)YKAlNxZwT-QC)}Usn>F_`+!?bFlJIl1|dHgNV902@I zxXoI$drbI>+!)>Ku^4upwfi(swxdI|`Z)!nv7>`;jECt@0Zjo!(~fr81? z6jA?dSw>Kqf!RFSP8E_oN>NYNB_gOHo0p-+6CcV_hEK&EMl#fMUBs9@*S!Glr5Kg& zxn-d={*>IG7?K(->nHYqeZKh!@4I=l&1nG!ruHYBTG1sCH_Sd^I#jLH(<&@!A;*)3Uol$&<(vaqVRoDe0Mb(;D44d4lRzs036jH9=<_D4LRAUl zNSoeN-MXglzBq3d?guV~GzR_h7d$>{jw~lNMe6G4=--&B$mdal$9Ha#S*QY~f(5b` z)pV+#sW0luGZQ~4OZ&j<(nFsyoCFB{we6ky7Z3q~rxn0t;42=pf{Q8gdi=aA-7REV z4q%Dj<*0ymkIwr>i~N4kL4UAUm>2T`!V$nM-H@emL%t?%uoK6*=JlA}$A2BQ9~VMS z2t#Ok-`fp7AM>yqX2eCmzGd5amGQsTLRR!0Mk3ltR_j%3Tj%W!99zt*^{|xXzRjZ= zlhJ0sbNUv>(H=K%-dhJC?(OCn>viA%2LjH&UwTgc=*ekxqd_@-Qv-#@;|?RXA(;>OPN=&L>;i6r#jZLrZI9%LB4f_B zSRQLqe1DE_RV_d;t{E@wj*2 zr^_kxxKi$_}khjnzj)@CWPH9cp5> zyS8%clLV8E{-G#eP~$RC$&M+8y=FE$%n`pM?3N1l)cN<(%O{QvcUc6p`V)E*6a+xE zLk!5e$T$FC`5yLV`c~CKLuRt{>0P)cTLQ#NXY=J)-A@eP)48jYwzS$9d+z-u_ErQr z+7YRk$jbch5)HLiGe>r(PX*BrWDJdrVP30xLy_0_!_xEAvG3QK{S$ZY=c+2a~ zPA)pSD%vb6Kce<#{$ZEX8mIz?7Yan;ox4NA`ijx8Itfa%SFztCQYD{zP$G`uIa%W) zGEBhAKVQ~Tb23P<=L6EO!@JjzMU>Pr4<{9a#j5Wq26Y?RpD7%1H`7Ok%t!9N4H9WY zRH!H{vzVF=Cz*z0=!y1;2e~L9oYU-NB&4)O9)B>A)Om9J#VU9qyJh6r(X{In(Dv45 zcd^pEGy%T$f{+D~1rZG;S1K*b6%si3D9242VKwCvu_@Jo36nTC`79xoB{(JNqDp|% z|ASWnnSQK(+m1XD$#o>lj>c2sVgd>1#FP?WIJ$MsALZ{B1I04KBfu7b;)D8~@&^p# zVSQlvFg)ZpR)M9+Z$3YZyix1@DJY;*o1{Rje@ITz9MVz%D6iV8!5~>#1@zF7+bH1n z2p@TdlcCJp>I$)}V=7b2d!~_Sx}`8E_(OQYxBJXs2XharoJuY-KS*n5pJL9$c)IvV zIS&jDw_*nDHNkwsuVY@-=VpNhz~^GW{EGpf@qB-pBxr}tz=~&!V*L6{(XMwcAn!|d zDCILCBD(Gg5MfFw{Htmhy)2n|Lo2=^Ir1haKXCj0Z{W{Vl*ySaj}YER_prwllYsKL z>Ny}=%};y^1EAXAOHUUL_S?z*zEf7`Ke)T;)jqb&uCLBA_m`HuGm;C^;R~273x;{Z ziFgwF&E@{0?0AJ6Nchfs`F%e5KzbT0ofWA^$$X*sh?0!QLilKHC$|NEVZYz^iY(wn zwZTv@d8>b2oyW|iWMt<<0-}asu=}-g-wdqxS9OR%hyk{lI(faf^;S?&yuV0`iM<<+ z8+JnqU7Zg(Wc4D>yk{0KcOSdnR2dId({C*NIds+O~?VT4gDQn zLFl;Oq4fyH4{wQqmQs`(#6{%{sEBYuYi#O7=8$((R;yniMgjM7Nk4rY%M$zA)r(## zqU2^or#$BB_Fwgdz1D4`rmZIz)*)_1#O9lE6rwOW+PnDi;ON7PYI67q<01-(+aqL% zxGrb8j8G_dZP0#r$*qYLZ(4h+nofV4R95W_0Zf8s_~)2wvSSxOWHrIjfN4b<{xk9F zHb-jT?bbGN^V5P=<_*3Qzssv2=HNWXS)}Eg_W@%$x<%l4+*-2`u1cRT?6|?tRuV5c zK}GWz<(?aUWD$gm)aNj0;C-{XhwSppTR?FCiT=tW#9K1x;SlQz8_zt@E-b=`)*5Bh zbyWhpUK;bww|U-RlRliFVe98J&%?;p)fDsuBksmg3kECTfC7aV>gW~JJsiil6$_6= z86ABDm^)OJFwhxwi`oaq!I8NO;htFXcw%e>)y~Qww-~<97e6!=Qs!rk8qv)2MTIym z?)jYBnz=4@ePl4djyP(@AQ7E)Z$}ydKriIN3U3GHm4=2qNDF@;^97+?|A76y_j>H; z_C%8B`=&^rUqKLH96^vTV(>;O)P+Qi|AHCv*1^4XB>NDoX5++7>3#Soy!ol)$S=OM z2w@*9rIqXlg@dhATQS5@Mi4VZ3Hb2D$7I5HLz4FqveAb|h?QzR_>}T6aamTnimv6r z_|BP;I}#T^tMwhC{TkUFRihsM@olh_>$hqD)tqC5yOXKb3#paXZWU5Kmd2KN$2kRm zD`(nni2G8SQc6V%qoz7(p{UnfnV<2veSManRauh+gRPsta)QL-!hsJz&ZrYU13m*l zW3X4ll*`b9$G~c%U?+Ww)Lt#GY(PBomMR)r0d8INc?2gVF#Znj4bL*palA7%Ewql^ zXN7kcq+2SF7fl=ivw16nD*3wi1C2`GsIH`Rl}Hdnt_ALX+^Q##q+KTb-z>lYO4Z@O z$r!+}zcXPI!Hz;a`obzn{84y|fkN{`SXCMDxP`0kSN7X(1<-)JWZUk3ZaBBN z5M6^uFOP(`uC5*H={r^;anYX4=M3SVA@Y617AlHNeHa)Rp&TFQDuNioiEtl;aUTMD zzWjZ)L~p-74W?TWwEShe1$?~u#P$rEeLuVnoCX58-lXSGUh*VxmGU_#?@}_Vx4%jz zdn^yK)j9<^tc%P{)yXsnJ~DyrR1~lB8=QaBAO|HG@I341I2)9gY6a)d2QXVPb$IKk zj5$RW->In9?Bmzq$`h65w5yg=Tx>G+JIJ zn|7-x3O7S(K5|^mGv>7rE9Ynz z9vs_mOG~#ziDD>VD9|Y&8O6wleGLByt{C{TGi90UIR+#TT3x|1O!URN8mco3Bl~q@ z>1;(Z58s843jc?M#n9WORB3>d>FMSrW~a>XWFG6C$0BO~ku>aTu%#~m^+methysiH zqHtrUd&+EX!;Bg3&kS2)y48Wd->RLb7QDYb9f5ts0W-qrc0PuyfqUC=7d0hU7fxWy z-^ow_PyH6fepGt!>Av!>Yw)|U+I+}>TDadL3vFN`llK3m*-;gg z2c=mc3t1>v8@?1{N&6r;E<`ehjHmoNTnsBZ|E^Op>+ruF-|^MV zv)*B(U_pr9dEu%d?)nI+My>bfs?UgTlCP?hm2OcWI8X@x6&`Ies6g@J0j4MbH1jc` z(5>q5%LXv=!Z&m9(y*XmN%lm%NG$JvFoT5M1ey&A#0FjtEex$-Y(oN4m)$mZgcAmy z_wRNLrg^ygX+2Zq8X!G5#iFl>kN~qhCYn^XZoJPeP`j|(ka>-iZyHHOjE(6O4!ra+ z{46n*sfeJoZI>#nc2olFaOcC+sNO`Pwc$SNcESv*QWiH+dE`|cz#&?#(fNXMx0Ga2 zE#YD~o}};iODdB0YpIM!UuekYF6|a%+M%k8n%Ys3aB)9jkx&e?=Pj4PeUn=34$Wfj z`17Q4AkISiu3@kKoA!KgVbK!22@TIhgd!7Ip!+mT5KE;vo_vmh5iYo~O znR}$?Dlx1pI>QNRn|844;;V9S?cY$G=6y8J&C_{sM~mZvdEYy zr4eXFkU3cyfCp0{YwP@bS>KOft>sv(-}Axv)xK)OZ3efBd8}cld=$EGgUFqvRdWhc zNPKAsv*37ZGP286pk_Q{m`2HE7*Kes)rOf~`N7v|s`BcLh5q_0*eDc!LmkEH--XLx8Lq(XBLsLi6S~Cmp=jn(l zX5gDe@*=snOd8^2bkyUt9i+jS>OH~vY;?|8lkp5S3`T;OKb43vX=B9PzE~vnQ{rt1 z0ACXneCvKSPl=&5uN1OkXttuo;%*L>#8?Y$r@6bj~zwB%4J?>X*vfgyj3w>|b=wZxB`nmL^d7lu#@M*>G` zpt^Yfhq#7TA5q6si2=&--tSD2diUMpQ>>FMsqp@2(LjHOY+NC^oFd`Qo zp^D^M(XcAOV6IYAeCibl0VDCb@0CRe5E~g)sUHYICwdA=Cr5fcTGN+_T8Ao$q>rVa zYZ%|S0-hFcTmk6&S+y|e4_kg7+@l)AAq-F!CkMp(poo|!u>!@lUSadYGSTpy4X3Yf zn6uGSBqiAan9*yqGlJYLEiO_xVakfwm?_>kKY$Hr;S)=5$gOtXO}DD=Sm0-FdIy!h z8#(Or$a}|%F)j}DYfHLO(HG7=VhY00W#onRPYo^-PyVF2;Md?Y&)~%rMmP^y4E-qW zWzAi1V$bHRNI00kj%kAZNCp(xVYCSEFYy&$%60^H5@k;7zW7G;$D=I4+;zfp@%!;s z>hPsHl2L$nxfjz#@EOBls*Q7SVrpa!n&fosj@4BwhaC%rl{UBa7DF9=OGc=8y!*ZDj2*pVdBbP#T#^;q(yDriFsvt@%?16$UUvu6ek=U$OeW z|D10&k*Z{Eecn>Q``iqF#MS=R$DfNg^p9^{=Nlnqs!6ANsOt*5U8hk6u#ngY?mv)> z9q;iVw4*MWYi;{J`ulX(VLH6NYyMUUj(^~e&JJMA${+J0naO&NV|_c> zvRVFhqK-DL-J5e=d1pmeq!#q##8&W408phq6xPZt_>BRo{s0=GwiW|YeJXD->C^JUD|e0yd|nOoTj^DnR+-KORLC|Dq%9p*7@d70>n)e``GTD_+s)5h_wY$mO~=K1sa8t8-yD?47V#lYmZvX^uK=YX|CK6)-P36HN43=K5_M&ds$i z7cr|huKZPcxgHhsiwPxYvw%jLb`fy{RRdwesJCF|7x(ewyGFQvRn^?{6^D#Y9|j;c zXlp^q`F7k3a{Lo&e;@mM`Gi@-axB&#^z9CrNoSnPSkO1HKy)r)K%=_upBa}|W9b{* zsj?F8rTy9-!h`@~^UD?59YdG%1Ut@8Th!A)%Ua)N4$}43sIV-^>op`!Zz`^hpxEsN=MzLga;5&Jl63={#?(tS7Sk%M#@azH&j-9Q~yt}V&Hy5R?HsenI^Y& zqi-;87|*yOY3z$cdFUPazU~EPOVTsPUBj#)d#vGvr`|mt8Q>y+O>|0O7vTV@&H|UG zdjmFn8Z`Ou3rU%3w8hprUk%~*QD;dS8n=`lxOF`7fBv;FWHVzVIzn%a214)%>49O8 zlQQ5A^)j2#!p(hdnm-P}h3`nCn?$Y54kA=9{uVe^mY27s-zS<$bw8Ghm_))z8!&wv zdJ4W*#5X7UT(3 z49=vwd%Rc5wb>3)EA(8SLc4ixh#T!vOhp zvGuS7|N&lT@*uDD_1Rh)>1i zB)hIo)0nMtL2Cy*NZzXcL)kC^Kz66h65ZA3SVg7EQ8Nd}frntp?+@)d20DhdpGgir zhfAgHE^)&l>sxxGey1M09dBCooz5mInqxM1pfa>)sE?U1cCohPTP-vO$BJgLBp8U0 z19~oizBtQ-35M+3T;*QCdu4djj5|z+lNc;|ZcgF2tNLM)QFTVJ#%BJM_8lAe&te#$ zOvF3TV6m)4twy)iZcvTNIK|P`dk_Hcv2P}=WBYHJxZp&0SZqhQmM-Rud<%J2?`~%v zficeTwaYUUCs82%+VbrVAG(WzL=u*GPcwxD9~s7}3_`R)Su1@GeB=R5~7u_^H?847b@aa%W0T%f4xRt}u@en#Vo zxqs(xD_x@(Zp{mmdM06^jydcB`^ai_dxVW7LrVbmW zF78Rhqhfd$7liINWs0MI2!HkZg&Xp2@ZBSzvAbwgPM|tuK1PqcI{cv;`y&(Tj$6oJ z5o$C7t`)()c}Z5*B8jK-zgpjkzL@KtKFH1&G+!V|4eKq-HUb0O)3-SJGPbn|-QjcV zbx+F#GnmxeP+mSR)E&Y^m9_a_W$)D_y4)qRim$dUHissfr@K2uvm zdej*y4MA@Lp4o!d<|@bweQ7wTVEmRfJkccUGL&x!n}~M*Az*D*cj_dUXL1OUuU&_&@O6i{$E0vl(Oou05^+R>Z=Kapu54 zSWg|nKfLt4Q{zOY$)3ajp$(y){l}0^iIcX0LA3-N?icEeccYSxwg(J|)~!+_X6wlR zuOAd3mwOR(V{MQto~5#l$_B`K!>fq`LNA7#)XS%>{eq26oIk#BF)hdCgIZitLA)I- zdMNa@K}Ob%oEa)N2!d_Scb}6@^k7Y(kt%Uk`uOsh94}lD4}L1@f9hkuBHtv)Hu+b` z+PDX(px&k80L5o^HPjS zB{P(9WuVcrQQ%J<(&3g!Ws*?O={0~GpZTX01_!IwllO(JcH8ht6LXn44icp{Z&lE^;GX9zU z_fMT#<uf_7duZ?-S956zD}bQy|v49;z2UWeRkfeZea6{Ltw>OJI8!B&r}p~0*x=cQ=!ht-GC1U23fxnf2NX%L8g*x7BxMs87LA>81Rc6{`Spd!F2_;$KzAEw( zl)~IXw?DmAq8b$z$8o}Bz)H}fwXREY$0w;Co{~{N{eQ%P&WZ=Zx6d8qe6uo2#A|+^ zO-UuFT1!~q68;~1-}vKR4pv5euz(*Oj1OeMecjEBTpkY^=#&upwIi&e7$g1q-`!R) zJk3~#NSfW=%DBibdgvROE~)@&4jV%<-`ycrrAoZmO0>;GNK4(iPcY$Mw1ffPk|Fi> zpQ*lld=h;ohHxEA66+p1fbW~A#{c}Y4M#Cp!sV11LWBBH!!z-(b{lAur#!{@P(K(} z#o44~?0+&Tj!0S{h_50hH-&e$I#$>{=0y|OndUj|v)~R~6G4&H=U?-GKfZ;Nprwm; zf|8LdLt99A*bARI`|`Nl8L3>&Lz5S-RCX<)exm|}a^U62_j&V#v4%i!yRqZgDMP5I z0LzNX4#C`;y2w1_d!eti2s7sH{CDKuufKa1|a_D%<&k@lb8>4yllz8X=NH(A)@ zo0p=obep|(Oak}sk2j!=k~PzW6x!E^iaz>f3!skgvS6E`atbxB5Cvq9yT`b`LPIbo z@1o7h#@D==^UDLJi;nU=;z4JoeSDR|wqt^Ya z!4iY>oi0Yx{oLm21pq}55ns!fpM>)*PIVr9Kwli+PY3))N+cw}k(u#s4d!l5Pic$0 z)CQ9NxRik;U!!PJQ&5y46Ksx3e;k-jWa(90poi8yaR~2iW8?NXMba5?dZLEWDa?^@ z2Q|yZ-T*YuO~m8vc{t~4gxjzzHJz#8=Gl`NbqPpmaPlA4X9uK$Wy;P_p+}Mj9+LO1r~k-09e{-n3c+dd9$eGKX!4f_guW5pd9CAdlCGPc zD`gzrNpqI-&z+aZ`09aG&9Anj*yj^k*7pR$er^&Qwu%0xrXAU{+W{xfs8c^Q!#cIJ z9Ev@jPz#P~{8mkeZVB%rL^Ey%KmSM=s#TZRAg+xka1QM4ZY*?Wvs1M3vZ4BuU|&5* z()x0oL)7MNz2@TS^>MOCeI{?PrAj$3>Hobnwt5;{ZDrDXj$(puCwFbP%BMuV9TJ8v z?Ho#vcn92liz-!s0q+~Q-@&o^#RG{b-9Y<#cm*cAK-tFjVF96AHws_+57QZTiFjD` zkYCFe6@v_$RrBwiADx-9IALbeY5=0(sfpc*N2B|VInU$Tx;kS`T6~dd92cp#HM2bZ zLO4Aj*0Bj|bxSqRkSwG|Q??QAQYhPa zv`Bv<|HJp+-%fo;(d+Cr5S3E(aN_U68`>5@<3UBbsZmIk5cd$`Va{(i%+=1!j zk?u*Ms#L{#bMLDXUo+O@at>Q&vyc*4&V+j2HL#$PZ%RNuCijrl?y#T+vsKQ{yk2nk zGEPxNc9!;Xd(h@D=f+Y{&a;8E5cV4L=A}mh<}Jie7=8UO$sc-g1GMRooh@YxF9kzD zp8PYa=VYKVR9O_iFf-MtX2}m#ZMzM9;``+y;sL>}pI4IqVlkqmhK~Nv?`+-$kOJv< z_U+Z)s7wg{kGF7!ujc#0^%Gd%fs$r%Ki$y-dc|wV2*Al&z@K1pPc$B{oyjWiJpG*cZY^PQz)=(Yj$yaoJFOun9M{psCKbSc!J;{{#-9Mg8mMlB-}V+wqCHA#z+*ekj2n*`6rTwl7>m>Il^`;ToJj*=a(M>j1wanb z&N?D1(f&{=`kttZtRpw)fR!p;{6~Ear1E&Utc^@_@H#eDmE?nvyvK9Zj>bpfDM?C>PSy#+}1dL)f?A>5HR< zu(2?f`9)qB4vhi1ZU@&g^^6@Gh4ZF{S9Vpoh!Mw6f6zxEI(u{5SA2-lV}=w&YG6qJ zs}huxZ&dqfwiVt4X7EgkJTc-x-y>RE&aY^cT;QHTc1yFY8e+d zIAi{-qNc}1U$JaOiy7Nmw%q9DnPXyx7`Vee7)QKY2Z8iN-)axNAhKAbmG-MsOGHu4 zKJh@kzwmx2f~pQLIl_(We7g1o=d4Bg{{^`+Q9M%>Xm)Jd777zHvf=>swIJo)xG$Y* zeZ)I_?yU(|;z6&#XUZ25p*&BDM0Q6A(@<^<-{vnWxAOz>`4^(hdaNZIOx05*y;S$| z;`e?(%@w4Ef3wV(7Z-|LD_##|s>5?y^tZzUBq4p^@Q_?=!kB49glS45N5DcB3_p5t zuMtAEkTd*Y+7L+NIBDZ7o-aU6$DQRLRoh*vQu1pETA(;N$ez!~v|6C~*WDkxm}XVu z%Um}gRqv0>RzfjFr~9R_ar)Qde=@o;RuQ?w7R)i(C^EX*M$j1hy#Ld@ht^Y(SKs{o z@ttkg7X2r_(4?gsfr?u)#irwQpi6j{Kx1q!HZH!J zmw1rTiZZZ=TKZE4?)!*GCabW1=@>uqRNh%OO`94MIFZ;cyC{7ev|nZd=DhKNyLo3l zNaS+e+%`-}P5wA9coDUI8(#e%E_Tl{;W}b0(I+Pwx+!G1Pce=cSU`eP80_AdS61QC zHOLy?$g3g55ax^HtE<&*De-bTgFzjLaji%5xUsb<*WPZO_IY+z2VPX97WdTP!|u)S z>9z}z^O`MvzOSmyCnp;IDESIz9ZgM5?Z7KrE&v1d66?hmiZYvyeD0c$MNjMW94>1& zTvax29+4}v?yd-7qZ^A^+`VSdJ4EOZ?}ojwxp(<`{{P3;dxpamcWvK#qIX7@s6q6a zAWbJk@4ZJIB}TL$$}os7dWaIy6TLG=Cq%DfMv17Si}r5Ub>GkNKF9Iwk3Jao?EPQo z`mJ-Vb(cB8lGAbr`+=-YAe8dlcYz)4e@~5KOa^SRM|N0uhafdquRdY|0>S5Ul|vp2 zjIpL>0*;t(c3ICXAY|>)HF|{H=_l}yk`?Tr+X1a|lp5?>t`uu@c?nJO@;!IYW4Oxy zdI11UCNGm%{!jeh=S13sWP1cqrI2Y)nOeJbYlJ>N`;o-dk6f@6vQ6!J3+J<x&-Gt^m z=BK#LOTgGdb%ib9=m2XCI~83T*>CNd1dfBCI8e?9p?d>9w_J^*RC=fV@Gk&Zcy5S@ zlH^Gwos%Qvs(kSOyUhFVoI&En{G{B<{B_mhGpxJiwpwz1%Y%7EtCd64gqXlCS93kd zc?Z8~jP47HpMlOlb*3B^^90-JDt?^>pbA1KTmznVD3wV2E;^vTIHiuNf7P9&{!yB` zKKrwqPmU)c$}By-P~`fjc-FHB>_={eoC|bV#2+ka^#7<6rhBg^hJ!tDL<>aP9#AGn zvrK0B_c|K2e%}TThdY(M9<$)r*o ztZvS-Ne}n21@h$Wel$UH3>)^X6Qta#o**mG_>&`vSfhb3Z{i0hjUjyEC#EWO{9-4} zrlCIWtFGK?i;1bd8DSZMz=uga`I`}H^iM9I1PPQhhCQX{C^_UTagLwn-zKdFvQ|to zWpqGlm)9?x3(KcsAB5xMkEmJPz1ueo0Z##&2!Pv{ln(jG#G@&qxO%<;VS>>p62R^E zjpB_Q$YN1jSC$RCzb^>!-T9-paPJj6IC#yT@gL{p=Pfyett8#zoZ-^wxs)bbrC8CR z&IqH*fj?MegHews|1i|mG-)uMrdCdOwEod}Mq~yU_u<(GlHBXYw5op41CVojBSfdI zIJe@%1fK3#*<8>24|8ks};D7~a7 zke*Ox`0_?WA`|en2|?JQ`69e7*M{{morvv2VXy^%`GhamoTSWD z-~1GmB%iw`rj8ZX=25;xy2u>2B}i>Ja1J*A=t9Kj>(Si9=11?ZY+V#jd8LPtSkhNx zJqFiPde8w`d>|39F2aSZ@3XXKsO*C8b+Gt>;_v(-iq{zSks)j3j|XdyWb+%E-&bkDzr$Cu77hnbqJ{+!?3LZ;0S0tKMEv>y z$@BAb_I}UTRWO=~BsdT4{p!6#SHqtzbk0DgDPCL`?FVSJP(Rs(2n(SNzm$GKBe*DO zhQXU}i5s4&&D4%tdF8V)szh$VMB6;%q2tnPnf z?T{+eESPzhaA_+i)x^R%`kHK5?i?BZD$#}h4N$iNUIIM#u5+`89ff_Ax-Z0wnXfP~ z4Kcx$rK$(-GfV4as1n7A9H&TQnYLBmtULu49%LIQ_stzUY2cCwe&WT_B#`~MV6>Sj zsFNnUlf<|CSui-XudefmEc+MT12aS2yA#w?kl^Nn(BJlV*93c8&cs84-zIVySZ7qt z$OV+lj51w*w=`S06#=hYGSXq7WBKnu!7rzxQ4^h^oDH6E$aBK(!zFc?-SpxZ!{0xwE(x3!Qa70O$JjFM~rxm(#KxtWA{S4 z+8L!kQNm)D?P&aK+wc)87xqsYF%ks)YX|P?wW=uKG3@A-Rzq-D5J>q&H62CO?#5m* z=4?-jE>Y`8q%s;Nxs3Vvwl(8;M-OfLZ>zgln>3%lmhHwvp4Q8EJYrz4_OszKv}NYY z2yOhzUi=-$dI~VYJ+FHF(4dE&u0a>U2#fM#Q1cW!$a^64t9bhhr~kGP2^kKn{zp`9 zrjfT!gs3Fr<{*fCEz^hxlYtu|I8Z008`P>^_S5mD9#Omxk`eZbh+o1CAs^O7aEVtt z9mI8tJrVue%Ao>Rp0>Qx$ok+BVmnN0#5TgJY4cF^{bROi`N1VbYjSwUM|p6KX3y^2~)=lKVqVvzjehzN!TjLv=}&R#!ATZ&d?XAPR5VO8UH8 z%EVo4iZs=ibzq0?#i@aAo zcHekXP5+DOPshjS?;n5aoXafs7VGlO|5=pRVut8W``0v(bPnXs#ZBdEmy`Z5>`@V0 z@lQ~;jtFd~Wbm_N`=-td3bBagXoEoL4_}(s4SlVg|i-*q+Wm z`|2Hy@FDbU>C#g3+8NMGGuQhf#Dxst=H40he`lO}`t6KYtsLbA3*yZ6WT{-PpjL}; zRWAJcq!6!!c!H8RG-T&5n&QC&xkLo`+m~MwU*~o({~NDcIH+x(42CzbNH_C5PH~Fq zR-+y22NY!?;I(+FE?(@Xp&>L-hpMbpS5Z->teDIJr3WCSSo`bKpB&8s_RgHC^hcuY zvET*lt;I=d9&o`A9}2H4NST62~x71HtYGXp||F4{aad4zm44tJkA+mL%>_x9obyW?OZ ze)@BLJR|q{j((;Khv{WDz!w}(*JZ_G)-1(Z?=2cSrpTtaS^Ai{HP{E%5ft~yP@(T@ zF%ty#B89Jl9ZjkiM3F(zGZu7^*fPiHWxWvF*O!0pYz`>%k6kwA|dqlCMcP_n| zb?L5}=)w_;GbL{n#QXB5>B(lUKz*H@33E{|9F z<9ooJHDR`-KzD!>;Q`@6F+&v^!+lWvLuy}g=2YuH9%r0n!Xb+c*=@5tOQ{%SAzX?X^ZsS)m*v)R?XZL^HI|+3RFHOl1CsKnv4w{_)`b|L zBZjg$mKlvY2W2i-(y6g{L}fn_3eT`$Tw#{}Zbmu`j9ja5^H}M5dk*8{3 z!91RXsB!TqHeWyMMyn^AIeysW^0R+8jXHuCqK!?PSJK?v(r*u#0GtaDj`%so-<(-`Dx7 z435kp?eBr9YF2SpISejb(+uT`YUQ;iGUKj75sOZ;e{^1(@))Dx{&DUFRf~C2m|9S8=>8yYcitHFfz87% zTHUdlnXCW{-HFb~{Q%;L^B_zzE*Cms`~vM`YBzf>!Zp;A%<)VI??M!j=l~Yl%4NRInoMZkd095e{BP!_4ESOlDjLGk9^7hNJBy`Sw zesFohPUa^dY;^FAVT@5P05M#ti8V#j60^^BOz11H3%zvBZ)zMUX7zXtvk$OUV)|NM z5l8H{+y1o7&o7=MN7nyPJ879!#0D?u-?8(_(UYg{4VcaG>3=)XA-9(+by<>b|CWl< zEljenAPx7I|F>4YCHRrvd@0#{y+EGxD_0o)E3F5S*c>e{2`KOuSNM%oKE^hCAE92fV*!cCy7}F~^lN3$haL>>hna`Vi9I-Q9C|vR$WNYz`TsQx;V$xJuwg(e zEOfRs1}>H;68da{YzIX3bNN$-100m1H$+}8Cw*V8M}EKj{rXI4da{);I5Mn*_mxel zEeS0N0U2JBW92kf?3&Q9kptZoTN(h}Bgf853zKQ^YL`Dh4^hsR;+nD8Dz!D&E|mAp zl35ZP6_+Nq+*w~0dJ;Gf3#l;eBmOP)^EHcp)Kc6P5F5n1n8K zV#0_`snR|TXYcPPcoRf|I0;o9xU;v9K9gH}Z4AqO_Rc+$9c#+ljxY93GaH3+eZ$&U znat>E4c4YRo%(o=dYi+2-U9zdo4h+W+8(S_7cYe&6>BF`;ABl}M7KYxFSyseOHt%Y z)WKwrM_DE3V-4d_QipX*5ipPEK^!xCDD&+ptMM?g#o2AR~QvpT&W^6Q1 z-$c!A?1>M8)v$s3= zvAh%R%bzr2*8j-sA_hhrdW|o{&iYQl-ja^K@Av3KoL2(987@k0#<^2|cF%rqi}yQk z@OE^_&s)J{nD@_?hvCYu}l;>SdI~1Q+ZYqYYp$2)4p*xc@aFJj2JM!$a#p z9@y6(u%pFcFCgflP?ngUS(wV1SI}r%kXIim5uvH=V3?L4!qVPk=3=miFjzbJ{ICD}SErikgos zwAk}Yq;U$yE5pi0){}WT=#K;_ma_1}NKd+#k|%ld8HQM+EfQnqpKG4<;q3O~@G$+w zdS<^bix+r6oZ~yow>gUW^y)Aksf93+UmpoAlv_EYPU5!*Mp5{V@o3ryDqq*iAOGj^ zS>*;+g;Zq>>D%kNIv1e%O7(bovWU7ALHO(bl2YR$C)~aI%}NN;^$SU#Gt)EX^f6s` z&f#kF9I4$Hthno6Ja!q?uL%CA3ZoUu-NsTs)pQa3qFI8QcW!MYrIYm8Yw7A0s=@!P zs>?X|?Y;_#K!xTN+l;p)DGq|o1(Sw~K71>T;Tl3Bv2(mn_N@A%p{y&V7D)nYxhCulz=nN*X20G+dP()lCIv77Qn#3i%hwP#~XQK^zL zwiIIHqTrzI@^H5|zCHNgOBP0|^oN4ILji#nHU`q&c}Z;m?2K0P;5{_qvu(W z|EXDlE%BcqRNs41QS)?xqdq^;TALul&$l5}E18enZe{2bp^3efF+@97QHzXK(Pj%c zxT2C7HB+=BZi+M49Oc{JFH*3vzrndA{^k)nHUcDr&yyneYcMwAiq2?q%EmK-SYp6z zWANNuG1q*dBJ`eXNwo<*qb%N{ajwUTrjIN(Yp?zjOT?{MV~fB_``psy*^Jf|F|WW_ z!@Vc}nkRH*zH3^SL0wQ@O#5ykgE}<_w$IN{XIxr6_DQxHhu+j#q;x~2BIyzK$-8;b zcyGUB+7)#q^u!Jj z*2t?WeD#18i%bOluU0lI^-l&03JtM?rDuHL!LX1jV3HpE4Sf&&SInKOwf1oByq7gz zL~Y*qJVqpmg>b({;cN=TPstA@v}7@8Mr7_$c+$&%3AH;=4u^6R4RJ5zo%-ale6gz} zP@a(f4HKhu#LmO7|6D_pUQ$@#jwL{vq<#k5I`Vza3qNuwcXhJTag4v6ZK90;M`Ii` ztfJTh;_{a%Pue*HRJHmi)zsHp{fPQhH54>@q-kgQAcG& z(s~MP30WBA)?T2GX{0gO@)WZm2-eB<=(syM^X)!Q{7mbyu~C$PDZ#A!eDet*V*pz^ z?KzJ^ACBbGbe~BU6?rYoL3P2r!WexkOZX2^f>B0PfR5Ahf|*X?&6a1e*(jK~SdE$Y zyg#2nM2g12+K)Ett>OHZ<-M!dlI&W4V@myC>xn*TQKletb4mtS#3JN^(#)Md&ql~s z*$jI?arGr>&q+L`ym4s}C8o@(iGiQ=rpQ!`K3akw!uf1X};n4$dhunr}2WNdeg{YJ9l*+{$NZ!GZ_h#A?yd`ZEpr~ zxk%#F@2Zl3G5l#C z^+7rKcE~jU`kT!_X%B%^+zG~?IDN7-B(re3fWy781OI=bIc8hL>zSSVIWg2&*dW^>Pp2frjhJl zffXvZbLcNKUR5$ZO&ES!5>1HRrrh!FT@!;A4(N6kdAqHOZ5`ePj2$zNLftRl-?@Hf zsb@i$9Vb#GJ9e|Y{_JH8vMT+e1lg@Mq#U2za3kc&i?G#317v?Ls|~c5%VCUpIoer7 z5p~36Mjg^y8sE9_0E~qY4ix#$K690KVb{{0%nquVhpL*a%h8KUeziZ)3=HjIAQp#% zjquhY%|>^&!sgPa->&>L7^Tq=w-ps;Hj2Weyr@9GY2$ZxvqYir2S-V?Bc)f6@4`0= zQ37JcNW!0)B)Qa+?~0wQYjs2ouNNsU6%;BNE~OuIke)7>y{Lp^J1`T$p4-_*pR(X; z+w4~EIz{1czXmegD5L#IBcAj+%@kjTYoqkq2)UqleA7r#GPE}&sn;m6tCvcBQ6sHL z$HI9$FfOHse3+LY?KAk5a_p8_>+?AVvP~IJXzRmWwtfhw-C}yo5j#uQSgibS7!~}Y zQ@QiHqGHkaRy^R@I0kAzpr8dMI+#F4 z&@Mv+OXL?!0E!Lq+7G_5{Z-N?RIOUw3+ILr!0BL*K}?icBK7QH3ZjO{Sx?TGp+79aZB}|Z^O5kmLmBdVLy`7dlv-D;Xr*SV+EMV~p@?XFABdQlm^mUHLf=Il+>X=w zFe;rT%J5%OwzF1-Mal3lNwv^zk+N3>(v*t#p9~gx`&zw!QqsT938Th*eRduC+F?>% z))Cc|c7KdZ_t}s~GC2*2GAt#17W~Po(H52h8XZ+Fc-_f|41&L9Hdw7Ch|(wc&QkN< zfR$}$Z{G6Fw>P8D-IKwo&^&G%S^1!LvimaG8$x`aKk%U9kU7b9VJ1@Hz28!3@&ty> zN^2^IY{Xavhkl^s<_uS<8C9P2WxAz1zs4fNeqIhY3KM$02UR5Lt(#wo`{am_i5`IL zo~d(htO_@{QVA8mx16b3yHQ3)9|m5IfTg#$yaPa~f<2_Z0Q{I?r>E9L$2>GVF$^juUkv z3*J74&l=@A((k!17;*VGnK>dpcXr_YAlcK>mw5qXZ~8n(Qu!fH!aVqj+V6_(fZ6zh zB{(Z0;K=*|5za)k$KiwAgDqdPG~B8NrE@>glZNJ(FN$8`{*dWG>L6wF*=!ymIKCLL zswsZfv93@u{^(4wd0#$(M=3}~duDRz?N3X*cv|LIX##12s%IIIJjWK+Huwi@-k^uz zG^A(#GR#<$n0zl0F2=sqRG^7#Vk)iVS-veg-70deiS`d)r>bHskNybpJyJ4wXJEBY z|KglY_RDr?klc7XpbQ?mT$FW@AM}zuXcVEupZljK>YE|B4yQ6osUj9v;9p}WbYZLAhx{1A~WMl#oG9q zpu`!=P-;$Ycx(uc-tkE*KiIq1?$Wmat?Cd{c1(ou4(kOgV&d`4uELTX1SD(h-m&ukL!FCiYux@I zBeTb7h2JyB^qsd)l&BbaTVHZ`)3+?EcJtZ3GJED35KA0PzxfE(_RqcMvaUIP7%`RUe6S6K%(Yum zuUCRiiPbzd_^06Yg!JrP90M(P*9H6XrXAjXkXFiU6M6{Cc9Rh7Wze*I%e7zQFSh+O zQ`f|(LY>sXG=nl{WD~RAMsB0wZC<=A)q6Ajd8UM~9kx~tB&zjoVMHSS-(h)-%z(F& zdR6&H$vhL`{e~VuVYndWNs3afH$H7gkB318vz?YPO@#Y5FUg)Jgfy(O<2N z)6aGrW%b&HVBb%%%)spXHMCYG7qmBAD;p3n_H1_)_(dtnJ+smx{acWu2SVu08CXAZ zYeGz5Vrf68oJR1M9rK12iFggRN2MdNjR+!Ha5CO(a7a~O4_;FE@Fd9;=F)S=BMQwj@-wclJLmgqxot|Tc+x{d~F;4>N!|kqiZ6MmD{HtZpAq& zq8inL2Y6Y8HC$XXbNG08KKxw7$DgBn<_M@U(>v=p-$~z6#;VwAYgNiUDxYW=2G%*g z_iw+hDOq;(D6Cdfbhxtc3{Y$j;<*czH2T{vok1Y`_2kAfo{gzk7oU3gOKM#|!_G#) z+KKjzfZDJ>w2jAYIDa^2WL#$muXCp4=2puz zG^!vb*~2yo9lE254^gwaMD%Ynnig@h`9%V<8gITln$Gys*xU`n{}+Z9W&+tD&IY+f zp3+iZsBhC))Wz|Kntr(L|H4bLc}x~j$GEQWnKvU^npg<>&lXlfsXlC!{gxPn`#!$0 zH$VzWC>+c*f~0>DvH8J#RfwvY7}!hO?|X3?q`QMw=$oRw`)DY5Lv&OE@fj2+GI)DJ z04I`}u-=UvzKYJK*i`2mSJ3|YYy(P%4b+nNsZ9JPbDH9+=%9d^<2jH;o4&C z^j+{y;!D$C1-<8wO*Xa*0`#@((%}6*YlYUeDJx!23XAR=d9aW(zC2Bvaxlu zGqco)md-`e-C>G@etsIon5weK0m=WCI7Ibm1%PGNboQ-6zH&^`a9D+xKc#I=etpM~ zSipAEtTEB|V=gh)R4{-lmZmB$-4`OeA9c1vL@T7CO|t`$IyY11u{K0}sS?6j7|?I# z#^_`G8- zd1rm^eZulx8hQL6s?nNE3Y-CZ^*T`LfWZpSqJ^xQ45EHOcksn>%?8%BpWPKGW?b}O z;5oRilIH4RX4j|D=#1F!J}~CW=YgauJ&?&b9mzxgTvbG`XG=k~$qd64V>W*jPe zOOrFwDXraWPeOy5)||p^howz~2}Bq{gc<(C6S-}v}$ z#jj+ps)&NEJWHWb>j$xivH=whHY!tg%ge-$60Cqr2RJnm|ny|tXxu&AVT zCC_ztdIy4&f!6T{H|1G~kSgq@fXT>s;&4OD2ys;ySb~ekW5L9-3Na5+9 zp8|Bz_mvp337C0}=%~n*S1(u-drv78k0f-+(m!kCd?gM}=(#N_F#A!ely|T4Wj1+v z%DKHRHTl<d4?dQQ%mu2c z40H0AZ45zb<6V*T*JkcoMVCc)32EfeiKshP8rswMCH~eOYDj+pg;u59adx^P)?eD# z`K{iYo=1D%gH$df1o8_v-!MVJ9@)?E|0C#wV5WmdJJXu2g5tti_ee%hdYQG(tTI%? z^A=7D;P^mkWen31OY5R=MI%js7HPVYZZCb|LH#t1#lLnihp6WK+2u?qCFFV`N0{Rw zMjn;t1qleirrQTu>@vE%_hR0oC;W~-F}z;Bx8p|-2!EvOGx~GaR-9iR>H?yraSpXk z9)m}%K9yt|O zJB*i^8SEnXXuJF=7$4khW+)k0?AH&=()}Vmlk24#_s=mJZJ*7qHUCcr`QxU_5L*az z^@>cr(0Q`t{R<5LUvaCf22FI7gE-DJIo_NYtrl`X(EsWT%?^7N>VMW2g>%x0`^^OY zvykTTFR-Yf7}};Y^*mW-aVqN!o|Jfpt)g#M?;E>Ezo=ACLx18*e<50XC4*YrJ?g3P zw++cPa!vnEc6b|i-P&^TkGoZ7mAh3o#UWg&i!R*3&{h0sBW`5&PmDv~EROj7dR5n? zal3-g!mr6(-zj*ro08tY|3^@;VyfM_BAX#^D1Jui`qdkt2IN6MC|Ewu!mZ|+krAV~ znH1N}Xzqq0LmIAMoL(#RQ6shWirB2LXfRoaf$a;_n??XX`|;y~r@B=ZSQ_h*HMd8T>c!n z`>Z6XllIgd%747$#da9YMTEB^X1v|#m*njl!Qi33sdjsIc-x>_8mVV z^~$^`V&DQLd^Bl%sGlrM;ZxgNKwo<`;c zK!nZ`VUkuvO?!U4&5;L00v*VXH|xWy%Us-WxOacu`!GRRGsz?Rvf z)|&r-+XD613r6dnQuK|lW>Jq^l;1H)7Ua0{ zKIXxjAdmagpAdhGPg;{pk6Pj;CDM+ody#C>TsJRgI!Y$aCKrHqI|A6PFYL%+bFMWv zuxfWDy$8>m!I7-*vNnM`q)Sh(KpyX8NrGo{>?kKZBNAN3FcQrb=3h}E`yPN99Z#1_ zqvK@rmX#P>vad%4^ zF#6#hNOMa=>=3G}nujYETYHd}lror>#*#5QVQhl>3+){OaasnF}d+Wc)Q-CB-`wCtOzS zVI^b&ejWE(Ht|oeYI$P)_(n1c5uey-^Ee8*J}QBV+cHEZY|+~I_bQmq zE#IiU^-;hRl+upose>pSWZ898`bJ2DdtO7jYc008378w#%r_eqBP`VD7S^%Rh;NTPLKaG)BT zAKd(D{;KRZ+~FTa28t01iA(k-ar-gk*7+Xwl{tDU9{7o>j7{xlO6S1IDS5Ly08Zfb z1!)4K#uLJ7h&LK6lzY74!tb1%*!0x6eEU=E_H}!lz&i?0VWmovd*g2(!d89QQ#1!` zf?nurP*qQ*3Vk}U_t+h@d8)(Ql^l_?uC7;%&Bm~}K()~T9i-jjyNe(MW&&U?Pm%*! zR6T;5RkiNaZzC|y_mwQ6o$dYfJ~Q;p+4@2(G``{oje&C*gCQ^rhAGt88IjX5^dkW< zI6aTiZdFm{8zkzQ0}3%&e;`ST|EUoDr%pVhRbOe>l~IHb9m#-O zp1-Uuh{#5dVY9|!jPAQodTC*o>@rBTJta4zR5}t@E52i=%cQE zBFH2>VFq&a1cug_(J@{<5dYZ0`8T(rgAA$q0x#;v=}%$ha_PJ-h1Ndl`N4w2@^;fO zE$rg48SDp9zt@DjgcgHjDNc$)!bw=;UDsn|Ea!h*)h*Tc?v9=8g!_?KJ~pSaNjSg9 zw&R{#{8Mi1X<(XupU6|cXdc=$?*&9VzDOwFEjPkE!>rxvyF*vzt$ zaV7ya@?&o@eNh|cVrX*f%B9{|=Bp?yx7cBs9(|qqT(4Ea0VfTrtBUKcytP41fgU+BG|bVsuU_{f(~?y&&QO zgzvXZE1lNoJVVyNv<^>~Sj>@L`K*BnpW~FOStOX)V&b|%_c64!>P@YNb7F$b08DH| zS{G&4s?aS#FxH4beZmYQ;#xD`67S$NM|Jav{}OG)X~fnt^4~7uI>+Bxx~qFJ2+jReE!!_`td`5NwbWWm}X)=ANgi< zXYa-QCLP5h>%7dRBhGzs)z$&|A|&{HmO7?Pf~oO7dh$Oh$MP9|U)+(RvMJ@Ik&I$wPEN>=?b&)W41wBx zx7hxm1SRwK1xf2VemF7R^^ph3GO8OG{cz*JM8Ur{U~YInjoQJ!*SIxDuPc70%Os&vfMT;kkHy6F9Q`(Z;`xr95&HsFV8ztg6EIz2}u&IAj;Ld2}kc_WkVEv`wrp%5 z^*?5e8Y%POVf%Y5Pv3g6gO^CNQE!+8ZE^+scnv29@UBOr4-%2XqiWa- zbnv77*TvW_!gL&I#|kwA^)o|S$%=@|I2IbEmjSh+3lB6rw2bJ44!5Fzl0=Ve$`k)g z+r(VhWee?)0v&+S+lTyO?EQp2K&^Yh6Q=waepHo_}o)95##L?{v^!&V;Rf*EF z5#!8pUIvC-i8bAI1l0H?*bLFBUKvpt3oGlN^%x6x2!Xski6T!5O-yBp1>6C4i_R~j zakcY=7#1jYJm#cU))a3!2rH8zh0f+v0ZCF1dlN}FXf67MD8YmMTL+S)e)}jZ`IekF zCbQasj%_efvhws9$*Oz%GFENW_TkVIO52{|*X8?r0b0Q#Q?f@yOj^C$$!*pM>dGO@ ztW1ccA5DBqJOfox=W}GPL%QidwcJ;LKSXg_bUqY~pGTc-wR|qc;`FIh3XR`IOlNP* zN2C0Q=*9#_EF4U@L%v80(7D|K74*xL)C z-fcALQB{zi-WtZPpzlBC#UH7Q)%|fF2YlDg$XN)QZpJn~@%JP6-%4QZx3c!fqd+a0 z#2y5a52~;Tl#=-~uL3rgy>szeRBe)96w0`Y&+aJAmH99(y19N~8~G;C1Z0=@|J)aO zk;lPp1zY*XMpj2qx265|sa|IlJy4c5ct@tST5Flv^9agHUBr0P_T^GourtFr*Rd<^ zoU_xi$B0nF6IL}k`omxD#NrOqmiF+6nerX(rp+FSZEjaPW$?eI!LEeoWeYc?=eXVe z{bq!d6s7)l^4SQ;1LXtXf^2_dM$*EQL0a{ov9GAio5~5pK%r2rQb)o=dFof};9V9R zsLS*Jx$fO3FdtC0WSG2%=Mw=qD>tIwLPM!8pyiQLZJOcTj~Ds0qm5|18tY5=D$c~k z=>8DL_vCaYita7Zt@nM)_@rl2a!}@GM!0B);5NL@rk)6~Ev=%gfSIgQrp{J_o?r>|o@^D1GWG z8EcCy-}<&JWOYl#UE%Bdx!m16=zq!=?v^IPZ-76wWdVc+@nG|)Wq;sdAVzbo3H2B` z2o7Zn5B(cFBLdWIc%iebp!5@(jWQ?xefU?Z&No&WU2iOdrL%MBUFuu@5cJWjcD|i4 z`u#JJyv1ewCFUUubZDzmdIU)fAr8wNfsE3I+`CzRE88N)_4=ps-4i@hO99$y&i+|a zJ1Mss^MrJ^ITfrKJ%-KmP!mt-Uq>)?mDlxAJSME}z{|0SSLFZT)?w-jX3qZ_W;l|| zR&uSgnm2WQ*?Om%=OS#R!V~3|_G2EK2&3OZadoseCKv$E`(7-GZn7JXKh&(_ zr5`wdxZHHZDolUwBFb4utG~qrI+I4F%q8zeC?JwZ;3ErWP(X){Eb~tM=ayU%HXJYsXPi+ip z>9;>?7p}$+&4@UlXh}-3_W%Z2My8sV6n)1`NRXa=*5ydZJ zBF@T|FZVbre{XI(^{u)%XxuyPDU}r2&Mz9?9YOCL`VYo^WSCaMsWXq~2xKUiVw-N) z!;X?>{9iA?NVH116olp6L*pM!R#hy$yngmbrrjUIbOGJWmiXUXf_Ow9f}`Jt%ZyTN zaF^wozWG+(b=|+1rfHyTSL49UE(aR(3})!NA7-u- zTL+EL7@+KH5Cj7Yl@$W@As>AgHZQrdj7JD7d(tWBaXCJ`r#^d1c_R(DEq4>2LCA#x zC$sZojTByr>;xWQ^Ch@L>|@hoHZKKU_zLAzPaYa&*Ir38^EO1Po1U~iMoOri6=Fmd zQhHYeXSR6G_NCM$9gEfrG?yOR2;Rm zus|3IKptd{cDxca)ivmxCj~TQGlP8?*gTQ^RKh{v7ya<+3;_>T!qbCfy+LTlUGA_N z747jELx36t96`l1xEO`X2Ar9}^{fX`B~KpNEZwX6@ZPkU)5dMSe?FIDp3Yz!CtR6{ ziLk^K%)j6Ao*J`xIPmVeQZkm%j8yQ`&`%(@w)2Sm>=aXWLT;t&-~O7fd|Dyg5(y>W zjA9O!4M=KZUbvHD6%h{{c02?x)k#EbpUKJ~DY}9;28^Q46V6?rcx+68B!L22N;fr4 zfdc4P@TmCnepOpv^^Alk-ust#fXgOOq%vPQ8O|XZoF_2x_L<=xu!;N)fASMC$;_JP zub9z3T?&2HW$@6>K9CmEWc^R!+Z*T8;4#HKP8G?*7!DS+xY+1HuW`??Q|fsFJPY)l zIsL@zPl8_?Qv%P!KrO**^gQZx))k=yjSF6lkK>kXMks~H5ipt6P#W$3e}uhdSX5ou z{!Mr1&`5VT2&jm3iG(ymO7|cQDvS)E0@5KNAl(f!G7McJjnoi=Gzx=&yqo*^KgaX& z-CyzW*y!5pTIYHGu4`fZXUqHE5LFp&-romSw7)-a)v=_(ehxvGlOsDtz{qJ8`|)D` ziyjy-CfdX?ITe-UOncC$(cfG49}9$%tPhh1LNC_j3(~VD93LGKlm$)fU)+q-S||42 z5XQ)`e=PP*8u<6T-*S}MbgMI2J%TanA-6nXel9Yd8`=Yzovls62lUN{Lst-UaU;~W z#FdgU0qGmiK0nxwHqHiI7mBXCIi7V!E>@nC2~gW}N3KpCam#Hq8|(9BZ$iF3oAa2+ z_H`$DJx>?p)|$8n+Hn+r=6I;|3#lEjC@nDaIh2*(Ef`@iSsp8c6KQNb;_ z2vBrh-EsGNs(=wK6v;*$UFjG=)US{w)yX4_)(SsV+&!3&l~B_(hOezch0+h>LgXWW zd0UuQFF$e~NlW6<%&pve*9J)J|DM2T`^og&-{}t`)YZ+~o6N30KhBEBz>t^S_p~rF zE@ry{HGc9dW6bpynmA7m`dkEHQHW|n}*2(!V;+5N(iJ)0*nf#8ZqH0~w66|gS44-*JA$$qu z!J{gN-j4fLA#lHs3z{s-c?tM3GDtRfB%imJ+s4OkQOT130YR-Lf#wJg*xBO;@oQr< z@*CPD=2(AXw+u4PpUQ@I0L&$*G5W%$O~#Tz_cvbsksJy7xM%JJZqdb4LxA+~FMskq zzECxNhouJKJgPO@VTn|8fRD7=(rN>+Ff;s(QOI@mqMqfMbu8K|^bq$sFu=`fjkedf zdIpwaZHW2%2|);d5triBbp(GBD@#ruK4}RJ2LPSM@{BZZ6yBN^9N%_j=}IyZXE6Yt z9Vtees@-J`m=5oWo(wPu;PU_d)+4aN#w5&YEFS-Nmg@HB@WsvqVg7%nZ>WDFVES&K zS~T$3{U!c*i(ex)(b}*AnE+gw|B2@|MRESNB95NJ8Z=1d!eYM)IEr&liAgr{T-*lkf17H%S%1&n8$eu2Llc;cNO$~Y9`s8yeDhImf$~ZQs^)T1f zw_*)qpAJ()pK6(JM}SG?{IdAatX&b_vY2@Ld=Hf#dAe^u1@1fwra^ouF=F)(74DhCc4($E1&^@=&`~# z*<=ZYuYZ!?b04D=utecY>XitsInWy8*S}-A+A8ngUa+es0Vd{A?x1^eUnv}4U9QL$ zRj_rMaX+0Nf2fPCxbuTgqKAxum>r^x%JAz&HiES*U5)2#Bkn(>*?LX)wOUH+yUPds z!#=Kt&GJBviN90a2GUO)Sn+dz!l9>sWp<;l<8d{}0V-N)%dnL-;1J~u&QrYLmHNF| zmcvu?`kB%)aCJvw^b}kOrbhLt>Mn*Atv{!Vd|!OF<&TZ>i`5)}7;J}6cB4o?N6*}|K#!DmR2xm-H3ML$`Y9TsOx0RmBI0&Y98npr96E>92z-7rPKNwuCY;3ULoYwgG>vkMgC3o6$?o=Q5b5N1H$R)Gu zT+p#@ioTK+{KKHZ0vtD#dKqNNu=EHMs<6Y^L$nFB=Iq1}KB`t(KL2ZOT{`V-3Qo(| zSxCRnWaTPYF-2|cC*~{W`+;eRhXJHAIjJ?X609axxYPbJMyf@jN(!Capwg*0b;85) z_?Z%Eaf|He+K(TN0zfigma$(qh#G`GOm5%IeALp_qC|MBxb77vi6;pf{2ZakL&R8& zU5{Oi-J-?}R@0SHpdhcA2YtA>6_C*^mLUVFKayhTT%vz%=vL?qY=Q-;)ky|20A%zN zE{+eDWDnrF7I=oz!J1~=n|wEt2btTuivBfn<`rRn(VFN;)Ja>v-2m=U%rBv-KO_dO zc_?Bs)Q}$3*-{(_;$OT`PfsUE*v+rIb(1$55u2!&YbUqBz{5HEO0rnfE?A>fE2-nB?WgLOq`lX zEob}^Isq@d(>)YhT#FdpvcI*xlIUuYZ_2TeAEB)|f8>PgvwmDoA`YtMfCf$Qb^dFqzp2VE}Xv!y2I45V6CAF|Xtfuz;G?gTT1W zd1IZrk4Xw9)%jCvam=+@$-n1F3V#^Cu{k&c>fY_3+&SrM1uAfq^_!t}thi4JpCGYk zH~opW6b7Qc2L)ufLQ1k4L$kW+a2CXugGv2a<<8~N492Hl8L-93}+08wdY zY=9j3Q$WN@sF08z`y9qAwPzwbH_VZ$La1Vz?_*y&el>cjf z%&X=H%o_!0XY@pA1D0%XICifbFmgou3%gxJUeP79J4M-$15W;YkjzT#2K}}ujtz6t z>GJki)z3rZa`fgWK=$}Qvi8|vfip`-u1u$DFBJO2A>RDr>*o8^!A6< z;+y|8|CWL@3UNL_4M|*_BiaLR47t5xe5ur4V)Y*IMUQaQGW_NeTraote^1}(N?(pQ z-}Z)V!QT=NaEN_kCMCK8zCy#?rStcLl3?TsGZa-&Z5}eSPE@vyHurx)NG}IEG33gW z%hpxUwuGC0%Mxif%)j(oW8lpF&T+TTU4uZ;G3fC6%4m6NaS~e@h~)j@#Ju-T;}(VY zwj~x|0aTX|?LYrZV}BUbs49Aqj*E^LcMkMPNqOrbGae);iT~CVmh&&V#H?(@zO1@|HyVYHmsVc5X2yNRrORO2khgPog^r}i z<>b`;5P&mr^+&0emV$q$y&%=KJ>%C)JN|4szX`6buAH&=Kxv3){&c(CB-0CVOou--CRdbu<=PgAUJJ&6>n3zH>zDvaq!8>1o+2F+0SrM&3&i38C_-bOxXcHPY|)dnxK20UT2 z*;+zMWLOgR2#So{XJ9u3vCx5U{zZ5yJw-im6}kXAkW$gH>g#_9G~WyiYKhS8fr#<< z15y46(uC)(p5;E9Gt=uBBGSlZ;3mn~l-DnVbjl88EBBmQA^LXOvY*PVgsQ^8&V?G{k(m4lqhZ_SCUy$ zGqR?f;~kxsB9=6TR@WPgxRVAA{dXhTPLAzs4yxz%hG&U(B|h;Txcq{CqLpUh0kr6` zk*9pO|iFlOk6}9gKmu;$7^v7WGtA|U+zk0*O?nn^bOME@!vRFHFQr_|5+Uv`#!nm2L3cH6 zm!JO8gyt1tzLqX5L-aN~oy6ywof;aUl#YowB9^(#G^jVu;h3Bi>;S1|@enCGbN6iM zV@1W^y9PKreS#I=@!`K*^zxKvKDJyL4!sp_Uxn?$`A0~-9F!L4-!~;TDqO2TqUw{2 z3viz#v}^qnnSW1bXQo$wVAC1D-bSK|ONR^e+G6$ADNs5&KG>Jo-jLMrN^RT9XthAU zUor2}>$8a+iXBR*z-(AVCJ}y=g?=f%@$OJ~-n&DmG0*wjNruIK@(~r`^O!t>T71Vx zoU!ugJ|vKW5c?9-3Av zemfd}UR57+!U5Oco+Im3aedo8U#jdIoAyk&r#dSUSMsa9(;9mJLx0{qSro;rGPp0d z!gKI@dwY%jER79)f)BSh5NR{r(qKUO+929T>pp7sl$yg2G-622?4i}K?rQlGW<%3{DhGG1TR+f=meyFVRQJo0A z<1hrH5Q&#T$5LuVn(6Kt!G*R8EnfKf@dgpKjp42dIXMn{8i+F7Yfz|XZb34a_gM$~ zNgI=)jy0~<#vILU#Fzd`ZmAUX`<5?BU-ZPca|{d^S9LdO_pFQBCVo?CTX(+E+F+*s zpU00?Bd%t2Gmz=~6OCM{o}$w^r|TSKuGv7wH_@YxfUNOhontSg2to)yd~2t5K6Te~ zdWeQV{00O9OTYZB;4?AfYjsxXhxg*f6naK+(`RKjy%fI%-ND zzgbhhV!7M`{x*8QKo?W@1lm=CLn;v>Go%9?E4~}h{fdJS-{%k?iH8k#qkbEw&ER^1zSYTHcOv% z@Z6KbYAqFR_kG!X3LXn*$5`2yBhWOBEEi{;(-o_Xd{t&x`k(^wf)|EC-(3xB&Afw2 zcLeP-mp^S%B0{$n3>`U}QsukxJ#kuw=QZJGgvy)q%go?`xKuBnC(Q>IX{LMe@XgbQ zomIju86{0R8F;>N|9KqPRBN=d<~bHQR30;N&20CAMQgt25va*y2D6k1jh~n5(j40* zSmBZ8p3DW5En4k*o5yo5z<9~z{IGpvF42O2rliAnIssXm6PpCeA(ML!=VNqz>Pn|i zGFNs8S0lh?(NhsYN4=>k3jT$ssja8E{Kijo(zDLGZq!lbWruci=Lh94--WHh8N>s+ zHIIcH4XhY?F@+xczh7*fvNI~JrgRaZxx&8=Jce7YFJ+HH9&H3&%if48uDtEDQY2nc z%6mmgeIO{Dx}*Xw@t$L+}cFY~2&(Kpx=TE)>L zJ;W{4M9J>HRbv}+P0Bu&DMQ!V$@ZJGl+&qSCyl6!rwLpsK;_ry2zl?a7r1*8W4&oZ>}AA=g#U9K#^1iUteT_IkOOJP&s(Uq7^9x^MlK z$}IT0!6Gh_i*7GUVn95RybTZS0$b%W>oQ~z&dxo1xKLv6HWAhp)^Ni7_>6Ak*GMS| zXor=Sr)Gc=+g%R)3~NTx;`u6kPp`}1acZd?8_KI*<97e}%9yMd{#$|DjQikAe(v2kzIzvoQ3O$uBG zU?uVG(HA3{r?eQzMfGLQ5B2*hNa#|zM3`u|5+&^ja|xTUYjs5iEY@LVhVhEMMvIsR z#Oj1-Q^DuX`&oJr!%I?}f8^jg`($2>tvP=Qa39D-3+rhr7d(?&?fBv{oE9Gwa8P(X zF`9@&eNz{ACRiau`_`f#v4MS+%;Ttk&QE^cylIpnlIGV1e4xs3wahl~q0H4E!6+uC zucJagMCy4ulOliEJb!9ZAxk4mKfO;%X!n~7eMKdmds3nJ)awCr&V2Ij%%a0bee=c&E%8yqmEJ#e&xbV1-=GHLtGas1$@PA|E~&vSAqW&!tNQ&0@JR z)J?uWhWv*HJ~xyVCUb4v$aj$wBb!Vp6?8}v{=gI}WN(w`XZ3;=0sM(h7w?C9+JdK3 zSSoKUK16>pNX$vyuX(-6kuWvK6v4KcH6{Np>f_NbI?!+WO@~e0O_t4opME7CK3G6k zhvZ)LO90vU3;gp(b+2f2EACmnYDjW`MpL_3Cl#!YV7FvLq$EBL0Ef5_0iRKy5YkY* zf?wnHgQbbT`Jtdxs#GfZH-1h>>sOvBSts*r>0Q1eep7d~IpItcSr+4}e|@&>ey)*m zfb^3J$Rfb=vi3%8C5({Od?lc38Dmu9K_ zfq{=OeE-pThJ-TKDmUHZ@3^hU{+}lv1@SmL`&;q(RziC}7OY0lW-c+idi!^`1|~H? zay~tPt&@PpKRq1ni*^t^wLhL~*2ipwu;k6d=IKF8balG-=kvACQva*l`E~Q_7OvJT z2`B5>`cc=*x6E;6dMfGZBX19_k(&^Kif{7Nw@$v(SC zdaN7;##(ZXZ+Bxku$J%(Dg~OF^V)~P7zB6jx8;G<$Po~jBP&Nn+(?~iS z#;zvYWXX@m7dpuDlKE$%)?lszj|g;@mRg~ z^x>7Sx#yAFf2D6C3BC$iCi#vNU_#5;p=?+6O|jaM;@Fr;ZDAFj(dnpXBV)J_8cOz< zj61E1IhP;A1#*)}J0J4bhnv|G*5TK)frTAA13aY%W;>LE^It3_3J1j@(8L3eDfQ~* z4YnE$Uia}l21i#a@aQZPRpHNOTl_*Uc7)7Bx*oJhGwgcqSomzn2b3+?g$z?TN${rc z@uNNX4&^KeuMe^qkP$oKc`S*3F_v%V{|stdk;C~mw`xE+5^|RC&za!qo2Lf{sa}sv zA`{RQv{3}V``yT$&8&DBSVW$ZrqgpY-jp@9%-@m@Vij^72bU-o2 zkd8rAi7a+mui~OfM=`Ya3X}5J>2mg@Jq6En-)_oQrY|0H%?MPOsv-4bhd^^I*0F}C zQN)l%*jCKR?{(~xi`A&xjNAa)Z{L1;Yq`6-Pp#LES(hN*`q6Ii*-P2x&ts`Lpo%^+ zFt}{|HMeZuu%eXU^IdlHEoPe2`Hl6@txiOO{UCkqBrv64cc(In3Qe-1m)7=tgXXN? z`7i7G!BKYoW5@f)xzLP7`##*)o=RDll8B6Bd`20w-QiT_hQ(}f-ZJH%Y_h4kU`!q{1nQ`#a<7u&CI89DhU z`mc|dM+bB*&c<{t&lDS+x{1YyPr1~^4WbI7XPAPB6_yaITw(-~-=Bt;j-cW{j8$#+ zIxi<-5>MUFbHoSOPv4R(8 z$}e;JQ_55PDWOms7!Llw@OKZHDvP5Z^^2aa7nWnRZU$Yt(%M!E#ps+4AMHQhmmILQ zm&XpcY^WdVo;YEL| zOlq0Jn6Wl*-gNTv1$*#_&+bKJznPA;s-^DLe;u+u33#W z=c*G>&{2!Y?SqFo8~q)i%r(|jo|^s%;yCed?Klvnd-h%Vp2#|yhW(Wz|Ebr=omf&%z7$<8pNc?pRuzeurAr;a6xtJIo#vuusUL4NUgOO?x@}_qXK&TW3kfZI>`yspD z(^&=Apcb_(a(usyBCm#4X6JsE@i-`h3(3U;@&{7TpmxrzYe{a2)QzS?j7VW5kkm05^T7QQ@yEQo=B0m%59@llT?ju-6lR)it;~_+LdQ8dUrfT9rt0VCniIK zOsarr*>J-%ym!m@dCX114^ZvUd}j72sb>lzIhjE-kfA^E&u!L;qM~kNA;uY=@I>llr%i3&Veo{v4T zgV*Mh%k}Sn6!PAvcFQki;j;9jm(MbOi@~d7ghbw+9Tr6 zLF%HK2kQf<=!CH(v?c0RG5`lO>DBBoU*$G%e#PQYpqq7H+&j)h*0_a#-DVH8FeT#=g!NS>W3!{vF z@7X{3!YZPuntTDi*q5Ar8PfbxUe+&t0a3rr)0L(cQ&3jDKB?lRnRxWDq94QrrUIM% zV;2QYaGP?p#~sDT(1lL?%Dz9_>G~V(lpjd*=z7%5 zy^mdKQiVS+4BwUYUjFv6h2L8AdhB9}TtyNCfm*CB(~Buw%6e}+kb+3jvHXadX0>CX^q@nK^y_6XR^bfRbM zyri@H3D_mw`=f;;Dy{vgmwU(3^pCcP_ooeDy%6lEIKTWt0`Mp3-@b{VxQ9+rs`+D| z+M%W^;t#!}*k`+sSYZLt(VuDcvnl)EL=lIRio3LT7EON4+Y9lx#zewX$aToyZZj-$ z+cf+zC~<=F(bQQd2XuDAIjtMRZG6G~ruhPvUk$0GdEX{Kga3BBs0aopa~Dv$u3vqM zKa1IkV?2lG?VP9HI_JKU8gr(XOp1OWeIkb+g zpec~G+t*qDBSy$3l14OO@#NQV=E8qPFnRs>vMMdowNsXVLnNi;B<$U&*gLf8eFQRoakB!3Ds1T91D zo`$p8sqaYf*W@XW%?6=@xs?hwoS6++QmJUi7#TT|d&R5t$DiPBKn2EI&TR0WEp zpG=g%N=hrdsQD_!}Cdq)!(L|C9wh%jwW>` zlW@Si$}$U&+CE19HM5tm;}2iq1*g!4Nt_GVrzoCh*8}q)PZX{qgX6lV)2~2pnWG5x zv=sPM@AA>%16Ps|QKJW`;6g=$wXMt@P6BXlar6ThGB|(oMOn81Et%k2v|_MO;Vi5= zwmZRQe7^YDhYdNO>eUrd1kU=Pb05F!sjXXU;5g?A7 zxJvfNfigWnONK)UVFEa zY`)-3!)LalUefaa0BWo{ za2=M+p>PqKDb+a+wP%8*#TuuKjZ>pse)Z+f#Aa$ALNO_%YtbNhbQ_4os+d zG0paDkAA`t=CP%O6u7>Wp?jag_Q6?;XVh4H-g_fR(F{eS@+Tj1pm+3Wtm<2V_VtTF zp$3ECDj@zYrBQo)-QuU#&u`V_rkVbxE&Ak>$X}&3|LgV>k~&sMHlCsLhmr=jd`Cd^ z*E7v!`ia`kzZA5EoIJ5FWfI0c8U3eeJB|$61N6<-pDhz4#2&|%DtkFTDK?#;Qq(@E zPg!Mk;o=iuJO@?()=ih-eO#-pos3XNaCWJ0u~HPQ#za5*n(K0Hy&?xQ7e&12pUG@?4a+ zFZ09IzKBP{{ADipI@P%+1>6EBsS;jFGmD0g6-q{H(*AinwYKP{rw%4#rc?*>*@UI0 znYw?1-Urgvvt92I=%m=fLguU96qd*u2YjPc?TxECi+v?%hR|nAV<1bW@U|=IvbEeK z^xEXtcrf~&1A=WIX`&*?ZD(ZPW270wbV-AM+*3qH4*cEWyD-t~i}eYq zJ>TyGOXVKJpCd8;d*A%5mlf@HT%1q1*J$Cl$mf?P842;c%C?GbA@-W-D8>4>cstJD z6m~VV-&%+kG7pU4ZE}*3vtzXcLo?@%=PHxBcYoS3iqG<_{c>3b94Uuz*^!eMT!L~rV>PI%?)B?SQ>gFlLMx7jMm^r8NMXA4*NX* zBaq;UXfRO}4%yZut8Mgr{K*F-%g3~4r57yB^S%vdBmbG>yJdjjcz)pwGnU+m#?~^hmsfw3cmiubZ!SJ1%b1yfViqSL zHu~+M8Pwy>e-Q2ml|o{W=-8``o6x3C?Vz{9LA)E@XJ6HDBe#&biqre;fvut&-vt1& z$V!@#gYOGV5@mD*VZGUSq7B%H7XK=U64;Qp>Opn{-typXoE}TtL7!s$;{;Pc>%n+2 z_W&L}1B!PG(sosfck*oxfDzf3&~lf=oiZM4@A^1awMLTO4yU;6!Knb!Ic_UKr30~cHKQcmVB(ci=zav@`3dm7D)DB_fp^7Js zmz9UJy(-WC^U^@HPSzeMo=f|ye7Gt!V-zxNZ^e0@V`!^NSU@+cwsl#>9Ue$pM=9R4 zK)C-DlN+8nzx4ie4k-UwgByN@QB)G2I+MaWvXwJ-t02NRqMA{(+%ZtN08}?xM0(}@ zd|`!h(}&8?moV@981F$e1;NyFrN`lp`ybB6~f#&@UV zleq-LwbK6Hy6A$yoxMMIW`q0oQH&3kp%wi1VV9cr+wF=c1(9SW=?@5SCEtvEEx;vM zw`0-#GO8(qy9Ce;dsIs{!xOP=lEq?EquY9^Z_)wCrat`)yg`F+y}`=JEk+M}gf!t2 z2uANjtsu)~jfK%;nP7CG!cu3aMhT=|Ob*=}ZG}&oa3&9Q3d{XCQ2NpC5kr#Q*gj4Z zjw9Zuz~P&KtIq1dKkWX{Q@+@&4tJhnU)|F@Rw*$6S~$7p!bv59%bwhNy0p-`5N6XG zQl|D_{oZKtO@>JIynFcAe1bY2d*~64pRLL93+x?2)a79)Rc-d<8NokLp>=;GgLZg=iaHiT{JJ&%KQ2e=ptTKQom(z;p-XWqJb&F3e$Ua zZGweI72$^cx-$JZ{}>^>@7Gc}WaO>yzR|_DW!RKM(RdI%J{s>hdy_WE$@Dh-iyudlyn^daN)8?!*k2jiq|2Dz;avdfoUB+$uv?VQOlT(wTM@%nWZwK zRgTY?zJF^C@BvE=7B3_u2xwE!j(}qCih33+Ov%`?vBUBrn)$N*N;b3NPo9c@uw}u_t8-45-p4^ResRbY=-?4ev|bhA8Q|Ww5AnByGxyQ%;GX znWS&odJVlZu31Wm2G8djcLEPaGDKzrw#)OCXZ}h4@KU5t=DgR*(7Qe32B@dkz?VPp zbXTCmrpv-EIJveJ9|p0{_S)Y&2*J}{-&~JX&+s>3f26cfz)kvLRXk5+u{|^s4 ze_18jBkx2O;e;e%y$x-8D4nIDo$meUn(pTvA5|t%HoYXWFe((uClHJ(1LpAK=XG=& zIBAyF1ouSwJDBU7P`Uy%k2{x|ux1a9ErA%f8f)tXIcYWBq^*{9bOzmp;_$%XKqBui zvc1%zQ6oL;0u@S=ekAb|n@iI@shc)KlLif1VvLe6t>bHi`Hn#&KbFpy-}*>9m(~;h zT~@;Xm*o+JY$Sf~$JfvD($o8GpwLGk`v^^B$DcNS<*{Fn z|J$+mK~DHpSdIh6@0#P}b>m!?`2Hf5da*`aoTl^iyJ-!Zkb@9*x^9+YeLbLCp5pDw zn1#1vKS1F9{CV~{u;L9L%{7hq$juHADIO(XUq3AcHe1VBsK1`lVhFAXKqjszr61hA z8`D6UL{DOh^j|-&_#+kHxS0^RcM~_0VS-;4f*xYIxP|c$#c)-KqZ7Y$>A^?tJ3Qhs zP?mF8ec5#RPy###N}O27g5ZK>>&zk#j>M^|;TJ3{ms7h!T=zee%ckL`6y8`gQOvt& z=0-b!EU{I<5`a0yuJiPa`;OXEdUyA+_Y9PtfWS^LgsxRBvUarxSB0`l61{+@k_tWB z1-x#pGgV|7kbYPIE(!gA?>td}>kJQtFV8C6X1mwZxzYf-H$OTG4$Su~Mux<1pC%^1 z?dt~YX9^H4UaMm`jvbbLJc2t0eR1_GbYp$OLifZ`UkWW5=QAeSi@s+rf(FIH9-x~AD?PV^kgny81d{Rp!w3K?q5jA_(N3_QoXd295)Z zk9TTpQy$VX;X#F9XW;k{MWP+AUmlK~>vSwJPD#Fcwkb}iNr+vXC#k8bAVC^+-J>p0 zk@!g82G=KWpm0t)=7W&U8_bin0Jw1M5xGtOtp?XhLY$VF$xvAz9NnlN-Yc4M_unmB z+Uf3!b9daA#6g?TW({yL>?%EaTO;H=PoItH8Vw;Pz}ZCcuyK*wkKyDL{p# ziCTW=wg->wMaH{dyq<9iFQvS3AUWTimeClNfvft?N}P{(nVznZ5Zb#?9K{Wg<0M{| z=AOOMnavhpT=cyz(9eA7dy;o-;@L|{iTr+iFKpoQ7k#W|0zl^98%Ken)m$hu=#FrM zvrd9JTUfe8AxohPm?f8ePj`o%7~Fk>jJ8iDI+XXk8(cK;yMI2;$yi~dTTWbuEa<$T z@nthgG)^q%P4mbuo>lypN#Tb$xr?#^_=11!DEbd53ZNJBbwWA~Tpw0UG#_;`f@Ww) z{TDL}^z!q2j5z!)$@mbQu4L3?8e}LCUM?vail2(#U2dKpvtx_-Ws-;p03}xO_j-7N z17tq#LHVsXV=Neol9fkZ_3;Nx@C_e6Af;O7V9%YN#bbPqlBdfZZRM zU@x-KCRqKA*UL8p>KM*(dxz-e3Z8FNM4lr`EV}A$*18Yf2Htcvu?+-kc$tWJ)!kRl znKLN$MM8~CDk7y&?a_WxHHbu;tM!!CW`YUQ7gCRZ&Klo+!tHN_{j4d&@h}pR*R8l{ zNqiN)0dQ7Yxf#HU0ku*a{?nILg}B#yn%6NNa2^h)QxG55NNB;d60?Zc2?5dhgvHMI zE;6L&>&`dgN&`Zyx;q9fHf#%@rC(R(ry`&=Ec41+~b&uEJA%$clTb8z$@`w@u`L#CjNxR6LUieJ(%@+=#^ z^^^GoSmRqWk!aN*`8{LBvwu4Z5ZU}fW}`*fvj9KcvC!T~A!?^T;a`uEfb&0Z&ZCTb zd{+*HJ3+wZhl44~tpoN?z8Yste~sA&Wq_<>{CGD=U?V5sS6JogkSV5LIN&6js-f@g z3%iLy`EkOzXn!OPNd!q!;#RW7wv%fbk4~Gbu;#Yg z$l3_deAmol>}U9DHF$^O;!T~(zpiu%9jM!d=}AneI1mFxUGb0y$;_k{EA+2RT*PMi zok#J5Gco(i?kzRatrrjU0CKr1eTqRsHEqcdp7JLrdWS4uv&wB`D=RszlEM5%10o7L zL+4t>J1s~9`)G+#u=WXz6j$<_{VV&DO9Cey|1+w_pVIkrI3=AR4tB6pCd&6gBNs z{_~i;kgq-8dUdceONDVNPr$Ou4!msdSEKS{uCGt^cSww|1dY7~6;Z0eBAZQL<2{g9ltD9QomfZ#1VzfKjX4d^rfZJ`NNPbI{GhB-wcb-06 zn&UnAiFH_RQp%noM#Atc7f)|z3 zKYC~#W*w8r*BZBhHvD#YBD{7CqL2+-XraXi<*}DRxshH=tKO@`$8f7+S~cr>M8`>u zH;lHa&bx1+bXgvs`6Dy}MN7|Sq~G`7hxe|fruIAsto6^GHviX31(N^?4iF)=)*QpX zszTn6{N<$UwD&ZE{dttpcw%ug1~`#PvQG)FaX0EMaxIOy0tWndr1I!}&K%9puzk$e zZi6i$yK^t08F;@WX7gUGMfjE0$Y5~a!7-3a)3Elq;L@dlS6E1=)l$ToA~1yfMT3=P zK3xYJ#Lj7^C*|U*3@)( zztPU?sJky}R8l&I96~yzWGIONq#GoZ&Oy2xDJfxK00HTgRB4b70f(Vm2|;QIk#3Oi zet5p`dw;z5`~$?yIeYK5)?Nz}6&a!Z#1^U}Gg)8I`1QP*xruWler3GDK+RrnE%fts zXc+`pb*tla6D~Fo1Q$HldxULZ>xF3zY^4nx^t}T%J;GTy->%Uj0Pf;Byr;yhcvPIZ z4m=k(#{+8+Zc+yT1xjaYd#9-o#eOnQ-G8k}=}Vcw1aJdAUBJf%f*~#7d723#B4$v) zR`4JahJ3gB*nx1N4ZTUREw_sAp$40dF84PRHnq`8HK1L#DJLsz8>l_4$zZt%$ZCg& zP-_MF2$V<{xfP!M7T01(@n~W7zojO)u26Nxr69`p@~+Qf#gXEN9W?#1ClP>iFK~J2 z((i3<)}V%`=*TOGUgARX9o=9rR5y_ zUaU#P>;9VPj@Om_2)pm3@Q>7i@L9c|6;19k97$MSmGe?v|wD(6^*kMS|ZLF`?cV?&DIvI)@t-(NELRv=JVuir|!^5w) zi#1PnUrVYtBqgOsR%g=28@)gP$Hom!9k{EiK)>Q>gFz!2o(+fWPz8 zyfX0BUl}PJU)&0g83ft*xgEo=wHIwnnbS_1QfX(=Xv!CSqg^ugV;FgHyon!R3D6v7 zHIil$@F_m!3VrfgUJtc<%ewVw%29b#OaAQWxZVR;Vwm(6#ob`$!}b}D3^DK z&tDo0xPDE!h73(PQZI(3-nP|PRMf;0ymWQaI_b(~@FUuQ*&KcQ`<3>BY?Gr)zqR{r z-$1sY2UQf~ONFwuTd&%@9GVI|uNX@*tyh;N3l_}lM|AO=&a@__QJ30jroa+Uf>k{* zioobsh~_s<0_Slv&v}Lw(&uLSWteUORHCWyfL?~9GU(826Gb;_@s5bdjGr9!C1P zR~K@B4%FwpIMm}?1@~GFP#a?{W^0{Mt>4)q&TyR}Guifg$Y8O)t-oDtZ73O1m+IX9 z(Q?zui(ZoruB5}Dh@dwb9HDc89bo|HX!p1Z%_NgkAr~<_8)@QAWhiXHj z+QTCa!Aow4$yQ9;Cn=myc~i#UL*e=8aAnQss1qskAu}^`i8H+gh5X;KB`0me<+@)W z;Iu1zY+9|TMm|l6S+&XR#?Btr#Fda`-?(uY5XRn?Rx@$vlLFWkIHEA&?7-Ufzby6R ziRal?=6c0-C6|mnT=-N?IoPuPHm}@dl1|l9yqL&wHbPSlEy^C$VDaV|Wj%RB@6xmO zOIMfWV)OdyL81_nix|b+G*}0!TQjf)Ln3qPH-`B6tkVMpI8@xKuXD`;`1I_)x@a zHU4~kSaZtEe_7b)!rWB#T?4o0e&&JXAd3b>DL<(lyCB^m?Fj4PGGkoy({zI!<&{u) z6ueJ^#^}eh=1(=odR1QV1NNV^A)oQRn+=^6t7&6kd_d^*5iVfTz!U4NoFh(;cCiX5 zFQ3H!dgn`ok93_Xv6>BNyVI61VW#;Qhgz)!I=h;qG+#vBl5k46BsLlMZ_j zik*VOQ}fiOvPUtII=(RrAW)=Oz+UZkVrQ9fV%e*B;hUaRmIkYcJ_+po^p>x6)@@-4pCMzfjdlh`DDIv~U>{=h#Y zcp@XX$poh7F{Uf;-LDA8pKRQBkrxVjd)sZ=Enp>8`wdCr-jOHhmkkS2z-rfi!JTG| zbt1=_4K_7bZ#i!QchIUu%>>p7WUcq@O2EUJHHbWkQ9oiOqCzh%dZuwJMn7gQNZu>3f6KX2t2E%a8$&E_x6Y#LrNk%YF_s^p)mgDEbBJy1tiu6V z_QNVpKLQKC#8IJ8HkDuX^Z~Bi`H?ZK8xzV#)?c%UHH*W1y;U&pZr8sgOEi&S30>`+9XuObwulYy_U&;C__ZdMqQlGP|GYU#hWf zB;x+3e%i&-2lX4Q!h-8A0ogK;f18+E7~ zKG3mQO!N5urAcp>q0f#It1p6;@JOx{w=e%t77mI`0bGKj+Ih3zpnlINzAJmmn%yxO zTlAGafs<}@@;8M@N#XW{44uxbMA9*j`8%O5TU1_D;I{*jr{3e>d1>aJw7=e617K)a z)yhTsX!Azizvb!BcZDJvb_Ls5d3}@KZy51xzbJUMFLg$g`J z%u!Rl|D?8c@*8W`81_Z%AL9xsWQccbzP`)N)LkDa9WyUR-n9%Nf6y{9BmDw}#ndas za3I^ysuq@wOTln#+2l-H)WMTH`+xIHH493MW1`qB8xT*a5Obo<>KEDD2{o)kL{5Tt zHvxTbgnbe*c8bJ<=nsWZ$|o*El+9oloY%O*S>xjR&;e+}=+Tnu%hwN%)5k zC1)`jinY|AZxW&~6P!ouX7c*}_Lwnm`f%`29y(K4nzeP`c@{2A)AN0rQe^PwMLJRC z1Uz3`2$3MAoEFvP+vg%9gj9>6U3*9=9C;2p2QBut&lBm&UyX{YcoRBfi*hmOu+6Wj zTrIHnp z-H08A_C}!5-3r|bK($N5aJ3>e(yN+}O(JyTWZ!2LM3Wx`4g@`-bHPyfr3<`>cZ@RJ zY~9Zp_3nfuV(x?&!KuX=5r)MIs}sucI8 zV^@lc2g~AHkMD#??!x@{jXvNHGE`$%3wd&&T;wCpWmX(l9!un_)9G9o%K9CByT<~X6Ri((+D=0+9L{)>}AOuJr(*-iQ%tuK!*hS@YqL*O)i-<1dJz0(#LhJe+ zgR>(YMXLzOhD?Z3^x}C%3(I5GisH4!sQifPnf^2fLVunGu8#x^k1h+ zruy$W6+dxsQ&Fl>T2r?F?oxyU8C^=o_)|)gRV_JM<#_O*eCD=cx$jt}wjB;1l9t}9 z#fmwcPwYx-;X8~`jV`zM(fwVMzIY$q$fNdXv*1;*`dXK5oa`fnP3Dq~S^|ovj|7qQ zVyuDc_N;Bb*RT|fMjXXX3ZWjr@awa6BXp_v+qHqn^>eH58sAOHcsprYx_dG@>qdK| zNdGb<}xJQS1(N zjV+zMD=VQ0URa^-87kQ#pB9a0nrcnAwRk@##l$@#!2F(}ujZjfZ%^Kf>|{Y1 z7IbRV)$&u@8_e-Yfk7#Chy@Cp5EJF;m75?=PpdG;L@4E2Pd=xXX}Q4C{|M2GytB2gI;Mze{ekepsXG{cR(ioluX)_Cv;uVC#QwRdZ#|Qtd~9S= zQafANiPWCuBXfIwBoyr<0Sol)WKtlMc8|6@Kp5HjL%DqTlG%?)R!HCA<9iWyqkfOPXR}Hyj{_wSf9_@*w6Mjj0nr#GpR~8P? z(o0J6W@s<@ub*No*`?&n<-c#lpGj*K8C|{ul5B+}h_`aKf)OX-kL}Eu$BimGpKL*h ztlvDXBZajii0z;o(xw~6{%v`dF|7BW)W_J!v6i#0z^3|&exQfe{+tiSZ6Ip^R=9#; z#WA~z9kE9dh_iqhft+y-jYq4%771?X%;HGiZKI#QZpC^|OzQ(QYh)HJ4T}IPo_31j zF<~TeH!k=IC&M^#S?kF03%U#f*8(>|3P@h9vfsa*RiD{cUuxExot)*Rwx#H})Hcl|7$8N`{Zc6n?i!hs!dXP!3HGVNOV_Y>N#^E19 zNY|H@SA^bDI~`j}TLGSeoC-@XON&-@!zD?D7m~cilMeG36kU4fnCk`+G@W%v0j%2` zq&p^HQmhNZvF7o!X;X<}Zc{*2h(l>45G|nPD5)hUB=_NhGL!J+eFWyiXaeuVzJNFg z0X}S@=(qj0r^V)j)l3%*6Cyf66EgmY&EKJ^5y-l}!g(maxJhsXZsSyu^_SC9A3pC& z^ngwYEhpP@&|B;E90;FjH|}~4?IvUC<>5cXyK`=E&cJv|AGN2CWv7%-y%Afkjs@nq zKUaLh7)Q*TZ(MxwjO^asTtntbzx56REo^?)<23meE(p{97LZu5NX=geIgHLdp|RADX@r zW8dFP^0xtQNFDnZIXRa9n<`zdD}|cL>sX9A?m`?)mDcC&#L^rCLk=entQ;ETM-YMp}pH z?OIa&%Waa#10@_|nI9SGfl8yb3ViuOO-=38o`zUaukWSaS6X4_=pm*bB?fU%a_WqL zrQ@%^)xVqF-!Df_csF}~5m zcsQeFbow&AKLb)LuoC#cpV|`Dm#9;ut$0O}4xEH@YjY$$7yOHl_>sP;_VjIAK8j7CdS;pRZY0R9 z;~ys=Yh1R|B)u}LA|PSf)Dx~wv?;D;NBT6=1SxzEJi2^F`6Nl=Kgwp8A`TAUcC`Vv zp8wCGJ}Pwf@Me=hq*i+CB|Gva@(4bO7_{dwaflq_sl|t zC@W2M#uoKfi?L0FRg#>jO`o-{G$5(gj*_Yn`3WSDFY;w-s1hyl7;Ph*W{0wSQm`-F z7LBXCH5Xkx;=!{T>n!;c-`^FA1xEc)*y!Z@JZY=p>C6tf5|rCL#(d89@hGrze>f^T zvq#~onCINl?s4vpfSj3AVwSE|5PfYL*|Wo<3l_kNwtS9yc`@J*|mO$&uSjAmyuFN_7H=fcvS=?3`OU^7SxreiTKA3_fxfVRXFCV|Dssym?FeRZwJBU&ZNrFn#)10|(Zx^!?x3X0W2~F(t+E zT4vF8d1Q*AV*Mx`5i&(RVj()do32Ra&n|++a{0JkbC9C6=AZ`5;QNnJ@X@$99N&k! zGwvvvk4tvPF$RB7?<`_UHUFy)N@uj;C)Zr0{nNxw{)F$cm-x&NocT$*~ZP2WhPZ5^p&<0#1AwE}jG$Os8!Mcbj8}Pds7YHy2B?%vXbD zD}8-#EmVN->WDIlfaAi*D6|l1kZ|UMoM$bY_J`eW@`86H!hUKU33INfg#bUSg`D$- zElp@a8t{vL%*@dYw(!6@~Z0 zO%3g?PwoM*;qckcqsgUx|5uwl#CCR#7ebPoOn!7OrzlRvJYg|0(K^Rk_B=a6`GqZ$ zRU1j{Ru!5lAu+}pLH)4Q$GDq)nvvkiD;rM6KH4PEyUe=LAhA5e`j;nb}vP6R3!kCk%Nj-<#{f@@t&D3~#DVSw757cEUzknBXLa)1=lTmDJ{?y-0Iu#2a6u z?6RdyHfWx>u5o2dGUwe`&-k=;hhI_soJ}G>@;epSc-I=qB9HL}SD55V6)%XV-l*VP z*OG~ISA|J)KppFoq~0E%gg;u62Q-elPKi^+o0jJ7B2Y^kqx5GT@84DCO>dy0`^E7@ zxXm=q=|sMSHQUr9wU&;k9`0;7s?ri?9eB+r>@pCAoBDYq(ppEl)SbeE2ZtX?+%ho{`f z&t2B|Bv8f|5lciWc%U;*1ZS_PpQLgX^a<>Xc%5uJ(|RFTB|gSZ@5^aPz-9`M)_b&= z739OfASVUskayU|=sD_ButkVmS>|UX17SorDf!>`;}m^_%_1iO{@x?^T|gmvIXuuS zIC$PHs6=*QnWBxN+}lNSP&m?2JH)z5Jw@fxu*V&1Ssk%f6Xd-JP%2mZf*Dza(eKF( z$v5-#yKxa*WI7l+BvHuE!O_a4-k16-gn%c**U!1*VQJE;p}H8;Bbn5F4q9ADd~?;` z8l~7Z%wjFf&cA;5p>iP|!JO1aP^vca$yb{t^3dF365Wh9ZTLEMt>tKxgWCyxHwUe( z7QN-Zn|V_+w`E1H0o&F)8=4dp<$p3BT=)+68UB#`UP<&tUD-LEFk zkyac5F62SP+}mi(0nVAlr%77n^#uZfMobw;mRY^BTLDcVzj zuJgrodHZYLmIuD()?9h{o#$$kT*hII6On`8V^GztFBJOf`NASnKk~77wG=>ww0N~H zeZz$B6i1b_bx#Y0MsH;dPC}(AF?*;1N<+9>Ws!`d-IA6gpfdR~&HsjHi!Yy^;DDpd zA9$1%C%sLJ@{A^mDRCB2nNW4L-O!G1{b?rrO{Yf#!Xa z?#>8T?y=<0ahGNI?bnwpdH>a`MN3$DtGn@ zS2NKK0cpzFnK&aUo^>mr$gHS3dAa~40{DSf3450nN}J>IcfCZDtCgwj7h_=X^-JU( z0dfy91DIHnJJX&Qu7GqRGIeX7q)N z&>j?ZBJol%V^whCT^?RO`O_f>!RU22F!4NQ|1SG#y0YIz$?MB@-T%$HQxSrPY*BUV zG6+k$?KLa}i+35)>wi`VcW3nMkkq6s6;i8uP8sr5 z4tIxJL?;~Y-$Q~C?sweG4D>jYu1HUdyF#n4K%Noq$^+`q3pwn?HDsv7Ilaj6^e)5o z#(Yw7U#TN|(wYzbGKP%R+Ch%V<-*b;6E0yq(~RZ7rM!kPI%e%U{%^_-c@7WFoC-5` z1}6Z#rXbY6(VifLAVc)Ue6cvFOo+M-<(Fkpp4hK@V*(l={9^c{zjCKyCp?7g7g8p} zZuwK(!2f|Sgiz&u$S9z94by&5qxQvSZ*O$(^b|K@*X_x3ce!UBG_ab$bGqG>;w8|o z>ra*2=Qq_lY4=Ssc-Cf-V3FWGa}&PPNS#+ew#wVy4qHP5gMrSgP?S$qPXnc&td613H9Mi=EDWY@L9h-fuF(hZxXz2jdOWSiib@dhdBDF=adKMO^eD zB58eL^@5q`(ePwZfuFI5;gqYD3Z`EfBQaOIJE^?3ujlS7Y@!=j+d! ztDfFtx^H_VKJiUfAn-X+AoeL3-!6?(UVd8=GseDnO;m_YMo+#^c5`^=mh^Cb9Kp$} z;WSe{WVB;u0z?YLY@y!rR-Ts2Wk|qcD)7;N*xD#nY=y4sbLQL~KbuOikHFd#^BNfd zOI!SVK*Qe0VKE}qYm}cTpO|1*`K`eM^_pu&w5j%kl-veB`y2bsX*kmOVPruXc?9$U zLOFWPF^8y0aR*__DKkj#>9st;lJa!)5G4{>lk@RH+4_AY&T4SSBcq3v{YC}i@l{+6 z`%M99OISCg&-waQGDaI4r33GzUko{u>!+xdy@vGl7?4i$BN_;cVmj5t$G*{#xzO@q zt{yiIO}dR;;0uUkQsc|pD}$2Oep?5H69c$BE;z?KAtAE#tM1)L&QheviDrMMo1m5r z?uV~<)|!n!5L&c3IHqQCS`=>^Tm`F$(_}x}90VpoQ;F@Ah0+G20w*<@o+6(|UF~Q^ zB(TqmWo{}8N4Kjg9VmSGZPFefH9^pkk`><{fM2JO_k!B7X8Ae0`Ejk7r}#}Ct5_qcl${xfLtfo#ozWk1~*nQH|uJyI6Bu_ zMoa^lB}g}w__pIENyvd6U5sA+)%L*Ji_aK;c()d~g8nY<+tzJz_oY68WyaeU+V1&B z8c<({3hy7<$XO2A=%nvPIKvs@*yGGZ`l~&1X?U|Ex$x5C@e3@;8I{i4hU7G`w74l} z^|{-qk*P&$iDeElooe~G91bZCL*Zpj%&iPN$e;!S@K|h9>kAuER5sx2OY`;F4M0`h zs(lT%0`v^*Lml*&me0Bn>KU6k8t(ObSihRa_<%|{dh(=Og?+y`P1gLrJi2vGzEX>A zH}l>VANR>GAKJvT4lVki;+&ZH_6}-)&zt^4x*fEh-{tJi-X3Ll_NBy}If7-$Zq5Lp zqjC2if2dIfL<|7J+F#d?q6a^>|9p~2{?dP!9wzR`_&6sq^!fRjGG4z3GDvU<^E1cG z9Hm<}&zAPvl6yr*9AL<1DzWUgGk7iY=)dB21bNu30%;-!{lmF&D1_m*-CvZ?38eU& zMn=ov^5=MeW^qNeE5$8XvWV_M!u-qD6)*e6;ALn~5mR=U{Gvq_xkUc(NM?ek=$d3N z)Q-N^0!622F4O}9R08fK9^UO6V?2OS(H$`vsvMxA(B*BT#p@83WfozT1(!o2n*;{m zZL?6}chRBlH8ZhhM={+QuS)Q}``tltNdPhG^43PR77P>4PY@Do7HJ6NUZ*D#ThdbG z`siJxT{{WR(e@PxoBY;>LeyX|iF`adEC;B7HvKRzUGi4FG5u_B@~vzLzGw9c)H|08 zl9(u?PH`xC*w*75I}7dDm#%50thvzWD7B6M+}eZiLIM)#ZqkmUe`}Z5fYu{3ygX+O zkpZ&dS6CgdTtlRJ5K6zJw^#s`~b-eda_sDD)`Pj<2gp#tFr0*wN<~Q{a3$9j`#2}WUvS% zd4220V5Kbk_)XV7zcB{sE!#Di9aQnlU%E)6(_Xapi&t03hvudrPKtz2)q+PdD+JLu zX*TlJu8fE5sMKvr9chn-J-P`L>J+~`{($2gzYmE#6$4Tg@6n_C6CW@kDt<4Zg+R(F zs2bJXbUZ)k2!BKRfQ4C;w|pc)f=yUCI8VTUe=3K2M~YO+tj^0=Ac+|k5*Nr>-QPkj zK8sKQ>166UKbK<3u*cO08Tv2Q$y0cFwE&K~EhOR@g4UfVgk|z31b~q~Fq0-kkwF{QMSFyCfqB+@9gZmI1-RQBS z{)^E@8r(K>NT&wnGtaMxPqASdC4pmHEo7N=zs8E$$b;LF8r{5EIgy6uafY~&E~}b= z&wC)W^dJ7R}ON8o)goM%V?X-O!b zteR!FYmAtk)|N@4sh_wBp(7RHQlKZCfT~Vlwg&(eJ`8VNu*>L>xqrvMgGj{v6EF3w zxAm7*RFh2VZ4x8MC0sM)itEs|Dtb`-ya>q$`bx*9`F@D|*`Cmx=Gtrj!3{3I zL3LSK&VZj{cX#+Q=-Rf~`(7Z{1Q`M$gvPnS_FzOZt*fBA2Q{$oBnkTD=es0M#OP%x zyfk>nIJfoV=qdPGueRodVR$XZH&UXD4Wfm*NJ*^mq5fqHN)q-$@@)@^TLp7Xj&U<@ zWi~xhNpVw3nl>bBGu)Tgu{}<52^^ONrB8ouhP&Cj>jNshUis>{ zsOkbtW!8LTfMEY+QddgoeG!DBr{ucDNyd%9FxJ2=TBH%8F8NuY(YbfA#A;`(^xm57 zoHNQo$;&42Pe{byCd&38;qGe#tbH(E+CK3}8SHmY|>B@~d-OmU?ar`b(Ry*$4|@2*mx&#kGJK zZCU4mpQPA?05hrb*4{l2>nfo+hIb^XX2L~2+Nb&@ds5LzqsJ<$*FKLKk+h`f(gzs* z?)FhzO+S}HjrmZ^mU!pEvPtWQwkJZRcweg)6K$=y_Jjn?aOqXHU%ae181++3`55-l z?OmPiJoMUgtN$LA&9#q{C=1AZo9QGNT}!=#ccSO6=sagiX`4u&q9&FX%U7?H?BYq4 z`hG>;-i&)ZTD*)^fL%31*t@VDpzj+m6OLWR)EerVWe-wWyn$j~Mh+K@Sn=UutY0jC zm5t)$m=kvttszan>IwS%-k&=cYZ+^mb6i9iz~D8>O3X})ZygA2gl(KpLYs)noDYC$ zpFL4fNpX)xAHRK^>Lt=nxJj~qCTQz$=F_?EaJsY6sw!#{b-Bx`X`7@( zb?c_NK8ML3gAW^1hDSzVjj7@*uS9yhV;&GHBtA-yU=A(@FLcbMJ69gKXC19Mg%BTc zL@rxME{9H9*5vRP4O3g6!vh*CFmw^>h2!<$2q6d}73pA37pLlrdK!USwAh!NR#vdLe}-s5(10;oe|uT9Ra0JGa}@ZG6A8%_Fleb@UW!!<=&9u$!$L267ITaej!t z^W!|e7XUq4y}+@=RI47c4u8S}u93`~HyfYC?xkL{|XK zgK%di809|9w~1s0;|Nqfq$aDvFrlp>k{#1%Qf$7R99OoIRgQ<>#?4@ub5qZ=*2(^~ zJm>8R)%&s@x4HlKS$u^r`5_hZ;K2@gn59I)zdveW!Gk;@x`+NHSu;P(baWh^U_Wfm zIeN^ja`+L>#HoC8((}d5xXJ7rL43iF@!SYh-7foGSM zg}WM!PWo6KGwlHzBF~TD57A4FN-#@4BSGK8VL&}+Hefk?$!n!#n!+KQ3p+UVk@Byc zh{|15Wk3U>jSPy-P*SY%VIVRRML!M|oVD2hT2fMIZZgBY=3Ep4J`D!u#;=vrXtCz?@p+%gpc8$=;(Z z5H6+fyM7RB;w#qPMe=TK`MPczh}e+Pf%hEQg^IQ;FmC;Wp|(Ky0*_pxnTD8N zcuMwRB7|1#ggcO7!5|7XJ!UJM^3@)_D-cA1#L>yviFthJ2YIj7 zfrwgPY8z^nFm`>!=?lV;9!cSuGOxhuCxp)LYbHMWkc`uINJ5fujzXusi(p4yD+Jz? zbEcZiBh&5)wiDw+N8d{rEMjHR!jbp(9@kMeHa4$wjMnHV{&!N9pug#Ia|I&*W@ZY9 z16)0$p+^@;^TOt>{PDO!Bw_gEXaz#L2Zi^h1)&r6u2MyY%JGKl7IMcA@O91NPs#Mr`o83bt$q-T{tH+r0z@!VLz zpUfUO#2^cOzsZHgp&{!&d`#4(;x- zFU22Z6_NKCr}#*f-Fsg4^sht)o3s}f%~pSWIN8p3y_N?hA5!c$YdmfcSKi+a?hgs1 z8?aUxmT9`MbuGSEC(nbzu!BM3%;*@BF8XoUL+Y8&>{&KuZ3z&3SO)?EvR9eifcTg# zB(`+{SP}!aAPk%Jp{fRhh^kUZ2g3uoVt7Ivwij4#70|<0HCOxkzuaLEE<HdE)5f(P;j{l~eEZYyy=dU&;mg%?XHO0_3eBpk)a*KC~5w(J=NDnX? z5B7HimY7VmzFB`}S>15kc@zr!n}5%4Y68|_sl|l*hjA!Q@A>n*l>XV+Tc53EdU63-uSnY_+cn33co=Qi$z%20W$W zwUeB_0%h1v2xi$9D^!q7>7gDkY3|$nvIGLS0yLX@17L4xZ@o#Ef#W*=-Zb z7*<3yi7lm`n^}F>qnSAJX0;|Eju5$^veHoY%06^)oEzVXEDh*uk8S2sA(eXR@n_yg zv66{TiS%9!iYC)n^{CSjj>OgvzhLGBRZFb4@tM5(V*LBWU$oh8u`A4vJVi}ncRRIF zd63$$f%39M*lo8OPy1fi$B2qW`0(YGJy5Y0X*P)CKK)SpoTX?2%t5f#iWwWHjg#!k z(of(a93V-c-DtI|^2JJ|sQ8twod~xEbQ58hQ8u|%zsy*~A&^cp&8W+=(`>ug;gT;6 zo!A3&Q&&xql2NF61SwPJ2*oiXAh3uF1h%pyWbxtZALH0w)koqCw06pgiivVv%n#Y% zuk$ZBR82GWwJ}s|8N?_Y!_#~O)vG(PNNb0Dnm{`Sn3x>oo{1~#BJoG#GH?XI( z2HV-KD2c^?vRl?WMwNVI44dN*T~A+$M9Y3}9<1T}ws@swdPOJvgd;Tljr(GAcm61} z3_u}b5=sQ|`_uutdV+&no|31sluE_fF`9Zti-04J&+H(sxSw*e(C6yEcaVO-_NW@5FcJcd&;4m?N4K8t}EQ)4#;5C)}^zv)h^0=h5IU)rsz-cScr8P z{+6_g!aZ}RF5*ASGkS_LWDDGhkNvvyse{Vuh$n%41QJ#QJTX58o9qXRv$f-v)9T(m zCn_bm)GbP2B7NJ-0;c}qP_H2jgxawMI){p!*GT+m%!?-7-nC6pVUL?iq`x-3GyYG6 zY4<>QusO`=tLuv@Q--IEF_Y`pvkwl-iKT1LDHX;0Lj; zw9aoN;celRoy-5zQTil;AKA6N(}1Mb%3$;k3kq9&I}u(1+q*cq*bQ4{!DyWTlG{y= zoF=P<=suN-u+EVU@3t=?Vv9Kc8xUkcvh&wz?DeWbn|Shi4f(4GuH4JxDV%d7!z9;& zVf>w!=$~62y$q|ilABj7*{KNx<9oFu!5?6z+Vl%u{_&!xeb*9HLlvU@IQ}_CM5=4c zj5l9P30-cVHS+^l!{+^H?WGadGNIxevXtp+&3_f#+wq#h`WK8s?sLmz`Md{bKW2gB zqJC*dWa8GFr#xE=T3EmGm69Bw`AM0V{0L_Z`@>8cSsB()F{7C}ZTlit%%=ko8VIR4 zse>3gW9dZJ?nY-Lc)_sAtd&h!@CQexo9?4hpfM3zy_u?9`E8UGZIt%yG2mBwAV_B@ z%L92liK2>hl!4Xi0Yt)rN@n)k`PholmbWW79zHw~lj$q)9_TE1y7}JZdyb2ef?|3B z37Wl!f$k6An%wNleKc7=GIyJ=@3b&N=# zRQ0z@vO|pC2syerhr_5Cu1@q|c=g8+*7t_a*))bqash@I)A;Dis%{`x_Mr|5&Zi&u z1fpj`&qKlLmw1Wl4{8YWMbO3+&PlZ6#6DB&?R5YSleS6lUBIuCVE`+ejDG#2@VL|P z>d~}ZI_1N#g8Kif1@Jz8Uo$1{Znoa1i9A*PEE<_ua!w6siTGnjBlx?^)*YJqe)J`c zuf_OOr`*8d%UlN6xBDLB7yq_7rGzG2VxI zbc%XPEFdI*EMIQbV<%rfIqCHdV2zj;WPu1CbIX*pIWJ<5(9?sw2+7DFAZI`k<3B6= z^}g7a7-8*>52Jq?4S75Hq)Xay@z@dmX;alBDv~Uw^v$UxV2z%9MpoFw#X+Zw*@QlX zvvZ%@>-ibpV>R~#WY_~r>;G-BRM{2&JaxO@Pg)+%cy&W{sESGLU;V6L6nLgI0^c$X zmWw3Y(Aot24fh{JpF zC{IC9AOo|ibKfPr;JfdkqC*h(PkSJC!~GcJN`R8WZCzp0q>#q_qQYCA$A>XM3{0vz`0xelO0Tj#d*; zmJb-PTIM$_ez6$%E)2^%-0*}1rRK%i6%7U{_+DzRxVpAi${g1@JZan)GlluxoP-yy z)PNr0`vDXYF8fFc{)Z1Zs&7j2+kYs8T>Jl9PSV^87%N6h1Tb8M2$bUgTjv!LaYR!0mh zMO5+9n0`BY)NGg6g>f@9WV-jKXKw5d(2a+1Cn??f5V76?2i9WFL;B8e| zIMVFzW>#KQ=AZPNOddx+(y}jqUBuywA~a!9cM)qwQJ(BJTMpbrRliC!{jsL?kB*q5 zVVIde4xo%O6m`Q0^9XYxzfv{}M*gY!pZx~lGeP~ttX3F3B=s=+xb*L6w_9YMkcE;< zD*8oYEt~9qtxs{B87WNXJ71qwL`2DLK!Tnm`8B-XU73L^zTdr791K3s@H^Qwb!{=@ z(@{>opxnwXI89AV=<{wD=HwoDC`_yL%(H_Zwk>r)qDX7`)<~#vFJG;D&^Aeys4GUi}oMz zzx|GLr+;4Uf+BzHwusB`*-$;vJ?c=`lAPl$5;SQ$0dNBOd{vJf)JlJAzuMmADHP|5 zAGI{?)@Lsk|Ch^7*t{_V9=J9=XayDqI=4QeYa|%7xLDri=1?%n)!~Uz_nud)aaTUg zP2roFG@2VtW_u`+l0BddogC`B@p22ET;TiV842GB=Y zM9_qPfGK+r-}r+PLBz|4{5*xNwW+9hvB_Y`f(!fE9X5+#8r2-ngE*!0ar=MTXXJ#{ zVYnhH(TkTW2{R&@NwP+KzdjZj(5MK?w0R{<3w1A71k;yBC+d|x&LG{T9aG1&DZZ(i=;gY@vtXNzs`E&>F!WeT`;1eUcQDmu3D|Vw%H5vTeN($Jk57-T^%&@F7r;yKKn~+!*STOLQz4z z5RdiifICo=ERoT-YCNN#IUlOq;q>u0Q-ib`TZsU|5~mDy6A!P+jmKP?e0F!OT`=H} zVI4fFFz{qSlke2k_0@?7!_(nM)6l>>c4{x#m?L`}X{e`x=1@eXXkyLi=5Nt5^vu|$ zwgqF=70s=2y$KH0#*N8h_pt)D#ESaLU9z|~1qcLMBK|H@HpIQA2fy;{oPzeAd2+6- z(SCo4uoa3RMP5G`aO;n5fspf_jes zC`H%;)8g3C;t{bka(Ko$8VNdR-49=I*->>Hb|`%vX_vBri-_L*wwNPW<0RL?Fy1^q zk1K?)(0{cSq!uiXkN^KL_Lfmm_FvR69fC;b(B0kLNFyCmLpOpjboWpK(kLLIpfEJj z2t$_$j5I?GNDhr4KI8p=pU=;GeVSQ|#nkUQXPwniMYhhrz{&fEH z2o;q<yZdO2LoM{lzM2wkUwN$o*BPSFs}D>=sXU^ z2GS0@k&&A+1o*NESpHM1uz)c zn?nI7*UE93t`5rWP_iX7bCT3_R{LVS7v{J#;;rX!E$vu+jbm1xvFZ>;s41n)H#~VeT>1V{yi~al6gXCFepor4oCJB{(BtA;0^>frHf+K;owK#W7 zLYUp|tca6!lpXZVAFJWR&(dVInT#SCew<$4#+9nuzVkGXw>~C$hdWIjvs+D4V`uW0 z&pn7R13P-i8CR#DT?B#k#0j3KMvUaPa4s zZMLFpWjJN;UW{tyZ@B#=iC{i`_37|ZI?h*iWQx=~mRrq+bNiFUvUQ5v2#gcSp;4T0 z=TBppSUbceS;=ScAWVF$Wc{$+Ia+%2BFU3((bTR9O=RdDP`>3AbkJJD7V&SDoJB_ewvKrpj z;rhk%{?;ir+eSF*3+Qiw%A;`(ct=V@;=6VCJ5InD@47Fb)=$w+?iI)2G+^QIlFDT@ zM;lo-z_kOwe=C^363qV&qt}6%=Gvf!{JbwSnCL_>WjbOHhm2guJA*_O_oK5*bkboS zS(yodjKJqr#o!{xI)fIaiE#}i8(5M8;ojg3&fEP1(6Iyl+_U%{Z+;g@{O_@6oG20c zQ(FLKi|mL~h(Iv3HI@Jy_vtU<%n#q?LN}%s!$aReyV9!YOn1NDay1UwXVX{?&~9$M zby>{ZyIuR(=+ydTypH;`f+={oV{{1Q3l2t}l5TI+Hatq3mxc^(F|kMx6-pg#uT1(= zS2D8`-KYV4JS&<1!fGSb*cHC{j@PQ&=wy9ev)jDA&!(JX2Tag=ni{#G$W$W%KY?&f zaK12uFp)nxG$B5~G71v<%x@IcrA>Oej@()ew16@rq<7Ne`Ukw8CGi*oWac}T&eOH~ z=B7s2PSAbW#M18dYY^pgOx1Mms1s&XU3{Ys&)2n4wJ8 z);1lH2#hDrJYWQXGt-(ziVN5Z;OWnapj@NZnQsaScHUb{-|-eGr#Kdtg1_O&PBmkL zxMOhurTQlL)iMQ%!g`K8%6^4iWjAQP825zNp>9HFQZM=~$Z~cH%Q!_*P;O39V~yQb z`#L`$sYoXM3VM|58q^?1E^xp}d@Kg!JS)06>W3u)J&h8NT}ABbzRaIehllJs7K1+h zHMXw7w-lZLG!u*JO}@Adp^Ok_GJquoqc=S7esZK0(l#M%1ohaQGD)?goA!THnyNf^ zOv|6WQMh5Uof#&dip47w>(YD?9ge_B=S?mknk3fEFJNexngRE{3h3n+^6dBQI9nT- zChwNufpWevRfJ+yob?t1Da&-6CY#Qr!6~OdRY!&K?n#ccX&Pv{&8Q)+V)guMU1kZ# z*t+A##tf8FSK5IWyVWD<=9!cquiYmCa8rApy~swqS>U0zQ*k#Z0opusM)`bl3uLgk z6ac&JO9rSz1cs=AhN)ZwMqXu(G}tAMJ?ea(r))zrR`^YwW}7|K>U+1ig6pXXP9sB8 zY(=|0dfM<)vD=%wA4>u(0?`T|4aff^1lNETHe!RY1Z_ZQ}~a zl#!afJ0ctNtQceo?R&~)9wheGMOu#bi)@Wbq)iCKI7?J6_mi2(N%8 zv{x;}-R+1Xu zUajAU+ttyxRc_|w>3?~vN)1}Yy>&-q@yb0-788W3dXa2%u6I>LdM?HfvGY$$`;BSlS zXp_x1cOfA#Y~Tx2P|h$T-Qe##STGxSYxC`_Yw?hl^O5wHBJOGO#!LUY9x?m3qngZ4g-5>qM3@5InL2^`3 z14Sa9(tnLvV*fRTN@)!PwkZ)GJ{p)Ke|IVnz5ES)S)z?HPP^!5i~F04JkD!xbotQ0 ziAw4C2m+m``m~p+A=3qP1Um@F$(#bLo~Lmrf6rnF1%$mAzI)9Pl$p5agI}5Ne0cdx zWSx;h#^n0SrWw49&I($d`A zPMx0kl_s#P*5M~~pk4KI47pUnN?vg*TjETJ#zn{1y-hhX3lg_^qN6`vS-9 zEzAqbG2rsui}pAcQpD(4RMlw(=SisxV^=M=xMc_1QFreTr&abC-kyll&YSix=-bfu zy{&tdw%vc2Oy$(QIYb~8nH~5+Cz|PCe@sY{T_6vl1pnS)yzBM*&7Cc-tvHN(+w|gS zv>GNY|E(;zS?u$*u-;T?-KSe5jqIuClD0RO=M|gjK~cPQKFs#B#=|B6UV? zOyEcHvQHlHNcsD_vPyH;yGd5!SDIE#y?;5&=Qft&fNbGW572H=ub>|hlVc2qlBW33 zM4fI%Wk5sB_(Ja!X7p`3SAkv2M# zpLo{jpZqq~peW;!{sbR9;ZdW|$RqdpR@-zNoRLSaLhLKfTqHyr!;#?l$f1@aU9{s4 zR_x;l5OZcN63KufLF(P~)Bg}snx$>IgN@>I_~fn6AMA>*0LYs~oL{&X&0j2Q*s1@DRb>sXf;QRo za`$GJMw{u7P@@&@pkiP!m6u}nKG$28KeAg^_mI4_6H~BhTtW-BhIA8d zUgIdgl8NaB9I3|2<8-lK+aKXvXSv+`Aivje3^%zi;9++GVJq`O3CZTC3d$R&%fe3O z8{aWWt&v6bxRjL&z+2~Lh1{8#xu9wU?*>rx4HM>x<}^&^V-`KDy#9Zfe7J>c*o1s& zrSp%r5U*hGL5w8c;Ln%IYa&6?K=Zcfm#X5=mKjhv*ifMh;t{c2 z%SvSx2VmSA`)#VF8TugKyHXIN3a~ViI$1I z39ZQ!9^&1-!JAuHEgSeQgUa`m4M4^pe`~9Anm@;5kVd2D(gJcDnE&-2TeHq!u0TOW z$02pmI6WKcdEbW{9y|MC%X$r(x|LN__9Xc80&eMc~bj2daG^eVTsx)%gl%Dv(4H-$!LtH*4&O(n|y;JT zc^(i&)A190^PHTvg=YxE7-##3B*GmFHS;(EON70B?IoY@G&`|)D9PUI3QyzpY4y## zyar<}(2325syqzXmv2V&Td1thnx!C!XIRSgUXJo2LRC}Zw-DjT9yW#Y`1tq%j_eK& zw*Or_*}7jfI1v*c6quPE_AOAw`7W@~uY{#M1@IEEp|}5|-Odlq&5tF)h(nkGNa^Pv zzR`m+OLdX9^&=5%=$Klko?Z%)*?CjQ0=Ey-`rTEO1zy8AV#^<8lem$J6t*HQ&s1)j z`QjXuyZ7t%wGFzBGFJ;}dE;$D32Z@5Fk^4};+=H^L03BOWB|J#`&R2D2f2eJ$|qkC zqoDwi$J+Q>EX{)~F%!jGMK;G3DolkB0R|&QlbHA>*@2g6VZ^dd-M_%*J+Q*#t%W3? zc1cZ-m89aXMbFfMQxqu^|2UL#y@9d*>;XuQ+{IP&@=d=CVkaa*(J(1QNOqO;`+#ZV zh`&k43+3U{sNC_X-igN#-!El|y`OJTI+P9+S6UX!6Un9Ift?p_=YKLml+Dcn)Q)nsDK`r@yLw-aA${ zGus7nR*r_HP6=0=|DvI?MSKX}SxXegF^V@Lv_bojc_Rn894Gur4vjx0POYW8NUH-1 zZ$lCmq?Lh1tRR^rmG2fWYclB`_-8%N3IjUr>%QvOq3oS(yiOU9My3T9c8yJ>g*7sG?wBGIEPnGqheTp{l6{|T zh+@ilQO%N1n8XoEaK=ylA)iNU} zYVZwoFi5c>8~VT1QC>K)(8?E~IGddnYV#}?fY2h{wk|k7VdE*Z{Hz)5uW?%#SwVt* zH}62O^c6K2s{_Cx0s=5-qj4CoQj*dL+yDnG5ApMe58pisqFo)!xNcc8D58kCp5V~J z;SF?ra@Q06aR*|5S7D>YhzYrm*TSYQtY3oQi7~V$T5>T+rza8{eaWBW{MSFB0!69o zTky|hX_v|D0-a=ftdI;TH|Qa0y3|*;Ze=UK@`U>Bnq8?f{y|nT?0h#6VE}my*6JSWjG35i)bVhNK?-Bl(p-`(B;E&paZIRvc4ejPaeuD6h>Z z#Qw~Or?r{8eO*pRA`n^UBOWkJ^!rm*RHN&*jL`VyMw>xifd|xN&_BX|eeH%f9Ou50 z+_zdDH+m0GMi(HR9Vl+lmM>^S9}uf2%YNV?XW%PmG|4IdHcpkIlCgFx&c1gbe{zlo zNeHjV$=Dh!I93w)f{i>4N!J){>}!pYj69=T)KeK0dQ}2C1r6Mk+?H<^l0n1nGwygY z?B;W27sIv#n*3G~jscxGaxOi3rL^~qr{CB$9xp@lD3c|~7;XLQKGXj~gh?7U+y1qN zFGVot6KU{yAN0A0eoa2aGT%bEjhaFVx{RQn9M_@1XJv8I+2fhA@6;%Zt^24)#^`d< zncILB1mBYEgfWwZX!J`yXz=`BEr6jt=a-v9X1pY8HmhiyfEMfIY=*Yv;2kNs&DPnu zeNi#6iNMtN*F`4)J8@mw`fSW-Z(JnfT_7@Z+#%_+!k<5mWqy zEz&~!yWv47R~lfLW4yE$P1`S53yiKk$(1oY@2r%fT=<)oIFR(*TxY-7moT1lG-MfX z`(24&J7%S7nMPa?;5bBN;#?+BnwoO$|E-h5}JURU@>{F(y;GN|P`r90Do4YOSy$|8mvI!$ zGp+|36wWdQzvzvzjQw;~bpwX_l0YT`HwGvtO@#yv%k+LZ(J$CUzmppb`1fQ_s~>8^ zBtF%56&q-WGjsq@6hp++l$=}<-QK_C4(9OqCALV{Tv`w(JTe3r0Ei0Yab=vgF~T@t zK8|(LZLZB;dcPP+6JuejXI11jp%Tc#-HF|6+o{;V)Mp?huS<9`F>d4@<67}|10UstY_0DB*XL6b_fEh}@_#RAzYCFs79bGzdHnNsFBi!7MLL`3F zFX0kr79o!*(vBurd*r_3)7z zP!LyK6q8;*tiQQJ0h146DqG(tDAigUKro&e-cF}qbI_WlI6ybF#el|w8UI4sIwdIAQ#^5Yvu^SwZgdojK6Vn&1 zXo{Qxug@$~RQv7PTl_ZM{a z)ej}UB^dzk*{u2?OyllTitcF)7n(^!>SmMS8*ubejJ(UywPQP37|VzcOHk$_av}?L zT4f$Bpi68g26p{_WvSIK|D*|F5$H~i6inl%3KbRqEV7Z+*Z=o3kSq}>xI!DW1B;FN z(bOdm_+~OckngN1p(1ldoY%|QW z%lwM+aDTs#N#9#)`;Ccm@w7{8&ok;`=t%PI#Vn}_PX7&EXLDilz~AXeK>%2>Y}J@^ z$^L4yTkkDrIizCU#N7t=lTVl8=Sb2pi{LO7Tz9JlJx>XBO@~yGcg_i@T_k_q+_yXt z6<$Eg(n!6t2BV=5b0uuH#x)J-cIfL}s5>-h#LARhshq;_B$P{(3k=p)OHp>bls>yan>70Xp2kFiU_qsHfSljU2X_xky2%`|J&pFuKCAhG}_n>05+ zXrKK9%X&kokd?7U()$T@vFvir1$EEmIpObv@0z#Nz9TA!5|lAy$LwjL2_oaVoRcxq z8je!YtDVAjiQ6_=f7LQHE&@r7PDH>)YNqV21 z)Pil|ja4>~QA%eTd=Wl4%iI3(g|%l;5H1y0viHb*JLOwe0tg!|QK3I9jHt-p5ZUXH z@s0YaiC z6dk)HTcB3tPC75_@}5aTsGzK`mzE%bfUu0LJ2|#?fu^eo`-s*f<HUnfV>5NiwJY$l%a+GurGKh%n`9|xRTOTA(r3sN6v=?zK zvVTI^cT5MAd5 zQ={VF05|XVk!)sAd=biwO5@_R>?LyN=sSxjeBfhA zeQSy;!tsdhUD4H7LZs9gNQZ!NX5-zdZKd!}F)~(R=(*FMo(ntp%3!ZV8IbP%&N|`` zQmP^toQYDlKyMEC?q`->!{f;U7Sr4G)w_A*G$bAW{!BKnaRDK0$e2wV=Br%1sB9n} zkRGY;D*<1Oo6XGOAfif_U6%X%a!|&34Bojdj z>K}TxioN>!6Eg2#LHfzw2aAAYsn{Pgf@QW6p7r^&7lZeqw5oEioCfqh<{1Vy^43o_ zq?6T^u2`M~87VO(7tk$C)scJlbCOeR7R^l+#T&Rl%?7SVVIrv3fGADeA_}#iIg3VG zmxnC9lay>e4|mTE`nn1+qZsCP34@>k%gHXb!~fdw9YzmOGM;Zs$^v!TqWR-m4FHmn z+uJZbyI$(}j^D-o=z#kRU@W)Ptou;}D7!W4pOTHljs){%H+SVyv;%-dRmn7Wq6lj(jV#-;sTsx2J5(x!Mli^{&wM2^q30= zfnaa^z4}gFJQ>RM3_w&(POYiDJTRhqyH1#g!PVclz9zq?^uK^N^QUf^{4klJ^MrEf zaxUBq^xk(P2o}`MwnbmhF*yqL?~!LH3ufL3thqR{@h|QX zjuixsCT}Ym*n1V6i}i`Kh^whiq75$EU>>T$iiGO_e?SwTf0~3SeyR|lV@ZeT&oq3> z)NKx_0v=%+g5h>e2fR6r{kHCoY%~;u2+Aw3P98EA zb0VkP<~p+c|D`qBeA(?Dk@dLHu7J$+(^teGb;#<13Vez8pBymR`x2Q||68%ZfrNmN zQmZ>DOHL}&u$B(JD~7+HDCPK-mk#AGvfnv6YLobf=c!tVIrC)2&?j$_qGcK9KE#UI zWg{&&v%n4Q63y_nEOOL%wg;op^S0;>Nu)E%@UXYr1M+9$zsAsif(G8(1{^!_ZSE9j zRDao%wddvCB}eKrrVJrqq%GBz{tr&>QHs0&k>2mfc;9}W=k%*rlRF5#9Ws0!)Qi%F z1dsyautR`w9enJ!mO~1nL1DnUIR5qK*4kvM$3D8x-dt@5HZ`H8kAq-A>D$<6*eT{1 z=A^WOCTNzTZOoBdTU6%{EIC^VP5{{s6smM3<~4>o-|#mb*WCa8#~+2sF`~$m4*J?u zc2>Gc2nWw5B%q48DzsE!*grGH11;q=WG0y5p|NN6Z?BG7T?dGd-MuzYK36@%k!)Ar z1f&Uxdy&FJ#x9b|{t1u^=Tgok7@y)waW2b)Fty#nKFg$5Ta=leqzlNc2oV*{#kx@d zAcjhdB{_pU$&xbc86VUFGHd23zJKwt`kXX9&uv3b2*+Ai?WZymXruUcw^}paG$Lj| zGNbdb^~w6U_#3hW^)Bqg@vBN{#`)Bt>R_Y-p8XWpx12GmVaHr%5ox1(wL+Qz;(#f? z*f^Y01Vvsi(^mhwhHnigOnffXT(C~Xg?h?{WbifY#|_Rjje zMq(MCSQq)6VOq!U=6^a%DoN^9H7U(0PQ1J*I9RhA0(ITj3KoT?JrU)hH&Kf}RjN|U zQ?7z_A+DvV-$ zB6n&rovtMXlbBe-5>fw*jfchpgFyLYR)rW%lH1psT%nIrO|&9Kj=4VWEnf?{rr5K* z4n*^7D<+5MFFQpr(Oct&gH3&vEK?YGxT5s2{y;Z?CysefViMq{r3Z}2Fm%2ab#?1`0`=h4w5rECh9=5DeK`#YVJ}PewM0fsCkLaKv71Cb-A=9sIKm zpskNOD4K(9WZHPxhY_jWYZ!%M!g4d6Up=-V_6`Y))ya5P|~=MD%IM$ z7f=(?>LS-qfWG(+wdkv!_O`UG1ZQjEJ{Yy`!~^)2*vrOK!RbsoZ-7pDcc) z77*&P)@vG68<6hCv5H(WKkeqdWh#n$p{{OkgiA#za;{A%J}4s>Ju z*xVB8%DCB~SArE~em?b_6$-r98BPINVN0LRv{F-&$6^nX-KkMLj+1WsaAzlmmM;`N z-L2nqE+_9MOl+cE(4k9@c zo}!l#3?r4eb12bBnL%K;byc0J@>FO98f1NQfFkYqL^PtLl9mRMevzWy@CSOEbKr?q zv|S5{(7!CY_cFSbmvot6Y-S@A9FcvTQR=oDLuUSE3OXVqE`xwx+ero&-!}gMLHkyQ z9>otYnZZxx-J$PJ9$3p6-z?N4IAbqAsjmtd>TcCn4Mo5g9w6F%$Ndw28ooIh9N_kt zVBMpejBiND9H%@z)Dz{NSY<&xwU%Hgo(oqeuf<;Q`}b;wS~r)NERX%-Sz zjxOS_JxCuOKMe={)$-L*fQX&?5B`Rx*A$<2hIg(WE`28q_wQJQWV~rlq@J~Vnl~x@ zh2rjo!Ltj7uWRczy*54@;@yn5Ei~`2L}EvD<#NA9GiD66O1EG0b&L)EzQ7ugb$R$< zA1Aq3|8@BK*-a4oj~@pF{gTe%uD|BPk!mBaB74Q5SFtx_)6(9_RJ$;*GETm4+q^za z?McV#V6=(+iJlPge6FdyewEX(?dCkCXHdH26s0%4Y|uh4Yge`J=Q;F+n4&y8e-%Hy8RSdEnRKTX>- z!(NdqLt}JSUla{91D1o{mGdUWP}&C&yL0y|32Bv^FQyJ*=sCYftj2aX5=t5#AWE!5 zkV&a$r-4OBJ3F5t?{A1tMM4hGcVFFq*)@+5qz);%&W|e~2`Ju!8;B zME_MhPCIVQJM_%$knXDV{5KKzm(tbH557~8X5D6m7{pw@PrIk=+mom!Z{1D$mvMao zomY$5@7wgrSU|KeDvDPVcS2^0^bVdf6Bn#&ezIF@!~btR?wv9pS0VXCTlHASZDglf05^9;X*Mb0B1)O;_4a0m&CLJi5IcT| z1Mdac8^@Zhtq5Z3-qtE%s7Ol%J0~cU=ks&yO`3Qr06ry6b%Ysc{(@O{`a|(= z!zNU9dEeDJloa6|lM-_II(dd2z<}0Hs-koh+LG(OvP%%cjLEBq45 z&fwxO$uer^g z4s3J$$~0#bMacb#;g1XFChKeeCtmpv;28c_r1XQONheTJ(y6&1Z$$=9t$rH+k0XAs z%uCl1n|A1vx3{V4Z6O_HVgDGq(1JtOz43y~0#~Sd_N(8ozPh@qF z(<^~+s)MYSTb5CF%1PJPECBQZzXOM*0EM+lgC$@GCT4_xJU1TN2ck!kDC( zq?wkK1(Xz~7BE3gCCqV1vki~nYR{xmPJPoJl`fp-OJ}hMQ!n@?1~7O`9d2?k$Wd#q zavQXlXZb=dDf$=JVk-F+D9>38mT8EBv1zKeX6zM(eq<0>ixkv=~|Vo8tWV`+*_ z7;QR~5FoPMmeuO+F{eiA*B-%`z&7zV}vnBbW?QL1X>MEmbyxD zUNSUcg&2_hqR(`WX~((;bTdN?G9qxori|b5JK9BUh3GeWp!A4YtyWxqeSpwnyzA+^ zfb{E0h^%%0+h%^LP87J$bSiK!v$WNnNqO?LdL(v<;QVCWUb)R8vz7`)e;hhA2!2qw zSw^X8vJV}O+@Dl(5??1h0)iDAEjX6`%H%Rk3}lnX^ILv~j|=Oz^BGrKu%#Ag5G&}j zC-Vi6{-CsPrwQwZ9ouJ02GuwiI1H63=O=5Mb(N*Db7%_v+;u8f-jigfY|&>ExJ`8) z3OmOtzH&KYuUMDcl+JF zAz9`=%BBRiN(Glq=G2yc0+Fc2XNxOsh3AaldveaE zy7hxrz`@<173u5E5dOz{8CFf8``d4opM{U_w6A0$et@GW!o3$9?@v)hg=YGS&01(njBC8SUfCx7&lN zm5wS{1opWcOVT>B$bpr7rredf8hKRPFEU6II=oYqA+Z*%)S3|Gay4|8^lbDO950%3 zQg<`eL9t9iI&ME^)AtAFJe~|%s3l1+PtKpHVm7x=!K=+f($9%Y?^u2f`eYEYIsG}3 z;Xj8yVTwa`=A|7ax!#uv)Xg{GKmOd5<)vJqnz=^e#1+ZVi)?42l!&Jpmu)*J&Hi>J zp(6T|isWY{?(<2%WKdv{fS2kg0ymf-vwCl&h+~AY!02hW57bUyz<$B-v$~n@tnNe; z_IBnZ64>-m4W1!}lc1tR4x3;{^&Is0{x8LHK*@#U#k_eEtD$GczMif`aBom;^hWr2bW4-k2Lw z=qF2if<_vMB~$_|tBV@?q@sK^V=t!l1(hU`lflqQ8wOAx;1k2pA*W}!c)<^!7f{AM zffPj!uud;(;(`j{iMjo+Gzdn&*e&!GGH>ixIr(ie=sJt-C5cQ0=j(MJeeZs?G1Yd8 z@;5}CtGN~3T%fi9j^0DGVWcnT(NDT4Zm1p+fUzZ4Mq>fG$wpBhWEZTd%Ut4?ff@DM6LV#^XKU%CgaJ4^~v{w zlKbBFNi?$Twt28Z5nKNA?zcm0WYhSAatG{#4|ns#hzQMp!Xtmxv^u;_S6_z*LgWV; z1Mn^26kw04%S>`blry-AszJcS0hBuJ*90#YnxRFFSBnsWN5zB$?snXNfunc14oU%~{ zpv%g6%>-Wjn|R%N{c^YGFXH9BTbaCd+b*|12L_D{8ou%KMlvfO+;G|19ho)~J#Dx0 zmY$Z&#r9oFH(!DT3~$on+}xEgJ!=6e$nMaOV|IsI@d4&I(a_mVVSTZQH`CIG_xHeK ze)_RDa$|3gj!rL15P;{_i29zHbs z#1r0l{gI&DapfbVNq(<4phZPiE9IC_B`x|cU6KAJ1J!H}fD!GdoeS5xue)B9_DCF=RKJeiK$k!h z9EC*AhaDlgeHJa<@g%b7(1TtkT4-oxG$c#XD*>n@P9;ZdH)hhPo(%oIrZ2M0-HmeS z#=Jd)ng(r{wACQ}DUdu9JqT?QXy%iV2<-A&T8!Ld^-b)dfTpwM{IkJB_H0F*WFMUM zEqPzYnQZ#R5eOxi^$kWXFJ1sRXvnA2@QiGL?BO-Gs{>+(fm2;KVx0 zcY7l~C;`4kdTbq)3B@d*oJc92Q7D z8XE6!WI&j8pmYh^e+|_Y709{8r!nOyqwoqYi>fGyzzhjxuyF5j4Oq3CL4EH_VFr~n zjA$%ie$pE+tFd5|QRElvAI_;CMGZ=y*)P!~FpWT%8so!eLD3b{w{yzTjKM{7F@rM} zgpm~VBFn6EDK(Dc(!88Vz6?7#dbiTQ-*?4fe* z`>WIqij%3-EH3D?nEo5MJ+>Wq+TBLjlWnu@(<225iK+HZ=x90IXe})JA~0Sz9kjG3 zE*`jJjqS`8&Xc!aoetZ++tZjanK22F*(5?@(cX)z3=As_pyUZ7AZ7TSZU&;}6}=;# zf+ckrURL{^Kfn?HTjK|k%`vt|CMh)%T*;o|2(l~rI?1~F>NkbdqIkp~Xx0l3z=i#U z+;W+rlTKb-cb-Gh9DGWZWVdzUgiJ}OiCkWTuywbY)TQ3Yy4R&g1!6vP^>Jf)qumT|L-YssUMi)jJaqqrFJ;3d4Tsjp5@psPrp@$xY>wqAID(W#KnKF?ms)6} zlvEEB4$5_+%W^F;b1ZXk`=}ka$CbRGORtrdFV9zqH6_*^J)tXmC!cu^riA8G?jYH7 z7D`h%iCgW4Xp)ow5r3hS;N8@pqO=8sjgeh%wZrKOT+h;OJ~y3~9Y2br-dwow1y)+g zU_f{TUw_RnrQ6ZNh{;nWbd;x81Uv+m zIlw}RN4fPexDjteB_$MN6^PD?pv6qaq{h{4*_2AI(ewL3GZH>j2WmS1ks+aP|AYDw z>mq*3{{f&8Yoh5%Z80TeNHph*wT*+3+<|ArUMo_YT|iRYOL(etOJs%rM?Z~*pTR1x zMw)7_B;#{U!=m?ml29)TazL*g2L0$Wcpr&D;!7E zhs|<@6xAbY5JJLC>OIr3C-{%%Z3b?g>u-;#|12NW(}9ysiH1E4z~&j9E=)<1Mx@_N zH+Hs`qUlKPox-ipOq|F|g9t-Gilm~=Iqn?|3>k{gv?oP@3@8DIyr7I9^R(C4*U^1g zz?PL3I^Q+#X%+DJ+e1-G1M?$joB#Ub{NFZC^TVRR(V?2tuHjyx1@9R97Bi1yKv+izf&1LkeqNO|MdC(-RM#o&*$}e__BwOIO7{5Z`yxt_?pwE>AK|kbU!1AsWkz5A$mBA$C-4qyq(Mzk1JZy)<+$ z{D|AA2CrMc7@;DNI+(^al_d7h3t+~L09(bNqjYx7DR%{;LBWB@hq1*wb6+zPGidi4 zN6N4n3=OEzhzP+riK8KZe21nrq5GO|g}AluL?_yQCbsYKFF3)*?MzU3lcJ{#kELs1 z#tIt_`(x(B+10HF_s17i+OGu`Zj(KlLf*2_R$53m(IC7ikJy!;|LL4jsq67U>re7A?GpYLGrNvhZkRZ1Km+2>y zoX_O&A|BL(e;>p2ec*R-`PUHLU&dA1c^*^xd6dqbtB6j(h-oq}UW!Y;&{6--7^&1b z?+QDI&UUpjZPC3~EVC6V&+a!%yy?F&2!lPrqJ_l=h#Z4~s}R zga@Hu&!$Nm@4^oc?;IbITYz8TkU6_TNVznmn$|kqx>fG9g9=m(7IfWuCa^eo#eAk> z^Mffpx<|l4D*Fs;Qw5_(sti$Oj9yS8h&tG{)v1bakedBVU0-i!19i2YXGA!L5`TN$ zfFS^sI{1|}4Ad08c04j0YUYevwn?_?v2p$RD^-i)F+1#%efBI==Gb|Rj2PtUx()}|6 z-pr}$8SGZL>xQ*RVxO?_ro(lfXGJ*g*lOv+I}8T2z0upV>b&c#i)FO2lkntati_Lj zR+>sNL6mUOjO+T#WtlekJM}LqG7HzUh-VGM*xy^Jt5C(RhYHwU?hIHigN^x?eCu1Z za{gfF!l`;v96C)zymymJOW4f&;o*mM>OhS!hCSKa!~sNF)5D$ly3R=8k+1K{msHZ3 z)A8Gg_djVE`+}?Fr5285HogMuTx7RPsTH4f=cA?gU`Ix8-;)|(%(=nPDpRk>vc?N$ zW3u~U9vq206u*Wl{;1#$aM>TlqixUi!v+Wc2tSFEJTlqS5;VoE`jK7v1SKJ2uNVis zUN=su9GAF>c^C)YWQaez~jP?W?=bVfNJz`1xQna7K{NkIC*?t>Z%5mNZZ(Ly( z{@AER890d)ynK7XGo{jX_G7d*P$N%`ozPp9L5$hm`2455zuhd2-TfM=yzo%7wMHhH z{Q7>XT8+r%j=X%8WvIYj?5`B^;#Yq};Ht5Qcp8|+eBb`utT|~`e~ln>XSwyqh^5CY z%I$vx#n5D@O{}6&$s}NU&VnPK5t}X=ZC%FBl%dUB}R9S(IrYKA~0YmAPl5Yf8+Cg-{0Tw{$D)L?&rSGbSR^lnyq*x=e08s@*FyBE~yW3It7ROv>F{X8aI|Ay4jqAe>~ zV+D*3jTo_MT>)c1+)&l`fvI$l{G%cB5rh;kzJNW4Dg?Fx4h!AU+~Nj%jO&=^eTmGF zRYRPOZX2i8bkuN)KvQ)aLK#2WAZn!x6v4DPX;AvmCIO{cy%Y~R4*V#U1d$IJb@(p{nb^`&kq0sAku1-JWp+th&M za_Bwwt13ugU>*8Ebyfy@vQ=gmUz<(xi#R)ib-@+EF7G4yC0-Kj>eluJ%f}eo#coh7 zXi}8k;)#W|9iJ16BeuvqIECsA!16F^Q$&+w8*71QaU1x+xh-O`rK?EI7@NfAEN9PB zyKacqL4YnPVb23tzGm zCm#zbXJ#O~i3Fm08uV&pV;a0Z*2MpN1dCh}yqLv+sx?o{pK3a5uW0#`1c5$t`IIdp zOoTs8A`<|W6?g3f+*wK6X#q{37rN?ksny?3X+~08NUJ)PE9;0}jXg z5cFnvC8vAAV$bdyGmuF^*lJMkc@ElZjkNGJiO5Q~A(FFxa`#%B7t9j*h3uxki7-C&1 z30Aid*~4mjgjyQ48wkn={qq0p7PEYve1@dUM`f-O*i@1FeGSe#QYgK&?$ir&i1tK2 zDh)VoFt82tUg1c}9zR(gb-i2bPVL;l9G)?h$0~P1Cz4_Wc$g0Q{h!VU*Cnj*)IKH7 zu1TH4Xeg#b8#Y5Gm+x_a$`e)OUrlg23YRHj3VpPcTf+{@KK0Kxj!&UeR&5RN z_UasN&4_q4ee&C+$p_w@QjXm?c7@`b=M^%kzJmKlz%Q}Paf6V0vV=0b*hNezDGB+h zzv$(szoHF8x=GI?ij*KSt8J1bp6gYX*BpxE>kZ99*F6dUyFA3Lh~m?I>ab#TC+^94 zro^}?2D3C7G(ktC6s?F@GQxgQCRw_m55i}r zpX6PrY?^LMki%6N9soBhNAQi$Q<7~OxjMIVHi>wlPry{~Mu0z6mwJwFs2sB*He$YG zf|=@k4JvbG3R8M^oabU>*wgB$(Yjk@y#n)M9)Eo6Ni^t5j=6V&!c~>J;pdE7$$FgefZ#%PnMh0!5jjLnI<})195TiazmPOJ&aP{n_>BIg#hF32$ z@_xEux8k*u?orU?Y0*CL-se* zLeODj3C#r=6|NC})a)wfJal4pX>n}h$E%qTstM~{3L>Yjl~SjsW7OCWf-OCX_MWKs zPa`uebGX(JsE?wlP5ECEXGbIQm2r{I)}n{6`4)p(XzBf$IEQT9p5FBX%S+~(VJ0ZE z`^6c#ymcHUejZVGQK}*Kmzy$C2n>0 z+BlX*@gGQO1&AOxv#y8ZX>MXAl(#ooe~e#N^!xV4lA|S(`lrq^mtdQ20uqXiRW=VY z1?ElRW4v<~lJ!>(SgT1Xumbx|F(`99N_fZl3ZZ3^H{VKK+d?V@)l-?Zl{1x*o^Y|V zF~th)ff^FZJQ3jl;K+r9oxy_{qYUzweOCl|I%JWlQRZJR=gv_L-y7c!&E6MC@sHqk zGA!!eKYnfh(;Ii50}(%iiXd5}CX~wbC{NbzPgm2=Ck)hKPIuJXQj(1=EAOfVYwAPv zZW@O-Zq3%>irssAL+eFX)I1u&o=VCokE`$u8pclaEaL}D_@rvhutv;EjEJxqndqB& zQx-Iov&iU8%5^O(#=(ja1T*^-&Vs1{_M~jGAOa_modD`TuEAp!tBrVYkA)Q8_l~l8 ziTmBO!R4NywN$b|LBG8fGDV$uj_8i}ne%$%2Rku8^@W1J)?O8t!8RO?i?12$Kxj0nXsmBtD8C-;D(B>sZ>QCN4xIAYk>`mC8 zl1?eSvc3{}Pf-kTWduoz_{z6aJI33#VDS<_tmB6-?46N8;@SIb@arCY+`0YHr5dcd zpL9F^!4{Cd7eDYO9y%6_PT3TIJ8&iQu14velYfEXHbGgP)|04k{50?Hg%sWJ%0k3}jwFGpPN* za>k-QpZza9S;r?f=A@E8L>DX5^$V*XKeVL`?&jz@?p~9f|EeNA{@>HXJm`G_+SG$1 zYv%M>irj%LxY8T;2nnhctQC0EG$B?otJ5g*hIsx=fij3=Jg^+ah@);_$3T|8mgvbu zVkjt&?Rm<$0ET^!vh#-&PA)wjM^Efet7VPF+mDIZtGpKTbRu*Y97T<}2lZ1cNzCX) zQZ#K#gQfAr#~1qb!Q^MbhBV5}N4CK>;Io3yrKUC#Nhv#;bU*0fV0tksS1|`z?7M9NY`Nb0&y6?$udIDT*-BDztNakz(9G{ck*F=rrPC2 zC{ckNH)xnZdgc-x;;4c512)}8UKBe)%Lum0<83yGnJ_uu{P68}ue5oWUhHKFk5uZo zpIN;#SLVABCJ6aloL=h81GebSG*a?N*vc5&>`qY>a^YR6Ot4}m>ep)hnvkOqF@@RV z__mRB)W`rV8>?5A!(A-EV!_ovCw+Os{VhZd^)cG-sMBOu%%qEI$`&d+678q2s9bSC zwr4++>m~_dr2ee@R;8HOew_nAXitsXL$p~junK%by_mMBC4xmru`D8dc(QOnlTF0T z40BM)7Ool(3=R%i6k7!PV4k!;N|Qi((29L!#YP6cG#&AtH5Seab-Z#$AYRfkp4GbR zc6>%s#9|3$nrx&;Kj4_M4q<4~+eLpR!5~#m28`?R6z3BLc@7!>%wl|S4rmX@m_Wp8 zvs6ChCl6GZVD@O zWDsjjP|wZ>8+Qy3^pG)n;C*J#ip~cTd)qt~JiD)5Q@-Wyy$Hca52k`#Ovc|S>;h=# zYR{|6D4gmuno$ z`qTt)*0@$@wKDHE>yF2=fHf#%M*gjC#F4U-cq8qq12|iqHRXuxYiUg!gC=S-Y@-6? zU7*Z0WSOtkIU9OA>)*`7@VgKk8z6=Qyo1gI*Nn7Q23I`-U=P;DmnRbqSMLMozeA_j ztIn;@T{YHIuV@pAHn2`iULn7soD{_7%KJ6{v$7v^tw%xeLJ32iUD3zJK8K1{m@_ZP zK7QJHeN#bdeD6($%rrY#i!xhV-iZA#(sA~oSF}1=#C$2m%E*FKz#U2r(2F60dMBC> zOok^hWj=!pi$9{Bs(iI8SJ?iYgq&$9gLAk1G-+cl@+n+YtWh8x_ByBV5d3Xv5gv9l zdP8&;O%UEWOdb*IhivHZs{a}yN~;<~)|l%UpM%y+4choh*-MKX#4rwy6tAE)=r^!$ zaAH~lV}@=ACeQQi$*tXEG{w<0+EWdJ_`&G@A!{W1^Mhhn#Q1+~*gHlXL5S^iOX5h0 z@M6KICW~kD+p7lz5x(`O_{MK#&8-GaNoWHaFe!yWi3fm2V;{9c(W{p-Ec3h9l|gsB zo6|epzf~tcD;d*XFoDI{o-F4Sf<(=o*(BjWJ1H{}M;hRiG$f*SC@2LiWp9(!^4_>2Iw>CCRI|m?O0FU5lU>t64w)C&_SRWKucX4vRAB zzC^fLvs@zYGiASe65IbLQ1&{5v9s2O`@>0uki|5^gJzlGpC&=I4+-s6M%VXw|Q8)~12-+k;P{a}77|;%uM>_k3@F zs1onzlxoZ|AJ|-;jl5FGFvp8)^Wc7{TNo?*x%fRy`>Y?$ol*YaFZR{Z5Ard&=T@!8 zZ-os05IKn(C=AO)itohmt^JM8T2j2qF}q5SBiJK~Jy$hge12a<2jW9$sS2^pDG;MN zg!o}B?sR?o@Jvy=;B9UhyTijbEpT zVzt1bOfGx#@a0XdrtyOq+q_VmMTF_a#o2ZDeO2F65?0h@iV#fhR!c=6__XCsPnwu^bc5G`?hy?#%=*169===69iC5bIFT%z~h8)edlG->ngRfJr@ ztEl$$B`Ey=BSTI=!hfR>==XMq3i&v9 zfNhu3@-@+`k`YN>1uZSQE`h2{IGfL2$8zQ8ST`>8=9j*fHrsVBd=Qij_=qw=KU!eHtvs zxkcRI7g%2;w9=C7fH8|$-^OqDWm%ni@oaoGt2e(TuWsPJL~TU*wkx1+&V*^cb=cBs zXl4b1u$GOypo|Rd1w-<<&h@ES2@M_o`rO$WbLHd}nK&o!RSM~u=N9={=j!kXNrJcc z(_4aFD&MazNql>O_)ohY#J?lPE{PnJ8lcf2wJPxH3n1HO1WQrw$x&k0p3`hIWJ;IK zJ1~rs;#2G-0vs)Qt7kNKC5fFig{zp6gizeQaM1A@t&H8wuC)I<Z)x zNcgwyMq;ji!5qckjW(v%+R5bcUVbTTM8k`imp7!%P{OYYT`XyL-0u% z79zExqI%Pj>^t%#MUuy&-*QYsLO@x-B%VoV2)00$L{3kMAe`)v^ z33CRNFgOo@BdO0w*htT*&YCNoED0;s{XaQUyoFN7Z}PRseUnP((Ffn$u?_7NSrBgn@+Ft-D|k9!INH&cig{>D~> zj`N&-V)x&gke-@UzT#CTrtW%FHE1tSgO#G0okUpuB!Y{N8@%+`AOApF?*DoLXpnXM z`%(vli1F&JP_-40t*&XB=dGah*Bs=bgPLCth%nkChOcf6hPb`Hs*Cc2{VV!;QI>^K zUC1J)(64U!Qb`}jo8o_#p3-|Yo~o3U?g|v92G>n-KOzd6JiQ8d1WH4~GM+r78`>e( zfDK*K^R*aV`&dpj2W53*Qfe|e@lx1_$Mw!tz=yk4}U(3 zmkDP2{lcEhb-PQIRc2|EDr1^ZCSF4nQgQ_YkDo->^p^e;K8ixD_<66Csh}N_aq;9DjaefIWB&e%^)Q@WW;Q$*~B8Ruu(p z#mFa&G2W3vounh@L^h(IHm}0i;6wt;5d_Zbf=I?B%?C>Qh?{}*m0xj%=jD5q`1Z4s zf*IhLy@=@;OvC@&j)J}W(XG>vUjWNy!$GHKC6E|yxku%g0PD2cX<@0B=b@9sO zUYMevgV{-grBSNunLq7`F&$!zV$`WDTouC0fxaqkT>HNGMy?Dk75;@rSKBRXLV}o4 zy=`*U2gLO$D)eD`&0IUfqO&{Z2M3%Gi7n&)W50q2+cX(?lAc0o0p`*H+z8qLmS-S# zx@C^=jZMo<8MnhZ=ZIgAmAsC!ti>Oj!xJYgb`(gQ1^k;=GgDkKeKm`GN$<^xT=fJA z8Ul11K1W%VA(gvp&Q-BEz7MF0Wwx#}k6J%S_{ZRKy&Y_wRO~&b*{Vc6ZyWp4U+LCL za+-dASAqLpyW>&2XF}>M5@F&Gb!J;X0d=?vr~-ZSiZZ2;IdDZ)y(z_{Kj|?M7d(1kJKVi5}j`>yIQn3t3r&MzEVO=i~c>v zNJZADD5W{G`#Q`owRn>8c^{N@c_dF_AZHwwzI9^?Xh+bOo)d6djc=$X&13df+vNZT z$YZ?1QA4sJQB{RsY|UTctBzh+}v-HhV35NeS{j%l%h_YJj*FG}MHjdpX zTwNNZ^lvbsx0Htg&GVzNz*(b$KW{b9_LJ)bG0e&WmU0v_MN{O3(G@D z48&x}amoZK+V7=El27#knNts#r>k`j1&+6m`2^+!9i*=Zmqx-qaa7|Qw5q(%FhjWy zxN)b|j5>b9_zK#Q0%FKq=jZWba~1-N%1_qye-q>To2TrgxuV=BQ6Aj@Y6s)j#gg7R zUa=%3Kn$5hTu@}efpNw-s>T&4leY|EV|c7t=m~fcxa%=luoU=C`!*~4Jzp63xx|&) zCKWjDB0@6y-0Z7@OjHSmiM(mB+Q+15I57`npCj)LAo~BgytWhTg|TI*SqF~kZVT&t zmx5O?VDF>#Od@5@%FD*38oY>E+E&!xFw61c4&*&O3~)9sd-6Ap$@~HIbr=ZVky6;-2$!I9;h7s}&t4)i#2>f7(%@$R}e($E0lWzEa61qRA?t~O&|J`xw+Lrx95ED!WW;OMes4PFZAgNx+E>c zW2c)o;4$JW5&ohQ0yADs@X=n>5|MpNY}($VamGy{`^w?LsjCsh<;mvtub}(V-3b0& z`>qe(Ukqe@4M|bM*dB;ZaxeSNyovL9-wHnT08tv?K40ycQj8E%Lrl94@t41QUE}`6}9q@g_P?pv=20PX+F5fJskY z;M2O&j4yOMCK0EcwTyrrBOZyo01#N4=&x5%K2@eyB*+cV@C^bic#X)D0%){%Kzl_+ zS(sd+Q)#p##=AKmMBkm;Nzp1Dnfa8JoJqO#8 z$un$*Ff0;EOnl_ZI@>=H=3_DX63y?tnxicISgvJQcfbKwFl~^5ILC$J4N!mkxO)C2 z-rsP^g-lr6g~MlL_vEmTsIU4fo;a~;<0_I9K&oRpgpU>XCvOrGgm+B~d@ys?GJg{M z3aL%I82DW;bjSP47t9^&L*+XENx%~A%6&-?#5@FbK2mA^$}mqye>Sp)m9reHW7?R` zsPSpam`TR-%n+$As3~Yzz0+Px`-$-ru_tDLfK%4P(`4l5ghda{LU~(hS@u53YBdnx zlO-13SY&HekLTV5$UNew0;YPy58s=zNCwU0B!>!d9;*=9x6Z;JW2BrO z{C-N(J)n%dkvK7y4VG8AI~h5`I*o~-DU6yJ&X({#>XE+*bw%qLVNP!Zc!rbZ#R1=t zr7Fydv@;WY5$p61_i;nm2PEx$4LPUpm+;IOR2zAR^TFU~**aEG6`!)D;0NP5t(mdf z>^O4+EI0a}v^W+QhNKb-9LV^L(L~7?()*m`J+X}v$Wm9}Y{W)bqpsY&yg49nW((~m z-{Xt7bfdm-6G8xSy28mxFH5=b6A>x`z%b$gTw(G$a1urokewswkjA9BGO{i$t}Hjh z*&r%ZoAu3I!r9K4am-pnomn5`nO%X@eTmYZ3-#%^R6cJh=b5wJWlAl!e%zD8|A(^5 zz-QUB|Kv0i;t0(>=25PAta&H{lt9)#Y+mOiMy)yULM8&(603_HzX_cJX7RRoF_q!&eS7h@(H?ZOpIem_v&o zSWu*&JP6@0gJ2mZNkO(yifpUm*6gfjI0aw?#a@fe*It8f>uvDIibYWT!^V(@X#Vmc zze@E0R+p`)h*qf$Uj(_jeib~C!GKDxffH^vWl%|E%Ozr})f63HM+euHBlPm=cMX0F zuj)DZO+?__#(DD^*`;11Mewxs_YP`N%+i(k{*-=+vJ&&9Sa(06Q}ynmN526Y6rmRR z#^<79=OB6rH#^<`pZI;AFikeVi6mh%|59+a1_AuM4ja0qh%*&ZjL`I|to(i_Cl<>L z3w(6?jAv>|$vCM67&$07-x zC1}bFr=jP2I#<0xAZSJc+i^A-?{}W?u}#+5@J-B?rjF$FoIpkBJC44yJ{0CTZ|$s= zH-}r3`EtlN@&bxt44R#K8h)&|8|VM|W8;K42S~AP=oc-KF$|QT`4)bR(Z{<+Y(&9! zKKzevW18u*+kTq#UZj!N#=uh57oPLOhi5v^El{Z&V}|0sUMDc0#0;M}a>pwgV1`+P zYH49B483wa;jukC0p*bU?R^d{H>8ChrFYkv_5P}+Zbt7*vvF~OJXwm2b>e#gEbBrM zpq#w($p@*>QrK7dG}=Aqc4<0fos?4o0~vm*RZ2jeeg&C3dy#$nBgwHTfDh@%z{)0e z+9B&WriqfPj{#_NdK`-@ZCMwtKOd)rgXwf5z>`O|Kf)wZWtBb^PI%~Ol_ zELfpT@`6b1v%^4!&~HJlA<&;%AHKcIE=GT^5;$LSxGVgCb^!+UIVB7O;qr-fU&~g@ zg2~yJmAIKKz8ypO5w>*J8mGc!zL zM9PVkX(_4;45F@8FXNovc(GH^!QxjCk$_+#j)Afcc>6iT4pIF%lQXSjw zQ*AXgOU0~gm1dV5*aPk%g@kxGY@M5J154GGrgvn{sf*2-V$l_1rrs(L3ZfU>SbAor zIUUSLYJ>4snTi!DVQ>0?MsLOArR@$SXOBW5pZUjJ@nz#L2NXuG@jR7bA!o-b`u+3Ugh1_e$sAo#hzAP ze?o1A(ey*Tco>#E_nezB^EbBEvD{ype+460jR+pO$LaG$Ui1DUop*sdKfHDwz8ck&C z%zsMRu7;&wO=a*>=I73&y$R(gi7xg;2FA(7lloF!IRragj6c26(Q(10vWG~ciJ7Ze z8X&%}M_kDrNnwfFKWnBiND8vyG2+~B!CH)+VN#k&PmF(u-QcT49Yox5j6kGKoeK#(Rd8~x}(zhw;K3xcUP3BI}hhO@mDQWth)OVt`k!0H2>oT#0N zPok^woHtK{f1`dhiQK&7JV85t!pN~&v56(#lbPef)-$lOtPAgpE~>?QpTlD!IxD7SWZ$01q4tg9OqwL-@X@mX#r>M623+ejmcJSpRR!IuAkt|$&6qtFe882!(^?jl(VV= ze>;;Pj#mOk4;}uzomL%O%velt1bj&OK0Q9K8O0@gwvZ3%fiT%3u@y+#U28m#q|f(i zAN+i6bnGyYfuDFyH&+t@miN0Q9E$g!!{b9?XS$n0u^9^Jxfv|dogDh?J}HMc-54F8 zd*0bK3{hrOlN0O!L>vO01q_P85%}@5-DQOB2b}PVhu9BD$*=ttnI$nfBtL&{4>@P~ zV2qP{_7B^yIXnd&&4k8tC)`DxDlcawoFoyX>SUVv8KNnF6xS45SobprFUd2U=E60$ zLTXZiDv|&=AJX;JYtrU8v{uwpV!cX(@veTqGrfpN*NY%1N^@%5Eq?C+IKZ)QOu^}m zNOrQ7);xMZ{#dAXR5~3;c?mq4&bcSEx;DDFgbi)@UY{a8!0mnly)3V%)VR0(Ocl}Z z7Ne+#yyLIu*oCOXK@Xi+s<#}si@;7ib`sU!G6$|Ae-2N`?&rA;RqW7I21K1Q znCQ9%Kv~Rnzwh6!m!ydczmOJZ)@{_+aPxd7F$Z|N0N)GVhNSrK3pAHu8C@-ElldS- z-@VZDnOlD4`KUcKt>7h66Hey3{v=)%;3$l6f-8@te0MWvEG7DKe_9CkN!g8e6RmPz zMXM40JBWsC5ik3bZ+0K)F8gDQ@+PKZ|0I#F!*Y@hEv)59?;!6(^ddiQR$}xjR_Oe^ zUfY27KedzFJ<9{JL+Pcz9yk`>NvenS$;QcJQ~O~Y)%KwUT0oI;7U3KHN%dnI2iSY5 z$MyAlwgjEHgM`j_*+o}Y;-&wr39})`O_&6~@Fi#Ew^|J7{w#Z(PIJfuO6y1R-(Qnc z}#f2|Om^UGJBviy+ee|S#PlxrB`dYX&$P-n5ZJ9rTR`IK?Qb- z2rn0kJ(?)8FCvf$cPRtA%BE80@wJ~apqdWW6yVWFw9gm_+A6UN{e>|$Gw>*$MkaM` zEWSC=jh+BMe{f3m&mAJ{YvVDm8}b!na6i8>2FiJeR1e=8K6G>hIoLKOYy~_>zI*e> z^)SzE5O~Y6nzkzSa?!rtgg)Of-QC$nDBvxA&i?20_k?IE_6rC3EOZ-uNof1WBv$&y zJw+D?9J*RSFowW{%Y2FokjMKxTCl&_{|o%AHUL?f_O1xJR%<-g7W4)U+Dt@I@y z+F(?#m;#;G0sQyj*{LY?$;ji!m~cuc{R~*!oSsmDaaQDR- zc>B=XG{h4A)@~RuCcom;m*JpxTUnH}Y3X)25XRkGusFUAZ?Dxc{h z02-$nraBYI+N#t65PXOfBcE*j4#s_9+kx*h7c}JNF0(X}iy;AbQyotZ z_R~^O#bx_oLTr|g?E7LMKDA`kK1WqiUouG?&jkkI<)iV{%$ixkX7i-wIeqdn{b5x1 zM|Z$6+M#xbA^wEp!$0se`Y|w|M@(G(Iwu~47uH(2lc_;E${U!R z@`(;-=Lq9aX`;lb-Lu4z#G{y6g zt4|og@QX?3LOxE0pJ!wCnuod}r9zq*Lx0QE(*i5F;{zR)GC}cPwyT5(?NNgJn%;qj}(={ijc#n@(&HtwucZ$J@OAQ@d^*F>iB#uFLUUu zQwIyf-)ATt9PSy^7=v!U_}sKH47LR13o2YMqcjgXyac!HfPUYvSfae^zks+Vmwi!^ zN%IuS1m*mf(Xp~+OBomyreU7ir6N^8W6sDDYyAVz%dcU_BP|I(ucax zRXhm+un|xuNhk9;IOb?pMkc6Kkh~ms=cO?VBOwsEIr%--)GG)l{{lLNT^o=aNI^cR zXIsY4@{BDO1IMd@e;BmB2j8$fdktMycr&Jc*Ef8GG0q3wq{Z`S$V=3nte*VaJ$=PL zl=oDSW<(#)fJ}ONkx+*nx6dIoH(F3EkV=Mn++{0LR4ZG3a8tVKD|qATn4N_<$rWfG z??R3hkvYM~`o$BH>--&g&{KwGt{pE$E9zRxr%-v$>zU)r@7V>&zL( z{#{I!ube^ZCi_E%T@~AZ8H@zcv}8BW85&6Q4*DTNBdnZ6ydOe*3u{K{mynR97}-59 z%#}NMCxQh+>zQ*?hmw)e;6;bXi4a2R}dDx=u%KWc(E(#>!`Z%xk(v*L$W)LSR z|M*&P(J>!2dldCmRmVezp=4FxjxXkygv~EKYI!_k<0tW*aKQv=B8EeFlB;!rv*ps- z!R=qz#Y>3uWP#6QOa7k-76sIm#h0jZg~s;SgUf4Ls_;ZO)`jKAhk*#O>8DqV(b@U) z4-Pu&KD>ke?5mOGtdB__`_$#g-kf_0=>dV75%A`e^15`Qs`o0wny=ZD9h~vG>9|6W z8KwxnZN3GSbQfR&sv-p^ropbwr4=ainlD&(GU~nW1T$PKc{N$61nhWcxJS z$8lR)YDinXH&MA`TGi1iE%z!1+yP!JW^izpu6hQsl5fx0eBP7szCcIlmr&z&Vpm57w+eRzdW*_@=A!82T?-Xg7e3S`mc+8?EZUh1a;r85G- z0$XT$h7?%(+;~&Y`}yet@18L{dQ}7S7n)ppHE}{;y2!N%SFdY* z&_jqal&eZ&`|VS>FH$`%0|7%m#;#rN_fbrykFCIHxjiEb@4mMF7RMQ58EIb-yS}S> zQYKx9GM{=o$^6ySwtyt}^Mo<;I3~kJ+UUskIJqcT}lNGCR`lnqA!$K8;rVo2U;h#RW+Ekw%nLn_AC8w-NRA!Cg8c1UMA@@Bk(N!jitVoRa}{er zdl=SRe-b|XF*%@+lVyZ z_Cl0cEKPR1oNGIRZ-Io9e;zzCT5JZ zbU7i<2{!b*R$^90jR9*66OJS)zkllYst{>|NBP?xrp61YmomgCQjX9$!@|vq(3yZz z%3J-%nauRo4{7ETVvdC*vLgSsZn}zXr~rcYM=9 zmY&ncXI(Fw4IWT@7p5wR^*Upe6ZtGEdHCryK`G@w8i~O9w<6=e=e}9JV%m*lSizQJ zv-5*^<)Qx8GRzY}b5RfG(0@qfC6*jN-(R%(sHbpaLBLyibE_O0TOt92SV10|>Sz@N z3Bi0Zno|j`GS#&rf9Vh{BQ@nG{04Rx^7YmGI){GxI8O)CLu5?M-8UQB)-J!^r>Q{m zD|N)<6h~*kN*=hM2MrxfCr^}?J;r{(P4&1Y$0Cb%y;wd>KCz>C;yv9XCKj{&d`xgz znzHxyF?~;8$T!K|`uA7(Vpdd>f3o8r2s`)kadYo})|$?n+RI+thv&ljY7Fhgb`(>t zd`uV1!Lv?+;4RLJQm22a^qDnpbX_qYU}9Yc`@dcQOt91luqg=N;c=gt3WrtBX{U~M zfE6-LG}f@d>ATI`?Lbt`-x~YLg7%9gu|K7khtD*2JjAtHsmTCj%AC+W*d_bMH*d`# zqe>h?^wiuAim&4JhS9yT2c!C=!2DV^ib!+GrM5s?NP^{ZnfLRQ~dn5)ku-9@b(X9-$gO1C@toHFQ1MY zKht-qys~>%Zus=+ly}}!8{=pHd%bufXG_mZ^47RKH#aws9~MyaQ^AHVV_M$ERg!1b zrl3#ARlb|c;K?JI^ZVnjdGasmm28fRPj95&HsE|gjt4l%DPTMf~(-1eEu~ysu;Q7za{lyEX5})Bv zT5=)dC(3pX(EJuyeVYzL`3ET;4GByx$|#Rje*l;0muM*GuI6puQ(dmFClUqf+oH## z&ZFu>-BTmZi`>cZcR0|Too_GP$E3X%_Qom+zle}$7x;6%o_N{fTRK%=Z;=7Rf%WY} zJIVqQ{LwoViklQF7m*VxT*!u@1Kqn`slVO_j03qmR|7YzZCb^noZdNCe#$8s2EQ-P zVAs)fZ_1P~D~gu;u6y`4zUlF3ROg2GEh?(lPES`RBdDtHFEI}>gX%Lepqh=3X1mlc ztvfM>i>BzZ!lj?f2_au;Oh30yo!W3?9G9PY8o6}Utu@?nNu&i*h}>QKoQbIyZJ_k? zns0(-C4YSs<`}?>cAU1l9bL27^A1YYwu%`d84??^%jkdmHae~mzpHf^VS9tKjTpcb z6d;=SMUe9-lb@;Gld2q(vqMZor*Hg7LbVX1mrXF#UJz5>)WM(-nthWIPCfL!k#9Hd zIR#~rGgBB^Wz%VB5I4-%(o1;mI?`?E+t+hCnSrE$KPj)i(z&nIaf1$VS=L*Y|2C2I z|DE(+uPev(q>I$rJLB}bI>5nO#qb9(DPX2z7jQaSCO|!! zm-p7#H7zRir&UG>rXf)GpoF+mo=+8{}_v(6FfDjqcwGeqz1`XxozEt$nT$pxV zt;Fb#drOf3Wyl^sTICIZ-LsFfxOOO=Yih=UirX!B5K5GQ$zec&PScGN-CbU>RWhAo z`kNzQtKhNZ5EjXB_EcP>Dydr5pI^FSxc%^bz#_rk3#M=emQWAuEIOP3F z-yC>_%?u!LUNu?4SZd{3TqagMM3mu_o}}LQBxjR(YW%m1)*N{1jkGnbp@-(%3Pyu0 zuq=s_Usn2)RQ({KsKkj6*=)FsPk!}IOz`AxS*ZpZXt%tq1~jD8liAIUipe0As^q^v zey-ORHzKM z-}QIYqTeo9Xsu%4p*@Yz?9DJfX2~$3@6E96TrnW&cV-!d^X;wOPdrMuQ~jT z8>a&nKs5g>F~_F`$eu2h=fY`~iASWxiFDpTwrcW7GUkFHiA5nqNXKP__U$GY`>#dv zV8^!78s_ThOtZ{=aAm8!&R6e^m0#bgr|#HhU$_?}VtrC?1!jd8Sml&Ra?o*8HKRF& zo-e8*|5iaH(tQF0K_CKu*qq%Tgnv{^Yh?5JK1%t{|qb~;rkkuePw*QJ;V zC6*=akq?$}KU0zX#J%VMxyZMaeV%bW?{!*#1Cn>wI?!G$WM@ky;I-xtFiuh$%3 z80n+t)deCXM|M^0pCm`&Kq~8gVSnTOQ7RCovnLcwa%J|Mbub!4d!k*;%#&W9sou1K z>DScfDo^QV$tt_~P_jUv{pRhTbZoI3ZUX$#InYn`(2?>{2_uQINZz1#UR4NixfGh8 zK}&kvYr9IN!+yY;uJ-*cuvU~4r64icWgfvX zFv~6a=b5TpN6CUBw9$SfS&;pAVVV)e3b7{eH{Iml8!}DeZEJ=k*WVHI=_;%c_6(II zMHC=|IVNTMQH@vW3@uaWK9AUd2clQ92`2n}BILQJ_m}FKmkt0`mXzo5Ic^xj4HAT}oN{4xyhtwgNl=EG>JkDm9 zK@Y4WiJ8KF$b}EI?wZ|xBY_RzFopggr!F7AnkbOCFb`^nX34eVTlBaze3Sil+$LW| zP`-sLs;Il47QG#<4l$l|L>e`=0Htuf@**g{5k$E}&OHO2)d{5F*Ng2Mz}j?qEC zy206wQ;I2xoE<4JNeMjr0tI7q=N<+=OZuFdS@c2MHr#cB29FN11C!u-$*U(!30_zf zw;(86#_Z+gnV(ojD`ppdh+U4SIN(AS7Yv&{_PXDKsTu>I2MUD58&TBF7HTRf_gB!$VKkbD~1`^){|> znk^8wosBTzxjDO{I7y#ex!br)ckFEhaooB+E%V0X28-d5Ykz--rtnM;C9hpQx+agc+iwg#}je7r)|>2mvpFerBC zj9oIZEIp%N+RnOU5GU-wjq42|dp@}OD~X?(XpyyJ8;yJ%mgurF^V2(AL(rbniPh z`kduz`8vIWSo_2KOe!mL5NNILfol6FXVta8Tq+&;q_^gpz_J5)PXTX!h*n+Z*{7Ry zD;dw%wRtsW5LuKZ#HmhR&s89|cC7XZ7dyi{fDY({cqALUf>j!VS(WU_^bB7y$n=sE z1WDCT)z46!Z4~LI^Fo3a1L*7PoHIl}v=rrwnh~0nP!;cnSNWqae~MPyZa1suo;Xk+ zC62nbWkUj;L%5mG^6|QTO9M^Y#ie2DU|ypri(EX*LMnLK7?F@uhVB?`6bb4%o{t)0 z+9MxsE_Kf;)I+&!-s)dFCMFqe3|$d$^OfW|7jJWXQtkEyx+m=LulBfbiH`f6MouShL&`EoTBZ; z826b^7+P?y`5i$c83tzq6 z6+3*Ec)FAPwlEDyDtDp_4%-P9(Ko|iKX^5+3!D>CRuO$ zm$CK3F*&jgeF~HUt~|$Te@n8Tjdx6W9n~9`SCOn#<$~JD1x98$cUYKd(0$dufw^s* z*RK;-F$S)Tk8fvmbuD#Op2>*w$W`)b_vDDY=F&9KFJZ|`&?}UF?LaZVPz<*x$>OLy zcs;Z`B*rtqg=7_`+dB8Y2m0!xUBl^&g=1@k5_DUAiQ!Wjp2Ac90-+G94B3pQVsu-R zMD-$1$sSQyf{8Q0_!({mIY26IRTtjTIV%>Xd(16o}eaDC)$Tv2s)n8gK4c(5Gh~$?YSsS-QOtm-UG1IkL2W`@?JU zo=9XMv6t*!d?46>hmJlLaJed`ysO*dVt-{LNMui@q+(2?wywiG@@k8ZslP3v-S3R7 z?PqLg)s&z3oT>d8*}>PmkoE~f6`#7JZe>Fe(|+3%!BJx_XJ3S#LId2^k2@W)UOIUD zI`X^7UYc_tR8=YkNBp=EQMzBUu$`;wt3S%jb&23|Xp8plEZ8tvgF4bHq$FYd(lQuf zV+&;jr%*-7vV3|M(;wvi-id2&lXEB>Z_4q}r@iNl=UMQhQKNG!beEqe2Pr`MmCW|# zIo6XC1NMyhF|tcdV!Zt)#P%PRagQMbBgTXHzF_=D&#pn!$;L;={(p<|L{Ld76N2R> z$UqZ`h{g~kj^N4T`kca`?vN)4dNpl{9Q+nhZwOF%n_x5R}i`ToNgX)Qv)nfZzv;7TA_{yWH5b`?q z>W_Wij=jrrZkF-LEzZ2H@}xV(OkrZ^WyQ%l(UVP}9a*+?3hJl;N>PF+;j1nrk4&yN z`>vY*m4g@yvv>yNW4hGYw#O?jP>LsVjvhd(JBqX=-x$v{KbXMSNipG~JS zMljtF2a}g9$!j@2j%`2hu>pQiifPb6;P5p25bhQ=e99~M=H-x%phkor<~@iS-Lyyf z;}qYU-kXwyGcFsXr< zoU?d&-3;%iUl@iB-Ev2|3D0npGzp*y$QwN@+}yT8LwOYO262f+m^}NhaQlNT6D%Zojuqmr zmO3fUVb~|-Od-}61==k1y1u@M-Sc8J3w4}z_(j-P^DbdyOP(z)TgRX2vYG{=tw*|3k$FGm0bjhRRn_i)=}IDAg2_6{ko$& zT8{L}bGqML*gLx3Pfv<}BJsMRk3G_jrJ3Y-s^NL&i-gj`)_%Al)(orO(kRZ>YiH?1 z8z{KM!UQZOpg}bwhDNKXgERFPM7t-gr7TW)yqC-3bjU9&Io|NDjpCf<0 z^5GV#)2khm)A8a*B1y|)W53JyGEyrO5aQ0$HkxP*>AYn=<($`G3+kb0rLlVl7f>fb zvgQ|-DZ##}GV}N_F(zm+gLBhVz?vk%lP(zvlWz4(xoLqJWaR1(&oQ!*r1sM~09z7A^wx+_%j>|=d`)XpK z!2KUyiff=H(S$8jCxZk9Yx;S&9DZ1B^!w?RG?QGJ#A7_zz=V%|P^=Lawo8N%yZpbu zpP}UF2)mqLovC*f#Ep&IEjR7X4iV0K;bgsh?^fmU#ldT_B$Qt&`MAUE_bfZ_Y)-yI zB8goRX|<)gGw2e1k`yC8l=UJz`{e%GUDh~9QgmCx-gK}VBG|~h8PiXfo7Fpz2NVWl{M`*qt(?1$J%O@hq;1a zBw!o&|#l$aHh8W%KgezYRYAswP7LKOx)ljXD6F*?)d|tK*(S&{* zE=bRjc`JhH!u=M-Ml|~8PYf~q_A-)au<*c{+)vzLQBPYc{xp>kCBQC9g%E{oi%=1t zQB?DSZaSUd(Sj`sIxeLK-?LPNo{`5g3sK-1Yw&9EDdCpBC#Fv%dN?tHjTmaThv_F9Bi+bEZCCzN?f(0G5mw#kxEW2a`SoH|0q3&r`Zt{#|yvrrypG8_E zIV^O^f8vJ@8dfhU`ds3Ar$<*+*1b|nI5*x8+O{f4@jt8I|G$*U$TUY?E`y%Cf}mO2 zYhhxNocvslo>9^p#C|@D!|U&xlKWDn%oJ5liKC6+&+ZRY$vmI>o@pXlMSnus;I^19 z&LA6tCfgrOH@N(7c|h%m=ArmYim4r?oy5~dO$tp73QVoncbY#ni7*mFqI;VyOTlg0 zhQ)C#2C=u_()w`Wsvs?E+EbX;7M03F1kuyzjNyvJWHt7D$)9GTY=)WHp(Ft1(>v{u zq6G;!^)ImFppeJvCl2QDfhkfwvAY%DTYkIlRKM+wv#k|Auga27vcK8ijhK?vP!7)} zt&TofbNli=JH6tC=a2@gCB|P&FFqdyn_`&mm2H|)n!BC#5}%X(2gv^Om`?V&W!qjT z>Y>;wlo6V4PtDG+q`3|@(DW%15qKk^M)f8kvyja(eyTV=%-$Y%vbhpezohS);tDYZ z(R`=_BJw^@c1XQP-&XP;-40L^DV0}hi789mVJjU-{?2ct$T)MT`}x_&?yDQs4B;FO z)!zob&xvj0M@7$rwDKBFI4X=2JTg8C>5rDETO@R)<^H7>|8s7+-BP$JCO+N$jWgpM zw{(98R<2ljK2o|7$0oAas(z>thIu@7&5?cTTJk-G3i^L@x1#Z4NP=CT0IkT(Ul6gy zs*jTC;hO|p4hH$dtcub2GYUeW-Q6=Hm=!t|JH`NENYc$tS1cOoJr=suSzo9m!FvTF zUaZoDzS$|K0r)`54*_OUc0Wn2%mk|;xR}J?!p~PhgiNLuzFxeI9#2fWrkVxRw+v>M z+C8|wR&Rz z1hB7fP;AS{DIw@L%GXFztYvaAO;S94`!7qWR*;OW_ku@v}Z-O%BV`R`8_exq0#Tn%p~c>D2DQw?mC&lR{WCYOCbP z^H?!1{xx#yNn>4`S>zkA$e+Tjy6aBZuaV34Y@)9niO0tuY*tvgsg;ZR%#-tK!{d39 zpp)ocXu?%jJP~a=iI{9N(^e>txX4kS$zrf~hotnMLw3cC>JicK{?O_MhUIqi@AgWD zQ>_;mWQjws87xr=L4%8b-=&_O$j#MIqW=@^y>kyQiTmGdf_!izj=wMLU4gyk3u{+x z4BPa=<=3R5D_v`-FSq={!n^Sp%RhWD535`*`?1I{dV(N{*$~YxEPH>R03EQTHGfy; z!I<3l=|ds@zq2)L%(d-9ZuButpCOhJ3BnphDH1(li{Fx{(|RqAV*vkhd937gADz-R zG(1bu@h7`w6&S$9b`|`RE+=1__umX z1>nwygt};d736Uj-uvxpD`j6A$FOu|&MoCZT_1tj3;p!{cjCD7 z;SLx*W8c+A8iy{1TcYAZF` z@#MjD4F(K8+1FQeezF-HKJO@JY&)j_wpLn8MJ48Y#GF}SVbec~iZR3Q_o1$b;Fx-^ z6EGb~=k1=43k4p&YM5+5Km!?;2!AqN;0HY0`;8;PK3cSy50GT`y~l1?^lY@3U5<;( z3!{{q^;X`OJolAwc^N_^?4{dYdYkDCb&Es1XXbH5@GH;maYCzv*Uexc13&u>)}tFR zpIypT`k`fbERNLJ-jVBgt&uvcO>W7X2Y0*QeR*Z_Rw%lF*e%i(9xg_w2>!7=Br?fX zC+cwUPi;)s75H0mBWa1{$xHbViQu}LZ!KE29qxqIo?RJ zVWhn3ve2*v!iCiiE(RQ#Bni7_@NX*G;m)^Myhmcwu# z6cgiDEFl|5+2ztajEB|?67XSb%$TQL<8Oa^=mVx)ZQ_iLi02gwVc%yYcmBr zilQiMzUHjmK-K@v4G zI<7ukS!=-EMv?3-DMnDhvl>dna)d>zivTj%1UTQTd0MgrIs9I z+Vo2&2b6;lFY_I^Az-0o6cL74>r{0Akkygu6hrMdwLLE<_hoCC6nX|reW1lT#}^3_2qZvCPk6R z*w!J{_g1pQ@s}_T2&+B68nMHOz*mAVLb_R7n18T}NQxYhao;fZ)3>S48)2Mp zeF38F3?Z16^<727Z_imq&~$qN5aSZC-1nB7GAYuX%&F!TskZjGaBRo7zr|0Qy(`-d zBOT4`HjYs!gJ7AY6_Akp%ulq>Pr@1TOU|SqW?!JT?_7N?gC|E^tfFWigq<#8zS^p8 z@GR?@fy&Qs6@rMAd;g&RIyzsar6FrVReJ&fQ2{`);|?&LYhqU^Q68hxu>Zu)q9tBt zv|32Rr(B#m!ls81aQYd-p&fhNM74o2XFe{t%bCW`B7071&ly7{uNnpNQsQP^coF`C zb{|jRr`~(D)xx49i!rJ!Q9N4mMt0n&KT<5%&7<*t!%&_l)BI-lowhy>!rH$ojN^QY z`mp)_Vk`?2<5P%L=%!U?;eF#~5rx%Be$ZL>Nn^Q)=Z_S1R4S)@j>S%rKDLu68c?kH zEbO17#nt7gjN4b2=ngH}k^4j`=5*wRpsP8LnUo8EaQ|spD6p@dIQmA2ag{B=r;PnK zPy8p|Sqo#Dc7MvB()9)2N84{t)H*BtnAj_Nbw7Sjso}&Sdg2Ps%GKr6ElMzcfh#wn zM->{u)@Cmns3=XbWY!v3q;t~7T8w_55Kb!}bi;q6NwB)z0>00-&+iEQ zthnZf??G_xE=p-)TxWepK=K_la*MCQc`Th76vTDB#p!WiLUdF7By;0ZKn;0x=LLmg z9m?DG;2-aW#0iIed@r8<3lMj6v=2JSZrJ-1CQ7~hLh4-872cTE{Wb923Z5MTpqCYk zUSDG`Ikr)x+}#yOPm$ z;l1ygRP_9uYG08^FkikzV~yBnjV;YkVql@V&+^%w{ln;N*cqK zG(wu=Aw+mHX0gd)Mgh@be@Ed>t?EE#UR_Mv?{N>_Xp2E>c(6M+h zjZc`o?RpkdFjA47E7#;1(I@Axx%^zKIJQfAl=hG3aZIKHSelLKy!k#dw$ew93Ww{> zD-dqxk81+-csteEK>VHTaI5ItTRAasb{aQ%8!=B*<24|J*@y(Xn<&BW7GjJ?9^A+`p;~D%7 zQ%!(>Va#aSvpsemRySs=8?%O3$HfW5@#F}nOG|qa8Amp7qmKu$;`sOU0myh5+B0bfX~r9rwefas`G0az-Sm-{91UEbMik$v4yZ(?sc z?a~z_OD&~Tj4aaXe~%io(63iQlT6AJ%t&#p4g!9Ltn#M!CD!@`L+7Ifw3^dHB)rB1|!<*wF+?LdsJK|0phlBZfRHie4)F@bS?R#pARiC zH$L(qKZT|2^7sqqUt-hMGdSR7{9}bm4kZ>Az17198ZvGVb(fC^ZH9Lhg>jjxqAei_fI`Nv6I| zaF`ZAad3ml@QIim*KwJK!LkTZ*S8sQj!)|Ge*EC#HZN9&)hLA#yefKSKO{kGBGEwmLIu&UU97Ma%WjJiMV$_w zfEFrnrsyfeQU4l|?8qg?SGBT$kTvTowFI}TtXIkyA*LkBrp~Vm_P5&(zP?^Ccx56l zk1!^a&%9=E5Sn5z&PuQ^z!@pW&Qleqmy<}Zd zX1q5isHBntA>-4$$}RZ)XPGDK8x_L3Y(Q^vy~4_?gg6b>?iXJq`ks+v5J+QTcJL*e7<&QCN^a*tW(&Q$P3 zz_!dR#dFY~bm}Ql@ZUrr448jRTt97MI9fqx#3@rjAX$S|tJH?lETb|iQ)oLVr1!rTt2aC#9 zSJ@9)MLoWf-|`TMFaFxrBAEwN?%4-{U@JT1{uYQ|MwC5-?=3ZD^i#^UHj0S?DL5{z zywXV<)rnH^Y2i_dtiaiptrnDkKNrExO9w0zHDo=KfsraW1uv-!}6XfOxVH(y?A5xI&ssfUqjKMT17=7=E48Zhi-rJX-Oxo zjk6!~wc0VAW9dG&KjWL#O!TNevA9fTlg<<9tF8^r6U4QF1wu%058%OMDX=Q9a*u92 z(aEf2iPyc*h}llWgKc-qhMo;lOOl|odeQG5=*HgFa~v4>QW`5F;gcz{pSdpzDPv z66eA(&#BD*DU*|f7pTDKp!_7o)6%U+$Y?hbP(M@Ar4!X#&*i{wsDLqi9LoxHtV>PL zl-|-#Pz+v(Es;ybLQ9NUWQ8p9Xf>znfgtB5I2YY0cf)M7N%#d#`P4XhVs$$2OW-ZzCkWv$T4A zvMm8M_sP-k`+|+~>db9fl}Jmd2r+D?Rbw*oJVrb5ZEv{{Nlt}zt+P~2!c^(}EIvP= zQvZT9MUb;(K1r}Virv3bs>^u@Mwt#WuPhh@jzzBZ9vm5) zE&dIP76Tq^QXE%e(Hx$q&Tq&4egy!+Ql9j`VViA|1PnxQ<<${P>X~OGkz!Pl`X=EF zGNm%45S`!?<^e;$4u*#hJpBRb&z+U)ruOZ+-X&Fl_i5cCoXfAWzm>M`TeOb9(5m>0 zv2szR1oDHNW4+ZkOAQh4i{;~XU8m_BOtp0+^yG>lA?j-xEF`Z;uD{5c*GoZke}m3v zcT`EPT}cYSn{r`?x!Mm;Xd4pB9BD^`Qg|kO+_g5%)th}Nf z5=CvPYx}8Ruw=8^?vTe84!D=ry=eF}fdLMH>ibqayT=+e{k2wMt%>Hs90lY-bR-t6TihKDEPxXVL%sbE* z7B0>k_r!B@A{#jsqW-tIY4=n^x>sY=>|IBW>%=D14sd&Z;J*F7Bso?xRT3`l+#s&$ zK&+iG_g^1PmzK`CaF4K{)Wpx|3+CnD@C_9Goy`5{cy9g4Vtsa z_m@*HDOzM1qx|hh{_Dy+Fx8FeEPU-zX4fNXDF&nz1H0YVr0db~mbq0w6HD2Pz2uM4 zA2Yu?uxG+^_aoaOydETG@>*;Xf>tD+6FM}1|b^EY`oR9D@8 zCy;(A`K5g|p$7<;?=x~(EWjJ*2|rl+NCDBd*;DFtY9@)%o7!z_@GK}zjCqM1#udEdq~p638?OL%Hb05wjd*k_vCBEYK0wd zg@_!<_kq~LIcB%igKxqzw1Cx6-Ja;g|KI>HKTg8kLxaN>3%|CZ#eG5S-V!B`m-TQv ztd25*)FLmrO$}B1#~#d1dSk~UUV#VC(U)LxN?c1w*jk|=!aO{j8{h*nQ~hNsxw0pQS%=-;GTY9Q@T^*`5BEiG7c7F^uj8IW`>dh zpO;6b;89$;Z?EF|Ro|RsX)vctcEERgTTz@c44gAC*jY@_x46?aGwQKlP<5t}&H!`8 z<}i+1S1W!Hw$0vwI@VJU%K>DLp5AFuM-vBo{<=$+@t!p%LT$yjk3=E!Jz<$|vj>Dz_N6FTvWP5ULkP4 zxAxH7A-iE(CblvL!4y6Lw!;40SN1SHXkjpuSiSK{X!+yBR^m_sX7HA*l0usN=1VAl zAe-XYP3G}>I7lfn6S(UHvy9uVm;jgqD2s^F`@5>T|sP3oKDZXd(Mq zYDzw4`X^Qr6G)ksf9TNE@btc95$gu6WKKA;-Q!Em=T%?G;DmF^pg{j|&01&_p0l=9d-?TZ$B(JsHT6yc8v*{H%{lh_fvCGSm65qva#*%5V<%zlMRreo?;XH*8A+4e}QPCsM=d}sZE(xvA8XZUbCX()4H;9rpc)W4<{{- z*v*O;*`*;l!@BGga|LSL&n|rQXf+wbf9i85z8H4E_hBvGFcut(kCe^{vUcD+lrHuu z0Q4Av;&RKrG!`-Dl6 z7ode>UVHx79R4}|nv*Q+#UhBkh4N*(iWa*PcS67?r8=QLw7 zbKBE1IUnjMaH-06+1SXblTSgEgx8EG=aONWZXX|f2u}8lCXg6CN*%eCUqnFl_FqKoyKEBONX0d$%n-vS`EVurC2wWo( z?d~GZGS>*?Rx?}+vV!&7+eGV6%~yq#QCs<7Rwue``{H5d4=qk-+Lo&ptK;va9GaEA z4@!=u*R=8fQnZyr@w)dPE`xlEzA#eJ{GsG zw2+q{tDRfTBa6b7WI^Quc@s8{$tULi6&-~ElQXe>bc<3fvbx8EMd+cnoELH+k#mj^oc-chNH2N>;|VJ8}^ zRW18Enu73gfhCXH43xR+j1|9vS0@{wrub&b%K6s(z_n{PKx0bEc)gIxjLBWIwF|Nd z)Er8nsz$WVgN^JuVLFke*vA%P0eMbNd)G7Ao{jQO9h#p#mrKbf>d3dx5r3zXktVmf z*}1JWb!e>_e1w)-wYy|dPJ96cPN}pVWObp_X2Cp?4}l)K=hm=|ZupDH90??Ov=I>< zC2?iN5;Vqg&kuphIg8e{4c~rU5-F=0jM|C2xsJrA*BEr-*FBEu1X(^=k>`gwX<<`H zkjCwME|kzvHpDWibLT0OY^G9Dn`e+w!zM9=#XxF!%{TH1T?zEoVIA%HHFT2S{HPZ_ zFLo!Cf9gSldY~OqDn}!KNgk1~g34X<7LWE{&6-K-N(B&Mx$xdH->{JBg`m5zlMaV( zS)60!H-2N!j0n8zNJ3RIC~Gl{5woR!m}tYtGBkmI(LS6zq4 z(B`!IyU9f9hr8y$f!ajFo7ozh7MgQ25sxuRy7umpHT*`aj~L(Y{4VxkL^sqCf7Q}r zMFf2!NLj-{hsU_`jC*@Ch|j2%n9pXxz~P&qU%O5aFSRy@{wIy;DuT6qPT)fx@C$=a?o&b%uS>Z9g8n`F^xl+e45PIV zb>uFS7J)CgFCA}W*9QUv713s}*(7U+GtLe9j8vYA@%wZn5v}{kt>NP`2nn?NvJx)( zWxj5b{21n+aI;Ed%7Jqq1W=?CzZsK7<6G0ggYx~p;bZ2CWX{*hx4psqt>(@E^(+3(7m?NHH)-{! zThYrmWs)SC_3`M+=K+krQvApCHrLV%79TkbZgKDI>lP;MS-8kLIkw3j_DPRPT9-5Q zQLfj-`5TkGx9dJo69_ zc1M?!w&s)N!o9ALKf-_T77tgNwmRyg9v^A2iZuiO z&akYOf+@CE!YkBT&g#vE>E}TOk#-^^8A^{#t{az*Xn*S+8%p0|Ejb@Cf~t)o{mIRP zE_$sRYwDM!iaY@Kv|;Zn{E_#E3$61HpZ0x(f+sy8LkmW8`_mmF?|xm>x+1}WsPtHb zjN#>Pnj{5Dd)~AINjjd(&w?%HgpQ_rYx}hNNGXm#CVMrMPrjA_If&=9pAt6_Y_(Dw z+tuQ6ScCDvL7nmYNSjn(qj^1|{}p^Kr_gn&AU3uAWMGnYW?= zWwH>y8#tPgF%%h~zFXjJH`z=}5N zHv5=%C~K$R8OreVyT)=O9bY~uKM}qO&z+W`20d&(8tHg?M}iRQP3ol_yV?W7VHOQ0 zC;hko?LFV>ShO-$__9Tf_Xd4wDOJZBP^R2A4Tg;2GO5vB$M4}uSn-f6)V1CbJoT#O zQU`_3A4x{yt>&m0M`|k>>w%bnPfx1W3^Bbq8?&`@Qc9+e>XXj$aJvp_NZT$B6P}Ul zah3VGTG6L3;Zk9@jV@1u$&Tkspbn?#)nk311&-lBX~RG>ad=AP zV8?79^J5{A=2D_PQG|U>+q;;D;}jOAEG^(YI1$O`&Wr2WO`p9fZaG-b4Y;Ge9*6W1fBOwTk`3Y?T; zz(6jT5sHJ+GXtA-j`-)=2b}~&kzMElDFstrrRv|k`1TYXBuB*q9D01R$XZ4f_WKS$ckHRe!i=2Vl zmB`|&tu%dS$hEVf&Ext>i+`CDjb_{~)5^|?imNQM#8C77?O(hCDj?J$K7f93+J+*7 zqpOTm)Dd-Wfm3K$3IaVk;`~=<*(1lmlkr9cShjJa21fQv^;S>D z!c4VWUo<{~$*u_&6>Yky6O{C3BNFPmc@8L>5Ay@w=VVJAzOmnY-B?-M6&A{lr5 zNxI4L8ds({TgSOP3WWwdm%E@GiFd)y*BAc2SZA?L84(#b8A{Y8dUH&`5~bR|@7{js+5lnh8R! z9q|u$1rlHfYRW$w%fE|n_t%Oq?|ar}FPRQfE>ke{)$SlS=DAX)++0s~;4628aw&8{ zZ!pmQfFYl(q#CCNk9Rq3w4h9Noz>#-SJk6H{9y%V11ui=FviwX+baYLcPy zueA!My~xJIKo;cSRqzomN@bn({O8IJEy9YIyuW?8RQ55D!~SFpqB&~rE|Lj>T7z%1 ztAmve+8o{+9cIkHSj!_>3I(c_VLT_a+meWGkk|xJ;G+lW>eX(lsgIEUv)^fub(Zvp zN@BrizG|yoGLP%4M*+nUVwZS^p?VNNNJLrm|KkPV)1o5*JJjm0sag%_gG^Mm-Cg#j zzx25pr?x(8orOk_g_XYfct7g@`1^*vQHS*ad&zMvH6-MEU<6JJq<#Xq-B9@Rf>&m@ zt&`OtpFjXPUXL`|0DCYFn2ERp9>DBPRg!=$qqjXsJ+s*I0|>vp2Pz;B;oBZoE>ClM z9;;uvR{Gq5zFUh`7eN4he(!e;Dm_c(sH@%3E?w(Vcd+=vLappUT=80Yl-W2iqCRgL z7>H?OiU|DV6YN&}-S>r0L!V}JvFbdS8)*s82@{fVS_@H+`h;6~P6K3uy1~QYA{(=D zv*dl%x3B8A%%d=7Jf|nA!-%i63?Wvz1UTCl`|TWCCaceD5PswcL&r*$%{2a6%ByC` z;o4R8WmtJjjuUXLcF6uLk6@4c;;Z53Wt4*|#+Psb&BKX)=ubj>yCOXhX67T;0}= z5nv*-S>ot&h+r?szwWS&QKwv`ef2Z8se1i=MTNGZhiz!J$I?aFF{DMnA%EXBRPEZ9 zJ*m*A4&o5a%EpsjXJGr8I;WJsx!>l!zV~AE)30fjq0dveAnkDMUt{oxPS0qMx`LJE zzjPzd$o>elk4^7qZgFTk@eI|?6^4R7rESix;i!MRE3`w@d`R=g_C~R*S$PjZk6k;) z9`Rd|OIV)p4*@_$_KHb5n%R?T_!WP&Bx=8;XN$;%2Gu2OofPGetWx}0KpXIEMQuD} zOX>*Hf6&hVMNF$B@Zmq?_m0!de_YFgBkATp80a7V*Qmu!mU}Y?Ttz|hYDh+S+*k&O zP=oaI=>AJf76wiHUL6QCm9hm2gf7J{1x@)Yv-rbJNXmpk+DiU-;@`iy^c&7X#td~F zbMe=X+-jNi#Q6La0)N5kzn;?ei9)wH5V|W2WvXjMn>*Ya+bqC{8U^|7{=4ud)u4}tsLElRO5zua)u{G~!8*V&MuvCw`JGV>Zc zvaHue?niihd>QV_MFmOiOK)zYQoj+N6bG#{&~*Oz7gy)?=U6@HopQC9LlM$BBI%8n11m))+;Mwvm}pOAxc?D;z(*9LR2w_2SxnL)QVExclMx-oVPZZWNGRXj?=&&Bx&(7) zw=POU3I>0C4E!U({IWb0_sRy}&?;8Zg*q-Y$zFcAE}W58nk0-@fDn(60+05K$ymC6 z-|4}8>0id7(Jte33O1EZj~d2VVb$>6xkipC>r_yHk>T-uL;A2juv|FPYH8~_33O2G z@L9q8a6cb7>Zo5N8kIqg{26*wAl(HJ_b+KbMpR{>x&pdriBe;ActFU5cCjpP3Q|S{R^~`XhBDp- zvFK2S5pMN2+1YYT@Ne6$zc*!d4TFiZn}(r0pHN(#vxZStIgYX3?Zacp7s z(>SNRjchuDc9+6Q@YV-KhfBuvMPru=p5-rN4!3K0;-SKA?qKnxwb?uw4gHU`t7IQG znM~JBtclePZR^A+IIdVtBiSge-!~Pm(d6{@A`>!WM~q|LQoO65XLekk5v?$MwsIPN zZ}dH$ibi$Jp8)r5(a?Ir80iZZ=U3G0-am0%k4vnr(b_FB%nKVG!X8OEaYW8Om-CAc z$@@jwMcWCa1P|3scD=LP!slBDkiLMkK>_~^t-3}d+nW|*XKGZ|ctGhY6~~0zj-~55 z*g&h;P%_K$)+mUckV}jmxa+pR=Jq^+>_FL^#_g7NN>Ax?TPSPU%GcipmftOwO zY*GhJ2`pu{8Ib1~uUG48TFF>sH^hIwIc$`Vo;+4nA{A9AgwGVihPj~fyzKNZSx6Rz zOD?n>$FIne8Z*Yhah>(yIZ{VFP*~JcN!HsO5vkt0Mfg_oOhUWZ+Su@{@Ic6Wflz32 zXDBf^|4r;?1wS&p>SmN&=X4tvS$yc`dcK#yK(KbEpF*^ff;}q7b7I82Iog+T;>|Ij z*WIU{i{$+eOoa&F${Wl9LaZzqNA^g?Cn?yUZC4)^Mj9^9(#wsbVKln=pJyZS6?dC= zBuG--O+Dzv3wl5ZY$@?cytu-F_796sEk8$k{>7J0lhJRt_ZQQq&*cSr#lQ8<>b54j|Qsuwa{e1YRPczMK)EV6n=rE^41LzVcd z8OlE106M(t*#bHLD=VN}9!_RE(84=;GXU-3F+6T_ImcE3+5!U6Bk;ohKm&^i#+p5o zEN8-F-q`I6-$(Tw=C(Q@U2mCs+xJbAwk)B;q1By_SPOpN?iWiIlQ0Qc10o>~w4Ob% zL4A{+%H?XWQNNGxU&f99qbHJ+-O(-SlHBNwJtnmSLd(kbA`{?;0+h682S5jYdiKZgCHxJE4_zy-C`XK#oW679tTWO7GF_;&FMe6t}J*w_2p) z64Za1<;Oj9XC!>8p4M&_YgF%(lrU`YSm(g2mnn^#4ZRCV9@h` z+`RAeL;hXC!d$Z};jgD%Z*NELdLVevA_9utaX7iO`%t8~6;-FxdT zURJ+HM!EEM6&rIutVy*neeb(0OmeUV^B`Hqn))wHti!hSgVVuqKgQjE2t)Ud&6|?X zdTsh6jg(Kbow%bZ?%v&>-lASSXpQP3^6MPf%#K9BpY( zx{<=P6)S&s_=}XkqMWfp!4#;yu1ZEXE!!Twv; z&Y6G7k);4k2jJp9nNh=q{vRoq^;u)C)GgqzoXJn8{{S1l)ia>PyCeJhRjHw^R7xDl zsb=FhR+*o=y^f08FHq~}fNb)$+LZ*Lzn4~Mh#35wRlEF>*6-YZ!XWZ@{&@cMkN&$- zCm+I1^|2vij!87y(_`*lV|zp=3zct}tp_9xE_uRNHXWKGUN(@V<>xQH4V5fvBPqIE zQrL3Alv4}XDieIV@p)3dC|;b`Gy}dWjt^NGXQ|n6;UAKdLwg-V`Gf-Hsb2<02ZZ)! z<77mN0tZ)0KK4WHfxT5IOZyX`2jsi0xPyP5-S<$em&z^lj_;ibG>p8pXjI68P1mNr zRlH;~MPQJ|VO&$l37iCluHv+k#woDM{o0CAi=lv4pTvGl>gg{bco2W}k8O8dp`Zp5 zU})^Vre4q9i_AVs&Ui@VeL}qw&sbN&3Ujz8HLb`^WjH{A^xVUp=_BMF(8m*=SAehKbx#>yC3ZWw-qG8mG z$I^y0MBq>J!8BB~eSLE{pf0zhFW69Co4X*|(`Eg8?aNJR&Svbn zdY!>C#T_OT>0OKsLx(AYw^pvHU^S$Zj~h>f!S|to0fw+xEb}Lo9O%C9hdLv{(ONjo8FVV9busVhN2$n&s!cUGq+$!fO4YgULA zcC`!`H|(U8<{`Y@`f!(ihCDHtZ-t`H+XiPjKFPbyMojImIb1R0OTKg_d44 z^TT4pM|g{m{*Rnx4IINq8pMDjI9+xNo)+%<|j! z8VEx@3R1QnC0g96Q<%Eg(nE&?j2~uHB4dzDeXe>E(13Ys(F9J$)oI2WR#y-fI$FRL z;J|z9Kv3Y+3(c@5LaTKl&=D34C)nnk)4eG22EHv~|K?j=GOUL!V@Vfv&nY zuB(Mk7e8Cq>i-&U@56SkqMPdmS1oHmp81GA>la0O z%DO2w1cuB2RiwS80|GZk@XZRPpDeY#{1@XGIGj`{Y#dh@1(?-P zJPoOSvG3sYePvjbVYl@RUDDkR(nEKLbVx}zNOvRMLr6CWN{Dm{ zNDkeS(j|?gbezZcJ?H!V{hMok%r$Y(zSmxB?Y*Fq?|#5%pVh(RMd6TS$u`BZI3k$j z@O(^7z-OpL$j`?_?0zq3Q-`s6PFx3Fl>Mj?A&I2q+Wav>s83Ye(9ZBx-h}}>xQ`j% z2tArWA*A(pEgHWc4tx;tk1%I+{v&5-pJbT;CbhrEC&}dyPTJqZ%~^0lIa;k=aH^g2ku@h~$`DN|Sssph${k)^oP~82}>0?=sEuO4V<{h@k(PoWb3O^N6lJi6pzjVUA z^F4vC!*w1cNKB;fyF+B)`DE{CFZ1fU$u8OOD{`Z!?MYvoEaX6|E{WNfxOZC+;Ry$h z!g`z1xXj(GgP5Z~W|l1pxnJy*kwTm_F2J{jzausU+1$Ei3kCeyzj-;URIjVE+}=i| zL`>qDQzup*!iAsH-cRh9XdIZ3GX?pGj)|Qt;7P3vUftD!Zid4c!zCm!EHFMH#AspK zwYUP!#B1=-pAyiw30C=C?5Il(%K~Ak;aHYaJH_R1utC0E(pOK7S`tEa37e25#(kyJ zOOAtfIxZq*aXgud7oaW9BU3F6kz&x8x)tZN6H=TGBV;tKHH+a2CMP|(+1^XB4stNk z4Ev-M4N5GMkRzZKd`-qZX!_?Dr>@1{RQoAva*II%EN7UJ4oFOQhAKN-PPb->CChJw$67P zzVhS_h^>B2euTsNG42J;N8L!Q{#%# z;}mp3eZVy3+oy%0OJ}IV*y1Sw5C@*h&~;SNaytnp$GM$pjd&<;bq_O*u5~)yHb^u2 zA?pNz7QhP+9X#qX{P2lBjE=g6px4e{xgnYt_-NFQnw7y))6pU)&=i|Lkaclx1N$8W z-D)=6p{yYU2!{KW#Kv@;A-4r20k|<^Gk3TT@qPw7GIf=1Mf1ue`8P;YtjEo>KtgFi zGn(6Y+FFxb!rVY%wj1)mx*XzK!0GtBoA9zhi>e0&+cgj#h8ru#;WwbK6!Y3>WU)y% zONJyoY%zjv>K??q1}7FJM4hS_M~Vh__F!}q2_3r?eH2huZdL<8T6BbEen>bAPDn>&&-M*Mw} z;x*V|Na$}gvlQP*2!HoSwluTtU)L&b=b6aJ1K3pf?JhnoI;8f9lAwn~Dypp-0Sj|Y z%qe~AEehPWTuzCuvIV2uPz0%`-)D5|iy80kU(09uwZ#jyWt@IKl5XW^g_?izom&j7 zjVCcAccRZQLe*I6>G@d4M$*M-*<#e9y3VzI4rt{q6Kf_mIqd(m8hnaORtv-}_g>)# zv<)q3(HI5Mr0swVeEC>2pU$W^;Il<6N` zb)bs`{7C<+ShBor-p|Qz(;)o&Prd}6WdLMQp;sR7R6a87+9{^UguV6ReaDZ;FtGkIsJ&8yPt9V$xY9BW%X}*(t6-LV(5a*JLCEmodX3^M zCk%{&&gLmc_<;R}Yn>b&gAjY>E4I}XbveP9TQPsAzRDaXK>FXK#vVK|CI(Dznsv)` zk*osEI!0;i2gNg6A1jR8EGeDow*)hK#1?1TwQYR4d}S2{erph{tRtwONh6%ct6iLw z(!G)1hDe0N?|H;i2GsOfRLX_py$!O_X&rm}p2ag8`U`HtrnsoyDOJl8uey;#3&GFh zu)&NcvKLoz>8o(N_X1tM0S zvIUs`kwG~kBv(Wz=U55Oqr>>R7drN28YuR2E9(E{L){?#!GFY=`VDOd4p>s&k+*e@ zz5~_FUth{b4aKL7hHQHNR8pQowrFRv(Q~?B)3HTAD*lJva6&=rQ1k5L|&h}uz_dc*7HLqgcX~qa< zh`1m$n1HJsT0;E7b{^A12h_Gj&zC;{0ma!7+LARLbvxN@j(77NH`uF9(ZjO23(#t1 z0`&)?aZEWf^dG+GItAa~-8H1e@&;!x)xhB#oQ66m`SRN`X zn!8TS=k7(tNV`rzgScl+i|4FZMlO>o{<+JIt@NE?=hv}+5P`1>*W$xE^lx{U;Gj#M zv&ElZQ&r14dWbF`_evYP7>f>1VxmjPlky#?O-ogXQs%|JX5yS*BkT*OG$!qRQmypm zhWE=aH*BfoxEK={lrGaaQvyh2J+qF99)>Uj`JRNbG^o_u5PpMNzfQ?9O(>;@r~fpC z+!YLhXiKgRY}>{Q{RU#`{Ra5X3d|ntrFm)XQ%}?|I^p3hOY!o4siWIxs_HE(^SCE!?$ zDYIfF3=cCv@9(!DU*}rf?IRbDe1n-)el5>|7P3JI>mAA>5+M|vCXd%8O6ki9MUv$q zknBMn@*-wHeUOLZzz@MkDc=L~SSDi*&i(BUy#>^~o2k|uUNlOk)v8^yepP8f#ZewL zDU(iZR|x`+2rnQ1@&5dB0- z^dQ=%GP-@YC?X8QeY&PKJoH0%K(c##@~KCPvSb));79t~&a+qwdewJ6-1gof0OAk1 z$9amNZv{h(WvAh;@OYF=cJh*;D0D8gHB$>0F;U#a*6^vIE5;``Y-U;uAv8udzx8Z$ z+>g|!@(VfD zzXq`5q-5{45^d6@;mSxsH+I#Y=0OARvgT($b$NIVTW*I*5QVwL*>Nh{IZqD0wp0#W> z;-^EV>C2Vl#QAASQ3@9r7OW|Hu=Imd3NIzGHUn=;HfmUJrn4bg9e;EM=Vb_sW;R_E z1QNlbGIzAALWA9Ry83oe-Cy~jP0RTzdkEizv$wg%x#kpCSxY^QN^#0_q!M{_el9uP zQ-q5EfawbWm~4wv38wm6!Q1HtD z0>>K8v{c(pBHG(%j}@`)Azjm4T^R#DRjXe|$8Q3JB#SSW4d+k)xRs>_$fS@l>bNAybtsDHI|1ThMuL7 z7-b{d;%^v-khdISr!d9yP{S91pqN`3VpZDWo49p~1e}hzTT@yAgHqwEYm3`vElGaU zLie~?`@R}S7dtO$*qoowLBET1^)?QEHSXqf0N;bdcq>(w?be@!$`cosAQzy$)+ej~4A9j=YVc^52fu{OC+L zg}O?X?dp@+S)goX80eLcE!pp<)w@Vi@bW(3AH+ zPZmo}1#VmaD?ocX2>>LMtpX9+DZ@4@0HEHt@dfm{{>S|FkA1QUt(RLko{g+8pZqW4 zn$QLamz)KdD3*t%C8b5R=w)7d4BiH258&)PSq@mJjMYK69ghnB_U)m}PX=OZ_ z+lvRfa(UnW+4a^3JB$kEtqONXqo1(H=#JMr=!;6z&+N);D>#b6K{&5s2NZwCiyBWz zYhk#uaZIQ4v_;XimCk$=G;vC*te_@r&6*#Aa1wfiT4RSrS&g+|cTcIHtT|F6yd-^; zL_(ArmK;6;p>WY2q{RmO2$RAKA|4EtLf3g85E4pX(a5Sgfp?{!Lhmwlnh=J5wqh=a zv4bRJ^35UFp)5e}S6ZYM)hI zEtbiJ^nYFeskVthgu>;PgF%W%;WIT@5|_BwC&WD6pTNP(;fcP}(E&DqSk-p-S&+RF z%*JBlD$y|)CBvIdrI+vlDWGUHVd7B`Q<#uLw#!8+gcOhwg>5{Fd;XP?TNI0g9z00k z*|W~|Uys#lmA4B{N%orf=a7v|#3X~Uhb5Ors(b*Pef?&-T8$`oE`X4A?b1?HuU>G( zKOO-bZ|8OD_zt&^=%GQQR&4$HVfymEr?ex~GQ(Nzg~{3->rk2ZwS@xL?J+Xpa@WDn zNFw6KCyoL7O>PBM-M>Gc?*`~C-IO{kfvaYxc#e1qACM1r5s#_+S?q)Ek{;vb%YuuZA$dcC*2US$^53^=qHnTXo(ur& z)eF?Zx&gq`_Qhzrbl7rv?rk{+#sjUx%9 z-zfe+UhRu-l?}isw*|%P$_}st5@Wa?m~-eBSrki^ARrNg93h6Cf;U#TfOQ^@{}q7E#q&#CE^NdJUm3MRbC@j>{fx+Qvm|-xhmYn2?SDhq zLS;z-w(JIuGXs>cYlnDIVsZS;KxIKi!J*eG^o97Av6qe`AD|EmxWM989nMt^H3x8(r}z1 zG$hX=gAj^1ZAa7mosn?EPM-I5N3}r7noL!s>@!~K%`1kNpYw&>JrW04lr$K)w+?9O z`FRn8XXYNmF6h{IN`^Qvx)2>=rJ^Jm6MQz1$`3eK5DyyKWZWyc-VRrrS+bp!ZB2%9 z{_=qst69NKUd{UTVJmYN-Y@W6o6T{)qVgZ7f-S;~gJN7?U1y(hx1mhUgS0@n%lrs2 zyIhnp%vlg7LYo3|jc_{d^2=ftv;|)Zd5U7iMF05rS5tPn(^%4Qd*sa;_|;jBbc{xm zDMQ)j5q_2-AY@<18TzDNW=UEjiSS{UG%HvJJ#fNP5NV|_(JjMdD|;9aT9sb)>_Ko= zd_%Yhy#5(BKA zK4m7GI=XH2(VzUzv&*=3au)pYJC|u{?_IJTKl&xaZ_LP70t_NE|KOk~-Nx|n$L!}e zGZ%MF9O~5ZmDh0CdUM2dJTuFRZ5*MaCs?gOa*W^)6Fl0&pFkdQ%)kbv6~4SOmr|N1 zz_J6}gGVPZoVt25zRlaJ6Y2BLGej7N0Al3)e7f2sH}@p8oBu625@&uPA^{ndl6CT`On#%E)MZX}g;^MPv7dO!_N zeXS)$tYNkJ=^rtG?^{OHWqzg<9-MMsaed^sqwQqct{RLO=rF_5?oxcZQl|qDX&|nM z?Mw${Q9j~xD%={{TaykLvb}w)k8c(yZjsCOo)v`O&vdM7958LGQH&%b)NuRLnhW|H;JblMyLStR- z52Mf~1j8*R2eIIwPJ$mo+4JJ13>>B7WIhHlp@mmQv~Nq%jsN+B)m0og)E(#v`xAB1 z&$lm064=#ECvABr*wc{{;V5i8Q4-&fyA{jO3_OO=Vk$6T;&_}%M>N^`A5;V;eq1UX zc>>WrU%{Rws>|&S%<3bP_uft~q~B6Kyi!7oL{YXGqP~z%e-FFStEPd<;3DTQvJRp% zUI&~PLxVIEpVH?Y_u7{Vv^qVZcO0bz0%$gTz>d|AyxbqgnIzv0K75EqIp+peLcK~< zBL7&o9^2=BoVn*ZU3coZ+oAdyq5cl=>&y$!bmbq6H3DW((%t%Rq8u#mM7lDj`BqRN zniGo+R}P|Lt3YB=(}&7G8Rw`Qf39_|^=vNzr`iaw*#F-Mz}r%fFaKP8bi4ina5IkS zfRP_&#EZ7lh|sF&OG&jTpaLrK&PjmpWJIOiP1$*;?sL3fkGsm5E3@$Ht854G#tcZa ziO4Pk$2yonrhB<1Iu_M$!myzk^fa77+Hj=!C{ks{2<1*h=BDx~x1%?FsynAArAOaF z1Q-lk@(FwIi2aBy*Dur8CBOxrlkr8(6sc`e@bzKa<1x5`A7U=qM0GhF z;9Ot*_T?1al#UBSU6~vduKcr`)->ZdD&Z+w$v7} z^!lr z$wcGeX@zptM7l}@f_({n=QpBxRcQ&)^Z8SuK~=4Uuk`zRQG zVsR!Y?^LzaxBGU-HH25HL%-;k&NL}W)f&%&5ok(in#~RdY}lec#HDs&*9b2c+f<_h z71f0jp(^o8PKcVXa%JzFR}3)$qi+#|t`|diDRT~Z)SFmizNCWo19gHng6?SuItYg4 z>erPf8VP0dzssd~H{K_gFgB@=0Gm7+${|Cn-RWw6s%fv0;=+p27lxCilCYYW#HD+R zDTR0x{%Dc?is+U^JhLs7lCS_-PC;p6rQuNI zH%0v;FXQ1wWjR8Q?HNPv=Xk)g!Eos*9@)LD@N&AX2=2MtvdMEpFAVhHsO{Hiv8w(t zpdVxdn#sh;W%!Xhy;{d^LJAyF_OeyqUH^=x5LDvup=oS=ef>w>eV-V-xwOANLs;hU zX~<9t5KTeSf=D>s@mB!oEH;Ac-Ku6@uZ?nXxnmL7d~DHe5e`%9j5Qg z;8g?}^OPB2p%q3X5AUR771CPG4>6xf*Peq)a&jfI^04e`TW?9-uq8+ zQ=CjQiJ-bSOXi9%2%-aAy<@JpnsB>DX;2>~J$*|rc(E``!bgHtB~TN6h=GS^nX3WO z48`yLKgXXQteX30y+3e+-fRg7gP$RoKi^?KzZpy#rl@H^c-lWH-41N71mvkX2KAF7 z&6BScUT6zxQeL0lD02)N6%9+}1A4-2jwYvi36FiMTlrd%fjr-4$1cJAA02L5<@=xw zD|K_ICfo^Th&>kmIPt(+7+jX&)G1sXO^Rr7eHwu}BTo6Z2+>oSt;W_U?(Qc>vMIE1ZtcOYU~{(( zsM;!Ve*@obUFPcQA>{&B6q)B>iT{_R+fH(cx&!}!L!*{GN4qEfla$-C>$&Sto?jEU zUjAq+)aM_Q#_qzCEJ&E(_~p^`^x;0Ra~eo(k*RMRO~}`!#m-*W8f=TI!xy@kT6c-# zb!ETzK5SNKVjeli+xnX9iYA0f@9_t#xu!lzweh6c$-pS=;nkXjMP_tiZC#|B5-Nt*J(WR^o!P#44dnJ7l~y2h#EBE;|b zn8lwI(Fi7|H!4vw=yx=*HML>rr03-um8S}bU}fB*q5`~Gy3+A4vhJ<;-~SSrd~U>_ z;eVgP_-nY+bly5~{b7*Uf zQn~JZhRl;z8FfBx-`mzczgXc%e&mN_3R)UJLEqyII=mO$OgpJ|2g{O}97k_4@0a zdxuC_ikTe95yFZ-N8wXhmgidH0j8vDorb;g@}5RJ3xb{sx=lrU^_&nM^PAG#%FQ!b zi_x$>7d2RlX9@Io!AT#oN{9FL?BqcoGM{jGesf{%5Q>)GeI1T4)); zIBb;tINntAW>s@Tv&TGKCPs!EbNEs}#dV1N_jwsDcr4fZ2r09cpbqR-NYd5hlpo|) z7rbXNXVGg>*1bx|TA@tWuDKs@(v8k`Tb`F}nIvlJDSxWsUD8Zi#zEM6G+*T&Z8DaW zTZedV8fvnE_c>5d9lP*IOE<&HiMCErf3P~M|MUTEg52~T1^YafuPXkgitTktkERQ` zq0SC$razc{p}&f~efH3B-<4n~NVvaivQtF7Ww6VOTcrDk z^kVRzr0Y|2vl#3d9=pUGKNSx8FcmS?2|IXU)UGbr23r1mV3qMLr^;epy#`Z^WYKuQl_fW(cBPTmf|K`7U?$T-_Q>N38NK}X z0<*Gm8q93BDKf0q{rH`?&z3aa$^EkfV*Wsed(?ULiNnd{gaV2C?~x`~W0sE0Jf<{O zz3P5lOt@RF)YFoh6+z+8XJMVKoFT1_$+ zVR+@}#cbYY$C;qj6g}5Wo?5|ZmZ{`pYdy8SC2=HmFeeMd?q@$J3homXKMC*MhUZcg zAI3Z-1AcwZj|n=bYF?vsI9x`@>yw?%$Y5f zp+hv$_N_XR^~3=r^_*LD)EdY+8Y3GWleV#xE*zzt34aq6f=A56;Qz{Bb7%rHPlf!4 z(m@r0V7jjwJE5S%wn-J_)?-5mmx^u^%X`H_foOa2`$T?opiF;brVpH9=&8_lqCEBw zBcdq&KXa_Fo(YM)6BmN62p@LuIA;2bUt`AM*c%X`q=l-LA>-JBVLg64!VFuq+9JZb zr>*^o&UfG1ev&>wIMn-D58*F4cvZtYsx$PBkv9$ccY;dEXOe2v*sR*GK02l zXU$bb5sn@41%Lc*IJ_uuAQQY6%jH`5N{cz_+r1$YhMad!p|{!Yvu0DW*CxKFMRw!R zG}k)5!55Z^w_A?~&W^MWe0B_<;Xj!(9Xc<2SGd@rE}+-}f7^vWuSunhEAF{hd93kt z!+$z6sq`2mTc(qL&O>GF;3L5HLizNW#An*~nKM@4RNrNpNZWOo|Kv9h@sS-@i@xx-ety`=rje^OA-@82UBeobQuSEH?kiJhJPGRD|F=kQ9YxXkim+Fxm=6Ad9Ns zLaLiu(B%*RP9l->K#vFifK}`SH@>`%D@!Xg~$rw zq9d|UTR5z&+eW|VKP5HIr($zm!Go)Z6$JVp<0x6{RbI2cDtKKt5^GJFp#kbiepGLQ~_->3-Gg>6M-dZ>V-(B47!hcNv9J z%$x>cr(o-6&mm3n<{~t~Ria8RVF(Ihio%gYC)bfXInSRy(NMl~)L4niXYukpQ{ky5 z5FLfu(iF&nFuu`_eL)~c0%9;1Ugpms<|~#0U-zcN{4a1r;;9QM>K(eQpgoW__&lAZ`IH8;gb@k#|*M(xxAGbf1HG-E)#E-jnpn+{Y{ zn)-u~G@Jttsl!A$YVw)<8%ajywyX%Yf?R&-_DLo%2?(vI(+xhU+=9AXXwzy44jZQ^ zf*E_sX@L3-BDS^A(g5o&vx2Mjs}l0fc>>$d6>p4hgOCMfd&tLeoe)I4E4fAd$=lfw zEIAs{S;ZMSLhMQk$prl~;<{(>-_U9ECopiq!~*AmP}BTPTdj?7#O*>Y^>(N; z9klPl6K~+ixuLa?Ur2tkv4vl_u7(iK`QhkhR^{s9wv*>xYuW|z-hpdsWqjk;H)Vli z?f36kod`;1q*Bp5Z@EnPM5bfWryQ|V2{+bGVk}nPvJQl7&$kN9SZm07&iAD7Fz*?$ z;9a{!ZU0@0*5rc#%(d$(7_Quot9gdl;?1VVlP-1oU~btK9$NKC7OUn30SlkPw2)Q7 z^|uu*;-)_Zi zvS1w?l)3w>LdZF>tMPdOBSz9@UP*-AMR82YE2=-K+`{?O#h{u$lDv4-C*#~oF~yN$ z?HF-J7IoVgP$3)j8U*j~45P916_&Pc-L`78dZ4 z*i%rKP3-+1L5db)(#RVR_=^fHBv$^uS#g#$>~(H`1SX)YITMY|1PkDRvMNzf2|5|J z#bHkw7kB75p3U!DKIjh^vMs_Rs{{gocq6~%-6_oW8pueZ0wa>tr@aI`_^*l4<;m5L z2i(O#*=?T_YIE}FG-IN3cT>#{*&jUp<~$ldai*Wg0hchk2L=3={yLD9yk-B53rp0l zfN$BkY0y@9en6~k4f=q>UkGPj9k|f^xA_jkm-VrvCm2k*+&N(aF(g?JtSLAZd*RqN zR$HM3f}4DAu+UY9ydK2bXx%!rRe#!PREiVNDNt7RDI}? zLXNi1t4~Jj-0#b|Lq<_-t*57>ysd`$#CjVezr@}?H~%I7o@}mQTiJ4|JM$*=iy9b% z4-6gobAG;tWi&Cn!$*?$w^hhr)Cg!7Hr~d%{R}X0_1r2W-xDrn9NrJlYSpE2V~=~` zboU%oKO6ckx@Ra}snbN-WjVmO(H?W-Z0b@duGdxQ@RblPKH-6AoZH~gysq0F_NtpZ zyq+lBW;TmK=pDRjuZ2t(1s&sedr-WSqn>YE3Wl6%ZejW@!G=)xQ&<-Z+xBT8+K^kd zk$RI!mtnq>Yj*T#nrk*N3_6OCDFTefj+cpxz`f89VAymvhc7%%#qjEt(fodG1lQOG?DV}S)bzwo@d08^Zo!{< z7?~aDK=0bKC^`%fqqfASuxS#_vyyLXC#8=klF9p!!cDG3R3BFjKUx@+RDi0u+aS6d z?>GhtVpvfYcH{Ij{PPji^!3TaLIr8uU_Gck5L;2r%e>pgDsT7m$upreE5koF739iV zgIW#P=!2iJ#&I{e!$%o7-ewgV4a`1$OdEDP{=9+8mH@nGi1`@#?T$@=^GBJ;mY^G+{z zM$#Rg+q8W-h18h=tQcQKzLoR8pm9W}EO6S({7~!N?B0JsqmeohAKIS+c-mw{=ZQ2` z5=M%X`+5*=E~Y|)6#d1O^*hBvDBWtuk)Rm$?%2Jx6hur#m}t_tOPHzm*WseJx#Kkd zJwy98W!vcZRk^&6h3ED`MlJ@Icd;SPSje;!WIqerY6a5w5jn;T2+J))CReDHlo%+- zaFJ(#jC9IZ0${Ld{aQpuAm1c@*xM zz7O`Bd=U4p6yxfWA8XREUhvqx6}Rrl2@WyrgP;LR#~nOR_|ZI<+jRb%#oxY%-r(hx zifep5e^wsP-a9B_Z~qI=H)u+>0vE_qaWQdkR%Jw#XyLlV1Tg_W?p}LcXYRGDWTw!5 z4is`FAS@7LYdL<|V(InO!(t)@C!+XMh$@(cVG)Zu4&a4ZivPat-ym=M8-kXU=#kD- zaIis&HObo=g+h|5-?OvQLgkC^iw~IZO58=^M1N{;O_$Nufx8EO_&4-KlZyre@t6NP zvOhcTOjgWXOUMPrvYS>fB|Ui71HT@+i8oni8aT+A#JT0hF5rf^m2rvN)^=%a7PLDz z&|M16@2<8fCH5h~6X&*6H3bhnd;cp$innqbnIQyWtKFu5^hdiaO2;3rTyQxNQc#3a zHrRplqyTJ2GrT^y`0AT1kGTcD;w>PS2;4IWaHZL!l}_lY+5m}LKeG)kQM4@nKo?re zFt-0Ihct_Fh8N;Y{e1Sd=3?z$$cxTtrNoEy@s6Z&JUOHn+w|(J5*>9`tU;xI{K2;j zD&ayFw)THsfLQ8^kLjvx*{_^kAHaO=+?+i6@GD3wlKO_^t^*t{EBWD19>3dK8@(!5 zJ`tU3k&~%(B$^%hcf-o^Z+G%rmVzhzLx?4%W34Odv|lT~s!rP`#j6}^9gF`mE&ems zZgAK3k{Y25GuKVayvjc%jfrhD2KIWx4sOuKprOFQX{{``AJIsn&=UX^dMg`wOsI31!W;i=TPjS<_ORWFl5>F6QfI~21D)r*zt`%cmVj#aKkY} z8>aTU5`4!Z&Ay7mk}okfg)%aT8)&!ZSl-iE17KL1G$p4WL1$IXb7=Z~@!Ot)RV2v1 zCfbf!5buE*^W_*WhFp+Va_6 zgGxIb<~YqX&3X_d4>j&xGiZ%M3JMpF6pn`4g7jnBWomE3voVrVJ>eNf{EZ|$JuUQm zk?LRSknf=ScN<+q%K4FXkY-gLn%inOF00yuM8j6+5lQ~cZ?Ny4^TGCLM>^4PDuT^w zNbiqrKAoh4F=XhpEkr&`=B=fGVo5O7HTltxxo7DRwa`y;r6br49nUp{8_t$q=cOXJ z5-S>8G&0p-T#-|M-}HZly%I)3N7)fMsTv{R*>kN(n$&#P1=}M zP@{Uij?tjPjr)wBK4n!r9-k7PA;@owy?z%Gs9^COiK#k&$_0K%7o*+v2bL8!ArBIw zwWthnNfy15gcnE{zL}zLUP6F$q$(xJmqbZMfIY z7GEXs=O<5`9Hqc5=kok7qDdb=o0${j+2gNl*;$qgC*ih7>U77Mc=Hi6pIo_6qeS?f z)NoS%_J2o^OKjE=ya+X{>hMeYpfa$>^}KxDbUnG(vGtup*r`L0mF>5Ukcmw}E{ft> zTm($oRCwro<3_#%~MO(Y^m_(M2O{!sGy5E(V+8zWZ*7?<# zu%1s|=7h#SAVvGil~}qgRXX69CN@_{uli^y--^Ku88Q?Ddx1EnVE9JnZ(cRdY4ibo zYU#r5`mC*eF#jUxIcGPMUdAF1)x%y?zWu@e&TeZ`1JW%HI_l6V-m!q?OS9o^aN$_n z`%Cd3h8C4QgjmWLCMb{0u1=3bB}k^J=U#;ue=`XGbYWi`t@}%!SXx(mYzYfhD;S+_ z_(w(*Re^xLKE5i&lZd%GQpKat^llxMH3v1E?r+F$f$L?S?GfYMT?u86vtQuAg?~!; z(eu38u$-tMkm~w}TERm+wbrzHA)}lW!9m;&1)Lhj#vZP>ss4%ZN#JM{(5ejK{epR{ zOjSW2krEt~y}gl*{o<%wBxKv>@m%L+p!xfCgop9sQmX=I->qu+0%%?K@%-BBvF{4f zh{ML8Al^%O!h9LpZxifbW|%#m8PK+i75~@MT$JdRCT#W6A?$}u-~)!fW8;s%iQE_3 zx2=04b8jvaPP3Z%jnHh5H&u@n=ht)V^^vzoA;3VgFTo&(+`fM`y23vI9Sk;}39S?~ zU>}QZn*dd_(9ey9RN6ESe0ExmI34pYEXUcFLmA$eXQx*lzt)ImQ`WUP=fl{5k4aCX zNhfB8LKf4wv?X4E4uzdUxiy7_^{_^BOVlmrv|C4Vud&{GVQ(5^q>$lwxLP%ioI-ef zn`rxKuL^nAgwp!;04|WdF!>V$mJ|AJxcgfUsFB0TwcL$I4P3^c_8Rmq$<|Ca7Edto zfj7iZqPbwL>_M>keT^FEbo_>8MAqmuVK3|45%w41<#;T5uN)R`BTB#Bj!Eg6 z7){DB*g4hszUBkoEgoK1z0;4UxjPPZfCeNiRgSz#xs3Qn6fTa?R0F)=e_@^12$3;S zDMz|o(0|B601HC0R|>k4|C_rjn>BaNZG-8UhvzB6 z5FThu?QD+9M8w)^PIDrF*h+fXl9wHhO^DQ%pqAt%x!z-4g+CbIC^Bs&pLv7VQ)7&z zYSTD~F|3Naili!TBReqdSU~CGsqeafJRluX71@2#fLbu59WT{wT?Dmotzdo!T5Ez+ z7`u%V#o8jKwmPDCvyoN9tslYkE#WY7<8yF@L!Vkxqfgz~7q(P%OmPkm5U%nDRACo^ zHz*L-H3#G;LSb4+m?w{sbl}2_EY!AQkFr^G|7?!;DmfhWH16IoM6;d`g?P@m5^$4_e4k{ zApS{lV&=GMxMBz@g@((N`8js>r2UP1dU5E+TVD9(P@od@k2W-rU}gU;4|^4XaVn7I zCPT5mo7LmPxKX`jHhlXcUO%rUn!Vnc-1vVa7$LlHZYXkyaoCegc%V5W)4pmz6Uprx zgoNx^^@P}#Ib=rX#R@H3lv^U650)c6aDixer}-9o>5env-tZDVD&0gS z_FEDTs*h)brti1WD_(N159B61);(RbVWU3ZS~%Hv^vQ1Q6MAfInb&Kh7f$qTANGVN za&Hd!Oah~__m0yMs=s^WQy9LvJ8bgn%6Ld?SNT@)k}v;v%`>UG8O{OG0owr;dm!9> zC1H`zkZL%cb)o+YdvJ+GTZ$Kb2M3bs4R%PuI$j=N=hHuwOCq5luDV5u&y|CG8Y_>b ziG&IMKw|3HW-jQXq+};%dOKP18CDTGb5$@dx@ok34R7!LnzejxJoIo^Ze~~J^(JLD z8YN-i8f!SM)b@rQE(M1(95ZdG7Auu- z9`SKL?5OZBW}C%ii+Rx!Q*iifp@o<7BIJ1GmLZqGE8rC{2nwHjVpG>Mz|oiH|0?nY z?;0`E8xNU%v60sS6CaLm{wTAG8njD!!xqA8tF*?~-s|%=Hcn_vRtE%*IzTPbrh}6^ z$G0Vgr_=Bf%@7NJNU+4fT{1^0p_&v-oFSIEz}OP}19N3jYYI@C6{WLug7W3;6-*P( zfa))dOkCOU8b|F0qpxY`$sLkH3r-Mx&mC*kT{aj3=SkQexA7+jQzPys^!R$c^b+=( zRQC5?b2)PzCZK_R4Uq=8zWQom5G}XFx$c(xmh5YNU1KJh<%)~wd`LxliG%FRO~cVQ z^^=(346xhrX!bJW-gD=@q8AAKMBdX%sR`-BKa9nf8Uec;fyZi5$}xfoU2N;f`*~N4HZJcQ^sl(^93ac+z!9!Q9Fic8FKpYb z=z}C0U{fWMW|q0^f%eO)Dr9XzacPAm*=QEtN=f7b%u_pvx(KkYiQP@bNx<%+fP*NM z4L6_gUI%$9&MvO!uc}H|v+dh#Y$J&`#8gP35OnHWa1k5CkxLphc#S$TLEO)?(-#0w z5-4XutyoTP9fg)S?co%^(yHF&vL(i7(gNHvGv6OijK1%ds0Li!5Lf*xV3R)Y2n~UP zFv#%SWXIN(=D3pmr`1rb368b&F36|?B{<<|8H0ae$kcYFh}v=%ws6=Z-imTxVaW5_ ztk5XoY98L6ifZr9W`)f+yGI%InWzt#B?&~`?zHdCJT(YY*@rK3LP!rUiB)od0X z&2la}r9%tT_WJ5z9M#I}4FF-;Rc#{R=UWn62%j->86s3*`1Kr~>O%rWUV~b~^*v0g z=Yz*ee#Y%_YPPM5SW)js?u9bfRJ<0H4~faX6_Q!D&kFM`?3)hD^NZ&VPgVca)O1g_ zP5VkW3KdDq>iDE|Y)5`#1qL-Zx{D2RcC-(P3$ql}Sb{NbQ=(WXotBB=O}H=bP7CYa z*Q|jbCAzQERXhF$GLhvbm3BANCa3!*eS_buqFxj}%FRi zu2zj8arbfcw;NSk;^e36o%6uLWp{QoHhy{&qk~OSbnh!}^THCP)?FehLXm?@ars(n zl|R{Ipm^09vs-EK#-9JhQoVAOxH;+ou1l);*aaS_&%f)pzr^kV|3;MfSj0{t-iyyx z8u^dcdBl`OEz^MWr0o#-ZHV|A1q8HW}UrHmUOWp1X?O*bp4YNaT7Y1d< z%?&?cju=pp@vb&&mAhT_)zo$R2@LtoV|bVGZ1*!xPO2!{*&-?z;!y4GkK%phG|Ig` zT!&mcnmTj^b&k5fE?*-W-jI(aI}A)IP+X*|`KQ;OX`QzefLeQ(TdEqm#MgiSyWx7h zD$Y#Y3pD=0F+(93-+$%Vk@QNnyW*qX*)PD{$Ny@!Vt?D7LfS~mL~z91fh?Ns@Jo3n z`ApfeA|B@}pPcE){fO5|@?UZCJ|nXsC}ZL_Y@s2shmaznxJH7*rLe*=k$#gf$M*EQ z$7NwEj*}zpp|&~M>~`-B)GptJq0pXr&t>{q9O+)#zHRweEreBksv^}ge*#Ho#eI-z z=X{*%r7y=nzO9Dgsbg)v*ut@dMTPc^Z4Q`m^*ST}?t2L`4q!3wo+DN<=L+p9wzVqt z9;+9$#mxUYo$sr(Htj6mE;|h4j&;tQa;lvT5H5z-6zTcY5Dx0MO9*{tKopekg$oO_ z?_ojgmKUL2ARazT7H*@BA^$TC!U`!seBpRO zg123sS69f_Aq=oY%~{=KZr43(uoiF^Gyo+0e(Xip*Y=~fb2^tD3ou||gGlSPMT?Np z*QHjy8s1yOFqx-G0Qi}TtXq!|^u+KzC-Hp!ymF|Vb{JmBHg?l{q!>MZV0P<<4_{Dx zY5#++@}D;#fcrA5Od8PQbmR(vqurzQKaBlVRGVGfH4F!Lx8P1Gn&42ZMN4tF;_hDD zwFIb9+`V{lic5eJtUz%HP+WsMU#|QApZ#|;$ru@tb*^)+DaRDl&#+I0R7OOH$ zQNTeS*q+01EpfuPbZ_Xc#w0~_K$eI1d4h<2*8|sUt2t|=3_(~@_2Yw>P%Fu1fNEdB zohJU@hEvsus8@es^vVIu|3O$EA1`nG(++}G6d(zbzN#U=3U;ZcAD8ZSOnK6RI=lXS zUkQ8>@_QoeQ2+knVzV2G@CSOAVE#pK!jGuWEilr@!8`RAMe9-B{kUhNUFuiEOMz15DY4IGNS71MR^FyIGG zP~i+YNS2BGunTrt;%)Y1-m2u@(LiC8YXr|`AS1UsQD_}ym5Do>ZE8^Ga7N}H%PyYQ zCE91*H6rAR!gu|LbUeCs043Hs2WmSdJylva?w*U+_ktMOnqV2ZVkL{K8JLC~ ziB%L|batWjZ+Fs>p*vl6!hNxNw5n&8&o-6L0IvqD2D7c<=({frBp|eujP+MN<%C)n zOMY)Y9Y#XZN7|EF+;bO@_16I+QrW!^MiD9eY=B4P1|fu>Gd`6He5d0{?@>){@Xi#Y zN}gwEm(5vD!Q>rN9fgbC{dB$s(;Gh}E2g7zYHLzQmX8d$Uf;0mT2Uuy$ncuv8i``0 zXIh`p^UVO{vC`l20V+8~`=t0r;llc?bQ4Nqb~Fc00z8oisJn!j#A7ggg?G%0ib*J_ z4=x~SB11oQo_Te4Ow-10y-Hmt4AVrd^pU?A7z%loCrA$%FYE=tnRFl!vlGXY9wPWyB64*wT8_PAqA@c%j~E&LFbXdwQdYdWKv@s>I7rV7qh9N&sTaYv!LMe zVZL}vp02t-MY_~QkVvdp#A}9zrxX5(uLkv>t}Jz&5`=7DiVtkpt7yWEzDh*q(i&w4 zd3TXf#50kPntjIh((#K&p|txV51J9}Tt60I9|fKGOX{o~HUQRl z&1Ss+<)`r1Cb@ENJj)YHk);RK-&gE?2S)ihvQ~<-K~CG8SwvUv?*4)u3Ao9HM69fQ zC^%m|#>+EbAd=a>3xl;T6iM&l%a>&D?QuM-IZd(B%Ta{!{DM+GVMIGiRjZ@T>zxaMc{_@gUu>8$l^rfOi2Nq(u3rm+Nw#0U%fiDcCs28 zkp|wasYZ-=&-se%4)OR_)#gctkik=0srtj8uYhTk|jO{!ST~5CWQL76`dBPpC8(2hoB@z?E6uq}3f?O9X*U&;O?O4K*vPTjQ-Cv`8XjR4?FNnobC%Pm=Z1x#~H%_WmhM z>md|j4gP$Bz!P>@AZaKQ%*D;G;*s7fa{9l}L>WmHYF;0%G<1%xqeq?p-9nRIVEMr}@AD=XABi<~bkp#k@S_mif!NeO5g zinNB3k}^o)mOj0qumCpq`zBYo&eABnMIwQ|Bzi3e2XqE~AE;PAkQTvh|C8TPIrdC0 z@&nFl&&6em=Y0Q|`h#TMX8`cACLu>mnt1{b^tAJvBa`NK%w?g()-l2W_iwr! zqGylA^TlIFj019)P1X&lA+q&H*}&)_BDwmC2_g-^#1CDeGhb=`%OIY$7Vz`Gn<^ef zsI2tyj)WT%+j5}DRA>p@-S4*rPmN<1xP~dbfr*VrMmz5tx#uJu*87+f^%f1ax&Is+ zerKZ5B2PJipp)B4BqNy(`DvO=G2Xh|pQ>&eQE%GIzwX5mLbgALZTm)`g%xq@i8tcN zNR{o8%-W^Gh@%iAuWn#frN4awX9f5|AIf-2Og-K@vHCH)j`$O!7}e-_xa4Z=X3%GW*IlM{fb;dL1~tB@6BWCKF0nJ$);Lou-#n2htEsvd?d-i|e$ zHEbY0P7ABZTl~YgDAUc}KD-SfxbHD$`T{|VDZ?xFvVMs!g(WcE2Xz!cvtS+Qk%)E2 zs#!v`i*+})dtJDOLG02kdZ%`=x%(ma$t(5AZa0fNon>x0@SLGj6RLzhA$%ifu$6Ll z9=N`D7334+{ZLKKukf%K9J%Brbs0D3*%E+t|fp2e` zT#q{8MPvYFD&ImcyBf{FjpIRk0ZL|4mv22F+ZIpQqS`YLTLRCXmsK*QlGKbyQ2Yx4uKc~Y9SbKkH*i@^Unq~fryfCb8dSxKk%O6{nwsHSt^lNsw%Od zP@f^*tEAiS?*9Xnh)^>37qF&r$uefoNbG}wxbPtKpjgb?zCmSaYd4T(x`FIMQ-#pAYCQ3(wDkY zTFe^Z8!#MM!u{R6_ongsVP(jz>8r-=TSN3t%e=)*y2=j2J;{kvC>IuYXX|eZb`OHD zC=V>?-(+I_@i)PO4E=FCo|{t|HBFyypRWE>HxB<%aD?{KwkX`}eHd$<2x9P>G;+U2 z`EHng&&%9se}ErXqXE%L5=qjsFpV|MA7=+*$oJ;IEsWQKoM4>pebu2ZSB7L*X9I%h zgtfj}<7;7LQw!sKT|Z@uj+TuvO#TjRU3#NTDWns^j25H5$a`NARma8lgXR?EU^UGC z&6(jOeo{)Aj-0rfM0?S-kV2{Q+Q-sI-p~7JKvyT79Od9(!xi^q@pZt@_@5{3eGpGg*X%w=)dPI_fvDeK=(+4eUT|0fY zMxQ8&-X104=YCXjrchU~`#~IN6?oa=6Ed{6 zI8f~YCgS{h6jW)HLP#pZAm`9^967u|Y$!ZBO%t7)j4Yf0#h;NhaBw2I1mz8$)qpq` zK-hXxTsyoJp;_996Sh<7!qhNUsa*dh8lY;hsS%zH3K~ zJ=Whg=80ts8?FZch@=n$?=kjL?gxKdV&*355ca5+-0J6+l*`{W1hWx_yeO}t!3TlzxlkLoDWP7 zTw%~U;bf)yEfM%1cuAQAvl!#?3blP>V7yvgag$gDA>x)W(T-+D8BbiIr9HTs^U zTVUF3iTbVP!Po1yo3II7j<1v&8gMM%w+{l!Bm>WL?9!b;vdw>)-Oa)J@0-3+NgxCu zSzx#15iU&puH@DUT5}qje_a~gkzE>w=-#;>WT5|>ri!7eQ!ZKx^S z?k$tN>aaHvibW8wPAvfr!(#n-u3+uYn4Py(ua{#HUv3`VQSaH0%`Wx2f<;DTUNH4Tk*Nrr%{ZL%UnIyvhE_(; zFx2a^4XQDJ?$d{b@o6i^QBmEh%Z8uQh*ClQcb0k79ExGA;<%WayI*vi#tfT<|Y2YIr(xW7elZvts4a3x# zGu=doACN%g;)?_rM8yszm0X%=u=|D||Dx`RhBI zrr%h{?PJN=I~zH8hKHv2te2VX24`%R_0vc4RA2ZJv{w~lTt1={dsoTF8BDRb&H4Cd z=~6W8cX-5dVhYie8)DUm!rAJO=?bFfG_jD&IWb>mcHW80nf=ROvl-twDf8b^WPXjN zl%$s~uz87;2wUsy65{h76~3yTIwEV|+Vv~6#|@s{Rb-YPeDl0p5wxk~ z2~*UfO0i00Gq%0n`nR$1X}Dn5=Fsixw55#QwAmvOe1$X%DW;|T9~k|Arw2nWVndvq zNpggzGGy&(Wb35B(;j8{(~|EOoDtdR zRs2AmH~#4Ki=n#Sc&dK=d~=G}*f?tGET$OVHBInQi5x~dnTCBP^ze6K5ed17M1e19 zK^^Yv@%QK!{i+dIwx|$GVrzf`NETa&kwfeOKWi$*ex^Tu*4{`&G2~5N6p2jV?i2A0w(B|Luub(?e6%sR7bvDz_ddoI{jRgEIViLtnMMEVFAXp6m zijCm10OTPz*h!f1*0P`Noi(93(Rw*zP=P-^5kz39#m@__;m4 zRP_Ozd|$fK4rAxZ!yYF!5VMYfdkN+;dx|rI{NFxavv97XL&1_Sz{!F*!BV-UlAp=N zwZQ7x8d%E&uV(+$M{`%y2eM$N00NUx0_HSDHR=Js+s&Eh|2a_lr}cm<&xYF~HQZOL zE0z5Tb9aXQn+GmQ&e~Z*i%})b+e zc;yUP*UsX?PjZ&hj&@b6$kTYn$+f#o{&q3Ug2x~UL=~`^?0c1Re*5%a0PV}EFI}Y_ z!NVB&cKLHN()*3f(77YscK;R}p+DLzRJU)WPHvXyoe$x`$vH^3>Mgg)H97pJQ{OD1 zK8yZvYb3ElXLPF@RpTI2f8p2$zb)KWR~0g7^9rrUk-Afz?m8Fgn#}cQs7&~}>b=p{W9-nVFfQ!K6&37zwz28FHj*{?Q7p*&O30uQb0nAeXDl7cHN{Rtu&rm|%7ESPUCJN%-Ptq57?(-KkRlvTgkeBJC6%seHx z6(S+cYMQ4@pr_%~YyA%BNX(z~&ja%;Hs?up1l502`~-@hiE-}4EJpk*Apw{To)Z2s zHnitZN9n^K#-k=@>5v3iEAYPRraZ<_$YoRcU>a(j5ESN;%%v z@M)R#HR6dPe=Am*9KOx>y%z?;*gbkUIl-$4U z0-VOnxd6XAdqK%R6TqkzA;fVVV#j@JSoHXRaUoRNcTR7kx%y?7#6l-O^Idg#GEdI) zM6mc?w_?1p-id_FIV(CGqGK1ksSBAq9A5m3>>A!X@6?!aFay*257Hj>Otb;UWQcb< zr3l7vN$u96YUXAJzT11(@J1T(O`c~TRLmju-x9OsG&a)^WKeAKmT$t!Y18aT7%^~l z>34t2HyTr1ZL&q!oz9Qqwq@YIXVn+||JR6rHtAyq=6va)s$n~17gAZyO0rj?__BIw zJ0jw--pK=YZ%SZg3@f?h*I)3?dFA^5Q&qWpOwBPn=vrezGEce4Ht*x}4LnA3_Y}Tu zcjR8>_ONTrFyENg-H(_)pU*2tP0_FHIICGY94_rNj=aI~eki7To{bzUmFV~UMpMh% zlX})M5lP@vIPq$8JEf+He?o6t^k^D6Y8{t(edvn5W%2v%jPEF4Q>j9(g@9v%k{INk zJ=At6@cxg>S~rqu{EBNXZ>q5=_2ZVC4fP?dGV>-wQMN@b=u*1Zb^PXCjC^7X@k0?I z?iKB!2JZ4NO_M%kR-=#HqI$J;q_4|_sNg*#2OCX?`NmTLbC*8Rm*ndqet`P|GX5e} zai=j20Z=1Mjnc7x1HGB|5(OQ;s?D1^|F2cpb}rz1z|*RG-n$k4X7+bKtJ(bc2AJ!Z zsAE4(t}uJ@uoq8fC{i<}`?0Zl^h9T4kU_q^1Xrqx-j}K`{~oLK-YJ!-=bRsfTy5R2 zUWbJ8ZzQlNnF?Vv^{f-$#O<)I{yYdb!wvooVczQKr0V%)?CZVZ+MMkbwu=(InbP95 z-?`p+kBWnt{LltVAI_50nke_-a`{}({&9?>MsS{IQ=*q6>L5Zbn?}wRJ6Fhm5$;H> zkskI}r`KPAOlh1#zx^P;iypCrgMWc18k}I>wG0S-MYKDH*^M8J1sysce)cM;9WCL@ zJ?=7DADKgl4DbWiUe0U4ss8?vztodPfYZUqIt*q1>}xG)8L z?n^(=ysT{RE$nvDy?ZRVdTxGB@5_qkr)Q?tcXi%tBKNz2L>0Of+B;?3G1uB>(JHB2 zz6E-3Oy8w)>HR=HUlORx*UqQ*{$=8wb_w#u|DJ4ex{mr`Hw1LL0yAXc$M$Gq5ZDWgULP(WXB)zi z>``u*N!-YuM6KWC!Kw9qL=PY+?QbFE($1f|lj!?=U_8UxiEW0HFxv~_9wDe zVm>-Yt5&TN2M6}mw>rhF1|ro!Xy~S!v?aG~lz_N%hr;u*>wvMda7@*@sm0 z8?syTd_}M*^jj`lJk>MR z$l^r_Rf+iU_5lTy4H@rLh#mB!gNpHpIc+FgE+;~#Lfq?FCwBZ#7HjX`z)Q47JX#I$ zZ&fJq5CNC%{PxYz zM>2>E33_Fn<3!d`#_ZG4I9gy)?~Vu4`xjUZI95!*Ty?6xXYs-fsgp;<%N73vH>9j>rRe?>CbKq-bvhaz(!4A>$G_C8^o8a-II3aykulEeC;{$dqqQmnxR@~6b z)`eiXi98_^4H7Xo57mumIyRBCME%oNE!Fcvg5FjM%7ZX-!Q>6-Ph(WMTt2Ki#RydS zlEf-%w)t`jK#Q<@UB5n_$708Fqc{;ErJD1#AF*It|Fp5#q0j^bgZjH{X^2>>S9yHr zx_9a7{8GjYs@=4Nf9y>B2#od`2vf9Xmd_Mep0{ZnJ7LYpCk5aLf+z75O{{#5Fv4;P zV*O~augG-{Dwt{%K1t^^N(*Jc`qP3Xur)i#DrQvaB58^^m=b z9GHnkA4?L@A>Du6qMa;bTp*Ws!!iS`HPFXpfN*hC4t?^yXHL2lt?PJWUiK#JZ*k#A zIln^EPfOO#sSIeIYHmK&miV+YED&aVYe`v31#=K)VL6AUbu3VMXoe|Ndd}$8KV6&$ z+^5=GVid{a#HiLef?O^v^d>+tdR_^h4}~La`}(Z*tq{8%zQCx%+eT6kNzu4L5gk|{ z6qRB9DoER|?$fJA{f{=3zm=ElEf)A|C_FfRG}1T0;9U?md5X2-Pc;r+!X{%B3A zpGz^kSX^IYu?ohapfuXxz__f2vB7`9!^9M$!`8*g!@QbcEi^A`x$U_+u0sCTI!Zc< z`LT>2;KUW)XlndziW~O~x1I(trSUULLWlt>G|Sxi@k7@mM|WrzhH8RHBA=mJ*nnmI zmy@}4FHSXTaIbaN%Q69XX$=%CG2cIQHjDCD4#PWvN95gk6Rcwv*#J-xh13vcAxUJn z!EnamjHZImPYyxAi)};0mt|MSk2KT?Hb-36%r6EYVDaJ)=tWMSnWF+TtuN3*&P*){ ztdXMusEdHT1ODX9TX|gm-hDK=UyXSWds=><)6fs#|HWYP!M9`i=O|6ZUi#^cveZ0 z3`*S;-{-IzMoE00k>FC>+FZ^Z(Xs=ybWZs`3OqGu$@`s48k5}BDLpz7OUhXB|Up5GY>YXmG#@ZYd zlxTM6E<(n7z6}LuoUqsRcc9E{ zv&+soc)U6NZH(02EIuoCK$y7`0!=ji1{Zi#4>4_U9mQ)E9Jou~J9 zFE@-K+snE;A3s64@Pf@&dk_zRn#9cZf^lJm+{@-DnyQa;)Ex`(GHu9D%TuaIEUSNC zyD#;F{F~gn@aryvBAk^yECR!;qc&>wQ6*OVG^2zO6us*qEk8r5Z(BB`?jUJfpVPAZ z+j?6@BC7fAJzZxgVP(FTfW)DHJg1zeoEvozr6`2Muy{vF-VncCP2k*PAQ^NB#4z%z zqk+oBdoFaAmZD~yWiz1N?S;escho=aeV6x*%N-@oA|7l}MFAF8YrJ$T2=HC|^~Z15 zW!L9)cTE?9nPR~cYdUl|9*y@#9{+BC=d6V&r@qK~cn7Bn?wK2df& zUyB?d{ru%-2$RUi>uF~#G)t;+b(722ZSgVxM-JITeD4GrGFIacYYXC?n}4VGfo{f` zZ58VQ1bTtEFX)RKrRh#AYU;5n0un-7Um_u>Y0?fC7Q)a`Cbz7LdEa01!zE&C(6nfd zJBY^z#T_aXC+4Ww|LsfctjR%<`^a#>eX z7NtVKf{J+9jtF4Nb#jSBv{sQxQ7A=OUjJuwB`D?V5i11PLqMK`_=Q?__B%OOh9G(swhxvAJ&8R0xVY8+n%6QfItLkpJr*sm+raiS*a$9Hhg zt^eid0iRI>G0ow&hFs0|opHKI?0PJ@%T%oaw-NRmWv`bvYzCIk@XND0+d9j6WBDYPr}(p>XQQ2Oug<(f3C%c7nrGI zBD_RG@)~-C2qheuN^M{nS<+>_P1Zw4VV%t;1*eq3CwsM_z2R3 zvauUML5AHEi9G&UdaR2_U^g?uRUovX7K+73o?bB%qb1O}hIaS~agbUW z5QdX(WZt=x?}oiWJUP7Bv1b)!YEUT*Ft6RYU^&JZAb~qrq8GQB|mkXp!Zc{opeXb4K${@|wmrdIr?TJpK79Ft^kqg>$Jq=}3&B#5cVlT zU%c`-lUZ|0O8kYzS9SdG4Vp!~X<(&2Fs#4n8Wn7>}=buDW z8t2)Dh3Sh{v$`pWvq!#mfvHt5Dm~qdo-86VArm!~0W{#HlKs}b*b7BOY6Bis$_~ir z0Y%D>1s`I-YHb-R(@C?1HXWB;WMEvM}vVTmNLU zkiCQoDNTLD*^UHL4HmN;X%>)j`*67~(z~;e!+ML$s%BGF<44nb?@n)2EHO<8J~`Ve zA5v%Hqu{-^0eXY;d9;(L@#KGSuxY*XjO`;AcTwb3RFoqbC9}r8$dDv-YAyIfch~ag z!||EF=En9P5v-Ud)pUGclu#C(e5>qBNuwX>S1DhnsDf)UOPtM=J^sS@qi0-5HUgUw zN{|H~7e4G#R3RG}s?Iy>pE&5^ayH1}ISEEldy@9jGmbtMD&lx)_rjM}m2;-*9%#0I z3%ciQ2q&F|h@^;CQ9bmHTN?tatQa)L728PWSYLhrRyd8!wy-)2xoz9&k;!! zCU(*4tcXHl#X%+(E=(f{gZ=F~m4;a~vNWAG(=yxt^8%1$#iDK;MrE?Bh{Ez(9AG5} zwQMwYy74@Q+ncHBR5SRQ+e;*>@-Y|lEfu_RA9jFkEd6_zdaoH3S0APSe3*Jvw^Sv} zXXN^ezZW|D?{Mx;Zv+xRai5P>%yka*SQK?7Yq%l&O$PXkDwF|zj}s~r0g;Y!RN$g4 zSBAZO?+)7~e#~^2<{#ebLBorX+{VwU6|B^nfz5r2a$LG6J#7hhj5IGhaC|18sQwG@ z`tw9At;DuMmZe}y&pO<@AWn$tmtTWc$5!-(=1Gs3c`WhAl!Hk!wJuKA1c1Dbm^%Iw zMiEU&)?K8#9LHK0O&3w6>?bW@t=<#Q9o)$nq3gbsM^sW;Ym|?dK|mZ96^U`)&oT7e zS%CJblxujmF%_qmXEn)cV{NJxF<~Yt?|E?Szp*nr6jhiCY&2cCeS$*m(!$YNDj#nI zpiFRObD`&D^@5f2g+7{ILKUymcji%Q;W!hbYuKy(o9m-bIz>)U%}hM}viW`xp(k)p zd^{;N;(4?J#gS1y^Ce?T&mYVvjO7{T-vo4YjHt^vs(u5tHm6mu8Itzk_x@Z|KR@OP zUSdorRnJc%OjBuI|4?a418_N6#AZLd^WFP{2Y4OdlOq1ri zgY_c#P5$8-#mQBUDRfG-VNWNB=xBZiq(`u>%UVK$0;{TV{36-Cc=2 zO9ZPgwWUXBpC0CrA4dtrkACu9ggNFD^`w)*{MnS~lD9qW{W#j)Ez@dP2qUclvQNWT z*1SK9HE`Z&1c`cX)Ii6xDE$*urW-u87xSg-h66YMD^qgmMbYlz+D$x5k#kw5p zFB1{R_B3Eoq&#PgRmRr|t>KC@6H@Cu*P(HrTab@)wsj$K5%Q#uP>Vmn$bzj`bzYjf z!l~gS7biM)bYzkgEJIfCJwNEwY_`Ef+-ifls0qAfjQPz64UKc|G%}k5se51V;a1vu zG=xHL_iD>ZSKa?Guu76%*gQPSe|ll<>&=Jz<|Wnxspj*kaSaEt3j`~v3_&o~sjc8K z0dMHeYRl4cV9JTgv@4cyx-YP%FP;lu3Cu7MkJ_(bHfF&#h#gC2=#3vInM`pxHQLcM zR~zK!ByblPN;*NIPNS+=dy-2I!vN<6jsJ!@l%#)H`(sKYRexV{+c>>(nJC`WB$O>7 z+yb?7b!kx-*_!+AI^dttW99y;ythE4sjyAcK~O&b@zVl5V}a(>8g> zX9qjbBH7o<&HBf}-bv%DN1jB@+4#AKotH0`QR6N+WWu|fdaI?2cbk<3SChr{Ft#<;t@9wPe((GBV>CQh3N= z^f~)a&Z=AjB&a$ST7TI*w2e?3FxB-3ysuZSbSAF-PLL!PB2-c05fYv4$c1rfRlN>K;Z{{j=MW&XkPt1c?ko09?^u7Q zYKFTLP{FO?NPoZ4xpc^TAocwm39s9^;$)rB#XHRdu7AQE&m=c*$z)8S6Yo;ny?jbe%~WzVk!YE(Q6=8_|4_4T%5R0a zk_v8HE%X2J$Nv$^C5}TOKi&)Wz=NRm7LkB~g4k)<*5#_hi=UP}O0_3aGADzMoa{o*;$D+U?6E z(E-_VK}`}?EeH_5m~Y8C@-<5cu!sZG=E4#}VRx+SKa++#pol=to|Tn)p{#g_j&RBB z_b7{qK{rbmrfX&LuZL5TiK0FeuM^3orc7I^Q+v~=?~~;SQgBn0vZ00;#XU(=py~pU|`QLZTbi0uCY&!|4*i9{U2BF87fI}sQ;>|#MPm?&v1;pWxLD-n{F1Ai0 zl&^X_+xYH1Y?I?!9JbzHd|tt+EZ@j(_q8Ad6H5YSVb%(?ZV3mY>TuXZjBG)A%d&$; zCYMZ>sYt`cDgGr}KuR}8kI#ERgyszImV!$+Yfx4qoA-Ro)KCNkO3A7$B+yI4E3l{S zRFOy*2X?We`rd){{68My=ZFRxBWfuI<9y4QbYQ`1_e{(ba*OngT0>_L*i^b&c1o$f zPB$CgM`>$5%VsnjS@sim7z){E?D{y?xL_s40k_5PH4%GUZKyJ;_U94Hq$WF((0IP0 zbv<*jUhwT+jYa@Yqk>u%$_xabt{MJl{u)X2vaV#Gtb|mH?OwKDOvlt?C(}wMq3Pv; z5Eth-f&bgw4BE87)O2W~o8Bb`_1OODvXWKk9|rvmsm;xKm(PPQa~~His3+3@e(RkPZ<*Z6L(d(qzlCaDT$3Fz2ktORw(kqkPPJc#_ugNB>vQZS2}t(+3m9 z^w%$Gsn;7sX97l@lDYv%nJc`P5qUxg`g<0Dd?1I(IN*Sm!u0fKVC~~z)wZOe z`mf_TLP!d{^z(9tSfyZ)GK}aW;vE5p`HvZ|MbEsSQ_La;aD{->gKrHAbrpD4y!gUa z^K`^>acD_gb&?RSfL-s~JNt+kAlq2K2Igio+@E}i=gbFNl0<;v1O~1@p%?L<5(&-G z1LhRAmg;SCS;(DU?lgUL5x#MQxPSFbRfw+t^f#>+7NL{9{>re34!acn@$8ij6!)6b zTT>S;#fS$EZOS0e+XJe87%;WtM2&BzIM6fSOu~ak4t>P5P0a5`r<>$zcEu&towdev zWl^&giU&d!2lSD(w!Poi1pIZaP_cqDsbhh}x{+w}f!5-zHyxHu_1RWxQW1>jtHVQM zy51x-cB;SA8|ZK{e>=or?=gJOkn`DYe39hXeIBPm)B-bF zdTeq9^K4-TORBlmFK1HA`*yPutEMNgW#Jqyc;9f~f$~t~1b+0s_I7rK>vC$;S+E%^UUyMPgtzDKqDp7HcG`ejz*IFq zqebjzuXX0fOCJBG~DXA<_s-iS`S zLJZxpcmW9>nmj>ovC2W^v3%>?hWcY^FMszHIvCeCreBIB>50Y8{R``B+?5W0^#`Wj zg2w#}?(^i%`Y zBz#u$FDj|jPU_zPGjphR_)eG{z2i>09FnOx_(2h>34KNI1l}0Bc56xT9rDtAjvubg zL3&G^pJFfIpGKF&B@&1%riTq_``d&71s&)-$Xq@O$$W1ewcZ-(og24=j7 zP_mJ9+VCJBl7sUNAhXT6?`)ydTEWl(`=5kF%lCe->JP%ZVp{EyB*XPP^Dv~o5`)pT z0-3YuU_fBfvEX{>p4vw7D+kxp-~7H6X*D~pxdxF^6m8`T*jANU=Usb5fv8! zcc*re2`YD0nU#R<*Gi{0?N9VWVk}~ApRFT{Ueiqo<}&;ie{yzj+D4vA3=Zn*r`Ovp zTp)Gg@oK=iQs<-C+=>09Y2WZoF`Ij3lu-67Sz~UxrE`vC^N+H*zfSc1_kEX{5n*UV zw$P*NRj07-)lK7Szc781SM<^rP(JtxG2?!xU21!W4-(Vw2tLIOU?IGZt|N$!R_vbZ z#^qk|A9a}5f;Odk+&cU&QqY2LSdkO*Oit?Ge+)cfCg5$PX0{iL`n>F1s3eD4i>nBV zWycb;!p}n$EH>E;C~f~cNTZPsPM>6%_xSUVSbv}xgM(MVk@{=>n7qFAnN<(n+>ae* zyD5{hPD&(y++l@Mi{-X)Ioi-mo45_67i9Sy&wL(iy#GB`6n-JDBCCsIL)ru<;9Dva z&NrdkG2YMMcX26cfg-8nrY|4hDl^IVGhvsU{a|}BJBR|i#ZPcF5DF9oCggtL15~{S za_2@di1#l|WP;hRomETdcE0tpg^sIdfJp{zI7%fVMz~a)BveIcRI8iB`xboenJ)*k zdvPIuEXB4SvD6@ClJ`tF#MOl)mEiA^d{I5{fF1+;I&{mUh+5K&1Q7jc=0!SKE5km} zDtB*ID4SEysk8As{EFIT@z>aD`>M5(7SiP)Gq>fTGu%2dpca`$ENZ!o?wE7rJTOF( zLVAOh;BF;pwUH${bNhEIJ+Di*aZ}p1sA!qhGpqO4l}m$0)ph!R&~^R)9p>se`Tn=f z<_ydJ`fZpyoo9QY1kS~sy-SPg--r?HkGD+7ygd)OaaQz@Tgmts8#s$%hr4Ts>eQ$T z`yD~ctH9wxVk4e7#RaI8-v-(JIVt;SRhuf|m`9LpOun4~G_T>T^@mjqx;aObjW;;p z8~a9Nd6e&~Kk_jO?%b3)*q zdZH^`e_{cqL46Xz@`L088htu6qDxSI8+~l`csD)E5tsNSGX*CHHYlRaLC9IWfuiWo z?qoAf|93%Rmd7?QjfH068Y(MTfE-mg0W7Zu0$ONB(3s8WmxNQ_UnLdqC>qpN8O$$SgV*?D8qlF;Id4CM~BzO_Sp z^50vwrxc6z$J{i6mnUojCs>jdMQfz+9==f5{yqr4j}b8X?>O>-%VosU8|23Jlf86k zMDvW?X%K<3vzk|K}J>??}}PEeHJrg=iU~gQiuavkFJ@ zBf@vUQjltu^9JOjZZn8qQsIz$ND+hehMesyO7l`3M93UCB z1y~WGQSHl`O{79^#RghS(5>|Z)|oiia{H0(KS079e=hm1fJbvL8}ahqt>Pu3irVhi zVP^JX6H?n2niC<99;xErtQ!)ZmTA?cwANB$_*wlR=Jc*7cpQ_z5P>)z2@~hobh`N)$N#{Y6zhoFYv8}sC+QjhopSs&Nr%D@0(K*K|;17 z3MZJwHkgVx`e2c$B1dEBwD{?;5~u5@VgED<`6 zlQoHSh-R?X=gB&%DepuK0xkqmoRwpRe}D#XOQ|8BG(r20VetHo#M;>!oE zcf|Rr6MrD@&&FkyRb=&WQv~4WJCjbcXwCb`nI;3YA1@Xo32?j zhG$JpXo=Gx3iWYSKcVMVp;)>=boc5DPVXabKH1v_EJ9UeDd+osnGGp4o5D zGhyUJs@&};rW>UWxP4l|7X0A3oUvZ;ThK544)F{zAGrP2^~&?dt9>70UcT~Tny^Q; z!LhwRxg>VSzHR&;z_0r5&$QuxXRDc?GaKHYGedPPwL5?2C-y8GeR_j2Y%qGx%*3*M zaU|x_;0nq+U=^Dj`o=+qK5WveM9)j_7A7!0?$<^iEtq;4sDD}D7-ts^dw5mL%20sy zBoe4&#qQE``dhW4V)%>^vObew>Je{-A4BEbf%|W(t5QvQ-!*qU-J`L_>+iXa*dV-_ zoP?6VNnRzpWPHD8N0Fh&#f7-R@B0C^LI)WqC6dQdWnz`(%GlvR&dE{U216&z9MbWY{+AV|PLHou*Eb$7>iG{${C~NM$0|7NNqdM9gP>to zqi2La?=byuM66pmVeG@XP99u}-znc}d1r4BtTEkpcDxS_+FKg&1y931d3dE;}= z%Tg*n7xB&w9n@iiA3ku>lGDu|lKrAfS|ZKN#MucK%`@3f59`!;=EeE*0D)+~D_H>1 zQqt)$$vPCtb4Bx3qT{_!|C~-O^P5nlb^NffO$SaXJ+#gI_itVYMV?!yvY(R(IN~li zM0rVT<&H_ppblOWAF(F6JSF@5JsmBRwy4}lMTdx@5VuR~n!iYl(Vv*JD)AhXMw9lcxpRQAne+R6P3X_yYe{6jHT$$mcQU$SS;tg9)>iA;x7TwI7 zqkrNSRg@)vS69>Uf8D}H(&%Jq+oB}$nS}%hvN{6^ORhg~ubIM6)p%DCOavm&Xso&v zf~Q})0R@TH^IdqJQ8ELCu;wjhlHJSUWAl^^466&Ua6TcHs`~ABcq@O1$rU^|ID_ye z>U^c&&0McXYK*?~C@Rac*L4wz;AvL#-=*s3f~k#!_OK8GAVgcZ%f)7_TgII8jm&e~ zEsUuReHt^31!MdDE_=S@=F!Y|B!8H#;feuzU=Ea+&m5)e=Nj)L0STSf$fU2r76rj3 z*06Bc#pobWwDc{vbItCR5A|#v*|W}yQU{*YMIpk|RJZ~Mtc z_j}EZbNskRgC?FBvk63357h^B&2wnxI?LJaWX(Ph+2q3bG!+1;C zKt_;??=~JJ8R|R+zqVr}e~rnGKJ2As$pp^DUNDrMJP6B~zC;1ma8aNW2$6PqD2M~r z*-?zQ?=FCaT-zea#daEF@ZA8$!tb9bVy``Xei4Xt*@IQY;WhUsb8>g~XsbUcag_`M z?mL=hD7*f!ppuz3aFL7_C)Lz0k5Km99=nY4#fGcz<6%>>E@&iubLbiIw9TaF;@2pW zj$ySpvmZwjDQu$g^>|#45Pr%`J(JI(Agh|dJxMz&ujrE~vMo|A%o<+YTZ$q59~MAk z(;`~o^oNWBnG&kB)D^1}d{X$@;oehKVkq9HK&p34d7E|y7cY5#LqI+_HzA$}b(8QW zx;-e|v{O{FtA&vR-1}Vg2v;I&HB7~X5~bL*}WMQ z^N#I8bA}5ksB$PF^QoiZLo=r19=G*ZWLjcNQ5AL>cr`BTK)CfkcsiNB>EtZ%CYB1w zSd-XGpRRf-(sVJE%q}-4LW~ikYqA%EtC@zpC%JwCu!zvnRkjQNUM+Vu&L@B#qP0g*YZO{CgP4rN>SV9a8MZWQ^;QE9Kj+o+%2rN$W*UCCiRcO|u!Sa*an=@pK#g`5pOV}=6$a1iP z8FnGXv19b8)hgl>l=M}Q_IwmHQev@Ql64Oq8XcScjT4_={)xMKvz>R&CDPkgvHux; z)!tCgq?gd25)az-XCT3*8$fEp1Kx#Ckj6~JLqkH5SYeKTVdnA()a<*#d?MMX%q>Qu z!BWsX4pa2pYqP#1tR5a&v$_!wn+3YNO9Vwm!ovNF>josGd7mrLhRx(|Bj7CPYsuzj zljE07SKQzD%A@A;`? zw|I$h++GkiJ7xx_DN0L)830Zzbua~8^KXoBr5l=jWPRS&0KP+$K=MRCK zW>7r3s6-JYp0;|o?vrU4k8*9~Q7F6`01fant*;7kszFQ(oGu#D-384_Qu~h3Hc_nG zEC)(VcY(O=bPVlQcFNuq*~8B?db?xDuf)S|U+&4lcgNieJuNVqHen+`MShA|8v9uy znC5W-JQ}Uux4c`iDqW*#Iy?jadF$wGbCiKbYV&B%-)Y~zX^6fRUOIefE>LSYWbKJW z>QhDkS$w-C3E*rh>qT^8!70UGp+)8gX-Yoe z*eq48>SiOmZo?fL5(MHZASHvTBE*Do$DBpesXi3aU}=J|YF84)#kTpO843elU*I3( zOf0p3Wmvzgzd!4EM=Tm&bKsGsBa%bmEmQoJGb)e-nnV+$<5O4a zjL|pvFGJ}$_krz8Na^!)mQyxtj-A%YL;m#XZegh0QR+q{pXKE=Z4WZhXAMeE-51+z z`wt-!19nOe=7%x!bQ5Itqe+&75IX)S#;9HA4l7F$vH=45Yl)GpZuFmC2fzBThB`2>5!94sTmpmyL&YAfZy0e@mbqC#RM zE~*>zial@TZ!EzDC&*u5Mfx+T;-o9zi@1FS8)t@P6}7#S!kxjS5-@O8x z^xw+$e@oc^xj0PGPdiK6 zP3xkAqx^>eqG1k4mV~H?EKlb<_wIL*zDbydOoY)8N0w(iF{iQ%o=jq0QI4h z-Wa?eKX5AKq78=)@<+M#Qf7-&tP8BLYGh`_U8Z$fEki!gS1pXLiZ0mp$pl$9oa-oA zXbd?u0NvX&wY8YDTK0P%<%QHu#+=*Ce~tPx#e@~dSgK)&JL9I;s8%{;-t8&r(To)P- zPY=j)m@;l%r%Tx6Y`PDBVMVt$^+P)+0;3(^<1N9Kv zzxx{b74yxvVsvkP^{CrMK-}Tw9VY1A5a@s1_VcD4|`h zj0EA|Wm>IK5v$=wT}qboW6!+=16s+3d6O9g{~*LIMU-%S2O+B^_&mY`L3nT?e8|ev z^M9ZYdix``p>OW|=gj@_UieB%mP_zdg7^L!k>AL0Iku1N*|FAJr#5!u)?CTA z9r;Vasc|^g3GSSjlyv(Qyo1|!uf;d*(%g~wc2tjE!W1_*KT)Ulf36D>4QKW*Tn?iQ z?CsUSQ<}d|o%!b6Pbc~9kL;l0eA;(dbXj(xwUwjf5qrmsD$eJ)y+n94%ZoI&$IBGN z!nnl4ae!`<2bmpeu_Ml>11NNY_Fxpv?)TKvPkEw|2*l_^k(lTv$8~L>Fl#dmvW;p7 z9Fjwhcvt$TGE(o?dJ}kI=k%V=$cj=n#8ZI|k#p|4$mJN&Z2H%vVSHpe97Or^x5m5E zxr`5=gZB4ZtENToUJgD_{NO~dH^wq2sk=|l^j#kPf#sW`A%4M!qt{w8h%^Aj0`k+% zidfQud2z5%ObJkag2qy<;J%%Mk1oQZy_^f_5Ew12xjyL)=JDI%qe=%Bw4IZx|%iipHJ;Lu~N-!GLF zf1Foj=8ZMli<%+BnW0iYLOVes$wqWVYRy6ovUswc6~@PkmV?ikgRi3)J3Stw%%Y8! zb0P3U0x97HWCOvmng~Y(l79I3XghH`Y_g5%+;SrX=LA*44!(IPh{gUq35t$848Z$r z^)&g)aikV@#A`$N;=r2XB-Zdb^&vNZ#}A)>37)b*joBEKXtk3xdL6vy$tb=C<_#lI z`2k^e@a+OCxBl6w2~C{>JU06D8C*rYj|Pa{7@omg$c{R|>qXp{uw zD-~{L%6B>!d_!P2C_t~29jMxV)EdzY@2$GSpu7%Y^CHGbX=W_AQ&`isb^@3JWfJ*c@yv@-4-^ob|BLp$V#7$H`u0@etC}mdTF56|-naLeH zUHn|srAu5;Xu4(EoJR;oeUZYqBkB6S(c|CArZY;bWLHtRatuO+;^(D2*DTVkPPMDZ zCFct<9jU5I8gxoUV@a9apK2ntr%IP5H?dkZ=^7=`(6{yFejW>mkb`5BZ!5=3pVf~Q0P%k3!dW9pgiux!CjV+8vs z^)bo_jvQtXFISM|^DjK_-KMr~m#KIiYDEJd7w!H#hd!weQ)w zJE7T3_Eo>Htibh2?4ZhkeebJG9Z=+XfxRG(^l3Gm^xY7BuKVUVvzp=yyYE+0Pe~@< z-w1e|_RPU~`C{|DG`r3JwX#ojJ!JeL-v5+4h}%%}u)_}hauS;V_Tk06)nL}kHhE;k z4&ZEi{C&o}-xbo`|0lXliag*lH;5oWt1Cq^*Uo--Lq%8-*Meh}2$tH#qb3nGQYUG( zMI@To+99zh(+q9dT$t$jvun<8Znwqq(>3_oiS-~58r*De-(Iu2+wDsUeXHP>_Ww?b z0Sm2i6)!rHhXx?7u{AhtmAz*=>vcNQ9mApCzOh?V+&M$E55?8J1P5@-0vA6^mTTc> z9ee@ObZWetR$wO+a5gUwp0~_E;!exN82;d0Fv)mooGAp-GrzYFuD^15F4*g7`!tx{ zHT$Q-uj@=Lbfg#&dkLFl$^>~)KRJ1b%(S^rjl^WSqgvwYl6R+I?Fq(mLbbEu?Y@uV zvD0cEBG$W_oCJOhv`B;VAIjMuOU^tVfE9JZ2Ga8#Q!!>vhF!H$J{1BHn>bqm%fsBr z`O`v@-P4!Rn@)z;eZ z77Rv{CITQ+a{-6Q(KuuhOi(+O>6Cc&N75@J$wdEQjZm%8EN=Bu&N2`$#~%O`8GetI zjN`pV^}yt};zQ`gk-p=UN5%bdKDShcR@Y6zm{$KGeKrpR8 ze3XUc%w7O6_zWQINzr`;KXvzht$Z}W7e9?cADBk5lt59fl1SQM3G==8fDVN9Vhs-{ z=I{t0!-5*A#44#`P(vwVyKZ~lpJ;P`&LJ0c`dzMDtdx+iE{M0Jl<>cw|DTJFh)Tn6 zL6^%?MpQAWihHd_{4_`vf2EQ6WxMpiODbLSgQ~D>IekND5qo{P-d3KdhCRnle;m08 zUnCm)cWp9sXi^w)ddeZ^Vi;busyAjwC}T&F_9Vg_f?gpNJqaS8AJ%t>15@5f3Q8-= zuGI%b9QKOorTK@PH%XU;M?Z}*Og63(g!k8aN#+=k^}*?=igBw-3W6Mx`3EHuGzknr z_n{0gocyNu89i_Fv@-}Ve9TgH4$4W$Vu*0nK(KspDbpnqAPA!&#-pY`e#*Cka-$K< zl3-M5CMWsNBwzC*8@u5Bkz}kO2+qtjb&lTz9-~r5wzt#*PK}Z=5)e;-G2EeGL=KE$ zox@RTjTnPM7lG)Q09osw^t!x};m&)M@;^UxAT5;@jBW$Gqd|1KxveI!qqL50CD_V`K zCrbujdT*=YO8N;BlL7c2>n1;hQaF#6c5}xD%9cz!2?*fN0#aZ0T$Ha_vM!vFr2GzI zdhRxamw7&%`bg4znyK;mfzY0Do-8g^D!g`u67cNVdgP>!;Zqx0N7-iaW@{Jqm9FP< zA`VoUiO7bs)nQdAJew^`ppnIh1jW z2&}K5h2q;3lk1>N-Tn0bL_kJuMLPdA@xTnXvT<<_+30d1=IbzfIZ+RG!wiPVg_?i# zmxB^WuYm6#$hI!!%-_FKUANVo1{6qly`5jLYUP!0_;Zr)UJh$o0zHh|VDE``*#It^ z^qj4dsMjK>cTj3#Ilf^+%?JMv9ctnvZ7Jcg2STgp${f5XfP7jU{7v$&s8kdVD?K>5-KL6YE^wg)^e>uMHxZ)TAsPK3uG-5lbwj zM%nDC8li=CnaDw!ChyX%{_QWj=mwbwar^3ech(8~sh9bdk|Hxhn;kQLP!$1HHFrke zsb^zQFJu^a0v6}v3I4Wu6g5T^uf^zKE?Udq440Q84IR;^{{s*`RwD}nv?~%xeha|@ zaW9Xg{%bQ`xHCeu|6bCBHTvs}3dpIWdt%5f6UM4bsHm_YL$VDtp&#bHl_H77nAuHc z^hg17ra|+M8pARN$ff>8pAKTgL_ToKYh;e@@~*Ra9W0(x13hKMYnGaR{jsuCaLV)* zov*9lC{E}S4i$TU6KH*%l_qsh98)La9I^^}?|&bJv~gFp$J=z%lo1M;7^Snb;~b5N zQy{d5BRa_Ll1X1_ub3qwPR1Th!8$wyKL5P@K^rz`=y#`$9BhD$ZT15dqPKGHm%m|C@Y_JwA%S5v}pw-hKyD zN>_U;n=hh{B`1aH$BhE(Ha%fnNI+GU)mS5y)$eB)57`MoTl20yl_Ap9w|KEL2SX7}Ft6l%`FIp&twM{+^0M(c`vZ~fl6??{$%{^u=;+|D&~X&0 zX#V9iitRa0@B9=r%h7)dG#DH94pG5^SLDeL1>m=yOzoVhBC)j-ATomyvao{;NKx{| z--CEV8AuJh+GNb;YKjb z?cDcff$KB;NFy0c6pMEJJby+pgoK%wRn9M})LLnNaWI}DZ0Oc}7w!mLK?v%m#fD3= z4u+lq@9r|60`@e!h@$0B<(ei#x3ZoB^79%)PH*Dfnh5*c*8B`YsQ-4(w7R%pUl4!4 zZxsJ>5VXBDlKqoWUQ*~vP&k9@70DNvbbdw3YVp=-daeo>!8@CP{$g6QJ&$|ZaFBj( zdP+L}!q8PnBpeBGQwU6e98Cq~iBF{X^ldxN0~xG|MVKyP03ottWnBA>bmtH3!N=2} z#|($(me>%_nVMUgf?7bUWJ$xUy)sEwFC6dDhPfckbzvJ~f!>5j;;_QUvkP=WJ?ztXe$h(-k zCJ2acSZ(_;oMukF+NLE=JRy16Mp%PMT7hMV(a3$a-6jNa4VwiTLsa~Rwt zN}XJLG3#;} zs>Sp39WQ;o0fy=6)8WTQ^0f`^h9vWcF>Df4BFtJ@GoCZ{~$sNU- zZRvxM{n>1cK^HwI_WS4&Mfy4kc!YuFM6bI2eor!1<~zKl7hPkiPW~<`jEO3gBYXPlN1^;cDj{IIb~7a2AuGP^21jQ zFuY6i9))?zh-%&6nbN82D-TR>{CG!f2f_vw%hXZ-b5YB$eQJcn(I5JyhxNCbOqkvksi$%u=nIXE(~clg zcOD+W8{u;A!hCx%-f(c%{#>o}RU1{h$XSCjJrjqi?gg52;`Oyt^M7mFnP&1BXIQEG z|CF}>U-3(B_Pvq`%IS`;DiV#$k?TwB#(YT)SwgiJ}%RqL7%sqnkOwRwS`>uEym9u0d^t}OWp&UTZlgEj zf2R-w57_CaNX2(dkBXFe&%~ur52+wy!?x2q|NF(#duOaYRYvD}aOnWOo(^{J@5VQ3 z^2z|Lc~w70j}S=o3uoh=AN_xn$Y)Ylpze@!miZ9J^zcnWro3H*+}mbL0VhpnT5u5B zWc3JWe=1$V&{8E*dw*MNfV{7X_fk7JilRMssUo~V+E+^8kKc7&Nm ze+p(6ZCvlL3B#pl_!-}}cI>m%`7&P29{dOsTU(nNoFEkn=Y+i9|( z$1GhV@QQ*D4Dl#+>6%iKZrR?r=it&=*Zc)oc z>xJIX9yC?UMjxUd?yFL3#fC1Z2T|6qVv;kWxRnIJOe~rYq*2}f_!DsDV(X!ZaAXMu z`H0saEA+n?;@e2L(Ea**@PAkUujns_nn2Heo(-oNvBA!{a`vPugf~;<-jI=S{{hL? zm9dHS+A33;;HsNbU!7>8`}=PUk0W(vBO972%>||sBW{kerVQjzc@YmWWq=F5hWO}fYV4+(4l_chQU^q!0)nUNMX}Cw6kh&Z$l=-(vsc=(&j$CA%xGtyGLIV9nYGz z8{F?P;F3Z_tNeR(`0@r$f3^)nNYQR1MqL5o*v!Q&%TrKvK0*@MDOj{|EpI9uM`S~* zxCjiY>3{C;i&gr%Y5``kBPmor$o^K~`RXMj(`(yuX(?VX^)o!+%u9X+E>I~85GF{Fc^O{j8b-1~92Gq=CmDXE=`8i{d#92FQ9PUKfu&JH z7ufyE^2taGRjz~#`{cZI68~Q9c)?>-y?V7xxo3aoc2B@g$qvl7AoyoRbcui`iOxBz zZArOL5o^?803r|tlO!AcP@i6?rEFCnA!J2+CQxptGJIEPP{LdMH8f7j>oZ;%LS|r3 zPT6a&*vv&`Prj<6c1K@aY%N4CnOdrLkpOM)S-`hF4X?D@X$?QsC7oWOvt>sF|qn21f5vA0>?Ya z>QiD-*3+GPf$rWOmt-Lq{^S87 z*OgR!ObarWm0F>kmyG5YG!kA}aSZiaS#!5evr*9xxs`I-nJCD2yr}=2W?2>pqDZ;$ zUwAdup;C}2JO)3VwiU5+^`xJ+^_P^+ z9i}0%{3IFCPe8RkoQ)&RzzrGQ;>A%rTWjm%*uK6RCri#Px}WY`3^qnx?N;zFYV%Cq zL>!K>DPESK>p0@3z?&0b)GE)>a{?Kn_&sNGjxc)u#ob$b zW57}R*?AU;w}^Z1itHN4{XtOcpE|SSeF`%`CGl)0ZQjHt;y<^{x19Tcv@Hwv*`0Cv z#E|i1c8Dek4a3Cj-^ID#UC!v*I2VY ztwGJcDZAs8hF|oZ;{dTSQki!&8-pTTBH_M22MNhWfYgb}Fd~pIh9#~Kw!)G zqKifrX4|%Dey93+hZ6SLb^W5y+%$jB9O@56t$Sj8J9Rp!3s=60B0Nv+o8W!b2l%~2 zZ`g!zaXYtzTJ?WB5_^8f?){Wo9wv}MRT@x~8V{%>(c`U5ASbo$Kw)+q#^oydnZcqS=$nl@-GZ!H7Db>VOGpY{0eAb zw)XC9WuPW{^cN?T(MbmmW(ym`^I((0D^3%3$jaKVgOzv`@`-v{AT5sM$;1IF0o+1- zT81p=5K-et>c)z9l++akw9FKYV7)3(qzq47*c!-Z0c6Xm_lNPNARwX*mwgUf@K zXaV8H;`NElI5Xy}Tpyw<+3+w`eYSjmqdjCBFo1u>)8f%Lv_U0|^(lLqv4OaTX7VJVp}3MX-@e$XorOaA*Sb&)qSwzn&$&y z6caNv(j_q^d8u2olfl}M{w4S#AO)Fg_*3!w4qkEiD0MbqjZ3=YdQnW2;gKA^=M{2o zpiTEM_b4-f!c_~^qL)mWv!pr2sCbrx}hsX*K>rBL3b?2sc=R zLP5xwMD*n^vsR^UF^3lV#$%%9GpoC%zj-{Xf!htimUax&%cLyY}4se%V_K*xy)f!L2 za7z{P9&Z<5OjYhV?2ghUhYgUEn!_xIkCEYRs6M0tG!*7kWj*xaP?pMeeySEqqB(sE zoXriL&uoE67y|ET7iEQZbPVPGLUB!0(`PwER0gXu!cBxsV(J~i*z~p-ADNIc7>gnh zyonvQ!Ts=aDX18&gqF(ie3(1BX?7ZP{^&*MMGRIbseFBZZ1a=u9AhcC&OKx6kTYVc zCo)x3Q(${1nWqU-xXec3VFZAYY*9vgLPVr2T2HQ}A%f-IC;71FAtafG106iK=-0vz}5!3m%_^LyH*Yl|tS)X3TGMnS3>l8@Q}9Yo zU(|E(io(ayZ><#h4Fk-{32BoZR>MVGaM>M>SgFeT1)?IN{W>*@I*bGWer+TptDUU5 zICL!%OFnYhU^C`0)Ge*;{z5{0W_-fECHHZKFY>YPnk_%{rjfsDEHxHbDkyeXL=O0( zSlR*T{5PAA&)6Ok$M&o5^2PW_)DJ1DI~-L*x<;pWi@GOq{)KR`%f7| z^>2ER8Chefo2U^ezO$UA#4?FawsMBk{8vW_dAk;yF!tBm{yzVox*4W3FX>(CBELdw zQEwhQ-J0VopEn!~?$(?NBzzU_GA}~9uHdPvX0Y>Poz5Tr?~w5NlR;UG7} ztk0D`0O+H7%(v}^c?%c78@*_#+Q(w9dN!+@hoXgO&p3^=-SowyRN!qD!msdJKPke$ zvF-griMv*J@sH}bY(_AHwy`f5L73oSRbeB{BTrTf-V_+oo$c`m&gy{2jA<& zxc;-=Cktwra&c+cHA>IJjo52-**@i$wmo}yXKVKQRs74p=vo)AO|LAGg#!e}7zwC)P=}Ba@?3 z9_IH2eq{kk7`E*+Y?aiLMF|1mpa!T|KkO*=IKMXz^@4`lY|g-{WCEEsIxv+?)Qt7L z)MoiA)j~U2p^7$&Y{jB{_DB@QV9K5#nJKYLNWK6SfEDbdOj}hsM6`TBfginxrgM4Gua zD|=92tx?PA^oMC$GDDIcZ;pfi9}i zeOloUzSiVN5j^4SRUt`!H3;AGVdV2w6(eg}EO81IXt*+LRodu>EPGqnoZ*hQ(;{31 zhKwbUm5G_8I*kf-ZRsRufutJ=+(~ew+=qJlY}Va2`LNHt@yqSP70_#d5{z-bwd-nG ztYjQ^+8wzm?hTn48kI&p?OHo={LexjKevEWEE(9l!czKB59x*N6h~>f0-(y6Cb{W+ z0}*Qk9&-^6)GQw){`=hS1Ty}+s^%0IDdsy(8&4Ch)vmrilOMuj#3fsDQ-b9t)nn#0 z+Apa?S%sBc?NrX5u+S!1_VDVx?TRzI`emUWZ>2uqO%gN*=*%!K#*mAWCa(qcyNK;Ri@ zo#OTn6`+Fy@6Qm-8og!Lry27VF3w!1ByEnrbqW)bT48zwoW}+iikyGT@O-bX;J@cE2(W@+uXpx<%wa#mtSDp;ntW0cyA7$qH zTh!w`?wwTN%bg!9=ltVSgUaLO#{;>`E;H^Ff z8)3P;P#V|H5tqc@+!;9cncDP3yz~hg5kFu~QXIFAE=^>j?oDChM~-i%#szXiUo&80 zfDotmbGc>zbF==O@3kDJlbKo;EFper6HY+`xsp%mN+if^?jEeqFC1k3HeVpY;?g~D zxD#kL`rrqx;&GZHrQHwk*KW9-MisEwTQeZ5Qw;33JcZ)tVb#m?nlJWDI1d%lpuXbW zL!gO`Dbi*p+gFZV1>a%pz%;4FRF8O~Q;&CjA!&6raUJX%Tg+XV^PkBAQ3pQtXvRxL z6^{@}Q0@$|@<@kxcmcpOc^=g4?)^ z8=hxew-04+JG%@04E}~_&zXb5fWT_j_J8tjEz-SfCr;iMV!jF?sN0eXJwt;d=v})T zIevxy)Ra=y=l89Q5>qoCdmL8VTx;49nvBdpZxMq7gSCv|4ag6%J+!*POiQ zM0*$J`fb{SvQ;wYZ3+cBnWTQ&LJ0+!#le}Os|o))k*%k!MhcL_G#zjmMYuBI8;nEd@zGu>;LC^^gfpAOT#HN@DoSAAoZ#o$n>`pe zCjQ)Q$17q}u z)tVibIcS}-zC(uH7nXvh!1I7_%s9<@j(qiJjk~BRDKL|I(=;<&BV2*8L=g8*|8oo^ z3#jFu>7kNj!@q~TT_Und)XA%5Q~fTql3dh8yK;TgajGy5y%t07qe0Ibapo=f)JRM-yOjaQ#Q5d-@$>{LAH>_!mb{Ec4fX;T0C{&+mKIy#Fso zqj_#Vc-p^muEPc8Xni^sr~7Mb*yDbDx-2CkaQJ_d$SvM zqyO?A>bth%b=N&)l>fr-a{b|O7T8U4@dk(6irI7GMsBh3KSi>)U=_Gc=zqlL|3NVR zTRqQRnXvuYCH#+$EjMPy*VFs;Y5*oD4rE+_?gATw_B>m7kiVOegns2A{wBZnB-ieKjDmKOJ(!FEc@|ws8YN88CJHGptxdp6%8oBQ5Ki_Mdi$j? zefY&7>_OwZjD>+b=6GErYMryM`L27lQuucw%J)psx7ZoL45o}Q{9^1d5qSjEW+byK zOKbQ@7&f{uz6ULxq{O2{-qwwP%9ghK={Ql~^5ze&N-=B(=a!|iV7Woh{|{Yn85CF8 zbqnI|PH+hB?oJ2^7J@r;Bf;Gr0t9FzA-Dy12<{Gzy9aCB-Dza{eZPBe&D6|Pb=B$q z*H!17XRW>V+G|%C6C~~p>-dEr;1hSxczY5Uw?W@Bzt)BuIL^_0Q)CDO6+ z&8772&0j0~ntK$6d%Mp_&Wmn7C;usox16^>a#=uEsAu##d$>lIKMb4noP9gt12O}O zkv)eAkG$TU^uNWk!bUGs`f~Hxkgc&M;H+6h!bDHBw*6PK!dM^Wb&Lnt^GKt&r*QNCIEIy>D$Lewy%t7Ca4*e~%Na}8B&jdNj>xp8~LE!iRTn63h z)uv%EaD;=naF)2kCO-r?a)E(nou47Rk)|Nj)UOu8;KffWw4T4Sz4<=Tnxe8qy1^1# z4K!$GSL;-Gh>`O_pA!@r|3tr03w%$&>6+ta!e5hZL@cqZWaXvm!U|zQT?8VK(~a9* z3*c6C|4iQ7-WNA1RU$_yq=Xo3LCEH%QbzZ=eb`E-e<7lAsYxx4J^!V3OHd~Ie2xF} zPhr?j>GxvZ^Y8GG+xEdrpG}L70Ah1<_F(G^-zW2F;ZIY)Q~w>|QQ?Ql9zm%OjbV))X3opBsXS1mSX2F?Ms+J++^k68VSAqd7@*YBwOxE$n<3hxNy9+ zpGWr(Jd0@yKIq1X5(-m+ zggU|A+=IXU@bjmt4cZn}?!yz(G^;5H!J^>qBQi+kaT z`4=vYT;H7{FMQr!>7GK{4nscnACN)1DgDla!m2<10aP*TuF+>?PyRu;#Fph1_P@x$V(EPfs>vvF|)=gLU*-YQ-Jls7F zYa#qOeQuGytiy2JsTf%}LbGk3&Ssa?4hNXPTp?JXC7O*eXF-dNOP zMx}Hqw)*Awp>HyZtQ-c&@I9^7&i&aU(gOil^{OFCVtJoa6jB%lC0hw2RQ{m!8yjAl z*rgEV7Zpi-#j^qNoUJ%SIdt>ADb-4-X(OB)%0-I*7khVpS+i_mWP%)ahmcMwf4Ur> zeZ+Kb*DBV5cE&08pLPJ}hjPlhr>~S~Z4}%~Vdx{Xr3WSm9T?Ptl&|mTG3`Ti@5KEN zov^t1*Z+>!4WGAnyAlP->@etq845+rows0~vQpc=w)0MCWy-;{r}lBpVM;(Dxl`XF zgP-2%vI`xX_uCkj^sKU7#JnJH4UGs@tU85%)pzOq!8c*vanrfQkt1a4(ahsw>xX|Z zK52?Rk?tR|2zPz_cM%YZ4Gn9?lwbtX6}XTF_&1`p<331q#w{fch1Luz(E@p$z_FoS zh-1K$iP>~}6<)aHZr$4#c4rBNAXS@o>x*wNu39xfm{N|mlhsvD`tiX*!f`L-EFfQ! z^8_Z%i^m>&z#~O71C|ZZCC_3x2)Xy&xAme zPSee-`a9XuQdT7Rdw`cr*j7A6=qd{LF=t48AFM6`hr+au{i%u-gd)gBkq?mEe3gTe z(4PJ%+g8?`Hhr>KOQ4AKDOBf1(?}B?@hy8(NFxD}47r{Nr7ND7PjlVm7tEYDAQM?# zEXpqBA#~lc%}SU-axem4`x z47B}A0-(NzQz>d*vGJeaiCLMuZZ`ETlE}jFgd-X@+jw0!j?EJQGOksYyGlQx1k!jV z(sbJWb)@ckZ1y`i+>%WdAYPzSIltXvS?eSR}8v`7+>9e!foo z{znsadE!lKXs5I*o*cxwx0_ZxY7xy%G0?AGjEaN|3_@?$L_|KBx4Bm@tM zW5oZDK{B`xHAq>S80?+V-==*<>P0z!KKy`tzdnYj>-*=St`Lc=!i*zDa;PA51mOlT zvF0?2oh@~gvR(}C&pY=7Crp(z(F#^%8H1rz7Uj-ikZ$S{{IlhEX~A#o4t4^60{%-;feNQ3FS>=*z8~R_f$Q)>;4s#|P|skN z>8L3o+$(!*fL|ZW&|$@B?YJGv8cXY8T>zmZeTadi{O{;e4@*Qms7% zu>_MpkDkt3%Y>Z4A&e!T&9r=J~RRp;a77Dnm*a zFJQyatS*DDU>j)xh~SK@XXo$~(B$MP#{rBoN0dK57s z8C3*CJ1F`iO?_{dCj0zeAU>-2o#u=QZVsVDlF2c^U3&&o5f@09Z#r(6mx_^qslEya z#s=@Yt#r6PJpXOmCB#xH0GR{a$X}rB2ysF2eU0hD8(%|E_)%SOsv(|D$rG2Y%+!`T zr{aYIMKYd)!eUeTfGz`K+90|`UaD3Vij;)CuQ)TL$ruTAgj5-PeZ`qFbN=)H)^^UwjbQNe*8(}UN2=1Q3-wWS;XNulsAQ>Es}b+O4MJhiJ- z#(7^+k^E5bo%b=nVH83_g84YHr(*C_Z+I36L>giygWC2!g-J$fW8!>Fl2>0W`@W)r z6NbWq;hWn>OU}JvChF$QYe;zeA443J6NlwWoyR1WH2dQozaq+XBoL zqmCf$0ttM%853~g-S!KKrxq(y$9$FVj4^fk_3}>ARM6x~`8b3Im-<&rhKXEidk=ZV-?Z-*+YGKWwTxJwd>Wbiwk6Bp)&Um9J4QV< z7-06=ioerY9r$GbMIpIG8cg{MAHQ&wIdM}eEK^B9EvI-~zEN8_c=x4Yk8b|t9x16T49JE?jDRUEnS@?hdJMG*G(FC1RnuXnlZpM+n%qvP88rroc4>kN97j?+i zY}B^%goK+Zlxe4WY8TZcXF&PI$!2>9XhkbqK3UkN*un!$_RH^-$oiS+_05P-=i3!G;-^?IMRqxL6G3#on zwqBLQky6<_$Nnc8v@nppM>mMttyvgg4%o_Up&`}+{vGxZ)^sFzn zi6D;FNmm0#ek+_>Tri~xTnC%LGpHbHqbNNQr^vhkke*`^~@n#GPcoHe5rskVq`%uSj?SZb)mXZ`(IIL=}62#oHnwhIocnK zW)z-}txkq;0~fE9F5ilwT+7Y@&z-C@9SiEY_%8wE)Zf*19au=R1NQw&pUR0=?VmQV&}o)f^o zMFf}~gsA|;NIz}144T2v8NvC`W-2^o;8tQh|;VY^d~6pYD0R_aH5 zdU11Ql_#NJOJSGQSaI8LK`Z|m{1D#$3#mS98|Zv#5e-w+t;M05zejuRfLK>UgC5uY zaCE0l|Bq{Q()9m#P|8+d3brVg7;@GZ=`k6ldui40#SjRc;(g7anw{k2yku8xm>VtU z{IaY}0OxhlB;Y{Rsd@2&vY7UemT)=i6;#LhqI&1o`Cg9A_+1}HsiXtX zjIHqwC%6~U2Fk?ojx#LqJ0BUR&o2PHI~uFYT*w!)-#-$q#?qG;b7G$;~)b0pG*OQPKbO;^edhl0lsQN8nn-|YmQpH0~VU}M5z*V=@i`HXHzxFTq~G78y#XXZOPe2>iA z)AFP-(V&Su!N(V)fY9=MyJ{~&bVOU_yWtS-(gWAp4lfbc=jFHer`*H;iC6)XoGSc!&nRxJjD0>En}H(cTW;Q6%CWi`(tSqOt88-K}8$`-a46CSA_I-bmk>L#m4#bhDue{8whxzYF@Sfwn{XKeZ`i0ucy>K@A!Y{W=CSR|x`h6XD z^sCxmrLg$IMJbVbqGdnH;wk;E=ZFpRLVtqeAl1TKnRQJA<>O8hQ=ld*=o68kIIs^$ zq!1rt_m(--E1R%rC50nTiH0hLZ7B^%4G4Y@GRLkf+Av9wWJSubOQ}~O&D1HA>Zdp zCSAR0{wa0%mvoIB2WyoS(_^vNBJmmmbKap!ZJc|P=!|0LvUDTmzIgP?8P1x7K3I-~ zH;##czoYwv-_h+aRr1J8Q1_aN2=2dg&}t+8hr!54eSgz9(9ST<5}JJeUiXqlu(`c3AE36y1Z ztA#;3M0Vj8Kel5#*Mg)8+ijfN9J$2Tn_m5)6Pu@xmoV(_x;BJ8DqZ~yIE7W>3oBA% zey`H}CY<5>eJ z?#@xgneYa|rz`PJ}n9R!#4<#+RzMWR3t) zZkY_1^nXmZ_^ZaS*P92mOLhF+oZAN08|xgk;!Ap4*^J;NFdihfkc;mw?wPl`$6{jJ zt6923zL(1EcjndM74IF39%$nwcp~Ht z!U!wEtbI78>;3bKe1S|zhvW(VGY-E-beO7+#irBV6zbntjK95ABsN`~ZG$$qgCv zZT95q$<}=mq{1#0bjwp@=Wwt6{qq#MD?@UmtUs0B!%ikZO~U)CCHMF zLkIkD8yNNg=%HCrF@tkW^&|yFX)N=8He?q@v4zc3pQK0RC`QNhqT}HazJQTKis0Al z<^UIPakUCTM!2BB$0Z@)Z*;!pc6H}2O}#xzVpf#ph{jCD5<0O;86Y|Di|berBX|VB zvn3$Abg~qwF$ffq0GP^ykQ0&842MINY`=bq>iMj>Koo6>_n{s^AqXqAgcS*S|Ej5W zGE9MrNj-iSVV;)dBrXJI(ws8pIB5US7Ok>?XKR2JSTaC6ilL}&p3@4Ssquk#NK|Pt z^LyRjnn%2uhhTDLe0FqMyf*C5I4ZI_x?qi{tj4Tq6(?%X3JW^2clv0qabE>Up+OOl zeLONiGAe8N^kWTmSiU?@%%ERP$SU2zB0hpK+vVyvcQL1w)`lAor>IVcr1VG7ArY1j zXRnA|(KKB!w)mmLapAc3~7PgvTo3aca1OO>m;G^kD_q!ZLm# z)dw(BYxuB`Oh>vf+OE;7;VQdo2;a)1BY=R0(QES~%k%oNKNz7`a6MswIP_;BnVC$v zGYMq9&Y+-9=48q+GcM#LcA}FmcbFx0VD@=MLDl(5Y8x|b<#xWE(Ag;23n`*k$Yk8( z9aUIH*Ghrg_-UQ1(O%j~RYcclTtJKl83iIv5XoBx)vwC7*rZ!NcICJvYMqg~8FF^Z zir?NxxxYWq@^_xb263L|WO%J{q+;NB_!Qq#?56j5eiU14IUDS0e)fEE-1A8x@7lCx zH+Ei{Dyc$NLwLeYW|g2pLF;{DM3G!SaLt>+la|pkoZ;bVlvup>lf@!KaDF_Ch%D9T zvQ0gu`*uV=qM?VkbGd*P*m!p<{%OwoLqd={@%bTV-qdsaBlHoDBPE|Cev^(->p>Lf zeXNrb&0KSMMu@-BS_sib?bcm*VrQK{V=}2>aKuMp4MPy)#lL3v`^G6RtC`a@n zvY*BHpM_sbg%9?ld@M=JyC1sv)qd`qGbN9@U~FlS#mjEK44Zx4vbOTypxAJ|;NiVOQPQZf{T?M`9P4(Sv9s{FESa}iMMM|VQ&E3KvoR? zxydUz(8tKMp3t)r*?6qH*W6Mb)7AQFzv7lqKrqNlG11f(qKx9Sm|+YSBiGeAYWMl3 zmBG8-aOn@-lS|?KDPr&~nxY~@x^m7N`630=IQwz0epYQeQu^6^dt*Cf+s2e23dvq< zG7tuPZpfx51Ub|#%0Yiw5bxFDwuDXBBN|y&W}=OJQ*JCWJ|bF@T4nj?~@1rRl$~nXkN5n zZ9zg7h?d`d|6J>jdL*-Or^sz$z$4nf$oFu#gxr6z&(J#c@YyiFb zMz5LExKjYow1Qban+>PM>eF5N0kON!W)?6f(vsxgXc6D0YK1dSChwsnBjxCOzERXh z!hld;N>I&WsDJ-pa+3+UF}Ci{gCcUEPVyEcI>aBZc#3-OK-RoFtsR5Ck&4Q7{Aa^k z>B5F%ga_`J(aLH?!+JF%mBDUoY|_7#foPBPNZqEiCTVqw9@TII1ydGHAW}I`<DDM<&+u>m)fw%G`-ze zZIp7P;?!~9Kb^I*%akeen^(CS4uame_p9DRP*)bBjr09u;~=S-!}7D|;feLZ7X~mg zUN)y2{f$dErL_DBfdu&jyljLBj9fnRZKYiA%eF@_2ct4l|MH#!MUFkdUuZ*Qd%`9{ z|IC9>17ah!_Is8li^4q&8~Sx0r1?5c1=Y~>Ut22;ekCoVJ^utP+KX*SHBVWJ8DOoK zy`FvLm-2JMty=Xw6WR%9RQn31Xctj;E+!Qg0s1>@?Kg+|)1aMeEX;71#B5z%yw08E z!>^f)+vwsw44!5X1a(I?4m)C2%W*a8x+g-FVi`#+_KZF9%XyX{HUu=|C=cJD*ewr& z)5CBk{zhe|kCYz@XaCXC;T$ZsI*!)q60PqWKvU*8Zyc^Jjj=(jk0J?-Co!XT1cGuj zKY8#>65grNm5JP$p9oGC;D$Y}JK+rT#{p-KBp{T(wsXgL&&-@Ge;vI_-EFuxs@8U6 ztyg_a-)94*3pnAe*E$9aVwGA+V@5-T8&v1Py$-@XFzJ~B%dD)J zRm4;OVTB?Bcf(2~({ht~j_iS9itM3JPP&75k9CwK1DGaZNomQSoLaoo2O;f1D~830 zCsaj1k-CQh#^^ClY^(#+3K_g`{t=Pt1{hnMcP82@iBA>@C~~ z9k2gG2>2}P$O4cq^QK9AU(X=?q(Kb*BAbh=mHS3i&K|#vzn4Do3NJ3vKH9Ll@KGbu=^tPzKBEr@cIO*iYQ^s*;+L zDnM}uy#taj!MPeQZ$BtV3?NdoUbne{PLqSew*fC*uNM74p0l1h(3fHZ?PItD{w>M) z+)9|4IB+8QAh-WCQoFgIcbwSE#^%=3k;DkC-JY5%g=@_wJvV&YmXR4R(#45Ak}P~jV-)oB)bN0B zf|=K>h)lpuB_=BJe2P$O|AlP-6DWzVYQnb}H~1a#e!48Rl=}o1d_C&-A7psP7(KM( z&I6V$!P*WhX*DVf?oRLlMT(IQL_UjVjj=p{eHbgn`nHC z(a=G=s{-5AswB+Mqc7?sYh2|b?#p2PIYPGB3M5w-s$nxBC1(ARY$*~GdPsKD#&M38 zdG0=n{sj$(q*B({C)hbjF>+JUS%QZ+Y&U9APoB?lKy42E{l|>dq}0GEXJ(V%_EQ?h z3WH}_%;1=ClULkJTHelbi9u(_Ps^%=pe$qK+rKZY0V?(G1VXb<7ofw3Onu?9j}{lR zYNJ*%->=<^B{r~xufy)@vcM{#v&oncyqPp^mm_~nJ=_+`wU^xlPV;YZ{-}6 zYbFRXmWrMNc7u_)BxWT}2KaNiZ0CCB$&0}X)j##q4A$!IBQTeV8`@%$mCwJ%k9xoN zP)pf%kD5hRcL!IGTz`w9_k_@qiw9G6>tcI)hn9G3*FE+CRwr4$ZeZAV+;H9gF3ZHM zKz{w|QAPEyDyV1aEAQ(Q!~V((s@iEkeYDtlr)$Qmg=y3^4_ETTmxd8&B-oweB1*Gu zDf_)XGgrn$T@C_+?rPz^R(ZS9mf(*!vVT?FTg_J6KC6vn=a^Cb{z{W(t# zS&N_C;OHq@yDGdqFtf;;M0VUvT?(J@AL1NOAmai{03lGf=1ST8&rrKm7s28R@^|?B z?`go1o`U;WplR)tNpcfwG7$EY%7p z{~v(jz>h0tb;ehmLJ=k42b~0cZ#JS8iEz7vW3f*rE25!ErLjk*4Juw`V+~uZE@VWO zoyvdYsl5E!(xw3ycHZ@{YI_k#`Y+bC)E>oxcRwT~xd&4+Hvo&DFT8PaOhNE7sF>(q zaG9FQ2rnaV=@d@uMt>mx9SgAf^V}GJ9ItscI{)3M_t1U-TC{5=0W`$;YIRZDGN^|0 zo3|DXX(sPV*iqQ~Wu!?yhBl|=>Y&@-#-DtrbC`@`Mw^!!OL!E?@C5ZA^( z>9e0Z0sFmeHt`^-@cUtSIOYm2o#s7AG1Fvl`uW>hXfz>H29w^|z`HPslpnP_53kEq z8>-jGjWK)W{<_<@0cFdPMGy71?Rlgd)fjSbOSF_vNklp}pl(Qdnji|@kT8q8@6ipt zjd}2Anhm96ra+B@Bc7j4A2Lb+C&kNyhjf?@b8;#>e3~>PUnGRx(rEcCE;AVJdN5vs zdIK%i(*r!OpzB zSXK<7nv8s?5qScx4Z30?KHsG2ZS~dJriH(D#&;jYxy~12oX?G-k3Jb5<#I?xY}J(+ zIQkE&!+G?}lL^Wh&q{@rE;-dP)rfbJN}U9YlWaI(XS0ex*I5I31uh`B~p@BmH)*lVq)LBsQyO-`9G@1e-x4aisnPP zHe9k6*NpX=#Y==RVaDP9%VC(li`YHXTKSZ~ea%MhG|bi>_)TjuF8(^?E^aDnpeMrZ zR667u^`l1|In9OTnX}-!@%d(!a27BT)41~yV4-lfukL_dW^?ZCbc+)rJgyc2A6Zx7 zK_!|@hF!|W3n`Wiw*Is}EH#N!)6RMEm(ff&n-8oxE;8RUIrb2TD=Q`WXgmuL;}k_E zKZ)*@(#wr}mZ>3J%S7)9IdxaXoJ-677^wV}MDx9S#H0(C=dy0TTL*j*o&ph)E96Ve zv#>6j&>rhaaR!|fZ9D}FDPkg~tkOXD&R08kxs||rWbU!xe@*uG#YNH@3kC~h2VXMn z!n-4j{A+6dYV6shks`W@V^FLxN279iW+vsBueDdq@^K=?lNXoj-(5`RO1*GO+s+b2 zu#FwYWrcTyYCXLl1u7#ooVoHW< z#5`Sg72}VOrnet<@)od8IObi2v!Crp#-UU+NKiRxO6*VUqT}MSEo3|8?mGJJ{xXcl zkyK#?7Gm;AAwq-D8xy`>J3Mvmoh(+@WWPx`WLXkrn+dE8ejVf2=DyYpgR07s8Be5^ z^mzwK_TTEnqEq*r-KsbI3yDq=kyG*&;UGY23fC1Ys|&vb~XmDfPQ~%-~6^wTXD4-W+cC zG=f3y^~+!%HSvFs;QKRrTuL?Hl=!14B%6U1;i|?U>CAeZNK&WS?qFO8%*41_55aKl z!01j_(fTx>z6%Ejby<`Z`#!$0hN!EtSxrg~JQ+X>d6(mb1-}&IC1!Q#0ZDi0iICcS z9?NY?FTJaVbxvfJ+)BhJ4kw+?u<&-jKZgiOdM5UkHFAt*e%os6C^PE|8uo}8cV4JH z-z*67UnD|#{+Q&y%wxse#zE0;!z|hBwb7X{kIj0KEJ5k4SXwOkDtP|pvTE926HxaV z+3=6ZN12Q&>bUTc8l@V;f8!VWLsSPmMMhWFdjI$rO$k{e7!kpJ#@02JH&}8Nxq6zF zudL7R8ad-BF<0WI5viND(y5@(k!72mi6i@$VzBewmZpSPotreh0b5DW9y8s}PAT`W zYC|I6B~iM=DeeKmH;%!EBA=TxD`EI>$@m^&DA7hto1J&zOy97i^SldIKGAcfeccQqa z5+)MVItK}0BIfHLPs}wJ&l}}B$=auneLH1O*tqVk-{djcCP!dIPV;JxMH1DLe|on+ zPGkOM?NV{2@xlaT_&UUIp%F}tqliZ)#DuMpN#eo!17lp{qe}n20adSmXumK0SWz7J zGu3_y-6%v@)rfVlZ>ObDYqNtX&?Ft>SjBQ~8v=xU%YU@+Yng&x;6jo@_ z%&n^H_HK!wm+s{WI{xvj`fgJI9^dzD`ii1=&u6<4DDMzLC=oP4{|6 zqMVK8n*r=+tn)wY&sEB2!*UDB67!R^FHBXJ^W7gP`rGCEY!mH7bcVbBbsFFHlnQmStnP~;ZaAkbcgec#^PbD4?RiFQZ z4)lz7nyCnJCG7#HR<~6Ka_S4J(t>QA{jTSSy$5!4lH{X+4lrM@*EB)T*QjXzWS~2F zCf79k_GaC%@IoP6CRY2WtyuZ|cPk!mOYy#+wsH6S1FgIU-{AEAQ`LZHcYM-&oRlR7 zKqgURlsMihysOz%`h9s@_*F8f&e2Tny zB=V?m_G5ZZpJ>R0KW83Ma(BR##r?+#;2M>IPP%Pk9)dPdX6^UC{kC_?E|s!MaG_Gf z2vV+N2LqAa%Z-nc3nWt%v*=X(hKtA=J$mn~>MKkYZ<;=egU!lx4!M4hYu1K-(^V`b z>t~;~{5vNHcf=rpMfQvYMA$^a$)7BWfkqGhWk>1p0P(x!awuQ|%Vm)g~1u{&h~MtTgSXaE}(pjIK0g*wBbgXTKUvMGsaSIme5%)+=Noa-DqM zMEEK%fS1x@l)t7$&yJGeceUgpPlC|v&kzuAF&9!nhl zDV_r<)`PWRdwiA(v5(fh^PV?55N66n-JJ|?!9&nSR-rwzI$=O!P!U~XE-^o$L+Uw0 z`O#D53jVIJ*3*2ig$=I38`=X!9(j~iWptGBX@r-m8=GyrahU?9>pbgPpVYTB=0w-X zik4kvBv&IzzUFAv&;Bq)K0(g@HO= zE=8k6?Pe=yEiX93B8i+&izB|NIhE2@i(a&~Yu&TcWs?w-S4lrZYiYSzsG;H=`r?>*V-@HF&< zc>={WWgF3=V{=Pe|Op>4slmfQy-@o3sp?&lU9Zjr8ErG zawyiTMv;VJ{U~msiW*#w|DYN(6Lmt3YwoB^vr=Z1#`(3sHQng+W(Jh>qu6B6%B_;b zhJsO>c>`zj_cxfTUgeiewBOJao>atAzDl%;;H}Or)R8qhzRJ}|l(8NcaiA;vq?gdk zC666qOGlRs4W(73b3jaPs@ME3W@i1jqT@y8i=6CE2^a-V3r`tHb*aUV*vf$wm-5qZ zbk2Yak$J$gvGKV`JDMi{)JRN5GeK-zBAP5!cmle>+Vxhk(Yz0ITMsNcPkG)@+aNnV zzlzz-kR@w-qK3Zj36FJijZ?bO8I{mW07>;6wU-Fy;EYY_6sM`-4N%H$tJIM%v7jFn zS!KIgEZk_2UTXZB&2D6-DdF4U#=K{$wrL`!qymI(zZ4dbZ$<2DEBShpPK#t^MQdN5 zjK>_tmdWP7uKlrH$kZXza*9_N2-z$x{o4t8$7b&|cd07cgv@zLZC9l0Wy_Uv!8YxE zHnKgsKtz@PbG~lj@N3qKepC$hI_+RQRu#u$##MpZ33ttywpb>iyOdL%Scj#0O3$xf zF_YDZFO4o~!ec3VM+&3>*1uX8{bR7OVJ-4Ersf55@qnyB#Q4drv>hr*`TV1zI*A7v zA93;yD~_z1@p*%sL(Ysyzup^bm!&GXz^a&RPxI>C$qQP=>U#T6qi$Vt=6}pXA#(sR z#Y<7IC3dS{JR_8_ z52+k;;ruC|a@-FoYZ2kbDTygb*N8pbvrJb|8ToeOA#fRN1QbhL;s)l;<&{UY@}3zT zzm(y$L75EC&xMVKs(PI#{##{GF7|gaK+}plSLE}3VX2072cOgQ$x7fM$|8;$QHCk! zZ_|u7YR8@aU-q`!S|vNwHr7yA&b};Uu^;QMOa@Q(zx~H5V)-I5O=<1pqC+$)thX@f zhBV5#?X=gy6ZK(os>EbxKoK-~KIv_KgqZx_4lg|~|EI0=|M~iV@AAsie`b_4c zo9Mr^?SZ!Si$@IB=bp7l#Wwr;|J|g7ie9vO`SPTQ97eZ?l1m`?8mfk9FzoQld>>C0+a!0-LYHea)ULdDWy4Us>TRA9A$7_Uy z?H;hsmhVNS_2846!#!3^9QyPr{)gI4-gWk7f=g0ZUpgW`>2?5kWN45<{hW~)^|eD7 zX?;Q|E6^JC+s1f_x3DsNo*rOIvfLx%_ZTm&H_nzn=*_|Tt-e6gvMxE`^y4gY@4EAz zSPI>Ummi&i^drs|L@gCqn3H8+H)!>Fw#2Na9X8=m%Z6myfSN!a!JkJY0zuNjl1tpo zbS6^^f8=!@Es#&pMIZ?UE!6G5mg87Lmv^W2Z^TSjNQ*U6lnoW z_2-l|RV>yX5GBqDqHNl?gept4MU17;3<^oikAWqT(9VAO?zo4IEUSup0IH>@#1rN- zPaq;Q{iV1w``_D{w)$1oOK7)27=<4t4He~lRyRq}15|agAquhBbL%h6v4X?H$Cp=r z?(?oI99S78ocy^xz*{Tl{vs;d@%8Mf&S6rPP?^%}zb(hAR{MP90W`y1DojdAA3x8zaly=(sxPeMoO+9ks|J%HAg^3_) zI}F?IBoStg0YL)fS8nTK?d(V8QdnIm={?hHY;$8=n!QD4$=}FVHq}_huFcJK=Xq26BM)uOeB^WRc6>``KVVxaoN<{Zk zB$^l%+OXDGeat}VTCM?65!coIF=NfTT$PymWQQib{f@p-6vJYnHQRslLhl$~Xz1Ms z420dSR(-CT=rE(RBq#g*nxYCV+4nk5Dy=r>%$n=M$!h8BLp2J?m`eECcH)>wP)@Aw zmM)h0=rGH(Tkv+KH;FUG1tPy<2&`dqj_m2TD8a<2!Ot62VyWSH(z=vEe5IWfMZIAV zmjxx;xbn}KEfq3^y}T|cDex(TNIf~k73v;{JSoH&v)|Ia7Z`KJMrHPH#&{L<-w;ETz_e3rbFM85Zeit z3-ENW1Pc#8bmw>V+i3>1{4Y5MG4cP)mm*>hgM25rzT>m0<2sNsqlqD(iL^x7+~<$UFb>JVMl0V@gY=bUg$)ci3)4d{nJ@gv5B~Ct&@JlJ&==6O&>@cUwo{lPqZ^-r#o^2re$zJtRQ=^ zh5)gqB^N!KvGCLyQ7e1g*xwFIJn-(+B z-_=Y z9t+p#e>VDHbs@ah@&v{_?SfmVHhp{UbI3|Nh5Ei4yEPw<-8aH@d2S@*Rv0#&HAQ~B zHHwlR^yaIZ{~qzQ5yY)cHfFnu^DLQ7KG1Bb@ippot6l83Gk;9TxZdXlG3P>sYPVvv6^l^MXf(_yk+XYv#A`x>x+(!9mRnUxMe^X|Yz zxa{ijUIbsC{^{BTn8WIM?3-&N{sr`GY=0VW-BK_Z2K^J^T&Dk1W#-2dcDM@o_36v6 zK4B6z4K;g2?N>2~{+;m;(53mD?q+6^%D0S>#th2;vts)&|Bs@$WFlYoMWa5TtkwU|nnh)@w>LXl z$kMl+{Wgq%3H{TsDH@BfOI%QwQTEF(QXnoc*|h%u^Jgo6^8@H?MDJ<2l(MD}6{os6 zs}pGbAm;ZIxQ8C15sd8jpDi=n+d}Nz@W!WUBGfSamIcv^Kv?HefoZdRGp)jHNfp zuO$YB^YU5@8;$oho{N6xnIJo~hu0q4yC0Fq+Jxbef1^9FZyWQ+ZX<_nuIGE_nU=2z zto+1GtHR2P1`0kW3dKc{aF@ZP`HA+%D3iRA-#kkC{AvoB4#2#oMpwyc}V%lCqClfS{bY+YSH4bj&0NJ(y-v8pFUA!L4{r*7Vyx1G@p! zz(lGbd=gGb`u7m3cFhIxCZimIzQWjV47>2_s`U$PoCXYous&eRgi<15EAeJ4SgVwN z`C)g)Xf+;1OJ*c|wQ5zu5!{g#aO8|?soWBw(4XO-&mCkMHh-${Bwn;y^uz?V*si`A z&+6C=^uhLHHfN{*-Wn)8>)k|WPH(+?G_B^Wz@``vx!w6=S$7(2-x{@1qL=^(ZYGjX zewF#^`kG-70?z3@UQ)H&B|MHdYZbKO|6%+fg}8K2du1w~H0eMrDur>$1_6E06dxqk zVNmH>0LI$5h!S1dBZUIy{8H_CnQXD~<~tD+3u&>03vT8Vhw+2-8T&(M^j)=C{f+6D z!Maos)uinTF5DGj+<}&GG>pc|s%(83S22A7frOFVMZ#{wgc>Zr3?`-0^3sp@Y-e*8 z6f}`-B~%yhHl6BHbzLQtUw*3)Nbx~E?&4TE28}Ml=o+~ZcC7zsIsE5Kd8egmokQA? z&Lq^7>Za>iytle&c4z5BN~bn3I*VGz?dnAei;KH%qpGz<>?kH@;PPzUTu0kK3n+^G zAmNw=xYC>=+4TRcp_o<{_+O_q65`}C50Nv=as6~oS(fbo7kHSv2nd*GvonDIwLF{M z+L%fYDMO%_O_N?uiDoRZW>Y2>;z9As`xAJrwuVnpC0wYtJ@Y4DydNHP{DDlcgSOhmn#D>CP8Q@t>Xk$-Qz6NXo1DX3 z^@5-+Efce_<7`Wa{df#iu`lb<&D586zH(_-tokNRf6z`)Tz<(Zg5Aj4_M&0iPx%oL@86%1lOw3^X#In&I(e zNAO*<+Yoh?@?}+lHiR*qS=FOtu52OW z<%jVjhXL0H_pta)WT#j%W-a+~PuTIE<4VFRfBRdcr9eg5gxB#{kubE4Q_-KikISlL zxngke@Zcn?jTCnE;_*7r4YVT|Gkg_qd;bxTo)H2r;6;7LNkY&)$K&i#qZXslCP4Z* z15+R>#fOq1C|T^QfO`PT^1ZkOG_d*({sj7BRo!1%y?|OeOT2Db>d*NvF9aZc+((A3 zX#7atxlWVV#)F7>(o!sXT&cGG2i$`aPMA}S+MfC*=0nk?d{Ta2aVjv*vU|k?t$k2> zeYIU4FqIu^u2wG4jKdP2`RN6a4p5|bAGW`3u#vPr*>*`45H+QAvA*&jakPw5woJ6I} zq@{84Ncg=X(NxA~+cVwNVY&NpevIYO0)5?139o2&{-13dq_WDyQj1!V{86-Oofu1F zw_uG-p=crbzllYT&A@{Eh+(sU4ZJDTGz8~-iZ1EaaKNgVubbO9+!A1Y5cd~%1LJ`Z z$H#}J@)Nq?*P}{ms>u^0kBYQ|SQNm|*4upyaNcQ3mIn{JK0f}Y9a-pQXjPs!mcZ@> zveA1uAbM#a@c41P;zQz=306hHty70Q1?xXWs&(u?cjjaZ>5@V2jeGkE?EG9-zxv#Z zSKmDAR}k0xzr>87$q#p zEn$I+%KC-nzuJ2ns~knY?JF0JCO%tV1D>QjykyRH1>78j{URim-( ztt<>KHI!Zm zLnj(7X_VM-^;M6;A=?Nis@)izE%x2Lh%K9*da!-lwz~tZjg%=LUCYP7k5^`?aN}Bp z*TJnCM-{j+TG;cC3CYG-2YN4LgmqOpsi zZuNN8DxK#Y-A=T>WIhYB{kC;kRGX($4Jw`ee)%R}WpCfZPf7 zLkI!Viuzo(_k4%lUp14#9$&`JsRPM#V_82C#cUjM9`|MM@=2_naCV==(^L+ZGM90$ z(`6t?;cvREakx}zyW?ix!a@4_jTVvSD)n;<*6utNKq zhJBWkqh_TTDawB7;;hkRv1yj%a?MIW%e~e+x z-B6Y55ICVS+i@BYRKN49{Es|m&e$754PrgB+2-D#*gv&2j6s{kUFt}+k69|xc!epP zD0N?v28c^_uOx38Y^Fv7!~tJxf-#$;I#=s;Usbp46PHI~r|TB~gFwfxShv5Kl8bIE zf5!HR#REI6Eb|*TjeYok?qawC(NP-^1-4t8f+WTzHa*Rl~IE%-cKVGRLkG}*h(tILxXA51!1c7 zLpy-plI(tu^DVDQ%XXN0OU`9Z{}?m*6W)r7O#NQe^qf{!TK*)iqP1e)!HT~o>MoE0 z%l_b#K;+Cat7KLvU*+m&^3N1szpY(9Qctx;_^qT!H}V!@Bf);F_5NR?|AyvNz(lE151sySFLmo}AE- zGtYN(jr)9j)Xhe6n)+CO^x|=M^sMI+=Y0q9uLR?RiG;qAE8D|fOIxHWX`75RPCdsP zwrM%}!Da4bVe*sy4$m{-jW>P#qweEHA8Hzh(q)eGoBYK!)(qH6Rx%(q#jvNgm{i)H9vfR=I>Se^EV1C+rdu20=X1H1)|Rtzmn8>T zT_}g=m0Dkm=Ce}~uP@i9bhAEaKTe(hSfY(Pon`(&P=3~%b8(|G785!8AO@XdKkf1DSMYC~y%}};iNAW`eu#6E*N8u(%6xBS8`BA3EJCVJ9iu~QR z7(B>|xR^-ZoUfCqreyl>5!;gEzAmXq;33q93r%w!fZ$O6FY9J^73?UrRtl(Y=phFF z&|u0}*D~9U9=>kq)XSC?CNka^Z5}AwrDR+}HDCegiT?PCY`Qm8CWY&UH4^^9t?gC& z|9A@gZ|;*Xth8jOWY z*fL;g;Db>PLx^ZW#{VRoL)O^#FVBTd67sqw$ILaEU^CP;rkhQnD?9Ko{UcRo_ zIPzpN6=WiV`%DIZb)kuW+%V5#cdphRvPjXGq|tXC->uH-jX#q!z67n7?S zEzVmC`;^R#LTY@EBZjs2fpAyIE@^w?#k~A8`G+!A^Di?dW^)S=Rf+33gDJx^*443Net9&@TPLL(BZue;&!z&_2LEPCI z?%`K%qgQ8r?fKxRv3oNKmC47x5@dF1&ByWX2a`5d`#VS8a5^~1e5hoa6BA0|#3xsZ z$m+Ahss)Z)N1qhprlAhh9Y8Hq1(y1uUf#aVtZjyRYKf{#ITQx|M>o6A5_ofWxwcZs zbo!gh8i)N|zdBMP`;S=+Cf=0f^P}Fy|6D=!+Y)Bu_U@<=j+y5DWTO|!*BC?QGU}b_ zlMpLDzuv;%cKwl@^aFmCVqv03z(C2?XaW-Ew@0MLO~)v(Ae|tBvR1G zHroV2G@@yGPEgT%Aj>u92W{Ki+ukoymUV1SBHIFT*J*b*&)$p2ot=K+IWXPGBv71K zJMP-#ohixR`Mx6%jI))%ZJX9#{U$pJ1Z;cOvSt!Z-j>rwEgTI>;K#NXfc8f*))1X! znZGRdC+*IRhdWi=tN7hw(5FCJS&D6xPfN5(*g_5+ckv){&k?-&LmQ>;8eqm*RqvNi zm675SCc?wF1*YE&yUuOEXbi>JN5(IlEfd-AgT^2(hPH=j_CAGYxb@vWQq^WjHxldo zAuEBxSq>VTfk$L#cSzYK9AEYrG24f!nf`}sw@b^@LCJWnWmraMrq-fk9y$FU*;`jK zBwP|ZbGteh!D^2e4A>lZmI^xY&-y}ozQ_Y1U$b9Ms=d@FwBd@+yHS^~vZOiK0wCkdA>X3)g+C~{krFFfb zGf@PCJ^_{v$BjH&s+*%z^=UA@<5?{DhC*dF8nt1eiDUv0u-;4UtFt<5agfutjvF-0 zEvWI81m(FpWC@A5Fckf%OM)#!g6%eIe{0m<*%`Gtusl&eC&IzhM8W>2yhc3s9HX1G zc7x|eM%z~rSu8NJWmn5|o2pHMef(LLmJ#`^5Z14Eo`x;6{k{7Ia3SC&WGKt;nwx$I zZ)0Jt`atTkSQ{Q-=eR)%8Npl1IFYcPu{L0AA3?&aiB(f2*Zre0^Wm_~_ zAa_kieg_F-mU2WUJ(uD*PWF|NzUR-3e&z7TDW|)0CUJ&d^RB|~3pPq9E@GO_>M~V7 zy}%PAjV@@y;$aolpVBrH>IKM0T`~+U)fII<@U`2c$0kk!Q*5bJH?^WuY^8dh4t$?_ z@b9{z$bfL_`1zEMZu`Pv-R?A7MO&!bprArQXmw~kIaGl$ zR#{*#P~C)lsr z3dy9qOQs>9Gjk>PK^a9vBIQy>Ms)JjoSks}4-WR#LLKr(dU0x^dO3T-VkMjFeH$mY3xunPpbzkv&V&*tDG{ zuU7dage8MWt*H=U;kD^X@L+3Rm=2;`@oEQGb{#W0aaG%5i{MSN*F}HB6{A1sp%Ic< z8Sq{!+CR?Zx5O!v<)}Uv*hpQNefvF0>(oc3BBk|p!g$Q+N=so)d3tppvaj&dp{S?o zNWQ42B3Ydflx>pzPg5`HZzUnOM!hyVFLjHFGD<{IZX%cF#*CgDwdScu{XJ_tb7aeB z`+?JYRSmh;gP_D2#=h;2@!i$mDFk$bv@hR#;T5Kz7gk)I9QpNr=QyK1eQc0q<3iD= zrHbCPK+jM3N?iDjy&|(@S&9`v!Ob?6`e!-nCq?%Sm>=NB{$Nj6H!poH2s#ZXF=)Rf z^09v{CYm?28v)m~{ytndGQ+DmnFkV^_5p;yR zv_>*Mly)GK?)0ordUNw4*o#f<%b-w~(1rMkyTG*^nR`3bCvtg>aJz3tuqNs@?Y7lJ zYRP2uY=2FBaCf9=%Pok};E^a@Eg$zWbaxfFG7~{49@9y*!1l&Tz!;h*N zky%{rt@m?i;NAm=mcI=P6y*ig4vNI4}@c;Ww?4a-RwjW|q&0W+U%LA3_$%4#p& zEv@x{P})!a)JPL2ZkV2Q+kfHXTjP^aGq2oca>x^T()!-*qM+8{^1_qy+sM80Wc0gk zjjmSDn8V-Ar^g5ETZwyz{432MlaCT?;pF1Oes=p4)p~us-^fz1JjinJMwI9_vyPwP zofIyOTOu-;1-e)zoc4_zmeqV381RFE*Gl9&#|@>GG#=z`oi%}#y0uJYk~J23=f-$p z-d0-Kr+@)}BZ)>|w0le?_TsLsv7e>S1xMyn9*GO_-?uXq@pmLjrjfx+h)sud1WrN6 zcRLs}?hSGm_xx~CdrsTa3J+MD$o`@e@N%0?cd)ftP-g0q#q#JNyUbwNH1w4=exfNB zF$`ukA%2lwD$mkx-8^eC<^-PX^DEVO-ba>@%aV;7#Z)*BO%wxumJi#$=YI83L(TJU z=(E;%30m+KrtM?JS25?i{yqukCg5uEW}Jt+Z)mu$tHCG1D5Bf3Xd|m@c+blR{+z0~ zcc&8)KLzh6as+iNEx0RzeyI}cx1>9N18c06Xgrrw5meFQrH=g70s(dicV(SGIGfp$ zPAuGozaWRD2(oAzjF1&b2_8R_(SA8N>^>dfwQ}RwHdFZh#)lmrgVU2LQ zf!7^Bq-f)&57#{fv)MfD$C1s^ap!`7p>f99P!}}&URDjA>V@oys_N~-A_5h)jvQ=< za#yh^UWny|P`puT%r0h08D~00--nRMz3+7^JStK9tb<-dHHE$JKhK_0uY5?0I;?2c z?6azEGpRx#Uu}r{=C!EsCZKaC6$LC%}Erhg*nrwQ7w%mGz8u$-3UG zxy{nVkdFtC5R zGA3QZxn{RA&B9La*jkHD?b2k$S(3+o;Ew*VcSGliT_3v-WzRkRo%!8x+V{U%SaCDY zxVO~@8J^lH>KY@2kqX40; zgK-M0ehYPN=VHBD;6FysQyh$kuY&}7`QPf1na7+h_K-m%%n_j2n&{Q1`%6D!d#grx zv=ge*vkrX;T5!7!e|dDeu4mCGq$Q2$ih*rUBp$;CU^EWpAbBD)BE}9I#3#y^7T|61 zw44ut>U;*?>Wz4c!4+8{&t#BXE52~r!Ia~{SQ$Tp(E<|on3INCry!56mWoyn-$&?Y zkR>Abbv&?)gN_z6fCrTCzm359n)h~&KMRQWqp!M*l399P<#fg_{~OJe;mB@d_HjXoN(^I4FH zY4UtO=n!t5p__BcRl9dBBebfAXTPgwX`<$n4ZIWUcT?1H;3iZepurJ3EG%U4aUu3+ z=w_l{7N5IRE9|wpcTvBzSYKrDNQdwaFu~2arMZQ&hi2Uu!Q3Nmileqya&vBz+n}*X zD_{I`w~+Gnh)v#xY0)7CS{%uTF2!I+z<5lc0DQBhr6QYCBJdv71=lq9f zU6*TKAOB81ez0lw?>2+cH?ocJ$sP5^J4K&t(+!WsO2a?w^b~Exs7pjd=Y2Nohruf( zYeT7Leb%y;T%Q$vK7!5H7-S7Y7#tXpRR4hCHMB=jdx%m{%EW{nIF*`I_T`oQBzLH( zj1k-#QQKC&yE1NY_@-PW>xaKUE$Y{a^ zWGGholG*4ph>FwAbX8xy6=Hm=>o^gr^;r6p16nM@a{&|jsvnFV$gf>br~9T#h|PL8 z6?X6QnL;3Ynw|Q(O4!B>r>YdA@CNcZ0~rffWExd#`}tefi@s1THm6or*X>?4&CEj= zJ~BPu`H|Xil_QHd=ma%Opgr(#vslL-7S3x<>BfO8C^)&*@VY&5Qw+xQJk#+|Ay_6v z+~V5xX#VR{X{d!D)n~JDZ`0;z1T$HYk7Dly3KQo#k2Coj52m}B)X77h~!sah@Sm960n zH5OoVrAL&4%{;_DUEutZFxNuhtnr-`LrdDIN@&E ztU0Tlwtb$c=uHXDyeB`aclFMm7*weXcmn^_jd&P+gGl&b!fqS}wRLk8@=|s-k#!FN?7TJFkQ9+eX?Lg$Lr_9w_ai#m6B&{&{&%pdXd zY&+D4Tca8%TK{qw<%X?El%C_L#d%8Xy{yT`fm`mqX4|(P!WBtJqIM zb`u;pT#2URAi^2*s#R4Vob5?V6ZBbsKCr6_WMT7~B?5L3*ufFt@r->q71_B5ny_x)B&XJ%9o3|R;M3)I z#Kyjfyz5_|nds1{G{&#=N+a~YJGqmUR{R_jK|d(kSvl#b`j5(# z8?K*EnmY0^g+G-3%<#$}q6zok6(pwc9sN6A*ClsH1SZR;2hqM8b!)1S?gQ{#T5FyRu*BeBwD|OTzRU5Ou=PkVSJH6Mri*e7EimUD0uFX?jENs@uB9+RManv zKqp>Bj7d}L1svIt5;N(8*>^m8U(vZ|LX4AZLms$3Ntt?Mk^F{aZ$6Mo#Tusb??*aK zM+)%78gP6st)O~R#w$Q$`L2k%(5x)h$iq^LTFf#y(~YYGbWCojYVtClzU>SnRdC<2&A6u8 zsDAOjv855v*rwOzaEHX-qY<4M)twj2t!pE&toixZ#ChK8tfiu3G%`~hc+pg1$LJ1~ z*k^!DkeJ9wxJl^MfUoVz`;rlRYUUNFCS$*`Vd$i6E zbgP=L!J!_6PO-uSp*}kjX1BDIRcuc$RJ}Qev5l!;Xsvp5(_G~C+C=ux%7x5kZUr#c z9`8mQNQ?r)h)tF%H5DKW=2b${xyL>_vjuD|nc$dm))b~@CqXruR~4c0!>L4!)Q^J9 z9)-sZv+=)Wry{yqyNx_1Vw2g=Go49@JK${azWKc?u@WSbu#VSE4)Zd?N-=()us3_K z9s;b%J^#yqnyIXNbt82Nu5V$!HIV~;-_0Ol7DV?lhCoN=5nM0*3TMV{9og_V(oY;t zU#sOPD<(*f($`@{6rvw)qq!YkxIGyc`(s=)V6nY!I z?(3=6xej7OcXaNp6(*0M%R2;2SwRLk2yWH%%9N*hpLxD^LoMs`4`-8OSE+l3$)_s7 ztVJ1_lrGMR6``1=vgyZq!jE9@NSH^9M+T=i29C*cC$y|&!uOute@5WK@9aPN^mM0g zlOUKultgFE57eik;(TJihtovBxET?ZGvAJh)-Yu#*&L=;tI5J^ zTf%HS<&g|%-Nc0xS{h25wQVMA&-<*{(SeQL@0`1)b)J4wxE4X~IxqV=+ASBgSPo~} z9jdK}MfkY1HJk}H44w2r=S4Wi+cGCvD?V*nKAl~eu^ndbAQQ9984+c+E`ngwpZ&-eeC}$bVqDiM!T*o&9O|~3Ds9;q zA0Z+L1_+sv_noi(%I0qcj1OW)O={$L3Gm4O!BW-OWLT%OpvA!CdGVQ`xnd%O0Dr*7 zJsIAS05WAsea0dP3YVZ}rm{ntCKcH-<=rdg!P1qYVw1V&Y%ZW9cERyRXZ&F%#bhG8 z`RDF|ya=cn{Lb9vwLMW#cpexUOqR#aADSNl>gf{n@_WUzBli=YDmK+_^S@mH*(^w# z;gOfR8dwRO&m4CqpYMf$y#6SmjKe}h7han_QyeW1q2dDbMD|eyLbkt(ZWo;&E0c;v zeoG>8Soe9-JD7IO8u?hajYei9G4u&)kVmM0wQIoT{85R^c(thJAk0&LZK6a*A(hGl zF1=yR&*Er{$o>IgprR{b)C}RT6_p~4i=5s+Me1lKzZ@o)s=qgJPFQA4`N#18$s$Sh zK}%WWGjWYVCHLl<(I-n%fnj@S^AyohD`3-xbBNQmg8%b4d^)~9Ck&E7E-$s0V=6UI zpQ}dCl+1G|eoF1$_SB-59e%wSFzF~P6wj%W*lUsMj;Rqz8v9u`m6Rm~8`h5Wd*ixD zYm63NE0XuMV;U8ZH#%}T05@8s;l?-G+JO4hQe;ERhxUu4mW*pG5d!Py!ex<>Ok~Q5 zTqY|q0#cZ5%E)mJbWq3i+&-4ENGj=H!(rM=l5@bN9)3cLlNE`|`^#tQtTRUEL`qy{ z@9T4%H9q-SGi~FH)aH#9MiE}f)Mso44cu^$b0=MCCN)Ne3?V#Q zg^!CQ#a?4jHa6+VCHHL!u0cMn#A3o#FIi6)2_G}cm^_2z+<+aO zbSSd)J(UuEc+JRxC%SwyFFhFjv@`1tsUqPrf!T6i=D3@+Rvke(H<@> zX-f%ALlgeVv&qO#bT(&@lPIhkuzbzt+}^r7Oz~^Pa^^=grlC0@JbrT`TZ(jN#2dMU zfZy2?5yi5ENn?441JC$tE&a;gd;V@=b}%c zBwxAy3a!6jRR95w+|8=%6E&O_=!wTl(gVD5$hX#cUmY2z*p& z^}-?1nXAV&rRRc7b(YHm_at8T4fW+CK{16a2|cbzithr*zIj(AWTq8YpL2wF2+I!- zgM>jH^J3i3XS3;nEpxLRtGu>IlOHwE$(5A|8D@ik)1UY$#{-_}Z03GtKPU8JL0Tr(tAyI?HnQfbu{&YdWr$u`L~oh~TV9 z7KM2IyJ}5Sk&pS20#Aw%kBQ~E38Gn-D}R_4lebD}<$EI>mCe85#@jxLQHx%+%_}x9 ze47`8XexXb7rmHfA@=dGq!giJmmiBUoij3mbN=Ki2ZOrx^5iNWS{@xmW0*!iu}8LZ zIcIM-hb5)4NB#EwPy$Rc$64^A1ty&?oB7a|bBf>nR5A-X+NuxWcUa$~+d2*_fE%atrIK`e?sM^$W=0n_j9G*xb zg%`;&XW{;s%b?!*pAk$g9`$drO1ibIwm+!uQG58fK~gXR>`vU*2rs)_PJ9clm^ta4 z!QE!cbcD?%wYlO!QWDZzG!t(n%Nuz1X07Hs%uAD=*U3h)+6%y745`fyV z{7TO-WzYP>gHI>2b$MrI7|*+9-6em}d{HoY`n=_H0dM332VCJsrwO^?LD3#+N>Ev0 zHnsTux%>75YKOgthP&UBXzV+|Gnog|gcgRoH1uWU0rUJtqu!%z!oaK*N?29(pVZH$ z9EA)pISx?PmHsD?fD!4fC`{@cc<5ROr#!y#_BgP;@&r8L;|PtiOqgc}Kdd^^sX(&N zzJxpnBiSH1>Q^=kV6{HyIncRb_ti%3_&E#>9Is`Cw8$cDyXE{!?Z*KLMfD8t51T+o zgziTdSEte&yE(`=Zs{TjX%4IZ&8B#4YnIY01WqwXYeP;)IFk787HDVO*0hR!Yc<&al7gm!v>diQI47=RBohhki~J82 zD6#=5j9>Qh8am2x<@#4Pu}K$gzDDK*77{GYOk0^K{Z&mAq30mEM&~CLBapkeMj`#f zYxX_L_5&Roo83Y}tLpjG-!oI3~`gwh)Z(D9xYf|2<%w{cNawg{3*=AzR zj7Rm4)$qmr7eLvtPyW=6bS)-h{UfN2G=x!c{Cp89pRkquw4*IyFtv9&-p2ihWrB?k z)+Ee!{Ze(_?t3vfP{2X}s4l;;dyzxITN%M$&~*IvNh~ae5b^m?=V@e6GO?0WEJ1RR z!qB1OYiC0j6rVw)k9SujfedXJ)&Lo}mbr@kiJL`xfAhIqwwUIT?5lOVXs1pMC1jOL zTNz{XEm`i8?e~xMtK+{%rF2<#Y=oAh1}sbOv^yv<hvRiZW(|z`FgwK zR4i$9djCDc5(WMHWvq$a0E}d;iqoW%BqFPt$}}>$lSyZ{ljGNdtkXL%pH~f%rM_jJ zKKzIwkjAhuo6cfv^watIj>h`Ay>A*te)+}&-Zc9Rrz9ebp@0omK6pD_IDNhkxsn**kXk4QgCzG%>A4Z$3^7Rqm}NO+1fMO1~_F zlZ9+euFORd{9w7g|4F!|9@Hsm2A8WB(nvpICxxpNSLX8kpJpGoz+WK5;U#&hx> zo9wyhx)?$4`^r2_omrzX(Ve!9y2U92dVl<;t;?f_`OfUgV z&EUUi$kvK#wrFI-QUctUWrzFch~y7Jc3^_Knvz&fos$;rp#(Tb%_n*GmspV|%QMo= z(7rz*45<(0A#D#`UT9zU+Dlmdlm1Dk zD(|)d_w~q9Dh5^$7HM{=(0^aB_sWMS;vj&_WF#FZq+=yxOc%rPE{*M4$FsR-@P0fy zKt76W#ByNuzi;@~WHf9?tws{B#XEhIbE0i2u1pw6m>EKsdCbFkzrQc`d9q+Y&?@~d& zi6K)}^e<<5F#KO!gi6&o*w#ykDLNjLl^qdJrm`R%42%{_zsIbP!I%8RmH7)dqy{vI z!POjX3PwkUa;#3!R0%d;B)_&;vTCVjRtn1v<-gCM zA&(}fA2|#*O2SF2)lApqGU1YI!Y4WzWJnPk(V*&TkI)>i3p z1J)LIBN=N~oi#a#X}nRQdCY)%m)xJ)Cx>vw2)Sftjs`39yB>ik@WP3=wPu%c6%})5 zz?>Gk!%_qfmCL+8ExU$76!PI3AP+_Rb7wlNxWM?ey(g1hhmJ_UXbyFE)p_BwT-cS6 za)S#Lvl{O?qA03o6jnVRioI^ptV>3M%}&iULV7{q3w`8-nu5a(16 zu>6_N`_U)9QnF37RT z2un_zV%c)0pKk~@mFu)HrwT;j98t>!8>r9m+sp$>WCc=Ps_F=B{*N}c_HXe>4TeEI z8p-?;ayh6*K%^th{0Sc_xsn{G1YT(&iB~a-`=&h_lNCspas0>T2hteN1+Q9KTE3sb zl3!f{8?^7tk7qNbwvNziY0_q5WSVA^Ta+QqYk zw^I9Fd2F@>8z~i6Nl|p`#2_6EHq7OuCeJfRshrS&kd=tRhg&F63OI9d+^Ug&>quk? z1{FE%n9bo5)wMd!tf;7Ld2-i!-{R<6=^2Cb;<~&0DeHPyL?j(fH|ngt zo&c6&@6vf(G`j2qOyJWR`uYINk%+%{C`zF8t z(RBaZ$=a}?WAavVubIJ%=E|~-0M-faWO8vZN_+TW+I~d!Z^i>GLe_>)(T4E$E+MAY ziz7p6MX$aHz8cc)o(n_@IsSeNAB zWh4C2t93$eI9wWldi8IT%0RF_TZi|b!;)$@1jB||&bbYJQpiNj)P<)K1MAIA7S=Om z#NP1m!eYIiQ!1ym)Puiy6kExT|GGe2RozyC>vP>^JSZ<-Uh2K>B}EZUk8>$RFv4n{?RuT9|dkNF{8 z*e>UFL@;DkUK}qDK3fC{xXbL-iu2l`DPUQ4Jdood=)>evcC==0HX`W(q>y*C5!|g; zLyLbEnZCm=|CA^5&C$o6sIE|%bpo3lL;CSV5~ia`_7X$YvTD{gcJ`;Av1yrDsaTQg z@+apWg>x46Lii7+zRlNZ`TTgQ;3z>J{)sbQ>!7#?d00$7{88lhk3#{e2L~)sC80^& zvvH={?Na8&q)yNh+$cBpNM35?BI3f}d1LdVc&lTrhL!>8{(>Z}&+oDGBiRrnn-@ zkNF|B4{!#~&{rGD9l}>U&fRmtQoAvwDt{b#k2c^>KIA z10(vTuM-mjZGEL}hJ3FZdV?;^#KKh2H}pXM`&h1)8P4&szIt*|e3pM%{rmX1?fdtq zJAz`u29gHijoW1;Y%`6(S6D%a=MhV8a=?CgDs>KjV-sS9Q{IiDIyrYTY}X>j0N$mQ#aHONGU$ZM1Y z9F~1c><_*L&O!RaJipwDc{kUgp#vI^{U?+kiC?5qZti= zQ)9M5wUYin8M16E_`OpAxN{3Mk%G40wnHtE?3%z5LcBUKd{@5*8`~hCY&JDCrv>bS z#vFJC*?PLKyW^+k5#mQ7g80H754Nwfwdb8y`iF$?J*4@94i0(EMbWdYEmIZvr+v!P zWTsMkvuQeI*7vt?J1fmDElp@b$*9mMHJvfhuJ^Xcc@B`|5Np8e;iKm!*+5yYN;hq` z6YF@xD|~WxS5M}B)FE7tv@wz|q%^ zC-aF){7~*MEC2!~#aAY)i_O~ru(R+o*9n1AbE}`jX)^F_a9_ws;<@0x7!kGe%b-29 zH~Sk09l~0K?GzD3fA#ybZT8wBupT{{dGNJU9*}kV#JYkrpXd*1JmgY*5~<8W#T83q z6(kSYeypId6ZA}0O@1o+8G|M{v!v*EP4bzKywQ;b4ufnDi@}_Akh~63tbuq zDM7g+$AAd_vJL3fT!CHVrk~T`)p9Jo6LrO`f2DL!Y(Kf|;(X$bTzsvC;r%vTSby}% zx76=maewvq1(mS6WTk6^6J!~1iGhh+5niWuk|8zu3tgypH_=M$18$a|t zENH1R3CQFhNk*r1(PKUw0G>t_{!`K5R48e}=fgt>90Ds>*e%yJ9w=jNc-Fd{D=nc$ zPs0!7GZ&yk?T~s&2T#p8roW9bPota5n|_zd?z8tX&X>N@@j861M>vc3xqds;PJfde zBnKP})|I9uVR4p!oH%eq0Oc7ueO6vm2^fDQ*xk48PMV%Rk(HS0KP+Hqm7G`Y(C2LF zE-A9B=eV~ufN3+jb~HYwF@}RXeeX_;zuPNH3_pFrshz?GOUhbrNlZs=rUeLH6%H9g zAVdvMmVN@(X3D8yH`L?N9|`!k5tj})UGAtv&c2>Q=PO`De*m6BF66@LDT4N&y=9!~ zF7)5ZEb0pseTp}l3HyJzym2*OHl-V+bbsW`eVBqPk{r$H^sc`B-RNWN?(Y)-B0xq> zwbTcFr9CU%o(DWZwSrN4JNkPHK*(AI+}PF4X&Tm<%^i~se?KIb)&KTF_*4~S*uV== zz1S>H-XT$~i(tpcf@k%!Y41h_GI(~U4@CP?f;N>5LB=XTk%TXxY_{NWj8F9|i-8zH zEK!X(Yl1GgsDky5F7k^Mlm^ALO}st)6Djuq8hI?}#biAeYC~c{oIccl-?i%v!^>+= zo(=+6TrigAwHRBEeSvvVpsa;_Vw;gbxJaB1&B&2ebcROaVXy`S!SciuZn}_bC`OnJ zPbF{lrO{k~%CC178XdvFbVVKPv(@7S_Yz}BH<4n0=|5^GR*1i0l^Hl%V44~`90kbD zAX~1(s}f&VVF{?#YgeJc zlWfVg)c%jI1&??|o+V4}7+a8sp9^u>C_3{#TnnNIaS)K2^r14?xFV3CD2>89`C7C2 z2CRc22KEb%Tb!`Pllbh;ch$15GjbP3$kGydR-5zG`<8L9YW53UTea?!YzwCoRt$3r zYQ;YQ9zUt1VnCF^zwyO}uZ+25`?|YNyHYwUE3Wa*7ElZ8gRsWvGmPaSklp4nA<;&j zuZ%((+A@+dU9{0U>7-C{+;C!%yYc255yoi0h1aSIy$X0p9k>_1ngJ!Jrij8f*<{v6 zK%yz}`5es@NB}=o`a0QN=?v@!PofugskULgdJxW_+w|9Dvk4m~+3PaFP$oGuvp>on zUH(_nMl@SE$c!f2P-ezelfk;+tl*p-hg!f=H{lZpYTb0+;7Z0=n`}o!56t@sI;|=O zTR~|vu*K4l8&&RC?&F!cM zV1S_{MY_9{7&@hMD5;@CO27dm1O(|uLL{YAM87lod*1i`{^c6Zb;aopdn2(MdI|W1)@8sA04fOz{3_ajwd;W9 zF0A1cvz+HUX%G)tK312$8^+qR>IZd}gkcsf-eg`aJ(PgJcn~DJ;HxS>E_j{zk^Z8l zk-l7dyhsiG$A`4*Cg6cw?Z-(mL8F;Ds%LDf{LXWtEr#o!Lu&)D|dUT#&A3T0Vhdxz05u@4#lvQwgP6TB`B zfYpoTaV3rNGZNztV-r6mBId`|usBeTe;BV$_TX{|f_*7rl_X`|1FE0-vE4d`*HTLH1a28#$WhsX4Kmk+cbl#i*`1zidheuVW3LO#wW=S&xa(1Xl_d*cB_| z1vuIaTNCJOKSMGm+mHD^F?M&Vd<$Pm)b_9jgVS%TTTUnC#H^0 ztfeFDPF7U^W`zXDAoVL}qgb27jn9Se(DAn;0(FJz|JU71{eBda7zVd3#@Q5Slj(F6 z{Zqf|^icL#I6VA~Qg;B+c8v*16T7axT{Cc=8Db{vZuKsRQ3lybiP+&pM1Qz7TQL%D1`MEia2iQwe z%Q~mOJQvw3veZ%S7KHmc!#$7NkJ(MgtssU^%xbDb5JgLn{1LWH^hqL+H&XgvBi^9p$4~H`oJ3G`;M-_+7hXhf1{xSSE;i9rfAb&8 zXB#{Gmzm6-Hu~ZWt{ZxGyu3eNzy8*6;DV3$Z72Tm=4 z%`^5{9o&nhY8YYi(V9M6s^+j&J7{5JtCjq8DHRHMp3uKu8%Yk+8&1)ICB$&`5ST)l zM_9F%(BaXHOu1rB;QO*{X9v5u)C(NNC4bu2{s z)k9>|<%6iD857)3}=O;QtdWaal78ll**Av^sUL+HCuLh^t{H zKFJEPI%Subp@zAPK$|HENhKZ!W`t|b4M-tc3D!jNuT_ay44iITsg{7C#6Qm~aJc_* zzmX8ad$Qieo~ZcnqUR%UiZ_K{L41|9N#HM0zuO?$_s32M z3Lk~V^#0?+fOnrm;uI{A{FGM$|JU%EWr310F<{(t^(46ftc~*(6|hPxn&!S^8TROi zzmKnp(P_b5Us(j_iyEw~0xaexCn|RI?Ob<)di;|I@y{S1ol%p*B%D9X9~BEs2X^lM zK%RyE5wgmExb3+=);xh>Dhncj+R7gh0YU0HVBbSH3QB;jNL%+M2(L{*P5_7k+OUL` zwN`F^&Ls~Hx4%A$@e^HF2+!CJ*102fj%Fr)9y2X$bpkn7o9(hxgfT0p|I9_Bf!m{Y8JDpuW@FM49h zyX^qfjrR z0Xh$CafEy9-5ZP67=Zz^kKh5ZdQ$#St4#mPfcgD+h&*nCy0%ZEY5JF9s!h5}rr0t5 zNFXs?+7T@+((^GjcfL!z&!Fem9H3bWsN5+jb{-wWH7@_y9<6R}B1S$Yy@nr|czlp2 zZYOJ4orM|@n?PnwxxZ*U=QXq2dhy<#EkT0=!mLSgT9-Mr zW8v82P-XDFQ)D!<0(*Ruk*rQlHpKJ1Y6F5zJV5SIOQsC{sRY>ubJ`I-C#U?VPm90B z9RD;?!6ba?-F9>K)0}{2DS_b|*e*W&Xb8Bi#3a)^nm&Sk4t|hnqMsoa5>nz8udaZ~Jn%McGoAKE3@lTU%BBzIHm~csv=CO-+foZ8mnIcz0-pnkT`&`s+n%c4 z6!((@w-FDo9i9PDzo~ecpTg=wZ#AjQE?j?l`c#I!T5ro6Ij-0KIrHqneJ?7jc)+GL z;SOk)$SlEVdy@8A?4~?uF|n(lJEwIgW}}_TFA4e65Kg%213!0UKbuT??a8TS|q5zY7p@y4CCRJ^y!E*e?sD>@E0qW{mD|WlH?`I~G9nvB! z$2~ZVMfa-};%)O%3vEXO_HzI%DjwC0G=t2$la+Om<yk0ng8@?1NTh?E`%RcF+z)5A+E5`%SY%s?wid=sNdOenQk<=upP$3_s47eg?j z7su}AmKD-e_fGLPi!pHw@QlKqAbf}GC5rc`-1`j%=>{M#Ho%nq{;Uc_Iy{s^%pW1e z{RUI%nC{bD#7rBUx)n%b`AW3qSEFJC_~^_WB_IrrO{Q~Bz{HCc*hq(jRx6mnWS|52 zRz&oe2DC4wzx7XKjthPt2A_&Ya;Ggf^}Q73&FGb1jT+F%i8&FY*?J>IUK&E9ARYoD zFHO!%rES>qm{@Z}YrYm{>iMHv`a;35HcuyriUa%mu%)WTgQK}*prgV9r9_(&?W=`~crJ*+5>``rBUb#W(b-P6{I7pK! z0n}A`k)3q1+j>}?SdfGeym<;tx8TGcI7KHJX=2~ zVN9k~ac;VHMY7eK==p88-Zn>#!uiV+=SR;&Q-ue2FUy*u1CMvNp?$B$^|Fmp;cK}hI4?FKkunqCGt5L+#b?K;P^rhqBtZ$4Peeb|fgHUS$E(ThFv>|DK^0&cExYh`gK;u+KO3V+g8s{dr- zY)yb#5t1-u)eqiO?)mF27~V-(;X9m?eGMlL`QFS+aZRGlcWf^jms{TZJ9KO1XIa>> zaHwFYH}SP!paL8(ke8I>u(g}an)Miajh#bOHF5KI;*n>um*a?6>*A?&-qt^DLIiHGrg6IgJ{=;I6+=yMxU;Bo1$ z<+vDuwQozCb?T=q5}~Ki4Zh^Dv|Fi8j{tLrJ`6F7(DGt?89eVv)x`cx+Sr^Q7B7hi z%JXZMTUJb`#MF|$r~PsxbNh zhyV0(GR6R~Ug62LT(`^MZhQ&{ZI)W&_O@YW`lr3R7x9YSk5F-gio0JoKV^{r-Wqd{ z0H=h42oqUxqGg~Nun~!Oe{wMvL|N5{?k9chNxZn}e%R$*iytXnApZDMe7C+dxAOJ# zLW49(leFB$@$}!}?cL!CHC#d((Mh6(X_O_KrOq>53qLOHIT0PX&Qrky`Xz(M8uP9a zh8Yv0l3VwYOIR&Mzf1>%Zh(UvKVv>4+>2v|xTqMx>iGo*VlU6O7V5Vps9C0ddaTJa zun|-E|qEU@nFFA_4l4`eNkQA=eZs1W8Y|zGwAmrbc%LK@u`h-MK%HeXwV{p4AyZb z+*g-gb>l}#rvgA`h?q>V%D`7$}%SX>rjQ+*^&wN zfj0THr29dyo$}b0H1oPMWGm{a^!_nYQMcm9kf_N5BF(ylt| zx5j!~+^NR+u|z+ay53SGA^D;N=_Ki;iOrtf3c~vhO)Z)Dxj3R2vcZ*BRnAnbBqga> z$s|^%M}bkyA6uk1!(hmvAgq92s!=$}t;rJ2g8q)<&5Pn`LS&RKg%Kfe>ZejdXPsx* z9Ut@&$CB%)a^9c~&-~Y~vrXuG75)8tt@K}C6V>Uc5UEVOc-M{(7-=Tus77k>u`y!Lbj#HW5>%);f{~_?Mwp3e(*Zbn5^3^fSJb$Qdimx@lxFk9$JmQ zRdbnW(&kldk7f`G&g5|95fXp*%;e~B-Ug~kZiqLkTf{J&6j~6Ia+MeZdVzb6MA!NR|Nb0~eE<^7f8t6(>VY)Wn*uD{?VdM$Ul3j4iqM$H231IVZ1q-qb}~v`}%F*D$<<4 z32x0oUE#k#Ba4e4wPw9rU1oIgu)6trEsBr}j+8@!sopE9lUr256JpiM+3dr%TE969 z;G?(p5^Wo3&O`lnscYYs|9pp4l_`XH0$O=V-HZ4`uSfEIsb84ZG`X zu;9x7fzS+>DJv^~INBIMA$sb!#mPR!zarQQ(^D`5mMh(!#`x|9&H}74>{o9S$7vqm z%+oz05OD#yfkG8Q8$~z{S8o&x$s~g0zY)zp+i|lcJGrM2HE6*9Ma1AVu$^zSiK~)2 zMw`+%EwBQ8Pp?w0QmI0>NFhxPx@St%j3BEZSEW)*uvLBAg2t%nMk|atu@JnA;lZH@ z3h%FQ`UAUtOK*v9Eobq>QUhidK?Aphp+)48Hi|`dC8tUSTPYmYs!&Np7i98F@+=m< zF-o6Klqe=CXG>v5KpgOh$V;&q*7|BE*sfx=n8Vri zqi^y@s_vl1@c6>`M!`-gCi!p9U|cwN|MsVPh1zoy^hh6AmbBF#ScyuN$|I3KB2NXJ z$aV9C7bLE=o&R|N?8)+IrEGBEOo+1?y$m`!31(pfu5 zg#CJqYD#P3IZh2|POC>4QoU3=z8O1oRu^Ix`#3jW{uUB3$O?KVLm-uSnx*2$bL2M~ zW;6gM?Husm_}oc8$OPfVpw@oHlz736)omF%x$U?&5silbi+ChSj$BJ!P~p?V_WU@{8{#{vr*>ncF&g~+f2#zcWS`3;oqMbZw_B~ zE95JQS8dYxOB`ftv;no6)0-Y+d1bddDYm=ZmAu!KhR$CY;_fPCS|Jg1B)5#Ee9 z!N2LP;&J6YRrpA)^W_FVCAn=`g4%vFKPIEvK0wiiPaTKMm43aW7np;IW+LRhrK&pr zAUqhE$s)$PBe=lRsu4lT%q|!p1FvK3G)&{WAapCK@$74DR3C|qxbJ2X=fQ@eJmmqH z7pL*vb|yyHLHESuiyj)zWG6fShm&Q|tW-6z+y$7m^4INRIg(@PUxE2lTW`=U=S=Je8#vp;rMh;Y6@nX;kBj(IyYoX(A@XG{v7lj1ake0~&<{5TsBoY~GUd zCD=fVyl2}X?2p17TH+oqx_TjIC`%FjF_V0So9bFUSc{xf&_g57h;UFWH>-W73$-1Q<$nunTDJ}6W zEmX;LcD$1n!5LB*bRO=kk~;lEdNPHdG@jj(y1~J27{i2&%O+2OVbJ_Np~w;EY-g1A znGEyiTPiz|0kEKV^UHIuBYX070fw-8qx8#?8@XNOht0)haA2+sNO@6pD^b)t=FNYu zV?tQ<<-HXxkGvt2&EzoL+uPN?>mhM~`u=jL3><*j0R}Pc*Fz^}p@bN9^8Vn#gi3#@ z$EoJ@ku`r2Ws4+KWK9Wr=*2H%?|LlLX)F-X5#XZgSHmHy&rx9BCFg-^P}Zpc;bZc( z+y$OTQ#W!+Psuwie?3P&pK%Y^mb$T;XU=9GWU5{703ZUK#IGvtNu-IXDVG%vh)Lwy zroSfL)7V4H-F^{UzXvUKHRf|HY26SfX?@QvPvHM<_qSr1M-_pg62}d1Ny(^y)c%>f<&V{rx261m(Yu~n?Dgh_5 zc-7cT_i!H>SYl~M)#F-19pF+lmrjAH2a{8JZOh^r6#`|w`H(?_1AgnjK*{ECID22I zjjDol-HQDWO!C06d$-a)uDjP?pHj;w$XDa~%a4T9*OueJ$0ae3Zo$N*rB>a`w3lL0 zi22op$G5~xQ{F2JsIi?UoXKQ)g5xV*Af1(sL|hv+N>)0MS67h?$<)fkP`P@!Ya`7` zvH1Zq_VjaRR4?2XVYFJ~dI~({S%^8)vPrb3YZmb^ut7&HxX{IFPT#%UcTaxl>l zH$G$h4{8Y3DR6vfOohY{1uX0gpTx404DvZCxr!vRH1^~%;kN>CcKkJi+Lko=h8>a; z1KLlNj#5h7LF9N3NQ+Y*kcOo+h0M#i{0u39svW!1l69WON}SA=CgM( zCizS|>`&~Ziq~SwU`RdcjZIWppuRMjG8L%7U3-Xh#lu?daw+=dIxqMP>vL{%q`)g| zDbZx>+K3Swg19z1GXtr@2R9t-6l<95qY&#c*pq#3i@}(7hIyBz#QNa5C;LdxUzVFM zIALd|V5`xI8ZbxK5N>AWsYs#0`a`Z|YyNynV?ZGlUta+oVg05CL*{vUBNg(RyIf=? zOlC{pkrVUkZ{e*yK)QxXh6-20q$m%)Y$X16ZQQBpnov29@n1C&rO!YeGrOzT{0!6o zh(1OJEfI=&vQ8}$K5K2Bho&_7O2t&PG1x#sZ+k;a^oEq#e+K@WPRJU-xZM-$=D`E z;;m(F+{g{0`?DOh1FDNbrtP`%=I~VU=#MPEuY`ecML?7$3EP|)2B6MD*mXki!HsavC84 zgCjA46&`9-aJA6JFdeD|R;M<{QSCG}LhFqR%;69&$Oax16YZ@-S{B|62~5f{WCtxi zzm!Z5idUM9;JVX1Hrpkogy};e#AYR@7M2KW`|Ee zP=GIPR9^JlnN`9Ah!LS`5e_g3fS_{aY1gSKbDChK>EanQFpIQ{_F=w3yn3F!Y`>b4RWcj+*=X5dG+SvK`8;%LZ`OTmkcIyug-hho>r48)|XA zgDifdUnTZ#mVxo?;iZ#m6>5gEORI}^eu*DT5+8abz6V4ob_F`uVWW;`NeSPLKs+Q*q8}foM};J8SqBA5{NkND zc&@IZbp_Wa=EYzF{9+uRnS6D)i{{D;TS@ z^G4smP~qHvSpfJa8h?P0MLp(DPd@8~Tbt|q*e^VRnH?ETh?~zwNRRh$!8?x%LWb4G zbAP~Q2eK+{l#}$gRoW@nP139@Z%z|Fb^b14TFaR&MK@Qy@r9}D;NH~L+e+x5E>!RK zsP_SfR-Bu&s)9&_w83BU%EEapZefx}=*!Z!Z71R5&|$wfacY;SPNt7ujwY+S{yp@S zh~`%6lV+fb71G#Xgy?*_JLuhu*~xI=2?5lmMnNHGndPBbT@sWTDP`Ym|iPXJX{c@AyoPftb> zQp3+HIbMk~cX!kCKl`$d|C=8P0kug1?e`$(+1zNR21?-p45{7pRLSj;g}>HItAlBg zoKnfOs)v%W+B43ISZsGFjW9X{x(8tbc{7O}ReB~yD?CzDD%1~egAj@9I1s(SEU1%< zrbpTVI!>}8mC6tr(0Y9gku34i0vmCe#IV%J&^)|80uQ>#kAnK~0g34^5UYYu;@xSj z3YSx5yJJI3wmx5Qzi;L_svJ$9TJzLQt~+G(p)e11dIrzg761y5{*i7rkheB3@&V!Z=yqXU)nBg=yRi4t~~X9MX?@j-ed=0(C`jF#D-g zo&Nf?n&xYfLpM#SN}E|#pR#r_7#V%seyMVERd1VHsef+g%{!QmR0XvJf5`jnapom^ zGp3g@x^u%(6)I8ae92thB05Lk`O-Lv_`0muyz>2$m`wrMA&&S^_j+jzR!ta4 z=Xq`P(fbHh_S$)=mqhl`#A24cnI9M?5yxpr`W5g8XIb;ez8hX(9ixfgvJXy(VwEFx zqZ!uv*sz-9VZI$9Ky>P-tGREJpPtkZvVv*)>4f(Ec-aS(c+S+@k1#>&M7w_E#$L~s zp1j?g4_MxSK>Pg&di|E8pkD&cPpmzT0prN=c1&O#7|RJ0_YW_(vyMP9qDd< zd*O`thov_!QN^DJXaaptl|N=_NfdaU_A3fE(D^ffOep=sZ~`|eH+e2b+1$~6*A+xL z8D0?mPEx$*q1XL3kqf(Ep+Q(GAicwnKjNp0u3(R^%?|nnYXbHy+)O$rCNj zGG;|3+OYgm@mf`A3!G#PexlIZxWh;*R@JEXpMv|JllJ2?AT&W%n~KGJAJq2*cGvra z{$e{=K!LZ_=(NE4{7n+NB2&ASg2PO9LVb8JS@Lm z&C(7wD8UC7ts;lr*($y3CxBlZDLvBTFt)=58Pj0>_8IU};~S!@{$AM(ki9cG2)$7& zHEJx47b&S8v&k0DwoGji@zyGk&mV|RP_CHeA7&=zB17oKkYdU(X;v6$krhQUyfEbK zpJznPplJb6CZ=gL{-)-8gy0q{+Hi z-^5o(oY7WK?&q!3c#^Mze#uL%$P7sD-6-COg@^MGBu3^xz%xs`zJ7i*NBw!NWu zaOfUO*z52B60WctUzWT4nB`v+|jidxibuN z>)qTB^?-f#AD303T{<0JtKIioa>)+>`s!jHoQd#wbd1O97w&GW&=MiNqyaE0{$i8T zUSYfvbn{1P4GvtLmfLpI9Y);2X@phBkTrw7woXsD6pAp<6hEM@tl4Tp0>OZ>SFj`_ zFeMP7(Waf#_F3UHGiY{p5w{)lF4|*I#H*-m`4%0(g z;;aIt#*SR_xx?3k*@2oO$OQgFM|Z>|v=kY5FRGrZ&Cw^%<+clXA0>FHobj-LIz-U1 zBAk%}dE4(V%QAQCSWC(SwW>gwXvDD3h~}l=R81d@Cj&}*xh#Gh2-MbFSMm?QN=l#e zLDpTMwflK|<`01N;3Y6F%MKelbeoU>FZJ-KH1S9`(yuXCq7H5)>9W z9dB{`EH+1V#)X=NjfHv=MXP}bEG}XM@g9ULlq=LYf|{6X zMmOTiJ-x=OkQuPNTq_|MI})=Ign_5HM@3O&5LQQ}0@l`|7$kyQx}W=x7fM8q3{rJE zGX_WRtam4kz7ce9Cp(cBo4K`E5a6$s;IC}~ER#&+;y2#ZX0T>{n-mwXCtGCLm9PKH zBun7ywYj=%e&!b4Fk>X=L@!FKr0?5$7`3`mbLA^7k4*ILE@=gNaFf3Dk6dvefb&j< zZE`UEh^El;koQV$B_$9#$@$x98gXamJ$TUl`zIzzZW%~EscMPR_`pX$i4tc&OH>hU zDl(ar4hu2`U49eGzdRF@GVZwG>vYRSnj_q}OM*Jj6sQ10WEa6&QiG_*rUR2^jGbd} zKc}BDTsNXq5a&$U{`_NmqzN$S2?|Q2Hx~bANJ@d4bnxFDf?Dv(8-W8nOE_MWS-v-D ziL37-v!~@eE}+N*$l26%$p!Bq7C{Et75lF`yob}j==6!E=@i{h8RroCec#y0MHB_Ot65mH|fpW4y6|Tt*)^U^`bAk^|F2BvNcKXZ6 z{g83S<;)-D-aut!kLDV}XXpIpV^3v42~(VFi+@ECXW&h6zRa7QugiX|HVfCVe@ho3 zPC<_6yM4}4xpANOEaLi1l>rLMwvgSt$WK_d-k)Wz^RAlp9}k4yFdRFiMTJ7&Y+fJg z$yx?@w*DsXy+FSo`Ukxm{&`YnVMO*{Tipq}PEvDPMfAQyCkIvGxpy}LWGg~CSKRIM z%1 zD`CsPvN8bvPr`wE#K9xBRY7&?!ozih7eD{<8dZ~$X~|N2E$bpVZx#g;=?ipgF|Mxi zMez+pkF^=#S;)tT7ny};*|2IW5^*DNiu+$5C7~x{0d_lwN^A&PXs5wXC60>8q{qCE z#TXG1EWKF)jdJo4W`%1oCzMf4`5-=l^QV5UCwSLRoRD%_%8M z$!f^kAF_8xV;jwYy-fHmj(!j`k}Q&FK>H`wDc+s&&%DP64CV0ZHrkOofS}U!nGGqc z4kbcUTg~-R(XCro-=)&h>kh65rKAec*o?ELTG$P_Kc+ki6Z0Do(&BCN2r}97coo>H zj!7`WrAowk!azyt>6&XOC8raXM3q#oK3}rQ&}Q~sy;Ouy7Xlq?n;ah_+j|FLAwE2)ha5TPO+Y$##6?wv~Mx>%a5 z*JnCwNfsc{@$m@%xBulyq)(N6ysGfY4{i zHl?=0O_Lkvc|j_xQH|-mS-$%wTWS9rn6j9ef#!tCz9pHYzT^pm^X| zBIwe^A`vwAY|i^js4)m*o0C1SCr;=)yC6 zdc3;)yla~qWrzY+2|@3qbAVGblATpd{Kspt^`F8Cr*c60#%i<&mCEbVp36=?1G0(& zLjSMMjAQjTseyasf4hiv8jdnx4gZ(&iHZrGu?uaBLUfi7;C{t?6@5&L1ATwLI##?ucfkq0{Hm%!sY1YIjrli=Z7RzKX8SEFcA1^$5~))>&GOP^=m`l zi@qv@b7G0Pn{5AYAb?3G`mMiKf33TDp-Eb7u*!6r2Mlk`FwAl-ls;YmXOnhuh}NTs69ZXj^BZCv&e(XjHUYy0R95rg|p4I?)yF zb#1*=!7;-y=h#^at-Jm@>rSHf{>LZ#M8|D_ z1t}}$H`=$U=@-P)ySYF9MmFL^8X!C3KYKGi@IovvTf;At&Q(rEutHvle$eP zJsGDD{t0YlLj!$UW)yeqLg-phO0&^2F0N^> z0WA{)2%kwpy2BgAgv~|%hGy>pbxH$B!0ymhK%RXiw9q<{GTX{2bx$hq^C=v-(U*;` zoAoFJtqOS<3hclG0t9u*;U8U=hmwyXb}_^_=e=;O+Qi8;9y}i^f{nuE5o>;Tm%mXT|~ zYFd)xOdHCf{U|Yu@A%6cqgv86Md{nTQ%*|ADgNo!K^0>P~L%R)p^Pv zBi43kcQ%azo3^H>ffckos)EW_Pn_e7cn`{9poOK)uFa`|8sl`Oc4&DgSujO~ zP7!q}erYY(aAnS_>SdmVzu=Q&zkT-Tk_3)(3~?y7GMI`UVG$e1||sJ{2hqevHVK#TDS0mHsDw(4*(3bvChnRfGZkTPjmf3 zWaNRM|H2y$M|8h?>m7O}%Vd{QHm4D^?x>iF@SvN3|Mz>q{8uqnDnqIn15;xhCI0iy)s`aQ49Pg)-6e@#bkZy1l(bQ*djSEh6_+~ z13(6JAS)Xv$N!~tOhZ2yH);Q7KFA(j2S(o{2p!<6IRYTz3RvF~FhXyU(~aGhqdFio zdvx|oXDzT2#sg?cR`K@0O81+}MSGnTcvaG%|DScxgpjRQcla%IL1)+hXb&p|7;?mD zP{wBjx-YtI%xU{?G#NqCS6U`gV{2?{HArdVwr*)gtq5t#1JKAS`t-emoI6m}(&EP` z={b!CuO>KIQlm)(Ig%f51&J6_q08A@vPKyo{^NM$wdgOnytsn=olB&sE}c+)$!`-2 zN&jAx7iU|FL|=Ofdp^9e{A%BX3O`WFa}5=5AM?yt;O=pkG>`q>-gOs5MGy##lj1Br zxD|~^z-01*Nsj>o;=6~}R$Ppq0Ko|xTFu}a{R#}fQHEYz@QHTh?CJ=T06a%C!axUBAYxS5!zbIGssLS1a~M!Y*-&>2C607s&X=s>cHzqfoApBtK+)UjvU zZC9iH5A>VQZ`uk*?*ploU@28)8MO%RFKg1|V~`?v08P5zF!5ff8ZlRA`52b_3?49R za)k;&_xd4aYOFw1CaVul7UIPDJN`>mvgc!yAet?0Y!l97jgzyUIh+DYZ0$(Bp{Hpw zQYF?_@ic!p?tHYfP~T4brD%)s@)-Va)1c2K9cM>!Sdt}wZks-9$No-Yh%fG+<9y$l zD4slz$oKaRXqx|cJ_CerVg&th+}@#L>T;?@@shKj)4Kt#=bl2ir!F-7uDFxlPYpKy z-pa^vyyO!!X!(QI+K8OlIx{fm2+w?#6C@Wd_pT&$G1z*O<#wV$pbA8my_o3kH2TGtfye&;gN zp%8jMBre1s^Y)Yu9e5@0GoP=|v`Uc;pc*_|46UmA9)BI$v#m@ZB~}K4+As7D>fPYG z1-_&(SbD__T)fd()X|!8OwrGbg@1L?JyDAGQsevaQ=sRdEx>M(BtVH+6)N{`0x?&r z7|{S5(3GGl&;9O=7wm#vcRIDPd+9!b1)G4Us8VVp1T19wJ-f8aK6lAS_FdZRxuA!( zgGM5znuj?Dv&tafds_a60;HNl&8U7!IDJZNO!SHka2)<7;VBR1TRZUl2zyn`f&Dss zelOD!-;w-PTAGmgX4gNxK!q(nyCbK>wI21$+!&he&mwYlas7G!kG9zeB#j0K+Vs-X zk&X~LZ2ix?+mcgT@2dU(GL-M_DzK_f0fyt5A+f4Qs}AwvK+s>|0*B^xdJa2bl=L`C za3PMM_h$R1_z&uS2GU%WQE!o=WKP_FEHm2@P^67kb;U`Fcn>+Qw71fYVIC)Xn-!b` z_>M$~lQiyW3aiL1bZeLYHModXf(D3mik!|txq?>(4!oCuk{qF@PV}RO2pAl=R?f}oI4YpS^8Q?i<_ZI{R;;J+ zisDkk(*AH(QmO5&_FDD7$;XOqyhz2w;Gan`gkz~M#U3EGF2_`}F@G3QF0uWIo_+sT z09f$LQh?FxP`ZZ61U-$@iP*X;pTXt`6{PnV^k*``WYLSkkkwmXszv%rPz=3}k}eT< zdt@5WD8Y-dO4vzuE$&9?mf25+FX!3Xtqyx1QlOsJPeCL!ki}f(-89Da(GLv%Li4Af zOERghsdnnmpMbCIj!RC?#PY_4uV{O$X}rO5UU?2nET!bwxD{U}zrVGtxeb$WpdlwG zrX{Woem8&!w&(-L*z=w&_D(xZ)d)T?{0Y z;qU_+g42NTHZ?0|Gaa!zKKnb1{XLv>F{{}=+NYzaLw@IYF{amGQ<{>QZ#MB)O|Y# zFXL;ek@#ITk%^KJhfx*P9Bpb}5?ik@m|HhM_Z~gwYLp+@=2CwCbmBMRr(@#Vd7dsF z6`ks5)dda~EuEL#|pq!-r z)~MU%WkkP1diQa0n4(7HWa}`w#MRg--+f!$ggf^&tINNZy^%-8Ym;F!nJaBo zW*0Zxlk{f`y!#b8&L((D{^;S&!HrW6_BT3nb@>*o?#SH|0j%6jiiHctfQ$zco7-fl7tPz$^ zy0OxTY+|8N)w(1$v4%w~f^JGOD!5F1f*~I@2s+0edstVYIk$HmTzdG3(&2OE8e(;( zXe=n1Q;2G2U=*c7FDS@Mr>gJCV2<*)Js)V@r)*egRUMd3CM|>ajF_k@H$HXML%zc< zzbDH2^V;o)P9X203F)WP_d?w7la4HZao2ZrkM3=Zkwxv*3~S1&-ggUXaX-B%y>wd6 zULF$Dj@kc`q95aroWNG4ReKsy>OK8m7QoSmeyRKY$Hjr2IS=5`21;X9wkRp;KgK)s zNQRbMJ1GeXr7gH_j)}sdLR=r}qp_m#)=cGykCS5(OD2+6dLrZrKUDDFs-5ny` zB|U`n&<+yP-6`E5(kURIv>+iO=NI1jD&_BPe3j1~kb5F=Fgx5&t%F$3T+tbf z?681ab1ml&H|k{W^bMGWl5Smc^S$7&eWlV-7giCjJs=M%M_!LO4i}|y^xid|uilFc z$Ah-x`;*@(h-N<-3vGAq%^c)=mAtPsI?ukO`DJ(0*xm%muvK=8n>?O8?c1GsQ<275 zDHmMclnyngJlnYY%2*5k56@OCMBd3M;S<*$qf-qUH3Cl#pr#C`rtL{xT!qa7umEHUe;MkN8AB1pjIR znUTDC*!j6=l{LI7btB2-Y51)wD!Zd&Ra{IjyRDK_^j#_##o@(Y)T5C*4{0`j?PHSF zr=XcYMe9U*>eT+oyAME!d45|KT=G?VABb15F>J>uL zzNS%3ZZ#jxK8an+u-127R8U}gOj<+PJ%y29^zM=@zO$A~-$Q&faBoInsZz+vS2Xc~ zw=jpKagIATk1~xjP_Z7h!HI^kX0*xS$%f)0V<25t#rVPNZnE=!iF(^(7yh6ei)w*( zVg0CRqzGOBr-Ae1>p{FE%duk>@IH&fbucP;JaI4H?9f`K4;{qto&9=DBUAx0GMe^~ z%~oW@Nse?ngqyS0!oWRch;nv#znh8p0JR!@0;P&#!c}bp3Pd*BN9U!N6L&On&NGks z20AuY@VrwlyEceFCZ9NU@pM?twpFG_OogYl!&M@08=JEvc7XFB<9GX%( zI}?eAVv=IjA{34o>RC9yq)KuEQcg>AtPPuM;LbnfqnQBt0+|wYAgm6J4Rw3=^ziez zB)*lMG8WRFb37r#6548Tt9yh5p&wVcim^aRc`P?lRm75a|1f>XW6b(`fEwGB#szh} zN<<7l}Pg-@`ccVuQcp=@LVwx(4-QEI0Wx{4G%YLvsJ%~?)U(qUgzmRhLPD;)&J%@ zzh|IXhrn>bp{Aa|u>u))9d{F|r-SFr>3_n#EZ>eZSCXpimMO=ohv?lf|A4oOj_nAx zWv*q6953PmQVti391+4o_;)$fxCOp#QfkXIs(y7#gM(1g5iUz+*e2ggLT|dxXDdo$ zTx4!>1)#1m7`uy5ff4wq@ELjqbCs>~GJ?v%{?E#Jj^U46ADnD;-fDe8mp7svb}C`v zNnlLCNswXTD{ zeS^Sxm8&scSswLeo_qKIXZO2I@)pfRZ@vCx}hY?ATLMt1V7I zQh4F$qw{>;VCs)4sc#q%HG&o#J70s1Ra^!6lAno~ABlpAgwgiU`wfm&PH#OO;B6=0 zYj2bXIZhIHhiOd*Qb^<^zs#=PkFnu{Uk7e|7BzQ<_RP_Ey`kZopQ9AmOK(f3mnBLb`$y~KR?NU%al~n6YzM(xhxIJ#9NXo0L9yG0u%hL zvMY{@Eg4f^wlkwR%KI8T36o%+PJR(_le5`ud$>r5o< zg&Kw?QH)kYC7C>50w)C1ID#$_Q%ogpqA3B~wmR6|9DXxp5KBgtfGHq`Plb7;spx<| z_dLND!UYyx2=OME%PcC}>ndMJhUyEk`Wf{55-u-hnoP5F>*-81lBj81>!d334DwwG zU_-4)LXXlV`qqHCrTo9UyQ))^hIS-GEhs)vy5Z9hiAvq(wVFI|f|( zaiSTC8&z=Kq$1*7kzM;2rAy%$hzpI;iX0ofVKdz#h zj;;dGCUR*d_twj|jf>ULKhv*JecX2|T$iel{p%pa{SE!d{V{ShLW^82hr4QrH{W0+ zJ=Gf3C|t?Zu9J0*zKX-E8?kM5qo)DmmJXRhh;K8fmzi5|#UJnrv{ zQWlHcQ$`A0U}N23Z3x_W5Mmc)H?Ixoh;gI*Q-b4wV+D7M%H9lkkx?gCX{>=kn8dSs zz|+v%;x#3Y*G@;I0}l0o|CgQTLnR=Zw$$lOM4H=>3?SA_yJI?Xjx?BhX>8|rkdr9$ zf!x-I(ecj+2qWH6q<&h-$&sJ9ZBVBqPMTn4v2`lj0j}BM@zhx}Y-^ngCH9jPYGup& zb#A{AerajJ?NDdotT9wD4o^hermZN?^nuaiiIZbs_Mm5mYR3-6QcToHo^cGORX0YL zBe%bSaRdS5!p(~v_jp^`j+#WV6fbw@ans`~tDP$}yfUjrNB5T&-A0T(MjHUA-hp)T zJ*+yaxiG*hp6Q;8ef6hy#`#Ic^!q;r`&6P?C>97aqwN;7G!z=h3TD9XNnrF^kFX6; zJ%*U>um3J7`RPlH63}h1OShBMPZLfNE&#MIneOkn>fcV;>P^`qQjnX%N4)zAJbCFhqjdzU0OQP89d&O2q*4>-toVMBx>Uj7^#pCw$0g56U znsOomEhFF0PpQFJEbmwvR1x3B|KTYf;)_;5W>f$%p0KjAiS&O!!%Vm_(k6P_JPzZd zm(C+4>Ub21vunfLW5II5P1=q4MrzKnEK2Y!Cg8iH5pfr9=W{o{HOP@*Q+_K>7X+=@ zr{!u&@vK>`^$062F)(SbY*+qgcC)iW7#?a5BDfJocSI*A?KmX`E8+yG=Cal&&*4<+1(~5^7DWgtu z>|kT0uec%}_XykmnSjIv2<{R<7Er>5+PT;*Lr!Im^2ouYRuBVN@)XQnnE z`AWU8ds8mse`|NKor$L#`6$1N20T%SUe8CZDY2l9OBEcwmU9b5pZtj~SuQHbQt*E| z8jCmDpoeYxC!bRP{ym;S&EGJOP6n^?BiWg1fok~ml!{1ToU^P7HOhgM;IK~vMwy>o zWDO$?b6JN&5ZjR(J_;2(u~Fw0RRH*d4d*cDT?TNy0Xkt)#ENFu%3lH?0|hHvkA`@r z-O!qdUWX3Sb%D=RfuPc3$n(J%X#ueVjU@(Xh1s>hd3}=kjY14GAeW7RnDkYqKuttu z0ggt18xTn)u3=NZzAyn(1I$6w?#y0(o-vTw`e5hyWQs=z2WEpLd+F%}dn!`UG}?Vu zaku;XN2}&C0Rp!3FLYQ&^kY~Mm1E`8EC3&5ee-kD_kBr&EUCy}yyx&^(#>Y015HJ+ z3TaPFsxN->$HZxCJ6KIYk2BB8<=TcLWhRLztcetfY_uZY<7AL2$Y-J2Po<7+&wf~o;Ic%Yvzuc*^1tLQ z!J4N%dPWq&-7tu>R#U`9*3~HM8|WFio;|==?WD!m9=<3yKKHYRc6i`{eUqF8dyCb- zG=AIik2wjkvr!rU-7vvYYHI}2()UO4uxaaKvZ~u1OI!7<0J&W+Lc9I+_wp{tSAMU@ zb6MFe)8$L&q7E*1V4KL9RX7&71*{uXzM*)mo71Ouw~ArvaCEgxq^_%b(1g(Nj0LH1 zF2C2rVB&7nFfqKtK_JgJZXm2(?Z=iqYDH5&r&a zO_(V~QqTLWJ#d=tL2YBTECC({>NHh$)o5>Q`LA!^eEVH`Be${26s78PIoy93QD7hZ zH^)Nru=E<88Ty%TM|6lLbGicu%hd$vYub8=Tv>O?mh!UD8i3W3^SQLoytV^t&|dKz zC`}Ctufft2EY!SD9Hc1facn58^T^gwG|0rE>4SsI(`{6-q9Olk>)}Wn9L3pntBm}d z`unzT+!0&m$MM9epXXs7i$4Ex`&&;m7}6eRzx%*u|43mf&1Un8=-$i`uDV^5`mpfq zj)YV^*~|2H-hxTa;{%hRjr)zG&JTLv&Y+6vsV8WAn4<7avmJ;;8F?Jd` zE3{Z5Uhvenawm4iH-|RDj7CurX)rA_hj0m(?aJ@7EV_>V&4VwVi!V`is(2nw!SX36D1&Ne8$ zCL6d1675HO6J^3w?}|gX#!~ib3!I2NomMd|@N$o&sGV~xZhrF`ss%b><)hTK<<~TY zzS2bjo!Ibg;%5>(&jiWK$F!Dj@aUKlWs=9A^(b>Rt*9y9ZnzdwX`t_K-s$w{t%l5M z=QApQLK%)=(US56an24CFcJ)tXhyP-5ScWe;0Av?-76If#|4WrtbrK^s4!up&rj`} zV__1sq70&AW%NW;MiR}-TrFl%793D*iHl?>T4qSwn3q2JAsI}ikL@}2xs^KDkoHrJRfhT{62{)jw>EF zY9>PF=!Iph%oRHJMmh`a8h|F=zei3>rla&>cxb|m`k29Mugc&eY|&bwq)=9n)L*a7wtE&DN`yc zx!aOF9mrM2?L%<(knQu$4V+DOXTV$VxxeSh#s%uEBzMXDRI#k z;qT!Fl_2(G0?7Sq29?%1gnS#?^J){<+hMA4s@_TxD((ig|Fu6db-q%Q@b2GyCIo(2 z$RAyoFu~*~i6btowEz+S(NR}j8j*%)Z$T=1haSgnNqB8R4d`YzRIfe!##Z+_!kgGi z+c3z(jqFWhh zyG5RvZ5p+o%~EtEh0&Qp`F>oETvvP*woEID+fC|^bf*AI5sG#7C%SfSF?MfN=GMF~euJ-A}8m}37J~Lnvo;)eqo#E3? zW8Gw6ab;;L1x8;YAluboAEmPkdOFFLW+kpt!5tpq#w_VWdniEwx zRePPT4S;G*>fv}EHp}S@Z(@}U6qqnJ%tW5iY*=pCbQoIqHS2q7MQRn5qY&)VPQ zSVpbAJ2B_r>HDKGjRjtE`l4Fb`FyEAO1ld<-+X^5_Wd<9@{BbvRJ?GApB2hjUyk|P z4b!@p2eY2wv0@j;@%*L?Y$~?$UX%zrnv;z3YP37;F(`7^HAQQTSaO6%qMO0;vsjIdh3mu&vBh5gO zi>?AO#)(6MElITA-TkH1U3Ip99k(gf7B^vlaip(kf-fgu{XM*O!`$~}TcY|)o*(&M zu?~95bvRaJ^+>`5{s=2`*~3Z4q$^hqFi|Mrt3BzkJ*9QU|0|3kesXUZv~n~x5<2EcX4)Iu797Ln*nK6 zxvEvFtsZAJVLlm3cgVli{chwloUNStN__olxcV(6)hDeeW#bf70%*A(eIX@_Jr18; z4Kibm8TW-F<+`5vF7VVdYT`i1Q;R{{5GJRDX`b;2stsXX?X@;4y+T2BKyW}hXAmt5 zsvA1By`tZy&IQ5eC-;7+RJ1hNe1~Bk%JJjV(0-=tX9^5QA|kYrd&&AZV4mvzCvJ?M z_A3#1xc!56`?wkh=SOwn28-FN0L2B?1sI0tXmOX_E1z#Sr|nlK8urC)HBxRN&=7_* z@tKZs?p0W6oJWpl^HAI3V75ZY>!OOO$Gv`H0w1GSuUGwh?2Cb!(2&|fRu{R=jw0LC z!g&@Lv-ufJn!oI*5HKUTa3s#Aw0#aI_WPk1pK1&^Zk881zEtOV0Ch7L8(ufh+-F+C z*@jsAi?E%eB;6~_oM(p%&NZun&K=cy2>TTf+LP?_@P5)7AyD-pNZqSJ}b6TgGzwB!~wm|4-igNci+dn>Eb!#pl5`B z_F&8fSmtziE{|t~I`Wj%PLYfh42#^}{wt`svT9Y0t);9Jk+29PeR=t4c@l-vDk##D z3}n{|(=ajI>B0ZLKq|I)p%{5yS_wJ?B-9o9MmK+Y!)QYVor&C`%R4Sz2Ur1ed7M zx?z-XQq3(b&VctC^4X!E4niBAKV$c?>m6U%g>U z?Mlhs?s}^>|A!){sI0=$Z6zRg*j=Xc@Na&3NbIkpN`TRQT+MgYdVjo*QjWBMI!nHR z{O1cKD0%#ATWDiE5Hc@gby{W7Gg4o?eJ|~{xdF6MQWcn9R@&5o`>xQZ3kPUNuh4( z@XopMrR9hEqYmhe;A_DPXUndE8hcmMrZ@}LW*_t0TfPS&E(Ep+qo~@x_RZTm(Zh`k zXXDJ4o>*VV?Q*uU>_&is%z@vU6|Ay$!yO_vI{=j7OM<6Z;lAFDP<%h?!;S4LfLqHLDWx)q~vYgIV=4tKB?guWD<6l(RzY%k~VDh4y$bSOgg*mYHx5cdQb{A`ZVL znqGUeJO2a4VO0CQweSJnGC~o@TSmw=|W4w(K+@DPr{#|)g@tKhZ~L{ z!*jY9-18ctqB@1n3V-L^u#L)sfA!l{4WEP+O>eDJMXCIBn|qWV{$YQDE8k{R7N_Tp z$7Oiy_8bVJMHAgGMF$XsEQ~EB-K`L;`uFcQ&f>+2)=l6wTb@Jk^6%82-&mU2M?}+9T ziV*TBR@y%{13Ds8CVUtcEVtIxZ3k09;PV%EUO;3CPI6$w2fZm|bERfA;bNSX z82RC9rb0Q_rf|3aiWA~}!zz3K5oGrp*h-gU>ai7(7}077S|o+1-v3uLoHmr2 zKP8wZsqbitBIyfv{9^*JHH>VwrU;a;bSJtb3l7k@^Yi2ws+1dyM>6dEC`}caXRPzNk4 z<$R?sI9$&@cLz*=zbS{$h)m`1nOZ-0Hn*MVE@=pT^hfu*N+zn3a2mu>3^wwKY9EfW zpbCA#?{P17^7C>Q=oD5c>@CF8`4hls?&q)I+cDW&loG;e;v|&%~gziG_~Pt*-XENT7c;NLX^lh z0S`QjMcDjHcC;IX3K+n{IJS_51mK@C)t-qKj4VGHXi203ZCs47GlxECeP8Z(Tbf%2 z+qB71%q2SxI*vL{a_qUq-Sj(R$p<00Wfk{us|Bf(xDo!6xtMRQlvj~yVCBiGWo?;8 zPQf$ygh}*XmCS{oCXqKmEdzTambCA$`(MPKNZ%-5Sip+9)M&p$hID!H0!Jr}!b=a0 z>-kmm0ukDR78SSU*L|<_l-W^Th+ZoX(yfbQ-ZR()uJCx3VC#fFc}fGzWzv!pt48m0K5co*)=oM z2S!h-zCf>At2Fi&-whtP?|+Ga2fgg!8Mvh&S!r#*>gcIa{@&u$z5@H4&oMA9t?0IC z-Nk+8sw1tJNTM8!c_##UAbRs{! zuS?@^ktyDIb?n2PI%lROr*P@R;E#so^)IHJzR(B>8ox49730B*d;y)$fz1P2{Z$cU zQH6i4mDsKGa57pxrHhD&i<2E#@s(;I*p*2fGK~pi_%98Wa7*&Opo;nPO19&XE+z-4 z?fF6RaPe_|&`64rhsGbxkh`Jv{RVZi(B@DE>zG-jp|ZDl8`U0H{Imq^%TA{TpOJ$3 zQxmwaNd17bpAWo+tSaP)VACU^xgKJtv$YD7o z+Gog%>KxE3-MWw5O=ReyH!CWF$JAJNHfA67h70U0_zpRq3`ZJcw7XdUfzNWF9iyU} z+K-e^uRKrC5Xfk>s-AGsZ#m+8-#!g-hyedkKCQFi-IUFA)khui3lAmCUd&u~0|rPZ z_FNxRgd+YD%$0;YUEo<5&P-*^K39@$_5_a)+4XBowZHD>5+aPW&16-lUn}zIC1YCQ z&|25D_Zy}<*9729d2#A3@CWYDrPBvUfhjQTA1?|go|h8Du7AGRxtq8LUQ<Nj$$3Zk9Xxrb}3kP>#e*m|1*|(28`66$;JV$!@_qZ4hn} z1qw6ZqM9vKFxSAnk545a3$RlBtHNQjxg5A?Ilt}LKv6;QCz81{uc3&A|H8bqj!T{x zd)QHok!{FMQ9&qq#PtnU?*{vdIt_+9Ryu*h(3z_%KBi>bL`mC=cb(c|OlKUjdRw(f zlivcsS&Nx#)1HT9GZQ4!7(;at>pv!|MgL`LX<$|3LlHe0=;{4YZdO&$S9Y5YH=RY8 zbG!@B*$?%rtxIA5|EM3!6dY-AN>z~BtCvVmO_YgW(ng_lXO>CQ#A1YVui>by(kRi+ z6rIR2xV`s_dz{#UoL<3aEhj_VY9wXrL8fwzg*C0pl|^9{t_njwe`uxa_0g z-GXcqxbjY0bo@6Y8LP^NoBK&(_#tK?|l;nrIfEshiY;|B$!B{1;6%he?K*q;e zOE*Y26pt0>I5KZ)hRDg!pGMvwh}uGb3hr@4yCVO^D%q6lLT$b+cWUEUYYKF%0}Nv$ z7t1eg+0VXIH4b^mUJe6x3%WCL_uvYEdmdBj7F3igtwno6%12-TY_@$vE97tg@NtHA z_%=LpZVkRD{MQ(!r2Zh;*uYZqoU_-wJRQ7)0CU5%m0}CoIdUU!=t+rU zO41Lep2n904{ExIUE#k`f~#7m3KPWE<@6Un=n!4#?YM#3UP$TzcH(5QWq&=N>}1_s zv>`e|iyue3Sm`}P6`e|Ts;}g0Qw|OqkLtOY(yKe8vt$1$ipV*Hft&~r&Rt9Vw5_KXoY&eQ+w2A015P8W zm`2H$BrvaUXZhm!uIRjVs=e|hj}gMR%g^>x|^ z*ckZete*sFI-Wf70W4u`t1$5MwisG&nv_GSrDislAfcxut+b=P50{~mjb4CL;-gmm zqwQ9bC+h3!A!CBzP!9A&kvgU5dqfwMbHU4Do3q20qb5p0|4hK8%DZf^t3$wmS1oX6 zO3w=Yth%#j-)*rg0`B!!#l_k4d@0XY3MH@*EHSQ!hGT_M;8Hyj4px$&rxTVcW&NtfxE_N!Mw;J6aRP`r?~rw4)G&kA7#lGDHPJAs z^)a(PFd&VB9ldLcf|5}`Po?JZpDSr9e!53GcDTb>Y z&^5>w=PK=#g>6ir#7uz#wh6h>)Z%r?VYOl`mU!lL{=LLZr1{)~;roPG%a}~=bbEX4 z7w1=dJs>RTJK`WE-=X7j7wZmG!`~~^7##i%|qDFYO3}Fzs45rTBkNZBnFj_3APP;=J zIme%53c5V46uZW=iY!9v(>QFjJ@PDv>wnNe_M<(=s1mq#hy@9N?jepg`prASrNcZJ zK_T<=bq-6D{~4n%mhvsZIBbo#Dab~J5ARZjlkY1m7u z$?|dIp?&>ubEv6N-V4c-{x#o4$BcSy?nzXo@S&+G0MToQZW*{dSla3UFhymkr@Wmi z{1HfSa=)ziKsm>yebTmYX9hs0@HmNC#9iu6M!a$5K|X~8gUZ%8!4PTqvdu=W;??-t z@J)6DkJ@?T6)ceAza0-tML(6)p3w@XiH4T!WlB+w*o;i)F?;C)?4z+rY zb;IT!9fae4rr}jpq;i(;Mei_76&OM{a8C4E8<>X3{R-dJ!}J2;sn=AiE7{v9_GY|z z(xyA{_tx$6cMc6ig?aT+C{WCC$unj^N7wC|Q58%an~fBMM2k7gV_RD{o9~rI-KzmDtIv|@)%@su ztfpiz${=abUo$fH-EoA%HG}6>r14a_*_xmb27K(Rw9Po?@u`w1)>*34fGpQ}QhXYm zugxuXH&yewGmaCGvQ6wieR3ooKYyzE)x*i}+RGICZZd!HE_m9K z?7ODgojI)mCWrrDd0|55|0OTTPUt%ziU9oPmR;3E#z(+9!>WUGH1j896URHTA~-YL zJ-QiHT6ZWH*KrcC2zYfJUArLx2??;eTQJyPeg_0%v{L(PEJ0)nQ8C9=|Kwl5d?c@5 zdcB69g}B(y4>x8AX8a_4DeZP$?XG<`6Yhm0iQ26^XNzd@(Zcq2q`(bU3AE%D)_ji( zJJ=rOvTv-Z=YsVyL~PwZHa+d3g(;JI~V7fA{#_(>7i z!|BlykOFtg9&u`a+|>Q^0&T^3#=sJ@lFg&nc84OWb*=u%y@;m5+!H{?+x+^ZhL%iT#K9!t$9O;V<%cUu~7KxKJc<_FvRaOz-9G z`OF;v;$&UwF)xX7_517;!F((D3K0w37_8ghWv7eugeD%*FjH(rM=GUTc8wO5f^d#X zjou4AvPn8e1`K6@;@J()MHZ5r2K-B0*fDbv(iu|ghXvP5mu%(~xX-{`%N_s#WSUaC zpSybNQYe;z1_*dLfQ2IMMtK@}Q^`X~b3r4tV)NAxZRm(kYPowqG}>MP8TSHi7}LOe za=3^B%y^pcWsQeJfI3S81B&bvo3(yee|7y!Hgg;fHf#AQK^s9H9cz-4Uzrm7rN6@u zBS`t$X7et)hpq@_t(wuHk%M!NO&n`pT}}^xM~-69Vp+`-kRdl8u$vkQrve*-g>AFQ znmDf>`?KZ7i_gn(uHJ~nCm32Fn2!PkrV3*Do71|*k>Yb#6p{Yve|&EQ%q@WD zu9d^yWbDKnKZFSp%n42zDh#j-I>UQ}ARQr?^TbS5O?B(!bP#hhz^pe(0|}awmJ?fn z17=~_QIFaqc+5BL`cjxEw(zy0Q{`1<5n$G-4t;+3J6h`Owcggp62e`z_x^+z3b5y6 zhe$b>ax9@Zf7T!t^Rso#pK$RGZwy-5vKUW2;U+y?f!Row!QzLmKlK%G6kSd z6}Dfgd1v}L75-}aVi^y66B7!b@;LXGI)`uk0l0Yq)EVRWggN2m9Tdwh2u0ciN7KTDl@9H67a%H!$sAnBHj5@z*>#KUFW)j6FE&sb{h9%PC-mppPS2)1s zJU{t+$b;wXBX^6}KMUK+->{oAamk6F=1+Hr532h3Jg%4t#@Ao;Phk~4(k8@8NZMgF zzzUQ#Q#`CxV$(%p$??=$!^LF1Q;ML%m#~>jicgxqyr#l!z*$fH#<8+k+Ady7fOcGb z`8>rT^0_Bs)GWh&uSH!qACw{8g>RhW)@ys&tnf1iQ*V?fhxL2NWzQFbef7c2kjx@V;?b6VnnW5o}%6Q(`GV@$DAC*1Eh*d zP58&ZC^*z4B+_U2zwP%|ZDL-t$pcApqhs#_gC){M?f`ORsXa#xbZRj4PjgsBt^UQI zc}g~33|^c)P~y^OuB!mt8Ijw+N`e*7S2RtW9YzaE+jKv8cNAB)4vhedg`0|H-U6?c z9B|QXk5_8E&U}EOa)V1(&>~vax18m=<2l!EI}hhgDCp($%sHOKSO_7fw*ks z@D*sV6hIILHX7>Ag2XkHYSL;OvFPf};X-`kAad6+ywx47D?ig)wL0e_oET{l(rv+`z7z%-0HTW8am>1@d$7Touqcc!H}(+Xygy^4!u+8vDMh88wI>YfXtpiGU(^OBE*M z&q0*JyhF1zOxR1t;Hz$OX9Yi{vw`D6z!3_we3w zT+n5mXnCecR`VYsXZE{;{FJ6@*$>Q%=30+4gdAb0!HAbeJ4QQ)@#+V6E;|M3s!qZe zK0As1Dv=(`#9oO{IDJL|%IQcpg>o#yeYHcmyE9*ETzfHNu^q6@Ab6cv#_^cOV7r=! zpT94gIO9me1yGt_PrM~cs7oWvk#c3t zdX(?(zhFj{#svwwA0S$ItcK}wekt~*W@giK(+la|%DXUAN%MA1N^DC%mqn%8d)1#*buxITmU zyscJA{6#wVrPM1=2v8Oy07Oo=xCP=h+egJ#41B20{Q(af486USj9 zHi{>Z+p(o0u7#0*$zN-AX5HMWc>p9c()(R7QMqK4AamZWifSII`nwSb*lr|{YbzmD z={CiGqP=na9| z@b7=uB+S3zTHc1*F97qE9@J#3%&s<7$JzpzKCgkL>8E#wnQn=K={TK4 zd&*cMlC_QUho;*tEhjwt>!4T)4uQP{k>MLD$^iRC_NSI`_VLd+T$NSC)uIVrIJE*L z5=7gT>8c95~&`Y^-i6uLcw2QhXA!HBGq7`=)8+)d;Z1 zwXT9dBdsGV%JM9f#;7;4MtrSeK?7#XtLvtf6~Su%vJ(~g`^A3O-#=q;YN9r*!ni`( zOoY;Yqya4*g)ky=DtNvWO@;TYhO+_3)4`{wq*F;`*6)HhUJ1JXNB9N0|IiQ}63LS4 z!PnlkY2bK6%V z;OC>V+dC1DYn0i>^S8>1-*~+6$V)up3UQX#8viPmMRoAAksIIVybT@*nS(25)*A6J zA)-e61WE94p?p6JY#_PN_wGF8ioJUuHRxZYCnkV0&urx^A-GA;`4muS>1Av_#6Jg> zguk;*C~4Cn-&E4Y-+XLUw=N)a;ayUx7BZwEKSpZkmDvBbt=gb=ex-NXHbJ51yvw!2 z+`@R11Q@BRe=0mq$z@t9o5ceQoufD$-&FXQhERs2`v>|_cBEb)dLwAqh+EOJ6W7aN z6jtQfPJ7y))djY=3S9a0<8S>5wlSH%!kdqoPv*0$oO7RJn^%wuDx>VhaU|8cXG1() zXE*7wVynADr2Lm(ASM06-3o-6EKkvS!xKV2694xuH;RHk@TE)Ry&|kYNpGhp7|w2x z`@0l|wNKx3*&~u7$zr>!4bC29tqgiP94Dsz63qxdf6l4?n{eb?%P^prd)ehBWN_h| zVpV6dgmEXf+4FyVp$N|68bKccmZoEPn0Q81Afqd>%cF>*aU<0xV;N1k@~AavoK|8_ z)nbc+x1aP-is?%CP!dtYC@J4`Zl??@Hrmq961wqai=^Q0bgpSX7`t}->v%1#tTZgB zg323NimwOr$8Quj?tdpvWZ>d{B^u&~*l>t)wW-!CB4P!5WuG*+09HvG2)cf*p%iXg zV1tscXt}v87E&lu1~NdHHXW!p04{03GVmAX{2tBc+nbbu92Cktwc*!XX{t_9J0?Di zzBU_1oqC%kR^RzurgO}7T-!zp%1!u6=_4K(dx47=mPY^yZrRV9)c14ANoqLzG1L0b zc0NW5pJ%%ymfd6)RjjS6o_6<2tMdQz0<0EdX^V1%A4d$@ZfK^C+C5r%<^6C*t$I1& z1lmTuK@P2>tZWLY4QbRGrME{8LNb5^#T7j$q~t?cF|d#sLiL+2$pI!Lr9xrNQ43etIuL2$LnAWyTN-_~wPE z;ewgJFw<4&oFM6?#}4C;-H<4xrJwwH0q%|+c*!^ZR|i#fk;Jrl5KUd7mj?%Rs15Bg zh|ETf$c>XGw1>e>V=LI=DMn`L3~5Of(YUI35wdh9vy{(e>@GZPynTMWzMU~`@HO=- zQi-?_Hf(*$5(0~!^a$ySC$UV*KDxpAmLxhlG~M6kta6eIBphU__H&=0upX?v z?)=m7@7~7yiS-bcr*|k_GZNw|<6EZ^ z&i@bglx$D@WnKYapch$w(gQ%$FN|c`;;EtUa(i^_Y8;A*_vT0BeMY|~!Z-(PEk$?1 z{e6rF$ZdC^fm&X8$wkX|y0F`^>Bk)K5uv}|JQ)P`7=uI9hgH)Ij22;tOT$w zO7g~Wt2^Rw>%8H3pMXk5QKH^;fk}PxW?bmeh_93ee{=MkZxQJy6z&?p;{aeCC9b93 z39Fd+s|Y-VFaaBL1M0p!zsMc}zuv#QFomQud`A2HNEXIii(5a!#Ak+vU}$W};LwS- zS&ii{UP?EonUe;m&o8HPXks?>4V*QG3+8*Y;AI{lG=?A^_9hYU08nbDhb7R+p8XPC z!NGuf^xmbm32-HHB3ByqZV2uXU&}nSHhu{_Dk2>}sY+ z;^Cg2ZVeLDezmuiuL6!2o(`-25m;Nej4$G#I8IJaNFzJ2%0^?f%*Q)JcJTxs zp`jkR^B<6oEp^q$3g7bvx;QnjM1^a;g^aAES4agCr7rBP%UW{Q>+jlu%~6(e8w8tj zLTXBl)-wkK-xwX=YJ>n+BFrK$D+RaIeyL3oo1LjJuHCpcb|1}omhmNP#bR$}f1?!$ z>G>=abaX`Y=-2hps{MDMdXoc{rT>Smw~mVPjk-YT?i?DF?i3KDOHxX@yFt23qy|Kh zP66re5(b0;>27cY=^T^}?>qj!?_2BMb^qWWV6lexea<<1@3YT&Y*~?{m<+Qb$m?7; z!?%LeL&|_IBw2YjJ05BRmQX=-QAD{Xc`=rDgf6@>{IHqM@2!$2rpr&70(wZUd94${62v%Qc$SUl9UPiOY!Yb? zwpS3U$C$Q89ybe=Os&~k24E!PG?rv~!DMq}aj9r_F$)}`Ydy!yf4tRv5$kKjA(p3n8MH&x*p^7_=`r! zJ_D#VlXTy`WFc8mv)n7!VJx1pRQ>_j9+zT3ZTw9dGBmJ@et~AXw=E20CkbB1xpou+Jw%bb_`ya6NkfECF-`RyxeThy<8{=Ef1+K!Ait`FyX?NYQz3Xjn`pWZtgeHsNzD+jnTJB%TdEH8dmBT-2SpELjuQSDX z@Aw_&d*Kf-=rY?Xw7u!ScjjLg5)Z}L1PwGm;0flG7!XykwCcTp`tP#GdgRDN)3uWI zmDQVeMV7Cm_{ppXip#ENlzlov>9-BeK=BLP#(%y7#zbSN<7xoZ*jXCRbZ0_ecvQTQ zv+6OS*KVN1_fI=0x;(M(uLb0GZz=e^jxhx>&7=uST-1*55I+YDgjj)KbR{E*O8g5{ zPz;C#G;bEb4zlC_D4O0_8tLmp$tMGEGdlnLJpE@D@mAlcvQ8`&QY=eiz|59}1H=5f6RLWf;w#_}S#K7i@-wWI zat5AT(plGlFDTNQ-1!@%@C-eyLm3yiEX_=^FGBY{?sJ3idH8vWO?3?V+g<5wms`b* z*X^dEOUGo&r{8H9l)Kd6#!2PO&voA|J~6bR$YY>(x%|GpeLz~xm3+9j5e}?#z`9rP z^fikQl{k@$8LScx~}vH8+R z3KSV8u6@{ar>>hfz$ubx75dU8aY&gI1#$XQU!k~W zO%{s9tZzN@6>-_#Q3<~s(*$p7{@D9`r7wJdNaWDE-htR|%s!d2B-z$qF9z8UWW0*9@X8V{#uM!Ut*;jmVQeTwAL7$C5nHE?L3p2E2C<-ip|NUB* z=zOU8`u7?~>$9Eq+6-ph=Mm-Q7mh`%_m+&vl57D;Te522f7^S{%ioVn0AyHaqr8BL zbun!Tm|UJQ;ncZJfUU-BLdWv$f!6PC4Ks}hzE>OUPbW#&3xrjP4lpW*E}>sglQUnF zY$ie&!RRf6eoC}Ph(lpOU^C1A&XL%WxUS%Y_r)46sCB%}FN0o*B{pjoLM>aBL4PT2 z_d5;r{OzQ52x=xHk!L6nFj6P3>j-kRXB+UOgguYrgjsi!3WLn8Y|NW1rD=Syd*8!E z$%SY}HHG6E&q)JRvmde0`F-I$%wqCNeqJs~eHX4c5RQXElet~Ld$)Z1!)(l%$wtND zB$Ydep`V^2ts!}&`+|ER)v`u$aGKAbQrTqK7);4xjR~V^ zwNEX$1JpG1Vz|0T?9A{#i2)@y!OPFBVVw$4@)*6PdnFXn$e26X)f1m^>y~mRpd^my zX=oEyq4+hWJj9(`#ge{ACxi|wOZ>Urdy!GY3SRIbaC_Sv+u@q&AJua8=<$#FPjvKD zIed0ODtmc^UX4bf$_-2x+-*&WrHni3$QI=}2~G(8e;Hj4l?EqPtLMAE#mH#l(TD=K zl`#g2T&sORNMXr}`ow?~Yqgdh;W5eEirAeq!H&=zzAfiWIF8ZSgp`(u+=2+u{0`wf zH8MgrgK;-nzLQ~@Jwid<}H5p|NiM6E&(q18%r_;tsOu0 z(i20gvlJLI3jGmZodE!I3M*@0*Wa?g9?di}a5Vt{QgDVhv`nYpPmz*3lman&;92w_HlWg=k{t-6753ppSBG>klE7$5(C%9;p85# z1K@ZK<@VrxPcQG2<41Z%a`xmb3bu{3@V5S$?$oXIbMT0fMQB<}PvO8tDR53!z$O}N zJ^si-x7GrI%ONc9@V6$IvQCI4XwicXkFrA$QlV`5>D&mB zh3~x^$0vP&I+mW2gI9_qt>trGKQqXt;VZ3wX=F)A1=NI6>nVK| zPs@8iQbQcZ2Q52Q%vgRpu>wb%ALI}ot6`5_K>dN29)=6%B&!Q&G6Tx6JR}HwhnMc> z>vh##acK=08V)(BFOcK4o{sP*KeJI|KS8JX#oP|yp;mztFsgQ`ihC>77WU0g=y=HF z?jkVJ6s-GUrXp%Jax|pYru!p)Cupm3g@lI6Kiz$s<6#&!3xMUm_NFn%nUi=PZp_zi zD+Ax9!q>$Yb(cf7@#*?2Ko-bS$iVi}HZ7^%@pl(k`W#6wX{6;pVTV!vI{T9S@=|B5 zgE8CT{9Zek@0vcv;p{jm2avpfOuptZa9?~r@vI$B3~37(>nhr@4Hi6cJymMdo+avK zUWxlN;>vlKGz(@urg!~0i>ywWiv~DbG1dSW*!Za9YTTd~JoR0jDg#MA;$~m??+cI0 z7Zm=_fF}oZC+)Y@MDlrApCpUeJUO$15RHRIBgpO7dat7I*9#V}LbFghu%o`=5jPSS!tpHUzrdi^ zr5^C%gXq*ELT7Ji)A4Cq#drO3Gukhigs7V>kSv~U$rY{gUg29VaQ4p5r$&TWV-h^7N=IT?pGWT#jM4 zt3Wd%`VRz<+spgx8OMQsJSUb_Tp!7Br?HFf>gLC5XL|Z5LWc8Zv zq!>!V)4UJlly`URg)!v;qPJoh>ACAhFQ#z)%(^*g^k}KW`HQ`_lqUA8zP$g3tCwJ+ zG@@SG7GLR4#z%IlJby9bwEoi0#3~k?=P#K;0eI_RW!AYKX^hoQh!76CA~1czsYG0a zR7?ay{`K|S`>?~tc}Ef*8UQN~9Xu;EQ`oLTYvux4EsjFd`2>#Rr-g3oF0KbPFa3ll zE6Rm3;Ge~oV2ogRTy(r&nXwdonTeA}CnR zMa@-ytz#3g3k1r?YJ=II3iT@0&kc;nYp*RA>@1p2m207$1rAUt{HCv+6mdTq{hRua zKs}5H;Z>`o{aFz0WEE=$xTK z?W7)ZsR+4#S)o^Bkx1t9_uR`Rp}R^Dv@a$l$o z1hOXAaI}OE0C~F2yL+I8uv~rLGG5It7yWH_M@plKBhy_esuCvD{4ID8ZI%1b0##@zgUr`JJW!nfX_6xYu3SXcxlk*!uBz=W$~N)_0ugeIU}z2*a~{?nw)*V&vKsU2d$e?k(?B{x-w3 z9hVqEh;oH0iigv&ZV}ug0eF3l<|jJrLvTTaYYFg&E1kF;b*FaAT&g>)OI*v`0V#zm z-8+(`cz=efb(HFnZeVvcE!3N&Y6koDhtY#THp9E%u5^hq&MyK^*Vvw{o-Qaoa~2dI z47lg%53B|1+o*J165JHmvM>_PmBtSaV1%MtO_ZDe#dGB6dtUqo6e+dgU4BipR;&}H z`>=Y)KZ}}O&_7D}6VasPZ&Zo+^{wm1Bx{uh`u(P_b2xw**IZsf?+*#jN!0r@mGnX+ zLDyaJicI&lh=!{8W`uT!Ap;)i8XB#`+3)TU-rh&FJO4GHv zNEN8b?*56(v*oyFemp|$7$Ed}{^{@U8||8MD?dSf;+=&!$F9BEdkhV%5xWN+G(6^D zlG;|#MP?<{dsSqENkqHTAy^av7L!v>Ge4lEqguq>HHiLSyBR}?k-j-1XLaVjM>;7L z!K9qJ>!8tR%998BgVZx6Cs%E zm%ypVURUMGbUpvCh*z{=0VX0$Y$=qZ4>uo0qR1l+KSz+K!|KeJfJGFjTK3;+DTKoG zbX}$608>P{V3>u44Ow@nYvg%g3K4et%w$hFBuz( zg#bJ9^T50F1$QPQTTSI{PimNe%+e|p_?x3 z-z^MQ6Do}1&9&Wf} zBZdT8*fMENj*Tr^2Jh5tZHfz@dP`5*-`OW@bL3fiqE0VC$#b5;6CYoF%rm-fM-nqv zG6G69z^Wbe^z|=lyp|a;`+G#%OlI7?cg8ppC1Mfha-(bP9c~$t9mW@ky(JSgY5+?I z;hV^OdTElzK}Xxq5$6O_MrGRM1L1y4iTP&;5$YTUj5*BD#f+HBGQBvb<$BT}a`B43 zEZo0un7T4;zq6P|TzeGVFj!Ra?D#(h`%iS_F&Yh$?5O0@f!HQFS}`}1g{MB1HBW&J zoD!JDOQD*xW0feb*>>}-D{w!0|`n26$eJ|PQ57DuuXORM>K zskMG8meZ5s@Z#~Lg}V8`TUIJAP1ib*D$}_{za}R}Rz+w;jUFU)e5vbs#|f}b?t(YK zus9J_3uw_+BkNRR&nwszyW1I>7A&oz(aJ#jL;qu93m^6b%11~z63_-@gc*noUe;x9 zT~wa4P}7uDeDo6F#{(v8mqUHWKmChl3j+W<{S1=g6!_q1{(x2_Qj5Gw7Vso}K7Hw( zA!=8iPRpz4en}~Au>lzDRmdF7((-gH!&O026SBohFE9BaXJ?v5vtdEZTjF2C7b7nQ zemHe4W3eoGkO%DWMZK1B6Nt6n0(t$D9zt2eUg4RfrJRrKHjyi? z@?1zV^fEDOR71UgFJwq(fF33DW%eESuNybQIUwqJm%{%(Xi4vvqy|ZM)6{3@GJs(q+I{yGCWmVrx8a{bp*kFzR{>7!C z_gzJ=*n8n0(7g@fhvN}63pP1$*U+|Z>({)DdjUt-e%KL>BTH=x2WCV^+$2f{@E}CI z99F2Zu%7`7>Sfn*hCjan*c<1GsYGR$tH^&>417i>BL=P*5JInH#rZaNV^4;YfKt@2 z5A0$>R$}6(1@7ZuSUt3>y8CtBcah!2hI=c|F0=^s_&cn zCjS(s6#tur7trNa+J%nGD=Rtkd}dyP8Kk97*dJ!TUTusDO-lZ^xWQD~XG88dEoXE; zt0CGZE_s>8moKK21BI>Sc>$WQt|R<1PE_E z;}DXv@vIy$kF$pn+OK`}A|<^3J5mc6DBHnY>ZT~%LIPE#bC1OSyuhP#LG&Yi*xQhY zSitfBI<^zSDa^qAA<$4DGA`PikeGFY$gXwW;>Q!XCV%z6fYsNpdzeK| zlM&}PokF^=uFVW?amg@vJqi032|rdarxxCJzVn}J%G`V(PuV@uNG5yawl%H!%v9 z=wY`(X2J!glpX<@vX!2OARNOG^PW>UY}q0~`rm1|jY60W+}LB85o#AwG9%~t81jPk z{kYsC>y}3c^oKilYsQwwk>A{yBIn9S7>p6d7!Qw%)}WoUF?+*y77o%f99Hckjcjs&izucb38{%^8luORL!2;_xWMveekFcS^eLHyAz)n$iK}sGI7Rjz1klc z89@gEQS6}~m+$C!&mGC6Cqx`b-jS6#=QA{7Gjf__xp=hbzpR^|;%w}{d6V>F!?}L< zqZ)5uX?uIXeY4YSkVMa_EG{K4v+s|Bf@AiFpI5{~I8rZ#r)5DV8{=+C@KHV3Pi#^AnOVW0zr}VsO4+&ddjbXI=tuOY5 z2;JnI{b;apURwc^X+u-5k#j}xy^D4hXERNf;C#d-V~IXRT4MrYM8_|t8RNeZ9Rv@4 zzwP>ma?afZQ0YZ&#e!!CuTQKO=`nRKf&E*2q4IrIRO6o=31%fXGFbQjm0Izuu+BpB zV(vmRcA-o>W+Fl>?pKf~Kv5>~henom8uwLddE)V}gPS7yFf^FfbW$c6ZV!qoU3CGI z!Mt{^qmsV8(C3WE98&Ds(?lBhpLhS`I}-*kcQ)XFML?;`wss6bU`p&~4g}={veitM z*i4D&F2i5GoG?F%OtFei03A;>Yd6|WeuM^1ZX-La#ozW$ey z5mf@|`?L1qKWd`uKBQc)tIz%|B(E)~s$6`uifUq>Kp{ZR$K1h$9tXb|mJbW@U*yQC z8>qJm$xU$*)I=sgUBRO#;>MS!n8>r{0xYmd-+2xDKgjA0!>M4=5Ddl`!_16Q_&eQd zk&TpxS#%CM`!nyv9lJ-?>F*g1T1~$H992Cf2)i@EPkL~u{1%AsQ_x=^RAo1Ze82d) ztr-dC$UMvO($N6M36v3@UyZsgDNDWJ;Sar8);XKQKXVg@Oz3*Yp^e|D5?dTJA#G%K zp?xSl+JOCPFt5sF+d7ng>?d0s2hbVI6seob|JMVsC~8RGQ3FvTAKTvxV_hp+tmKLT z{Wu<2Y*Z>y8|#~Es7y}ktA7=-l;amIn8Xs-GZrQ6>kawIu}2PU%(SE^nRepois`kC z&|`Uu1*?+R?tj*r|0wbDpvFo~aWtyD7e5pYH!DH_nH}jdDL@aIi-?P)zF$r9E_pwR zI+u%pA1(`%i6+D*7!V@@eY|OW4K8EO7Y4)r&DCj@j*Pl@?rp4q(&*?;dkM5!V+; z{?*`kRwW66JKlfpM?I7!} zFkpTfNZp>M{~U^TWmy#zwH2;YPd~#~eR#vW7{BcQ(}IeR%K^){r&21x_;UYtluQ1P zenoOMpR}0!r#uPu>i>U^sqdc}QNBeKqSh11Aw?Sf$=`c9v(TtdbxhII;3^Vgv+Vpw zeA+#o!N-+0AjuSKz%wF}f zvQLn|e`+;3QzaNjZP0`M2bJ9c+-MB5hwUH&?}H@?R2U{f@y1Q?OK*-LS^p`JxGOTZ z2(YrwbM7MV9EA51;|Vk=)I|l#ilb>#lZ?^UJ_7AlO8=wovC}|~`sPaWyE0VH$aA0U zy4NLh%v+r+-?L^D6-EPc7pK+GT_O-Z zE4IGMlca+<;1#r%QB$MddL;@_n!HY%i}G+FMOE6D_!RgP1X|EvcN zt4{Wnkq5S_HG;J@Do#rqgm7}cgMXGk8ZmpV28W1Klph*E_ZOx}hK<7Kd<8kTGn)^ULB~JH&*)(4 zeQ!{btMXh&HzzK_fZPYzmD&5mxbO>yhF9Fj-iT+S%3D4EU$X;4%0Akyrs$ z)4t|xLFAjYG~=)^b`5fVO286qF^VlDuO4A8vONogeb4^>XMFEfr;1BDXm07lY$hblt^9Wyh zvv)hy5Xz7hZQ>H03Mxh13&4bMja0a5q<`gDP%BIh^aVdC#_SYtPW&++=V*aa;b*7t zhmk{~zklLo0J@4R^MBb8)!5cQ0ShsZbL~F*8W5+acli^D&_OY-pH-&4NzoXd{Azom z+ng;vTWD5<@0c--(`*FFYjyl+P=%7M(VQi?+bh5940OkWvJwwZ1;e*ic>-$ObtWo> z@46NH4rB2#rqRDEtvJ0>^KYo~rTmH^?7s~k>n1%)ySfYduS8SEjzz7ZL!v5Us6S2E zG{#R3XWDrJ`wEmb);PQjj>+zV*8(x4##lLVBV#D%T=a-MS)t-_U9*P)0?UOzIQl&P z`FEQx?Xu*GJSHj^$=#H)U{7Etwom`+MY|u2Y#WGbHC}k_hH(AsdeR3^Q>8UogEQ-%xN^*7bQU)v=Hi(m^M?Hr5;l)aLFBC zd@#4=bfK_Xm=ucyPWWy0m)Oip&UT$Lg6wLj7f1}ghJNT1zxun} zb#*Ov5cGGeZqoH*sf=zSdvo(=o+#D#Z4C6=oA}%sL8yFerfAOD8c!7?p9XP{h?Btk z6}7nvQ&^p}IYL}EZ$fMia}jfd)PE4e>SANXyHQr7eh?6^_6acS8pF8U+~#aY zCp$%p8t5!k`@*TK6?4rDM$F`YQfmM$5MPF0%qS!3x$;4pv(&J2y#xtLjW$Xl(@kW9 z9y#R!>s-Z;s#JfKg6;=deiDQk?_SLUn{dT<2{IGXsBJa_aK+7$hnQHAPnicIk}$O1 zDWNp5Vz^LzI-7fSjhF9INv|KaSOsp7N4R56Kq;{yX9y7!(exrjR}3164-5K=q0|*E-uy z*4?$pEv8y=W*mLzgmfQ6T{d9AD-{*agd+9C#?`*cr`BN_ZE<^AZeEa%f&v)i&_z$B zLSq8+@=%XmD@E|h=E)LwdlCPl2}_}YYqkJgVU<`^CCeat@pJil!_I`|1VO5cj?m7{e4 zDD(&TXBWOn%r_Ongc$y>Z~uT=JEe^TS@DmVl8tg${ATTDgH1R zwny1;;HQN9MR(~i{Wy~?o1hDrFEgauzx+L*L^^~9IBrns+jn=kevH-LF=>~s!%N>s*vMv>eaj}lG zX1rYDKiUofAKdfykZK)J#@%}LT5ZdSZmxW3x(5{%zV83CxC(|ZTqyb9_zmE)J|n3| zcEoU(b=^C)XK9%|5`~P3b6srcC5(=@7dxW4Y+*kXelrYEi~qX8usZ&F8m-xTN7zZ* zam{jbKR|A=xdpy%nr++ObgSc1?x<5m<-f`wW-?tObWpZZAY=yY%K~!jC>Z_ACG$RX zZc&d_M0V3hfvUc_JdOum^7cc#6kaHl zk_u{V+FB+RTD#D+ZO=G-$m6R z6C4~rgq}!#mf0D=O>J@9C<7#sU9DfknIK?0Cm1_Dzez&YI>edO2HzS4>V5~O-87== zML9s(TIPo~4GJva$9Qu9gkzbbF0Y+&jsA^Vsf#!f4$Qca9m8VOhesl3zFHL1tQrM} z>}>iu!{XLjAtKDVpECsu8}G;mMY$*?zNyV{wqId|)jEEzmTee&{p(g&BmM=xBtG|; z4-apfUiBOZSDazXS`Mo4vj&4qp$bpF(RJ@gd!g{BL~Kpz06RC1E_pGET5Lu3jBIt| zpT(m;p&!XmzC}KRp+YPY695vx?ntg^RkhD+0y>Hae_LZbY~R!qQ-guLs&S-(?n=MV zcUdr2KaROKbj~<~pT;GwyGbJpVE|6GDYC($R)aF()U#agU?Thj6B?esMb)zCPYLX} z&D8P0@g$^?0?6IUo2ejDIsS8|{3-iF^kT*O=>ZIdMD%7dva?-Rs%l`?6Lbdq z(rL(}6Th+b6D2RqU%nQRzugO35^!1Rz z9{Xr9S|+zwUVOm-X%L=cx}mwnh^#);b`K`!)Q;9cjnDv$T&h0v=WCh4}&QvQt5}i^R8T0y=Z~stsFT2Wh!4 z_jgBb^Z@A=n6R)~1<%@z31;HBerV^4peYV+G%Dl#Jk8<7aVAch$67n7CGZz%f@R5r z99zRZ<}hN5`QTd$R}pKfcroIjB#3p9?=Wp}*r0nFhgOI&%HVH#URRG@K_oC& zo9j=gsoT-A$-0fcZ7!QvbDu7&JHgMg=oVtfz*Ok2Y+#kP75@S(OhM6r$=}X~=${kW zw3W+a<{D{(4y_v(enPb2c1-&;E~|kK&U}VRrG^~{CI~BV(cr?!IiKgm^YbKwiU}p~ zlo&#_Ne1o7+T^?#af+BGB}yD0YXLEU-H?WK(l@?^z6ZEohL=YFMdke*YY(Gg$f~f* zsLzYLswbbn$934}>grn42$^ZMRqAtU`hGxqm%3?l@nz#|rK4|H-V`&-wNv}R)Z&-U z;wxY@I;hx$YmDU=o&pX#MCM6&#{BVp8m$j*_r~fjpUc!4v4=Goa!dp7yHnkz%CE$& z&vDqnkAJnSs_dsRE})7_J`t4-R7>tww=U7g7&+uq)~c};Bft$&W^c#H)cXRM)xFHj zAq6^tu57kL3kJ)dNJ)9e^l<%O8@RkYj8|7Sb!X~LVrzziv;EqS(@7359=#{%45#l@ z)SB-T6RAaxE>M!!Sbq5yeUX4@4S-l=gYTqcyPp`3IbtiS;XUhFQ5v;mDEa46+Qle9 z6s9v~&+#LruY)M1*#f9uc8p;_*l}294V-T(2Z+r^evDq%yekeWlUe*-B(u01@s8gX z4%A{jd#-VfX@wl%go|_eRHH~ewejP$+}Nny`Xu6b9Vbtvu_%q%gaKeFP+>bNL8OmV z)quTaao;=s(8ne2B`jCQ_vxmG+!oTy#t~|julElt$hKK~0PzML{`Le9mc6$`N8-HU zkq5c2d`sP_&_adFWuQaM>hm(R;z4Tm;$nU?>r(E}Xq|R~12;^_TJZEg-{NuZiMzpr0 zI=|!i$HPa5muqxpqx7$i>E>_=4i79fJy7 zC;>r(iEM#qm2Bz4*u(G(9-Tew3Y4Y8*I9FLk{{@r0*>ik?x7VgKJ0hi7Fky)E%9?k z@S%F31J85Jv@6`SLGNjloD`oI2UHg0ch@`kdfytPT(AP0!~thSJ^&N?oazd1hxMC& zm2e~1AQduTmurXV$Fop)hPu6Ue>nL^7wuI4EZ;1>Qtua&A{xTpz@^1tY?y|<1gDW0 z3|fv?nFOo|J;N}+!J+%Wz|U((hPs6Z&C#w-@d9l*?s`6cAU^8^??(DUgzVQS`&U4c z8G;K7T5x`ZX|99qf`lBTi~;q{sb~cVQRanQivO8HE{W--O5v6vI0d82U`pa&N_o!_3dU6 zGT+Sq^@yaE+PHJ;;t=9T+H71|Y^zXO)w)@2T)1t6GbddF zSDjYPA(sz$>|YxiUow!ck)d(pBpqymq^t9D$)k<#n6o8Y@C<=BP!Tuz($oTJ5t`b` z!%xATY5m@zQ*(Dsx+^TZr71RL5ugjYVQgEv9IS?rfW82P7;0wS-N(fAN>70^e+n03 ztn#Coq*~N*FhGi8DqAC3`X7PGUDcmM4;H9z4{5=P_LCw**T}Vjb}x_yaOA&2X>g5I zA$X@*vh2Djvq&@{y4B4{CwBWOo<$ZyC&F^+Q|dCVh+Dd95pi(fY}Rp!RyqJqWOnC{ zV9*oZ$F|Hvk1L17>OE28y5XuxuFy}C|yLI5X_|P zXW%03G=RPbPPEU6bV%ZWwi4mMx z3+YFNxHeXNV+{zRxjNcKbLpgIr5!-Qgfw6F| zzmm(+VIc`$m4tbb8T03Qk-xC2qDeo2l?KT5W~iVcSG_9>VDDr&z<4!x-z09#8((`o zCNnnB{_WkgcGgsM)OG_%x=wt2!LI#RE>V)!t+C|ipm+xB>RJ`Y4l0Y9-}U5x$ExPG z;xaKHRmuaZ#hLx5?Y81|#(p*iofjE&MLk1%zPwoXtcMXciu(09fz=Gya%`z?COK;k z+B=rmCFriyr>1(B`z6JQDHrd4a3D#R{$e?VK=;E`@YuEBrmKPrR>r$;hI$3=*IDHD zY$6kKk0wPV!2QItsQqY^0krf!^Id}?F{u{7ye1>ZK)*r$DJ!e#{jBlAk=tJX`N;pL^sVKU6F7S`}&v^HrspIv!+aVtQ$xES;IE!zcLQs zy*#i0C`mxu`U%AY)rO|!)WD(OpD56jLPBG>2L?Tb7axp1?L&pEQwj zq%A>Uwu9x;wDfS*Z{-ru2G7yrV zq3_*T+(i!xNnU^9e|2@`zZ$$c@oKu@&Tn^jMc*PnSZnCJ%*v0&hC}a*orYlJ$@l9= z(td;`pSyeSf-SC^3%ZW?4fl?pODrzs`1-Y-)E*ukUtC??#U|&#CjyG>op9`t`ZTo` zt0sXNKBVx}hIPxX0dIR(Og~H4XALieTXO=)f!o+(ffaF()>__HLahe7*=OdH3lo>X zE|m=Z_XlPG7EHLdcahkgeCd1=MG`DF+j3mBLefRp?%`LwK{9a7T_i|G`I`BUNuiXw z*Q6!g+SZySsjqgpr17I7z~DGxk*CB5KmpO0P@DqSy7}KHxN?bM* z)v0_4(ljePbHFzeo*|0C6{LJ~@{T?6gL{R_xmONGEc|V)lgk$7a?p!bW&6r#mrd*!R?y=L4O)L$oq~xLnU&Bq{Hy7p z;2#60G0*?~FAA~=0713G@AMqN(iFCN7oP0o%O9MKdBax+Is;2N3C+vKM#6%=z z)ek^dU2o~asIh>Xs=bUuv9Ih8Z)^cBNvUaT%=s%3qm25VSRmMy$=`PN#prTUkeX!( zxfc`kd0*BA%UWKI^kTjqD{z$<%fTi$SOcQp0219@X({lg(boge*P{28oh$w7i%SfhIV`B#ke?7h|C*3=zmUO3 zz_^a^a`T#QUycNxL1thujv3ZI$I6P193zvEvTG+v9yb`phPqYpH2hlu#-YP^aB4N@ zcj7!HFFYtVlqvbi?Mfj?ESDDo0UwjN;2TH!V*I7-{~c*a8MiQAH=V6(V+2&84%EW( zI8GRrnwNg5%d!Q$gp+7@5Ioyt=RTBMV*hqiv#`Sr*Fkx_HqSfSus62-|7jm zYHHP$wf#7J3=5yNIJv8$^S}KzJ$Rs%(&M;drIfFNsc;k@@9k2y!f^X_3NPXLlDY1D zc~>WjJKi8d={O$SO6-tSvHmF>jD1Z%;|os@)<^aFN_5_02F2zMya1G(D-z za>|L&fOrJo-XVyD4)}9oybmTu3_yL0?Lw9cmrw{^BCkdS$mK**^eGKsH0`-8$RB9OVZA%-OU8cpI=b+T6X<4!{Y9$M0tC~T&6lEWy zSK6Y1U%I|aJ3$4>^8B}(tk$BdYie6PHFemqIU|I|#riBOV&**7SG=R&GmWZWXv2Qz zvOaWy`A{!vjzfx{e7cVpx=7YsRriFz1)&jrrQHSQ88N-}of@+Iz1Le)Y^brxyqgT!)!EkMo;oh)VLU zSI{w8x`QtN!P++U{D+~82(^es{2nq|B@N;5Cx?nZdkXm56*j*?81Q(PW}t2z6li+O z)!))K5gTnaqZ!Zy!alh$H3tLdu~>J#uLgQYoD=zlwH9xqztU9v^0pE{+Bo8rTirw( z1otn`o~n7}SfKusPhPck)h}Go(K=WMG_NQ{v&nCLMsn^?DLe1HHXB!8P4An*%uDz} zO-!TYHNsBN8EvH4F!Qr|OGS_u9X*oqfq~CjvM%MqUJ|MLTYwbVA(m6pPCejG^XAp* zF^*{#B5d#Q%dVLO=84ImvTkMQV zlw{=7K;5#lL{-8qiaCKSMx;+I8A=a6!z+ZI8TopNQhkx52M+}I}S@CLL_KZ=vQ~yaV%fc^f+JamYJ`mW`+3-_~wW2B^ zffyU8Y;2HdvVCn$s z>yv8xuN{S{6(Auy(+beq`8yFJS9 zcx{k}PGaG5p}77qCt(k*;k0jps9Xw{!G4}q0!cIpEVhE|8}OHyR4|kpt0FLq?j~zZ z<_y0aXs?s@jJXb^HTX>=viZ0hKZHVA z!@TJ=kVfRM`=4Fse%UozqlRSRmae2`)w($#7(?W>9Of9R?Pllk=3U1do?mN9}gv&)T)1`@TjLA6IF-NwS%@5)U>d3&+8yZzb9rcoXFl?hx@uQucI22l^6lmyZh6 zx~|FzE~5AcS2?F8=yFKKv!{w-+cXWB$=KB6j^&lFe)m7gnGv1?Bv&B=V@Z;{|{DT!;{IB8^1Or~PIg8V?twEJ- ze5=P!Iblba4+0OqN0)la7Vjt5skrYXC@+0^muByNP7E!a&<<~LP%jBHWJ-5wdkENc zQVB)sz!(eZKnq{Ph&+eGJcNhlGM3!DGpZV%zUShv<>TDMO?zo(oI~(!+(~Vs`52;O z>GVH+IU##SDLbfv$?7tN$BYe#5GVVamE>NkYA(%MnBcc(s5z1Jm?`NZ<(9uxlF7jG zv@9S>h*-QA#K)2rs=^V9%9sC&W~x&+V~~=6fh#n%g}mW&?VLFkB;&tHDvSztl|Kbh ztYkU~kHo^-S#u2JA3uGN6#Er62<;O!vq8GAdbYYX!*j$tj{Nx ziB4dA7Z3b>oSm#qXofmHIzt0;6GC3R2(>z&WX+z#y(-6jl3~wnw^C8pjmLAjBk6YH z4CH{C!C1Me5rmZ~U7J!sc!{9|?ApikR081SKsz;jH9*Jz3wV@LqoLQnvuDFlY}{Oq zGYM$bUAs$u|9_}@%cv;7w{4glK)Q$S6p(HNq)WQPp^@%J36UCFq(czt?jC9Y=`Mkh zMp_h5>b>yyf9|#3rQbxZ+GiZG&s~N-s!wa)KaADp?p7>)GKljr$og^pQBjj=Hm8S~ zhMA61l2D1IT&b#qShKZ_9gHMD4Tago>23x3Vm?n1p`x8A~VnUAw({sdy}i1+uj9ir_T5JtIWBUX6H{lB~(hlv1`bU+v;j*Li?SCj0T*8Uzb&K z8*2wl1k4S2vYT@FwsjpS@H{kPF2)>auAD%X$ZNxl-BBL(12OA3u(oenO{z>CIyr=} zKSXp?mv3kI@n;73dR77FS9hueR`Uv zA1^LW%8PMLoy6u5lr)6z#dq6Ps6y8VuoK<`4X{olHf)fZsJ=o2s|mS45z=gGm?5tL z#EdvdAZFhzU}{;cRVeLm32a67uKgdk;%flhP=8VjhfQHGGdgut#=d3M-C^In_~)*O za~K*x(s01RY+!P*k_z-B6bV@o;|%4XEoTxHt2Z!iH~2)kj>j-7_%SE96$Ur0%S*f> z{nqOLr7P(m@Nzz~!bdqsqK9{B3UALoP;%`N%S*IUS%*{TV#w_#0s}4Zl%o$%evx1< z(j|&bUD}5myRkOnf-;v{IzU(_uj>)jZ%;TNKCe(--Vj~3cl500FV=NPU-@)(bv>8% zy?Wr2l6tczeOlgf6YOW1b#L*zhX1$Q)XC-aN#94mmX|ySlUuJJ+h8L!uJ%&xev8Si zA~JsBYm$R%6ZSQRz~LAawygh`z0``#! z8iUuR=)q_n)xDiY5)zwOcc9i+R`Dpb7h$s#xZKm*!+V9rN~CH+jKWZ>m?BK@Q?Pv@ zc*_V;6z%a5@5y6_aZL0KiAtlA*m=Mxaftw}6M}pw;{qVMH`F=~+u244{EDz-oA^b@kFOd@2l| zy50FE)Pe^&_{jJcpjHC0a(oLAYIigSOqc`40!FQc6-@_@o;qpmb1K$Gh40yhNQM9& z3&w0vH&chY4H285ej|GSjn@2>>StkZvC#Z{xw#)oiHQv9W=YlYZB@Mrw$3KJ_r9S# z-?0bu+$4F*hInysAeB_ZB*R{B@xuySeX+$5K*xX1Khw(HHZmm+Ji|?^!?^LtPcxW`52~-%nO`LA)6{DI<|KstNNHiUrWCb`Vod97LCtb=xVcb5u zD6-sEoGWdJWBOin6k-AN$cC)HobYkRp`~?WR5zvd#!(fiiAkuy%Zw#V_ zIRJHy?((hNrMU$yF%qVqbah1!;5c&-nh7*`R&OW0UAnZVKjRz2206|-AT;hivgAT-mtufc`Y0|*@OE>Z^9;zr zj9pCIf_Me5mtNxxCgo1&$4;0w$SmtWQ`6r4PI@SIFSXpD&@7=D`xPO-B{wN@*M2F%qHu)_l+1 zM_*qCvL0rxl_q96z?K}~J&PZW;3qNSd;BG@9X4aAqwwXY5Oi~`lZ`FZ9l8#H;?+;BH8s0kR&i*qB z0UK@Stcv`$Uot?9I2>pjN4!rI{V?s#58|V=E(DmuA}le!zw6qcqLaf58Kc=6Grjl5 zal_+bAORDSkY~U<(@=O^@nVaq=KV6j{YBHmNd)W)*c})@?J*lr2$noCPQ#VWjTjHt zIee~JTJ5kPe`v*8h-1{w4GB_safPh5B6o7&qIA_ZDpW3z9}~_8Dq>-+pIxjvCLvB@ z3quBHhkeuncI3Q27x?hJhCUw`0OfzoI=&F16Vw1oO);=|1|ei;RrH9g*mnlVYCpx> zD(t?vjJlUmkZXY5Kv_lBwW@G(l&yMyogP@mE0ICkuim+LW!-aG6&1g`7w~_+7O2+f z4FLGB#KG3`UBT6qgTI$w9)%o}FIS&`8au=9&fnd4RKIhI`r8zG-%gt`pUm`A*hW;BwPVphf&gTR{62hSoH2f&tv7_chG0 z2sULvWMW$=_6)IZhV_Yp%aLt$Bl;3}{Z>p$KP_TLK&iIh7Lt|z6OgR}&Y2`7wHREN z9nRH*kgv`3b)=Ph(_{djP0)D8UVJeC{_c#O7x;65acKQC0pEaTlVzFgUHVfL@UwmJ z&0FVTJzPMR-ir1J^B9$Jt|?Suqnrbq=}XMN5r2&G-x~8pU-4f7CxA4}O|bFeA-}QZ z^$Uv4|9#o*&N}{b{~_}_r^%}tn$b)2;<>KKIPIvnOGkO2-XHU9(V+oSB5M}19g2A& zmgSAP^Fl@3ASpy;E{f(NCg&sF*o<*|QV!&>S%oyj3xw7HjV!DZUH9l*eX+U6*L9t$ zPl8VvSp&QQHk8q=KCW0VcbuCp3)NKWtvbc9XbuhH+Rj!Y^E`!wto>_}0>4t~@os9t zO=4A|x0qQe)fq>EqCKJ`3mm9<&PbBv8`0ppHO=SV)$u*!pHK3I{@EMeL9r~oA?hD8 zGWg*b1W1^|*3LK(Irca92T2QL*bd8in>B6ju8)K|F3Zl-UpxpD0Zy+fKK&Mezi?U` z&BTvfQpdud`5Kq)nKP`U>L&>cc;@rvy;sJMz&^Uw#WRjM-XT$#>jg)gM)K zQ)73T`}x&aze<#lwrJQ0Ti#WyohF;(^r0)TyU1P&=x{ z@5Cv?pAI8I#8vA%-yU(atAnZFngtpeYMdWlRy2yNYhsf%t>AP|;UUgN*q??}O7e&@ zA^}`SY*a^1;y^9;xAe4Fs80f)03%#ZLM01Fy&0u=^=h>b4hhHQ4$SB&Z&z>x(}f)T zr!nmyWBjFRI~PTOpaV0SX^vE+W50p(`7bNPw{QLqZBP#;Jcj@rncbZ8avyhu&zTIq1F1xPbuFav zlP~_jw+LcFbq*_!rM#D6R$Et?|P?VM`3w`lp(pjf2L)R|{z?Nv>LwNrg^0PK7&J#^ZrrZ`ewnu$s2Z zo;~Vu0JR(f8vpE2nQM0_VCJhh_hD%kmYIeXVgzp@dLY+yP(j*&X3+s|nWQG5N91Mu z^qN7Ez-e!y9u)Gm#`-E3B3a9mdez80fk7K{zjkOy`c#OOK#keJ?e*5-U6<6J+3BMb z{7UvEV?m`8v3>Tr!OZvP8`?1L-@07Zma|>JMzZ%V0xw01RCy`3CSf9B=*#{S#$6@> zRmVB0D+7zT3H(I~Np6cfus?Uxg&dCcik52^OZ3^SokT1Mgdd@^#7c(JcB~ zjp4XHV(w$7FMr+K$_fCCJ^wpvUX!p6mU7Ucf7bs@E$_xY@G+qerQ%JPBzV}alBK+n zntFWYZRL;bOO&TxWvcayEim!WS5c4$7u>%cGn5BX)tk?S_|9u%$%WAT?*=og z?O%NmVqaL9ctFwBP=96Qm}pb}@%jmk0@O6@YV_JFB*r|y%mnCodgaW5dfDFDMyX?v zTnf2+`88c$`W%fq{nnZ~n#;fW*5;bRfB*b|{~4uo{dM1bdq-EUTG%sO>rbwxnq6V88F#jF|bp)Ze>>*Yst>(UQf&M1C zfCaAuE~ycG}w$)%a zX6lFXHj%A~sII;t^@eP+k(}Sm_vO?7L%dII7_Fc)`8zFYw-dlzDPU~R)+gj}EoTvj zZxb;6SlxjCuj=IG#!2Sw21_-gQ-Pu{Q&y8h$v`1JNDkY?`@nl(fuM!LuLa>%e0_`gVGGN7vDVc))|%eShrZ9HSJIkySQ z+|NRj0YD&#gEa~`B{DxWdrQMn8|FDsA0bBzKH75f)i-s-r_a^PM5LnWMQ!4zVXfJ^ z7e}>;@4c@F95FVwMPE1&>xIeRFwK$<_h8@`lQe zUeCv1O*~&-pc(6DSNvv&tP5JMID4J&xvFiPILD^_^4_Y%Sy!h;B;E1vC$EMMQ$_I#xj43;Nk zvmSFMeFy_b)EQV6qX+j#m_EYabSF+KAz>U*R^9~dVLtE>(h!Q$tb%Mt!l1t~@>`*E zauiye!C5~4zw^TPKk`E^T^|+Dh$6mqG7z=PneYo%h&qzutb*V5Fd3wZ!U?HMh9{9Rck|vr3DA#@zr;~$D4v&$mRF8R%)eCKZbjQr=Bu|xuQ6k)AVKLZW zmbNm>fdLRwo~#2+CGPEO8v85eNo!%4trsdb7#6QCk7ed-Tda#~zL#c-o=C!)9)9oD zb(HL#*G`0`0nn48ym@j~2pANUrdkk`hC-0V)M)1EX7-?UTwU0KbcY(+7zI6*qY()W|-r z^q5UjI0EOoA|t{8hdlA;(iFa-_G?FlRD*2obV~SI+{-$^Vt64FH&M}}vs_9?=pKpK zonyT(Vf<9l++VGYEaOQ}8s$t#ih?ld5<$5w45bIaoQ zqCQxXpyhsBuAxfd`uG{opXv-5zs;SeVV7A@rBEFnK%_(^XDK0dk1MX|JJb z(+U~`azY~oY%a5vuDr_;Uq2_{%a!YJOrYuzNel5kHJserSd#ESwxUA=wJ6BUXMl;Wnw*EjPOP z8IDd&HkI5p_4pj!eha#3J1R>+y%WDIR+RSjx>-6N7k)nzq%VAYcrtWpvlvp};&Z8> zNn9B8_m6+ZpDAra#~P$1v%dxZ&kK+~Zt~^u;^(!vdw;ucw^8QY!`#d7_HrR-ih`NP z3W)o>`!|mc;^95zUeSnYA|<0?OFQcK=LQJTh<@}a20Y;i0!*|>PoR_$3Q|3S=%#&= zAfegftEf9Xhe)<@qc6Wcx8QD1>rh*pKbvTH3pC72!^xfLNtyh1%4VGawkG*mCn_tSS=Bz%U$rK zj(uSw5n#4TpxGGK`!0f5J}-kKyNe}xgwBf!8Sf?Xrmj|3N=Ftztk@;XYOsD{4?&quiwA@9JyHXh z)nMo%9k99|J)Fk2I{D<^^rk<@|JJSInHAc3661$?GBS5Lo`KGFdb%5Rj+Snj!(we0 z5+gO6zv?;h+qnd>;Ppb3Y>V!SqGToFQM|L`o=pxw*Q<^aV^u^|feNfNPqhMsxovxQ zo*vgcCY9o#a7L7<-sW4>^Koa~?BfL*e@bun?gCw4p!ol!!K!Cp0T!)}CK$BkMRbY> z-LMRNFtT25X#K1eYL7`WK| z0b^8Zc;{{OJ zdg3S{LzhWUf!!mo(g1+xMA(8f%e_quyhbr%pD~pmpS8GNKvP7E0A$5T>;nvMTSUh4 zh+NYwT={*|0UA9%J`7p5d-daBy!mRU>A0%fEJfp{StRjv+&ZWs|HiZO*G}v5>c+84 zZa1}GSJh(T+BY%Zo4;Lo-O}JIzviREyX8p?$J~%Ir&k+>ffx4aG>;8%=wzD6K{--4 zXDd_Q_G=dJ;{{>Yi@0;Cxb_hj(4{!I;!!K1?aS8HB8e#EO=MK#n?X^;ie--FRm=j8 zZi?|RLh45=!gWL&#j zU21!3kuA#^xUyLLOPsYi$_hgU>6pJ+A@NxLpwlYXbn&@f)r43Zq}ia`UCMulWFv>#%^35Hau1W^lk>z7MG zCv7ehQ?I1tR-J-!QP2`-SMwl~gs99^g=J3)xl2nC%4mJe5tc~|BkPBEH`d2UI(l== z68%?y{Ew7`El-=CO9Yu5N_6(T`(8b6Su@^S6JGVXZU-%*QgZSF_}eM$>pV4(EA+#s zG|aJYF%6ORJMsebB^mkjg|#$8m5$@g<^_So~V| zH7oJ8w5iM?mP&I;rK*K$Y`KtVbZP`2?m7O;+l@ZXDs)b?`DtXyt;u9*WBw^0TrE%0 zDNzPLWoj=%2u#&m3QmlvtOmNzzvecg<|6 zLQmHyXL~4ar+O!Y?0>dI>i@O<9JA55s1My!ulu7gA86n~>zj}jt~wqI|05ez*3$K> zDrfjk+NmezboA`slS){f=$T?yqMtnDNL~%b+G8OyOW>PE*z@xr!s|+Szw8i=(nyj| zA|`1*9TzYKvJW+T=?%NyGv<Bv`s_;GBq?c(`@q zt}igJ0eBv@BSu5y79-SIAc(GDW6N!qC3=fj#-w^q9|kiMhMkDg!PF#@+!+)$XEyd` zjjgq+cLavas}Wz2`dNID;|P16P?oCl;A{uv?FHne69w$V{yG{z!-NVCImArE98zQp zV`ra^y)KqL%Y*u9aET0c%5+*|tyA3F|F~sL$**jEA@!m6ASQH{8^=*ffcK?{D9t_- zQr#rN1z`?Bw#x182m>a?cxe8&j<+~t%ZxT11*(Ic%a1jDr1BLk)BY0jkObf;e6#6Xe%jD zeK_hj>&dWjcsW`H=2@nR+sB?tdg({KhD1{0HozMJl?P*DPYu0GWm=QfM3QCw{&f~_ z-^-@KMreo_Y-1&#(n7Zn6%0iRWbU_-9SL35$|@iy7~JQMw5(@7_4e=ZQ2xx4YUM|Z zm$8N~nB^gZj60G>f=~2*;soRQhoy+R$ryaprBmu4l3MbiH|TRp(7*4B-fX!3NPX)z zd6D3ucl|3%vwiKD57#kVmIva{2R?!xA-xy%NP#w>6Nh~QOX1Mt`FIdT>IZH>vY{?$ zN3f;$=iLyA%@BcR<99UuAM5)48iO9c&t5ScmH1dL;fYU|PaQ~n>(Eo3mv01-r;K_I zgfT0{kE~ewqzck zPEiw)61Nvivz;I>_?7+M_e#a&9&thsUPt`!&tcm$w_VlIcTzgz3#(paLp47nnSJZ` zTV`?FY5zH*yD$R|LLRicH8;sg>C50`Rvq>9FBiBA+1)jwIqO=r{%cJ94fmEg8UDak zK8K1i_-u6xQMhg2KOdR)RbcD8JZ1Vs5$@C-{gKobZ=kJ`<97*5g=xyWB<4xcK&$)f7G)|e7-4!OrS!L zH8h)8Vgv(3S;@NV_k{0> zD0ZJ%F;NtOsZFI&DSweLL6dx$#_!fOJlXnNPQ`Z25~c~6obL#n-UBS~%TNkt-UaM+ z;X0fQrY#q0w?75E|9fH zxF8M?9MF3LUa&QRJFQi1uM9nI*rt|9LP4$S>i7~vq->2+RJREXFQ!TZtJ#mL?{XVW z`G0GkbS&3VLX;EpvwO0l$-7ZovxHVL3bgu~TGdG_$sK6cr^$;SCd3dPXvqC7X$`KC=jFMVL#eg-LpDcanto(H9 z!CwiZechz^S@y8NwH;93ne+qAHqQy4{j@T~t;@`{t_WR?P5mM4*=FnN*^7gkD)vESrq2hlG>Ax&)hg*+lT3uk1A82}hK!;yM z@~ven@7a$`#=RW6s`CGruY7PuypDIhs&zy;?GlSGn=h_s`CJyWo=CGsognc z{!8QaOU{53U*@?clOnTll_zp?Z`nQE)^(& zh0@ImRC}NQs(ty)MJ~Vl)e`SwXnsbdW%UHRO0x!VeV@RftDkpc>hZSypn z8eclg=|s#wU;)@k8#8I7V+0;~{U^mt_hWqogk1 z{*7Hdb_pL}6?IpKjo?+6M{q=kf!*lyFsU`6X1)0mQRL9z6k|-D_0pF0G$GO^2AH zEU*kQ1hExBV(PI(S0PZ6duDh5xC<-M_b|+aqKS;xuoh0;RGloMTCy58XK?!19az{u zrj3|fNl<5#{j<0EKLVe}^>K#idvKyrnSD4YPCdG7{`Q~|mzGKRosOlO$%xu*^QY36 z)!pXG-iywJ61jJ+e@D!7)Bk_*z5K1LnXI+Az=TE61Ap_r9rVVGWVY-1*!+#)2v*2A zYSeRwsym=UnFgX7Yako*sFD@FqOZrPSGPgF+a5*%A=xv&2jjf(?w8GqXcT0x)agQm zM9@T!!&oE4p}64e=-Su5R3h8{7C~1q`5OX%fq*~q0Xsj|JLu#b7+0x{$=-L_Rs0bT zCLMl(lQxZky^$Z23xtncG&jtE;&(LnN$FvD6=BgjqcdmM%w^-x{>y)j$l=_-hPQ2G zv`&`(L4u&Cl4>YQK|k=57$);D#Mo;X@+Q8$4Q)A}Xeuyeu&xNzM8mnaG_CG-DRhBw z)M#Uwb&L9G+t0&nSkD@@?xc6C8S-q-)@t-a4KEze>Ti*3)8;_RWU3#vm)9{1a7y9Z z@yZ!+Oed^$0@?v|!VR^mY0*!FbmnOzBu!0!<{U5}J{1;=t6_Dsc(lailNvap!*7*| z6VqO{SfoN%e^8)f5o;Q(LPui8`5iu6`9NeP>rL^ttud%V%w{;UV;s zdv=P}jw0UWT~w~zT>2qz zWRbU+;+jxquPB2D7eSlF8ltJ@-|B8Xj|xaV&edDIHYOeNwtKNn7m89KeI~fsJ}i^x zP*r>IQHNx9hscj@Ku=%+t9wHL;u<7%%4Jq~jz%IV=+6C}cOD(t%=lx!E{(0_{ATfw zRLoXN4*_1nQu131__3GQ(V*Uv)cOrIjUqbcC68@iK_x=#UboUtjy+mb?<)3X|pdsM1X+n5_tJN*gRNqd@-Il@6?FEO-CWRD8`A)I0g zXwU#TjbD2qJ-8+`X(WiyW!iM;7`6Yqh`D?)n{>%ndBfGa{nk$+evZe^dqO^FK z3pv44=xgy!T-!E-^^Z4Kk~LdD2pFpWC7u9_LzS0*+p5^V1Vx0>p=l4gEn|lE&E;%X z88xPllLoCIId9)x#tHRI*6^{U(vH{N$)Ia#>oB$)Sn(uf*jS|?o-=wst(>7^E#EOJ zm%E*&TczEoG&4o5L{^RE^r1~SAQIqp^;~mcuheUT#uX&2UU?;=|g8OdM< zLu*v1ExLZ-I`l0~cQ{)}M**-(=Yj79IoHupWA+zLhMd!2`y52fR^HE^E;oq|QS8r> zC%BTr)e#2^PXdopM|!YW#XXj}-i{pxaBp5_fP`Ww!rd}5n3-tm`k?uPgLJzZb-w|y z-0-zVyJeW+OSX0nL29Um3;txq*q0* z)nQnm)X)l4(SE3TcnNwWg$JkjET67Qd|@`_pOgV+?8&=lxKJGIp)ozGTe(0`8oqiX zzOFd{Ab=2{F+5i-9`qB)VXf!Ru@+Lb`k;32?11>7%q&(&{zGGKvs8iWe_b^Vp=D7% z)9vz(;SU>(JxgH75lHlDz=0izh$>VB?XA4z{s3h@mI1I<0pWOQ|$) z{E+)Yzq2YL!0*AVU>El%Ny(i7T?q3CzfeEhPHz7eQ(`y2FS53Ii+TTWYT+wp`lrZp zq0SLpDU0aFA3O1IP#A}t3u%{POVhOzmo_04(7?!t78Vp!;)K5;9RWR3c)b7BY$vQg zLO*tiY~I??m$1~tX}=rNW%KyFQHoq=4CjduO?v6yDTG6yRS`-_Jz7Y3ZxmSUqCSFp zX!G;ye3u{VR%&V%D>6C3eb+1Ga`b=Hl2S%Nn(81aC4r`OImIkNn~YmuOdu%{_Nb?E zLZ*(Hohr#Q{e1s$H>3bi8|)3RjsH*oY}pYPYEzscCwE;$g~zveu##xquSF*QYnPxP zD7t=@gS#~E%s`JXx%7kNaqZyXV3wE{D=-n)@~Pf|)a_Y+<+rypoVj=LTmp`$)>RQg zvM>`$zpO(f60@o78 zWEb87(bH_H#LU!F=Q*B+d>Emh4o191kwcF&hfUgPHj(R?t-Kn3YWUfYm3W+8(F~V5 z2{<=wx}Kw%YyNj`G{DaJ;EvHBb#xI$Gg`nh=+JJPnb4-l^qt%Z*!EgOF0`Z=Bcz*K z?w2Q@0z|{}5Ye7L-)OBn<^3Q};rtPfd!;|O?Em$6H(aWYB<63UEm;+_teN2)(a9h- z;)&PPAo*004U9RIQ-<}_tuE!Ce^0vR{x)Avo&tzad}%lXGg#$}1vuFyK!&c5uk#QX zaaM_ovY-gjC`=Z)%cx5z{;W9d693ByI;H0ESG*{_palI_%Jd@C0`1qpe&lp|sH!ND&{d#1J3Xr#ukg+0H zVbDM*Qr!@uU*D`!G$t`tau={IQP@5^2zRmAsXSWS6$H zbfsfH8KZo8n1;HS!Pg-4_wxBmAd|890>hm(VFqH|y28sJ8|Uw(CJ!Zpqn#u+<;=Pg zhND`2xt|ZrJH2jM^QDT3>$y9{5j#b4=d==pVwJTHoTbOWE5B8ss zzy4hK&7}~$gm=rI+}nS_y7Ec0qh`;C)sIWhK<*vigh%rLJ5+llsi=YeC>pt$vJwm0 z6s#5#<2SSwI=)rxL4vjJ$+8s5*Y^ic?}{MhOiuHJm<_Q39`eg zM4Rayu_8`eGKz$Gn?IV5ENp4ecSwDa)o>@YlC(mB8)9PQ(d2!wvieg=z0iCG{7+er zNDy+q?Y z@J-kw7>)AVs*zArUMAPqDRMAJy$Lhj+g@>7_1pmT0Iah$T4XuXza5PQI^@~f)@N}5 zU)^KsxeAc&V~+?&l43Tr4u%2NRN?v@_Ha^)EIOz*&xYCha?=-q(whys2oJ4K;GL-b z174SBNJ`>+_TyS12&X8gO}S*$qX=-OSw@rY`hP~IJ;byWq>*ZE5*z*ydN6Wzo*otf zn#3kEfzgSpQT1zosv=G~HciEfNN={3wAaG@4}G-i{kKZ$9x2pU9|(CM%vQ|4q6NQg zAk4fZ(adgdlr4?+K>`a*>%^Vpgr~+iR{%bq_#hem@(b`$HJ}PPxKIX35vf#Oh!>sZ zt6h`6$gRbJqRyimk(Cl4Gc`rnC^6=czzE2v==L#wrA98I-)a0}yY9oJaH)2L zaj9~|SA@JJhZNBzE7K<%0Yyc!JNlRu6CwKC1J8pVFH;l~!h`ef4s+U6$&)lIvPB^9 zDZL{ZXqa&ZHxSg9IURM@Sudi<`rT}gHn>x?7GnwbNVpV#z;$nlIC_oMceHM(@36z> zNbf@~Zv4?B4S)A}Xdh@{iVgU2erv*>23_%o+&B3;L;O2*AHh!#>6{YcllR&B|MLQ5 zH+Z^em>%CO4F1jX`sM~_N4YQVxDHUFDcTCK_z~h9eF&VRqN}Z$F6^{WX@KuRBNg~d zq^5N<_FsoFzp(IgPFJ%jF#51 zt+@?N%@v&=Z~*jcy37x08;(>9rz$ilz1qBXfMm7dLUDVatgCE?3{8_2%(Sd z-_?Ng@}hGBkr4ScR%zsAG?$kR1r7tfgu6{<-`l4+Qlls!4;y#+27noOXQ}iX^gHQR zWX|-ugFCEFXeE)RnA}8{N*X|^Ki(xKnB%_L8D?K6rLPu!Z#`J4oCl?;m5-Y2^Zi&?dF`$-Bo#tJZjT9#RO?O zox0!rnZDmxnt^7&qp zZOuaSwqITVgf;J$B0{n6a;YVB1B9G7nd|7JYid5qUJ0BGcuKX6>LH*Sfr$@jWGi}$ z3zh6&bV=Ol;NFN94UOAzpzptk`PS0fYGi2UfnKB-@3_O+@ueg$FxKaALFzg1g*$gQ z(&pIPyJK_ibDnXCQuYn?@~puL&XcojG{_~lw1gElL38Ra#DCB{rh9PY+s4!sQyJxAG8Kxihj8vIo$ttx4Kfx4;9qtU!&_T}uG=!>PAyGn#u zT!Zt3elx>ktMVt#TZb8#>a7AYL}CiX53}dZ^Hdz4+6!nZ%9Z{`J6qrn%jG{o;b*3e zL%X$F(7*I8cLF|+lS&KRJDFHhMbbcc&{fSx>bQ4IL0l^O>>~yF#6+FGOVb8GueW>5 zG44)gT1h*OxX|U@avI>hO|FnwxvJkQR<&qrzd9I~r#Z+U1+5Dhg&Nh`(@pxk8`&OW zF_wkaNNBTfQTE-JJTUhjE$bdf>ZMDTpq6y$#fKGuoH|{lGI`mH@;kwM>l;17 zOkg5ilzhvKKGl8t#01g=HN^54;tY>$AF99T4 z>^<{Pg@_Z1FEU;5cF8r2x`Wv_>zbaySAj7YEMMwZD=pP`f9Z?&jp)RvwDP@oyQvJm zz+YyfU-g($W-=SF{VixWQ3y+Y&a_DAb5ID@vk=V58~%i4XX0AoC0jU8j5%0>xmm(r zn!uDX;R@aK>d12S5qVNcI|DQk&*5VQi`xtRC5N2ec!fCLwn}=yxRyZFDHFG}=(~<{ zlTv1Vg!d3kWE;zbpZ?*~$=eIjrlZ=-inY?wh!}!(yDWu~nc)=g$%Ic6dt@8DxC<)K zeD3CU49wZNv2$|nVA86Q&4}w;=jQG(Pk)aqNwe54JxL|Y4O;Ql88Q|r~LOPV=9QQ1rMrD~I-yG7IBi&q(Og(o3(5giQC zCGA?YhSc z8Sk@OhYAQpA#iF$ZvyW%K-%j7Jsi4(=u`I`r%f}2B!arnodr{l_Eo>X`KFLpCmEl` zGl0(gTRnRK+@*Om2{WdSTfVqQ^y_26A{4vuW*Fh{fe^e5>d%rhv4zs-bPAK~`_8Rh z5`ubNURnr05f-a6PKZCyaDL;SHQ#bqB*s`{b`WyoZb{Ed&&tfE^&2${$3nN2|1KZB zVg_`Uh2QpY`x98&^HJF5u(VxZjy_+KE8K3tv-jeqq;ww>cxG3loV`ojns^= zb02ydf4Q?pVoi}R=VMH%mFN<<67Nl|+lLW~#EXP^dzAvENk(9b;Rc$!kf5O#wnB;= zpl(zgp{-?lh((L5`S;*Wrlu$-6V3xJ-^cTQ4%jB{=)9?_UifF%l?y>k-3nWi3zCJY!ta)yR z7!d7M0BvECUq-rj4si+?fUIm4bM(txFZL^4O)AGu;Aj--SUf`4Pm*?5$#tH-jd|&X zY)D_tYt8um1z`vJ=$Jp~{OAnF;s^WW2*3u;FAc{NNuw!ZlZ{@Nw256>{g>Z3BKb6w zZpqIQ0Zo%m$6T|V<$)HPpMThS)OXQl^#?JLeVRsHi-~gw;3?qu|LFenaPTFRHDzn2jDx2 z@mmK6Xkf-Le&Qa=OGeGc5?JYfrUY`2R0;v+oL&@STe(*@uY<~e`#-7hE+4?z%V6L` zR>u5@bP<7*=RA2Q4WM!|u>pVR2+XDr9g>BUhYQh07zw)7ccpIf_tZXi?DKIo;#)ct z#5g<*X7Ybf1@f>8SQ+#3()vy4ws#)uiTOX82G2945Gu%r!^g#|C<>;Hwj|>j7QQa+ zIAT58T0yEDS}F+r%`ePc=)50mO}P33@Mrv01JjVc(z%d)=|KzUc<0rA$!O8Zsl&IX0Q0P5RK@apEj7o6F0?OixK5KAC@MSNdI`dg~ z4A?~+hb@JlKj#VNnT6cQi8Xf})8zscaxdAiTG@^@5p`=Em;k)j4bYqwuzpx(^eIr7 z@LLAo#8n6~hxQPD!*d?IUeBSfaEJ>D%3J)?WU_A+#bj&=-3gzLt{DBY6#H?>*-|~7 zK{ZSu^osXQe)L60fZ?(ecU{Qo0Es~vU2Pv^>&UF5o~6ZHt2h&cFUse#KoZxq-Q0Eg z9iW;-5&lTSL#=i%6Qq)VWOZsX7|W7wC&a`29Jv>oG%t}_PYr68@+SIl4GqxZJPU( zPE|^enp0u3-1{_TVK2Ut5k3QWBrFn^9%k`wNW6m2Lb1~oz9JvKcq`LB$yQ^wCUA2` ziUJ>P9Y9$1S&yOG-HKrXM~M@`N4-3a_Sh&w=EnJcACd7g@bZwWH=g-8!W?^Nqj%)} z>zwPGj#R^rjUL7P8+UC+NIS)B7~i`H&I)xdZ@BJbZ#QWB#+8M|lWNGLt(O}HxMWL_ zXxBQT2FqNTx}ECy@#I^H&s${V;lLqjTdS`mqOAY&Cs4CRYrk_jVe_!z8e;I?ZVlb$ zdqMBWR4c?CfqTpny7XVhisQ5>e||2ym&Heh_iEzh{gpv4C!4`YT{%bJ#hZGk(Wd|s zhmh};1$fZ%CD%SXMB20!GcbnLE9Yd*95f5e|Mn$CpQqd*Qdb2%1n0V=9KMMljot~X z;~Iu6cgFa#H>JI)PoY#eq--U-CIqxkk~23i&*(qRoIvXwv7HmHgQym3yLP>-@xon}oOvj?B1k!`3b)NdeCfS-0%b6LF*Pu&iVejR-P zPS5aQZ{r8VkJ(#{5 zMgBp%b)3)(5}R+L0hEk7kuSh;NC4gqUAV%OZL&x71tITdcgmMu=(|zwVoOm zRMAK)u=rTTCzo#TEPze@#WqrAw25q!tPk_oluNUR7NPEuGsiFhk$q&3APlbJgNXNp)E>5$pN2VMcIko~auwHhI{fie9z z){rwk@ICW@J30<}J??v^dcOC_{g^|8G*WKWv`Z*+$foLZ=x{qV3qOzM>-*sZrpJ;T z$fum(4DAKUp@6Ndc)xo|NAs5Y@g{l9nP-png&GpCX7vZ|EIDYAqd9+TNsPa!X^JTG zHv`h}vGL=A4ZJwzzkf2cEtcvMQ10|sbmaNFpiruDqg}-140TY0z8~juRhk)@$2X4a zrx1*@3tHrcVBe^{0Pc~fR@$9^&D&6@8DuxdEU2-#S*k(Rn)#>AEj~oBc46Qa>CIwF z#ckl*GXLV4O^H&^1OZB_w*BOT<~9XC0ua)Jgu4%8uRq!!2B+PR-fgGtSVqg z`{jT-EL_^AFmZ%|mCl+I){p{d(1Zj7__#R8<%(6rRbsyd944see~+V29GU!Ml;70T zBN|~Q*(7jA(4knPCvXxP(cdeRo$;q8`j`k;qJO3TVKYmysY$Aph#j#>q(#H`<3C1Q zW)ATsu-5qt+B<2Lfu|ujbky&wz&J@vy{{8#I_5Esi^X!UGV#A+I7wMog$fQ_m+cWW zbv~JtuC{PIO%D2^_`6VYkuQ<)ofJDx%%3GJJTns+AYW&`04wY3jb+K^s`A1qg3{bz zFxFa9L#}NbBr~|5n0Q#zQzlyK;770}T??(|sro#fo6LKHki_TX=2t z`E9#H9lrqmeRrSlJ1_j7T@o`l8*J6-MR?N7>-)PLO61 ztP9e|bzDALtQz0T+_&a;s|TYK18JFG_NuFs({*ASGuEMs=xc?!cbm;z9@ zs7z(mWQ5K`)l4J;V;>AYA1SBxu#dg82FkIRbJGOihf}E{GBHbc6yj=H1u_*v5C<=J zL5>yA*I6H_ni7s`tweco16K2FPm{FV_BvU5TdlmQ_~G$d1S4%VtB5d50T+Y-vRS26 z1+-uCiU-D>Pg$HyAbGPPC9L@!zqx*(cqn(m;VA7!09XXEEIHTnu&?BkuCwXqqd%fg zi$tCo#<$uhf;kWud5S#H(-|1^slMPm<>?&I56i&pQlP@aw6p5P+AGyb#fFL zm=);d3lF1vmw;0Ly5(R)>(S#l2%&>#F%`#pwcPDIQaxNfhHFaH`|<8a8&>5k4~8fk zX!GOF{spbTdrKTSoXx>~uf)AS7+;OaZjBZFPN?2@hzplO;y;NwT?EeoO$ZZE4ZXKB z?cgHFd?lOXL;t5Kj-v~D&r49x*s_syldAE5r9|i-i5%Ped_jp$#6KBK;mYNaRD9 zdSh7#ei$R8oho3Un;P5d*60aqHMKoXUUaBsz;7R|8-Z~%ErJv4IoyKI28n|+A@}O<&(dPu7_-2R3eOz zgqLJnGJ&(hvqc>qz9UDP@Ey&sfg@@ogaGj7muf`W*mKbebh5hd=>Yf_div=$MS~0#0gD8 zBuQhM*Wgz`Vts>mRQSOW9uO^hc&%av+;af2la$4B@L%tayeoHy0`FR(#0Vw_b{jae8fLM@MQ91JJ!op&gbdTrs z7W^cAx%A;MjBO@n3KKTbf?6t@D6lH0`OqY((cHAB{W8?LS>GdFfE#c!yR%trXcAgT zOnJaO&jr(E_=kKxwY>hf_FaX9hLm@L2?F!Y{?xUq33t!rol(A0^Uwd`D|hDkj|g^f z*FYcd7R7cK=0!Wm=vYGUCg&8h6*YJ6Gc?Y2G}hJkWAQw)d?u*q(?>>)g3~{!Pd1+I zOo{9C)AOHR#3zg`jA)GWV|3A}_9dopn{3BA0g3ea_iq66t0YgxZ6%tJM8baK*e>Sgf&~<~Z#=o`bm$Fy32ev~hR);bfj3g;gs8Zl zn*S{Y!nMv0iWJJe)=$fXG0vyK8sI(eAPHe91;w|ZW zi{8`W(nVu7?sI_)Abq_tYn=|fu`;|E4jj_R(~e9j*4$UhR3a>{ZhbM39brb*G=A># znfbQ43Bdg#)RwtX5tqz}Z;cI>tt)Gt&rh>_#z@y8#2rO)o1aY4?x^m{B!g17$t>OMGo>Srpu?p@WD&W z^(aQn^}O{M==IiAcDm6Ry|X_EuK0g&-QSRyR~D{81ODgJmj<}|E`c?m=s7w*Mc*Uq zLmpYONe5HT*`J>Wup9;qWQ?3SWaD^iT8>Qw4W>|1GUE~E<#avCeD0U^#Z0-JfN%*O z7v;h)%W)^)?0(K*QWwmy+p#mGfayzc%t-GB75LkQ_I(GhubN z_$B#8X4Cy%JR*Y+7$=j#kdPsva;Bm9!JzuGE4W1qxTSjzA|>FCNky1f>ezsif)IHU z?g?Fghy0i~`2T=}Fku-p%piN4P5ZQM^IHE2k6~LtUubW9d;t)o5_Pz&P8GoyIQVHgt5XvSpOOW%JngD{q+9)k=w+Al7|!ctNXcuCoj83 z{-k)HK6IY`36`FKSh62#Mph{_d3el!gz?e+&Dl;ZymB&H$E!cSI}i4$;#DMkS8F$Q zn&q6ZG@kiM3)!F8BEcwk{j0u ztr>6PW=_yy5;3+qf&*u79lDZGE$~jP?fM znjwV#mS=w%@oEFj)Qr)kNvq+P%?5Li*w{#T6Ie*4ZP0Y_dziF}jSPF%L{9TGmE=XC}H1%S@z&zNYhQ{i10kKv``amZ2i*w(lo6BY{)ZO+;_U@DP_OiemZ|Poa&h8I4$FqXvEnYYc9hr{2nhC8j{*h-+?5)NbuyKJL z@YQAQ(V^=yIx1xd%&<#V0CfSg+S4sha=~JhF$m2Yxkj}Ea*mc@>aabw$?E&XxMZZB zp#{;MFh7Ua1D^Vo z3xBg$iLKZ~0hkjNu2h8<;?=r%ws5mF6epHGIQh{f1#T;)YYH-#e(~$|OVLE~q?->e zg~-^5!Qh{M-`%~)8;Ngb2y&WV(kCe~g1~CCE_zXryO`E)Npoqs8uOjKMmTq00@3j; zOwOkt;qM*YO}og%{l}#N=Wd&B_dZ9DW8R5$`hkYJ#fu)@X0zS37F{=%E!A$5@YyS& z2)oYP_!}n*&i=`!Bd=(&N2K#-J+DvJbM{@|2Pp7@ASSOlopqFdFj9<_>%U(%Sabb@ zB~=>tlADmL<r6TrQd!t;QAWsFAXPy z;1ItRsr+tZw9yZWK#lC#H|-{e?QIX-j=4Epwlpd;RY;#8Qp*R8L95KU&PrgML{cfc z6oPLo!DlSpyWIlghW?Gw-Vt;eZ<-YdgZM%j&zz?yHP{@ z?55|hZDaXb=R*G_e#8C&>T9O&c~d7A1*-Mz9*w1x&Qss`L=C@xoc5wI*jX^380~F& zKZDet5`znF$MM;FTRBsEasG1t)!;cEQ@U_Pq*>`l9ldPU0o~1_6)-VY_;&7rpUGM; z3MGPg7_MxNKwF2sz?6l9xMslX(8fs(qKyyqN!Y{F%xS-*b#)zVX+PWO<+LD`Gw)=p zB8=WX$1?JR+Ja9r?Y|O@WeIXcxIfSX+Zn+4Cs7mOjmWto2Z^y&5jM@;TB zhLC^}atJNBygWO)Xp%N=;uKk{C0g7`mCi$H=O4(#azvIA9%XRT&Vu0 zyUttJ2WfBV%h{z+3=to7;|iF4@auHHk+y9DKZHMmpU`G4 z%8}_WvzKbMbs;0OB9AQDO#DImlr!T37QM7U+wP$Tc-2VJH-Iv_IFk#AqW9cSX_{I6 zrEuiP=ZkRLIV`#cb~GQwlb2pdrY$?|vR=%2$?dGgo}wb!klei~=Je=pnMC|c$5^@A-DJDMe}(MZIH8C59s_eYN!e!2Ke@y+TTcf~L3s%F8W)mTzQGomCp>i(e+AGj zFuxV~++$Oba?Z+2V%5~QT}iUECl}8KY>D(UW!cS!NctY0Y7^^Ik^nW*h~1-07XJK> zQGp+pxr%c@&Lwn3{%hGU_ov-6xNA4Q?PbDP_k=$8PQlBeQ0o@mW`zu!*p_Ej5J(LO z>&troZ5qtBUJ$peXMccPs92<53M3R>LkQgIvA%Di3E|U=6oSwmF2~5|4sM>J=^JIU z=yTR0M^UdcIKJ}X9|Os8P0G=7ERNDv$Em#ypyo9!J}%wEm5?dN9blLb;NbO^^$>XkY4~e0qV!- zQ$BA?^Z*lES9F*2mgs0D^fX0voR)V)UlIP8|E_+VGKJfy+L&#BG5Og0=U7V?m(@f6 z*U`skd&;9@l^NqgZ88lC0U72j4%ubS7OugacXBiX=DPsG5p_u=6=Sb2mdqIA*Jk5m zs%XfT6Fr@v+n}v2_+YxCS^gkNYoD?G{A=QMvIj04$AZy=gwePwLFH3&%5LKzrUFW`pEiwF3hk$FN~&#<BJrF-s`4H~1 z@x91D6fMOr-O9>#$~V9l{^MbdX-c+?!T(+uOvNl-U#t#P4$4mt{{W9zK7e^Y`nyGN zYxar~Zil&#li@*A@D>bj?~J&a?EKqGVtj{Ex`t<*Ng`{-&MToVc3yvoR?{~RhNHaj znh-nz*oH$)?Km4l=m3|{&i68%@O~I4jZjCP_QyLyYlG4vBa4rPywq zYFZy?1BE-))^!^v)6FI%>t8@D4v3ZOK2o*$SiHc(ow}bBqxgT@)hgO}J85 z@x63Uxmk&K7jfgTaPc6kd$zdO@0mr!V|K8$9z9=PUmoL1_ma-TbZM42;;S)*LB#dSme*GJ-V2+1^HFyg+GyRMUmphy~={T~_8<7|3>b7s) zLr5FyNfR0{JY1NF5DT7n&=25VIGt}5U?nXWeg6nr7@?uK_a!SpH%q_OJj9Xl4}x@t z)(sE>fTiI5_xR7e6Q13V(%T#_UgG+3b1oPD?cI0>1n>8_Ujau~&D{?f{M!xXCaN5oHdAY<>9QUKnunCB<*wBPQ@K^$=UkviC zO9>q6wz3WF2gP9qg8!f%sa1`n*E-Y+1$|j9#~SfyH-86?3v=kkjBplnaGVo1qt@|e zN}j8>`zq#w=pxjjZpmG=G%gME)Nm46v?cUsI-&YkK|IdyP{u+zFqWQY+|=Uj1}p!f zt3y27*c)~F0>gW#O zgP)Hz;h@b?a2`x_@hWLB>R)ctR$~HxzW6vd7xPwNPX(%W^8Fd?;e%lN`YtrDD`Pdn zS?cLbsDo(c1)kU4NS^inaaxE98ABI2_(ebQ%yx93h02|jZpIU3djTz{v+mmD$1U~u zs`Gv$m(-T24fsckCF01AJH!p9h>T7@ZA;b55ddz&RDf(H_ai6O0cFwUuAviL$JI)>ID5f53Fhe(p2hG+r!i)URb!e$XMr7>$4=aE)Q|sDH%M~@ZCeA zvDmiq@>oEm`a$Wnd2m^rB{){uB{!l)_+d_jZPh)wvYvO{yxKe;HrCy@!)>8W=z}Oh zFgCvUsx?pKz1|rs2yFQT(MESub>-6_?6Of1hv!l9ObWyn7qz0N7K)<>M2&Q~NL0+Y zSZ$+=r~R;GkT`eL>Ae!8$EKL>V|KeJaP&kv zW(K2g_#3i0vmq0*j6u}nDb|)&x4u5>v z!wWI+*>}lCu_<=NN~q7iJq3GIYC#&%34CrY5aS-Qg-jUyi1NTw$yV&!k`&*7C41Q$N4S&5&L4{L?IA> zR*LQ=IxEA6mc1(BF$b>*Cx#aDe@Xtm4Za?aA|I%?6U-A7^6N@ba=}G*L_NC45XSx5 zGc$O$$H4TcAoMu<^Dwe_g|aM`V0`6|lB~fs;}^ai%BQYHX-7``ra1PJ`(lT%qSBqp zjY}(g#fImM9Pa36=9zDhn7@%{=oW;_xJ82g=EJ!^j1;FDof}yLfrr7Y+mG+aZxa&e z7g%m%@gCHa^Gf}_1n*u>OWx#%B}7v)V|?SWMUOgE*%1-@uA5o0fe6q8;8aO@0#|WD z?*Yhh*C@GC-a3A64D*~(IE&vjyQp*OoX-|*v#bj~mHVc@%B((OyTs+^G)MmjCMIRT z8uq|-X6u7;^DJ87ZIV*LrwRL5Rreb34ebft@d6Eh-IT;U+X#G9|K4P#aQ0woCAI|K zR{*+R^vUx34xup}e8{>O`=#ENjk8W58KeE|n0MQKeMA$hQ{fT7ve{OAb_C7&m-kx( zH%oPL2|NYaXrJH-y8#eXG;9=K5IOcY9H(?ciJ$)Y6lz)DbT9bb+rc*o0%Nz&^D}tA zVhGd7z+K<#%%rqku}_c}h)e{zj!rlpOydDBmvUG}lYaBJtozAzZ2uqHTFZSk{+Vzx2QY7!^YekVqxit(^n#uFZtxd)neJMX%z27^mW!mH~G23!jciQdm(~cc{SVTUCEjnA`vH9G1U5smGPbktS_0&0) zxC~ri7cNZ)UCGT&0|;EOVAE$qUk-W05!3UXK1?6#3^Fcr-A~hOfB$>%b=noF_Rszf z-8C}43^(bw&oj)UVH&V%qT`sgPXMS$1sX%mq57-esvCb1^*=G6*%vW)k5If~8W15o z-2B;10Qrk{Z$C%>)hu>%7FceM7K1pz+5(?7ohn`pcEu;`YK%6R!>C@iJ8w$Tc zgh>at$++>Of~$C%?XmRX{OIK1((W!hhP+lpMN0 z^o9lDrJetQtV$7mdvDrmC|B5zs5*-W925U^I^( zpoB2-3ZK%^P%KJ5a{nn_q30)3#+qj5tb(PElnZLJu}(ZdwGgsiL>Ag)6!w~b3%}g@ z;D4P{w+@c}9lI3D7E632?BK*a0%gRJ>u?z?wcm;RxrOqRJ0@2b4&9t(l z-g?`Uy)le`Tp|nbaqsM^VUlut4%}|fiiT_k zIl6J>W+0|7&+bFb?9s7Bwu;o%BXmAlWu`>kkzI^MI~GPZjFwrR{OCDfRfq>~whTce zKvUyXC>7^{F$R2J@vS9{fx7F3LSHvIDXl&8m03YSw!edDvI(ccOH;#@c(CfF#R?W(#L zF!Oi(BNeP#R?QJNJs4!WFFr$>MCVPMz<>MAMIpw7=O;80ep;J<-{kZqGKE|Mz`}rT zK)+emQ!>aDc%+9k>;`9^E@bnMp|O3Plk~{^(Xf0-Kw{r&q@-#k7da$QP2q`z^a%O)jkj6LWQMNxvXA%VzZ7*jl9$=!o$;w3>rP&El{xb& z|7Nf&djeGh+Ao=T3^M9{f-wGdAOq>d;nBU@d)^QMj;s3QjnXN<)&In-}`s3iC zLn?-vnfX@~CTmAIIKf-w#x;Q`_I>?m^SR_{y!?9^p=a#e6sq2Efn~~u-7Fh8r#VRx z9Dz1&k;N(zMh$M)&0k%jzgAoBS=;>TLJIWt$jMx9Cam}$H3i5`Y1SoZglMm>JOW*} zWA)OH##+qaS20JJ7m*=yGnLNa`}_}1!5$Frpy~Y(`*`-5mnJ_wys6=HpbJs1CKh}g4QCm1dp*LaPq#ly03l0jyw+ZGIFv`ML zaGo>C&bM{WY&(nG%p<}FGGNKvsP>SS$$TK1XgPfnz#}#1YQMJ9H|O(wST77q6gp0C zjW;X^|JwG`Ki;TnhXnBr5jH>axe?PT)sIs;mXS2LwD_j~ees0T4n7nWHT?#~%3RBtvee6;` zoDX3(dOu{F8ko65nMTbFP9+o;WI;^B!9k}LwRihKD=BWiRU7@n_Bdmo*Nv46w^Y%C zw(A>1(qMlfz*}G2u&P4%RkimB?{Zt8Uwh~YYQeJY0#!jy~w?^`)zs6W7RO5nD z$KGcujeV=Ip0b5Z2MT)*{E}h@Ki#S4=htHIyfDb$$l^!uh+=kND`%Q`wcUU4|0O2$ zQ|uZqqtN*0+xTk-ThRfv2Hp64Ter5unS-5bqeA3G$J&KnX}iWidsWE%vGQwlUH9FA zx}XN;6q|fWPq$5RObLC0HG_QGhu~%NM9rP*U&qoRx#@CI#g0$?p?$S4JYMCWTZ)9i1)btCClBF)^Ca!6H6ui=67sh z#ZMP{>@2@YUh$V28me-l!}n!kX?4~$Z|{%zr;2t0VTCi0@e?ab=osqL(F8$)NRpY| zF9tpGzzYZqNDJ<5hw>CpKo6~E%kK;OSiY(lhc`FC0YR?Z^9bKO52D`2j^unDt3}j~ z?5CWcF?umQ{Kxr?g`%V+n0Ar4ImaE{O~_oC+pZF9tmgCpXbh%<-dg}KzuxnFWPVuiGUlS@WJhJPYWKE6BNR2I%GBq5)4jLx7MEW8gnAZkn7o9b5=#(e}*S zeg!$LdF`Z`+k2trmB1{kk}qM^sc2oU({41!J%YrO&iHFS`D5!3+laAF%U(Ak?x%*6 zuxIUPlBij@f^lvH1jYk%qDUj?TS*32MZ@K)-|WvJNj_dv0iuR8P;e6%mhW1U_6 z<=?1W5}@gU4F?gbVg!B^!~6jdWi>4s8E7vOJ^}H6EnTf^|L7;N#S!Tpxs5i#@HN0{ zWH)~u7uCTrIAxlOrS%6?Y>QHkN)f<0gc5-4RIt?wqo0U>Le7P*h+g)i>#Rv zJmiUs!~!0#Z2a*gln2MXHxAU~zvM-p?)zj|ehV$Q&Lkukp9R{cYiZ!N%AtjVnTA^_ zSb&M0%ut|%)SjTR#jSH8@by|?VtSF5Kv36HiXBlDSdwiOV7AcP$b#~T5m0C{S|>0Q zkYnx*g6ccadBq9POLB!kkX&p$m&siwIA?)PI@E~S)@qa)!^|_e*UVf5Zrp9Ww-jaN z>(1xe|N2mAXPS1&)fjcfRUsG{F28D5;s1|8nAksCF^6CIRrj`}YZ)XX`XJXRbyz0s z>jrn+x)(2g#4UQA|2D$kV^sZzzb&FwayzQ;vtxRP@GnFX2EkG3uv%dXpwZaRVRe6i za=s~Zw7CZzWcZoSSq4^4T7@H0l&mulRh{skH%1rWr1P0!yj?g972K9l3UZvY{NrCV zkTNlCC&-j$DKQz4wVz*9>o2}iVO)aQm06&&Vt=*~`|@ksq!oF>4!R{}kicQ)cY3R5 z`DF%NmX4AzTp$sC#Fv~eCt!)KpqzX)QLe!}WB?LZ-xsaiNfR84=q#B5$Y`P~fdRWL zD_+G`E5Xm0Q7g~sBL%aWUUQ1+UkHxOcpRhrtaFn9v2l7kdV$%78yrdv(}(!kQBrcX z=_VMVn33_*L%DQ8Oir&U>7BBv1w|P}IqM2&L!@@%d%1fbQ}-wD4&;HH1~4wC!f(|e zte!7ZZKP~sri0Eo(g)4s>p-7KcC0@|UNnu!Y&ismm2_)2$p6a5Fei|TDJes#MFCf7 zPC0`Us3jCMC2xS-NUB;em0DaZ?}SS1$L^*F(M25hK=VPKK=_0Dg=DAdr}9SCOyQWn z_#cJo^FGsg;}6KO^6%OHPgxk;7~x}AOTFt@j$EDzy9DE%G83d=wOM=RfQ%}p@(9zZ zWrp8v-b;OJRQ~jmr6N^(^JS|5yJYINrjXb$=I4tSUs*7VE;S+^n8iEl)}grjOQ%#+ z71Gx-U46Kud*$Oac+T^;jdrDk0v&dxVz#uU$TOIrzWb~0lIQK=2TkgeE|c%;CJMil zMJK?h#jAl>t}DqxHDSXxJ^rMdckFo-4mPLR%9EF0vs4h6)S1=1=y&<>RLs0Gmy9wK z`PL;b#@tK#l;l!AOOZ*8HK^9kfZNBTF<6#L{1EC;w)Ml$ei4I>#~PT7drDbO>Pz;w z$ru35I*b`r*$OG>SLcV6uxNTH8_wt$&aDO$n;HF`*{7KC?bCW!(a?f_CB-K~bt{Ry&d$VQn5EfWxUk{nYJdA^to zO7J!NJR1FmmWmF1L2E{A20dP@hV_R3B;ygEz&1MXiNfF6{b*o2i`iwVP}V2IItEA$ zh8K4solo5`Cjb=D-+jwC&!{B%{)RL_az6*q8f?Jo4-a}$t$pI$JC0n&HQwE+70X$F zjV1~JX;3gY`3)xXhuv}3&_o=jbg7cV^eq>#FT)9)H47f5u*Bl*!UP=qL7J1OS9#?% z&=fD$t;FBvZ%{mkm`4aa7L`T6AyN6P_k?I;(MS^d=ey|Nx^lyPdN#4W(qyK6Xjy|Yjy2a$H ztg?@mve_ht49g(XK>qm|-Y!M*{Y{-$yW9CdVZOyJMzGr%FlPPWGXirwKxabBW)+qF_)$yu*9Yx*xU=( zXD}(V&ymo#16cv(lQaFxf~e~#|HPc_D4igGCwVzqY;t>(+=q7hHH0<(^ZD36Rh_&g z2~TP4yLVeJG!*5-?aZq<=aB&^W+Rr)VG2*)YGHRFx&kla&6RU0n4_)iVm7FTQfmBk z;_IWye@N^{y$PZTn>!QiO-B3p+*SvA2Xe==4hFwvh?G&CfUp`=o<4(Idn*9%CSaQDpT?NwHic$jHK>H27QUEf6Qmp{$pF;|kMqqRWC+}p>+9u5o%^KEzeUt2TI}6Dm9u#>7iA>Ab!JYl6Qp^iss~2GNYx}(_jnwI zU+snFdK?C`l)@p^dtL_c#FgVAqKk2J?vpnFgZwA#hu4o;_i;VL(JE#y+EL}H-(kVw zwhS?5c_nj&>PD|C73xEIBin(ZXAbBjRf!O`%t*U>5oXcM7(OFQdb(PPcW(LoN$*T; z5!YCh-rOKZKTA+5Iz5s2KQ90!-v9wm0z!1IX!1Fw`%B7J$=;;Jayk%%C^;J~p3+ps zXjnI$*k%uO$RUezL`cV}0O=dt@d0Zo;G36?|7z@vG&c}ALo7CsMOfe}S-x}QIuI@~ z{$Ia5Fww8Hvvm$wbEH9~0TV=pDhg3h6-i=9=I21#QrTrgh<2QvvU~SlCq5{s(C9 zxahG|^r(AZUsBcnU<^@o;-#B4FVT9Q>r-51M6PzS$`A)>qJ-v>bmg-JuJRn*vMyCl zc$l-IYXC>M&!&P_fcN$%XJij%{lYyn5{)rN?GNfUwC()G5_NL#U&yvYd?Vn7juv_c zFQF8z%MTKY(r=~C6o;Kd5Ts?Jnb-XB2|C9 ziaW=aZ69fJ=?Fp~pV^0fRCJyoTC?AP1ME1c^ZKS>%1P`|Pk~DdvS^#YVoLKDpQ0Ve z)N&0$osVgNEAzC<&|ZcMI0r1i$>6cRKT3;px{nIVvpKpX23~VOIs3+M{a#49V3@mo8y*7%=5OK|7%*QoT`;+^5W`x7@z`*}-qJz?gD#EXUHt zz8wNgN4j_(5nb@;R@6is04+%U9nd|M5m&nrOss0s*oWKo{ zIO(e53aU|G_sz?l{$ZM4K4Kyv|s-Ok{uL_u5j5J+H^syZ#T!jz*R&q+szF(*F9+ye;^vD z^pc9%9lFeHidAGs#naA2l175!v=-*E8j*jJ{W)vQu`kI?mm8zv795#(%)L=l2B%o- zv1TMju~9Qil*oyvC3^eg1=G~Mfj`O*e@_a;!)yzpccMz$HLvmo0M82u5SFQ8@=apZ z3MNb~!<;M3vuJXQe?vw#fOjL>ZTUNdzAsYAT+k;K$pU7)U(t7OP(o29k!PQz_PzBd zKi>=uuOizXeYKoPyt@!AE}7o?(KyVMto^LxSh7aHt9!Xss2z~ex8(WK?7o2S+-AaD z3bS%$n9qkkl={yZ*n>xpvY&VfJ_u;R(;E1LIxI$*LCer@hINyV)st4@DFVWNe^JO1 zfzjEGpYCd2_$S#KmAG`DQxsYNWK z#e=fv4Xdaiz%6dTN7p5oGRi0RjIbde(-zc;Zi*+^Sr~bZQ%?&978)Xj+M0zK#HVnAN*j zk9Qub1JRLF3gx6pU)&KzyhKnW?lX{zp{4}zXbiPL0$qS4Wy*oOn_B;+;ro(-gek%Z znC+rhAS8+zr=W!1k<`2pTY zq?T4Lug3&hsdyd*P6IJqP+xTw&V}y?Rpp3@=as!+!`%>@wDWpaD&|ogD42zKlsD%e zzW$@5y#R|DvrWxwZ(h1{s_BQ>QHS~V%E!7j&rhTmyn7OS3%yMwv632zTto{e@`4gp z3uS2_E?_&Qdo#w_y@|gOODe|h^X$|q&_}%cK1cqOyCfDT-9W4WO0sjev5XKJJ5KJN(MeidQRaP}50L?&~us`p)+ zI(g2JTRa$eDzcj@GMrw?S|R2ONFss8ZeV8pE8h6wm6@LQHO7r9r+^{K<>0OR@CBZX zp%YIoFm@f-J-bq$h{qC$ctoH9XZ_Pb*pJ(#Xq4NE1$^bKY-;~bWU;d{^-uEf#x91z@o;yRyAu1a;F=h2^`2kyI%epZZ zbJYvp-4AGZ2qMT2F?PF#N9N8&s0;qn^Afy3T2&pa`Z;j>1!h}ddGQ%_-ek~y9%#0w zMxL#;jBNa@@(w17DO-s|VDkK;p8tUdyQANG z91flvshoGyYluS4t)tDPV{8XMgsySR9w0zSFD_HcBNEBzY3RYqTq=$hz!@5#9p+ZZ|V66Xx%=m$Pi%hy|>S@{Nz2yUa$V6)?f z$r#@P`AXQ@qu{AzYj*`>u8U!dkV3+@y|D+kkMY&|gNS_5; zqo+UhceNzk3&74lBIuy&)7fTt;yow;!0{ev)$6HUALa zxSJ0uNdVT)%qJl*(IyDaw`NCn3O(nCj|i-VU)m$_O8XK(o82V5;ksAZ?($n0XWVDi z;MLaUUuCX=CB|E;TY{@E9L7l?^4!lrt)ci`wrpvtC^f}`EMZr?^F21uaGby@b7+*- zLrkLI55nh(8<{Y^LUe2-Ls`ueJG6lyk7e*Gc-s(iaLBc{=*F!F!7&}DN2${1F7$nk zo3Y*mDkPn9fY2rg^yCmtiDm9<0^E~5AFa~~t1d=fMi#3CQwoUk3W&wbG7r89+(jbF~8*~hhvgFN=3bs zb;9^o*^7pbijISei3>~{!_9IZq==5AG`;k=J!iUp?3ZfOoT$GdkJhHkd@D<7!la#r zGF^$`7?CpJw}{zuv;1ynI_+MgjTe^|H?yo^UkaDxx2p~CdAc;bGtjKHOk3UveEV$X zOa(*IL3bQ`;$xu_;;FaAuh?EU7>O&yRbQAcwsdH}vK_rhXzhL#Q;Fi~`L2?&@rneP zfG+Y9!|hXj$CdJ9*RN02wkvde8MS*;SWbjazWF~HHg^ph!L39?!HL7=XT>Y>HuUY) z@@mXM85(p%lKW@fvKt5r=v%Z38UEMX;g>=rx&LsL$Ds~jN#cKLV#SNM?HS{ba%f*Y z^qQr}z4vtNy!7UHnCM)A^W*K#Q>YyqR-bPvpo?HtBUd9T5RA`dGnu)=9lIULYKUK3 z3$By{vW_l3ioaDCj4Sfa8*NcNpYZ^&?%WtHpgs8x>+c1ipCZHWR{0;N`Vs*-sd-}I z{3+qG6m^+ZU)kpKZ&SlE^ttK{u%${bVD(o4#C7hwmVXMkXB~lrsmS=aUbXF6@G`&< zuo~W3k~8fY#5K7W*#S19rT}*yYS4+5Fr&4H~XB^65xmRS4LE$Mpr_CqM#t^ z;<1%rjeGG@4)>%5b`kT%<5)>7M8Htsn>WvArRc0Y9w(uJc;$vR!tR_M@}b;q6V9jX zk^~zKQ>#&xugZ@_6l-nR56}et2yWv_YDl&YyvPYE6YzRmMV=2nPvrFIdXfh_P1RJ0 zb<;q)VeB;ZuCGvxj`Vu`ub#Y&2mrR-aqv}Whw4WNk4%PKqB!q=@2;Ah6=e0k+f_qh zE}c<>2^b|neyP=eh|9_}8BRG$7RcY?b$h-Qrn*xl3XrR#;k8W|xR3jRVnj#IfS|uK z17szp6GnrqOaQ2Ey@iT(Q)+}V`^w?BZ!KYVr1ASmbq%&*37-M#$|i6fVB}*9zf};o z&8&aR5~PIxcXE|`f`(l0elyNmDiHa=UDV9voOaQY*RV~GJ^#ZnIAZ!mt7!KBKuAn9 z6|f?`=|H|s1R~%RL54{1%Jwcr&ebG@Qs^1Em@OwZsOU)KU8*_Znb#0Th;Sx$SaMj8 z3}T6*b&E4Am*t+go$AVy`owYR_g(_kJ{5zEPCv+*L0H(xiG){K*S7B>sd|6Ih6dwEs^O z@IXBQen1JZUZeWwf*_O%;9?XjMw%1D{0Rg|Za8nX@fI>=r`_<*&Y@2Np4z1?)#^Z^ z2W>1LLqX(IGsbDkq{~DL<^Rn^4Ur2wYYw&54cG3y=-rwblHxGTG89MNJY~(b^cZogd z=txX}N#aQ|;ouG!S>%fEVKD?1fI`yOSusJaVncNd;#6LF{`WIFjq~d^S#iN8|I{-} z_Myo4`e?h;VYUW#B;NP1tLL!?xnH9?_rE{)0+xFw*o02A2_`AF$E@DG=N=$+t=G$S zaSS>ZRBSl4xlznZe4;uz_Lw*H!6N$*9}UY6Ckq;fc7CTf{@;E|WLU+>zb9<(OJ`3~rab)`I-M68Z=^F{(MQ}dQeVnbAxJ3z%=SEq-AZ^Zp^khI-$g}a5gC3jN( zP6%vF09XV{JS1F$zWaM7F9hQI#Q^s_vHkdSc2BKv`JV{Ax8!<~J~$H?d&#?Bi@HMe z0eEZ$pR|HUaFBf0CEXHw42odBiW3<#tg|e7m?*eD2k45~p%h7m%x#?@F)R~?s3!>& zkbqJQ&1;{_B8eeQaROI%TffD;!Mm=yY)!6oOxZ`o-kQfUujy0ptdg4VeNV@fkP7&1 zFVyd~bt-+CiopZAAWdSq?|Dkvqyg>)0$udlNFCOeUo`7{=A@2UQ;8}7%CgR?buErZ zd|Ly;L*UV%7-sj58C^Z9s;+P}q9$QSBt2(zQ0?Pkm>Mf(H?7pvIKtQ^?ySqye zq#LBWLpr6Au0wa1h%_kOARItCq`MAC9y;Z@xPR||jQ6Vy;i|p%TyxGfw+oOOWk}!r z?8@zeCflbqlXfKnX*F@p??Vswb;dRidi>F+6iu!Vo$)_|>Wq!PdL9AM?6tVR#by5m z9}^SG?5@n075-g)xK^dPo z#8#6Q~6ur zNUt<6L-9FbINwo=kCG3tU8DW$Gy~Wi0 zlfd#%HkSs*Esn^?>d|y9jhwg`M@YxEJZ+wt%*QPm&og+v^)m$9H-H_DGg?}l7^rai z0vU%F%9)lT7VXkaAXcU z@9h}F5#caII{X&}=RP_8_l$7pYa!VHsrv_1_~xx9bB0(@ViVxFu({ z$zIin4CVn2ds2@o#Y22^KL7c?8wi!q2(qWo2J60*&ob*^&ezs|hzEFBX~c{FIjHiZ z)v8{;?7reU*~{!T)7S@l3Y3&v;Bpl5zoL}FX))AV8Xp?E%sZ6;yH zo>A*qS`JTeIx^o5N@LJWreS_5t0^`D78YT$-tc4IW&Xpb$Grq8F&@35Z``1dRL<>IC1i{?MnAjH_P z<8m^h&Y<{&YSq3y5bcTyk}QlEYzSgo6MN=qx4ud(mk1Hpl?o=4m~{D;G{&A@R#HYK zVJM3<@6^4K_bQJuVVs?~hSU4(WZ)5$Uvf=RO+BVEfk@xial zbLOL(QXOi^(Y8l0S?2#Bv+u=tekG}b-U(TiShcrBdT3VJl*+sC^s%8VF1}3lBCGo zn7SgB~%E2c>k%2J6IsQm$(H#8nfz1^>=D{-lw1aMgZx zbpb6TjPW7pTT3p-HZT}Jej4dnF0+9z~27;t`UA z#2X;g{}8?)$g`_y!YUWV(NV+KCOi>0yyo*82c$vy_Ad~wpkq)*RRLsgi3B*Np=@s* zs$d&{a~D299`4ogF`R~CGI!_RDvgjLa9G5)G=7$5=^Ldxxn;l{kYt_sZKdguw*8AK za**}8Qp_9HAh4m^7|APwZky1(t?JfdqfvV^XrVK0M*TUULHZY;g#xB$)-;D2YX*w` zhrT&)m&WXA9k`R=?uljFLv~pXo-@+h6Me9!j8}O~155(rln5n4jf$w2Mpsf9s9`KN zcC660?|#Sr$zRYu#9i{U+wn*Ir%H$YxxZ{Q7)$XDZ43pAkYh)BJBLW357K15u* z+LDolER>E?xtAr2EZ1^dM)=lVf>8$ei5B#-C{2v6&Og2{FB&q#D(&ACi7^n4982YD zXdOT*w(HdZl}7LIB)|-fyMee9Zt_dKID9vOTE45usA$9qYk2clBqsko;9$u*L|DN5 zz5mXD$!Drh7ycFpj_k9An41@Khpnia$EEW#GgvU+?W|>C>GJ1N1}c5c_7j_W4(Cp- zp4ZX#Pv1K6c))I@mvSC)Poq_U`V~??Nt?rU3g^dNki4jG0>+#WJYaYCE*ap*5&rzT zrk3@SJ&bIriw+DnMf#c$7r40<+TQvMfj;l~E^HbLua7`{T7IN_-k-g9w2b?mDoN0R zrhBjc?9pbH98sANhpe!yg!Ci!>p?|1lD6k^$V4NFT?a_@?a95E6S17Fh3C`#v*&>H ziTv(`Iq?72h$LZ9QM*D{@oA5wbz}*W2ZwW#(}!`SBbPjLW0~pe-LG;Epo1;=3T9p9 zEhrEBVN}38o6(Y3rxJe|aucyen8uMzd=WUlkkLVTZumQ5C8L6QRb2Do0m1`nuB55o z>9OF!uLHTO+-cfE6E*94ma+x+D?0Qmxr&=XOW*>G3#>t9A-)-i`zmSF#&6h|{Fc)s z{g{vpn74cwM*X2@Ki$gnU*Ztv#5lccMULyKkg0^0$Qg`mkIHw`5YFg~06srh-^_9Y;2DrV*^M;H|K* z@5TSq&|+{VTuo>lCu>n!m68uX;N7A34T^!Lgqh0vYSFoy2Uyn;q{WuuC~*%_l#(*xHj6W%Z{;any zMTkGM6Sc@2A((-a2981(^4+j}Xft=>KkbaSi69mzIWCu5Gn~G!rjhqJgK=iS10TFy zhsVGUmw5Yo^!`sktbTTt*bgP^H^?m_P`81h85$ZvTyRyF&6DD`E)i!ognnVz;Y{#z zPlL?f2-7XBsbm1`dFV3(#n};LBnuuesBqxt-q>gR7Q9)Oi=UiWu!696TyKoptv4q; zC}Bsn0#!3+lM%;sxx4S*X+S~8HSwSQcm7xlG9eCD3`>osti}aRp-s_`NN&E2T>tt) z)i1M$=9ff&u8t|Gdi-2%P;-wGq=2WO!IL6_xls_Khh7Dw>It?md01tMy76V-@zle+ z=_Ta*6fAZZKx}vz{AYt|8p$w;#hC6G!>@Zj^nMI|MiqMzBDL(OJN^@j17&6eL^j&i z+H8<2EW`2EFs_7-+@!>$x9cz%NeMd-kN5XRB)E=& z8uWj6!D6c#T2{L{Mbv@vRhwUM-=ZKGb$2Cv;MS#j7~! zy(Jrsos_ydxMS83Q~KmQzH;dMrIR%l5N-^dm#E}C{g zjN)29cU3Rz#D1rkd@nzXq0Kh@W7VBa2~=fmguo_eWSMZZ+lH8%Bq0Km$3ujTq`^?i zGcHIjcU7Lz^C`?bhB6yUvmIXahuDdhc$vb~!I<~P=5O)K+;l9oNLD zBs$ffjeF;EgtK=v8YOU+@eJ|5&m6c7>B&2kvHqgc(X<3|$-Vn)NqQ_Xx$9u+IP;~d zkQ&3-cmlF5eLiS8YT}fBm)MJ$!Ywc!F|gG(u|Rvh6!m{zfLpsJ=~OARG4k+%V`Cz< ztLq=1IS@#V5&$C?ojWv(jetp>1SJI)0UP$xYnWrhj^u&z51?a7)dd z%f&r+5RZt8x*Q)4QzHwOKt;kW%YPpwEeb{kVO)9+3vCsxffBe&f1ytU6B~uVJ)Y)K z%ev3uBMhbGe)pl2)TG6g!5UO%SHSro6j_c#FFceKv(;JJ(G!KMu?u_}`yvq@ObHis za)WJoa^z`BT6pZRE48l;kI|~66FNC8k`iQ>fgUk z*kc=nX!HjRL;H#P@Z$`&d}`BLEU_d3LVrvRrDu|XAm{sKYEYrd+=zzU!wMQ(qZ_Q_ zAzqZ2jQJ{!pLsy)0e`97)X~gi+Em=Z^^|B%`E4CVeK)cHrR^2~GJfv?n`fy>f*&q= zZ@<=4yE?*Bl|~}Nuqk65FJ^98$^up3Ny-6_oUSC?(X3KtG3t)hnL@j*<#RFc1lJOO zGL1}`6(A-f){vqzkj(ft%77+I`Ca#4`lzN9vgD5BZ$+(v&GgeD-vL5Opa#`hd$Xp=3qU71zA_@Pxg| z8E)f#$61VY9bJ$7u#LXf3EWs`eWq3~<7tQ3sTRL-bt_aKIbVZ7WPAZI59AKXRrK7v zA0ieF{UOGg3yqD@weIY6>dNn2ECdFHWoVW%D1R^s_Ltxc{pf61>=(9-i5i^HV`zwW zrKm2vIyRT$QLB=Iwqocux)7j@q`&uPBO`ppL&HyIN4%Bfm#fESP1rbfSS@&iIz9s( zL@p$qr(py8=wvRAJsSy=&PNb|+ybp8R){R84k5Cavt?)E9~L1qS9MpWkT<%|X$v+V zj68+8^{uQ50Kw@EO9=NSd#tpwWkTk+6#5{qp1-`pIcOA!^DvCu|6~i!YVL?9hk8B& zqacfp>!n8slf+Nke|dsj#P{(Xmr8rE*w&iYPkR=JoSilHyRb2k3|i`1t|6DJ@$A1D zXpdoQp#}aumtV-+7f<4(VUmuI{PpSYjQeauCb1rZ@^K^t>=ei({5U(^ro341Y(3VI%IAjjj`pGF05 zK20;N+FFpiN=RyX!R-)V9*+y%Jl~5r6jt2eE&ec#dnWoUyfa&&e4`UOwu8=FaJ@~L z2TlA*&G~xK!$?&st1(dI%~bfUXx<&7bB~z9?7M8ryZ(1cVkv z|AQE3y5E_3dhC{qV{;JLcq}Uf3C!8N>!pj$PH=b$a4iTk-1lEpdN#9AX=X~-?cOAa zxWVn%O-$>E^f$Df5-u*5IF3-o4NoQA@@196PFl?92^3MM|Ky+O*WY;kbjHo?=odRs6Z~GUH(1T0McCWK`1k2O z5sZ*2K>W&E?fY0|{#H$Q*Ot7U{uq+#M!plc>%7TDAYI3hKuA|tR@TYA5tf^i zyO*%8Qo3iCWQWI=T#7xNrDJN8$8o_ArvkHyY%_T{{g>e9O6ThEYT~Bfsn_Z|MTn(3D49h1F(ka7u=&F;m7VjKuDCel z|0=bZgo!8rP7w=qzY^i5;xdTptyhpukj=5cy`- zx{d50d_yzS(03}jPp$SQH1OiF)S#`|P$x?yZX>#Ia=1u-jw(_qG)CFa>(j;pzo!ZV z6AH4kqU?bW?r#K}HCuWE39B~N&xG3}T`mnKaU-VHA}n~~4eKm2jI!FARR`NCOmieI}oO!n{FD$RSby2PulP6X4p)uu&=8{j3 zhuLo34vQ~q`hC(S$M#rTqZDkJDz6B=2)8Pgh>GXP0beQYnyL*?UZ-C0j+D$f$Tnv4 z6KF7+K6)_xzPBt1@r9SVl}#;)$9s6zPh@e!P9^TW7oDsF#jinRwzlE;W{2lKs0#pI&=94Pn za8^Jqr)o3mqb@I$3~uXjE%tx|Z`d^`;N?mFnR5(-2+B8t59U*MMBny)ab5{ zV`icOIMA@zDOU&+1pj2VBJyu3ATDI1Q|>Ky!D{owzq=Aj|CWDc!v7W-1MD6RL<4Fk zR~AdENzDr*+72h34PAQL7MSUoHrJ4i&L_ z1y9svnse0rcY;E-u0DkG7X=S2+7<)?&??imB^@%kU+xuetp^$WfOrc_JfOy1z%_YG z>ED|$AuZZ0UiRAv`7?1fy<-dZJZZ4C1!F?F%|md_Ir;D}@@RgWRh6U?zfJTQTke8U zx~IG8$Kzq;rXx^uzW%B?4AemwP+;j?&1!egforsHjwHQsjp}2G2xX|`)a7$=%K}rJ`L?*;!|q8q<2W2=I4=nzT*Tyx~+e_5fZR#dnq96CK4|& zx(2Sh#q(zPPvW3*UwGNf$>Uy#pd7glK5HQRk$WmMGH)T3{0jY0%8uXcZ6*DvF14bC zV2K*wR40D8nTYj*f1VH%-1KDoG@f2>f(3l2x`0(z<**P6pVgvZ3o*i3k zyMJ6W^WSOy)7kb8s}pNpFUUI)80XLNW~!*&|0tA07ND@rvPn*?w&iQ_=vUB@*KK$i z^U4|TW7sC6R$G;5oj2~{yR}k<^9Y^F`kuHO!utayIqXn-28$@EIeX>L%JNq5ypXQydI&1Yb;(o>h4KL?}_f)zU~6Y3NQuhc;WAbey5V* z-_s~)N*XaK$wYn}4f#t{w=9VN3+romXAhg*L^SHF_$dYK!C#A0avE@c_*AB=$Cs06 zu+uuo;ujzgY2$d=Xu+Z)rPKa=@73P(g{mYsf!hq`fLn=v*;R3CRd{pYOVmf3E2;rj_8t~D#0Jx*=^{>T)rfBb;PmWF=2`?AzDMmQa|Ls{GoowVE zT{fRiYq}h(pek=%E{ga=ESg!}_x_`YHN;sObX;5d*20Br#ls3wZ|iY&D?9M+4;9i*qDII3KG9q3X1S5^@?6oWae84XRfMh=kwrlO&Xs|8xj`CBIQ{>4TQ^_vNl zej`gu?cADWUi8N9?J~NEm}ikX+9C*}h*rVQGHYU#y^sSA&{vA3OX>NjNYFF<^up~t z!9TRL+M}`FYV#i+z6%vVjVN6in~j{NmXfp|o!wFt63;0Pti2bcSStImE{1Mx&9^^$ z>#*fN1H(tc#*)$?fOWylI4kM4b$0&lue=AVD7OfX9VKybsX#F=SoBp~+;z9vnKjtP zadrbn;}Hc}hmAAKF^S(`;Ld|LxP0DBI=FYX0UcUiQ>2_t-ZyfVnu(ds%hjytbRiv@ z3`@2*By=h|gQAgbG`qi7;Q&TovF1+Pp!PCE6d-~z zFirWVrL)XXr511~BnlOWW*dM)yQ_4^JY{gG?=P(S-f6ie*cse2csJARb#wc3t>7NK zaC@k8cJFUC)^{d@ye~A){+o<=UzJRSp;ps1a8mnf~O_z#nA*RDUq|>yhABSh`LO#0c+IsIkh<|GH!N-cnzv zEHYP5Y>Z?4o-jivDLmC4=T?DuOw8JW+&ikk>w?%&u_59; z&7@vGIr0K`UKR!nWUcKP{Ay2>vR7z7rQQj8jL8VX5i z*5CZeL&k=;h<^zo-iKzc@z*l{5CtQhmAE4iczF?_O2Q|5`$O#{LXGI^NyFPrjB0pFL3hok>*lW z8&#;vBZ=2n8oh|yeCsE77Hnt9_Z#d8#MKc4A=4DzjV?ELEs3$CTme_jCIw$8}@(HiHp92gp;GZ2_gOyIny2g?+_&%3kkzOb>-m zL@&GnuS}-UtU~HXzeWG@oE5T*3yb|RSLy5{Uqv~Ppyd}32^vl9`{r7f}7bf<4ZL|QnHler~;C&24Wix(&$Rr0K4^YlATHyvV?;+i@@ z$bCvP>b{_hW4~iqQNM~6ja3TwRTUQNfd09n<$aKqFI!$P|QAwu6??FPe3cEByINs=hy z{O!_kDL^#BlKcJ9h1#VmB&kjtOHq|$3YD6$>J8AE5__Vw8?j`im8WV=80g5ZC=}+U5V?YWn^r!-5Sm);|X^I`Cycc(Db9ksl*S===6br9mm6CXFexEzvo7V4jYR zkAgP6!B6ci7+E)|Ay(C+5pwBiMV9}2YRNxkVu^$5KPWRCu=%PLlJ7CZ07|OiznP?)H;&VYvzN0^DeR!wl&t_I0??07)21|3<)XF=xqj zsk{NK2)B4UL80WR+c6;v-*qo!V@qqY$J2N7ytrp>K<-8ldy}}~p;5|WTV%n{2O|D~8M#E+(yw(j6Egyy1ltNOm98#z5N=k{8ueAPQu;VUMbXc<0E>K@qVX6ouO=P5m;Gdo>=FyAG)+ia(R@QJt9iC zJTKHGMW%g zVM%fBwazgvbLwKMk0^kC!jU(sEcxUokUXn(xM)3>FG>J5Iq zMH_Jxs6B1ZM9(;H82retwhkx(hGc|Gokw=E>>-{V1IAwh*;zv)(Ors4kGwdT_s`u4 zsA0t()>-6jnR=JM-jp%Zu3N)i3#nn6moEW>rTN5|$2XXpD;wNewLhOls_y;}ulcGa z3j49Cso5jEvsGGLdPrjlWRB~yMV>k!Q~Fw;XxD2;rxGq7Cy}luGQdQQT%uHhTl#V9 zlH9AGxi7n1OMMSS?~{QEW^2R)F|B&{Ucg1o$JUI2zL0x-N3ih&AA#TY;)&fh=eI;cluB>Hwa9p&g6 zxnc2&w`elom0L0gkbHox3eoOG2PwhJVhvf5@d)XWeQ0<#Sr;xW!Oau}Zgd=UA$msp znH(XASO0W*cIe2h)8pUkgSWI?{gkkxyc!F|?tgJ1PI|MBM}{~iB{e_Zo3ts{i@Rt2 zL>0>cET{V)_KE)%H#eyMnXMrDTQskD2nd|azc_+l+MT-C+p~t&It^doc1%TEcZ_zb zdYYB0Qo;jqoYsGCy?Pf09Y5|~?2-C6*`bNY=zYLy34&viBm;+5&kT6zYF59{c4&G3 zb|c&lvR$pCf{tZFI|(0Mj}4(>J$Z=@_PMuz0e3F$5qu#c&MS-HUVo|ilAjBZa;qaz z`F9}DBupXfUxX8eAi5nntGlh6Cht4V=F(m;f%O^^rN{QE7RZm$yw(fNM<495@7p{8 zP0jv&kQ%NGe3o;z{r~)`#L*%1$+R#jLGAuIJ1VSh3x0KIW@#E4f-%6+)yugZ> zRrz{*TeS929;88Z%mNO(ZQ;3%$q>EpS66SX<2P*kNTCd>Nh5)Z=t~+Yw-pPiF-0b$ z0HX?d52?O=tWoz>(wgiD&#`?Mo89f%#t&uq_C>&MX#poAU?UJOCau;S-Xx zBnjs8%_X}PK=Q;v0egRa%zytj0r$d_AwkvMGeLVs{3A~Ne}ptm$i7WmY2h|WOfI~j zXe)Di$GS4p0KB==6Z@uDm|&+5t6OLG=%tPkWvkC?KM}~j6p&D@HY}pSD5q0U4U(}j ziqK&`}pDcdi88XrY92N$~ zzdrQJhF$ly9npycy>R2=KcTiYMo&bv>qT=4F1 z^U)yo2}s+#Z!PaoQ>X)dEq`l9eR>%tIYI(aXH|Wd<#{dd`Z(#?tFJ1nh;L$^PkEjX$d*7yDqL6 z%C7Q0O1wsGYog##lkF)a#D>ZvskMP(EwZu1(+5@A@hTx>f5C&wc&L3?6)^MFc0KZF z4&WrhUpAgfTih|z`ICSe=OdX=%hZ)1&0)#_ANeh$C>-Hby&5J1b^!)8wm?T{hz#hl z?V1{ML|nx}bd-erDjt;}?#|XJuB50xPM9a^X0Hk3nB`X@xgym@SH21Ns1mq{5}uBV zw(qn7X&V5>4gt28?{#I%kct~*eX&1^5%m>U{0{0n@s<5f6T>X>zLjR7c-|t23iS2w zG2xl3nbUiv>QFTGCet zLgdHcCu$Fb}-LouJ;a zTsll4ucN_}VYlhOMa|eqB|yUdTSnqUuO5R@k5bT42~!^N#JEMW_{i6vy7(m8GAl&=6Z0|DGW4?Q6+DB>-FT_=SnH=UHZ zw+D4!+5un^66ZC>K6yZ}cTYbBh>6dpkc+&!v-zQ}h82)*)J4F*S79~oPr>ls(6>MX z8{he1x0V?G-jgqH*OPn*c7%!9bu~@YJmPrd2evZBrG|w7CV%LXWve zBdmts-{k;e0yvX!uGF<79#wzs>jwmCR!?dXD*#((A6z7GKn|~vjWbGVnTv_ft}Xx1 z3&2X?^FRN1&`-c>!ZH*Ocw{#BwNCwTQ@7EudXk|TeTF>iTG7Hj4l915!u~ad5Ij&1P3;-k;hdKAW=bjR#W8i- zW}66XzDe%k$ut>rfAiT6a2MV%pQb@Dt)2wm>(p<=^bDt8e%|OBinQ&Be{I{ceM<(s z2wqjNNU}r}iVUcPld0{CdGm@V^Q$(LV=(_sYJn3rW|MeA(>&;s;+eAdC3LagDeT#m zVMWaF)qw>ph%XI4c*NhW*?N@yJXFv&Bu;!o3Zz6kTHS+k!X&H;;w`Vq z^KDE(LC^guq}r)@g-BTN)pHhucek(lCqBJivml*_m0ri9LI~9vmSr|7fhNI#We6@I z*KINGmzB_JaLUHSKHT4c68k6?78X4{O%aZOYnd4oO;|SNq@H;kEBudYB9TQgCZV3C zx+M$!RxWjdenwdFS2@!=GMEVzm|YpAwq{?}iKGEjEJrx7i_WBL^5>}U0X6(miyjQ; zq9shrsv)WOr7~3`q+IOXg0>KouA~+d3)f#Ze3F7aYdNGojxKnG<09!g;mDAW(I!${ zOU#mm#2*mLcMpGYvvE_ENaS-_wd*ZnRxapK$HKPfQiT1o0*g)EFnOQ0;{2}s2 zg3u3~pJTKE^{0As3!B zYD*(S#wDdO!7yBoQ|0P*W_l$H#99TwpUAzag<-wV;pL)DJw`XhXi> z*Ge@e^Xeo0fu_A%!B9-1HqVS?My>@M+-j9=0Atwd1Z&GctNbmK%Uf6`E0s8jXn^Sb z6--!0f+5zkkm?pOkkv>O=Ia)V_6+>e_9&t2flQ}^fDH#gxrj;B5Y>^I2N`gF`eGm% zPrJ5YFYH(ovGNJ&Qaxg{-5!GzcrlWC%jH^6IXAR^*j?^uLflCSgMfkAcHqk-uR6;E zL65wP$IttpUH`vc<`S=$V1MCT?nhBhWJkB+3 zseQ{R?6BqxTg8QoEz!>5c$52LPYcQHm}I#OtjPq0B86Z*sQ~YhjcnAOFn8M2P3F<@ z+>-bLkl*S5+U1v)@}<}|(DUs+`@rRe$r7XE#1r6bk`S3z!S;fvV=(%Vc}0{xS?Hqj z>yyY9ipBCVL{uf^@P>iT5-2&&e1fB0w{Epyw=NJVn)CbBFK)E1KneT?CJ%}Mjr(dBNEqW}(IMuSNQcMDl;a*=BLKe_5EIJu{x_BlHHBSA4 zUY8R-vY<}`$qq)CA$ALIL+hx*X3@aM323Pi^IJh(f9>X^&VkU)#%4d8UXnWPTg7R*k z4mwDW*YutLA|&tIiP_cbNXqBJn!w$l-qbPe3_;w3+OS@wo|-+Km=5lFs(GAw1rc}& zUY~i;^Qh@&nUb&#P*vy*e~tULzS+UJ1Y#oG`h6-FHVLC4yF#0nPo501R=GI3aja!!5F(y{O7+*MpCAzC zSP!LL_D|k~2^hFep`YoNftcH!@B!rX8Mn5YK#5mb6G#t$+>YIe)k~kZ#|)`F?O9?j zPA@rIzP5-qnM`i^G6HAQFECFP1D346?_D_mY@Zof0C3njd=mF->e1M+FZ2U$;_daN zm84#iZ{0uQ?T%;{#}%`e4K_i4*`-#)1(6+Fo6g0BQAp_*CmO@gho3JJ7(--;UakSQ z8T04bx9nX9e=jdM(oUaYvo2ywlP4@6n$+`MBXTU+^}<($j|L(&i$Sm5#HKU=pzC;7 zh3`Q@==Gt{kzX2{(S036J?UzkgQBXP9ZwLl#27`&ym)pN+oWm_KnG)$o4=ULDV^~D zl%IV4^|lNL1C?gbK&VS)kV>XxArxLmkx_UEfh;gOC`{brY8TWEDy_Sv3v`1DzfMpw zjQU!o`Kt}?%1{)oN=K-<2$o8zL*%XNWywp(N<%}rZjQsh&~k@!gAN2Nhu;>Pw`jVV zlYHTWM?-B#mHOb@o^Lrk;QBw`M4Ms^P4YeXfAX+M#C!3uGM@}zy}zJzd)Ez~(DUkE zCiCh0z`bhLf^zmC7Y+`f!`GkqD6FZPPiY=v4P@A!gpSo{*2B=U>TUM>w#<{IU!)Zh zc#!VFQyU1YOWv&%ICb|>63Jc_CQ<=Oxmw-t!b^t+>TwWDsRUk8xkt<`X@~q=Tcf&+ z0lOH;dWNbAc_#x3{oNM55Jg1UqD)q&N0ggIlu>pYv9Wks0cHulDe@{DeGKr){KQfO zCTsH5u*`@xi?6;lr}!<6et4ot`AZtx`OjnL09ElM*ZZXY8&pJPw6BB0erSkz(yjk7 zEcfBCzKFw9F2a5f4@6nD>eKV(TG_0$Rb)%bQaS~W#i1P_$K{O?3wy6y&%&vVioG!_ z{4W}kiTGB{CFSbx?Jojyhy#5d#-}YQqDtus)xku6CcfX6^qFbo@cm$751LA9F2zaC zzDPw)(JfnG_-#J;UCOPTLn=kb!K5>4=N+z-P2>1N+IEEPABnfXVcKJ}I??4Bl#P#_Rya~k!^zRPlQp1uXaBxI6>3>Qbx@gEB-v%3w zSiF|w1&cj9-kpDdRf(5yCo9+c=!I_wI}>u_5eK;=GYw&Q4T}5R3eu5OSTAQtVJ`GC4`Q47AZQJE<($TjNE;>)47xoV5=G&bEJmigfCwXL2yG6cPGqoq?6kQP{3rxai*8`*)}Lx)rDZ7 zI$Yd@78sE{r62h137d~-jDYR1^|&LgJ29)BGqtoPx8TVw_X>i6WknhOja;#k&>g+t zC?A3tu^37ka)jI+i320q5!1qjkt@VDBq~1HK~LW~yEfi{s?X>GpyLOF$|3Mhy8{A$ z^d}%0=u;Y4Ikyxe8Q*HQb4?2ES_?WVEETj#w27Vdi+NaYG|OOhInFNipkK(|UIV7z z=h-YSrO1+?pOM9cO(9dS>WaHPU|rU?nWYFE z*>oHDsSwF&ssINb_it1`FAA$eI;E%kbHcZiB>i)sX9KXb4?4DZ2;4n52d$qM6eu9r=qDC&36A0nvthr2C$42{29A z%(18ulmbI+sG89R*r%-W=J*Uo4l^|*-}CklghO|m01h|w3jble{{+DoLAEDgku#&O zo%*5f>T45lqlbX~VkT0N07Sy?o+c`nj#*OdeyO$fT|lGQZA3jn8eg^vb-Vvl#LBO3 z4QojYy}*o20`q_7Oly8fG-cGFAW78%XAn1P3~5+zbkPD;)B!%o3{7Mb2H8@)Sd`X% z1nKz$DpC7tC4#I?rkr=hu~y_m#cs9CbEkDL4#UK?cWSI2Le1B>imyCbp49vddZv+h za58RbjKVAz6$gJnv6xgFCh~fn!4hB@Z^Dn=U0?nQ2>_o@GT@MGkkOauh0~R_mYws_ zuvCxv&L@{|79v?D-GtC)XYFTL17eY;Hz!M_AKU6Q<&NX-C;FflPk+{#HVW0{-n?ogGq;RWmzu5T%o z1Vn1$A=D_EE6ma@sgDQ|R%s&$!ref?f@7MaKC=GVaEhYY?0sW(fM10ck|AHAjjT#e zk~n_pdkIBU)`+%7@qQx%i7met;y_<+#{vU0VdQv3019J}Sg}cK@fJkW_Lk%So#Yp{ z#3Op2*MD#^mHeI&Jl&|b&|nm)`}>nH4sH)Hjx{;|QrPu5G396HnV3Wmq(*6jGX;j$ zS?Wvca04+aY1rZ-g(cm&SITgzu?4354*}PH)rqmw>?JD(^INOQ37ebavAnUEpG3$* z!r2Ppsg{T`guSdF1aQNy83&vjcKa9j3e6&)oQ@dqXQ*r^HaL#snMQb8SfVA0R}dj%C#~z_;{=mlIPfeR|W5 z254xpLZ3wvhrQ*mmN*QRvJUym?+idE9es3U1bK(uhB)F$%McAyiUk>vLn@CNT^0UW_IN zPFUoCM)H~nS|+CZJ{NPYOfNaU7@7T%rO!WErJEFdS51evTLlD3@nPQt_^sTy!6I7&W z?eSx0!EsjNgBaUgFlTVV3o`-JI|=>AG!D(*?1(Ljt8lB*dZ`j9Vz%d?&7n;E`}_OG zmw;L&!?TsI6N>$i-8->uZ?hQU57D*=YRJvbdVO)W7RQa=KRM{lg$wqGMiD4!Nz00hmOcs=gkaUpGfvKn-`P*68$V^@ zaE9vSpJKxjQG+6=`i8M@VoiXy!Q{Mv@WR(5YvgIf%h1b>e_-0w!Iga559AOsifnnt zQcviEzZll=7J5++Y3k`5^|P(ae|@qt3Af-e^@Rnne$aW;V#AW$CR-iIH*>J#&4V*;AUgE8@2oYIT1=8 zuON74Pt&_KGBEQ`r~9?1z!}$uS@KfsP%jAv4~s#vZF8tN|7}X`RQ{C#OFsOe?|&Q+ zqM6AzQwXiY_vhnu963!`hAeGJ2G=8kAcmhUd(ebfmwv_|GN-i z!}$5dmUt7KtECrMi#pidq^(4+GjfMh4ChQ(PrNg|PSKnX%nnRg z|Ht5r;SDL6IBat^WT^{xmYtqEo4KTQ7OaW28n@lPwIjDL;)O~wgxc{>N0#ze9WU!t z4O?>P%Cy`+YFAIaMqK$bC|F zd+~14dbIy8Ftg9nIBbX2C~TKu$0wKjsik;aIyK5dXOPRbIK@19O0b#gLSNl9Ayvu3 z;R+64IuZ1v4@R<6>!w((hU&o;EtiO=RIS89cI5Hc$5NduC7J?)- z^tCw-hsk=qa_sk{CV60s<+L zLBAnB{?M6E@PQ3BvPrH3ZmdgWj)lDFtix>U$JZf7%h9f`6* zjy-SAZb#R*<`j3$AXB&r03c5y^{+l_^O_KJM*3u@=`I9M-%RQ}0$)zH?V65pUcW~# z=O|c0Ja^uE-f_A|a40rPcX3Gdwr&1h#SPyc!Y1L7?(%}_!?NLZ-Io{KyPa#+6Vt-e zBe{LVDgl;5yPbBvU2=B89f3{1UMzp^0)ES=7~7top=*$j95aH=6~dh25zs0IaZ7Od z&v#F65Y^tOS&BWMqxk!0GFh3EQCFK5(#F zBCfPAmPL*U6zn{}VcR*Ab>Z%$cBuTrx%{F#w<<9GC~wEW7YI8q;L^39#5jVzDWY=V zU;L1u>)-Cnx^MTI`;rZLa}peXGHxm_w4r82WbJR_6=9`DXW8}tc>2n)sQxZmknZlT zp=0Ro?k)-GZlpT|WN4%tMWwq_V(64kX{8$}@8SR6d!P9*U#8BP->$XSUi(RCBVLYb z5`%K7(z5W7*Q#I)fy9Xv{!7#IoWG~Hc86Ll0u7`P#Hzcd(p=-{uDkt>ZMc>VFa1Gv zILEJj*vlIfeVwfIlnK^I^yl8UkZQ~!z&=S&7`0{WQ2nf$zZHK`U*jS1wM1pxP>wv_ z^YMRaxL4fBW#RaYQQ;%62M0ID0W*Y3BmFF$Rx%5BJbe%zjZ*@Cp1c zoxTN>EbUM#3a6#fXcy&(dzwR{#dua-avT<%=S8;|x#h8w-u#PEThy)0Zq0 z)iMc|aKGRlZ~#(nz|s~%5dA6}J-i&-Bz=tvF=utI?qyD|Ma4Nl2RD&e%wmfCgf*KS z$GxNqv-)AiaeBXa{l~V48tLrh#k~H}Z$v~{>>g5YvBHU)!({5Y-aWOT{f&pE>n2}v4uCM&R zAg{D=qATv7l+mbIG0MxNz*?Zcyd=bv>)WW^A$DQn*ho#P+3I3-m5N6bk!8o!ksd}v zmz!j-THzQqltN@Ej*V_cwmpiD^e;W6|$;o zZzVFlD>rv&H63L?C?8L#rq}wd`xy>iNQa6BY=>>7S#W9`j!`rPG3%o)kRn-+D@_f^ zQ%TksF=9g1#&0BPRBE(nw2PKralErDbP}P_`ZlO8eut;YZ>3mZ5$$h2DE$lDnw~I1 zHa_ZKONs0Tb&OhCXlCDoZ6}w4l~TmO;@q#V%D~fq7er#Hgw5W` zai2m`!!n@FM##qJ0XOt1DkuymLiCQ{>KBjC(5Xtn!8{WaaPlz#yPA)%!wB&)N~y_b zf8NhwUkTsYyJ0IUsf0DRuxbKt{%JoyNZ7N`pen=l!#S|qCfJvR1M_Rd0ZC>x?rO&g>_w+oz08>J7o zGP6n=6V#8kveVIuAO7u;wy30&zXcM~TcAuSFq&S{O(H?I?q>lMjRawlPA1LaB<{_?V*QX z4|aN1evDssol~s?V%ml1QFYqZQM2Tum^2p?a+B$CHv+#RpqlO zk_`gJ<8!p7{g8|tXPJ^YsRqctGmZ#bNlf%_Tj{Vt-JgWbkI1mgk+$jZk+D)zH3%ff z*xB~|fgjKj$F(jCXhR+@jGb4*9)t(ML9Ik$=AXg_vn69&w#fJT`WLs8^Xr%FJdT~LvE?ANe&jYPA>Ks?h z_Oqm0v%|8J=HQ`>F8#v+hi%P1g`WR1XVzaF`~&>*Ya9I`Q9eKLnDI$lPUgb045 z31SR*DF+@ParVJe<0ftB9R|h8H&DN|QLQ)I9q^ndC#C5I_FtRIse1ilJ@f6cF3GL{UN+^ z*hz<1uTJr3;TI=`WFz&l7v2Ad9qcYagqjyIig1%4?kfWd0t-nMHJv<6z37f}!ICtMeEx(w>04xR5o{JG+bzq1}Kl)6j1N4R^$2xV8HqXlO$Q8r z=nEJ@24qJnsP=C#%$vH60_k|hft=_#reeHx0pc`nNLwfCUey=9Y+_XdhL$nB>XcQds&6SG6uVJh;gnW6I7ib+`45tdcvt|SwRFdT4}bzGsV~vi&Db}-%K@{4GM4<`jjJF zBU1s$Wa7})Imup^#i)9gk9VMshlVz3ob5F|@G403%)T{|j*&(WjDcV>3gdT+PyjL! z3i?GYAj^E!%1^l6jO)vL#587IWPa^6lh3km@#rmTfRI z4IgDt(7FzAkuv>Tmq;>4T4lF!Bgc@VQU7?QC%%aZi|nN#Im_`|+=?YK6@tzvD=*Ud zdU`kCeYDN(5U8jc@gN!cguBR6S!Y&gx^EYA1ItP6V|nb&EYjmeACLfRK#$3#e7n4s%CL^G)6H zuek==HTLlgmnX0^Hq{Zd&Uywt{8~MEehpOTRgB)HcTX_i{H6@3+QxjQd~(Yoky==N z-(_j+7}@~(vm-xUw>;w1{#R@a46|VaYWs@2CKkGv#+jA6jQ(9Ynil0l>8Xo2e(bIw z1;bg|}g zRQxPRB%0Vmn9ArjuyT>OGJt=YsZn)iD%H?KG))O-xn{Bv3@HRk=H+o9x3`elt&#+i zZ+esjKVy&Gz2C{DTSd$9ph#Nz4ynn&m3+GID3%S~{G2nE@={Vurg%dI<)6RHf3wZj zE239yW0fqF(wmM?p$(w#Bw>(@xySRPC9~xs&iZcpkS(_HVwWe|)Pk33P^)(?F@+Jn;FY%3Xn5$Rt~*^+ zki*oBr8Rgs^eyYqAbB8x_?nhwIjb2oK*m*iEH@HYE)d{UVtDqOQR9msKq}CQEBXCj zyh72JC|hvki6(Dc+^02bWGLAxuJYlyDY$j!n3YD}V6#@TMnD@3H&(@`7arHrO|CCs zD{7FZl0saKOeoL^M6lrrP?IVzsQQ;4-mTi1W0+ha0>hbyr^NryUYcG~8d=c=HmClF z{E4I&DD7-`_Z%Z{#lOdZ%ejQAbV`<`6m?j3gA8T*-84(-h-g*Rqa)FJRjR&0ZuOAOwaqO*}1BY_1yV|t$T6zcu0+#p~YMAV<-7Z%muOPGRH)XtU7cnq3woVgec+^A{$Ys0t$a< z(u;HSv!~Bnk%meDjlpkQj$7>n(3&2)fvsDTC;W>_@(x@mk5`l5GmsJPq6Ham^Yq$< z=b|_%K4MGYik^^5Byav1h?yF^A4n+?#l*bd!(K@I09zxf+|&<9mjKI5M)wd)JOYag3yY)IFGNwlgkty+T-5iuV%3;z z^uEOknJk~1PYehN%;ix1^+(slrFLM86e0YS4>H305H5heq1oDbDq53?)_KvjT6Lt_ z2uw-K0;|yNYiv6eFLxjLeiATD-8ySDy3HAEKO559p1xLK<>8omzq3?-{3%{H!micE zt4~A;5y@iHrw%Gqjz}e8z~`_{ufHF(;$yDhY5z2vAjt3R{cq27K}6^5x!}Z+2{LVT z;oVN2ul^NeHL-DL4ZfhW4pqpWZY3)vvx(R-u9N{4s#SO&KwL9D*-#JvZ^UtM^g<@b zQ2I2)3-KVWH(XFh+sQ-3OW2r+o1!Gk)#1hVY!DG@%39=tA`30{GsPoe)U{Dg#TK#r zVlQS%_D8kF4<3d(j9xTcOiYe1YO)85)wsWsy!pVGyU1(sJLhy;iHdk+ z!DWX|56bYFjdusgcTTmbE-8peO@1s^@fK-d+DtE$Cl@hFWr&@7I6j>OLRMWNHt&1 zSLj%ew~jmG|8p!@fEbF=XpW0b0b(r6r!=5UzDT3^w-xD$ zEt0}m^2yLnO)R~?3Vk?7e-wpwKMIkFM^YKR=1XKZ!R{_sEelwS z{9zZxXH_>)YqGv3@wO12r4$OCqf9xOeB|$OBXH_pWy27_&T=%&e(=QH3Oz*69Prpa ze>Jtd{45Jy2CKU(DsGtYZ{z7DA#ZU_ z!ND?!IbO~&xnnv;ISBqUG377(eR|NaP%oK3TFnucC#uT?N%0|$6#8c3jI3dYV`04> zln%mD0wGQXTXSU*h>+?MBVF4acxYQp4v*>Z+9%IM%zU)>mTDyvXQeBQbJ3{6ppIfw zd>0KXl@(ZWa5%NH;07qqqCmm2RMTIno6fuvDT|;ooCV?#al7k%*7QWoSu#9yx)dJh zALvgTZcCeu2_`2=smUkT zEAk`C5|NjL*F7%Q%|_2z#=(hllOA6p<%kVX32_FL;)%(60(mf1fIVs%P|_=>;1U|qAj)bYz_RV3c+7o_2VncauE1r6A2g3?HRi(0_# zr)<;gdS8As|8Ej-%=(J08=_QvRw(YKK5eOW5g(8+ZvB?5&T~it^Q@+1TD;sj=&$8y z58x_Ve!Jp@(%ch~>92(5#VwjNsG0NMTXBXQLcY$WQ?*5HNJjOioe{aaM zBC2g^$t2L3Sl5>*j^1B}H*p@yq%^bWP(OHg9uGn{=f39rE`n#P_pxleg;fSRvkGY=v~0Iu?+VF@3#czO?r9nFwWxjeIXh2EckW(2X(QTF(7h zAbxwLJhoJP=_$OWFBZ$3rqPJ;1-S59j1XX?m?zC{VIU=6wd>zo+RBu4d{2C3K5&YV z@};*`y0!NX^B(!ScyULaD)UhNq?)5p`6p2dGeC9qv`8%^0`k5j>iv^Vz1Te%h4tEc zk-<@Vp_b8rTVX`>OL=K}Oo8VoT(xvt?wUOrK;eWUe##Do;w_=*pLMyo=ALIh4|zat$% zd|=J=oh9th8Y^}0_iiA$Vjy&X^7X|Qd_xZC>1>C^ zM5>c>S%r2FzZh2XzTS)msr1%@!OD%2)$#kc@7!`Oo6bUJHUJPS*zmQxr8E#4e8>@4 z@$%BNdQFBKit%&>w6i2arw@XG-yVtLYwbB+1FIH$FmWMvaDUWhtmVV4?>5t9`y{&^ zlld<_)VK$y%dr&I#pTJvjq~3TaO8`ZoezLNV5RD*7$T8;uYUR_kcg&@tp)PwTk7nWZSrPdIvn?4z6+AQa`!K(DQ6?BgQAvIo zpKuC1dg(1foC3C&FT6`{NQk$?>gMm;Ws0a%J12wk6>BIEN~ zm$tTbO(1pCaY@L8Z>YdKxN&GCD!hXLIs7i11HysF5RI{6))zLQX^GB^9Qg;KcA_-+ zJvLSo=`OrW)YhO+)YzLxbom;MXyZ*a5D9FlKu75GJ6Wy>Fq4+tb+(KVHhnDR50IaP z{1}7=It^aP=E*z?blgrI}2@;dY(pjAJBfJPy0KLv_CR5P&1j- z!AZ{>?++m`8&kXV?ur^1vod<)B>*v_(#Z(>U0)b1?dy?s+Gge__W`(aA@CMOA1n{%mOpf>h#Xk+b9;S$+Qudx_-eEW9L2)w$L+** zOAxX@^yokz#P;}R$Q7yPCwxsNBe`Ja0*Zl)u9X67&mX`ciG(HL?psaK77&W&cZ3zH z6Qn(E`RrkSHc{upbB-g+t23;{Zxs}&MDL8d82!ez*pSQJll9*}Wmf>$T@Awv)__}e z&m5%~0Ft%e%^v){`u$O=+c($MXWPGMH0$sy)eh4+C-zjOxdT*vdgHyTcoO6&hW>3s zLJxxLWr2pMXC_7Vu`j^tQNRgBx=!<4eBfMp`R%8X!ZY?7A9=-XhqxhovE~RIw0QQ) z$Gv|1;ij8L4mIPRUUuoP&EzbD>&(&-ma-V@)}+wRiN5&f3I zmB$bhSns&l&30ec2h7IW3VS+r|4rW~VqK$$s^JRYL{(+tF2ru)AIlzl4^5dwn|@_o zHg3`Jr?8155+G)~8RFIfsbP4RQq%ESwG32$+@UHfCGL;J8tw8zGf*^P^?-A)B3XnL z!0uMSmL&^R?c7gT?=8r?82#}EsAq`%*46ha7&vmBP1Kq2HSuI2)EoKECL6wx=em1s zfb8Rxr%G-V|2>B~sq(};kLkl7zi?~))=4$m6jjLS&zbyOXi8g7WS}_D{N3<8L2kaR zG^yp~58vO?WgJlt#oa0Z>de!|=>w2Q(qj%arIF-CvcnccPxxS~?izDT)2LaTkc8nW z2wkZd>BqJQozA+v%g?%MWbg7OCtg(qfU`c-7TRI_pz~44z9k(LS%P&HMqA=w@=`lv zsd-)C)4B`axF{pl5ICH&)3|-wJEZnYxpj4QuW)4rF=ZF#-bvQP)dbxF0c1nSQA}* zS5+|8B_zpI5U2DizWv@7_DhZ+A#w88)psyZ7gjsJjOZ~pA__0rjkSy>zg#rkFaWL&!(jDG)CJQ=TF7X&^~Z=H@;v7627~^ zYabDnc+>p~=brxVo-9vrbapzpRXuz-lBD&+^=m91-Yh_yE#_Oju80L>L;apnA6u}k z?Ru?xUARM>`cWUpmRy@pd^ijJox(+hIMTytSDtGqH<=*wZ#=NBHLAjj~&Oy85t^|x=;Sjap~HVr&~HtV z7|hr*6S~2HxeRGc4J7%EAVKqXcX5nQf8-RZV4|gP6!5aC7i0qYIUS&XCcmfA3#xr2 z9*1T@e? z{69gH-Mr~}~t0Xy8;3)=4$ zB&-=)Qsk9`pR($R>K4fZpSfzL-ZTFOu%F~~k@0(IFCfv;Ahl)GHy3x&IB{V2mDV4C zGzoP9>HVSiwrnW}!Vyfz%0En0dZpfB)k3%UumY`*{jH-ZM7_>{-9VM=<^QN#HzAy2 zoj(eqsP9DXnO~^L|CtP#lIbsH{PwE~Y_`|3>=e5Qi7cm1f!)@_Tg8RSU{%#Ff}T#_ zB2MjB1T_)THQH9Z5S%N-x>fefy*Sn{nl{K4Lhs484jfXg`)b$JjWjC8L-+dAfonWrM(2<47P^!SgP~mj^4r2)oX9)cegl9 zYE?*TJVtf8p>+Z4M4h4~jyr)niPhs91+I-Z8@yA%SZ=Cc!QRu*DqqPBu|XB z7NvZk|1oLbg6;OxwZI4B!=^~9@Fis#@N5+)w%$K)`tW|!DSlLrr8EJtMo>mSb|8qU zU;8OAk9?M+BT#11{1_PS6*Hgoz3GoVEAO;?v`=B_#4I(%gk|(9*NR#rj^*+S%A3kt z=YJvEf9;20eu>QG5|E$t)t~9!HWV#F%%UFy+|xy`cgefNpojTNIKKf*u#byk(moUG zjH#S1UP+-SPxALnTEXOQG zeAWLrA}^OfkKOgVCb6R$-OwHl4DRQ_=NS2m%hE6;a4tynCgc%YYaWEyKDzeoyxo62%Me9#@l&#{d z2~$#4-UZ8oZ)0@T@qxmhM1OgJHEq%TiK_>t=JybMlg3c02W4#j_69R-NEqDZ{0{|` z6-Nd{Dv??NkE?*&?KbokJ>=-ur(474or;z}cjzy}qAlV{s_I< zN)*=Qqhc5Zzy-9k?MO(gyHzr+NjD#E^)0dYS+_O)Buoj%F>s#%fO6SJj{8Xa8!qi^ z;UZo4^?k}bEU!~y`G_|06Y}>yhc%=R?2faxcHl zfaqkVdy!bhwb%@ZSpN{Hk0R&11-UP=bOwtfpeoQ}?`yTCm&Di_6b~}upL_o-huyAM zW1g`^#Wh0flSP0m%p|bPSR|H+PN3?+p+!;Wru{;J73j~VZ;qj!{gbQwSq}MTnqp@@jm40gye#)cbhG;v^?At6lE4jaws&vKq0SMF_v@ zso}VUcOx|yASR}g(g0&tSreqvsLC`3M6yWDqcH_;65VguB4)U&KwAirezf!ewlv}} z^L!FPsgj5RkDK^hemRaMQ5>dXHk0ssJNI6v9n99M`Dfm=h)p07+b20ex@t6(Hk(&< zXEbKV`>}05mfpcIP0t>fr=8g(T+SlgSSc^=BIf4i9i8O1VJ>sgxE>n9&M583 zZ%W1h;O`Mv>=UZY#L&AuG&x!wuU7zxclx)saIj%Vj@^4&L+ROm(KvN7m540pt{g-8 zPh6@YTxw<8^dKJ>`4+6uuMAh|Cd$ksT7Ui&<3n#=59{BepG4!iC4#QcA*u+1sN}SG zojLXQDA0{%rc?pEwGJa9diPHnt)p>+xCRz%AjNNl3lsr{=lr#skYK-CtK*iaXR-C; zTqT+z?^+-#Hm2`ItWFq8CBI;jipKaYkiGWb_ah+^0MD=6c$>SNjo*;PX4~YR={)7Q zmV29m=QhBqCDOnVA&YafubZheNmdy)Gi}QCJEUM_!}x2q%&FanA`lRZYkReJnI^ zn-Q}Wjk<_z>=h`592{HR;2GPa{?H$A*}sOh zCTjjXW{)(0@5sL>x$FG72+jRUSJ4{Su!5Rcfwx1t<>+7CXDFRKV3tgw4|@w+^QOk) zxGsHtUfwJ>vGseC#&6nD6K1OvA;LInho8*7hPD(t(9Sun)d#z6K7=I=Z8nv(4VfV8JKA;2=%!FE_j2g z=>6w#_43A?QUndwl6mrcrnQV2mKp6(DtT5K^-2(3zH;omTGu>5CsCT5l!qD z7^#b8+DcEktLu9FGrSW(o_BF+WL1b!`3=8v;XQ0~rsF+)I7|=Sk*oaWb6`D{t8}Uo zLD`_%Dhw)RPeDmgOW!^0)A1BiHoM-HXBrf(er=-2PKy13UI>z=vLrb0+tv);E_&wH z^9^YkF^h|oaWtDtRjKzKaR^Z1FBu)zDGjw?o|;Sao4AY{9MAMSPj8 zf-9-ZtyBpG^u02p{YF)fHxK1>Ko%~%_Ls$qvS?PBN>Du#X1+FwYdAQ>V54y@iD}Lm zH~EnwbHWf1nXfSMIrB5ZOyG=qz;^fRa_d(&at+Xpy`o;5{k7wv(oadfXEo*y|A=~5 zTplpu5|%AE&2B{t1y>O#oth7c5UD=>LXK1U-~oSclUnPyYi-&Q>UsKdsvdk1|7jPO$VCo;(v?LQMZGh-_$n~+Vy!D$E+BoLMSlh^&(<6y z;0znodOqHZpSz}>&pTAy2Ot`Cs2L~+Apona^nZYUq~Ye0etbG944Hg*6$WW2g-}3TQyP&mNu-cnZY<7T#8>pBbO)VhHez6 z3t0AA&|mg_8)*bkDjTiwIDQGxg}rY{Sn0f7s$>x!LUBezEs22EXE|)l{f4b?W!}NrlJb5 z``8UB6|5`53-yF45d^t!~4Fspp(sz841&9M5yVsKcsIl&(Xw0)GL2b z6=2?JegcFToC%VBIWrCxhS;DI$zknz0=M6`iEj8YN~+DKhLHm zJg+x<*dqHIKmI6}dTm`}h=aNJIXAdBAzusl2g z5iW8J_yc?FVGJ@#G(+SD+xJsL%tXcOuPA4PW9Y$;DhtoWD}Z*0hrWyM?6RU=o1)z| zbhpNmH!g_M$g@H=rolb`#)CqY5-Ok=>%|gB9W0m5rCdfGG04=W3V#H&aJ5M}G)aZ! z9YATpuQ?pIfFUp&^#{!1zP-)nYDr_1viABU)omognLxc^BOPwiXAvngd9mN7E9nJz za-YUJ!KygZ1XeXR+Tn`ocR?4kcj3YE$sM$S+=S4Qfb+4)>Rn9FjjwSDdEw1=17ab= z@yQLG1Y!YVL3icwl*DnsW>@ZesqI$vA-+o~W!vmL2$uj|V3z=R17?Hw;scRetEgL^ z#*ZGwU2kA`FS=Qu5_(U3UN*pPYmqPcL9sQU|D@Sh*v#pMAH#U*Ad5U4vbj_{`%>n! z2!LA@ozao@y6L72$7<+kA&5cJ?kPNGo;Kpo)0r;VBMYv3ST;}L5Q$}Xq@KWPrNIN- zqXOMPzP&W{wfzJeL;*Z_d%dmq?=ne5R7C?vt~vvn_jvM|fty`i75&9?&H9{qE3H@i zhxi5#r11IQaaUln$zt%q-QWDxB!8bNn4mNmDUR<*4qX}b&MK1&h1 zVK9m~dB0EneK)Trs1DXn3;NKx{3QIu^>nP0lM?Jvx$zw$7}1M#k+abZD)SBnAyO^a#UD`7Q@H zZs70bA*J5eB3lA^E4U_7%b!vh&~MT_e=o9-Y6kZ&2QLNX6OwT_Ij^qYfUI=(5WVHH zF=S;p#0eR4xIx@Ay>ptMR| zixs`tTx?o#+Ow%rrZhJeA+-m4^j1Ur!R=Y4Oc$L$HFDt`NI+2;NY&TmwTHYaJe}HXn(O72$2n(;# zSAb4wJ0PLXrRIffOCZb?AiVsGaqqK2=JfMh1g-ir+|?Dbo6m~WLwbz%-@du!&2{e1 zBf?z0JH!-vu}F6dfe~c5fcBo91tiy)v;HbDU;7G({7G=Zv3E~9Sv{>xCfrJx)aAeZ z;1YPFMABpT16>$5?F93zTKE3jfZLl;fd3T0=d1KM*wt=s*#Ie|_m&k$IPSX-YUu0! z$qx3Yb`Dh*v3^1w)1c-YzAyB3X*BOzd;A3aayOs$)J3M!x48P~gDPU6*k~mcnY0an z!_=SGsy~z&H*lkfqiW1DBTVG5MIvVm-onpBnr!4$5$uqyFh@VkIy&15;lQn0w6ibU z^4>OK-VmusZnz~nm)`WR!>-3gIE=u{25VJcYC8s{w&t;YVtKteB5(Ne5X#3U?iO`m>U|1hc>1IjYn3@l4681Z3B#JN0h5{qPHBA*OcT6) zBa+6+m?&oOYh5VG-yj`oj6Ys2x}UFpcYqfsyZvzRi_>w~pmjOW)niDFSU?4s`epKn zClNq%ZFH{^Zr+7{4POkSg89m&P6L{lqeqMO%ivkZY2dIj<8sq%AI81)auC&x)r&qf z^^dV_8@dhxkO zqNa%mgT|a4FAtd6V^pLJ8(P(GO#qs00*=T2ubOWKoLprPu>TM@G)sEsA`1d$9KvU) zWes9eh-V7@l!5%N6nlX@Z9jVeoE@*k3O35O+UB9M;hyjUjA9@+EvDxi4NK)+Ev83| zz(THJQY)Mlg_N!E&pSG|tc#CZOxyJCzPxNhqS zXQS?q3?{6$%A+or<}MRh%^`Ze9eG$vPl8f^+A*`_MPn}bAT@N|-B(h9JJK!ln_tstdOUdDWHZ2^(B$PQg2F^eoo`0pJzHe=ipaw^JOm zK4u_ts*KWv`?>twd2VHL2BDaRfI?zY`Ec7=F?0B8++t;{;d+I z@>JAok0Pel?I|*gf7<@w1?pCip7Ejq)ypOwa<}JJM=$JF*g*Jf!qdFfS<`KstJP8F zd$NK@HbuAie+?}-r^Wm@oA~5_a>PLR)nD_#U8RI6yEXHtiM)u~PiBa%D4k&*OQJFG zNckT2^&`HMc5ChaEi9!@tw1w+GxqUeD4y(aovJ|6BJg>qA1!5|T2LNiry>yf?kk#p zdSmsJpU`@s8a=Mca=kem|Cl|Aqqr6Nw^Hg^Sx8PP2#oks^{1|)p+%!cx3SgU_=xDQ zrOh8%)Z~S44TIQ%#4P0Ts1S0Dk{bf-*>-tfwrHHpE&+e<$bSaV^{D&vr5v-r?pqjg zISai9M0_lW2F$G@aPa8hah%p;y!2^I*GzsW0ajEJ0W^=A3`edEv~w?74awfpE~fnizQ|MpM+A@ zYXkPmyyNzxJQly6f7VV9H*`2BDiwk)C_uStq>KGxo&R~lYCirm{k;z~A6DUXMbSmH z26?PCCk8c}>8ZLcGbX_Bx;S)*dx9au*zYS@jWLcY6G78)Mrr&OoqS}u)h+N8{-E*U zo%X9J+rc?oHW&;}Vaa|=TXZNyV82PyNz)ql3QeA!6?|y16rY0^iMlhK6aBPaE2VaE z!E`~@*!_N&Byo`{@;V2ldf*L>&XVqZa2d+ZSEC8&c~dod;%!M5BA@JWjhNwTwD1k@8diRPeC6>2eo3 z;7b4HZe?!Et<#o_U$xcml=d{tn02f@Ht#XJ3`0Wcmn9ibyoh=f1h%LCO6svm zrS1ec?B71M*&WE-9{+s`Dr~*6L-{pbimQ>mGxDCGKp8fAAi5T?Kv*-w-;cO%t4$-_ zfh4}nuK}sz-E!@Y<*y^e0E;o9feYH*!!39Y{DaTc*MLVK++QDcB`)DVU^0rHDS_LY z9ht4Zhx>p-0Kt*X=1R%R)`Gf6NtQ<53#n#gAe;7$U864Q_w!nK)KowZipFSgS5+iUbnpqbe|YPl zfK%~)Z}*qzLfR+J6Yl_dAy%8j%pt)5aXAvexy4aD>IJ;d(F*GvwTCi&y2P%BO}110 zaFfq74v;PVqG1xL8;Dg2FUT#^Cw}-#mF!dN)Qo|dy1xcqGC{ZB9EJG&u4)hP`a7evnH#WZ2s7 z`V;(HimCD_=+U4}5k&eJwpFS1UhhL=uVe;z>67JMqF(=`mXOQ16J%6}``fSK^Pdy$ zU~2n1KWLE%p?Id19uE4rmY}UB#3B${mhCs5lW8|Zo-e2Y3sAQQ>*`}1uGoG_dPBxW%hG=V&_nqm4?#kzI zXxod6IA7U#gpJIULkVwJVoEZSXzU z-EdO~SJiSHU59*C1e$QEJ8nq#jVX^uMIACc3?E52`Q?E2oq3cbD5@V$S_>NuHw&$h z2kj_B|9L=4l@)LJff7T*+x0I44O^@w#tLp5$rWnJQX5lz;ShLdATNTx*(Gr?TqsUS zs$ZzgBxZ4iMCS`;&4Hfqf(7^3@LZGpwsEQbWV-*57uYrN!thwc)v~iEJ968Kcqi&H zT%e)TIUrGUSCnk?Egm-raxTPAor|sNojd3U;Zt;Y3J2V>FJ%BXP$;D0_} z1`Ah#Jzx82a48u@MF+1W!ZMUVYsnxYAv^K!ZMu)u(>V9z!e%$(4z0=a*y9Tb58Y6Isd-d7G}j z=Zz~f$X(98MV|Zl`sr^A zjrlc$`!>xggr;AO#ipQT^j@;CwI%s`0U+4D9VXDN?|5}^5J1jcAQ6KEsg}J7Midy- zLj|8p^%Y;?Y~7++d|~>)x1lt=EJec}Ez>Inkr@^A6St}g(W>A%Jsq_$V0L_u7W5dD zI9Rw*lkyjVAI3NPfTIu5%Q^Xn)pgEeZ1V4bnXOm|T`x{wO6tL29CKos|Ag%J#GvOL zBp&qP`7U9nYa2GMkKrx>8iz4yK)oh`3GH$}YqdY@`1lCz9w*ZXn%?JtI;9w9zq&V0 zunG7>@Q`5vPpT1qjqngcKRnF>GR>4A`ImQe;42>0VaY_#+o23K=?wQAYEl=R0Yi4F zIfzmuGZpt)l{A;K`WQKTA&(x;1nYd%>D(jVY_^@QP$>)e&tNMF9d46!r}3~p`=~y` zP1aww&y}ou#S!Vkfx5x18sT2E?hotq!FX{lq|acw;XW9SBTZmqTNS&qvvfbuR1?%i!MvcpAh9^>1EDo;kT`> zLa1$0DS$QG_I8wCsSPOkB8y=`Uo@OxoG<=Xg@w-Jg5W36vKTLeWcILdPlw zOz{z#grzQ;c>=afQT6Z_ZFjqb2nW&AqAwe2Jf3@gdiF5*u%NIf!m`v_P>P_0&vA0# zP1jGal=q0=ZLZRFEz|SreIbGfMwLUN5~4(Mk; zXP%EmyKP{kaq0B_TZ+&JQl=;?jpWe@LMR1_QMx%1l>9qcVqRJnJ1G;J@WKEh>Tkg` zAip3|*BbbPUtOB{f0%m9s3^Pde;A~@VQ2vf=>aJzNu|4U7)p9*q+4JJ=}rlyk?tJ2 z5s(f634x&{|D*T!x1Q&EF)wD#n!3(8dw*i@tw_M-XJQPFM-g(pZP}`q*6D{}u(qOo zg~@7UFIAn5kkHo;7vH%8UuG(BI*Q4v8c+&lmf}}@DnhT2f@0gTM3BMu`pB_;Fxr9U zx$N=-(7OCER#C7g=+e9U?XbO*`P!+5Jcq2j8jU@tSKz^`-=lKX!b&|8R@zmiN>=Zd$nh z{F5+8mKO)Lao=M1Gq41BECyl&^-)`;5jdX%9!QW=Q_qpbMauO+Vso_}U#dt0J!Piq zrvN3vMZxK^aNjt2bUXr;s0fPKo@|&+zzmD7_u9WBV@Is@?e~3R`xuC)o@J{y{-G!N zD93KF5Zi9`R(h*#dR9-=C@{5C8?h03ZiT6n-B`C&d(fex!J>GAgu6G5*xxkyu{)NbaSsQy-h{Vw% zgV#l*LF6`_Tu=ElS^Jut8s{qv#F$ONkd^N=kvlg5rTsBqc!eMxwU?tGs(r3NP#8<^ z=qKv?t!;v(6VqQ;jVH5t-f;fL3wE*3hmxIcN&cNrn~uH>=)%J-lgN+fIRs19X5CdR zsWsp(#lhWXf^B5V6FD)Y_86D@Z1h|KL_;h*v)yV>{~>&{AL5;24i9xs{O}+jx>Fbm z`HPY!n6npiNl55~uzOX=ba~YOP#n|?Yc1ScEjdRQbGy2#X2G`;-bV0)K=*D%^s4+~ z1lMaX?hbFw+NBHXh2)GeVm&tEMu_P0xYywwV0u4JFJ?Ke^V^rS;cCa_gayj6j=$P2 z)g^qHuwjmcFL9NhqkkFm;>UcoOL>n8G4+_6ULNNqojL7*xRN)Tw^X#I4~4`YS*I8G zcI?~hvezb?S8^HPm{G`)@<|}yeXa`t=PXcbj7}6^kKONjJRwEtMU~Cp9sV6kM9{}= zBQ{A1iTkv;(Z*etVbdRJ-C8sO(9)+vmM6MQ_XSvm!}Un18Z6MiGECR7gk-*W){z!yL#3w2)3vJ8#* zADN&JeACkHA4?ZHh zLW-rgo$%|NRhtRpG5{y`VHC1pki<`i#M;?nSS^ETm$t)xHiUu1=xHx|rMB4ejXX|@BBXetrb*TROT?rhVV zs=oQ-+JXMY@Fh-w0N;r99NyO!0J|O5IB;!Td+-B6=xc^^ox`MxII85L?5-glf^V-| z>==@B_8^)pZQ9+VPU5SzG#D>br|?{?!4LH$n%JxslXrPg@pU zJpcI7%hRDGD(AEoBZ)ADG*s^OXBzorztFjfBBSIKcZJ2W&U;gEzx`za>47p*_QHHqIe=LF<9E{Cc~)#`@~fol6_^LXNP^pMM_e0yU@-@(qH!1I;Wz)iy9sLo5AhOIp%&aEs3zH zAnbYOfzcpA2fg()cbXqU?pB4CJ(_J#|Z%FpszK1r}Lx-^4|^&eav zHJ~O(*I0N>K1nc9u$W(yj-gcz0im;w=$N+7!$c98WrL1I$GORu!`J;e052r3^xDqm zNm>!Kc1G_X8)X~mJsKo$t!PHeY1*`BW)Q@Hel^?_N-%UD0KF!u^0glGHr(P-@niB5 zduXHn{i}E}GC*|{A(u7#QFMHIDx^`JcE})(^m;($F~t+PlC@~?v&#$UkCN;INOPDq zWS;VMwjj96>u@KxJ5zsoSR-@qVx#$b6=Dv%(!zSHTKv`@v#}xFwpg~;wpsAUL7}B! zoYg%croZVxIlPgEt~(^3bXz>EWlHe$*}oBV`QNvw7ur7l{=_QKslH2#e$BM@5+29K zON;ip+lx0hY0qHKyJ}_kNBM8Mm6p>}y?Tl3_R;<}GRuw=^kbH60@k2C+}vvz|Jn_V zgua$S_q;vJt6a1EoLtN~ZCir%xX-(--w12r;#nLLqD2I(|GdRJz%KeE_dWjmb0@3I z*N4HrKSL`_U>);G4HVZnEU4@Jg~B@R=BKNE!6y~ENANG=tw#0mTMgA(nR06k1GWvRem*w#sehbH>TlFqQ=metBi6?E9H!OfxXFpT$6+ z_c|mf#cB4(&d~lUQ%-L>A8=>jbGYAhvK0Rseap2{_-KX!v1I;2Zvdk&GcT&xU zuYP_$sZGD8X3bt0oUF;n^%mG2o@6(Rb#u-DeiCJg5Y28S9e4OI>Lvco+~RD?Y^h8P zyZvB*AOgnkW8p_?#aRWhz3TkR*oRbe9WLRr4MXFw9ir|6VOZ_4cQau{E{>e4CwaK_ z7`&D;)Taj*CWf8yz?N_JMvBGoog8?3S9Ofe9XHeZCvDL_jn6-tNk~!#{Ke1zkm8l$ zI2#v0KxcRk#L3SoI3?f%3mT&l@KIbXG2Xn*KfpmQ*NEHB*b<5*R-f7Lw*+%5UzPrm;?-|^Dd#afx;9mGpC zj{mrYF_w3A-?XRP6b(vRRzGv_ReVBpGbIOoX4803<(9bWXAyM;UcbMiTMdRgTl$6Y zA~zk`+fTiuYNj$-H?5;^MJCn$fyZBhh_2vo-p8#c*XodC ze?jGg$KQ(jIwSI9!yE!4*$zp$^#0eDTjvw-xABhkC&s@z5zHnC!Qp55#Lajqr!k~` zdxS?GEt0J?{L8?lTEm%Ra1xK>5*G^fznF(ek5I%Y5k`(f7O7c1{nJUlbiY7A`*>31 z!F^=om*^yp!L3%p1H3^}WI#*x-tZ{9FVrwmP zh@L2XRZU4gZU}EzCD~$OYD`ukB11!`xl7&T?Av)aDKAR4CMFJI5OXqR5^;69@D6Q~ zX2RpJt<@BeY0`x7LL{AgvX)mAntPM4lKA)DoNp!Fy%L+j54ZTu2bSoo^HF3UI1dG! zb%1?V!h81X38gt!pq5!sk51@CBcUp? za*Bce7au)FNQXL&vvus(az1Su`*u*6I;-lYFeAV-P7wkH7JYW9_!Vvu`@x|~*rAZI z@D2G$SO}1bG_vQ9f~5^6c)_P%`3ch3D~^k*0&P#w7ERYgmDA#WP21)D3~*&+!&!v@qCAs2NC0~vYnwdUCuXa+ zmMqul8BofM0mKkk%*J@J39(VWfkqwBkm&h-d_*Wc95D=fRzo{boCqQrwjmG%cR)G; zD4i5upucFy52)MnCGYaOg2P`~AR~mmJ#(p=py^Mx)ZSq(KfQVT#4IO<#Ij)>$!>;Rd#32pz{AUvj6&tMW+5HdvCkp%{jL`==8!qJqBWin0i3f1X;h^fKuq4- z?ZGK*H8ZFR>-L`RJwi*#E@Dt4!6DWUE#V2npsWlR$@G!u5P0*K#o-9EG`ezevtBvi zbD~&@*b_wCJap{--ObfK&PgZUK_zJ_)gA%SbeY)@AQ^On8=7u@|EEqonjPH#QgjxT z(v02{Bxrh#BSNC;{H%pdPxDpK#g+>?>n@auVn?Ffa=B|{*)I~&Fs*yTzk3<$I!zTx zjVV_bCiE3Y%wMEhMWVxu3CC^a_vT6SltatV#)?WpBbi0>%MD%^eW^K5z_yDujX{~q zPfaWcNz}R3Abv}cW-aH<;8Q+@SkQ64l6kMWRVn8v zCy8KsjJo}^w^J%*o#OOHPjfj82q2X;m!qxYq?VOy-rXB0VRwq9SVjnVyKpY>XLpsV zVxdLtR0jRp7p@w5hgGMHxe&I_cS8>Qw(H|rH_%k21Kf>!VE;QsrlWasBfuE}OeZ%= znn$pDkXiBnc3zvZ5pw)E92TwdW{u`>AhA0`Wek#j|p zWCQ=x2ybN%2Son-zNp&MBd-b^!q59HVDMVkur9}UUm#d~yV213bjG0nTgo)h$z^Mv z?GwR|HDQUEQR-jg4P1n%_k%!u3KdMvHK9+q{}fS%YNi)42s)aC)0{cD z9f(VPPX8rnB90+t=@I;6=Y>X8Ops-~UsP>-|C`c&^W85Vvfum5LO}#N2!5i>(Dt3a z5b)Q4dU6y#v87RXf=7Z&u1J=5MYEo`oLb3us2ktxM+M4n-qvI3$-qz>Sct6sh>ta- z{JdVB1XrI|j_>XqYwnCWI2l?5-i%_C`y1mV(4&XUIvGnJmt>Em%UEA%!%G|a44;iH753w$}TXd#?y zOjJnL$}reK7o@hS!?01jSPkU~)bd~yg35K`ePSni!#y}(dZD{_qt!32 zByCGe5;#M-kya-n0fhrM=m{Sqq(%<^Y`+*&Hhzh~pbJ0$0C8pK);n*-87`LXmAHf(%W zqUdFwXVEI5#+#;Z2@j)Q$}W>DwUm%O1MuN&B3dTmitne!1S1C(GC2|fkcON=2esFR zcYc9+e`7kT=aJt2_kA`XkCy3>MRSMBkCx_at*e1L4MFb+iat4-OEyDCfGQmjxdZ(uDFti>5I_4FT;F09{`+}{#fDok;mB2QPu%+`v|HIZ z0GCv$8M~v#D-Qh{ZwCd79|)5Zvw@*94UWuUth$&nDNzh!O0>osKc-QNC~kHt-8{^B zIe7W4Y>ixj%X>V@X7cJELI~|2PX>2P4=^US&4=D@Q{zo*Vg_&E9GTia+{aw+1H{V# zLM!fDuSiV6z?f+kQcyiJx$)T8PR+o@LKq9 zz2H`JB%q~5w=In+(D+slk-xoIGZwptj{MeIvB(vrSvjC>qF#w^CfjD|uSA_bRNp!T7>H6vS;(90X#5haRw)_Ms)|9uf1 zjh0PH;|2o~yv2*#5@8XR&)AmOzWIZxEQyGQZf@<%A?j5(-l7aBfzmGB8}`IzJRUcP z9L(zbf=2ky8rzDQXPW3@WSzUQ`XO#KxsfNIOTbYa2(A6=oSoRSdyddxGRrDQk~aEv zOUXcn<)u!w_~(y$2y#BSM>4=K>0z+=Fu<<*u?pvG>YQ=sg+vdu+(x}6FOeA|^ z77oONBfAPel=g{^dB4%9QWPG)EH* z(M5dtlr*F?t}v;l?k2t0&SrKRhkr%tDwjL##Q8RZ>;gkiQOfLe2Ul-qpOe1HvK60D zYMzLE9hVTk!G*wBCWY?wciEywSN7d|xM}&vOVH;L78Auz1>7!d*lE&WA)uYSxP%1i zrtiG{ttZRA-KQtEpP5?dTs$mXKUw-7Y}0wuHEja~(Oz+`-EpL4jO@NI_MM`LVouaC z%6C$~jQbQYY}b_Gd9$onJg|O3;`AM>uu|ifV$*~yToM?WE&$d9t=XW1`4n|+aDvMy zzX7;>GBp-OW5ImqV+cB=DWg5}vtiz1(NYaqm>?srm7-w`5O-4A8q)8u*i&;o2b5QV z_T#>r)^`kRexwxCX^-QQHvO<9*YmYsdyGz~LajM^;M&xoPCiT5CgDqR$KUwSUtB1u z7Xp5M$Xk}s)_v#H3H+#qOc^RSAC~U?Dm+iaxSB%^?FIVX8LJ#!T|zMVB&5?|Smc*g z4p^00tR%tzN)Fv{OaWptXl$kxY_Rp(bQ5B1+{8oO^2!&|xRhsc98eJUg;ch_@y#lq zF~esr*UtbCeq)CNhi>mrq8@R|Ak!`m{S-jKP>E5V`Q?gfA3CUl&%h5+^MglEMJE(v z{KY`1)b!^}pZ$RhS9(vq5IJ_Ood$;vrp>H?^nVsc#BucCs)KP!661rgo$|xfh8OKl ziJ&xUKH*)3gEvwQz2Y_pmLI+>HtKa@-z(j|j!geGG^BhF8a!9ayD7_QU%B%D-u#rn z(-WibyAj!t(#@@T$+8$|wI?6&U}2_zvdD0K7Jqh*|JadwGIRETph?9k+_K88?({tP zX*)~#-8)F?@kYo)s=Km$B<>bvt{%>Rtj+u1qUKH-{t9vX&_uNf7NUxW+nn7ieCeZ@ zAXij)!Huz;JHrFICujJToCV)U5IW%h3vj>d{^!;5By8i>GOx=u)el65K-s*+)AH^9 zO1vlk(`#~?bzF>+i&ofU1{X}(0%>Ea<@SPwg0`c>eeqR?(%-;q5$oEf-LE$00s&XM zH(rGzeWUcygQd8#cM=}^$aiQQL{K30)VOKiww;h86C({Aw<6FQXUQqU^J$6zB!FCU zP3J^=IZkVptQw*H*bslbhv=jxsv=T*`m4yXZyQCH<%G^e*eQna+AnOXQW8TAsYBPU z6t8c#5II<*1C6ZaBwXRj0Mqu_MN!~zrzH*O$}p=@rb@0 zzZ{+#NEonEbIwrTAW5Ydot-S5z0a^En$UZr78G|m0oojOImT{V5iPxpWKVN1W%ab< z*<~*QerYmatw$ff5&J3fO&9BKmd6C+W=ze{E08#9bYQ0D)f=L8?%tUxQHcr` z&Q%l1s=Z&Lsid2x1Ln>=y#5T^D=9Lw-6H6vp!eRdtGpVK1m0kyvl2Vw)A?v_pQAwA zvLV&aeYk!WPo<>CVZjVIgJ^C3C{Mot8P6bPhLn)tg&*#-@D}LT96?KD`v!MhvxX0M z7SB)hv{`L1Cle+C9MRH0DLJCOUchj_)-E=nYXjwpn25jYZ&1OqVa=Bl1~!GwLNgqI zxPj-j`5ySwb?N}INZa)Eluf)6x6PttKbWimC4WZgN^l%Mr*(of@DrQwHoEl09t%l^ zIi3aPV1jwS7&DZrxA4BPSxB2)7=t<3fN&(Y68Y5X?dIi$wfEe3GG}_o#wrHLVL9C5 z9xcisG&OveKn0412HLCWCuKHF(zq}Y#Ey30c6aeBUz#}&LN zo1V^NpsK1%wf*Y{mE^tNox2wP$@x}fFg^MjMg{W<(*p}k2=~!&tHnCW*>rzwq|Z#l zWQ&_e@SOwiBGQW7O?&WKdl{x%9}gAHCkU!Aqp*d`=N~_JUKA)B+x>OrY~&$7nfTel zh39OIV6A`Iq1+QegxT%M_;e5+Cq)fULHIw5Ml0Jqssm=Bk>I|iknDssQ_7-HHe^X8 z&y?8po1ECIr9a2#4I>Co8tic8Q2e9^PIuz-T(R~L6@)N{+7M!l!Ig`8gsKO($Npiw zzSYite{^Rp!p28J7kW@9HwL1IwGcl3)=lcQ-?#5uz6*A4cWNgKL&jN6n=O-n{q^W4 zFNPKoBiOb?pnE}kv|@q2DJNC#D$NKjlV`7Da%qKQo6fm?pno~I3Hfl#&aJx%Z5;xW z5?l9-ld0IbQ=0ruaPqyf&fDp;uM?-l@n@mHGxSsO4PO@1(>My$^-=!L>lT6^U#zY@ zB3DLF_Q<0=SdMF?rJXBeRuqIW*7YlRyvH}>F!xOQWANiPd?4N4@Av)F|6)5axRmLzPKwSwl#*7bithq&n9Qp6aRTPmf~gaY@ep9t46C^}60<9xrfc zSjK0DIUrh6iS%sQZ!G|QU&Y$?TU*bvl;{*_WEP76M=w%3s}LY z*P)w!b3Do^1bAC9_jw{TwXgwS`7t)85%_(C)GE&27C?s1joh-}!0NuWfgd1%=!q=> zX2yowe0n(i-rQZ^6Ote5VXvRLmeiKO&j!nu;~IsA`kV|`4n4w3F04DUt4A}Av=j1d ztkuWzlvG9)Lzcb|z1Jh2%>~-{fG9`T7ORGIqN5Pzi9NOgmGMA?nf$-N*k8=3U|g*c zuo=_ZVZ6Hsl!(<=!?fVUUed>`f4D^m=z)PE*N*=<5ST{4BNCrw!RXn!so#gce$UYs z$+Sery9;NP`z8+e3hq;u$4Q^Td8KJ9|7Fw4Pm3T}AgxvLsy}ctUi>lPVP{}%_s3$V z+EZlzphyQM!&`k$i6=(bNoD!z+#hnHe-R5BXumbR=;%8D&g6g05qbO$rf-BP9=;&f z3o*O-IjT{XNHr6=A zTW~L2(t9X#)ah?>U8PA*X4(4OdcbX&4=qFJn=op-1E_E#EWGe``@gb)cS(Pg5{^Fc zg!3wQxhT=X`1)|a`e52^%c>-RlDQ)6qq}3D$Mk3_|25%&`twzU0MFh*iJpm({b8$( zEy%ioln@@+?NhjT6#MR`r-rYmS%jB&&ipD<8q9K<}+I&YErLsNl7M0BhU4dqc4xQucK^Zy6x`&;0JvA>A5tx$Isxls_vj> zO8IhpW~{KxQ=;_SVQFO`JxSE}X(3n+xlFOt*R`Y+Qdq`6S|n!eJZ}2Nqs2DNwjW+y zR_6Ugege^G@TOsdHFYD&1+BCWX5;v%sUeElMcNrLCFIh5kM-en+_1Vru5h63w6N4g zR6zmJ`rvv0^=09;4XNCov@Z6^Y=DA0RTm4f9t9%luBh+!=7yP&Qrxm}zbd0Z%g09J zFSy|!!m$q<)J-IB2eOgY33=i>V`eTgq?5 zIdJAWz?=kI%b6l}A2s^R^20Q|csVDVMbJrMJ!Cxc;J)=uHYhFQ%4~W1<_ksZbTRxs zQfQstYaUkQT`XS<_pRqG+fd_(wDh;$ICa-6y@#TuH7n67v{c@^W58`U7EbWIZzeOi zfQc#<=qNI~o8AxPe@=x1a~~N;6dBjPZQ!(V&+jdZ1o6Pe0l>+RLh=@Fl^W*#P$H>V z7d!y=(SU6`#_QgU^+6SB`DSgQmR|ZTAy5+k3&ylebjrp?V+B*J#jOs)x>Nt8}j> zD)ggEVtsGzHaTDg`a~e}Q5W6W_ee^#*1ZFvR40s|Q$0}DtM5&bCm*?gvS*OI=zj7q z5I|p`LI{_9n%j}e?HJqQ-M*YOIFVS_b_CA?9bx>$7!hKVX3m39wc}YAvbEh!NB@xN zCX{Q!s!-H+RKG!}^9MLrPm}h}RKo|gKL{;#?d7>A&#~5xf8bE>-ep*8y3a;HnU3fG zc>zQ}I%jSBMD6i;2ee$TAX0+^k9ps1)6tees4vE!1{zM{^}K; zDZ<7g)}6|;pPE=J1w(g}npq=Vllck2#3zt&Tz@=PU+skz7xO|&ij`a6vo3d;= z%yXd2+cy@pAY+{st&47j4K|kw!XiSHnSM>v;38>1M6)eR$pLDYph}ArX>)KxPnUWHzH)?_FU1Tmes+l9m7LOC zzvctWZ`x3=@$dAz|KQIFQz~aw(BR$Xom{geX)B zsu7hL-tx31F7VDfJ~jtZ1RCR&Nf;a_{0SLfbcYy%xVxfy7bF7KrDkoEMbal|$7eXl z!--0&zSrvf4S63(_X72e+iEkd_X&%$%Wcz5E0%?H*{Ueg>@y`~$69h(V|H>kTl&CC z=eXUP(>C`escHVbUo%Vc?5lqN$CkOpCF%gUxXdLEa~BRxg>mrkNBqy`uo>>ADzld_TQ5Ce-7g{oVMYY0VI)T zBsTUZOJ6k+nQbeuTGAT&q^L4{_VMY;oAG$rC4S^3da%=jne|duEF;q zJ*-$H^YY11fIH{j<7B|xXNc^V&hWx)ZZ#|33pfhpR1nO}qh|^mZo0<22Mu1dn%6TwnlFT2eZl!*%?SCj*sAA?E68wF zG51LV@pmK8)$rei%Lx|WQvG&nP{R=Ce-f4}_O4*@7jtM@aGG*^7+e$o?Wm(^z+ciP zJx9S}!dduR(TRueVQ=)9dY@1*xY#0zwyom%BE$p9_D>ZXNw|a8lU`s)_Sx_3@+6jh78d&q-ey_LY&KUYLkD z+^?Ntt4XQ})4kdnv}A}#nTC$5Q=zN)u+Y4M)Vl&zqEbE5Y0i|*oO_eL)gowk^ioQP zG)g!1Sia#*DS;8q$ef}raSv!+c$eJw7zTcM-VykTHp@yA0E)I;1h4%&X%?^Ur|{%O zF3(~1>@~GDuMjSJcLI_^w_!AT@f5p-BZn-}bLNPv$cWUmR9xhZ^v~mXk%8W1_|BY+ z^9y+I9Zw?0HxlvzKV26@-G!y4FuUKmLKl>(b;&`*hRB7owUDek<;i{DJfodG`V4~< zomKHw@oS|{B5^lv9RrWAb?o2xx=wtW6knjf2@~+J7FH4ljQf4MK`F;H$x{|P4SGrl zYG;(5WIvau)W^904d}~k;GF#|IakoJ+Nu7|bQV~0Yd>b$3&1O>;L9+I;J0eRmfs9O z$q0WLSOIf!Tn)p9Ei5RT(=hbSXxf$)FrCfw7@D zbLH`~IZj!bpG1bDpH~ZmTfa{k*9f!5#`qzpN9tM-#Yu*?CcnNKNzc|9TlbW3Z!S_% zQL&Z6{bzF{OUaKM1M9~0Z`nP;16!R^NK5q^OFi0rD>fW%X%SbyEja%Sq zJs%0sq3eEtJ$w~=-W#w&YBPYf9OKz8L9Ic{$Np+H~unaq)yI{Iw6CAXs9qeM9KIbmTkh@(O(?SL{xKj&cYjsNyl(dpdogx$Sd_v1v-titMr~9`$nf}& z-i2gMZ&QDUBkp}WT!}5O_u-< zGklKjRIl5<+x}~NV|~B9SJJRFZ(h>~$+LJ4vCR`W!FFyAEkN5_YXgtSx^icH6BOW5 zI^k=)DI^)vMz`Wau|_zWh3yR39RDL1px>n{`II=}&Y#O0F=+2N63MnVzSPaxNlOHp zXa9!hy}dZ=DtHth(W%goJ@|2RG%Hyy^oI=P2`qo-Lly;YLu|9-=9cQ9omC#0FgV3v zTcx3rFRRC3|9oCuzH`PrO=BT4@z8t@FMD{yAsS7omEYJ9F3ol8#*ZTX7d1gEI)YTwY&CiJHJz zpm*zye!YqAVAyw_hs64(#WnF#8`XpQ@nI@nxx5k}G!h_(0{&XxD^|rm%SO31cCJk+ zg!~yDytV5t!#VJZJJkZ09Zr^|0NGH(kRc&=LC;k>c#~&RK1OlMZzWY=k2^Xad)|8T zAl$)@qx%d0+Msh4WDM%G{N`V>m!A*N&+qk!O73K+3HOOTRv?!c^kXwyo+i!seb@lms3vuYx=7zBALIRaspIo_ z{pZ!lQ(28!c*7>Suaj=~$fxb4%*&e3No zWDy~vH>sNB^fcBB9a}>=?l$`^dY8_~>(3<4w`R}OoG%|=F#o+Ai;DvDwLH6J>}XbW zI3sz*!dx*a9NKsc{m8tjF?{?9c1-$%P0`l)+k`!iie|ddB$-~m+{d4qKKaE)d3TO} zH&-`_v2g;&3iO?3B%G(ns?WkrfCA%)hqxvWnPj7Fd{gZ{cDP{7{M!kU2Vqebzh2_A~Pg+;# zaZ3Y@(R_lg3vnYxdv&y=Xs=8Rt>AVf&;PEIM9-4R_KKvWc`1-+L`3}vs@5-Gb6e#4+c}

F=_oIm{vrUWqI9UeMy-u+I*uV!CQH-+Hyt zw-0cMVg64ZGyttW0RFrPl(&kPv$xFo#PAVd^@fB&tC+z{x*~srw~l*Ljfj(6rziT5 zfPDnXY6JO190D}(Uk@}PDUK|#;fmRs@G>*$^3>tNDH$dnVMm!*h6e8%Q_;JaQgM2@ z=^iuJ98stq+#IlP8^D?|wdk~YBly@OD9fQ#Amtpa?iV9$5gHoSoX}_`(j3|Je(_P` zeIJ$x(u%D_DGK;=!b1@18mXOv*bCIruaOk3CsdpQ^ZGRUtzKYd3r)?Ljv}T(4@-xT z4vR(me4Dfc~PI!hjb^S@MSgE5=a$i0`M64w2C&En>q-TNW zc5ajs=XI+1)Z~kdk~@eE_u}*fnSDgELFV3nb~~QbI+_N>TPchpb~9@*Kx(Zc^P$C1 z{Hc!a{(yC7E_Q8#pVec@{idm3%CK)81F~@WY$Wf?rasHuea!H zyBSyf*HgArWJuS8MAstYsZ6ru+Z(sAE?$&1Kl9`tq5|vNLaM()DgD$_26cRl!w8V$ zQQGbq&%5(tPFY6sINCpPNZ#Mhwv)tfI+4u1Cb)0L*K>?JRqgD}w4|v^#o!hDJks}! zVEd6SYGepftK*D=m>vGq#MSN?)X$L{UqAea6??6J;v4A{iAB>D56WA*vHF&uMZ&)j}QJD8Q8|%m%gfBTeSzTYLPSxYy4{k40$9c`G zc;5@#Y)f#j#Q;~skuxJ}tx^?q_{zsfS(>D^!r;7}mAouYG@hC%W0FOHo{Z1$k@j1G z$4HYo{ewgfGN8CXBIZG$0$?WaN8ECtlPH_mBhWtWJ)C>la;If9z0bQm0Qu~+lx0@0E$5Iv5HN_1XZ@J z7(po4vntf1Ft$dvINx=|V>HLoFpZbG!>djf+zf`NY)bP+5fyvvvZG|Sl5~_(Vz2!z zU^(HkIrlOtLCK|cdBjwc>tLlJ?ECv3GBt`zNL(@2&DS@2WHHn@9AH)^+sY52v%1FX-+SME(5wz?vyuiCd`ZW60Uyf_+;&)#k$xri6UiCBxlhG5YybKzIlkit>yKph0wVI5@cgmAs@!B)^D1o(WBnJ123{jxOmYoL=*0QT z{37#XAOU^;!PyUVYa(m1iRfEPlD-PEiGbhRuDkR1iJw1zrY;ty#G?q3?7Mx@acWS3 zKSJqeVc2ZLmW?)H=^`jpKkLu*a{o%5M!TsHDkyK9ki5?y2S=hE4MWhS5>p*m`4Op6 z#ED>aQ&Lm{QmGRp0LXA4e&IdV?{bujpqK5lK6qOxn{i4k!84k?U{nJ&|jrs;p9qmz9<)AO&R@F$Q%=n3(q8bDV_)+hL z6o3C}kSh|LZpez6zU%Do{*mxg*H0a-`R>iNYRhX5LurVV0kPIIo9}g)%r3gP=koyUI>y_Nnfh!*2P77+yLk z8(K+)g)Hw!jA=G5`10xLH|EAD8$2O!wS%dkq!w&qr*EH36H zXLgN8>MK|;y1A?8WspYkdW>bC#SBq86%-CyjDumx>T9JLH+@a5YIa*eNkv7c%H2;v z)2WDLE^B^m5ew=uO#2vLP(4!jvFpU}wsE-bH~6iqSJ%S~kAiQE$=6>)5XawiR-6}H zmCW{RNfy8s=TazdC3#P?Ap5bTp;Z%6W+7rE1L?wGHeqqWh;Rh@2ax3aZ1!U?PMO+>R=BaTq!!tSgCJ}ah~xXXx)OwD z9%GdOjWc}R>?{426KB3Ax)50cJQwqOLay#b&R_c#om38<f3 zHNN*|4+eFty>dF-1=$odr(`>c*n4u#A6+!uxbZTLZ();ee{@$+@}Tjg~J z;Q0Dg4AW&7xFB`>W;j4+yO7<#HSOhPKDAQ?k>9wHneyX3UT)DyHm`!@q|E#bB2%eo z?AQnloohHp7=mT6BV7VPaZ15%m?ualQLan9qJ@Z`HM>f8Qc(#xc0!V6`EC3*&R!7M z!*6lptp0d`NT0X$jON{{4-9JW=d20mY)q#k`8Nj(@84{=nf(d7A3m=>NF$Yq^kuna zCGUibstwbdT@th^KHSnDR9VMU@QO*=Wpw5yK=%UF=o6uNvVT5e(<4iSpcpguzAyKq zzmXWZ=JIs(4Kf>hc7hZbe#)e=ro9vS zfGl|rEB$%Fwfx6^YR_yYBOs|y*GGB-j#+aHuv$K}VAxdIzzY)+*p97!5OZcIEWjlY zs2FrtXJ5M6ptT0@Iosyq68e-UuCpZ1* zYx^Mrvxghq2^_`j1O*C;%6f=Zgu2T6Rj|6q?+|w4}>J_mUsf;-HiP!48YjNQTVNR+t(E|&U#p^j>8g}$NAF70L z9+Sz`{-y#sB2XRLm>a+=zAcf+xS~>}PmnIgun%RP-K7C=K^d#CiUr$5+?__>oIjf)VeuHcYyo3_mCsk^ z!B{};ZGVoWs8wWxq*GFyo&i?w@bPi@K!>7X58;)&$JNX@$=F>gy=hekKnK<5be?D# zt)Ni(+67S6JkRXaAsLVd!ijsZ>)=mm#o6fG*E7(G%SUlHGh&e1xxCv@zfT?P*c7rP z{XV^eY|iuTo8?2B)DEtsBMwSSXVjY2MquNKeen$<0R8{2!!M|ij&b*+#acD9$uozd zln&9ypKntmkDsO@C%P^waeZZ0m)5c#Gvdq2=g%K z%5Oyr#p;qgaD6zwt-h>T-Ji%fk>I=L>GUnSBFGnawVgx=G6A=>IMwa$Oid^?ORa$x zo(tUs2%jg|WNRfqV)g5>S#J-z>l?#ZBl?dGrPB37qM)qfaqRfIj{ zlgw!~j=ThP2MPcF7ITN+p6JFN!ES8E>Sh%892G#lwD^3#96lKPuy`dMSjdTHFyU=>L;C|V5NZ4g)BtmBOU4F`-CSo8JXZWVjtUq|0xAPWYWUzkT(6$K}DoiIs7qlXI zX!4S%1*PHxTZPhDgy*OF&k`+*%yc~F#vyfvQRb=XRU?zS~^BL=1;`+kQ>b>88Q zERKaaZ&0@Sn`66?1@x_GA8WK+-b~FS1tUd#Bwo$8ApS=8f{?l8JIM-F#P{-WI+K@h zm!i*o9LzMjiFm65DKBwjlwQ!1f%-#d-l7?jM?iR&$n`K%bnrSPSItl5kUD%I8SI@r z#S`rq>cFxFeWJOh43u(xAg;PAjq)(E_3EJ&0o5^bId-VBzV0vf3!Ro1l=is4zPb#* z(ZfBrSoOE%9ZS4wp}B?pkw~rH^M3q$jFVZ-;R2V`S$i)_mqR9Z9RpZ!a~pOHbDh_yQFa% z*VpIV`^J0qvBv({KYMhqs+u+Dtm2!0aM;rRI+(dzq;3G5jKQ<@w~hnji>E7aHYFwxxSC#+FN`0x=%b`j067vP-NDL`0i`FiW3LgU)GA zjn)F6a+%Ia@6mEDBhdw|c{wWFf_y_2H(#4;92*{1KTW?Cou!FKxou-#6aqmA6$MWc z;%yzshc#D;$mIfXJ(QG(0e-_h507Iyy>6;n!MAeG<<`TILETTAFMIu^i*NNYEweiB z54`Li%U@UeA0!@TCwt$<#i)YyYqPPY@&aT%3lB#m?q?n<3!c+1_q|{Di%QSmf-zP* zoNg3lUgxbPo|ZApel{kOFD}fzGikoKLyu?T!w>-C4rCTw%Xdu(3Vqm zx#k1Tg^v0CHzo<%T~7JO31b!2v&k7W&I;f2avyBaQ~#U7b*Ftjw>dRCtwZKTnFhHf8sumg% z59qrtx(k(ys#y{;R>e=OMe#F>z}3DQmrvxXH~21k5tb>leAX@wS0w>CYS`UWXf6Ty|ixVRZE6c-zn-LlW66Y+_u{7jDYE!X)Xccrs!Q zX~i{Nhv>d6ppnID;8_%xb7AxRNO^QaO*%(p1Xub2Mn)I#J8Csjr*@XWOiKf<#FM~+ zuAzP7?PU2E%j$$p6x2oyGbfhJgh=jgY(}k+wP(XxWDG5a3y2PFG*#0m0z;a4qAh~u zQc{+{a(`w-LN!RtCV{jih2D%4e#=j$rp|QdaTd|Mx{lzlv z|FYNCRjFQMx<`OMQ!r2{i7e}+Kt45m?1Ux@WheE=El%YS0Ud#l6?t%g7(Tq( z@xiiUII$7?E*t)1`z=9Z9XlcmL%*g4pZ2>!)@7bEfkbxH;iZlre_Sr98)lT z88s*8nm90=5e#70tv*>P9yyZaw8o4!MK19dG4D*bEbMq1Qt(uG727xbFBc%r9}kqA zE_b?UmrOb0I-+Xe{rZDA=YDMnX?obF-4UVr#__W1ErA|?v4FK0olAUp804_)p1x!I zZ$tjS$C(#>^s!?ZXYj+gz;fBeJ_gA<`(VTfI&6))qmB22DQOs!QRWou+MyK~4`qaE5# z+dL;9fP=d=o)-?MX9s-@$P*e!D<@ao^M<&F%(rwbZNR@aaZ&R zHKXR81W0bP=?Aih9qE}qd7j8aU9xpBnq_srw^I;4A{5$mNW|R_`hAo%2%#H!zbXa> z`_+fq6f3dC(oD9)>c@ieWE51?zuMNqAF(~YXp_zFw_{Z{F!ko6u+dQ}k| zvsDHA_l*poasI-1kD%Q7RdXNGH{ww~>T?j%V4+*4#(*AgMyzGY5Q3tW#T+uuVe3rn zO;vDJKeA-}{Rx%B*FF@69RC2+l%T&t)2|%vTkR3xwgC5OWFQv!gNb7Gi=IE5Lc!Ex zkY0N0lG7jle>0IO2?k2B9LWIBC*@hvVUT+lsyVqPrF|A|zvQ<;p|VfaAq!DnCb8ll zB6 z{<%LS6FN9p^oK*aF;^TdRV{%!wKHy^ zSb_%aQ5>YTx z84P)mmdcOUL>Lbx^vA8lqcvTd!!8Fqz18v2eN@%$i}%xXOb{i6FB?O*-yJE|n1C5+ zUa-cIUg$=*z=&`wnA-QK+o}J@(>dJ1s|D#BNL?<9 zp4a{>6VvXJ7+9#}gD%)mwGr0++npMGPt{c&OL>CJr=cD~&|lHR>u|SQWq96=v(6kh zbnxPzgcExw#L{+;!<_YDN%=tG-;kjV3t zmn+dl@n!+U#q6YXLxk+xyZ zjJr8khQwVk_lBpkCJ9nYfvKlU+AN>@*B+La zuqUM2LG7CJ$ZVuJRXHIE7@3OG=n4vVk^DTT@W{h~W*rIW&!%C5nHUq#18yyub3eMd zluc?((htwR4Sh;$4>_iYB0Z}<^PErac;@(8xbn+~KY-|9h@abntyL?v2#4!^whr3e zfjQBD*otF&v}{K@zo*EdxcGU)L&xTn@8+ctlyIMSYtKLX20F<}}*; zbj}3x1YLKksOuE&5__-G>Ywi~wn0&wcfEJ(V55%1>s_k1%w=dy2i-RP-TD_;Ue}!e z`V0Q!6&Dy--(I*=2nC9vEC3$X0SDML2d*xUEbrbI+fjkFna>N5;6kdO@Z!G(0v>Wy zM#mQHH9hOabv7!eW78}_w`l$tbsQ`yBuO}m*x2NO3kFU;MmO0aOQ zXOqoG@MCo-NC*8LW-Oe__L$U=Y=^#4Ic_qz4G%yPy$y)Zg-(Abu2X+ODt$6jtFRbjduXt6YHPt!Z z?Hk%ZVG3YMcFu+u=P{5)?AK`w{AOBJ8C$Pw&G>?(lV*cN#z-G=&i`5Y$}+OktyI{p zoWa$E6LIE)_+a=g@d6T_@05=;bl(4Wl0R}jlzAjxk+1+4RG}Z4z-2TifyFWio74u$ z{TW{^5NA$qs#aJ_S)n@@hnu>N*)TLPH;|)8T$E7ioWmx7RAUJ*%#3n+aKy`bya&C2 z`A9P2%l0T?Xwa)I2YoKWB;j{MvFPXcfX$3rqp0pgH9tivRf-ZfL!{%a=;B2X-BY;GZ-s{4C7>5`E-Os|C~2?qPmU6X-;-8C z50?wM)0b*E>w?+GCLS!73<0Wy1NZ;plW`U6}s`Kv2p0Tb!L+CY{HWO#hEy#w+s%9Sy-^{C9B@D5)dsnoNNOiUD z9wgHuCPSEYy{R^kGjWx|&u&`znVCnk7P}#{C%D_a6Aj}794(kTNfJ{aS)4!CDj_a76LGyES6*dW?AcVx|2!5OzVK9r(R(3fH4q40}n*_cYj z6`r}z+(>@-(`l73m+r{sTa?&ZE9Mh2%sYW7Oh+s+mV-I?>lW@w{}FMP7yI?M<5F5A zMjm~JAa-)-4%Oqrsb4LW&>g%(9qU26r!}b-4epL<1{cpLfw=orl~+xav^oR&YfS@h z*HEs3H;l1hWrDXmrot57zl0)GQ3VqJ1vy_0jQXPP^nQCt-1CK3%=@nI(9ZDNr7NZF z7mi_NX@@))UGfmVOmEN7w$L_gD_Ns>iUBqwtMhj=+t60g-6iWO;b$=2OcipHOrJmH zJ@)`xx;HjQY{M4}cs2BN`HBrRi+_ZWWq8d$k%TV1Ntt(nNBF81VjFAXsbQ?GDLBWd`(-;;(FGe*0!de(2oGG)8 zXcru;FGH~U)69m+@o|8@@gaPGmp@ay0nsj!5O0UbCf*Qn%Vi|bSo}YoR&1k<*@y5* z0R|KX30N2sB|9)fP!2P3Ms4A>4Af8nnT>Fl5j=tv;rkZQO&lLE_mgR+Y2b$sb=qjw zx%GAA6Pt;?<-QmE-Uy5`I*4qNXpnl!6cxn4HH9%@29})SV(6N^%)*@_2^->v^H>-@ z7eMet+O7X=nkOx`;4}hh!Gq>rI=tD5!9!2p6e_zzcf8^PmoqDuLubZ9VAZzD%bKIZ zV-u1GKEQDOB7kHC`r1_>Te-NO`kzUyOlOqyMV>OHrjwkkZU=u0ccBo|BOUw$v$gHo z0(hqQuV_Brx`rezW)8)zP7d)^Y7Sw@>@B?$RVdV{&{ZsolX*w4*tlXm%|b}raUMn`2Rz5_J*8I5lXoGzv#4mgieOYd?w#&XQ80o z(jK|#*4G9#OkK-9*U)9Elw?z$kWq!l>7J?#WY|AAM_OAG`cp~0Hwt=dHX@5g@Z#?V zoZC|Sp4M0&v4qFo+-6$?lfV%~bGfg_0avUlql#^QCUvp}!3x$$7?^vMgZjXP?T{Ub zF!<^Q9kyZhJ${j2jc(cztt?GQuLa3Ao?Q&z{vD>$BL+Ur{*)v5xUk`{ETT4@JNNe+ z!JZVZ>a_5f(De;K-6=dOy<`?e;&DI=a60qCH#d{myb3P85?w~)aN*%fqRFo}A&187+Et4?nMAf5-Ps*p~Bew0-N z7I#MIRODKPV(JD(T|KoM>Nv^lHnJp+@iLCrFm&pO3%03B@Vyj^b|RFF2lr{&pR#-+ zLVzXe3=u^H?W>WFB4f#_3=h%v{^dCD>{g@H-{_#iLNrb}joQ_qVq4Y_qN!{cP`ffnIzoF{Xl@>(2}v z8AnYC>F>V2Y~&5Ij^5Gj#=z8h+Wv+JF2WnExNy$FJIL5B|JgB1yCuVm@Ky?l#q$8w zbN`d)yJJF63z)RtSsri-Z1EsRJ;CKmiz-&^WR;>W=Z1V>k0+Ofr7?LXmM3-hk3`#H zxCKV61zcE5pt|@T9`@7Hx9+td@o=$QH1*0^o$pj5_U`a!9si8pkkWs*#8=9N;jk40 z@zc#BxFZyHahFEsVc+S$cF?{1zF{3sbDZx;%A~>4tUB!Cf|KzvT4Hf$${lkL!)H3r z0P!GhP`scdQKSGq{9#6305km0jY~=>GGyUVyzfof6i3m-fDJ)#yJy2Y@qpgRwyOt6 z(_bV69i|jXYX-NF{r=E8qedT=?cQHmjS?T`lsTqIp!J=9r2lWEyTU>iQBayrD3=Rd zC&rtw_xLjIunncxw@2fT*S+lpLs|oKk>Vw{fi`c=kBts9CRb#?;VLx; ztQkX5aPYUK`lbmnKmuDd!23J%=cNQv9yOWgFW)0yNJ2=DvObBO)1o72*V2!``XK#a zt11m^U}~_6Kx}jpm4#>1%aZ@4M#$BRMG$ftsm1EiGV-Uv@}kt_3uPr$=s&-HW-Rxv zqqo-Df2clmkw#T(83tZ)@IAs8tS2AZvCOc>q6YhjGSy_~Hbry7c6?o6H_x?7*#`ok zpZTI%e+6kp+a@RXA#^6lCfth)>0*~~^Dg*JbYt-!$Y?#DF@D=M6@;pSESlJ`xJmj1 z6iS7FCH+|Cjw%b8J>EhvG>9A=)@5bi)GQ=^@FELZE`orSVH z$9tp+iYNL5C#d&aHF0k7=4@FH(0GeFvIiB*d@0Ti8#)?}3h9BnlinA|2TZ}1%LtZ_ z+2Ty;jsHcTIv^>}I1mbE1ah_g`K{ym)>yuOQoE7lZ`Ain5m>mqhln=q>yA{>&pJPY zKh7!fRJGx}1v>Zi9hfe^(e#-G7U=J{AsA01bqAejxc$|BPCtdtn;%vNQlN8VkPlw9q9CPEh}t0jk1 zrbfE+_+(~SOJ_#@(U#6oThL;wM%W_H%Z7@#Xq{@u<13C4l_SzkH|~r^YF2f)Zz60h zrKGWFeY!w9m)vPSort7CZJ4AVs3uW0-Zfu~Op2P~*>x5BR}RX_^RuEb{ER^SG9mjT zUxF)y+Ah!bb97wv2<-=Q8M8XV1ZiX?^Irp(ZTeZoS(3KVW*;fgYvD$YVa;I;)Kh3k z0WODTdb$0ITqOD$MPYxq8_Lurot~H+-v^-^Ja^n8lp^tCyGTwCuk9eWBS3SClHF{{;pw*x>pZc}i`STJx zF*I9XJMnNTb}r%{WDh)b_g@s^^vgr+CJX}4M4>id=k&3`blJNIGPKe{cN@9}QLAfPi( zuNlMto+y|`-{}qAd^1)5n{8=X7H!K_XY9*6jx->1^Z`YwiUtCisXJ|`d!<&oqsg6b zq$$05u12NDm-t0;(6LJvw#14Qxz1sEN})OJ%Uyuo6NLf(n(i9?0fqmDl^s{E&c{_;7Y-jli4^dS3{abnSIpqL5KIv*W;|7ARy=e*B#Jjk1iIee;LvL3mbnw z`xFQ*Qs5^Z`!H@EGCayQ_Zsvu>BzNRrA~k&n!XZTrND;JL*sdVO0XT>FIJaGq^79e z@l|n!zu8|Rq-n2RP2>9{9PT*_#ESaf&mB@dlw_40mlSXQ{@vZrdrtC-ITj}0S1#Q~ zR?_^j^~hZ^9?+g0TAG-0pnls?n#y58UMI~ zb1^hHn|5MQa@CxhikxytC#ld$1Z>JAJL84GmV>ftL=_qBlb|?9hAu2Fy&r zdvz%k{4prnSBK-HYlqRK@;GHjrHyyD770c%+=gU%7R(owI;_3I@0B3{gxx5YW*9F< zL+qF&!}hI0llOGqK9A9UYI#ZVOg7X!%3(s`asV>Yb836(WNFpjX!C>NCF`^*SeQPW z%9e!uXdRsSmG-_d`lF@*!st9b4rx&-$Edn%;YLyNiERW80pC0Fs^c7t7|X&)x!;FP zl;li&n#4F}@6OH%Ub?S{2@l1u*^A-D5i@-d^pxJCs5D&#Sg9Y6@8{g^f&-iE-fB0z zt8Z2pZkE9>Ei1mbrA;g~+sr-L^2cOY7;1#`^zp{jk}>e?GwFf6yW?od3VqUfMU?h( znI~u%dDOF*B>I?W-MY=!p1R$#*hv7V!CeYoFXY(gS#LeF%@m_cB!sX_|t+dn;o zGRtik(1#dU|DnoBDOwOmb0wCNfTUF!=32BqkMXkr7ZizG!{R5X(Tilw@0*<|BSUe5 z&og6~i)Ep}>?AP<+F3r2klx&}3)`Zqu zH(+tn!ZuE7K7&2hJd=nTkQTXVmDu`tb~Df53i4Y5XpW$RXRw01KV8(P-d%Drn8H)P zi-*m;5;qA834sSB-8b>pzNmfm>URFmMVjD$M59WB?LF7k5j@M&PNO6wy?-6`%AU~ z{Ky~Z`fwujNd==?m#wZ=UmLIqCe~F2+!~LwJEBvtRh!%9AY}~x0l6?w3j%7$ct5(g zDkv;6U^(c*Zmf^`{ZsSHC1n|AjfUGEPkgr4%)$Z1hmu5)RFmUxGY)to^DaoVEl=D? z_izJoOE0C!tZ`=uv4D6*>tXyKa&jdmd0w4U5s}!qlr#XM>134f8=M1Ah#N^)IGzpK zqM}zuTlFEq%oi4+Xxf?601r}(GSyqSuDOPBT`#?D*iJ4SE#H% z_c+4(1IgKfyxGhc4Nhi#CRCeu#!%caUyztk5O^Y)T1v`RgK{!}0jV7L38d$qDB3R= zpx^qTcHjqpP{zZt{&#EmxX3hqg~F=rx3t4>GXcUl9}=CAh9pCzLJQ?w*$~86Bh3}( z&LL4iNaGEC%J0Ymajq3-t_kVd5SKXIRmby!4@wT?tDcDS?-eQ@mMC~SbVRfdN3seubrpHn4_=q} z*!29mV;?&EzxahpXFrfkV&2SkF>0$1^5GLmi81@r>6=nXoLF(Tp_d6j0tv92Rqnp7 zkb&|J^NdwkxXvft)|xuV%C)ozIKuj_WsZtRisXg8=y0_oQyS8Q|V zlr2hF+;uf~iwCYQA7vdhn}Y)D*jAuTTJukK(Nxi7DvSAoLNM0PpMP`A`%J@pd0Xav zc|Bh`!MRy-?p9ObRo+8FyvxF^wnl~;Vr7+t)6E>|%%mxXWEPW$!wyxG;Ln1I%fOu4 zZE$?2Pn(M&e=RR13wWxS3lH|sy0_W-+Ip8P@o2>M46Q!sqeT3oH?i-T*1AGq*1%#a zakxPxtLtV+#d>rvXNhbN7+dNS3WKkcF93|`IXGE7=w8LjQd6k59t)0a@a<_g&x;0w z(!c|g;eY?bvi=V`@bBqZi{SeC|DX)0j?j7^@5C4qe5?rrUDClnV5Wu1N`6rim*I1Jf3F4~lwjtF-$j(rdyZN@p+z_B zhX8y;k(IW>k^;9>$+l}QV-)Q&3D{FIc?5IFR!p7{r^;mB{!6^;l6`N3wT85npHoUV z($eDJjQVYy3>}LUQ;^`DP_cU0fJ}1rJ&0usQ!*2`vP|y&9qZ*L9;30WB|!*nAEsdD zsh|w^1!lhXGmk% zKEKnO0NjS(XT91|F)&gfqV)KjX^S0B_+JcMD(SDDn(yfJ!{%dWF2)yb3cuM^#=^gw z6ORjx=v77Ea9~|gLFYi}{@E+{kWY4v_G2vw@O}15Os2uGvKEi=HO+aIjJ({k@Lb0u zaOno-S*f2C0OlfnL&`v|fYIir<#RzP3?vV!N1+~oDLoGbnMq*mtU9%&U})*ndJGl4 z@xr+@y@VO>J@4YLp}A9~ zD#o11Rg^1>#j%vZ=xAw%pnfCw#FYbaw?};arJYf7bUXQQUBwS)U7DjTA+v zzbj-zbD=FrX9T>-qmF>0R0604hDV*FG}6`Nv{pA)@xDnq3%Q=75L>HSmipr)d!|R zf2D&{mi$XM+ejb3nh>fr{gxUA1dLsjEOf+^8bSy|!L>QIeq0MPG5uPnjBd%d1Ho_G zM>LE!?<4UP~hGMpzNn#qRv^y)X)t{4Pd;^Z%Ne&-5%8lE5ig) zd)^$QrYbB7!_ACcV})h=S0nx~lct`N&rJKIZqq=7xpnpEt2dt^)8CEMsDNpB=TndM ze{@{t*;y09$Th@R!4V{CRyD3~yD&9LG?>U}Ym8&bq=$mA?d6%|*up<3VUFuY72zb* zOQU$v?9GT<(^2T2YX&%3Po%lCx;CLpCJZHRYEa+gQuVkeRxpDfT1?VQp-G~_$V#WW zpM&*;XMnN=dT`h;IkI(W3KpjKF$}zrhMKqoGvS~G$prJngBOIyWtj}!5Q&3Kk!=4b zQwHFJzi-yKj(foc^*7#EXOM2Li?Y?Q5Eu3>83?}W1aBKQ;ziJOSKf7N2nCiH=ns!H zT`&Ww%7vSv%f;O%cR}6nX0dMRe;5ul>?WXA*23Hc7QU_ei%p3?#lCv!JlOFp^fdZy zBfdX>MSm+|>Z=`#|2XMjjmMlB6lU@=JhGR5bBqRY#S+!t=eo4t#-2gug-?5myizC6 zAUq>$1GhQIn+R6!_P}C+L*Q9NL;UkMlH!uw8nl+;$l72ea~sD*8{+@q30hFdxRML- z^Mzi(hGK&fcA+1&Zm$oPJ7<7oVSb%jnnPms(r1T5EYalZ(%wrqIXd#KYlFV5T zO_C!t@o``F+3nR|%R1Q{-5$|p{H~{s)L!TjAUuC!F8oPaUy12=cfCJHR%@)OjX4Ps zvHHHaMXYOomQvwnVJX+`S~coGxIXFjvMRfINqET*K3SW}8w*hB?tKV0~JzG-`%OS6lL#w;g3z0lzi8x zSKXft!vJX!&D6h|U>LJmp(&%o`eA~n@{^UL8H^@uC85Qm@|ocycLYV4X4l!W06ej( za8DL^2@^9@_l$7|W~nNt3BO6Q5YNF-NGEdj&f#h; zPhr10ao0pt15^^YFsZ?~E>;C%G!tvbZ;i|tSb)(mr5MC-Mam+ybcW-tO*LAjGzep% z`Kt8+!~Ar6c<4M5yf!a~XMUMUe2o5$H8Mm$XB@XHl*aT~tl4o=wZR-&H$r!VtAQC< zs`c0^oV~KM8)XW89ffgmL3zJw{V_G0VeeM$neFNT`RB%99 z#rf_%e5upgY|CuBmyVfIK(`Jje7M|#B`s+R-&~NzjMwob0ayu37w37Yx1oxk=MkS! z3snQ2z)U>ToB8_N9~i#aU^|1hv+p12F`0qwIM%tUqSJH7F~Hb_okAW*QUB-ZPlD#xc832~vq1IAv{-T3H^ImMwLEbASIr6N`9Y3-pUILGidJ{p zSu)Gt4&#@~yYm&i{={J2dkg6vLZMW*SunRC-O1mUC;$aNpP;;46++pnP~}D>y!<(X z*i)2WrudtliBN3nOju#fsBs-s+yn(ytY)?(&v4N&qtRk9>hD;|VXTgRCNU`+8gi|X zr~zQKLH5Ich6M$yfh4TCVsm=~XcBEWb}Y>QjlWK5Ds$btDes+|6JJA>E!XWfO#4Qg zC&!vo<**v{2xO|?W3z8bHn)_-CQy6RbToHXskl@tq-6<@j)Zv)FR-Ke$3MTFt~=Je zTMpd3JAc!>3(WODN6+YL!rF7Ql!=s9{JHhln+l+ZCvzCi z1@Xew0v}ZA<32}n#8`kv_UH(Hcq><)i`hc=k*Helf#Uni`e#}WSD|9mgNe`4(3goLXNZO+yaXr zTrU1A>$!lcVc+ESZY9|nJA*0X3L}ZgnK-l9dSO+wcDfZ|mnRr|-oCQ&YMchB7}!%O z5B5YKwW;MHtS$coo`6BwAOcsEHC|0_8yjz&l~4xtCTlGay-2sp%M2 zT+>G~L2d;Jrbrr2#qZ>zo3~Y-uo-A9^9*WO6|D#1i~D4TO}GfY7v$OnZoQLJmM0Lf z;;M`vt=So5$c@B#vM)D;{CG_f*-wG(NmSYB&aou9IzbcnJLPJTRsMil3R}StAHav@ zm)ADQQXcCl;z%i&BmOB^L~{XM1HB+jIpp+X4YAiwn}s@Y8BgKf1|v#3E(^$@w!lnZ)_moJofx$)lNsaNpCZdIK9QTM$!^}p99bm~-iB{oS|BQN z?+tj+9(kEV3;KJ{hX|BgYQazLU3@;CvgExL&6B6(v7UzOIy>1uK_tV}hV`2C4Gx#E zFfDm}U7~QH$Pb#ravUHto3ICt69Mvc{cwG}Q%u{hXhb9}*A9Lm)m}uU(VC&7jBeS5~dP!{EPkw{Pob0VT&|8GUd5 zy$|o+68i68GTC$8hzLTpcS$y}M7_($Z$>w-SQ$e{*jxy9U1@bDeg5PzPWaHiy&Tz+ zX_MyRe{>iYpnLAK5_SIOEazj(x1&;Lw3~BhcQIq)yU`|KPk9qtjYHXgxLtGZ>hrbv zyw{s&)bl;O;!SK$$;Akq0d+*Ioy0`$h zxFc=YMP~MA=GAIpZZoV&`AhZ5UKqLhK?4PxeFrG%)FXlh!=j_O0%ny`m(F`7Q-pG5 zd{LF-aK9BG>mTn?TZDpXPs$@ZLYf>#x}LRVOVPQ{r73t@=3ep(hZ#lyQBoK{tkHDM z$^Ak&ix9{kYWx{MZa@6RM>iv!~2d-<-W!=iafr!=x*ABgt+eK z52#s=;GRX-9|pfKi`|LiHKzMU^?>US(CucxZ{;sel&K5N+&NtOVZ!>4r{iwclAlA2 z*;c;mv~~FQZH_Ntkw>=n7#P!?0kEX~G1|M&R0L1&}xw1-F9!@f8e@ISgV|0bQZ|eJ*`{SFlMw*T{JKq4a69Z9Eo^>Q{VbheB{#h z+hc1^xk7A;Xx8|CosKx8=OnX!(bbvqT>YH#)Ru)H_;Y9J*ahC6v!i`lT`yG4eFwylnUWZMq{#gI=zN_`rK zTY1=P*93mE2~)4ne)_IwQzrH9DxX3?dh;A*B!-*f3J{HttLR9K% zFDtF{@7`*wd~chmT6wALd}m(vAg|6Hkj1Ra49I7X-J%ixiT0J?^J0_h$vp2%;#vH` z*voby9dn2`rY$0+&}V_v_pImPbJEx2nDyqM52n+x;@0Ijo2QGO0++%djKVq#2r{j z(@ydxZ0?K*6%;7gKGRKYfu!Vui2YqD z^8n?KkjtWn=3UCj2GMu^R%^&+E)TE`K|h~~-RV>}V=l08I>dTZL6Km5}2-&`P9 zx2xUB<0H_wK^bd}quWFr!SD!?*UQ@35R=~pe7zym6`Ram?71f zGBpQ;;vP+fR7}42J-zraxD)F_I^WS|(=(NsT6p> z?2ZHZ)XLggDf#*dsxyw&~1s8RE4Qu;g`2`%(O0EY;9NA04UEIH)EM< z05fF-f3Sn3en}ym2^QJt$S7Mhy_Ci5v_iE4?2)6hKXuY z6FE7+s9R;qb9WfLZa|i9)VQq~8+rL5MwWe1cAYn7n*ZK;Wx$r^Jb5H$IJ#^d>`Tgz z74oScczU8jN+k@(QTZwf`y$!R&2*gxc%f-&oQ_y=xb`D?MRjuJq z^T>olM?Kn>O?zt6t=76J?nKfm8P-n)3!KzBqQmz2^UEP$4;7k&1r9M4M;;7wN#qjT z?Q9DwxRu#?Aozx4+=**hS?)5X;BTOSvkG_YWoAcfzQtl!Qd3;(iD81MGjbnlT*24{ zq|v4LmlnN8%)2YsSE*!?6+sx|&LckYN7>D_j@+-N_J^qH13k2c-0kL5X*P!3yErO& zNauQ}>}$M-U338jLXhj>M%YRIg0NM#c@-y0p(nx)9F33n_D+Vphx(X*{eEv3=tE13 zem5?iEq&2FCWof^)ZcJAq7lnR{T;Z{Eaf17wyX6LdsiLkl`vPHhwqbrH*}C6WAB41 z$mcd=ru25;4t$?vSRHTgxwZ1hJYpFVjEN!w=_UWzzdIj20tV6nLH$1DK1;J=LP;H$ zMwo9Le~pt)%P>2?jrp%@0J=8a4&U<{BlcPjS96#3NpH=&jM0?t(yF03c-1zcZi$Ts1-84D}| zw<&9Ow8E1b%%hK+IPZ^+0frQ{5Z!%I(meUl5eiCfpC1oI?S9$(wS!suTb@xFY@Tc{ zNfvvH(px!B0mVGVJE-+*wZLi1>|JfV!rUZ4l5el`SUjW42Hv)syVtR#0gB5H(44xD zKQ#rNT;8V-oq#hVNiyAY=5yYHr1BE?cC$<&y7DJ7xCsb*n@cMZ*)DSc+HR*1;CH(d zbI9W=H=uFnLC^#6RX1nTAd&9atl%!_*}I$6_beLfo8DbEW!s=^idG?t71k(^x_gYd z>&Qrma~qG}Yd4jRxFBX!oat@&JN)a1DuGFzxSJ~11r&J4uSe92T@+487KHBDC7^F2 z_4{VG6boUlJ&C%+uDEpV?xvwPs^KF;hQX*)WwMFx0OZ|nLv=v7_A^5&IE2nL3b}vD zW=iPn1WA$N%m*_Nq)u#g)@{XEmbfnOX*yz6dCBdl5C56Vs=oG1kHkclFQyCzO~i|D z)vt4rcCy(6kpp|Qa$;_|Ud+m#5387VL7SOT^+HN+f~TStoO{YbSI-(Y3|ztoa+Y&< zPv@9a!Tp@hl;+}A0s5uK)}I?p<7>`p z0yr133a*~W4VJfNj%-Z^>uk+h%O55O3Gx{@m5w!0>Ia z4taoW)}pzpu39p&g`9*vgc1x<=_ce)&wue-{+PwPE@rghf& z`%_sSZ^ua48}!#H40F{A>bb8Za^uK)=Iml3N@#ZS=Y;VuakEr@5O|x}NM&M^D&#%2 zwo7hX18Rle9ocnojY?Eg{wvwk;8Pyh@BFUCBR2=X{E1-k2WI_&VS>Zf58Vs*?%*>%*Kb{bNN%x zEzd1h>4Mk>|F8H=L)(JhrEo zlVxkM?(49C@L$l|0Ps-&9|_6n2mp*ZcwSVII4t1tnTVHP_eCI1ao%89Z+i0MGln(h z^_kx;AniW8Kz%UF*Vs)nc~BD}&rSNbIQk{_uFWWNg%h=-D=d=o3qod1qk?WgUv^8s zM<90@K>g`Fr%{2N(wauJ4I^SDJk<7K=Q$40(*>~&E9u?mNFpYb}udC^7*J*T+5#iV>{-n@lQ(5rvb8&&#DZy7il@Eel4wGRQVYH0L<>L~Z z@Rl+gI1|sj(rVd@e=Vr;wTUZOCm3xVvfX2hxxx^= z#1L)bKVDW_#5c+>NMjnhs9zKb_0RGi*$;VqP(CCv@cR`Q)G5HF(l1T}*tia}T}d`x z5td|JD)-rbP`Hg)8wdg_o_j#u8pIv80?8_@?@Senh5j=Wz}nKv zB;B3YvvlIWfKe1ZY+QIM(}5uRJVVegc!iI!p!7HsH^s#krJM?@hJzWC z%fA~=Zun<8#~pzGz9uQplNW6J1$=zkS*sjV)J_!uuF0Cbdz)(9Oqkp<97fI`_|h8s zjbwLCZf&$bvP;l{cj0Ph)6HTsH&!#T5yV6lwur*a#yV|a;VyIXXG-Zj#I1uQ z&vBTGExl;J@=LyavsFny%u475`FY;EY&><6+c^nuz7I{k)d5?Mf6Tx`UJkRjqQ!Vb zZC+1~Kg!qsh^zZ!ItqYd=By^J&hQ|&LD}OHm-yn^UAyT}J}WUVtramhiD1~RUd>($x-tRd-q^)%5*I(ut zL+}aCF{YkEs*%pUe7rIF{Lv3q&6|JmA(=;S$yrt=rhUMJAerG*eWrHPEZ^ONooX>9 zmpLpWk(arh^Z{+r3pf#z@A1Fk;MAChbKhpO49M*}_?hPYq8zr&9k&vVgaoN<>t}sYb#^@@ozVJ>zgwHL{h%+;}Y?@M8P+4zoBMpD16;Pl+H>%G)CTx$n^h|sJa~9wP zJjZNa*R~JO6Z_)(2qI9@Bf5#Bi=sXYMMb$%HjyJ7VBQet`%Ynv-bI-Pp!p2tE>7Ot zD{|8Nj;$lU(q0r<=R@Acw+{;p4|UwPdJJc*L^PSl|CobKf1-)Ux$Wk=_LGeLk097+g3_f5h(PEil+Z*h0YneI zOPA23L+DZz2q2w=8X!O*0YWvDFXx_f&-32%ywCIAKfm?I-m~}4OxEm~S!>pBubCAH z>%&y7t?>nJ7BCP1@g?3dY#*ZDNe19y#B<&gDWMjHK+xq1G#XoLLrRg{lGt!x1ZN*f z3Z%sb7Bi}HEege}a=~JN0*crNF(NVoUV)mu7 z&n=!nqY?|lHr7>rmOa;yEOO<|#I2j#IvG2XOu)P`oR0EPI6jcXF@q@*(k$gq67q$AH zCZ##Z)v3yOZL?2%ra(3*9I4xlP#(!++;SOe)So%wEb7ep$QR`eD{%}zo8XmTC5HS6so7Gy92f+pq{t|@$6Km<46MR0Mwu+4I4IQ5PfG zkYkd;aj*fQ=`pEU|1cn94>fpg(!Iq!Tb?OsvFU-a^dZtiP=wofO^mE2YdNDZYZ+z> zO7*?^o^dV5Tf((>($+IlyxeqBKnm}GD!QuYaSQUTx!)uI?F+!E15=q~y^)dTa}kyh zV=c(pqfjy$4{6Mkt?Mf|lfP!LpMzA4t#s7GO7>_S&nK+JX|DE~Q>Rxc`gFpnoVNFp z`I%bkAZezkk^2GGj+Tg#V@WB49M!r+MM!%-ICOiN|p2#HC%CkdU)+=x{N+(3fn3= zb`!{P-STf5POzwBPhx^)&Q+GE65YR)Tph3(Zb4emT#4K#dn=>U*FQFWAGV~!x9HzZ zb~l~y_kWTSy@=FTq0FOD^7yu-I5-D^iw)VSW92J&l#TbNaNlYVElWV)T$Nd};r1mH z%t`-@mAG{kjNbqC<==3}o4(M8LgfSs1M-5<&S2@*qa~DeoaN4#vB50S5n+ljP8wHP z34X&25pkO*ydqo?7WQuY!G;TAIhy$wc$#U`6fH7&)1akSgY)ItC+F79^Mdp5&huYB zXO)x~Sk+j26>VGMZh{7|NBuvb1nN*XYkteRu_>L&b?z^0^#rG5_QTq4$7KP+Zf z{Zlt{Za-J9ZVSa61@TIF^w)&)*#W`jjF>BuKIwN_klS6~3aUGUf+-)e&c+A_C#mUX z@N)Luq3%*%w4=sItFzBY&bE>aL%1$n{q-BWwd~dnL;KX~sPJkZEl9sP?E&WFu73vS z7%DZac4nuJ*q+qIqVRrs zaFje{iWuSxLk=$}P`$UgX#VlUZi$@5wGUK|nJEU}L4o5xJ&aZw=UTo$)Lm3@Kkes6 zjz<99ZVS$1i}sK?CfBt0L63rP{Wk3qH1vKy5^U~W`Q7V6_bbF}%=JgjX%eqRk{a)} zpzjS;chY)4M3+=`6YEqiJfeKpayXkY<1WxJHPAiSbcb`lK6T)xFc-l9>j-noSZLJe zn5iJFx7--m{dUu7@bgga`PSj1{)Q63?fqm$t*Y{u*m!D0Di+1!>1`i=6_zd=ZBY9u z?i=Lj;#kLw%%xI#1y|fVJbe5TK5s8n$Jl?vDn>!%wx2y4@QFN*Yq4^qVeG<(<$Wc# zDu0JARl3ju=}JzFD*T$+3tTlV%1PBqB2E9R5ctpBSH0qxl^8MK54Dk9@& zLOt;o;@diH^6$93lr>5j`PD^p`8g>J&^DAp7n^4$GUoI#>JA&d3vYNzWTr=wW$>KN zk1Zc3&+2Jj?>8^EB2o(+7N?9W`NdPS;JlJWqFDmWp2$b?s< z_5{M+BbG&B*Q=1h(5nADLCf_^$OQoQP-hS2aCk-f;E_kV`_r@dl(-IeAE}D5XcOJD z0D*_7n(7c+Rafd4Jdx8sCcEQ2a#2#imof5N<-2Amm7bojYgq~b0qJy8$N?|r01*qu z7B9KaDslmZ$Eqd(T~)!TLD2PRX#?V``1|hZqbW&Uu@v`|j5A7}TKQn7>~yrZkazA! z=*opFf7M{hFahOH7&JC=pfIPRo_kD!bt_vemh8)wfD02E{MaQ@bzh}m_ZqeP<9-LRr36l(vO4x8f zeTd3ZoxD1MMUBcY+*qzO#op+Fz5*N*(i>Z#v#<(|<9B?DlAhJ9XxpB%U&=)y#{Q*! ziOMv~>R?ZrM`0=m9t<5CGC9q2GyFhx=NYX{piAeF+NtCD@mpel2qqcHe=Om#-=gf% zt=1FZokkW@6@q$oLsOL3ry^zLF;kf?>iU*hI|G?F z^VREgcma^4bR|Gixup8bp6vHXg{O=LZZq^=NdO-0-$TgZHi)jTiyGaGGmPb&vVMSw zDVj#Ig;||wBb;bv)D2$F80B^VYX__%_>1M!{0}5$We284fmBU_$@_O2^le*|XbHB6 z(t2i|iAUAoRqRU0S2wE02u`Cnj$cND&rn8vj@GT~9=o;5;+oQnQ=^fa7i@y~a$LF_ z2K`!Zsg^gGOfrC_HBl8{A0jx$G;D*WZ8-*(PQCj)O1%24;or$g)xCGnM$UVqu{q!K$#aTU9%4ni|8HY;@#S|5;72ZhHO!3D1xf zSqI?IkMvs7zY-&#Cim9sthuxP0m>}e>!H3S?$ty6E6Ia%U#bJW1~gy@LFwN_`}NWH@cI5;!u*&6$;Y(?&J zNz_NAVCaH!O$V-O^1D&1{_VZ=DUP}Z_f!^U08bQTR@rXOv4d4>&51VI4qZSIgZYH7 zRHWKJ|7B;%Yw{=Z@W*jk-|!7C6g)jBzCvPLZEh=T!vDgV29Mg6nt8x}$bJE>LJV*>2nRScN)oBJaH=o?x=CF0sXX&T5 ze8?)>o(w&XI;!e<4o`>!v6A$`-R1IBoNIp+{!3puX%}~Q zB$bX$`g8-W4)vQ1)4Jd6H;XO@oA(TzlI!h zL&^(QWedA^QEd0wSe1{$_lLtrPGJl4nw8yjRdfX(3KI(%fUCCUa*Y-0dQn{sowwI% z7_+YHu=29K;@ZQibMwPK_TF@ zTf?ilGn5W2WEO8%G!FR$^n#dsAN0n5=yi#5%v^{_kmu8XG{aHv>*h`uSMwe&cF$r% zeJHkT)N6#B_|=5;4B9Q6Xp_59*8AAF6QYx}-}X>spg7dytgSmUWyw#}W_6)lAC;Ho z5$7K6-AB{kE6(I;u^Cz<;i8q_j<`__4@+@>w~*EOGY=rJr21;s=Y{Pa&>yD*x6{;f zr$|^^Ke|P%u^GS6>b`9>XEOoR;f|bZB3bW2+f^O+xZWCm4+=|JeoKF51r~w09&1m92X^MByNLSP8OK=}OEbS1 zux^ykg3dK>-7h=?2!_v!FAex7-INf$#=RPO>}EdBYRZ92DAhwC-Vj*4lP{RI8yH@J*;5wZ3~3Kkj^y zbwXeU@(Xm%w@^f0T-r({t}f!(BiKOnxocfcRbk!Sfg{V6(jh_OMCb`k8{*OwDAm)C z>v+@{8%jAxKxzqX?GW;bcLpQHTgKGV@W=V+M|=4O1gF$x-V`Oc3>|4@{St*;JdVBo0C~ZwHz*5^p>NW z-^Q}|tFiU_cvYcVLCR8dwupdFDxmlBIDyrE)`eLCK9H^PDkXVZq2$(b+pZKOXz_(p z-Y<2b5~mk@JvtRxQMBrhLm-@B=?5Q*D*N{Bjah0k^HTOVnm;jQUcC#Ml`-+vzr{59 zq>SW@e`Bv6R4!NW(qhEFZ_=|AdYb2UB-si&$8V8%Tz)%La+Cigdo?hfrui|mTo=~; z64S9|(;~N#vttWme;-WiQNOM8S)$PbNvuS@a`uUU+E!R?*Mo9h`QGSvW8ViJOU+aI zs_?oZw+5W4@^|%po;g9wP{xp^$rCCE1O9y$n`&4f{rkyXekUgwq9F;q{>x!tWhURf z`f%uKf5kZ<_yg|#>^wUx7k8$o*2g^uo{uNqk_LAX*=QeC%b-It_v=oNuZS^+)#Zn_ z5xjC9D0oUX@V>C{1&&tqXOHvEiH{`1jWLCi>lcPPJ?R3;&c@S1}}PS;`!2RmIbTrR$<~&b(B#p3vW_ zsrt4fh?Pg#^i{uIV&A7e9q3fprAJyZDzMnKQoYg6m!rN@tUX%dtj!i6W3$oS9E=XD zq_r#}fXPyFY{lf3j0r2NLegF8y(jSB1yEDA`xJ|m_uv=5sC<(Sgy}`towkpSJFQ!> z_3ZwZ=7=evXo(`m0D;Gaq=&BMT}H!5?Jhr43u);~LUNcVodrUJc3C}NeNj+O16+Zi z8A!18EneK3DzJMWC;*cA>HSpO(XXn})NSw`#ZTbtx!3n~q~v=syr8;v6TZ8Av9s)} zn5D|eS4ZZIgDzc@u?w;>eY~T*L(A6pB(XYLNTg?BT28j*}3k<@`#b4*N+Re3fP-r_^h}n zy_Aekoe)W9VBPUs$79L1$!jhJVafZYvgZiVv(B8A*Uz=znDCvLWSk9I-`G-^;?HO9 zBb)iJ89g?C7jhRE)srMrSV_m-qt5-f!sFSG`<#*t0_zp~-mD&F#y~b#fftM4TrjW; zA6(itgB#CWpM_%>AK^x+#~JS=0>JQeujvdCbTPKufD+uH$>`9wQa0@=d=9T0`K9K4 z7f}(&OB2Pza>lStAbr&LOp0TRPa!(M8mv@Qf`j22rx`X14R@czfMkmn#*NEs$S!6SKqic^wZ1BsVBeK zSbtS0XkAH$!E+-&j`p*cJ!n%p-g`-G3Me<=eUAmAp>`vB)Ip}Yy`+oY*-bli%9!0@ zpgJS^i8OlG7cGkGE^;F310{M65Q0V@97%4^EcmWQNg8B|y$T7j5vOf@SG4UKj#gh+ z&rU`H9Hh%3%i9Nq)v-N6x}%XNjuQNn%z0mx-6tI?UCQ^N7`nw&?5x>D<4>Yz(8Oru z{zo63IRV^Ki~bWgpNnqRukpT!03fg-ZmHX54xsM8p(dM69e#s7L}1s#H_LW?=8pST zjq6W;bMwpII$ohd0r?{tMovn#9er8?Ul=HcPSqaoY1z31%RD;tmBJspp!cI4agA0k zDepc%v(<~?m|cfsU@AqMV3iRfpuOnHEld|~?RxQOVsLw?^2{c$iJ*u!HagCQu zYPIuX0bliR-?k2$DgAxLf8%Q7;c?i9^WXzx>7#=0uLQl1>|lZ&$JRetc0_6vwds83 zd=^vR{ToW{bN|j3Rq^Y$hREQRgGRDD)3=qUv}(R}I_YH5Jp;4tnR`ieE)|RnL~g72 zSCLL{GHDmDNWMWPmGQo@yw!y^wXCC72p{a``joiZ+^emrYvj4~sh@KKc{!0^s=<2u zeHjl-Qji{C<)|Cg&of9@Z5cPNXFnU9$HO~jGoD$gYzfR^cn|QlE-pB1BmFit^L4u; zmy)|MfG*W%6LjH)x`uOJb#yRmw1oAcrhJ)11s^wTTJ!GLBHJ%W%eZdnu)RQCIbGf7 z+xZX=wi;_Q+o#t~e3Seh-yp=iW`$2pxdBesW!Qf0-WvJAujtVg5+a*X;?ZN6^HKWM ztb(1MT+}CPGc$L+aQAu%xwSHy?69O8E{`_uuKe-^|FS=l;_9eom4gFLFt4M9k0yld zXV=ZH*>=msaRyCe#CToDLf;$1Mx8)>Ff=#SU}0vsl=G;Y?3;SIch!qJwYPugc{508 z^%AI@bQH@e4e2dY$tVc5i`Cxp)K8>7<&H+g1hIzTpe7+Mkwq>8a?-($dLGKI8KHd_ zkkz7u?>8vX3!_|4a}ALE=B>*z|) zzNBOig-m~yVD;6){)#s2@V4mQGf_*#QmlAY$NKgFiYwp}dWTUSZcuF7jy3c=lG7Xy zCvS*{_fjXAN1feH)+^dEnHSlsm^&q$-rhcABD_QfH0@*#nm78~XYjpgaw_v97t;kI zM&97^d=c!APN&~?Qi<#Su;pK8=;2`793~#fsGx^!k2rl<%&Isa%|i`{m^(ww-zy7j z3j+$Iq&yxQiisO^1oa=Y{>~(BVADT{4e0Tg2`uMJnO~6UuWJrQ35oBSW5SE#6kbP3 zr$@Xv)UIBcqz>Kb&Mjzi325rZ73wealyodYOgVu!1VGBJYEy=EeD47xC&A2hcE;PA zgL3sPP&z?sDs-`XW!Wcn4e{;j%%N}MamdR~WvlIlQClAyhfc1K)>{30`trva()*Z< z5|kq-3n6NI$L5OD@Sv{2n_WqcO5)4gh~qwQt^TsMtRbdUE5D}GHjkBR%hZ^@S?^NR zHlz#v9a9q5FDxv~R`_N0(5WZ;_#|f2)nihX;G4PTUwCRVe(wxVw@DEwb>2JLwy5H^ zt+je0v&|Dh4hjY<4S4>Vob@mACdd(o-~#mUN(M*{**=(`QhiPo#t4{hM(>ox;No6R z2)o%l&td}0--c*Y*7@`;@jLch*JNF)L6TZ1hoEZg`3)Eu3$aDlX_>AF^JWQ#$=eRI zEy;e)DQs}Icx@T8wC(Fg>|0arwt&m@a&=q-jSB36Pa$$!!{C0}yj)#bXU~?)T@k5Q z{_Fj1CbX_cgp(WLqByqNyOzUa_1?$!PF zz~Q#@Q(auSBfD0EVW@o~mJS)Dv+!AJ7u`{&>wGEhF{i5Fqfw~HM%ltNsTR&Rl9&sV>6 znIiqzn4ZZnGXc9D`6>5c8RqilEx_z!deW5r(}#aRNPpAvokI4>fbg?esnbIw0PFu6 z7X}qqM2Z5p?WLN~KLFLQ!QM@rIE=n~fUrlhBWl^4)L%xMF$*?Fk~R@`epcKZ9F1)u z2VDmh^LWUdwBKiyb)p7XF+v)9epXr())nBE8P*FUgjzC^KWF_--h#)SbepfZp7?Sw z-r;V1q<$7@GpDMma&zbT!1YojYf_n$TT_+SgpBOh*O~kXE6`Kj+&1U0?TJ3r0_lcJ z)$Z~U9Xx&Sfz3WH(d>vs-c1W$`ni_-9}46Y8hl9wFK_g+9unkef{#268~7&J5?Zl* zV9!(c)Z{ijqU-^o{RwO6gFXx&(NB1CmX{{adrHRn)#F7simPl-xUs!;Ka4962dH)O zg~NNfPWWNN7eZ8EgTym8w}lisf!g=(9wV9O#P6pXM|ulk4edu*WkPF?3TUw2NBK1| zR66vm2zt0{a4ML5a0C$At(U0-J6>j$t{6HhC%!fgFZj0(`|G?nTcK$6{UXoS+aox@ z6I_(+2yr&6W7+eVGor{x$K&^8^?QxUgS}BuZEgQ|;Kr|llkEQ}qA!%dBv|>hlk-xI zgs^w|*+%kdJCfn6l=cx1ZCiuW$;Lb>r{(OAZDk$m)7WRwxY0H&R^PuTMB}J7ep+nX zr+p}t?B4`gzZj-=0ZNNx^OeWggsw`bBBTCpus;*t{ai~y+0Dj^(-P@AVZYddDu<#r z;O_9YP}Td2q2EslWlB9|O>KX0hZY~hbN)|R^+&ofg~ERV%bG&`+%+GYU~}AgZ*yEl zc0QN%QE-_Ag>E_cGoMIoSBGtd9md2d1lBR0{ND9zfnNW#j@$6>F8gO2_|VN(5W>O>=&4L>Feei1Z?d#Vn&*{{9oC0-Lxp6J}i=uf^)(rbpy8ixL(@??8B zU==~NNtLqG)P>#Xb8g!f3f{pd!Eta>L@B>m0(UmK^^ws?wu#1+a`r0Y(iw+!NYITWb!O7 zz&g=0#?I%Z5JxBr^CMF_aVv74LQ9PbPmwUjB@Kp7~-tD0<`SKVOM=TdDB* z@xYPSLf9`f-IlAz{)tJ8;IV%e!2IA$n{e1@is$^bd2jQa7P{%4n))9d{LLGLgV-Nv z!2eFm+@WOoqtZ@5Z+ZVC-3_x0A3sWv`xhqie---I^JQj6uS@@R z*`Tg9GUMDWM@#P!2Q#h#&Af*-r>CdQ&t9Q+$19-wV4ge6{OjYUHY*DY3t%2hM4qD* zc{mXu?5M=UV3o)JWJ6w-Kp(fpPL<(qTuD{uH zWJJF>DOe*@pwcn$Mz+>^Q=TH<7YI;ErI7?^KRaSx{3U4 y5d78feNm5wc+tvgmj6@R{If6q|9#E&?p*K^t>DD@-8L)*nI35C-!0d)jr@N^CCi-v literal 0 HcmV?d00001 diff --git a/doc/html/_me_base_board_8h_source.html b/doc/html/_me_base_board_8h_source.html new file mode 100644 index 00000000..8e1bed28 --- /dev/null +++ b/doc/html/_me_base_board_8h_source.html @@ -0,0 +1,195 @@ + + + + + + + +MakeBlock Drive Updated: src/MeBaseBoard.h Source File + + + + + + + + + + + + + +

+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeBaseBoard.h
+
+
+Go to the documentation of this file.
1
+
34#ifndef MeBaseBoard_H
+
35#define MeBaseBoard_H
+
36
+
37#include <Arduino.h>
+
38#include "MeConfig.h"
+
39
+
40/* Supported Modules drive needs to be added here */
+
41#include "Me7SegmentDisplay.h"
+
42#include "MeUltrasonicSensor.h"
+
43#include "MeDCMotor.h"
+
44#include "MeRGBLed.h"
+
45#include "Me4Button.h"
+
46#include "MePotentiometer.h"
+
47#include "MeJoystick.h"
+
48#include "MePIRMotionSensor.h"
+
49#include "MeShutter.h"
+
50#include "MeLineFollower.h"
+
51#include "MeSoundSensor.h"
+
52#include "MeLimitSwitch.h"
+
53#include "MeLightSensor.h"
+
54#include "MeSerial.h"
+
55#include "MeBluetooth.h"
+
56#include "MeWifi.h"
+
57#include "MeTemperature.h"
+
58#include "MeGyro.h"
+
59#include "MeInfraredReceiver.h"
+
60#include "MeCompass.h"
+
61#include "MeUSBHost.h"
+
62#include "MeTouchSensor.h"
+
63#include "MeStepper.h"
+
64#include "MeEncoderMotor.h"
+
65#include "MeEncoderNew.h"
+
66#include "MeBuzzer.h"
+
67#include "MeLEDMatrix.h"
+
68#include "MeHumitureSensor.h"
+
69#include "MeFlameSensor.h"
+
70#include "MeGasSensor.h"
+
71
+
72/********************* base Board GPIO Map *********************************/
+
73MePort_Sig mePort[17] =
+
74{
+
75 { NC, NC }, { 11, A8 }, { 13, A11 }, { A10, A9 }, { 1, 0 },
+
76 { MISO, SCK }, { A0, A1 }, { A2, A3 }, { A4, A5 }, { 6, 7 },
+
77 { 5, 4 }, { NC, NC }, { NC, NC }, { NC, NC }, { NC, NC },
+
78 { NC, NC },{ NC, NC },
+
79};
+
80
+
81#define buzzerOn() DDRE |= 0x04,PORTE |= B00000100
+
82#define buzzerOff() DDRE |= 0x04,PORTE &= B11111011
+
83
+
84#endif // MeBaseBoard_H
+
85
+
Header for Me4Button.cpp module.
+
Header file for Me7SegmentDisplay.cpp.
+
Header for MeBluetooth.cpp module.
+
Header for MeBuzzer.cpp module.
+
Header for MeCompass.cpp module.
+
Configuration file of library.
+
Header for MeDCMotor.cpp module.
+
Header for MeEncoderMotor.cpp module.
+
Header for MeEncoderNew.cpp module.
+
Header for MeFlameSensor.cpp module.
+
Header for MeGasSensor.cpp module.
+
Header for MeGyro.cpp module.
+
Header for for MeHumitureSensor.cpp module.
+
Header for for MeInfraredReceiver.cpp module.
+
Header for MeJoystick.cpp module.
+
Header for MeLEDMatrix.cpp module.
+
Header file for Me-Light Sensor.cpp.
+
Header for MeLimitSwitch.cpp.
+
Header for for MeLineFollower.cpp module.
+
Header for MePIRMotionSensor.cpp.
+
Header for MePotentiometer.cpp.
+
Header for MeRGBLed.cpp module.
+
Header for for MeSerial.cpp module.
+
Header for MeShutter.cpp module.
+
Header for MeStepper.cpp module.
+
Header for MeTemperature.cpp module.
+
Header for for MeTouchSensor.cpp module.
+
Header for MeUSBHost.cpp module.
+
Header for for MeUltrasonicSensor.cpp module.
+
Header for for MeWifi.cpp module.
+
Definition MePort.h:71
+
+
+ + + + diff --git a/doc/html/_me_bluetooth_8cpp.html b/doc/html/_me_bluetooth_8cpp.html new file mode 100644 index 00000000..1a62fcf0 --- /dev/null +++ b/doc/html/_me_bluetooth_8cpp.html @@ -0,0 +1,190 @@ + + + + + + + +MakeBlock Drive Updated: src/MeBluetooth.cpp File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeBluetooth.cpp File Reference
+
+
+ +

Driver for Me Bluetooth device. +More...

+
#include "MeBluetooth.h"
+
+Include dependency graph for MeBluetooth.cpp:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+

Detailed Description

+

Driver for Me Bluetooth device.

+
Author
MakeBlock
+
Version
V1.0.0
+
Date
2015/09/09
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for Me Bluetooth device, The bluetooth inherited the MeSerial class from SoftwareSerial.
+
Method List:
inherited from MeSerial
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan         2015/09/09     1.0.0            Rebuild the old lib.
+
+
+
+ + + + diff --git a/doc/html/_me_bluetooth_8cpp__incl.map b/doc/html/_me_bluetooth_8cpp__incl.map new file mode 100644 index 00000000..e6045724 --- /dev/null +++ b/doc/html/_me_bluetooth_8cpp__incl.map @@ -0,0 +1,55 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_bluetooth_8cpp__incl.md5 b/doc/html/_me_bluetooth_8cpp__incl.md5 new file mode 100644 index 00000000..bb9916d8 --- /dev/null +++ b/doc/html/_me_bluetooth_8cpp__incl.md5 @@ -0,0 +1 @@ +8711606210fbf2acd85567084b8b562a \ No newline at end of file diff --git a/doc/html/_me_bluetooth_8cpp__incl.png b/doc/html/_me_bluetooth_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..170c249a39d6a02c77759e51bf4120fae8986712 GIT binary patch literal 66171 zcmeFYbyQU0_cuyNC=C)r3W!L@(5aGwfOL0Ccc%yl3?(Hopwiu4Lk&GB-5?{3bV&*5 zd&ckmu62Lw-n-uQ{(p~uFbwBBXFvPd`?L4{>}~98btR$)v=1;aFo<3%%WGj^++)MQ zz}&*e1-|K9P>cY6;999F$z%LQ|NGQcl8S-x2;-&va~=QO{nY^fwDYb%Czq(Kd+yBd zH~TiDRdoY7DUF*Px#DcFJf)g(U8){rF}Kb+Qa3G$9PE_2XjE0{RaidxG{@t6ZTL6~ zL*$@L&!x9r$Krprl3tFH}eP`~S`L zOO(n7gN!WY>EqN90lSN`QZMCoZK54y>m&a|qPw_;a;rZ|6BGpVqhUdUT=J&r4KVtdMg`KK$pX@(Z?7RQd zk16lR^Q3Rg|2XfpU#z$}F+tn(9|n4f0L$$#aa50XZ>ef=2@>r>NzKr9bkW$< zXzhe_b{ZME5cK&WlViS~ck6Oz>it6i{k{MkO*~TICs#A~{pQO6<9T2EXdWNC6_fKJJ}ulP1lq52yE)k@mEysh7``&73budvEDK=;e#6cb zX@7{myLy~{AvkidIfKf(aQ|y%Y;Lp2f%B0yaLZJKkT!5Ig;0t5;DU~fz($|-L}%}| zCJI>zLG``)WDll7(8Xa!l$RT@rD?C1SEQ-#w?))HUu znW-XGk4y0Oc$W6+P7ZL_a7<$`dW-0bX9eH30|45>S9PB^!*2j}8+w ze%3-RsQM={lAKSBypnJz&`&={8__TZirMe`Ls!&?7X+;pLs)1r!apbQ0R z;pBIu)31C<4Wq>($G2 ze~9a_6Ak?8O~SK|wj2y{P#7_4gC|tNpP8X0k|pjj@W@@R9r_XFL@&wS9`5fBg4Sj_ z9%$?PtIdHnI}Cqjzs-lv7ez1p4r95Kfm?qC{ez-=;pH!z`*M3g@4~IQ)rJnDO1;pI z_qXVu|H%A+yF7D99&D4|l|l>F^A8hJNNgKckfiSv$FUC+B$9x|&==vO5y(6{*o?`C z7?5)3?}MdowEg3fi@J&q{nz-LLV(rZJCE%zHYDBeKdvwJ`Y}t~{{ZvKB1D@`|AON= z>FtjUW7hz&U3%bsryAL4>8EfkX%1cNN|-zb$TXEw4*d7)hVc83&7S>(O};N^Q6H1o zP3AH9+*>5Ry93_vOI;%5{~HU?a{WIM;{WyA!k8?>Ovd%w_Nox?Z8OcE%FS!H62P5> zXaCMf-on_eUh?<$^6K9M)^)dyGap$>0zmS5wtpZAd}1NL|L-H&!V&}*+z;HhPOE>;R8Kt6uXz#=F?e6CYO<(p^+VNe5*pX_9)wCAWuS zXwxvBTs4C?S5pGE*Zt4-l;uUj3f2}y7nidQzv-{l`aQNc4^RVMJr(+&aMYG(RQ<`8 z4E@dYKe2y#N(;+91CyaQQu3xi6<7-2$9pH*P7TnVa@aqO7N*+GT^))9-ZHL=D>}XT z_Peerfu-ekL9e%Nt4l&cJ*fI%IHXyr2zX)`_Gya_Se=Kr`lR=WveuZ}#-B% z2Q2k2g{EK}q<)xxiTj{IDWi+*W|fVB)_zQMm*K9ns>W~IjDdlj>2h%m1-!Z)9a5-J?hFH$e_OTkIKBEhCg~}shmDZOc z90GyhMtNyD!L`H&*0t@nPx`eii1Kcv>?*nF$Hzp~8vP3VP0^a068^W&H0N%Y#bC$2 z;cJ-8bC`plBKFM&1nUA$L$r@W_&ICtizUS|?lI?aG2JBcb_6;F z4;|u_{}!Wts=2&z3GYBCO%oGx-xH_*X-rpy08IhWh1u+|Sya>j#)`*=PwqUw85ku1 zxskIM#;nO{kQhIOuW(%GHP*aB`%@qR+W4_w?|sXR08h!mLtAtEXjHGh%N`N%M9Ce# z*$by6cES%JNB(W%E;C?=6sAi^KUk#ELO)xW4%k6TXmR6`AB{-vT_1PB1dR(q23E@N zCpfqU`*~^kE{exCvM$!7tu`)Mf7O4$BE7#ttRg2TU@MZu-&B>O+3jL~QB&+e); z$+||m`EKt4E|O-hvkrPm1naLxIenKrj1H--J_sUa%pO}@NN%YE0Q<2KT8+Oyg3e_g z4-3ZG!ExaRe(o%KRLlD7CrUt`j zxa%r|2TQ>NYTU;m(i?PkkH-zRng2q0>w;Q34>xI@BP(t&Xx{_M$; zGTDbP0R~mx{-3KzgtK>eFn4upMmy?#jiY&-=Y+h&14cPLN#pQta zM6gOo5wkHf#?o*(LnIB$q%Ujv!ylpi|j8fiE? zy8Nyd1vw8h)%s>6L61+kynpHgd*G?cHP^^nRU1ypWMddQ^l*AJ;7!YvV-h71TY|?E z#W(E>+b!q0HdSHc3GCxyg1XMC%U}e~dAFA}>lo3Y`ryG-HTyb?Hay7>MGMiu>}jIW zFHvu{Z}vTa1Tv936+V25m*`}e?cD&{@m~3pa^wu?=z}@h+$4U!4O|bHR)j~pKeK?G zn|!a8t*rswbTr6~6&ZTcDOV2|+^-x6ScGI&Wo5?D@U8O?(iQ|VO!cJc1yz>5Z?nrK z&dug*RyYVS`-0#byw;P$W|a`^|HO?%flTs=XhhxWd5*k~50V5%Hk4rBVGMe(d9Bp_ z1Q%1;1~^FrO~XXibJz7s$$CTAkD{}AyNSVQK=DC~*8Ia2wK7@S_niK#r^)sL%xf#M z9}_pI(d-S}(a&rkV8p_9p}j{AlaG48uY8o1hmQ_3&ROG4(@-?gmY%4(msk_0Yy9%f z3Sd}xw9_6pCQ3uxoSXOk^2#{trif!)OER{enhRZF^3UWt<-{CE22i- z8lYZjqq%xoJM;Z_2(Fj?puE#zbtPId4?r@TXYH+UydDC)djiBT+1vyExeW}9Fbn0e zBD#@-o!Y()1t&wJ@0ffd)W=g7Yc#RH-kq|UeKZ|geYOI5Q)YD&5|nSOd4y9z8$gE| z^^RSg`BrB?d(H6~ybeWHsO*ni!x>~sZMteaP-MMoX)#0aj) z5%v+H6J>>zE06YpqfC#JHquV_|kh5-iG?9exrm;s@@{|}381de@o8#qD z+EwC1DIeBa<>MI|YFaMKvS>bLDVmijEqxypp2|?HJ6P4tI+?GF%6|ZjSrIQRAIRH# z6>S5j7AI7r_IhQE^IRquyskw3@R$eufhO!Ed8}Mz|9f+uz8MnF2AdaSG@RLP#S-D; zwRz#~XHNx0EEjYV7-ICMiG)@n?T%-|V&hqEzTpV>V_ z6t~kqsIH4zGdM-viQ{p31jP!+n@PGe9yZ52N66W<2i@u-y)8&~WkVolQh%_jz2S1F zG|MM6OiWAA>_H`cEXI>6Z#}TH1|0nWtB;nQIB$edMrv9Ok2;hkANL zFJWxBB^XJPCM6;4=%ADV1eP6PyO|r_I=IORDNN}FYU9xc>mfZMA@1=?_VJdh6iFvW zrv>v^S1fh8dJ|DfH%1EM*ZP=&n(#?~SYi1{b0PTh4Ts2@KygPG{b#OHRA@>IWODT-{ z&0m$sJPj-$M3yES^xFsn$lXYYxnrN9Ej;e40Tpcea|6rMjj{s44)qJnb3y zX!rU<+;YA|P|d&#*^Feoh{!3ApwAVH;%e5?gXJms>R(fnPE3guGX6RL1tg=sH z+GfszG{@sr9dfA&{?YMi&Ck`@rmc6itkpC-Dacpv3!>!v3jRJ}u>Fxz>t|NFxx9u2 zKQ8CZU{PKX8eE-}t(cv%3(uA)z>qFINf8qb7aMb-z0}+wwJ`Twx2BCi ztpuz=P~!n}8{%9W0cr_UZ`l2~#@rh~sCEw{-MU%d^Nd)?I-XDw(l?Ni9P4$)$r)kw zBrYUJbTI?9*A4a1OQ1d=J!XiB5AVUnq#n<5PV)P~2;L1*{yIz;IToR5x58-CR_qzq zwIE#vxH>K)klal10ykv7Rih`BKoSx!?>kJ)u~FxQQ}gFFC)*Nh7{lTi>TkQ0M7t?= z+*Ww%lJk*|v5{V0aR+}oR~iyU`Kw=2FZ%>2-*4pR!phtWr zMiO2)v=w6d&wYQBYd>ya2d@_(IrCI1R*F}?dAxV4bQrw&Nr`0aSDVYC~N3DV9pS?czwtoFsJ2)QW7fu~v3!A1HlY&p* zNDZr`ldwp$YNFPMt|buE(`>$e-G{~*Cx*DPE)Et~UDGbw-G|GZStkm_a?^wKky)sl zKTuu3Lkx%c!nIdk5`p^kU9%mIe1FOC+yuQ6F6sM@BqqSWQn%N50VLI+VZc}jF>DD! z(!?p;iLv3B6yZr20-x?1{P|uVA6~?W+$m4>FB9#`A_X~&3jQ&TtQZ#;)wSvwM|Dv& z$&gs*d#|XEqe6_+ZExKphsLj7lrJ3aBnq^%Xzmr!^kC4AD;LKdTteG5U2Bs5K7dp( z$PkZD+O-9)=>&1sL;%O~TL3tgyW#80n`1Z)a{S{45BL#399y!xzO zikmn4lA5JURS;?Jab*rhs8Sl+b|2*rUwOuKly6>C1+U-q3wRC=mG}{gH;Nu|fvqEs zDC0d?-LoaV76$Yy0CdK`7W-37$ zAvhg`{j$z@jLj*$M^Xy(Bg0IpEmV5!5bDY#4|x1i0XNcIcW zYaW|jret9EG~}-yYW(tBRFst4ah1+W^+B~qJE!4Zz8^AhLpsJrcZJIDw_TgsOAUc5 zCO={idsi>;dY4OfS4PhOU=w#hQI}#?y)VP$D0wVE06J>h{EqyQVL=G+5`)vkNq7k4 z=Mx<-Obs+xB?>jZ_f}y+zWg)=9RmV!Scf&F9ukK5Btd08e<+h7nsRc4Ni9O@ZsGQ) z+uIC!^zEMPkT?TsDVoS+HoZ$kW`&d@G+Y1<4T!|*4)Ch$${Jcg%kUO0gU#6%_3`&1 z=4Ti}8&X@xji9j=Lt0|Xk!loO|j)F}_TbyMrc z_WwJ0Ev+JbbjQpn(qR>g+~z-b*GPdF?y$gb*LucaVZQ-SU|#RBjuZaDRtx0jvH&Ul z_(9vmH)2-~CSrEc8%wF$pfO55?4+EtRy--!WBKw0vpCM`_ue%&a1EcU^nT&hwn^+~ zEXc4ve+g4(ln+X*YE&>ZulIa0+~e%Y@@XDT1DD;*?@)oOA{_efh;)Gcs;sz_>OlC> z{xG>`f+>V8iy+>%=S&9-5paZG@8_oZxNTlIyy6#&Uim{Z0Xxgd57xv_a*V4PhNV=V zQLGwW0(kx87touDUlp<)HOP&`@)jvj>;-0=Q@ZL=qUfPMqsu& zJnL%W0zVQN{Ft7!#U2YedJwz{;cIJ{`@UOlnXYakz(AP)_Dh)N<3sG&d1beF&gF8LE#tPHCN@~$;WT*@6 z?GFHVJJ69?SF#}xAN~F`l9k~}<3m#BHY}_AwQ1pOIk`h_e9f0%)VNu?bQi6doF;BZ zENxQ-+Df|3(`;{taM_EIzVaH7mcfM>Iw?Ciwbr1ohDOr5t}Q6v)*T8`eea>@_@OJM zCWw7Em=-Y^Eg1~x(aXgFK)_=yX0PI6f0|`}N z|3fDTi=2Mi{5A6g!VTN{siC@tTAk9V&(V}4la9{7HOwypH>RR-9iTA@?*aLE_$ef5 zoL0$b_#VWXK?Y|Z-x&s!_Rk?PecVaoP%AeDsJ{H~;`*Cl2mX(;V*B*b^z#Ml8Y?`S zL(919uLcj`jC6kB{{b=y!26-PNCi18R~(h`E3NVc&a;5Oz-yd+Imea7q^Q8%QY8z2 zawi4Qc^ySMx!^`4;;lPM%;Lq^kfn1S$vY59V!+29pG&wGiy(g*-$~zg)3~S@3!S^O z22+yZzm(a`9i^?ycHyp(*wrQv@4+)!(1ArXMFbYgk@`K24-{+@pBQ3R%k;_{Eq^1f+?pCcFD>AKuddnw)E6Teyoh8 zg|70LJ6}zsDf3KP(GXrjXM#uQiE`5QaGm`Cu&p~9Ix5ONTAJT`M>Y6)sobUDb+8lI z8tlo2o2wMiRF`Wsz4Zvi1>3SS$v$EuTYZDh9;r@^Ei}LgWy<9vK$5YZd^ap}oImui zYjm;EJp_c^SO8>q&dLGZ%j!w=@3i9z2pbUR3Bf*;kMnXze-PVL|e( z$6rw|S7~lN9rJ$@E~@1rDOyfgrBWfSr!zpocYpU`MYKP!_w-exAHEVh&rQHE}F%9eb^tODJ7 zM9pdPQTtXXRoz_v%Usza)&1#|=sm~^IkbYm+v&LBoGAEwZ6{;mlAn^2u``hHrQaWF z`zkyW9bM<9Yet~hDJ%gD#Ei!fY0aNVl37i z)+0~|fW%&?=aGY-&+r(=I9R$2{{fQJ=JC&H+&>kPq1J0;4US!6LV{{IkoUXyV$hHQ zyQ;={%wI1SwcOtPb>VE=DyV_|Y)iWyo5y8c+{L9nx0(qX^T+ zR$H-E-@HE%@~;cEUIfknrmX$h3)1`8^X3J;!ePv`y|MiZo0wXMHF*F` z0Xl&JU9LAcm4T5PYB^%N&2KJ@X0kBIeL@?0naivsnWyO6`ii4hxLe=4n9SKA^tIW1 zLnhhw7*TCS`O*?4ELD4ka`=BBFD4`R|=7G3i5?5Kn=ADq{4nQ5^4AC z=$-gSzE8s*-`p})1^so3v}RDRh+Ez~q^|*jvYzlMUd5kWOPO=_J!C12R`tvr9yG6_nk8lW2E_W36-PJriK|fV_m^ zgU$K_UaN7r?|CJ3@th{0V4DD?>1aWo>pf&6BHmC0AS|BtM09v z2xIX;MwXB4&*ZNG(F{#}OIcAIRv5)35_!(1hS?VLI>;jE$G(GwJeL97NN6-AzgdZI>)Iked+)INK=* zPPaZc+}tBW*x5p5Mk&ly4XBwhwuOai<=n>ck}JF0%g+mFvJDY*i$K_ zHS}-t+x%JKXy)Gh$ikBHM*IyD(_(VpB5}8>1Q#fF=(ZnEvH3omF>JQis|sTg5`?|> zED-KGor}~5z_FLuFi7_QeXtxNQ37KS!w_^6Zn)}@$EzDI2(1~Nz*F*KpvZD6SS&;L> zLheO>Zg_z{{kK=K5#y^L2*g>u)rGG#Hry?wlRenAEoOA#E@}hlmqGzU!VD#+DM4^F z-vEXsJp$qD^B3239w}{T92%!xm!?YgcwdARk=d16$`g z4#lG02V-DUzF>73s!Z`7U`LLt$yCd0B_^nRBQzQq!i@QNmxh?o^XFHs zPQwN}AMGy@wuoHugZ9If z+4CH0-Bkkbm403%FZ;pdM@(RbR-|@=VIl_Y+m$Ej;D*Suohr%x`1ikX6#83XkknX6@jb3ZGij!usTy-DNJbUSdZO(At)qeR>`GLSs@- zdB~-AT!M+|nGcQiOG9|7bbuhh%@MxhWc%GJ4<`{q68aSfWh7x%tX_q=nzVgq`19$G z85pYJ)!eh+%uVuA+_edMvMY69E1*dF!kQIGcomlPfDL8LUpH2sq4pnbe-BmEm>kYB zcCG+eO^UVn6IQQ7j*9bCph01ECk6BsR~3rnnS>e;m&Cb~&HH309DZ|{1pL)&L8MKT z6jkE85TK4#FsuqI+3Qv)*)uqI1#?-A2 z>oC4i)3kp`w&TWIdI_bYyC$l24#Cb;f|eA}`{Ic-c8;XUu;^NaDcjv@iMl==y8`Qa z-1s~cpYrJN(u3#YfBzc*4&yQYnSZb|jh?>xO8`t?E&C#@)~kS)#A9&xFt!;kC%>LW z?$TG7*-k4omACnt^D&@IC2Lku%%GGlNVizXDuk>x!}XU!S?el(A>lS+^s2Sgb3Ar= znojP?hLkHa3DD+&l-2|B_U^b7!L1ox)bX?pO6Sy3p z`aiy1ZBy<6=9^N2UvqpT06H$t4rCM)Plv=Q@foPF!8s7~b;cvQj!wY-s2iw$U-ADi z67A06ZC21k?QnZ3T4Zy4(_aOSAywFH7c?*x^eF zj1YVS{kUDRm^6Si7>7!(*n{?ez&loD5F%@xevQfQmti+Qodq`53fSNHR+N+9@Ej9} zx~j}w|ItLfq+He_xw=;?V0YV8IhPbKfzH%Tjk>>K|EJrhE+odDv*q>d87$aOy_$17 zB2OmL1ZX~0b0eoCyol5*fJ!@7LL*Z=lJNHmF7))MKC+E_Zn$Knts^*=iTXU0SU1(> z9Opdr1yb=)$l8MiY0J~_6bSzk@?f_1Z7j;zz`i-S$KcY0>e>-q9YY{2rfWt3tJec5mfF8T_0k z6QsnFFPorrt3csh)a0`xaD-Mj2DlEprMr zpWjx6tbN;C8eK_2`NXtoI~#tPeiU!#NJ=C2}~s-6wFPb?&9>4uEA zqO_KO*BLlhQHNsryfmO8`T^9#Ydl;*EJ|1DYrXsXd>^n;x6))%vYoDax08_EzxWov zyQU8!0R?<}bOd{Kf8ArA8Oq>rruDhOZLMWR^-DnmMYFJ-e%!mYW>JOq0ap){C~iw$ zSPw~(ghqu3}0n4+sD z&TfiO4SD$`z2>j%6rNen>+2Wt5+pQ&(pFJ&kuRbHAg27$Wc37yM4Em=T*-Y%U4uBQ zw2dPR63>FLcM*q%aQ_}54lZVYI72w|pWfg0r3Y)ED+bf%x+X*7RdH8yelgYSVywJ1 z9avI?{7it6Zu)}Tn4rwyMoX_ERjw|wWL030_6q{2lDcwKV%0yQ>u!9p$pk~OAn_Tj zX}Hv@s$#CV_rDlW+!w2rSpj0RW#l=_+Q=tBDMMYWnrth^&rJxTqUm_Y&wXt2jdbd? zDPu_L^4v7sG#rN6xrP1cGVg{VMlts?+)r*{1Y$}bO&5&Ox&PJSm>1DOlQZtm?k$pi z_Iy8T5Kr!sF|xfX3-17G`YkJq;F?n;Fy1`ZY7Zd&>Uz6u3GVWMt`q<6tE%!%z5LRX zSgO~O_ZY=$5GA|R!oa+dG$)(HBcQu9)Orv3Dh3y#BU0#T7Fz|8045{7S3cRf_Te+| z?vIB2O9ndxKRf}(VBGzp=^){tRh}jL2w0mohm+th8u$o0HLpmCr<}}g-%6QU&9|U@#*Z&|3z^A}%qbyq^6!&h!RKQah*?_>eiel_%$Q&3UK!uqJw?Sk{O)hDPV zfcSaYqSi3~p94u%i51b&@vq&bDGqIw$Iigc9LoL(BnN9r68XTE)CG}X26a&}afX&K z=RXSpKHWoby9>expxA~EaaMjsj1Ic}?}$TUR&ITM2*#(Z6=xjwdvjP$6NUu9xCWP4 zQd^w}zTw_+F-|9iO@KY}(He-(It1Nbj?NT+|LI0!-J#~d#SR!xm0D^q?ur`No?M<2 zBfV41U`U_vwB&}@!xg)+gV}baaw>AI_?}ST)MeOeS^@!S{;Kd_UEc=y{-q{I9g+R~ zwR)r+dBp~K?j5}&!xMeVv+%?dAhPBlde&n^srg5-Wf&zyv(GH>OP=iBO1)6DB*eRL z@$`)w3=iWSHjZh)wKsLB1pAL{Fk7hYjpIbley+32f3db-{Pwf{(y3aolC0a2wTtO= zipTQVI$S=_}9(7!iCz2vUP}Z$m`vA#^tw z*5TiBJn1A~;Ad3OD`r`X)nuLMi<&hg&&wg39>MqWwi0;kHGc^t9P-o{{w^vP(~Xrt z;A6RRR9&zhL0!AH@eRU(2?&9LHTEIeve>BGH*hT30CekQ*91VUpwcvl6oZYMK+H^A z=)GhgYqN;6$Wbd}3Lg<5{jCO)OG?VRq<&z?#pvs4NnMhpb-2LVxW(|nRpea^bkK@*Hl^pu>1mH zD9p%2?jFVs#|BsoA&fsg>?|w?LK~{FS;Cx{7i-E9FT z|FS@`Eba&|)aWmmzjkBF3fZTrqzSIN^jL`+cT~`paHzf8O2_v^jyd39kc%%4NfH#m zPQjb#vJI^v@-9qcm2n^)BJI8pjJ+U}pVIW2rYjlMERwzg=Hs(8kL2ER7dY5e_KNut z6F}+?AtCDv)bGDr)RNf?!yowN!LyPY`Yef}Dyt=8GbI{YfO(B03-=gFlEbs7vIo(b z3v|NSDzTWBN6&A)by-n%*r9~ER6coCWdM(!IeDpFAI1IXlT6#NhBDN7QXZ-*FaJe& zL*+l3a#z4N$H?>f*!DR>64>ryX+tbP$^i`mM`k>0dVKnyn0OoX8}8x4^-5#5%(V~v z1-#AptyB8riTQA9>pL#oY4ipz85E;2Q@J>~oo_&Q;dKJu>EzhY0smB=`JE|1HCcYX zDbA)x?Nj_upnOwQ38AOseM22HWd2S9SQ79(6yZlLE4u_HDuS!#{vDWL?&Q(k(;h~C z*^hDWf4saV=W`B?>1q){V$$qkVyKB#j2n_kXk>XXAs!GIkU4K=<;iG?*L_VoPmUKL zN3&@fi41I!it~Bo*oy4~jLJ5*exE%|ugPUQTM&QHLxSk^ExUpHH2k*>H0+74GoQjg zrF=V5jr~tG<`>=|kO9gS*tQHU5PTtTbMv18M1X?yQHYV%&c% z0X3fGhVW85UI|S)RdKtP2?FXp`C+M;rE;qd;aw?d4sQ`(yKDFdHr004#9!eC!?ugz zCH*a8OszoWx~vsYU!`FqMSQykjT#vYH32#YWIntARUB~FoF-;pcciy4K3{Lhi@7F* ze0#q4(kUw%$V9R=k2)SYZ-##b*}H%27xN+>qqX)*Wpo(u{{|`X2(^aC@!NoM{J-q# zER(wYZYFxmgvpwnBgVJOEj{5`;^y6&_7QBaK9u*ml{FM5?>t*@ytb4`JkKoS{rI9+ z!eQ;|h~%)9t8*POD@(O;6Gm%%&5nOFnS`6Jy+0@q58G8#xDM`V@XYo(GFPT9L|!DF z?FM_Mo_!M44$@1=cL(zF_x}KkJ6_^hH`Ej*N#x0kRedizoau<>begW%z3j`X+B}d~f>|z^XGf2TP@#C`DvWc}O-$U*M!Qs`L8gPP=l_#&Bjmav48VWW9|%a zf5_;!E7Z{LXn8IzF2n6Q(IKYQ#RDIVq)ZF{!axst^y ze3Q+LIgcf2h}lqpAgAJ3UcwVX+cXrF70&y7JHs^DU zqNozr6*FLedTRBQE~{<`ouEIPw6eduXk-Ojxl&Fz>YgC>b`lIal z?#vvfHggTyvAPLjEVz^cU()_HB0Y|&hiFvB8HdcIECD54(&OD*?p$-Wy?!w0=TKk~$gx%S3%ORR5az@WB(e#{W=?TVoFFU zc^JubYMX5N-zql2ynEGviT!M@2Dl3#@=q8*y3nO7LtEH2%R2k=IF!o$og})2-oP7^ zXuyJukNCV}m3YXt&PopIxz~z-OqRqQ-s7|ykVrOhhr6n3mCQ;LTq@`=aU08h3`goUH)61HNzZ94) zSXxWfLia$=jAVKqRKu>{%c+rizH*F{o|^Djw&9;z{5_SRmw@1rgH&Yayu^^*8NLI= z*5};4d#5kzDGb*j2j%no^HZ+~eOo)wI>rxxQBs{|8WLnl;2i>990Wj817Mdn{J;c4 z=2C-48M=fGu`3?<&y0sGzctnCR3F}KeJiei=0k=q9B_p_(&&^d>0`kWD}?V!f%&#U z11#?Igxe}U`nJWK@yfFTEEKbsU7^Z;rY0(OsnY1Lyu&Tq-v0Vr7}!|7M&*O?MJ=^^ z%V6shpL*$O3d3dAl#`rrx#gu+aMsBly?RoDg)`96n#rmg6_gp-@U;jbb>Ge%x$w6? zoTdW?eMDgq){J(+3QSoG!3-v+-U53RYazeDEp(m~Hs*m@YrA4=I~$4GH;W?bReQOSpG`F#_* zZ^-V~s<9XT2%ZR2UF|Bito9}3x~h~&nr3{=%F|jb?}il< ze~5b78F?Z%V1LF{h8^0xIPb@rTB~p#@BMzx!;9whHD^Ul+MaJB|BnhgsjlFMB@I!3 zrQ=)>He;gPGg;SCB)FT^4W1HzGFrPpKD?-0uPFT~h1lrI=q*d!*IdZxrU2d(w#$^daeBVFz%SxtDr2q zK4tg-`0G(ZLb<6-93SSos;$opUAz%Gjr#ePAAy=9GfQV>RI70w0jth;=55YFF0}R) zyIvA6H&Yx_Fx3I-#S78a$F+DsS4K5!xq{yq%{&c=x2^~s5l78AnN-GYxzIlmo3nW6 zPRRcO;X*TsL1HcS@V%06$VdCJBHMNoHE2nsl|aUDD?dfcUI9W|@UiNaL#hA|MT;?} zmSM;9d}ZPB|18T@zi+-3m+@Cxx-8*-kE@=JR~OVx z84&k#y17sZeJ`eM1^@IsxGop(l{l)In8>Ti#h_PHP{zu=Q-XkO8Iuc#B**`rzeClP zsrbr@iyAE*B{$RH-LtPtqaK4Y#q~2q^?{%(GG>DNS5oe{$J86qE^?t-yhCu`yD&3? zS8D8)O2(vG;uCU&FWL85qlUlo>q~A|wB8q38=&lv?z7#}aerm&Bkk_##C4OV+A_OSOCksV9m$ExU2ad)(PU|RhUEESXTiggUfpD_1n60mpY3Rhv|L<*v_K${f}TVN zJFLHz=_DL`qdTnc*U9-Mq}LdqDkmcjQ_mufXjYa}P?d%h2eWTYI`Y-V z-pD`t^UgzE!ZoY(>{pyk8O}=L)o{BHedyWaAhum)ggEL!!Q(jcgm~S$PUsjZHD*f{ zk@!%)kOV63&7BnffCtQAc{JG#ezL?AblXj}N^;9(>VyLo7VJ_`igu@i zTYwRciOYR2%zAoeP&3>feeWGFoan6?03tQPi`uE9S%k6I!Nqh?X{>6wA25VV7A9|T zo)WULJDZhdJp17Cd$syause$CBs9Jrxro9gx zvmv)qs>R?&az#O+_Jdu!3P)w4626!k<_ofMQ4b1u@0Lk22EX;k@L(kp_4S4D4N1F| ztkE5q_evhGP9CV~q63WD`}$llRbDkDp4Yr7+bum1PbC?(d>yXA<7O>r>q$NoD9dQ= z_9~~Q{n17Wv#`m16B?f<0DOc{zbTQgS76T(ptv%|C<$1u@~Z9;;-2{$Jgh|e*99I+ zj)xThVS5rvfqU!wnvLW)Va{pFC`ar^GMb^x<*&Uj_5$DL3L;g>B{5ruAY3_{7bfKj zD63#DXzgV#OjBLUa28uuncZ2rW^JKub@LKNvGY!CC&_uFvY2KCU#dJD3`QQ*+|{Xn zF05~-6!RYFr#Das3(ToDJCuV!7FrUPXI~J=T(4@kFB~e$dihAJUeSoGI^h5M2#w6i ze;5>R(JjxZa)~DV?hZ}_({NoqeI4tsSvzc@8A?iEpHLU31f4xMoA=0=d}LSTbU*+E zwb91wB@Vk_MfmlzBFHNx$@N9|p1WVU>JJ82b{(VByuMY*RH)v|f5q;+zSb?8K5O_4 z4k5Xir>fjBWFYN3fZeDCmy@!G{>uCv^*i}giswW&%jm{-CZJiKv%(n1x?c(}bLWfU277RD5@{wVu}$K?3^ z3!}!DrpyCYxA+cKi~~iQ_OX34R0m}Dg4g7`HqTS5bG z&?@*oz_eqviZmyJa&|>>+YOH5n@$2Bk%Jw1^c!n&GDdgRd$V8lAr`(|`ng_S$AWGy zE@90?j?@301z4&+pqC|=QpG8;hcCt7wXJ28PVTtJvORN=uv{!XbB>+CVo(}(vkjK{ z7XScjaUFYD^;7_G&?St<+k^a-P+k4Jy&gPmSf{dVEgXt!PU2mnV zajf64@|M<}dog2mXV+MLuM}t&0n{xfA#s%mqJ&WwAhZZas1k@FZuoE(#zz}zzx)r^ z-s+uak_Mft4zmc**!?>Ekw7HOV7Uhb#N~~lb8*wzbrL1Pri&RK3Q&~PN&Mwoin<7X*rDZ%+QxnII%7f zaM83=DKl`|B=)>KI-@W-x_1|FqNA5D{E-J)!pgX*t!9?&j_|Qw3O-01cU0jlS=8M; z`ux#}ANNYOw{=d>SA~6lX1i55;JK9rfHVdUw=KtzT_@e;!sj*Rw`SnG-=W<9T&;v|xQBx!A@MLqU+ zZa0fZ(SSnMyO5TiIS)j7iH#l}o_qbk2u%#O6Co7_O0)NNyYAw$6x=?g2~ImB!y|Pc zo)fW^4akf(5FQaewvA*6UwodI`aptd(4X-nBATt7dkF8IqrDiW!9ok5=UQy=8P_#1 z;V9_tin)2N9QdVcrPYARur4Fsb|r1pF}TA6!Q&CsU;t`wa2e)t!s<>JMd0wp3aXkz zO1DS1TyiU=cHoK$uFj1>j{t4m#pbxC#r5qNR}sAd6Zda4!z#Z6anYxNl1}iQ^|;vm zE1Kiy8^Vv`KN?HFr^**awofO|)=EjmdjQjAwn5XsT+ty^X}C?07sE=>&dLM|atrA` z32ixN=eZYf!82r8d(M;n$U1MSbR^fR;wG?5CtfDuMD8@0KaL`B*Nc|jBYwkYJP_jZV4U^tl+kj=E6ihEK4me{ zT4?(8hK_owmf@<2cE1YvP;O>qScP78)6(}PyR%CB+_wMoK9^T9SIoypzO9_Q+)=Od zr}IW~tM|e)Um)oz=C>+9S+UDFcbdr<4v{E~t;o}rK4xpNV@2i%IS@%0tAn^}8 zy4HYX;{}0u-v$#diJ$a%>?^a|VTcRoprPjWPvEW~dSnNTQXBOqv-C_1mAjYq)>q|m zL$>R&Hn@9^zNKn2M+vZQZ|PYX-A!w|;CsmfA$GT;5c6vfST!13)?RqRUhce`h?meX zf7~FkAfZ8YeXo|jwYn+2SUmNh%BnJd)Dh$^CtNQ-T}2 zr`sDNXnipF!n8$n*N#iX8$WZnm8P|#Jn}a>)h`&<%GYifsM`_4OFN?~YhPR{E{?V* z?NOUwn)xU1a_3u0wqlgG)`IxQJ>#s_kcQXuK8W=0A6P_6xsG3m#fS~C$H5-@LywH? z&|#bYTl(j-?TSD(*b!T3epypH0Q6-x@ru?aHvD8)ksCp1P)5@1J+({xT}kyIqlhAd zbGseT{cOV9yQ%wh+NDl&6MD|dL>f7Dj~QB&CGVjV_bYP?=m0x_d#~?-h(-Lh+^wEi z#>aPsG8Y-?#CS-;@9(s(()lm~0GFee{6+p>j%a4#D<0Z_%-!qa@M?0>rKFG(7~Z~=23Tpx<4+{rg9U;^*)@LMIM^EwIwA3#TU z0|!3u82vAzzA`MTFY1@>?(UNA1_Kc3F6r)W=}zg8F6jn=p@$lzMY;!&M!L&;_`mnP z_k(=!;Tg`Ev-euR+Ut;04m|`U|8Li0`Qv%yE~>O;{T{r@2U$st=<;$_%Bjx_4bBO6 zWvW~Ji_6J&(*Uv1#-@4sJShXdPSLZ(^m20C`6-ghLH*yQk}vGdyguRFq|R|4hdI{C zH_|M72DViN^=kw!ti@Q{Brz>uXM{>m2<47A%|v=eCHjxV2!GUV`yI_B8{Oj3gmnLY zHvGx5ViH;;R0cO*Yg z`nEsmhG8Iol#Igu zNk@YMB*Xml858s@2(H*Nd8lr#} zXb~!&-XN;?<}S}uXAdtmhf>QM1Wv9k10pt1#suqB^6=8PzLOW%E)t@CbystL?eyg9~Z9Vw6&-=+gPLej7oMOWxyf%*2SS44) zSRf3pjJ5|3BRRPa<<4kESf9wV)mtB3Me98YxCpEO5RA&#zPR}u9Vn8;kk{bAT0InQ zfJjga)9~gXTw=LFHELJN>JxjN^Yl)&_GRtMdL*}XQ%kwqC<+-_#(r!Wy~Em%+>hUc z$4uns#1q;ZFG*&aei6AX6$Y!c=(ymXrTURVv4I|B*sqiiyIwI7X|4cF%A2I1kr7X zVqUo+E8Jwpxd_-|98K)*rY7dbZgxqKF@4S*{P!R{fF4lhwR%6D>LAx=lgt>{-(CT3 zTTKES6%x~T{EWYe0oI{47M=HHx$0B>w+&8PWb*JZFI&8+tVj&@5K;F=b<9gbEoI%=T{1|^ z;lto{DL!;#S9?59#1BmT924dspjO$r!ZcBl_LM<3P82ovCfl_?O(5CJvB9a~b#+wj z!_I~*RaG=!|4NOPD#4m2|DPWDHV^ODQdW}P^csndkf7cBMr1`NdH2=qGRqc*;1%{i zBNoa9ql2}Usm{y&?X=e-l+PoBG z`W=R8s63PvKLyldn*!MD87zG7?#bh59vihYcFp+VIZl2C4<^Xatkl5>_9oHw28Lu#$W5ZX~ zL4?Tjdkbxj5t-%cU-tPz#&g}i0ZlR`sd^KbQu#1gcntdbO8~h)8f~C?Pm_<}l_O{@ zCX-iMZh?Wk{__<8xaR@P7;=|2*amRvKTbV-<%@^ApC7-QRK;ipGTtui{n(4FuXLV{ zVyuJjNd>^VMEi+g@dT7TeythNXHZup@*3(b?EcIW+#5V_c|ISdK9i#Umo80q|!9wY}dwbg2-ZQfu81KlIhwUM-(saaI` zzw)+TsUs8Pk1PaJkAZb>^mfN}lJMQL|5tfSfs)#x*NXKi3%kyiQvKGa8tN(!}o zq`GgyijcCKE*%tB46=SS$zKcCzz%Yb5Qm{aS#vh7$f>Qe(ALQKYW8MJxzE0cht<%& zWX3gTWdWnK(Eih=@j!!rEFRJTi@KVbc5Qd~Is9NLpqH8R%&+1px%zP$PfYVV^?%EA zm{zHl!H1lLqLC6tOGVDQsHxOtR<`U-2z#a)C&N(gEWLqEqM9-Ur~YdG#{?AW*z#e3 zo5V>*x~h}>hOP+avPozV9|c^C2z+n)q7I7j+}XW8%%G9+T&Ubf&OG?ch~HR<@#bcE=&XT zCcf>PPsa0{YAPfYM4r+4co_K4;wonFb6N(dU2|%3=8eGpG(#4b6<0aAT|eTuWI!?2 zMcCMhNH%JKCFtkYy$j;d1n&vzv15$3u}llxU6O^3Xb{^JRBQt{?=g{zkP!e}k*H5NpkZ5;mNGFvsBcK9oNHH9_QzsuZp#W#g$g+hDJc5$9I^usr^o*DVvBt!&_8gM3m=*Pcb z-p$&_wL3ZI0riA%3yWrcLI*z-jZadSFHPagmx)EJT;_8ah@aTeXuC$}A&K3bAPH?g~{%K zsGVSGqgtPv&s$cba_PMeqWQM{52SIaB6C(-^XlW*euqjRK^$r`{EaC&O`4vJQ9CD5 z(?q9}Y$e&n4oz)p=0C1*kl%X@HG^sT23phePtNFaS7vGlI7Huj{fZP!eDAxa=DS&Er-6q5Oy24hp#;x~TB zxb=vspy@^l_lg_fCbhjOWlzmMqO5)f0LImy<%95NHlif%X{%+ZG#1;bGHP&LyUkk! z$pCHTu#*2YKkF5tN!jr%p6QpxQ`=m3=W6F^)DfbIkpW()duSF>lb?G(q}1MVGIyl4 zk~U;Aot+OWs*W}jBHG8sv%Rm_Pjq{|JkunqNPA0y0a@I4jpl_T^{XWr`rcEgmk}Su z5>_0(Op0Y<>MF)Kk8W;Y(_jrsiDa4INSmv^Paizz4MgZdGx;^Y<`7f2wMr!*1u8CI zaE@JZXL^w(&k%17Ek*!$pk;>~%DaA?)q91uWx)1@9@vm7$&7BV1`B#NA~7~+1NHq4 zY23u(O#IZJ>LtF^1_k8)KyM+KXnK?i{*r;g0kCNV3A^4~;}WwoebO+YdD=!=d_0K_ z``&b4lOT7QX?N9N*__pQvjPtyz%%-+LAE11IBxVVE{&(o#wBeQ49oOJmG~Ws4`9QDr2seuyb;J7@uJ9juVD zaiQKTbyM3th}i`_BZ9C%oau8x)A!!v!~IF&r1Zc^&LzLa>@iiUZLY&`0(+|7|1n58&(s0UC`&Eb%XFv=qY()9+t$BW`v{j=as{S z>)oUJ;rXX+ zwUtc+<%dSTsO$nRgcvzB0uuzjm(_@1uT^=*O?3GKXWAVoCX<`fPRMFKr9r4(0 z;|?N3BI)ll%Ok%$L~OizvuyuD;~~WZVh%r5wBMBC+XVbB581pGAz)}B@;gx{m4!Wz z+Ci-m#11yT_1KPDiyX&R+sB`>lIp+1$bta6PnuI@a0=FsC&6_ zifv(>M|<`{Vb2KYag;yXYeOwYY9LI_+2qkt6N~!Xj)OEeO3cTR`dhCmr_9ktwJ*h; zH#^O8EpCnpH#6;4N z5{o6d@6Q^?kr!G0)9aUNn6r=X~_J?xn@{oc-`c!nB9%Yqk!WFkRF# zV*74VN~sQC*+?xa6Y&;CgP3l6REFw^z-S zK8GkE@U&!tbmjwtTxRd+A?oB_GWqJK@SgB&mwZAbyHFEm``C=HDu?PR4`Z=454UQ2 zw*6|f9E#UD1533nSSEx=^0l%Fse0)3Ns?>zl)*EB2s`(WEFq%I3&2xXoZ-WwgN(h^5~(ob7AK;?^s z{Uat{4S*4=)eLg}>^nOt9I&hajpAsl&xkq1LVLWI`-lZ-)eiKYy`e1$JG-rS; zo=GfphktX?dWcCSv|SsUG_7XsI@unwFCi1t;_HQkF;H+Lx=>n8;>x!r2YuJ~V_qA} zwyx!$BcM>rmIN zWCcjdpLQ#NKnm^O#$l?p7r!8bUZH{`E_WvV&Oz#6Y~lddSG#~ie(-}GOifsdKkudi z&#PtM5sRw=8-V*#dX&c|M&8+X`uA(^_gjAl+jDRn*0kDBIB0LA({M7- zJ(Bvk$cOD-@BPOqFI?qvx(-7Z9 zT~YN)+vfaE56I2* zgY_ZJW&5_daX+sRMHzt02xG>fmd?#caE~UYUwzlwquN-i&nI~Mg83HPL!V%2@u-_y zO*fQc>*t%eA5yb=^L!*kY46Js-d!U2>AKXCZscUlL|0tC+f#a0;Of4*8Gayt$~5|N zK>5%A)?P^4VE^QjT;JTi;7I9)j)+McMoSE%)S?IJwM6(hmxnjLB&Tmgx7V)!cQtcQ z+<#C9oxtH9{aqxRtzXF37oBSq%-lQ3J(hBguDm8VM)tpyaahpeXz!4cdlCf$%oqHq zcHk{v)7Fu$5ZwFuXHDG`qvZgdw6pQT%q@|8;{tq=E@ILtG(g6971)2Elt+b`cC(5p z+o=blXJ?X&Zzi&cgEOdNf`C*uyOhhun6un7y;i88lkWsj2QYn+ygB-C?DR2$raDs| z9*jHFihg*mEo7gt_}-+_4VcC3dhtQ<;XGXO0A6nNRqMxO(IB#o($vP`2O|tWsE#X-bqgu61}~l?AMjZ<4j=j_b3fuY96(@T>V&tx>K||#U>+q z$?e{`%<7?t#^K#3TpXn7I{z6ku!IaCy{!iP?&8r+ndo)B_Q)0(9yP-M3aQPyJ41!L zek$PSVEh~5kNIeVa#qqptK-$eDyB0pigfzf@P5Af+3VRGJ8d*`NrU;ld+Bh2{J;BvYIJ`5jv_t^9`Ig_tniRSnCF@5Z8Fm*og>x--%u zdEG91uPk~Bwm^30PdR1Nyq05h^~uAF0g(@=y1#tX`W^Ea6fExxp5*IbZj!!{YP#88 z>OT6-PUjxQbSzboT}XOi401;tNAOUPL^cweafv1>tVS3IRqHGS+3~ixyVaqd@N9dChvTR!^Zg$?sg{c&zSzOg1+cdh8~(YHtti zE0f$vweNWp$a!=P(t{`D0mu8R5qV6C+zN8ZgKCxSLK5i5=17Lko{ZU59A^+7-Dlf# z_3K?5S&f{mfr)1fQz&p=`0?C4c#Y%`CopF?4NM88PsAkskx_;&2@o;SIxoNv(~h6Lvqhv*o!%{ss?2h@`A;GV=OgPuJIESWOx*%y~y& z+@ZKF)HUp%l;PXDKlRoBhQ@%U?3cf;R3P~b<3Ab3RybF!r>ilbucf7kkX<}lH2Ig@ z(h%TdLX!H733QOZmGbEt;cR}DH81FQOfId^n0N6& zJMg1R*lASFRl^i@W&=w32t87>c3V5b z5hFL@G5Sws!{j$gbFr-c55xPbpBaXcxNIIqrgn?}Zx%q?>5N=_f%x^J0{y%&FOPeA z_GuR38~t>qO%aNlsz*#Y&YGZ%P!%v8=@^QyNI0RE*m>+*QqP@_TRQK-*TD9>d(FJOlFQYcwHkQ_HHX-f>DGv-iT<6w7!aJ?0(9B0#Eb@d@|K>n zZlHCjDya|zj`KCdRy?^gIsn+`1b;}Ck^K-MMtFX;)HJq`mwWLQ7?L0K+6a(1UL)8* zYe-y?PcoVjh3{J~0m08C=Ul_>p;c(#I+gjgNVkK<0Q(8hsdvn*HSU3~P%q-71Zc*L z=a&x=q8+}u66C=3DD!%8PY2p_SbA>(Qe?Uqu!@^_{|jjRSphSLY#_Mo$Af@eRwf%y z%3NE6J=IMD;&JI@|G+wuAFSUrMA@(&gV9LO*ajuu81F)&Pk|7kpoF@@nm^m2yh$~D zs#frLAVLW#ew8&VF4L+C2LDo5=2HC?jVRfdiFqaVSgfW;`)RuMC9zXTj{ds7fv&s$ zlz(M4GBaR4qP#?AQU3*E7c#pts5(S|=2}%2=^pG1`|n+DMqP`D+Me4qfCtZhPsi7w zEXvY8!cc?n3Qe5H8q49T;9<5o2IG)|1btZeoiIPVP#|>a=IwDUs5G=j2feBL0&5^8{WWOv1f#~beG*Gz4!9M-5cBr_S3Mk&NAi18Kuz;La5u2} zU`f0c6tGR{<(v5e?vo@RT9kWpKSHim@%a~0%NMhp*Nh|N4Vu^_hVd6@R;kMBgCcER zbpU>6^JSpeO2EQPoyvm9-H!mr`;wp?RMHt6w8fk~DfCi!^h=Z3PT|j1irBCuo`M zRdH-m8jqRpGlH3%ba8ScFa3fPuWrTwN&P6JDiNT0vQpEToK2fIutYh$Ss}98Y)7A zTshr>{KKhSlX_V94#|1qFbEoiu7}-Ki*?xkk4Iu(aY7Pev)$j)o*KQXnlO=A*ZU^H z1Y{y&M?(^()}C7O)A^3r%cxmy-e6-v_F0xwgm`6{pPMjRd6b&3B0s>74CI9OoE$fZ zwpsbg(037O_wF$5Z0&U`iqJ&fxfFi5Np0-y>j9s5yeu^-pY4Htw9j$}-FeQB$V{< zAla9X5a|nCdHjUu3WNk2fpfKXx(0# zhwcvnEGH8T$IU~Z`O@d|z&Quud3wN8{XJLe@m3W#&h_|RfhAtLW?WA!kcKs-|DVQ_ z>@5%a2_zF1oSuFbN~r=!krHT_|9AjhQIGr)*##y~p92f-W@>M#`-ricCtu*a25}WX zQXE@cqY>a{%aD3kZ^LZH?-jMjVllx1 zlT2xrEuSERwkxs5*9#^?n%c5Em#avcWUt`n@xeTgV_Fy@n&NHSq~#tY1Flc;J^+os znGZ9~%Cj2$`yM)Ip=}Oio*Njl=DObbcUQZpopm{=ei!y`Y}H?ZRMdrJnPYNR+3eM7 z#!(G}j2kM%wfMu*$We~jGm?gFk`VpWn$?a;PMN0%P>blB*s?0g``oS z@F~d03Qxu#l_UU=5I)^`!$oFc4$hG4TmtIMM3!w2oJn!VWEeptbE1vPc1;?5??FT( ziJ%GV3su1jLNR#*tAc!Xb;kPgN9F7RV6s7|%5aAmcvdy&L-ipdNAY4#F)KOGz=*C& ziaq!Z8H)ui-r8Pe4uF=BJNNdwC+*OKw`*$^mwz)~0g}<@z2rD*2nhbX#iRe_2jjvr z-fPlG7kq9g#m5ZO3F}NE{&e$e9F+bH1)tS?e*WbVyaoVApB8a9RJWV?+|c{p1Y5Onit=Ye-+IeT`L>f!m7u*_EW z`Y{Ps1vF5c7%AMSQQ^T4UPwtkq&{Rnvq2xt4qDIR|Gj;a>wYqS<4C9ocNh$MZ z%eC5A$s%X20k-HHn|-J8Y@7O~^P(){WDslm+<&1~x~V7i+){JM6fQA8`}E#p=a~7B zjaP9P8i{Zo-jO9`5_eq%{pg5_`PRt8R zMY$x$*V6?O$3_CaTvmlU5c$ujP-nY0p~4y#Ui|?4AX&uPhk03Sx!xj06ersC1s#2d z)iHT>EZ>te&n)5MmRIAzju(A3zOhpHV9eM|W`5QS7L8E>{N?E2O-` zH}qR$q^jPBo|nnBGX4Ig-yRu3ww%020Gy22hD9ZUb6@^&!hX}01~_e)l>LmnoJc2C zhlMYY)Z=Tj8p8@8o5)(uhHH!xkKbwa@k$Qx;4mpiHDf*&B7ta)C$s>QwfFJM-yR#l zT^C~&@p=|VgL2a#5tK93RB!_Z^0Nj3(*Tu5=AOrX+>R@&gV!j?A z@Lg8Hmmc=|AgIP)8qpFE5`bxSd$_rTV0oxF6IJ@T7^3*5O#arZ7-1L5+ggot?rMUw zWg0JH`g5vy9Z#cRMmR1vaTmL8>NOHaMuQ)$Idq;wK59klNdC z^MQ2^#7%dz{RI}%mwEC}vt?cB8sN{!AQDJ%q92H^u2AMUT)mXV>hbGoCO<7K=e~Sq z{$FIY0^A(tNQz#d8KgW|<3INHy;ezQ)7n7P6!~M`5P*t!sXY$Rs(^_0z`|Wed>mq2 zXi{UTFsN3Of!GFA>HZ>RL*e8?(I8<)dFDrYOI!D~&zui9#J*xw{Mu)SmPr@1qVGt| za_T+|F0g$q_{U)SFIv1@09{Uiat|W~qy~GV#qD0jGt_>hR;S(n(h4Bs`VINmA^l z|37eOc~RNANz{xBG>0uHw0E%%;wE7_Gh++R;{Cl;N#P46uFUN+F9vrgOLYJ*`FNFG ze1Q`C4M1u{U?uQLD3{e1|D)1X5X0&3BwfPcUEp;y*2II!U}X=iA_KH1EFbB!&g40E zj`W2U!9d|-)W724J4yOv zW#_0(TiGPUhUDfShj>uMOUR7f(ciF^Izjmxy;(@gZ?({e1v!ESSo7a{4+VU|Yt*Df(&oAF}#1asSU97BAoi4S^?KnrH&$Qgk z1V$_KR?CL?@u7A$ysa~C^=Fgq^L*BGlNX(o+&T073%HYf8$Fv37C;~ zh2CHu5VvOAi<5w?|Go+TmN4JPy-g{SqL@7?*S8SQjJ>vlm>aiQy|tiOAkX>}CjoZy zvw3bL$#1P_kS46Vyr_<(s+&E zgUiX?9^M=IV{W%viW6ybEVerG>?FnK*Lh%Vd%l*%k5;vJofj{(})y%PM* z$cXu`TufbL4b>lQKeJfc1Vc8>;GE0NifpOET|3?k2a;={Tn>a3fVZN!0S=Ezglo3+ zGCJPBf^Mo#1<67me^3w0Yol2g9%JP@vFAvxC1CIRh>TrU_n(W%8bm~l-9@jJT@!zO+H0m@+xEgfR*sL>0(6bKT&b?lu3r*CI zDp^-{)%d1%o3i>~8IG|PCVXUjgp;b9u|y401)Ii`vWYIXQP3f;FI~FhUb^(x7<~dx zO~$mk2iALb&2sPR2IoaCSzpRH9teqo{5Q^Qy>eNQOFfVj4L6Y_Ud<+*Q*+v42zaxu?>u6Su!!ku~4-e`DHZ%1Ic z?R)qJ3@xFRqrp_7dON=rt0mo=&NkY_J4|6 zo%gJo<>{;j9HZD(V}Atew?_zPGWThW;hke#VmNf1;(3<(?Bu^qs-;8e0->xz#p0U; z+>TyEwUS9_dk~KWrp)b>%et}EL63M9O5HjaL+d?5a_1Ih=^Cw3#GcTm&uL-?cN*Un zUp77C4bv5q){u{xM$;OM?Ya}*kYljzR<-1iRQFS}5$z{u)l}lXNi7ARj~rkKwR2wg zeUro?4$M^;scTJnba9u6C2bL1#7$5M zdTB?OrQa-(y%Dyr8a{NNe`F~uG5p3fY753mp{JvW^3#yGl}JsQ5qP2LNB{aYSK?IK zckJj}E3*bYBaNEFf|`-~PROUMCzXyzdmTDkF~l8FC=AqyqmY-peEv$a`U`rxXAKcwzm-DPK9V5BeC$WY zeNSNsi8-Fb_wc1M6V1f<;dY(y4_c52d~alTb<0vwXR49pLvCCW>L{KRAM7Uq5$^|9 zV|CB4d(=V)|OwL3ENT}1s8K5bX49Dbi<-71A3qBE1+8LjvhYhU?AVxnG%yx z^-hxzG=a=KxcSqfZ^QT@9JWt%%^(qObIP>We|BUyD)?*4epR%w6Q+!3H>*}3NvC7Q z^yP7LaX^U7T?jm7RHf0dSv=3K0#M_AsAzqN11Y8#6wL|{@|v&v=NncSagcDoaw{e36*TT zBI?Cj1*Xsyb#TZWl?q3-Zc)UEs1=M(HSebg7hHoNzsjytOM^;}7reEiqL8-W>Vd#} z%y&C@96rs-Vfus<;#g;}T*(vxyF|?%C&Ej!Mma?lFYitNH5fxIPlQIO`OHO!v`*lO zoPp7zmnxZDT?ubi5K1~o7^yf@)$7fHqHxIwl!e;d+ixd}s$lVu7?jK?W;c6IOysvR%d#C!#P&mb3+qjXfLaHib@Php{32a444Zc-!6gA z^Tfh;;i#cwH14~!o5hH6NajGGh=|6slY;M8B20>(9$Iybji0AZ{Urm}n^I)z&>>e| zS_yG!yiMJ`xO-gFl!5}>Wpf1W)9?5w6_e3FUYkOj8;mC>|C}bPgsMs4=|-Q`Gf``} zom+kAP&BSEzP;D2#CrKDt@p=M99V)q7ILV~5m|9pI14+0xDP0~lAW6Q=b~kkHlEX> z5rZ+O!=K#l8WLr@dfe?g>gMdfFmc2ANJT`sW>KFvvuEO2=BYKl^Nu0rC1#npUgj`j zV1)U=Bk?|c2rOdS`^1wP;5;__?S@Oe2irio*lA({nDwV$w=sexeQgqwsU_0NH_~^2 z?&)1H&^S_@l^R?GE>B@$>e4kOQzbqh!=9n?r^->Qrl*WzY3Qj$4dR?F8VNVi+=GpZ zR1jg=cnJjBPF*vwiGa$zSK)%(Ku5I~@6aQquU9##FU!YNmrLh@)<6urx-aSI;#Yov zp0P^mRRTKuUo_d7;Hta6#YbsQoClReZD3Ds&5v>;q zZpS7fea8+}G*K}TaG~xG+f?@*TG?0hR;-`dl-y)Ua|<^Q_I$_D|Acu|`4=;Nd+O^! zof4-vEd{c{ygEBKwNF+W3<~FOa~EHA6RQ^ET_0R2>+$FVZr67C@ZkR5;DR7e5%0a< zKk_m{Gtm~LpWN)dS5P_T*M4Mq%aH0AGO2hpSTv(|DK=5b1Z9@H`=-e;r7hS@gYm4` zayj}V=1MP+>&-`h#14C!h)_f+xE%~h24hrjzK{l4{nAhu#`sB>_QF#6CZq%#;Z zVSu!md34NZI8EM&8Q3Ih&n^9$#`upqc`Vdl2xYBbzYZ(|+7CEBggeU(1&__HX|jH; zI%iE9j3jC;`_~TiF8!{3>hq0lV0yc z*A!H9A5~Ae$#F9Fd|}0zvq$8NCT^Zub-jpr#cAK%o3xiK)uP+Nhw_Bq_vFP`?eG`zR~Zx|Iy-H#5(dJp zY8Z^)_fj(#e4*5-vXoM%JB!A0c{r=2o9CcyFrz*X6k1Bph0yP<|1gM(|zR8>XUPHv?% z_uvpX1zL_t~aN{t|XL1%}P6SWX)*E z&8s%!%JW;5izK&tcyGJBwBbn>pPb|wE9Z;^A-V@~TeQZkZ+}sH22Kv? zj5BD|6D%AuivSfF`<@%7bs6xYBPs@fH4W6V@W-;x@vUL!&;!8~H-u#G|m6 zkg8O9|JPkXruGEi+lOS)Fzo_>=lw_DzOWL^plJb94sGNl5s40PTz!=y#^_6V$F_04 z@<1HIfOQ;`rAE2a5BH8h`KF3f%FX8jk>OD0F8FQL0A+GalbPR?z>?*%*;;#H*2uf| zU}_u9yEvB1hc}6zVLLcbhKSpX}wrZcE)aO#s9Jq?`X^M!TvukbNU0L?DVEWS2xt?6-~c{ik3q!gPF z=a091*HX#tmG-uAu*hdk4MFb@th^B|%SVwGpo^(2ppHFzK2&e#BAHoH8+~X$whl^+ z=V9su_5d-;kVh!%Wk~OR_MLLssiwAe)g?qNm!UrbEDROUa^gzhW2Vk{d#n_ywkBta zHXJwJMw(<%ERcP`zvCJ{Dlh&Jm5b3Mvfs0>Oo~a{haJJ~`${+P9=bBv$z#3+Xv&sMl)2bk5 zI0LMU^}6zyk1aqC<`PM(3LWY4IRTGv<+1DXGk4j)k4ySsts%82%LKRYXnTj6`7%EGkzf{cTVJGheW31yMkvIxF+Wm|;mwj&|ppzFV; zh9;aWO;=11&Bl(jd;4a$Z(Uf$`(rH@QIt;bC4Hc8;ot3|Z~0~N0;BdQ)|LYi=D-<- zs^%M(b*V*5{grmkVLvV6&Hm3EFRP}E{l){OZXLut-{swc3SwO(xDC=pCMFET09L^^ z(})19UuNY9w9LZeV45H9Mn$7?$-KTluBSrP0BseU#jee@2z93qfNqMi$F={%&!x?( z=4RmHVl?z6N7aMF4*R>_%K}b^9*nu#hCL_TP8DSk#ATH-ltYWQEG6jSjArR#lZFR3>RT$t8 zlhXgn_R6@X-z&p!l;ueyV2Trn$O(R-C@%lN6QH_jp(ZIMT(N^?=KJ-Ak~@i9rd>5c zk9^^>WL;H-o@7p+a56Q4lY2AFbZlvD%)+9nZaA!p0$3;3-LdpqtlBoFmr=QlqXH;W zT3JT~Zl2dZzV#)0Kp$2cfjMD685qxJ!k;oO7UOp?W9(mFSyoO532Xl7)~Ad4!cDecPu+@hAy)U}43 z{t?>hlJ&&Wtmep}Tdsh+W!g)z=gD3P2tYFM$iSN;n*9J{`euXNgA$y~!lY{02p zxu4%&ow&Ni{%(e2)K^@vktyuc3dDPpnxp^EA6T)xKuIf;WI#rd+c;bc*L;dvBF<%;%wJSKw}bia0Rl*i9B9^O1+T6ym5B(ybh- zgdhI+O<1?j@}>%h*kyL7PBNgqP$=Pq5Aw~yS}sQ1-AU2g(M>NJSl_48qZYOukL>l+ zJ@5*`#+z=1@1PmGW>z~ZdEXu8n`Wz7>OCyA(qj>qxr_$eR7XQJLd-%KIajry+sRd^ zO_Bj>d-)auw>lxP3~%4c*l7Du>q9(04L2EX;=B{t|ORdk-6$O9l<216#hGY9^%a=3nJ> z4fGI{zP+$a9@Qob-Uxqo(_2CQd z*DT5~UPzMfd_I`CHjfo+GQJtJpUtc^7bKWj;cvA2m4VkHnGvaQudU5s1k@MvuzoB` zhw1o>hzDT~UNs_1enEibamQHM_{FPcJ}yLM;u<=-9?S#k!*I1 zzrkUx9{rQ&abw#`R58;ChfRxt05(AHl5zv1S|p18eZ^Uc03r*T@xYqt~t~~Roug=!J>tuJ76|OcoAgK z%#n{ehY0_38EFd{ZqyjXCYdojaYX}u?TJquR6{u6ubKnQ-U3&ikxa2dKvC^n+ z!b6#*j1YWkAoG34Ov;roG?_PRg$dV{_ZRh!UiiH_xO;^)+Pam$TRG}6T#Mydlygir z6^wo)bT;AN1;0VsS5fytxbRx065o38c;rHbYuk>^H)@@l%W81dwQ1zY=eO-L+*(Ot zQj|35+WJ-OpIfQy_urYdXGEpCoHHl(eRA{3?; zKu!V&4el7dzE4Vm`J}v4r4qRIDo&Ydz?*-LwL&vEw5OqpKa@|Aiw!mOX{sve-IgbX zLlf&94K-0by%I6V9gREL#lByDq&p7X-ElY1_xHb_dtdlY_St)_x#k>mjIq`NY^NG~wH3Bv zm}?o5KI@1jRL&z_b=t^S{@;tu*%&m5&wo=*S2UNI@5pl+~pS+hcEv($zE%#DkwT}+$;wvNiH`X?`C*A@fX`b^0MI+ucInm z=^Ud@PEUWVa!Nv_?{7+WU)ml&d%mI;*_YJHj*$j9;1;52dkm2pD=_|Fiay<>*YJ2L zP~7=;-sghRG6OdGtCL{sfT25kB4&5g)i>3Htf?bQr2k zfXiW{*oBNKsU3fo0$|=cWca5%o?7SF<{5sx~D+nNrM9k2tGF zd2USj1*HfVT+4x@xB5m000UJaObeI#n|AYOmrB6Qtj_6LQI1$2hC8S1DcGUmX4 zjJ=jhF1XfJ3MO}lPfNI#sB!`Fh=}RH0b@5T8XH>R&{YPP((J5vReFNY+59xFAahYazYadDpbjRSV z+usIiJvvmWTLz|kpky<`RqhTWUmYruVQp+&6Kit4I^Xv|-q-$ngBYN;pBK;eDJIwA zJ0tu;J-C_praFL>w&5aJqFy6{Lj1|7DbE}2E|u;v=O~m-#IV@=KILE7dM=JAaFi-T z96+Be$GrfH3=p|)OC3`g9wmpi$d7IDf&5b`L#0fkah2cctp*UEi|pR-2GtVz6A8FC zlvlPOzgwlZYgGp@-%u@P+{}im4h>{N5{LTy9>jc<)T+F&cJp5&XN~Jy?*N;0Jqyzd z3nysUPB0CB=cRMB${OwOnVV%Kw)C_kmu0}n*WePhVHZ#3^>6sbe}t)& z-aNsHkQTV*(-jv}lv{0AE)Kghbsc~mht1&^`Wk}o@1|shL$=TqYkr*H=oF~rlV9TB z)pq`8>`=3TmSBb!Qy492$fU}6Fn<;a1#GI1djlr{g+S*mZV<132^=AE`mp0 z*R?X+DK`yB16M3rjwLhgmTOVPWII$5rmpIoJxjUiD#uAhQFi=+^5y1z%OS_DwNkv(lM zEW4wrRA@_!9i^pKzWkeP*`SM6eiNu&OJ|hr3$npQlB(9=cGN%_ch|DfC&J_K(MnuT>C` zWKqk?*h9Gi_~kk6ll;E!Vr6M@G2Q8i>wkI#nK-Dp5$*Y8&*wM-;;q-D(n(XKe;%E- zy60d-&m!I-7b0-Azjmk83hu-2fcAMD;PvFWpwm6=RYjWKj}dFiw8dXqi4a*1NYnJz ztuObZw5{jQ&z^7yCE+0``b%q_=_{c7Y%_D3U3HS3)iwzsA`*%g%^w&Gjbbk}w~?A) z;`Ir?Ik(+344!OCe}6M90}PR7kw%F@u4R2CB?phx9>Q(V7<~`|#tE*Ag)0Obi*IS=-#=d!73{;=3fSUz%D(Jdps~sR z{{A8~z^^_d=k~?(X645FydS?@f9)O@%Ur?4kZr)aG#$nJlTWN^!Esv^v4H`DKG?Q? zhBf5bS-xd0ls@kc6WJdg4zoM7A!V$nPwh@@oig}#W}6gK*#6@QF}Fv$px2`%rDSxz zLYDlD;PH>0zPYiy##U1+v@v@>ZLNB%gr$jzYUJwtVD^D4e`@MKnt%qwhc+S!QYNJl z`_8zP%h{YdW}`Q>_VJ{(h>~dvj!~m>tNr$$z*J#zaq<3o5C)69HEnxeQI_w} zA5%-hv$}=sFF~NY^`NOmNgmJJ6}NBAj;6a=A94Xk$6mZ2ru~gk6ZDxh&02lx80&ki z2CIr2wV?#Vt!kK(_VBNZI(#caC;#r~@tP_1Z=<*}h0{D*B>3XO@dqm5@8)^0fU?S# z()}O|;WK_zhrUW<%3YxtVLK41b% zZ&1l|$=T?y;!nmJYAHJuW)F;u+hfe|u06UR=%m>T8*B2#@Q_(Hwbo@N`F!L{1d|eljUG5dP?QSA zpDsT0KLFKNCr6q9^!FLfh;VY2E9&vrRgVFrDy1&7~C-chqUkS z^%5964pwhZLtAHnp#PKK0Awr&q$Y7dWrE&z4apLJa`fVVKooN+>|$onAvqsDa=tQ* zVs9?|qpV|4iO30X4@rr7TtIgg#l8ZxuT1Qeg}tiH`0i}VL)`m&l<%iF0@ljTrYbA{ z0DpErhFcn-yLp&=E5`iMAi^;zlV-Lx2uqiyNZ zcs>vfcIS4&e~Z=%1higXj*lawZxqaLwfS%C?EFTx4)?B?Ru30bZa6IEOUlLXIftAT zVE#I-2$AtG6-tp}?oUFFZPzXmq=jsGXWkh4eKKHB0>(+rkd998K-7-EZDd^@r||a3 z=<2&+mgb?{oKR7zx?F0MVnN$3aRW)dm5F|%#vmgTDfnHXy239Fl@(v0jn>fo zYux3T6%)4$NINAblyN^W$TQ>c`3oP9xOoX@xZ ztLgQRy}l2S3wLqdNk7}Y)k$Kw5f%5fxsh!k3J9iT6bnn)3aoxV36T0Y_n+|qgoE!| z%C58PQsQeBZ~G2S1}`g zpzeac-ibEmOa2fbi1Sl%D6NiZg84q^g2R1WcPbmgBcieJSA2XAPqh^m=G6o9uWxks zJIiW_jiaQ{i0LqcB4){>RpW!{?3d4qKK@b_2?x zl1#W*N@bVyd2@4DD|`uSiNb#NCPN0sSqFTuwqm^)tRD z3NDZTc|x{hy7CM^@fNl`XYLK@&NvSxf@G~+Zd~f;{H!amIhfaO)t$hDfSrL{oDaKt zJ5IX>(pLvA6n+cn@QOIB_Zry%dk2W>O$hAULY6x`>n>{s-=#eurT+*hnI=&8zv<8RdLyYPE|Pboj=&$KZDhg+7F<)PW60+~8_ zwjs462VD;889^oa-u^=WL!mjWDJWgrrHQMc?V0Wq&Y3_@3gBIcKe$mTI1X9A*+DP5 z?Bh+qFK`V=;}`N76}Z%@Ym_tJt=T0OaBbW|-ElC;PyqEFYW@i)rEMQ?IN+@-x-Jf{ z#2J=FAntz4E{2C9NvU6@LBw?Lcue`Tz44+B35`jrdaq$dh)IreU2E=qJ zmq(!)&w0D0k6rt-4-~buy)ljWZcA%5c?6!l;-@z^YHl~(4U0!dhl?u^wl)3QT~#~ZufXJ!flIUa6`64LqIGf<=bII+d{Z!J z{nVxpgu6VV&*GXPTXCw5`W*g;a2=a>i0bMQX$LnyfeNy}`-k9e+9i1t$iB&AHT1;5 zL%bTKrMbZO?>_sW4tay_8Bfj_*VjZN!}42>Q`n#3d&EnhvaJH!Vu2^@GXt6GdvEWk zSuKqe>{(M+<6CW-;$v3f(dw|d3Id8=XT@)95dw4U!R6&5ofCR+(zgCdYj+WSX zS;;=O4rP1>Y%)$N3k~~3t-nTntY^z><|b{V+;Ko30e$lfNPDuo#RogAKs{NoD@(=F z>Z7GwU;G-b>JV}WM+SI%QV$v;br>*R)k7mx8-YsMt{WEvMov5D^Pz(~x#cG_ZlDDo z^s9qJEIkMl-2w7b@&Qk0(?t`gH?pC?$1bZeWWnVv(hWuHy^FUqo3$)KS$m(9r?PT$ z74qN`94UV1>z><|@xKvE#*@d2-^5>TwjMPJg1MSmZJv#ZIuJ zUPU>M8-Q)|-t#Rjt$m0=BYjTzoZ;Kr{LA!mV3@zE7g(=4(@M&lw((UaT)zczN~fes zqoAXuU6$;kHw4!aLwarNfmoKxG7FXTVd?aC!Zr?|ZHoqPHP%|!=WBxgIuPvl&^Zu3 zn^A_+Ux`~NyUSrAh3Qk4yF!?<-h@#8lhvUW$QdTZ2$RhZ162)Z1z4H>ZF+6#d4QlT z%FFK)hyZj$>5$=o5W`NvtRYwP=>vn1Lw|ih@#RRcb(Avd?u}@Mn5eitJnSp@r4CIrQo;DR1&&V%DSr0H!K-3gghqbsGADO! z3^Cdb63Dd3^ah9HIK}5hiGw6QW~285l37qSj%f;_Od0J31%6A@W4{rZZZCt^naQu<EF z80Us_Kx*2-KV2517HfB&rK;0)vp;2iTqu|J@AlR+$p`)bGsmgkqDxQyXb5GYE{A?b zw+ZeU`Rw&bYgO+)8MwK~TzRIFjF4a4O=z7<*vGE9?dFd1;z8y0Sc0>Rf_6~Cz~Lei z&hg5(zahpVUkZJ`6mHU3&x+lrk+f#qRzGNgjLvh^kTVWzCHhtG!7GlYGED1&b zW;EzZZ|S2DlN>EdC5Zo%11)GEj@&&Pbi?*d^g0YE%9Fm47ev>9dFx{;iBtdw`aIkn z>b7Zc0dgeocY}qesqIMB8(?)cXRqXo0UltKCxFa&_y*s2SU9(DpLIqwG;N=xyer~Uo}bdG=0-OPl~fB}4`Ze5?h<7|rrKSrkBWqp#3jhR~59TE2oJG{t6EC3uZ z?xjl@)BBpi!|w{ASm~Er9AIzr53iA#X4@^zn1wa zu7MTk^aJJq!_ZBJ zHNgxe;GxkCK;cNqN0D%;@mGH|6=``$#+>OT0S>^{H9%vt?u9S?ClvS*ScYHIji(LE z>A+B-v2@wzZfc1XOpIseVl(eNC^H-YG=je}H;Xk2I*g{m(msYQ%*L^Ew?RU zkO0ssbDR3aKy59m2U80gfCpmg2tuL6;D4RFyt*8!4Y(r|{w>%=IvKZEW0Qn9qJ~?N zOG1fv2_VYA;YI$jaiuRizWhrNcgW8)M;>*6ko#2LBKv*VXYfiu2!m^y!yB2)EZMz5-n!mlPHd>T@LM%+4j$vKbM%T%p z+^SMBzGgx7BEq#7)9%bF$b|!Es$Dfj(&$wcU3+X)?>JOZ^$=GN<#Br?>Z(!GEie31 zwTa-YgsrGKR^NpGBPU?>MA1dZ-5>}!r;4z+fm>D6{8+6T+%KB7U9jpNMP%%_)bJZi zfufCwCBcc4P_Yuos+Q}|)%x;sYH2_ltIFZ85$A-$2&9g;Ibi&co;&@hL(Y<*??oE3 z-}e7s7MRgPsaX$FrJ{U`5!64Hvjp#!XIqMVD4lxei%^caeRRNaUzT(pd~n5tdjfNV z@wly@a&UX3#k>z;gKdfziyeCO?m<&4xVV+=pV0dM+D6Bp@T#%TO1d25O)IOXnawQS zl47|Bl4bWn^q5m?8;ZO)g<54<783Q)ZNozO|jk}kQfLJF&-$Mb}`JE)-Q$Px=uFKzd55FlF_`i zL%uyjbpGc!)ZpN|!wA-FQf2w;{E9zob#9Jsj;MolRHj(gP~x|3Hwu-Wd_dULCZ zzL@}oJK*&YUT|)PUkh^O-Wq4@2+I(LP9pV@=n^Iqo0dwW5WIuXBmB@w7)o3TBoa7O z`R^CeBJFw8jOC8OGd!;yPQUAkcc4ady{lSeGtc-7X9Ja z%C44>O0lBO`R(=RS(A!N7Zfw}@_XbCsufHCOjPO$_=22u_Z);iL(1W!ksr4`sv!H! zZ?=Xp8gv}PIvVTGzv#pkLi;k-=f28z7HeqE=yb`vArpn5u`hZ|*9)Y$D0TX6zqpYb zC7&GY=g#Z2@9EDv5Zs@A3G3_|p~U;%UN2V7espf!S4 zL+W#%3(yCIH4VMcxS0RtbQgkfj)*=|J!oNxZx!g*bl1_SG{Qs=c zD_tkK-kmM7CxAi77OC%wNQs4k#cX^nCQhL}8o^+PLa5K>UVoj*fcY#CE=C{Xw|&m6jIp#bG3+^GhZ zQ|(?geyz-2d!CitgLJ6@&Lk z&>EWIv})X992BGUJK1saf*a-xnpmpbw}$8~jSp@V0L(cj002n;tIPJZ_Eco7K!oJ* zx66f`+RS$eFSy5gzquh?`Se2~{Y7vopi{F&C+U)6I4WRi zEGT_jfAs4YIOqZue1S@zr3(+Y|3eq^;X>4znyyp05-3sMgR7`c1KTL8hj8)ombZc) zgc2{USacD0Be#^ZI^kCBNuo1_l=Ofwsf-X!50edo{R0r4OS~aM73`%rl7^k>@ufV#;=IxUl9M&K zT7JFMs`F{=(7g={&?P`V^W!sOlY?7Vk)i>a`EFQ%6{zCj#{2a=f@MghycRu6vwqt|8l91pen${i~k?NO4o z^5oW=qVTz$4)VvAkOi24_fZGNT}8lG?7J|fyw}VZwT~;)^X7Xt^6P@;$$pYEOh7DC zD_LubeXwCZnM(^X;)hPoizqv557SR{Csk1Z+zuab_3%ukT~ek!Nfpd(^yG0W#R%hm z4u`wWE!1l%AKB+q6?y@HABHYh?tJ7Rye;{#vy7d_rQyx~EanpMS#+MY$dn>mC$3!m z8HOb^gmzG-#DX*F&kNAe5d$$ze->1&|HGYBhCz*GGO&?|0P`(7bH@gQlnv&#Xin*- zQOcDykAof-3d$Qg)fQ|Yu#O?t*;sd&J+O4UW?qy1m537c^1&T|n%y>6*80xBTa= zS{|7bC#Xmzfr|yQG=c?;9_&GYXNVe{T$_$duJ@khMB#8D>vYwl_c9tP{)XgCf%3MC zYzf|*qqej7;-^jqaxBUDxhU3fcn93m;#}WRDfYHgjHpb>|Ctf29SN1=vHddw0GDAN zlT%2+|M^e#z}8WNQO9q|o27FLM3NdQ{_EeHGfVBxypJ_NwGKbx;F=|P+32PY!}yJ9 z859^lRO-NIiSufYHV51-&S4h0CqevCVuWxcpEm{9vE$Va6l0W65z8J1JgAcnQIkjO z6+3-9lWkE+ z!YcP{dF(&f=N9kjQmjEam(Uxk0muy{dFFC22KU71g zfsIKO;2a`jWs@|SKo~#`xt0oc07Mrpde>wqP^n;M#EmpO8ydj}xaHW08-QWXk3CCg zko1^&{y*d$Zo?wT$MNz}A0gr$k+_&$D2iSpXk*}peCtHyci2;!_IUk_<%ThOr5 z41K9v!toE`;UH`9ncYt(Bt<}Y72-Dk?G2@x*(v6?F!5P2{xuTJ2lOXiq)nC$`syB} z#w}trLrYyxTlhKsEolRMSla{vHC?Dm$U!a-{J-ha>4*M!uhI@|wI0XB1CIXo&l|hF z5exMC$fx-tY^Ak0(Ghpse{t$>vCbUlSvi#_GlBARg(T*Z`dRH$Qow%t0U$kgKnv6q z^$}9DFYHt}rkfGU^!P$;;Kxu~`0;PkfcA?w2U&2#G~}g*qJS@$pPWxaBjV0iyPI zz6^_;02gOAFt798Y{52VO@8RyUe35ljuI(~YVJWTYQl$X!7$gent33P5HisW`X zAwvjv60IAq4?^41igWI-OF+xKQhp>B(*n_vny#7cSt7kRD8+-^uX=Zv0T` z+vW%c2Psu(G}%JnPxhI^|GuG_fd0WMW&k6ycX5{l%W&6Q5LI0;10){=Dl3)>*h-+0 zZPfMg1d>y?T%~9C4n4smEP6HcwjFYrm}Z6a^T5w(po#AIddzC*`0cPjSk0rl`IpmW z^9LjIce$PgU8ch1`W2}k4%?$?GqhM~k)Md)JevZZUO889{Xc`DA8xc14MQ|wQOL?` z3#K|yz9Y#Tx;5@g)|o7c#e#ytp!Y_o&VRQKC{_#|Fz$s#wg8ffMK;e_HbO!I(hMd= zsgjRgaGpPU99Du%-FgMQMAM)tFAynRm`z8C%Uh%&o&j*ky!Y9@G22g{yxhphG``*X zJv|G>IR_PfUdZ`y2W#SiLpO9HnsY3x#qgb;4rAV|FgDje5a#=Pu@GbiLp z65={Jv&GLdp>np+{dmmCBH!MjIL9_fnT_qWXDFl z$9?=xipxikuW%%FJ@GHA0>OM!!Gx-FE! zA1dE{N3M5rDOYv6260LMg0K{)PfLxp>4To_DcMoSAGwl~o1bpY@;%WIPyuD? zgi9CgCZ+%hM;Qki@9Lok$#&d6v>_Q-Ch8r3K+zyqmd?+b0fkG8hMWw@m7H1dSV0%b zdd;tKI5d@`(=T8Kn#te}4kYUzSFJLUnCwuOYM~`v(m&>mi-#Y1&aqN_|EaNrc8{utY=p#&-$oKM z9}={p!IgvO@7`C4Dx3lVMXMmz57%|>I>oM+5sZet!bDSDF1A3|XpxlxNc^$%Gm7Igagw$0>y|s~W_chxS0xkS&Q7X*DaM&>};@0e1xw zY7pMM(<2X7jC-|g^&;o&2uAHdyMv1(y+G*&`Z_N8i}{y6G8BFl_Q(dSj{{N=vhCs= ze%yoKcxZl85S?M!cHhQqYN`(5&PB(6$&KkV%(KO+aA0j$7mQ&X`T;~eIA6Q7>^{*n z-pj`vE+VkQMS;F}_+oyk91~iIyGAdSm#}_Lgl?TUc;lR4z^}jeX1Du@F>!hZOP^%B zw(}722o#N7PRLl7*7(zSWYtR01Gu6$MZk=-YwfRWrzUlcRUcxeh25@QAaNRntBn0% zhNIfsFbaSAoX*PLIR&|B?YS|VXpYd;RX&x9oPj5|jhb)&vWukb)86Jn%ZZz1%_jd@ zFc_TfK97fxQK34`#mHrb3T6=a4Z|KFYxp47hfRQiyvSp>`El;oyu(8k@cJzYrLtAK zYS?o;>Pr>($ZAKqNIrN?zRP)0q&C;>JUK0j z{NKuH6GlPpz>1*XW9l~w#T6KXC&ORnh)={GEoe+Nk5Cy+en$e6@Bit$U1qq0pP*3{ z0?CX+gkC3b*k3);bDu${dmqgfr6PS8Fo)IpZHqlYiwYv-P{65?NIwm=6XNWFbvL#& z&1F6RU5%u{=ON@i3Jk;r+*iuXxS9d%vaK2hD)pNpb{(!9zRy%-HMiTxN%lYDWwf}w zBf&0R_yPJM{P%U*xY@5pNEs}56@B{)2@L)=qJNR2BSVihzU-g?cmG7+t~&weNcurJ ztvKceskF*IYNx8WS!8+$epqK!HY5BO@xGI6C~uUsNZ^@8y6^WxQ{ReuH}p^J;{@+u z2G_}8b!6WaoElbCvrjeo9n9zF?tSRTKGt9dk|N&PB#Yad_mZb<&qjjw@7}}kz*+}z zn-uA*=DU|0rrHvYu;*3qV?Zje>?K-xuf_~UrS~kzftweWqFA|ptSDy%DWy$_(&$BM zEQK0XcveM~z28Olol>8d?!BY zpb|#r+Wn9SjQcO;P7z$z2B%=wXb#XK?*MW71oWd>*)c0|`OQzBzV!Fy{Od}YLz2A$ z-4J+OTv8Ib!nI(?RhCJO>BvR@E!#^lsDs_c4~1X7Zf#-t%SvGwGes5a9_kG zCy>3}JRaphXe9??-qFoBvh)Y>>9t_=#m3&zRV2h;$zRMiytQg7i8bz>+w4|*FwolA1o_s@5>%)Ci!6GkCE>iMV;={<###Dix`mpmbE{VMg zw7x?3`kzQFh7SCl;%bzFW-uDREw|hi{@$sJ&c9&U*Zom>8&2o54$@TfOmQ=$IX_~- z2=~9dWLKe=*~B5c@vYFf)JDwwQe-ix{d$O#`NC0mA&Z1l&e67HXTDeu@b-p+Bi-Ns z0#hSDaI+H^mgk>0DBJ0du?|g)>6Zv*z)*h_wtm7aXZpcwU5_MWGJt(v?L)K2B=3;2 zklQXoX8nGg92AHR+|p(R&a%@#P&s2D!{?G~NcdvPjKHaGA!b3G1yh*_?xyjc&mlM` zU#ttq{LTliJg!dPOA6?H$IQ`D^TDPQg~oH#QTss*!7 z?nDE`K(+_&LGivB`hM}pAb}PSN!@E8)hN@=`b@IVD`*V3j%|=>5Cg8&@aUz7rvrJq zSDVuRdrvX!$pM$y8utS8HJ>IBe?J{+4e+rg=HQT^mVDf9;B=-wA_u3JT)N1|ZgCa3xG7PzU^Odbp{kX|AxbTL;RHMPXMY8^UL@ z&Oyw=3uHs4!a&3saTM;Y7a(K@E_}2mHA9^0cFTX`w%NS-XG=Lv z%71~O<>HPDvM)j1!>j)8QL>HC$Nx;!14>{{E`1J`NynawZD#-_2!Ub0l~r7cTnj&L8NnBXmJm5U6~z| z(raK1S?A(_dre{|6H5^huS_%7`oMVxZlDYNq;?e8zqh7QAtB*w+PS@;5jiT| z>Mu+gtKWUf9O6iJMdU>zO?B)xmoQ=Kcvef!be1fa28paZUPhTw+7L`Hp~MMZIDIM= zoIqK_&5OdY6)ck-M~z11gcs{J4Wrz3E&#f?!txM4=}pj_Pwb37`Lgl8GeXkccuYTv z9A`b?0~ z$;l7kuEitj#de{-$;1@Ln&(4A4!bMfxNpx!Xw}k2YDHj(TS(~Y@|}f96>`V+suGuu#k7IMVC~m4zE4BGsO(rEnfwog_3;dCA$)m*&mkB|UzZV6zoob?F z0;IcR{83O{J-`E-*5_7_65XQcO5CH!$LjrF@r2^+m=5s3c?vX}NKpvvWQ&PAyq_|S z(jHpYER=6Q7DA`73*%>v1R5RRZ^i%kf=kU}IeErRb||~Ns%d-8H>6r;R?l!m9DZf* zN^UW?WFe9T*Fm@#Cqyh?Jw_twOadmX2EeDpX?J(x7*p#$F@#ygf1b5 z4N;x+j8381(t>a@m<;NLEM~quyB5?PPJ;ujwRbO+7*j)^vH8_4iT%||`x=uIFP4zG z=D983AMQMC1}>?*%_IrC9q|sCEw%Cm{@q2f9rBV($k?vQbi=-)a{3R@Ow^Qr-rpyo zC#3<=ol66AY7FP4C8+Y{+ z(iZOjT^iR!PeypxGFy+t%(E9Jd1Tx?vIB~qBCo%-s^bmp^)XGAH!IR7L5QNb+%aJu zu)5?F`oPq8N=&=R2n}Yjnhf57fj}??sDVBh?$W+d-bcJ-_ zDU$ly;eNRneOG*95vPX!%MJst3!_?!-Z;NO)=5L`N9?s|$)f`p38xmNqzPY3hg3oN zT3Ogp0Oc{XqL#4wwpK5`Knrjkt;J4;{|YB=YriXOJwLdb^G|%Y5*y`__${*#p6-y^ zj|!aw(i|Y%0jx6AvG+Qe!#dHB_{;}Sj}Rh5MF4t1%r)BY#;+o8zq-Sxop~r%FB-)5 zm5!!;t2gfDD6;$W`U9UL4N%Hb2~zdxY;2 zSzn|-Si&Kkd@Q9z%)yY0^h|ng!0+TEvlNYHlCV!o0kPiqQvv{DmQ|_^BkY|^Iu`d{ zuGo}`R|!u}me(2IP#axgT zvA?&etwFq%N6o3miqWi#ffnvNz+!-brEdJeQ#9(SXXsKf~L#OBWKb?zS(IXopBG~aQLl%~oj za`zL_`8D{$SRf>QhJiRgT$HjOV@4DNIS+D&6?Gn>7-eyaY?L;-kLJ=XL|Bbi@UPzC z5+vV^ut9n!)n|Z8{SpZ0Dy=LZfh9L{^OY-S?Qv5%+dC4={=L!QXL6hOm{g90e;v{{ zHPR-;IKL->oFDBaFYiBRk$1{Irg8X?Z#m#>?m4GYGCO4%1$A2iJrkGvz(K6#%h4eVezu?==zyJ|{G_SB8t;FCUC+%&EXaJ&;OFn{!L#rDcmkHixNX zp?PfkXGcef%eoceBk_^>0O+2?g3L<_)z6x7!`RsfksvymREF)S%X6l=Gieh~w=^hc zoH9xz43;f%E<7&i;Qx66Xr}itc83C3aMt5Hm!smLm^ihJzLbk2@W|KTJJzom0ps`H z9tt)cIFNBNATUn|a>*CH1Coy|l{pZicZmE#K<)>IwR^>!Ti*KhyvntM^M$q$#0VR9tnTA5pMm5lfG-joFfyGRdZYpl&zelK8n zo^!`L?*&>_YK=!`JeOe?MgCDItRgP8CCX`+|JwBWB^1!1h(?CJ+pl}MX3y>B zFW_x_&>Ft`R}fd*5*r>8Yd+GgLZw;)Y7nYZKvJ7Vdt@ zDD%M&QjG{2`H(9(Uw zcxD_Kkw#tc6YdwdE)FLjB|%KCu886fBmZLfv)U{T*sK?loC+wC9WhUYJ-gShVI+?H zerojoJ|fBm-k*JWJRL`(O@Hqk_2=qhnDufi?seZwJ8h!x%G39=*`9AqFA+4`KMp*u z5az_rc=?<`O>6rzYGxum1|Oki7o)xT`<4XOlY3PXWTp7G%gG*svE}W>!(lx43zCo> z(<}9em-QPs3543=uU`h5$u}{*NR!P6aJff`QigpHMuBTD(%}Di&yA=@zq_HBz7`Y! zJ4kETG)G6#)QuSMZ6ZGS>Q-=_>)(&;;OPA|W`4h@HJAe+c>qz8fa&4*n5CgK;nukG zN=qXwDsM@t#t9V-{G8qL4Dh+Zgvq z{@>@@Ii;v|qjhxyn;^*?T=(CPI;3~} z)mF*{5>}8yadwg zGUk()4>u18(#4*7(r0XGMZa=o-aq6KAg^t-ZCPq)eQJO9eSZGd%=lw2Q-o+}m*~Q) z!|P$`c>l4PpY~)K?{&>_!tYgJ_isOU32O}6!8L7_T{3DVJE+bIHERec5hfVx*Du0f z?OW_sc+>wiT#A1^@ca@^+WBcdvM}Gx+a)2d(UzoW0%!A^!Mqc#)8~nA$Q2WF5yy`Q z2aNbjs9UL1GuLIGLXh0h9%GDrjvX#2!w$h?;L~Gox1_=SZza#nr+0VRC~?hgG`N?S zyj9}i1Jy#-6DDWZz_pemyEVuLbp|SaWNcpHuDqZgL9#IoIxs!{5^zqP%7KXRIF!5n z*NJaKO6^CchXMp4 z$=S&KVim$eI#jtfXyzp)$sk$O3rW0&28yscNy*GbZx&?bNZ0K}VhwkW*&da28=z-3RD4M=Au2X&&xE#*F&+Kw z$2n0Y{qZ8k9|9{5<3BgwU)6i;mSDE;pLoQLTPyoNwnv4_b{pg|D~k&3A1d zyuN#RdN*fT(^Xz(SOa-vym|C`?c(zT=<1qiQYG43FYe(tATKQi;!)$tHFBNtt&7%b z;j(PiAoN~xiX&B#Pw|?huRlnE3X01<8VFz<9~}DKy8PABcXW2a&-?Uva(sRwpBN|8 z0gi;q$k^u7%5Ci&6#*7`i@bAENuw>i<5S1Z!7;ng^Q&T$EAH@RNf}dn#@gx)Uotoe z()?qSe@*DQyzz2>>{tMIs(Ewg>oTV6IF1+P^k(M`pybm{vh}}wAE*dCWVM-^|G;q-O8anqbXvYn09Dn4OHE?l+JWBdl+JPSXSX?5 z%&*xxBu?h!o~y3uQnzEdnb|G?hZ^e1RtLj|cy_Sa=*<6aQ_{4`sv%e~xx zWrmScFJ4Ef=f8qqL>quhojO)C+QrRbHZHxlm+g2Z-jYR0?d?#vKAzm{m&$K6bJv3cqlYB0J#rLTdF&XU3_WUf@bY9OrjM ze-nnjBDrM{@FTmdybVuYd%Muqn46*Pe09zTutOD^eC72O5srltOg6hsnN?g1n#0rx z9`iR~=y072Px2SN$mx~d`g2aa@t^VbfeG?O0_0vt>~FZT(MP|v6J?;CJk#g>(vu_G z#!&FCN5&U(`v{GOqP|stM_8~A#NBo(Xgw6G`S%^6`%Je+V;1$hq#hhmGjYQ;+Syby z(p-WNhG^bxf2P;FC*dlFOpTDH@1t3tKCOk)MH#mGYd|mYz-Q!J*e=$U;V=RO+9(CF$2brcRgwqA+fdUCfnbx`SaN%%79!TDnV+9x1QWlelVMzv0nJ1DQ)%(KxW8h{ zU6DOb?Hi%j5=9+IEVo>3iM@;Nn$-cugTl^(&#Lx15A#`L01@2L56Ibh3X%hlYv~_4 zbjToKpG8K;;2%(Y(?0=np`*`{(0XLI{R=J?R4UCPCl;oG;{&%Zw{eKXyMzLq{>3_l zIyLUe;FI#wP5ln{zXo_`8hsx78%HYy4V-~=U#A-wA}nA!AjnwVh~5tauE0b@(>UjJ zFSjJ{S0zL~x2pjg`XD%x69;#7` zkp%!#BlBa4sx=DnGL%KIe3m$UHW@Y#^e)y2meo+s58Ni7CQ&MJ1NDeR<0e7dalsF~FH^1O{LUjs=zj#v+R$ zq*#PTHI_@MnB0PS6>Xwslbc=bqM!F?U;Eo?n&)?EwoLPm&KOeUje!8ixYAMHf zz4V}=STFn?fbmiIwb)ASXYvg)BZDH3mk_g5LcOGaT9D2ch1GSWNAXT+`VpqnY_}EH z>f-@-t}F!r8m!X{tBPu#cv}E`9RoqGPtb^lxTo`kv8e+3kx55{F-)*Em$krgfL=t|q$g7j&V>RR^bGWSXjRA8S!3x|l=m?H zrJ(XieF@O`Vw|;ydc1>4kQTc10OHK|?pGbp@NDW-IZ#lVSMU8SANW9wDoE&-!>%zT3hY;|I$y+070%6WQU7tmEY&vb7z(pks(3L!dUR(3%T*|bn98b^GNmlSA z^@WjJO84I!)frPietH&eiisvPHt6}2 z2_lX#f}VMLh71hFgPep(_gBprv`Zr5O5 zrqu1ffE(4Zp3(1M?D3kcRRiBu`EdhBsn=0mNh2`{RN7COWG^VBzo)O0NU^3;I#W`~QIRiCAvfnKxnuDF?^SG(f(%mi%|KyMb_ zX~XJa1?`2|`0{N;0Hk38XwH|^7ZzNYE~%>#JO$N}F6X?}S9WVAs?t=7AR~9e_>^Cj zU##;^M$0*;m&-c71VDPgw=MpgX0CpfS0mcd3%md5nids$7-fLsJiO66>v!)V1S!RQ zsv8c5q@Z1wEG-dK@e7#=DrXc_IRL%##uAGKnCE2$FpS*TSmrYr>O#8coNGTusx`Gh0fxbr{@aw`BRpGv8El#sXP5p>X8LP&Abi6C{g}lV<9mY(c zABL^M%9)mn<&2~+^+60^m&^~-P8MkZP1{j69RBl+s}YOfOtb|eaP^dR-CZf0BQ^R~ zRlLO_XP3sLw4&3jDxz4mj|FFl@=yslA%!}U{)nR`1}<*)R6sd~mij4Y=+N>g}LdrEb;R?&ap<7MW-<3NiB zXsN}Gvi+}^Jz{XjNQpyqKJ}RVOX2V4dST(7EZ<@L%|f~~^|Tyw4hw6Tw6&-`#=kW~ z=oXg5dW5>bikyO*$?R+5JW%MtH5?T1D->ANkUgucnU9|X{}^VizLOBdQ9RlwYbhqP z`+~@C%BKS$Cj^RCg^~S%IAZ&BuW+f3#$aRDBwj#xC-yKmYJQ&%s9Z>^Sr2R4n)E`v z640F0BTZFuKdoKc1xI4Oe@l-Z4|9jGM1Q-(;$3)=v51G8SLXyvUo@CRQs2Ia{3acGdC!PZy6*XS+Z-~i%6Wk_6V=~w42G(h=- z+cGBpTV$WK(?~O=B7r>uU>Gnrs5j`~NQ>s>|27)|WWQ3lqOR~> zp+f=YIFX31uD%(EM#-X_=4iLBoIAhBOK+ZYQ4)65W=c-TA3TWt|tF_FE_5`aAE=E~#c z#_>9AglX`$^?f6&l2x##?VL^6rV|g?A=01;&>wX9QpJlDuW!H8^pT@z=00pcy7SVg^`-!mZYnt#W}*RHou8M(S< zqfFOjh&txJCl1708i-r?xe2A#Q44+mq4ij821poVjeWT@XZNZ0=BZ}^(mZJ5l%uZK zC%wy97~a^<1uyi9i=)gr=brYTL++j@<>aoG{-jUV=bY`ynuO`IYG;K_Ws}L}@*CeF zxdpqWVkX^h9^04WKu@2&NjXS}%E!Ezmk|zko|+Tm9`2%DTipI0RP`#Va_URm_7$|> z`U!w3#F*EYPsacC!La}z{FyWNKT&(N$qet5K`U)pz3NZux`HM}OON@3j$$1OU`sx_ z-Q^G59^u^c({?HZLXNLjI@KI_Hkml(wK8ZT@8KPiC0kpa>QGB7ceW!4fp%kXF;w`jLnwuf{y{}SzyYY_ z%%RP~@b{1iP;-ktW3!=NMtU`_lDHKc*o97?(oNw3@f*yNjjlW4(EOzrJ>o|?5YE?}R17jWS;W0nBb&tFkdn!pH}N?%L#%8aMa;WzER4q?p>Foa#7!26ey zGO*Wy@pxP5L0TBT6goVf19uWTofXwdU#3EC(X&xz@g)Oz*v|UX>#Zq9PQKd#{Da>O zzYtENyuJnMc~JykPye2pP&(fXtf^fc`vG9n;vZ>C3nKJ6`IYzfza+fIBg0oo2G_J< zZDl2zY6cQmwQssXV zkPOr5WMLErqkcuhqiXcrXUBy~QUtkfTT~lzu1<^XAH6Gkem&WBv(wW__?%NBpY)sy zJW-PDOgZzlK-*4vR0o1$QBCD=rlhs9tb785!-v7msmFGf1sk0`tXR3M&Lxg3LS}$B z@-@=}MZRXA)F^S|r1+>$@z~R)h7xch0hOI&f$S>O3ZN`5^fsiP-N!+mPC1d7mx}ab z`;$D6tfcfRdL zAy(OTXt3Zik@1DksX|nbA9S<5oHSKSzHQ1=pT$!DmKkW?!tmeop>(&dLfJGIt4HY~ z3aFC=}E7 zPvzVCIAQsYyFps+#Lj<#6s~yUbFr!4rTIoq0{AZFf3*Nsi8R)~c=VjNPRF$YVFa%F z_XTzfSrEJzghxpSy>1Ie)2J@nK`G;Y2kx6kI9)zRu6zaHMRvlMOVy_rlwVd9d z$H}aOpMw9b5vn`rVPA5=?xjEIZqziMaz5V%Jb;a6%t~A&A>DAfoCe6AsqqF1uZ$|J zdu5Hv-QM_>CJ@nKd;=V$$=n}wUb7z{91BEsa4kBdo?MFD&HPc@yrGtM#UZ}H_LaXX ze!2p!kjB<*!e~ev-a5G`ofd=NkFYTju#KJKweSa7kGEcm$A?slXrMyc)t<484<5D9 znwB}7gnjPO$RGAE+GumQHZZ#S^GZnsGO~K@)>u4fyC&EjrmYYgBdr0BEA5~bAH3YZ zL?;M|Vb)E6F!OzR`If;4K8~^a`g2;`yg*zyJ!TPZ0(|l(FnmSg%ECR@=gQj*EJ4W{8ncCx0fTIxn|*bYUwVq^bye zA{XU9Q-J<74N}AoZzdb705D%{>B7)2_O6ioV3xSCZN;tv;9=U4gE@9xn+P^fT);KP zf<{9)51*@Dr`(o(WTT7iFRgARzc*?8detOV$E(>u994d?enszC{^Xi^+zu%1i)p8v zg4`hrM}k=K8c`2sVZ?jMXvgE0E0FcHN$r@~jbt5nvG%JH-EO-gsOHTbbRDeP$qfM8B<|O1kg98%#q z^PPE)SJm){9O#9r8nT>+Ch;km6!c0)qP-#G$bmY;ZNRZs(r#F0h< zwf!`t-Ahz-Wl^u*sS&{{eAsV{|2M%o7v7UQ%wFT?tCY7bIim}s&4{4zj6P7{isSQ5 z_5Sih-M%yNR@6|fpU8oNx3SsdoBQfTb3>-erY}%wznJDdRfV-qFsIAV=6XF+J(4|zc8LecCaiY+Bw`%cpKv^%ijodrnoyd8oD4gQ&m{3vmZy$zZyhU_f2>fzX?9*2j({*X-KyXOzD(x?rH&o>g3O!R?!5o zq2h=}siZcstvPMg3YTYNcM>-?)i*;(24kDf*_GO=;U5*?g?IbE;vbtmW9BZs0@&gS z+q{DiqojbZ1ySTIa{mp)6Xcvt_|TFRLl+3I$iN;HRF4c#y*J;rv$~3~b9uJIrZhl& znLj-xz~fBI(g{PKdoRU?e}w8(A(h1bg)JXX2Okr84_Z9AfbSKOoVlHd1(@a+TL6zr zY!sK;ro6mG&BWPWe4kUQk_i}P_E!vY5}WcCR>_ccP;r>q(_9PSNE^OBmeVVxesbl^ zzuPaLK8$qlVrz3~9pVJ^U;@upXnB=kjc{~r>hM@w{SkzbY7<^l;knyt`$!nT5l(o$ z!1zAdf)m?PVh6yZxPYX;h->rlRjP>;*OFAvZm4cBQ@&hYUu-gd=}_b?lGBZptY0%0 zGkmqImWx!SMzbT%`l&VDfT|gQ$-4$a*zjL{9!DZqkZGzB9cgY{nl;4*@Pk4neMh0E zk&l7S`D(?HKC=v%s0;Wxfb^`^2Kk*(3rp%OAArS^x>bX+fMMnrTtfDE_n=^vZt?|< zKPl;pc^##d7PFkqxl)~Kt;IEUvBxjImM#N>FMHz?c2g=j!#4D#x0~K9gJMC>qF1#_@wzYe@_}~nD>*3k6Pm@o?9^ph%7qQ zep0KL4~5u?5LqJ7E*HG*sWj)GyYog!Cjxj2fj^8(<=3on(K09HXQb~Htqp;P4T11_2YcaHA>S#GrCHWZn z_IV*cvFv~OSrCWf2X2nwGqJHh1raS7&oJdH-6GkP`u@wCb4GN+x;RD$m6MrB@g-6K z@}kB!C35QNH@xQC6Dq={;nSm-tsVe!`yZ?ynv~U1JBsf$rU`<~Std?cZKfl|_h0bp zZLxC1rSW<^QNwky|Gg~nT8MkcY&U6Qza(S5XW{tFc!bRM1c}tdor!B^nLmuSUNjkq zAW1#e%LdNpXt7%#5_sWAX9v$*mNxteef8I^JicOaMFX1UH4|gY-zcpiJ>k@N8yUk~ zA4rpIJo;j`Vm(Ad*zbXsIG6~MxG*=Gq0Q}VZ`YQ>vVnn&b{)8p)3bF5lkzjg2WO7D zeOwWJWx|&k(&1jC6I1~G*Z+Ue|2PiX#;Ug7n2Li3t~vNKU;ro{ekcR5vJe+ZcE)TA z`U;gZrqgMQOl#Rn`{^)do4Au}JW(X)P|X&`lUJZgO5>6**HV}(n-fk3T|Ynwpq2+3 zeHl!AY#jIkLjsr6mU(OEHfkxR*67!Ef#{odip7DpU?;6#hW57`NXoE3Hxl<~g&;Vg zFQ*-ca8Eb9D!qar8F-0OX_qjP;{!B=6{mOte|S@8DIdm(sN$IC#1-tL_l(`RrCRKU z`v(4HS#9~}71SqjoM&6Gz~RpziZ0?&L77yw;lyi)PwJ$QYJCtE-y4*o7AB}^Y6mnm z9v_bje_yYUd?@<6zSbE&tdWLD{I|=}#a8xw*Th;*uGQKY0}rPcHo7PSo8gF%)GOgL zyY)BNws+N&N7YuM&e60jQm_)#AD9^$$fN0iA|7(lMH|5`UtLn z=sFIadH<$*Ur835(n?N{@N?<)9@Fkdt|d*Jn{(>6DOEf@UO=zEK~>FPMY%L=1~V;R zk?68VxBphxT1-C?dP9cCY)8zcPp&Cr=#izs+~2;t@vTv1ba`6zdPS&fx8C19y74rM zteK)U9x!TG-L2c)yDBF&>@rxrfcTKO=KY%{ES+jsck_ri6~7p1Oe`L#w5abNg*pn1 z&+zhtexUc-cXkr1Sarr{@wLvfZO}2rxjjz1)dn!F1k zM$G%IaSF{3lB#!RGF_&eKxIs;6ZKrl)aB~|Z$4x}U<5i89GmI#y45$ItsJ57jN`hM zxbNG3dnFsf%t*DgR4JW}{%(ry-BPM@4HaF%!_f*su{X#_+OCxb2kwL*tSg(B(|03> zw(#quofa$U7o$cCy^N2T``@(f8y16bOJzv>XwkMZ51>XV5}p*bt12n`&P$q!}4r9Y$pr}RXg)fy} z45=;GyT6%mzq0Tk=N?M$Yjgu^cCQcXzR_?tKxJUGz8huASShZN?-t$h!OL&q?I;>W z3Ot8GiyrGsByj`>rQ*8#2uq=jHZ06bB9=L|t}}>C$k-LC^vhMHvj$3)>md@qS=n`N zrT0MW8Jn}(H3+XF^q#cX_^k(#-+XrfMlg&L_$}i#Wk@r;Lmp?vb5{~@84!%F-r_9{ ztM&W0GvWozMh!V<)31?S7mOJv6a{6zT0I(8=w0(rhd_r@8lz5|q;}f8_pTep3oK-T zL2^6L*7o_oQ>~B=P>|Bl&kaU5KmYA`!J}j?{3J_51p>EWx2QlV3XAO$amBL=O;H*~ z^EWn)Zw^}Fva`Xyo!>ULIM(^@z7V*tZCXOgARgYQlK+8ALXmlQu6zb_7CFvCR z;r%>^(!$&qlhV$x=IGit0DdBTo}BA~k$Qq2uyOeLD)%RY5Wmw_t5wv3j({CzwmPdS z(o@9i6X;HRici<)b~R}=W&&ZayGuuKIJz)5FJD0rl3+NyTC(l>>L41@uC!b29x4eD z{r+tFF8>{ZovJp8=2@dDi+dNB4<;&F0Wr2N3mLyiTrDscP9Gv1YY)l^bt42n2nQh1 zGp}FHkKMTvXVQJ3%1Umri`DGf-}Fh2jvRN%;myy>BRxXJPviNxP1redxj|&&5Q+YC z_il7QjKnKWD!1|lO_}TiGpKNtK_t@8P(GSpS7fAYN^+pJ$GC^1pweZmwbQSuZH!cL-mdO@nBCu87zszkJYoxz@9*#g7%bK%S{<9En% zYm%h&cDKH}_Z_enR{jcO5(2!28_S|hPL>&CSGD1dNHYh<<@ zBpu{(q4}}fJa4||qhryAGA~JNi3PGbYlTEAhvZ};S?u~^DjSv<$e4L=4BRPyb-n0* z>b&aDhP6PFD<9Lv1rzPd=XNVGUn0~8-bhO4Q~8KvC;k|aM@-?Gwnt#bhQ&9rt zgGK*%3%<28{z+>kgIH0^p0s@F?kwBTn`?C?4eh_QQZ#Jt(mq&j-_?N&_VPBA&_^h* zrT?Nr5HOcSwQ!cQY)k(TK|j$$N4CjQ{)CAMRh}H}RN2!;RpG9x6y$2P+2di<3iAbW zTkHq+$?2J12zeVIy>w+>9e&MTS2Yv>Ic3=KcK+@jK` z#xSly7z+|Be(GdjK2LFM@-14%#5}Y;`&ous2|YvwG(13Hp7DKb{h(Dh=sHCxgukg8 zhW~~o=$+p3Y?F}!L#48E zqHY-Fa6z(=_R61fYWl$!0(GdCSB8VX7{2->=*&x39?Ec%yjF`P9^*2@C6=0|&u1Vhlj~Vq24RxVU7n-N~;+??r43C-JF?RNAYl zI4Ehl6FRn9)sx2QB=2px&&I`qcOUcFv_ufIrDWRiv*6dwj^%(S6@L0YxA>!7e%I1g ziIO&Rz4E?Y$s@ClCL^(eiN2uuh#rj0ju^;I3Qm!PIhu0?;{ato{rP^?ncGGbXI;3kvwZ)P9U+r znO4;q+3e{iv!h`j{^7sRuJZZwXU_dQ&@LIXr^z`_NFD;2OiKl_@bp>A17IoZsE^!$ z&CxW6ihr>a=M)*q(Z%Jhcj5&(*2HH=vGi|!NGcF0C3RzaU-0ZM{jHl`lQhGfSBp}z zd|@|`4}ypGzAm3|2%p0x7FtLvf|7#W-9dk)sHAOF0@TI3Z;<2UnT=hq}jizRjPED1j(SIRKNY0>U(xAfhsPbM_=3Lx+z)qYMfQ5Qb!pk#g4mP0VY1My+{(RAk0&#&nENvJ=-XS#HYbNuOTdXi;mdl|W;u+4%cbn13g+_~|#y{C%g3JGUv&1$1iTJJ;ujoQvYVxLcnL zuIVen^Iy)YBQr=Glvm%ni4Smgg+tdhLJq%|q?BF4{wCWf%qdfF5Yh>Hh#Nkc!Tw34 zeorii0^?dN2{&>l<2X9D+v8DLG3wJC_0T-=^{yUA*R;fdtS_F#xR=TOJO9k?)7+7D zh)(=QBx(f?IpUAg0=J5bJS>ZTCd;vR{q)^xMCi{58j(JbHy_>#F{g#4+n*#$kgIHz-`@&thx@FW#no2M9-%5FFZ9HC~i!|CM$(qg5P{DC}9?UAk z&PQDB0?saHjN>O z%>*I@{*&AJkuNa~jE15wq7)Y$^mkBqr%Qvy;<;w6=u){ulXt#UH5{{9JDCD*HnrIV zajY=A2!Wqt83}x_``nTv+1?|@xIc(DQMxlfBgS|3nYPOBiouZ`rtgCAYQ(xZ+=Bcop=YK1q=GmRlpgSd>G|B5{ zab6s&R4VekmCP|I_;?CW`oqKSa6!dy{P#R{HpsZ!@`RbwS#vgYg#6O7!6Vewp(-hd zG0ZxKjc;aY=`*~-kKv}~_$(nc$(@9?5}AgOD*@BuPm3ykD+6r2gzx>D zTU%RgDVLRY_OcxRByaO_Ez$}s2j#HsF4H{shnJj#8cO#+**G{r4%q8M%?6`zwkyiZ zJ4V)KXiOPAv_6S=#dBC)tST*ZKiIQ;AXThF%rNNi}Dv&TRghkmAE}eHt!&&xf@eo;_*{f(DCzo1hm(FM1zYO`4|1 zhnfombWSpVwUM{sjt(e&gcKTPXKyNcy8H$I{xXp>KM&s#hen1ba zM`hbOBBQ&rRlAk+Mxdb-zM7ll0Eg`yqs0W_Wdo|zZc&=S)^3_1>Cv94B&xs(tCAoa z1p_#f({8ybmL?a(zHYoTU|j;1c6Zmro2TU?;`hFD^t@eB>$iUV+D?E zvBH{ve}_eaUo*9hbjp9{H<`87AybU$CAWorIeB?V|=uKmL2_2lk&%oEhd%zkr9J zLn#!d!>EzBFF5-&!hUq=ucWEOuU{EeB#_EBlw9Doe_oF8UA@U&vpNowZOO-=7u zI-jUtlhlZ&%4FH#-~5m&m&K^EDpw>-&ER=)Jcr8pz?x90s9B=MS3~7H0r94u8NDJA zZTf}klgR$Fi0*b|bYp$+Pj=)f^&{WfUp1y-pmykOkuOB)MyQ{zJ-He_W36Unl*mT6 ztcz#WB_O%GM)lF*ol3_G(K5Bdth7S&%0ljpHxt+%A4@=;qRHW#?|Kr%_Hs>t7p`KS zTEDQX1d)knbZqzHm`}a}_^%a1$y20r zWDSe&Y` zq79jem)}g0CTDDps;|nbhw1-SU`{!?h&6+^u}fV7#)Cla#GPWwYqj^hIV(2b+_by+ zdS`M8h8k$_$o8v^ITKhwiokFKs$hHRn$&3j=5Qv+& zFQ*|Id#9n-S?x9y6!cG7Nip@L)3N-vvEd>1Z2ND8v)#)kSm)MG{HAByzrdSwG8IJB zB#{tsojWZUzA^IX=p$rCvqq6#j+>56efPbW(Arbj3@qpE2c_E#_0f;}uE1RTZrQSb zr(Vrc_~4T;@{)OSC()UDaO1WFPZ8OT-MtKwcmHB(vTpfZ`1303q1@dHcj8ly0=T}) zAj=EzK*RpK9`H?(bVqKJS^upLixyRaIbdB`?EGiNq^pcLa4WJ?5MY`C%gCJ@1T=2@ z??Uo6mIX>#{`V$3Ks&Yn{Tn|CFZI8-1MaC{fc;A{?d9cV_ml90Syw+TQm+x~IvMam z?_!fZQM>0k#1o${CA#|#?77xkJ=xmqdAL2m3OX5elmB1d4falq`C+(n(YZnZwM7>WAcg6fa`~QF5uv`AZxBAvC UGL}TPKmjjVDJ98jaigIB0Rkq1-v9sr literal 0 HcmV?d00001 diff --git a/doc/html/_me_bluetooth_8h.html b/doc/html/_me_bluetooth_8h.html new file mode 100644 index 00000000..b0f3e9d5 --- /dev/null +++ b/doc/html/_me_bluetooth_8h.html @@ -0,0 +1,228 @@ + + + + + + + +MakeBlock Drive Updated: src/MeBluetooth.h File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeBluetooth.h File Reference
+
+
+ +

Header for MeBluetooth.cpp module. +More...

+
#include <stdint.h>
+#include <stdbool.h>
+#include <Arduino.h>
+#include "MeConfig.h"
+#include "MeSerial.h"
+#include "MePort.h"
+
+Include dependency graph for MeBluetooth.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

class  MeBluetooth
 Driver for Me Bluetooth device. More...
 
+

Detailed Description

+

Header for MeBluetooth.cpp module.

+
Author
MakeBlock
+
Version
V1.0.0
+
Date
2015/09/09
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for Me Bluetooth device, The bluetooth inherited the MeSerial class from SoftwareSerial.
+
Method List:
inherited from MeSerial
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan         2015/09/09     1.0.0            Rebuild the old lib.
+
+
+
+ + + + diff --git a/doc/html/_me_bluetooth_8h.js b/doc/html/_me_bluetooth_8h.js new file mode 100644 index 00000000..b33b4b3a --- /dev/null +++ b/doc/html/_me_bluetooth_8h.js @@ -0,0 +1,4 @@ +var _me_bluetooth_8h = +[ + [ "MeBluetooth", "class_me_bluetooth.html", "class_me_bluetooth" ] +]; \ No newline at end of file diff --git a/doc/html/_me_bluetooth_8h__dep__incl.map b/doc/html/_me_bluetooth_8h__dep__incl.map new file mode 100644 index 00000000..7f94ef62 --- /dev/null +++ b/doc/html/_me_bluetooth_8h__dep__incl.map @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_bluetooth_8h__dep__incl.md5 b/doc/html/_me_bluetooth_8h__dep__incl.md5 new file mode 100644 index 00000000..95645749 --- /dev/null +++ b/doc/html/_me_bluetooth_8h__dep__incl.md5 @@ -0,0 +1 @@ +4837af9cebe46f8e5d0c82643eced488 \ No newline at end of file diff --git a/doc/html/_me_bluetooth_8h__dep__incl.png b/doc/html/_me_bluetooth_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..5c582b54de4b7fc2b5c2be29bbf70fd4ae0190c7 GIT binary patch literal 13510 zcmaib1yoeww=X3qDI#4W2qN7*C?FvM(%ncibhn6z(ntvmNOyM*-QC>`-8BsH4*I`$ z-M8La_nld5=Bzojzi;nv@BRDjeS$y9OW|OWVImrFT^a4pn;+=|H(*A;{m#%a2;r*1^eujm=-rKjS&prH67+-&C zNae(KkkMj&BThounGkiB7S``3+$C^|piI{H?%x_(vrkHQl(djVUBi)kj-fq^Hta!M zQAqqTb*kcd&Py@2RJrIz5G=gXwZ6XIwG8-7E(#sO)<%M&3JT5_G?xk*r#!uzQ`o-$ z|2GwepY_NuU%phTjb+hx`AqVSYZV;SZZ?spN@-vHPC`N=Or6*j75L3?2sFHU$5qdA z;38e{d<(d<%8N&Wz?GaC7Gqf)W`jvJi8RK09mM(>#l>s~roai(RPW|-p5p)8B3EAz z|7RCJmlM+oxaHq1F9e11zfO6R{#NQge`oamKc{D;v1nKA#otqc>%}hOc9*0t2!o7f z)q0A>fomkC{KFn(3iU#MU)s{~gODi*wA$ixF$IranCM^7u{lCmWx*^(n2223i|hq{5>SY zoVR}>>=?M#Ni5z*+Da%?ex>ZFDA&@91|)y}ZvekkE-G?rPy$PT8)f8v1O$JE@pqP$ z95&)5d4BVbx7t4l&YAnV47ljmxVdD32@x_C*iwz-U8Lmh!>kvMJbsu_#$2N;ofs>R zNjn5f)@z5Nn93gl^4C`4Hro9@-<0H>{eat;I58ifKU|YgGq)O4d$afC#sSX5%O9o7 ztXYlTmvhY&h9coN;(su24xUgU{)HUUhYr;YavY1t2#Y&zM zXlPj;fC}W=QgfQ25V17jqn&k3DdFQs&SpMXU&c3qJx+e?kKM=n{X@tE9C`}fULnnt zcILY$taYMEU;Q~O3sur$aTPu$^uFJ0z;zSpOccrBaC(Lt#FE#ek#bB+P@c#A=E2q( zQU9urCo8j!K~5wg0kW>M{4oHE1%Jmt_u?ob*_1hD1bREvbaQi?YdGY!}9yZ&(}9YFxwg_g4R`KsBqdPvHs5;Bkbb{h)Jvus!ZzEjY>8u8twy2IqPq zm)umh?UnSP%;pp!>2{@KPb=pMqxq7OD)Ec`rQcSt6LcB3sD zR2(lD^Pc}6Eon!d-K1cR&X4eI0LJj7T(hft%Da@dK_`9Z>~J5Ks^$UQupX>uz*0jF z6xIZ0GV+;b-N-J6{(1#efQxXt-zEGDc>q^1CP_;CF)bUiQ0e$U@%xp~7Dod5k`2eH z={|AF;=(>(oPME`z>sZDQhfw!r;C_R=y3+QHUY9Wp1>TvkN37W4h~LrvR&(wO!y<| z2@(p5^^G`v(~aJkuCw?{C&YG;7#TsycfYxLftGJqA7_T4Ccc5!ArTH$LgfMJ-oEq_ zkAC%xEQy;jIPVEFw2Wy5%SlMAzy7Q9S58xcwr-zM#z;fJ8czh6zH)Ja^@bij%N;=2 zL*#5AEhJ1n=n?b(aDfubC9v5FPCo)T;QQ^|F zxL=tkwzXv7;nIcQUA{H%Nx$D;c{>_~D&uK5cj)eNiWS&ghA;Se(nN2MY3}t?t9TvQ zIm6`XiS3<6k#Pn*sTwk{KBkZc9v%78eonBP1Vt(+0=@f0e9lw89KXLqFLxA|BKq{^ zNS~Ve&$j@ z!uXPmhr}!#`fEH3mEUvJm)2BD>gsFf;syC$Esg$9V5x>GrUE`#>FZ_Dc{Ii@Ka;z) zG*{wL_jrybg}1NBS85y!&H(bAY4<_A8Px+u`9j@0s(>Nly2h4NA-3A%rP;(Qqd({J zvvoHZB(|WUq92hJIg)rt2mH(Y-#BQlpQV7Z{e540Vet{~PL6iN`S5``~F+intJ$FkhVPkcR#qC!O zEml8m(uK(9h^Kdd+}3{7RDN16b!md0(RJIHiJEeY*xqkg=%p$P{{B7W)n8?ke#_N& zq+;hWKBXNKr?~iis&kF*V22`fP~Umcaq`lyWB0~d*3Ke+o#@LK$t~=7LmICl(H^O$ zhGE?2jty1kcc74=D7Lr!i>c(OL?=`E#2RKCU2i(0z`n|y>uaVu`$tC8&@&a0_%e(A z3!#4aGrRbRA%MHOZ5lkPca|jd#!r+>Xv4*kH;vx z?1BZBwpE#dRk<3nd>*&UAk%fy1ul&E*i!e!ZJqt8(QKmuKs`1OQN6py-o&!&ZJwUo z=9mvZR(#LMHXSMy3+hG^D`^TRQrEfboXE9YXE zB-H*xLgvLv2}E#l$tQWALPm&4bf@^@9fWpiJkc0ubq_aL`#{&ckyc>Q?qKhv5A}*< z7#kbKdDH6*@~EnTqN}gMDSe8;w+kG?Wsk0`JagB$c$MPHH*>ndzq!iV+`B>!?RoyR zs^-+%lZ)#I4hNCVkwuFk$Z~Kg9{+k|+a12=cxAY3ec~tg#B8nCbWXdULu##NL}Xh_ zb%rq&cBbKgIHVoaGRKPKO(7xfLm&o+(wt0Ukf zanA@9snDv7&NQTpF|0A8gMRu%i&^BbbhW}sNn zar?G_h~f(jX2veLlU1pkm*{Y6L#V#SbBg!=0UQQTOy?bwZ>z?;`ZFv0L=BD@!!D|k zUpN`R=kLDP55pI7Ejk_Rzxv%WA)bsHg6yhR#W#nL@+in$@G&GgImET?c-(`(Ub}+q zHEu|ysGp2u&{16;KeyoG?5eXMX+h5Nh zS||~h%0#(|jHYnGr&)l7f}HgR|Eh}==LTW^C4VyLmKm#-&>Xqw1529o4GfDx=I!^> zKNABN36WH6Derf^OgQX+2(+MhVppBZhEyaLsiTwod~5SK4ZrucT_l%w z=!KrqEtU>ubCVSJY>k};t2tx&#T~u=-ahloPcHxWR_LiMx6q5hxc<*TcMT_pGj;#VwW4N#cs0DOL|Sa`Kl@{kO=7kbS|3+mOd$iM|#M-{@G{3b&@sD^uJtKycw znMw{SKonbaOb|toR?-!s2_c&?W>4H&Y9G(Km2fU{(dfqIb3yCG#hd1^@Jqh08oplh zBm}H&`|l#`p>Q{nQ*qpzQ5QYa)Saa}@oQA0dyE5y5AH+bnNZl+ha82U&D zLiU*($r_axIg!Exn>UUV2%D1|*=U`KYCJQuMm`4*qvNm65=-Jk_U$KJHL={ks7JYS zB8hsOmRTB?a!W$Zw1IPp;JuQ$y}kKjPMB^eptH1S9Ui-L)dA$RswBPxM;!qzSFj1W zi%2D^`y%JXqad`DPWO}m@^~TjO12VeQ`@=GmEfM}+9*FF$GaqRGSy;%fcl ztF6mgIe*`5qK!DCo|J5mLOgHaY59(nE;2U~h8-m5EP`QdlvR|Alsz$G2HekU7S=}b z^ZG1bIWZ7g4#nkiL7EdWkuu-QQ7AFqIIj||B7Olti+2zC=X2|LGTyZ}B|T@0l|Bx> zU){|z__M_mTBGsd5|t|rlK>svKHk}K}w2Ur;LUG!X5H*E6af5D(F;?=pl4gp$DQoCvuHEs5|+VSnQ)ej6Gu41Z!)x{rK%8p)fjYuf;Pea93LCP$H*%)#v8$`wB zq1@5#t0gza7Y9DOZt?E#R?dN=EN6^o31IPHNFJV{SE2z-5PBlQoLnk6jmK zxW!Du$(QIdPLsOe_L=gC9)c5{4;9bh_B0Cok)ie&0qLqgRBLC8%ae~AQT~&#Qz+ufhI<@^>;s_59gRpS$!zse3KxQe^;nMAUs z`8_)>`l;)TO~Hgf4;E-g zFgQSBi|&J0klzW4PX|xNK=ZrtPgHid8vigaEjueP2rwv2a}mcU&7QFja@8(IUmRvv ztF^M>M}9~HQcaVP&yRS`kj+fJ_?sfkyG7UGc6%jp9uTYM*rpHps`zojvSis-CMJtc z=LToEbXWG7A@i?e3Z7=?*`@}K&2CJQ6reWM)df%XHwQd05Rle9!L?|n#JyaSME9gB z@Vyn5fZGs?=Zn+b2fpLPWb(JY49Q9MC2PfE&8!Bl_@j^s!4J$*-KUbvDh^+TQISRO zjiMW$Sq1c&#|J$v=i*(k8cxS}`toJw0~43g{*AOwZ}@}ac)B)i0Us3#eiZ@ITc)<00<+l{c<8HT-;26&-n-nEO!*S zVNd6%92d^WBCa2?Qq(BMpnmz1@xg~UXq-i)DC!f7sGgl|{eGR3fRofQlKlhWr)#P> zV)*?okj9&>`C|%7Vyg)oKIDz02dQH6kG0sx3b-fb2yn$x`@%tKl%jRjBXbjqKz<8= z3ZpvmUd}Z^#jMiUgegmwAmSBT*Ce(&1$^m|%))dfd@Vc;a4Wyq?%Z zopG{)1-l*r8uvGLHq}E@(8!xNT`a^pyXOoiJ$fA7A!cn6LCgmGZcpq-iHc9lMV2w3 zwv8#fR@^4$X2qvhUR8{d98 z=Gy*tr6P5i*>2*Q)`wzUUnXkWz#{z-Mh_3XU=I6?s3u|HuA+0ky0Ht#dqh)T5x z6gOml(;BskLA)v%O~}&bYs$YNW|+np9W;G&442<+^C2><=zT7=yPzX|R=*T}x_kC) z#ebySS5!g8*neC}CW!yfF^uRI0b}G|RqUCF%CP6*8*>=kjLMgdY z^mXR%cE!QP8$X^r<|cfI1u3g`1d26|sLSZ0b{g8Y^ZI=)k`NC=Vtj8OQTp{#G||Qf zuCxHB=qV8Kb5UhB(FQ57;@1W#xCSu>9nCx}%OhUz&4iUwra`+55N}b1ES=F(zmHP^ z;6c}^_WL!(A7YZcng=^jt%Yc2cY{7`Qz^%3T=1_O+ zbgqPTtF=GA|G|ek(%sQ^yhYYkjitObttLKT_IQ~5S_Ga)D)E+#uW3BHKTGAOIhlXV zcdj|vXJz-Y-Gz*-kGdZ!=CAE#zlOuep2AH&W_vIwUgbPxkhPr11{;`;*5*xOp~1@k zW#81(3&T*Hx`YsB-8BX}20IpctRq|lCBgY)zrkZA&&O%Yj&>2U-!R=DGA4o&3)S-T z_St337|je#!|?AaSit-|%YRSqWfZYqAe?T^N{9Kx;JYI43Qg6dhg@jQx*OU2KZN@% zkgqXgXMsYvo1XB?;6o53W+!%=4ZT}*H0OpXH*fIz<@0nkTU zxrfK42~61P)(^#7{-I5>&*^yF#%6HzV$Z4+tSI)S)Dc5S3%NiY=l31<5HZQ`ju>`S znD&@eUbPsWi_ka@FwOF}3BKv@Rj~3a&65&+vTt4(S9+@|V14&M93TXIaQScOWxr@) zCzxx;@DF*_%#l=I+8jmWQm&2)r?ZDM>J-0db^{{Wb~}Lp+hcw_em31Cf%8M_G*1o; zh<^@0SII)MjbXQoyg?!+_s{N6K%|g<=TJz7EOnPWFv9Su*?Aft>Jmf=-g{wU_Gw7I z5Xy0(1>oNniOp|=4Ni^ZST*y>GV2;Iy;dcB{umUx35X@>g1uyEd%Ia2KS+)8LgB%SF`^L9i>VS ziJ65mzi7VvEa6*JJ0#eXK;d-0{%(k)zl7zO`B&yM6VT(i<`g|Sdm?wNYaJ?N1%O&SW3W+2k21C|h#jB*`)PiE zgxL}@WYh?aHtx5e8zivbdCiM!&=uyD_VRjrf)>M1mt^koj1lsjm|5bh8QwLsy%Fbk zCSIRXX*mZoY_9{ByOmSV#&b^n8FL3th+g30p04*M?&EPZp{-1N@a4X0g%K?LdRwF_ zr-EfT9?N#Qyv=t+kD`Tg#pRk6O}e^8Z`V##e7OPkLW6}(VD07GS7(zkA6)D%z=@7x zCghkWmoB@p5w3-Hyu~^+3Z0LKo8K>TaV+&IO2NSxw*4 z=I|3QuyeWhi-U`C6hcnw@b6;DAF*l|(pCmkinn#Ts{|>_CTB@E$GwJK;e5&MCvqGA6JnUNv!#Pu z4AYE)r9h9TaLP2(Ge59#wR6CDmzlXK)0t=MZj0>?oMFw?Y$f-EuAX^{R&nS{1rV-GE8_doF_Ar9bkWC{Rw*TPree&i}7rAx5Y=L@!k;JW-x&y$t}5PzikyvNTQ7) zUNzvAl+6<*m+_GI{+a<&*N{3inCF`UnMRr{@x*AQ#6}crS2OaGg%HY3YX$VZnoD%Z z$av09gjw#C)4rdvXo%R50j21DtMdgygIr_~yVA-2>Cr@t+=a@#O@VWvu1{!-;BtO` zqWQ#mp%btSo1NEu*BX4!Q4l)w`=odPO~>pCZn0=_BN%!8Er?wZZ!cRLPgj!dA8dH> z#F~b7o%Hb)oH%hWMuS{f9$PWVol2?=(#AhzGG&FmKpdk#&5z*? zJ%Kk?9sZ6!-K-)lIjrtLqKhX7@;jB-+@Z>Q@-(I3DQqY>)=Tv}K|mF&ugKBsqi%oH z`67$2nNxL(qUN316tR_jb9ps$T#yQpby(E$KIzJ!j{(l$?>6M!=iI;KUAo&wB8wHf zqf0fA2Ezdg^d|?OyAC{G>Q>bmwI3%0OWdr8)X^U+n95Wh$<7VL4mlhDPGum=-c97m z<4v|fufz{5$w$4aWAv&O7e)q_mgRdJO`en<&u3Mt*C4oA5XsD@#;H^WZjZ5ZaF%Fi zwBXb+*_-w!D|Z)b)hG=YM0m7NOw^cwuZMO+!&r>O1wq>O(8(yQCpg___!hE05E+U#P9VS_^aTo_}R$ zlV&-HRHSxz3bSCTWmO^pq$K_J*k%)XOet{#$EIT5)wxgarLbzoF=rYaA(ONKKFbn) zs`VwsvfFN>8{6J)F~LJ?&PqNz(ChO=XcZ42srvsw6FgdlH$Yv@7v-K1ru$HM0xV$Y zKnIqs2}McmNSz7sABOV|&rqMFXhBoG0LZBRRIW0xAcEoJ$#f&uzN>wet8gDrAk#VN z4G)E`gE#d^)NWTn>ja*H1zJ*wI;NA!d{4c{bDjPXJ~(oc27w-uZv5 z{Sy>2@%XqrS1#&!>9Ef#JZ#OJIE1U%^j9a|eA86`dS7JGgPD0k@%)xNM5nB_=Qviu zHh8DLc0{PvMc}HSRd7^BRvNYgtzyj>8lA}RZ_}D_%Plceb9eEH8mFA%RCwke3pdB( zuP-=g6#hdrnR#w(abLdR=lsnu^+spp`*y+5J{b*LrM!RGcm|L&YAqOUu0OWn#HwVh zAY~YB^W5J$Sw0QkbigoS!KWe-L0q1G#nef3(1Ar zA{KpM>SUA*m2dsSR0=0CydBt&yE%Wrgp$JTL4$A!Ws?_V79&BW3rU603w8r?+bkE)msctgz|s+WR+#r)hDgU>{0?yjK+xqK-iOP3`N)HPB>91Kv+~{3UaSKLr|zj()W%8%8ml z4}V$(7^}{Y{--*4Yr@gV-=`*yzhXWL!*l;Zm=(m|{B&uajO0b?%tnE>q8KU;ZlT#cr z%1zP+e14wF;LYr*l0OhZs}Jv-wVLJwvX{E!uopMwl@TZi!w196%xWvdV6}to{PWZ@ z$DBXg%!-eQTWx_rMN&TU_eovstNepMuylZUxrD#Z#bAOv9OC@V2ko!o| zc@i@6m#wcof&vzsmN7eRLDPsULR6wmTyo5CoAJgm*bb{kSoPNdkh}9p)$#&vj4oB& zUzgCadXn`37iE!BkPoQkegl?2eBr_Qp$S{seIr$08Z+?*CQPy@vyC8{!SNL`%jUd1 z_f9PU+cL)fL~6t^DTqLs{Lr7Ds8nW#UyZY`H&ATQZ6XsWCw>MkA2@I222goZMHvCs z))4z2vYtYZBqJ7Sh?UH=b8vVIM~V2=&h!jWkPkudbWit{pTX?gLjDV1T-ah2icU(( z&X@%9A0o+r`mXE=IpRAS!XJ7XSb@RPkxM>7fvBXD<^IwHD$h4Z~*#2 z;IZe482yiSloH=p$|^bAaI>krAage+sKH-TO6r@h;pW*RH{d(Ma`f>(c2qd|Il(u3 zz(2=ioPBQC+#(j6Pzp`<2sq4&UAoP}#F&ij*!8X@r*5e=2GSVI`TfY&f3-qhq;r7b zu(H^jEqj2cMe8g?4&=zybzGFwMn|F7??C4d99GTT>%bnu6O#}pAJXa8(x2it6{jvj z6t?-98VO_7Ck0K;B-3H13>9-Y(HS>@V`KM?p zdZk7k3J%`34-3K#a!T-oOk`b*kBkM=deea$2jo{yXq?}oOrkB)Gr5eB;uA;=xt@-1 ze40zfyU{NbFm>yTwLjbx@HIfhrF9$66Po4Wc5^`Q*`(5?S!N<*mV5EaxQ(sWhBaIF z$kOLD-|R~hwFu1D%f4UA@X@=YXhJ46uex!BZiCzLjOj&j=Ax}?*;n`kwFg17`>KHF z&Y!&aDq~YhCiNobKAz9pqnRl#m!uoht}{ta*L1#pOO1?I9k+?Me9e2DC zGq~X?n%8$H2K1oz?^X4&HG5fW(Z4EnKQ(P--_xn<^cDCt6lkjRoIezoSdg1u-$4H9 zr$hP2dz@~gEA{@RQ4xjyrLUI8gMf~=ey;L4GIH_+etV-LITH%36fmqu|9&Uq?(Qx~ zy-24PXf$CjpEDhT3{+T*^_F@v{sc`gVMM#}gqCkgr3iE$ZFze)T&@26JX4(@H^FoK zTJ-9%%S$s(-@BWdInE>q1X9x6+>G&BHdR?)|Gr9DLB#nY!3?4qwh$M3e}HW5(N_7f z_)3{S>*8Rc4~wm#ga9~|ps$h+?s&C7w89g5NRo)!YmV(apyd;agCdgatMAu9GgN4r zbcJD@TG;o%)AG1BZv3)fXfmEGDD@7HUD=kVB`o%cjv(n66rMMHbQE_U;Q=TxM68bZu;YvsB!f|7S5g49jU0=<-#Yl$5am zT4_T{;A_-rkYaQL{vgUK_g~{Kt7qs>AY?hPTtrc+IIV!BtSpvUva?!lA}h~w8};20 z^w39rQImU0&yz)6$Ns%$I8CK7&}#b`xUZ930m#_C@VBThh;PZu5jbRQJn);x$<;OP zmcK4m8q}dz?hq*a5P3Oce$LlY7&i&Tp&qiY(KTN;i;C`M201OM`}2b5-ROpU7m3rhl`9|Bb(G;Iy*_WvbPA+ zYoJyFiFbMFD7?JdzNqi>&5=#;Rh8t2p4Y>sr2E0sp0 zWn-CVx@LY`3g~5gffPa~o8gJgaD6+)dAX=(k5|Ed4^MyC{?pX^uqz$&w+RmDtpM5p zK0nkn{%tA=Kd_zp|Ftzo?s;;5C=D;2He+FQPGK)ky6MT@=Z2w%z+thrmvH2ImG2wdYsMmQ(eNSNGc43;StCsrb z<h;dT*{*fe1bSyMf`qaKmyX|b)KXhg2PQ39?xPa& ziAfQE>d6Ap*el&fe;{y8>36<4YkL-~KJP7__w)K^dm)84`x59Jq^jw3%a|PXNU#mZ zs+X_9p1=0)>f47UNkJ8dnw9w4J3d5>xOZ_pjZURQY3>DxV}2<7%yUEV;8XLIQMfji z<)8b{)$Td>gP=j_BAJdo21kV0tmu60>rKyzyitS+2cl;xOe~CNb}F&fyD%rSNwJ%U z9>GJ1sB_q_j)mnb~B87$`BU0&jgzonxPE;xL1m$El2* zS4A8P{{Hjgr}p!pPu(0?`x5B_l9hSwz+_Q>=0H&FR|PhGTdC@~yxnUOi1Jo1x7_oM z0cY$}Y}e-S#7r~D)~1Ms5p)fy1so6a{kU!5o<(YiMF6rK|JY{>v@W(%^NE?oz*5W` z;@seuByu^_dmwC?oU2-7eKDQg7d zCLLkflGwNRgvL4Eq1Ake9}Wo8EykoTREr!%7q3--?(TcS^ijln4qw@rJFOpza^4O# zx9c8<%o{;DT7rjx59YMx)7iJ=Es)dv{7!^1{KH`Y{NQjEliE@SP?$sBy466uLhYNW zPlY1~t{E%xn?oCx;!TGW*Y7jQt|f|2lSO*7A{>Rrhe9uEIw}~aKtb1b8F%V8Rhiap zcDDvO-h`e>XH$}Mwpj3mb+SU=SCzUR%OUWG}w#X7fz&k>|M z%~C+q{)Jh-49|IwQgd^dlm6O@)}zV^KFRA#oqkX4Kcd>!h`hjSS@^Z=pZ#H;d8Y$HR_U; zwh!+1L*|gI681SUeq`(GVMgS}9>AyCHhipn7Ww_ID3fG|?d8k1v0qFNt{K=O|MwS2 z9$uV~$osgM*4-D&Lf+>hO?b5>B}(Q>km11d3xSlcR%isg_p$*Bk!}IP*@w@KYJrCF zI`u9rR#QbRFhdjUSI>e?YQz6n1!Mo&ODX2HT`WK}*-Ia)PcSSYM(q8=>hDRePRpvL zKd?F|!WMLI6@Cz*wLl#9)Ti3>)T^u}mY0`xq2mtw`kjlw z?w!NF_S7@RPcucD@1A-IVz&(fN8ZFO7UwAlEQS9S{(t{kJ@Q2^To~~kd0+Agcrgh{ N=DoZ`k(j}k{{sRQ)_(v1 literal 0 HcmV?d00001 diff --git a/doc/html/_me_bluetooth_8h__incl.map b/doc/html/_me_bluetooth_8h__incl.map new file mode 100644 index 00000000..fec64773 --- /dev/null +++ b/doc/html/_me_bluetooth_8h__incl.map @@ -0,0 +1,53 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_bluetooth_8h__incl.md5 b/doc/html/_me_bluetooth_8h__incl.md5 new file mode 100644 index 00000000..4d2b866a --- /dev/null +++ b/doc/html/_me_bluetooth_8h__incl.md5 @@ -0,0 +1 @@ +9d8c8a08e13e24fc731d0e408436a804 \ No newline at end of file diff --git a/doc/html/_me_bluetooth_8h__incl.png b/doc/html/_me_bluetooth_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..e0f7a5c6bcb165247164eca7461db068ddf9dfd9 GIT binary patch literal 64105 zcmafaXE>bg7Oq~R1<_j&5xqrp5+wv7MDLe#gLgjPXYCm5wiXXVEV(dA<4maP(AN{w0S!uA)t`QE$nV zUL93^y@B=9$Msp%AGfvpiQOE^v!?UQ{}dG7wb&ciH{^UJEUMS5lBrh_#;z;&%H^Im zb?d_YMMCwNh&3H`b(@5UN#+<*&*EJ^-%g<+^vk-w)A;qoV|20TaUWt(W zKaZG*SPHiPJSYgMIR5+GCluVO=+9Ls%nrVax?5QCa-wrlb77+6d9XV$4Pl7_{ur3{ z?<*GBJl5F9#|Z6cFp^1FQj5A zZF6oh1$}F;Poa`oCkzO1KTGa=!p1f}Q~ZpTjqMwLrb~77)*Cl{C;hPo0>C)~`2W7c zQQkviVae}5#fI4dH??Qdo5n^*uf4L(DAH zXP#$hl!@nW^juXA*qA%I9#KvO#->bJBP7|6McBT`tRiD&)f;E)N z*R$9u8F04ar)39NvAJ8P4cy>WvPg~Wa}=?gRpUc%G1^#>VT-h$hZc#hJ%3gWMk2M8 zsnE|oMLRr+dB2XM!|@Y)YcJ@h^A0Aln_U`RkKmWp9nu{5#?7@iOMQNVWA-?ay2#%paAy?@is4Bg{lpw%@| zC%(6^>A{oN!>&xLrbn?NsK8UCmG6ePav+8h+k%duy`&hxG8NV$^zF~<24|9iQUrx* zstP4q8Hj!CXayOqXyL9Fjq%UV9qlFlILK5Dg7w36X??Iu-SjA}y!iWuup#;tS@tC4 zGQ5CM# z&02W9m&?kOf=|D`s6uC69{xKZUGr!%g-5Nh@dV5ASaKO(BZ$f3lQuxV=n{k&XRm;i@2AT7lIv4bGi%dluapzrAKuPQsXj*(8hOpNC$=XlL=Eot200 zxY)xgc=psfv1&cY=L|+m_$cyz=IqePLr=U7OWNL*CsUT+_O!p%_h(Iwjf^4-HBQ%{ zAhAo(^=@Ns!ni~(jFd>u>!>iiwc-ljF{^la!z+NPR@1d_{T$KkBu2<2?Ef|KYS=XZ z@ulyWYC6o%Ib7zdaQ*qD%feP9exRER%Vm1|PJaIA@$feqhd{X>mBg7upDk>D z!l(f|@Bb}^NqkbRFtr!rxdgL3cA)3931XGLRU1^K>|uB1&VD2YxMl80rSO!9GB()Y zn4g1=oLMoW-P!q7(DyqK8igNU1~_swdsL8YG{ec6U$&IbnLsma!rs|nrwG7geQjWq0GAu+NC1VRtpq!S)~$t zs@qrIz~`Z39dr*qE|L-{8T#Zb>mDL_hQ$Kr*^ovsB1A=kTb!9T`N~hyfPj=D%i$$1 zhNcm;*}xVa_j%PmH5zpxKsyH?okQb8<(!&oeRGGyzzE%#I3^PFMhHJJQ~uBGse z44tZb#4K-zt5o(*0DmCLx?HoXi7;1ECQL+V-aCZgar$8;_Dldai^J&0OdXir2X*Jr z-(s-cMGf5L@e9M{AqWdLCxdjv@nVVab)Q~k<>87YC{N;zg(f(X+SO|cC$(;U`!Qh4 zZ*&4#Gr%hjzxiBOqx51)uQ8+=TW*{za5MEJ>i8vp`M$Yj%=@ZscwZvb+1D%yL9{vr zv1JYW($5M&szw{^I)Fl3_uCH-b>x|D`se4Elc3Yj5VmNy=2r`#doR>y&+e?nKc^`v z%w>#2Pdqwy4{#BNk0CrOl1%S;0AJjqeG#-oXULKfp12N9e07}JwL}^~N4)3>>Dk5; zz!+^kZtEgqMqWP53i06+0PfUSPV{A7sCNCGsF*XfS=iJT)reZMhGmPPu1bVUKkc^- z7$tU8${>Z3a6DRUG;{xV#Xkui_IV5 ziUB!a4V8eJg2o9+OQVb0^*b?#)m4683LYz6vc4e`)NyzgxCfxF2Vj&8!Vhs7e-Ox; zS`_E0C%nBbUK?g!KHRuj-=%U; zmCQ`?^Lt``?AWlOt?lLy0k~b(Fu7HYaZqh&5-lCLbi%FX&mW-5Qt$y$o2Oq?c7li; z6%?)_EBC(m2czqr33AClGSr-no#o~GLNJR6D{B$ytXEtae)41hR2aG)Iy6CeZ5FVv zY17^f;qfN8>`&EbwtxSnECib~{&2u^fqA>1c2~E07C(}eruo>(B2ogSn_@U}w&%$8 zk&y^&B^a}@kK5@u_ow>jSTo?0H92(8mr>oG;3XzK3B@+LlG-8LnRTDT%LtH?uK4n8 z+&I4`xIn5?5Q?%5=?ey&-=l zVkZZ>MT9q+VhsB(LkbuDo(g7pBOQjSrTY(e&d$=~PCVD?vMpVi;7Xgq*M?DeZjDF0 zmGn2{&5TUM{@j`mFq|p8T@a&L6a7(y{pRs;$Uh0MObN2#$7t9_ZGiwuSfBf+e zQFB8+K}aJk!Z}!P>Le|_aEbVUn~6dPh2QUS-#x3$Q-AS?v?RZb_yc+ohhx5Mp?wN= zO7DK<>LPdR33B632nNbR2<@0%-vTyx`?rA#M`jDTowN4?TWpI#qrcJ?FmiKc%b%v4 zTJ>yXF|dy`2QK;t|EXAwYfTZ@5O+7RhgFOF;2(USvq|N%_ylx6S!Do{JN(!bm3=~u zq}*e~U_`*}MPx~LNLfz&eIM90(`hyx>+r7?hruS8cJ~CvXGV%neeDY?k(79GLB_LvIygkwg}H&2J~@N zo>tS!*-KO-Ey39ZlnW(%)}iUV)%b*rKHs93+n_%~B-r6bDlx8Lf6g)V~PC^M#P%=Pyp#Im@{WP?Q;of0~WK+~?bEC2c0Nq^C%4l1KKe z@-%m(pZ3P#Lc0J}iU4{#XNDV(;FD!#3ypLXwyK)ngWMNPjUq=9-i6PzU$~car9h20 z@=6AGSeWQO{*k{|AXTk~@`QN(%$UDyph|o=TbVoTyV0wcs8<3wAAB= zg%tA15=8zs0CE1Ac&q_9qiwn`BMFx}{@F_2pxbnEW3|ZL&_9z%NEfO4%tFtw`7@sYnTBLtd^`%FNYY z=tWr10Q5T^jXuXt!%aRgTWq$Yz0ie@qnvogXb(YG*T0OPV64yzz8_^c%w4{}5SCcX zbY{OqE(3dY6^}}#kx{faiz|0b3L5=B;j^i`RE~?!Dih}4UNW}U>y(Eq#Y;MxB~>@Q zJNAUtMaq^HMLRBBev_(Y03W+#*q<^nRklqlXS$J(^v2-327l$R?OYeA2JrfRZcc;> znHG@NkJm69m;9^Or^u>6sU2j!2bGST!FfHJixM!4Hv}kM&Ycx$biLf90xlxvT`#uTLfsc^S6Qkt z?Fjp&;A+Z|QWj=>W=|yR=%LE}S7lpf7Z>GBBgG>p|7m3$xG8O^+LfD$GJ`;aQqA=>bD%-74bjXtd(;P7Xo7Y@@41joM(`Uh&C{_*gm^=Rv|fwIzu z#I9ci%fisHK!T11HYzgT>PpK_Mo<^66{{65;++rP!OAYp(1Kw@u*}egX8n2YTRyf( zy?+bBCFfV{gn@H%NT!PS5^Pdi;zUO(UN1x3ulD17(b3#ceA*u?eVb?(8^Uba{yOJafsXrAtvymT0MMA z`Dpjks)rT!@b`wgZas!}BJC$)ReW>~LupXc2c1wY((L_`jVL}I>TjD7yHixhLH2w9 zw=`{UT}oN~k!PX)mFDPL)`L4m*eYyprO$ho)Xew;tB{`8Vek;r{C($lV7vg(H5Y-d zSwk{GeN|;Z9%bC0Hb!f8KxaWPh9mv9l=-2O!iBz_RDGPvzW#r36Zypldr&rIV~E$( z!T{)=@G+!Hz-J1aStq@B9jZS;DAiGl+JEk&#cn?&9kf);1qBHPN7a*bXzJlf^iRK7pjRJh0TtEp9O1Lmf!1Zu5`d48)33zU?bsW zlhNiz>WhP8M7T_CL$(K-zte>SjuUn(6NCgx14p7zsi;dChc3oX~DU!3C>gat5i`oVYS29 zsl6}UUG(?bsgssU+ongwkTg)Sal+PW9+d2{_p*%@xl4;sv7~dosf3T?0BD(%n58;d zA>d;OWYdtv5}r-`ngOhrQZ;`h5q#++`!)Cm3i1e}3GXs~}jIE3v@H-G^+1+QayGaUf$d+^G5Pjz^$z`YC1)aOa1(+InTKw;hK#5`o z;Gyd4g*Rs(^+!A3C{3S_N+h<38F(E!!vpz9&RKO{GO_jD5wAH@CB}IU@K4xbJIHO|DSo!G?b1`PS7*h0n?*& z)mv?nZk{{k^np+C_E)}GH&xc)g1nmGGN~Dip0Mo6nd70$_k2J0{Qy&P062RRxR+}3 zD=dQ129`u>6&4is(3hfV2GSZ9P&)L5b4Mg-2I=Jz{@u)~>>rXa4Zz}=LR z!xiQOP7CuW0e#N0iigMQ#%tFwd0Q;xLh(mec&9_o6wL>IAUrAnXLtsrc$w901(6x7$Qy(L{P)tDv0O$P!b4+^A+b72iUPS0uWp$|-o(doc2Bkp0P#Da_K4?49k%R`+3 zA5q@qn~O$SV1BIE>+X!?Hdb#!kBnFxVKNeSmCZJ1^41cjQ?c1BUeL z0=*(5R(ukaOAKrLsCxMTW-9KJ>83x0!^}G=;LXP7hjbp`oxwI2M*S@j4tTPqGEnvd zX(IE13!8o0p}Ifuh|$O3cre=O?#>cs3Cvs5O1~fENFzmvD}*k34k*4wN^4pB$For4 z4CB0(FnR9I)v5K{3?T6zP;ul9=}!CoR$~zV94e3|!hAvej#zrzwUEw-_67h1qsolB zih00*ZngGE9$F)1~O^6p9Vb5#yZK z>fu$U&Q0cf^mN!h^lyU3NF!Z+u&@0j#;7Q@Q1KW^nz2SeGczs8&1iJKNrf&Y&=w#- zTfj{+T5a`X&-S2oc}*vX<=bab+(RLfdUBHA%*IxpFMMYh)eBA8j0h6gk}e1OS6SDo zF5&f?NyC5Ebtnuzi+tWlanCdcYs^Mez;&M$_ujdUCgE-|FvQTb5Sag`nK2p!< z5}eLFL=uHS3MvDi>*w}y+K1O0Mh_~y+>@5~xFxuK-Vf1*)h~a}s+PGW1Y9YT{;p zbGhyj>-3C=59|48Y_uo-#8x2609!4r{`3^I?Yw+$lzJ@p`7j3HG2$dO9rOPAD6J4f7j1=~Wcmt2WY~7=L?y%#qGW@&}&e<*bQ8e?U$E~W8 ziN-Zq?3Qpvmpfc{JA?#?15fP*tcd5t%n;}s=y^Xy`9L2r2767qpV026O()m2BES$2 zaR$w|YN6%;@|u~4>DRt1xBY2Aj8t|xe{CxpNbliUEaVhm-~U#K`e|5^cjjIHa50?a0bd=xt5l^?347vL`2}v{8#ITP-dtj zlnso_0N!~^SuVSp#>SSUW^>E4H|&9?2l8{_wW7r!^A*7tkSg{Zc#RC2YjO-r>)9`% zJS#5}p&E2h3!GVfnu;OSi}0wWI8)UhS#;NN5FJy24r~&7`{<7VtU-+g6-UGoM@OTm z&>X_oMYci&gIO5mjYX~V7V&CWdJD|Pw%7|&x*HH&b4L8}?CxOj%5r*Rdm|ve4`5zL zEjx!eG)3HqbzVq$)?9S_NP9>xK`PY5iadLNknbxMQJ`x@^hZ$4hDnRFj9j|hl)I^D zXLNM`Q*PChR}))pA&0MFQE)=rNN$VQNi=twj4Zx+GlGfMD^*@?>cW+*iPCqGfz~|ebNPPF zz#?CLG~J$wCG2)hJfBAc7hr50-YUh&uCCDwFg?sAMs+d{hC)KGU7Z_4jmp0~B%kYu z#cvaD{L=Zmt$ud`;Jv843U=Sv2J*opH-%fB17@;kmJG~NEh z>{zaOJK1N%%#5keV*7lH?H{&fG3p~t!~m20AX;THeMDw&cKMyCdCo$`LOqkIalX|( z7{FokFXU)U{F5e9FDjJYs$&(@=dtA%K;HcK`23`uQlY= z>SWn|w8%38`-$^wL1N{!Iek)@lQDT^$6Qt|{J+WgEP-DIiBZ_|ysE8kS+!~u+-pV(u*VklxeZ3k2qrOan9%GLaO8PHmT52$XVt4WuPLTwt0PB+j~KAY*fyXk>=~9pOThhIGD=KwRV)!0Cp5mOi} zgRAhtYw(!qUw2SP(ndNHfT~$WY1YSU*#Yf?q+s|Mv-+zsW7d+8a^v5|G25k@`xVor zXz`djfJEH@IBNkB+XCS`Pu=dloh{;8&RGSjxZ5g|gl5`w>uCX%zTMagv>(w5q>Kvp zb^xZi56Y1gf3?jXo;^}T+mYPL!@~!X%#BuYd2ci*3RT9oQr8!Iyu<5(hfQMYpA+tB zA=x`(f4rW}#p# z=Fcdyua6q|g16^|8l@t-DKh-N+y2a5r)Pb_@uuUkMX&?cxq9g-B`S4}$TSO}v;6r^ zlmC9I>d#RLQ`SPkzrQ+x(LxFY~|aM zX0n7^_&6>8jj5os+sEL<%5_&Vp|nYrpxjL`=r{Q1neBpk)}fo$22cf;l$2teS9j#;FuK_X2Psb2_T*Te_kF0T7j-t(6m}o{qXz#drVA@FpA?Iupk5nQ?RO`_5+3aZEJ96JP+3 zDjmL9-)UN8_R500KXd!5#rdT_B*QCB^r=X&@Bsp<9sB@H<5f`7w3tzHsLSk{nc_Ng zQpO?&z?WP&a4wldf7M3@e&vZ8wl^qjHN%+0K8z3IoV|D=!jLK=-LDVHH<XZZ;EsEsD6^}eqp+NnHn_GEgxdfxrMAW`hTHuuv=#FL{Fa*-XT=C4B*xbd{j4?QL|R6y=5&gHPrQn`D@bhA#h9JGEtgwfy8e?P zan!B2P|?@K$h1|l? z!@HnU(P#VZ3WGS2!H@85x5Nh3@edn^XWl_Fgkbt`b?$BRc**ZTv1Huh`uzsD&X?PL z#k7U39#vgP+8?kN?#Qx%0;^eIW2AY4`XXy%0mH89Fph%VFeT-JyM6L-~%L zp8dOFwz^7)nD>iknBF*etI6WYMo`k1Z=6SBF_nC7a{i&4Z*{Ud#!^<+=TU4QWHm3* ztU49>c)R`6O;cDwiM}FEk`j7T+(3R_$thy8;p*X6zHex1+nFHw1CVq>xK%yJK#?8U z_`rc(#%{cBa;5Bae$2IN*--*355)kkvJslWc5!~*L1mL#yA@a%zh7I6OWaMn#wvv! zPLOf$X=ew59Hw@<1cyAV3nZ2r!yu)t+7$H+-xQw^5;WMZ`VICGTyo204fXn2+XXrg zFE}R({w!~oxV+Op7#T?Qq9tz5#v4$pJ7G<{x=5nZr+-R{L@+Hj9K_|)4|Q!#0E9N? z3EsDwZcohwuy$ikj-r$fnx7*FR5r@)Cty@q_6uq)uO8n3k*z=glgbJNeeobkz)WZn za^Byt8U{w=7k}A_8=m5cMG}*Oe%ca~#CL5F<9%ro`2~6<-fA%t8Tke81I~z2BpEl+ zSVS$g0e+b%$_Y4;D4Y_|(x&~PlJZNnq4lIBc>6|_+dZ^C;wDU~2ipKm*K<}gnkHn$ zZEL>$*J`W%@Ji+<+@9?cm`{U{XQdYS@F+?1W36W_=uErMIr|_O@Gvnho9a zw((9wLkG*rW*`{?fJ7&O16&(Dy-GzyEy)?oP#sFho?7!x&Kjth1pq@a7OxgI2qbZ1 z{Wj3`g0X#UUB6nn+7pY?euN{&Xc?goL5pq8vj<(7VwR*hBaqAm%XkULP*ErY^#L*5 zsI0kvtfZ=H8sgQ=xZTF$C}sTYjjgmT{7=K9CoSEn8OF}L9!|{#<+w4^=T4=THg<7O zOgFb;rUlz!qgA0TMl5&IH@g|%fos^vp7gq_rr)&YQ){vC6+DGS+7-b` z3m=PzmdD=Fsf9Ifoy&v_kX3jnQG}(~G!C5J$BYaz6NfbofQK*3y$s~kRaP%wWfM5x zJ?Us?X*~6qZ!M5HZdku<2xP2Bw2Vumj7*(*!RTxp9(@Mk_}b)hTbxvpowW+|Vs-uxrivke^*FD39D zmd_%@J|hA1D5NoL_&V(=nr-KgT)e0QH?X!(0&__4>*-Nq%Px>nr=NGaO)k8yxg=uI z&}`dHR68A(O0mRknS*XV%lGDA(O&zu=cXf!*e&w&xn7 z7c^J~&#RK}Wm;jHV{x)Ax@N%$B;X-Zbl&WmbeqEBoA>ghx~ zAt@q|*Y%7L5=4B4d4?tXfHL`V+2mcxVM3;|M-l_kEM55NqOXoYp=bpwlc zC(SvE|53H_ejq43&U!9I;G3HjlWmAwTeW2c{wk36#*y*94V*S zSaRz8C)*R>cY2FNoCbCX&&EzbEHuz>=U8_JhoPFf$7%rlDBpj?kcuu zhg3DTux+2vv#i2g+-w2XuYqS{hm`n51Tg&3ZBHL=k82lD9(W)efuPQiAPlH#o90YU z8Yy4d7?hMNb_a_pK>!{u=Qn38#X22}3tjLAj5aC~$~8q8AdW5*GF^3&%X2S;|A2pE zf=D5^pF@B1Wa?+8_4F-Kd>Vsxnw~1R{ z4kLGWReD?$N~Sg4E(FL_>YV-OXd;-TgODc^nl9%ivaUWm?P9Er)r;q^d+~QZw=X;0 zZ+feErQeFCAF4leT?ayX_NF*BPI6*eCuL3!P*-9icvWnDMM#!o(D=Z!-OMmqh3_me zAR!wW_}e0;#}44^1<-CJ znG4eO+J(=NHX|!9ls>JG8~a|Q;>#sljVeSP7Ju&?XrH+oTne<^J%b$v!FESDHLqei z&n9nXWjfpWh#82ExPyjf>eLKD`@RWL_#|wE!&_UI^SJMfx}5iVd4bh4`*}NznwxUZKb~) zThksCNom4k<_G_3qx6Nhi3sO9^W>sTMBqy?lA8KzHtpP=U-UV7llH5J9B=JGL?j9L zce}3ZSN_i2)+;3+s>ue|4TzHSDN`M8n`<50*4jg97=d`+iJE5`Ui@a*L2`rD#EHi_ zsyfRP`DW?#8(k;Gg?~lF?M6cFF115W>flxS-VGc=H)WHWAPF$-o)EKY?VJx``(u-d z#~yIMjWRDgSbvC{f=zxT8ZK=r5wlpp{`R z6wge$+XD$S5vrD(0PImm&RFTI{zsCiz@ngS{Bp1;5yO0dt*@9D|AOkVyC9wwC=z5? zpQONqXYpJ@+6jiF79PS*UC(F=*?SToy0x(Q3S&mHt)?SOEeB4)LF7wm=c>FfR|@y} zX#bcHj86=xfpnbkSY;2eH$f}I^MsZ}vBr~2wEfnw5SN4HloZ+0a-OHg^#5d;WF3}C z%&bkjDspe53Ej&!*-(Bx^U>jPZ8#x<4FLiO-XG~RqsJm@YIEVCodB_G=YJiGZn|MS z9D^>$VXs2?-B2coYUsuEPLr1(B^P;8AbNdSmq8qgO^OXefG|lhudw$eq$3V7;KGQN zoG$6#3}yp-5jy4BtFY5O#`mVSK1vWy)nZUK;@}69{FS-PZ~8y}%Ro7&5b4;2&ApTp zD+y=(q5rl{7Z=oO%Eu$uk)knM=A890VtLA+S%3%-*3xg(ZZ(llT zZsQ2B0qCMn75~tUOkx-$L>ooNxC+M*S@J=#TBJ)2@gl;myrhfwy`0_yioF=saZ^{D zXE!`SQgd<;$Z3(ilTevbfNb71l`Ef?qsO^vl;A>`dQ`amyWBQ~>(`ada2K`F&zDpS|qDeH*%(t!;6$Nmur$xtgQw~Id zqrtZqKco^9o>{uDi#x{tdy?0QvmO7c2$cE~fmF!z>iC=UvVn%D=#u561#J9@u8T_p z;_D`++Y`9*usu#zm*K{NvQO&nL-&vXv)`#?LsV|{U3e}Cd@Z|8(paqNHOB7O-nb1$ z$tt$DkHJKtl`Cz;H;&WgfX+pBeH8%XSz?P*U2!T&|&kfmj?H? z&+0Hg-+GZXOjDI}XO46|VGL*~0I3`$e*8@|*v~)bR%%P#$*spaKqBRoGBl*(6XFN7 zS<8-sJgNKd84t&|dRbf~y#+f=Y{KnYZ8BX^v7ulUQ^46jPJwrgz$3vGNnpVOWlGIF z77$B?VWsXF4qN%33WONxP4Ic5BDRFD9Vh)-!qHn|1ip(avs)2UPIs4jef}C)%sx$l z)`TH{EAIKf({*Aat34Mw=Ds+x2>Jqxo94U2;E9j7xkAW9DCP#(OxIS-$F@!7x!Bh> z8iVf|vxi!J4vD~AA$pP9vpGeW$>hZhd;y}-thMp*0?j2E-xH~JSYo=!@4aYAZDU=|Pi6pNCfp>Mei+qy z^^1m_oU6^*FxkF1b`)pYp#Qfdg{opp9Kh0xy=9E|NTyS!bjSGWVI@&Td=W9RcgVC*z!!?>LIjBo zoLH~1SUieY5q(pXJ7Gn&^~${;SdxdTsh_EF@=l}%08+CnN{qS6$Cy5-p%>ji9oPWdt z9J#C~{$-5B0I;%*##1MJz+V``Jf`PJ#d%zLTB^B3qD zGywA+&rF5$(+41~zo%MJ4TWVRPkNfT`rRDt8iW;#*|x7yU`{4kLr7KByu0R5XCjsD zf)21naFmk2POu!e*z^k`7j>I1n8yQ9df0fW?#Xn06h{)Ep0Hr3s>dB2y-zO!KIfM8 z7c*e@I?sAKB=)#`Ox#stLGLxBQ0iYbP9E-#WPH3)g_T<^=^UjDDHqW;l$(ZhMzSi* z9|y<_BWW;b&K*BYqLFK$EwExlBj}7XP3f+!DL%Iv{-p{t>b!1B7^4`Z>7&wm%pqDw zMZU?z#-|E4LFV6LmxNJ<#!a~KPYB$xX+J~za*t2eiM7xFIBTo=CE>wySA17Hc(Vr} ziaoT^aLCjtXW4;ai=zsLb~1{N75P$5+vUZ@Lg{|i%DURVI7JQ4zSb5;Fsux}Be>%(v<72Lio@+xcE#xf$MnH5Lyi!OOvM1V)NuRUsx3`p z7NAkb$pMipjFO%~V(rVonfoNLdy(hC#-pk}dhs(%WEo3!;o_s_{QNUE8HG!VWvPCl zB}-{Ij>W?RZWshlEkmBVnBey@I+zFXQa?OTX!?guo`bS5+fs(X4moB_z# zQDhm)_W&o3SxZ_AQ|a-R_bbnKfi;d3GE6N60M%{M^0gLw0M*(gXhS!98IK?TW9X4* z_tN0Cv>(8#3os1#iHkEe_5mE8S)pxEUoc!)#LToYL0~xhV{?&6Otea$lKa(bVPqjz zZJ3n1gvM`g67qo`Be4(r#(!0iIx?ox-wcB|bSZtST06gS%{SD9?PK6aHs6mfL86pR z&2CvjviGfDB`Iz{sG;&HD~}~ID#?MW8|2lKe548%6#12(V_L_rn?3o_xW3$Yv3oew zn1$re$0Tb!?Of_uB5vm*T`f$dQawU`>-7E0+oTvx>k(m*<@B|-ia0gF@7H&V3g09= z_B=f7UHDY$Ot*^#F@3dIpEsp-ev-x*b2H2*?O4Mn##lOh>U2(cfQ zoIXg5If&*?{B_f2p%k6P4jywUIm#jE98#1D)_9*XCjT_YgqSgD4ILg=c zC+Wi+<&>{M*kCIik7M z$yYeZI~Ov_+v9~~l>O?jRDBSx5upz-jl_vxh2^s??6gP=H<4-1d%4LZmwf$4H6jHL zH$i%VKNTAkMDnq?l{{&BDE`tCbMSYyuwhI2In#~6lDW*cr~0(u$fEQ~^PfY?Bw(zH zDQdVXwJ>G>tZ0_*_ceAM&PWPyX}4&pvhc?%ESaD^96!1D0p7g`wmswaFrII+!K638 zwxvyl{u16***>viTCb?xK7H4kF-L24^j=Srqd;IxCXn=)ykoQF#ue`C$IEa{Z{`1m zPPCQyyn`c}vnzK2ooADEN(u=1K*+kwK zAMqHqhVFSGw&pPXnnkuFKAyg%%Bc>$c_H#fMBvfPjMiRs>OhLAS+3rFgzHBI?4Cci z&eqzlKbfEMpL3t|SbqEj<{duCf{<5CdFWo4dSHg{GqSS;Kni)ZAuk1D-8J*n;ir;` zLa;RWkZ<9y6C8YK%_@1VN6RyMjns2|<&4R$yrq&o#54$OS0Ra#7t$8N73 z1bHy0!{2TBXs}R?d6n#A<8RDonU5j@3}|n136s9$Yy7v&TZ%I z5b=r`E=DSn{{H7mBPFp)Mj7fyT<@q!RNAB*BUk-p1oMA}wb%US`~8%5#sRAlYbYc0 z(yhY8hAwt{3c5)`66mq?$l(YWq9a$Y9=pC&z{a;bzApuwyEkM|_zTp;oT0M{H6FnQ zjm|W@v{K*5d+>uZ2OKS^{gW==4Dq3lBdfA!M*Rxc(d*H{y<*xpB@qRcXp4SaqDOt? zg9xu2ll@1orY*91G-i|p1y+2TO(*zc{7W6b&4dT`i5?U^<6_0RX`Y{xd`A6M%5L(n zaNkNtw|r{Us-z74SKPTjA!-?!&DFp+C{B4+9w9U;k3CZ)!F>DzKTePj5LlJRv{s zc&Yoc<@T5Cd^e$tSxQI~e``LH{?J0+p(GAng*h?Y$%D zJ!K{*jRhg4E(3Y_!DA0}oqJc(OxhEsXsw0|#+SH+g2I^B9=KT?Ug2pRT``mk!HlVn zy{@gvIg5sVO?AgS3&7yf^`%{J`)umVs}I-DT&QbFGRL@<;(y-;|Hj{C#1!fJb6c3) zpyHv)GF0ZcKt-7Hy1uDx>-ZJXjwXEzNzF*)9oC3K7MqOekM5~wRQVh@VVM&(w)pw6 zkL_@fEsDvRz+$$iQhe5`ja?c+h_;QPFKaIQLA1U^3y*NZ+)teMip}*kW@PooX&|Ae za(VUd*&fZbhxKXcy^y#lSLjY#DrT#=HMXdM#y}5WVh&Oggy^sTG)QmT@Ou57g`0X4 zVg2m~ZUsj0gy`d}gOOv}PvYjuEkXMLXDHpAP=3`^8h` zmiOx0vrbU*8(362JrEWhbzZ6wj-LN?vsu)?(DI(K=24-Y$kZ90F*SNXN0!XViXa%N zI3iOPpV8XTPgyq~YB~gh@-6gF>W7L`Nj3cxeMhZM3JpVCnz))u`S=IyD4ewcUS+?L zu-lq8J0q2CuOf$A`kXfvkD}-}IEJw*-k|<4QSp4ADVW*T(xB8Qx^a0{feab}Z}z@3 zk7Q6PBIP{EB=2lvJIfXO-!4GP?(GBz{a3Ni_5MuVF5Ih<0xXFV{mZ*d_^A~4X>*WSl^zQfYX! zrA@uDZkKP7;EV{Ku&*2tu=<_hK+><)+v8z$cg$>CwA49+7 zK;LbShyJSrdF2C&Q1P}0jEJeb#Ys6PF_%xnD5TM2u7fzw%0MKalP3ccl&4lkQ&RryX8Xho!K^hJ6I>#Y zk_sz!(9NX7BgG71IxF{=XgsrSo$MZ&1eGMeGjucu`J|lhI{l&Q-^O>rgkZM804PU?t!;o1jfJBL%TTYtk{Qa`6u7oCVpQ}Uuxxk?AYUWoB6;F z+o$pNdXvbDC0n?hFgRPY7iInJI8Zjr*y~Xt*10blB@J(QU7p3KyUDzZETpPPyjuU} z`9&D!%YO0o?7J*D!kxan(Y6eq8E4PM-Xh8L&~cp0q_nU2AtpQy&l(e>ghKUz?4P`! zVeBGaO16^2(c3>sZyt%07;tsh!{NgN>pad1Zb2+7TSev-$C7Hwy1e7#*55S4YV2RG zrq8nLl-fOBSo4s84wXuXQCCbX)b?DzC=6kR$h$$X85`S&?)22fU}+1J`5G~XqDD8k3%P@8xUC0ro1`|NfvlsCr>8uY zb|=#HoMWQ22ki`s=8u-tT=JCZ&`vX$cv+RA4|l1?eG&0i*?Fh@n$K8l*wG zo00Btlx}H3U`SyANdW=<9bWJ6XRT*F|Fed3?t9<+y7slNeVKCRy8Y4aSrfLu9OOu2?rq)!k_|rtPmVMlspvJ&a3x0p66SeFHoGb3`Mn42uqHa0QUryls8}ZzY#3U52uC zaKerh=yZT&6qjeQzUK}QxS<7kMPF6So7|<(N`2X*mq51ae$W~FMNGFxbI1T>t@-Ca z%!-zPnC>Vs5mhU<&C?v_Qhl)R8n^c=n||F`yf9E!m=(mTC$B8OCK=vPi0#YE>~A>d z^!cMoP*-i}NDE?y{qCH-ddm*YAFk~Utc2d-)VIVwJ~6tV-L(nxGw7oQ36pKWB}F*5 zhtHl(^hPSokMiMf#AC{T!eFuAQLDv{U2h5T*bEM=~2ngr*EDSCw*m##2 zPDk39O+=~ZD|(roH+B^A;Bu)Ju!F;hwQwD%P}%w3yzBS#^L`+=f@gVjKZVASd%3(> zx6dTD0bm+n1aIA#siHACZz!smS{bZpP*LxqA2JCf=b6c)d@2$W-iaH1z*4*QcSDm~ zs<*1BdU^Lm+nTnPM*V}d7F!U>E`Qq?*ZlbgZCaD^Y6UxJ1BE*_b|1(arrmU$Sib{4 ziie!HUWpkgm`ZVpKGQDjTC`2VdW~Pphn#yEFSLnA5eGzu>cf&@;k<+`bXfcYt|#Si zUL8W}NOvuGK|E$KX)0t{*(veMkMA2FO;6yZO3}~UnLlt6yfGH(r$0q73%q@<(A%Cgu6a%?!e$-^T^-(^jTZ zG~eV~(WVX~t#p8HoLE;vuDaiXQ6-GBc78Ra4*;B@^)U-?P;RR$4}T=mlRcl@y#q0f zjyZYzK~|Y444XYOi@Q!F@5sZ_N1aHlzRBKbR4}>Bv5UsKg14#H#lk+IYkH4z)Pjvk0$dEf0?>qa|DpFy9w{AHaX2PKJWwk67*ifA!fXVq zQ7#D6BIasr|Ma0HlmueJIqY4CEy=&0UTLN>Vh`JSQu-Vr32ixhuIA8RAioyokh#2+ z6F6MeR9?(_QKX4OjHhHy`r04g7br_X)bmn-C`@5?`EcKZ2lt~=)NM=ONF046)Yic0 z)&@+;CIgVpkB~-tg;#<9gst#Rh1|3hgt6kX7G8GG`EyEuI({Ed6<{p*`1%g?M=N?U z&J~uRE3*_Vhu;9O%q*x4V)%hH_g6b2n(}kFA3dBM-uKY?j15{N-*lkuT)K~RV*V|yaG~NKI1egFzNLE)No}4a8I?3gq z%T`d>Ukn&6HMCF$wT$wkn=_s#3h5iHLz`vN)HyPj&AAS&_A^x%cl3NKs#&)XhuF>NjUyg6BJ~MIm1{0YOCNS#oKF zo>c`1-y&#;a7_fLs(M)@7Nxqe;TWYWPWpL1<+k=h6=2wWYs~p@Rky%YfB?mOxtYTl zjR|6YctoGW_A88bFA8-2QziV1^sf{wcoMXV)IKc@&LBL1kp{K^Jjo*>R!e}B4BeXV z+KqT-?XE6dyGqp8G(0~TOn#`h#S!lIF4t1+2^*b>JZdw!RE2cWXRw60Qn2oGA6{j< z$%i{m7`#hPx7f&bOjGa>eNb+(ebM~O#p9-)!5FB@Q|3*YOI{_W;Yj5#3cSFg-ban~ zn$>=BZRqk=HJJGcBlG~n6Fx@jM7w*a&d0|mbM}l}IbO}T7VZAVxzoVYn;bI}_WLERUKPrFs>TzSH@vsl0NpjOyG1m+Ec9aS8!KCu z7}s|L=Eq}%bRbQlfph=Gm0&X{t5l_XLa!N!wuErv z2)R{mndo_v84rRG$-k5&sr#@^@nq;8kv|yB>*zQH9#lYYolvzTn$)ahvifM`@Gz?^ z4M%n74_}|)eJmaE>l{if-JVfZlX5uF&i2}4IM2$A_Y@8s}cXV&p&?1k_q5@5pgYyVA#yIM6n!LPN-S^X&&vm%N!j*I3#~m z-Cq)wViQswE*53@@GhJ4dg?pmqLKK8Q<)+O8|XHG6vAxoy+W=2tX-4BnCL7rlhS1d zZAj5A3*_xx1TAm?51L^qA^!-Lo#u%ck{<$`S^`i|3R-2#hD9xb%L1M}5oX&?KXo6@rC@u;iFzB6rrm% z*czqXU6|a-Ek>U3*Btzn3=I1c{tfZ$* zg!G_phO1j+b6$xF_#7e9nIxwrgG`FpnfU?w1sj_d_zEquyic3uW zY?`wVdMBDC;lKSdu~Y}TgJo~PKfSt`deKk6kt2}H^%XD`#t~ub{&@M+B+|N3Y~}f*L+Dx zxZJAIfzsjX_rA##>!(LL|IS(hPPVcnW$W`1-`HIdyIF_h9a3(Rn-{5FkaBrRFvH*> zpL6LBqfCGV?!EiKBWU>_eI}^EYNcq23VtD??y^m9nG0;DWe5lV8CWT+_=|~5I-TKD zcT#xZvkNaK?zRCIe`DQOd@|Sj4O%o@SW3Qf=;7V-@Aij34_SGDhnV)wV)iuIcjwnh z(L7O0JEc#)xYITPT6Tj%n}_nQsYBim;E3`p3G@JYjH_;_p2deYVxx1sp62!`f!&M7 zOermxQLEuvG(3*<44kmrT}sP><#qJb{q0>EDQ)@w?SN4g3poM6kG)u|$W?Wr$_4S` zvwH(*7n*U}t%+{Cdn&l10)~%s{C5Eis^8E}nSw50<+VztfiVAqJJM+%c%T7e3ZJIAfR6~e-P`7)#a z`(^JJAOg0|q%HpbO)?140Ky&6LaOTTTe0ev0+mEyA$D8A>!biQLdiOIF-=DKhRT5l zv}TNKa2^fE#@gF9EW?xgDiou0sC;z_>@uK!?>@FA`t%O~f>{g*Sb0VlQQ-<840~6~ zX}Dq+jcrT7RVpXA>hLyH3ptD7mVaFc|8H=XNWbTtK+#r%jzXTiBx&meM%rRS6sy2@ zP(NTFkur8nB&&_$3l~hsq4Uof@HE#Y`S+Svj+vFC&P)Q({xHvWQx+V#f8+frKY35! z8#|<)nz|Q833eP)%cU(hG~Pm?r$RL2QvpDyPwtu7(hc9}8m|+f`-AHQ5Vmvh$hHB# zjleJ$`whE6Q3Rk0c>buN+M-%RKu9mZF(UnEDp}NANrGHhTG)AZvhgBqB{lSQew-sZ zES~7+P|_HDn{U}6(int{HCRKb{rvaugr#Mq=FsN%uAGfegbU)vWnVhSzvUK3Q^Ix@ zKFVvmXA%BGS-tUXqV>(;Hh)jb+`hPK|LS(UQ{W4X%9a)R3@GVWoRbT~+Rt$FGtW)5 ztu^Dzs|~mfs=o*>e+6P1|7?yhq&J+1jSHgXn6S$77%(~foecT&Ox?<82 z-`8v3C_Ikgx8S%>KGfw)c~H_WVTbkQ#kJdA799S<{Z~>0jj(h@dH`Jj*G6?+lxn4Z z;bb&r>4hVoN;S(6ahSid&lEQk{rO1BpmCifUw;ORJ)p`fRL~vy=h$-G{$T1L_4Hs5 z@+E0C2)6*h6NQm3bz(xl{0im*%0`kbmQ`{utjkR*nUNqS>&~fK`eR~L7okwOsPtYs z4ZVgghT-QOrnYYYXI>G76J@KgHw2VWo?9&R+nkC&>5fn&B7y~R4Hrtg%!i4swoTO=GI+&&Ca{ac zORha#LwTz~*9QXKH3t`FW=`e1R zTwI;`a48fA`##+RwLxOaQgMe>fvH*U%PdCE#Y_aaqm1T}C^rHR{a_%SQB{JM){$p2 zU0MQIhC>No^DvT-7@#>(2isXRR?S;*J#;hSCH84%4M}zuP`XUXsqbzB!q?p}MYu}~ zs88Ro|H(kTBj!sc1>CiwV&{r&BBePs%&QB_`5MXd>mY2TBGw%zv;cE`SGsYpQi$6S z-f3hII2P3~Q&nnCkl*C9*qf6?eA-|HYG&KJpH=ZmWFddy&;-8GD3DA21q7ud@L)eM z&i$LbeBd({Eetg39pC!*RSf@sBrX{E>2eM7h3*BkAF!v)^A3DE83GS>V}1$WX2e?hJ06pyZ?g z`u~^~b4kN?Y&sdmICTclr%Ub}wo;B9zp5w1R(m^U04zQK67a6peqlP$9_$-RG*nlH z8oiIeM1ChXN_M@&COXo0(Ddib5ub_Q;oW55w~OKyiv4nZ$KQoW zw~!&@I-`JS;cfe5_5q!Y|1ycFs*&>Ti6y9(f`+{S|Bt5U+s@>J`;6YI&eCNCw^&0i z2t8-VoSK8Wnp^SoFB)$sSxMP|MFaw(p)hRM?Z4tQtRdtDTg5Okxo=t6yV3bb;-g4b zInaU)Q23WddrwMuFg#S^KD8~OFgg7t{yynidC(nBo)mPF~-xbn<*lIk<1; zSHGHRmA1r7?|g8;Y~ryo;Eb8b{5Ifto4KHCT3=rPY!1>`7j;IzHM_^hWA&aewK4@K z_?yaKa-a{;HEsv&D9c>VN0Nu7!gBdNyk8tHt~XWh-y>F%!w%KfF=VecFa|VU5FgE) z-k?9`--wjU51Iebq{n`Lus`PZp?|e57b-K6N$;DGT7{_n9ZPm_J#<(U7OO35J2Frw zGQy(s%^7kw5mir|AgI-ti%|tIX2}G2Bto&*XT}5QdzP&j(K5O6YGO55&#;~Q>Y3kx z{><0OVo_?_NR$r6J=}Mp^1UICLB;3Ffkx=SFbL=uju2Ys-3UYYQvreMKPMV1EgQ=H z8g*_bFyY#fB*EmPdJy)l`Ia)-g?0?kIhHi8+KCpHN}1#WYLN?Y@?xPmcJ|wwEbCVQ z@Q+7RK1PnI{bb8KAqeM@tKsDy7~Xt}^vKLD2%M646p$vo-{*MyJnrmYlvA@DIv;if*M@mUIQAqnU-e`+}AdsRoD zEGT$mz7{>pA$i|txQPDt>4g1@#+_$wY1F4-Ma!~PDhX|lolpFLO?hS1d%G|87lR-N zY801hkkyG6Ksa>XV0lq(kqHD|c0H(jVkY{uATY-Kw_b$RUMVqIjR*64Y{gJ^Y;qZ= ztSw9B2$o9E3FbR)=FvYA0aG2atqYN6jmDS}CLiU4bnDbKlGXndUOm?@>;gn0S&z`a zz30a>bfgWTj(|;rk-|&$Y9W3SP+)%pA+Z@}S#!vZItK-XT?dlx7{#SRU^}8KRT;>R zM(R&wC>b38NB0#MN$B6#cM#{Zq5MIvrO{*>5Fe`aRINvR9M+q-NLkWklfxD*@OQUM z?Q%mS-Wj5qD`H~@{IZu(C!bIkp(8+o)d&vB1xS{#|JxfNDk?x^@2T1)*3)^BVwuQA zM)XUh;vKx&C=(^00u8wMZWTeCpvOl^RZLVQgRg*%*#~2+epFP11cr1eFB*jhQvaq{ zkRp;Q5$t!yGc2q&Ks)LlDjM%T_SJ8(w$(l;H>rDt|Ep`>8fGva+25~{*Wmmna3o9? zDu|*F73m$dNwNXePT(Sl5g10F<(Mi)k4cMA6ST6QoK1CS(pa21Jy!mkiQNYc{NS-J0Af(hmq;GS1OwDi^0R~;=hZW_cfkZn^-mVzJTN^`e0dw z|M6+NMPxoV|73WvaY{BmL&s{l(s>rEKXu^!KIc9AFPZ5s#Gk{rPiiC5;+eC&$uc4X z&hDL{tC*Jnc=Y@wGRXKZWLpT#P=)0Xk6%n$jw>Nn(DAf`sS2=w=;H|jhQL!eG@W-Q zN{8;@KtrU1s`xI?J(;16D%E;Jv&%Fn-#gfB&ap+a_I9UMdmG6nix+T zRjI!WjEp3?!GEtb2QXbJU7@6OQ2>7_PH?^vdh3?M4!3y1meo0y;Y>8QryGA{AN~&S z%^RNWc@Nc*G9acL^LYyx?m0cWjvB!xB*@<Y8;$dK6076MwlicUa2|;FUon79S&nM7>mBjt&%p-ZYl0 zY`L<85OKBQW>mv9`Pr5N=4edISNpae^>U+FqoZ5VfMjO^bZLm@c7?fz=)*-o+*qqR zmkERkL^F;gQ9to~%Q~(%W8hF%hy*X7I5f1melipyM`t_8y|?jLbtaZ6zAet^lM9^~ znDPo6Gz0X6OOl9l&~%}#JMvC`Ep4gOB1+cRs+vlA6|qX3U83`=ok`lhv-${}zT5eq z6lrS_dOK?y9EOYcdmir^UF5n~_?b)>rn?2P?4CfcHXgYy=Cthp88rk}8!kFTrZXH` zgfD|l%LaW`9{K%{*5SXRP^MPbmKNTE%oJ<*?!sR9V3t9U$0|f_EH*5Dc`h|-%B_BL z-;eqG!l1T6TX|h#9^fKzQN$G=&tkXmdiugSwi>T8q!MU(rKY(H57X=RgO)=QWDa(8 zsktgT5QPEXW^dhdcrQ4zA6C!a*89%Z%LV%_NJqu>Js$bvc!~(nrO)obVm1dREhDB%2e(XBtg$cvc~8RhlbE9z@%xLo-FToIl!%q6N_9QDB!f{S0^ z`QSdZFn#=JczX>mzryrQ0PwoTX;KG)U@Gq;V-MkQ4}F z(DtA~=&Sp}3SmOJX^mq=^sOm7ynOo4<$Zan=XpaZ5<_AK*K-qiI_XIUB^SR>Ylu;S zrywj!t!#Vgn9lKO#_)AhE>t%~57W+nGFx1=KFUWG@|LLdHAyheoYV_TFF8usz}^9G znqxuG*KXbbjnsEa^tHqCy~1=%VGnwV31E6?FB+JqIV_WLjTz&-n;m`CuA%X0gE^xT zE)Dov@q0HlsoAlHs}LPQB{#5C6W-;ZkhQgSZ9}tDmCo*t;|pkF4ddgmKj|2j4eqK~DHrpnsmW0{Ii63nR&{db`cx!`*_^-Z__U26{L`pS)oT1&pk=n_ybmNZYf9lgWA}kRpOQK_k=)0*klutyYk93=McJp3TCo8aqf}cN3Z~VB@W;#^_BH7 z5<~G5sx{uVmzH)<*tC6_ss@}eL24+%Fp79lC|YNYu_B_H#%GbnP~xZ_Q~&DLFL!r* zQtmWZ0WepfluSt|f+$SC6H|<#a2F+3C}S~CLd`@+ixw*Yc9I1DJLE#M{S{*7Fmo_BZ-VQS|xa*KU?k@TcPEbJ8=YtTV6}UX9%F+&{~t0+|}(DOFr6q0IkZ(l3Z|;px+`7dl!ms^pXvTKPm)`P~_^{ z`nrkmRcmnFj{6yVzvj23tWd!FFf(WP&-YFz9zu@wAlKcsVctSMfnRnwAvn372_>d)5kVf7+JpXz&yj%4Kz>1f4J&LioHf=qy_ zNE>y_jF(SYGe@Wb#x%gzqj?BPoV-mQ<|8KX-t=3@Ed^vGE-nMy0Y0XA#(#`9X2P|> z_u?b*HwpijnQX%1u*cr0#7OeuX0L(feCPfD)~voujGmI`O`{x1oM z-m=~iUg`HI+^o{4j=0G0Q!%5NFr*YXE}Jk#{IdkMky)P2d&f=J3Q0T@Dy^S{kV6Ov zyMN&3>U`LvK7-hT!@uJQsPa@*a8FiiYg6|IKRyvFQ0;(o4O^pI=eW=)N$jD$ry&*N z8OUwj?99m@AI;+-^c*N29J;iWBVUPHjivW?D*eaRMq*~$DaSsb&r+Z=taLkfA-a25 z~!dHj}diKp@U zu`53jX3YOQS$n=w@(5F4z?HHFw9z57bcAI__%<%h&Dus~cmW8h34IXqS+#vYd-Uti zt??9F-h>?FheqimuWV0D!2oZG1KtrUKoKp=F8x@iOn|eHYBR^#j+pz50dZyZq<1Cr zhJmGab{Z1-!0)ZhRgj0ecX523H1XN_=eot4>!qwl#P*u-aQp~hne+yZq3C~><)?Z? z&=7JXD?8`xvtgs|_Clbe_Sj6~zJvl3snHhPk_|9f5=kGRJmTv+OUOnJn4G;*jWAwZ zC9(261X?(M@})zCC+0_=-_&x?%wg6Aj0dK zH1sd~jp%=s!d5-t`1EN>yiF3u*#a&W!}(3XWLbj}i$944OHc1_Sa`=LCOnT{=5sNK zyu|)wZuY29=W=!F=7bd~Hm>$FG5(}SE|ga`9#BYx+>1LviKZUB@CZWvZ-Gu~cam$u zW(1)Twjw0+U4q5Vt4B?prY#sFl=sqDkp!NOrDTOK^&63xo%pl|yDL)E^XZWCn5(T$ zPvq?^OVb~2rg-2umTMj)YU|}FBw)#~#x}=Coe}q)yQQQ~iDn-Dhn8b^Z}k{~Se^)7 z#Y$*baEP}s^v~f-H!!R`JyauACzcbxL01kNMX@I45vnU>&6p!-TN3i4>5`T^p#*@{|XOzwk>&)n>WIu*#=RV{qpSln3Y%D2#s^VKd*8ZLlPSe+>DQFtw`xhs`! zBT@jzg(J^2qyp~`wm5gpRiF%0a^)S;i@vam-4K>feIA-XzNecO`3a~q?b{o@;to?i zeVFOz^y$bG$zk_;p20yA-h)ZTz4glf5inw@o7bJ|lp{=5K0I za2rK9-#Y9;E&TMEilHC#2p>RbRV_GHA+`p4^!;c#kvpVqpQf%3!X#wHb6S=zbUu$<9 zTM*A6C2RTd-;4t@gLdnpg3OH&z3<&D^8W|qUY=b*iz%x9vFYP7J9faNii{B!Ur(>P z+aN#=ltcI!gb5K_Y6>zv9I*!)omcg4 z5%L8%mU643G5433UW*k!g;gC$!|vJyeO@)cjTx?*oky~&qICp^6GF{HXnJ$T#+H9% za=%_QG(qA!J%d*er(*|e&{B<;7#)iNIfHO^kBE?jCWw+`&?R%Bs0)ZR?Py8HR(c1V zzZv}7?=?qV28+FN%v==360oDclZ`Fsb2iU~Qbs$`xAK^1{?iN?2kh(*QEj?CU%z#E zX$x}{ykpv;2v1A1>)$+?uYk_Yoo|3_8%8+M|Iv~I;8eBS*wy?ow<4V^A2vYV+p}F7 zZDsk%TLh;MKY0#ZCyXPF%P)UfmSr<^XOC-9AKPveQp(R}|HSx7A;mY|-AM39`zNjn zZmwW#Qe44kz)^%0bK##>CJNC}2!7|@y#b%ucdM7yzit%&ZuHa{DG zxgah(OS@(?hvv=&nQ2YkAE|TiK8}p4Nqq6Pyo5CDPLIl&b%x!gv-r)Q2C83&dJl_< zDR`H2v}Gp=oX(XfUJ5Ks@I<0^q72 zZNfpTL$ebHP`9}+?fUxIO}*q{b-F#Bo4~8-npBMMC3c3xwP%FV|Ff0G(r{^V8*qC5 zD|TlUHb%#4%Ak*496dVV4wTTciUnDRpyfD@kj=lh<@=&={cKth8)PSaxQs_A5MY^-)j3lo5QPswg)=iWQ8HOSXmC3{w-l zfn0`zZ^ZV}Ewrkpb4ZezUSb54tO1qHVSNNp+5TT~-TeEXO1>=0-{eNvFYIn0#kVPU z2FcnId87lXwO7HVJO&$SQ3k!Qf33p`&{k^eSdo7NV6IU+U?!)110KUW5jj$kcwFC) z(aaG65}{Hio3L)!24wf$9qZZWRIk2{EjtYanY&Kck{?@JvaT`Hu%HeehDSa-uxq)m zTRu3jD6n`4Waa*IDI9GgC?(M#YeUnoIXovs3P5)T2xp?c;6LA84hGed&@fnIXEq)$ zb+-#X?3W;=(lgg&eKb>4GtZ@Zb26%e`SHK0JKKYIKh+Jmn0A5BuL)w5P!Ash5#Z*< ze40dLLfB>uQin{DVjssHjUpvx!viS{D~{L%KO2W|J-5xb%(8@*aiyA38|w5H)QQx8 z!)RWy(|*_i49bi&wZvRc5=mMpilc1@?rnfo)?UwVW$GxfsuA}Lrx!_>aVXFX2NvLi zIl=NPj{lk~L#pw&OM(J#7np8LQ@`mz=h^w+NIfIC52xus6jdob!AV8829=}Y(5AQj zz1&w7V>@cP<0=k&`d^ulMF9Q20t1!51rY$X=OScVaujd>Ck@o-r9LE)MCoeb1gSYO z{$mJ_2pGPR87>0cHg}Vs1F8^M0_(qQsboCeUULKTJwXRuH-e>CiJAE`&Cgyp>4;LT z8@g1PJ2yS8ajCIbGF|!$Rd~$y{q<*Nbvw3ag82?a4m8yo0yNZgI)uRFr+-lJD4w+% z+sNp0=8$g>%vWC2J9o$CFlVT1M`ptJqjdbYGaWN_6wNq|1e0+Q3b%E1WIzdz(=gDD zxD6713b||uCJWN>&2IEzHgfe9(Zk6vgxxxQH0IY?+aFRlIcKPRAu%jYUW-eLcSwQ$ zUKw&TkD2u2yYlOK^ukvAaM)<3D%eHLx|v7#z5ww=lzR~k{b5#pMsC$GQ_3{~@AUQc zDr)3)<4@~|f9#{pwsLVIkFSmOP*~*Adw8K8G%`Br4fZe7Ah3a%%xGf7T=u9BWffll z4gI|vf>v!POF8d$WaAHSEDeGG~3#RvZZ!K>?2bir1 z_z5Ez7Z;nzZD07--bt2P-3{;b?JqUuaIllsrgIo36kR#`n}lX45nmFp2h7JD)u5FF zYFmo-O8Y%`aJFnh8B$uvNwL;@PdQ`k-n`k2f(q4VI}ULf{=$VhAD_-jQrW(n7xCp{ znkFB1S$DUreX07iKjUw266LM=`r(gRLYm&ytnd>l+>^w4D}(_pFzj>kGSowzlO0CA zC1d214+c&6Gw1EL?KXkGrDwd>e=AICOg6(iDrw2{?J2EH#-kr29( zFI_HW0g0qh1B-;zbc7>j(C%^|QD6zl8tjGhK3DzYNmAKzu>UtLPgJP zk=DZ!fTQJ-?uBBpaj8G^T@S;>M6ZywqZsDx___jNrfSV7ARS}OSnTUon zyIhK#6Ilw}45LI#D~)CJjS9brj#GvHpkARtyM=;XxaR6g!>?w}@WC_3$DexT2`ysq zHi>}ODu&mju`Rz7e$4oK3^=rlXNA5_^q;fw zMOGcW*sgRPB#(b%l<-Pg7;6g=4i0TcNg&#ut#keu-of9<{ zR>^k&^XX)EG{5@3>iOd^j3UYTXXiWyj}g2p^43R8vzdj^TGXuKd$@^2r8uc)n?M!` z4JqH|=cg|_;}Xc>E=UHqMY00huMN&Ehw|=9x{4>5_epK-)A^rcsnj`nLh9{g8RGXm zI5E1d%KW*{<(toVYo&E1m1P7otL(`hj{XYqN9i&%6X_)Wiu(KLU1lk~oW$Z33>Z2^ z%o`FZZ#7LcM<7=*y|`K=C8_$G*2q_xfJ!a|%4Y)Mzvq+Y5_XCifmXHW`X^nVG9IWX zIpb_|j5;kVRm;*<@YPIpF-1s)Oe*Sz z{b~@)5|b2t?CX80teZRB)KNTSz5QaXqgRUk#?JWB>>{`x#5BE{ugMDgicLdR{4_I+ zBtO6+>q_O^q`u8%2}n+S@NPoa=#izpqta&g$1>wpq{G;OQPzN@s!P5@o#MusL~X5n ziD#>B_B`53yMf(eCAf4Ggp3M_L_E8#w3NT4$n1$}LL(QK?F?O~q>KRs9xTEzbx+{;md!6%yt3=uU z{bpyG_TM^1Ow8dtmJ)`bpIDNhaMs5E=0-Z`1AnfEM#{zTu2u`Cm377Qqz)Iht5MMf zOMTmG-*4$ExY{L;cB}(EB`z}}C=pB!EK_jQjEEU|${t1y!>yIIa+H>}Mx{zVt8h20rR%+~eC~~7M7X@$2)Es$ zHerq5^A2G&M^Bnyn`|Irf%Ry&Q;!N_W19V;+-i|(9dgPcZ}MT6UV&_v%^qu2Z%fbe z$x$QmKi3_J3%k=#HVrk7i1vt{RIw1s(0oFH+7poQ#44%_7T-Mtf-J&bA%SD}{{Ff> zFO&oI1z#ZS)GgOvqVy4zed+JhtNU~Xf|MWR-lP7+!VOq);v?yfub|BRvR#I%;3Fyu zRIdgw$VxpTjof$*2qmQFQv7pY-E+0BZQg;IES{^UHLc1}&wAtiUeWD{r_46tuQTXd zEO6N7q~y!1Rs`^OetGn*r2giZ!Fl>v>Dc`3Ext4xT&Mn?X1aO@kU{GODCS@il@nOp zk&|yv>PU%r9DXTr;>VLeoN;RD~;{hp|Zt`)YENh=wKtJ6%`jj(Rh=y}AWA^ojUR7052kA4X ztol$WR;JAT1P!R-13Ut_Gy9`jo%9|=+E#=)X5@lq9G7~x(GcRs37YyXOQ?MAio@k; zzBH_S<;^*mxXUnWq>KF9G#2Y<^yHL8&g!}_(=5eUMw>euhQz&jxm*j!h9fvZ;=p&P zs%0MytT9B4)|%aQ#Y!w1q!R(;KKjs7 zgO_PdnR^|bDrD}=LHWYw1ydA%i-&6x^E>k@=rvcNH<5>PoA$&*N_bHPbBNwfY~|%V z{?U1%@YmrER@ekUa5ZXP>Q*kkBDY z_f`^Kf^mnJmVGEzl&Ite-Ds|9rf^Bz0B6F&w&~A#<*T+HUv@i%`3#x-^PkG5>ud>)PJt>ZLQ@XfWE8Xb$1 zPK=}54x|B&MyPD0`$g&4sDs&g$$zZQm*1plBRw(ytoDN=LwJ!N&e7;IGQt|*3h1MB z>~QFhynl9pA*9)(leD*3)kJdwk*ca}yzgWMEv2MHXRths-+S&Bkq*h^MA2k1J~W~E zU}2`fehmz}nFC8e8@+d9C+kYGOq#D#`f}f#IfZ9dK65$`Ac?fQ6ztHvo8RT~9dKMu zt(B42O$u!H`1yI)TmOFefF;+a(b3vU?LdRJLjHOt&Yh&j8kOMG8Os4-m-lT3gY>hN z^zt8W9oLr&^2Y7enLjUUROu;41={L%)gy0LMdf7-%5fU2!tg>!Y6|xkk9TBz>Z`)S z9)Az;Fn)A#{&YOIRg8@l0^}{qlqz<4$yz!3X!ma32fe;HF#xLG0>4YFdOmO$k*{IP zy-|2ub~NJ#=-AKid>f@JuW_nf*6Bdp*!j@s)&(pFj`=wslmeD$Lm)SV@u2i4PmlE^ zD(!7#zyLb^u;So4iK|ReZZizei#h7B()NHn-VRNh|0#d`^~3sUD4kBwQfsE~(AJXX zy%gnh1Ks9P{n zY!R2>j)gw&VyJG$t`bdSM9o6le6FGEOj#it^i&kMqaH zdZ0=w8epJ`qNke=e$roL7UU=tQ5Y(7CB{T3qoN4w~{!LreM|PZ-f;ScjouI#& z1e8@C&RAZUO-DBh!7Adxn!q@rRPanuh8p{CZ}MF7au24$)Upvq*uWy4812sjH&!yD z`-ZI)XtKhnEpH-nj7;V06V@Xz6Hlm-CYM06Sz2KTo16@7`=r zY1C4vBXN51dYFgme@QOQegXY|cG0 zEA|&eM+i%-VZAWlZrZ=5lFD;svU|(P**HfYmuH(sRCGVqPAHGgp~zROW@3flftNEh zKYiwJHhd`jZ4^U?lG^qdr8DTLa{)xYf(;~-4(%$6S8=bSZlq zJ#v-!s*M{z@UPw)16Z<5P3xe1Z{MSWzm%+Ugu3`k`OB?${bT#9&%)UlQ%51IA09nX z^?Cn)UI3;awJd!;lzByF7+vcAijltcW;)rzj;B{Xa$)+(vafrBO(B;Mgj^6>**S+u z_57t}Pc4fP@Bs*5=^USN=>v_(fZ-%c-@<@yQfGm+UpQrws5UX&6E*O476TwPpkJr_ zN^aFZ8$pMUR%Ea(krq60^ic0Q{I)#G4;g=a92C@3m)IqxL5xsS3V5(kAwZ$awj5|C zw=(8=(`M7J@Z2;txYEm1{825c9+&vxs>LcUy8NE*YpENEqkO9v<%dtIRxU-=hCQ{Y zE_S9oq=vkqL3zWr(zwdyQ(?VulfrBqCi#vqh8N3jm#=yM!opskJsv>29|#K=$Sb!2 zNVMY_pe0eds(K~+ou-4@0fGJw^lx`tPTZ(VZ5pcEp zdqPr1H$T7)yc77yNSH#u6lW&esDrQhVs^z1u5g9b(A-iT%dbcL>{ep&{T!xgSyUt< zwW(q|$XLFnhp0Z1tnSX7Zh6d}5(?7hfN}&KR(u5g@}UmWYO7X>k@31(@_Ke0<-YvU zt`=#nET%eTOpQ*<9*={&Lhliv}l z7ru(+@42jnKL9!8tD2RA)Je~!%T&d*u`^j4S@IrGvf{iIZfw{gl%6^+oTo93HXW>V zWc-oHG^?9_bJu?d$YP33=wK9%>~HZ?brXYh5a8Sr-*+@Tv+*kd*;l|{n$)bAlka@< zj6)eue|^wvTrvU{*#mi}2~8LAB_yYLew{RbLsF(DT25*Tzf?;_0u)YWBlIEA8>Qg$ z%-k4$^+$4zC+yZhk}Ih{?CV*$pPEEvQ{^Z=3zcky5y4hM+K0hTothx7Lu*M?Xu$8{ zZv3qqxMo>c5g6!2b%4kUnFyg&2@S!;#{H^q-5a<#+kbHsD5NSb2C>hV!4a*7J=wsb zsrTVIDz_3`p0O)0OtxkYNRw2Ou;1Wa>Y3C84PlJGRh&pTKK%UzQdqs}H{Z&PEq`34 zBL(okvkEZ^7w6*p857OQ1Q&<gG&1<;-#3TkvOZXu)urxvZN7h zm^R+o+lv%JZXVCO89mc$yp`8+9{u}b#ix&A15-h2 zUXpO!BTCX$b^DVqo&u8Gf9HD>QZ|*935Kp3i1}$VmKb)r8<`nz<;o4UX{|)0)Yczc zc+2|?%#SAC)(NVX8xF)A*_<0Q?~Tz%2aAzqfZzetj$ zp}SOK(#nxk&&6m2b9pquC)r*rU*hCFK3<8zE1CYPBvC2?eatQaa+^ncG~m>i3W;pK zB~=#V##RhL5XRu|eatcuwvX;yY!19)XQoVO2yLDsiO#C-bF;AG6Vpo^RM!gkQMWQu z*L=QsXrD`1Q&Ynvb$#Er02z2;*lL)kAkp?C0jhh5Fy*PqW(Owp(gA*%3oxm8Vxbwg zR%!N6qb}>1S^J@F&oh16>4^$a0tr}Zp3BN8YjtFa_zNdbp#dvFIIsErDwhp#wyaaq za!%&piP2R6GriEJathj0qy>D1)Lx@W>2S-)LpBk6ff9QIs21qtpjx#b`8A%$SLzRK zVY9k1#qVOmeVTdi3ZVy`??q#o6Jnk586c7+$Uaj=faRA(avRXc>4i*E5~*3)FQxUJ z@j`+!`Dw4`)#_4ym;8bn{QvVww}M`Z!`Eg+MLD!#7w}A4o;1~K1`Wr!LoU+3-m5}Q z&EKV-zpuC(*G{5ch2oE2F{swJUf5ZNe4r;PHoheU0z?@I5Q6YRFm}3W3b$EIMpA7U zup^HkxpY>MAZ`P?k+`%EM=A~lEISg?WUikCbe?W&D_jW&gnEXopkS?<5 zhN`u`B-{!jFIin_%=^bh0Y^?LR1yp1R2A*pzZB9=OQeG<{i_{{M)2>hzsaZG!lI;0 zm0DMQxGy0M1_mBi(}SuelE$=1%8IJ*QJ1iteIVU?qLSVxhaJ5Nd9$z4(^mQFZKEN6 z@gvF<#>%(ue`wRY3?wy}StzWeQBc-Vijsz&9(>R>8$Ypf(@B!wj}oD}(U1JUAOyC6 zO!Ah{pD&D>_EF=9h4j4seCjoLYey*SdCA0z=_!#aHZGPCnq$6TfsztH_bdS2tx+O5 z>^iuktTG|UGV9E)q&8Ff_&v>(O!nnw{p^jZ=q-zi!vRlipps|aa-=-1mlAAQ$izuW zN^1MQo1;Gcyr5jG7p;dMd=kbKM#j7aTa$Kq)uL9H4ah-b2N5P0-o#N9U=;HZr?M9% z;NJ^5MUi-h&7+HloItX(N`*fiQ!bXCm*TuEJlK;Z41)d^0Ik)1WB5@e#B8LMc)srb zk)NW1&t&A7 zKrY`=8YNHv^cj4mAR4|N!t1li`vT+DRQ3t``uE$WJ5nax$zBQJ$@^zNQM=5g^B(Y} zGj&=!Y2eyo5gw~)ad$OPDP5!}V}@h^&+4xF?BV}M)>nr`-F00PA}L6N45HLf(nt*{ z-Q6J|g3{fkq`=VK-6hf~-9vZRNSAbdKkoZ^-mk99|Gbzv=gdAk)>?a?!(@#D4}xFp zI6SY7zEZ!z$#2A&5KuK~bckYCT}x?kYsH8uK~_oGt-tw>`PK1QLC|2dOMlymVF*7V zC&gRb<_)q*%m!2Lf*YSATYfZMA4ClN`t#WWz0|aqbK6kuMS421Gz|noJwJX`r&2Wy4d`=rAMg-W#lD+6>mlR3 zX+*?BljRYPX1Ri@^dX?c*Q{6j*&3o8qloD@sc_h!5x963}0OYD<3A>++2Gd>T$y*!F z?gkC#ewxa%l2pzDyC*#hPaZ?%vMNUA@kL$$DY zx_FJ3J_xu&gBNuT3=E>7u4*;U>fe)FndN*~Uf{#1r%p3#0{TUH@T9K$OE-8l3wOCy zmaJXEuU3n!3E8Bot!Zc$X&Lf@Gl*;1$*;WJKMXLFugoCpyl2le-7uRzQme15xZiKN z&a18Et9k74ad&Ud1@l443CPNPYEV)$qq|e~&(J^_kBJ0S1Fo7{ z2uxorH}~D(ec&apL*O|U5ZqA9 z7zBFO;0H%BX5|gr$@!Pd3u^)(;Cl0aln!Acf__2UdXMX^K^VD`pA+#@=RO+a%+CkQ zkr!+a<;=^W0K$bv`3EsQW(=0~ShP>q>cu-Yo*wKSp)}mUoTx;(swwWDYCOg8oFTD> zT81}m3X&9A0esQ{I;(zb;;HxW{`g4Np1(r-s$468_Ylc2 z!_~u2gPy1laxed{PR;d@H>@teBlZhFka`lm%ja=NQVc4Z+{uFhV$MX)#~4_%YOPd+ zE$FqdtLqiV9S^zJkXE5&=rL=htrqT@Bhx#eC9t6jzM-H#Sr_2Y0tFgp00vnI2>wL$ zB@ShPK}kzk{`>NP{HTXfXvBnV8Rr?nezHH&=*A|bY>&iSFn=DJ^%QS z)Sz)kL zcJOm8my67}kCxmp;_y&*BYgRF8*iPVIKh?z;YdlLrY?I^kh^{A<~ZENXKD(?!v+tp zxbd7(J;WD!0EpfC^#Q@7R-p!tY92;?10S6OaOE?9FJh%0Vwg#M1N4J8eX&tglH1Dx z&>j2*IBksQz*2jGVb)G8N$o`D> zX=XL`hXt4idw8}9nZ7{V!7VhR=F#oehrf1a&LmB`cM=aUh$XX5RRMyPb{L98iM{2P z-FWowMJJa#R>vc!M@|WTcP+l+?1leNFmXf?AMU}dg5vyvES586OWDD}*>bA^ zKVM)YACW5Q2j)MANAcyCK?N0M5gxv2_wvu0F)6uocmFx8N$+3&n#B8FJJtNK8ft$) zZUzIs{Ud}2PTrGe;x@LtYiVAgxi7{i44N!xuy?-T?{a+z)^uBYS6dOsU71S`{zg zNS;6Q!|*RD22u>Qx(o(#mS--UE<9=A)}m&*8qCGXojt*$k=8$!DTgB_FmC64=Ql$D z!Yl9Dy{GgugdBViyV&J+%)c)TNhcVTLnZrd1o$PRg|6@8-`aiO5+DpG;n4f21NekQ zp~}_Fw)`SsOa%b1!+GM8$;=)il;3#Y`c-JZZsX;uqlHh@T*6u}|Bt4Pqgi#V`?YKr z$qIEFgYO45b4&O03mdE}mvc~qwu6?S#*&hY>XVxAXIu9Gs*57y+vY~DSlicSH?Hh+ zyFbK5j*r8ygY>H);*usEYPEp&0=Rt&3$!#K9i?MJl~oal+d(*f60L1CZ0*W%((Tx4 zO~YSwW@}+5ktiDDK#`U|UCa9Dc0@t6X<-_gzOY2%{C6=OQc$o0FJ5jQIbbn&AOCE4 zyAbtI33ES9b}?HxY#o`qnP-5kqH!m{X8fMmFU4Mw?e$FX%28p< zpF}*U|y9$(dcv<$_)NagE2SFw`>i!Pu zbSYfg%d$?lfaGk2$NRNLUf~o>tilACIS?T~2Q=RPgz)T#uxBoi_kt^m{K%$C9*5Bny)}pT9|OR#R%PY4y zvaJQ$8GzyxSX3C>eG(O9zr)6vyd$Jt)u7iz&Ls{uBcO}P!`EteK<#s1(Toj{t6@9i z@1;YcA|~p$sr5n@q(aotSVnQ%>u{N$*vj0W2S74jNp&X@C#5d@5H(N>#P0Tg*-~}Q zYm9iHd!R5|G>tm~{&B_#3%eJ=L)m&Zi>(T5 zs7qC6xpSg6vrb)7l2WZ1$qfVQJqB=ArwRqq=<;`nzoPKGY?b9Mt(BP(m}SrDLf(ErD`B4p zdkV%KT*L-1F3iqKnV94x7$s8AIAti9oH6Rpw5;GM6~*Y4Grw~g*PHQbEGjBmp~Vuv zu}`Wh`++|G3c8a+SAfi&_sh=a{Pxm`ZzU)VT_E>+Dk5l?A*W8E&3v82&ri4nqawIc zMbBC@C=khYyVkdPAwf{x3E%c;AdXS>OxAI_SES&D$rU=)<_TGb=mx#vspuUF)MIll z=ydys)9LbH(Sl(RafGd87{8bXi?_Og_FoAbW0&NI>UsvcGv6eH|FE<{Cv*jfnn()u z8ityMAGFpP6o;7Or|545fa~1rrMf_K_owy$ zyd|d=Z>F?WR99-vD0T)6+wmR26e*Gq=+DpF3@|WO;UsaNSf}tdgq_HgfHk@6Z)m49 zQ*SH!mbjC-?Z>>mpI^^Dzfy5)jYMB7JS-nLpiB)v?d=)X<2nL;QBXA;Bzyo^r!&>5 z&)Ram#itG*F^+BgSGcU#%hevRvw|F7il_de+raIiPsJcW+uXr6t#O5OZx%7_A z&BBtaCR_tuPo$<3gw`XLWdcbbmSso6$SMO&6AfuM=$D_S=j4(3-XSBY#l_KHtS8il zA?}pj&eYB#Q(vt0b$s4Xj^*VRcE+I5Q#J*B4`}MUdc9n%{l^%(x*F`&h-$FZ09+y- zaQ9{2&^WPg#?63o-~+)jN;;ud=>XoN0Yud;^;0j1$|Ov>x?DoW6LHIqVqcRq)+q^_ zVJ5)hT-2_@Y)&K=pV*O8Szdj?p7DGo({jwM7-r@hV$eV zs}Nr7Ads>?iExf=qcB#G#RBHgxYZP+>&C|@sJ$xy8h30{3L_T1J-s~$Nme<&zGHnj zoT|%oDWe?u~U4V&{UYO|Z z4l(wNT@%xDF}J0`L=FY@4mM^~YlQe)z5IN43~`rV@)3kvkLrZ7;*GaWPqc(RkLK#v z)sF$M{PqBz^!<`o-P7HXPPN-*HHfuqukyugE=|@7oIKj78kpD$m+LVNV=Edr4LP+{ z(+sXGWOySq@JYCVS+ArT7kE;^R8D3gd{^|N6m`3FgCGtt+uVL^GVxHa&=Ns3D)Vl5 z&s7el{|_N<@{2lOFAPNjQ4%qrJ%~EqQy+!1aC~&Va(%?tb5p--neiX#)FNUS@zzYr zdxxcF2kJw02w-MNR|?9wRMtsvC_ZPy{+0WY76VMUE5L*=zC`c4ll!|eCeF6hgrXou zDrr35iw?{p-;>I=%?BD0p3`{AmIFmAhErN>@J|EOF9^?0DQ{u zrY^sD38>Zb2XeCI3K`;iRi?_Huxfx^vs*ovQj!6xNyoA$G1b8cS_p@ZUQc6(mNfO- z`FMUqaOF6mMi%G)1cdSgJF}F3rE9p1>QNZjcy}t?bQL z7mq0Uxu-a;_Jy{p)O0Z_|D5phzbxNuu&pxn8y8n{#n$3N&BqjZ&^B$tk|RFX8-{efsu=Z?5 zFvs8_tQD4jxbmWY(>ACk+)&JvuUT@czmmS6QJm!uXhmoUcdfo?0D150wL(GWjuLf5 z`ZKf zC-)-QvQ)WDEm9%~U1oC6b>9E=xQL1v@L$D0iH}`Q?7XISPNQe4tYA+b9S#SCxgK)V zRY>6zt**3{eGCgVm;(jiJ}aQJJS5?_AOODRa1E=PJXi|`{AFhST{_=~N79Dldl*miS) z@@<}A03n?!m5AH$US%VrUJ0B3H%o{jLsCh=_va3;kMaFJ5Pk(E7;4JL=Na@)lm8pw zXEh+IYigNjT0xa0^3)8)v{eu?iDJN+EkGq??m$lhB|p+1VDP`7w}JGQTEbIkxK79+ zfHB2uG0Z>3B9|x3P0x6@(&wDoZE(-^r!oMhjGlvD1y!M$kekMKjJ2o#H>~q<7DmKP z;cq#ym>k*wFR)|@QUGsq%vDaBZIFoZ|5poO<8N_3h~~6zZ(nP$U-u4-aYwL~TQ(S? zupXt?n8=b*fvkHEVhjOn+3%#iTsWt_8pElWX%1i};AvFD2E7(x{qGhi=y4~EmA_*6 zds$=lH6>v%%us7GG}yc1-sXRmF0@snYOj~_rLy0NhzC;rCfQx5gnZg%VxzA>jdJJ& zF=+Zv`W{sl0G33QjIJ-4$7+@^z7hY<@B;by@!~uD%@0SE@2zCL7@9*nCwHZP4(%nn zGlHh_ic5=_30(MKf`UkVNY3W}tJqD*^vAe09mixzJaCrtk_fOe8mdU6wQI{_2?eej{X92k#s zTd^&Aquw_GjA4YP1fmP(1305yKU3&l2%68%_O&@29C`>gWlEqDqjUdI!d{$X(o2<> z^}3LtD~6*jlDqJDUQh!w(p(#WJ6PGgY~rH0O=74je%Z1Lo9G{=z)3W=YM(-97}U zTTQU6m)$vBke=4g*rk*Y2k+3A52i8fQ;KQ>bTy!|BzzJ9AAfuZKQ^a+LkvI*im}~) z9hf~8W7$`!l&zK56ag*Tk&|W7%m0b&cqp6^D9@hc!u~XP@RL5$Q=tkIt{zv5AmA#N z8L)KB0177vKH^rgt=gb(%7*wpo5wfH9Se_sng$KzC@H1#9S7ehl#5xd#1MDQZ`15i zqGDqwbX0T+hr8-8t!3IbJDyd9a5@&cQUaqmh8GVS@$eh+rH9-n?fH>i4aN)t=7yc< zb-XY`=uUU>;^udl`g7B?nUlY20BgF1&#b=2o~ab@HDCougI-mb$mRjXvTal+dUWC; z+v_#g%*anCa(;Zu@w2C`0F=$IAVZDmUh|99a)iK*17Bn-+E(odzzB)Cc z#Q|FT+Hxx^pm<+;N)E)`B*~GcVm@WfoH$AX$>)mYI;$o=I+`X4BQQBa(LTlr;{_5U zp~m%pOFJNvrz``yUqJA#-)_{d2uO+M_7cbcO=V9E{dS8p^$wgMEperq__S;_CUmwD z$lOB!ofh#yHnfOssiA#~B&uvepob;_$y;(Q11VHpdwnI;j3FY1sA7YwCl`htgZFQ- za4Ak-!VurYj;mHKg-z;-b0uEAffqE z4B4dvKMB?HDJA~dK>1V??sM^P_W22RzX&tLNV^MES)p%ExV`ZQLU%`3+ht}<McciS?V9@wp-Oo(e&2<<&ID7P2BTSI=MRx@bJp8l5cBFVu8YsC_~%M~I*Vb2_f}1h&*l z&p44Qq7uEwGAmU+y0xn9a|_Ja6~VG8ng0c1^^!C+aylp1go^dF^qHz#pkQ(!66JUb zdZVSHTE5(J?uE%W2%6^AMN@rO5GGAvN_Rt2@;&A2z{4d9{Yh=OXHOEt(ij&jRgP9= z;7_5BvN`RD8iyHuPAw>WZIlZ@lolRYIxV997GCf6E!2mfns{hJ_pFd)s6?)HZ5F<>#vTum}HURHlbPr?k7IU#UWoume z8(KvjZ~7N8#ZS{$T^NYufV*CxPc6}cLp zl*6KVSoKIG`AXkASpZC)y~1RWmd0VKZto-ZOxJ17h93)Jr(cA!#+#5v0sy_c*^33H zQI8(viv0`Xl-L?MDQ)L+6zaVMe1RPa2)&Qg%bKyc4#5!mjAv1S0XS_JfPm!dI9P}4 zeOWVqa?T)DP9Tf+iz}}zwz}zlkag=1e34>s?N|g8qANY^zMdZ9*d(mz9C#1#=m3Nv zNy5zm%#|Tmq}CysHx@e>beh2V26k9YiCoJY&P$I-dt+W%QPVvpWFJ3GFVh0H zCHB??6r{`?rl8P9f{CRRjM*Gksj?{cBKTiOZO>_uRw#CAN6?y49Z6*MGCceavZ9eF z1sHJ#(lUT~l^FD{$2l`Pr_xt02BdIvpK6v!S9|>ra+V#23`GRR&Tutg6_r5PnzS_j zS!RxzbVy-*$Z-Mf>>f}*$ChXQT>4M?p`XAqoXiw)nOA08mL6nVfP-DxkO}B($mf43 zW``k3#3Xt@h3XU~1G#B0*M354m95j=%%Q)W<}q~uKC;KKi0w(oTE;-9=uWO$3!oD- zV)Za5Ui;}!+FL+A2!wAf^;XPOoYLnHAeQxuIs8wdbx~V^qaXN!DHSX=A!llMjBma2 zT|WaD*+Q_HiF<*hbjT^t7~bsbl%1-p&U9J8SZJ9bM?G{>Q)yucM+mau$`^HTQp(R| z5Cr1Hl4`3QrlUYmk5OqmUBDO;7|DZ%Tf1O%)!cYT{$DWc0-T;zD9CuMMoqVJ1~`dp z23|h6%e_|-%s@HLHY~1vA}Z6r1shD}pW|MMkr1MSZHc#4JB@f}2av~qoGcr1pTx1} z4yDwZmyu%8#=#v;?bZKJe5NJ-OGl6R61uyAW+R5g&P9&6_03l8vCvk=NlD?4EPp>P z@uMnF9Ut9g-apG;_`g6flBM_eNajy<)SD<@^YdzB0Q{@WasE)_-h>t;`R%lu^ARJT zf`cMm@wYDR{zXVDdAnjTqKIk(d3c zoakbvA*>ig)8XJ{RgmdxgFpd9bSV)nAhC;{&o>Mn)N&#TVCQ=cN5g$~B`h`RC0ykA zPia*(Gx!^w(f3S=kgU<-rud(>fO@>(NtT6VZ{T{pFYPRv9u8 z!oikQcvah8^Br{pX!QbWT(pS!AAvp8e_eCMw8ODggQo7U554J%kI?RD@nTbM#}#;r z6@yPD)T=xh)vJIm1RoW4O-vW^p|^H;;^3#6tE&C5UtTcHdu=pRP(wp8b_SqUPoWno z8H2z7#Z4Ffvh=GX96I`&SQf!1(Evq%`xKIp^405s-)KKhMFDZDE4ktO`u`s~o8Fr} z6*td11l#r0Fs8dPts=3M(8j+#zjZA=b#&|8Pzpa0ivY^cwP`>3mLzrERO6zbu)a7ppr{dS{7KK_O!VU<4Gp z3aXHfq->@gtIdjRdPUa0|w#% zx4Dai6r^fDpD`>>49R$9lXmZ!Mq>v<>~jjv{kGTy28OP4hHU^yM29F5#+J1F`2DHi z-?q-2;=7VYt=5H;lThPEmrz;44pN3Y(=%G{S;K&KHzFJM^m zeympwN}Rl{k*af+7GDxG^KnY!n;Q9XBV}df-zauUxJtH&bMv3(SxRbu2rne%k{43; zO(SI!yhD=-MI-Pl`jtilKf9%($C{W+*`!W_JL$JD&!=vB2FCF6Ho(pxm*x6`W`jJ$ zB=Rg1aVR_JI7)<@ZaIlgHed`0?bV$BSL=QSbzA%WeM0x%ZD;8G_!{ztR>)Yp&ojms zhg>=5X_se(9x%Qwb1m@@ZAMOp$&ofT@7ThcK?m~UL~)gy=#U<Y&qB{K=eG>7dtE|M5hUynP^JYDAzjxw;l}3#5k|B z%Bxy%s<}|{%Z|%6ug31)C}}stee9_JSr*>#UAyw+Z)|Nzp#Db9g(YHke4GIh?2az! zO9&a(>&2h0+s=YMpbK{?sH#|?dMrXPjZ@j`mDucZ!k}j6dZ(*3Fs>nz`=Rh1-$mU;5xejC#I?sFS^~ELPKCh@d{V z`W`4Ydx6dustPftC&z}oQT99b)8u1xJIa6jX}8bA%w>n&lkG_OqWqo7p;+`y>u(e+ z+cZX=TzX3%W~I_-qAycT(r2bP+gHZl!R2LgXQ37ab0uB^;OT6KPpKIfJa)f7c@#&w z4a(n(2Gmxp37bkNflyNskzMSK-jfGazegc3`=7j>-tUPQ6 zW)Y~bn!|>5ikChRdIrn6L`b)1`ObKq$O(yAF!L#it0ptEHPTyR*74SFRECR(>_hr( z>T0Sai?FJeh@wpACp^kR0%gn%H`A$$RZiX#q=2X5SO+ z+j!IU`_thN$?>aobhlE`($g@oM8Wl*RMK9u{!rzMja0ERE|j!hbPehvRr$O8nGz;H z$or%#VMKt<#g_F2Qxu&b!w zp5O2PYKRodR?<@o@)mk34x!cjwJ`M4O$9`NJp(`(XQsctP9yAZm{ zU)3=jdVW)L8VhQ%=2BlHIPV6W*5J;T~rgkd+T~X3F zo7d*{bkjt>XcftnnLToXpmz0OY?W>3U_6Sq;mgv~E(W(!m0+;F9XxNcJ6eb4%8Sy{ z5R)$yKUJ%GnLYx{+LJ9L;Kr=f?F~2u2?>vh`{n89`^& zpEI|NtvfVVh=N^{NdB$Tp8u#ipUBxZ{hG;KI4H3D)r9(Qqj-8HkeMy0QegD+ab%|Y zdg}`^SMyA4;j!3sk!D5@<~;(>vZDAsS+`gD_@!11G6-TZH-wcol$Ks;z5^1a;u$ef zB##I=K?_iD@+73o1K-J6ulx)!Ppm0z*$#r3S@rsKnD2<77?b2(C1X5Q zs0?u)7P~dH4GGocEFyc>^giGn$dL$4at_QV(e0!d=0Q@PJL>63I9bZCye||!ktpqv zaNC1!(vouYl^?x*X{)O``(RkPGoZ+sHx-PWdHIE-{c}i6%I^LHlB7eU+roMhE4m$J zCFb$-b+#}MlrpmU`ik4&E3Fb|RbrOW1CLxk7S~zPp=I`fUb{f!lu$ee6}}$gOKFhm zAvj@wcQ*>~apZ>>^zc7J zclVCq zjKh-n^|4 zgEoeFUh^nDH~5@2+X}Ut4=WgF9h9H2dtS1F-}8}FFJO$oVw&5%_89~CvmC+$*CKqd zU?l9^L!hr1)MF1S5F66TzZVr0Le8fwN2zU~!`03gIH}fWVV_{Zwy}W=w{w_x!dbq7 zv52Hgi~p=gHB4A-)E>^v>F7Xk*$ekq->fQ%!0j;LPlw^bFQA!a1Lk;9oHlg32K`lU zB9eArJ$juQ)*z{6b}yQyqS{F=oLDzcz|Z?qxBT)(P_?w8My;`**;o5Zr6X`O+d9=m z1zl>l#7Rej+=xTg)653Jad`MQZaQdH6{MGv$%GVK$qxD_Q>0P~Kk%%q?i%w0DHyv* z+g%(^lEuH;;CGf^B`I4_axI?IfqLoXUkq|FFLk4ApT+G%KKs6XL2CVf1hMeW7lQsU z>p6LYm!<4lO!Z99N-o@e!AsZqwij-Z@afmxpD8Xn327u^p~FMnv*24zVCuvnXVhQk zwbrK%+3uts5)D^EEsZGAJ#&p3dWHq&3~=}~wU2q1zqj2~f-7@cyoUXlO(n40jp_<^~98%7VFr1_^wl^G-uJ{i@K$S9eOKG8iU_8NKUD^IaSKb4w5Il_(Gk9YX{P z^jO2J(`P$B;`~k*OnQ`P#%FsytJ;Gduf37e*=4rw#5{wAhlM zE?rgDWne(x%uB^SlQ>kxE5VX`;x%CfaoqXklmG?)T?2aMQOpfq{YU z(hIKT92?|KY8;<~l*8t$l522U)EL@iMPmL=xkAztzMOe^zX!4Hc|9ykQbabC_WKJ* zV{x1{8p4A|hSMCa7sYP(QYa92ON%o+u4ZET$tLiX$Mm=Z=biDwRc?@~?gTVWg{eYb+C zeuV2hlarH<>2^J&Q*J9!XZb#lw<~&%W8!WriZ&T9zKHZ?dX)VJTx=UGGnI%Yx#I$E z9vc7AGl88^=HtF)z;*C8kAm$hvaK@yAFx4qFMBO214$Q8 z)jO0>*Rlo_+`(Y8(kPOa!_Ix_^uv!p^yg7{DaxC2b;M(nkh7+-L?ZMI8dm!!hu7x- zq2CN_N>mJDKf6L()pWJya_*%E7n5uWxDeR=t|8$^CLCZA<6V`xos0isjb+kM^zjA4 z+Y20?kPV)vkCpCoQ>MhN4Z_l4YmM2P!Hy>7?_dqZvxOYjTkvl2Y;`xjzm+!%4fFA3 zD_#{4Cbvx&=~#_uzu~SME+wlXrCK_maZUoZg#lXV&jD&QT-V_QMwzFN22vIYg#w#q zX}z#2%JJ-tJs|Ni^i0OsoCuVpA&TOl@Z3yOeGJqqu`cF5+=sUHNnEjz7fc6r2mho0XZ=`~x! zgaqoyhu(jmOW4?qbtPJqLhpNQ$gVhR7ludwww`dvK(?BgsrA~T_yZ@~HQ6dB5%j?L zLQP@OcXV=i1Dj&A>#e==N%;P7f0RT;4A1=y;Vy(_Gy@ORL2{JW@yBunQ(^Z6 zeaF+WFMDIOk4NleG+;52lOC|a!^hS#u)MVH{m#2y;RPOrEc&kM_Ih&_{^x0VqZnT0 zv!^;O_x;`PJ9*)MogZGw76HtsK=&wu^>cyuZXvKTNr%=R^VTLfY zXddE8x9uQqIQOl!(&_{Q{U zsYhO0b0lYToU!1rrF0yGskg4Iib)`F!Og4k#j~p4*f#q|yqyigu-+i~DlC}8fTX$E z14=Ia1U<;>o|$-}A)DYY_kc0$z}BKV#!*3fZ*GOrQz~MWXun)zMn{lR9-4^_hm7$kD9OwMeRB*Y@jYZ~@?li&YpQsZ-SFHHdo^DSClZ2I^7gtaGcAh*GbtSFnSh;h)RW3 zw-6W9w7ke~JetBsXI8gO#|&K!G%FGv4JBGa9*vJ}6beRPGU1nXUJb7;&<^ja${Hzb zTr52_zqSo7T?#CMKJY63t+Nt@Nq_KaySQl9YqdEuh((YpxF)hSw&?C!1 zY<>%kjpRYniqkh;v6J|92(Cy6_bn?V3Mj_5q+Pk+Mzf{j2=w-UH^UmR&lPL68f?hE z&B(ImNIdJWO?L=9t;YTfF|$2And2CJcs_q*YXC&(EYMMFE%`vz!t{!d*)hg_6J!?4 zt0m~Uds@~$2Vj;~{gI*Y7rAf5Lr_!?SlTP7nMa^}boA;u?BeJ?!BjN9R70*jIDo$v z+bN;sA5FmOMgQ^Jft~hQS|@4q?^H#1!R-;=t+F=$h&;jho_?ImWjY0sFe%aj52MP3 z?VD6JxucnH1T+Xk^$4@@hGEZErQ4ynk@BpFSRiL$YZqzNN~-$^Rn7mg2D|{gAlh>l z-12Q?ZBwxUr{Q(Ta}S6<+u}~BhYdkcCTv)sKmseb;!^(UB!?4iP#9&pEDp5a7)h91 zV0!eUsek%`mnN8kdYkIV6@)~nR-f&^VOh0B>7Du31**C$2f-<)W7ErXFaJ}bG-i0Q z?5zQ=JH7VaJ(B&-U;CS6;N)RkQEjy2O!BH5M%(kkzXbj<(t+Pq8)Uxn-ZKwzQpvozhm9YGKS+TQFQ=#8z6PU~T79$4rk@w>b*U~9>Eel|DZ zkdpO!;UV4du=mxEJy&=#e{Hver33Ker8NyBz3y4w~nheSEziS@V1I&jE9fl7UAi zyoq01f!R$EhO9C6`?ZK!e^9G8H>Owlp99F4X1-r7>Bs|WibW>;@8xBb?IA<_rK*kg zbG}yOmhDCP` z2=6UdiSaB>>VJ*izGl8wL-ZGQ#CnhheeR)h!`uP_5kZ+_FdWfyMSjipp9r#}_&XFY z^s`pbZ#R+*D2Za+48Xu!msiR1-pmagH%e#|fj@sKQg zI0iUj@%GCnyWS?x1{2+74B)l}2OVIG$Q+0ENT5U;(Lva9T^{SJKxk^~Co>Rn`_yQT zStD1dDmG9U{32y(jKcc>A0bp=Zn&K2TZg(_+xONsqiDR0gf+C^&XB9~y%R0@@STip z&7+y(kEKT%mm75RX$SNn@L@gWj;HVkDiHD`q}f)inj&#P5&E&1RVA`T6886{qznlN z>&|Noi|pG>wf9 zkOa6ATVCNfT4T}bC7}g~ihH!$e@h^zuL4IKX~dQ|oV%sdX&9iWh5HR#iGWE7)Mq|^ zuDm|a%xNxq2`}Rq;h|b-vi;FD$kL{#U${|r;M}vUWf(5viz}O>U*|p^G={gYNB!7pTSEpLKXkpYS}^ATEVo^y+jbyuc58Ol0$ZLn2-@HExe6Qnb&++Q z6?b-oPWizlMB`JVs?#z%qZAMJXYSoJaOp@dh$df#pJ7x%_Fa2>Lcm9#Km7N zUu3+me@TLK_v*?U03_iS848DDG07~mIrNrmnbl!x)hSNj;A}Xv-C<`NHSf9mAW^xk zHnxcCp&@)tw0%r@fBwNGQ1Q1ohQnA{5w#+!Ix=f=zUOhv)xj~-EJjogDliTunrD@N zZ<5h!ucB;5(OyO2X=f=g%V?_D2nr!8VDc%t=o?p~_L)oyFSz%3fAgvT=8qryN9901 zSnVklf{g?pouMFC13JnMKh;RD)*G$-Z3Su>%gjirbC!m zwT8Ke4M#!}n`Gs$l9&(?Pwj&udQ0LSoz1~3QzrV*po85^4#MhxAiiy-5b5VJ^9#I) z$3w1I_3Fm`{;1cgkt->b@A%refvqCQwHig=a~CpEX^#=mY%A1-N5!^&%;t@ryvwhw zd7kzqR4G_q2Kl|MvS^R@^Fzu``ocN-@XIdxVD~T+-$!Fk%vWGY`%<~oHcx{~(=3}-MHXlri4V?GIn}5bwEt!o<*`f`dPu1mw&mxSr zM%q@rR6NTyO`p^;-`M`MOq26X>YK!0(}~boWLM=%EIS?b;}s@RTvj%{3<4(r+;J8yyePNQD#aN|v+l0K$bfxDc#%!#H>w{=TMOd-hsS zv!*$;<}0_;3BF+}w5pJ!OS_vdOc1wrkn-IroA+z!0Sk-;*!K~F*rzX>`Hgy##B8Ed zz=M^u^xXrcjWvf$FiG-koIZ00qJYXB+zn5y&N`RpEvd*_2OxpT1` zh=xS;*Ndcx6vo#ibFRnhqY`3`BBMp2*h;NBJ2c?ZSWF9$f=d|OVQ>vj;2rM$zPHx<_xi^y)){8z^y#jy+PijjvoNv)4EU=YMoJO_ zJ4J1}AtFTt`l*49ul(pIgnsO-Cpw?4p3wziCZoy+9BWn?#DO)Hri;8^9*ie5vZ-0* z;rjdd#4=~mxi_!S-1iEJTNr-{oAKA%6rmJ87fLP8V+Csh5o)8u0imtim;gO|+06J5 zyzwMcgr+uVi5GX}%`8YhIP$8SlyRySNK7fC#TX*hNV0+N&^a5!a9CEirExQ3BxkEvJab+; z^yAt)O&{0)4jhR(xgb~FkoY5(d?d7|_3Nn1A3VD_`kk#C0L#uPH!gNOrYv<) zU>wUoqcG4M1gpO-Lf5+GC|iMfwBE*UB~$eJc&0Twx$6C;T5Cfhf)P_@5w_4FE&r3z ztpkQI$#AcOH*uCWn$l}C*gEQjI}UBD*~4@4P9~oh=M?DK2OH}--)Y9(H?b&SS?w8} z1GGr`gQI&{weHBnLb({_Z^v2URwR`GZl)GxN;j7wH;hJ^W1azDX6G-u@BV)AiPC7! zdB$UmQI^TqzTjm%2i47&^dN18QwHcyHo=P4D@h`LES{TL;nfhY_IUyq(06EBre+ss zzqypiu^$3ah!@@(%jA} z?U~Qo2hw#e8cje>wNwurS1K^T|Kv1>N=|S_y61jL3|&LUc_0$jFaM})Q)yg2IbTl} z^XZ?=xo&@K!~f-Q*!eZ9`<$;a)z*`J0AZaLSIh?%;wKgnWyH-V zaUPSr$Jo&_R}B1ipTJsw4p>0-qbWw6KHxsHd>gtb+_Kep?J8EE4TRo=++?*KU12$ZW`@&@UX19jpk=uH!VR%AhwVT443G@;nAFqyy#}BwVD}DvmaIY+63SYyd1edWpHAo&oW|i z$Bjiiyb@!Z^T>g4b?7p@PBm%LIO@02hD>Y}YA#E^$+t-q!F8B|nj3I;=#Bs|LhKdZ z4)0!I@weVr>z<*JTghK_DB;yNRCyL#!pO`%g z;;=Wr0VloV?o7N%wmx`ZJI?kM$(LUbTV-u;q*Lz!m&1RYi+nT6iRL7t)GM37F#Gjo zmdigE>|}o?Zx06{^4&%;05#LT1PMke2=gdy&XS~Q?3rKogUs-y00jlPoIEnWblOIY z)9gYh3HDr(p;ZkrZ-kXpsbSfgaznCUHaaw$;LqrEPB+Q!|K zzUUJv45zhO9IJZ8#0YXzhDK5x3zp3ch_5WV8_8xa;i@}G`HMvsYrvwGXao2QGBaXu z4aE!RQ>0W8K8j*r-j3|O6+<#bS`+KE{D(&;Xk=L%k9{GM%WTe8Cg8>_L2C(@ceBw&WM}b+nP;t@{vdM^UbiJctl4oc?<0~Z z)~e~A6u3dLB9!X`UoBiv!CxTs#WQ|5s_Y<^I-^a#{9b%&vY~yO z6YM!+rAiFa4>WYta!Oon@O$y;>F=kfOfMF!2Pwp1znbsV?Rh!4rz>RyKTx*$I0&sp zm$+3hE2GCnmT{1L9apU`lv7eFgUm%U^;QGrkZ*xtct*pH72tvQiCb$NV5Nij_XdGK zqF%HB{IQa&_RxiaNTO5+sJH8fW?*>-A~AnZWB=nDESJ=WKy^L&%J=Xeg^Wuxal77L z#*1pzu?KIu_hR~sje3PNpAhCh_GexxduM+yS1J2|?1gW}IB2m|WepAjOMlhq z#tTJRw(KfSA5zCLvts>o0(Q93AJ;1+Uz9XJA~@_pqPH_%S23_E~9niieUJet(4Otr(-J*em@21 zm)_b;DROH`rJfJaw^hDT_K4ZdFUo?*bU<E6(n&KKRSTK(FRHtsC?Qa?DF<4D@N`0)s{GyarJ`6;_uN~lSjgS@wH`W`{MqjFtr8`VYNCGdBax1)Z01-E!aY(l&=X8L*zeiS%|m zyXt>!&7Q&h5(G|@z4s#8!t1T*X~Y@9V5_PuEqT32mlka;j~(f4X^>FfeED^J3*A@_ zp!5dCda$4r1E0=xh#->TI~{A_T1Dp8SX2+Br-c!EUpTBC?vNy3Ae#?n9vce2$4s|h zN7F-^!n{3>`Ql5n7Y#&#ofr}I;^DuV!*)p0PBsPC)w#fnlY{*76<*9{xHKjJEW5OG zU_IO6R&Q^^9Y6>_4iz>RPVa5D4 zR`bZG>F|-ru=8fjBWF`Sq3#Q6sRo7;ZN-O(!=OBXJkA0{5G_i>1au^%V|fsr zJm4fQ&Z=GDs9z(`^j&EQ6N-*0UsY32ZvNt0yjk|yy-bkeZ!k8fQe3vqfFs-^Ang<( zZA*YgnUtafnVdQe0PBJ|yTFDZx#d7Ct1+1oHflw~=OQEj*Uhk|>y@9YMvZEBsVV0e-gVULs5=Q!jqrZJa77(Ep^4f*UgbE4}t77@#aFU$E4Yo?=EFTeAx{xs# zE84&9WY{BvOtwkjAM&{dN23J|Kh2Ikn(z5HNlG*5vks9nEbWC$DK z3K09;F%BTl%$(U_3KmlS*wjXC>&&d~sUNaxR`LdBXI)|64qzW& z39w+dlwG#v@vQ@rgw2)bF2Glm%yjNXo^`h4bn0uA9uP9|w1h<>a|g#Eo_<`8tN+Dx ztLc{rxvq)b+BO8N5Mc)AixBM|%Mx|FhVK@LdvK$NAGg^+_qRiQV^#B7VtGkna$u~1 zP>n8ck?=UeID_lu0m=GMWZgghdGp@yw7fGWj{2latUwf$f4QyyqBO$kDd6ix7&Y5ZuUQq>UyqC} zf_nzyhf`qJ%zn(C#sJIU-;kw6FgND_MGP(Pu!*;?5Nm=E&wvs`K!aXhosj+5HcIT07XG9B|eDUxo{`E|o&?!71+ItDtlUSuj z;XFQ7^MPU*9J7T6p0M3yhCnhL_3+GNC#1kHq%yG$rPFZM7Dm;kDy1Qt(R?h=;cP4H z*J?11U=#8U1v@%1*ls?4j!RM=BWvbh|7wRQp#v8KC_B zn?)noMFIy?F+Tvh&X+A?xy(rPTMs)~D31lR0CB*)OHMwIr!GEg8L!=UeJ?(m%-Oph zI{NO!@Q>NM?x3aU;6oJ0m$FIh@Y(0#IOy3bc5LoDW>fC zZq8Kk=x(CBK1qCOnWmb%?7_8#3+O7{fkpOiU$^;**0MF#6MH~|2(g>!5GcEbh%~5@ zoww@#Wj45F!^`~_BqKk)kIT5c*D0%NC*co;+ z#IM&pX2FGQ@}qz}xC;+0C`s{gF9+-5UjfUUmb?TNUkMUDG}!EYLufPP3a#1Xg(csT zz-uixepperLD%)u(xkmuu0`;V+Xws&-z2PL}f>r3ZM`kZ=WE>oR z#HV0mG(BdIU917;B+#mcK6jP$P-rxMieVEU%iJ(cjk&^tO67Ph%7Rf5?Cu_6U`Y6{OXW*b1KlhnxSHH-vXS&_?Dn?t0wA*34Lc6ii4qN|7tY)yjU0VD>i{@hQLX04uAo4;QN4oWKjZLT z;P>@4mSsGvxMlASIAh_TqNZ4^v(Ml>(+*bzhd{p#GBJoIHM7YD0E+JKJjmd?07_eZ zduHP&38D6JWj^m*QpWn42G5iZLWb_+a4)XRX(vhNjb*(D{Yhe1X;C|l>s1$5+d0%2 zRQEdeI;X-pM=Zg$kN*=c+ZMu`CFJd*?OfBf`gSPy|7`;CybBpRi_99@1mxC?DOviF z71y<4JDKUquC1{1@UUW0y=v*??0A-j=sdJ;6H~3iaYt0aM0Fwpw;;dov{(2c%;t&! zpO<lO^c+?VXWCh%SDb0g71tlL1TYWD&yjc(`qHzZGfJ2W={z|lVuqMPP zqji~wWo|qGzwDQlWy{-hlDb!BQ@2cdFCcl67|2eBQD@GkS=c+7HWBCgUH9B(=l_Y; zR??tq8QNRkcD0SKs+y2HFd=?H;UKNfaYqa$g>Gs6zpTBYmKyQ8J&r7Ik#p&1{LQk( zL!+7cpJ@C+kc}6)&$X=bK-+79kCXPIgu8w@wFnh}i^DuM$!i)4xK-@m5?-eYITt;0 zG>Ndnalg*ZZ@gw$n!B;hSJ*@Y$bgP~?j3mmQ`{NOW^!V1zTr9+OtFD3kW`xJvX!}_ zQ2B11IKE?zOUnEW%E=q`k)yS6iSe0Mfd2j6hE46*syd-00a`WG@7)guB1IT6DI@5g#Sw3G@fa z)?r`8nEP#%l8!PyHsHzflvH6`k-AmXCKP7)mSNEy9Q~58Wc~z5-R3C9G;m|SO1>J) zozmgrx8pL7PbJMh+kF_=>mTZS?Y=a96TLQG)lA&`>UgcXWKjff({??nN2y0!zH6Ni zFmCT-GAoYA(Y(IV7fhKM=aDn;&X?sBfk{y4LxmMAYhi40;Ii#Kc1t7TcY%CsHBN6~ zD9=J_*D?HX;m9o=HU0U%3sdHY5cTW-77I0Hh?#1*6Afwf@kEkhQ=!-X_$gj2J$3ZG zUy?eWI8b4BQGDqMH#uCFxv2{}KJ*KZ+IH-P!S5;jt{kAw=YL8*M0~#6R6fU__|MVY z?Keya7|A4q(?E|#kMn4q!g03!OHkb1$C}6}o75iWk(S1k?lA8}N^)UHG7_^Ip+#KLTPnxMO6l+n?#S*0NNFV!Ll=fP= zznLfCm61N8pOZ|+1432QG>+Ex)a;Hne#*R(iJb#z2Ho z`#;JlIm;oS_{hi?HCw*8FW{FnozTzO`!ORJ^;hEnz+PEFh3PkEA|q_?`HJk%n~w{G zbnjd@mCJPBbiUjA_nPIh(G!(`C$y%Z6=o4A_k`R@+CoA;mDkjpw)Le$5anD!>z_mn zn0SbG-K~FUSkcu6i6EwOwfOZFb&0br9XwiQ6r(T^hL@n=^%mwO++N%U0%)ky0%TD5xC#Qzzx@!j9#1#Njb^y|yaPQlfI_TxBEsTq{`F zKL2mg=KA0aCk=d5sPdo8L69mkvtL{N3heqFOj!tsb>(?VDBq2vF!}l#oVAwLb@9U< zl$hwv99wRmY)j5p4{eW207?E|<6R-HZf20aduCX|Eit~rK1;9WoeO2kg!^AG`e@E~8{f&i33uw>X^`5U3=A$1HfEJTI=nu(vK z5EW*d*NwMD)%O}PdofUQCB;qD^}LTffI<^Bfthf14xD7)q3nfc&06|mY(kqg`1Le{ zheQuWt)fooqBvMflp&+@hJEsy_qAu$CKE?)GL(C-PB^y&*0;{}^eOD+8DuStlOyPx zX`DOyIW4;kzP+Z5lLeTwS}5VK(T;zO?3i5lZ4vw9dpsaJVf(zbxua0N4qX%gkyVA? zcOE%c4=+gcGX!x)pl}e}iMA#${T>GvCB(>*zig3#lMgWa@JNMC_qp^D{};eH{rKmv zWz>jrFJ$dCxYJXa*AAAbc zWtmHNqhpMwdFb4?b)yc*d%d)cFth|LD6d5?eg63&ytN_Dk~B4CWC=P1kPiXf zyN*dy4A^UuMs@ak64oh3kaVCV-vcDVTiv5=77A2L?6hpNB?HMAv=gZ#1dYroI*=8$ zecAQ$cz8x?Ms7Vy-C{pAF+Zfk5tu+-LLw!{l>-W2Iai(_ebL7KcCMajo*ru9-kVfD zS%t5O+=jjQW_zi?GpaH?CA>Y|3y`tbf*1s}_d2(WjMWQ___$LtX`(;}NA{aECDbX*7V6kUw&qx%G$9@ z0nnT3kEyDZiPmF5SJBDtdhrJLc&5F;=vWFUYbm9@y^iraZapB3Oy>yJ6&YrvP z>E4L5%4zbyhj6Re4)Jh;<^DN`H9C2A|1-N8^GDtazwIne8gCW)ap!a0!TsZI z?6f!M*l`*C5gig1@wS^s)TEI!l$Cl~4Vl4j6v4xQr}!r%z^})sT>7r#=3$9z#Sdyy z_k;Xj(uX_xKWFnniW^GGYs1@EG1{&0&w-icJ7G^NqbL274SFsj!Ky z-(gmgwal?7m^`?ZpbSQ~$@)uDW zN%mjzo)A?G90412Pg$fvtD*bjAEbl@JW;XM$vVmU68oarV|RuT%V)3rZl3~tsZAel zzQI4+#O^S0U=|NwbLqU>o~noMfQ&!KRBnegFNbr#?xaIRm*9UQv?4#_8cYjjFS`f) zDhf08^rnZ>-BrQmW2hKWt%Fx^b2AAw2hYyU#u2rt^@iF>vv=m=frsKlCO&aM=k~6P z=uF=MN?_lv8HOSom+;Q1D@?jDx6Tr#c^fqwv@*5lg}ys@59!Qx1-22rr$OfTt~hN= zqF>+8_<^C>9w##417*HkJ{e?iRjJ19xtl55XXTmDS#`S6~BhKDn`+F)^!}`vw5LO_H)1JEV12&n?RyX%s+QR z6exjJ36V^upH_{*iO(Y3(1v^n`T^1z&g!C=7Qn55e{i0?mQ;UIF^4J`iT7Yj@UeE! z*^iuVFMZe{#TgevJdJE?v*3vRHhztgcug4-ts+%Sj-hlv(lcSo0(S#EGAujQll5e* z^h?@U{EkfhYdPJtK0D+%AwL^oo0;bMz$((*Gk?eB2wamR6}scrtynoWK7oCeoiKR3 z!-C9|uB2`UVH?jmq0$1mXQnfK2y%^6De@8Ypt*K~@%i6dQRBgezp)9ua_jbT81vi~ zr&~6Ggv3u%F`h8?6uZH>0Sl651FIyL)&fMoU)d^xoq0!n)BK0G3lKVbHMx%ZsR9h; zyH8_x)Cwp3E6yWqT+V~pzS`z(t+;7rsjUZXGLh1N0i^7+JuOCWEJykwDGzEnE6wW7 zgy42BtoyzqI(w}w=B(LR>yUd$cR{oemVQ!xv&&R}sP~2FdxUHwY35)3V4>jtY54$N z7lnQQwe|0v;0|KXU#!9ZxX$oBbLVfJ{1k8njO@LBx3;z~YTxGgwpd`w-3YfN3U#KofS5_T|u z2;??}#C)e~O+L8^@=QFY!xq#rdHj{rp`2&gR4tqmtE%NW;lbk*k^?8>L4L+=E^)$r z3nxQuV1nYTU4J}?V(;NRP03|d*5`?k?%Ea_G{MhykJ`30iP!4WB7q*-p<>wiCf&+6 zL|6wpFC`@y#PgXiQpC@;joN5`%*OIbd zfcW^fjStlQXz`loohE8@ulKIz-$>wH`8C=hL{jY%Wx$pxe zO~cp#T>@W_`IcZf4>fg1-TUe z4n@;WPoUk_C-ThVtl1IF(s#U@2!0t0sb6^=^)dD;XO8Ra!45IscT%wG$gQ{+jId2c zUyYMPuj|-tpG5Z!$d}YNsZaQXhfmudYKn^Ix9(;pJ$^Lw~p?Qlf{@hdkpt&n{n#i7qi#?miBH|>W;|Ip6Tb;lMvhC zZExamByOKyt6a|@VA51++f(M9b${awIag@Tb+wzIz>0lB#U+YT_>k*&XradxG& z;#ZcL)ehL!>v0`N&HTMDoFA!sOQ%?``*u!LHk0(5ceJA8cIaE4LuE#>(+=s*4cB48 zgrg8Mmf>$CO|;)h=u&@;S^L@z-s)A{;e|2$%YE0In~St-tm5p{IA)zo`fx+Eu#lNX zlcTeKU=W9cja~8c?3)uBm58W`aaCz{j(RthvuOBv%qwBeMJMj&@AbIH^QTZZ_eO`# zwI{X{ono#f%BzzR@cN=ja7;n{R6f?c`59(-6^1BxY7@#q^E0qejD}G-R$ZyD0e{l0 z^ONT`#>12+&W#@&8x)&&b}2MgVmL=PeYi_3g7nqoNUJ=aaq@Z*pJq}wR5*Op<(4#0 z|6!=ywoK03z~?DDG{Y2}sHP=iaC~o0RwP>vRaa76OEE+6Uw!cq%~PCIqPFi2SI@}L zYFs(2eeTUPpOQcH-f}r*6xKh@$U8HOxxq>BsP{ZwB~D%Yte+AO$MWuM-lt|fHac4B z8o>ZOH8tgb@|56{yz<)d&1h9OEb7m%U$P^!FeY9>!Fxwfr*`}vz4uO{SDS+?&j*8I zaN62!4#-}@DNSn?k_HV@G#8z!H_RA|6J;_oGS{=d4ATOvyk$}UqzgqZ= zK0Zhu79p#y3vr=4gx1ChMTZIcUb6rOc{Q(tMH+_3yGD$k;` zp^LiVzY|lq)cL?#Q%FNX2i)FfgAOQpaTwkb6v-r|s@5IKT@f%$+-RkmL= zljr_nC5k*50jXV)OMCXE-mIMX#fc#_E6{~k*!+Z(j^YHKKA3M)RQU3@Yx+Z^& zuzms_R_(N_2jo;&dEwYir2GmL!&E!l{oCKEWCzY7(CGN@0$-8D5dRNlo$6Q}8_3-c z?F&7+hquF&l?i#IDXTXc7kULZY%${AtSJY#xj3Kwj=u03$Lsk+{?g%NN2<(TeW}Mu zH7=<9YuT}=qo-O$29>{7-3!Yn;FP^e_4O;dsLym^W|V|bsS=RR6Sy{Kqg3wfYLq}K zTyr&wYJBBcy5hH=4ULhpu^B&oND;0usEM=F@V-YcnfktCP*Ju-J<`0Kiz4VL&ux7u z^X9!@1C&rvO6s?2c}Jy2EyYl?mI#HEZNakNYzUVwSZ_zUp3CiDl8o)r2C1s??4y<~ zHgr-&UT83u*lqO)C=NeMTkQX|gx$Fok(XH~C6!v0{Y8YDT216XCL#N2daP8c!csOqA|hF(kN-da zA|*vjV4M8EAJr*WmH3~_rc-LJ^54Fs3wRvqEPrYGc6WEzCixcIMi5v5+!o!<9UZ|Z z4_;d_{DLQKd?85;Dud(_ec1w_LMq6z@=p%Me)13v8E>P^i*}J_jiP>tE36%pLYT;t zh?;u(>rW1Ym+viG6=t7pJX0@IE;wwQojE$PU#4m*Os#}PU34n`w)<~?{y$zBkDlQ> X2~1Xy=PhXAfF>ucECrS@`TBnV!Z#4> literal 0 HcmV?d00001 diff --git a/doc/html/_me_bluetooth_8h_source.html b/doc/html/_me_bluetooth_8h_source.html new file mode 100644 index 00000000..2cb004b4 --- /dev/null +++ b/doc/html/_me_bluetooth_8h_source.html @@ -0,0 +1,150 @@ + + + + + + + +MakeBlock Drive Updated: src/MeBluetooth.h Source File + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + + +
+
+ +
+
+
+ +
+ + + + diff --git a/doc/html/_me_buzzer_8cpp.html b/doc/html/_me_buzzer_8cpp.html new file mode 100644 index 00000000..362c7895 --- /dev/null +++ b/doc/html/_me_buzzer_8cpp.html @@ -0,0 +1,202 @@ + + + + + + + +MakeBlock Drive Updated: src/MeBuzzer.cpp File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeBuzzer.cpp File Reference
+
+
+ +

Driver for Me Buzzer module. +More...

+
#include "MeBuzzer.h"
+#include <avr/wdt.h>
+
+Include dependency graph for MeBuzzer.cpp:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+ + + +

+Variables

+uint8_t buzzer_pin
 
+

Detailed Description

+

Driver for Me Buzzer module.

+
Author
MakeBlock
+
Version
V1.0.0
+
Date
2015/11/09
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for Me Buzzer device, The Me Buzzer inherited the MeSerial class from SoftwareSerial.
+
Method List:
+
    +
  1. void MeBuzzer::setpin(int pin);
  2. +
  3. void MeBuzzer::tone(int pin, uint16_t frequency, uint32_t duration);
  4. +
  5. void MeBuzzer::tone(uint16_t frequency, uint32_t duration)
  6. +
  7. void MeBuzzer::noTone(int pin);
  8. +
  9. void MeBuzzer::noTone();
  10. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+forfish         2015/11/09     1.0.0            Add description
+
+
+
+ + + + diff --git a/doc/html/_me_buzzer_8cpp__incl.map b/doc/html/_me_buzzer_8cpp__incl.map new file mode 100644 index 00000000..6fca0533 --- /dev/null +++ b/doc/html/_me_buzzer_8cpp__incl.map @@ -0,0 +1,50 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_buzzer_8cpp__incl.md5 b/doc/html/_me_buzzer_8cpp__incl.md5 new file mode 100644 index 00000000..9de34bdf --- /dev/null +++ b/doc/html/_me_buzzer_8cpp__incl.md5 @@ -0,0 +1 @@ +52e6c79162aff01fada8b19dc8f67ec3 \ No newline at end of file diff --git a/doc/html/_me_buzzer_8cpp__incl.png b/doc/html/_me_buzzer_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..06d62249fdfbcc8868cbffa73693379e3a442666 GIT binary patch literal 49812 zcma&N1yqz@_%2EbND4?vDWE7_(xtQ@NOzZX4Bd!GgLDm`fOK~=fDBSYcMUnx2-4yC zh~GW`d)B(^o^dT*Yy4vG{nqn7&pV+X6r^#no?sy%A>qo(NGKyAp?M)8A*W%Y1K+5! zfct=d(2eD!C6NBz{Q1_B7l(xO6iHU%jjB6%d)~`i^(g({pGk!L+n;hD!Y4DIDifgD zv((O{=`=#zncMF-C!@zr9&9QZhhx|`z|NlRFMoJiu z2!PKN;1mry3M7n)SdT5ui+ZQ9g7n_uXkxwysP`V}4 z#U)IiDoxYf{Qs5Sb_iV*{1;txgh24>6gFEkM2@ZHakxNm$S*M>2`Vv(`%k5`S#-$V zM~3?TX5juH|t=eC)9J5#OwL+TonJKN2AR||R`3-f!U38Hy3ub$J6oZM|mX2DvA)mfd#`N!qQ z7S!ClHAz44^k{mG*EvEJcwokV542?~2rIPty*sp?0d6Z2baYCPm5|8FtGr*Sfo|$} z8qV}YTvlEgS7?aLzi&;Bp}>*JENl$yCJ1NF>%1A8m#aTtiAuG(^w{ieIA3uiCFrr3 zxigSQo?w#W(fD%%FTuS9bnZGgx3bzy+r7*5mdW(JnFTlkCNeusRp-phN)R(wnU8vF z4CnRba5mrd@=iPopVb&?DJn^Up;5Ws;oUVd+hJ3qZ^t9<$Gz5HGbDFB8b!>l+y@_A_s}_{&KeKsXFrOJ2K}*Z& zU}=8qwla8XC4W#rzF3!w6tfK?6o}%`SyXh;{Hdd4Z*&ioUsA#pu6%dmvEs8&3OL>U z1O_aU`m2le(k66&szIv0A68X%iO}mHh=K6B4+fbiRr)Iv$Pu3gYqDLm#o-+Gi|JBl zNCWx`-ph5tX`#B15FF;z`^TatF&_q|Vx3lzTU#$57qn_KDD5GP<}CJmQVG4v%O-%+ zxRw*V3j`-aH)PO2$m_1;(WI@h#2H0g68?Tg=9BCTCl(;)Gw*Hjw?d-DV0GUT-VqeH zGv2CSHeCPs6q|zt*z2cO{TsI@y$?yBkH=Uv(T+?|H>>62BHiMKmv;6>{oE^KC6V5* zNv*>Gzx;k@@SJGf){gK`{$5m1jQ5r(8g!d@>=Zx4#?g6IbG+ZNPLdGBe7rLr!3LdR z|GU)TP45W^p$|Wy`v*D6hK*)4!Kx>jSB1c@)?T$faskrK2E~8dGL-oh z?H?!%zbs_L1}=?BwLA_XH{h*rFb>M3zPYqVZO@%bm55!mwuz=qf)(k<+xJd-H` z44NG6*BEI?ZZBp1?^1TbH9GcP*A-Z!@`dD>M`KoDZ^zpe5SjSsv%@SHkl&|&+}kv` zaKb%+U-W^#yNTeWbb6lPI&{YjBocmD5Eid-ds_eHcNu(J>zrQr)w;K9kNhmTOU7>D zs~Q8;MHfUAKhsrw{vnXLT=Q>(mtZ3xEXNP0o*L1cs_ezQDI{EDf?)tcoEZIDKESy0 zzrA+vKVQk!vc41xmNdW2svX;n5>T{fPO;p8oC!I6CH@ome_X0b2O4s#V7Z!WuuiQ8)x?!#Ze(Xki*wS@?*qh0wg z5;v(MaXG)UuR5^SyJsrgtrZi9s>7lQ_cvRUg@r;>JC|tgpd^r_#4v4zVeHO346rr( zuD@~X==YL;T0tEHXyrZW zi%o}XfJf?&k!J(W{D90NX5HtpLo9zd0!%Y%=Az%uE6 zebtmO=)XTFKk=FdrtBOP-WT}ncE@cGQxh|JiJ2KDkQx$l zm$PEt6LtT;)QKT)F7ebWrM;1I+V5Bro1z3b_Skn z@01KLc+6(_*(U|N9D90gx&BQ@zqzgD@Z**CtjWxUiC4Gtn#b(XvFmOWXLtyX>w~+N zDyF@_7I|#puy%$iVrF#OxB*4fKv zhmkO*{XTiqZ)xxCZdh&%(^wpD?|9*iIpvi^g~bYYVK+B@*vO}}+T)^1H?iM3p|1ka zcg~&j6Q;DX+6yqH3N%&Ab3fJs`m_7W6|>Qo&My4Q^ITw5Y}%JO4;GeWDFEp1L!PWKIxMdjD>%(b~)3yN4|;3*##S7v74&%obZs zxR0rD4Hjk(VP6E@j+=QicX}HnCD4iVpwDlky82V z&eU*p{;nT65BN*4H#-Oqwgj@|A~~62t~fOo%5D)$#lKL2Ou+1v_wIHc@acWQ4shOW zC?<>!shtnsKrRBmG0Cd8(#^A*72)5r3l4F70gLdV zICG@kut!Z}hCc%bqiCMYxbm<9faVz1W;ZVYL{3ss85cZRYm7ibqVgVER2MZgoH-e4 z@(gagF^U*nmtWc^65X+HYZQ_3Ih#0+!d5&Tdlix5CFs$Ikj*P+eDE zC2N6#eWLMCa-N4x=GX4+AP>a)=@t&35t&`MKwyYWZGP)*o&vvAJYR*>kEc7@&8a=w zAK!d+T>6PF<^bg28&+ZZ^O3p6`^xpwQVxa^~3Ru2ltr&49K3Jwk#ir z;GHK6<9hNECDs2uMBA`LJTSO8O?2S;$(q|Ef|!MS*Y#PBHS_(Tf;@?=F|5q!T~Yfp zmWnD<=A6`j)<4Z!Zu>l=n18A-qn1%cq?9}tF8}(Jue^;S4He-x@6m38Q}Oj7qzCdQ zCE6C5n#&z!g#(mPzGRaxGVUt<_cZ_o((WLXjJg>s3!@uCM-0gu)Q#smHT_&XG{*pA zF62+wO#S@CXpP#jbMb)^n|xbuaDS+vJgNfn0`%;8`5f4V#Ke7uzXwhamw@wWvtn4I zWN;%M@>266{(SRixG8(TTVsHXcMn!f-+PQO==AM^SLTvuhjlZAZ}6Vy6StHYNPcmo zj-LI5#`LHQY2M|~i@cxOyZgi#VU9dr5Ki!q2c2iQ{%swO-?u&a!{vH)Fshf7}L_;cl@4Z%?sVBe|!uZJ2|mV-_D!P&P`kNl3aXUHYPzq zBp*(vDqncmgYvgGQf@pCcx#&D3wBg8{7c-GB=jOw3rm;KmU_hLp@#dPAu^M<7AVl4 z5OSIhS@d9YJP%xp7K~!tZ_jYF42Jq?iY%sPmApj>V%qOx#LFC0&^yXQp_ZAo?2vO+0xS>I`Q# z=o#{lOic0TnyX%#xb6p%7o?>1o+YPtCmDZcl znvhcQcd36(KQqV7|B%ORlf_VLTbRDdbF%ct60Zkj-0XK1kDzdujSFM(V4row5#!tL^Dk7T~ENaa!=i)ELbrFA55`< zH02(y+VGgP{1=p|U1bckoQC(2uTYcGhg!^4Uzq!odK1PE#2)KTF`BD8WUR5^_^pAd z+B8wR){zLKIoQ@Ax3ha-ib|jjC*sG0eS_(GagDQgqOt5Ci}JQXGy(D{QIJfZ;qSy0 zu`Q}6pHQgFQf%0cTx|hn=00Gmi*CcNPp(%AEWk zqEsdPOXiQpmYKLlu60_nQFtg(yvhC`AqNz8yqD+>?$h7e;g-BSd_rnp%{#5_D}OZo z$PJP4yN}5QrHbC@6Ye^c=fWv{quR6^qXU}DuwG{Z1WU4MQzhkzp6c;m`>Ki4fH!m& z!<8!xc2c0C&OO0`Nm_b*@;K+LkUweZvS+CfXy|Me2Q`%TG96c_123W(X_a30q*kTW z0jLi>N@4`xl`k%FIS=h)hbA8LOhx)wY|2FZmi*0<9=va!6qhoISl@HQr08A@7H>nh zflk>Nt&f!Z56sq8`2s{k$`(+ZckW;TXGl$I-=PcF0$Qu%Sm&6kn%2}PD3RgHIFP2{ zPiJF+ZfJ@Hnah+`MC3aR`mE4L`H+IkCAA^yaC&pyBNu65DVa#Ngu`|>L-up zz{2!52bY-J*!d)}V@>Iv3<{<7`Qb@O++}eb<*KX37-F6X#ww>8@GPpK)o*le-0uca!`CfHz7s2r^jlrB-w-#g{u>mIb32#yyz+R z*VT{+Y7QR2+d|F$PLR<%{==GU6!c zb3!}`F4}sxeY~BsL!BUeW(IQ-g_(f297NbjJ~|+%jpuZD$Mr)578g{D_p?JBDcL8| zD#T-6Qj)fFyFG8`0AfF`jZs;I<1_Za8M8xqd)Zsf_`Y`7w9^?D zo2MX@%nh1a7ykw=qKlt|EQ7!Jq5FhUHa`W6p~-I>ob>nE*N}+?U8`5LXLnguCWA?5 zTRbeh0qyh)x&3EY+hmtkd?Y!oS-6kPA9mkQAQGrYjpIcbv&1e3uxB=vc=-pc5Pl4I ziqoLZjz+#V%HLIvGkBq{7S4td$BDC0nwxhb&W_hnBQIHWRMA532PO7HIf~w z$d^Az1KtI$jlxMKhlAQH7*N*=oR!m|WFApFzh4s#UgBnh@PspKKV)`nJ{(PJDVO^2 z3ok);@2B~iJHf;Kj&>1$zH*pHAV)obB3+o{d374nmG>CYL8b7gKMeIlH_4CRnJ!7v zZ{68(HKsR*W_VjQB?f5%9jbP?e0*V3s#Gz9e`u}@`A(){y>cwUGq?z_jybp4@7+Tf zB7n=X;rTf#p4()?OeesobYxJy`Oek;vB8=Q_R)~C++e+YGQi?^j>Bf~xv^0y1BrZH zn?#bngy-Aa!YD)i5-?$Scmv9*n_+M#?sO`UevBJv-bbkMaj==b1JD6@;P3>XS}j>( z{s!WTtb9NQqX>Ngov8G2 zVXmrJvEx&rU|+Bu)57l;M2a8jm?4;i!Vs6T!)1zjQULy)+AG~se&!-I1a44C=9)43 z#J|D;#Ab@PPS{gTd~Uc+t^Yve{#aIh3-L7RBXYF+&}3g@x{?|39*Dq#`^`5LvRTCR z>o5I#jCP5#QdjY!w-5kGJ~iq$@7?`aGm8KLjK+lt$8IX`_%)?VZNTOMvHoAz;{Mj6qz+^JHg{vTf_A<*G2!E7g8 zKw(_Zxs(s?qCPO(e#BY~fZUUD?dflo(wIUcY#a=BlRQC13LDHNpq9k?<2EwO=Xl-i@2}f#qRfG1L|TA&f5Q(C zn${+OncVC%>r?S<CcUWnGC@%9=|>YKBQ)+wx}jwnI})>-+nE`MfwsnSq{GZc}NG;T^f2L(}L` z@UQI?N^5FL-{ImLh+0D`U98Nx3nUV91gIDw)`{)V8+cX|^A87%y5KQ9HMxX}{xAFx zX7hc>-Nck2vpCgsAm(!da#3M#UIWVnj+^@Vo#sfX>H zNP4zrY#xyJNbcRe>IgRty(M5`uHkzik5&wv!EvA!=_TzFh^Lye{>yC?by`50clZ(Bw4+fm21#$ zv#G#;#kwx??eS^S458e*)y_hrcM$0gj(eBUKLtE5LA{?|PHNyDxRTmhdo4c4ym%@1 z3K2vgSZ8snT@euYa`O*mCwEeCO)X!*BQRb-1pVe1KvUs(*0@hrf7HfgvS6 z^fPXpYkLPzk(uyb>n14BT$1*HxcLtvx4G6Amj0Yrjte;5#*LijVP`R;NlqpTPEErN4$j=*|Af?-`$!6LN zU9WMmoIFa?)v;>pH+wDE-3t*Iq_m z#CM%Y!@&vAi6CL59bSEhMJn|NB-hO0M|a5}cYfkl!8pLrQd6V05sXY?|I)Vger23$ zmS5g&K1Np%NQk85#1qQrlxyW=^{*zIPU!0xX^uM9C&|AP%4FTSEi+8Ek~j-5Hql1N6`Fe;u=@sZXw#1}oRFRJ}n8o`((Gya5aYT}nXTmUW+ z;R$NhQ8C7sOn>i`cVl&Gs3Xu{CBtFvTrZHiM>xqE$=%U`Ze2Ez0n@|jfhLf3ARVg1X;XC(io4QF^O5zT3RvTP;Wd;V$X5D=Dx62)v7E21i4*g{5l_D zZiP&mI#G!j*_@IC&wn2cy$6gqVSAYM1+I*J?1%YPvfPbTL@ymC1h~du0gP z6orGTeV@i&=Qb~hT0xH>+;B&DE`cO-DUcZmq~mhj)&B2&p%!q!< z1A%=qDA8vj5;UP}*HngsoyDyY(A|D30h&9oB=3+vFwLJ9p6erS7k#q|z&}j)zjfL# zOttqv=d!hk_c(t`yRnE;`eQ9NH2hEv4#JGJ(Zt^Xsv7}MO?ie=6QcD$IIH0*u?OZo2WE2jo$^?9IQ~ zAXM@^_PPv01v#+-NU8k8)whzpWo`&5`1uTB(f@B%FH@+w=Nz{AjJSf)R&7L}gko~mzruBDvv_n1pLj0p25em!=|Mu1c z1v!b|;W^$K-Xx1|Ji9H$y6*S%R|0UU2y5#VS3uWvdR{RX{Q_z}5>c9NHz=7dox{th zeqprGuV${h1S^8DTzu&tza;Ld6>jn$VIMYZ?nDb5^%v(1ZvI_ftK)_SstbE8NO?Ti zJc84_yWiEw7tSrz1^|~E&0yn8|F;#L0HV195TfsD^LUM=t)X>%$;pkikf~-SpKeXt zqh(Q3!|ET23to)PD}xQ`R1m7dgYp4zA<$I#ocU_yO0XTCEc{fj3(CZdKt(acfUV%+ znisoS>`>U3yAI+a^=|nTlPlJUWKv`lxL@Pw>gpK(iyLL*z88KrK1qy3cb(!Xq_kV{ zmKH|N5-B09N^B~+!@>)YMXaG`uN}R3vhw0uRf4vR(mx~AaAWDJ7fZHIS;U^wi9w(DMT_Zg9t zp+jrkV{zNpO$1!^yc0jwfbx+rVXv;CG3b19eX^M3+uIK-DK5SY{@40gf>;WWPE4QH zJ4fyCE*YS>L|?xii~!lUlquHe)hD>iK1E0v|3cLA6R|Ab(zGx&$807JUqJcd7 zQN5i6foNf>>6KmIuOHUl|I#Bb8Q3}4b75&#ZG&s)c^RHotVtAKRgYzO#((Z;!L!0V z|HX9ja*!}=Ub(%2)Eq81Tp%* z@JX}B=~D2C*1GpFK&ULZ0?H^s%$pM0wah730YC11M@0LS9dsgbit4K3w=De?9Qs0? z9}H)g75yEGL;d>4v8HWkI@OarlWn~8MYWtuM8Yc?QXqim0Qz*_ztpzRlAM)@4=e-O zBa|)kDf&IM+}h7ecBi1qK#LPZUaWi1a)CT>7I@3Xo@BwsZyGRyC$HS_kVMoqjMK7U z^t27UK(B}NB7wn&6LvB(1f-P~j{4HZpZXC3nK&YYexEB6%|8O_E$TC=XA8i5Tf84wSH$SIo2Sc0@TS77$Z1$ zzUl0D2l=s|k_BPR$MJ-z%|gb^`W^1;2P?VUHt*=KV44vWMR`-l`G-C5B}?tnz1OZQ zk5TyeU~=dbmJM=~TUzb=oMVVQ64GdA5w3uq#9S^<9y=#H0EZYI5en(;a1X!B~KyXNFKlaGg8jP6Yk0{X(+ zU`0Nh?lTi0s|kAr(Ga@u#NjLQ1cs*q8!2M+U5 zRA5cgy7T-h7d4L&wx3$dAGnr{L_~)y?3`7>&UGIgPuzq(wR`jXW7@L-s2Sn@ITVlB z9885KlmIjwH?+#ww8Z&417gOj6!RO+SZ09{5O-`N=g=cuR!Tqlm*G_lj?l+mKY;VV z*Bc3&M1T^*xo`G`kF8jD4gbqC-ulDHWn}n1Kk%dpcMNY& z!Ry0%3oFPl2j*Lfng{`|te#*cyvDJKWm9On(gGu@sqJtk17YhnRqeZQepIQtPOD5YcgFGJ!3Yhbj6$|?LGK(rCFb7Gmq6+zMH=F zmFL#vjG)Hs$*fK`)85X&!h!SMm_iRlXbugIF1GFi?$6I?GDQb`i5!dViV6=5w=Cx# z(Blxkc1)vj$$japifOiWSd!^h^LqpKhZa@RHq;iyoL*T36%oa4Q=EUIQ`^?=mU!C( zggQ%lnZXiSbfzlJ@BDJZgK_ewWL$N@zQJsx0ySpocR ziEs?0W4|sa{b`P~nuS=7r%6?)LU*?p7!bt;27FrH45Sb53`;td@z}|wMG#S1`RmlC z!%_j?qHtl2sYPGe85hjH)xj-{XNWuGGxw6F1~p0z$_=oTto<_F3faG+|H|oYfGYFqtj3HS|XS= z1fy=r44Jm1ls*uK!?su^K!Ta|cK;Z?l`nEO3B8_e%KMbq28_%jyu4b9x{r9I6~msg z&DrxgkU%kmjqo%HfT(*?j*H-rK=|9P+Z>YVxbaq+Ar!7ThveS(-~$=0)GE@?U573S zdC^l4t^$lBX{lJXMG2%~I_s7@TVNh8geAik_ImkesjKP`!gu7uc}bX>Z*$(6$cN2x zW_DO{o?~mQ?J*X@*{Ph#**yQc+P`Vk1Y8C@1OFCbnE81x1c>eCzCWi($z$M|)|CvJly?j&SC9=`0_pVVOj8nyJw zzUVNvIW0LN1T*unnNZ-sC)rx;DX>Sg+_Z7@j%Wm3VB!ekqahkp#!U(x%Izj)NckJD z0_y6DK|ZMU3z)!okH4ms@Fv#wHA|P5Y}P_w|LL#@G(w`64Zw0EKnA~~f;XgZ`p&;h zy6?CQFcvshMzX1MUu5oH0)∈B!2tP9Hw|Hw8Ok0&#yuQ~GLa&8XX~_mXd>6*URy z#L3p!Y5fVP*$EM*V9*>NA>FU|H-4xYE(k3y9zh`rP{#As>B&Xoz8h_$Z;#D5d<zklK=c2Kv)izYxskRj;@iQ(Z>&ywKM*PH4^Gj0p+Is-7Vgiuma|OY0$iB z7^41&fqtz%_yKgCy3^_zf5WMKSE2aUc}~yGr(4G3WGGUa=xu)qEvy0R=};+36bB!= z{j1NEQY+p#d{17=r1t-2hVM+*Q0UCSV(Q@=*Hk! z-rzMj)3s4k8*|JF-W3?tN7YBYo;q&1Ayqf*Be1|G-`9-T(fO#z9z5<4ObTvMxvsBx zMpC(Ci?Gy#a`6pB&i09EnI{fLzcRMUT41{2`;{z+$mQ=MS0RDr_!$6M-f|i6uDp+s zi}s{%TR&*-oM%*biW8hf(zwBpO46I5KxQfCA21E%V~LL8D?_Iiu@ygF8kvv3J8U2QKgAGN|$Y%d5E}D?mosuV6 z7dv=!Or{e~elJN(SfPayBYt05m(TkhoMKqd`V6iKT|OiC-HnL`N&_x~*+8}80EcDK zwjQm>9-EIfoWBKvgqRdW%1)7;#bb8@bhY4_#fbn3W7>f4SSM zm^wWuAUy0F49^~fJfZ$venA&@35gkM#`Zc~E2Z+=|LDF&TwGz1_RjlXXSomlr=-ly zVZ`E(-$)%RgFkDp@UQCz5aV+`ZV12D1F;*~_3NJi4uQ`P1GpB_hpYQ>ISqMXJX}1% z&~v0GZ!JK{>!A-u--}MKeLu)C_~?*FKKPm!bp2`L*nKP|$FHcgG-G4eQix`7MYRwVNfHTR5{ASn2g}yzl|6sl2AVSl941lfoMf z0lpT<1K6GJFSsj@-CnHpLrxz(TE0X!DIhPh&OPY1!;N*VJ9zvL$GaUa4_Cyii)LPK z-CgjonRrJ-gnfp)FCV8=3C!}lm|aPPNr6NRRIE>rFxnv zj4;%ztUDk>KN`01%VE~%0W-(P$Cs#DfMZcPuuI38Ge7H2a}C z`jbfb>-!tjER4kdsBUY2`zMz#a8AAFRe^G+OM7-F)tJr;f;`|95WHZD&1L4^6TuGy z|A!D3BA{YT{7Mu(d6}Ku0?Xkk%shA;y~vHfAOmNd1yGlO-%1DtS_eGjYomkb&eXH) z$in*Z{1*+Ie>Wx1j0>LK=;#~VWnN;EmvE(}i?QRgwaZ^yu`V!`C;G??Z*jTwcU@XWvrpm5eb5Jt18xDGG(xgyfM z4(FNFPnD?m7a_;b1^}Vyx!jo*jqQMt3AEs~qt5Io&Yo$(N!;A&gYsEpuo_oa#`X@s zP7^?8w@{fdDv*jD2n^MblW4$|l&s5T!r^gl|%|RXVKvzY$ zt5zzViIh`NNqy;O^Ve4{akd~;tzM0b-%kfthf-o*c^tP-ZzK0PB<_+P45g12SMXZ* zYwre=qUml!N&S;44yo)?XzFZR`0cx_M44^YCj%;)UO{tqVU_@=lc)XbUn+-yPLh-w zFmti-)>lC;W`BByP$whuu+=&}Q7|JNH=aBm$sV~4qRDBDc{JaGV^?0NyGA!^c|-R_ zsJ!KS1?oE`+kXKC7<{*DN-k=-z2!fpyOeRQF*iS(u!1){9q9KMwG|&rkvIsrWn(uI zZgfD)R&yy7%`I4h%a3D+u?D9f#tAfgmg-NMbq(WTkvfxh6ba9hO8;C@q$RIDvq)7! zi9pluI!$P|8Y#|CF(0%rDGBowef1eY9YXu5{BESV4RjPqd;|JR!Dz_V{vFP#ew#gd zDeGfiLfo-UZ@(O^I#oyA{E)yET~!c_Klee$nAdD;Zs&&C(v~4tAcso#pSC@^4*dEY zSkP>%t{@F?CO$3x4=q<7!%YL@K6>DwQclVDrLR+Wy7wE-8)jz5TLTE)RAAMDkEp*P zzniO0VwLKaImnR)rn82YjZ2a2kZSQ00aDS-mFs`VmM!Lh06XXxa?-%X57PPThjK0I z9cEUVyXS@7;TkPx%ld>RIxva*M&b>c zJeQ@d7QGq4%nL5dXCa1K+TWQUsMeB5AP3Z<3~-)YUMD~NncMS=rT;ndt1cUmCSvhE~2J>Q+>=)W(ZY4$l5E zQ~sK8ax~zq;^_~4-QbvdeH>kkpD5YHyju!c@-in#Po%BVRzz|#6t|QzRD#vgXCdq8S}HPS_S5Pu%HeT)2Xx9UZFacT zpeS22Zu8&8Qzj7{(BwB;BS{FZEZtcp=pg42)UQ5yK3`f8?}Sc>@MHE!AMf*dXqF;| zE82C?emSGuJ3&ow0eVNemDQM*8<~nyDH7gU&c=ahqUizd9(km;{(3pil+x#HUJFS{ zzVD=APLj;@f~JgZyIJoAB!dL~Ep(IO*5AjtHHRIERuBoa2We%2-xe}VFd7z;%*g;1eNd+@#(BwPEq;(V_zICO^Hx!;07D21~Ch;j;bZ2Q)1Hd zS~H&`4aomi|Kae3aS`QM^`o<{uQIPBb)R$bW>@16owwPH7igc$CeYWq2Ke>)zKcFu zi`SHanlpB1sIrW+JwTbmr`Jnb;mPYc`k>15(NKb)=z%#h1CkC_b$xkxal9AS_h+6w z>62MH_A@`PY32PDTLmMxvCmvz1k8OwYCOM5*65ORJD3B$VNzkq`3D8;gjkpqX+0~n8deH; zUob9ONJ-!E24c5CQzq%In;=?Lp5-ohZ5-VRSF8D`^)1ri8<=6gC|&NX_BA8$Q-gaS z(^q4gV2SI}l__K!#K6)Z(Kg5^&2khrSV9MMkf)3D;KQLsP3MOWe!0>+&FBkcl9dzD2kf_z?(lp|VryLxpyY?ZV z(|-q;rhNw=MDb%KRG+GC3XnTlPQ@15Z3M>-l*B=CEY!DeoU8wza)Jyvj-V8|mTjz6 zNKbOvliz`OKV4I%l)RUtl7qzO+sMEVHgpAP52~dvVuGL+yAWWMARuOKuJn;pyex=m zwMU*xkZ@88Zcy>HA2!B;L3UycC#CH-Xv;Vx8TeXj1KpGLL_4#@Qj48&swSxyPw+S* zK8RgBBMx(@+NGC``VdSf$&bS4|M!^fv-AgQH8Zv0V%?XC{f=Gd-wBB?z^~ zJQeN*b>T6rjr2zHJ5uGn`+;QasgXg;*~LGS!P_u(bcnpXvu)~cJnuN?2AR;v7`HMZZnmw)m< zypnI~8~(>dLY1mSl0>hSu~G3GHG$e%MCY@8QKhg$-qt~tjbij$HQIr>5TH>i8^rA; zR5YeP)r|kB7c`gpX9fR*=TW;J4ybBV$hreZgKLzG}?sVuQgjNv>6sHqen=wXCAbcRcqFmlPu( z?}#&lJIBWwhoQ-=|2GSe=i}jvXT#9ThSkERn3wW!zVPQ7^=Gyfb`~Bj>YYoi_u(Wh z!_ZSZlVP0))JmGWYk+wQtw!ciI`|>{{`u@}*^$;H@=3f`zZeK7Gm#gS`C8h>mBd|k z3FmW5LQW)-bxGsR^na4&r;@N}PePAgBEk+j8?g%haAjVr*8F~%m$2ghPL`OL7bTpS zWcz>&-`r{$OrHAN>8iLEq}uq+o1UHIHG3xi-L~R=xd8Ei*_;sj$@j5-XXzTOGNibPC|-Pc-vNKyfI)j(A|)qzmXEso zq}o7=ZD$RS`EcEd>iHkRNkr@XBnZ#x;`dOhjGr~k7x9fhoM$L#e%gE5h~)t-;tM2r z|FMR#O-Zxb5jAG1oRF?1{m?YN*V!PCSGB%7;DO5i7>1t>{lL94vJ z2vd31^4kinf@J=}xkx$5e#Ie$(f*sRk&nmq?6$eEz&Gyv${%k-#U2(ENQM(9+Rs5c z8^*eGJb#cdEH0rDx3V~}_h$3yQl<41iq?H~3FFz2WW2;$`=l8(x9ZX?6Q@pl=_~*0 z$F!aQd}g8fJQKW%2Z`;PfL5?p%JgVEUo(PbJ@nlqhrR%-&mx-JZQb!SYL|v z7|+pQfyuCYk}8QoGz zUz^te_djh969x*gd`3$85J%Jj5l|W4D6tMCe5sk9;3r8RllfZ!sfCCJn7s^-!%IWy zwZ-zAs}CS=m=dci)H-pB$CfBipMt;SEpiZNrr$eD*Ku2__tk@+KyWL*dUK^!&^>IC z)H^OL`)X22?)GvdGRl8gy&^hekY+W2`-|Wg>Z5ZRnA|TL6)5+OcRQeNbGe3w}pnMlcat4hwG`!%4LGmwgR0TYgeR~JcQMlvQkIE|B+c$z#fD~O~z2Xob=O5?K@vYlWmDfu(#=0 zRkm_}ncRdf&s{AeU%x^8UN0@MbaCTRG)R>VGJqT(DCXg3GEC=~{&0+LEJ~|AsA1$+ z6<}GHV2;OIS~`&0R~t6(O1Sw}|nQ@HC6@s8Ba$FV3-$ zbSsgni;}et=HLj%j!pSH*(f7AQ805si z!W45eAi@wxPI<$*%l~HsVf4o7?IqjJC$zwbs zGj*Uwued4b=NBkh>^!5y>wmn&Z73Jt{nIF*DO9lWf3fwIaZz<|v@kSCcPr8`5C{Bj$3ou3Gu2(7~M+*TnDMw{)kUD%!$6765N#6F8MY9{z5Aen}V5Zg9&B{ zdj(*0YDWVr)Lf`^KgfX!Yd}hn#+f)Ns@k+mW}otx+w{frnWFG!L={3f(NYa;m35A> z&!K5bc9#%J;IRG<+@9apu+6q6)S=1KZTAmWeE96>?``ZE>NE&|nvUbX+6P#^;?Z94 zLOzrQHUw)y=K%E^naST;T=oRv7P0YENAMgE2{KOd$j6#?2~y}?=DetoMV zmNr&;-NK0r!bOwO+_E0d?L(da)|wtiWp?EpAm+~JNYXfIYwhtYI!4Sh!f{OhhdY`T zD;1I-0=v4d8tq!JAEyttHSoM-+>z$=y<6xeXpt!UnkoG2++W=+?d&}txcCi0BcqPC z2gNG!e|sU3+%7VSzyKSkZ{!kHCpAorAAdD`?2LWdhK?P|7ak2pe@=(@I1hJ*ZHEuPYN?;u(Td?#DW-+JT z3^27F?O4iQ9?fBTj}9C1>AWmAQE#O5>LQNKB29nv4uozl007?UwJ=W zEdfaTJ2&j-7Ye7Fgw6^N7PyCagD5r_T(eK?>`ivzn}*jHCON(a#hhx<<7aba zFkj@$NKJzDoEjdwYz(7_{Et1<1kDG(`o`Y5>!kyOjuP?+#{y05G7nd$3(k<`ge+wY{gVqo4B!DVa z&8qo#G>dPsGjC|gpPG?}A2H+T^t`VYNb|PP@X0%)4Gy$n`)+6p zrHt6wf*tVLXR{|Ss5!CKo;;|J+Chw|pu0AWx;tC!Xbu4En=a;O`F z8+Ew7yf1l(g#Oe5XR+eRYaL`q?UZD;Hh(&o49q!{xf(O1nj?5!SBlENL~tGO=4gh@ zGPdV;dJ-8EUud(_E8Y&-F<((e8SBf8DHFoQQ)7X})Jr_CEMfi*pi9OvZXd#SRarR} zvn2z-rYMYGPCgVS6l9aTUy6f^w4*3=F*7)}=HKDAP2@Q06y^MyoxbHNLy-~UG$*po z-LCVC4eyaGgOp^7kySvEL`jHIkuyytcs^9vvdfIO?~yi2oRiRhLg%*Wn>_ZlE=v}h zq*o{imT4eOPD|! z@Q;zEbxu#zpEG!~wB5MBiHQN0LFlovd+9u`F`x5mnTnVb6~sEA+2}EKVyK=7m1&oj>1+yDWVram{~60e%N~2ziv4S|YZ-hVf7qs8erV zHlfhX7IkK3R?y?SyEm_sw=*#Vp)dowhA)9{r7vLFy0ZwTiJ4hbfaZSr|& zfqg9VWd6mSv<s72Rp|N%-H?Z$e)u{=$Ha#`>JF## z%^Qj+F}dH2ZE|5d_;=6baf;LEoFt$*C0K*Z_vr3w%aAJe|B0BP8$p!93c5?@7SJ3_ zrjuvExoR`i@Wv+MFGUYhk#-VN?w{o%LuzawUoq8bO0atQZ-#y@=W`-bQbxsJ)cqaGGxEFT)vN7N;pk#! z9fWYdQFm`1#Sh093(kf;itk<}A+So0hOw%1f;@<2|LCln1$>$R;qEKf|FOnzUe)`cL!(`H|?Nu(OlwH!?6gU8iSmy;X^) zNhb=RFW$LAbZM$~j1)=Q6X{g;NkPX5E;ywWnE%R`wmk5!)S>1x*@#9EpaXZposToT z;?O^lp)}LE{49ZRq0V^*e~<+M!^I(#wI4YNEz+i3RC~f&xI!-8xLEDEBmzPXHC#Dt zPuly1UUxKNMX7qC&HEjxi1P;jr}K6z?%;Nm-QtnW#+x5;{LhU)@@-|XrpvvPw;<4u``H>(n1ykfD1Wri-l7z*}6sw^k`w`ejS4PYM zkP31=o{fu{nI6lz*KhiTC(86WvN<=%0tA*-oeh90lV7?%QYyRj1+UR}qbJ4am-6qy zL#uz~HKgI!__> zRd1O84o_Jvl3=rwZ_C+Z#b|Blg&#L4f5t`<)NUp};{dryU6>oGwa<+04asj>3mFb+ zE`v<%vcJn8ts17##j}8wn+*_*Wt^Mum0&2}AkR`a-n>KlvOjrL08@uNyNqAFw0NX( zY0@^D`A?WZYOjC7LoCRB2Y?oNk#40@Y(K)$C;LJtE2M5?fpnS9dxh*=JWiB%ZtnlVWk2e5ig zgq$>i{_KI=_$yctdLx^VHWPUXDOb+v3$=+~$nF&MYlarGp{OmdTxH(~wWMMXq%(?6 z5oeCjos~W+0;+sqJ{v%Y3G9Yv(?mk{8gKacq&ZI*n#`U8^g>!d&&Ucu!>tv4MzGE+ zytuPE>~esgVK&|nFC&3fpt$miXFOa_j2N|yvD`nZ)f{7PSJ#a)ei z1yn!E2{lbx3y424~mCr7_@>#OQq|Z)+njGA{nv>vS%cQ-LPKS~HK z$fsnZm4=d?_UfK|`+eggphOk%Ed8QTb!(M~G$p-~>hkw4(&qdc8W6N~f&lUPBtK=Er^YV9W_7Yw_I(G?S|A#Dkb&};B2_@QDe5} zKDQaR6a3rHtVlZ1jo>QPBi}fT!R0T882fNnMC?idU3; zvTk0qu##+GRi_B<+VVx|FF2#~80u*k5yj{^rBV+V>pGo9B#JnE>YTb5({xQJzbTpE z@b+2i`opstm1m997p@XWla(l>p)-gs=&F_K9b2_jsw;|Pz97#h5Ks=H!RnC|KFm4& z`&YYG{#?@xu~N8G??Ld|N!jW=;vYBDzqPPE6UyXH>;Lch@_buF=+wTQ80;cWA?(s% z_4*ISD1pc2ZlGF7NCNJma#(i&lS+_eajly{>*6Q4C*{g zd!Bn6BsyF->JdoewUc7?j_WCw!?b|Om?>eyQ$PT?hQwbM7t-1nDZKpd7e+`Oo?A+q z)C>8S!Kf^NUh~r|A3fJ+n&3}yjFwXhLh<`SPxEI@1s$uhl&5OM`>uG zcRuG&bUueJ;D)M2j{Pj7Tk^(t)a}R&i?aIF(>Cwvk?VLMAcF1}9Dpfm)SAo=ce`BJ z&*`r1IxNKSdtg&@@POBR#6C0kKxX)CcVJ#l-{(UiYnbqsfTMAM-!-jALyo9xJCF zX7uyk<$9yxwd!C$0^0}Ss}@Q^9rlK|lP@ETM)}pbL+UFrj{2`6$@=#gb`vzsv9;i&hu^hzE^MtRalNhKT z=yTbbSI2fmcyii_63h6j!AeHHFayVY4e)H-=`Fl70e=~ zoVY^H((^>#1AuVM+UB$45M~Yx!sZVATz{uG#%eCJgP}otD4h>z#?!b<-N$!NnAvjW zlU6be!KWVa>0y26iLPAcq0q1-vGV3VR0N^a(};06jqbpUnC*dk^kXj7aTqb)`$X3I z5cj9#Ja*uefDHe$>F}m<;qC*Gn}YC6(bO{Wni5C9>sK2glO~>%<%S!6H;xr0im2{N zJ^1H&24c_qUP+|pQE)Y21ufa!&o8?B)ONQDJck+<;S0ir;E{z`68;Ku(Xzg(k8e2cpXnLH!$cg}?d()?VN>IcLzj zr1LijdUaqk2-8%a3->#6xrno$@E3-(J3ee!Lx`eK2dSBb>d(xTSlkA;xmb>t`FVu0Jvar1!h5k1mKTnMCEjNTLqAX2kuL}q!$3-(z>bbBz#Wzp%kb!2Ap&95ekRPam;NM0E^i?jOqp z0s9ah{e<7F(UQzMmUfr!r*R2HyyTmI<9&KuIKks)=Ti>n%Zt>zoBJy^>-KIZ(L6J7k>go!QzdZ;+cnx+s+esyhofXK$}H8@)kSHY+O^$WFbki*nQ*GI4hU=Iv#X*3 z8x9}^BmCv1I4znj_=U>#B^6L5V_t4e;(w*XFpkXc{!SUs``DTge4U86${`YukZpyAg=l5NNryK0wtlA|5R0_-!0-vc+F zDT@DNCY{?6QX6bzIIR6KZ1w7`zuXmv9C<#nv^gLrt?xb&T*@~k}>HQZ%_yEM=;<9@h0v``Th@+ z0$-A8=%G^w0Mzxs!7SEcsPk6|OZxBk$2>{AU!#H&gAvY$9slgLMOzL?{FBzXyPv3b z?wbO1M`?IFWHi*3`!GZhBV!$$J`zm(|)+!ALWqP1d$J%#>WdzpR-hX4GsNyjCcocSO1?@lq>h~cUsRC_nu z2pCMZn3q9IDEz&m)-T@yf42RmT0it7GwFv_q5cwq?kAy-^crwJ9IjRhOUQ;l{--o? zb-t#~UeK(=@}V7<`8Wz(C2R-T@yM0oGxzO3(Ovc9iRi_*j;wR{>!AvznYmRfp{!-c zhIx;jzk$}?lJuJEZJS07Uj}! z_>->O3MM}yKls&_qw&vTQMnl;L=_Ydg(T+;;1zB~J-&^#+M)MKI;rdzWab~3)IBuq zhUN04SVT_jnI!*uebVufss@^KgbDyd4R zW=8S@YEa6a)_mOW*<0a`gS(pY`-Rhv`8WVi`mFpU;T7MjpLNXggWNWh-|q#?X2$*= z^G9qj)l)5u|B?rXg)1>?X>n{)73T~{Mh@*VaffnuAh^u-oDl=b&h9l2u(Y| zGVbOn5dOE+`E^I&KE6Anz=g}2p||QzVTFa)ye0qh0(@WNnVQ{bo*&J6;u!$BGh4W{ zb(vI+X<6`i>O_X>IuN|z*?6>lb4Fs$9M|uh-M4?)T3y(%WAXHyeD^P!5B6Dt?0Jgu z+KZ9v_1xghxXcqsEUJ$`He85GL2O!E=h^T_SK_|75=w|Fm$?J{NO{SLZtlU!2IP*C z&Ld=6EiOm-w4i-z@f?loAno8b0QHJ7w`0~}XyU!!Lei(=DKKQhd@TP|7OgOC-!q})KIiQ*T z8pk^VqQ(E^~6E`f9+zri8O; zJhJ8V=gKs&UGUOf+~Zj(^R`o(`lR?S@3>9P4tMx9W%!-N>dl$QO{-u-AC25y`F8Mq zz;4a_NPUH!bET;FRbR{X!IS}xx7++#PKVp81hd*7lS zO1aFgpQc~^aMtSmU%Bj6e76f+#FaJ9Tx=gwZBIAAKa)A!#nvk)+dj_g*s*cj7apOy zYB@07kLQ|n2>jrh*+K$GbsHFrnao-~O97I9?#OirKYS;sIJ0}^7X%LXqs|8g-MAIS z_>=u!1DQFiwS1^zl1&T6;^ zXZ8rX)P(DW>f;A^$mAyZ0$;=V?`uTW##P&+xtmt&-b_g+a{Q@F6z$S$Cql=ZwyS7M z@{G&f0ZykZ2@Wne!a)+3ffDL^K?hzm{Y3PSAHU=RG$tazhblwpqd=b{j@<*P@?GP{ z`76w29*yV>+QnA;W5x#bqg1fCo;K*bxla`s8jqd#RefqjyFrJifd`wDldF`>s!<2K z$uwdAl)Y7#Db++SjNOLvL>CG25yTsCg7w<1&b>0Zxu41;nK@o^TkttxWoQ8&H@a6G z$8RyrdXl=^1xDK%{i+~gvDA)%!ugW?5W;1i+W9z>U_p3LM6K9NoD-`+tA=Lpna$%n zX%LtXqN-)6X&~7X5IxO5-%Z{D_6P*G^#Q#fp%~ZKSBgMFXLlM)-l?webYGY|%4Np= zI1K=|hxh!<{2DQeAFvdjkh&gaHE z`B1hX%!fyKG@OtZKy}_#wf8T`r#yY3ZI%vu?NIr~C-lcP$nK9Bu|nB%kwx{+<71}2 zf}9_|r*)H!@P<0{iONPN5R!;2t>0mAL$P~AjnC5slww1GD++AFOWD^WzGq}B}D zoVIp${dZhtyJd$q6RTDdImS#)jFgiO&pP(4^y`g#S|Y>NBAnyJm^(cYRii`^0I!A4 z$6>%oxS{C5Spj7xxC5gU6cAP^0}@f^m%poP zaw*ZT9k7MV`JY#0-FjYbi1{4+?6$s~t%jue&MnBP7q8OrY#=P$Ubh@++(1;{N6&e) z&3n!m55+@DUQK_V?i=^;P1so`^$%;%u1M@)Ft)lC7wg;n8xDia6PJ~h-Rzj8`3pWV zpj%KLA^v;{GdgHH&$Qbwr`c0T(R2bLKRS; zaGY*6AGmMfJ=3r2#zqfpFeZOp^9J(6CValNjsa?=F`#7j7P+1&bRvgh#PVpHiB$Su zF*;$09AMh1X``5qqfvUf{C*;D#TpLGwo*cif!j-TO|cTd=uyG508RBRcnf(YoMSH4 zWMJwfE8ym+mgI$B_^5V@Ja@J}dEHvG6ql&IsyF#-Dc?V9eo?{%vo~HEJ%`RKiIYPNg@gvCb*zWz2D`?D)wofZv1C z_{Sbm%#IEbMbIh1(vJt=&$TMOa^=6|%CVwoe8L8`ANg{GPsJr!*U1g*moUoCNKwY) zvD*BGAu63{(BM9O^)PEX@QdcYrCQ2n9_5RnT%4tKUxxTSLFQ8 zUyh5U&wg0Kp6K!oilM%AR;4ntY!Q!$E>2Hf&9*!;QO}=mRjv33pye>6sea z>Cj}QthJC5+(8Zi6lz=m869OkEY%8q$mY+HhM9PeSt-`)XbI#DtseA+xuT@9`}ZFb zc3E9s{$F41&mI2y`f58_F}X*ty5e@y#JXP1Vai{8mZdMRgPnZA>0S^~UKrM%vyo(K zIMaMe#eZbz$ z?9GfWIDE9UU#S5u+cdOe?@2R}POpU9QG-ek<;68o(^rR2I(b1Q{MN0P>wWoqdTkGV z&}dmDxS{rAeCuW^ui8H!F-7Rls_gVtS-(j*5tx&1yumgRy>4f+#`*V?-n&vgb64Ge zimCWFsU6le?T%yMWyQ)F-al!j!0IJ8?)h4yb?$-Gy2(r&;7?|C^lwkgk{5&o8}tiX z3}-XP*}xI>jp&Ue@N&LzoBI07Q-(J2I}dQ|f>(ljClKJMk7$1$2nDPOc_^$7O zTc`?VY|tEi?%SyfOwXU;EwL{dnnuGypnqanRu_OSwQTL!eZex9#}w(TlctubSkcp+ za^ner0O0bsH=$0zjMSI zY;4|nDswzd&QKh84r@2a_1(h|R=9AVP7$I55(#&Olu8EddWwCTk!(CuYiE>v)h7>| zg}s*u0)CMuu`Xc4TB#mj*`mQV?DW1D8ByE?hf;v%T&W10Klm#&F%aqq#yns)#KTf( zoBaE4s>A5yUOw@fToHQTi!5eTR)YwiHZ%s-Q8}GC9&Qt_qQ1i^)V=x(8VS) zb4*qGoH6zN=e_$?#YfE>e^;83Z5p;htcoIURA9h4l9KCp)UxCy&Ip{d`A(xv`qt{4 z6%$+Xw6isLCY+AL+hC~puqCFrbfbTl57ez~`7nhb;8cdKu*n$j1Q3iZLMv0MjaW%9wy3h?Gtf~6p_^fmxFUqAu(^5!q zDyxud*-BK-kVcb1-{jfx?NA}tqaRrdaU7O}eqN%H7E@K(ZIPx7V4Jn~a)uiqG{AcI zX|k$wusOc5HK+5>RrX77>ftro2UO!K`CyP?wXUF7x~Lczx;cMG{eM^F+W}wZBQv0M zjE=ePqsT<@O<@#XKfEt?F`kxQIsxnQ1U0Ap;m;O`r3pkXEq{= zu{1f!j+BMSmOy_w?dyy<;2nfL3d@eX=XWg$=wY{!EA@b()Yu4~D#ji{xR8BFi~2h%KdyAG(Qj%^ZDb2C&ZzLh_Z z6@>EO|22Y2U)b8Qi399_8l8VS&760axp&5HkSvclS|{9J{nfC(^N_qn9#lP25(mIyM< zDLR*1q)5V&Pphr5fWMYL*b;H7nD3>CxD@Z*19xG34(t*kr#XBqQHU^z3jxve`Js-G z?+)ykT3V#;p}%%S^KxYYC4=$7zv)PN!TMnNc`%2ud~RI8rkY~(<4!KDKV|y=6)-nm ztL#xt+X+At|L~X`0K^!F8YZ(_)=tL6mn3ifviNe2tOCXA^#_!J%bt1{a&y#tU?iRH z(ay|y9aWu$xf=YpF&dc&4tCLv>8D#Fm(?>e_|A5zy|$@^4!kKs;CM=cFID&`J(VaI zbKG@?CL_wyd-_tAV74H@hdZn`uJh|T>^WEw5-t%`BPE~{YV#5pw`d3#MElw?Duge3 zQ;fykN;UQ#&;x@6;-rtRihmhnQ3;H@p@6XgsIOlz!w~@N6Y};UUD}}fP+=nBXwR^} znAcd*XlIOI<~uwumBjJbt}#}Tn&J>^r!+dso52|alseH8+=o`5gL9$C(;E%2rmTRC zwJ<;))VWApbv~TyJ*ox9{gTQtLUy=tyDt=r0R)G9l~3`O3hZB|y|k)?>bq-YC!R~C z0&+!6zy`qXJ~xV$b<#d~b4lI~YFZ`(BctveUB-@w7Wn3&KPgv7(UUWA5(2y=uik7g zrM>r>`2p1TK@m!?Op&-azdn-}KORbwoC7NF$;B!yQgVrgL9Hn1AArUOY`_!U&DK;w z(&jX)m42H{1R?sw5i2(n~H15F!hIzqu zeDo#Jzx#&bTJSn=##%xz*v=fq#om^5tUi!NjwZ{t8WSgeA zut-rWn7w5jw|6#hT4ASUcYg7so2+JhC6(FW+*3PD|FjPd!xSkt@tF~C%2?w_u?pu1 z5*mO7&9YLuM;*Clg5kwin8hc;S@v?I64vO3AS#4^rBe49shIMa^w$%4e465a?kO^J zA!&k{>^_pyXQ}(%rH#Nj4@=1F;!~ldURogjty2C+Mt?D_4)%adKng*8O9wDk(?r&i zzCN#+g%tn3dTVUM1jO1I4ySXoa0%O~?htoSgHHln}eY(Le zqA!&L6qmepbTvOJ$D{QXSYr?F%FHjg*dX8#n0Xkf?E{U&5YJ)M04$(jK&}(mYX9&y zN{kDh8zpOMHGTXuF#@LhQ*JWcDLD^%*ZQhZ@7&WU({(8dIMUeqK#G(K1(kg&*+lU1 z&dLB7VB8HDK^=o*n?I$mSW?BClv>Ae3uYG<^g7kLWOtGP=NbbOwZ_);A-W8RnMG;z z_ea79hNmX8HTq+-H3_d^d-b9vfo=pojU{s^ejlB6jnqnYWWJ7lXXt%9A&`HA$K1%l zP}kGvlTA{D&A;_|#rZQU|6SnOzKB?P^TPebj@uADOTO~wjJL1(zLOy9Cu!inp0OGY z8&Bxd7)yPL5ca0+fyHTv_*$MfCrMgfH?+1lj{{lVCKy#O?-WE=D?zN*j5x@% zaeQsgh$lI!@+DQU#xFBYmL|?>ojq$yFg5j9Y%#w!q2vt*5Ds)763mZxQAxP4Kq=}8m*DXr!lzR|svnXlu2ntu_BmQ6+Q zdw;RG%9vnH7{VyN<6U|xQ)%_rwt9Y}x+W7ctPlg$F4KnlgeF$K<<#~2YJb#HV6RC$ zeu)WL`CHsfUJcx*exu!_bPh3UM=%6M6M9J`&bT~pEL?xNb=D#lKP#zzn+W?Mr&e%b z6vf?r0v?Crg1G)9%7cZ@3E%y$_;?7HQ|r!m69;N!KaKfl-nZ9Lo^0?+u@FYus2&;w zR(q}dd36ehk+ttN(={49)m9wdJ~X9MLa1!%*t+v%a`+M7)k~p}KQbOl{pW z`PtNKHLMWlt=t@_j_--M3ci%|ZvssJ%G2epO*HF1A{>W%&Dl4d2R_xxkQy2SH(i9# zpm~%Ttwv6sjQlhHcVEE2vmI?&((v1fSmJ#;0C6a#y;D5{<7Jc4u92|8g3@Gwq`Iii z(vS-SkzR>jJUf#ZFGNW9SM|Vp+nE?p*^}ULtH-@#X}8F*`hcgj~A8}>%9JrNAGL-ZK%PCduXB&;+Y{2_%5UTHs$8+d}B1Z z#3?5A*!-Y6(vz=q`G>7P3I*;NI%nv-PWUa4nt>lr6xzv56pZ-m9S}wUK{8Ar^P8l% z?I#J)(C_me9mJMsT0FJL?G_xxcnOLbFY}R7Dn>4kB>sErT(VFI@O3rqD}(%AZKx8_ z=3FfX<;g5rd}4s8;sU1Z>Agq_D34=TJ$Z2DH9|K6$yrLC?v!~nRI9<+xuJ`jjw+<* zH@a-kTdJoZXzMae6SL&-LU~}dc*Xz1ASZ6@vjU&5wiUR33%w!4q{Q_z^ZoH}*~{QM zG0Ik8IpptthtY`;MQ*19$oNErze4_;i*x1cK0&)FQfUuELH@0eW!i)Q^#DE`Gnja} zs2s_WmF3yn*X3J-!RBCZA$$r7bESG8B6y?wzJv%LqD@20toavfvp5!JVr+d8Xu@;q zWwO5lGGXR6@XeGr#S%)18`541p(ehEM4g(aWAIlUJ43Rvo87zLF8L4@ zJ|^Up`OyT*puRqxU$rMc`w9|soWz#KviHh-<$m?+__5(;>-@#m#Aey-G)(~V=mZYy z)NK}Lx}tT;U^}+>9+hQnYqU=c!k%laEIP`v-gMA z&qGE(4NLP|Lq<@PbEXM)2$67*%gJdUk0tE`r{tmkWZ zN{XUPK6cGH*R+$RK08>%)=6|`15RE(8yR6?Z?uG>q!k}c7`Vrh4?aiVV0C{kfB-7T zEJP4LZu(K0OvVKT%6;8t@5&(qH~_5QH=aY{pa!2wv;G(}t07^$zZ8$NyNy}$Z>jW4 zf0dp%hhe}%wx(oD3BRMra_n;V)>QVaC4A+>E{$^u`mw?RA*eBgM_(~b_sT0x3kvb2~{keky%_wBalX@J)Jc1b({`k>KPeS`z(Zb zj1fI~*wj>PF9)uCIPV8AED#O#fCq(-LlV92O3U|`MkPN|RXOT_EU(npm zWYIi9*WZwz!(BUu^Vegd3?K)badzO8C<3H8L=x(n?9?uj?{2B3T(s<&EceLe<;B0V z%CZKm@u9(s4x3A-&RWThoct3i@u$7^Y*gbVZ*e@iGC79}8{WmU(xsz|ScUXZn!5(0 z4?}xCZ_Nb2UTc+6CX-WP`6_8QK2)zR%lE&0jVc)-?mt@0Fzmmtl80HNP=IaEWh%R^ z8p)fXMFIND({gHeya}gezS zUig4(k|qc7c1RMCh*YF(P9B<#yv*BA>+)MO?HhCx1>;YWfGA#-?1z-vwC1aPqnyZ7 znNnR*bt3YbAk_Y5xF>miSE6U_d8U#3?e#o&?qw|NBK`%)*{*s=|GadU=-uzG;1VtI zlYo8Z1Oc4Mapi_=rtx?EYfd@7kZ%c<$O1?!t0#URS0WBsOkGg>`wi-N*A8HlY!oLg z`MH9GITY{(XSP5lD8!NUb32Df2EJjD+Ix*}IJh75-Bo~wwlSvoLcYj;Y<_cT6-Q*- zlcSp~o(NunZX#zexyKoa2g_xH&+>Wq0};bFZdWU}xVBn#@uxWcA;4pLn4cCL@>FUk z=tFEslY6!c`Z{jPg-yT}BS_8WH^$4z2;d=8G_yF!a9;r6D{oz?^g>%?))FNFbB+~~ z3@2Fg=;)ahiEGw>^HFI`tSCM-?|B0jBf27bmcA|Pf62}b3wS=FI}erpk)W^y)x}@L zZP@mQ{+U3tWC-fahYEncEq!!WZItGUO6ZRXXh-FJ(Gb!b)OeV(SO-8yjTK(k7#w~# z3HpGTcn!K}#KVNa;)VKNlNC=yMscl*5$^eUAn+(Byq4s$kvEZzpNh4sw6N|4J7yMT za2#CdxR_xyZ0kjA*?E3GNBiV&-A^Jm>Z@Ii>pnaxb zvMJ#v8PZg37SJ2v5IAvyT1k?kpZ+!e=5@$RCg#cwwHD>CYxJOPL68nY4`?R{4ujL` z>%OKg7d9m}sZYwCE`&6DTnnC)>-$^ zv0hc_rs#{MHd=HPDFLH|KELDl`X%l=F^Z4mPjGS=;K+8WP1TF6Y4!K@}QEWh$|GI`=a+3IiSItEl0^e;Okmw z?hIXD$4(zyvcnDlJ{DoQSF{OEg}HDWX6OdyoM3q8s+Sx6m`E57q%Sv7SOr zgz(BAKdlxgXpNZ9eg0N15mP1Q+;|;Z(b%LvKe$q>CJ#+<7FFn#7{&rll1fZL4}E)9 z&y*%~KGMDRULNHWZO@JW$-MEYG3VRJ7K{kinfaucE&j}#?KDk#ejpsTt~N5NgDI20 zIl*O|?Ie1}_O0@2O)zw%?{8+;`7I~Vyim6oLXpO*%+M5w7wWTno_q)s6=eVOEgZ`b zO$m*eWnI@)&P)}k7s}kg)jO-ADNkwQjkhemb+_EQBMvha2;Q5$)h=Z!#V|X=l!jzV zlrfh}ng;RtNkdy#G2$ILSGguc**rt_>!{#!0hy6G=#mZHX;*h1{UrN!+E}S>tG3nH zqOlWamo41Qbb;>*J^B8@)nf@KvJgwFJ{*}E31SE#Qja}Va)I3(L$_L(ZR?M^W~ z#tn|kH}AsCH(fnV`Ce7Ygl05TkSo-1Y_ff*ywD+Xpas`8-5Q#}<(RDUiY84#IEblo zLtZMX)=TJszG;CGfF}SiVZiN^ExE}Z?qbb0$(|o?rJgQ8O$)bTUUWmeC*Nnzsn6#< zH&@_@OtwiK8I#r^)_!^uAcf&MyEH9E@EhHbQonrXNABl~`9^u5wiKNSRO!9sc@4G@ zOg>!J+rH9Eq6-ai(bXLPHU>n}))Oro)TQq%Fuv(10LK1%^I`F0wR_x{2BWnO@rCTW zz0V$wuVf8`QO{nQgpMwlyk!VrXF4@*2Wso@7Psuj);yL@`@h!A)Sc2e6LuzTSz3p6 zKc_YRt+4y;4b4=>TF>hCC|OMeuEjf7i2=AQOqNh~O4I9CutBq8qcuRFdKb5qoKD9q zy>0So*oxXl`wqQ4lBbMC4H(rnpN2Q;Y0jo)Ou4IDk9sH`jc(|0=^?ZxU>3;5KBr_*`LT zr(@r|M9TkahRHFxdUz2C72)h8z!)J*WxYRY;pDA+NF+!+&7zT%kJT2(DQrufP@^FHHf^^c4Y0OW-F6tn(zTGbj#LCrWcqp0@_~tZAAW%u zC)aNky{xUI!D>xfari27o+E68Man7Cd)!)ap&pIc<5J$VRgk8AdL#A#wsD;6FgFx| zgATDsLS~dSsw^UGo%-OJ2FLt1m)O=8=jF}{uS`#k8I#c7(l#90F5~cn9O)J!`RpIy zhF@S$sn3nlh;wg~zv2I+U}ovWXj~ye`-6?_Y>39R)Xks0UF+8t;kiID(a0G^!U2{0 z*}tU@kP-_--7*f3`^Jx#r<3c1$~zw+r~m7N*47GwfdT)Zku|Gu>Dyxef|osX+TM=Tf%8( zPccB&#S6XxMv&eFD9LRermCRx+P7?xv_6OMZ&xYIfzb*5iN$l}y-u{4I3mN8Omtak z0xsWZPl;-oGQB{<#}vU}V(ex`;8r_hX<8Qp zuJa+{(-nkgbEH#~4VZk6bHCD@+ArxoB}p(Ih=<^$)E--6Djf{ByW0mIX8F&<_@-`u zxhKSXYFv^pF&BcUXY2p!D)8AvbCa(@j&NBJxy0n$6uM|+$#z&MHJg;kl(6dm8Da#mJ=YN*38Yzw>hApxnAiJPEjvB+wsJT6yP_|rjho-!D zvI8W#z1kW6PPZkht@WyRijweV0@9yVsW7IX4#gXi=Lnb?u(ROKtRIb{-af)}51!mh zrR6bnK7o2}#^hT?(*rHX!~E50O7x{iNQ`PT#CPvy9PPa8V1>tQ-4b zRm$7F#_r-}WGczpP~7(n_F>0bPWJI5G1Ct#B{TP9=(HxLdBmvXIDfs~ysG2y)e;2$@$I^VhD6|QnGIxHi0tBj&bad}nx(d( z6!!INyk3|Nz?2q>b2tb*za`(TuU;0wK8KvlPdF#{f4C zQ|#|-_75$7@2_*4e3C(%^}4rI_>bimZ&Cl`t%FngYu(}1b^qzByU+ax+?bldvW_Ck z^_P!N91f$z94b-=jK|z_d*ijXrf<+zr5?yfYwKqB__1XH(;xByAx7Y=IZspH(0u3T z!5*LN8PsEMTOO{o;o@3671^f610H~QH%cvFd1;I$?$mh-;-No%hzLdbDPA?r<-2D2 zy`l*3>YcnRtapLe6h)Wr)wBJ{T)&%~?XO#e=S`A7E(~L94G#q@>K$J!r}Ou=#@?OP z<*wg^SZ+Ap&mJDn?X}$Jq-P=ZCa-2-^$3xkkRo6+y8lW(#&BItSCA!J>)|fd&&fg% z+ZHVSwHXVf5B3jBHU!RG%_>pIC31Fo|9$>j--61#I?BnRX4U+68CpAS_ZDBfm|7gg z{;mR-6yuRAorkqw(W+$8sj{BjeXFg(`Wl=x|C{e>cG3CWt6s{1sy)5-^J9NnMKCr} z#v9?;A=9&IbLNWYsoZp^{X_HLdrz8#6V9tG>a9H-1$umBXXjGyKsk5%A=s9)!caTr zjpPi~koeg1xaCZ&0O~jD1(72Y0zI~)isc}FY!W@JJbF0e5ufUW&Z z5#8dOD#vH!^=X*uP57RU)ypY7vO~7*ZM|W4rg+NDe_6aCvUOXNYv~iff9a47gz!+Z zz2;Z};u7!nbixiWn|B7V5kj++2H_dHk{Xup03HC@Lk+Kw5-M)m5%%X9*r$chZ#lAd zcgXs@`KKt9t@4gjD94_UEjRQ=`-v4$HVfdBtv;k>FPBpx-EMKQy6mzuK;3zP3klEY zXa9I-TY8>cn64csb9OvgpR$5}$jD%OW9z_6^+s=TX#7NRqp2l#H97K}hgV?wQ0x^E z5{iT{bbhE};McetYa)I3%O$upFI@1k*l6J|J1Boo5v|C8y@r)fRQEgqD|GKpPtX6* zdh%f>xxJ!nq&>lMtctoQX<>He_g@M}>b8cqn)_tx@z2|n+zAwWbAx+s{Hgv#qrPB1 zK-Yp?$17oVEYlR;fkK0uZ=QhLvs6DBZD{cv(1s+w>QPIHsT_Dn62?TWX~riVmZ}Xe zUQ5)4K#Gg{i82$gM_O}*Ly>MX2Rg#5hrj=c|38g=Wk8hQ*6+~Wtu#nUgLFwqcXxw? zGz=Y5(kk6uLxV_%1A;Wt-Q6Kw_rd=;?>*=Ja_{p&zc}Nw_w2pb`o&s%us!^2&O^(X zwXeuL-TtaHQ#fnTnS8K`Gv(aMdgRbP^+yJ{Z^~}l;V7de*sr{!_x#k;dZ31U*jZ_k zQ=-(apeO6iRW`>;A!;dVsStoP}0F!%@z9wImy&DGJqwafQo@HD&lC_a>K#{%T zTg4*KrULJ?s}q346r`4fCzazv!T!@`z?!-IUX)`Q*9qU!B3H#1%vU&^u&*=NLbVe+3gv^WwP2(lm~wHUrs5rPTiJu2YVSi9 zQl|-Yu2KyRWw`5!9Cgw#24#V=#BA7NPbKLGu`O#xEMJ-{=*hHNj#O9HABzk!$LxbrM-{qKJNrKCb1g!j}^*4uvl~x&$Q1jzo-q| zZ?17WrXf34*J~E-7Wmw7x38(@`GLEF9jW zhx6yP7KkJCgX>@J&Lc2S4XsC6_lrLGAOIyC+^~yTm~01MJY~ogRb`9B{1^^YC#3_= zeM^37@A2i0+xkmRUq1bk5bZEpx>2^RT!<5}t_6=;w<~~q(}$;~$xk0oe{~IuK3$%nq25bD3C=Up`=Virk@gt&Ll#^FioynM+?M4^WbW_~-f6LS$j%y?qk?mSeSqxxwJha{k?i)1tMsT{Vzxbh9RtS8{|JE{^RoX%F%nR~C8em%9eRP>pnKB-Q zs0(eHVmQe>Xn1k_+)RZvGgYS09J*C?Z^W7*;(Lvo(5u$;&`oq3_30@ZVJdR01X}SW zr}cBcUuvUMlosVe(AiI!riGMPzYwjxA7ewdE6VFy>R)1r;;l{qwns82I31rA)DDm} zlfY<2%AXN%K0i==rpgrf5Lho3&m_MeEEN6e>ES)NGp@Q=TCW28lw} zBrmDC8Xf6mHprF6l9YR=2DWuJNs>%-d8D89k zT}IX+d}1^oM3ujCo+x}fT|d^|M_*AxW9+4t*BC?*>_o(&wWztj&l?}MNY35~T&5p0 z>Hjg0Jt;x9`)>t{J@&pnK!3Kv+xUv0~IuNR0q4xx^+pdhrlJ>7(sEbxm%!d;EBVYluQ&rub{qX zBwUXN&K$1Yxsk#T0=9P^vCgDDKJ0IW=%`4s@Zt1TvUbTphaG9|Q!l28KvDNgL(4fRCnS>g#=+A21>*GGCuo~*YS`a zmHK3p4`wH6$m127O(d*nK3}mT_cVgunPkHAwKzZu0*df)!8LG$8m3udB-rXYDBOt6 zjddR1TjL`HTof-}utc`?ajwWH^PO&S&VK$4yQVnlh+xIf{z{*9VKDZ>b_kq^I!#s` z$u^(t7cdA^&2;Bxcy^vI`DD{@|1?{OkEPl7_hIxd!w;dp~{ZQ=^ zAN?!}9j|Dr`japwQ`{M1p%a4?Vc&t~RkHTTKp*Cy%gh_xJ+w3vc~^o^SNFF~7S;P& z^?P2B1qj)J1Mkg{6Oc6)^ly5n?Ei+x7i1S4H|_y6L5f{u_VnwY%GfiA+*I7nKG+q) zO3j?Q$~SG-uNSN6vEllm(?mtH8*BKFNLF@>g+N&_A1)ApH!-a*PdEd~1=iZ8I3>{jl&48M+4*o#r zqglU$PLLGoBx9I*-*xPbs5V{{q%FwT3I@?);%Uwz{KKW20bF_uQ=GA=gus2p9C7>y zsHz{bClhYM0Ah;+1Ed31sRXMZrL<}g{{^tUs5pLJ8g|l3^NCKXd(zt(#UB}KbZ>hb z;dK!@;yo#exfj*L(1zU1c)o4nkpxk4i4%!Rxpj5yZyO2C@K_?SG6_HIaOYo#ID8z{w(8OS~inT!-F(yMmU~8$8dTH)U;4rD_Sss}% zppDq(pfR1t3kd#jlSf_8{aw3$JiMJu8C&4`VnxCv#5bw#onfR+hgDE2q%H=?w|Pz) zY)F-=g{;*?#)DyK30YAL1j9&}a7M64PN6?V+^!mkU5j%3Q1u=(g%co= zPzQR+Ijrz|BZ%oYj5%Zr_G}cZXiTHrJ5(>(Lf>$(_L9h;w;{r zP)%5_AZvVooSFD#%PvKnc-?2-DrFF@Q}|1c?<8Qa!G6wv*DC^WVMb*;$^YPi5SqQH zv*9?*QKk4G`v{d4X#H%!55)jcj2+d~rrRzk<5AZEhE=4Z5l8qQcFEmr(1=?->%66C z$@>WMuh6%HJwhRlmpD3BnaKI{7t&TP=PS-nlq{OPTsdcac4Jm!DKRpIF(E~N#IR-}|Q zZ-vTCs(`DOA~M+tA6_R;cK&5O9m^JoRc1LR7*5}Cb

CE(K*$QGioxa5o}wo7rT# z+eZ%1DLHe!Z=e^*bIgkBqk^JfR85`1^rD8G`bHNmJn=@)p^>2!t)IKYuFt~{j&dcW z8$%#42K6v@EGq@`(KH=qB;|l0);64B^~bj@DKF;0=gT`Val5xriewCCj8dozJa`c!$3zb=dW56JYEmC7nsE zKn!lv2YJrZ-PxQO=*dr7ugF)C6>EsEHuTCm?KO~rGb|F3h1{^;AgBsXnt>UvvI47L zuEUP26whIjB3Gl?$0a9bIziw8UM&7oToj@oEG1iytxo_CT^+D&c^iToBvV9ER$+kv zW0WYkKd||7w;ZVAL-QHSVS=0!_`?C7tHFVuY75F_=E*oW_!PzaJXU0TxU^auy$uAQ zy%>tTR0$yaQQR7isDwOc`sA=LsNbRh6DZQ0qbn~@>VTI5sb-(opSMhx1a8w+Wx_53 z9Wx1uVb(tmyb8s?{PWxiwo7&pe^VY+9U<#vWv)WMvBEjF`@V7n-B2o+FgdB#C}DXb zQ9fq*VxuJsgls9q9^?t)7CHTc1WW1cRqg<}ALy`+>2o|!b9>68Hd3{es};t2j%k&> zu7I{MD?kc3)(I~QWIdbwBd^7(tGuBkyvcot9d<9uyVECuPC|p=1U;{aCPkW(I*aEu=lQuNE5S=TeC4G_dZlI64Anj>oU~& zJPpxs$41vI6u~HFi=+E^m)TCrLJTl7;?6jsfRP}|W!Eag%UCnYs6@QYlhlA$!sxUm zOI!m`tDm9X+WOOwg=z>PLXtOKSx| z0@3hQJEV<_D*TKS%ER4SeEWhBAoh5hJ;T(M#(@9r5J&~Q0G$D0wdxCJ z)30N_!8=4eP*eYlm%&3RKlJ}WZl}b__A`c)5aqJ7Z5b6-MX=v<9vyG>cZDIoho?g` zP$5e2d8o8$^k&7>WC3Ip1u3q|zdbRr7vol}FZ2g60 zR;VzAn{(OG;-PaXsxkaK7!0N8r<&cCI^z<}0V$gvb2E!DzzpU+7z=na{@NbsK?1N& zfek8CbXFicaPHz#cJyowLWRJ9dfEc3hhmYtt$P_cj{1}?5o?21>F&S10P&cBPAI0B zjyMGd8tltU-MkgKFjh9mF_65sW(JHP?+6?eXTJ?VaBVkvf;j1WWN$7lJD#Cu;r&~a zult;{Mf#+z18MaehT(dlXn~GWA6@E~-&n>2Jim0@7A+|gtq9z*f2UrKY+~WXTk_#e z)-N}JCjV$S0clCpQO3ju zeGvD$go9Bbu{-4IPH9xp*hZNE5CwJWCQ!5bE_9DYpV)eRGF79lnm!n!SFe}&GVqoD zcPCkqA?U=o9w;0&p$XOp?y!@kD>IgVB2ScXwTv2mzkefWLNilX{A%yLH9S_?S|e+A zZRwBrf%1Q`X&{>YyPGlq@Q5)$w2=)+Q2HPH zm?>iS^n#{<3laDi>z_$A<*-*hcujDgKpPeM>}Hw^&nf~K16rto34T9Q$h(pC%O9;< zDp6X%RU^n~`~3wxewue|9CyEMS0bEWWthT!J2d#qwX_6PR61ETH{)zY?$MEvyx#gF z+38AHZMWuFh0^%ivf@yoAHX85Dp6U{PKligD+nuLIw-s>B8uPd4E1x%BKOEp!=?NA zrda=+FaJN#sN&2qPgG0 zP^I0$p}JzBo!pdxwJ&m=8!Pq{wsdB=JQD~0F!ZiQQTxJp$|s~pni<^f>z*Yo*AwJH zw1j06wLYsQ7P!g=dR^oinE9k8Dr~bw?^+8whpt z2mJ^BT>knm{KjJfsJP~^=uVjA+7Ro@;nB~kkUbF(MDxkqpSo+E9LGg z``4#OK4S)y@mOs`RSj98x6PcTbH81L)xXUThSFsMV@ijF=-<3JF(;^G>()a3C*q1+ zElHJ+vW(`6GjPTTqSfn~Yib0PIellKpH3VY_n%&Gct+vt&e=54gmHC5i398Y(+Lg{ zAQQs=1If;F!fNzfXN%~~%b&afKpYTwb^X~wfom?`4YG#gHD18R~X{p09C=WU2h+NVxE}pf+j=R*_RQW}TTuI`1 z(7-E^%E@@tCm%7C27TWAiPQ$QD~7!-3dlVeFe?updn@>pP=W*yX9&;&6$k+fxBCi` z;ETxBJgvogo!Js-L;0HmS$bd$GG5GdE>H8+9vM?3@ zLyww(Lwhf-_%~@#fWS>EwVjHCboq6*$GTWixoN^6H@ruHk}((`I3DD6hmJ~h2lT+& zN!e(uPWfgl34Bw-N^;PG!-~-#$`Efl=_uEgU&3(^Z^XXV0yZGPUqCdtO9Z{S=~q># zPE+?TCA?J0lGc9fP;9JfHU2ZoZC0yYh_!I%Z zS?oV;j;jB@DV89n;ZYV|j2^~kR2hW7vlSsuiZ@oE?XGbZ^}`Of7-%t~497y`@LQCo z6&Iy{L1D@oH7-bEz0u}OzE2tg7E zK74)O9W57GB&CSuhoqPQ}6EW-S8`)s?PHa$xRMhuz$GiHppiRAvaJ$nFrE5YJ@ zHdRr+Czxnu8Rb8SLr!2ilr)sVky6UDY)1z3UodsKC>yh3k4S|u-++`cIsMk_F+nC( zXhZr#X~NF1CvWv6!SLW_RMme+SJDr#NBvh?Hbnt|@lj{_hj1+CZ5vYP7t~%fq1dyf zMJweQZ!r|>d19`AbHQ1iyg^;~X@;x4QT-c$S7dMcm3XtsYrb* z_f3@}2tMO;qZe|uYVM-y9Nzd3QBsutfcx@k3r0;8wr!RKj??AY$P>pE^Uf;x$D-33 zqK;3sB&*tcPWhfd#@}IyM)7jcJ&r>H!0Jh8Qtm;W7@dpy-`N9lM0$xD_Le#ri602BV0 z)hnUeCcd&A>m+k|o*uHe2cJu1F_vfr3bKZY`=7P|^8P$&9X_H!xm>9I!U+Ae@q9O%pJGYH_YZGYcM@x>TrZ=&vr z(XTMzUkI^^YnwH(YC6Qg7Ydvcq>BSN7iNj=qz!}{v`^bP>#n|O+?K7(jng`R&d2mp zzb+*Ig`^Emu72pYVK^m)sri9o5{$GrGy=eDVH$^30RHcR{ck#&tN8AHuQhWE0WySh zGZ5$A&kt#uh8bUqz+ayt;q$WP<@WPNob97ogf>ML51hAU?@xX`WFq+M9Ud;MiP+-Z zH(FCs5?b*(&TtJW(uww|Jv|<~F56zybt^U<;s3&UBhiD(1x$lQNExjN*T!;?@rPOQ z4^&tudXtc4wM{`W*|l8O9GMVN0ZePamp>$uWUZhF5K@Y;m-0dnL7-nzHFF~SXv&S6 zPx=Y3FCMOXGVz*KVS(bC=^6Ad&vCU6=NVK^n=`6xbRJ}JkU{h=C^e_BDO__za1*Ml zLN93+^1xJsh>_UMDm-uj_@-e@0P}FB(|qaIr}iKt9XQ*~1{^FrIgH80HI>f_4-!^R zw3H{zCU@ssu|)8$MYetGz>CPe5rlTs*6Ky`u@77pXx;jriF^xm?3$*gekw`V2DWO? z@=K)?og4xbf5k8q=~vy91)VUf-PBhw*^&lveelnvh{Wn}MVf;+Ck-skRZdk1!FRs? zD$T}9>=riw|MSFv!LFhwA-H&^>CiZ7@B6b`lCf3wh#m_`;3WMSH3Iui=sp!5P?>>g z0V?zNeS)VplAX$id)C{7DoY5sPc;JMJp(E2@i(ObN}tNmJq>CJESbMCGuAno36E^` ze#YZ*C*dRoN+tFMm8pNjEsQ?+jbq`FD!w_*tv}bhwcxcT2GKZxS0*Vd1U!>WYp!jq z!^^NqjLfBM>yHL6@Jd}$$=92O5czyh2EgdK0%~*@B8gK~{g&Pd`zN#?CGKNS9@e$E z&I=hy*E|=tk@J79AJ}L6v2uJmVosQC8=(s6`NEMj9~w&%tx`9&?i3{EEUFBqTEJx- zXa{wSYE(@4?X2Mvv`gOCeHU2)u8Fd#^|#*F;@ziO#6+4zvb02$Q%rZ#$liQFn|t)^ zL<}0(|LEcv*3U`z8raAV!yd8tUTnZL0aSqd6cTKX4sRSAPzv&=-Xxy$`RFk0AB7V} zaNfCG`D<@CwRx`d+QK%QldAuR%4s z&4_>voY9+V@u$s6yFrZ^uh^AMsZSzN!RxVD?sn zzC0*Y4|SQ-k8Y|v+cx*$kXAArht^2gn1|>Lk;ki zyMbLbvOzn@YZc#?#dXtDV9FOmFSDp#DtO2%G&&LbwKT!PR_)($wOwpS%BWN->N^*$ z07x|$s#+ngJ8}FQ4}TNrt83DMq>!-;p%>`ivq&OX&1&Aw*avGvBzZIcLkfUXjL&SG zzbg{2>Euxb#AbO{h#gw}9zxy%boj}kMWu4cf~YCzIT&@Kp|<=ESTyYHD?RciHY!4j z99WFd(szv3A8HpweGgc6$b{44ok~7mM?2i*ww7SZpS~~0I;&pZF6vXx)oLT$ToW;D z5(qMu{^$~F?4G*uhh*@^Ce#kr=d1;&aV>i;1-T|XCAkr+-M3PxCH%I>Jd$q{sGP;R zVyS#>&qS}sUZnC&1iymPBOwR!~86ZJ!(

e{@$%+IwRX4z6<1GR znAC4QSb##Lf2;ZtNNPZ$OxsE3K5k*iviwd8z%mysB4X>TqAgbdzS#)J@DjWEVnnLH%Qa@Eu*4Tb14-#Ynp za7P;x@aN#IsnZZi7kVI6<}Io32-{6kBS!w&BqN?z<-=YcBQ3{1 z!*$1-Ji$IScw0$noWvM(yAzxf)SKfE32Y{q$ri5ySt(~-EkuX05_8Av=&5E39$iiCmc3u< z+2k=A_H=km%D(l87Jai$n8B`0{d4i=+9X+6b=aIJ-@42gr^nMdtgtX1g@QPf=fhyp=LDRY3OQ*>j$?UkDB zDb;dl4ei5>>6HnRyxXZ!z!bWd5B7-{S`$is;=+e|L0{AA@pi4lYq{UT2f;}PhiS7@ zv`+8L)XR_bEyMF76$^BIz0*fTT|(r81Ea(nXT+0CTjMOMMo}`Jekp)5&mCJKRNIp^ z9#JFm-#CAqni{BgUb0(gVpp^6Z$^N~Z>*5AHD0n!=2$3`?UGz#H9Ehfdd(sJmB@&H zB$p(e@c0c42?l>ByXHSeSArCRzq)#xg8w;4m6@K>+&{(k8hUbyS|BYXV8rt6hh@uK?TP9zb<Cfayyp>UA;=i(R z0{SusWa%lt;_)GppG-T_H|`&6&q>ysGc}0L?4ix;U8jYYQ$2xg`ZN0|SHd1KeOhsy zyQO^-fAB8o4hrItnZExf%@HSlRlWS8(|Akf@@*}>GILGP=i!a^WNNH`khW zQyq%VuRjv=M%97gcqmz(?+YIs8GCU{L$a*>Y_3?{(WuVU)nyM=3E!H3KuR9 z{lJW$S$7Hy9yr& z+qSm6kpEchw`U_N8h!er?~Gs#o_HSmd1Rs=RdsWW>)>f^_|7^-g3;?O=@}6o(zV*F z7n9H1WCnWZ;QM7`dnuA*SLxWK_(8WRjyLm-^4%I`kCLmB(lk3}EFK~Zxxff)+;@eu zYy0M>s-=w@bwVfY%jycDSb+u685?8P3s34qe2U8_TK+HVWpJ4usuQO&yK6L$oWq41 zN0uope?C`XdN}K|&?$R=zilF~7EIhYrQDc$WYwo|H=tH)T>7wdwl#0?ITchJIIv(t z(?r>+^z~fL0c?HOH+;pE`1upo%_Ll=Zwt`;WcCx5Pn<+{P-_=wg{+ z$IJeV`0EO!r1_u{^Te$@3*}&7)z1@VKzm`YHION|t-r39wJdOr+JLoRCtX)R@t^e4 zCI?ZtHdoI;`yZaEpTpV7$#%Xyr5|zt2V(I{A={pCE17SWbNr(=9h~##Q5xbSpO#mL z{W{5jNeKWZ#fFn^PXTj+NnxiaIQaFoLd7D;U3C35vqg6_BUY1t&H#Cg03A+hn*j=C z^wrl4J6BxK%xHKOzT{+H)&`n7{;jkRBD|M8jwHTB+gp#UK85Ixg>-+=Z+sSr5!!*V zQGhw4r5uNvml^$62&EaMFh)Lb?&6)n-Rm+*hn1J`+jshuc5 zq*T)!{?LUuQbc})NG=C2)ao4CX4GTO%sUh9YKs#=4l?T*Ysd7dFsS*IAb)RTEFS$t z_k#_?z|LH?m!@!+{FF5ZXiwPUirHgk!m(?r(yIuILfM%bZ!5*4q%f*3FTwQu8eB&h znad;x023E0Ey+Z$47;QD^w{v|UWOsrzAVJ4`TZY9#@0~oUZ?@F01=4+ z>5BpMN_ZujS)aRJ3);XX@2JCcQPXhO!!qk`M-OY^(ojKW{>4t5mC6W|b|d+SBeg&1 zUXB6D7ey4k()V#f76T^9ho9J)ZCvCoCsHt8@@N#GU1_j~>+nUW&XTX0j>=(cSvzBL z`S>2r)t8mIRFh8GpG$o}in_xz{8L9S@*+KhIQoXx)16SVWQt!_=QRw~R-#>5T!x$8 zm0gF^Vtl-7Dqc|lW475_lW&c9@c9Z42?}1R}_b;V}z#A*-sYa;$4H*1iGrpb@sN&n?wN zE`x_G7MtChryX5xk|mRVG3(ZbNJRmD?stmw^>##fc)wY9>YbZni0*j(0G4AhQ=YY{ z0GH~`x8J{2=VBl4S9nFtMB@YqOBLT@f6H?2A<6LCN>vRXbGtlR9BB8uJF5z#AGhuC z=pdYP#$i;n)frO`VgWVIr&)V}nZIP*^P}rp^)PV}zS2wGBRSPx);8u?K@}Yr$Hh~GvkDwwioj*ZI8j7wu>#R)-@(UA z&FwN1H!Mp#JMSl`WXMuP1KQh-arit>DDN&cEtYPIMxzh?+ZxuXzy28HrQ81FMaIYT z&x1%J`MHXClSY`Nq?_>Jf)kY%ah=`hQDh4fYxH$YuOy^Se04LY-wz~ERdpqSR%ET z^;P(v*G?hnn9*{xpGJtgwGymFH)xKB9v=k>ls5+BsYsP}yc>0%RdwupTE7Bv}Yca#NAB*G~rO03*wQl)^zCc3E977y1qG}PHm zSK>WdYGFf|_vR}NTTs0XFTJL`h;Y87;?MPb`ZSUMr%mluRg`9&T!mV#w4|g3;TX|Z z>I-p8ElJ6OQ^wixoG~Kjre>RMAJ%2;YTtRzt9U!((2`_RYt?@6QITNrc;=PaWqMOv z!iT1v4Ec&a&9LIKW0w!vHUV58(vJjn6f!HkoA?vz2Dfenfp@e)9IvmsF-qTeZmKLj z|5+lSC0B@&wr}9k(0yRMH#T3FJ>tvixWr;EAsEFPY!&QZyGqTzpOZ;rmiplY`4B!88F~%V8|<K7st(ZabUwNk){gly|do zT_anru#`07lL8ypP3A*urFNk%!>sytzozNtymaMJ*qARWQqw>S2m}iwEBRLA&^ZTD zV^8tbUZcy!C{CZ$VeKawQ*}HBiKV~0ehMOiJ zE|Yd#!lL8fednV}>onPT!(EbQ#YbBDqdrYUiOQ?F=lW_%L9KuKLtSyv;W$6)MH}*-ZD5i zHk4^~#fUL+anfYsLxR57P7_pv{aM03d6;htsL1%7#Fnd&N%@>8_ptZ$xW3Kyt6rPU~YSx7i2eQR!R9vu?{oVG(;btMuEvwzR6Puv;o==4_yv-wd!b`;)` ziM82Id30pWJL8mAKHOdH-|GJJX8)gm7F|7gE+~;QdsXa#fJatJNfKyU@bUiuwx?l$ literal 0 HcmV?d00001 diff --git a/doc/html/_me_buzzer_8h.html b/doc/html/_me_buzzer_8h.html new file mode 100644 index 00000000..f17efa7d --- /dev/null +++ b/doc/html/_me_buzzer_8h.html @@ -0,0 +1,227 @@ + + + + + + + +MakeBlock Drive Updated: src/MeBuzzer.h File Reference + + + + + + + + + + + + + +

+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeBuzzer.h File Reference
+
+
+ +

Header for MeBuzzer.cpp module. +More...

+
#include <stdint.h>
+#include <stdbool.h>
+#include <Arduino.h>
+#include "MeConfig.h"
+#include "MePort.h"
+
+Include dependency graph for MeBuzzer.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

class  MeBuzzer
 Driver for Me Buzzer module. More...
 
+

Detailed Description

+

Header for MeBuzzer.cpp module.

+
Author
MakeBlock
+
Version
V1.0.0
+
Date
2015/11/09
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for Me Buzzer device, The Me Buzzer inherited the MeSerial class from SoftwareSerial.
+
Method List:
+
    +
  1. void MeBuzzer::setpin(int pin);
  2. +
  3. void MeBuzzer::tone(int pin, uint16_t frequency, uint32_t duration);
  4. +
  5. void MeBuzzer::tone(uint16_t frequency, uint32_t duration)
  6. +
  7. void MeBuzzer::noTone(int pin);
  8. +
  9. void MeBuzzer::noTone();
  10. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+forfish         2015/11/09     1.0.0            Add description
+
+
+
+ + + + diff --git a/doc/html/_me_buzzer_8h.js b/doc/html/_me_buzzer_8h.js new file mode 100644 index 00000000..6817592a --- /dev/null +++ b/doc/html/_me_buzzer_8h.js @@ -0,0 +1,4 @@ +var _me_buzzer_8h = +[ + [ "MeBuzzer", "class_me_buzzer.html", "class_me_buzzer" ] +]; \ No newline at end of file diff --git a/doc/html/_me_buzzer_8h__dep__incl.map b/doc/html/_me_buzzer_8h__dep__incl.map new file mode 100644 index 00000000..d814f306 --- /dev/null +++ b/doc/html/_me_buzzer_8h__dep__incl.map @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_buzzer_8h__dep__incl.md5 b/doc/html/_me_buzzer_8h__dep__incl.md5 new file mode 100644 index 00000000..2cc8277a --- /dev/null +++ b/doc/html/_me_buzzer_8h__dep__incl.md5 @@ -0,0 +1 @@ +e820015a5d3b5d11568f21fdc2328725 \ No newline at end of file diff --git a/doc/html/_me_buzzer_8h__dep__incl.png b/doc/html/_me_buzzer_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..fe29cf6b759d7cb18818593f652dfb4eb3b540b8 GIT binary patch literal 13382 zcma)j1yoy2v@X&@Db|)2mr{Y^?$+W?i@RHaV8Mfy0;L2it|`TeyL+K%a0xC&f(3Vd zhyMS)@80$9TK5fWk&}~?GjnG4?EQV;-U)rLEQ9}${2>||8or#Yq$(QPJxk!&@c|a_ zUq96C?hTfyf{Y~E?cLw^rra1bwC8AYlJC?#Qc-iB-ulNrySE4=lo!vCJ?iuCPTm4k z)cu%y-SQmqcI>a7MrUz1cb2b41z6o}le@4f0b5T%H8~6}W9~n{y5WBb5vKlVnMIbCG<nr8;#&Umwo8NdlZcO^Z&ic z&Y-J z@Q^pzkTy^(g$d5!LaHWkqR!BjeAjQ|&%Y1$v@j||F`N7(*0!aN?zX?WS8Z+3a^}`C z^4Wpza{8_`aA|MgZ-YC_fGR5_u+goU*$ZwZnLiPo;n9nFx8lqz%_5QTD)b|RE8d1W%R%H1ATn|Zi(Vp z7X>KcndzliyN=6(i{xB3^hz)48b{rQge^N?t_j!YL>t0|*Lp3W+$E<(If`r7a>&3| zY^j(@U?B^Ew2pyxe9+Oreaqe!{_hW zG1o5V%WJ|YtMZutGl5%DNHf33)8WLL8( zV9xtW1)QP4)7FlMp?KU6$nw><0+GIEKiV~D;U`fE3VIpPq+kZu7&<5S2Q9AJ$f2)? z_RxF&@2I+hIX8s;QD$0&z-0OVGi6Xcp+;Xn{88IfvJ9@5{$vDPvjT${&?_vu>3%SRNaGyzIrcETL?apTB=|B5eA8tUua&A#>^#FuL`L2MoN9cG1K zU3rb~PW1ROgUH_rwfN!Lgh=BLstAm#z_&!>f@kjCH(PthFY?%wfOH!?iN9U#ALD;v z;%@ZP5 zAHLF26Dza^aVx7AZN-6@+l`QD6h#37uwB*ue-<@*g2hm%H00wEIJj+tv|={tS=P;O z{uFj{XK`-Ytv*trxebm<|B6uzx8P2uE#k@OC7HhZD^2i?NiC9h{pHGskU1=v_WY_9 z7W!au`XKJ+vkz&yd}nzk-8j^H5{pXi#N?@>@JLducw+)uB4Kk)U5cjGv>?k=s^C}T z7}gs{d;w{sLQZbUWn3<9s_g?CIO#^NLHN+&JL|}^CU!>$Y;OFAYZ!u{vF&33*sD_s zHM|&P7MReMqN6Z3E7&N`!dBAo&EOo1j)m|n1jq9g!i~Uwc%=kK>|zOyzBu^gv{)ZJ zB1iv0EpyP0al9=MTVSQ?wCs!mLRE}Ohq?Hf^jZ?!hbPqXodPn!GuHbj->V+=#FYrqDAQeTX_1f>*!GnXj7mWQ2718(D__H0j7=IrXM`47qT}d z-ctkLm@CB`7iyRNxb9w7%Ym&_kiZCyF+;HS9M1$V38@FJ;+tw$pBXNEsLx=nBC<(j z&yHwfqhX!`rwXGa7cLuWShfijPAL7yVcN?i%&BB_o3<<;NUC7ZTZ!;xLa1JE+OR~k zqY>KJGJi-xbHv4X;>uHfIcx>mx^DRN++$YDdy6Kf6SR_U&=J~ruy0MU}vu#_8R``PwL_{yWu3TDq@(6EFfar^^# zh{Wx$yQC)gMi88_8YxX{=dVUX$a?u=GE1D+O;jUGA>)ipAGPU#m=b?y@ZGhlt@IZb zj~laW4R>AXmHy13>nm>dK~HPJ7@cUeytT{+PCw#2DbFr1yqZt?nYLRU2dnI27EC&6 z9a#jtR+tO_P69R6N z`Q!X_d_wUlG{eWfgg5I(Xp_FUL5-^Pdm%XH31>BPkX(K`K zP8WNp`~9YKzzZJ`?xR9WKk!${R*~1oE70`Z`;|R=&-+F|0L!fea zWoVKQ4l$M$ag#{M5Aj&`eYMBYFyy;pv!HWpiNsiT)lw|yR7j^UA zyu>%e@Cfox=yT%lAmP1~3n2u*TZb#*ny}L9VnD*%7rG9V zZgBW`X)4UZiY%Mjg}I6y-zUWHRs zII*(_qKEWnCShm4XGy!sY8MXtOkq!Jk6wayiz*bHi2EabyGC&9VeCy~#@Q7D>UwxC zJM#j<4ZCKY+g5wx<2?m!aomHhRxDWCmaB34Sx#a4278XNw!fjg`ral)if0R@#@$e= z8kU(!-VVPq`sg$}y>#p_?zHx(2{eF7m(7dn@}$*sNSXF^yE)`JS<^M1-cx#cbB0 zilsN4(!HIX+RnDJ)7z#G&lXP!~x^Hz`Ms0R~M zKlbr2ec7jO+ie?igeDW*BSOhbYAh+7=Ex&%qJtM|4f)TU0cBW0O^7iDS!(J|E|GmRL%scp%w~su)W~ zK;}Z#_#1e8mrv`IuA)Yje^G`K+2gCjkKS&y?E$ z2>o;%S%1}0ziw%1$!M2^1Lro&5#kDnQB5IuG`F&i;kLAW;BSC4X)#bdu5=SxNwh@{QY*6wHftv*Obp~ANsPIhz#QWA zE6vR7=EOlGJeD-kacELt6Nue185|+=Zq6m5IusE=MIZ#9Trzn&{TW^8tH|j$06CJ} zAv4vef3XoBJMIq)2V8>#Ui6afsjdOlk^@!7K)w`yuz#H-t>Q#V{|Z_QbFPU-UxT;d z0|j^;I)9)#DOc3uju6S@2^^&-c2l-kMP>3$sc1V~P8h71YQhyIm=T zTou>a;5S)1XtiyFRJ;@93*lU7brzYh*#u+zfkzd1x4xX&G=vp!5Exx1aDADMf`;-% zl{;HgoEP)c$I*Y@-w~KD2IEh2v`Dj`@fNnYWa%G@VP_@lM|C^g4f|b^u!Ga&QR;i% z4z8IXsvWBY&_N&E1HR}_1~VA7rU)}wC|5QzEsa>OH~(qz1KZKwR?pgq>EsY;>zQyX zwo_>Og<3>X!r;QG_@kaRVZx7K^|wcntr8r&2{NBPD6>@z7FIvNJ=E_o4@rCpG%>DA>Cf zVxFGhtgl)>8LZ=j)$1rex|9{f0lPndoeo|W6`w}1RLUI8f2f2XMB?2P7WJgFXf)+z z2#P%?C;rBgx}k6cp4j|-qMK*ay&50x>uiM2rpKMSPD&sbD6ykoWuGBpxTzcOdhsL` z6(p*)g$0W$T<#rP8GvCZlj41RQret~5lIQ=mU{4aWs#nFO@}u1BYf1aGx1K&QQEg?;kL=!8Hw^t+J|0ZCL`u+x#Gzx z81#RHBZlV}22Xc&?bv=BnB}AhdaE|=rvO{sURS$}bZ7eT#j^qQxwSf~Nd4f4r= zcH7IAaIk8@I>Zd}*vxp`vcxkl689TBVb~{9=qWn=x7VNZ$QJYDb)VE6zk{VK9x$X@ zLJ2WT>cDJ!DES9wSa&EZ08vYFMyd=l9?Ma}*v2taE;i9JTUuj<5r5wP6`^=0h(_s% zWZ^O_qF5xnIVXp34Uo&2-t8yKwS0A1Fv|xIq3tV)Rnsr8*9%w+<@hFN=v>yw;c~d3 zfmQ3h`N%`@>Wmzp(yAxFECK!~4!BO)r24A%t%dw$IISp$2u&gYylR)E14$O%wN^+J zb*P31KQNhBIofa*D^06>L}zE*m!>tDp&dpY@S5TZKCNpn8^n=7gzs8Qlj);Nm7-~2 zg6V|N{-RMJ>~W)dGrlP3PCmy^N=ld_Be6N_`5lyDK;@nms4I94X+1_Gb@1r!vP}&z zZyoeUZf@!90Z8<1p;W}LA}YgM%~lx>;$?3-o>Vs7GTi0{`wUQ6L#KXo>6D6~%a_ya zARe%Pn7^R$UF>g9zKi{)#Xp|qQc7e6!%{`E`0N&IbT9NI&F$`pOy~!WHB!=&xpBRJ zpd%SAT=>Vi7{TJzbVe7{(7pb27fBK~EA+;UVI`>5*BDb8^5?0bmXYZ-M*=_RPIY07 zLsA*HW3fTSP(7Oc&YnQPJ`r>jUT2CDzm$W=Q4fzS?b0tYEJ|^SR#y+Zp%>OJ3=$Gu zJ@q ahH|c>)AB(?61|ebt46JhK%ij1a*c^22d}faNIuX@r_}zJ4oGN{HkeC!fIU zB|Z~^^H?c&cI-%`gLA}w?buv4efiR%bhlbKtLw*{+pijQKWvJ4nP|H`Bc4Dx)A@Ajv@)^KV3yCxs{k}IV8^N1RY(2P$>WiAZX}JS*^JJ_YEAMXp{2Jk zD6=S{A>CB3x`&M`6W7C7R|J+<>FM_{u3Gp~Ns?%Y+918@lSJ~npaCP-ABTN5n=El* z@i)Ye$^LqXpNKx~+JEDc^aHMxb@$7!67GvGkheAT>pB2n=+t!#o%;ua%If8NUUxYwFCJWo{e)gty|;J!CC7qD_GEI{6(pEmy0kaflEQ^3jED z2P*gniw(@#I@OxKbWh&J#AWeAuaXq!7hKy4oA~WyL0%6g(YITt0?J0i zsd!2YM0<+&k8swlnIWx%?2-2B;%0_6raf)NJ6)gI;}=P6ku!cBx_hJooHE$n13ywG zVjQWvtZT@d`KWyf`}od}?F-$P3%1Bn)wNp;RjUTRaYAAk&7%|D2m2E*pR;7uMZfvt z^K89v>{*BNN5kDvhL~DM_ClOg0qUS3dLovh8@!Ju{WsSxkw^g@UKdl$4J^%@p9Vex9HkVub1MgWscIJ(e z1?3yENxA4hz)V2fl^5|=d_Y9!`6oi^#3uDPqUxxQepA&*#GhSp7 zmw83Tezv)I_y#1UA9$%Vc>7T2~RvlPItWU=YslWh-#*2y(CdN)PgE{{ghNSN|+GKoDrv}1{>W7Dk z-g~lVrY0`Ymgqv*|Ki)?3nqj3lrTc{Ty!~O3hBt8;YRj`HM3Qg&np`Yy&ye7nN4%z1eg`a3SA&6>L4Ma!NY@L!h zSm^~V7b1t79oP((O*rS6yG9iP)Owyw9ARJOlgAse<=7!GvA`Vj_=?IPx2uP$(k1lk zAFN-#Sd|1EQEZ$kGlGnA?W4~$zhM8C2!|7+l^&;VvLJ%KvHs&1O0sHnn8N*_rnO4F zZubd&&|rswkv`z{10|UhL~0#q_#zM~85U{H9g759H(sF3>r=o&NLWrUr(T_z>&jM; z0Ak#dpwNrtJva7AI-ek`+j)Qrs7zw=vYj(d&phoa?Y7r z)tUg1R)^){+}YXL)lm%O1rSNe9J`mg)R&z1&wEEI)-YRz08N)m-$nRT9gc_+aafw8 zqzaw^!s%LwSimsEQe-9{WdG`MC=Bp}455D`W4-kc0~Mvpl>oIB(D z2jTrGF43=axu^qTWl@h8aUP3Qyu*Q*>$2aHcNr+dhik{Hcf6mi7LP~fj2vzTN3?oe0SA8J%Jj=&`C^Di(K+Rcae#y$SbueH7LUY)4 zsN}-iCv?q5c{5|I(~GI25_aP*4_zlZWuwV$ zdMd$=OL!u3AazXpf)LHMRWx-WYwgv#^4rrSmAy*VN8mnEO(%gptUL|#6I8YY_>p$*FVC>i@@L%i}W`JRQboL-C%{f-yo|G-Q%79Gd#l*i_KV3vog*e#YsbC{Gw z6WX7Q3ey~JAKSJ)%g-Lo{Z=pSyxds1xF-A~djy>TeK5IfF3oCo${u|t22&XPSK_cC zi9YylENz}jVP9^*wU!lJ+sb~}R0znwn=I^Z_M3Zh$DI&P)=IW}7{-LkDqasNfNVsQ z*tzZ8Vs5aj{w}S8stKIhc-cdHq=r-%Pzripr38fHoK0@hL0<19_v!%pBh?vh>R>fX zhX~O;XP>xXOBqzlF0l>zvyfJj)p@V+b09W*Z7eG>V`}51F|5u0l<^_+#l8c_4Mj{5_YFkLBswxW!M} z@o-@Hin1U#cvX^wgYnVl5D#eyNvZshPh`=I(PYh^+4*FPJYvDwnNjn};w&}u;!iv)=mYX^b9)`VJ|o=a|e zl>ACQGbeaAc=p^LOQz($5yv{PA78}1YlF%r=>T81x#Xum`l( zwDGez0<_Thi=gA2d_`MFJdqG>S5d^Mlaf@@VF- z9UJmlJVCxTp(aiv;s8|O{try|I~M`kez25mUG)Y$;LbmI)qRZ28neU>Km{^Mqt7t+ zR8L2NZoR{s$c&C(jH>{v6nZzj5R3tQwYD%S1Kxe_#mMnOFEliw-Md-<=$NHkDv~{& z!>WN|u(s?acY0AuuYJ*tYV#dU>3zkj_)9oYfB=loikHV+6n0%fcjVZnR6M8xfJhsfx%V6rV2VPJLJ4D&e^h z*`l|YSHD*?8L|#6`XLc(kFm5L3fd74+=qq;8-U4$T$>m@# zbh+_1&T!m$1oWhItEOxXHpukPPd5RE?P{>Yes)v`=pho z9!yu-7mokAvc&e!hyD~*%Bf%ExV4jMME;okEz0;)J4$Irei<4EotkT}IzA%mxW24a zkhOY>&J6u@)hbu;V|sD^f&JyTkhXE>PmA3vHb4R{iG$vCA5C|llyRk2R#=g{a$EKR z_{X6FJ`)AxKP0z+pV-NC2b2>3Bq!UTgC(HKaVLaY(chqePDs|swBfDT7ujV7KvUP; zsc^9uo97p)6sHVX4B_Hpc*CCj)G}Vdx&5Km>?F%CA_&4aG2M)ZL%szfI+F=MtlX(j zs`gXs^rr~UzV`KwKj>f}Gf09)pUpcX;qqx%byVYd7paG90V~%>J{do}R0&2X4n}is zc2XCRz`vzW6`DQobHzpN0=#Y-;3aA{7ao%)->|*C=P)1wJIS3DmCHj`Uy2D09hXBs zSE~4Z>*7|C|A_Z^qLGk4n%P8YvNc|)q*S7eSR?}9P%UIY|K&q_RRtfTw_XkhM^emC zLzSV5Tm1CVs(7f(LrZggIYOggrPH*8+4ZWio)<1|`3ja6edQfi7x|BqzmzIw&)xHh zxAx7+gsIyOgmBb&#~AH)dhs>a7Z2NqHKgzVStAf*d2ojFK1T7tsXsxTdL%-H52GRg z;jcuB8r_`CdL633_G^>7R~0Vn|frE+J|)NhRSb zX%8g#t#E6;mPtJhi~aVAEKg9E@%_KidPF?Yvo%Q4EaPdht(8jbE~+o`M_osE=py&*s4+ICaPr=`;1`-Vbo4D%d=n@*+3^? z^WT{V`!rGRP+rf6F6H>~$84C&?}!c)s!Y6!2kFQ=u_WMA{O@HVy=3LGfqIT-d3Sku z;Upco+9>PJv%?X~NE*diY=5Lb;7zFS51g2@%#16Qdocrx_er8r=;h}mB^PhV@9*@` z_?!swM7pieD&wB~|Io13#+3SPcV=Y9LYEQS@WxY_7z^Y^@bW;AACjle(+v~!O|C9pbU)~YEm6*iGQ7qyGYe8ri0aXRzZPz~i!6HkFYW`Z)&g~xn(?h2O2dT>;yxks`t!*9cOn+D~dTb`*$gqgYSDACssug^E%sg~2d9`TO zS1jcoOi^e6b)R?9j-PTU1MRt}&adSEOWclfye37bC(Io>^vlh=Q~eXyFB}PmhmfIp z{SjLhM5Im0eD8b1Kaqvbu`eqv;5RZ==}hR%RsH#J-0R%N9hupb5rJc3v()3jGrhZ9 zsC7`WLMxVS>0c0F8F(jF1=e3CANYn$S1tJ7qH#fCgPy*xMh1j87l=1q11 z8Q2tk_6Ek55Bs#X0!2me)SB#4 zr*`y>JMAJ26{s<)(e?VLzfCX)-T zqFL4Z6d1W@prb`Yg$J{5U#p?4!x;UM7dNFe3{T5{mC83B z`-<|c>6F7rgs5-yEB2L-Nq1xb3@D(GKISh_Boo1*2v}L%FQ;qsDJUs#;z)Qy7SRwd zAQ+1^R#5Z8q9H`CX!e4dn_0fo{}UNm^y4F6f%47h_*80|VC~KWQ)5P5vJ6HZpq7YE z$x>9A%TeV0^4{|yWg4-uejf{2pKrJSQW33;MwXeCgrwnBWyBGdXhB^Pqu&3UB^k%} zJ+J>qj@o%2_Bbnq2as!YFY27}nrq&*raoH3%3H)TqZ_`2kb3YQN+3li^D}b3vEAq5 z%({ah0Gqdvi(tb561Ou7F3+d)Fo(~oY$_0qV_o+HX`w;zb`P=PgW&5{H^8r5UvAj9 z49`bYSu=bEs)%lkKi$t`2jK6$RC>TKUC$PoSjA-n{vuVeoGdZXKQeE|%|g4nN6b{3 ze&94$q=ys#x`^PvF%WhSZzZ}qOF}krmk0FH{xk3!izJuMrWo^1;ay}PTvsO88-wBq7pXWF z4ECq_I-wb16k{si^9=^8nEKPaf#xX|QFx1&$FmwskDRZk;ey;}dE{>5-On|4uDYQO z2v*~uf&TH;90J(bBgb$uJ~XABF?2B}q!EyO5i(;{c{ubx6Os5&;g;HCcNFv2@%~1w zvE^!STtbk^8Pe(L%S@tsZG84E*C$;SA`<|5Z|4)>Q{<#)XT?jaL)Tv%c6J8BE`-Pf z%ZjPA-#CSA#-`pL0$FTTFrq0y&_4Tq@>#NWZ%YfjSJhO#yUI6pd6mAn7qFY|kh1?J76Kf#dMO#c7i*>w56!1sDH=T zjN!!KFFi)sF@t)w~5B-h} z?I!Y+hP`K3w}vt#j!sT63NgM?!xN`gdWCnXS{Ek2G+7Pg{wdCyJvuu2?BnAj@;1-j zuDVOJa?zZbK6s}<0-0P9*)R#e z-aF)jCkwYzxW{7co_z3U8-T+^XBozcNG<6O(d&yUhVxx^7?m$^Qye}((PGTAo>D_ ztnm@15PTio*IGGJNbi)&cuN*}Vr_4~2IU%fW51;Otob0W&kF5m`s+rR~Kn{DBctL-A%6B~>>y?er$-_B}#IgM^ zIUpJ=Q5tar(_eY|o~v>C&ONVxvlvRFPG%e;KP8!DY0~-#AG>zkIR#y_YEN$Fuhz0- z59uG;{jzNyCJ}Z?8PIxW{_}7+stv0CJ;CokG`)f{p5%TjFPy%@=~Z3FprYk^T%t{?;5eJ+g- zU!TEv9;4LT>)I`#_!y|y98s976`PozCU?^!c;4Z#AzZk@$;JqODLzMI99>%QBNC}PDl#Fv8M*e(IdOwkLl=o%x8L%={H1- z7#SA5lc|o%*w(V(gl;2nPqKG}vD6H1# z_T{Y6pkNkrsti-@c7>}oFs1KLTe=vs5N6x?)y=CkA@&(NA!4(l2cCXRRrs+6kz`cD zuVbb^cPN40%fH^KjzgVei?v3bbL~mHvl8mp!H+W%#`T zKDg(ki%C@2RUFZ)kjk%zZI&FRrs;p)lq)_T9ydl3b0(LOV(&@xLq~8Am~*| zrlPm9w&NTHf-^?VmuxH7V-Of{)fl@+iRc^H)<|@9K*ouN?Dg-9v{>_qB>1mjCT^I~ z*kVe|&8~JIQs59InduoJuMq)yfuOOVy`)4{pEn2V&)^+6YPq}6XH4el3Wqj;id+`RIOJDDe( z;7g{~i2H6WVtF7pC|@+BV%v2QoTo}IRTc|L>3)s4m|1$u~^#{!edy;0jt z?hMm$qHJ+oV`&mHRM1{2;cHF z>@d%F>Pov1*6}gcgSkPE^AxscRY_MgF@Km&Px!`sboFV)c^FPln`3*=`MK64lH|u- zZ7MIRKFY@2fTwIoH_L3qeyWS7bf5TIop|*io2Yh>(wB{ZDS=?^2BaF`%fLo5MNZp zWqq60WLVIma*xnZLYZdy^#!G79$Zg}Zxy_<;mWqj=1qJOO+t1D(OCY{nQ+A>+){<2k3&FV=iok_`8wVi0{CoI>=&ruw zpY~r*$I#N>8q_(jYERHUTdbY|#DaSaM#tH{pK{Z^QCk=)TyA`;e3T9XrvKah|FC6MCR^?cjnU57yUz_$z2LDG_?0CLn361?o~p% zDvJNXCx_1_lZN@%eP^pXsJ9NYuHD_-+}w@t^RG7>wc_O6(nrc94?g6Z5&Ji6C2Dkj sdOmb6KN7d?efQgq|D~-WZ?T;$q6?o|Wl#V=3__EWQkE7>F8}}l literal 0 HcmV?d00001 diff --git a/doc/html/_me_buzzer_8h__incl.map b/doc/html/_me_buzzer_8h__incl.map new file mode 100644 index 00000000..bee4a71c --- /dev/null +++ b/doc/html/_me_buzzer_8h__incl.map @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_buzzer_8h__incl.md5 b/doc/html/_me_buzzer_8h__incl.md5 new file mode 100644 index 00000000..a00dea61 --- /dev/null +++ b/doc/html/_me_buzzer_8h__incl.md5 @@ -0,0 +1 @@ +479f9175966ef0a29df27998c39a8e09 \ No newline at end of file diff --git a/doc/html/_me_buzzer_8h__incl.png b/doc/html/_me_buzzer_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..a5014cf88524078ab4142d63cc4fcb0c063904be GIT binary patch literal 46513 zcma&NWmr`27d1?G2}p+^f^>JOv~&qbcXv04lyrBBbV&~g3?M@fO2^RMAky_5EU-uvEr?X}iKswl}|V~}CM!NFn6$x5oh!6Es=!NIGbp#WFd5nO%% z|Dl-3%SggKJpRjXFG+%fdjTgW`BuX#dw;>(FWVgSa58$PkXpxMo+9<-TV116)2eE0 zi^jY~Vw01kx}KFiw{`vtgfGdb>U3U`$mY-RI26Y)XcJdIF%Bq@v%W^_8?S4AAx!v| zFtpgtnrrmz#+07qeHsh5cb(r-jh2Bu*Qm%vipm(2|H5DY1?~U$N7PuA_}_hqmR+Ba zzk$QQYrRfZH72AYBKns#@Z8}azlO`nQC;@0k4e(mlLq30=$)t#FTbJ$?o#Lq-3$u%3u+ zs;8^Z5{xB{<076u{Tzk0GLlapGZNLAm;c?*75)0(!xG@#2N_F#tW6*2Pbb~j@7QyY z@1I3R^#A(szty_rxC}Dht}}?wuJ-ww+Fs0z^+`!eh6x}1_xE4nq$MTk9vbTZJ*KJR zMk(viSW(MsT=eJcT%&H?l`DUzrLxVo^_}iV)6*M=fCqcgrmD=QzwWai^|QpaBqfVF z3C|x_+s|ju{Cf8G?m$0ll#FkB+`ZX-DK}tI)H~31{<<|XBI0lO(>v~@j7UV#Wg@4f8jZe=w!XrwwAwC$NG1~p$=KYNxCod2{LP0Z9X z_1EeW)n~7^2Rs#lJ@Nl$t@pS!b&7Yh?PF)K17yi|(QaN6&j~C@rlh2q*%zHuEglo^Cnp+|T<|^5@x3+=V>e`@Iws4~RuVue zbIJcJo7DAoD6zrvw=@Hv-PXNo-@u8+$IK`){rBw0=l}l-<8L0e$51EG(2F=-r%Mhs zrh!h-pf4>dE8^xm3#;WNB~eiS%M6KVVnXs`)evM7VMGo3yCW3aV3}ZdfjF;d8M5Me z%mgB4T3SS}dCzrjzZu+0@uebzm(bD*tketNX{FLFOM%&R>hCj40@+l}O)rg1)Rj|#Rb_0@y% zk127$FDg5~h(NK~sWsoDT3u(a;|Aw0Q|7!A{)frj`a;yK$a)V9hG8b;cj4mX4P*@{ zzD~*qoKxScNwlBS4}=_!*>>y#>>@teuK3>5g}&guhr&v8loR zS;9a|d-wGzqfmZYSNLry9^CRnW)CZIqia~%8aJ{GwQ~OYkJTc~kfwj2Zf5Xlg?uVf z##mW_!_lQ^ZUj{Z)@ID_wh?#6MX%B}tu>c1Cw z?M81BjY4TL6EC(RY^FtC%`oXLA}sTbI0<*!7a} zON1=$Q|(Ilk&*WY7ug9J8VJWvM7E`;WfQnG))<*g9hT&BY5Nv+qp^N}W3ie)u_yP? z#zw^JUOU!h^s_ilU&3roJ&u)&73)lhaFge{t#50l1i6CCC{Lt^0KyEn?*KDceb#;2 zr1F%+mRziNTy(*ij+VB)h3eQt$x5J$ z@7!EJR8;rF!n$x6vL7wa;0WUo)%Z0r6odccm+1AWcP$;-Eig~}I8H{i^vm$Hj+sA>Bu#gZd28kMxz&qd?;wjjg#Tb5ro~iN)pTXODhUIxUBx@$iTkOwbX(c}WSK^v8$#8RTI2g$F6zBz7ylnlwTjd)rw>YZ%TD6+f;MWaQ6`60!z)6t^dil6B1Nzxs-R<8E0<8lH$AL?3T0M2RRw zk^9rTrGg=zbZ?IDc&2W)i7~G+G6G8q!}qaE6d9I(yd`kZ!=czz3K3q?Q*(HjSv`Rh8WQ3)+#Ed(wO~wzqbaJ zf{Y}*!;~M70*w%k5=?MdiEU&*?aVPB(sw-{Co5_8TK%aV`Kz^$T_~4a;c)cjH*$|? zr9o@Meg42C$B5yV5ZTJ&=Dk7Xa>mLIBXUECDB`{@mhaZg1Lo^vc+ekL9^quxLJT< zK5c6jEMVze#(MNSX@NCi^#(jm*)fOL%N}=T314v9YMh&g?KSbC0`BQauCwM)|3=Tr?xlqG%DG8`Ko>}5Q z-~MhmU7BBf82lt7IMCVEjxV@G%RJVH{AHD6e{{V zeR_4x1cE**CQgkyhEoNu>ms^!o1VtA3g^Lfths85kWK!t<$idT81Mq(>CA-n5gWQ| zAE5>ukYdcMS5DbICFHA9nI$g3k`X2qJ7iiT)||yK6_Cd)8u02^U_bwa5!jhd@H!|< zeI-6n>wb$7ENND%_7u@0F2|H3eA_LNWtQ*~Y$y;yd;cHG1RTHLSxltNi-Ky-mk7_X z*f7&>st=Hd5ty)w5m!`ZPU?9@F@l$!qZ^4Vq<^A9TD9iA+-B|MWpvvkqUoOUbKPFw z-#ds}+oIvDxsT{{Et7F-cHURB@!DWf4u6I@r?{acsr6dIcyyT;_9^eM=@|kg2GVO_ z1L2FGVh<&Dc3SUuB5(tO*MF*NXny$~tt0@4_G^`aBnrWQ>s1(GV)qIl zNGUiKPqk*c5x2M3TUeq*j7$#1DjCR`{3`9-&8xoONRa|F1-?ISH>D#`Xk;t+{jyQG z4C2-%7-XCui;P2*(tK^jY=HnV{yb}FjBwns|H=_A&Ws_Xig(KxS4UU8CpV_r=2>Lo zznYfttcYtz9dV7z6UTjR?o*KCq*6WhUHj3eP7 zbA%~4{?9bxhCmUDXlOz6|2`}K#YCYtzK4SzE}T>W31Y!MyIf1OWsE?DV`MKhBJuLd zmYz%P2?3JA6Tvo7!;$?^OS+A{-}dW(<|q?nuZe@cq3|DQDHO6NwYf+cj~;*cz5V_7 zD+SJU%xpA5fl8#*=Wb5&2Q0oXSMgCpcT>dZu>?8X=t&ja(#@Q(YCX>rwT_25IqHXN zkSSqH(_#CxT$len5Yl?KAxQ3pe`(_nO9ZtBY7P>&x;Bz)@hfbx42x)89AbuwzU(8; zYBviH8vP6%u<%2e33687o?wrhZ&#h>CwUBcQ(rnEk^+`-VyFT{fPy5aeO)S~vEVyf zP@{2w>nEi{%?Ns~zyCcjto8a&%PA#SjK1qwT1nf#f{Dsj{a7$t9RpwQlV+4>`itXU zB4pf)g_FScl>B`N#SMje4Psh5x~g45kL1(sF>>s2?BQkF>Jj51-cvE|v$=2f5KIqn ztf^vmTZ$v>@}6R6Tnxkxn++AmW35&1Y{NSXz!-X;PI#C1uUqb3TV5P8go>)A{24Ho zZ6q~>!{Eq-mD#`E@Kik#A%Ac4!Mn@V`n;JZ$%!5zDQEypV@B5I2^VL}l@4Ivf5*}+ zz0~eRVz`AceWf-V0cw|SqrBk~^F=x?CE1CRV>%k-{>{Uc?P$pm!?$SY-wu-GoyLPm zsNt#jx3+eIu3vp?65G8FE8m?o*k*S4C-r}6vy!K6qu*-US z9U8WTzYDMyaP~MBl|s0myBugCVb7h3tljFbl>^ULSj;G2@<;jV>23B<(YjZsS^g$? z9K^D4ZDf@$B_8{)11QZUPF9M1zQxH2hbL^-?ps~Tfl-4*>(Xv}a>CKPX0pSBQ29x1 z9bY$2zhwSsM)K6@xFj`e&byEEhCR1v^LwH*vB^tE%?)$e9#KWXseA}-8+U!d@Zs;XLji_tdW%JA$6{9f>lbKZ&6npGWIGXtnB1ospu6iOB%x6n6eBKDAw zf>S3W5t1;G2IrT`>uWdZ{jyJ^pBdWV`349g(bY2jn3Ec}pTf&1$dss&wfXQDgw9S_PJGVu3{@wv*5cosAoddlI zr%(37H?7RKB$(FlQ@th>hQcF!>%Jo$rH|MHp9#^ouhaU%eG7q`4as2p+GzU{!bkQu zDPX5+kVqVg(DCWidf9xrq~K(&pmyAz?tc>lb`mzdkV2gTT7&X=q9-Nt9$JgCdY4(t z69vH4Z{|6vhmkDE0*opXDRbk9bskZH-7&hs;!TaJ-|d>(1@ZRIH8sZ`D7rZ<%pjJ+ zn?@+HD{zN|NVTnO4iC?)zjGC7Rv-I^@Ju>nqeOSLOy4F$Rv(Z#i*` zEkjXYP`WgCyMxg_>ypAbxU+h=u z-gQJfM|ZV5+0~YdAg3(S@v5$s=_bl{UmKG+k*DtrqiNt4PUZJ?(EcEP1nE!S2_&8%Y@PlKX zmY>43Gi>L)d#d``PE>iaGLA%fNRVJbJ*QK(``UZO6SBEhYUG}D3IPJjSfulQgFn?_ zzmD3&Wx@t86iG>+keB4^wyaGTt~VLEt#qy$*Geq(m&5^=3KMx5u5GTfGtod1H z&TJgl^{KUmm2|t+Y+cYkijR4a8OLBM4#4i26o)z{}A+ zy$e=806@OhN1TobF02?}3bX~ZF7Pggw&>FK;s$e567l`CKM9(Se`#oUo~R1Xju?96 z^J`m{_$2q6`u=2aje_)J*`B%L%HzKjaw381BkAcG+9(3=g(%S$L}&99ACxx$&`e3L z#k*`GC70NG;7xXsAWSk~A`|_f_Kwww3p#LS-ei|=+utY|^)Qt`d_WnKDIC0c-I9Z+ zsZX228bAS|4aore<7n+04v*RvYguL0pp)>HgDxuFIYGE^L5hI2{U-YNkhPEx(pqDh+xvxddSQ#Rp|1P*4vgc~|&p zROX}w=d_A#LbAyDYj5gi&n-TGi~P~^Y5sQE4Lm)ZzW2)ls!1|!^(oD5dR+faa6JTZ z>Sy+3qq8sPV5Yg#Qz=L^os?TD8872}315jGT~C}gmseP6z2dUuu1+%|fGUv8_wyk5 z_1-{udGgXSRPGIpw9N9Yi8E|dT0gBn)h%n;9YtkbS|a$=zuhRUYVZ(Y7fWC)`sIS) z7}v{{iy?y(S|@SH-64z`1;&4q% zhy9M5ugIX!pKn|n=0s!B@HiyqJsatnScd=L<|a>g4cY#>lYaVUxV+`eQem}XSQxMy zY0IoQ+@@R^(!U6Tap9!EwqV2UDXiA~Bwu$wr^~0)kO&~$(eA5f$5gHXEygd2al_Um zG#SOgIVoUz%nSo9hfx`Q^^OUE_BhMBM1`_}D@>zi)fJu0OZ%znD-oc`9-dnz!KdOq zR}VS^c~4lwX)mcU@|mR8V6}_ajsRCuSgZ79A+}E5z7SVGyBg zUQjwps?~|1Nw$?!jbI5ITm8e(h$Zd(6J=F|%cOPLQ3L`jBy6}lJ1gCr(ZfSZy90=G zQl7R>Gpm1-x@r2B61ED0p8mu@?=-YQiOGdL4tL?|JPzJk_Vms+Hy__$6+66 zba_$96c`QHh}2N~oDrssvpKw($9)kI8_(p3wk*sIL5s)`Wq|& zm(3$>CqL>cOOCX8oBgh1s{O5-z5RimXQ%g3`vp~mva#&V{L+0`MvjKQ{#|URAx0sS zEI=`t)n?7FAF;k()+JI4Jqdqd^k;R)BXGjqUe0`Qw04-MR(@Chu?gNJt1FTAZ-mkL z$Ixjx07yFcDDeAi4P&fxQ-)uq^jfmOf5O@i4(yVK*dH|o=UL~IxO!Wh;b zm%pZREzRD&z)iQ$$&Q!3=6_@h4%G?c1Xd&bQpH$q4;*#xXVp2t?*BMtA0Qn}X?LP9 zFuf?ajFuPa2n0D(Hctq*Xa?b(I$d@;p4p3B0C%l!nH77w}mP64=ZrojL^5 zilYRJXdI?x^yi2`x|(C`sBGP(`084I@|Ct zoH!fkPvnbTSvtj&c%isC^Fiy=xC6xJ9hLLiceq@ht+HQUTurE>N-fPhK~d=1IkMMhl$3s_*E;9ZrF%)wx&61s1~BT9(y4(L8{R)- zYM!|a#L|RghvqW?bK~5+H8Oq1X=E4|vM6nx{n@vviKYZ}@B^Y!qX|{jdvABCua3?X zO|oomd8My@KOx+g(zH7d39`<_5cVM9${@tO!OG2Y7u&ejrh_uQl^X<4IA3_`D&~6B zmuzLq!%d>;=Du;BoeuJjSBay(QS0*nPg^GDAin#0`OX2h3XSVaKHj<-xj!kjB_PFu z#E>`lE^V#dw|iHLKSiNd3y1>1?TI?Y2|H%GYWTx8aW+wg7c`r$z2r}2UTkkKw_LY~ zK66*R``)-*)ExY!t#hxcrXaeTf)u?v&*s7Ibt5;T0N3Y0B=}|qwMA`!qK#|iOYj@i z%I8WivwYMSv2_0*I=r$^u*?{ZVtSV?;ZM&t-3G)EQ|NU~o;kaWeo_RMebibLQG^yi zl=nQ};fbUBc!gaNYo{YVP;$j^Pf@q?8cjAbcDv#W$$C zL5P=_2Y%%q=}4lwbHSz-EjMk|2S?AUszf{Y?hfP5%wqhgi3vz$-OZ;c=0oJb4?P0> zQ_!ABqMC?SwuBBceh1jRF{0~IV| z#jCRL<}kMdg+bTm7cA@MuZLo&FjqFOLNoF18sBuba^^|yi{(Yh!A@O($pywSS;N0P z9J6EYAT(W{m(+XzWSRt;$0A>DbCL=6#=69V%DFpdHMxa}61v;_Cs>`Rb2uOcaGg_a z#{4~LoEL&LenT0d9TRsq_qYj=qOga81WLYPdbgDK4t=ebH}h@vI9|UNm{9rlPsQY- zo1E}EhJ_2xW=Ac&MzNWjYw?@4n}7W36xnOqWnb{CGiPD;T^|%gWC2=4c5*I5!6QD$ z=-!r}G4o7G9k7`3f3RkcU^cUZ>ML37ldv3?Jy@g+RKY2dBO`}}|9Jr>+D_*=*5j{R z^hL}fot@5;LbuNmKO*9KvZ7Q_3bF$CAx`zQ92P0bs7_Bsb!4Nn( zv)LY}KaxBi#pnKbfEx@ZS?Vq0uyS834QmmlaM!<61@22EoJL4NiM(!MjchIMGC3{N z_uu(Gp0%~r2Jb3hJXJJkcJK^kZ*T3qCVNqjE{<%qsl4!a92s|}l!KnOTDM$eQQk-D zW^oxH6lv9_0L^+-eWR2IBq40-u)d17srf#2w;y279@&EDFt+Xfovn_ek<3F<^=D?{3iT+$EBskK3^aGz`bpGy!G%@|B+=~xX7Z; z(9=((%7Q=8GM2)j>YQG`g}holQrmy;NlE@Oo3-;LD3vR^CCau9ZYx&{xC+D8i}zQc zbJ4|A^%?){?fZ7PiRx%Tl)ux$_vj+!A5tf60EothW><7+8mBImqoMI{tplD4#DC<& z*C;He(sXPmc;y0mQv>gk|3;=QDKe}D`;W{pxIs`MUf~0WKSqs8@bdBSwwh@PE2}u41Ovo#+bdCOq=Uz39Ph1#)N^2iaryRCmLuHH;V)58*%$IlaVHu ztKAQrLCsMJ7If5p4e;Ao&JL+gr(m9bxMJIB*2V#7VQZjoDNpbYz-@cAe>E-_MHXr7 z?OUi4>RmMMzk!kLaij)aWSn-qAi#+2of)Sbrb$@kO}uA0rhvGj>@9fXtj%hJxo;MG zPkDKXaJIKzzYNKkerxYOmNn)S(?glU+L5l9Jr1xn(XArSo@S?z;V0g|zuw;)EB2$F zh3(gBX07s%{_Ktnk>9n1Mi|0&BfJI>xobu!c6^@An80~S*AsUd{Pf*1G7RzOfV6Ro z1ziaH5zbIsZn=?71*XSJM%5e%QBB?TlOT(vVCPC+SMoWqBjhPHc!iQqt0-7+VAMFI zJ1_%Nk6F>vP!rPqL$gD^GUpUcaA;)*oS~{^F#_z2d?X-hEDm7ga}fRceNB392JFl) z7fn!O(kyAiWPY*G&W)SU8XAcs6dngP-I+thrj{D-D*?XT5*)xLju)J2z$u4A)W0j` zHne-So|Ej6}HyI4IVamJ!|nj?JL*vHQuU-{>DAd z91-s?VVMUO=+03lr@(`77=%fV8S-e)H!_!27^>7p%1nrSr{W ztBZiLR|NFvOfbre#}bN?x4(jY5HBoEvVFJJoFdm*oFC%)9PbMj%hRb|{!fSqw=>Lj z>)%RCo^LJP8w{5m6yH=z60VSmS^azskew5}XT3i(#mbEcsNETGl2;W>_5&MEWz{FX z$>A($JJ^HUXPZ5@cZtm&<@jMGeBoa?J0xoqpR{j?JdjBDL?Cl_N9&}#(Nv^$!RK<3 zM4i3Sw&TdjnoXB!WP|(A#{e<1>>@lO@byQndqD$CyUeo8$lo!gV#5k#4EyXFR?K0M z2iBEd)6!tP>g?`X2#-2taU#06^qR=VFB|xwkd3Wm?Hfp*{gGJ5p1^*J<@E>2x167I z@QQEFZx_Ejw^-!cup)S;5_H5z<$L7}>q#PFH-M#Qk>j#G0&Hz?aDg+PlPp}g0L8ma z`?P)Y8d4FWZbK|8-Zl2z&F_kwRBew`NVU&EiFfnW;@jw66zAo!CcchFyC(ZDt!$() z8(Uk;wi_V9IW^K}6^>=pik;XPf6z5R(TCg+N7N;3iS{*OGGRI=nUEfesvoSB@Zi~o~h#BLyKS^x; zhQeE<_iG>O#r^)C$X)nWlh?rquak7zyz7{U;=8l7Pg9sRdjqcBI%$U8OH=eA4;455 zj#ECqBg+13@*U&8vFnR_?C80MrzVDnC$Tq*A}btu9BY2vv4J1^vWB`>0a+Np$bm<~ z$=R8IE*eTQjNnm|u!C4m_u$Qx$OLLTn9(qz8+Um2#-v0DqI@${x(K>o6rIWJzc!xsyXW> zn%&kvWlS5G3!u4}3i4uCA`2>aMcw)rJ4x@-tvM!FOwA1ZmQVpN2+@8QWqZb;+hf(D za!TxaK*Vvef?PRBWVBc495-q3_^8UEcOru1;-I_St1VNduw&8bwu-k5i8(ar`i zOAOeZ15;vcG!9k%AZ1TYW`Bg7>~#q7z~62iODGqAz@snb+V`OVXqr)w{lS|aC7cl@ zOkt9AI6&Wn6S$?^GUf*CM!cr_GSQ6~!C}Sa$<)hGR|m;aG-ZalRx z8r~g6%ID5(zl;g$1rrB30zB<%$D*w(P--Z;^<0$@{wbJ*Wc>Po4Q6ywNMhm9_2e5Z z_ZIvUj~*E+8U8Xzv_9>}rw3s;7j1IFV-*kDWGs{CF;wK-nWqbv^uH!l-=uU4C%~R6 zy&!;~9Kay(EMWav-+#5?A@kFG!*Dab`xS{Huc@(q*`%~SzL}wR%!;gM@#=85KBs36|pW%%VTBW0?AjX>dnn8(58#j<6PX*R&~ z21c~fC#*a<7S|=8$edd{Ln_1$ZrGE-L0b-e8s2pzU02H{fiGp4Pcp{=qL5t%t_F`E zR`OWIJg+V6l-b#2xZ8d)ZgqnRb_K_oP_i6Odu=Fy)odZe5|+{uun%XOJDRKkE#$Z@ zu2zN~g!Xc@JKRBeh`66=@^l_$onHU8ibwKEntMD3g!0Y8O^5~6A>u$u?QQS5X3gKb z_9S!%icKey4E;ArL9|8$wK!Yw;i%YD5$=E90CKV5Sm8glSV4X7m~=V(yQqL+;G&d^ z#6MQ%uP)%)Ak%}VSckYDSVKo+ov6*&bh(;AT?UoxW$ z(yjmwyL8&IV2BhLDP#%cZ0=viyRmu?r^(p)Gp8PQWhaqw*TjBNs&H+Il^VlZ{CawP zv^>i%&W)xMDHbD|{cj0_O5C*G&P~as5*Sdk_Eg|_Ip`Td ztx<4WozG?Wnrk1$Lj$nO@*B*^3%8FNhG!luK5Tw~4?!Av7!?Y?hzO$q_X5K$U)mmE zZ=?;E+8i!puFtym%S+a3b9MHId5oC*>qD*1SNWs!jItGC$@v|XJ#6MExI_ca;iurI z`>%vo6DjPYP798oAG-P?4g`XrO)s$`=Wd zOI6PR4za!6+B^RoscY${4AXAz5Fv)Aw3x7)d2=Uw(|7r}4cgIkwYKpVbE~B1+G0}! zXWD;r%O81m*DvIj2%P+>NY()=0O`HuQw7kPM@}><`qa&>_b}$)s}C^=rE&AYf=rG> zdvtdS%Ut;dRWajfBTb4|dNpnTylHq3=);_Au3)Hur!M%+vG}T2R!~e34-jOU6 zjkzFZm>JQ|gtad-#NOb7oQa{CB$eJrq9SVQrp7BdW&KD0Rr)8XCE_c0K<5rDU z%xfN$>E+|ZP7iTKz!Pf7boHN?cA)IXvneWlbYZd6htl*JQAp6k31ut1+>Wt;kqcD> zi=)y64$8a{QlrbfdmXLIl0ReQ(aEqM8O`yJ+&9ZA|8R|@?8>OJSu4WP!KIdEY0*i< zjCG%j6M5muHU0ro7!F1Rkwh)3|0hV1T8LojwM%5?ZPu&Wn@2GWYwtq~0qy*)(qYD5 zlo0>jwGXLLH}<1H=5GZV(d zjf~q=v zRWl7+T^ocME*e2@Y?{0`0aVAN*%;AraHDM}%$@9Tq##T@;quoG72H1Ydh!@fu_8M~oV?}!mmdW|nD3sOcc zN<7ks^Ye0WmWZa5nG2WDM75ixVC_z(jXd`)`sKDW=e8GV7fKD6IaIa91ryNW4gY2a z;i`S1As%I_UyzacM=S*^J62HNxj@_-)*&Ktxs%Pz<|okr_%|Uz9Md{MYWP?Lgk`B{ zVdq1xHR#>pW=F#9orf(jxiE5#x8^d81WrCGe?Y0_cq+AykE$ee!(x9Anz9I$!e*F( zlwZhN^lA-SSJX_BJusoeVzpL0jd|x7ZpcvXdmL1&T&z1$F$uMk~_*mw$;|M@y zVP_j6t_`OH*rziNXz^X|{}n2?vqBKo>)w`ElrD#3T)y8 z6}MlqW4T5L-vk93-$L_wu~|WO>oD@kk^6fni6Oet+ig3nY+L^4E|X{K2YHA(G8-6q z4m6#-fah&oCqC}0Nn}wo$kjt4V{+?yvAvWA=eFC}UIiTKu72>X)MhplFcrnH8Nc^n z7>j%p-1FW@C;UX7G9gm>ksW`ar+%^gl7zbF3aOUi7~>e#C`GVhcU6QZ@n*`*lYtFc z39dsh-D4~gi~iqvm#+2vyYXmPcvR1T!_t+{v{NFihklzc=CEade@O%>>YM;>ciTfNMDfg#kdBQ>C_Z zxpwtCqh9@b(GN%lZfivEQW=qA4HRQg1MfHpV3)Fdw;3q=V`u)Q6--V|>Ouss86AzKB|7?8^KZc|;F*0t8!bnA&&M-?yO;COp{1 zd8K*(+{oExPE<}267|S_oq#>zxw(F%h4`1CC3w$h)?(VcHp$JBTZv#-Tx$q+Dx~Vs zu>|s{<`5XkcAQSpQ3Pglja9xtYECg!4FuGrSxOIAq5ObHoqB8)ssHxM=Uy?^*%Sjp zxcm|v3$90Db>QjaJ87HKIhX$VZFBOedN;3nu^36)mx+=AjV>hkDF`M3V{x&hX`oZi zXx;7gy^sy56C;&J+VMBc3_j0e>mdjoIMjEn4DNt&OG@81?a`8$V?pJ_mhm0RuN!?d zsaP*lScL`Hww?F`;_5AAwl4kni=cdC_x8Hv!qUzf_PXV21_#hM%2a#1mz*=Z^SS#8 zy@FuC;T7x-KHK3D*MIE20MGU95tYSligOf`CnsgxP9HjlGmfq!er^% zFwORO2qK(jVYa=(Wb? znhYaY{1*LzqupVe`5aO7IY-_T{`yA3keLK{r1PZolm7ERW2rA(|M4S#^dLwu@?(XW z%Bb$zc##R!V-+KO9rhlN2?~-D_HbD+@`rCQ3Z*6u^Lu_NaxCJc&jN989JiDB`K_Hb z;V)vaaFAtGR7SuEp|AamsjBx^{ICoy>gEs>llG4E=5E|Cp*--y87GDkpyok<;bCfu zv<6df5p2H;|KM63cQD{sXs5(>^k_uoG!;mU*U8-x^x!!z?#iP`4TsbeW|E|j35(2UsOPBnkte>c_ejIeUNsWd z5-_TW78q-}-N_mU5$P}zl~aq|gGqqc4E?JS<*OO+72@%GRffD);AaC|Dz;k1w=zUr zppM~K@>1R#+DD_Ljs+wfmNBkk(HYxXeE;$BhZ5{YAL6e9chtcZV3+Vc^7mH@vbgD} zUw_))i!tZJa!A31TXPXuTgK)^`pProTIJ6XOm6&%bdoBh5`jf&73Bem3-K5uAcIr>W$q@IYA&Nq_@ z{Qy`gp=nn?x~7ABoDON1SFd+isH53)xA?AnF)=|Q!`p|9h@u%RzgPKn-Z<-*43) zIJ~;!Bp{dY*xZCFKyS`gztM4DWWzwD7Er&@Dt$e*Gm!E?xP3)KM_Bbi^{Jkfr{0R^A=oWwMm)0^cq za{n6`H<%UCoK2bGltE2&mPoX|{?~gW)BI4CGse2IrNAH@Nv*xb2B!p!G=yHJ2_nH; zu4#buw)#aQr6^LaQjOC$sgxXenIJ<~Z5xbgLUZ+<`s9Ww^H-7vhrggnvL?I-m3b})Jy#CzB)~XKgQ=Jz+ozyKH{rG{excwF^he4o1j}YS9#(G`p zbN7jPBI8NB%p5 z3+6Ogy@$|0Yucf(T`e5{6jGbJ2(*pr=G>53Uj=d2uX`XXY5kiZAkOF|^et zx)CQ!`oqOatc0E!l=aDeaiqyc-e)-Gaf;h>sxg#W%+37%?gAYt0x?hN8yZ_W3;ShG z5~o4ENgOAHB+0Uy`HaN*iud^Way6Wu4rO9Yz*dSqwPRH7BBw0^2hk-*z3;FM`myYY z+@G{uD)!7@1RCDjD}hb+=H*MQ-1cE?$|(0Zw|ts|lvirC6?(;O#b3&ZSGbkFtd%ni zEZq%$D}Nis$Mc)6TZi|pH@HT`10pr#evwK`#O(Jx;^#Y;xFtdFDwh--rD6f>bXq)G z(W9MbpI`OJmyR~VuhUm8ysvT%DnN(>)mqJeNWHv+&1H~c3(?i)Y@mf#xcqrz<^G9#MdvlUiis-Na^ z_Mx}Gk8TzEHYcoi!n@1RxPv3Xz6hSL)F(DqcQX_cuHl#WcAcaTBz1N?l^|aKrC0Dqn4Eh#>hPrxBPWt&?`T4mNDv<)NVxcP}r+q4HzmqGo1r{`#0z zSn<~>G5cFL5AcJgkQ~hxW}-wb;0U|1d@SifbLwE?4w4|ueFvIkUF*>M_&t4g=U6G2 z8xI>MlDCsp~q*zQt4A)+R2Fav`ea|AofFM0D6L`ugFopy>EB&B)4i+tj8Ip`d zphox(2g@F8jJ<#J_~Dj|XfeDyFz!XC(K$1mnqE zNmmn2-^PRPA(#rNN~j*stelKhbr^9MgbWrhgk|c#Zrd#A>ZZTKAug|Duhm;gor|wL z7v|S^^&@d9!sYvGZX2d`woY{}`mD+s;4L8Q@jF9q5342t@Y$HRi_Vud-UJ&uou|7o z-l&N^+$M*$ zH2LE9uJbioyjH)%4vNslZvL+q;6?UVK-`EINv}%JQA=_9L=ZfLq=b^IdN~6B4VI+b zh90W5*Oj=wm`Y2}n*HJ^;5Npsz>*CQ9vTs97V0SHL7VtX>UCS+JD0j8kXOOo^5%-N zlcr^TN%5rh)k2b)?SsX3o~+&l-im^IMywOdaV`@sT$GK(Z5f_L*7Hmq<}=ypjn4jp zLNA_bajh178hp&boPZ5u1wNhceL!nF84uk214F}lzL9ptkyhf8ahS=nIpZ;382IA2 zrTb5E-9*JK)=En(u@}}#SCy_n#hLnwp!>&b)gWKZj2Y^-N}$rb3KKf~+33gcl=GGUgq$ zS3aRdIv7+gqL#dVd+r!(SvB!;fe^QNkfhD%hut}&;*v)77@`^@6y5^iWiWrxjYfu{ zE=}Mmzwo#LU3K^iKjIBPqo{6o2gc@`vm-;gg6Vv{Z|{qm-Vt3UgmBK9J)No{wvW|q z&4jK_iYjDnt@?D;h8mZRV1Z=^##LWlg7ut$_x00r_E7=&Dj1cBsf?A2O(_rdonsKp zgwJB3E`$iLJt3bYEgy1~d3jGboEn&t+F=_uA9GUE1c#A2F#X6{mV)=TLd~kQINSMv zV&X!<7ayRI1m1(cY{g7_t;aa%&HLP?X4Kk)34gj19i~Z;XnPCowM|I5e(vrqYh?NY zTsFxt;B)E4H^_~4v-)R#hAv~xvpOL2`SfqLY#ATOXh%_A1rdsovDhe-N%Hq(D?ejL zlJ&`TGupI(M8=VfFt8cohygF~s?Y~+?_(YR7vh1!;iieW!u<|+a#Nv9DZHw2<6S3K zr)nl_vWHy{K&kWjx1JPH4X7F0s;6R^M3Rt1;3G zO$R>%2NxpQGOb?$-Iih+U5c$nQ#rBI({rAb*)5MY98VTbxN$Y%v zzGJ@<#bsy%F9tXG++x#5-k7fX=%wCV-f6~dvNgyTX{P77QeYtFC>C4E+ZD_=oXbKu zrl96S{RXH?EX{Ayh(*+(L5ii=G&L6)rcte7YH0OV_L`$I#U`HRHAF_H3h`8|IwPh_l zJ=(0=sS3J1gX@Dmr9dxrAdVQ{6pJ5^57P>3GL3yFTfEzfe=z&ccYnSZUb$}-ZnXNk zK6~&;{`CVx?lMO?Fk>OVjhEM%A5Zd9T(zSz!zAa8T1ts24PSL18UW(QMiM=g5j`|W`naitu?(a6wpmlUdag+CI{x)DaBI4liR?qPX?lDlWp zpNA+`qP^ehEarWW86bK>usZm1+q^A$q06QDt961ZKi^Ig%w%Q^xe}=0=rvaiIXYy} zDf-7~f)qSQARI$e_P^yEBgIH(5WUE?L+e;HA?13EHj;a1de4c*uJ+P~Old$MhCYnG zvn(9g76!a(CL$|Vg_snd|0>_vwdQALWcsLM+T(dMbWB(OTs23jRUh=h5i}*#C5LA- zv`&82O=VK}*MiB!6qkC{o7*YF%bO_6wv>MJQfTwFv$2nuS&5)T$SJoQ9sFU8wG7iX zL}X4s!45cXNBGN>T7VbMN$E_k?pq)iwLtfo5dMk<0A2L&=5{NYRs@>=4`FW|6=l@6 zkJ8|PC=F7Ibcb}8bhos0=g=*P(h?5c-JOHrC?Jg>4Ba6NNOzqF-uL^?IqSF9Ie)Ph zi(#I<_r34?y07cn`w_<7+E~R6?>!0s5B6gHMEfQN-{HDxXyB7SnizJ#lhzLXi+_8P zmo}zr4^Zj*hs$j2yxClerMc^e9DcPIlXUX+FF{Cw>~!2wNze>&XFN09)@{ewM3M}H zl9*0ik`iLKF#PrNAH+=e0`sSkmyL`!P(DWSvT{wEACR;dciw}Z_(*m&OW*3OB*)Zx zebkK)zB(x@!0f?jYk5;vFVK@VBJPH27--y{BA=FNdX1*QEQ6mgG{Q8#I$(AYRH1Ka zlVLt1A$>nzx*f-ntmSAKPh<$6aq2M@HHVF z`CxsTf%uQ2{VvxQygJsr+Y4AF<@l9V3F3Z~6RD2%kI1?q3Fbz*kHw-Rp6z`^9kzPJ zAlK?@qem%2;FkasWn2rSC>gL=;CgKY; z6-(_1368La3nR&h9}3x4fb^odF)w1IvOwY))X5ADXVUAr@|~)ZtvT79^f&%?Omd44 zU_z*75ex1h6P{u5YG!!f=xSm}h;l>VhPoCzi%=qz*ytbW-yiAz7P>}q72L8B9-*U1 z2pNM_;)YtUFzBpbhpSXD$AL~V(sr0_1M?P8PxfyHIumr*CycdvjL?lKAB;YCJuukD92F~@r+d~py#5Cc=U;`7wS2nxKnL`;zq*7#x zbzwrVKk2z5V|UE}Oc6&XmCXQl#G$KWJ+zMJ@}z_*8VosdUsN|A^+Hcq!+$4(NA&&& zwT;)cT2R50&R-F2lvJ;clN~f7=Zqny{!LB+)t{#v3P2XqZWx*s#1YBe!*mMO`wDJ# zU9ziJug%`E(!RbODe8Jac?>IdI%h@4Qfe&ZQ}c4a!{fl_?TlMU(i&89`e6r*10Icn z=b&`o_ig4E1V&aK0Z=ZBh#;}&%c^Fy2NM7`D1dMIz5VbNJ-rn5Z4t${X0v?gu9e9D zHiy&^dOJa@^%&FGLi&>v9}(_1Hws7Mov~liSll8RwRFb#s`%K-S%Gk241fxcGNCXy z_yt9B%;o#P!iTejIBe&>%*&-|?dD4s{<+aYxfhor*n66Vfk$YyHdRG2_8Zqef{_A# zh!PLJP|1^>s3>&CaQ+mrzI2;mJQ{&G#a&LA1quEJ7G3F09z*HiDOTUh##};gw`1A^ zPgdI>>DTrH@7c)Sd`ft&EG-~Av1RyoSx})H{K^~{DbHhfd0>&u5~9N!BTb<27nJO6@ha_~ zH~X#A6i8H?@>`J<8YxEO*x~V)ibrg6;t+;z`-mSZ(a%bf&NUNFez(0^o~EGYkVSZA z3e7(&q=@8!nso97HsP|V9@&@~+A;NQy;G{-+WQZ7+b#m2^z4{2<-nn*>0e}q+x`xT zR(jgw4&l4xp7z1q??#X`>Lf8Kn{eJ%k#*4LOUZ1eMzw!G+-}QI#ckQVnBFK|W!_V* zz!#pX#?hXn-{XXx(D$Y@`WV zR@_mlBC?gsB)d~iuy3X~T;5)EcDu+3a%_+7sZurUoMLZ$@X<(~*_QUYbOA@V&y!aq zm<~Nt7}?8hYG7CXTY~p3gXyF&WDkp1HR{LvSAwsIldZDuhRX3({~9G%{Jo4c40E@n z%`+Vxk56cjxuklThG=@SVGXzPaZ+a=ERj;{<-}V&5`H4Cqx0DiK%SLP73hX{W7VIC zC|u2yk;%G}j%yE%2B`Ax7n!}-UbXd(LK~o1@!p<{u&1u~H(NpT_10%1Vr==WPF@9P z=2)9lP0*WMu}og$d*hY?sf(F0I4gW;nNFk%O@c#Q*|yCy(`SwZ(4pnEZM})3x|#xtvFq!4+62qDHhaa^ zTe7P!(49$E^mrxPU~BqGp^-#EM&yYOoiSF*rvHuAJloFf0vKB&Rlq!!NKV+6mxqD> zAg$dF!tJ%2s7!>vtYGmoZ8U6x>zi%<6oD-{pOncTCs(Nn;4K*^ZPS33!gC&D>dUuJ>=su(SR z-qg42xZj|hyCJ(q7?(%=EII;!BF*4b_@e(h0psc44B*puw6A?+efE$Pe$L54m=R zUhxLnAN>c0#lM@UV*7upF9Dc5X>C%R-KpOT+6tdPL~B;U3P*JFwe|EkG$x_`yGBoz zZO{06+LyzyMSO>~jEzO#>6o6ZPMatQ(xJ^)IuD&CVY9d9GG}1!mJO9423tCCzWFCQ zp1zLE{#AsarIW=>LGbWr*e>zWa7E3xfr5B3MU@C`Ft`I?vBLLom~c61H|m84 zp39NubIO>XhbTdEjBu$$Qt@8Dwd6U4*7+V=FZ!%K9bJo|5KOGE=N?^KPw%=rt?4f= z7UQrV{P-cn+oNr4VoIV@)m$OBY55Z@=E%n>kwDqHaEAi@5yhuj!qS8Rh5)}Y}Efrt1jyr8c&{aiohWx~@2d*osPGKZsV z6Fxv?p?v@13~dQ7ZzKZKn%=Wj&+UEE##5aUB-Oa;b>@d~BL5Fr6~lFDAO64tDfg9^ z|72q_Z}0A+u-XRld9+@gJ%%|sbowsiOJ**_$!1i8 z$6?{LFwoN-9rt5(z^c9C;WJVH`CoGB1_H0Zhg&o}u<6(WWi+pmMR4)9ub=7@$e~7@fwpb7qyGgh2@8vhin^F&E*bd_eS`quI{)=N zk5%1QA0nF|bv^+Y&P)6%xJPG{g|gm%*e9MWBB?9QzZ#SA_m&mi<9Dsa{++(x@2(Iv zHn*t})iqoBC0p$YrQA|ZCTj5;6Z;nI>j_G;Iq{(v*V$}96(Vy@D?XSxa<4w*o`UAG z>a7qHIaetEH8<(yE`I$u@ktZ!u(_SA8kQ|$`qgMC!uNho76JQ0-`p&ut`F)znY6x- z1wmbU3PNj3}zMSjse8L>ZMOpXQD=h6fX6SmKyIkK+?Kcre z3$cit(nA&(#o)2O0=Va|N=_qu5hXoN;=IoObJE5z(zA7aYESadT`)O5jE zI?FhEX6QT11OKwjoV+i$bHd1B(Zjqh7LG|#xm*v(HLk zpEBGdV0xPCANa)mSrX6oIs49*rKPlhS!(~6m5e*p!=-!J*N#tT9sP#_g4f2f?gYBB zD7(~0s@emHSFE~@4>afczI9>FdV!ywdC{xs`L^7X2@mF}SI<>@dRJe$;ag4n1x0rn6)1^yJ#O zXM6Yl+7Ft&p2p$Fv);havSB=;+1^90b~&2St`2Brn)H*fttbf9!hZ{Ac>9KO`;ryIpvp5>c%a7;;rfH(9+1b3B*~KBGqBD*N z+nwZqA=FU4iG;G3;6FKi*3N0c{#J{z0vyAH25@u8I69FKfGtc7bp*13FT8p(1<1B! zD>jT@Tsz}V-lTqNcWvu#bq!<6?&U`P`k1agZGlee^Pg>vl~z^w4~F;y;hekTa_W14 zna9<6i_*%(a<<+e#q=D)zqJhDvv$BDJO|T5 z55j~D!ZVe8`8b~?+`;ZOdh&+ro71{Ek<a}MW5QoOtU_6pw%Auf|Kew)Abeu0pGcI|?BSIv2 z4x%Jp140Y9=V1MT4U+3i=XKB(w{`~V=yP0I;65VKH9S1JJpOWSm$#jFK9Uj8e^#y9 zWL@m`oA2E&sScbtEYdKc z1TRQ*Vd~)O6n$G-v;O}7!ckWUUuadg`acDyeCC${n5k=4l|c3M7pUfca&rR+Kn_W=A`L(|ckpnrz-{X~@;4`f zm-b%X-E}jscfuPEk~~$b$A2JYl(^o9*@mzY@j)0Ki1LocDbByL6~uvwdm3 z(+nqPhHR^qt9?;1>Ge=*6CL|W#O5mKngXdC>V6f(U>3t=EtgW^>B`-|MH#8V9zzVN z!?Flj;C`6azl^aU2TJpWJGBEyIkQ^>UhtJY<-2hybQlvz(v0&UpHXj0Ti%%O{jP*g z{*!9mQq7f;CdtdsB<3&{aDMAgW60q#L;t@EXDHCpjc6)9CZh`t+)X1cuxW%xeeAqj@sj~6u)q|n@+<=5VBUr_$nSy&% zcR#2P8FzpHYf#&_wOLB!T3!gMjj6zN96AwF0g$bW75YeDTG`QYl~TB^zx&K&4_oK~ z>TnPR!zcC6?m`FbwG!dN_F+fw_$?=N z)H6+i3O?GWCViDgMVN(}l{zc*HM-A{wR^!!gvyxKs6WuCw2J(E$hs*I+Set=L(Ryt4Lo#+z0 zUQm|oBkGOf2CXa)sVqtxl;FnVR)USEoaWwI1m6@;eMV3*GSFnAWTN0m`sz@AEnpSS zO

;!F#VOrRJ5=5u%5JJW?vAFmz;*h|MQr#^tFf`%+v+f0M(8jl{{3o zn$sHqoIYf8sZ#hVwy_9zb*G5TzuxSARk##Toe4E0`JLQd@A?Hh=G0N$eD}tR8xevSEdb9hv~koJ|-yW`VdG z^=6*zl_bpwS%h-uqWh4USG8{IR%$1fJkU?K zLxS+x1|fnf_-kz+`EYK{OamT;>;vHvd86PbLkTo*PtVIMbbsskwIbZ}7|nAT8+OXu z`DiO{fAysrC8vd+K8ql@vS@~I^)>?P{T9}i%M2_OkZuPC_0v|zD`;4&p9~NI5dSf} zQjsh88^G!>D9xSf!<%LnJIiX^>qRTDe}`umDdPChr@W6^La*0NtI{z=ql%BPOwVZx zhwQv8iSf`*dm4lMLblX7tfO-}bT~BtzYI=*r>lf_eW8=e+l!-|M!XBrPBkJ=_N!TY zcp?q{}7hd8ger3clP6 z>pu!xY9m{VlsDo)E`R@OX5wL^p{mhV2O~|L_hCw>8B3dD()UQ=p9^I(DL<5F!eoGC ze3!F|q`>vgsQ1j0fwd)ux2^tNNoRoF=+4mpGI>O)#srC%L0f;)`q zt>64jkRaGX^#~bFFxYFb!j5({)a6Nd5QjHD>C1oHeB3zznpjal2#Lbkr?2#*pZT z2yN1g_e>HgR9|N_&Cz?McA2H6r>VgH6ir_*{|2jdd_UkF8!1OdXhuc($=B000m*Ph zoz1V1;|X~ql25L3D(WW3!fF;GB{7;-Sxa`L78vw;2CG>75Lkcrtw|rj23`bbIb_;7 ztC+*lDxQme3tabZ>*e^Ug>dE6Oml2+fWc`(&7Ohr69&(8#z`6x9W*VMXP>M1G5^O4 zFd%+AQpNyt>r`JRHu^@IK|2Zvfi~P9>`PD^Ld{X)%QQuyF-sdqiW~p|N?V;F-{JoN0w_5?4_mpP>HkqDw^wmt8r{{NoQ85h z-p+bibCu~;v*GWrYg7KB(N>y39JN}z=qiMpeWWDkbpvYeJ!7)-+yJC=(apl=gok2G zmdafNUL+PMpr=*pj3cRr3(E*_6DM-`0)a#I0DDB>d-jx8ogf575m$~LqEYV?5GDPr zyg^vDszm~?m%L-5exBNN7p-!aTPH%dy~R4Y9wY`rRiZpi;Nn<(^*K$MVc3(S>ZMDv z36kI8L8d7)bqN&9k3q|Z4`^$@$K`Ey+TZ`%~(Tv1%g^MeSG7h$PRXrD0i@1V!6B&q)gM8 zJaIB;%TC#)^vHJ^;5s>bNr`sQ@=K%OEH+7i4K6(YJ)|H+9O$A6sSIZvn|2(0XdyElwI0MplxOY1CC}mX?t@S%g)z@W9uK}jZ7u< ziLnQCg0|krkWD|j`g|3Wxp;|Iees0w;jt+Eli}+SlRoZ<2QZylU8Z=Uftw$}g&U(` zj>Iv?o~`t?)(gNu{|rZ{$mJjQ{Ws-v4)zt~IuS6WBz9kTv0+)GGjA#|frd(5`&QWvd$8JY6MK={fGo8}5(*18ofQ;K+ zgvrnq;jUCE6|@3wl{bRWyy*$!oZt(QrbS%8hOsO{4|vts>-iu+U7 zvZYH)X~2gPiVY;llu-H+67x7IE86N<8f~B=n9 z_>W&URo-Y6brb!}QvH-`eAQd5mlSBPn6S>93F}(m8PtH{ENP}wS9=b$PbH8#W%CEl z2)!DxRZf)%EE5=JmP89*TRYclm{qYSn%YwLF)NI z<226=6Q3ig904vSDo|HNt%2q1*QzqiEQmpQn`BbuA+WuKU}NMcmo7kcFouBVnt$7R z2#mMekAkq2Dn1T$K&DLb<-<8i}%jeCQERtx*WfR&d28h~KEjeu>V1jPohl$FBk05MO&OhZM! z`cUXA69vHGq*Cw$yebaURznVHI*!~5_ZyF-sl0wAjM=gE?Abg~mNe(laZi6;&zCJg zRPp54un(XPld}!GYI7Gko0zNrYRoa52fyvnm6l_E`7n#pZ27)TjP!b zpoB4IiN{)$6Y0&K)Y7&qKJzwaC*0UsrPcWo&aPGT2n|Oj2#MWDE0)KHJRY(Wms63V zFU?rEQleW(3EMxEnkdeJLDJ%bhZG=I3bb`C>7?7t1!!+=KGIX8?k2VM<4Px;2Zwdx z6o$42n(rA1bKt|JWqjmQZV5-4`S*nZpvf1(gUUu>5*X!pBup(H@qd6s5_HTnMb0G3 zFX1Ky18GgK1m_>BelY;?O_6rqziJyF6nH2;#?}BO$z#&X715)6M!Ht_kigT{kDVgv zyJm)dgE{~Y3Y2wwQm9K(Uk^uZwmC}FV$WcPNYxg7V4)nEtr=&a{;K9WON;&L*T#S` zN@gPSCP_Cd5Y$?GcJ)t7G0F>`P$Js3qYg6gH+o$=7q`0S(?NCL+pTRV*bW+(6aXGU zPW!R}tIv2)3i#{&u8mc*M(g=M5_2gPb*f|G93$=m$w;(x z0qRuLfR97=Ic$ddmeQ*#fQ6`CW4RbGx{m*MZlp%#+AQ=S-_yKoTvh=a4wiRM7@?s< z=QcoWkxpP{;i_0i=Jm(!jFlo!O=bUbI9s3RpUU3I0vw{WMXX4w=+$u%>wY;}1LXhH zSocOX3zq}!$*q9u^E~_w&t+q?P%Q61XdAp;$2@H=SKJF-t*QJ(s-;gAJ}g}Vv*Djc z$zrOzF+B@9bTmAXHZmLwl!w^txwUv$c*f&A92!2EqTzw+PI;y zb>c`HN8O&0y0gkVE{6!J9gGXgS_n+WpJ!4y6v;!AX-a4qIIZ{dL4LLFowhdv|2Gph zGcQH=p8h8n3LAd55z;b({bqcZzHZRv0d#wDfZ0ruw%SE_TbF$_O0?V&FEkP912W55 zD%C?)CIjl1K-*`HZc>G3FDOwdW~`%+`9rn{snD`n+hT_4hJMr8Ao27u9tZlPTv0iR|KGHz;{5vrnyu#oc#4i6 z()Knii8-Ku5J?p;gBLyB63gt~B>mwr$r8AQe^Kl(7koL1p*%N^Bc4XLMK+-qedC+* zROM_0chBI+&3_7vY;FhsHQP|n&Xd!p^WQcZU>t{oN>XZ?omcKtAUrBs^Km<5@C0p{$8at9 z;BK&Tpb8vFf*A3|HmoSL^c}6^nS9c+?_bLbjDrO=!wW(_D45>wmmS4mjiQVeYl;ZJ z*SmYqA`h*T_Sg0EIqfK%YxrvDKQ#il!nR^L8iH+DXaV1@Z`u#3mxY`qe6+_`fzdd25)AIi#%bwKy0*OAKR-@QeiRGd%L8ma0X9`^y5Tx*#jV3MI zJYm6+t2<{a?gP4+BhBlD+MiaeurIWigbCU!ba+!ygOodCe~W$I17>2#lJ7IZsqD#n z?hij*q%O46YOy9=8i~09MY$Qo+s)HYtM%wrQEf5Hgp8@BFy226Q0kt%C-g&#dLDPq z)C5gV^Y=9H0p4qp>=wt|fUYaMI?E^pCYX0ZJ;20ZdY{SMzv-#e1Tf{5=gkL4%ijZN z2euB%r`KMF{&TS&VgPDEzc0@V&rc0mqn`ty1XKEEwA=hTbMhRQrkHQa$6KAqV@=rd z-cUB2vEIuPTqQ6wp!T4!!{VDASK1$sW#kP&^E+D$uSo3dJ;QTUXri?t+w$s=U!`z(G{&g%W`WC>I0TN_tGt96XyfV1yXICQ?`Q8U+ zrPmV(3L6=H9fD*QsK8x}A0^&%6OUw$k&1*8=qGa!a6>kiAl*YtGK`~43~*&p^tdC* zbW0CpS%pURGl{haB6aBOTQP|>|6k{R$v1mL4+OGNS`^rf;?!r^Jls8b71xFFO@%{Gwxd3$2_GuIp3XKKqR%Z1 zE2Vshjbp0>C=Sn8;?i@WQ+Gj#c&o5hicf>J#q@WC##ICkfaD`~gH;>}cth*1+2xq$ zS00g!G)I(cnI0y5$Uy{L_pD7N9vFm=^Mlt5B=?C^H$?-bKr4e3JNZdtF0^tx`(~s3 zO|yWA1rM1>F7uZZBV3~#Ukg9b0-?W`?Wkh$T*I4%Y@#M0l!!WvDqxEN?z%W3pAw~7 znV{O__G(E^LF;$vj>%0K94j_8!B0Mu`O)YC-%-gR^$6Nwpde7GoZTFrY3 zwG{`346cQH6!!s{u)lnYk2P7N+jjgIjLQ&M<@DB|0yma1Hm=rdkk~|@TPHnG#Sbaf zpu}Hro2`W*aS{JTGQR~8H}ux2!*2AQ^`1f7Yp7;C9)!UzP+6F!5sBqJf#46X?Bm{t zBSSB{jodza9@W@;SPSd=S0DdM?s-9~J>s*>9opah*6fRr$V;YdB$TT7SP9J)=}_Q~ zvm?y=dcG`xe2HTek42yPk=+7#Da@>;B83P1LTmgFT?U7QL`U2%0{_#j*fhtxfPk}E z$~oGA;nz?l#*>EyJb!Yq&H;MhKx09%apR@6Q+QJ|d|P*)=ugm+{fWFH)tb}gLo^<$ zAFwp5YiE^K$mV5%DB1oG#0v26MCOHOmMO&to%-s|JCT1dDs81$fRhbad%Bmcu+~e- zy35zMW`G~?&r?@qPE^v&OZRIXJ$5O@6b}dK`c_kdHw#fy2xDe|;wXeY;v6|`y2NGa zaBK_7HlDf2XK+Lr4Xa8@{UC6xPjs%2KcauO71Z4*#I{7&J^9b8`Y>O|!t2Aosrey! zJ+g)N;meQoaVTE0wi-SL<4*crQu-ven}<7EmRilnoSj;exw0PgzOJFk5TjU9uliBejlcgK>HWl3$95| z7}{H6RngNXWf(AithS=``9DveM&OxHEQY#AShJj@F4n$RqpAQ3=dfF5jcWn3G}8*+ za=fs|Q1n;CKNaM+Eeo5_vd=$|x>LqamS?ZiBQTxD+Qc7(PJn2u!F@5r)~byXR}lal`owra!j32Zd)R?eLnb^L z9{kyy=f#QP8S=+26d0WF58H~{BWzrJz5-7EvPh9B$=JNJ`1q*G0BU7m7uR@2qX>GQ ztlSw{Ak?mQ?KIN!P?K8&K=S1WiC7LjMeitIM6W22-=qXTh@Z&^Ea9Irg0_}!mD$l- zK0TjyzYM?wdN4v}bqQPJ&!?%_-n?xhj(gs1uXtiE!{m)}q*`^7^HwJPT=&p?C->(u zfZshsjw@jp{SXrN8dfGd{F6m*+pc*qH$J=udGvw2y;bcYweaiNcp9Ed5~*v&v24r{ z=LCWP)B7{I=jwi@-J~jr_gElmXDGgzt%epsJ*9B5l->5;=>#TS|s1kpr z+ix}sV*d>rGq~jAa*@f6C1HZZ=H|`zg30}CtAn!%aVr%j&r}w=f+q$O?IAG?^F{# zEH5jYk&{t9p&>;rzmg9Oyk$3Cm(VX+b4P`d`jN+^Tr}LJ4tFnUUy{SLzA*+Lvt@M2 zy_vmhdlTU-vP$K%gX~^B7=$zh>RVY@#$+8$|+z$W=PQMVExin(3-LC$?y zA##u)8k4vB-8V(ge@ZFQ?CrMshTOXnY?KC@xRiq0176gt$xm54q9c<9Wu*t^SL@9$ z6bBDdk_CH;iguE5h`jscZkE8Yo&mNN#&k?XTOmq%h}tu+MUoZrQzCag=2h|CUCt zmQKTIJt&(=ZYPkt(3J}pXUk^J=;#u3S%k94u4n#^l1k%U)vKp({?SVv5 z!N0wBM`8#1H#Q`^!|l&ZzrW(k{m z-?U#8dl^pWf24d%s4)1a3HY`cu5B8ap0-anLI4;FrxCza`Y=c<5g^V3@BDM;_Uy<5JH@60&zo|j zzKmGRoh~f|Uv*SD3aEa#rC4a;o!+Qlaak=gV(ci>{?#YE&?ofU?OzZSvqAYhklwKR z>RoZosLQF`Xno$Dd^41`frEo^Z+WmBN2BjyI_BwN9o^Zb#g*@gRwTk9noXiw0^`}c z+d;^AlWf*1;@!G z*~*pa16-w;?aKM16L9X&1E#_FV!Eo{DOIO(>~OAfWt6+RQYps+4GU#ek7VzVMC^B@ z+2u~w2tQ_kMHU9)&yZLYq79dN3 zvfK(yh}uhoB~Hz>3UN?edq{F8fHkWScO8A>dXAk{8ER00<^>lSe5aCq`)#W0b6F){>hVxtgU+;S4K= z#D|Y)jynQ~WQAY9qk*@RpFVYkvzzyewW&1*)aO{d+^Fv2N*|Kn;^HsXDo$FW=Q+Ae z#gMx4T}Jv@Yy@;upY^db<7s94sXn#ra#s3n!l|M(#?1}Chdt$!V&!xTX)GRcgY#w77-3TiR?q39T6KYG{xBs|UVvrwm=)vT@9~;#9l;{nv~%4Z3L zL%nn{n2V;%kQNN;L?#)*2|zgm5@hds&hJ6g-^(rs+QdZZipCd#NZX1pQPN zI-W%p|KkM!o{Kbz8ikGG$?jUWdyNG^-)eijV&-n8dc#}c$zj&`j-Qz)72e{ZQ8&Z#8Dqeh39*;gZMp{rdd{Bq!Nq8gC zMG2@6C4LBd`(m_eg&GWA^}BuoOgUKQQ@L>Kwd3dEpQp-EQrzg}eNsNh!~8bfanPcW zmxsZ=E^EE9UXCh?P7Ce4udfYSoGD$t*(CvYT359!4*Uul*HL2%vs4J&ZJNF;e4KWE+mGl zZ3z5%0GOWK7y|N|KAiEAMA5i4M|b1%YA|BT7cai#c@~=#i(V)jS*+HA6Q!v7MLHr)cNPq_%V_ zrP$K3W!~X2W{3H!fL{zfLZnmi%G1-6H4qr``RSV(9?x_9^VaCNl&4Dkzl867mO3P$ z3^d!7C7MCFiN7%+h-rc|w{xnlc3mM) z$S14Z$azx{^)gR#tEz4qwv9gf-Dm(}lNt(Ma$;z;sb0wl{RKXZvMgp0xLd`y6wa?x zhI^=l7xd`>v21xKN)*_S%Hk;=RVpd?47hbH43@RyzLn4PUTfP*9vq#`3S-8ruBb_1 zakrYI7yi@umqe!(Gr=~w1^~&y=R))o4edf;6X9$ES>TOyLcrU>K?6A&U(rf_X)V6J zusfC#T8yxv5D3UK9lxV>ac=mxf~EKJ4@xfU^NranrX#=hb0-jd-g@DOn-77NZms6O z-MgT@cWjGkNQwF=@)U8pR#*qf2Nbo)`XvMH&3shx42eMeIRMW=txZaNGMI+??p{n( zxxi69(t@0Ra8|p|1{6u>-~OcWuP;_~h_xwZ1F_Z4N0VhW5k95wW5{u|kV z`DUN`!p5f0moh5)&sl5^F$C%DJwJP=`HGspL3P2N&95L!x`RICc^t||6v}SwZlTpDxeLh* z)j2fVE|fMgT%x58QHWugCh24-rx8p8QV=Z~LCGDT1@kb}PH9jW;W&xJ$B<@QMpE8EP30X@zhHcUWj`u3r16 z>~3pMmeTzg6jWQr>|SAfw&tqi%01X1s9^1`lq*XOGqiwb=~*pfhq#5w1o3n&}KsrjFy={%`i*G;Z@ zl}T9noLo{|ZWx4crW;`E#?fG}sYymasL6Q5&OGqY|cQ%pgIU~f0^ud$i zr*h>txlJjf*7Yftr;3!XUpU;Zfe6s(Q3~V}keH(mESWp@$t^%yFALc~F1!~-?Olke zhZ%jpNMfZLSTv0^Y^@FqF0%aXX)Ni;zV<~kqc|}2?Kpeh@|Rfj$PMb&NYyar+%oCb zIre6MlCDyy<}%_m$RNExaMYxzAnJ9chEG@N2dzCAmp7X3jza7FQz#oO?UbngHzF0J zv&T(I$z%;ur{g4ZMW@o#XP2E%bFpBsvZyZsLh708N=H6g$R|+COCu}eIF(>Dsdg$K z0rG5Z26?0`q!^6+pBSM)PT6tw8K`cH;kpI30JDyXeQ9#^Ri|@wc3kZMQE#yyBc7HI zz{C`$*G`qYe}E-6>#~omYn6?Z%>H!tyXlVX?!;30rV&m|@tQI%ijD+GLU0{hlyB50 zgH0ws)ybzgWK!gw>!LI8O!Pv31s(2RoPt>9jM;0ydZv-+=UuO?DTmsDN}|SAn9osF zE*IOmGLl5I?Dr?|elvQ6uzYHYu_dJLDi@c&TXC|ap97DuzIIjYG`$-|_~35?+<07c zJSwrQuTI3%xO#Rm%9|gOUC=Es(BV=di2LkV$b43)2dh zp0Bkd(?q>F=Whx93XPpm7mVBbp9r6!YHOeqlcjtUZ6A7m4jQ)nKFur1c6dn+ciX@}q(aiB<$*wS&V(vsCbbnHXLU>xxdeS*=tMaJ=S2 z%1h)o$QO<`d&c+@&dIzcBBXD6eJX?sT=`T&TEhSZIVHvjWB+A|0ZqqhCJ27JYM62tO<`gt`Y{F-CoL zA77oYtblWYL5+W1p0jHm@LyN~7VOkiL6#G&ocJOMw}61`%(P-*_@BwL<13jsm{mJy z3l$T!rp)!(Kz&`2NW#;81CEXN^(7TM#G(ci?9!J)2O!r#2NrC{=GR)3;~wbF3~5?T}n!W z#E_VD`G4o<^X=a`|DD5u?Xc~6-uHR#`?{_>o_wV#oJ3HZ61_J68{&Bih3@?f%>^rP z2vNl09$~24{=je4NZ$jv+N^A#1={x-UEYP*>1!V5qZaU++9+ zyMymSR=~5eTHl?#j$65^Q3u$KRML$R{9cOn2$zJXXry7QWAP+vJ#zNEO0o%%9)PW|0m<0wkTHDbmBI*V z9PW|iF@q&m+^WaDf)-AFvKz-}KE5og91_>s8za_T6$n2yES0-5p8#-tEM{d3?gxwq zc_Ytedg*!7f?`BxIQ4xI&5xPbwtZQjb^hTgxKt#poVTu%tRnu}7Mbw^DrMjMBA_!bQ$_ z$;L?`XHS$0__cgLY$t}OExB)dxOCbXzw6lt-}q#w{c4aHb&vpkjlbsG3enwl^+>{4^1B#jA1!>BsFlpvMUXU`)qXHou1j?RY5V9T$X&)3t9D%XnR6vNjZCVN2k*~kzfM>~; zAcs(5`s7Q-jt+p@3n` zRdaQ(Snkh-5$ZZ^^R1Iw^rn;z7aeuE{rH!AtzK7@SzvM^-dC^ijp{Ghb!aN%EUPOq ztE{S?Uw>ittS(Ie8z3yf?|FnZmkr24X6qq2Jn1Gke!NfwO!O;BrPQOWLD&i+i8x$eV%whgSjoz>Ssx(`7~93|ar4}Kl&+T2ToGxnyJ^J!Ea zoiHcD>B*J_gLO>@&r!%(yWM1yUDIw`UbLTbV^y2tb;d58=5m#tHiLn9NoDJMJ{VtE zX*l(z)Kpf*AOL05bKjQ>){txAEZ{w16{~a0Yr=3ca>G{RQzxt1%5X}6kO)|Gy&-H8 zuJW!ZF)delH+zPAu(#Cad>UiE#90)W%FGQwZ-egk3scxS_kgdIn1i!(yP07$;873q zS2#Ml!-}h>W6LsaxE* zvpQMzIEf-#`g3J?DohsM)=2htnan{DEO8inTZ4VaHMudvpcd3&D#20O0r3?PtN zC?`uHXBCPn;g(N|yeu>I5C%~iJft^N_C-C79r(i-SVLo3Wbqc{K!E86sBX&Z<;_3cB4DNorvGCHn!&1lOK?E#E) zPUFsWD$_6dB6WPtM~3s0G6Acnlu0UE2Oe;8&@HPEyr|h(|L+vPdk)J33$$p`J!(_t zleg0D>>=xnQxpV=e_KPtIfCx9l8ukt9DvPxoSAsMl3Diw!>ekC5GH; zB$A?8z6=gjGzQF^bFY`pB_|ZaT8ke3#ahuntm@_eLY_DwOosy_dgNa9Z~_z#gc-+; z^t@maajBPjUN7-uZlX5>2!{+dgo}Q)XFz6R2T^GEuT%}1$k~%>93Ki= zJPyH=Vp)eopn{qB{{(A662D?%JDVMFEOgUDiJtWDArg9TTaXgu+=a~pj0ZYk)N(3z zHa(FOf1s12BBXLUl4E(S`t^%%Gl}S5Gkw zqt7*S3zaN3FI39oc%Pt$JBao2hIUM~nVFlV6eR0JN;x@MA=q=Y>43yV}vwSf7HwR1*%tsw1A@?#RgC} z%5A1+2Qj_wYu!!-JrbKd@1^F%2je_?!+OJjYPnCbu|hPGi){S&BPkIhHp&Y#iAloE zZ6>5e8mr`%RUh+ffU{9i?^5~m>#0NT-}GOvE_uYHC-*|FgFl5nth9>Iahq&+*W&Y# zak;&g^a)WM4^6_Jdu)yw4L(Yfo0j|i_oehB0MEr^^BvtY+r71rK-$#`5Y+qSzL^OL zRHC@W6dAW0u}OLO)7f`xMPi|`01AGJLBX5C`b&$j5k4_#LBqd5;S)zElf(PeA?qkB zdFN;LAddf`s&4+86+{u<{w0efI>?Yb$a9)<^7JMW=&)Xa247JH%%d`@)ijNq zAx#$6_ALXr&+EtrxM0-HEONtC8HGUYCsPGfel!K_{2&>@KO-sy1V&xnelb|$;^xYc ziR*-X?&BZX*lnN5Ezx}r^nb>y#ksn_i1G*fqW)s5JhcA@TfN6OntQTRC1Au>6KE>9 zpm+s|s0pWrY8S5jk${*>E#S5uO^=sYb%!e|Q}6(=m5kwN9J<3#(r56wu=j3O=EeD0 zZ6nnQf|&AXS8fK%v+rBCc)XI`dPPjp1pi=(Wr$_C*YYwO2;!oA%(iH?E!k_k=LZOqRd| zi%G);NgCEbHR;0{1`3veqJWIm^aF;8vJ&yy8_TRi&?I>4@*URHtt+%r<>~?QJ#}EjNUvUwYD5j% zvw0swl(N6*Hi8Y8gO{w9#Hn{58cWot;B9LqM^AaaJp>&1`JnN~Ale6JWk`F4H-xcN z6~+c^?^+WCSh`G)_@TLRH8a=XW*-Mg!6Qg8m7 zLyhGcAYy*`fn41B1H7M!FkRvlXlJ$Bm#?5&gxzpco0iC7V?xCgl6U@+)PbD@lKcK< z+`|B4rZie7=X%AbeOZU4|0(`9TUVDIf$GibY9OzxIgNO{S`&Jy3N?VFx1Vx78ZMXF z!`YqD^BX%!Sg#)W+Z-6o>^$q>bjJ{kMcu9-c5p>y;zgi|AlW1bHy+*0t`zowRk^ zQjX+18pn28ki4|pLK`wL7Obc_tKq)P#j=9=-qhk}V?+?6vi?)WOgrS-%Lk=C`M*S> zxRSBZJkGSI>jK(0B_0%2XnmOeEx#3`>y^!1s4L-JKMf@60OcY(o99*4$8t>M@#sSQ zMIg$6YtiL~(eJAbf^{bUl7Ug$%+Bdsqsrwew?MzX4nH9m)`-aL@JM+~{`OU*G#ZYJ zPo@!aD57Mn9lB~J%2(Es%H4n^s@&AtrdI(_+Ry)&FKuumjVuC;R_6fR*Dl>_pAHhj zi44V-rktwCbuAa8LT8w7eYF?fc-FB<6(WhjKyzyqB|rk9XMj=UZ@LR^Kftyy3iXai z?fWAv+qQh-dJYRP^N8_KZonC(#lrK~STZ)84yzu!8>;q`QbUyFYvivU>EDHb<75~-`RLph08ix_IP<;c8ReA z)$x0WY}>WIB|`xtr>f)nEYTaD$ssLrzuS}tf(2W0j0ZF#g^m-kW?!LQf(cKJu!~<1 zPhyXH1KL$!gb+5XcTTb5r(o#o`5ROO#XbFBm9T?i(VIy1%%70&7=?^$0E1|{JVJ_) z4Ju~=&kMf#SpG;_Z@wU5X?J&BMY;r^o6hG(z1k;LFgP2U?mg8t|Ii4dxe`GN;j{tz zVF7&F5TnAde7AGQ6^X`u<|9+`oN)S@u15z&-Ub19_gLu+;n)SICr-K)&32Zk1}LsDRAZ}2e3Ls z=-YD2et{c7j#5nOg)8@n5%w1>9Aw~4bz+^QHD28guKfh0y9PUd6+OEq$hey8@z;pD zC#j57X|;7w&y7=#I_Em6>PQH75w}@V{LRzJh$AOR8xc^?W{4GvlNOCec+Y?FuCHMA z{q+-14rf=z5gpH73lM$P-jIoMi89M*-q);U(A3lfDCMVJR+9bmHs@&}Mh9ptsa!}D ze#4~U&g`1JMO&qz(abLNVMT2ZVcF=_zGq>FSfswnrbp@ptT5OK@>I`#m~eh>W0lxu zaW29@C*nDw?ATJ|X$B!6dWY#MEuISOE?stDZ(o}UfU?bB$?&20)TJmT(Z_Kq$ zYTYr9=*gcdDD|1{W%0_#r!=7F5@udDvH|itxI_2eVx50yxPB8qWy4vAZGFWlNUS=t zfzB$X@QLuXf~}(4i3-1HJi{NOlF~R{OZ+b>oH)XpO&E_`@!3!AA04J#eeE(NK1I#n zOlsjD8p6gtR1zpt-AUode2cI>=4FCVth@MR#(S{u%T-~2g!=$7*lG3>NiSsJ%Mp&H zQm`Wy7B#P$@Y8cZaMu0BPmZmb+8c*tze?J z0aBSq4v{{R2fAsR8|yG2TG&a*b-eG3qm$xH9zuOM5R@4=L|2Jns9&HY2}qoK5==5k z5e1&nm*`rKFtq7L*r2Q+E4N@$7t=}I!}egw)KBy`0ao(>R>ho9eLMOUnrmu#QF*mj zcTn(0d9J zZ;}L`$z8cgx2WZ!Ft*#5MWVY~QkeokSdHou(?bxs;BvAcUj_a~i(no5og(3)&q97d z^tSH*B_SBo4M$}n!9Q@3Ch^r_%t^A?zqYTcxhFg`wM+jY$={9Pke%c)o0{x*Mac34 zZfU@yxVv|&>3gau+4xD=e6rDD6hP2E?E1&`Jpp!xQG%&PAt~rQQk} z6mWt|dpH+QYp12;x(OC-9Z*?4&nG=Ta$swM03(F=t!x}2*6)A@db+X%DBm?bPmcH_)aL?m`XG?@Y#rNG z8PQP3G9vD1OqasC(q-$Wj6)>zve)UHV0j{yqy&Y4`>XqP0Ep4*ZQGDQ87iL!pTIs} z=mD%5Mfu==M2WDWN!wd|3oEWf_ZrElK)D<{&qRIfvj1Dz$HXYj(@OyoU%9tLP1}R- zlEQ7-*L~w~)wbJp%ku^<4rF~1;BO6?v4a`k6S;5PBLVt$D!x|GQOTu z$_MJnC-Dp(L~1V@K8Bry$p#vUzo>>T-hVnRUZ6$`?6n*qjIxKcB~)6U=oQA6p)Xs) zsli$*&2fFOqGxu1XYh=Z)Fx(|B|ve3N+Hm zU?IAs?H2_=x}IezAlSK|dT_4jaP&Xupi4>rW_@O5@|+%M;}^TYrvtAZIJt{0hIe(p zv$PSsh|PA@O8AQ@V}sW<0h&iR<>PBx@@&k#*n{zt@gzHM>uM}iy&`^q3?IeAO?tdv z&$q;GW(4@tK}V~ewJN}f96pkc@^!x9O(mQ%eOpTi3l+^3=BuBjD%KQvU;#K3@6=Gr zt^2B8J5HWNOG*^=uXeDQW7D8Lm}q$%juT-LM-UVotTV!ed%Rg-A5|h;3dD;B96ja% zDBH_^S;QIWG_MxDR875n@tN>Ckyvs9a~XVPxO&{r9Vh@mjO7N2;+V(NC@0uTr@kf( zqacrJ5br-+q6*+m_522;a(r7pA>?`$dn`rwK8Je*!2im;C-P)48U+6G$)OCsYZNlv zwft278+!@H#nE^&BJ)o}Qn~SPiuz0E(?8Uh3LSt z69NK<8BBT$D)&T3_vtOZg1*jCaFQSiDvLZ_1Cl|SQVeZDt-j6W_T!6F@|D})RG9gJ zUnF=qP-D^ao#h)F&}IiE?=$pKnc8=0b?{|h^?2TXTp#1VXBCul5VlTrCQ<{-0PFWJ zc(eW{+4`9(50@#*JlPGfVQi3ike&YnQUH@xUdh{*+t)ivV=hSYtd)g`$+5MUDnW_&MR;5MT zsGEw|D)>ev__zqP{FTM)oeyd6vPueC&gm_;hvuk|Jj0IMM&0J8?R^Kx@mlgdTjgau z;*c|zuvvSMmkb9}7C$WV;I`+6!JKSN^nS}ZVH3O3@=qJLnviZ!f7Z{YpWr6e zb*HCK1T}4?9qQ7kpAS;`NNHQW<&|5Ki_|X|h-Vlz9?R=T){~z4mRwjEif<>Pp@RCw z$wo+r^tEiosE(nB?StCuAs2T?b7Q-ggMV^}(9?1p)ANRh5D+^$lu+P%W#Ugcx^zGn z1^0MSWEHg54Evs?7uPk30OC^C z9j}KqY3ZQ%TioAx-z%2sY5R)`D0cZgXazK^0hg3{Hw!uP8y0wNfTH;d+?%2ftk3*l zoMfF41()r$EM-`ooRl*Vx>NVLgUKRCRze!Xw39fo@Pn($Q)LnUNd5U-uGoFUz+zkF zO`UX`h$oO;oHQ|mex;i;Q-!S}y-d0=2u&-nCEM{j~~fOVuy(&zni0kUzwXi{O`Pnq@>P$sR0drcxU91pQK zaje8Xp*lAqKraR*`3)zkr zU@{qIKeuq-g_U2VRYwgCzG=Z`Ll76|HXLl**QCyWsA4ML_AJzBZ)VvadpC7_FdS=jsohS6zs6 zGGSXIZmjD?GBRAET`N~bZi-5lU4R4`DdVS-qr*x^m$^l0o~TRB9~@16uVUWgcE&Pj zDlLyEa#44*g_^#gQRqdh(dPeCA4{sHe=1Ku^6Tw$jV7LKW~VNe=88uF4R!HX7~~-? z5crW$BaEqHU`<6ozsQ(4UX2j|3z=^r&9vkI{GwS-JRNwKTW}`{PJVHd?Kz>8UJ4ha z@g8l@J-X<(G*`_ik90@$;$7;mo=wk98Gnr*+2#G=U!Dc{;)E;sc;5`a^my--w!D2h z-%FiEYpr@&KO7A4PLlBfxvete|Iw40(=+23?k^4UfovG;7g0W9&#@A;)Xq)ld2 zFuo^9ob4(NIT9WJVXV#+9y=ajtN+ziLPaIIc;EqXD%8E_g{GpW>ISda61x3DZrE>o zyXy$VX$#&41YAulImXbSbeu#+`=MMOv|H$jh(iJMj#mKlLr8#@x!`a*jw&z!!GhM; zP-7q!gcK+Z^9ysnvs@NQUHyHPOcMqK;h5hsPObvAcoDyFDuCq^S`d^iE^w|wt%xsA zqV;3aB|}}-9NXFzXZXhXFT31mBaIX;11V_;L89^x;Giw@bQBe{Ban@uF%{BG7;z}L z#Mj}<&JV9l^nrg5xfB(@k)3W-GfjeHu$pRoc}v|qn4qYT_6H8%TAD$R9az2V7JVqI z(P#LXnLEuZjA|#JDa-zI$9PA$hx%A~nkZdFYKN_=vghdz1Jhm`-Y6Tg?40l{ujsQM z00>Jx&x+ghwlV4J$;RfC3fsaY_A>5;L^d$o_5 z_~}17!@6NK#E%Cu#?CwtpnQ2hD_evmO#l#KF$4VgeIgouNA)8KX>RnDbHm6UVk&B+ zou}~`BF0gGQ53qFa3aSImDdWI08ja_AWm0eL*MOQ9o{1wH#Rq^x@UiSEJ@1m9*T-% zZ+QM#cP;N&cTV#7qEEFwdf#FuBu~EPDplawJZV+uOu6@5;&VCC^G;fcqP+KTcA*{P zv%$%a7p*aRWuJH^9@4$kXT&qqxSqIT~~kkKWCQgIUM<~OqE@pzcN+EeDI@ylz>Oe_sP|L-E?MPIk}f0 zy`IXT?MROaP08nrp6_F}uDru*<|S>uByQG!C_k1LWPXreW?NdcO8ISa@<~8b=qh5N zw@H}3sAMCKPUHof(s`=V=7d};Y3H%(mIUQYEVnTGb+VjkgIfV&e$F#1Jj8f>(T9fL z$fKg<+G7uKl7P@@Gu-3L@33$g`4WP4Z0|hVKLfPFeXus4)-yXh+f%#Ku_n{&`Sdmu z=&-}O^JM^2Kdar3mbXqU!GO&1{BUdlh-96seczlqVW_xGPl0P93a!wZv@pMZ=QQK- zXa4aMYtNTHo|0nyfmYTpkYm`C2B)0;Bf)a`5#E&h`CU)3OCtnhn8W;69!LK6n1z$n zZmt7R|7*B=uP0|(T3VJUbnVNoyM1OgaO%64)?(Xp>A8B>Uv`U}EdZG#`q}>bdIx+f zBVw}Ba%9fE{ihGz&Eo>0=Y1$L=#_8tw3n+ano~}3)cMMwds11k|Ij z?>dG)R z37CS3{Kqb!lLU*jXe{aG%ZiQ`Lf|mU^^^W%#t#cv@qOBpf7c`c)p#b{ckrk*_&@4X zglg(8_}L;6?a6Y0MwX=Se#cfL~DE4TK)3GPayqd+qHj*S8 zQ1XjiP*?P4mIVqfhar}8C=_C$E&K{zQ*I%68_r)7Gg*VS0eX5PK3E2sNQ~{ln+tb&9+lb-Da>FE zJ*Wt(>Dtxa1}*Mg2Tn~jw`cDJ#iadYP|CgHWDMUj&TTh6S^YlYxwq%r^1DTT@5q6r z$G@Q6zOm9?&p6uz;Xx-C zPjRsyn}W_S?rC$_QBQW8FbNhc=9Ny>eJzoh2?+= z;=Lub0JtJx!Oe0l%_9lKYyywjWHr~wZLy0v(-)4ynXbt!fxI`(-35U{D$c3==7gH_ zules%?*d8O=2L5aCsRKIzflnauDj6yVkGN&SJz8P-#^LK(~3(c*?C;Ix1c04K_q56 zV1~{%DS7j~vri$~_ zav_&_t^PPuyeGqK%G7)c0cjRF8#DpFDvP&lm)b0p7qNSFDZR)DUU#I;$Q)aQEjDk5 zlu;rUvQKt0-kBwqfCR^mL800|5Xzr!+p%0(FOGdr*}gwFQ7;|3X9rx7M$i%Yp|qq9eU0ax07p{_u=p+PUNDc(HBlJ2=l_4|T;BKeH{J`%-BI4x0m^NUJk@WM#< zuSOBhUuIKR<*QPf7QH};-9Lv9n1d*qA^6est&y5A`IiWGH>Z Pyr8C{rCgzC_2T~lJFz#` literal 0 HcmV?d00001 diff --git a/doc/html/_me_buzzer_8h_source.html b/doc/html/_me_buzzer_8h_source.html new file mode 100644 index 00000000..80aa4c44 --- /dev/null +++ b/doc/html/_me_buzzer_8h_source.html @@ -0,0 +1,157 @@ + + + + + + + +MakeBlock Drive Updated: src/MeBuzzer.h Source File + + + + + + + + + + + + + +

+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeBuzzer.h
+
+
+Go to the documentation of this file.
1
+
43#ifndef MeBuzzer_H
+
44#define MeBuzzer_H
+
45
+
46#include <stdint.h>
+
47#include <stdbool.h>
+
48#include <Arduino.h>
+
49#include "MeConfig.h"
+
50
+
51#ifdef ME_PORT_DEFINED
+
52#include "MePort.h"
+
53#endif // ME_PORT_DEFINED
+
54
+
+
60class MeBuzzer : public MePort
+
61{
+
62public:
+
63#ifdef ME_PORT_DEFINED
+
70 MeBuzzer();
+
71
+
78 MeBuzzer(uint8_t port);
+
79
+
88 MeBuzzer(uint8_t port, uint8_t slot);
+
89#else // ME_PORT_DEFINED
+
95 MeBuzzer(int pin);
+
96#endif // ME_PORT_DEFINED
+
111 void setpin(int pin);
+
112
+
131 void tone(int pin, uint16_t frequency, uint32_t duration);
+
132
+
149 void tone(uint16_t frequency, uint32_t duration = 0);
+
150
+
165 void noTone(int pin);
+
166
+
181 void noTone();
+
182};
+
+
183#endif
+
Configuration file of library.
+
Header for MePort.cpp module.
+
Driver for Me Buzzer module.
Definition MeBuzzer.h:61
+
void noTone()
Definition MeBuzzer.cpp:224
+
MeBuzzer()
Definition MeBuzzer.cpp:57
+
void tone(int pin, uint16_t frequency, uint32_t duration)
Definition MeBuzzer.cpp:142
+
Port Mapping for RJ25.
Definition MePort.h:128
+
uint8_t pin(void)
Definition MePort.cpp:427
+
+
+ + + + diff --git a/doc/html/_me_color_sensor_8cpp.html b/doc/html/_me_color_sensor_8cpp.html new file mode 100644 index 00000000..398c1f51 --- /dev/null +++ b/doc/html/_me_color_sensor_8cpp.html @@ -0,0 +1,213 @@ + + + + + + + +MakeBlock Drive Updated: src/MeColorSensor.cpp File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeColorSensor.cpp File Reference
+
+
+ +

Driver for MeColorSensor module. +More...

+
#include "MeColorSensor.h"
+
+Include dependency graph for MeColorSensor.cpp:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+

Detailed Description

+

Driver for MeColorSensor module.

+
Author
MakeBlock
+
Version
V1.0.4
+
Date
2017/01/17
+
Copyright
This software is Copyright (C), 2012-2017, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing +GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for MeColorSensor module, It supports MeColorSensor V1.0 device provided by MakeBlock.
+
Method List:
+
    +
  1. void MeColorSensor::SensorInit(void)
  2. +
  3. uint8_t MeColorSensor::ReportId(void)
  4. +
  5. void MeColorSensor::ColorDataRead(void)
  6. +
  7. void MeColorSensor::TurnOnLight(void)
  8. +
  9. void MeColorSensor::TurnOffLight(void)
  10. +
  11. uint16_t MeColorSensor::ReturnRedData(void)
  12. +
  13. uint16_t MeColorSensor::ReturnGreenData(void)
  14. +
  15. uint16_t MeColorSensor::ReturnBlueData(void)
  16. +
  17. uint16_t MeColorSensor::ReturnColorData(void)
  18. +
  19. long MeColorSensor::ColorIdentify(void)
  20. +
  21. long MeColorSensor::ReturnColorCode(void)
  22. +
  23. uint16_t MeColorSensor::calculateColorTemperature(void)
  24. +
  25. uint16_t MeColorSensor::calculateLux(void)
  26. +
  27. int8_t MeColorSensor::writeReg(int16_t reg, uint8_t data)
  28. +
  29. int8_t MeColorSensor::readData(uint8_t start, uint8_t *buffer, uint8_t size)
  30. +
  31. int8_t MeColorSensor::writeData(uint8_t start, const uint8_t *pData, uint8_t size);
  32. +
  33. uint8_t MeColorSensor::Returnresult(void);
  34. +
  35. uint8_t MeColorSensor::ReturnGrayscale(void);
  36. +
  37. uint16_t MeColorSensor::ReturnColorhue(void);
  38. +
  39. uint8_t MeColorSensor::MAX(uint8_t r,uint8_t g,uint8_t b);
  40. +
  41. uint8_t MeColorSensor::MIN(uint8_t r,uint8_t g,uint8_t b);
  42. +
  43. void MeColorSensor::TurnOffmodule(void);
  44. +
  45. void MeColorSensor::TurnOnmodule(void);
  46. +
  47. uint8_t MeColorSensor::ColorDataReadOnebyOne();
  48. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+ zzipeng         2017/01/17          1.0.0         complete the driver code.
+ zzipeng         2017/04/03          1.0.1         only detect six colors.
+ zzipeng         2017/04/10          1.0.2         only detect seven colors and add methods named MeColorSensor::TurnOffmodule(void),MeColorSensor::TurnOnmodule.
+ zzipeng         2017/04/20          1.0.3         add methods MeColorSensor::ColorDataReadOnebyOne();
+ Lanweiting      2017/06/23          1.0.4         Canonical the code format.
+
+
+
+ + + + diff --git a/doc/html/_me_color_sensor_8cpp__incl.map b/doc/html/_me_color_sensor_8cpp__incl.map new file mode 100644 index 00000000..0e1cfb5b --- /dev/null +++ b/doc/html/_me_color_sensor_8cpp__incl.map @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_color_sensor_8cpp__incl.md5 b/doc/html/_me_color_sensor_8cpp__incl.md5 new file mode 100644 index 00000000..bb2b1225 --- /dev/null +++ b/doc/html/_me_color_sensor_8cpp__incl.md5 @@ -0,0 +1 @@ +9f9fcc7625d78679954ff415a9d7de16 \ No newline at end of file diff --git a/doc/html/_me_color_sensor_8cpp__incl.png b/doc/html/_me_color_sensor_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..6fa180be5afd006fe0bb4c3a852b6ae53fc3809c GIT binary patch literal 47924 zcmeEtbyQVh^DZrt0@5WV-QA)fASKe>-Q6W3UD9wsq&p;}In+VwAl)V1-E}wM_giw#l@7}K|6CE-tnvT_lJY0vTt9|ES6Pg4mVU3)JztY z)&%28wSU^hu6Cg}ek)#DTC2KSDdX8-sZ*S9`5R$&Mjs!s1MLraO?N}}qUz^yMEYvm zF^0M~Qfu|Te#VAWNWVE!Xj8lw$|ss$9Sb=vOo-QBdM-?$Q~sYn!-RM)un)H#={l|T z)5Ct1&9siJjALHnDGT?y^pID)+ z$1ell7pIP<+j+W*h1Ela;`MOt;d2!7Ki)3jyq03tvfZ6NH<92lLpE2KFE~9om0m9) zE`AmFp9Qz<_j3-eK#1*j4lXkys+t|DEF^2r&t`$mD*owxT!KgRJn~xsqGRBuQ3hgQ zJxofIRKU-_N!I?7E6irr(3u(@RivxR#^uzRVyM|ANcZtko3~O}vk}#mG}{Q32dh(QU70=MV$yH(uDs0qdxPWSZo(U29uCi=yxwVDq;bFH zI*N?lP<%93ihLwNsj1=b<@)#a+$3F1uMTux?@Zd$&=9GU>PVT#6aHVE{Z(xGDJ?b@ zmg3`)JQ(YnhlK~&Ddx$?8=ix_EWb`3VOWB;XDsP6Y4WwnWyh93M)~XfP z`5Y2r9Qx=@u_AP69gRG8^Fp5t6ecEFyj}(c%ZjkMTTTfq-0bHSY;W52TfZCS1|B%5 zF^c&3QsX{QPBf~43(WF*f~L{vDR5C-O!$B6rw>N_zi{jSfBSU>wd*CPSEY&*56@!! z&$B+{UncCYEL7WewiCFm6}<+&UqJr|P_e#NZCqYh7gQC^xH-GqW&HF#sYM3qd5ZW6*rIP$|nPLvaV z)r(9TY(u)yIc&hUL!K}()^{*cYc8aDn?GdpC9ns=kf%V9YQ@KM;5|5N%;2iE_6+PA zQl_S)#3p@;jNyIeWOJ?l3+6v){zD{Ad)j;>Jd#=|fJ^WF+ep)k_FcZ96jqdXb;5tY z0j8(?@dU?5?FC{?RGBq|Rfkuq1&@Y)WitY1u;NLP|+F%=_|R&N#_vZ*RvrpSCI=y54W~8_ivr^i{-<;bd(( zfGcl0>eYPn5dAR!5ODs>bDU&$qxYjGQmh))=2(Tw3|kyPdcsr;G<{ms|8v#>mj0h; zj&)+*G*MtPkVXU0w>z? zhVcpwN8ng*1<@^m7td$PxnsWf*x>CdjAeL`sCC`Qc%-lB)!tL)=~=C zvE{#rkZd4wKRILg0gYOiBXaaSgWc1vbSm6%B_;i$R3|k5%KZCjSC4u zHaB@lS|KN3Xf5~YiKp8B_Qrga?#SG(x}c|y8f2&VM^Z@0%CmpFXA!h?olPlsIA)G}wLk9=!xM1ME(TtYL&Gq{ulnE~%3bEbi+Q`-t^r zsa^WPYjd+1%-uzRj}U=wpuHGz8lw;lF&}=R;E8j<^gcVN#K9abg1g-AZ%+^>GwG?< z3#{0k%76T6-f3LJOgKS4A2X^U>YR?`GydM^=G(2a{V5YZYhPhE?o-LeT~q_k%DhMg zJ-^%2U}xvP5?qlceMWNRbO$6OQb-CX-trsG83C?kYkQ+evFwgiu=#9VEH|pz^ctvz z9N03-lO;W@p&))5a7Dqk`LdWngwdL;X=_L8qFrmlYbl@W-l#p)Zoj>EBtn0 zOTf#F(n&>|@3F3@hpM2*38-aJ%?B4UQ^ieoDEZ#^jA(QBIMvpd&kzIs)}b7=KeP74 zy^PGtg@3h$*CKecIYWpdj{Ph7mi^xa5d8UEH6Ky)qw=*sgw1$hu}$bIJoL=8ypwLF zv6_3^6<4;oL3JD7UlK&w9<1rN=m`}Cz$o@(g^oC zFGbWw0AUKjds8V|_Uz7)D_l+Z7yI{N=ejz$t&waP4AwFvUT?e_pbnPiiwjr+JMA%X zs_Swk(@af%Q>h%4d|_G}$ZrI1FL1zAn*W8{u;h>+GJDTRM-5&W3u}u1 zpY2srN+odjZeqrfz@n4Yq1&#`f0cwb@nJ>VF5YK#mTm3LqIlJodj{d(WQQ)#(sj_o ziy$;b9((Z;p%`)*U%Q`G;a%_T^HcN_MzRYyh07!3U~M8kK?JoG!#9y0O|^BBzYz49 z?Y@z`hUvi5Zu@3JhlnEa(6Liv-yq?1Uf$JfYnKlL$x)n$1YfJh;qjK4wk*rPm;HHe zKuOsw^F-xN)Vr`nMhEil6A7p(-hM?UH92Zn{$6Y}+dSjQ5l>^wDt+cWm~0Uw-4 zx%k4b#GVHm3{y_bppyLzwEUJvN>=USlK?#pKccP(ix*9|HiT+zlgvo zqNQcn_fs*tJ!7Xp_EHSIB3u5QLm&AdgdbR_T20(;sP=f=^K1;%h>o{rAi`i1c@#ke zIs{Gs8nC6N8hq*NmC#7L17o{Vd2FoBzJIWrq*8j)exPF7cubW!6|ogbEbW{(_+gBL zJW;-ifWVAG$tr(3aH>egK;bMs<4EUOoAF!utW)=M;ehvxZe$0I4Lv38{n-VjyI(47 zqC*F7_z29~G|G4NDLMZ9V-PGoC#&^De3OyHsl(puwS~2XoaO0hM?R_P)D?OHay_3d z&L*tK^D6S)5&+V*@iD4u{Lgw7m;!^9IEM|-c3P^4wIpZL7I~B-1cHcTBa_n=9%3Bu z&t~yO@#KkL8SV1~m@p#B#}g-=(tU3^$P?tN(C8w9WXn=42TdE_2MO0FT>2_>rvx0b z>r+8E-0*mVZpx}C^vjfi-6u{EPKhCNk!9){+^t3GRClc6; zKKZIoYoJ&k`O~{7?Oe_ms2C_XGbs6f+yI%|Qyx6mOrvMzEm**IRMSKCoi5hg47x)J z{sL7GbeNxhmu$3C#iwzf~b;XbG(T-dkP%Q!Qo zz3qUdCLOPN`O)>5+N(wl<-LJ|o?^}Kb4z-C0mwRf9t=ec+*Wg_gbVF7F;>zf{oL~a z!-}m_Iiabs1zJkVshp=MpQjp0S|{Sfa9m%X?~HCZh84~@!m;0THN(~7FZ?CC!nm{P zWmo7-w)98nw%!mZ&TX+U7iq}=`L%7Nz_GfZm(8CVfv<)s& z`W`+osJ)Hb z^-+^me~uo)&C5D2MN53MY$(8fM(zh1y3bKj=y=z;7PC!nM$%{4Y^CETw+goVf}Dt( z%w@pOM%dc)OFHj*(K&`B z$3j7TKJVtT(K4ufjZSt2ZL2cV;XC+?EaH4va+vYtstQEBlZy#!QD@6Q{CzkhVSOQ} zx;_a+eepI$YyQjlL3ac%KBcjF64yh$%Q=1n&zM3;yd9Th?+KG3Eb#mHMWv)Mkv0Qw7 z#vamU9>H>d@?y%`9|B3ZMiX0)woG>GIh0xkHX>eI!T`o6GpmFDNz%@(Dp0B*?SD zio`R$?Wu%kuAQr=sJJpd2nMfj0-ncgq9Oza;DJtUOW4hw)o}t<1juxA?4ByRZ<0md zTKvM5Y~GWo;}Wb7GFDz!@k_2cE=*`i!CvdjZpzS7)9=J?Sz?Zp_vNEO*_KiFxEhaT zcx^#?mY9+{dVUX7XFQ+K!~&x6`%5|*CV54#5!bj+>iW-06=m@T$tN|4jIR7#CoKGu z;a~y$I#}lCSWLO_hTwdaZ8~k%6thf4y;N`)@wDj4hoS<;D7f*q3Rqx(wwx|ui zV+36#URWHS-zZhA@9%a`%>}ojL=F>w*jcq698yB@GWKFn5}`mV|+&xNqU*|Pz{xD)B&`N1H1M|SN?QJe$R`GW0$SKpW56R%&< zE#ubJk%~!R>q3Ns1s~aj zz0n$Ugw<0r;)Z9>)KeWU1P3x{D{MqxsUvb3mQ)h>jjOW7ray^_!wS{geNN908ajS? zWdmUC^hspy$Nam!u-ySdZb>aCyMY9B;4Oks-K9pGsrDXIWms}VvaUMUk@tIl9G2@R z3`Ae?5lyl>^#Poca|4E`BZeE1S!gyX&^%WA-zz5SwS;=`*;wGuc-D^++it3Vd1))> z+$cM(5mV3KzgkyT)0#{>HVJGe+bpb|7ZC$*?peDm=drC6A)3^(Y)vCIJmw2_ND6zK zu#HQ{m0R zb|%Av4j23fRpQSVwpe{QU!Fw z!XUFx)_U_B8tV>&v=eR(h^tCt~)1iL<%W*EI@xaU613g-)_4Wg^*b7VJjQ!YRF zd@6UtWB;|~IETG+i3-WD&BIJa(!7biC}dDop*m42EWx+9Y2K)-BiRzFM*4ba`p@N6 z>HA$~nlshWQ|WGoy`vv(`WVmC9SCsX%&aG;Nj$&zGw)BKoI!|7hHHg;@c(&8Op$~L zwa)K)@UH+rLGS#sQCn!w%ARWMUo)h2evpcq<*_4&9cE{oFYN)p>&?Dq_k~ zPiloO;u|{NwNwY9KYyXDsBmRP^p&*PWpV;$uDy~(5xncjP8jFoN&rI*^fz6!<11!f zWPeN6?E&!8TdL_Ii3a(nNY^{~-XbIlf7Yv_m%#)08zV~|65qhmNyDe&!LBA@mC8<0 z8F2Z48_}6Ji=ts`pN7G=i3d_q`ML!Sgc-qg;b(gz#2(Z&{desCfo+`>lYIE?9!$j! zAtr&1=$$>Xb0b5K=nm)}IheGih@6nG$wThLo1%Ei5m;$eouc1(%6Rzj>IP6QOj)Aw zSO99$)isL|5BpsqUXw%3>3p;vUALNl5jS|w)qZAXlk%)z#r`$Cq)W{+;wU3c)9{J> z0d-P=B>bH&QlHxufvI{RMU~_Rbp-lXQj`h@u!$h-^wy&PfLHa1fHWu^gWyCrQJ)+_ zJm+WI!al4hl05v~qP?$9p>Sd!k-WlXS>RjWz(Ym2Jled;?~eR_Jjz_|q_Fv#+dL6A z+(xtC=qlZzsBy5ll$(;N4zN&q@G*uOI!o3WKF;nyfmPfNefjz1A7Q@Cz^{Ld%x}GK z1?00mVWmg^r3`g|^JC-LQ^4Xk94mnC<>RN?wI>|L4HtZ@V9#N)1O11!x&5KFVL1vM z>f=jY%Zm(e3g=~?4mXz$vXrekLhBdh}mOuF?TTPy}_P&AwfE&9D8JCzh+yNV8v+f zlQjwrFJg%Wc+y6xe;hgstjNY6{ewX9!dw2WX=)-t9Yh2L11`-;Pp&556>d+YY*V62 zNrc1R7Xh>e4TFJ}Ggoy}73a5gLkyW**1OnptnZYs)s$5o$KVj2PAU2{;3DlNIcID?X{r6`-8nR02 zsC8lAM-aBc`QprkYg}H5{d7!;KIF2RZo$yMY5HUp@$+>oG=%mx5d6!3B)|_wG-|g? z?()h@#Z$8D6S)Bt0aOX*(}yD^c^+N$NT^oI0g-8ZzNFAH1+zHCn%K(;V>9`Qu98_U zBy}&IGh4K@=%?OtZ#BUDl@=u}=qMn(gjrWr(;{$@Yo^aQd9TlOAf7b}d9M>KrB*Fi z+l=B)SjVB$8HxIOIuQuQyUkG~Ru+yZ^H%hT@q{;lQ?A6xRYm-Zv05K?O05R~RV0@W zhXgt#?OdPxSXbqw)o%7xk*&`tp08T4W}KA6Ou&fB#7}oAPQ;-m(6>&ee}}=R{jfV+ zu#L4D1z-(B`kG-ToIBxq{yUKP=!_VRC;)_S{es>Nv%wm@U5s$yLz(1s>T9eG$kn>& z1L|Qzx3w@py+KveWOAn(0DV14gWMk2i8FLO%8+ zjJMy&Yg;|OkzvJ&*O#TY7W&m^Fhr;%7-(?wFd1;;F;hsYf7&~^Id^RQ!)Sa92o-EO zjW@m$&SLh<0cF!{b6SAJQ&ytwjJp$yAYYCrW^!A;X*r7?J@Smk#aBZ0?uk&clG%aI zgX{n)l5=23t(jl)7Xspovu2!d23lQWX(%N4vyk4LAC08T2 z%Q`+f+V6bca(*sDZemKSrlQiky`S{CAnZX3-o$+5RCDc!82HO2@Ocx7)53}qHKh-r zw(CC=fQ^|Pn`|iK#C;CpcXH%bY2~(?Zz_<95&8(o!0=|!`tEXM_!c|J4SKiZJSg7J zO*fP|szHR1fP>MEtXIf?{C=w9nhgWvT~sf^8_6Y-{fg#NO+*3$5clMTp~P_O(9n1p zi4pnGe`W!wqJ@6qFG%~k?^JdRcuIRW$`9sv zcn`Jo-|EYz@OJGDuHHzJ`#7`YZzln~if16rQ~_2GG`A>@M?DNJFHQtT7>`IyRVtx?pv#;ghb-Eeg-1)9J zK}|VS#8|UBHYQ@w;Q)#{7R5VqHW@C*Fw|D%oZ@+~E{R2Q3_p4iA)WX7=VKJu!9NXi zR?Lv9ABWaUsu`sz2IbXri57pnJ#CAjtdCG_47S|vdxs;MeYzllAGwtcCQB6W!@896X1~5BuOvtUC`gT_s^rNJcyQkJ4=G-gj?FzoW>_+RT$1o}l79!@% z@bSU10z~ft#R;B|k2yCMmcFG^w7IQrSU-YzBLCT8Ga}CJX~Fh%iu5+z>Z5mYF}|CS9NI-|Ju~Y{v!AD;n~`@=EA*zsW-y z06c;tv%kI@Gc>=6%&5Mt&)|3P)`uOdTZ)ZB*~@(Yh2`1rELkP;fIsYXo{sF+h^P1n zld_R5KSz~TdF`Viw7LxNU2)H+sSm;zP|cmj?zp=VHpnvH@?5f}mSxHj5VjHw6KN2xjl4xcJ6Yr!Q9MWE5*W;Y^Xr{!8)%apX99FBgZgwfe+A= z#dXr8MlpmAz!-k>#LI50nhH-gX;KBsXa*(Sni~IB*aWad8jpj!PAGF|LoKvO>WYvL zmDEyF1e|p3H5j>zNUMXcJbNn~z4w&^#mP9cfUyP_xWBq%$`mxYBczdX;?%n>jOSuQ z*_`_eE}=#CF>F^#0sc4rr;}<=dmTbrNkA?YKMgcwGzGS%1sH*(M92hF20W?UIJG=1 z#CfJYC9#aL#zX5Z27C7SQtw|wRTZYgNBjJIhn@;FN2&K8L?m_=-sHz_M9xDuV${V& z<-e2Y!x}QIEwlob_x6P*&Q5C?t*8Cw?(U$|^V@={b~CB2T)J+SSesT4JjWl^jQP}~ zGRCU^qBSgs)pdF2lBSko>q@+#=oTfzWqZ7NyB;1>=pcQ4T6E#AJ_<5@<|*mqyfzKp zDaj~%(lR`#GERj3Q3H+xAZ#nGYYH`9R4m1PMa9DEerOZ$4uS4Ap##wkd34sSFM7wf zXZ+@-GV>YF!%y&0^Cm~Yqkw3TeC*_uQK0=d$<8~F+)Vxyd-GTT#c8}$tGmHvyVk38 zcU_Rk%1d;=x29}#K4D@vq}Cx6XfC#@)eNIDD(NB$J?{)a<+b@sb<4g1P#otNTGe;KreabCv#7?xlmDoAwtl*O(|y zysRPRmRG%?{O0qJ6&D*-(0!F;z+*_Q<+4}In=z<>S^Ok)zW+X}E?u;^KYf$;NKvkG zA9Qh7mS=hVOnLr;qmP__Ob5t$>H-6X`k)}$qI65l_c}^?nQtViiBd$&H~}$p3F;yS zUid40fA{-Yy=vs&-14nGo+9rYn}??5aQOoaOZ1jY3;Jq2!khR- zs-6ZH3{`WNvHSz3pehHd&^zY{PsyUh%YrqoKL2+0-?Z2xR||y(%_cJ=KO07j@)^tb zcai$<3hmN$FE3N6<}~ao+9F!>)716cvYKPZLdAbFRn=_&<(IilGWZ=yA%v}Pm9R-! zgfCmotT;gnC%6C^^UWQsJ-4;;THY~_g4$B`jfGJ?mYT!sCRaz=@ZJ@z0IMr!SPjk{ zVM65b0C%Q-@)Frf^_;1N{h-!5KXshmT%PaZOpAQfu5%72639MmkPNSiaG2AIWDUL) zge(N0uUQ`uY^SBE|MK8uJv;xXbkxyAe`fB{><5gL0J`(5@y>OIII?o)n)~nu9;``U z@NmNGenC`2SLbFx2GWRbB>so!iUcO2lVBBE08ZY5N<}Q~y|CKScZoT4L)F-ZI&JE>%NxWP&j58G zjBGUPp<{#|7dLw|$Er#Vjex|*oPYI=&-;JflIjDWMP^Q@?>+qJ+DH%UL-#>_qk@a1 zpB}Y$bpP!PM{E!T-~7#w`acIaP7-Yvos+h8fN}uP6Dd3`1$rZ6ml3 z?M;STOK=*+9iIe@6=jcROa_)UCe4c$LOVmy?cKBEV%9;y*-}UPqy{Hgd)=(jve1T{ zy#md(4$Wa%4!R$w>?rGF;EvX*Oo|fidX6n@nm)^@TGPeN{$-sapp|}{#t)9fY^XsJ zGq56X{>lF=2$I=`1OzyYQ0QTNu#f~82hk$Kb60MBlkW0HP0h3wXlIIY3vy$etLEHH z>x^h8YdE|fre|%rFdU^h(R!M5<*@Hm5($hcWlhsACFV8zNo0^PG?X;B?15kG?E8sN_NN27mMlWpP+B2=_E>4xc-+a)C&DNsx%{kWl zYD`=u)z)TABTxg#8pM0HvIDr+n5Y-?rm?-s@|Vxe{`CZ6 z);_+4B(ozK2|)?;)z@m1W-Yjk(C3NZ__>P2obNyB?6!S1;>WLh>7H4iGGd!ya39gY z66^icI{vwr-Xe4$`q0|h`cOx+ppcnb(;nPiTR~tXYc89vXNW1GqvVx9FN&PJ!}i>a zgN?+jw8JrQRSTr-mb#S)^mTr8feh^_*f7==5VTVPAek%V^o=He6XC_Kd%!H)L&Dyo z^u$KC$v%GK?Miet+vCBNzHe%iL&AJn%f>m5}n}Yp^?%P+4<@`0!_SaP2aO0lOo4KjetDQuf!bH3~8hQsLV>L&%1; zO=OYgidQb`C3>k?dlE1=q`(9585Am|%}7U%Cys}+gLN}vBH<6A(V0Wy{Rn8qikn=) z%OnPn;J18~PR8D7?l?x=2g!obkcjRPtqUtNwJ7O*V73K+Hs#q3=g2bCQKmLE`BOzj zR;a#3C3P&!`4`OK1}$c+dX`njsK$_VNuW?Qy0{9Lz4H}&d$v+h!|@Ddq11vAN7%T5 zFc(a>s1k8+RsrHduTk11pGq!v3?;{E=Qs5xbRPf_qmF3DMKa4j;L$66#E;4H$31(X zUM{oHq%ZFsWqw!eSxe4jJap=v-b8j3f@uKI;nFg4%K-qiBE}Kq7!jRzIQYU>?st0w zM`JnfI#d$Cf)Jn$X5)>_H@t|fN!|hTY<$>rcy^f}nplYE&o$ku<_(!B*l3oFK(hY0 zRJ>5a_f@I;gVp8pM3zNTaMzCZ(y8C0#2X{37OBR0_K|hNV*mG zWP3@%@1$R4&Q)$?hh4nmQTq&3Z_Df~9Lc7oj8tV-gq;Hqb*y#7cm7-pezsY7`GPdV zK{qpy`*14)lT`f2QQ}sNW$Ak&dzzS#-7fwq^VufOgg$RHX3!2K$z12h(HH(x+u2mQ z8Z%F?J8xBB+AEopVg%ltq;!S^GyC*>&CJG1QTE>>#vWKeMtZ zSJzXWq_alP`c!>pinRYK&DFuX3!z=k-V~md&!=t+JLP-7MK()z;wTlaRE7QZlE`hv zQ$nMq2;hbsAyfm&{tjGF1kLDRO!HgeUnpiYkly5~pLwIYA$2QFahJlbs1>jmpWn*G z?ma2}>4}@6j<^R7i{k{^TrWg-fW+Rhs7B_fW^D)keTEWUYc%vUDA@6)L9#o`ZFrM@ zp$1vrWgTu29s^zMceLfhOjQOj(}(%|+0Y`?fPJ~u^21I~Mub}I(SC}PBcN8B7DJ+d zRt#ozR~@lbFva&x>A3AZAnYgq7``R~!GaLb*wwMxnFGTw2Hu#5WXL?ob+y(@?@VR= z-N~KaWxy|4n27SL*sm?`pP~d z-D0DuGMry!%(3Tkho9fa*dwKZ6uTJr`#?}!>4;A)Kb{W?8xt|Gq4C-H{Sj`sSJ99rO8b^%m+Hyi|#vC_+!AZ-!; zb9Gd$2B;_`z8E)5itWEVk9;PlDmU zfjKANRAOE@MkD*)H`;Ox!=#TnYNdIWIb#KtAPLqBbF@Whw=2#U>i}o*FMt{2>FkaU zOrB;YsWN`(7ue7Rc3(0pQ(e0=vd{f^HHNlsbm$=I2k~->NHF6BX)#y4Z~!`UZk~Tc74HlG0~;_GZ31DYwj9S4d&NXhQq2_bhxA@A@)W z(YV&nU^e)e)=d?6XW*S?%}*a(Y0=?DdHoPUJpw6Okuc|^M+Eao;+MIhqR=H&0H|6gDO6fcNuHxY%(BW?!`AAnrQwaDuuO;Y8%j` ziPd@{6%JqrByuM{Bm$HsgM*lkTQI!V+r9k(o3vZSwb2%>0O`H{QpPGoKy4jPdh{8r z%oz}&dYuA6y}JAvH}w# zT}0IK1?rsjX96ld7Bo^-gm%a&IrY4HNeH47TI#Aw==;mDY~#g%u@|KE^>5J7PY` zh0qH=Cf@ZmIXinby~!}1k18zZJ{@=>76*D5IGi&FsSbCtV3a^yV%{V0!<^KXX7;C) zqqw=kj(WR~sY+Q_oT@oby<(1!w?JQd&|i3<-Y^poWSl&E-AG>^5l2L0vk9|z-Hp1I zK1>Q5F-qDxF?q(d`C#;U9jl)}Q)@agBM6-W>iz30Gffzi=7c)#2qlC8E#u_A%58ng zAz=)@yLDZjCnm2X?2U$rRRA2KhIq~=fw*c!F{PNd(q?&L@p3O6t}VnR#Khki1OKnV z{Sz-?k(OeCDu$q89rT$w&6+vnZ4k>(;}kF8mmuNTP3`t(Q+h6i6v(U{*E8Y-dD)%T zdhEkIM@m-7XZV1U4KjUZJa#I8#S2_v&Tla zt59YemT=WV5z<|>B3=F$?LAkiOVP~-gQYb&aTEiZ_pXBL_#Z8Q`lRcsEU`RW>;C+6 zc>hMW_OiB5Tv4Rh9*(pbJda5BsZKA*>)buLHR21U&Mx*G|BFQy{SrDeNKsDDJ}9CG zUv-BaSpNGM^SHe{3^f?D!r=&eX-ewi8z`fmu^wNJ#N@ckWef7NgC+G7Hv}?Ob&%p6 zTlojwGu|1@pg2#Gb`v-ye_Gr!`l;BN+dUI3`7Ihs?Na+aeIhMP3F^}B>>KvDrRB@f zkKV4I0?Q7x7A@$PM&B|NK`nG-Yv(%-0SKZ_xEAWhG1V$0;RNyI#TdDfKTt4r232KTh zMm`>QGbOoKDgMI+z2hh*a3;>O%$hkB-p8-We&>t4c44gMI)43KY3Wk{l_FXDQtyQ^ z-gSLYi4s>Kevv(M@8uyw{m{01Y|i+r8&_HW)p}e1x$o1t4R&A?tOG23`4r-Btyk$I z`Vu1oZ9yq?X2?4sM{MnHCsu3g$ByzAE>kc~h=bI^KbDd%&m+1MlmX-74{^LAW;*B@RLU z{UqTJ(p>2;G^M3XhsE7;dM&dhGu72EU|C>YmCRA-k_HREwO*uaLS3X=9RIYm&HHQ>z4iD=#?EL6H$!sj-4`>?eRhZW!k=yX z+FsZ?W#rkB$I5jt=u{{a{~jEFjWaG?sCU7Y-;@ogr}SpUizi=a+gpXphrDyNFEhkY z^{GlMv0B0htBKbO;r)GfS%G3zU`gas+^Z<7VvzUdh50*mI3@z6_Z$nV>XFW;r&}e$ zi5*?JsZq?|C1Gsf{678Yu`ufa(I0^ZEo>|8KSg6LVS>YR+k2=k@6Y>xn?CK~cmIcN z0?A8udp!H^bV(~R9n;#|B;oSiQYZA_Gq7lY30*h`#{RQ-E!?|051f(X$^hHlPjeHB zQ2bnZgShP3oc7bhn5I=X+qod6E02H$xQXs}M>X1zsGL(%mnmLF8rn6Ey^qGkybJ!0 z>v;oTjt^UiOH%q=f`6iYS4&Dk?uN4~bfm3#h4uHxTNX>);s%KZqr5MnQwz~b0lOb{ zm4mzLn3z`9nZFGyz{vOy`+uB!5pQ+_?Mc?IGK>ZySczKT`l!I3umW$jk*btc;lXM? z-?MX#sIRCO?Xl)1JqoVXPwYP_;4QgrUPF@BD zG0esz_e#`9kxOsRq3qMVbu=wA!j#}Dr7au|IgrguR|+o-ur&_d6Z7ZvXR9DT;5ZPZ zeV0X`8uc>!31chi@?rB~jXvtW3>NIMS1SpVL@hly&aL*XmaBhu@r4Q`L`&y)2Dp!7 z&m(fm1{9a8ne7gNXzXb|VrcV!yE<|v4ktrkxCZ`~-kf>^_rsvSLpz2wQfPa7Ov4RL z>1TFtw3r8So$ZL}o+h6Thwu7Cn)T9Ovc+2Wm;!QE6e{{#&I5HJYW#J9vyT#=uAT=; zM6vbaiXIURD`S77gP*~Tz?9Iy?*{^!|N&&?M1s|vfV!`WG6g?m zTh>+eP4#+CbOM>A$_?WSAMY^K@s-K{%mOqG&n$OXG{1?r3i#gj?r1=JbuI}twfcrM zcm%NpeW&=(%NM?%koUzU6Swm1rBP?=XQ=v*itX{FHy0HD9x_~pk{<>?<~FV8ktp3E z9Gt2&ZkOqC_*;Nsyk2(0nS~!n=v&20b{e!?i~Mq9{hfM)CBNw&KorkPxl?)&0p11M z9LC(t?cZD}jT8h7W!Fn2IK9X^%)FU?NCt>ckcwDfo3fYDb3nCd9k9Af$dbY;Up*lqrZN+Trf@(TPvJtk0u6GmM?JucPrxLGqTp2z2Oqr%3 zo>Aqpp`9i)Mtj@s1H^sc$+2KJ$CK7^B`>Z(nM`MbagHm01VD*LZ*{SfQ^<(0%$8>*H zLB;KRCe&*?=01UyhkG>m&TQE=cC(*yka08j95$C6AC-NX3zT z?NAF~h1>Su)(o2boY}OjCjU;cQ5+Kk!5rx>m41E2183Do^th+&#2&N1q7$r(ewmodDy3Enn>EAb}lG0q##_=qx zvnkH={U=_mS@_q7N*`q{T)N;(Z}Zc!2Wh$beL+30VKeDZ{P_q^aqI2$>2wFE`Xvlb z;km2|&h@^sGkh%*l^eKBX}pR&*3uCVai9}CpX5&@Z#r@K^bmS;1RjDVOQ60A_XymM4^IBcx8WbP~SZvdZB5E6m zB|nnWhaHMW3)pZbQPrt>-;(%}qV~%8uA6zPHY%Sp_prSS($tRt`xJ4lXvJMheX@Gt z3qMie&HA3Cx$rzgqm9-zOQkF9LjM z<3k>UcTm*AIV;L+4jZqY=e77JBDg&y;McY~OAIgP3}k7ae8^+1Z=gYL``TM4$c~|j z`ry=ED)AzH;^PS~UUSpul}Mab(GF7HZ^OF*uk|q%KUXq%IMx}RyuNuxO0)VUpd6kY z(Kpy$g#v#ICQGg%O+X07n#pRtidQb-*DbVAiLWpz%-&as+Up{{&wgvZ&ZD2o+l$(c zzy5)$p|cU@BJrWqDXJqeFh`{oz$ow1%N>C?;NSF^z^~0=ffM0|~=LK5|EDs%rFn zhim7blZ-cW(m<)Mt#KH>u{fHx@7k5)Dh#eWz{P^X&f~2n4x>%1j`Su4B&Uz+zpoon z%!3rI+(8EiEr-)df=x5I;+8lsCvj-M4GX@Qb^n-mogS`6DRZi{<(LHC4uGNM1yNgh z39zJ&#~F%gByQi_ywojf43R9q6ND6qb%+!=3{Z*U05xXP<7$?EGZS|}2!T*#HFUZw#qXhYPu#+7zq-b;GWUI-3cDt-2wy+BuH>~x8NEG z5C#kG3>su`cm7SD@BPokIX7G}vwL^1UaP8Bbx(dwJz<1YyYR?n>n_dNw$)1Uc7XBw zd2$AXy7z1aoa(p)tMu+aG|3rTkMrZ{(;MU;bzavqG?%0LXCE2ObZ+y+ zU~bGruD17h@B=`#WG4xr;aA_0f{-R!N7=lJ_|xaJ}g_MPs?H_CMCC4#)!=StcBjSmqjWbfd z02(hY=KPUZt)aufokY|X5?*+AQv@~?XBdKaq?q8E07XuxX|9i^nlv~FR&XV72Cuo= zYjg86+dFLDIDMvF65Sc>aiNdFWl_=`YTzHuGY?lGUO!^TbQ_a(jCMrH_>X>>sW;1d zjU=5Agc)J0rY0hTbp*P}mG`J+TBMWVHCxJlt@{PyD*CD~RpKe54qB2h`ibBNMDo9c zA~PAQO*N^C6I;d4Mkk3IGiAu9N_FxmAB=3Uty24!N}!*dA`1twu? zSbSD+P`^g&K}A-+u6f-e#)Y5IDpJVvb|H|t<~1n=>QK(Z7+ngbEqcK+wRi;xPwaIt z3W$Y-1MfiCDc}Btf3!pW1(C*mC`aK$_(b`GkqHt1mFHXTRAc7#!qtslmA_g;!>g7; z9N|;?G+>orc(v*|Z5E2@=uu`|x&0{Qn2@E7_xV%-$(am_{}>9?4K^=XOf zlC4{Dkm{o_JH8ebFH_Ss+;DY~XzXB{)&)YKzB<`_^SzI$g6k0vzVNHqJ5#2%z70j9 z;j^-5Md~6^gf8hT1P2|s!}150DXa2(J4B;@81tqP#rjWO8wvsK2>OtTV0@X~WWXZ4 z;ckz;))N)@OI6VW2c%dPJ;Fx4MrU2Yzooo{5kYl5Us5$NZD|D2%2PewJ$&#-Siqaa zEvfGFp`vtYbj`TG<1M5U5_Q$+DFz!et|6>Lc)_yr%>?VH`y4pyx@!(vM=Pe%od22{vW3F5W+#CUL_ciX^{2U3b^#n=T>e2W5p>LG;%P5!A z7_6cGAmzW}d}X|meJOu1kG78t2hDmjht4FGaTvushTX3fKeK|SQAlAb5gc_a9aWYh zdu<=Pdc2%P=hc1XgsA7X`3|wo{<^N@{m7z#^XSP5ajtIq{&`A3BI)-3csOM-dtd*5 z@)mwH^`&(Wjj%%~EY^AoASTX)PtkC0y)A#E>{i{wx~m(4{hRNA*Qs6zGS^p+Q(kOE z!bqVa!@eI{w@V{JuTYTk6zR zW`-MLCP5R;6=&X*zto!0E!V6{+%rMkpiBuFHGgzAQJ8ZQ@iPH2>LS+sgPH9`M({D* zp=5L;-$C;WT9$yD*IBFA{Yv8IVj`mph%(~PkKy249pgAv#+;oJF<$M;M9i3RE%M+WHBcdG*kcy3jsSYW_bLA)|th% z#F#Qv2Ao8@rh8}n^DNNdbvvH9Np^Oa#vP4X;7s4+5=K&_GsOvdH;LOdUBWB^{ZhXK z$IP*zD@~iBXfe^)FPdmJ?PP6iu&AL6{phY`k)3+GuQgKlnC*{EZx znTgaA^zsAzb`_fX?T2y5nTJPeI>0VELDBr!bV`@!(Q`T@LrR&2}! zAoF8Mt~AafWc?Z0v^0&39q_Tm=IQGCMw57W%PCF<4xc}I$`4wGm9$mbz&Wdl%_DP_ z_FYB|oyBL9n=Dl>A?oXW=E%+_!3q+~MPEmv%43!AG`vMc@k4%Y)USMHqaEQyO*@Q2 zp+QE*93EnVHK!r`EV zS-)T`dE2HIEx1bj^}8=5dbQ4N9dk?O*4%r_aeV};Pg_jkh2Gk%w=B!GAc5%2|B5!ON$%!#+=*GAuiqG#6PrACTkLK{{dFEUv%_)q^9I{A_ODo;_p@??X5F zA_MCIYCbcD0(KLW>B2_F4WcaoQPEu0^42tq>-FhT3*nKz)Y&a_noY1#ht90OGgS-< z&pw#_avk0Hhm)~NCQng{LF>JiTpJ7BF9}ywCSa@M`R=RVxs+@QTB@NXafSZ1|WDk)ozQuQaXu>w?cn-vDZS58r+q#oXUmo}l@%hJ=|qXDz1 z=I!}w9bfZsbd~uni}l0=Rpqm}VBo+<8Lcx@BYDvy2P-NaA!^>Yit5|C4A!?kF&=_7 zAGk^1IUKk9!`=|Urgy}?&}fsZmo5VgFnbHT@{=fZ7NSLc zY5yGc8X(u8cF>-*dHQ#(_du(MMVFR*Y@fIo7B}8=73FAqiy0lctqInB^!at1`5Dyi z3q=o4eDhB4$V=qb2G|2-&T*i|9%Z<7UD>~PSvv2)jx_-|MdGA@&5uxQoCoIBs%k1e z=8(DZ4!^q8R9gz@8ji#$Wyq~!TdC$lc*;J@#u?km*(^(9kRCI$aX*Ju=|9?3Y_gN> zcf?)|jXM>@?B1K$QMSs6Kg!F1crPrRfEkY#@t~R4v)65H7GgW@q%JD$w*~oz2%54o zo7+6FSfqzRBq>de?8VI+zeaf>{;`{U2-nM15Z@f5)y2O!5np_u-|m|}LipC~4&>$5 z7UH$D{!&`fI1Vq-9NlMtIF36yJu~_OQy4Z)`d0jJ@1Qj`m8GS~=sWzKR|j!)S~^Xg zx4nbBBBuvzS*{*NMl1Vf0&}?|%KP7{Pjq{>anNVZK2h+aNs27f5s~gR9>xh-Xe z&u5WhTEwr)-A}F^4yb*Icbl=jB_#U9wI1zRO+;3!AHQB29Hi;cu#OuR4yJr}b$ToI zQ96-4$ga`;j55tfW2;P7T{Qk{Y@rX&Dm%t%YKPgs^ak&GvmW7g)Jo+#|HWFnQuilt zz$=v`Ne1bD{)ECkNxQbHslg%Fd{U>zbJfRsAf7_>LK1ae^!ZjryGkFpoj@gEU&Fp( zlqY*|h!;2~AvWxH>@cy>#7tRBaH5~b)lF7*E!Q>FA0U_zbd1sb^NBo1RLMAoXOG&$ zyQO#int;nTS!bzoL(A2Pt7r%GtB)ao7CRvjRefM9n%jm4SP~S~4crAGUV7+XrEewn z#F0dGVV#nM?(t0KiY_r)!xd?0Gd=6ad?T0j>^@A?ZU~Opk#j5)p`Fp@Bc^))RA=@9 zT-uaQ%_=}vxHUO1{;dJ>SIebM`1{-uyM6FGyeC>L*v|^c%f!}7w)dYG1SV&IRY?*PtEuZ+}qWle9G?Z^yZ>rStW#|1rpHU9z6zDnn_pu1?EeJO%}KdX5j?U~0&J8XusE^VI|<7zMj74OqtRsrV7?z^k+q z9i>kcCL8z5g;^vcW2>vVi+So=ojT2;=(AM-Y{$2_ZNk^f4TI0ZhC8Ht zzU^HSok!vR4l8kWP-efHEe`-DS!a#Ayc3;U!JE3~zAF4190k-) z)8gKRZ%NsEmX!%)xA-T8RyLIeg$8~^!>OzP$^F*8jA3X+e+tSe{Lyqmitc@so)OQH z?uS{sg${O@JS95u;X7xgiVFD8880t4?y}_H(HG_n`u~2H3a zj;GAe7q4U;*%tK`AN)Lx#sIf*KYKCjKQ@*)CxFUfgl_$FkWeF4azUet-!12A*-eEJ zEtc&n^V;d0mIYxJAq;{03-Jj^xlgVhKM%i%C3BYOl@J|wfDCNuh{ zvmxYY@B-hQ?H2b9_LXaN$Nbb>z~m$3@sY`4Xxv=I=K`<2<{XVXA{%!jU@7CLP)+D< z_I;alr*I9taCLVOCQpu`9-q-FjwRyB5O~6H*Rs-E6`x_59z42Ucyw&ZWZw3l$^dcL z*MK%dVT#&H0wyVS)*}YV0SBe z(FD?&0zzT1QX`md1>!Nxs^Big%9)WPSCo$ zZC3JZDLkgscMeXB?kmtN(Bd@YD}&&zmwcl&BCYv8*com4e_HSmYN!#}<{T*R+lSI6 zj**`E%N3483_rO+;O2n&sVRVM%|Gg8BA#{poeJ0uZ+-8>l`xs1TAevj=mpVd&gh74 zye}|pKeAEof2YIR7#KT+6hqK>j^^O z;kGd#=Nv%tX(^YKn(qz}PVprI9+dpzu{aaE{-hjKFpG45$vjkY-zw7^o&VHCOo-Qga%vSlf;q^6@iD86%BmFwDp z;;vm=q7^Y9%Pn^ts(Rcf?mOm~4swdnxC?@ti%1lpQ==L8#bX5ieonj#zz!sog9-yg zVzfec;J=hW=L`Cc_80P)<&{q%&BAXrlflWyS$<^LO$?)FpWD(Mh`YmOy zxdy7iG^ZW*h$ZCr{yXdEJGV(lzz>>uG8>FXVNbSrhVS=Hq7toRMlr6T{5#(VpelL7 z))~C)CG`ocQGMJ!xGLrjf78M8BJpo3YUa$L(Edw~Y@$|sk`$o#J2fi1+-9j5vVghG z-<`-dfExjDbE;k%`Wc`_x#m%+_<5lxtWk!2YFO9G;=iporL;3!H5UItugYAJy|hM0 zCM*Ce8$jpg()BN?G`Gp_k`6!V9_V*C7o`-;!@d+OEMm!}k$URq7+bJ|z9^&c3pVl7y^A6zGde&PNYD!)2LxKS^w}vY+fK^NNvR_j6JhXiM=U#H&+A$WF}e0Cz@LIv^UFdHcKHwl z9C+7JF<}H+>-Z-UNi{PpGXcQXm8P}(V-Gk%bXO=>*fn~+Nio#6O+zGR8`&^QVHQJn zBz@FZ1NR`BYy&&)U)T{{7BIcr&C)AhURUwdWzCO8sPTwU88PtKvXXuK;iD1iMDVam z$T*PwV})LlLMnD{m!5*Lomr3$5hL3e9&IEC57hyB@L3bR-Sql9Bx1u9Zkoe~Mziz| zR5rh>gK))E=h7NT82bPW=ztOTnVQ8sR`hR}g$H%fb?KRd5X;rHO460AJS##1Abh6) za(id2wKV=qK~((4?^NeF_r^368HdYYS#PfQRW4kf(z*|}c1*okcrvl6$A^TDU9Z&v zLQbsw13KMqz=2UxjpfaiFpaaRrtJ^s$zB-tMQy{$`1vZ%!RQRY%&tI`W2AH4DY4!D#P*{vasn zKULR8;Ln4}+f~jItgovcSIGj6pU98DY@TRneIGL}j~D}NUfx7@%E^UP3<2|px+~}W ztmbLosIEo1fduATF@%u(KQDk50J)a5>zxp3-zqvM)uC*LWYtG>u+%Q%&E{63^?=bc zysg&VhtPB|JQyCm5sP6oLK1_kRJAFY;2dKjwvPMoDk}7B$*90taQFPZdTyWU=VSO9 z6+9rp!-;T^FX3A|eLhDg>MQ+fEZUa%Y{V@x>whJ``eE16s14ZXEzDSI50nooV?ENh%5VJ*5fp0!0Q0hM+P(!j*gAdyqHWFbma_QAO^Upw|YD(*N zbe3i5rDi^i0k~*6-&Pp&#>Xz0{hV&7TNu3w9;;E}h^qH$VJdE;VI@0s8-}PR8%g z2BOX=YBs#^lH3TWYLco~1%=+!a0NzzP3GR5) zXvVjHjBw1$uQK5cx&LB!9a@G|v>$xT7X@X0LzXL; zJFQ1(+Jhs2kAPKyZ%#_V8P_r!O%*4Qv!jx?6{0S=%Zg#QvWTR3BHVC%X9)baP2Z&gaDKb@U0k0o!GNU>loZAP)$iPn{9a-i!6sAw-gN%= zvs-OWF_5JOUqD$gCrxR`y7Elo+|iUr8J8 zz=z1ZwBjEM3}W{rsEbryFXNyNc|DBv6LNBd0gYp16-LFe{_ijZHs}GZ$-QVJ4nyAO%*iUifN+%dUss<9 zhRijFO?B+1ajF73xjStiahTL;uK!T{P4)0zxuL8Kq&S(9%YOOyC!mgAH&}fcGXK~9 z2!D=z^F?dO=_L#~T_x4;tk;UXWv#r)?5^IdjH92#7HHmHTBR~z{F|ssV_)dj%Ezpu zGY3EI8cmvnzv62jlLYn2@>>^sXHyQIZk9CpMbv08?~?y@;rhbqbKqCiiqw*!z*Zve zcIBYWv49u_NrzDZt=c^=k%822RGE_taC0e*4GJvUa5Cz5!Jub(O}Q^~b&97i9L!2` zKQoMm1!vlf3Ct&w8P30c`!TNb=f3a@uzkuoqT&vE74{N;2*MY{(!RLayx;{3GO=qC`~X)$`|md^p)f%btsKTQqGy5>yYu2LS2iMy z;$&dk9+I91v0xGs<%CASzM)tR`0N})YyblS(Bfvd+5+16+NRguvLc5bl?_vO-(0;l z)*rl8-xv>a_P-d-Qu8NT^^q)@$R1T_Pu4$XDbcHJp98CdV&$hzkuO)Jy{^4h6zjU! z0rFWm&h*8RgU+c1;$mSqAcHvrcc!$A5|0vHQqjXg4iVC|T0}(B`fmd<2{{cZZH-{; zDKNpf-EQmyu|nT|C`;VJ6J15CeA5w%Pnql&%TS`=lF-`lf&)sn?urhS53C#B=e+RF zPj=^HR`_j)ehFQG{rFwC|8n+BMck7RM70HOy-A6rZ20)Iu(N8>&?{rP=$e683EMfxN91u$cMCZ>;$cO)Ft1 zHF0$3#vRyXDP++ahgp+ADB(Vck+YN(+2_-Q-U z_qUi-aC{Lu7@tZxQ5P0BBv+$JFHP_PW+J8S2l-dEk0Ao4c42;+w!iyzbaG{H#k6#k_a*_F!^;}Hu=mss)&GCddzkx3_T<+X*Yh!)8&F}&uHy~ zK%iANq9X$uwH#+#bqWowsb) zfd`X@{|k1e-SIW3+WbUSOSH{@NFT_=@@qywm?8a8FW~o)rAcmW+bd=J(uBFkFIVro(~Px&40@0%Txg>Wb=Qdna#Zr+ zIJ{w=y#2Wqi!Ps${-d&;f(3~JE4G;{6aDbRn04*`_dT1rZFen}!h+m3^{~%?BLDTc zGck5gj;~DAg|ztBC)dcA(j(m@D<2fU@vCCX0x0N!Pry_U#?uxV?{9|9fapt#LW=?5 z0YXaM*}8nz>z*eun0YiI8EYpp-4)~B&6nc(IP86ccYam53JA!Zy$*16Fgt@1Z_Wiv z*5AnOW%aCA^}fFqYOE3kP%Iq=LB2nRw@k9MR&|B}v)#kkXle*pxoCk9a|rF<*07)W zF6mEEl`nSBollQ#nEo;X!|Yz#WE*wXDi%BzB}K!YSVcO zXw!y4ZqXtDhs`YcsCALK|NZ~+o7;r_Wa`gyhgk=B<_;S0v~Duj3pyJB%1szbkm9TD ze9~X(72u;N5dQ>Jx47kni%Pt>eMf8CEePpYa16~px!d>Md0%~PR+}yDlTS(pwwD>s zI8!DIk?8qY^0yY@3f_g&K~XpsjiNjYx-lm}2YeVCW?bm~o%2e5K&Y3!|Bp&}MH}r3 z-6k6eGW-%MSA}zcKSzuVSlHnVKp>B?o6g-Wu?&A_5&-!QTMmlXl1W~Z5YQ0^xVTeZ zRRbpx52eA7RV!~`aH-f<(uvyNQ6u;;%#8%11(73Q4d4%Z+>k5!59yCA7H<{msuy<^ zD3%)V3GRVVn`WLQ<1Bi>zexh^(3D$bL-@DF58nv$VVM>o6Z8XR26F42SFAP+l5vSf z_5e(ltT1(AB&Yuzat|ZF@s*(n`O`paIP_%;pjq6nzYbF04wg(7f?8I}%8R}hDyKO} zOr>T8WCdIT=z_T-Hq_x4|5|CiT2gmepFGmvb{0DxC#!AQtm&x$zwb+}!V0nlhC13J z94`fHvM|Du^au`a|6~uKr0ZVFtsG9#LU_vi;~_a?hK1K7IkZ3{Xv%q5S;YXEsq*Cr zM-hGtlLi=*(za73`Lm?#_xp?@qB=ti@tX{YEkO86Ml*a`>Jx%uB)HdX>*)Rr#H6X` zW_7{>aR=J~#2s!(8=ihSbfKmjdne9QvDY<>+wD^&(cTi5z29t)WTG!V270-WJ}5KL zO?CA|u*4AXnO1=qedLn|akSJoy+m5SG6yRYv=H*4c@wu3b!6ViviPSj$53CgQVJ2G z4(R}nB0_TksmaAsuy)i}#d9HTdEUsAFS@G49dVY?5r8hs!1mA83KxrWYua(EyJnh; zW`ppAQTgis%Em$XLd45pJod)V(FLxegRH5K@i0r=^LsksO5%Q;mb_S!jP@n@P=A-Y z3if`9`dWD=$g8ouuWe&%C7gjfrW9t;1-X5h41g5Fbx~l}ht4@+NUPtqfXXD3{fCG7 z{>6E!kQStprlzsByCN2ka86=sYYsuXy*K^aJeNY3oN|E0-NgMR%|LlSq7Lz8etP{WjOWyLaVN2s$R6a6eB)v)c(h9ZMq zrYj4Q^z!!v;4lQ$9~iE%MBhw4!%{GMa)0E)zZzDHgj$CHXTu-m;OX+9F^R#BFkxcf#TmB2O^?7fEd~#g~C=$91`q zov}DChk^XL$rIR(2iW`jfl+OKOP6L|YDx%b=T;IyOCf{N^fpRPj;sHZPK%kXG)`;` zG*NEbF?dVgz*ZBVvq7qB26kdoQ7?#v0MKlE5CyTw>T{WztANp%sU)0t}cl zT9<&?F#?W$@UEQ|_IR1UyKRNsZe{$xljWiHG@2&Rvj;IQL^_)Z(ZB9K2b82EN`@>r zCX^qi6E6v?f^R)3(0DD5eLHEfT#r)~D9Tn?zP9Q9uWH?{zCPQgcL1=+fsy+2Sd+C6 zrh<%eLDMg!?}N&G+x*RF1zUfUc4Y_@u%F!f`?ff^~Dhw4?;#W^7;q zu!vrTA0y)B6xz*8HF5V^{jgHq76r_g}I(7Pnq%aHU(y*+ERw%nfU381)*3aajDN z!pO*Pw0MiBy8Y5229#<9d^l9-q_3EC83N02(pjji{;^sS;LzNDva&r(21TI$aGVe3 ze&iY0D#|DZFMUfAf%et~TlbTr*Qy!PhfDR64CPg?g{{zC23O=wa`$(=@d9 zm|&2TK&||`nW5uYOC{)@a6I-xgsg9<*m_(0KWCdR40&K|+Aj~;;epX|<^ztz1)gNmE#!#k;XDwjeEKO- zgnURWXgsD?J}kpfH@p_auJ^R=wc1}Af2j8iOkc+fNzS}(MKyEsD2-G3UKF^a`TGsv z4WKS!4}p#uR1S+Yefk28`#ao|jADSa*h238`&j5)uIYyR{|kVoA`gMO&$*ta;$V>g zvwj5oz=c$Di6pWQ5fxT0cVbAeLRyN8q6=WMX3*zM|50zqR|w@{5+J76$py|j2$3z- z9{ngDT5UMgTg_-S^rE-j36qpPI@p80NXejX32!3>zR9~0w0N;#1x}*kA4zOGGX)Dc z+iX4WZKlu$KlEoC_kXH?!`JMX7TD*(Pu7A}8dK!J(gvo zK&7OubJz^vK}%vrz0P(R2Ukt<1hQaQOQv7+dpG*uI0C(cNq>p;K{4|RHou?LjP@8Q z&5&Y`3;L(n6Q6L;S4d)Sb9+yF#{HGqk1g+|xM9%$L$Kwp5|%VNpA&&n=;2n;f7cZI zw&sU(Bs|4yx?GP;~}zlj;?x8fYe&t$mD=t|i%@RDI-_VM@f(5EaOUrtnf zFQN|C2sx$}cP)an;wJ(|8r6s}koj(^v)F#YY|l_qa1U;j9({c<)cyp+A&{qJOk8O9nM ztd_|Bcb7q*>%CTH=4IG}*f-HSL!BZe`dnQ}v++%>h9$j3^h9s}4CfVC^VS`cdb6b5 z;)TAT-=5^l%e#g~nRC4`fwe0S<_>JRz5lU!czzw~q7(pDrSs}#U-Q^;8g4x=w4dLU z?)yD&){LjgeG=KuYNlzmd}j7* z)O3}6r8fK!TCSP_Y_j)^_DRz$I>1=P#b|~z$B*OFOd}UKIjz5spP&BTd~Y?Dc}_Go zl*WI2ZWK1uqrv0d!A?sOdGe`^G`sxro=kG4%_Z$;UG1PnSj_i*U7+%{YWegn&$J zoHqHxceMEaHU-~lf0>=WhgnJn=bMzbM~ip z%6uizGGX@5$<;CbpGb{_HzDKOOL*w|`kWe-2CDd~sj;d%9%L`QfT;KBbVVN@t1;_% zs;p|64%lr846FU32MqS9+su?ch6+-RTF zK1TINZ*j}5X*|+PW0)`945`o*^$_vGjV6sCv9r?slW0FfbN1ony|8q23mG5Y#^!~8 z^hWfFkEsjs@UY$t=XOp{^YHgw%mG|CVsRR9XdeADbv}2OXYY!Ew*VENN*;2NEEzdE z&;IhFy3g-|W>du64mq#FWC>F5NvM7-yOmf{_d9=POQYr`1~HhFtHPS4EhbbyMX+Y| z3|v5t#D~)|4LTaDK7ltW6Jm<%+@@LdGy8v-M6%1%Xpg;(ysFC$^X@%=0UEbAjFxgy zeC;4G|6S!Ek5y;gDL(OfCJQdj9 zl#Wu?6dJ_&8u)!sfv=4s15$M~-bsO~CWU%Y8_!!tSX>tEerzlRnJ^^rFTQdunvSPu z!l|pb`uwn16hhk`%)mOlJtb<5mOwusi8I-xPDVC|HMG>IpL1|c@iqz`LQiINx0gYZ zao_vQ4a-ML54RYc5*c4JRVm-l9co<;*#B3xGEKzQgoW7y4l&M#VCpFvf7EKs=?yhO zvx}mR^lC9mn}G$QBb-1*a4c@trU@290t-4Ikow$n-Fg8l!T7WEyS%^tJ@zhLC>I@l zEmXB#DLq8))wCM|3w#{nEc|eYf@ovyCxPXb%vk(+cJB32_1t_MpdwLIwDZ#yn86vnhn^dhy5_O6@*?Z1Wcb^T`lG2&*baM|r z$s@{kECYzEx^M#MUwJ07#U(^zxXD$5 z+GrX!P#(;ttUm4CJ#fL}MB5b5KUXs(pZ_;{5bnftu0JatvrH(qu)1cy2bF?qvBSklkgFaDzPaN9P=l;;V>!f_O5 z*gy0M!O(g@&cHizF+5VX4!ET!{hGq!IJv36q#Nr>8$|*_allZ7Wjc^cOn+mW-K}23 zvTF+KUtXkT_>g&%yup5;(JHP|mCZ8CC4y6mq88^y7P#fX0ECuo4dp>fG@c-v^tuG9 z?}(}Hd}9BnF9ODE(x!-FYVTy=f!{Ftg!z#@oOF**(b+7&MbWq53vkEUVF}rd%!l;z z99pY>-+^>2t7=op9aPPj4ULoQ$xue2RVwLg#Uc`DPb>m{r`^&MFQ#vBez#)N~xt&>Mfx(drUpn((XE<&K8 z!yYPzw8)BK4(11>C_tfqv+V?IaOZXqRGL8r!lj|FaT%z1rdj=`u8z@5ploL55?UB$}$v2tRo_|UynTAO%ak@XuPjdpuR3;RDryX>f8Fv zr6St)_+Q*r@$|-|{C&T-k$*3OS%)E=)#lodO;`63LB~rsZgJ+QmGa!wtFZ&%$$MX| z^+Mb#ze;h1=vfEXq;O%q!gBenIhD1J*{TQ3-qdQ74>Vn@bRI@s_EC4yURI(}{Xp6+ z<`>0C8K=efG05X*ANbWMVq>h?E6{#2u8jBPu1Gi5FF1?n#@q0a*c{_DL{SMp^7e+P z*6RaiJ4(Euvy2QjCQ~+uq_b+wT}x2nJCe@+#H6w?+k40+{hDnJ6pZu}Pf>8uUSJeG)wz!-1-aD$dC>l6O0ADk17PZsT9z`pVv0)e4(KC}&TkxvL8 zw`mvzG;FJn9s&Y8kF<7o^zp{N-H?I1;04T3S;iSU-u4P;rSm!!w>nn)`~O5B@SpNn z!O?i4RrEdN31n*j0+B-Xq{j;SrV@Z4a`}ZG%Or%tBrpCGcKALksOR+l7sExx`0?N= zKVP7UKSH_kW;675H`MG4wBBYSzuuxFD_c`r+qkCuzVPFto_RNpm-Qx;+1~e@igg(4 z8~V)548v{a@9puoD-I93KF80M-2s?wL02>yIXMAw@CXH{MC^<4K}ezqRFC?6lQmt~ zz?pEn)!8`hj84bkgj1s0x8?VIV8EZ7;+Vk@Pg4Nc3gl9vr5`g<#`&FZ@`F3Rj(8wZ z-6he-hbwGHTU5_&HK`yVRYQ-cD1lqRM%ay~6X&vh{t_9^Rl#egFi(&T#IBR{U~1Bf zeG3dF?+KrBWK5Rv^&j(4S@zk<8Yky_{YYoVNKen_FlXc?Y#J|oCA;UzVM21yCRp2Ujo0ybwbb$abk7RU@Y=%l ziPHum_sE)P-4=LN^x-k|`2Y&j)H4=QlAoEGI5G|+bNl8`nbBIsk{kyd$vcA^pm z`S40C4}E^o;3koZ`ZI-3%_3Ia7!(nauE@Rb;BasUaE^!Hfl3R0FyKb_ zovz|J0VXj*PH$9VcixcG=x{)mKA`Ds2OWH$_PCqJfoZHAM2ia-CaV5e?hf;;_`u~E zP;DP|#MYD=iia`ljpbh3MrsIDaOhufE#lIPB_URhz=e;<`4OYyUj_XP_V7{3-1;mm zvJRuQ{EdYqq18C?p6OudLzKwjI9=e&hDr;f9 z;#md~b>hoM>_=X%1_3(p4A@9fO*|Ha@enY$YG%X3@f&8Ey2z|*!zF~lop+Q zr>BLXV^%cR2>fF$^6`7uK5`kp;G3`H18DM#edO4C*ANLKCnxCc@#(r_d-vg1jONi& z_4Cma=e&nyZy@o}{cczFI!nsyXF6l>XLH`PGoPRmUz6(}Iqk>C>r7Jt8Gt$Q&Y-ya z+G!_#)w1{2Ja=$dtZ6&Svl#x63dODVr7Xi>XM?z-#nuo2$KdTu+xCl-Cy86xB5`G8^EMAmM# z+i`Mn-;+$XFj2P(Tl-2kDgTH*QRyCZZR!nkGskNO$QLLGKT3 z4LZ4V$an8tw-wxZ4wkZyl&`00@}X{>GgFY`NA7rvF&ECS*Ar7scOS<@bv+NRIxtw{ zSB{n_z^4lth6|8|+M0&BFm1%~(H$Lc##`7htZHCrTR*~=wq~c;x zWWb)NWyW5X#rMHn-rjUuRE}?@BzbP`*W7E?8zX<4DFp9(^@*;=PYdwm=1Wp zXjbGIir9S3asBWO&G=Aa&N97cfH^}q<2yRBxgv@Ko(L0+KO2Y$>XsbULozdEslhR8 zeWm~&JdpcbZIX1?p1bF;&^0?Tb@f@Jf~e)^!P3}vy9ng5&SK`z68kj77qMYfS;B_` zo`~v0EijZ!cZzli{uFeJfa0LOg}H#L22o)Iap6Wp5^&pnxgGsr3Yki1V)Xf-b38)L zRUZA6q)mASBfAO;+dwKc@zTKecv5F0X*%0vK&eak!IEh0`e7tnlf-@wIg#AR;Gl5W zG%h@ZWohZ2aNosx(C)9ol?ZQZ**V|d-P9aMR(Hno?9#3I+d+lmvXAPbCsG~`U=MRe z#}?b-A8?11L$Cc_(Uyk`TSWrAGT8q9EUBWS3+8B%#y;2U$WK2o_t>0%aK+S)YwsI4 zz)`WpJpw{2?CO)_Xan3UI|~qA!bAfRMd^7Bt)jSIZ(y5pO6uWUq5UXxa~i(7yfNK6 zOJS)&vw{>?e13{c&im0s6bDe=xS45%?YgD8CxwC55j17m%#zRf%`l}ki-$Mz@%F;S z334A4k&F$v6rPS=$WkH`rGKd$a7%2}CJ|C>{dZxj(gY4Gl^`#iM0Ubzown{~|9kcC za`#Qm`fb$}HILlO0&Ugp-Onjq`?6Q}gz{fJ53H{11iw0LO|^m&uRM0_{5Zbi2llO~ z2qPeOdfXC~8;WMXZHOxi$rMFoG{4GYLo!R7vjn7Ij;kBrbnwUi-I zIg;Gg8o{v6N0F~Vn3fr#fK6wK9P9_J>9S9dyZ6jpDY^6We|zu4HV8J2%XrF$I;H(2 z^@6XOi(5J1_e8qaRf*r(cp6Iz5YBwethD^BKBqd)2!AVVUo7K|W@cnWw=zhns7 zA(3h79|zc}k-7vdobGzqSMFoViHu&TqjdI=bbHG|$EVr=hlJ5M231S^+I-(Q|E+&> zY{8D?-)9sx(C(r)Z~mEyv6oycBaK#Pp^JL~9JlgdcE3n%&_$tPso;*ZhTA^?1uiQn z#31|Y%wVZ7P1o!FQcxtc!(QCCz!)T=Bu?HllkaYr51d$5N#XJBr6Y_tH!!E-?$D)pMn+a__B!1 zs-jmF5DOns$odWkwl!$s1oDFk5;eaMN#Osx-)kWCT_W@GC+E+gL1fZ`UIhB~L6kqL zk|uE3u-WfzSz=EWNk(uj>wvS_=8E#N9hT#@)eQ)=pbp<*&4q-@HpQoxXnq+An$i7W zn8KDyPmTZu09A#h(!w}GZZ3YBNVGIDpN?v*Cq+w3k)`(!YH&|&k*R#-9Z21ZVITP} z?AT!$@3GF&H)%KT1|W~ZhPV+`O|&Y5U}}u?U5b#n71Z1D;jgfv>>}qQoVTq`u$jNs zk36Y?-|4{qQ^$P^<%VggCNXGpXHZCCxorB1ZEgmob+Y>nBa*}Vecz#QL#W97>XRT^cD^kV0ajOhRmiQbPvX(;5}4IFl@VM4O3Hf>6a0E) z)boK%sMGuV!*IJ7;2)Qu`m?@&(n}r{vGt8Q+2U-v1Xyk(1pod}eW9W_DuK>@>mN>! z@j_3-8CwO<)H~qENKO^!!GKd&0ey%UPj@3Yz;Xs>j4{4*(T?o&`8mm%bjNqj1FGKm zq*xqB^ds@?a0W;7!*1ZZix!xs7PJogNIn;f z?TK|y7SV^Nt>fUj?UcR6{_d;JNB?~TzE}WtU8kN0zK8xz**>(UNU%N*NYKs5I6J)R z6}dm_+bFAN$DP1YbF5)VR(MMe!*9TE7$ygoC;mj=#-Q(U!Wz8bRaJS&l z5SA<~UT`{BX49GfL~9LwZO%dbOIDv^`70{l!k&h>lUpg8NxL4MR`EekcjqwV zMAN15ykFMe9$_rA1h@*g?sNH#f;a)Jh?N()iV%x}v~`i!5oo4a(gMcW-|1PjJ#$SM z=Jfg1o9zf9c6ajdMxH0*6DIvylF<6}i{S1&>iOVxB~FoYxL_Zw4@24#hfAI`vqTHQ zHgsLRl?HDKxq2GDFqFF|=UPufkJeZ*{U@W-B=(cGqZS{*jU(UNIbWm1+aCawVr2O% zNeY%^fWLy7g}p3iszN_`MY(!ia2QHprcx4J8t1mop#}=}#0!jfcE~4*W0%8;-W?C| zS${Kte&uwwj7X+I?O&Y&V?zZ-T|y9}sT{uO_5&&%ij+rGo2)}w68hfdX-2Fla!PGQ z*5HV>wp3?rF}%i2K?)9)Ox4k#WbCLO@(08*nVZE_WufIX z_ybu=p~3M^?kUU8K^lzc6yRmRzAN0?V#qDH^F+EEIDuBos!Hmm^7P`fzydT+f0WMm7gI9bMPu!_s9MVTcD;*HQmbM1>waK(X+%moHZ39DN|$uEba!r2 zYSWFxrls>O{GW60dH25YfWd&V*MPOwp7Z;DHRr@bnKH7ie+f?F{8)_7bW|SZc|h}4n6NUQa!&eWaa?`o zo9h8Ds z^nBlng||Q5{C+W4}lgu z_`&6{B%PKrFDJ@cy-^GO<54vR{~{s%iWUv&gpOEC(anzzYvlY-kigVk-NYF$?IQb) zwvxuhwtY{NxBiFpSb04N={DOUGKJB-ZdAm&Z_GZGMTb*+=2$1;8K6qULYcxp z2jaOm?=6+hg_Btce(6dwLa)esaqjsus{@aKp4->Q&F zzL7XByAptar>IC$BB!GxZ^m@C@jm~x0_uk%ZC-6^o1I1m3j2Rc`gj}N@luALVNTr* zd+N?(sU*|4x>=9l3y4*{p|vg`_>cQ>r%{dpb=Mf~C|cq`MoTFj=j<-Y>cMyR$$fNV zGiJkb&iRtx@~Duh%k62dSh0gtBH~^l}{Q&YvCb8{jO37eKU> z!+HDMmppO^SrGz3)qcEU*v z701N{`G98nKc+Q4p$b@v;$2S^w+Czi1*2sGEra-0iY=}N?WyE`*l;vIZ`t%M}c z9x}Acm=%A^E?&7w#G_luoBo8Jzm(vB8&~aMWCd~29|h7h5xMb`eJerw(*zWK^(|nh z*dnIyGHM#>gS5c;t1@OM!b3~cHdZ1l%)1cfwx#0Gwn4}U74Vlg0lkePspDTmC^kAa zXcoESI>*(R8uZLVhPc*=#Y8WfDDV@nNFU-EFRkZ?#YsJ1@)Q?OxqsnOmrTM;LnM0! zgis|KrVegjmRMWo?qhliYL-ubo%KvB?;?cn&l2+Mu3dY%p~UugomK?5JFDZ6OFkYu;LFqVytca$2t7>401ovT+RNR^$4Q^ zIJ9?5HV%9nVWc&!v3uNJ02h`WgPTq_c(n z`7aL{iwdUi-0GVD3^Vmt*)nKT2$XL)f3v30`CK;TmkS;hZ>R)uDX(((w7*~cjy_4m z(1de`$QVJ$Nf!%We+YPG!d+58&LkV}!xmWhnh_U61Vr|-ODJ`M%N>&H98eLt+td9+ zpd;#~xY^yJF1P-Sr`|{Dp*)~mum3sG?a=nSlq@=Y-dVwYEo2kJ@~gFJIn==-|BL9U z8aCYcCnG*8q&rG|_)M4J$JQK4k+T{jli|z&nj6ZvqX7A>8NW7q&c>m3LiQ5Ofou(c z^9KhC%i;h;OfCW$x37`ie2G_`;!jh4x^?pc)^_+S?B|hHBw3^2#y1Q3+)9g_UZA9P zCxI-F{JTk5%1un+rT6N~)c`#!@>lCx*v2Flree5IlD^2lA44;8c~foU-)Zc50~ zbfZk?9h3*pDI4@KJO$~@beeG*aBv8TTx%Sb4xBa>E3CMS2*Y;N{IXMg6)u|+6rjQ& z_$cMYOawRGtU1*b{K-yHWA4=#v5n%mHiUGqlV!o8NL~G5!29h#9 zFb@+m!hJ+z@e}lUb7}hV@x(}y7;O6%C&twZnz@d+V0`&0T6xilmp`>m4FcBj?QQ^<2^!v)u&wmohJ^ zu82+yV!&Ax)o84!(`bu@+$ebetYkoBrfCvea}{f?_;H>5JmKtjc3zWuNrpfV#~yqK zQKm?2zLddiAzgW;MnG{2-gOc597C$`ZFJw7gOMyh6*VyJrM7u@l4ydPpXD>@ecLTN z;8M(njaV|8qNw{u6H-uz>pYsqdZ7WeOtYwZP0}p%6f@8geyqX1`!~_ylg?BD0W=l{kfAu#4#{=6@qnI508OuN6s1_6M!8Ot#4h}X!VC}*Te2W= zeiuTFKwG=jdpKNgO1@-qFg9y^Pkt@&8>nJ{p0yR{8-xhc!Xe- z+;vb(C$!&dEeL4SUpFez@;J#>)2!2f0S2>q@$on2l_IuyLpOb8cBcQ`F|EI$kUe$G z8@^~2KCV8;RHWD7Q_lU}Vw&PujYa}~yBb03hv!7 zk5knrW^BD>9~%8QdF}N4!}#ygPoJ!5&7XCi_WnPTAQSdK@U1*va-S8H9@lbhrO*=jfr(1h82obKn%O!8u_Qs|6=Jd{TdC| z&wtdB)2Qri6~!pdn)287TKF~A$X1P3HCGKXD)}|J$>RUIK3lkYA{)#Mn`)G2DjIe~ z?{WN#>f;Aufe|tyj@wFb^-nA9YHB?F3FR?O0UQv6j9~&?GX!%uWVnjrV;pwyt;irV zDU|V^b$@O-Q1xCRc&L}zi~KnztHZ~;p8TUxFThC-oA4dtTuVM}H-MVlX#K-fCF?;u zDjjelVjmKd;7aF^M_jzQ^6k)b1Q#^-z8pl5yn{_a3Moj`XLO0#W6_8%a^L;~W})!J z;insVd+q5BVgeagW9c1&s(Ts@+?JEa#$0C z;wwi*BqBo5rJdWv!2DFSNL5}^Ia)<3a}!-6yaqpHc>(XUkfu1kcoAc9d7?|I@in@- zxfL84LVWblkxy${Qh*96G@7#ul{TVRf6>|mL_nleJTG>$GIqt}qn0fNx2!_Jm%qnw0r`&1O- zsknFGz2Xalj~6*S9o)AB4#k+`GwoqW!f(kBk$GB8?n!>Et{2@z;?uk_K^!NF_^aCp3 zC_@~r-bRpmztI&rZmRRrz@2s|zS9r*^I2}wpaRCZT&P!qcq0?=eBT zz8(Qh@2Qn>I1pm=HRY<=rw3ajJ<1O7O zNiazy!F!b+qaaw&nR8_X3U?EGsf6c+P#v#ynEQF+l%ppOtO&8QZL?X7FOdanYhJn7 zgf4D^h3Wrj@)SLeX!W^b`u40n*K`5Rhq(T-MoQ7Nq{tKcGO1vBUiaDLhB$1;5!V2K z%VBK^u(a$YGxpa-pNylS8gxL=Y?Xx27SgYU_6G*8_zFL|?1IbUj8apKgQ2|L=4CVU z9{1M@OByvqmM8DD1$ypQ=G92C-ypP!(!1{1m#yYL4@*&F!vzgXC&!|=iGUKQry?VM zF1B6$#zOauDXS$ z$JkBJ#12tr=HKhnPijb>y9Xk7)1BUXCzQZN0p~uJSM)kI7;t=XIzvXm0lmdSP1B~! z`rLWFu#^dQ3a=#@ukn#YziwYXjRwlZCO|C_$NncS}C%CxgesQF-MQ*_q_^H8wer2`3~Jr6__qelp&xnV!vXbbwt zFIt>~7GJM*E<%nKNe`TwIC79CUl zZHC2ORtJf|2$n5V@u!IF-U3()W(TH?xS~k9dMw*)Av8oKtBlNONmfxXj!ktX%7lMP z6No!G2g(AEPx(P{_mKt!A}N!Ve5>JywR+@?>dR}FF92n zh61xmB(KXVezXF4!Q0)^Uz^0}o?Hr2{)c5)*l^8nAePtTnut_Wg{CN%*EyoVr_YrwgM=L7`qw{GDn}j2@YH3WD)f2lMoae1eHUFfSJRY~v zCKe=@hwKm&XaSq2vVSjWEoYei3Pj2r+(G>B11hHC2GA<3NXk#?$=9q*1W)YEu_|dp z$MHljXA~08DH1J&fYIVXXV!xOmxyPFS=qyI$7-k(iKPXA555|10U?R>og250^Q&?; zrfIc%oXLg3APcTaQXGVbXm&W2=I%!wD^YG0z(ot@G+|QRB5aS=E-4twmt>hRPkX*W zJQCB+fMlGG!?Hd)dKieFxJz9gO*~Dl0wlXU??n`Bt1B5Kz{v(Ta;n~X_^UE=UIn7F zg$y>!!+VG7mI-`&4^hXtC|0_>4tqxV^NTZr@T0`W6t753dBlIf99_#5Malm|==F4a z*t8E7I+U^*jN2J?6Rn(MNJ|(YHhgkBv<8?$eYc&BG}fP&AwML+fL$@hic_W@Jy@{$ z zup^mZs(Za-nt%@eB~eRQbR;h!k^T~l?d!XN&xZ}S{N(!m?r}a=24c~a959|2a+=~p z*C12tJ6B%XJJMOotH_RU5=ze#7-K4qcMev4$WUH~02|xBXcCOVB&e$^9fLSxN8B&f z?^ajm{kU$%271m-@=E+bvn9Ko7+&Wz49zDmzG}4D=c(x9Vkv_Tq@>ck0P~M)%EsA> z$ANxT`~BM}MR|SPUm47LerhBD?s-FrEq%u2XDHY;nC$gkZ8?|rhJ+t*kDMe6Rkwb< z$K8I4-c5cm4*9X>tC8RSG1d+!%J77$KguC^My*!@ zIc6y>ljqlx_?@@EM9ijC{y02rw>omCC>6@^6EXS+eG)scfl&Ab=|$QL_V1#3Wv_tSpe)`X zx6Uo`fPbYZk3M}Z)L|v1(Ov?%^vmv%I1uwgi59>r&{R%Tq)0GVkUPTxP{YMLp;mp+ zX5V|0jPq*-g6T&F2;t3O<4+%PWSPKAdH#))GC2J^9lH06*wsbKdFnR zY$u$^pS$5u-E}Om#UpQI0tCe1#NR;ZS2=Obicjo|0Z-_+hDOWe@_&o+SD zt9B=W{Vfn%xN*X`2I9$R{3wN|oHky(_(xSpv^Vm8c5oav;ACg0f~B7udd0uk`4hqr zW(SKwNWnfC_9SvIx(HTH0%Zn%&U~WhVYeL5jwWB$e!kTIk+L^zwl^R5LYgrfxyU}0 zF&>RA>QtA|cDSFNJPWB+eq(9LYe6`xM{+jXe&k)E;Zx{UnE6*y4GN$VI&4(?;$r*I z!{Os8+Yy68qYIi=GI<*52&M%Zgr*hk8})aRI#GBn*s!+I2riDD-*l0$ z#SEh#|55CfyJtPn%kAO|@tK*qA@|l4);Bmhs*T6=FbeK&nD;GJkSJmT971$2$F~dk z#IscPmH^pRQ2)^PDd3cT>DL@&jb@=ML$<@Xr=q$J-S^-A_~ci`3BBjjV>K)i*k=Si zS>1u^PXYJPycY;SC>adsKx;`Ki*ZNQubMmFzP$05^ZGp4e$W~un>>L?PcS_s)u`0D za=?U$v(?X&rxt(Fl(6f4#jkJF*2URD%DfmYuMZ#-(@K~wkQNv8YDtLtKt?19u2TL` z{EDa!{g;>nVTzUf)|Cd7)2LYOXPRiq(5Fue4mc7Gl%|4DYQeC^mumolzriTD?fsYI z+}P9J(uyou)d)@+#OMrBioKfsm_ZbsUH~Rf9dd&KS=gm{Ig~5<%6f5s3U7H+K~cf z!xB;Y{6dFNLvIu{5h7d!Kno6Z&ngY6oN}$T0E%=++^=hR*I(wt_ueuV!!!gmJVa;o zR$W%gH9Ww-7Pme={Fl(+mdX8A^Yv%)uC=J4{k`PVF^y@Gh@B7cuBcZYDC2bw`t-}Z z>N9!8QJpAKJcTNgld~_;qN5#?zlRZVn#$KyHY6F+@Ylj!--sD%Yvzr@Vv}jQtXEmr z{r0Swg+k<)+LWu9)w?uemjIoA?p3lYj?4X2Y*)K3@5u*JGX6inl9B%+y&mn&-Sx1se)&4`PSTCy){V%cN zhXilZa6*#(nsbw@6XLVwX=O7H*q|wZP`*{ID=Y(T96gXm$FHiezm?Ulq z{+;l54Ee$UeKB_SGOT?ki2z6ME* zzV55y?J!5=`^TlaoW*aW?2fIdQqJani3BdW+f568u`x^MuWA%7@hLAEbZlDd$4Fd` zSTdg|-16;0}=OmKd9c?&|sQHXOfqL zt$!2~o(NPPRD-(}cmSV?H#2wneHb8qJ~?+02f7Qcppl;Db|P0F#cZiD*X}$=#T3YE zcK|iA;_H=jzmzulxF5Uh4B`s{fSmL6bgYrTR=9+~QZor1igUwP<+zpb3_J4)DwiK+ zZ|oT*k{M1k+Fmr|+@8%nDSur@__r@bW=ZsbYc5wZL;qGxe{N^7B_5c8wlBu8t)a3e++#=)QgU zb^=v@g%;B&6%A!+_tM*qb;mGRWmWJpCa0z?Ae7qW7D>kT1O1-nNloP!LX6nY(bY)9 zbBZ5xpN`+YD~w{+SVoj~@nPru_8NYy5z?Ey-0q`Wg3WIj;ND>oH;n==A6km)KInMe zR#O0@#*W{@_ayXAI_UvbOg z-K?PH89bbEg%$o)djhB5wQFC*ay%^((XDrk+j!L(7`o1dy2ig=Ca(M6$$}wwkH4}J z9GllfWC?umG zq`0dITI~~9PdUnD(jDh zAU8$hw>DxaK~=5S=S|vgsV}q0WU#;F`$eLZs3^ga1w#D|Z4>x#WsxMxJ%;O z)?8?N_9h1y?A6T^eV@_+ZC17e#RwhZq>qpp$<|_l4~JpMm_1#2;E^dn_6`4Qq(=;j zPmoR7tahZruiTe?XMI4G(#D;ZEgyoC8MpOuxai{%-<^~OyUqvrPjJ$?6$B2Q;XwPt zd!jjrd*50(>bIpcaZA$4OG#2{Z~eKC$Rcg{wZJ2sM;{I` z3+=pOUMf-fi;EjIKs|HyYIzAM9OaJqn%xlP-vmKhr2q^r%z|s5r*Xvg`*x|><~&<* zZ5~L>7!@vX)5nYBe(}2!i-L8-C9i^o&3439f&D@WgzLHXM>P{4i`cfp6fl(k#<^y{ zp}0>uG?wOT*q$}9n+$jS4*`oxgt|k%r$5hHE6+Xd)VUZwR3#@J59|0Hefm)lEx|9e zz|U~Frk@pygh;HX)TP|MU0s=t5fh#CKCJ_*u;RJy{bwzpDrXC; zl)(t6-Okf^PZ6$?5M_kNlrEp?gm)%Qbs6mOxJ$H1cH^!C$EegnRZU|2ESmbk%-MoU z@vzWnnT^3&N}#@1pqciJagh5`8ndz2Q!nCU4fq5#M?TSv4q+OvqKwS4lEf}J0k?() zUV1|2>>C@+a=12ftbtlUa0tpD68muyrGv0heB3<$!b^CP-4_r6f*K^Hc2pAo0F5Xb z%Jae`sN!$NV%@~14&gCV9<&){bO4k_F#iJUQzy{kMHdQmR0S?QBcMJ87clajn1zt< z=*YftfC2#V1r^~DSwXh%($EBH2)GFv%Z0bMS!BUzniqIkg#4xXk_NKpbtM3&mL|0; z<|0`OW=n1OXqL86bQ#uDLF&8k5zCc5o%-?JI&VJORM!6MkW6GyhW&eRXiHM5PK0d2IM)(3B?tb7 z@82|u$ME>G938Z0WTvi~7vi(zvp+^{RWdA)Kl=KsC0!AGSey`-q6Zf}od&M=IW;V`eA|!r%!IygOBGWK1siOpTphduw2x%;5n}) zUH?nBtiY5rBYUdxWe*f78wBB(!U;y`ERBH^x=cxWaur!BHT-?hnLys$9v9u6tb?N5 z%0$61{n;}4?~>G2G#|2JeviCOaj8z3`vH7jU*7wQH6L00p8K-mzMQOmH0*WZz~(lg zo^H9Em>y%=*>_F2_-*?qUpvzxp1%R%ae!SYW~Qd^?WF3HH) zZp+bGsjT6-;#l$-SXOz*{^A08j}&yXL)+^5$Fq*Kt~~F}AxhcspjMlz5~+`2;?@VEyk5><8*6Ky@)cds;Q;LOXP?OLSN!7irL1qX__?o=dd3x zVte9f@q<%vwNDh1ZyWutY#;_`WFKaCKz#6Pg4}gPc16?!&8j1LGtC()(CYE!*8^Ey zt4s5jNr6kXiwtY{-(U7-mj}5-k4Q}2-IJZ}Q^LJpaydF3E(-9Zjyppx<_|8SoRo;!^#*8imV+ za&Y}I$u0OWrQsAaxZ9Ha;C!9nSY;LZa$he_$ESJ*U*sT{4LFSs$Rk5;G1W09YyK|v+a(R)zvwXkqU=z4AH^+mqW|Z z2s=3&4=>H`Qf9x?%elOj_Kj#`ssEaYpY@<^7V_#+iBhtj~bPY zjg9kLgR-w?5tt6ufd{hzA0b8eY`6Wo;VzRrXXwO7Elye!vgS9xXq8J6?V9b($!S$g zF)scd$+ae+|5`nUbZqRMAj57w@Nzxnh=@CL&bY7K1{eF&F=F&-&Yb(#rK7uIG5e2+ z4hOOxt7#AHmYNe^WG_cne11%7Q3+g-{5_P{OZaGir)9E+p&%XD@%)RC(&eVJVcVhT zA8p|VkLf7kgsLT54ta(Gavl|r|2lhi&9ffn}%(@?chk{y_U`c|^(vGZs zy_hNTw)Q&ft3G>QPdhJfS4df-b&2Y%eK3p{B1sXl1Hah$pOa}G$wJ>;dB#+|TmYTM z)L=&I(2sb@8AvD9EbPC8<+p+utN8o-x}$t1XW9El2JpE(nW^~auw&k*Z4&T(h|saE z6q3cGF^)7}JYut;RC5ddF8$@D4Tsor_WWk$J>72TMeffCX3|<#_eLGagc)2WM$pz& z4Kx|*p<+0^UzFq^;}eXDqsUbi`8nh>!aW0Vr&Xr)#Hhoj`lm>jXQ1wLY;Wwgu@mOK zubt^J@+`(uWwh2!)O!qv5eR}Raf(C&>}4+m#h%}ofPAObY2Kq`=BOJ^0>u*O2EFwkAY;5z>Cdc4uSovC;XUA%#;VE=t?`E zCBEFnG}xw$Q;Z=K=tzso<@1K|y@whfF)-zfsv=o#HB_D>R&2xt_HvE##u!nu71S(P zPc`{N;pWkOi%ApIt3{-#`f1QHE;N8BG>(h-_fO>h3@i@NH-}YMH4Q5!BrCg>aGkP` zz&om%7Y~(g6)k2h7LpyM=YUG2*znr6P8xvXq!!y;Vw|!IFZ)O0H{XBq8*2DFQbEiC z$--iaJ&i)oo_<&H1_n0|=U^TksH#^41qAYa?eK#5?~!7Gz)b!7lM3~}W&lV7<#L}X zb7W+sMS`(qX=$lNB57cLUT2va6kpTYI`RDJeCq(3JU?EO jh{}Nbdk+7 + + + + + + +MakeBlock Drive Updated: src/MeColorSensor.h File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeColorSensor.h File Reference
+
+
+ +

Header for MeColorSensor.cpp module. +More...

+
#include <stdint.h>
+#include <stdbool.h>
+#include <Arduino.h>
+#include "MeConfig.h"
+#include "MePort.h"
+
+Include dependency graph for MeColorSensor.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

class  MeColorSensor
 Driver for MeColorSensor module. More...
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Macros

+#define I2C_ERROR   (-1)
 
+#define COLORSENSOR_DEFAULT_ADDRESS   (0x38)
 
+#define SYSTEM_CONTROL   (0X40)
 
+#define MODE_CONTROL1   (0X41)
 
+#define MODE_CONTROL2   (0X42)
 
+#define MODE_CONTROL3   (0X44)
 
+#define RED_DATA_LSBs   (0X50)
 
+#define RED_DATA_MSBs   (0X51)
 
+#define GREEN_DATA_LSBs   (0X52)
 
+#define GREEN_DATA_MSBs   (0X53)
 
+#define BLUE_DATA_LSBs   (0X54)
 
+#define BLUE_DATA_MSBs   (0X55)
 
+#define CLEAR_DATA_LSBs   (0X56)
 
+#define CLEAR_DATA_MSBs   (0X57)
 
+#define DINT_DATA_LSBs   (0X58)
 
+#define DINT_DATA_MSBs   (0X59)
 
+#define INTERRUPT   (0X60)
 
+#define PERSISTENCE   (0X61)
 
+#define TH_LSBs   (0X62)
 
+#define TH_MSBs   (0X63)
 
+#define TL_LSBs   (0X64)
 
+#define TL_MSBs   (0X65)
 
+#define MANUFACTURER_ID   (0X92)
 
+#define CHIP_ID   (0XE0)
 
+#define SW_RESET   (1 << 7)
 
+#define INT_RESET   (1 << 6)
 
+#define MEASURE_160MS   (0x00)
 
+#define MEASURE_320MS   (0x01)
 
+#define MEASURE_640MS   (0x02)
 
+#define MEASURE_1280MS   (0x03)
 
+#define MEASURE_2560MS   (0x04)
 
+#define MEASUREMENT_MAX   (0x05)
 
+ + + +

+Enumerations

enum  COLORTYPES {
+  WHITE = 0 +, PINKE = 1 +, RED = 2 +, ORANGE = 3 +,
+  YELLOW = 4 +, GREEN = 5 +, CYAN = 6 +, BLUE = 7 +,
+  PURPLE = 8 +, BLACK = 9 +, GOLD = 10 +
+ }
 
+

Detailed Description

+

Header for MeColorSensor.cpp module.

+
Author
MakeBlock
+
Version
V1.0.3
+
Date
2017/01/17
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for MeColorSensor module, It supports MeColorSensor V1.0 device provided by MakeBlock.
+
Method List:
+
    +
  1. void MeColorSensor::SensorInit(void)
  2. +
  3. uint8_t MeColorSensor::ReportId(void)
  4. +
  5. void MeColorSensor::ColorDataRead(void)
  6. +
  7. void MeColorSensor::TurnOnLight(void)
  8. +
  9. void MeColorSensor::TurnOffLight(void)
  10. +
  11. uint16_t MeColorSensor::ReturnRedData(void)
  12. +
  13. uint16_t MeColorSensor::ReturnGreenData(void)
  14. +
  15. uint16_t MeColorSensor::ReturnBlueData(void)
  16. +
  17. uint16_t MeColorSensor::ReturnColorData(void)
  18. +
  19. uint8_t MeColorSensor::ColorIdentify(void)
  20. +
  21. long MeColorSensor::ReturnColorCode(void)
  22. +
  23. uint16_t MeColorSensor::calculateColorTemperature(void)
  24. +
  25. uint16_t MeColorSensor::calculateLux(void)
  26. +
  27. int8_t MeColorSensor::writeReg(int16_t reg, uint8_t data)
  28. +
  29. int8_t MeColorSensor::readData(uint8_t start, uint8_t *buffer, uint8_t size)
  30. +
  31. int8_t MeColorSensor::writeData(uint8_t start, const uint8_t *pData, uint8_t size)
  32. +
  33. uint8_t MeColorSensor::Returnresult(void);
  34. +
  35. uint8_t MeColorSensor::ReturnGrayscale(void);
  36. +
  37. uint16_t MeColorSensor::ReturnColorhue(void);
  38. +
  39. uint8_t MeColorSensor::MAX(uint8_t r,uint8_t g,uint8_t b);
  40. +
  41. uint8_t MeColorSensor::MIN(uint8_t r,uint8_t g,uint8_t b);
  42. +
  43. void MeColorSensor::TurnOffmodule(void);
  44. +
  45. void MeColorSensor::TurnOnmodule(void);
  46. +
  47. uint8_t MeColorSensor::ColorDataReadOnebyOne();
  48. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+ zzipeng         2017/01/17          1.0.0         complete the driver code.
+ zzipeng         2017/04/03          1.0.1         only detect six colors.
+ zzipeng         2017/04/10          1.0.2         only detect seven colors and add methods named MeColorSensor::TurnOffmodule(void),MeColorSensor::TurnOnmodule.
+ zzipeng         2017/04/20          1.0.3         add methods MeColorSensor::ColorDataReadOnebyOne();
+ Lanweiting      2017/06/23          1.0.4         Canonical the code format.
+
+
+
+ + + + diff --git a/doc/html/_me_color_sensor_8h.js b/doc/html/_me_color_sensor_8h.js new file mode 100644 index 00000000..2cad26ac --- /dev/null +++ b/doc/html/_me_color_sensor_8h.js @@ -0,0 +1,4 @@ +var _me_color_sensor_8h = +[ + [ "MeColorSensor", "class_me_color_sensor.html", "class_me_color_sensor" ] +]; \ No newline at end of file diff --git a/doc/html/_me_color_sensor_8h__dep__incl.map b/doc/html/_me_color_sensor_8h__dep__incl.map new file mode 100644 index 00000000..cd4c8abd --- /dev/null +++ b/doc/html/_me_color_sensor_8h__dep__incl.map @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/doc/html/_me_color_sensor_8h__dep__incl.md5 b/doc/html/_me_color_sensor_8h__dep__incl.md5 new file mode 100644 index 00000000..e993ea9d --- /dev/null +++ b/doc/html/_me_color_sensor_8h__dep__incl.md5 @@ -0,0 +1 @@ +412dd61c9721add5fce88fda2f4fb8a4 \ No newline at end of file diff --git a/doc/html/_me_color_sensor_8h__dep__incl.png b/doc/html/_me_color_sensor_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..7a2b236055f201ad3c79e0a8c258ffe5dcef2466 GIT binary patch literal 9965 zcma)i1yoeu*EXSq(kKj4f`katG1Q>aEg>!4AUU*@NC^Yd4JzFoLnBIecf(La_Ym*p z_rCxC_y4}N-nG8NS`3SO@7#U%KIhrbe$EbkuOyBC=-DGQG&Fo!83|Q1G)zO_ZwDMK z;J14b=`Y{|%UE7o0`2bp=SNd+3>w;VG+Bwa>h7t?d9Tl@E=lKygD%Q5S+7O?emvJ$ z3(xQRS)}t-Qb|!qM=9FVa6CGzxUM%dvSIJ4s8IPcvisC=T$DwWp{$Oc|C{j$@3JA0 z@()F$aS5V?f)GE$pV-+}+~=p)Ts%nLGzOmTzB%WMW`okkE9;H)MeqJTj`O+6n})qb zLW%!%WT|V9p@)QYofPTT+R1`~9%n{~_e^%cC4TZIq}3S%_k+P zgJby^4e9A6e?3r;$iiULD)Wm`h6rwRX7%mP!DFa}T_vc4LS#PR{vvqu&pWepUZRr{ z-wzg&`v>pGKM&tu&60`r3k|s+PeMsJ|G6uQUIl}Ro_@5(ZoXdpHqEv{Z$|M(fiXQ_ zW)Y!&_R%(*CL<(-N^S>uPDa02w>IK*XVT*O20BAgI{!KO<=MM^T?vVT0I6092~(X% zQK_cZ&No-5&yd8#Q5CuOHp{^@jT7=yITM^36+%ZOUdY2^FJYfv%pwp+I=PjLCuiK% zf+~%puyU#%Mo9??#t?e?4^|aN%_n!{1y3C6k>;ptJ^h`jHOG3S849v7vSGR(cz>r{ z%KZ$wwe}MFYgW^Cb4ij;eC5X_N=4(s*GYV9W;ZJPRegLVCDz`{0k##q=YJvk_x(1b zGb!x7Vs^2r`=F!*gU&yf)XObEscb>EPlN_+XEUtvvJcY3LS(9Vaf3r-o+j@JY3KVg zvwrAf>;?%7#UdqWRC>>v*iMHbfQt!WfM3*q>h&x?`XD5r-7xAcGKu8=l(HqL<}JqL zsn7l?-kSauJ^gff9wrfS)RuOoxgsJ;n#NmBZ<)x~*>)u><1hw!~nNh$1wuHpD ze;n}t88qNFRfhX1+>dV(_c4l1oS^Z2Dn*DM2|rF0jI2Mb)C%w9*RyN*6`}lU)(dsL z?g(c5s^+iepyYzMb7iaS{1u@nkws!TPe>f4x@uSKz3ZBY84enAFEDQN@b}ADzQ$R# zXf z_sD3NI+G$R3z2zvzrs|%=%B8J_ZmGKJMpEcsS?rs8Y+DU<#)Y($h|V=sYQIw@5*-a z#Z0R!dE(QSas|?5MW7Dn7q`S{l+-kBt4iQ!(bv?OC@B$W?VtS>wD4=6DVhcp`L37a zU6nqxCPK)OUD$1xMg3SqxVFQhFR5+8LjTnmMD==2UjOf00`1%WA_{CD!OW5lT)b9m z^FKJ&#-XijVAFS4KeyuN-JP3 zVg|W%`$F*oZSMht(o_b%_=0P%6G|h(aigeuki!wNPi41dSp^H6)08h2vm7A&4a(Tm zvTk7+^Re4KdvQML!0N#0*H$KO*sV;D^oFD^w=&OA?v^soDj#bYd^z+8sC0TX6e>J7 zT;6xfkc$Wn>8kr@+2TG*%P`hn$h8Rv?P5U6yaX)Pqd%kDT2|%aPH#jg*Axr$%#mi= zVJ$|q2?i=PPn=v{_UqpGxa~QEMT^!S2hP#@QQmEID3VoVW_OA;c!tsHhTMGi32Yi# zXdQ3Gc39aPd$S^{)I69J!-3ZM4#7ITn`@Hf-ID3=OtpZy%M0q?@UZ&|nyr}DkdUaz zB<3WJ3YnimN)vQynRXb)Lw>PIA4>jf>Tw(!3VTF z;lB0oHXq#(@0zo#Kmvn@5e#9n6>}a1nNfj>ipk(y-TD2;Uv56nrHb*rP+%M*y+~_6 z$Fyk0#4;YJ!H1ne*-=l3qXOK<5Yw3rq{l{NXqQVG-kw7j)MQ zSa)$$#1yPb#->?fc$byB@v}ov6L}_K%otn#N4uwfwJvPc4Y>`2hgA!!rDm~_U(xq@ zL5y+FK`+QmmUDV{r{5ukKRTECwl1krQ3XCje&**d_ut>L*MrVVYbgdouL z;MuIkjG7uuQX(t)J{7R|RnLA75*xH~)Cw=3B4IAIK$k{yOf{(IihcH>3?v3h(c(S7 z`tkOL4quoKy`}7X3jgcMbgRGaku5?rh-W+{jtGqBtud>*!C@(fhL%OI#za*LYp-mK zJEZ;0gH=|)qZXz7?riO=_yVWgnD)1i1$o4M0=V|SV}}!qM1?%$x}{shH5xUK?9b?x zZug7S{>8@YOuzA!>;OsBEL5K%oSTeReR3(6n&Pj?S+h1gHN0TRoPF!%9XVLYr=J1Q zd7K&*e)uqzju6yJ5z^M$ffeLL{gae9A9{~`IaV$$95`o(^;Iz=o=XZOxPSDQxD0VX z4i-PmW08~^Gg&-OYEG_Rw`P2QDNTv4j{&JDi%*$luPNGFrYOAB7weYN4jujK2swyu z7w}i&89=-JQWedMt?Z-nq-gCR2x4GKM_b`{&b0roSDgf5)U|WOHIooFp?~KUOb8<# z#UXMt5vL<5kJoScz3dvGZF0VUpo=k~)#bv#bdX4hmo&Q7;ae>*Gw3`$Im4boJ#mm= zcTI~Yf97A;z7Zkig^(Eh)ZB~Uj;ZXB?a}{3p{~kA@AMtWY*AFai^x)5<#5Zu4rAwS zH8X8f5IXqwt}YZ?SK5;h?mH^~`A>3N;_d}+}CPH_eGadf&BOwQ=Ke9d6s%S=zdE`^&IB7mpfk;;+-E4S+l$$=t@hiS>fM}oNQaqv+VyJOJ?y{*IXcrk!c2ao z;&jpMBWCQLDD4+hIlZua6d~0hu;^%-nLR0B+!)-=T!^;14}fas<=ox<6oNq+9UcZw z5+if)G62#nc54(o6b~s0rbvgk!AGxuTWRsqj}q&W*yI)3_n7n&&JCN z5dLx1PTQ)JD;CfqH`x43(#5;*&Y6UYmjxBoe7e_F?)Z^PRZ7W}N?o}^@zVxmuOcRj zZzG6i@Xy#khnO($P*R{Iem$w_P1{qzol8Uvik#uF@x9Z*S)F5rgYq!XmabolvUoWP zM3OmeC=y2*zXuZd2gataLzvr+Way=gjv^vOU&~^ZFOvCDMIOiS@IT$Ba)#*n!x4TZ ziunA~MM1&Z&b1lTZV@|{WyKzZ;DG8TA3dr)Y$XQgB!iIQxdp>J?Qr*w(Yc+E@reX? zW!fzB4$hG21xs3XC{;HFJ;!2I-z{GPg3)40B*QNUZDD)hu$4fd-br>Sj809}934^5 z^LQ%kc#$B$91qS@Wl}5QJ|HFP+*OFrEaJM1> z3*8AQfI4BCRHY*oHh$Cmye6`jO9NvPt*pyK#rp zLqLA;6s=R%>f3TiQJX-j>`rawr*=CQC;Hbif`hj(*q^Ix3y7$;AJ%>}ZwUh{paJRJ zI#{@$D}WO^u{Ygbe2j2x5I0%Ut8q-a;oJu2zIaWcE4i}2E%<{x(|K8;hU_T4^|R&7 zZu!Gwuu0#VV3_|4SvH1So{{JZQ7;e>T@J}-RUzusKvAO_t*TkuzLo_tGM3oE$Kp`7 zb1M5vgoSC6H#bS%QzkXZ9_}@_RZ_SH&CBYFQUo9qZ*V8V@e3Wct5?)A|& zu@p_yy{n(P7ugZgF7gA|cgzU~V7k&acTKO%d4kaHR~!ASN=yB8dYV>FvrZ*;%Ywy*l%#>E&kO$&b8Nn^*QT@09GyGR-(`VKENo; zPDNP-WwE(LZW_sImzzVLMs5E9O0aJQmv+94MotB81Z*RoSVZ4z-q@f87lXihr$<|lY40&KJey^g%j;@nOnZksIzt~0w{xym#3D0Oc@63*tQ zr=+@G9vnXQj$CQ-)-T;jNxg%~jEc%75;M{WPsiObXKX)yv?+^TRp{OuZ+Y)0l?iTJ z36 z20UvntQo(0<3S2 zLaK*AI3n9zjXLzONfmCPA|aOmq|~IEfAY?`v!^Gn(ae+Kt#y$AkhoDQw!OC9pyV^C zKTJDwN6rwE&sT4Kag@`G%q0%ig1&C@d31nwVA&YI9>-geWC!q#Jcw4I66B>GV94z63nkX^+Rb7|;_yKI+A8>!7uZEa4`aDSo1D4T-SAs(~Rp*eE+;pgh6VILZoa1|@$p{7S` zt-pnLVlV5KsYuL!=Wd@LOf-mJx}{|nfGZLgyh~e(%wt()7)q z8`9)PRQ|B~^_3I3acte<+2C2&!ep)&SHJ%^d|5sJL$>~WMnU!Y#kG5?kD;B&K;U@% zcc%TQE3z`1jh6}coP@|lK}F}D+8dQ9M35MukL8d(EscLnR*3R`TNXKK78Cn7^%LbY zD}MI^svvnDnl!D_WvAhig;1t-0bnkgWY z_Q8)YupE?Njw<=Zh!3_lH5XP!;r8fai}t+n$Lh#HPVHo%_s=K!-J0(PCI>$XS-l>C{Z!YM z{~SxJA)c>XlFaXAyQddVH1woZcV3X@B9La(thn<$gi z?Qr)-^gsw8M1Xpt9v1f9Eau7_)nkK#S?xQiB2$*=(eataBSm;D3!9ws*^N!>kE;SSi_!@%g`?u?L9wj?Y>d?z82$vci%52nN1=hC6vu!j8APH|$;X+8iNc1yT%@Bd zYRBv>EkvA6(4@s8T6Ws_2f0 zNf{edBZn-2?;=9HcHAL&Vy-)5qIhAWL)x*#-oV^Vf?8S75_#M^e~IPb<%L=N$|Wti zhM&;qRBC|Md4B_-S~y$k6o(hwjAmpGCBl_{P2f8ur)9@?VN9>HgMfh#HDcR!l09i8 zoKYBZaYQR)m|Oo~FqG#>dM+7E^;AhfJDuT-^@`TyF zJd+~ces7-`!8_v)F9E)(puANU=He!wIC16!_?Z;y&Df#(m$BV!yGBy*(~E3MHx`Os zCEb=u5x%}H6RDm7bn}>H`eiCaaPoU81_6NX9X-E!-1}p}D5{Op-y}MPO7-0)7nU%4 zCG)Rvcyv~pL-F&dwY>*5hR}fs=UOF#N4eR9iviAI!oK5xZelQY7@N7F?_1bL4a%^z zFN>6-R%VnH=5I{<;~A`6f5_Kwot)wrT~X;TXe!h5Tc~Ew-C59)(^hm z25wP(d>KT!Bm8XlMx|2?SLdpc!h-Z*8F0NR;Q9)_rskJlpMqJr7VxeKHizkVMiU@j z_Lgk?S{RMtc(U64FJ}dcs>CFomB~B+P{yIGkzPUR8!;2pUw3h*ehL{5y02}mpb?CO zzyzJ| zqoqUm#(00vj&JZ;k(V+7CG`IY5zEoQ;?s<&>s&H&u7ACD2Gg7xq$emZs6M%(^z-uf za@{wN%gG;T*(kn!%L7?2E6E(@2cpksHNC=2w7OkoYD+#8I9e_CLpt>BZMb3&*nOBM zDwZOEj7Dqcr~wJ9;aT}Ec?1-$>Q%CGID~9cNw4U}VC}>1=S{a2$toq!%cUk&pU3ND z_F@VN$IsaRicm2G3Tqy+RiD&Pm1(RW>~z6^c<9y|?C(}9FoOgp5BpC-Bj2B=quHDG zkCIAllHJXzdM4e<8cj&coir{JzQ1*A&7ui-gZ}>_SlD~VekL&~B1ld{&P~oI0qAi= zQZ`7@+imw$8$1ng<3o^3od9RO_0o=jz?6MvgbIQ6)~Onh+oV^k*(L+O{kGXU^~JcQ z0)&FzBA#vcg6Vrb>LJ?;$EdvF@Teg;;cI&p2a4#5_U2hNS#1!a4UoT_0Xh+l&uFOX zdY{Mu3h$E2Cr85g)hhcj&k|i)UqaA^*9`-unVF8qAT8CEzf#bpPUnXj=55frL$T=X zE5Zx@gCas_I3$V zKC%)gPZ{!AMm5J7jYSghMApAVM%N#o9k@cP^^99-QfUS8lDV?1?BvyE#s(D`nx7N) z@#j#^$r~K?++q52tqkZwX{Dmzy7II;{THN$e{--<=3{i-fUN5i+y00kUb&&Imb%^o zWH1uydl>HAe4s;us0WDDp^A_D&eJo6EOhw~0I6VnA)eG`yi~W=u1tv+)Il`x1`jL3 z_j`slasSBZ#70}`Lf2)y)|1O(pi(TIyAV>EEVO|e>>y)<|4nZ2Zr#N*MX6mB#`CNy zJAwLxf64m4%epbH?q!X0)EC1<)_$M_p~{n=?|l||Y?gLFzPRmUK(xE+GR7Y1aYls~p^ncx;Dlb0^K1MGX_^(gF9N`wyWGIBfyS}3D?Wr3k7z?felZ5PI=PD zaY6SJ7*-jeiiyo;LI~{|?{`R1hVvTc%K(=A;MVglz#e#Dj^QO+bjS6T%#2MKkVz&Q zFZJR@+UiIWm7QQEb(NR#>-8(3acN zTBMXuiNZVb4y73iJPC?k7d-CgreHMW{)tyTa@xA%r(+06PKJJ_xXUuF?FN=*i_+xf zYvR3RV*Vh_T(akUCgAD~SdMnd`@M;|-u}0(4et=&BBXXAg%~InPemc6{7d=)CjE7m zY5~X)APn_f=ffrRr$kJHMK=n z${3X=POg3tX)F~flnkHJcQoxmC&!%-2=p5!r#Y6Cp&CGzYBg z_dI>x1jnLFk$mOiW?kTXl@Q&I3@k?@}|}B{r?er zl9IsUnu+0`v@i0mwIJ zZxnaKi*0uXFFle);o(FB(`ZPB-?$qyNs>FT*1mQB0w`WIo^AdlEBOte0mt!Jvw_BaTi@{yB*PJ=5l zci!8GZiYSag+8R0!~O2E?S;Y2-r%(a^O{NGbPOfG?aM9?MaM`+bJuHa>A=nmw?mAMCr`T|(!J~)e?>P=HG2ymnr!deZyjrDbxqr)K1{`LWP*1) zn*&EG=W~~OprfvZCXsmL_u8b7ZX>eH<%Vrv-Zec4?cp)NO6)B!9|hMyZ};4Gr`iV6 zgddO8B=rka?riVuU3#02mA+AS5Kj zcqrRy-k0b&J}gb^J>u9&EpXYv_$Q-*RJi#}HG<LC%KS+S3VIo}6ms1LmWxr>!?bdI7$t3H8Z~P%u zX4~kEW^24y2@^S#*ubc0Cn<|{*_n9C_Po0V_*}NPynLKGSx5bn?piq*;7L85CwU3_ zo-BwoH~r>!WJyC;r#p}1{jz!a_zrtCn=5{xzF%LZv|Oe{0lqBxfzoPp=VH|?VcUdc zf$Qt*H+ObeFMObEQHN`ueLb;IN3?wbLkw&XQfZx}9PKr8?nP14x$Ba}t3w6JD@bmIeLmjh-l&=t^EXJ|Ed;K*NqHH& zl_=nvLHhRxgs0qkpJUoqY~J0}_%B$xcLTl-_0c~X9ZI3t3+6E38(-_4@BGB0JL*xQ zV9R#{ z6viC0)t~;dA$@!3*tC5%>6W@-F_fm)Y_mmGNK^1ER6$d>!o!EX)I|uTXm8)B0@I`I zW$MWP!=qiao;QYqvLnOErTJ0GdpnAY&8q6Ei(MOF?lZpit9tJ0lz#rW5sNW{M~epB zpGr+8-exagS90-B*rKM?2b7O)E)m%e9Cs;&hwqqYYd~BI*?5k>24Ze!oIpCmCjeE`S;>PZNRGS}h%#@cywhPxMUs(zwGWsEvg7EY`NY4kx zvrt>blNq%e#)ON?`5K~6<}>`WgB2sO)*0**iyhFJ;x!-i@nHd{o915VdfofZJg3ZC zr#d~9Jpb%YB44vAGGIDU>5lyb!W5nGz_vbAy4my!Q{nE$RMYSqg<3Z2DMaNJQ~ht= zxEi@-(Ngv7quY4ktHoFmtZxkFqpKB;u=17vU0Xv>|6KlSqB10 z00i*U`p&7wRXM?{LVHs$s_u2b?zjbDxg5x{_o^rCZPay}Ev^`UO0_ zpL^AycPFNzmqaso#%Ef&*gcb>l(POy9VG#w8FUp>+lm>Twy*K#n&i(phG@JqP-0n! zeB4}JRi7;gGND%2SWMhrbgo%+gNq1EUi1WB$uD2Y*Ent_eyI0$D2PO4Mw0IwbHD== zdtpHXz&Z4@O_Y+;&s%!#<}V8328uaCe}LWzRizVeX83zwVu}osGLfOTk_8{CV`;w0 ze7P-QB;V$sPs)Fw@=s&S|K7Cp55lY}{VoT3myA2;%nVmMV77C0T-%%yM;oiOckW|! zGJDpKr` + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_color_sensor_8h__incl.md5 b/doc/html/_me_color_sensor_8h__incl.md5 new file mode 100644 index 00000000..e62c74b2 --- /dev/null +++ b/doc/html/_me_color_sensor_8h__incl.md5 @@ -0,0 +1 @@ +564b38f6c9bcbb882f3f4751496a2ea8 \ No newline at end of file diff --git a/doc/html/_me_color_sensor_8h__incl.png b/doc/html/_me_color_sensor_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..02dde871c3a3e101f248c2d33fbb4a0f9fe40100 GIT binary patch literal 46663 zcmafabyQSu)HNkYOE(Cpba$hIfOL0BOLv!uNC`;8FrXkH-5mqSAT>xg3?Lvqbi;Rn z-}|k1t?!TT`iE^uNJzK}@-iAoNND~@NXTlB(Sc96 zP~2L8ztG<)%E=(z-u=mGEl5N{dWxhV^HR$Pv_0?Zle}7cv%lx(jZXboSX;I-MHCq} zRaClDP92I9Qa6#~nEcA?^JpdB__CdStVCAL#J9RAdQ4*b(hfYV7ygVKwWVEl9ibV2 zUb;dme`tTeqMzQoxUNhTWO)6l_0YOOYBCv{elG}|{Ml?*e8}J_!~g#>HdiORzi*z; z1_pX%CNt*wJEYe9=IXq+F!~8W!ggt82jERI`mb-c^?9odqmha=N>jgn{lV$0gv#OUmuPj*@s z>L%vYTU$$ApBjk}5hU3Dqf7-}|M!!MYBr6mU~uV{R;zJ+arqvsr^!=oeD=8M!gm{% zA$Do>uP^=cX9s2Txcl2{O4&4xeZBlUUdh>xocG+km!tESLyTr!G+#KpnA{%9HYFg4 z1m7<`fj)M^)&?`p|91FVU-=qim+qsRuD?lqnfqGPj33=lPg7uiA+kvaIC_zXqeoRD|8(j& zQ)71|jq6`xc5B>e0Tcb2Qg5)0KVDpa{-+|rH|XFIUDdc}@N)K$pttXi@yP%_erA9R zViF_!RQdLOuio&r*4eiM3x{(2?ZFG18`xr|3BHN1TWfvoM=`(HT8Y~zis;7_TgWRY z!kt;F6am9oAT7?HKAn>&vE=sbd66Lk9Ef!>?42FSi$5|ld1UOHD0drRY1`luzSs66 z{I;WEAj>m!zxzDA&SPtxm9Q-sD+Re3HPJq5JH2d|hiPf$wU1~B<2sqX#fz=IxMkcR zR^%Tam7wIPEvtx3h;KYKZ3)=HzNty4`|XgUf8ub;J8_t>nK(Br#&vglhiNGK+B)MxQFUP7n&Il_uJ-H&>?3tvt~JcPZg!%E(mx7mSv3 z+j((#AZL_yq;|pegUxrdUct08ujvbDefkWATTeV@rxF86P8?>#*#b@{I08Cf=QpUM zQNI=atiPtVM~{pBcAGAJX79s~HaW$Z{g;r2Cr}KSu&OEcZ2NTrE`-nHqcm&=Vk-*g znb6Xi!Slz9{QMin@_L4Uf1@L z!YN|jV2@6ApyX~0THmzzeEPv_9QXOR*^h^$^DC_y2_sWorViT*34k~49ItM$FTiaq z*gG3+JZP)^{Y&M|RZq3q_l;-W&L2ZP+$Axo(Mo#smS7{?*_UK0HA2+}U15?8I3jtB zXr1I?e6+$Sk3)1or!kR>6`}dvd=6$`eh?A#GCXA82-_;|4W^J2$`_A2>&(+%fk3)~zaE(kgEp@GmUW7}ej|c6%j}j|Deh!g`V+!p?Q=ATFzf*mqKG}T? zzV(6-ti^a*P{Z{2pb5LON!TAD?!wCC%H;MqV7$7D{P#_*M6!bn41o#{@$1ol7akm$ zjo(|jhOk3jyRTju&io*2HWcsm4q>C=Ea#}oaKuXd-MQo5TP`DZr zYeIfhw#sW|nU$(f=v9umcL@nUQ{v&|{$krsDwuNQSz#{y`A~eL*en*AziBjWCS0I( zgXB5G$l^n-P2k)ZOI`OHDPSsdc3QjJd_`T8MOxB1>o;>|DxL`(zdd5H{4Zdjk8$1w zW3hG+G`J~wyPFLQ$JO@&qVcL9hiN_|$6pv}&~|2Se&1un$7)t?N>4(08Fbc%6Rgs- z!pydHA>xK*Ju=?uAN^JXJA6azQqZ-r7EsqT6$FkIB{`9?nBbM-m)}>2QKbZ-IlPdV zxF!?f*)7g+p!#0sYRIbV1B+(Ct0G=;g(l#A5DlV+>PUo+ksHXMWBvCO|c4Vmj@3Bon zfA+)in}|;EjnxDe9Yu``rP_P$M~`VzP@^wbw9B)8>TNVSI`jG!Ke0u*O~1bRqHm4Iv==Z%X48uzvwpM?Z!vS2lf{wx+E zJ~=WC<2c(WdG}-e!Vhn@`0uvNPmbmewv0@w@I&AqgY;r4Lsd=?@|v^fNPCJ zhao7!&eLG;A=wKCv2N`VqeRNrJ*oSG_>+mx%SQuanE!K0M=sUfQ0)~}8q?I~aB0*^woSP5=MRN5 zH_W_6WQAK&`og}R6s~VZ^5^sLUmi+()m4!J@sVZOJk$S})33WSlv<}oDtc?b5yWsi zJ2!yuH!JoGd=$6B?rO7IVGg40)}{`Z2Hf@UiArKItB+4{6I&t(&8;Uo8WlBvazt#iNMf85}qao}D-cB(V9`6Wgz)v1RWG zHn1Op_EU%m{+YQs-Xes>Q!j(a%`RU>?ibOGzS*~qd5krpxT>D0PH;zQ4a}koJI$7x zNEr3EtIr>h>>yR6^FGcjp=a#%%WlHOW{%X{0SbGlI=RKX2;o%mb;2=Zlw5iD3UhtK zgjWb6D!ukN#D`~w$#S)yqQ?w3EkXlTj*O_*-bF1|t5aEK}tq$U=wnA^tty~5^S zT5YEs)Id1#C^9<^d28_eCzVtgOO=$2kx4uM7V;t&Dffa|fc%AA3}Yz4PFx8p<=~m- zKk*&Jk>Oy8zId0QEbzRekpG@nn9CI>w)j+Ho{2HgS2UU_fD=IjZ^~e3X4Tv}`P2#i z_OoRH|0qN?ad*!hrvm*!} z4T@0(xlLs(3}OZM)y^`WMe*!eSY}AqTw3bSHu2jvfaXkE1Q0ZoiL_AV`si)`ps!HVuhdrK!@N4N+g((>27E zr;u%v@bAAse+Cd&7rr(OB~QJ#c&V061oi+`!NN+z7~r?C_WU-V*n8}+XddUm+&mPK zI8=ZlJZVmd5ONRtidCquX1n#h%sHnB0Gl>&SLX?l^fw-Jo5T(c$1B$*Eq{)YPT5c7 z|1nu3@g@Hz*H{rU$`X}uqqdx1w0%dCcO^1F*gIW)8Jb=jJ`ukm;Rig+LGe6HazZnJ z_A{zKd5KHG`y=ik0;|{i9eIa7J~5b~e6S_vkU#_-*|<&xbGce^fk$% zv;Fr#Er3np-u60pw_(;~s5hFU3Z!rMk1oyS?WJs84Zxpy=Z}-l?(wzCyplNJa zI9%jW;mhq@(t>NlRrq!bIcwH|)p4^LuH}X>hQ;T09@(Ddasy=*oL5PkR zKlEgoOPfj0{@0Ia9NUK^K+id86Bj~_XyPe<-aYP}tmiIx()0jx8t^CBEJZApOjVVt zch420gBlI#OvW?dkAUJ1vPULrp#IUtX%EjR#O zAV+${K13mM9>a!Q9^7B}`SfQ0=yVB2K)YTHT1AAI=KJU!uIU*zBH|Ny@8k(z2Ongj z!9vJ6F#_McNCSpXmNX>=tc)2b=`Bl-VsJsZbHZ4{GcmbyB01Ly!N|pf=bE-xy|LrX ze}@Z;%^3C`=$9qZzqwQlpFViiCc~w%;3;Svj?oiig~uY4kMl9V4$D7J=$>@vqA+84 z^)xKLb}Hhilgll0WG)5(sixLd>j^jK$9+;>s^jPMUV;oI86swFlv&y)o>ePUV{DB$)si2U7Fo)vkmEH6iXLeVcNaVwG7Mpj z*jwKooZoyt8tkybs<%FjFbuH?(XLT_6fMG59JM|EkCk*o?BQrGega2RpSF+e-L}UO zPz|u;wBx|kb4=0^B>wJqARU2eK}-K3ux)#gCh1i3O}1B(*kqb32jXoH*QYPe4*5EZ z8>zd%nQ5}av3GP^CQzlS;_0+frxevEU+j(ZP)a@`!hwp!)O$Rx3BF|9_-Te*jAD!P zI>T+or{#`&Sa|AASN2U&%1iI zAiNa^ZPp)(+ap}z71dhRY9r(Ky`)1GGbWlw^3hd4Ji^ee!EyN6rOjBa!cg-3dROnt z@2Bv>KO!^os_3Y1>ZA^+5yW|@IiPr^;wb&%O2kO^L&Qa@UD{=2%AY1S)Rtcyc<6u; z(bR4D0rmO6%QpL4`RKt25=f7{kkz~a)|sPn!nN+A&hyv31J8q`O*qL!LHK`B$MYI~ zS{JoG@pSwua^J^Yl2mxm z&K?Gu$aSuxEPB~EIaUVNm!A%O^cm@QDVkE5vfwUg`b~P|Y0P_M)X?eeY)6l0gh%~P zO%+mGtLb0`tkf%M!gt{}3Z8NY+5X-9q5O;@jMs2+r94pq04U{9hPuin6MBU^62aKq!>w zgkXo1XIAofv>6%x&Qd?}VJCC3`>>>>JSj1uuHEBwUEgQQ;?z#c&Qc&0eh-q4JB zMh5MW!=0E zbL43=Qwe|V4xa;OE~m^EOj7~Kaow}N*=nYTCztN-LGD)K8S_c?mLe4e%;VFS#Uugm zrC#qXV(=GOuKGduu&rOsNiY}N2Y>Q2;+0^<^skZ4Fse^@bZ9JEC~_VP)44F0a8wn1 zFJYqUOAIOyvq5eoFAY5$J(m^a+ia4l`*DXGAjNr+^6S*KRm#OoUEAQe8t#pHRyGNr z8^!?c9uepgIVe{_C`_{OI$@Fq%W@ToN#65YU0@$~K=9382xplGKj!w4v*w4`C&M{k|gnth*f4}YeS@6Wd$S{6&`J6Li; zUa*1TQVF^l2RBG+fsgPT4xd(Zzsi3=;v|k_HgTJI(wk5|LLYYz$xAJjn!3U*!i}it zEs0>wm?2bCcN=H#ps@+)B$;x3YHpb_IyfpBytO6bP;C9D2h|^i1w=Myiv`lAt>}Aq z_08{VD|kb68Iucx{F=O0)O@V|;bo3q`HnC(xD&ZxL0czTxiADh@qutmbyP@#e;;9q|^; zcxm|i$h#iH|p7m}81n%|a)Y-U`%(htji2i==H*K@4A zmfZA{@!MSX8(Jh*+vO(nq2rc9U(_Hn>8-&|xuE6XfoAd`-&}hMKS32-F7dME&+X09 zrV^?uDrVB{PrRuT%f*>_#b~XfT#|hIGs9`C`ivg)0pyx~)WE!1nBmwE-4G#~wi&uR zSWQ7hqMwS0*HorcTrY|0XS>$>d|ezPK8UCnB+ak%_xo#Q-xFH_rGkT9G8YmgH?6d_ggg^9Rk1CkWAqi%>&KS z9ZHx6h`&yF2+}f_dY=z`JY^UsJnNt8%mZweWM-*7?Xr@Yt~?^LGY+fG=&W@C5o3C0 zs|8T=MR20LVr=32D03Hd2wb#&o4_)@4BYJobT`;w`ls({o6GVlklqS^;j%g}$ zWKq26P64BP1uB0t9#8ep_FnJ}Y@83t8%nV310Yn;MX@`qjXQbS4PJE>GHs=B3x(p& zRr-8#jBI*CVL(beBWgxdk+(AWpbl#6xh$WU*ld8MeIPjYD@Q(^?V_UDbY9@^J_9^G zmeofumue^Lu3HOo;<|uBvU|{NIkiczUEl{ z%ec=nx$mnS3t6h{-<8H7@A9u-d_c(nijUxKQwM!QQ(#8x5)5Ob&yj&?(%d_YYO=PX zNqmW}KPWsb`yrn2c1fKPBU+rwknyzuuH>PmTG=}0&5^p^`97i`B7}0x0YHyU#-2yY zFBSn=VIRGXg)K6cWomvU47NN5<*7zD2~soxGPzX65Da|iaSP@kF9pMxprTjr2iry! zdAdnjzu6nzSxtFz$pv5MVq6JbQdeE9)^Cunl~=Kb^iy+YVu#XPy@2kF%2SzvFbj}_ zFom7HS{Dg_72;$)U&S;9e`v&x+TJhRO8oZR3IqvWqyHowbyQpW1+Abv#`9x|>q-@;hF~WDmm+QvXW02QGxyGf6tFsXkfDNH*zz zqiEPbWf6s;RG$8>|9hE&%tgeb=M!iH%+3ha23KRG;25TBCi;NJ*7_*<6A>n1fSHN7 z-)uvx@rDc_)jxH>^V9KRL`6jxMI$ePUhmF=Q2^-4BzFWC0pd9*)fHC6Qr8VUjE}4g zF~4ZHlq%fQ%-84@WtUX{xkb*i@*4d#u`hMs4!@C;`-WQe4A(GbYc^9n+H&w;z)ii| zcVi+?n%C)^9YCc1{&SGsCT>4>#y~&0N9p!g`mx_K=3@1a@KuP9yQI2dNsgS17i6Fq zduL%vk{UUHqT$)lxxMcQ+uN;x%#{jR-fxF89Fd>y&z*vI8S~afytj*7>Je=fHQrCo zx;{h2lINQ`=_e`BQGdOFYfWW^eCmu5O{~d8U1|rQtZ{gn_1I zea#x;rO>YDdITfZ*=z9)y0|96gc~?K41Zxw%Esb)x1}7=+wP2}99`f9phRtteFn0W z*Qj+hE%`3pQP*I1EtcZG*i&1_)g(X?e6g9~XW`$W;EhV+9Xw>H`kEqKgqN5-!}7L- zqefAK`isE&t9Z8gH0+Wtkzy|-qsdKn z@DZaO;|8=}q%>(vss31f@)>|Aoj*^Q%-n$5i|h3CjizsB`)JCLH=w8ws!uX80QT~o zHOl)>OUF+w1(EIx<8v}X(b}bS8#H?tjg>}QFKX_+{ zq;#jXZDl=caWYw=D$rOdkL!+IPAyPl223yYO<7Z};F?f+8Z$_EB04Z`FG~;0J#SpM zY`p7qbWi^ET{ao`=l`?3UkdB$anMK;xlp?M2eDdTWZgTTNX}T-J6XslQY<=j^=AOg zK#%{ZZMMx5sisxBu%LYJ>aeV2etumR{X-E^2}uJ$i@56I_mED15e0#}8yftoN+X*j z6Us!-;9JH-A! z@_$=@q9+>k$u96IV&AAw0(uyLn&dGxQKmU;H7b4Nm`{kkeu$0`FQ*Z2HfKa18b!M>-pw|OkF|2WFb1^ zz0sY33=}h>$*fWqoXa= z9TQ4{?quZ+j!hZWBq_1W1PEQqIjHiQXLCkI)Wc|H^Xd>Lnte2VFXJb&|AQrVJV_xsbpPLwN#&zH!7hl`XIWN(;fGxeb>l5x%16optreBu7IG z=K1S$SWs*6&~e=tFxtx?nSCGh#{?9vZNJ)Bv~i+RFGSG$ z74S)j)F@OhT0ah8$IA5)1}UnrnU3yhZ*bL-efKE9JcNBnqiJntvv;~4fCVjR-ZQei z#Z4d&M>>zm8zBOytz4=RQP11#SyQt`K+D{~=BCIQCtB({Y$UJ$fHiEW&yb_W@LJsd zp&%l+pnlPC7!)@DD#YkB(-p26$4+RxNIATuHl+63{`(zElWryD*gRDrYeyS`O9Cj| zUCI_nBzsroSHAuq*epH4^V-nOw5=!^3u)6^jrcqx|E{yBzPV|aFBFyUc%bf|cp(-O%aJeh_moe`cilU<^w z6pRtII~|GgaU7uc<;XU_s9MHiW`Ell=!coA89JQG8E5`hd(e6>!u8n#EK9U!bcGdZZt_<73N#}}mxALW&|P8we>%MtZrgk3!Vb>O0gpPmsZOa#{(^wThT_jQ zG7%uGB^TO%?f6;rTT}%@qUreZPPd!QjLGMiXZswl{;fLLjCuuDfFtjnj3&N0=-H$UbEP5nnqH^SjdubTn;(;Tv9vYRU%#ZbQVX!;-}=F><)@3efP7POwKd@%QEceHevL%k_@2=*1)bsD0s; z8Ky{@Wf*Zx7|jR0enAy93c&5(&sjWdp?rgnDX_F3fT5`0y%80-omxXCi^i36N3$t7^BP!g z2#FrEt=mujJ`-2xhg-bWF1H$$zr1nXg`e@`J;K9>yF_#;w8uIGZ*zpTe?pLjNoDSn zsqRm5@Z1z>(uL`syDbVi);kcM2MEWKr+QyPm_<)m4m)X}P*aJ$5dH#gORmsniMoK|~xT?d^WD z_~|TJ{rR?+&&_A??4#t{Z>u|#VXKp{tv>tC4I$$p``Ac$+<5yg%;a|AaI8FF!P|ea zQoQZo1^kD0`H5w$cd5|s5o6%?STUyItzBs*X~g-X!}rnKKNrfx;z8L*r?q+H_Q(;# zv`G3FJ^1l$c5q13m#56!l$tCV8ouHZgWIVx_Ax??PtIum~?cV{9y`s zbWGRXr$i99h*c5)LpASwUSmKGbH)H!A*|qP5q=sp8z=BEb1JzSRctXFa_kt?H%P))H0ySJcXKqh?_-AxpV*pZ9EQ-5LiH@6 z!@{~cWNwDRH;3x~W9RCtPrxHA=FGSU&Fxfv|ImIO7Ch!7zT_UdhXkmP)7t8j)wMtY z^Ja~R#7q1T@^hCO=?Zm42)!TGM&Xjb!0FE7{S^~Ecjj#7Ju*4jrf=vFys>L=#|Fqd z=7lxI%`|q14X2YQ2Mw0G-f=i!#cUj6JKA}l?zr4xI}tbC89O2wAU9|lT!3SouAj8=9}?B2Y(=(G7>V>1yJA%TDziF&Jw1bE_q5e1tHCw@tu{V?r2FIVtT zTc{0-{ZZeH|J7%C^arXC18^u+xFW<#+Jf9|`U9aq^Kw`U40aKADeLCf zr!=4#@{Y<~rOxy(uDl!ee5x7MNg>b2HGNtN7LByBSlsrV$#YuP8$klW9oYd zlwE$|`J6&ATw@!~eN;DhUlwjj(e^*I8@)Go7UDBgl(tnBPnhJDx3`M$j?!h1$gtT9 z1dAD27zzEH2zz$+qM$UDugxsLWd$wRS-#+)Kt(pJhoxU$GM1yLu83P9h$}>=A_UT} zyqVH@#5S1FVe`_Q(DnCNJM}=Xz?*h2#wNrR05vy()=l8B83tON;KZ_Gqa_ipdKaI6F?{57ltef$kS^<`zP4eJR$$p^oAK{{ zUET;46maHdRy)tefTNpUB!sHmH{(Zo_fr!>NSZV$U%Q^yCOSBdc^)Ub zC$<@y{2t;_@vt!fl*6|2lZ9!$BQ08dPLORTU!^VpAh=v`hp^IY z$bkIZDwf*hZtYk(znCb{M|fiw)}4FU+kbRaeV@Ro*~mSQpf>)aM1}qSlK1mZ=xNG+ ze&g5>)p`B+pNWdEhwqHdr>VIdfAvO~LcXAXc{&dY;De0{&^w@*T4JnOH*#+{4=$1XUGD#lK2d(Bx~K8F)~dKze{dU~__ zy$C2-!!$myDzFx?y?S8{IiUS$DR%M zZt*TeI08q=X(9dOr``J3-Ti8*KWOYx9pAwxa$j%nZ^0s`3$vj9(jkJpqGu*##)nAi zdJ9S>t*G)vwg1#fGTx>G6jS9@H@1zCL&L#Aquilt`JspW;k>iNGNp?tlBopM_{MH* z0wz$~OxfR{Ofkyy_}*w;+6$ia9_byG72WCX?qI4^BpxABG?q3)<9A$Ee&q)rO?O;4 z)YLUC$6NK;7T~vG1V9h;npbO~?o{FIIV4uv(VdU%t|C`8n%X2M)3*39&>_PFRvgT{ zL2?{s!}-KgG^~?Mm#=_k>kX-k4Au)XrHTg;_UkU{5t9%tRG%bF8$%qL(f1ack<(x8 zU&DkIlx}uL*#FM_-^`Ffr@R+5N1nfKip^%l0>zq4`61KyH|Z1B!MReIm*(WTSrgW_PRq$@{`P7`owtM$j{vfuu!| zL^C`X|HWF1(~7c%N}tiJ-V=V!f>wY&EM}!WwOK)44C^Z0@pq%j05RI^RW{efT z%+(#~+chlK@22irmKa4c;)zgJ(7aWiN?@{M=tUe>bmXGP%}9#>ypb}V3`+JucA-R! zx3!3}@cwy-e8-H&xzj#{eF1k)6fl27$vtZ{R%bC>W73mH{X-n>YM?5Y>MTGS$jg1O z7@N$;Puj``*gtySyqd0USOMhg<|t*w>764E7^wSs!L$VvOPezcmpaf1<+H#whZ4>@ zci!4H*nrWl|LTvkbg`ahcNNu4MH>y@R=R)4*-)15GiJnBDk<-Exd$DR3JV69WR3Ja z={(3Qxxz%Dt)V(2fiT*-_{9jAvmX^DzTd7+TMSpTJBQ02DPxe$w^kZYeTM6-`{vO% z6|iSA4Ti$=E(=>6p|u#2Z;#b>Wz`qp*)A)RaPPsvBu=n-X4A#Yi0Gn~4>H}3I4RAP zB|`p9&v)gAf%5lA;cO%LklYS5l(DUZ-E6z;ayt>t^ zy!LXAzpsQi(GTVu*+>ss9RyMrQhY|FBCDt17~`^D`p`+$Gd{f9ba9Tc!D}w$HjJyn z#&qlp!y(W?p6X-se35MAlTKe^3s>?3qAbo0|NW19b}$867v2rT`fJE81RZ`#-p->} zX^yIjSNq~@b~NbyPAa6sdH@)SF$I(Y`QV3v5K+J3xyQus<}$I)zqZ+9{cp>@?sWd7 z6#6|IuZ8Z63|fwpQjkNR7z=97{k|YIMY@8GJb;-M8|r?UV&r5DOwvuKdM0rkvXHv9 zQ%IG8J3$UcB+*PQ(^>uRqf1|m+I#1IVt^Om#lFO|(Ne9N%q_C=2e^b_OGxAnQvwXh zjhYsXw4PFGlqB8uZg|c!Q#dLl?p*-&IuS$?LIrUSC0Q#efFWWJb+MGCs<yStfm{j10z_?#KZ_ZsGUG~-Lugx?;a4w zRRuSc&`kH0N-;12^u5GJ4$zrXKP)M^TjakaKnS`>L6?Vp`S0CId+NSA(dRzEjC#ew z5>MD-W@QUkM#HJtE~)ClbGYHImh;^2?(3arS@L7|9XrlTV3tZ(4e|(5Yu)lFAh7Th zn2iP_8X@&!s!RQNKv%!6hH(A)U|qfv#vDwQZ_CF+c1vomGq@iBjTrb_2EE zjoPG?2RuRtD6cmmm5`fP-DcYTn9q6$5%3@Ir>AnotT|6x-DdT00)E3mn+(ldn;BmD ztcUhi5{{nop@o_GulFp?Va16iRIPC)?3c_UikiOFxS??Qs3x(i| zFBcDU&id%O$Pr>=h7j-ffTgBBK?2NGJU$~q{P`E~w%YftrPqim4yZ@o)n!o2pWg7& zLk@6Gd@I80dm(*Pe~c?bQg@Uh_AztLHQ z)tKswlbwlI&;bPG?T@ozK&>~Z8CQsSprrT~N<7T;66fXJOY|`qZW?2{$y3$plj*qC zTY=e6;gWC!_um+RGOLXVM9SR%7U=g=-O695PW>zI-8tQS#I23)8i>fIvK#oK#c-eR?s~MJ*!9)kDXUL5*6QO1xjb=67jb>M3hk`pFlx7LYNhscMC^eD@R4H& z2bK1sT^PX#H#jtdf$jH+iNx?i&IPSm>?-1CsLy=f-AHJJJFiO_MK-cmx9X+gI^3l)@54>{Jl--PX`lhOn2J!(X|CYvr9!jzH3m8S}0rsEp`90YP(<*2a zH^s=HY105^O|F+_)RROh!Jl9rVG0m#cfm%2C*0nXf@{ZWMQj&5a_C))JpRlr;Nd#xStb*>|LU8CH_PAXdY5vK6V{fAvT2H=&sjpQK2< zfAPToa1TX46ytvtb0FEuz%#3)!QR!@JCu5d)yJ2B z#$yU}d%ZQ?nI;18egpQ7PsL+>Zsy&k?3lpu#3RMPxD@JqjE&nAl}8I`DWdE}9Dj9R zOPKA(E#seEazqe%=c5oQoL=~jfG$I_b;)KoZP~W7P7;IaQKi1@D2I2-QA9ngfnjH* z&KX6eqd|z&MRwfMpJ%h_Lc{6@23OXA>#ov!y6BtRkPsD%Vf?;zq4JsvRoiFtEb@<( zcAb@N*zOcWKS>Lh=Pu7+U1&zSeBnQ?_oLU-6|X|(jA$7on*86Hs=kO8I-4hrH#N4k zIa+O#P`?+924bDA>P1Y;IhSW{&h~1UW>DMtrX-YCjS;+<}Qd*%zjatI<|!&u%MI#Dq8UJN*m9;tN|!JlYzo9Iz>B;h(* z4vIV9nR$s^eqtBO5?FsKWPYDrH)D`3SX%12wXEujnJ(QyG8QGxi)wozZagNpjORGq z6hi7)S=A74xdvXO}9fqh_aa(D@^6lH36HTP}a^e3p{;eyB?zKOoYoHR` zS%AK=u-)QR+uG%@6!Lnuj)!j%UC7%;$4IW2S2lbD2su&p6gXlwBd2B4J7_JjsAy~& zVbvDn@(Hq$M^`_oPU}Xqn+=r7Ygna_HT0MnBL(%=#h7(X^=t5XRwB=Jca#K_+(L=A zKY+oX1@YQ!OFF%OwD&4fOSMjRXq&x;aEjQLUMsN5VfU0S2X%P7Nr=NJuk(j=C04C0 zUi-jtvOXWBhpjqM9BWc>S7j~HDqYZDg2*icc&MIy(6-!FThxmq8SP!UGeg#1yYPl) z?feiI96U{#bJ7a2zLm#{C>(QHZ0%udiNMPhB7wdEef(ntuZya5gOF*RaJG6mBTDDn zq!3c~cROgl-Fu*z4Sbz#9^jP^w5*FaGDB6P-88FWwn$@AX@b^QlWkw&qo`=5h42!P zkIXs_+l+6K8GkeRNG7G^`j(S@E4xxdYMnXtvj(OE$toVnjcIWG%j51EQ4TIoJ&p?1 zx989gSiXbhMhvdkWPNcKByO3eB1hWRg~yBxNzDKUWa^`AcR%O@iE>;&g~%kaKq#c8 z%}FZq3d1pqR8#N+RE9kmS~TKPh!zg3Nm@HbXyJ;GDM5|m95+?lLdWsJ!I&U2op<3;R)-yQ9V4N$O1_AB9taFWuVx#;pjqb5%1O-!f z<#^)Xy`WW%@f=yIOk2XGl8hX2xGt^O%J)Fzb-u=Tc1I4OPp}}F(Cq>MTu*yu)P#aIlG>lNvFUS<^S`G*DQ&Z2{%v2 zhL2mnvWMIvrkBWZ?La29;MeLwhQh(eMPDmTx!LczE#L9_)l&ldR`CO;NhK&JHA!}f zR$tn1SzpxhDQYK+Qnhzl!da7CnS)WB7V5GhQk0UD=tPcX^8;NTA$%uS8_p9gv$D^% zpq`7wSEx%8@cz9u6v5DM3#`AGnFq9=EW$=<>=sa+ZOA-tE?N_Lm|$G%Dp;%xu@NUh;Ci zhsC(2lMuVh53Nprck%o-u)5)9=%J?^)s#g8rv9?!5t`PSg(2SYLtA^*{_$t2Qt&)Dya!a%Xe?@+EISjX6T9W4D zLpQM3^hl5DOj0WYYMF=YRCq4PL z>{yEv=z!=v+f$>G&TfdAnX7bzpecH0osd-}dS8SKSD%cW2#>DUW9-Q-I|lJIRx35h z+n^ef*sVztTC@d^aLqLgtK3DAbNY-wm7GdstL$dZIRtuI>~sEdYBwA1e))_=g!;Xc z>YPs{rhKW?GBun|-OF?hwY4`LsC!DKwLUtp+Fus%7+1cF1F|?V%=#`v&jdPkLz*>N z%6?B8`*AA$D=;+ra{a6BUj?C+zCzTvW4-K9io8)dS`a;=H6#9tceZEmtxqkjQdGZ8 zBnll;CDI&ds5&{HeF6e^BgF)NXI&MX3PAw}_v&K%2T6+B* zZ>Pey{2k@QYoB>@^Iz>Ah&{Kc>U}^@y!1AuQ!dUmGDst2k0##zN^!$=+HUgCC&U@aEm_J&PIO|xiYG6^F$D8Zk>DZ&@2)%qmP zYckbzt)nGBIEpf2=ZOf5vp46-_pS??iip zrt2x_|K1=gWl=(*?%4U$P2?|6ZvvQB>c-<9q`jg8q>4hpU)fmZb^71ZYc=9rjBlc; zS)=5ZFZke>j}!FNg0^&Np_Yjx{xLwTNnP7;4#h%fzhCjvtsQ7_j=t=D_rM7RPa2Gd0TI_CL!T$y9^&zsXE z>X!i4fc9#__h;+%!S3SrKWLZoeYmxuQ;$}xqE+oK^4*eY0Rn)>O+=2_f;U&tcQu1` zp4mQ~egc#v_D*kg7)Bkd(Rzwogz4>#ETJE6pLUVVdp65ZIuY_j<%h~xwSAB7JQ$N` zKPro7WtT6WhnoTx&u$7sn=aqWh1~*v|I+!oe@rMpAfjgJotrzeXNxCnjxA3V{%JDH zF@zk<>c#)tUOfDn|AH3%i-uKIYO|4Y@#q0>L^{MfR2B79%;mZzzT}uSf6{tl!{kfX zn~^v>LLUyKMVBSQa5hsQ_nw?JHJe#X+#f!%G=18P#hubBuh>c7A6PLx(Ny~$y zU1F;-4zF!{qM^s@Sc~-^;#koBTQhSt$8j!mv*Ro*?Ta;m%$7%*s1Y`(_$_K@@c5^{ zB6K4=8qdm_b3ySGB}T|N7=n!ak4v1Kth+lCR|jtfSb&07yMp&MZ$@S!aCrsG1pLS*tPya-YEE$pW)f}fmDN# z(@?kY^u`4Z^2ja!$Ehdl0WYMi40dUey}ZLm7iRnTUiaCloiV84G<@lr3dlTN4KHH# z6bwkW2sxAyrkWyIb#>J{GmpAN*XTDaD~{P}Q#ktuVK>WV*6srT1;Y$TTfgcr9fm2f zA(n4q9F+wBtGX#i4vEb&X+@lPosTNx$7+HuTRsLAjjj3%8-44eVwQ^0{!J*Q=~N6b zqU2Q!@!ssq%W&`6E5V?2vL|m)LcJDm>L1HZqOFdDX}Jg|dm*o-*-5`nXU%gOlt&aJ zjNuM&8ueYJl>N+Cc8L!Kvn7(ZW@qxzSI!nDM7N&2$q8Hgu2GGVw>{_b;updUU3$#+ z!ws%#Dv!zh7rW>m9^W$c>GErq5Xl!Ec(DHx&eT7o5L#rF6RDA zzB-=icMm*DkpZ(6J+=4=HHnr{9a@xdp&!aDue+}kN?+&}dgIkvio(d)q+W8rhnnCg z{W_;;6+gwJUO-GUgs>)A{p8hIeX9=C%Jrg(c$jIs5iNG_poEByaG8y;OEw#tj2&JL zcgcn2^i}2T*w*BeGU7D$&S*$!FCppLh4_z!s9(o~Ntpy7yta9U3T=3Uk)vkxv!g?1 zE@8yE(cmy!ddDCxWK!&`F8WEGc{NSu@c$v~FQcOT-alYex;s@`y1Pq4=^i?zrMpW( zI;6Y1yGsy|p#-G6V<_qN+{5?xf1b0>oAbh@tmQC!_PzIYeQNK?mCT}5a#|M-*$T2N z)KepxMf7UypjrUH=o(G$QuUMyKA_#;ncMs`6Lk!RxKa0w!QusV+&9hWfcl(H97)DU z21t>k4^aNA**e&=R>U;3*EVTMI5)_?n75pc9(89cLSN1&x(Czhwc#Ycorw@hG`$z7 zZn>!e`Vxi^G2H>nB;Biz;k9r(%1`wy-sGU_$<04Pol%_Vg3NNcUj$jF+cQ}3%H|q^ zIzZSk@2ymCz3f!{)j&n#gEj20cRsJnlVccU|2o$fqFZ2p0T5>qjQvFyb0Mu<6<^Qip2vKRk%!#MD6Rx z7v^Gd-%S1}jA(&MN#DdS(#~+@6Se@oT8%pPNr`0*%0EM0FiuN!%1!5Z1z+FQ8=Q?@ zZ5j6~p_FIt2BnVznE#NDB8css>nCAh7L;9RK3navEkc*|2O0-2<48{SeZU;jO0K6%5UWWP%pRI|k? z$}5}wSFrg1HiQM;XavM6giho29}`LmE7g>pCIaXC@t?z;46&4ndH77F?-Z&~z;MS7 zO8`Pi2vTiaAk4zY8loM62qh>7q}OYEFtF{p0XI}=<=*k;)x}%R{!MvY{PRqH9BykH_3)Jl1M77QP$J``5A^@Tk|f4hi9f_mvtgn}B|jc_sqd9d&tBUYY2G&s`+0@B zt}93{Ltl!_T1&d4Yq;C?Lg?_+bSr|o_6m79~w;PySc|yPs1JJt+dn^9YW8E z1MMU0l=>-YFS*t2d>L!Xi+;~QopR7h^|RjARTa`Mwmx(Co#&|2GV zQMp_ehS4r@@B#f^gi3y3W3{ks3xhp_?B6tf+kp|fBoq#HP-(3urHYDQas<8SO^_#ylSiNFUerm*X@F?oU+cz43rqkntwDvyfRsIL})WGBkK1!lM-|18Z+Ki~#O)nJF*Qzn9*c0XP>ehe^2P=R=R@yI1 zKV)ya>CR^Qx}o7n7Ag`PgaGv6)rRg=KR-{yjuWb1Urs=B-V~U(M$) z&LKl}v~XBVkFC7abKb8ci(RbA2`)EIV_nX?Oewpm?Ggn(?#bX4Bg8QTppz(@F4*xk8q)U_|M_z z&2Sm|J2|Yj-T^`mY-x<--cJqN>5lpVj4EV-kP6BA;ZtAt4;Bx9oART8R<-vuPG?yL z9`)|t;2#xVU?Zf`uwsIF=pSt*+bIl9Z^5)+E$Yx*jrHLz%H&mXf4Gn=G@SULO^^Nd z8lK3fOU(;gIW8)&q0{@?}{^-qig0E z*9kxYh|r@OyTN#<^?JYfpm)v1ir&-n5U9<}99wYjtGKf_^7sBu9I>aDBsD4RQwdpt zWi{}37BKsT{UM6@``Dk0!DJRa&!?+7kytM0Z5c2aEF7C)^L#(oLz|I)-&xA?787=L zct=865AI5EnCHo91#^3E#TIgW;b|vB7WD_x274oo+YSsXqZ7ih-&a!wtd~Nk5Q|PKm{<^dBA@d809+6&x_E5I>GHWf3pAZ(;Jy&zcfC+j<1yj$ zqP$o98T>@ z3}!31y4O?;S>BQTMAdFrm#t+uPL5oA3Gf6rRh88nYGA(1I-FiZQB!Isb>Dk_K#k`Z zyvzYeG>c;cD$iuA|4IeFd@(q*kRNWoMoPy@s3uL{y~syTQ6qOuZ}k z)5<`FHh^_Lt_zjx<0;Mu+HZ;d-zz#@CY@I>h~LyEi43N)E(21Hyg()*iH6~Lmf;|v z@n}*M%N>sjlJ1x@o3@+&-@rWF@tv?=RYN5J13h+CLy1&O1++PvpCj5!%}yL=`CGNE z&S{wEzsrJ>V{Ekx(*N0iLg~o=VF?Z2B`=4Prq|X7(F#^Bc-2ETCS1<0CBOK$9 z|7o)uy5DBWv)cGYUEI~#*TnfJckiFvbTwQ|Phac~+>Ip-*?KZ)!LbSUi2yY&T+0cn zy1g5HMFo_XxeES4*Z*XD;b|SpLbebx(9^zhGb;0OtWEn|2GLPX*R}3!tj_+uH>iNDCT^h(Oqlkzy_0acm&dn*X5<}bHU}|79;4R@8jKZ^1Qm_d#}z+-_+}j^Vx#i zDox9&JT^HwaD*F#Nuoa4B!&77Hamk>a!%_ktx`=><@@Ym*r(jRk!2ZZq{DlSre{I}St6+zcw{y-a zSx?EF@kg)5*aK-ykuC?y!-Knh8Lhq2k~uA->i+KStx)kmfnNV03;%ud%tP68k3=+h zi%_jYDWFeIC%*_*p5=Bhg$*E)r|(}=Zdfk8#6Fc{2#WO+dh3D z^@00}+BQGEur+lZ?flRu=McfV;Jv&=UeZ(D<=biBH9KRvI(IR%!t-aLDRqpbQ_U~m z_EojSoqwTH>?NmWrNoJ(XRqpKOQ04)-@N?SDLhmzt2L-{mVHn*a5+Zs?ryl~xF8Ar z`YIw4tz{mrjjNPj>zsXIW_qY8j{M(-vg6V>r_6VKET#UWI1{2>DBN5^I-`r?Tyro) z&>o`sGQ$aY-W`I2H6RH%X`>}hg^BsQ6@hrN@#XWA4ghtq8XlC2fZ5#r2#d3YtJ_>j zz4OZDmUWn}KFygcdeW?whjesBfB+vVhW1hobb?XyC-gHNSgz*NYq;4#^C*sD^2TQ8 zt4985_atS9Z^Aw%6xIBUjYJo1gX5>;BlteN%xR1aJuU}W$2DoQGbUMGIyd!!sbi2i zf1-LzOY)2C@!-!j9X1@~qZ#xQ<+v{E_X`;96)AN2wTnOLd6VsZXtlNXT4R z{)yGQ6f~yxb0FP}rRWj16)0R5#tkoEL)ld$?qF=KL MXAP7&{@hbD1d+|Y%jc66 z^>JRR{?_Wwx8Bszv-gf|!a-}V#CW{QF$`7tF6-Oe{k_lBid!Ss&9OD+%1R604MQrV z`K_P8gk7X_m%#4$AVjHK!~%`(m(cg%XY^aIMkR-uG-?M=f(nZ-ouuKA76ii4D4XNQ zIN@UuGgqz7+msg+D{i~ONjpJ8r8^IurYD;v&E4|zWW?4*h;|)?2TTBND+0)8(nR>b zwo#llJ6km?7E-S}lq!K84ms&1JFHy=YVPY_(9Y{|tZM+RwmAOZa8c$UGRj}WOVLu$ zqR{A4H?5hujQ?wzp@8ZiFOx;~8gOJpY|oJa*~y{&ev;f&;Y7upIxwUDld>pNBJ2qVOyg5|ANJEk54Ly6nExw_rZZRd}+gUW_OC4+h{s%N)RTBqUHsgiuUR^Cu^qmhM zwL9b^h&;IU1BgtAvJYJDfy+0+dx0s4;AY5R>NAMzJJLIpXI#ftT>iCbZM^McnJ&YU zKCFHw9!(+D=M8gVuG*J^i>l#SbP_s3A2iuJKbrHM6&^l4C6Z>#lkJ8$PX+u5)nWN4jWPdG z?f=0rzn~b#XkyC_;d(v$k3~6bpGTm8;h-+iJ%hKr6M84u6!zH!AJ)fGS6|@w_V+Wn z73IV_`hweuh%8Bv6MS<)rIt1lvzB%S^JZEI-gZ`2xDMd2tPt?zJU>(;{k=ibq&)3T z4#_EWX}{U~e)A9I)az3BBmByi%P$KoLc~OL2`mv5uVbuQJN4_>wU2r&_B(BR*%w05 zU#?qvp2kk`AE$b1Xh0$GIdJv|bFDg@fi(>X$|Y6CHO|_g2<`_@6?xtkR|spa#^g zYtC#vFli8NwN=naP(^2yIU?p?As7I24PDd>p`4FY7l4SLzf}mXE)*8_0 zHl|1b(gSq2P|u?9Zu3jMvDSuzFGJk!I~{;yn8>8|0@!FwBeqv7)#Wgmk#w2;46)k z12FM&M6Q2K@WEC)TL(Y!rXfrI#raVpO&6$KhYS0apoM}(10#9*v+N&Mhu_2-q1jq*B(xf2T#iZ(qGX!h+l4{-&1h5qAhcMB}8PZurX3e z`{=WKHT*SuC=wDIIMQrqIv-zlo;UYb!Q`dTo9O@sTi3!*89w#jP9b&qQ4;+8E(sp0 zvt^P6a5e@hZc8oG^W^_ZKW?@Qfl-j@;OO8aRSi``cj!kj>343Pbb?cpekbVfu&(cj z2ToTgCt^Gi2*v+)DA3<)ClLsUue{)#1)OwZ{c+EA&YPiX}?$2wVRNituU0&PHL3*A`)Pa<;` z;7=HdDHqgd@0owq8CK5Q2u()mUM*z#@sc5KLyUeJNUGrGQ~RJQjt^PqO0}%mLJO(X6&%vB15c zJt;3GQbS_HKBFhAnc<}C%5jAkpDRRM#ze_ZX7?^hp1;}@ezw%v#4hCLJ=Zlf`613P z9V{1u((9euTojg`weo%}Re~TK(xX}(1Nvp>zxOHXH8C`Y!yhvj7*ZFff9%#Nqc17m z1y2le$$uPxcosXp^sdDNv*vN_Ty!fKLkVpr`*s4Rr0p_ZGC{mCsM*=e3 zyeNFjS%rAI$8iSSIU`uE!Z6jRuETN=kQvx**Qb{wrUzHHmsev9e-=CEpd~W5Fn*HU zxP4AN22fE|zSEOH-<@8I^E%L|&N(%UTQ4J!BW(ZyBc<-Y-(IA%+l2=t!}W)r(+ z4~N5wOxuY=3GO`0GF-T9*`m}q=!xjn10?st>15SCy zx;>k_F&Ax))ZrC;@Qm6|QGWu9Xbw2_Vg#Qq)C8NaYNu|UjuHXPV4AP`-&Qzf(>s9@ z^5V+E^+h3)9v-b<*l9t+`c=!1V5x(yfPcd$^2|^!Yix`C|fBR%d=! z>rcqByidiL`#9ZzM19|>@2h+iQb@aoAm(1#R6f|RdZY^KI{5EdM3GZDb-|ZLgqSJ! zxNr=j3x98YhME6OPL6Kwj^T%qijO9{3_OdM=0igOWC1lkubIxvq zKWAN^7l~AGO>05OXk<^+Z_|5^(&I*Ngi6K%?UQ&%eynd_Ussx|;C(1!IzM?TobR{M z&pB0kI%Z4t=|R--fbJGLBysNczxVgfiguK2sPzcwR03pX>);{N_ighK?P7Lvds2)IcIB%-gexbkG)C$d()qPcrL&$>w}6~Y>9{dQfZWPwsdCZeAsLk z4;Hfda$dgX^=3=JJdqLdsMJr)#oh+S{n*-uuLOH?BbZGeOCPM-_0t`~?Pmf7bOJSz zGlEFp{mCAFe$F~xvK~zVVcjie&m=iYl!U9X^r=g;U&Z7;PM>CaQ<2P}A=v-ek*||I zk6OEPrR6Gh7i51+Obb-enf{Sm1J;^LP76z^&Gt0cw{ul5ndNHTvs46rIHbm{o`=Tx6{Z#++IaKW(S2+&r_%v;Kkbr zN1LO@Lt9~YD&Vkv_1NoW)r8o-*U6{>o?5&^hvn5QkhK|cY9+s=lH=E;lm{{?Y<*XP zYQcMfr@ParUq+QE|G$e{^W)NXhgFx7nh8SfM`r4O*Fxl`qrHhXvj#04qbmqU^7vxC`UJ!Ckkh26eR< z94kSJDo?^T1^|$w1>AJ+gB&A}lTh&juf*--ad@Cm-+#|i!AJ_)=`DsNoCBfw7O`1I zKSyI{VG*^h7ot5GoLvMq80-73zbM?djr8`nZPal2e~@dFQ(R>M)xvAz8We@Lu@Xf%yE(;|%Sfb@sTsVDpYh+bR&XdiM_BjjxnLh8 zCOCx8FO8UEvP@uAMhwpXl=3b}3{Yh8$@CTge479U2~zKHelUrm4=o^}#4O-xz$2_B z+wpSp91q!x9~165GxM50?d($72Nq5mH1EN`EYa?^{|#WZfV0@@zn8?q1-aB7%7fXs z)K($87Rt%OdBMQrs^+}x-$t*G6&+jr)U3|mQ&+Q5Fh?TnFurVe+l?ge##Uh(aB4d0 z-%ezJG|>iSe3m$uuQ5&QgK8@Za~d>{^hlF^#7Kjs?B6ak2EKB(-141~oC)_`z)sM} zYj+rT9-XmR#$psg8JmAdcJx8ye-X6fw7qnnm(|=`ghba9?kry^;lJV5Dx;r5#Xazaa|T#U zwb}rS+kKa0)2PkoB7-_e73G$wn!b)~tPGFO%fKxNmI!HzskJwZbAvOvg@{8JS*u|W zZ69u;UG>OILT^pLtEesPAER9TxS}(LBOt7sNh+$m2|@#O)}$cXaUzo#33KY|Xeted z6>z>US+G6o#JV#koSal;^aybRoK#{fEjBGoHjxj0HvW!8%~on3lyASzW!0_j;6Wf} z>C-l5W=Fk+Re|M(V}pwpFJO!|Hy4K75he&&Q1u*+xVAn;3 z|AF8K`{+f?FG0qz`kb;TYRk3fAE4E31Ugl9L#eP@P@_VPsV^Q{hHCK;u zFaT)pXtz4d)O-&BP91DS9l9!kwFC-T*jyczlL1?8DJ}J!C+P@2CQuj@Vln^&_FM8r zTP%j+w|7p!LH>l3_7H$JSNX{5U{lj}xcS%hudhP;sw3k394+++% zd044D!q00*IWfd1nP>W;;4X#h9nEMt`)!;3Wh6kb%@3wDGGtqhZ426b+|mdt;wC&_ z58)F+EBFxLQOB9Zvo(^YKYrl)$Z+)Kcm7#?p%&y3(Zqm5*m{ZaI;zRiT#G-CfZn6x zTvtxO`+Z2~u7^_FzGMoM2a2O}d8*N?hR5+C<)#v_d+wXk7+Tj#h#EtmgIwa<{wwbs zI2RknpNNq3ET_cYX@5GCC=OE9oe3(EEiaN34;=Rk!59YS=K7&j=Fg<*%&ev}P@?pTqL-Zxg8zQ&kmuQ@CHn(fWMV}$c{0W{)&UE+UpgCat{Gya}clJj_c z^(PR-!8wUQU}&E8o>m8#O)-`rY5FMLH(I`O$pS=eJs;Sb#RQi%ZJ%V1ms~*oD}IDl zLBe>5pAv%u0JZS>xj|rJrbQsZ^AefqL{6eFfjNDJCe_+NOJ8%Jl{4%&opSIzFwmLj z=xZnQ2ADNs)5Vb^?Ynr!p+5j&U&{Xojq-T3qPO|P+g>mNQv;~43VeM`Zeq)qwxps0 z++IRp?+`b$Z?rA^!ln(3?lDc4SF!&uS*BggC|gB=Pfd`ko3-ARTc`8iOR(YO8q|cV zVA^VTKrM!A0NojKSI3sAiF8J-EyxK^r)}cKNK8&qPuxQ{wktJZdB&l=1$(PrM$+tC!h>DO_?!ai;%$q+y1j^HYUeeZTv} zp-}^_cYMV%LMI8bqw7_8{g2bkb4B29%J|>p;m!uGNvzcZs?Sr`4*=}Z0o1o+0oZcM zdX!dw@TV?oM}aK@R=kbpXhqwIpKkx-%K$QQjx650>U4gPJ+Fr1Ck3Kxjg1jQM8}Bv ze1_lDk}wZ9Q_x|K1|}}N-^JE?9bIU7)OzZe*vl%8c7}V9H(X(BRqr7>nN369WNAQz zovayJDZ&KdyztWB(FJ{OcCZ|eFPl2@(7pS-r1@;*B{0oBKw3%`8um>K@`Jieb0-*_ zM52k|PHG9&yMdL(DZf@A{!_J^RCZqtRBrQC_%i}090mA$Igmyt1L{%qp33++XCT~Z zNg&mRy5S&4$biLl>X(#*J28picls&sr1)|9Q!lUnRWnY6oiU%;G7dDnL;Opm_kJ^4 zxzVyHRI5j_UBsrX$?`Z8&}t0-p+0ytOMC({yD0+9@DivlpCvhKa@3h+HdD==09~ArE+Fb^A_{_BZ z;bk|BoAKJUdMxoG`ZVFZ-(eJ?NZNGMBIXmLSN6u~f5CgG&=Uc~okB=*j9p!AOi={< zZ|0H2lN6Dod*M(au)q1)ehEInFX#a+Ie<5+V9Ke@S2xSQ?CGrAs*9|;Pm(I}`)2Dr zwO3z_Fq)#BOm^fSh#zbV6?~xhuAXdS4XozTfrQ0PJWX%>KBLH}TboK^MPz~oVD2ga zeJHN-T1a`ihl=S^+*r)1mXBvJHIvZMld=fjon?=G-J0!FVfu6pJITOm3(y!p#SY6K zd-UU`)FFS2+g2A>3%R1IBuEhgI-}y>pMYe?)^kBd4>aq4=7`~I!DnThCOGA5wk&2J z4zFwpJ_lOH%N8@IGCSO5+W+8Z%gbR@eSUkJ99Z#>;qnzeCCQ%pXDoBjGTwXVe% zu8vk2@v})a_>i`B32_|@UF|17D1Pi9`7_{m>YUo|6j4gvsw7Tqf$E0d!>+82rpDIs zvL;+W9db*g9HKiby2`p)gV-N-k^>!kZl5hh@Qiz$r^y&Qk>dC%D=2?Q3AKFA;ML&rBFydT#NHTo#(wZJZtJ?t`@-kje-SGld4_{xvCbzGgP%izOlF6b!d2d8MQPx;`5Z+ zeZXXr`3Vr)Q#=2DVKh2BT$jeoM=c9%a!Shvmcw7^oi{AAV8gsA=3IoxLalM9EsTA2`IO#&vMMM|&v0D%os$7Y zUl!1tnx39`N&4ZP1h7*~6cryC+I8t>72;a_ZgCW_fOP1m8`2n+)@i6OUL0zOzoAxx zS)DfLdH9LkIRm<;|1Lw%QV{^bgi6K&_zxw#T!i#^R`0!Jr$z2YK-RWSo`V*goPGRInq8>~sQKZ$ z5oJYHoS2ePv1x?7CozA#vM6G1VwkCmPd!6Jx(iQjJ7@Jnv9Tb#Uec-b*8Tr<1_)R} z)(J%dHxHRV3O_mtB};|0anrS0&Td!6mgiaxWPHWOgd|A?S0#B>oS4?!Cz;}`IigqeK1f2hB3+nYW`1z`*0=n#dVfp*WRohR689HTK z#i4Wovg^}n8MbOxu8AL@v~Ijv;N~N6uB>3WqV}zC=Zq9=R5{T7pvsfz=Luax?Bqqd z^|lh=m++pf>)?F&tgLB`x(1NlVt*OC-U!-8T)?mVZJ!j&6qP}apCLAdWl{B8a`_d} zE3QDwG`1Eaw;ifN4S^P3>c|J4_tRBYU8_ZXWOZ>GP*HjCGOSz**Ei77gqgl)?0N%0 zWf92oKwh{WAi%$_|0t zg32b_jsej^hQN*q8v=gIxI0;~2cYcjN0aIw_r*%7ZsS#m>B=}+Qdd93Z#VSz1bX9i zUztQCK{|WEbJz$B;BuH%)OV`mB_8Ua_^BopAxqvW zJ2gq`cSm4k91~s8j(D#N0sDLi@EcGPJsi1^u!DRGoK`Amsa+oUIiD~DsKs8UBzsKDrC_qeGvu?OEP-9=5x17&R|QM< zE~|fj<^{g1#YiFg1JI_B>Jh<~D4y%W1Rsk(kT47(ZD!1m;Z!oA6}J)k{HQyGD7C&z zgxT7hAhoCL%7Z4r+)>$}bJgFMWdy81)#R{{!{@G9|CB=6ZGL~`bLNd|fQyVJ^hX%$bu zH7UqCxY*li-%$doX{k~Wy-kOZI+B!eig>({rq;Y%rEflreM+oYKnZmhjF#N=SDRBC zLbAs9d(Wj=^#1^*t%uhWxn*4qg}?e7kh9)c>90Pm4}m7^PvE^}`WFnft2VTdarmCbdmhsCQSEUkYj@7?Hvf0HcyDt^ zY$DB;0-m`wkO8M7*y*lOFhje;BlzL`T~1V&_V&OD67N^S)9n zuVjii+kQMauj9)B7s_3siu5^IYs@2kQWTD-{1V9tCx5*i42&n&u?qFDw*Wc7v3b(W z)Xcml*XVFB`06y~j4s@f#CSLxT_sOVe^s2gj9tq6&5|5UD5jfg5LHOcM+36#CJiS0 z3|0p--p_Ekj$crD<lTU^>?_Z zJu9b$@vs_&pA1f)LFe=Md9n25!n_PVbOaFQkGHb^*zqZ>Q&(iy0*>H%@ zEV8>ftfrx#|4;vKsqJ$~in2#Dt9C6#W(>w2L_p@_u~@uctdMrLHg~Dh%sD9E#i(50 zb0Y+ACEn!W^T97pkNsbHYRwneCAQjWdcuXk2_>~%!W4{tE!}T5z)!3!pc1pv)+N#1 zf7LdHTkqaN7-h@&k@V|zLz`MIf{^!SwSKLXg^duKauyZq#HxmVEC7o}GVUa4*b8A# zArU;UuBV(9J9p6b_*I+7hLJE)1zb`Q!}TtRzY}+hB%^mE1)KGTOpF!($>Q(x5Ttsv zp49N_c*t;E zIDS%Mc+EB@)$vyh8oS}_{QP`K!Q}q)!J>b4+>m|D6S)PI?3I!%TF%4`tfRPKb5_kB zh1Wl6&wtX`X?t$WI-eif*k<(Sp7I)7vKWr-_^UFSdrlzN|C9{6b=EG=eUiT-`aLc# z36Rk{Cx)tH11Cz&G^D%+knjgAw!LWvGRU`(nbbNJ6ZX812Hi$jTFf{x;h?iDURm*t z-i=Y8Di@VHmG|KyxRf!6TJF+S@bRp_<#Z@@B9m*KXRg{{3t8u7@UK+IM}Wu@8u z<$?7|?7`AhkvvLhzh4vaTW%pFf*6I&grnsY(K2Bq3u>x zOt(L08Wnn;r4#w4YYh^H?v*G~M;G^g*1;awpwOK}VfM3-r8=kJ-0>Dhl)DZr( z)e?J>Y&0w|;1k{AH&6Uh&&T{|E^76X=nTr3t1RmMZv2(&t*LWre@8DX!%Fd6c`~=w zw!rv^ zxhTjV_}>&UmjkaJ+-6U?aa7AV3hxz#WlvP}W3f@t0*c0aKE(vAz@besp;GHvky}B` zI+!eI*4?x|XCxfCroqdJgUEfC8a`B+ILuV$~F1^p#^yS#&bT&N3T2ze3DA8RP0> z{SHlGctyU_Tr~xtVK)4H=*Mk_Uv~a$5ar2&AlY z9~(!bY0mB%KjFZjIM!~j?&x_s$LwRkoNVY1|Cp1?$7`eNBm*u-!_2R^q>z&b(tXZw zQDvhMYQ}&k*;{Ra71ich@;3dUQcjfHp+3~QA0MMR1jbZX5#+`lOgzh*%fO=LwhGWU z{uODj57!ocsy}4LC!|EHrL(|7vfx|k6Ty;#3ll=0F`^-etbl8tH0MNYI%+KaiN%NB zWuAv%DWgl@1L+&(Z1l*bkzBlp2oHhMAI0(-y3paughRAHQV)k^cdqqIBPo&l`uxo+ zY+*i!xRY01*_#KDo9^@>tm0+r3jy5Yik98SCv$VYzr3By9V<6tapwyOz5=Ulj+HL& z9jd;>e`ni4aV}6OdiQ#JfFrX>?jr-q;iqB18aYXzYJL^QPDQYELE!W%aO+%xvDp$; zUe|K#u+#Bq0%2HuR<^17;gn3?sP3xSUi9zgyn7FhY-3h-jMj}G7IjQFSfYN%f<338 zWbL6t-zaASe6l_#+vq>H)**kLdgE?t?KTtBDTs9C8Wn#qn@};7hYiLvb9nlWYDn6j zk6iM~UKIz+!YmYsHh-W|6+L=|?=ClR4L`_aTUE0itzkQXpPZTM-319zGvebGVOd(@ z#XWXluS?&)+M9Q0UAuZZsVQRomJL=hS~{2z6~fqdq2~G^6`-?loTHGk67*mmO5 zj(w=T#qOF$Rf1mCrZ&j7qooy5t-DhAN?GtQ_D3>8O-x=db;!_O4x^q3N-wdg+Wx!S zQh0!wmCa{YL?LBM|5R!$UOWFZn(Yd4m_tr@ZJ>8#CKmvF^pWdJ0Yu%C%1(Nz?3`f`?#sSLWu%hkD|r)1qVj(X2jcK6!B_#zlHouMvs&p{t zd79F3_Yv|hD;-hzXC^7agDpZ6=pDHN*0R|CoF+#TBHJ4}ZZ+#k3NVGj-=SsugP;zL zk8mBOG(MxRip)l{yR&JFKe6lAxc;*ZaaT=N9BMAnZnv*!+2Wb!Z@2HL>5+GED!g|= zr~bgy(PrSDu<(&`2DIQ>DKw`@okr;YRYWNq7g@yZ?scgzn{u3iIb+&=K~McYu@ZsF z&f~kneuy}5Nk@pN+`y|bdmJPGv+Nq9_!Ie0{KC*r@_J% z*NUiHLw(^>4Nm4v8ohsFVOwxSuXy7Y*2|}#B0t^D1=Pw)tnc`vgEUb{qN%4T^w~#K z|Ca@5K_ri7kP?^%#CvG9-wr*;QGornUN8XB1_oY~hy@}Ry&aqP6tQr0{&aYyp;%{E zA4{s2P*HhAh$%EnJ5#9u!wxdB>j$jRm(N-hjHw!-UR(4x44C5H9jOsAP(~W9(Lx&I;Rwbu@mq-<5!E zL|9lcr}0NOU&8&K8}$K#>**F?3~ z8$e@)cBiPaUS* zzu4j7&#P-ZfZ82~VS_vzZx(Pf!Xat+A!eu=u_0&4diKL+Bwq3`?>GOQuMS4PJ)Tcb zTmq_ox_1>rTK25>MHa^Y z2a{W_D*qw5ApoD2pB;}#x^+I})IsoDvv{Ov6(&Sw_RctqCJ;ERFzOZ#2Bs%B3h!;r z5cmrI_Odh?h_%zRS+xR~17)6m=cgYdbX zn!7?*zSMN51qiDgGFi0X*jyrq^WbY?CytZ9_;UHpYLWkoE%u!Tken3oTw6!F}zK-jq~{TH^?K%Q(0!%ds^N3Ih||S*QA(BO`{?Q=MMZ1 z)d3-vDV;JtkmknI1|s*95#TziVct)CEE9+l-k7z^eCb@STu4$Tu$Xv1&0!^~(9FYe z#r1UWET?sFuWk!~XOsg^MNb1~&{M6HrFg~@ETsNAg+VyvT&2dLT#a;dj_Q$kqvgl& zqYvYKJW?{m5MTAHGbV5kH$q6qpPlLu^`FI4BXNg>B8I^rDt#>@%9K5Dv!Z*c^<+)C zBOApe{hB^E==sD=q1e*R?Xc6Gdnm$D@QlUSVVxjRtbiF)>3d0M^x4JkH`h+I34X^j z*q*{C+0{&ol>r>qkEICWX>8!8EA{Ow*V85ZYJsu#$gMM4@ThUo^32oIVv}yC2n=-{ zd>lVXH5hwca$Ud}u2w0@&CX7kOqu$%slqHU4zW^p=KYju#Kvbi5t#y8mC$!@X-5_{ zhAdG-X?)sI8utZ|(Sj_Dkhu1gQ)1Pdj@u|nYvhvp6oUPNF!H&jeV4nf>I)m2!tWFm zwQrn~cwm(qn>pW+DkIwTc{ek9M4V;aqqZ^3Eb*-Z`-{;L>8ugo$>NC`=n|=;dmx^2 zhg(P5O%)n&S}$>8%8bctRz(bdvhm#?##~uP2O3>cq4Eqfz2?0q$T#JVO$PeuuB9jk z9{AOZv`5XY5~6YzS?x2x0XQKfcg0tfB#7t;f`LSVZa?wFg&36e#iXa!1jhj$uYxxv z#(4Y1U%-U|f+Qh`S4w`UW`C9T8eRUHnw_t5=tGhiTIUYxG?8Xu^N7Tr`rfVL@ItTs z&uopAV$8_5w2>GJ@l<T3#n9?^H=y*Dn~K8 z(^~^7bFeYZ7I{C;+Ms2VHa-3qd0KTGXFkajmo&8KiXfir>3f&lwQKq3Kk*woneWct zts5tXI<+$Lr2u2AZ!46NTn!kmK$Bked}h29Awq?uJrPVN@lK^{SI|oS z(7Q)%<2Pq~A#1TLJ2CAEG@Iu7v@J8$f9fXbYr;6Iy4BLvyPnEFTtzeQF{!3fuq&BP z6OyC(!i2q=n5KaNzP_&=AQlN4P~;v&*o75Z1*d3>B+-uO$+@2*uSSy2z@B_`Al>Qp zkku=TOa#xgz3O`6VAzoCe`MbD7fO%IN1v3H-4rHCaA%U(i>HXJsLM2D~m;f+`6Mk`J>e} z_-}I;&?9Jk?p0<=yK(yOx=_~$c2cgA)Kc=EFd4{yP#e>N(R)GK2;6SSH}eDTr<+7c zTByDit8BpSwx>E3t{P6kJgDUOZjSK={JSx|s3MptK7k%m{8il&yxyehdF2M>1@8tF zV9McX;i`KjQAY~HI?nBm3T+jD^@suyW%V^me1)yLp&49JIZ}5JD=sq!hh^EHa0ri* zYZ^Eyo;XkOdkIgR6jOPDCxxR}43^TM2rQ40-gG;LYlS z>{YavXTj2GzKk<>8X5D7vE;YNtyp=(d=b9^nDkD)Zu?6*;ZriIVlUQL|F+pk;?Mo} zNu}q=edX(B(rZ1UsGQD zLv?nb%|DAonT$S~tAb|zKQ@w-WC$5lzc#$Xe7HKB^ zjad4LR`3B@$uFO@7?W8>QV{MAx?5U^Bl8(dElFOP8`Ic9sx@QEpJ2Byj99Q9h)tOj|=2_qHRiV@NLy>e%Ml(z=<~JY-(My&UBr36<+czkjt&qleZC z#+ABGmgm)~n)Y1UtHZOuzw8pWjSL5EqJ}YNDE;Pxh9FPpU!SYrA|DvR^Ugf%EFFZ6 z;SyZ^y3g**qr6VeStrV&wetBfQHv5yfJz z%ZpC?2HA#3PUP%3*ND)EGAy5U{=l=f`_SI2Qc5S~yh=__bC?KKIAs{KGf=G9_v~&!e0@4FY zcXxx-kdo3!4M@jGcc*9L^E~H!<6GzO2Wzngn0xMh@BORm+B;Xh>&&lGiHDd6;;iid ztY8{G#477bt_$yA>HB^GG zu9fb1Gq}C9b~0b7?DBK1oI;z&WkS0NSSJ}w z5JXKi`<(Gh_Ax2}$$9LIP2wbmQde?WJ_l(?ej88JUOV385HpI>z3|E9`<=@*!tZ{U z?56HD3v%O5$;{q-DQUsunU zP8ye@hBbkS)tOwk0N`ny_?bnM z;;ntJjD5ipe4k=Kgseb>7oWs;zk-j6adbSOvHJ*2Ct$S}wesKo1(!(7oX%>6ay5xB zVEH+4mT>~I&;WZDd1Lw1T#&Gq?|JcgVN*M9fl;D+v=Ah!h_sYNfv^zm);3H1=b(loOjUiV_1-_v!9*Q4+9G5Z)mLM#2{~V%Q(kAoV5=)oJ{s zsi=Z6kODnlk8rT+-7GYGpWa=%9&8&T?tWb*#1xvazhAFuH=PAwR>5>!;YvZA?Swv5 z8F~0g!sYu$+_}P7-kTn==Xc_Q*wJhVRZyhKTLmWhwrp8wrR~_nqkB;q4|%k->PBL>3W>9$8yY{?*HmKPBN zuHEmjl#cZ_qmkpIHjZ1JUj*ohet(?9Rti*5)TQ^@<;yXI3Kr8ka;)4IMBRR4x*tXz z#Z0`ow=HMxt!h{GQi%mB)N914U#yID^(Wk7Sy_=Ntg^sWD{)&`df{V+MH@7l zT{nvLoR~lX@SBG2bE6jCmS&N8-=7C9CCA`$kxI>|pf2;;OWX_-IJ&Vt=bDTBZj%8HX3#;+Pty^xfYl z+g^F*1M|<(fzm*)+W-w^w@|rxL6D^z^c>*n^~@Y9(;Iboe>$(G<^>Y|8jzh}T0&L~ z7E}>`QJJW@G1x z{|Y3tcYh_$& zMBo+_DCNuD3Ps~WW8Pb~nlNUPY<>+mHea)PZ!g)ez}+XxjwsiwEz17qC*O_6n14Pk zb1GAS9r6*ORhd_TifrK;^da=LP(a?8i!VnC16(_o;p>F1ezpARqML~4;yNH)4xmZ??Oy~^!P5Sh95R@v^tn*3Wl^J&1cP$OJj=K15@qij zJ-iI%rzsb?Lut#S6;0I=&|=?$p_k0C@$;wiG~Vyd!(vx|8KPL5uTja7YcXUytw+^# zK3b2i+mbMI_Q@Y9F1 zDVU!{2{28L)H{=(3C#0Hsp6I#K+E*59nJs;?KAlUtInd@*UW14+^*!|4;%hdv*zc% zB3()s4$=9z81U>mOIWJr0xoc9X@*D}o-q~oO`(PB6%w`lDh1#9^8u-6`};AyU_OZ6#N)6!2D(=T_u@Vap*40&~fTG4%Mv6gPZZZ$zfyjRw~ zKt7loXqUh=&7{0;X&egS7-L-7>FM?kn2l?b1#rs`R9cnNkTXp#`J8^8`h6eWBlAqA zTFNZt!$CsTp#eqY5_fVg+8cD0`ZAt)vqY2PVfhZ+aXNRo(Qo4ZyXf3Q8LE_*644{1 z3`jvRO2(Z1@BqH)yPM3d>PLk8#H9xNJ^zKA;^YY!Q}BVTRG=SCWGc58@tZPRor0dd zAXTobNLNTX;H!QOOz?oWAufcqf`Gw*vFdJEC**tkV*I>|kOor<{Vnhrln55OU)Pp! z_|xJH|9;KG1!&ua7S}k|>bhmCRSYHfnqK$g@X@cU1ccjo&P)mt%Is*)$clouj%-A%*&Izq4Y$sZR?OUEh5Z~e!3M#vbp)#BLLlD{{g1# z#g6$f7y-wvJiNGjwWts1nIfsTE7(HpLY}!{82=@Ls#}`TbX80pwMvRosm&W;#Y5m? zvKcNr5#MyihkG0(A|QMiB=<#v?xQvepo}i;M$POdXc1$sz4p`gC1mFeGNMp&&iux@ zVnofQ=nO_E9q7*jEJ+_nlz3|2Ea~P%c)*f0 z=uBq!cC2J2Opo=Y!0#pTmN zdZy9GkK56>saKfTtgnwwzWAKqA}bGjV000V2zeaYZL`G6NOC=8MmLNn&?BPz!=&fkHW4^bn z?Y9p-MdmXd7ew5K2}z&YDZXq*Ww~84Ykyy;xDX$)Q9H~m7`EpSRdDKLc(?4H(Hd8P zF(c{Ow=V+uihnyk47=1eZ@xxpS`1Ab-T>lInkd->z?fsc$B}M$Um<*7Cj2NM*7QXi zQV{5=^Kvz)S7lw|%%KI+6tqhCM(=0N#)O1#9bBce=vJt2Nx{`BXz#YyGjU=j`N)wL zMQAp{y6;voLM=v-v2=47I1BfQx9LaC(#>1p;SAv@;XrO>M&y zm#o>QPe@e^qMh8jvQz(+!Ql@`+T?5H53et^{8I~UW+ueWUQvD3SS^5yh7;>YV$U9~+oKYj{33 z5lDi_zeT7vQ_^QyVoT+)b#S;|5RX!j9nEtLq!Cn2C9ilAD;{vD(m#}~Rb{}}I6yyF=g{D^in+kQ=STuqkR8!9q>)QdBcGIj*SdBPy zlj5+KEk1Pc5Avkf=?icbT&mAAtH!15$WjafHNhSrhW^uyG&ScRVC~E zbe!=wI^00SEbyu{?0z_6DYXfS5p5-bss4$(<#rB?1F?s=GZMH8v+wUK+g8e$#_GdCR-8-J4Q#|=Wd1Kgv<)smkaA-pu;%{!Og`|< zKWw;;@wPt>3PF}YP!jlONZDN_sg(;vmMKC7Zu`j z>%dZN=l5Kj-KRE4!qy}KO~wtfc?X!QD&)4aB3XiEAT1RH%j8YDuyq z@?EkFe?wTpP{K&j5?R2rMLRnd*|Eo|pZ0b1tZ@elN+X(`$w!2>8l;@8Sl`1jN91xK zMs(&l38U%ssha8W%cFjWw!|RR0p}q0G4+ag!DsXY@g|{FQ|j z18ihVbZZ9zyaYcfl0Qw$^Nsuk!Xgj=6||7Apiu0x^`L!|h+hY#<5@~a zc;qs7bT?ukd=YAObHV$e&%EymgFql{6!J{G1n-tR>JG!Dlepg**PASHP$sn;_y@~< zTNkTUSk}p!vu;8Xu1bk{5&w`%TgV)Ez>0fL^e;pg?dHQ<-phMNl#s>`j1#t7HT?@~ zpr9gOo3MtDeL7;4N8t{%dz=_NnT`@J6#jF(BG#@KsD)3A!Gj!SKKFp1!9aQN>@zYvFSGT^enb3-AWZm9j>YaqUZ1f zPM^S!z7;%*l}>&CPDf&%yr{Cu<|Wk>IWl%slRc{Q!%Nm8X!0-5%d(@{ItFc;D_ND_z;|4VLAf33MB)n;6 z>m)y4`l{LeNu_*z$&HsPhHZkTib<9>#Dv{^AE^CEbuVDO;ei9*9CRKBCPWAp*;qWV z7K4C|iWj(FH8-SoPlWDC0ErUHWb&I%O8EWAw(M#hKU_;g`!c?CQxJ(Do4Yi$Pga_UQfGM4HmBBW?J#eR<#>?nKe5NPM* zk)0G9r1k~mZHOQnwp6IPttihRG@o#R&VLfTMOQD08^^yJ@ZGI8f_((W?5sCB_v|oY z6E{wCC)Ph6*6XeVjO|1kcID{QcT8*LG7Io(6|0>s{Z{~$g5NL;%5)=3k^s|ru$k1J zA%uO7TzBX)kg6`wF6@BEqrsm6o8IW@JBXzjGPUlw<%dH$1E;dpm2B|hNSSvUi;WsQ@sjf;$JnzP*r~3J`r#bf^OPh3<6+U#2Y`RyCg8Uh- zV{eRLOJ(c^m0&>g))1Dst-+HY`#E%q8;r;`hfOz`N>6P+RwoLQ23CNk4T7KBY~o8= zU0SYN%o(ObDjY26A52&X7?&+F&vL!_c=uKM6OGmqE=93pVA%bevERJLbe6SY2Q92x zJ+f?AY$fpt!$WS=@pyZ>7uEI)u%vmX6@Ma@CO{Zs-H)V5G?4@D3?1&s@` zp`?x&?_4^@p?4bfJ3>*GSw1)!lb`p{i+!vTmR2-T8T!ys+H4r4PQ0d8@4D)D<67m; zF4;mMvKWj!og3d47Zt0T-Y({jL+J9n3wEzQVbuxxE_e(akCXmKDscGq&)C8iq`^V8 zP%&KPHPZ?qC;!I#z2DHAKPzC~t!L=MPcKV9uzfw8$WlNKKNRF~36z)idtTEWR(gN{G18 z1fS{`e#f3KH>J;I;Zqmvf0vd+3G9-t_S;A93VN|R8jg8b9Hb1($DtSq=`_(&oCV^9 z)qE%|)yG~UKMD-S(>GkxQi!qqgP%XhNSoJ$64mfb&}Qo-d&{Yl~C4>LWTwR<>bf0ZDTSpJ zaLD9SziKC_A}2q9ts)T_kRJb3n_yh~2}^9=^9OYDNNhwGr>Ok4JV}6s*ZdEkiZNUn zjrmxU#?U$;z~4WkA-uK|-UKmNv~`)?k2LZZTX-1B?fMQvj zDk+svsko>&qjx>h(TK&!txUuBD=m_%Ox?^M{1boRCItJxv@VHoLZfQL#oV3z8dCm^ z!9V09;c&!y9IAdYi%ld${fJ~Cy%x4Cv^8G{B&95{wh%g`$LI_B`GhoGPxc9q0m~mx z#uf$(HhWCOI|Ez8A6@PXL8>I7reFQQEd&jKdjlio840vgOvMG^`M?#;XHCETgGlBjvbVNl2I??pc&JlU{P1u$VX z>!06ak7HUpX*QrC@6-Q^(|X+1zYJ*jG6;}Nu$Tf(0$=9-+!hz{n?tC6M?S=|zHOgy zv;k{FyE7XsJ%&}-(dA@k_Gk)RdeN$4PF@=?>WI=F3L~M+7Z&ah!X~2O40nGDF4yO8 zyJ_Eq6uosy=`!!{q>_K}!XihlLBC>WjlS3l7Y<>;3pn^1+is{8HDQu>@BG<|wB&qH znvzYem06C`>+!Oou;@*#j-MHwqBnaKC#LlJkfEX`DeIUYw7gRTm*|NDPmlK9OZMK4 z+P;?2KVC1WKT`mN5$tKZZ; zKY}z8Nh7fVL1nwCv&nBWgDDiZ2DLLB`Eid>i)h9A0xztt@9pH)FC+)Ryx^Yt9rlbI*MpGm=>8`;&+FO6R}_j6H>9;w7s8dWKja zko-a#sSSc`7|L7xdO>#>%bhgrfLtQg?_%I?h<(sFlx1*_oba9RFSZP2W?jLVFF&Q0 zPwS_ZO46nJeaNDqXbL7_+n=Hcc2c7fzD*_;dHB73dK}w@-(VVqg?3gch>2u2phdmD z?9>Sgwj0Aia-Y3u(Sp9SCR~`Fg^!_3$yGD-ndU`_jo^w&hooe+hSA-&qUaT~y~UDO z8ufCdd@yD7rXV4;LdOpcex$ff7TG1Leurs)tF`eUJObvkZ7%cffz!MWuH#PTEqQ`k zP%mbF8_sGloNZM_WcjnxjqZsLvs+9>NPpkwdQ_@L^1O_iz4iAQ?FomncR>cf7GCsw zk)zX+%CV6I*ZB}X)@<_U(NB`f%nn%xJ*B9R zzxCRc*XCI{%2~52NWD?1j?kFfT{+zsTZ6{8#tajlx$O&YX)wbY#Ikut=h<(4%dRYp z{fL=6c3~u*vj}2Luuo^Y$k;dBTINR!v>`bXC!U48%s;zPRtlgDwyR3u*xRy(wqxzp;Ogg6^Hr0Fj z&kp6DTn|Axd)$gGH^&@e+!aPLi1W%wCVs)CbO2T)j19$o1@25rzIt{&?gFav2VCsH z<_3C=9+db;pEBmo*h7i+$AS#~Q9;sJ=_4jk zN>VcJ(QBCLjOhBUi1hPuGVlof z0`J3XKCyI^*xxe;woR(4v?U0(hXx9)uTV`Z0S=Qh2+aBXzS5=iUskCsD`Yb1(N4vt&TYq9E-8o$87Qro#p_9$Cd0T)-8Punp z9sp-S(DQ?l{2g0zB(O&@^i9kLO+yoGq{YD#lU7lR8Kan ze}a>5*5g6i8^3r!dc;WXZ(`eZ%MdRmuTuwabNOE>YdqR4_F~P58N?L33*8VF>0<>=x(w-PDE(-r@_CYTlR8 zR^%03#BaS0Tc_6OObWi=tydAOG+KRZok3u3(c^&gDV-o>zLw<)M1z-x84E{uWPV)~p_y-QMCE1emqG!*{SUC?u)u)o`(0-=#x0SA0UKpvNuP z{oNCCY$*A&XL8EAxgTYx>c#l@I9HC*Z5q%^#$m8JlzxFt%GI|ahe5?LH>Py4+xFn> zbSYdH14MJOi*K8&rfiJ9N6-x=e71*HIBx9EDfNCjs0G{WTLD8G@}R>D5;sy*&x4Im zfK42i)>g~-a1~aDKJ^n%>oenwcAc3_f#YbO*%MO;9%h8jx%|ux5t*b z?g5`)(!ueR3ujY}c;t-JT=LcN)ZoT*tN}^Z#`a#;=1nLGZz0a$MV;qk?#}l1uAMs_ zUfvUZ4WBUs9I7D-JYoxJI`F7d^d|HdDgj5YQumW@dAd|@pgs|Uecf1j+6ew#k#6(s z#&ap6vcF65LBBv$oL7NGw&dNkzf$`56otH)m}DCa8=y}1jayV|_InIf1FW%?+t2?r zirrN3D^N0!l|)Rd8A`Byl#PQf0 z(&^T$qVqR@{8`p1a|c(n7c@fZ+${h6rdhfTfgDr0pN#k=r>IMpt+UKRYD-A6&<{MF zO+F69<=H_ZJLhB|+Zjl{|Fj~2Z^NxVC*GQ?Qom{&p5N1fdj?NLxp!uLes;5Y_@5q) zEYU{Yfnz=l1FX+slaaTNXWe!NuMF$80@*Z|d*>K*1q0ZEmfxHW1PtnZLAW&BcAYM6 z0KH|R@Qpf$(EydM1f?=VS=ba9EEi<7s^G~;)yJ|P>YB#=9!7Cy#1+q!EjQTQCDw2d zykBGp-%j+fi?+p4Ubo6k#~#?%Fa6;4aGaLD(Kxu8ZZ9zIipj*bK?!CjhZ?flEv~Mm z8;*FEj1TLExB4Un$m?feX4YMeLQ`Ak*TS=s?XbFTuAm+p>m%)qlZ&4^x;sb5dJ6V@~Z`c1aFIbl0<3{?`j54v62FF^QxJ;n!9o-6}oud$#})w=D{4yeWBObm*dJO2Fa^O*9|6J)5{-~#%zPC5od1f zJI{iRC@)qYT)=+iD8){uRL`8b(K51vBRLS7$qC!$=!FK-eBd)YI8@NS;bd-AhPoK`sAN_xRLP@9`IzQS_Z}x0N=o>cvo`aE-Qr$z7Cm5|m z>B+>>NXKQcK~qW(6`{XH85w~$-x9DngEhPQQ7AL;yNsG;%E~7CM6!{(PSv=AdA|&A zR-m&Hcj$Uvz0f`kZR$gD^tgs2#=Q=c!PKBYd&f39*PZaqPr9P*jZur8j2^QOn(9Q_ z>0d6kq)ehb;oIL1uU%?6cHKdkC0I?8L;mY)bA*%@uaBbg;BDm1YvQ6ZA|uz Cm}6J~ literal 0 HcmV?d00001 diff --git a/doc/html/_me_color_sensor_8h_source.html b/doc/html/_me_color_sensor_8h_source.html new file mode 100644 index 00000000..8a3d29bc --- /dev/null +++ b/doc/html/_me_color_sensor_8h_source.html @@ -0,0 +1,294 @@ + + + + + + + +MakeBlock Drive Updated: src/MeColorSensor.h Source File + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeColorSensor.h
+
+
+Go to the documentation of this file.
1
+
66/* Define to prevent recursive inclusion -------------------------------------*/
+
67#ifndef _MeColorSensor_H_
+
68#define _MeColorSensor_H_
+
69
+
70/* Includes ------------------------------------------------------------------*/
+
71#include <stdint.h>
+
72#include <stdbool.h>
+
73#include <Arduino.h>
+
74#include "MeConfig.h"
+
75
+
76 #ifdef ME_PORT_DEFINED
+
77#include "MePort.h"
+
78 #endif // ME_PORT_DEFINED
+
79
+
80/* Exported macro ------------------------------------------------------------*/
+
81#define I2C_ERROR (-1)
+
82#define COLORSENSOR_DEFAULT_ADDRESS (0x38)//0011 1000
+
83
+
84/* Register List define------------------------------------------------------------*/
+
85#define SYSTEM_CONTROL (0X40)
+
86#define MODE_CONTROL1 (0X41)
+
87#define MODE_CONTROL2 (0X42)
+
88#define MODE_CONTROL3 (0X44)
+
89#define RED_DATA_LSBs (0X50)
+
90#define RED_DATA_MSBs (0X51)
+
91#define GREEN_DATA_LSBs (0X52)
+
92#define GREEN_DATA_MSBs (0X53)
+
93#define BLUE_DATA_LSBs (0X54)
+
94#define BLUE_DATA_MSBs (0X55)
+
95#define CLEAR_DATA_LSBs (0X56)
+
96#define CLEAR_DATA_MSBs (0X57)
+
97#define DINT_DATA_LSBs (0X58)
+
98#define DINT_DATA_MSBs (0X59)
+
99#define INTERRUPT (0X60)
+
100#define PERSISTENCE (0X61)
+
101#define TH_LSBs (0X62)
+
102#define TH_MSBs (0X63)
+
103#define TL_LSBs (0X64)
+
104#define TL_MSBs (0X65)
+
105#define MANUFACTURER_ID (0X92)
+
106#define CHIP_ID (0XE0)
+
107
+
108#define SW_RESET (1 << 7)
+
109#define INT_RESET (1 << 6)
+
110
+
111/* REG_MODECONTROL1(0x41) */
+
112#define MEASURE_160MS (0x00)
+
113#define MEASURE_320MS (0x01)
+
114#define MEASURE_640MS (0x02)
+
115#define MEASURE_1280MS (0x03)
+
116#define MEASURE_2560MS (0x04)
+
117#define MEASUREMENT_MAX (0x05)
+
118
+
119/* Color result list*/
+
120typedef enum
+
121{
+
122 WHITE = 0,
+
123 PINKE = 1,
+
124 RED = 2,
+
125 ORANGE= 3,
+
126 YELLOW= 4,
+
127 GREEN = 5,
+
128 CYAN = 6,
+
129 BLUE = 7,
+
130 PURPLE= 8,
+
131 BLACK = 9,
+
132 GOLD = 10,
+
133}COLORTYPES;
+
134
+
135/*
+
136 * Class: MeColorSensor
+
137 * \par Description
+
138 * Declaration of Class MeColorSensor
+
139 */
+
140
+
141#ifndef ME_PORT_DEFINED
+
142class MeColorSensor
+
143#else // !ME_PORT_DEFINED
+
+
144class MeColorSensor : public MePort
+
145#endif // !ME_PORT_DEFINED
+
146{
+
147public:
+
148#ifdef ME_PORT_DEFINED
+
153 MeColorSensor(void);
+
154
+
160 MeColorSensor(uint8_t port);
+
161
+
170 MeColorSensor(uint8_t port, uint8_t address);
+
171#else // ME_PORT_DEFINED
+
179 MeColorSensor(uint8_t _AD0, uint8_t _INT);
+
180
+
191 MeColorSensor(uint8_t _AD0, uint8_t _INT, uint8_t address);
+
192#endif /* ME_PORT_DEFINED */
+
193
+
208 void SensorInit(void);
+
209
+
224 uint8_t ReportId(void);
+
225
+
240 void ColorDataRead(void);
+
241
+
256 uint8_t ColorDataReadOnebyOne(void);
+
257
+
272 long ReturnColorCode(void);
+
273
+
288 uint8_t ColorIdentify(void);
+
289
+
304 uint8_t Returnresult(void);
+
305
+
321 uint8_t ReturnGrayscale(void);
+
322
+
337 uint16_t ReturnColorhue(void);
+
338
+
353uint16_t ReturnRedData(void);
+
354
+
369 uint16_t ReturnGreenData(void);
+
370
+
385 uint16_t ReturnBlueData(void);
+
386
+
401 uint16_t ReturnColorData(void);
+
402
+
417 void TurnOnLight(void);
+
418
+
433 void TurnOffLight(void);
+
434
+
449 void TurnOffmodule(void);
+
450
+
465 void TurnOnmodule(void);
+
466
+
488 int8_t writeReg(int16_t reg, uint8_t data);
+
489
+
515 int8_t readData(uint8_t start, uint8_t *buffer, uint8_t size);
+
516
+
542 int8_t writeData(uint8_t start, const uint8_t *pData, uint8_t size);
+
543
+
557 uint8_t MAX(uint8_t r,uint8_t g,uint8_t b);
+
558
+
572 uint8_t MIN(uint8_t r,uint8_t g,uint8_t b);
+
573
+
574/***********************************/
+
575 uint8_t Device_Address;
+
576
+
577private:
+
578 volatile uint8_t _S1;
+
579 volatile uint8_t _S2;
+
580 volatile uint8_t _AD0;
+
581 volatile uint8_t _INT;
+
582 uint16_t Redvalue;
+
583 uint16_t Greenvalue;
+
584 uint16_t Bluevalue;
+
585 uint16_t Colorvalue;
+
586};
+
+
587#endif
+
588
+
Configuration file of library.
+
Header for MePort.cpp module.
+
Driver for MeColorSensor module.
Definition MeColorSensor.h:146
+
uint16_t ReturnBlueData(void)
Definition MeColorSensor.cpp:724
+
uint8_t ReportId(void)
Definition MeColorSensor.cpp:176
+
void SensorInit(void)
Definition MeColorSensor.cpp:149
+
uint16_t ReturnGreenData(void)
Definition MeColorSensor.cpp:705
+
uint8_t MAX(uint8_t r, uint8_t g, uint8_t b)
Definition MeColorSensor.cpp:965
+
uint8_t ColorIdentify(void)
Definition MeColorSensor.cpp:287
+
long ReturnColorCode(void)
Definition MeColorSensor.cpp:250
+
void TurnOnmodule(void)
Definition MeColorSensor.cpp:819
+
void TurnOnLight(void)
Definition MeColorSensor.cpp:762
+
uint8_t MIN(uint8_t r, uint8_t g, uint8_t b)
Definition MeColorSensor.cpp:1003
+
void TurnOffmodule(void)
Definition MeColorSensor.cpp:800
+
uint8_t ColorDataReadOnebyOne(void)
Definition MeColorSensor.cpp:221
+
uint8_t Returnresult(void)
Definition MeColorSensor.cpp:455
+
int8_t writeData(uint8_t start, const uint8_t *pData, uint8_t size)
Definition MeColorSensor.cpp:938
+
void ColorDataRead(void)
Definition MeColorSensor.cpp:197
+
int8_t writeReg(int16_t reg, uint8_t data)
Definition MeColorSensor.cpp:845
+
uint16_t ReturnRedData(void)
Definition MeColorSensor.cpp:686
+
void TurnOffLight(void)
Definition MeColorSensor.cpp:781
+
uint16_t ReturnColorhue(void)
Definition MeColorSensor.cpp:638
+
uint16_t ReturnColorData(void)
Definition MeColorSensor.cpp:743
+
int8_t readData(uint8_t start, uint8_t *buffer, uint8_t size)
Definition MeColorSensor.cpp:879
+
uint8_t ReturnGrayscale(void)
Definition MeColorSensor.cpp:607
+
MeColorSensor(void)
Definition MeColorSensor.cpp:76
+
Port Mapping for RJ25.
Definition MePort.h:128
+
+
+ + + + diff --git a/doc/html/_me_color_sensor_test_8ino-example.html b/doc/html/_me_color_sensor_test_8ino-example.html new file mode 100644 index 00000000..3c031682 --- /dev/null +++ b/doc/html/_me_color_sensor_test_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: MeColorSensorTest.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeColorSensorTest.ino
+
+
+
+
+ + + + diff --git a/doc/html/_me_compass_8cpp.html b/doc/html/_me_compass_8cpp.html new file mode 100644 index 00000000..8c390c31 --- /dev/null +++ b/doc/html/_me_compass_8cpp.html @@ -0,0 +1,198 @@ + + + + + + + +MakeBlock Drive Updated: src/MeCompass.cpp File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeCompass.cpp File Reference
+
+
+ +

Driver for MeCompass module. +More...

+
#include "MeCompass.h"
+#include <avr/wdt.h>
+
+Include dependency graph for MeCompass.cpp:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+

Detailed Description

+

Driver for MeCompass module.

+
Author
MakeBlock
+
Version
V1.0.1
+
Date
2015/09/08
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for MeCompass module, It supports MeCompass V1.0 device provided by MakeBlock.
+
Method List:
+
    +
  1. void MeCompass::setpin(uint8_t keyPin, uint8_t ledPin)
  2. +
  3. void MeCompass::begin(void)
  4. +
  5. bool MeCompass::testConnection(void)
  6. +
  7. double MeCompass::getAngle(void)
  8. +
  9. int16_t MeCompass::getHeadingX(void)
  10. +
  11. int16_t MeCompass::getHeadingY(void)
  12. +
  13. int16_t MeCompass::getHeadingZ(void)
  14. +
  15. int16_t MeCompass::getHeading(int16_t *x, int16_t *y, int16_t *z)
  16. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Lawrence         2015/09/03           1.0.0       Rebuild the old lib.
+Lawrence         2015/09/08           1.0.1       Added some comments and macros.
+Vincent He       2019/03/01           1.0.2       fix issue: In the Orion board, the electronic compass was hung in ports 7 and 8. To avoid the crash and added timeout processing.
+
+
+
+ + + + diff --git a/doc/html/_me_compass_8cpp__incl.map b/doc/html/_me_compass_8cpp__incl.map new file mode 100644 index 00000000..cc24abf7 --- /dev/null +++ b/doc/html/_me_compass_8cpp__incl.map @@ -0,0 +1,50 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_compass_8cpp__incl.md5 b/doc/html/_me_compass_8cpp__incl.md5 new file mode 100644 index 00000000..09ff1c64 --- /dev/null +++ b/doc/html/_me_compass_8cpp__incl.md5 @@ -0,0 +1 @@ +fd55c85f822dc1b88dd25ec2af0adccb \ No newline at end of file diff --git a/doc/html/_me_compass_8cpp__incl.png b/doc/html/_me_compass_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..364029ff3253964ad2b76b3ffa9ca00f264b1d88 GIT binary patch literal 50001 zcmagF1yogk6eUc9q#&Kr(w&b`0Rcgf?k=U_(T#vKNQ0Dgw{%M9qr1C1CFdgiXU(_f zo0;cwxfWjTy}wg?pMA~?{467mhD?YI1qFpBDIqEk1qJ5{1qGdmgaG_RktwMU_y<8> zN?a7`;qlL}#+)c9sMk=EqVE))lJ@3Zoiy!hFOCl@Xe9gS{E%V%V&%nLR(}2R(ik@V zIucDmk%#onf(DJ2FOTTxx8so*COmRF@dy>u>#G@xZ-R!|MfEEM-!$@xe`5cL9kCsw z_^tc(XTQsWurV?@l?6J7TF=_O=A@>D@kF7$Y++X8&5a<6=>PkZ$-uY+Me+FAA4n0b zhr`FUM<=l69!v)D5ZEJOM&#m%lDvJqO=hDiqXQWKyT4en2tw>@q6mkmF zl#joDC%4xEi(%LvfGM~61A3(cPiHMgMLQ65Ovm=l7xt&)vg( z{`64NyZ-mOCjq^r&p(b3NdMn2-)^bhOt~p0bF|lVgw(H+Q&2>rJpZ;sT7`Z#t=Qmx z_2T`7h+lX>z}mN`n?*P{M6=flUn)c9w^#)r>c%0mk>aNcU&CCxj30#4oe?7oo&=gs75 zhljgMG7kOrfZPmJi96?DCC7u6aT1oMD~ghalis>n%lduT#vWRVNQ~d1QvWwkpGbSo zx5C$_WKmI2H0J#8ZU#c&{}>hWFYTcoLnI=s;bO+D;e0|vuImT1{%noi$YQ$$qsn(Qe+DBKxSj+XVh-4AZJLzy&V`pm{9)3NUIupaFN@4z!%j;7D6cbhY$;m>d%G3ll7Q2Hy&4X22cR@_dz}V;9 z5&C@$R}4b~55Y6dp3QEmvoyohfuC>+(n+lx3%=Q@qo5eMd@^~!S;VxYFu|sVv8I4y z{#_PJiJ)hs1xn~B$przSHR8cU+$0`mMALH-$i!%myCP5HSWMCxi&g!EO|TI&^#O$! z?M*Ok4SNtOkfE;6iEV4X@sZ4w?EqFANj)!!U1}ctCZi1pUqyx6NiA9p2c(~wy4>!DE7oLIH;MLSp(Z3W=&MEpEWv)@^#Zm))8v)Ki;0_L0!+7=p z-%Hu6Bi1z`$NRHR+~Od9S#eXDax~*4=p-zi&dCf2P%Wp^o;*O+mtP;2`W4#oXlM{ymV}1o9^3xo$^N zA5(isZ1wYO;#E>Bzp_s`P~~k~Ftu-jB95jvwETD9&HwKEr$0t$On(ls;pK069Q%}% zc;WF0klTwZeX&-SP<|k=&qAI9h7sv!ZO8JEYWLU2lo@k&$!{7{UUHjU>cV-Eifs>+ z_idqIey_(==zfc5bp&R!?BFdbZa)a;mo2H)Fp7NGJyPQkQrFNQ{6HcJ)F7FsiY4lz z_n#}0@x(B^67bN-(HqtvCB1l8mU7})m=VR#2OAMN_Qk*uIRJ0UTA45B=bjplGDYnT zD7JiUN$cpCBmMUd{LfAk{H(PPZO!xfrP*?b9|t3jeYSa`aL4@tv<@7kQ2NU6pUH~l zo}g|7mPmGqURQp}EzP*j0`PG0m~5F*%O&wfzxqyU(4!spej;!NKOW9*6mSJGKSsQb zhehDHXfo~QToJ_|7!IMYLE8?c;A%s(;=gAJHjSbaCAZ#A@in$Q;ZZNsn1cfo&GC9gBU&3 zFG-nWzUo7APRT&Bv1~mUy>mK7l1$Mk4lw^S!e*lUFC~e{J|%ZdwsMizZ814jndUa? zp9L=EpDYk5H@zet%W|Z8vuVO|n!%(S);4ZW?cj+$eH|r-p|JnMPSqMhA)I@+J3daT zNOL#zraUm<8Pp@H{h;kTItt?}$1Z1&H3gR2+J4;3{T(IJsG;w5yA!jo^y3869I5M( zqx9i94TnuaboOq{1-udb6DdO8P_XB2PwYNoH$~=Qxmbva4e=^jn#~S5#&KL|R|Q-= z;6X|tm%q*^&T{2t0vPSbQJ7UU!IJQ zv;@uJh5Z3)56}1ZYugJ(#K&rk1j;ntbdRSnN6Mp#TXTb>|>@7c*WsTUvu4HX6tZ6Z!AD{A<8 zgq!&vx}4ERdE|o3wwDIG5Q@-unL6nzX{Uc8t(Q$LK*J47*z zw@aDGD143K8G!+)E>9KBaEN1-vAX{v1HDFJsWbg%Ld zNEkSPAZavi8o=-;6QSAyr3TfSYGFIThxN3#M1MAcx1^o>LaoLle}ifkirDN3#54B? z#5YDP#12j%n~3`hye#M`$Jle#P;}b)7h3&>^*g1!71UKsb9Tct4|5qRO-!Y(P$AMj zOm^jH=wIlpjn9m@F(dxSJU`VE+N9OB$~p_`68p5xA|w$s9*Ie{`_SLeGj33UqH z^ zwh@Tc!!X6HbpIXQ3k*mHj6<*f6y83{_^YTPxDt!{$#%ow`2%wC{H^V#nY@d7ro@CV zkV_6n9#5g)Fn31bfbpKPf=^OuRW@?JNu`_4UC}g*G)L3mn{BrU1 zqLtNctKk$$A!*bF6k_5cujrf6tnh=rXmHjs@m+h>$so!5m z`CpqDh1aJFnNP7g%vw}yYQcEjO{2G63~qDTE}u{8I`(hCe_X@doii z?k;0&nXiIznJ5yZH*Wbe#KSkdV9~q(+9RZQk-CPcXggCs{TB4V<7+&AoS#DyD6tZx z&vhC2aisV&Q~^I)FG0oE7rbQ_6k zdu8pj%q^SCYBGAUOj^Z_fPjX?ry3mC9+sZNgd^nBwKbff*6iUv#wIFy68ZF>+f`v7 z6T*5ENd_HF5|wYjb{F>~I@O*2tO5yAbG7x_@gHCnx zLNR1s%@{MnP34*2_UP=R{DL5-r8G6~Pl7&1SLqz?O&yRr9dFQUhaaLaizzzC&<%B851w%u>E!h$Y`b-{T)2bE2N?sXa0 zWE^Tx5T27&+K3w8*sv=%d&QFqID8NpRPYq;*<@EUHwFA^o2Lro;wU#Q7nBcU*`MVTUxMVb) zh4D!c(LqB+iRssQ_!-|8zT@C&3yR$ zOdb|3W|Lq@Tb%}Uks#X$2JcG&5^pT9T_Ct-!;yj{l7dfoa#ch-YbMu)iy86d>3jt3 zt*p{a+70m?!FZSZekhJzD2{DaO*4Pl>i5yC8W$WBuFG^EY?xY_t%czCUYK)kk~&Vf zgzyXy;J^_tL$=?w9PL8`I1G>R)owKqif}-!k?GfVG1iTv_@vWbS=Zy=>oYJKl`*b8 z9A*Ub6NO?AsI02ehC|&g*meGlzgja*Ytw?6b2Fim_-)P6a%-!`dgZG)cuGNn z#dAeP%ks56B57?i3FuVb)9^mDERNKZ+O;Pm#-;WvSSybjz;mE7ggKb7cN&JU#B*Sq zXl)g;UJ*c>S)-$igdv3lw&bueBk5IB(1!3_xrB`4hvJ@ye&NhYY2GdTX02g1mRcc< z(q?TiMgTCvkLSN1U3eB4xQdHV8!BRzwKXljM#I_))$Uh#pWgDtyd8!+f z{d@=}0<6#r_cm{af-3%mW|N$H!DQG}V;5L4S8Qwvr2!B3eaiQqylJUh5j|*?)o2hS zGg9sE?EVP{J9DwtLAG3Qjr&-e=G^?BHlL!suPi`+w&6AdD-_HDfA#w4I{||Lm83+v z7avbCin_Vy*lzJ zVh2+VXJ?vA+`RGjwfgnaI2LrjA%=7%K!s4=IR+T(GL<5KY5#J9A9@~Tp_S_K7GRz~ zo)4N2yyMZW1N~erA(Gcag%OId7H^w;awBcZ5rdZ*Ym>H$KG?;@B1SN|KzkdWsLG~+ zfEG5&J3PJ&Z8IF5p?S<=B!99VPh%!YT<(JO`?;w8!d8_zR`8YVsg)NKcMJBm z>(nI4zRKjiquX{CZj->{3bw)RxLCd9>Qa|df!N>cFXr%d`o7k6LwW^c;)Wzn*dPq< zHgj?ziYNGVP)NuhEpC-yXtlAm3a|mwCrf8e(i7fVa}*~@sJv1PGNCrB+}DqElK&M2n^8FOE4ee+*ns$Fkc}^Bb%2jT0V)(e2nun+ps;6-V6W#TAqs5D+%!EKCZ@Chf8dob z-oWY>qjum%_Ju9O<QDY+{4CFK1i|_Lyg#bO&2D{W`qtwv~(WevUOCeoloQtbF zfOOB@M;$ds+~$WRRvt?;ndABTK65FR1y}8n#l;mWFIaiHj~lWTwB-q(jASj1zFVaR zaLnuRA3^(jLP_;sogdJ}&TASEOgC9}u#>%uujPp65Mu4*C5GRN<6Gm>CE5NnbT~({ zS0NCbU;+vU)SYLssVmrKP5(sy$`@V@~-m_0a8%;JPJp;mw=!6p|Zd~Dpb7!^ZsoS7PMO5~_qmaG77tON4m;g#%_wJe4M z^WfZcA4x1?XS!mL&LBgD=ZECu!Ypk8PF-{3*LHPqww-z*2r#e3uF>^mYby|(dP8zr zvCXbUJTN0Jo(e$sEPdP!udEI1=b5Nl0gH}TLIWXw2aHl^%OQ_yOzditKXADHB%J%E zR_xR^K9Vc*jqP>I+jRJY=7RQn5~HSzUZA1WZsVJhmu?x=Xl3^sifGYJXw#-`q&A-q zW75MdEv^jcY`WrNp%{54kF9(Rx9;$C_kBqyHuoFWYIlk^BC>-j(@Q$GtLQ#D!~(uf z+?E6LIP|UvVF?WGhrbdOP>p|RA6Jk#LDkS!vGkdSRmOgKbucHh0TW8oNSKRb;zO|e zK7-Dyb4U#j`$%-((3N`SiX!q^V?ouo*f`NN>P&38ME3}oS(wYqrC8o1xa|*3oseA~ zX=*sH>`n3BzU^p|1w)U*^3IMjcxWTyg67n8TCEUA_D5ONcSNe--B{gBUZ26~3b5i% zQG%!Ht#A$tN4>sa_Ru^z&PP#Td(>tF3K53q(vEqs9+Ci5Z!(z4iI|y~>F#L~;5bb{ zB_-g^AxK(1!qm+mYIfKRbI!V$%soB-@R()YS1tIb7ey<{Y!(MtRV16vJU>wh2UPLC zbCxA{U7uJQQ?MUBw;+ZqQg>~*24Nst{kcTsTDN;ejm3hfI*oPqV*5=Zbe#g0N}`IW zDp$pewYcdQsY^1oL^=pUP@D-BtkwtlbQP6yn|-m5#{IVM*3xz+{aSXB$-FE7R~q2D zHVzK&5PSSjq!~6q-Yq7^I8j8VKE(?v7J%@J6BJEm5I=O!O0T}1>?tx=*M$>!QU>M? zWnJ74Mp}XM5q>p->E*P-N-D0U$8bW>NeKi84H!p=Nv`rDf7fp%FI?I&!Ranpc;*sp zK@-w1*0z=2p^HP^n4p`{2)?evG)Wdw(B(v!Ra1D>SMYU2DV`Jos=*kRqx2Ph2x5~- zCsEpI(KXgVZzpl|3B0zVKuGFp(l?tAz~fW>x&^b#X&;O{24Y^?(sa@pP zxwR}UwB_?GI~=0WU)6Nz|nZ z?}!pg{z1fs4rNKo?pyGPX2z>?fFUjw$(vz>yuqgPiZ>SAkXa(Y#c_`y{KHFu!zY;* zb`aJv(Z{&J>CKkIF$K&M{+)~z`g&4%@wL#h9c0Bk6eb!E8tvY4s9Z0USul3u z;}II2e%u?J=6AHp-6LrDSK0dEjA3q;1q`7b5oZ6^R&iuKstS7D%Ll|^Z0MWTBMjc? z5aMzYRg}U%PQA&r29Tdc5CzA$>DcaX!4lO^QPV@I^g_6FJdc|ay%0I1ZzFapwcI(h z7pJMYIudRnoGq)kUD@RHwh@q0fvh$!(Wgm}^8?eDjwkEDI0B-#uxN6LaK2N^r9KaO z7vEfx%>l7xr|J@`E|M1kOU)@&rvk4Taf;n)o-=h7+sxVjOnB#C0J~S#?C)r)_F_U` zgiL6rRINzezSL*z3Unr?J+Gc7qj$|L%J(IU|3+ZkKF{XSyf>NJx&P!xC^LPw?8zj#&`|`|yr(>p6u^a* zYdh-GKsvar0Ql0N5yCN78*nD@Q^|PDe4$_KCn(Al5Qb@WiOE+58ezVqXL$-xfxEd! zsD}t;OW@RBb*kPSPO9Z#Nn{#4CBQYvF_@N@WL3PyV?%S2Kbi~zkY`)x>7dM1BZz=c zoe$YYt9NPRd!z6(Wx!vpFwC8Ny z9#VY`rEbk#H*7dmW58=?h8bFWeFAryNIJI z%r?3nd;C)`x$O^8TSLUbKGFfOyBPz9dAER%;@DRQS`$`NO~q7rC)n&l^!y{s)KGs3 ztVv0ADyM_vRqh`h>xC31Y(lFL!q&|KS~W8&J);(Sou#rBz32pRS(}M>mj_1!KP=ieaH-3gDbL(>?#g}(H?PTrMf5~~XsYWLr zgX}hH{0#3K*wyP=>WiG*3dzaG01u#?8f~=jRWXx7#%kVhAQh8C`j87;n>p(ICnh<)S?Ntw;pKCY<64vCC z9=~5~_jfQyLZ{3AB=q)1>z^k#XKBHntP z#r|02(^S?m4L>*fUJ=zKF4ygjPe!@4R!4Wy)zsj@t;l%p0s~=xv$M308&bdXk#S-3 zkKyM$>1(zFO_-#>Q{qlpeWv~*VCv@h*O=gCe(X)@gmM@XOs799xpgOq7;P_+Z;jfg zbLdN}S{BGhGWrRp&&nPnL$zfcPV)eQ!n>HCXo_;f-}N`xJ#`;Up_rk+ z!=f;Day=^e0U45HxsUy?d`LO=E5@~WZbt+nDVLf{+@-_c)5y30@zb$fj=6o(K{GJ` z`Q65w1CcijY2)O#Qo@qC5fcK7R(kQDC35g`~|S9$3toscyim=b4sZKKc|;rma_P-dU%~FxXPPs!8nLdnvueN=TYGAY&u*`saL19)IIUPa z7JljFKO;;=*fq#dCM+HynOU@Bijg85rXaGqi$K=pG$m4;$6|zOOlmI_IPvJd4g6RA zyqz3AX>3BMdotG(N3sT->Jm|ig&!+V;sDisJ-|Rp_{juRh!B};Qjz!fqoE95p}dP> z`pmK#6-2igX=P&}oz?P5wvGuFf$XwX9Yk(|o#db9#cTVAKh?}a8JHaqbt{Q=NlslR@XdXcX&2R_7 z`+faC4T`9Dq-#Id&UHBlWs~SUsaPKpBr_T4m9OyCYg$9pT7p}W#$H-ZGSz1lJl6nu zYt&9Ql6l+(J*B0>6E7vwjI#R*fyCXI@JIS~N;|z<+wk2^`X8uDuv8}Z863?{VCy6b z52OU}C&kFjo z#=8yW&spe_JFl67#=98k0(kz|*Au7a#gz>Z>jd^GO`j9a80KpcYRZepih((^gly8k zfyWXuPrjFmwMXeX+D6`4gn2Fy`sx~d6iE1Fkxg6;@NVtN^Io_k)xJ9Locf%8bfgE{ ztPf7DWbJ&I5^61IVq$Kx8ok%wpP<2V=L_>-EK~ostS4qL?Je>WVMrgaZc&$edKPnq zCG3m8E5Vix$aHx2q!A0eEZc`xHcbecFt@NZdY3u1vfhS_ZkkQV zA93$H4*!O=(%xUgX>k2_P9dv%+mZLM@Byi`yOGM0UyE%8Ar;KNx*`z$YGzko5tv)1+P-z%byJ!C4>F2|9 znhqiR@}uI+?_b#iGdL}fA_?Lmc`@1d$D_L3X=G1b#lNFz0l*vpla(zA#z{&V`j;CgE)^z& zDSF1u{p(yVRByaWAMQw|=9_sP59Z*3-7jx5W1nzlq^mH{Ce-f0mE}G*?iWAbv#cOQ zH!7LsGNGxcBcFs2Eu zF+Q(AkM3qql{eL0>`hnP?8w7T%+-Q3!d^S;0=*}OqB7IDnLJzmd~FVU&w9#{)ntr1 z#f}?0@0cfK0qQ>98EV_p9KQ;KEIlUU#T6^WfBvs85eaStIy^ppQYtcE1^f0Q{}s9E ztQ87qCpW|PM(?D>AY5=_`Si(${G|rWvS1G3);Dm)_ zhDelbslndDyk1zsfbKe6DS}6Dv$33Y64>l`<)N*WcXt?uhrzq#m1G3LOO6pdRFk0w z?8H8$M03YM6uw!4PZ~Ed{6@qH@U8H>)k&Q)<`yB z+KVfD4dduxb~Fejq$xZO0eC=SI%FaO=#;*69$KSA390Frl02NI1gurgu)Ee2kI_KW zg7!>G=~IrJHyKZS(jhcHqhKPe0kr!E}eoRYhg*_(J-gM0=Tk$+om zhC_+9BbQ-ZU~2L>egPuhQ2@0@a>4u3Mk5%X`1)+Bs(&8^f^ue2(4zKqArMDCbc zO*sjeKrON`u5AbT>ImB*3D+4#HWJti5eP88Zfu_X@`tWpV84ZCiGU{sRhJ1e12yrz zbEZ!IW-{#31c5Vk^s?vlNgpNn?a;rTmOvJD4<5$JxZVaDL}OaF_gjo@&TJFCV|5;N zClaF9+Qu#Wg6k-^3xEW`lWS?YaqHAta!>;9qI!te;}wRVsIA~OF0>$Mop}_mfF1$m z9~7~_=^(nTAPOZy?X0yi%MW-+5$@3r=btQYe|2B>G8RVm%0VViauG*NbWIEBEB9MI z9s4fAYocq`rzM=Opxx`(D_H2YA5#qi?3JX2L~awm{~ych{>APZ==p|m$u!B<2Pf|b z%K$?~b}ran%xFY-6#~o4pdgaK)~xvOo}K~}H%$mO67w14SXB>!KSt2`&@#FE(cFIQ zFR*0Ac`N~p!w~#V@ot2UeIHmuj(H)XJiVq;`eYK^Hr~Kq;lvi|^pJiDEgJsY7Kqdm1da z`D(kkiot23MCYM+^Fui4-38bp)#^r5eAD#7MSOCr*Q~z0Kw$o9aC!0p7$8V4+HbJ` zVnh9V*1+z{x}rL-{EzC?-~6D-$37 z`u~g##%f(21@093HSHx)j_k?UnUh=&F$)u)D5a(V!^Huk2~2S!V{D67xLsDbJ zI7*?nwW&cT35grA$wc)4OlduXT zxQLxS0H~Ue)t2iiw+ctvVxjM9pv1du8oF}rNJnbCI{|?=Aj$Pmy1=q2VJ7}N1_Kxa zRC3DqysTbj2hp``K|j8=zJJ5$R{v7nzYN`k8eV$(<=k7ZYt$gF5nE3CqQLpii3PFQE%OK0s@u!UBgH88V6D&!3vo|NFlJ~hlH_xDQ zb@+9iHZ3B6=ZZv(j=BEa(3NS&oWdvJAMM=60|e2OnRa514>hN+tTt}!ovWyUwW;Pc zYeWdk2Xu1ne;pMStcr1;w86$PDIU`~`D~I%E51QLFE%eWz5y!%FDK^(IYLK=@3C() zlmJR0$0~t@@Ha0LVE1;w{Vc-JD<4oup>%*&?V|Hdz$mgW1)T?=R<9M~NtUHDI(!XH6!7MXW! z>9c?q5?{!lzf{&ppMQLOC$OBzn)2r_s6hb^dT=aerulm3RN_HJ!xTf2>2k5M>V%Sm zaOFjFUt;a&3OCW~lz&zL_K9i*HZ%iHdHi1iID;X#*$aqaB~Ttnni@L#D!}SywK3EA z@w<@7vBbnCVhwE)d*bc1e(uCcujVSxq8&_@xqFrmh!8~bJ62v)UQ&EC?AF=YwgqO- zIVXPHlQZSbJhvKy6gwSb>Z#foNu2{o5w~v_1Cd+o!4&mK^;7ny0+OCsM@Nz@gG$0N zO(#5}aFPz#d11pcrmtoq*$OHS7!ZAu6W<907TOEBIt+cVM#ANIOAttfjKu0syD7s( zN#x24f&B^S`xNH}DFDBnj+xMHR(&kDDc(rOz0={`92$B=Tf4o;{IFwClCN) zMy5Ly9}$WNgP?W%UrP;%K>5bujx7(;sNu<9vyr03Z{%dg(^PV1Jp1-?af!d6`_ zP1n^SJ)12MvNCR-+YY>#!XN`vOk6?v&XdWlxrTq6u$W4G*qS+R>uPD{(HjudP+W06 z2;XnQxLxfbZF~^?z9+_eU}(Pju=1ep_+fv)`tbH92Juk_f8UAN8UK<74&vn4`6GqM z@GT1D1IL8l2Vmr$R>3S?=5o(Dy0~}pSzsH77wok;z?)Omt}K=;d0qYU=TCxzl*?uv zc!615Gpk-pq&YWGND6KpCBNu?=(B1a&5Zyk2A? zzFvIweU77~|EG)Vfw%F-$3@UYzdvy&f^|*XaweHSvS0A5JpG-P8I^PXf>+OzkKpVme-#_1D;02Hw%_Xx1tM zs}5F7YeGH`Eqs-L;K#iqO#*O;GQBq5ndBbcQ8pQ<_esJAjO+$t``Gt0Mejxqlq1$E zTBs3dVLib$Ho!Dv`yjc?nEA9#pBw|mtePmxF=nc{-uBKZ(iq$%4;uFvPTs8qb*;Bx z%;hmng_jstah~@+&iZramd!)h-bV4Eyr{`|+zZ(Mi&zc}4rk4H{eP@jzwb<7LpPv+ z@ah87IF-4toEa~G;RSjq;Y-1m%!dbiwj)Z%`=Oa$K1Z2qy!0^Y$ndB1nrIY^Lu^7c zx4Cj~f8n@(Ly`-8yQI-zRyBl;nX?!8?n7z@WK0?8V&G+L<3qq$r92RRe;fpcD!!f+ z)Nv*tH(hbS-~X()z$FP|SzBlYGVMr0`jNd5*|bkAq_=mH-5y0(#h^*SUw{zGwA)kZ zm@9FGhkC&3lv^4@kf7Ju_(cD%c%j!fl3t*8IU^b975dei0pIE{*QC_}bVy)7B|=~S zCF{ayb5kd5M}mkp0^$4@RDeQ$MfNXuxu9y4lNDl3gO6ODGpzFXTYRHa|hA2<Pw5;vBK}1ea(-L405rn?F~Poc4%koa?2G9kJ#P?^`vnKDx9EpsBJ<6Ye)N- zCl8jup4ft>0WiM!^?FHwhZ$PmvL9SysU2vsH{cAQ;=LY2GfGJ8J{yg_ql}bsWs6Qf zepFGB+~eR{k^C}(84FU#P)R+_d+1sm)wDXj>1FF9zqHt5#flron4VTYyM#~xRATy= z6{IA}0bYJzN{;G~aA+(2LIhIq=5YM6lPQs`o&9?J+6N;a&z?|?fhk=`+(xXr!B~Rm ziT4xw#yo09*bf#Th*j4iS?3D-X}RF@nBH|Ehyo+WmAE(Cc@@^~j73KI+P9b{lT!y8 z=k6ZkXqXHy6}I~>U3j|K$L}#r*C-qLkP)={8N0zd4J6H?D9lBNGRaiLUVFT2`S^=9 zW<^1;mSJ=cf#pSLd({s;!RfGxghvUx8pf0u0@I|WVmfKOJ4f=kcgL7XoI|`S-0wv0 ztAkly>XCm(9ybXQS9(Zo1Yv|16q54Z3p$p2b29yY^V$dpE+6|%H~nX(WJx@3Nwtqs z{2XY%%vZi43y0LdPJa!Po$$MgF|r)VA}ZncOVLusqR+AAZ!}QSz20hg8z;DWc=p5T z_b=3fX*o7e1)P5k^b68D9!PVTEL48;u3jr~z4rFf(uVWp+Q z8*0=nJPJ*_t1wS)v$BovbByG6*;W@6x>jfUp?vRMg60b>%aM$i%$V`?c`=xi_R*!* ze?+H~0#|c#IE$b@ zGqfOYY%j2f5Xltg6<#ZBJ|okA zcHdAc#Q0(qWedk!()E`o%uC+%scZ|euZqQcS+n-S$*(Sx$Pd-hT;5`J`hpY{6}{0fkA^BCeCn;I;5sb^lGlxLzfk({Ibj+rCNP)3+`f zDzK$2A32rDgYO_c@yne-f`CgxwkP+fueZ}FnDNMw1!$P@oR2p=d68)CvfrG->w|>* zC)v5?b7ob~dRn@rL&V5(!C1hQJgy|)nzR&cXo>3YaYNq8H@stdqTiVfN%h_@(53rD z6(+t!X&1D5m;G>KgQdI3a|sNyk*d*(@p)-{&Bb3={;ryy><=f7F$$d6)@M~@M&uBh zl+Yq$zubH=ad_?=<%e9`QY1v!`mE+g^kqz?`}Ee{mEqfQQvW}oW;v-v4C|~nn*~RS z>BDZLkPJ3hlMd2HzntX*7ENZ{aFcg;UQnnh9J)TS!wKD;#4d*Sz(hHjXX3-S3l)ol zx-@hdbCk^|vL6hC!sBICiFpXHb=P2PCfK7Y{F7@w6p6V$M{XUBqLV@v*=)R0GfdMc z>1Ux&&d2tuYj^N(sQR^cTWAYo`A|)*a72wIZ7balJJB-Il9rMsBJQ}qQ|{-~>S=aY zzc6NtO-Qr=`lkwcxY5p3L=890Ly(`LOm-MwOAQ`OGq&EJ?`UrJ$EaWXjBisi ztN$bwf2Pi365sXGP)g9zAs@U+)=5L+*_DZ0ld$Lg7)|L7D{1xc-s$B!xso!T#UN#s zX_g~+l^^0)?^Q&+z9!vdi62$+oDdJ})sh%C%PL6zuspO;ZuP%}C6!_%z7=?(;6REn zdK$bJxDpM95m$ihWsZAI{Gw2~#$oh>rM7@b(T>SxmKwc`vMt)fx^ z+{i=2lNwmeKr^H(*xu0&blT04-q2bblAMoO$R-gproVAj@xA=~roer&<9+sq>^;jZ z%P`_^h>=5}xL*jQAK~e)8^<*})mnggKk|Te;NajPMJPRP&0uz#xMxeh&1aFdVH1Xh z0825%%qcu-DMug{VI}S_zZ#O%m!$pF&dI-S?Ou2QQ6F$tl{X641iP0}idvH`M8!}Z z>znVpI`<~;TU%h+k9H0c3arWV{M-Dd_r;L2GDK|Qv{aE=L@^s)a@^>gyY37gF0P$I zP&B1=F18U(DO2x98`UelNMThQ@*8?0PS*S+_efUgbqUNcm=4Cx`;3Ht40w*Tz{;J7}PC78)9mO-NyVYw!gC|M!X z*KR1Eq202oSK9er+!@yQu|06$lKhm5jiyqI0Pq4f=AOze3~5o`$aRT(a(#0;h14%! z^k*$P^$wCw0$y}hO1s2S+MD4z%!LdGwue5XmOh_m|vz#y<>t+y8S&i zcjCUhmsQFlRb8)3V)qPcSa+1^TqAsfJ-?mRCV^(C55XsW?+^P%zbd~MmRqr`5x}V;t5w2iu-IQcEx)m=1X<5~b-U=% z-s87fnL&w(Uew4aj?VEn>|8bw)K7MP9v^4<__aO@Ax~j!K~4P7X4{HA(M@Y~7!2Hf zCzBs83u+Clt%`);H$O!f-P?#7k9W%|F#gayQkcL(0@cF_s6_JzGa)1Fg*EZ}Q<}b4 z$)Pc>M8U-t?Ypu+K6z{kRjXlGYcV6pAZjC8BEi)R5AKsi_}(L}*SGAcN?0D#%h`1d=~rsZxK)Z-|7uuJ5AH%c{*lQ9CyNMdz6)ciDR(y-P6lt~9Y`R@$A(>*x?o@yo+ zRL~~t&7t)5T}_P;mDw$XK}C^ilmrGEiz38UtBIvm$V~wE&fPl(St_b`9)*4l$Ft&2 zwMH`heT}Ft{ZVG?xR^oB_@OrLGEJkZZvi%hRN7!SEr9CmOSCX`)Ly(4TE`~$*CCvH zC;boH}&Bw+~V*b!P>K= z?%!u0>vlh`jQySeuhbTgTFxkqNv zr}{Xyjg!X|pVR}7{L8YUjq9NuJoA6rmw5GIExlq+Vil(HJO}0c38Hx<8FDhO@O{d$ z^vZT^gU_XUn6^JGD~QIY=h+;>6pDUTOk>kQxs9mNM$#;5wXZK++x06g?}=|x{a5{a zOvoVQA_b~6y=eX=P}vX7gqV06L5v!pqRJXmF6fG_)Fsmgi(SFA z7OH-}-*S`@k(>VIjkzw39gmg-XHGq|(wgqD947Y8dGU~VpzG0))JN3z2^+l9O6#M@ zR>)MJW7lS*OYDXn(~v&N5CPv@h{L#r^x!u?pFjbO<&v9mi_D8%Q>%Kl5&F(~^swP} zWLDMAuQ_dxzV);RBcW!A%6afm(-liAEj2wEtW*Q_MmepidpWMMtB1cCyh~3!ISq3v zR@1=zMz}|Rjtn^o8>MHn0tZ}bs{Z?nJ3})}6HPD1?)%%VIa)F-xt2m82wZ3tgsHBIy$GnOe3i2 zTkjp06|m|*Iw5Jm-t&(XNv9-44V8tRyjqf85|U$v#C)%up5Vhx9+NoBYjJ21_FjJ@ z6^Wh*+dF{lIrBS$pmyqQb-voAZS<*Vp7PYz8=hQi3r4ELt7Hww))3&2X#8 zGR#KOF~@YIrV`ID{3iS=If`xC@E?gYjxPY%{=8lioi+StWKB5fVqXY z+v9!?{|s`V-rW31Irx*%eu4}#c9wh6CPxZWJY5qA!W;aNx%l^-MysXq>ARwiL(vk{Dmo(CG=#=h5Ntb{~2udT}aA>64LrIr#=tCX4 zyL~tK``_`7JMI{lG5Ej-_TEpdwdR~_K6|4G0gzg1I!agr$j8zqVYHFp5Tb3ye&#lp zzG?tdtV3BBS&cE&6o*L}VsAt;u=PEqKr~o*$gMGVGejPWOFSWZpVfm7kDu3^poZ$n z+H(oflf=}+`N?D1G61ELj{ZNU0nM{2cx;2;AXzxvciya!l*;FRJcOuBh@#jzB&pnkW zB#SVxK*ig>j^&Dx`GL}ToGJ$Q;1vPGOhSZfu<+A#qIzOrZerR1z~>KO4;4ctHZVh< z4shY1`w`*(H=?X9M58=sZ*-sz3X4FDezP$|2;pvMh*dr!oEx->GXAtx*5=W8W>2=v zvKQ6?SFmHxC+B#W=Q%L&C^-@$WOlj<<-(UQZmM~hhA&fR0wkZGzIL-h|Iw4+{38R` zlh$cIw@>PnnDCe-H0ymE`7PFg{bHZ?w|%@iHm)GmiEQ&go+wm{tW>0WY!*qKdM6@x z{M81#8v^@39dk$p5zfp9uNDc29Y_#s`a85|-~X8Pu@JOoft`G1{dV2ocY6#zMDoDv zu~LrV;;4f`&v!ao?uN-c_qg0)T^>7DG6`kpar4&^nhGd!!lZJ7|Kp1Q2%#dl26_oe z-F1KW;>XCmLA`7o(?}U~pP-EF&+zKchC#1@ZD;BOG2_SaerG}uyOGkq{>yfPeEjuw z3Ck6Wz^2rXYfqt58!m}kwWU%D?#2nw#K7}_JZzlppt+P`sq&?gs&}Zg(ud}9&gf9B zfDeI9#B0&MNo)Gk&t~Uk9{JaEYH5CawnF@`1b2ufwhC#X(6o`?I1GIjqQ`ROH(sNvt*^_)sgAi4*#Oc+O1y_;=n_J- zhGE_U=Qo%4idpPM`ALk2GFc2xq|zjB-GU!IGxocs z^X%QfX_O}gm6IZ_8lRBrz8hU-`8OVZb_!S+N*l_Vy18HL2_g)DiPnNL=K>@xkqF>X zy!8lkY+aPx_!|7GxGi6t{!)zxf8szTeQ(ozxPslbkQb+SGk3tCR@T|1~js;$ymS{%ry;@W+D`@a?CjtR*LJ_mg`&Z=}c>b|6ywifQMN= z@e5abRUsZy-t+0G8t#cZ5zw8DVeXc{oF{7EDsS?MR-ymn&y_xOHgeS=>zJ($PCUd* zin1?{%;k8Ff9Iaa?usJ+9nt*MFs8vv2;&NXJI=}Ku(xE*5iT{kq2#b>7?+l2y9!YMN?#kQb-)^FYFPRl$9T{?kFamhBiq@4W3^HB`>DaoXXU|{S89q0Gq_^tEQ$pvkJ6PeE=*$@gW7fC)J9;yL@ zjO%v4`r{k0-K#cAr8b|B&m;VVDmV^W#Up50NAU=Kze-VqQ$f0OdJ>CU^?MuGSRiSn z9&=l6@C4_4*6$?>VsExuOXam zg+cP6{b#{c-Pxq5(WorwTqM4k|MU}4jNqS*(M-zgV~?wA>Rjfan@3*x%V!KTxz|kx zZwZD_7KjnmZ-7aYTf&n`*3^1=?tXWhDm}m8WQ80aD;L$$8Z2YdG3OhKE^xZP@q)v^${O4(=BN!ZFX<;2duS|Db;<7?#1|5Fnly7 zO1vM%Ww@Rp2e7|KYdIe&`Uff8;Q0VeX83t)cXp#O< zy(8Gjgl>P(`HwR|FqKj71FB=4&iNuV= zXA9|*#*|;DMI?@O4S37G))5fsFGt#}ohBWZ zKL&!W#2M>f>&2-DDkB#MN_9a?dC?Jy8RJ|A1NLJQG02ed*TG3KmJUU$<>MO z%)_#x((ALXr5t%|`EMOLnS|eMzljseOcQP_XTQgduo=vzzGyU*_Gsry4rPFKj|bQX zCW3U>D`-?CU3Q(SUe0<-{W#$ac}9SOgt^O9&SJ;W=iAF^@z}%sD@2k=pY45f+b-&+ zA(3U_k)pA3h;$Ev(XW~OP`p~sQGJO{P458dsaV{(#)UY0`Io|bwb!IN{2tagoC;>x zZ7kH27out+(;{Jj380mkHw!)7Ej zD`HXc4xfE<+Vu(UG)Uu2y&LE6HJ8wSEf6366uK2S=7x_n|F_wDQ0yK_04YK09-Igq zXk{R~cKvN8AoseanH}tEAbYptE;9X8&Wa3yPB5eK3N;)_L&eFHL#LbSzBY;!B&$C( z1PBz=O=`tdg7HG~+OylOmV-7Y0KFgHaPadH@lm)tIcffh_DKfvb+&%7{S8=!g{O|& z&n9n9Em*sxzip-aG2?#=oe7cZM=71-fWCuJmqvkODMuaTgm`h21HN3{C(zy`>TOx*Tt_@!c*Vpd=9gILV( z(+nwKd8D!gy~?~{XiCN%m}3y`B&M36IV;JagKY#K z<3)2x++29Js7Wdf3pK0zHRpb>O_fkYy*7wj37il3%QUx-DNhmV;Yj3nqe%&)j6L8~ zndupf!HnoBGqZ4XM2BcuI~}pz1%OdD#qo<4MBTf^oprghh%_3W@S!3=!M3Qo1N|^n z7{K^3n(^XJUDQGM!b{tbxNZ=z#<7z1v^ss04H~HfpTV()jCkvr)CT?Y4N)Dzp0S9q z5(b{fAP$&8jGU5IA>kB;HpU#J?%r5ne+~t)EebNc8Y*w09q~|av zhz0~qQj~q6YixoX zTVU4-J=hhuLUB9_{cr3~qPF!_ZLTj!CmtE%MlSu7V1uN_jwsi%oH8pA+%ldKMTD+!cp#$SZ2H5vs_O-r2@l0C5JrQDppBV zdu%p5ojoR7UtjAb439^;Q4S#<{C!@trXD*?@pGVp$b@qL{1BIcFhud0TYFKNd>K~aV}3CqO6 z&%n1Ik)&wmFnnhByXS7h=v)cX?Y}=zW}DgfPsNJ?Q*f_}_4wVZdL2TkC#|G7y~H~5W$hX@RyxL9yfg!ZOGk~pH-E$1wgU33ch8c@ z;?EQHjm_mWvsW2I=hAIJ?wEF~H+Z@!RF3T=Q_l+1I&viq+dgg|1e(Sp`}#K;|I-*z zQ^mL3WG?Dec9xyNcHu&MdNH0a=1O9_=-+&sg=A)T@;I#8-YQ~oOC;{iy47IH&kv>| z5MRz7B-#}7cD@)2li5=R_UFGDzu$K+<%(@aRr$DS?Phg0Mm1dEJOZN18X_tlk|ycU zhW4z$kJ2Yv8}}f_Dt5B4L!y1^4qJG$^f~pKZI-2yIKEW!XSI?~kg?T93Sd6gw?3)O zYGoA&lnDwH9Zwl$6`)!nR(c!-3*vQ>Z}^?R3;2}x+Z2&3j$D1ycw8s0JW~MjoZqLr zsrC3ww=GdcLlTp`E472Bk0$gevk3Z=7OzcWLS$ziW!agbh|1&^&T~pp{7iKyXu@fJ zbant+3&_PU71R)zugtp|b9-d3Cy|c^j zxXX+*Jj4w4To%U~UmaDz`EfyBr;{nzJrkj3A@Ix9?E6+6R0pDgJc|>&EzSwwZ~mNf zayC<^(%1R2h&>Sb#12(#Q88q*@|)0>TY3mHAf|vCNT(JX71Bke7LJ%T>vh}-6XV-i z^qLgz2A^7=GAF!|Fn?fuw*uEYKk?lS+)Ln|7mE0T-kh^O&RX*)Yb-t|jl1XLCdAp*hHj!+(^% zlivO|dEvYyAh*m{?&$sd?z#L&A@F`(0$gpm)o8;}3Bz|@8dxv~3{tl{o#5}n#NOe8 z3)H*ylzQ%ey=AKH6Wyt-$!a{)ETz8qXc`#IkHGCAKV0jO<{}PEID2y+sUtEB5$X>r z&Vi+|4(spa4$mi_dX;@o$zKC8fdn=<|3JXswJ&tT5dG&4mVt^?WuB2Dn;A?;!2l-g zW6~m{@2h2wR7+G{20D>ss@;XJv9t8!?N?VOMAg&=%rbkFwHyV%<8b!w&hfDK-TJ=&>y^xXOXj+=zP`S0$d=tmn-7?1IGU<6>t${_NHQ8pha}tMxqd3puuO5$r-cww>c6KxrAa2deJU?pO`sJ$+=Yi zf&0ie9kCUH_l11?=T#V}h z`HuG@q!yo)@rfp0+aaeWK(^KEbr-!jv5XaTEpEBT*?aO5ocE~>_ z-@AV|B-LM0^&VE&mNa-)`uUQN!~CDA(@9~?tQ)S~tIRs-2a!w^f++Ccf_pD)|)%pJeLULtGacn!JNmrTFc zy+3z~6Kd5{)we?A+>e=+c7KggVS=Aks8GfICx#PHW>!T8U%m_fMUj(Jjte8=X6Tf%k%i_AfgyVzESB(Xx_@5V` zn@gD3+>3d^_3qZVR^3fh+VOn<#^rq9?e@Ct@2+2SdMk{Gqc-W%x^DjC^+xeF-0jx! zeD=&WGJQ|*o9S7+y2$U&%U!>eg%6JzGL|HR=hK8Z&Q9FYT>rZG59hIYik!vC7*$>i z45_$m^n#lmyt$Hk++K^i7_Ar9^|)o$ZSM~U4KnJH41WWvE0#}|4;`roISWY~JvJ=D z*|c6xblaTOwDBJ{f!lBLl-}*ZPp{M9+pHv~njX&-*n?Vp%Vybbd%^2k>l|xo86@tv zf9kjGF^)c)yy&3-B88=V$kFl5=cD?^7?7RxVHR(%CM9&|j9*m#nJ{BzPuJ*8DLm8` zN0Db6mm6|M>sFaCm`Yhk)@rOhfI@SbL?ter0F8LlyhOR)2lXNalUJ*J?8E)4$3LKc z4~Q*tZXHN?`uDH?>oxDTjKJ33js1^$RW&a%>gdh3ZY)-68)$AnZ;r1XPMt1LC6+nH zHIZtftGo98Sy{N{n{GV&yyCW9(@J%mm0o^VmbFmUrLeXbkDGGw>Od`2B?4lZ@#n@O zyjnm`iO59s+`e@M2&YDtBSB=q{)27@0kLo171@^EeiE6Rz8nnToqiM=fPPdrh1xJ) z$ftGmI{EEL&s!tvzg=9p_DbS8ctTIDEj~W>+Xs~ZZOssX7cxMHX}>md^GH#h164Kc zVT&*@KK|$yX;d7H-KA1zo)lPl++;35@iFm_|8ecq`1l!9+tg`t2KrI`+L+r$$mKgv zIzrfUm9nJiLic$gDIPCk+eDd*)2j|XtkA11&{fDxP~Lp8c6WgN3THQ2?4vZj26Wxj z&Bi{<*NW*aDqmQlj&>6-^-b4#X+L7{u%*)dJrn$Hx8XPFT86j1JJ^``s8hkP?M(l7 zDx2>B#tadp>8`A6DKj^yKTxcw17X-*R79W^Ux=Bp>yhHOULVc=sWrNIJzJntu+?cf$C5y{>L$eXs#^CU)cw!oN8;&Di~1 z>uV4cwA(wbwJ`7Bz2N*iWxE#tHmx`-HK;X;f27B)5Vi#N8gNKr*#Eq8<&OgUoZ@Qe z8zKbE>J_%9$XqU*bV=rW@B$G|-?(8H=RfnD(5U)5i`V{p`yQybenw7S*MGC99A9|i zkp@{G@qe2=o9L`*LodI*_2fG`x;b<6J3`EbSMYwabo}kyrINvTYapZN3=dozf%{^( zWcV~VTyw=8&($#TCYd@|H{U(3>#-Y`UW-q3iQ?18RXF9IWGG|jSZ85!d;8W)Qt@lO zVK-Muf2|Waux;j_E>E(Veok&tH9Qc+GF9-?2E0`?`jMRUGr2uplq|_+?5|Dcvj)yM z6JFWH$`z7bZLh;EI1)36dRF)bBe`llvdxI?G)DJJ$bOL=pQ zdvwnBfx+UphQS2~1d7JbZqY?Zy(et;O=1aRh2WgUdR*1vD7d=k_HK&nhMyFaI(Ei*)mbgKk)I z*(;hE-m&sQc~ElmOXsPc7|=wC1`GihEs>Vk5%+V#Fr3}T5X)^Son?jxss85xxg9~y=FDf#ie1So;#-S&eVeXG6Assexx-uU5Il-1B z3UPxHVdqCI<=~Zl8-fxOCpa3qN7RD%zObYECZXlvkGDEu@wOs22OTAyo_h`JOziAK z?@RQ@CMOeasdcCImavD~vmaif0#Zp}JTHR`Yb1 zu!QbXn^De!_?(knQjydBBW3@CA(yYphjobUx|8~r@7ZcS!mfLP&9~=uh|7!ObTsmY zV@6lFwKsqCMCquRj0KBU&N&l|mi>apu|$W_U%vVGXMdk>qbvA<+l?%GdU}_zw%QA4 zvRcXJluQc3oh8(t^ zZKgE8Jcwi|kpZRp~nOD>{-tTdVu=A(=UtOS&*XwtGGJA{R-?k9&&Or!=! z5hL&dTPT+X?)%zOsX!R8EFR^yo4dWdG-rsWbeK$|K+u5JkZ1$FpE{J_J9E&~()A^= zY5b!NfM4?NKA!#7O(T09M}tMMgaCD<5LOAjcZB#qMFccrdyZ{;F#LUhhCYPA^(2!6 zs;H^Ur=~H$0X&QQxtiN0njX>ylLPk_>+k(@^-(S+&-z@0JEW|nJY`La>gQB}HqSAQ zLjll`DI7tv`-a3gLCHAmMb1G8>kpK#{xa-6T3!fX&^{UPC(H?KBXmQwEtK6(yHDTV zNRTRS6hY>yYx;TGl4(l+_nhfCH&txyQz5ad@N{(bc&kq!Z2yRmRc>X||l>9x##Nmt<*c(|O8VFtn?KIWEPIMOJ)} zFNR_+_g_2IgSf5OO1u~Z7$K>cK4=2%jbGbI@wmEbhC?gujoPw8_Mf%WMto!56RY6b zeFaA|*POo8Su)o*JyNZfv(?}eCW#roN{e{I@E61}S{mC`f>9P3vWi{40N$MNr%Ned> zq1J$b^+3R|v7JX^k!DeBQD@OTFR!x-q|IefA3;}*oX1BJ6ANT~GIcUQZ+#1uGo`jr zF85ak9trS3mylinCMMAn&V*k7hev%0fB{4v^e(Eyk3CYpe3BpO0_~fmCn%&QD!iq#p@B2mE(tfb$FAH|Gi#>9;|F2%YG_IYN}v@$-8MO<)LZf%%h2r{&7NzS>Q1D zdoOvX*9trOK4IkJ1J$6}4>QAwvYR$iW?Ho6kuB^*aRGS}Nts6IRfUCocZy??{!IEr z3SiLL#;(I^&XP*qks3}7gcz35#>!37u!cQCP>3!!u@^v`k&9Xti=_(ZD*~k=EM?Cu z2cN}u{BxZBC7{>UddYj42JjWIUtxEUdAzcYBlQN4CEmRkzStlrzjuR55)X*qg%=_RMoGoOmnc1ka zm_zbKc4LgVae!x*!};Avb@H1C7p>!1J`f+7wjBrlA%VJu9?}y) zRF%*d&`8ix^o_hzOO6FaO{>@_VEb5-rZ1;~)^_BZ5Jo~+N}$1qmzUYF$_L};K>}b( z$o%6?IlRhv4^ob#*KH`{Ze>qJliPcW-FUKv;`@u;8lUsb{=9l(KlX}w?s0RfhLWMm z%kqmfbw?VkTZX=9R48)IJI|qgpGJtoAK_R$m%!H*X<`xBux^H*+^}+FQ%?Gr5vlf% zm6-|;dvys=tOfe!>86EwK!&G6hWd#pyF9)lk3rwzSik{eV>hGH6{hP~6kqx`P80>S zwpoV|69U4Urrwi(5zA*KhIv=VK6*<9n00n@Vs2%;6jXZ9awA)WE2)E|+Xr?7jvDn< zsYStfTrbZ{Or;k!GwXY@pGd=O4KmZTcU?Va_l3S5#&P1&uWO<|GsTuL=004VZI&R2 zZwIAgXe7M2sREjPH_vWNKJ)5L13BONwrn!6?Yr)7m2Uimxw+8y;@M;`&eS?fz&sau z-NHQH`|D1~7mIiM*YZ&X^XL^ekUKo7Og_P)-F8 zQnBdm>*0I)Y`Gxu9Un*?vFQmeq_3sp$N?)%8z4Mt@@2ukI9pU!>_2!(eXe5J$%dZP zfBECG_AjA**2@}6T972XYBfZMOw#BOlS(yN{!j|W19k9J(dvKG)lzUP3 zuTsx;n@9FGE@*DoFJjt>d%jceiq7kBs!>utvhdcV9`l|ieI=xhW>i-CjrV5AnrUXq zn;z`bOf+y+ai+Y%vgYkP2V)H8A5JPI#E2bs8MpitQRiU+Po8L zR|XZ$R)-w}T{fP!@fpI+?y-K!Bz>TF;kVAE4R}#)`9Gf>o>(&#FLkOU__e_ju@>K46EQf88X01Gu2 zz4XW%LRma_TfI3C~^gdiRLHB;5DU)WFNG(1wW1$M(BJsoP_Hjsw6Gghp zQtu$8klXRo=?%xp1?IwC9p5k9o7R|a?MAV37JzQ~_uiZ-xpMV3#7Gb?bRdOQ`65l3 z;h|agx|OczaF-F)5d{YoxolYar<^Hp5)(KCrRymZXYEEjw&5<)O$MA|AY#5Ly7%F} zob&;GECT$)-oQR4y-#k1_s(9qkKgH5I?X?^D17_FQ$jh;>q%-}Do`T*f8ohZ%Y|vR zFZc09<$q(kNC>its9kTqr}6vE%`xneH#(VCI~^41__w+L9~rM&rOZ0^dX0PQO;pG2 zGAB=lmi#l*&(X5t{^9*amDtnc+uBR@>9k-(_g6bTrZ(@CfqQB1kp;jN6S1!a@va+k z!v!%hQ1nnK+i@_5zoanl(FuC68fn>|M&d)`5GSJEc}m_V8n zD`}i=Q4YS4R9fEK6Z^Fp+O&tMOpml3X@`(y;&HQuO7V&*wKp0|=BvXdLIjEmuFqKO zT)Y#$i8bWsR==(V^5R$_1_R|D8p_r|*Hv#--+pS9`7aGm=DFN9G(QpVu!Wz1FuVtZ zM?!jfEt$6dKa2>Lt4gAlBm_v`159*G$Tx2A!CSI!8-LxMq?E!_S=F5CAJOr&ef)!R zW?EuQml%dO5)hxL7C?&VMV%zZ?%_JI;1paUAhuv^sUBxk$8y$9FY#`gZ z=g!_uHvTGR1RYch!S8h)HtjkUCTKMvjngeRO};S!5cTKe2P-RbcbE_Nf{*Cpu^83} z`VFNvZi%M3n-011)bpRw(`O}t+hZB)v$<#CM!LVfyE>fGn84-jav?l-+&@OJ%H(S> zEm7n^4pQ~452r{5SL^;Y^uA(S0#1r7_$8UCLV>J42U;sN4(H4^J_fCmuYSCTZ-@`9 zpAT58%AO<&(0H~~dEJqY*0i#*KE7fs{E0_5@g&KI@zubpO&tlY0@XTqie~{qQc3Eh zakIBWuSkIzVjzy1)a;(fc#(25#5fB{+?ItQG(hYxYTmlmVAee6sVG#b3wY)@Xg`Un zpV&irG1vS}XyrcU#;qMctC2qDddc3_SOc4BvEJYPKhQzDRp4LGh_d#a!-dcY)_|;d69iPy~h4n z*Da<1_{v@=*vBAwN}C)@iC3#TTpJO0Ad$J)7zebfaK+eEp4*HPbuKxB9GKY-PK(7c) zbV`zrNm5z2Z_8fIYDl@2iKlt^v^xAKIcTD41F=ue8zkZc$_G@UL_^dBKceAJrn1ia z!7QEim>|4Z3SZF7W8gKwwlM;gUXdL*8zgJwxrkg#GeJLyS5ka4h@F#wOI;?cb?0B{qdz7?v}N3V z=D|I-r(KXFxI`Nh^s`lmX@ImLbTNnq>z%5^wejJ}3}rA6Ul{K(v1KcT=sxQr}m<+D5>NZ|s_BW#J zG=r;d1P$&NtkH>_D_|>6AipW41D%Y!L4JuoOxfvi%GS0$?tu}H~# zdta4=OTD~aO^Cvi4gEH%=O?pdvGIPw5(~I8r+r`j*~=ss$!7bA%nFVz!+v@&~VP74)U}!P25@$Aq_= zfcf)XtKHJJ#KC{DQ;s)Iqi!Ase~YNPa=ujOgSerA{UDiih?tbt{3exjT0z1)SNxRx_rfrm^1nv6L5Bv766 zM*xcRoacblmL%N|n8csqjTd=*19-gKEZ?n-iMF^PYz$HU|z$@%9+a?gmw&^eM5{sSHtzW@D>sG&u-*!x4;Bk;g z_ACt==C5dB0dnE}qy7l!G5Qd|5{W@2-y`xN4U?VE#w1!UJw%wH;7_%+v0`KkJ&9vc zY!dFamC#3d)+(i}dDUmchTve(alf{Cp!k~hIjg@$&4wKFfT~niUQwf5bYa@7ef^pI z9DxKC{8VJ0CJ`psm4U5Dk`XxfU)!3si^lcXE>p||jNA-pw(@byLDUCbAEa`4HE;z!vo28HBA zqf_#)%8DMd5P6c#0s;N*2%o7(wjX3gb5*O`a3A}AlaGwC(F8tfC=IA}WTMvvd${=ZQf+3*Y0Yn;m0wYqGQTu~sGfXy z6Dp@Y#bp*2ackaQ^}o#C_2EVfq%o^e|B^Fa3bkcDm}+da{aioVQRA(x=R9|%!#jSl zCGBA8wrv1Qn$e+Krze%|db5A9*Bvz0nKI>Mua-Q2`nB$loNLFADJ*Z=~JTp^(gVM6|ls-29B3n zX|2K?iI*&+EEZ0n`b!a|VMeBO%nS??vx??skf0*)9rv8(!sEt{Po+LNDyKw={+6@-Os_+d9@-;{YX#Q zL0tq-9?1k_bg+5pCZ9O-C<63)=v5dCM%r_+HUN$&i$% zzirv4+|c`x8XrlVs!@*551O!5VSV1d9RHsepvI=5v!I4L(2rZz!?(-=^V*fpe4%vx z&~zcy(af&oAMcypd0E}aLOH1}SPzdk4dOsy)tV(i~)GrfSm%D%A;*wcw9@zy+pL~T(~H5a~SE+P(ItL#si<~+T$jvKp8bchl<*(8j8tF0Hm z;^9U8k_>dhUU?MNWlD-fJXyq$&+l%fl}LIIcZz1($kQ7J1%@_PMdE@8NmG3F{9Utz zR=YYr!JM=sk79A3dsI6m_$*5FT0Hpx{mMj-D$Frb`X0$77AhRoV~|`@{zU52(NUhg zm#YjTj>-_7lY~^(c%WQBh%mXD7Q-%3`0BzNlW{Vvtcgkem4z%_UzrvsZWYz2cmC+M zLTOnczf?$WQyr;Lj-Cu>wN=Z1^6JpJ|AjC_W>@p2_$bla! zoV+>NMx-#Oy>Ki-0x)}e8a=BZI*fYq(m)SnX_0Ja)oZH6x;sh#7(dW=ywW5@t>VyY zU{QN2Hi+GRTs2Mag2U~CgxVn89pX$^VWqbnny``X5lKXbPaRe1g1HFvh~nCSXm1w> zY1)?y`L1wp%EGqa6sfmp^mKlZe6avAPTBnWy4&rt{Zsm!>U=J(>3g>DM62YHaVa(8 z1e!Un>|hML13T(4E3`6vw$X{@QP~@Zxz4S4T@CNJDb{Dnnaowe@)xVDZnv!R1kgLa zk`kNIA~(d54>~h9>cOI<@y{LT&xbq}bOM25SYzxFtUNlm`0X6#O?pA0#>G%u;b`8%fp z0GzH5bErGAM=MTl){)7b7@TkUU#uOOE{=!M?!3DB6*$`@?*abRTeSe+QgA#~H;qC z$X#8rK;*&IHOuX}N95kf-nfyyB0PKzq3$9BQ>-`YIkva~ZyIp<;aa|o1cQLfI`>r^ zgfoeFRt{64I5Z_{dA{QeGtVu1F-Q$uN41291x0o_pk|Zo7||w)LGEMOyWw;y%MiU) zh+wwtTsD$JrTplZ54dqpm(cW`!cn)-QTWP&h`=k)Rorx2M?0_g@oe=IFOS!?a+eV& z1&xhY0wBtivfcGa-za$6sVz^{(%17_Rtd>T;3ps9LX#mHR1M(vRNbseZjpzqo6O73ia z@4mV!V3z=n7e)9fg{)KXx%#OX$|7ndRDIva!DadoTN)0q)jDM~jP&)d#NU51DkLq+ z2tV3QwoLzZ+$?SEDHY_PrQ3&SKi6Oq|89>i9Dq?UugM;LcAdIT*|riTnBD^SyUuHL zU1>60aqhXWdYWkeMUG$#t&`k+q$rA^L5+GFR=ysuH71Cqr>Z(?Ex6x&eCNGWDWiKH zdn;hFJ|8&mTWmbv=mvZXTCg0+8q4hHj>~F4Y}PQp{p4;(zUK_%?=%e8?lUF6q71($ zV|)g3lr!N-r6-qio>>r3h~618{{2RHupGo)z`f%XEG%qpz+7j21P@sHB}Hlw*DLUt z`ZhzWW^3Bx=Di6AQVjLG0(qe*q$^x+q_bH^QNdba?IYAFS~=DF5Tt>3yU# zH-)*aa0XSE9ttVs@47E9Y&n%cx!U3Meh~ynAxg&mVoS;&=F){)C>;R%XOd6;!6UTi z6adfczoW0PW#+xu8r{K01GDbD2{J|HwoLKAF;QIABfZI9hXFy=e2IMR+T*Lq^cNcIw@*r?J9rehZd34OP}?%H zS7-Skq5VR`K|LNdpoUi|HtOMDp8tG!omKb6`(Tb<m1nfPh4?d{}E^qjy$VCHn1d zT18<2K-Tx~yz0Klw@Kd1@5^FlJ-#PAvi4IenAb$qV;xEFdOfCSX=ZQERq6ys zcxq2Cz~?Qcw@<@esb&}c?p=yH+^u}O z6mS4kRINr>oo`IUBKk|_)u{eb%inpu{hsTx*zj9N`;?*?t*qXYN=mDFv$|>T290#n zptp0d(Zsa2phVmCGI9Y?k)RkI_riXpUlc{0?kU#5OK`tpz*!C^jR2f4W{uoUVF{3l}f`z$f0!ZI@-dg~TD zqf2yb29rA_{d0HrR^@optS*tmDBERe>df7}v5lReCF6Nvy8Ufy>DpljzhjIi4VjvhhMC^z;E4y0!a8{atAiB`M$i|eg-6c>4Fd5TSq!#28n;=yUr9$-T3#j=RvY zg<_GR^5M+DC{_5%&r)+|xtFQR-&*#mixy#TPJ|e6O5n|b@#NE4Z@P0wNtRk@+Cz5L zD}|NG@tX|=rFe2bc;{E-`VORPY}`s&>ydJ!vNhG%pVYN2{jrGwJb1G|efHO{MG_#- z&;>$kYtnx0{OnONl;Jd$e4LQh6coGZ;?A^h-fK5(Hw%tBovdwOyL}{nTZ8_*ueMGT zrZU7Kn1Rknxli38OnM{mIa`4wtJEo>)8|z?nW>tU0%Ho?z5SRhK3g#g!%%j#Rw1xA z;*Iy1eT4z7g2jnLW$ddUe$p6&kD0JHe~yQSU^|IhrVdBy!=7W;mbU#THx5U$V!#$o z<(SUTS43?mo%s0*_Vvx>Qn&ROvTIl_!wvyiIY6LZR#h-!HJl+{8D07!&o#+wSGn(9 z>xoRm-oza{RJ{E$AiMsCH(w^d!!efp(nkUIe;WJBu&BDX-=QQ0=>`Sq4(Sr5ySr0z z$e}|@8l<~x=q?FCKte#eVF>9|y3WSuf6n{7=X%d|o&AL`%*@_vuXW$|FV?->otWAC zpO$5U(TbeJoSIreOwZSt5Mj$t&a?+IO=Z8uh8+%1zkc6lGw>rGsr{k;d{ICvbYj7h z4}iQ`<+~}PE)d%RHvD4?OK=^`*M|NXT0oO#dzMjJeEGIIqf8V-x9#te;mE(i1_0gO z=^r_~SA;_E0}d-KVu_)NQSo8A-z>CdEN(k+-qIIdLhS@*g!eD#(g^%|g%$6SP!Qa%iJ?BCIWOBs%glil z&tw~u$Bt`K`?N^p8O!Q)i2R1L9ZbFi*dUh!`IAA2fi&0C7J`C&Bb?@sWswt9MwjM` zwbf`}-l_jtVSs1;NNv$eC~ZS1)y0B+`$tpu;tXdH|MBO_+0o@CehBidwtwvQ#_4FX znQ-PtCe$KSbyj&*>+`j+mc=lC(#TDauu&b1C=@7d_nZnne0UE9xd2<^LS{s=Fb-v= zrvd;;8Iazj!6$Mpw*Vm#xJf^7B5^meB5&+pXjwQ1j8(EQ{08=Zk3}deT~BuQ{D-qG zhrH`gOf`g_3>IQ=!`)@ta9IqvohUJC_V(+AO z#65n2*I_5x;2INBOC2ESmdQLagzPnw6TvO(sdgD41Z;cON<@!-9j*f-{IQ(YT$Td0MV%|+`oh{&Y!O|ABu5=<-+uGYFlRb*gxTMLY_}1i* zYi7Th5!KIfkPy{|-Q6Bzoz68vicD|I@D?{*+6PsVwDyLOx}0Z)a~=pVZ?jsOd0}@s zleN3}I+q8%X9pchIQxGlI#=Q5tc*;w!F3f_Qs*9tA#PjF#NQBJTA_zUu&WrGDuFiJ zaxen)Ei3?5^7RT0FWY)PE^yYqZRUJA1zjcFYL5Zm+;Pf$_#FpUhae^+ zWC(2N;qFuuy?N|R4L6vtyN}c5AD=psxiACGhu|`i$WXpOdwM;% zkM3V9O-+4r%?29w3`f|Rx=MS@S>~neNA72WpVFW zDKMx;F$+STQcBiR)z4;lNpSH;Wx66qGb}7{IdGEtttVsBqLNQuSHRU+b~mF6iAD=G zPGX8$D;qAM!%wteZi*d+ucu*saxzK|DR9nd>{-tMd@iS^#qDYb2d!v`UgKNg z!cKk0&<4Ld+Ko#pivzo3GfO_^gWZ85djY5!I^>l+Tu*#%;g>=Gv1KbVMrBL%1GEN& z=Js*pABk#ahLIG9sIhQe;fPzdyGsDo+Lc?Qp7dDBmf~3KVnll{F6XLr>hXe4Ie6a9 zqHYR!9x28}*WkrLymi>9yfHEkj34f(GJ~qzm(@x64#V3^op*P%ma3;4zdJ@Oi0N)l zH#a>|ISI^E{c?$%A;Gc8Gyw>n+)R4he)lue^L;DL1!K6vzBO)A;OC=-{9&v26&;u6>vH=S8V|pO-D48U1WK%@%LK|lp z$wAw+$};sc#|ZXm-J}fIQ<;@lsz_jss3{k~wMQ#=VP`B0d!_J_3#%Hz^+`BT| zI@Eb^YvxdYM1{Ha4IvwA^_DD;fnejSkKJKvw26`f^-31R_FVNC>hC82}-A6Lcm!wXgphK zGwq_@`c81}r^DIb$B{{r`}1z?v{ zqu*DRjjK29bXI{$WRZGauOWm;F~n&`&r@9dL6JHa!)L`U(lse4xYG?GrFwfEyV{s` zpfR04sjmIH2hPpn46AFOSXv?D*~-q^+6r78pS-e#U@opl+SOIWA+*8qACB;(*~U!1 z303MGtJ@_$SD$Cj?VU;oDqpb({Xk(SrW#XBYk;a4f;;{bqI-Wn7}BKr~is^2|9eL z4b1s!Ot0nADsde$hLrM2l?(=Ef(r~)i6DZMm|_B$Pn|L2uM^W{Q*8cgHbJprPNS$SR%qEI1U`CqQh;{QND``jp3F6T+%>mQQ zR^zt2$>a3114`-d%#9j`Xltt(io7 z``W?h%hS19TXo&XUaBSmpdA!rZ)Ol@@mdIQ&Z)<1oJ8Aa^@bYdMLzqFhCCPeD}TKNB!Was9jTSfS(;^6WD9BCK;Lh%lu51k zz~I+Kz2VD&F0il|{p{=((L9>A5)WY0r_BKhaG?5=zhz3RRHBz^gwR6Kpmhlb5e})S zQ;K9?AXdE!*aiN~Hf26?&8AP!G1i_z5AUr^S^1=KT z#efGC>ewxvtn^)EBVKu>JpAHX25FgTRSWVawKZ0$fO|wg7xk(;oWte8)$`|Zy4QYd zdCWVcA-h0>aR1sCVaj3_Mb}qXxXNTqCaOG04!$9Je*}W%$Y6=r7H7e$=Xm+=*{@!L zb5ZK;WrwHA>?W}t=+r)i333IJO9zi2wlq6LR9v)vt4LM?=GeFGjoAP;1jk6#Md6P| z7Qb&BWGdfZ?$OfqznZ_e|E_co+&+9eh-2+>2Os3de|LSs={Yw0F`6R?=dbod43sJf z26P;)!(I4Q6<9-et}|9>VIjf{PXfPeRM?A)-$J8p_UU&k$LTk}Vax6^od(2 z(b)qAtvp#y>oKsP?$@&$EejvcAYHZ#>F+zRKy;viEj{#dJFV%8fwEqNZdxrqmeqD1 zOL4b^m?(S~S*kUD@;Q;y>(&{pf>8Kqoq{lpv&7pA8t96H{Ff}dxoEvZ3Km|;dazes<8DYdwXog- zzO6SOn8)y5pnI!se$-s<)NVzf*D4*oD9gBA3K7Lcp=YKEE9S>++&j-#FFz}~an?D4 z2oIJzOvEos2tA8p-L;&kw))=gH>-})qav&oETBQ*V$i7%P$E|bYE^)rNh*X`ETkLn zWk4N#9tWi^`VCD^Z#D&B+}K44Yo*e!9AfS6$R1Dv%nIdCk70POx-3Yrfv;jYoivO9 z*n%Q&KES!+)p)P(#v+LUn!c^okf7g;ZIn!u$t7kMiWP>X<=Qv5A2NW@m_2&)G_&ZE z)QcF0E;X(?(RdF!GRvJ!)_(5Mk`tq|8-(z~TZqY<5RVh>tasWSh*CV&40?gTff{r8 z*y|bf&m`**lxmNlXKXU;f(Wh;4Jl1ax zWVoX>_me6VHDoS*F+M0;nX{2^s}EP!Ik4BxM2Y0d&DP@>K-(P2KTnj5vH4lzrYr`; z6>c?MJ%kQW z3i>vpuD5_Tns2r~zF%WUu&_Mt@(k{e=SZI8&fQh}1XMPF&qyVSDZoX=@LkK-LsLK2 zWo8aaz@YM5qm(fAe!qBd-)~m!6Ht;P15i)a=PoBZXAI}@=&=?=Kl5V}y?9vEmt`(h z2;1goki=C6eb{W$@Nbz)+-XNteg39k;d&=clZ1BW1DS%qhKq5;C~VkN8|R11_ToG= zwi#bAzkzW~58|2|K1FvyZKwW2VmJvS;r>z8Fq-iX=~#wqFbpttRY#n-XpB~|r6Au| z(NVsB*3wR@O&;k~>>Ie;_78HT%cKUQobbH(Q9R=lk~V_Sl(;E>^~p(pGV(cYqixI9%VzjWq)I}tYTRV`DbKu_?E@y6G_T~TIq z3f_k3HtHu@3emnV9?ZF~8n83?j|ajRKKC66*@MtR!}M8=JK@6N{a|Wk#w?UesA%xe z^wwOrM6-GC6^BKm8;o<;*hJ~sU#Amt7fy?MBIPf&$MbJULrCBJFAz1uCrW$B88X~; zG{h^H7?gi~;}co!JkSE5XItVbs=TWKz-$m8AJNXU+-Rqn z4+e9gn!tt#OJi7nwEkzMdiL`Mg6=$ci>B@>F+uPxxWo*zaYyO>RXWPoHcn4&Hw~*; zK+Rtu{<;C>s~X<6w>jCQvE=psi%o;lu3zT-wH+ofeCy3h>&ATDqYb~L$19WL`lSXbq@Zk~3P69K z`aDWpCuV%dbLma$ESb$uS!@SfSUv!l6pW@HebHk7zY74Rtgg4j6 z6FlUN7U)uZm>WVwY!tZIG0!3bqv`#3$w7yWAE##&<~G~G>i(ciV$>m%MO~i1ObUMN zMr9vV1{vMkN4ZrS%f%o)z(FfDevGixSC=po6%jA_^S3`gV4A|%7N{qY(tx3)Ed4&Q zh3UrI*zYyH){TJ@53p+WvG>$HN8GNR^O{2cuLSDUQn@Gp3$S;2Bt@RH55SnH^ijSr z4OL2TR6U+!c+MU#psD<=h$E>ojkIVl0k`a_)VVCn1msE{gO*BO9#KpRj;5P7ahnCi zdCg2VO&T}`_(=NfSr?(AlKgC{{hb7H8Ll-o19a00Z7vm`kONPtGPA0e6THfSlwS*) z)JUaPe)bJ787?}I^=M!ClaA>^&lXgu?lK`$P1*<%s(WsyafDR$32}?IYk!ajkiU|X zc(@Ezv7`L*yTuHo35bs*Sb&g*bvVg7P4<9Ly$#v)BbBM<<17;Kp?3$KA|(X>ES zXw3|F>rI?G`w;t(*FZ!mNQ`BHam{c}|KSk>abpv~*-3gaQ)E)s4PhrRr1SFpJ-8B0~!EgpwO#s?43~8x*@| z=`Tpk`h*VMPmmLzJMbFGTfV;a!FBj~{Br7LCN@LD(~}VVwVL*3!6)Fe0(MgIF598R z_q<(`%8V~);V9{aWN|7tj@+=fONJZa089hF zQ^kmu7kDp&egLrcCdZpLMu?WCn9PF8? zB$?@%U2~JzRdt%Bq1nKkQn1;pCe_r*LT`M0r;9McTJdJFFtohyct=cA zmeCq2_mw@w`I*XEtYfzZv8#+JJ8xqKdSlpig+^12Se0%K)Y@p^1BmIlaN)+fF|+JF1rGKIBA?Fym2z%n}7Ys3?+nR*zqE%AmL3teLZ#KirF+_-^T3 zbdPXDxH#UANj#bF^f`ewE$q9`g_`=z zF0v-g3xHgpFLc!wdzG6}4a!0KFNFC(kg7Ay)L43JpC8lvH7kp(9dK8{APRmm7dCD)z(goiF84D^JQnEL{XJ~10yJj- z7s2a8G1b=mUwkgXI{D-iI`v~15+>#0sDAQzK@`f=)e1(_&C*`?V5~6%o2%d8Q}h%# z9n*Q{kL%vzQ=xlLFfCO`t%LDTER0#ez9q_9pN`AQ2yA}ld{QnVKX6=@QJ@9fm+kKu z!aRof0#CC6t{SI?di?np>1vQQ;7a*@*d8>f_{8KazC|87kZ$G1Y|wAfct_vm-ac3E zUi>9tkVN6BbRJfJvtKd|Gckrp@mIcRgMxzf8sK4uiPe92-Bs4bcm4%BeR3298ssli z95g}xMC~7SLY!g#I`zq4*p?!|A}5E^%2ns>#p;0a^M5er^kLvxgaC6-L9NL5jgST3 zT4kNN1Y(WKwj5-w2vsE4vJ<^v+x@@x^5jS_-E+_*F6z+OUDW_y)04)+y>df`4I;-n zcrOa4oSR{V<|HqjVE7MnhL))f7?hqKO5!p2#OpPEJ(o@n!;>i}?}=O(AUG0Fg%AE) z=BH15_%~atr`J@1kBEs+UytNY^8oYp7E$6dc=FydOSG`6(ypGhXS<@a{1oonc)Ruz zdlZ<=MSio~K#Mbho3!7p8Lu14j8YPf zUl(S=DzL^>JBm{t+UP|q(9eSOJ0~fDJvlt~rk<;1+)R3|Mp7QC!AYdN;63Bwg}WLz zME#dNcE)%^&cTvn8&y6TegglZc`tt7g#*hth_bOrHD7S!A9R|+*7@JbUY7>c7SUC` zqO^zUCj&V$mcY;s7A2k}BN@vH_fQxlL)c_;g(lO)Y@~3&;)m{8b}v8tDm%U%g3xv2!eNd7|e)M=v z|9Dz&m{6on^CcLf(*Moh3b&^#&^Isx@uB#%mayw%9UP3-twlnp3N*Uh5)U-QSvDI{ z1}uVG;wo8mV6Kzy{^$|%(y`ON%C>!ACrBkmN=o8;aHAxQ%~km)(BJBdB?~$1gl}9! zwI{qelQ|=-EmowGb`%jFO>VIMLs@zL4RuJl$`JL|ne^BO;GbnU0SX0<3^r8&Kzy5d zrik&MB+jha(~7Q`e4bXphW|t&Zv=hSM3IMsr)PRW^1JmsjW`pmeoXyf*w{E`BH{5; zmDb9twBn-%5DXSJ(qhgO);tmi0{3|x*5PhBF#&QGA?%iXM-xjcN@O-qcN-Wv$$DFq=|M>O8 z9bgqe+rgrhv2&Y2_vrsX^bdCVtv}i#`4VxlJVb=H|H0OFckSE{d#xS>%a(I4mVn%v zQrm+83gaFrP%Zr6!w3 z&}flQv?tP|xQe#{Rn<#R`s^ z;z1sAd5u?U`JQhSmD%iI~7gc<{OutV>H$a=`aK)KRL_**Tmp>#oSo^mRl8TpM0m*jfTdMkYwP;gBX zmlw%gGBU0o7!qzD!$;y1%%q%3vqp!jw`#|N4YJ|ML>{&TLzMwt%PU8AUu(-$c*MrRqQVqA}*>~bo z%5BLhX@B7mn`mJaU}Oz+K6G$(3P(%9eXOX&;=8MJkEocRY5R+qd;I`@COJ@bl9p_m z@M`B{lPE=v=2}Esu25oLUDP1jlR#b{@=iho!=DyDhsH1K{J${)g(E=duub9oBc}A0 ztWB7&u~S}GRXd#nuwV0+K0s6seSYF|9ZQ_Ab;)Q^#Y zkjtngL22$(gkvN`gs@CeuyW<$p6K?pDmGF4=WWa2HlvZqJr4~=^;C(w;l)KU?i9VS zv;zQ$nTN-+T*#d6csd`~wnlY5Ij70Vg9EGKb2P2plPDcn3NfY530`76p__I2>2%qD zNZ-qOU0x)bP@o6;SAYo2ZrzI-R187|fb24?!B>@2A{49)Ea!~V{2OeCX$>eD6+(_J1#rYrnoSpLy0^hd z4mug)7qq2)H1y9|s8FZ`DK@5?kmZzOLRU%ojI#O|PK#RiA)VN5+&0HU(}y}n12+sw zpqxQ-yN_1LKM6Y&E-o&RkOyRpSc)HPFERl=gl7KyUrfG)kg~5rNZ5(>(ydJP_hk0z z&88AOL@gIL#SC>JAVa$g;7p57mo8Q zWJf?VN8;XNanEVnX=wHNvO1Ub;R2ig6r`=(xLCZVpDn56Q#%0?`CC}2X5Ps03S$*`Zok=4CvHGxoXUuur)Bapsk>L7)@~8f7zfLwd}}?$gtw}(=bA~rk-Q0!Pg@_ zbZbB?CKpcMa4LHr&vL$`l&che~mo}|U`sNYl+*_u)l*_6#|ndhSTF2jeQ{(hB6} z07@Wi1ZxgA!=bc$4(!%NT9vgxkNfLHUo#D%M70|LJywJ0kK5X7GFA4#Nz89Mc%IqVM;G3!$44%!l)vl>Ljap;ll|5wDRa){jC(XJK9e~)YyDGjyDx7DUls^k86iq;!RPd;kjjzvRtsx~i zi?|DGiTypqFFF~VZAR~(bRW3L?;$5nVZ$7d}ME| z?EOoYo4gXn6i19dFn;~5vbH(Zx`cRV*14ibm4rw6CyNMuGM3!^c|*N2;qkfEbZ#>e zTuyTwDTnUhvSxcP;WL4Q{ppx$JcD;4#)B(WY4!^6R(w2PhgR_2>7jG))BCKNt}>~m zTDVbK=z}9!%sKjRr7zIPd#__h5Xbo+M|qy}SI10e__*gMal~M4q=TA5Uom|Q=+I$P zLOj{wUA#_Q@F;r*jG**ooPT%pB8pB7_UA7rL!OvFh>#8UY@4w(xcVEa-WuT(-H)OQ z$I%A(S}u7W4gZ-j;i2dWjr3qBt~_J=a0Y_HPgI#SbkXav@ENB7}t?|kyUD;xjzWqc=X z)%?F-N+IgT$9s&$HE1XTxrEFKPe)gIoW6R5J6SPP;>-J5@O9T!V%b~0Fs;(BPw##^ zGbf;rC{hhIcl9NI+KnDxH6xrl`Kiex$7uc^GneG?9tx$n>w;Uv(KS!5YwaRC|ACJo8VXT_VPUuR6AErenmG@|n{j^6AY&`oi@SJ5*8+?>D{c z^Xp2uJB=7~%Gcg!-{ARnM%5hd4#fl?_4nAwmV5n@1W5xt|2B^B%)E>ug*4GeF2#xpN^=+JAEZ8=Jkdc8B1HR zCQ9$Tyg~YKFae~CF@lJ>7G+Kwa1ni)P5__Uc@=lrQ+pd&c~9;xF`N6?M9kJxYk0u+ zqiQ_=HPto!yxMkKn6DGjSy^|>N&;{Dt1{9D^Qtgmsc49nnaoLplIX^E7>6OXPN#S# z$V`stY+hIA6;!`1?9OP}^AXR5o`&tyy9eh3kP-BKK^w44F!frNquD;+E$MOeFYglX z)Kn+ldL-zaN3o%p9K;?M{<%=OU@Ol+;Ow9@D1^(?;vPqk zGs~=MVV%p&@ptmqOR&SV@Nl2pwC>RuGYasCCf%V;4 zF6;y#bZM+00S7W^5Zq{#I#ZpWUDS~-i7Gbb*;tyB%0Yjjz z6pP&Mmq7E3H&~K=+{9mb*Q~gW*)T&Ie0yVS2PujrEV`=cigJ+%_xJmr`39I+(mFvy zak5|BV9a~_HDg+Pd>{N9=9L8SPT>2oI37A5Z44Q=tEbA&?r5SY&`2rZ0{C%34h?)u zI)^6qR3UpLe{P=%97d`PyxM98!nS}XtJO2Grg0{Aj}DO)N#@({t(aD%nGSGcIf6l? zwiaijRj<0}*t3spn=4fYsHmoa4-Nbp+vpi@{l2z7u5AZw&LtUKSrmOm4fkh8&+h4E zW!f46VJSh-R)%HCWN`Oc3ujPgSCG)@5_t4X-0rf`s9 zUd?Q#Qco+MbqV(?hAE6s(!%>w*juKz+F5=4BM0Hr8~e7$1hkhRJNY@H z*FWd3=EOz@zLwX&6mJ}r0h+F&a8&E-`EC|Ywi(_Q+2)Ys3`Viv%UvV7AQbdvY1^zY zf-Uu&-=HzCsRz7JtczQ|&uXeQg_A7=e*2OH{C3JIk@5A*+$uuZ`A*9p>F5QR`77$s zWwx+!Q$+lV$pVJ~i9&9Jv77l{gDawCh~tiM$5c}Ar4}D4|5VkyTkc)i2K(CJ&v5gC z!|aci_{Kl14!V6=Sy_ob^0VJso#)m*iLvz_VDwvklk~=RX2-B=aLWishpHY76aO`q zL+M8J#(sM=D=J!|J$Lqorm1?aYxnR_c;`spd5|Uvr7SNxDvEu7hYizjgZd(})GU4h z5Ap3ju~p_*U~?R?8@+_V)Hk zezwm|Ry%#8Vr<^G0Kq;1xZAOhNa*>P1;vN+^(9qoIBtHCyqugkZYZkAzedsujVgylI^IU zC0*0uJ${_CwUpAzI9H)lpI()niAm#)h-M%m{r>M&DAqB2*mWalUohaYgx-E^hh*92 zw4E1lc>1cVc!DE>o0G=-KmSPuzs<=Nk>=5fq>bXkB(kYQY2!Pai55aTG0q(&_s>5u z_Q2}&_v_mdKs6h^E&YK8M|VVXmQt8b^A z@G&DBl`0#f!I(zAh&nmbR<5~H7O)}E445%=cf%Dg)pe$tvjiaof7%XySNvwBqEcgM zh{nb)liKwzk~JhOr%2K*GLQZA={t8J+iQuvkfDlCpQJa`>Pp@gv8_A1O^#mbcfK;d zZn8L{o9#qXVe1{uPdr{ya95-gJnlQ-b@66cbpFYoqMJ~Tp`^LGwIDM6P`to152;BN z&^vc_p|?u=aSj3QaRP(Z*64Q!&+LY?f!cPYid#jZEH3wK>w!b~eAiS_vz2Jhwf@D0 zc=MK*y(LC#jGi^dXQQeymRq51;D?TQZy)>Yvcc@xAP{_~%=@?MOuvYzR2Z5tl+M$g zXG)+cG%3z0^ScLnTN3YWbY9K&Cm1{?Z?v>IB-58!DIrL&9+WWEiZhmoGewpergU_q z%1YyFevrLin%F{c<|W$VqwGs2j4$0{N=WcEis<;6?ZB*NpRv~nO(B)*NYufO_hQ${ z(mnE(Y^3~PxHms(Ec@d@G5KY>qNN_myH3tHPnUQv=_gMl)UBw00n9PBiG%QL}S zPlIaNdgZ#3(WLU8q2^fq<>y7$cnce1&r7E=WT%|A_VTDdM=n@k$M2>U5nV?fVW9;s}y}?kKTQ~S$=+7VD@*P-6VgCmvWT=>+His zEc$#hQ?hD|3Wl%LzFOPv4JmK1qU!@)|2 z;NFY(Bol!M$bar5x`99Wn0Zxi{u6c7XJNfz)18E+#EW=?3WM1s+ya1ruwy-CG9|Y_2&?bOKT7wa_JVybkCxkrqDDQY;HJtg?JxIRfe5;{(BI8U7YaOc7XSbN literal 0 HcmV?d00001 diff --git a/doc/html/_me_compass_8h.html b/doc/html/_me_compass_8h.html new file mode 100644 index 00000000..9f855dae --- /dev/null +++ b/doc/html/_me_compass_8h.html @@ -0,0 +1,363 @@ + + + + + + + +MakeBlock Drive Updated: src/MeCompass.h File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeCompass.h File Reference
+
+
+ +

Header for MeCompass.cpp module. +More...

+
#include <stdint.h>
+#include <stdbool.h>
+#include <Arduino.h>
+#include "MeConfig.h"
+#include "MePort.h"
+
+Include dependency graph for MeCompass.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + + + +

+Classes

struct  Compass_Calibration_Parameter
 
class  MeCompass
 Driver for MeCompass module. More...
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Macros

+#define I2C_ERROR   (-1)
 
+#define COMPASS_DEFAULT_ADDRESS   (0x1E)
 
+#define COMPASS_RA_CONFIG_A   (0x00)
 
+#define COMPASS_RA_CONFIG_B   (0x01)
 
+#define COMPASS_RA_MODE   (0x02)
 
+#define COMPASS_RA_DATAX_H   (0x03)
 
+#define COMPASS_RA_DATAX_L   (0x04)
 
+#define COMPASS_RA_DATAZ_H   (0x05)
 
+#define COMPASS_RA_DATAZ_L   (0x06)
 
+#define COMPASS_RA_DATAY_H   (0x07)
 
+#define COMPASS_RA_DATAY_L   (0x08)
 
+#define COMPASS_RA_STATUS   (0x09)
 
+#define COMPASS_RA_ID_A   (0x0A)
 
+#define COMPASS_RA_ID_B   (0x0B)
 
+#define COMPASS_RA_ID_C   (0x0C)
 
+#define COMPASS_AVERAGING_1   (0x00)
 
+#define COMPASS_AVERAGING_2   (0x20)
 
+#define COMPASS_AVERAGING_4   (0x40)
 
+#define COMPASS_AVERAGING_8   (0x60)
 
+#define COMPASS_RATE_0P75   (0x00)
 
+#define COMPASS_RATE_1P5   (0x40)
 
+#define COMPASS_RATE_3   (0x08)
 
+#define COMPASS_RATE_7P5   (0x0C)
 
+#define COMPASS_RATE_15   (0x10)
 
+#define COMPASS_RATE_30   (0x14)
 
+#define COMPASS_RATE_75   (0x18)
 
+#define COMPASS_BIAS_NORMAL   (0x00)
 
+#define COMPASS_BIAS_POSITIVE   (0x01)
 
+#define COMPASS_BIAS_NEGATIVE   (0x02)
 
+#define COMPASS_GAIN_1370   (0x00)
 
+#define COMPASS_GAIN_1090   (0x20)
 
+#define COMPASS_GAIN_820   (0x40)
 
+#define COMPASS_GAIN_660   (0x60)
 
+#define COMPASS_GAIN_440   (0x80)
 
+#define COMPASS_GAIN_390   (0xA0)
 
+#define COMPASS_GAIN_330   (0xC0)
 
+#define COMPASS_GAIN_220   (0xE0)
 
+#define COMPASS_MODE_CONTINUOUS   (0x00)
 
+#define COMPASS_MODE_SINGLE   (0x01)
 
+#define COMPASS_MODE_IDLE   (0x02)
 
+#define COMPASS_PI   3.14159265F
 
+#define START_ADDRESS_OF_EEPROM_BUFFER   (int16_t)(0x00)
 
+

Detailed Description

+

Header for MeCompass.cpp module.

+
Author
MakeBlock
+
Version
V1.0.1
+
Date
2015/09/08
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for MeCompass module, It supports MeCompass V1.0 device provided by MakeBlock.
+
Method List:
+
    +
  1. void MeCompass::setpin(uint8_t keyPin, uint8_t ledPin)
  2. +
  3. void MeCompass::begin(void)
  4. +
  5. bool MeCompass::testConnection(void)
  6. +
  7. double MeCompass::getAngle(void)
  8. +
  9. int16_t MeCompass::getHeadingX(void)
  10. +
  11. int16_t MeCompass::getHeadingY(void)
  12. +
  13. int16_t MeCompass::getHeadingZ(void)
  14. +
  15. int16_t MeCompass::getHeading(int16_t *x, int16_t *y, int16_t *z)
  16. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Lawrence         2015/09/03           1.0.0       Rebuild the old lib.
+Lawrence         2015/09/08           1.0.1       Added some comments and macros.
+
+
+
+ + + + diff --git a/doc/html/_me_compass_8h.js b/doc/html/_me_compass_8h.js new file mode 100644 index 00000000..d787ee7f --- /dev/null +++ b/doc/html/_me_compass_8h.js @@ -0,0 +1,5 @@ +var _me_compass_8h = +[ + [ "Compass_Calibration_Parameter", "struct_compass___calibration___parameter.html", null ], + [ "MeCompass", "class_me_compass.html", "class_me_compass" ] +]; \ No newline at end of file diff --git a/doc/html/_me_compass_8h__dep__incl.map b/doc/html/_me_compass_8h__dep__incl.map new file mode 100644 index 00000000..33b2bed2 --- /dev/null +++ b/doc/html/_me_compass_8h__dep__incl.map @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_compass_8h__dep__incl.md5 b/doc/html/_me_compass_8h__dep__incl.md5 new file mode 100644 index 00000000..717b85bd --- /dev/null +++ b/doc/html/_me_compass_8h__dep__incl.md5 @@ -0,0 +1 @@ +eeadea467490bf69bccce9fc9bf93ff4 \ No newline at end of file diff --git a/doc/html/_me_compass_8h__dep__incl.png b/doc/html/_me_compass_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..d2beb2e84fb0518c446ee18a9d1cf4c23e475230 GIT binary patch literal 13542 zcma*OWmFtn&@PNaa0@Pn06~Hi+!9;@1b5fq?ivV$;1FDf;1*ni4G`SjbpnG9?sl7; z^S*z+wZ40swSYCfr@MMr?RuW4YInp(B^fMqGITgNI4n6?NmV#FBsbuHCo~k`ci<#L zE$|1$R6#}(?&!Uv4(=Z~Im!3xUYUn0zJ8hRSyxYU&~ysj98_Ff#xGPk?-0-l zaf(?YDH4)H2Jtmh+#Bgcir=)Xt~UA}9eM6Q?wM%?uC7-2?yr`OCxCs#33_^xdEx7_ zk?r^4@pm{`kxRdhBN|VcSByRM@l1V~N;6Lw{*#{83W}AX8XxAFyU0p&tVr`VT04Sb zy!yW%TLYU8L0`Xq{a*3%jix?T*v3KA63vNDn~%HivOO*yUc8w`&k7tK9v+i{2}!{G zutP)(CH@;^LEy^tvcWOHH!*Fuhtq~ZVq!4Mek9+M9^&1@!{`=LU_gQdt|y}8e}}mn z;SMnR@9~}V?*;x^XCeLfD$k$Grm5u6{%5kP<^N~6>ZE45w)1qL%%a2FJH;pUQuzQo zV02;@0_C%PE{|2Fx!sC{kNyWHZDaL`{KNp#shI0?M3Y=_U#w`2(|;(eP{n`wCcxZ zgcQ3cs!vO%^(L)XV??rBXQ`+D2VeX~!&)l;j#F&L2PQ6ekhhHqWbgU~Cymx{6P>a5 zHubb^%(`L3N<9%6rcM<-4wxPPnN0A3sp8!a3Y*P8HV~&VlM>+$z;^uq?&j2!D$SG4 z`^PMIDb0RQy>KJDTh%K-N>Y-}Fx`b77>LZ19nX2AR4}MXA+W}~#hjyG{*ev@HEa4j zYPJA+zLDtv+-T%`j;SIw*{2Rjn}50e0FOKK(n&AZmVBN&FdwgRB3s~}Cyfr)a8AP} zQX6Je**b{QTN7z9l+F`&uDHnSU4oEKpM(W`TnqyIJw~xk>)o_B}0GNsI}Ne@J4qS76BmyH|(b zs>M0Evm`sJfoI3H$R^aCRRYY>u;F*Q{=R+Dxr`n@nN?5oAe@%IqQ3LdYyjm++9}l{ z_)H~y&KSwdu&m(HY zMR&x^E-Nt^BCe=O2^TU{C=!F8roNHtbxVs{Yx`E6701Al?Pg~C%6Ol~YU#TpTSsF< z!(}ogMyP^AIp}+Ia4@`Kz>S6GPhEHQSZ|{gkPl-%8@vKqQ%@GeE_LjCef@_st>RHM zCTKG^JITSF>p#pnACe!b1cgdWp*k!c`i( zKK0>^leJ$BKeH3ehtGa@Vxlr>i%qW@`fYIQST^YKemX~{aNo2IZ)QE5&Oh$cZWFU5J2-J!z;}&lGPj8 zCPj{HT0d3VdV6hS_;^Si=^phK^mNIc=CSueU6GPSR$ruG@C7Egw3GlzL&b<2BWAI} z#wNPs{yuoU@9B2F3RPfZn#lwr_B5D@OhVkmO)XpGE9Z)BHhpXSkLz1ABij%xz0i`9 z72CqB-)XxYY13dqJE*!)CDMo2!7nqit{Yl|jfx2^Pt97F zMY>Z2B`XC^XM)0Ch-wVSZ9LdM{O;CR##lxw@sY#T-h1i9V9X&boW21r(j`B5qTJ;l z*?(|}Vkc`2sIzyoGFy7(+iiW6@~NNj_m4bZF2qT*$JNQ;vB!sVw`ChCoQ3BUn(%j( zVA4)k3ZSOOSKq|%(qQ|Jc(XkqyX1sXUKv{4nR?@bC*1=I>6`dJxDdQIq;6l0Lw)Ek$2PYJc@XlSj2QUWMbzyJryi?7{p-OAhhvk#vVRowXD-7WQdQ1H%*NE;O z@IZ;8he@W$@Ha`he>SSJnMLP4q7Nw)gpx%!D=*-)Y3HUh^03wqu(L8?I(8yv0;{qP zN9PKN*GS`Nm~a}~e)lk`h8mK-p*p`jEr!4`ho~uM6jil_$F{|5kSFi_Sr7mAq*6!M zh8{TL4_-slnVlYOtqi#-%fdQ$NVnf|W(OzjdFQTo^MUKN^Sa$>km3s~NU8LaP`X)6 zA7`HLWPNF-x8-y*H&6Yi(Fu`)(?+&eueiQH`>%vVf%p3RKLex%svU*nzzo?01|!R9 zf2|$|^1l8DbxCiy`EL{UG$K@0Odn2nL?REbSoi%=ds}H*TyuAo+eoPG?CVBP8XP|r zJuPQ_(T08O!@?17UnQ<8CoxJ$5j`O006(E2K6d4A z<$X3e6}XRbFXDDj7>+ypB5njFL&R9^$%Hp>SK8O3+@3TRuh7*(2{dd_?u}5W1Y}V2 zyk{60lpek1nK=K(9W=#%i!pB)0_Cb~5;`bIhsyhZ>q)>8<>vqW#gYYy2*DjJ^$yDk zcOLy5E@OGY?f9Pzml?EAu+zKYPn$bV8?j(90IS#f2=sZx{#a@EkGvyrlCr`3X(ndG zFNYwW8C%D@2<`Q0)lV+J5_ka#gd4#|Boa~n^Z*X5~q)<2yL7?d2($lCi>lnCWMPb%2p(zx#h>$(h$pY1xwRV>fPPrIk&&M+jyq48Z0 zX-C@-$`|;KdeAA`=sAn?-7k`5zmUNSUWAgHcJkoD8Lac)H++I`|DkeeAJC76$@2Ss zsNR;an^8Rgz@7!&4aiOAt(8N{ho0N~!op_ctsT}slaq)=pZbj%Y{A`yFZ zEDS%y@`ot*^B{K+m8;-`_Ml6lDK=N@dh3w zja4~@cY4sh%T^G_Fol-qyB*i3dVp$V?%DSn0dCk+agi&aJWZhnMaF^0>!F!B6;Ieiw@?vD|LVTX7+jdGp1Izs$m*%Ps2J(7z`74A&N{6p-(p8p!wU8MIs=8^?;Zi^ zqQgFKQ(<_hq;`96tir6MNi3bTW%+96Ll__za3)SiHns0Bi!x7`azZlW%@;V)^Kj4MfS$S0tX<2p2d^v}tYw zI~78>wj)VE%PpwZ%D!O)G5#Tj;n*D$+}>WloM4uwb!lq&IYGrVeIk=rFr{U7&qGU$ zg8~8Rksp|S5q^B0mKh{a&rMJWd8&|B9cv9W&Pqec3c*yNvjDu}_PxNw+fpFViZ{t` zP=Z;rR(E=#&YE>Ri(%rzF@+wLX#!cU;nT6dFpH6~*M$xDXp{@LvI2a#jHzhOmQ$@p z{lagEE_UY%c`<^mf+;Nz;2M1UW5(xIvW)vmZS4c?Z~(0)|M@vD4=kba*uB;;PTYNl z?slXLfx>8tn;O!0o+Oj5t!I&{ZKv7vzZY=IJ9qfm1|(?fTW)B?LgK72FEgC?SFkRf zI2RWtccI4j;Pvk&n!4zm4RwYx{`ymH$s#)#2^zu{&03_iJTGC~_K^oikuxy``wt>C zb!4r=cbrP(Oa~o26@W+8{%|S=`Bq*?wjDf>DgQABmEs%W_0Z`;9Sj~+>9KO%hVP5$0RV*ZK4;O_@qj8Bh-&`9 zjS4-0+Yas3hsa`OoTmiidc_p)I91BH+j)>5$n&=h)`yK)|7p5?^2voVM$|4vXS=m! z*mxa03pJPrv~26WSO(J3Fq-ovylo%Z=5Klp**h)lqQ!BI=FFZs;sCQ_F(8!fp z&nPLj2jnSD5=TzM{d>W1#A(&zS-+-q z->=g0Qnc>5N%fiyJc|rw_Qvvn9FcyT{)SRepo+8!&P>HNC7P)@0IWJ zH7^aNl}N9$g8QO!OdQlSx1c}vg?AT|U6c?BMWuN8;0!>iqK@!@#QgDj)(2(PTIN20 zMs;>ocrAzN&DnbO!<$ix3LD+MR&$7pQi2RUeGtu3gxXNCkKF_UyxBv~zcXbD=49_E zc=$vdnnGrMr^=#MLP81pX&x$!ic?dfY7-po#F>-bsnM+7 z2>2lMnTj%T(&|f%uzdAKgErfBZ$G7)FKH1k1@lwOEKh2!cTa!K;9yR^?Ts4WFQ)Gj zdGA@E?{B!c<+{?$r1v$^3oEOPt@g2LiQfpy-R<>jr?&9r zg@*Z6YFF-9?dHi4k(Ao#I02F)d;7Y|&iJ^?fc2j=`u@s!_A$*R$kpXj`w~s?Q0b^f zgh062Bs1z^Rla?fbsqB<-h=Mvt4`0bSCp8UM0=nE_d&tlhXk5tcO-XrHKoS1k@8iR z>AB9u)ftAwYXw(i<;O1yvhElAbM16cm12`^+mgPjTBd=QLZLubWNU67u)Ej0v#WeO zrApeY!YCo0S@Vb>lCZ7RF=$MAd@+lX&i#a)z9_xyg=?;TtKHp3xBYnwHF>TSA2x`mQnBQbl}L zyzJ_4iuBX%{RKC8AS=XWep2zwIzVsH9-|!}2O}=)G6m8O&0RYW*vukAn_VrIUM=B! zW_+Vjpe(YM;;|ap2y)+|@WaINCZWJfMQSj1)00)Uk%ublk{|Y@X6U;imn`K)62E#S zzyw4BX~B=7UVIm6uXC<7S5o1QZT&^xHFysjwA=MYOTe<- z|A4eBYbaO(dks;raM~r1zP#bP1>G2V&|IN|sLi4keGCPK((|Gdir}s_xaY`YtDhFm zFC=c6FjLX4!~klLOwS9mM*B1eq-pTdK;!&;C!Mi44K=fKU8Bbz%vM{x!yzeVB6~E% zK2-*OEhdqIru>q&Ewosvhf^Vx0rk44ZEndC;&3H7z{tCVG|d_DcUr|zuW63eYm$4C z1ovzPP(V5}eV&wszThPLxdm6}#!s)7+eekFgQVUizRx3l_;F^C6C&Eaa)~WO;z^D{ zuh8#G>ZH53ohP2nF_3q~(y-RIu-cR_V}=6nE+PFZ8{>nreR8eCn7Q6h70K5OK-H6r ziFILJ?I3ozOrC;ZaTswMf5tG_dSK5WUuFRpnGd^74Q1zH6YEm-1I`b-m4?xxIkHL& zggx8*}89ooI}W3J`WN4VHG6iy|pI&Aw*RkHKF{U6y|QysE%pZJy-kclg_t9 zGnVFVnBIf0f=kU4-Y}?ny*Sp2y|yhyY073?{sfmmrC7UPEPo7sW(LEGEKS34eTaKb zdl6lFB>1Q5-Dc0i(7A!n0dVmY{><=I+zravNZJwnne!-3sRh!6dZP#!JL+)T4zYnj zq9F@Th}k|A^!0-h;G}%hm!`1xFxOb+Gl>8cle$5|kPC-V1|QfJL^$5?l`zMzt0U-% z3rn0X<1Q}4+sEZx=q@QAj3FOV-go_}K$&6aHIEAdPixy6S`eZH)(Qj?t zDe$Eu=!4o{D3HVE!~G&O2k&r98(u%t>z_nn_otZH1AYQ}l_yT6aD4W+RJyp1Uwv-^ zngE#xtPeK^-N1(VAo}YRo|Xl?7!h6Bha^ih=zf?DS93LasxoljWVfEviG^+GW;Ya` zA)j|dfKIQ>mQWfAvsEV8B^~K!Y{-;D|bW@X16q+-wTl5#uvNRwtpBBZv=E7 ztHxwsF93<^b+c(rw7T3(>J5BVhhXvVTAXnZd!)-SIP~^j>a$SsT^>w;b*#MlG?yG$ikzTX5C*MN_AgZ`fqMUN-)hy^TVR`n^}>5{%HV3lt*EHw zwQ-{K2W(}N*stH2fn}!ZMjKT_>Kx%%I`2IjyTC)bAO0bqLP}st%iE}Hci0{<_cm$;_xr57YL*9qjJPn zN)MTG=LW;UR{t=MV%m9H>5&jt6m*wjx{zg;T=YdCqV2 zVvBpA%p6RkQxH@F+L!2q$@`t@qWu+ZZ~^QC{Sf|!TH)~;Tr_P;VnuH|1DR1s%&FHN%G`dt4di;nvO8^$mJ$Uz>{=&M|SbH^x4N)6`wru8z`KRhi1Z0{jMqh151~0fCNRz)xSK_bXI29;8sq_$2zEZ(L(wDm z^p)2+^9jr#&Ej9nd>|RQVB)XW_@j4NY=&}X;nW3=1b=j32(U~UxKBC=)tDaB}i)HA5Ep0`Rp zaLtT+bFIE>A+zR-Fe&Xjquv{L8+AG5QtQVtA&2^I=f;-hmFiJj9OO&_L3bGgzYvTF z>FoF0Q2soIAeftCS3}vZ28gJH0!RbQ!;E_i6kXn<(NqdpkQuJE0){?~i8(}uIKx-V zI}IGn+WJ_rD+|VBeai>m;xC4>Yo`!rnSV1yZL@WBXO5+vw6~DkX)GTyF(?QnDbIOlLwXP~GrVeE z(P)lnoDQoVP^df^;1JyIZ&R%sCy*3UvNQN&wtDwr?fd1(30U z7EZCGPhOrO{;yz{>bX%)P|aM|i=$wrsF($waxLe*iBC3HzlV1-LD=31MWcCFodj~R zq9bVD*i`0;=y1e;0h7FQ8r|tY!k{0z(i$ zd`e`RglQIoTlUdV&N@?i-QtHElNE8j8B&*;nDrX{t3WOpBbG`{uauP2)8IAFo3 znBOpcZALga!r14%0Jb~RE~jQG1)|GaVB3EDQ|s?GC(jXU6n69eGcuJ+1u2Fqayl`G zcB3QQJeHlinclix&%7XRjs2*Z@XvU=S3SV9G9;+- zStLBW!xna4hB*swP9iIoWk}i$|yMwIszVehd(ba-9JTrJjBj7|E8MPD}kht-&G{UWXvSfDs0vkv()SU zxwZ|2Ouj0h;h2I+iFoF7MG?*6Ljf(A5R)|Mrc;@p|MGA7(o&Xv;5P+ag0=!!Bv!`XK&|NSOzb!Uu zx!U+gehCRG6q$Bu8s%P7cz&@@_I1Q&4yXC2f0^X14lW5ad=!D32o6eMFkBArOZ8wLgaZulU{G)G;~s=~I3%h?ZYz zoy!q=>oa-bU@0<~=<^f8qyLql%iliIPGQ+T(+=%65FKach0OmxrxN}Z{yLk~txgN89J(Mhj|WV88jv+hj#&$l0u#AeVI zyv%3!U;Gf2WrfA7P`kiEKe0BmB~Sxal7_vo-wRGF8F2~Y)rGaRVi~*=*2q7>&%L>m z%Up3d&lkhh{S310ciQd8ban!mneLLAQur4?`-_VP9vH8ZCTmsz_OZlzi8*T|kM7TF zz|KH~rpzA~nyZm6;Sb3(#VvIL#K5i`?xZ_8>vx9M?%xe5mSVug2=xgC(S6m#! ze_asg22ZXb-Y;)1NblV-*_zv9tp_ghG&lA_iryk9y$1G-aP9ul7eQw;KUQp~wo;b1 zt|iFpBLHT#1hety*=~LB{^y`yxO-|B4nzoQ{WVdg+gmAx8{(P&!&f}X8CnYV??2#N z;~fhfL3CODh2Ag!+@g8J8C6~125Q0_u-9@n%!6=q1Yd-(-c9Cx`bw$sf=b){=V5Gf z#7lPWKPN%IrfrnmOEO~7y-PQ$g~$(X_?O;1--)fanIDR;7$0n%FU8*L;o5+( z)E#7xWT$1V=KWkbIHVhGFn_ygIWKTNPDvtCM!qxQcQEPMCs^sv)9Efb6uBm;-Y8F_ z^g{1{l>!)4Zd2C=NKGyqAUU7!`n~XC=*^u)xieX|PcVC)w-8YWE(l6y5124hhEp&> zuKfp`$>!e^68fpi{fSPzdlXu_leDK2MXRziqHX}#Ku4#iE!p9Pf~meDfWSKooAW$-ScM~dSNWASbt@6_K$yeM96)sC=eN$NzoJ#$f@I6q5U`L68?$CF&aQeLE zYrhBDfNJ>R&AfVF3HXf+>*qawFG~)X+>nW}=_nF&Fzo6(|10xf*A{vx52udKQIH`* z(`O%D35sdhKWGMuM>?#5^H!LcP7^@Xi)>z{O5tnr z>3Wu9C7YEmuWKkX2t)>3zg3Ru8U{MwF}e;S`BsC30R^A8Rc#1&WaawHZOuM{(x-%D zcjWt>OGaYkCRmN3|8|fAqsk6d{RAo!3ZRPAbm)#gvNJ6LUU7QBV~e2 z+|IAgM%Y)Z$9h+!NdYoE_aOryNeZP=Z|Yh6KFPMRt#Ntjp=qs6S!X~T5~IpXR*IBB zojfJ3n?k`5cO@3q-E=cBLWuVdYEReXK|zTi>_J~dLKER z=FYP0Lr5zf%iChtVm>c!Cl?!n5#>tbZUgt(@1IZW{u0f!N|M&@tgr^DOGwiaU7x&S zxE@X>bTsMTJe@Ex#DXp6_N4O6&RXZR;foK zySsWa2IaG=`>NLHZss4tDqbPWB>M^D@YB@md{-wIV$JXSv4r5Uhs1l6U#V`vhUWmE zQuu9>vR1Nbn^EgIiy_s$sd{4un_V8rdJp!MfZjGpFX4J7(l!2X^@$rY*g{^;2jd-> zf9`oMzGY*`8OYR&kQTX0or-r`(PfWZCgj?0E*8Qm|L?nl;7sJ;b2*b}~w>34~+Ld*RW%#V@7!EnXc7UB>aW%oY? zCrd9d$XZ?B;=j&_BD@Y{R5v>FjsFmzPkjgYGY!p{crNb05`#){mx+D%NGpw=Q8lmL z5EUqjCcEDzBZv$D+yDOP&Q?-s!>JeWM%tw0?=4yz7QcIY+H2E91u@N3SZ?CyIUqOY zJAUID@a057`Lt|y-`+FxFezf{KF-LB=FPD7AEo-vE487c0KG4WZ-yo>+9#u9HU79E<`XpLcY@-}1mx?0 zzcM4s2&KX4d=ppfsA&efZ^?%A=kTtcfaaPYrd?kyu=@Sq@DC@JIn-&HIkf-&llso8 z=iAGaaFgo|ell7J0aB;c(XagqkVT6MM2YOBtcxw}w&zXIHF<&DNw`yGqm^>;tco z*R`(fFV{qWuwP50E@W$zX};WYJ^7ujFl;xwuZ(VGz&oTYdR4c+k+fFu6#MHREfkk5 zpxuRM8TF?*)Y^UCtgzOK9Iwr^=NnGAiPuf2FfM80OqmwnUrc@Mzsb(Qh6-n5aInDv z)kFqGgf@OyZxjU7aaidTZ{-t4u=JQDfhC&Nf+zdX)*O=WgTekOe z4>OsLy~x38P^WeYgHz;fRQMTKD3~pTfwG;Nqzr9=j6}~x(Om!P zjs2@c?Q1u3Wzmxip#6DErCV<^GiXZDJ?xOi=SanEHOkTpD`50731t7URX;sqK;plh z3eLN_Jl%|BC$d@f@IXhWZu^Mj+~RSaPW&kKKqAshA)>WY7#V*Um3jPBT`)B%3}b6bta3N1(@3b zo2IKgGlZ-ht`wcTq=pzz3Du*J9~S~x6W>C@%qxfqk}}JfXUB0CY_+FQD3(8(OZY22<``; z9`Bb^sHU&l@#~x+y|lqfY$c!EmGc8)tO1&F!ktD;*UZ6_02L2G;rdJ^^wjH*F(z7m zRmR1+e5W${PG(TK>S}IHakS$$F(MA8(^t*yu1XB-Uj+6sF>35{JrszM4b)DCSgj6v zUtaTxjisqoM$`wZI+e`%>Fq(6c7aZbuj%&5@Kq27fp6f0z-aq={yZ5Ia^Ab5g!^0a zj3rU8kw%%-kHBUxpv##zEib3crq^IcZDmusWgd_2(}1A&wC(t~9oUKN%qNHb&)2_O zYJpvVKxb6&xfSs5F&OpS(EfYGbN$_i^Y`=o;qT@-W|lG!p81EpHAg3mzeQi0f|Byb z{kw*19trjI`xL2tSsLX|M&$@rQ1e{~A({M(OOTz8TRl=8rt@g=L8!mlk)s*k!kt33 zSW3xLwB0LFvn^L6|Bei=9o=lp6t89>zAd< ze->q`jnrnP-*5mnwHG)5_h>-%l!?-G&+_9f9NliGgSO;Lu@r{s#JyRh%X z7sL@ulK#C2ZOTbxS%K(9#=)bq-RUk^judhYV(lA~jn&vm6rcDl8=kO5U`~zEmS|c9 znRbJ1%294l)vKE25bUegn9HW59Ev-mhB7%?k+68fBmJfAsb2AmlL^rnzeR%>`8MSk zOR?s~__6BVJ1_3WO2VXRzEc55O#csg{`w1-8DqRjlUCD4-`0$3>?>Vob5xH)Zb%kq z{qE+qMM3J5`$jR94^DUemn71@nG@~pUtl=MX)ZkH15~gzT6-Zpdy=8LvJFA?Z8LJk z4CzHJfuiKCNro_H$qa}f%xP)+&P40Mar1V~>j-psL23WQqDf6X2I;?Qa8Y~VUlZ3y zHU{~b9{`^;!`FM8t$xt1Bj+#uU|~9DL0iuXf@rBeg$%+%ZeW3LD?ib?btg6{AuiU#%Qs3eBsfJ?PMVbnvJ8ov~=|R7a$Ll*`9&l@H^PsD>;E-rUvC z&q#t0EG~5VIfB&32iX@-k_{!3Nj@NwqX!uuzaGC823rtWwES)$feDL$t9tgDiz@S& z4scgh`#H(tx^~Xl2TV_~EHjjnjwnAdgO98g^7|nP9WK6yQ-|bZXcaCWtMCMG@*R43 z7vHq?1jN^1&7^+-d>mz-Kj+xgr&Zo3xNtXZ{oU*-W5?-&ww8R~5Y* zvC^Kl#%!z{xU^Io^fwi@CmU-2cCo13Aj(5lu=-S!<@@cXFm>#VGhI|vB~T%0x=-P6 z#Pz^BlFolY^Ac{Q+wam?0Y8gL`*(BJt4q?VyFgeKR6SU*xQ#MD zh^GEDirStxv-d3Mc#bKkAa&H%{7pj#VY}l?i@_P$4(k0Q>ARzi#iYYaKWYilKFUu| zkOiw|#u-u0<)iQ=hw{ohuht>VXzaZFl?I!rhnzf%i#3xh#63X-z58^^U-ac-4Y2 z1un8Z_E)cNRC3hdd=i0=GzOtX16(umlCN%Ck|#a}0^Q=YLj4F}$N2N{|McRC3z3vz zwP}xJgTx@XPwereDdV4lvW9t7?KU5tGObFsOB2b{LRV8A=DlWS%9# zv;>UtvUHLDm{|(uBvMa)_1)ULI3~& literal 0 HcmV?d00001 diff --git a/doc/html/_me_compass_8h__incl.map b/doc/html/_me_compass_8h__incl.map new file mode 100644 index 00000000..0b7faf90 --- /dev/null +++ b/doc/html/_me_compass_8h__incl.map @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_compass_8h__incl.md5 b/doc/html/_me_compass_8h__incl.md5 new file mode 100644 index 00000000..8fe3d967 --- /dev/null +++ b/doc/html/_me_compass_8h__incl.md5 @@ -0,0 +1 @@ +67e2512e5ab7cfc2d40fed64245cd29e \ No newline at end of file diff --git a/doc/html/_me_compass_8h__incl.png b/doc/html/_me_compass_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..825cfc72bbe57af7461ae4c49017a82a58eb3ccb GIT binary patch literal 46589 zcmagFWmJ^?8#PLINQ0ChN;lGBfPj=phjdCaAYCFN-93OPNOwyOAcNE(T>}gvj5LxC z`Q8K1f4%3!IqQrcTnlFA{>2sh+ItiAQd60f=q?ck1_r6BisCB_44eQA49u4Vc)(8t zu{_&>|M0BTloc_q(f>Ym6sKTd+`~{+e4^_M-d+p{oc6xF{@cF=+6m?AwPq3KNU+GO znXC&=f>e?I6p7S-QRAdOR_&+K>t+jsW&5e*XvcE3#K-^tmx{gNB&H(p;%Kvj zfsF`A5~L#)?H1v!ARX<=>ZDgVY&Xav|1fm4=@uP~D z?g{!SB(k*~r%O3OCv%*eOyfglLC1PazN>MDlTyG}8$Y>y#?5mAZa;AIp?f?5=%1lq zcz4p|*#CQBe;j0?xP2vID%vLew~ZedpX-#-@2%V2t{)9vPFVO>#e3=!z*vHJ(EpH~ zz2n*KTaQZk)94nt{arhbr%#u3qk)fmso(y}M$d$MV&YVH=jO&gJDf4#uOAuE@R>X=$)WKC{JJD80$r`>1`_d3BtJm4aeGJVrVc zeKs~TQb_P2JTG8Z>P>#oNtE=9uF3qN3Ii&>tnDKNS@N0mVzQG{&oTA50U)8 z-RsWL48JL`0GI!-`)BSDK;OSeXraQv+&jh1^cc8dn)OAa=erJS?}ro=8?XP17QE!w z(idC25v%>N-2;->kA7|Hc4!f_Ib(t z4R6@6A@c_@F?`uzlY$PazJ6|Y_Se?h_;-MvCv~sD*E%P@KD?q^W%rrJfzGVc&i@*z z=G8h|ax}!+#!)YcU#QOwf({oZ5Uy-skmWNr>&*=>(>>U{3Kf#Pzqm(MD=JDW|5pw&8MqY$Lbp8R$>4cTrXs~Zuja-Yqf%Mp zQ#^ei6leV!68d z&bRNUY{Sm@hu5ye=UiE@$PpSAkA7lQ^f>I(m%q{cS$Y9HhBVx zr+=Fw98RzosCX1x#y4R`UqYnGlv0zsQ#E(_sg(pR*3dW#EFS`P+1@?WJMq$7NUs(W z&Gf@cB$g%P1KIz*y6*3l)BYBScrQe6oyG73KM^%=L$%Kbse zbjL!LXS60(MCw;Hh>pjbxxjY6{A?()4S`^#pp)!Z9+DNov2jvNiXiSe3N#~ zu;on|%-epm`1a9QZc3Pyg+0PUVmFTA6qf6trI=J+IDJU;0VKp0=?D4qRy2(4Vf};3 zh+&IA#RC<1{@;osKKLxHxDgl6f8`R1`FQm3zY_fbDR7!A?(#c%x>Z&X5BdN^?BY>u zw(S~4t$-!q-O}>Vb;e#aXD}~M=harNWv^sdC?!Y}_XOL_i_;b}#=0%3LUua)%Ww-y z_^%DorzX}&41P&LmriEqMd`b=nvJB|c61a2|9cqs&ia9=hTZY^skk`PnYlE|O55%c zI}Q>%{XQ47CegC(4LQ*id1x-B#6xWBuxpEp>D)fCzgxR`CDT-c2EMLCCb54$;Yfpr zV@t`@KBdd*yNp8IDUwS5%LEr5jWfyctzRx}-ES%_8EUfro>N&k#$kXJ4W*+kf&o8_n^y0dMkrQgKhZUvbrhOZ$ z7#u+Hj&%y_g=b|<^hod)&(6CpZUtWp38!PU)+Q3B^_`f$op`Hmt932pRJ%8x+Dk3c zr&YkfUvOw*v62|L+v*4IVD^SO|8XU3_^-A!Y$z2f+@7|`4-NBQ_Ke z*}LBYx(-rVv)`s;#IXp~+I{ZG?rSkAsw=+E(nbatLg+}oV&&tBOY(`d1S!gw?pE+@ zZNaJ!FXAxqo6;T^2v38@=~s_lWV}9jObbl z^P5FgQc|f^sFl;;^Cbb~%Q?||jaLD3#F=EX>49^w`@|{sYn?xIZV>Wp`?LBoKliqMiJt2-+mGf*Z7Gb0^cUi;MaN1K$J08YZJSTxOx2}Op+ zl&_`_PhSqbk{`;=fwz>}vC}>8uvN4jMFMih%>N+W{Q5!5p`1wZxs9!W zRzOtYC|)p*sUCClP@VVkPC=c$J5TxHr7VKjX8oLrP!{__c3S<|VrhNKs7Ni4wP$*D z#YBssKGYgMhw0GmHxP#xu17{HY>3joA2PC@&&i(rAJ)Xn94}0eXd#oFjgy+o9y(<4 zQR8U6yXpi{n(}C4b2?qpgx6R32mm?U#j+bj{0$rT&3HQ zWbIg3ht@*aZ1CD7u&-w?Y-(B~#Qq%eQOeyGdTd3<4pu9uR;Vgj%)rXK?7vOYIip;q z$A(WZL7|Rz>g7BQGWCAfJ4JQM^QlW)y+4qLnBX-bmVc2_UF!I{qr44|w2@oYz(u+t zvB-!_3@{>~vo5(L>8>lIhn#a;NqBS&Hn*7d2n5{dCX{9!?6j{d{ri_+--$(2KF~k> zdOvuyG4#2D^>rMM=YpXp0Cr>MHrb5y%dW;Cw4e)L+trPy@2UR6#3i5Dpuoan?Tm;$ z8GiXk&P33UYP14FY|87Nv}spd^*X+aYk-?LtBndWVUg~Kx^Qr8diq{aQFt(J?p zBl{p>w3O8XP5lACq~?GkBVFFGL@vw)vd->yrROFuoev?1X_zmz*VFag-|UyV$GrOG zJ(DX``I%%7;_*HFS%;s9{nYLWdacHWeL5Fhstwuyo~PnBNUqVV=cA|0RM%Y?wcPus> zRVwlKa!IoFt5+1O6Wj6QXME6sG%DxUS_<_t#?8yAcqg6L#f$y9yu&S&zKuI{&-!O1 zUVYg+QZq=KK98c^pPJ@3a|+8h`JtiLcj7rY_d9$({)1MpVfYxCHJ=XF&Z58Sx^7Kq z8fFF2v%8+gz7+sqWVCfna=vX@@b(32rFH8FV0ex3YP>3z|q55RuH@zgdCmY1O(f>6>a zs-1$8`hlj#Tp~NDp<6EDdk--oYL(UYKhK{bD!dG7=t3c=#jn_MGR?M(;g<~g34=`=)&!6An)u5b#9{Bet8dL8ao94?hofRld0t1 zRbuEu*B3SZajDypfPLCkU^ERPV`tjBd|&r?-6wTu^HN=6ok4f!lnZ&Bv1iwuM|(n) zB{(eo`-Anif#{go;`k%>MQ!6fPCO`zEFb^MdcR&n3SJ@dDMZGnb+5q@JCbUZAo9LP z{5{dOQVe&CNBf10S`-J=t+GZS%2DfepzJu_&R{C>s^^gkCHG1@J>J__Ys3PAi{ZE zbe{Y@l%7%Y3v)acy7yuC_c+le9^u{Qe@97R(%w>X|Jphjxu1z^N<9#2;GKqMOd+KInGnj2|x)vK(arz!R*e2%~ULAr>EG zlvg(Ax>nuH7Y+WPs9SWxhvq%_H6s`ZEo?1J#hQPz#EVQ+^mPt>HQjV4bLXmvT1e4e z-ypQ*?i$IR2s4dchoGk5EgCV>87j&zGXBYjfeK{oo3F;frmLJcSPL&jzWj4fxPbx; zlOIzVQ#l(%4b_HxoK`c#&vPG5eOxQ1wS8`%Hzi)vt$IU7sH8XK4`GW*2a1-p%I>6b z2JQV+Y1K(2%M=Rve0hIRR<1~FO^NnZBqkZX61HtlHi_w)T9B{wh!jK#B4nW{J(AG) z;+b@LU@5tqxYXWPaeq%YmVX%1rGM&E(3 z_t`*IM$LKUXFVqcb*Zcf*ei>a2=xk{ri?GJNgbZ_09dxh1+l$7qLKo&tt|{Q{tSCC z&VZ(#KG2(EcJ9D-cQ4wDBKG(Iszxza<1GJnW@_0{@g-)6@!-gEv2X;_Ejkc@(^zW8 ztu9L6w09)!Fhvz+V8;5U-mMhc{0~z#Jwroz5VJcw^mT2h8V~2Jnl=(EGwVp0jStg| z_*wKi%|h2_*yIEy_ca5ol}w>LYT;TjSGlkp4RHRse{BOv?X&r;sg!4Cjt+%&)s;}1H? z9jk=Cko>Ecp}Xmq$Ty<(OA54ikL_eT*hU7L=}fFAv;3bqcH}!iS>Y&MpnM2#%Cawd z0}0_qzy-=A4J6293}@Aa?lc0;03w1Or>L#f+gvQH!=8oG|NMAJ7pZ3_)>7|z>97Cx z?b;ioL30m#*6{S7AG36roz_Fp!x_s(BF=4gyngj+ONN?yUk{N3F(F&tBnFx?FM4VY zU}iC0{xR8ElUp&%1+gM8^w|rgW$GsxlC=pibtoD^)UJKZK@uj_Lkz^ z<=2+ooiccF)$LT?@gulT+;=LQm*(yDLsYNFT>}hoUt+*hXL|Ic>t6e-p|NpM)U$D@ zHm#?w6ADCK!-xTU6U*t&BH>%nHwysir6*emNzKRDP$_h;9TChFwTBTtxpUOoWqwvB zL{cq>1cR1NPh)OV+lA}(uYTj~En!UzSAeJSH<#ru7TcI0DHG;VmhC~w$&rB8hqH7> zwqe%sQeQb)MeoU;%v!gcZ-9`n$~ftmBRBh^z<$}{;T1+a84L+G5>&UvTp4%JXl!Z% z0fGw@f1r*6kqA*@aK=$={qZJq42OWtlZR&J$v;+ARDd^keRdmX%sT$E9XVBZT}j)$ z_4o5bonHkHMDZj7gt&^igiF$1PD*bxe<8{0=@ZCoE7eX^3CO!pYz=9$E>=@sPP|jM z6nHXcpTC%su$6HnmF(PF`Ev==mCJndaKcdlPhgNdQ#<=$uhP7~@^&~IM2J-XoW^hp zRdVSPM~5C*Ew|Uh#6Q>84r>Kdr!qo^QuTWJV_@*~6?NbJ1lc;yFXRN(T}yvY^WK@k z*Z^L39Em37fZ+)?vQ};Po!L&e-^J9N-=9)7-vvgBm!aPu(ENuY$w61M#v5qW?9;a$w zCBup^Tj1dQ!b7RThpxn*|kbPkExn(8v+thLFEpIz|i!&tk~BdSQLi<2z5;#7+=-loV~@gY&FOg8tI zf9z`50)M31!YKJ4r<=mYq30Sn7Asmtv{O|g8l~b@7QJJO*kzyBBTRgCL{3 zcB3&1*4oIF?guVRLm{KjNW#RjTufX@HB%Uz2>hUNUHJQ8sq$y5t+TuBzO&Xb@_W0* zN_T=Fw*!8-u~F_G5>tU-MLis!DZUilN|5u}hg-7OYZ~w{;W6y5x>^knwCyRAIxWp= zA7SVK@C%?YX(0Jj+}E}Q%MQ7f?Bj=EYi0muwM&I~uS!KC`4FvMqN6TbiQ(3~yaBu$ zp}+u$mdc9I1lRD&7ET~Dk_J3c9^-5|+1j**=K9+-F7S}_J`X3=#hBOl*;!xe*^ncG z1Lr6^5o`vyP;)BPF1r*D@2y1pBo#=Fj}|~xXv9qjAb;x|9i85 zE%G$-GiTD#>zr&uyjWqR=p!W_e?a^gZZG?}8@BsxtF>}-8 zc5~C`3+6LpCR!T<0Wn7ngVvR;(ykI>$bAZlT~DNaFY!Me_O*N<7*x!KJb(WnyKd#& zT~0ei^I>S&2$4303I>2A28*|SxRkO%zl*Us3j}VqA;N0wc!hy8G6FVaZnpmdYmjTw z1$#BV^f)DN_ij$r&blAojb@axpSIo0U8hGVNRp>dpZ9#fyjm%#k2)&M=qRFao^9xgp)`B7mTQ&JS54n zLcT<$@ZhVAO^gvSiS{lkxbK{}j?Is6Ed(!J1?BoZ*K(ty+R&JaXyR&;iNs!ZZxL%s z(u?vJi~{hAPaKofK}YjR*Ys8YNcG}$hxB1Ati8H^u3m{3t-0Df<}N>6o%!AZ16wba z4iL8lY8G6IZkoQ<)8Fgc<-Xo!W4?Ta%x(2CsHWQ>=SgU^ zL!dk8&!@pS@GO>*!X`o1pPS0w93-eO8Cr*j48hSoA zP9yjCc2Xa&&P_XD9@^|+cfTTIiUj%V!5=oj3jg>}9tVp*` z$?`C8>{wQcC4Td8zFZqgHJ7~W`sMD&hMR0Z%LOPX6Ob$~Y1v|{Ac<6=w5!4K!smWK zQtKl6SJ2xRUi8OtVQ^~hsd9LdlK;$w>WRO1Qqb5+yOYMF(?5_~unsh0(>CEmj z-{jGF?H90PaONDmv)<&DUnys8GP=j5taU341}(J?1r=*Bwtim`0n=ew55k|CFnL$) z=%MK-;+ByWYS34GnmIXb`%T9jI zY{LsYR!t{YFgWPYsp%%JO58SFhdjJee1^VQM>F!&}F-uSHB>oub zl%tB-UuvV8`TmRd8-$2v`(rzv+3Q-wdeU#fB1zwpV0yA89Z7^uHPAj?Z;!5@$I_34 zIz6KDB^4!olx(K=+CgjesU?TJ_| z2%L?hAiGcSuSSZMOr!`w5Gx1oW}@U?dblBoC1}}hQv=P-5HgF!ZLb-9)@}-@htouE9>_x{2V(*ZK*OQ!B$&e;yKxGXoSLqtj_P`(NfE&fFy;dJj!3E z2P`VR&bG5yBI!FIQLKwz9)I-Rz_c^Vnj1g9`_mHB7d<|v^mmHYCv-2-e}Oa5K$Mx} zakmrdb)-q1;)~HT`+QSmMp>f^p ztfnx(T%axjS$NTHhrBDgt5Fze35qqk;Z|S|MGSB7a*|5p$XY=ZYYHkPW$qk#SRd^% zP3hg_%%g=WaI`1<`3G~AXZ7UGWR{IZS**#z<|k$G5OaX}bMcFzXt1%vrKr>Tv&~Ge z{O!;$9J_}eYOKO>2`K6=1o^FpK$W{pX(_a(V7PyUH9q3 z5~QQOo@~9z<*y<+189ohxJ(Z2_uN1AhS@RUfn#ekWC}rqRH`8Z2&4H92H6GhC&B`{b1Z96@yie9r@ z61R2Cc$FBwCrxB>P7d##K*DlOa&j3@`PX6s9Wr~v3Ow$(t6)S*GCf^)K~4`XiT?{A z2oe2P&Jc1a7P3sex@UYW?4HJdDA!9{MiL$Bbe9oz(o@>Ry=gk$tf#N9>3u5m1vX}$ zIk&O4wzhYEu5@$bM=jB7d4~rNUo4_n?qJ+#R}ngu8J+L;f}#pT2s7Q>`-4#&XT2n! z>tA(RSAnpg)F4f~=U8qsvUliX-i6w%;RKZKoYmFUT@G(kF)#6@)BV#fW<>_DdW)cX zpW`N6{(6;neW}K5)`pv>AUoP0av0+1kBqaJO9M$CX1fo18yudM+3X|Bmc7@E_T&x= z-GcjkE`DmuHX$|Km7^U*G(@T=0 z@#foTTZiSg<+u4b>Kz68s1`&TyrF94+reJ zPl~t~DGg?wq@Kh7fa|6K7+`3q-O2Y=pURuOc24kF_l_#;3iojJF1T#x9d**lJL;I& z&zauVar)I%A#>_j?Oe+GoVd8{udPVE``uxqKTyH4)syX$rLHcX(&P4(w*91t`0oEWVH0*@k`*Ff3Z$SsX^$@_hR-h%LQpKxct~qQSz^xlL4E@JW!BB; zyFpQO983UxgqOlhi+pctXe7Iza94{XNPPc3qHMF}HLZ8v2r%U>PDsUq=vi^pJ?+gA z=Je$Be8ga-%3>++fmrF~`*vU?^cq7ZX|D6+GMoL}#9$9-!L{#J;9;U;*w7jE2AW*I zMRb-vP=df);Uou-CE7u{w>Io6EliRF9+;1v(Q<3`;T3QW+A$)1BaB z{@F>1a|d$(EpkUl`n_Ylc74==nTnXejLOKx@Q_yHDOVAoUgglitVnDf2u*gnX;(aWpYjfT3m5QEVA{ zKJt|&HWVBLQeghQIAK>9_?{s$X?_2mMMDY$Eh%+_*}>g?F<1(o7M2!nz`nZp^`h$A zVF1>Lf$$S!{;q94JrA19QpBUYsg=nzYrL`&7ZRez$OHQQjxhO*Vj#=_jyDrqUDVoG zuRuv!*YoVM)8LNvXND9HD0UmhXj}cHg%MxmgN3#<*XQF2gd*WhT{!JH@H8PDurX~5Hc*4Au~gWof1eFHi8=u>-hBpscgDKwp6BH|h!`*= z)mvc{K1Z9t#F8RMd3^n+F z2#&OU8&(q;=ZT-9s7RqHelpP5I7xCTK2d8Uy@E>kE`Fg6jN2_Aw zSs(rqA~bwsGu@ ziUW*jcJ9Pb9X#{08#R(+eEGKVyYix2Jo2tZa<7$V%O|_`%6Mr5H!0pVne_;GxCi)F z-0V2sc43amgIRA}cr*z!j-u1v5*KVK#3(t8Xm-75`1X_5cJ&Ga;GO4li5I0Rzy8?W zg2}x|xxx*PxPLG(bh2R&G?G&<0UvB-d}v0K{lk~V`K>pOBzB?j;SD`OtS(P`vnG83 z(&uOq@||gXP2!gy6&TW3lBvV)2XT^GDcqs@IGDW72KtVTs-sT)dV3frM6uOJ&=6~O z?EflB9dJBru}XV=v68oeL4wlg2f-P??nJ-{@ck^NoA%hx8(!9gG>h`T zHjh>GhLa7yYLCxPIU){q3d@E*hnYxDi68$yoG&lgM-;98!*Ne%u*Z;Dk+s4k7B56i zS2kZ7JCTrT zE%V)HRymm%;0O@W9ceyM`zNdZyE`M4Z)&*AS6Z)Fq3_xHt(erlVo1LmzV`IYU%W@>{{~QTPnUe&T|6=P>F?J3wW!U#_i({mi!rs7>#-igqA?qrcdcY9S zZ`5i(?nH7@6>p*~zT39)IKSSv>jY2ZNn@=SrP7C0EuUjVQ$Ck)2c~V znm1U=%VAz*nV)l{c|?lbw+HdLtmTqz(^Q)qO)IO&{k#+7;pvkgu)J+}L{wnePwz5v!8q6z+P*inOO*!ig#<1NS#f0)Y37yzcFC;j$C#tc+bo)Z`SN z?l=_K+%D$R28xxjf9uoYC5~pTSoU$jl(AY^f^8lNG79;0&HbNY67*nzvH(4c7q{kv za(X~9+ptG$*1>W%Y#}7M_)X1XEc<9!wCs+2fvD1W{;TO}0OzJ5drUDJ(NsbGm& zQbpSiv$It&=rHdyZNmR8wLd-YTJjAx8q@+I$q@KxDmdpa-$kDlDPW0Z)(Z{Wc3VhGRSR;xUjO2-q8MAd9!M#9mmqXT z=<4HPB0~s#kAj7DIAqCH_4ASzJIHvZ+z|;njM@n*{$Y7nQ2j4Fq@4t(ySt zGMQ}sJb5Nn>iy3fwi{R^Y9b^qL)-Cj_|D=KOAWpKSUelxmEeEHEXBFT`i4+yChjmS z(8o0);-at^FvD{s9gMEZOt9c1c@|tc^`Ju#AVo){masMN>0AYp%n};nUr?-KhOcc+|NU;k_^#_g zW%+b4cC4878@+-{UO0p4<;VAUd`MFDvXKS#aja7=$G(S8H ziTIqwcc*Ey9MG2PM~wftF!R6v6NA}@%7sdVEn^Rj7@5%^1;hRDCXBe3g-20R?$J`_ zgoJLoR_4$BVHAp5WQ zer`8_xjGclJ^|;DSCeQ=EF`}wv=lo4k$36;+*Utp;Q?@7RJOZK1w*^0cKd`DMZH=x z5}pCN3y*2th8QMBV9gm}5G}RMBQ#ZF?7;&dJE)33dEV&2>Yh z3_p|{{g(-255w#H6?)>9S1On`!SD&}QWJc~<(b(ZKe?L9Tr`XZhZa#;y*(?C|zN#zUm{1+GkcLk(kwBs97awt|1>zM~jV<_&*^WC3B z-JL})Tij4;3!s>|5%hrm*4y(LM`Vq3>W)R~(#SmiZoV=NazL;RnIG^q#`|N(fsEO+F|X z@URN}a@bSlxO|Lwg6O*le7GbFTiT67rWal0?5bDCFFfh^+rFELW(*_vu-=NTf-e1< z2GMh5QxqY@$VT%MF>`uW{k*-ftyY*RN2wr$3Gi@YPPCJ)A zQ*T#4{Wpwb`i{B^PCcj`@^;wrC z0k73mKeN<;=fz68M*a_VgmE%gEh^-jpERZ<1GAeV;)2Cjv^pZiHOtxUWV&8WCpbJJ zwo;&uDqt&XF-hgDYL`!JRniAm#$9Kwoa-1cV!YiZwkGu8$3?Rj<#{4-o^!) zr?xCBI7?Bti4xK)+f9#Bt;31oI(jx*N;&T54OK^Nxc`)#eFpX92Q3P3>JWyboa?zX zLNT_@3Nr%`S~EVwrgC_AWPMRM@o((|w`%`flM^`j@SRgO`C7xhks&(VL<&g41>R<~98|9T{1BBBJb*u(gvi0EirsxW5f(=1V(J z@ZFLd$MbJviK~9_o^D@jo#2(sPW*Jwp03DYP(0pr%ipa`VYgky0QO(L<6!_iDEJh5 zjTDj+l1IWiAqt@ZSjgR05B;P5<@`!c@5Qjg{pZDnf+HqW8>Ba#8ZY!eXT^QY3NK_& zHhTcarfG+5z4cfzMgX>(#l=!?ABvyvP1j%{-x_{PJ@u>&8&!Gq&f1S2x35QLtahkW zEOYFWo_`v54pv*0PLL(_E~;DZllY;A(j)et>F0A)&h|*I^l6%nIxe?&-!Q`isob@! zSFi2&V5?uss-X!Xuv}+jLM~&8mks*V#@e;~jZM+)qL>-qLXD{{?LJ0-K5;CsJa(Lz zH*OZVqRvPpq&9t0Nx&f*`gL?dDTrhDr+y`|!x$}Z46&-+F6vU4iqZP*`Z`PsrYnsN59c%f4tiD802h%TOSD z0Qdegi=oF^LlXlRQMy`9N~7C+4V1I=4s5zXb#QroM6Vn-=yIJ+38cR3hsd zK29?dz3Zi-O_jitTHagRNVUcq{F@?b%NP-6s1m%be9;;G@JLZ_SNWd_&wyh@OPk); zP5~+z$+Jf%`*up?xBEt;a1A=1r3M+ST{5dS0Z4 z(t@mZaQvqBz_ASDKOV>5Pwk!xuVPsuSfbu&XnDCpq} zE@SpnTN$PWX7A|~UU<9^;M>ZteWkF+mGSWvp)Nb{59z6NQ2L2pC;8iN-o z=sP06#cES_k4w721Zx`49CN87J-d?Q`|PQ0JrYiwgLk_?2ZLZ~{!1Zddwbn+n0F)#M^R|(0~%TFbVXO$6-2$q=@v##iNxkuI!yEFtZ$+xp!P?!oC zneEGPTDRNvu~^3nKOB8;u&Mp)zzJ}@zQ$~+ljdN&gz+xOFVV_%SWn|v@aGc0@94O zF6SIrz8owndlDlqHpbCo^yrBnq+0gvccmfknRIqqUM6fsE4J4DJ#f2z>kE8N9WaqP z1wm5Y=@CIs^2&orA6a4a4(rGpiN(2KMbyjSJ* z44Dq@`4jA@(cMXqrT$*&$nb~?wf#BG%lokkse zs>c_-oX;vMdyz|OZY$zWGbov=fGOd&2z{pZ^~GQU_>6r*z6I;wyDd-ng=!saG>~WY zn-9@dn7cC{*Y%dYfQ;3k6=`b5AqYW)_+XgGO6{*^SHAyZQQ7qCC-o=)vI*Q;_wNa) zz2W_x5R9~!7BALRQ=ry-l1ZqJvqaUxoAp_o&R|qmU?NxN0pAlTeP+$-TrS>A*Z_UC zVQoLXb?ksg77aB>Wpr(>!ri-Icx}Ve#LG}4`WrKI9#j05S6F6G?zvodk)GZ!JI?dG z9G&7KR!Q&!cba{_2J`sG=VaMcAI+?j_G_vY$W!`@^S=nY zm6gY$qIkwmI$mikFOutZGx3-d?P}_YeEOaqL@%SV;+3|%=rLgiws`J|Jvv;?t+wzC zHC|fY83&IyRK%g8cVO|jYnELg5h(F(Qh277DgFXSxntKTvjGd1novM+H?yoxTG^H0GY3WB+Ud z@~bmpKOhY9&YiHHxLAxLhAR zSJLMbD^6r2bRT3R42VFAS=u^mKB(Me;W?Yz1ddcU|9VbKcSwvdMV!X>hK%HJjh^Ki zxamG}7|R)nb!_JMPl2$~==(JC`|CIOVJ5s}AbwHF=^-s7TBR)QF6B;EgV`eWv!^}K zvA5LpOCK{#^i`V5yEhbHTL*v7CyM<`G%M~oJ|m`hTARqU;v+CeYgQJ{wZ;-g_<6Wa zqA)8mx&q_|2DG3wjegkptBgM-9c>!kJ76!wE zM|op7j*L@zL$hiV`3^+stm_7Dn*o`FXa@2PVwvdrHDhu_Fmg(#GCWOYf%bJy)Jz`F zLLH6Zt7?VWZ*k@VSv(^yU1n3Clo*?I!rkM0n%_J-uxPS+`$DgWP!mIdN|Mm``HIAO znx~fh&O>UmO8ghe0VdIz4esyS&;Lq{N946W#*vhxO{VF5Fc+orl&)a=F7beBF!EQ# zNqA1ALbqP-NM5#n@tTiTa^+=CK?u9YqQ-mCDO>5DF-Sm}ECyd0>EGg~nJ)Scc9oO8 zuQRUMBcp#MwOo<>lYh!Vo4S0K7WuzRf@)o74T0_p>86^m_nPJn+I|DoWqw(3iMa}c ztP&0B48E$i6MerbZH5qjkKgRNQZcO+ft+;QP{!QVv$YD@t`o7XO()?&I;(bJvc?^7 zGF2tu+Gb^VbWp1PF-@K0+A>{hL8bgQ#~6FR^l5Od3~Xe=mhdmvUYXq^h-9V6@TI_! z44t6Tue-SGWd|zS$%hMFQhAN9$bEEVGkL7H-~FwdD;5jVX?=03RwRj^Nf?W>gt4n* z8|)HsF|xd^9+1?+@_zqy>R}i^(M)R*d}XF9BT`B%eXkDfSgZ@x`x2{u}p!CDP%EBd%MrJm?>#yw)@)XaYt^_aVc%Ol&EPZ#2}9Mb2ffnQ6bBE#$T&)Q^vd+daBZo+swkWQ=(1w+lCI$p)*6RQ_p@FE%PBdNh5ipCXn5-@x zdWOY_jj35GuRYz{U$33_WR@|*#5%<$e!2C`5kNIRmSw85hz)i@;gcf zTX}{5G{5$3Ewh`hlGt{#?)Z+iT$!$%>+cIkKyE{p*0!lAnA&!xa)EwgjPIR8E}2fG zQy56k@$tXv`9xXdvv04Xzk5rhQi+78@rJHI9=^v5n;IFZF!Zf!pURg~TJ zUFG?XLxz1q_rOqxZS?fWccn#>%hRvYKl!4gZ2@Lj5I`ekTGC_t_;CbEGn&!I%juu# zov1A>6*pq@RMacteax3tLZUM!ME5;{SXaicz@xv5)rS`ELtLxe=g&=i?cAkEiOjL0 zF=ssJbKDL)+h6Jx!Op7P#oY4OkC$XMQ>(P z;1fnepAAHK1A`MCan0cQwQ&Ovc~5{oB|Mj$=i-?`pflC?q~#uMa`v=ae#Xzy)Ng_0 zk-WNoRBMs7L`J{t2VK0|_`lT!c5$LWAzk~fIm;ia_py3Z?)}_dxTakx0U+e`#H!LS zX$D_{k9|)?+UggSwvL5pI*Gxg?Yx7z10umXTrMJMLtaQ-Lbn1E$8+znLgGE*KyKP( zgNwmx89M%%*Euo&n!mhX*Hh`)3p^Xz##<~ZjcNas~@jlM(cYxZ91 z@ZACOYMAX+wFJBAIzjO$@!-K#tc!Znf6XLWI8V`;#E=|Tr7&}=>9%OphG%qLA z6Y(wgbueg%!*SE80-gEdAB>t@V>JEMjs_sEkOc@&s%@!={@M%e`^MGCvYJGgd6y{* z@xX|jl)hw@y`+0SFOH%kS%Xl;na$i$)WYPJFo6M)I_-)QV%mm~7!;KE%1!B)KjGjA zfhPX4E5$6kyJ=NZsS@QGZtDLb>n)?AYQz0uN>WN%K~kEblrHJ+kuFK;8afpu1*9A4 z?nX*LaOe<*?jCX|N&g$4bIw}tdOx_-4;%KrrH)(iv8+{c{<+mV% zxll6~Gh#DNt4dTX;GEra+Wl^lqZG&PlgPZ$S9|@eypDcmciT8T819QEhVS>J<-6{m zBdWL8)+QUuKy&}`={g%Hcm5kCY~fZ1=u0<;(Fy0tyF@|sGP5y=;($5Qj#yRzSnL}a zzokH@B7LR)mMZ1L(nxZ|Z}?pI5^H!6O#|~?J0G)nX_=;VuTEOD>zk9U*f5Zqg?Cj} zf_-Y8F6!1NZ*bDuP0kuxL#VJVcOS+cX1+16aK(sOVNCm!k#4vf=<7^w)<-( z#s!pUuza8{-C*ozQE26TZF(61ATKsrlvcID9~(&!a@FR~6IA|#Lmuh^RU1@hh5G|% zst;1?h7X&VWJkMYp8%Gi-hyFC8ON$nH*m-V^R};) zoE%#x3;jd4#yit5)_lH%JG-$neE*ZB6qv48oKG3{7u6##0fl+|<4_i=zpk6pa3tIY zTvXx=IuSI@VpdvwPdcL-r(@tmrn-ClB<3wv94MTx+|?220;AQ7IC@(=OM>8Ga5o9v z-5f4~7ubBWnX=#?w622l^4790)E6M{7w=18-M@dp@(UI@pl1*X^Oda`ov z;F5Sa>3q9p$dw`1pyj)Bv175Z+X?&`JV=UEVqw|<+rLB=R`-jBPGYWbN@rMxO>r>J@L&l zm~lTyLp9QAID?(jn_}#LAACw~EvYTGr2_df2=CoR!&)09e_;Hbnv=Q3w&Ehopf*W^ zO1VlDD~=r-12*;Xs9RmPLVEVf+ECN3ad_Va_Nu-RvpjPNCa4B?OVy>dF@LF+XP~8X zisoaU{bF0vz0myIN`lZws8Ea7#nNEolk|I}8@D#@?t5T8yw$m58H-ZefR^cT(jyqp zy&$bG*O)^{6W2kG*=X4@PaJgJOaQq3>JvJlYsd#oCc7Iy94ZketQHUh@T8vG0O$xq z4v2PrQd3qK?nb5>=h+dRMiJim+!CKI==HCQQVXPGj$t!wMu9@y4zK}Ar ztXB8tY}PFMp->o?5>chdbUV&#a4XD4Be)3AF432f-<8FU6SM6ABBx4ArJu~sKSEY9mR-S)*ijK;euIi4-~|XQ<&j`@LMI{2gF%pA12&7 z8wT!oXS`XTfrxnKbuf-+R7-_>=qB z0To0PP_rDUr{GEQhB@HE&L+u#RZmdBW68VM5qNGUG}ua)$V^korZ(vinW3cV2O={# zMJQNG;w!KO?)^|P*!h#G1pq&C$PN1Y>5vDUb)#C!R#XY^M!fm6;<03)cjpXK&c-A zXC#lX|1Z$rN=J*n#{a{%HY<)m%Dh-_Ou#z(DGV)7fR09V-Uc!R$RvF zVh51sM%vPXG*Lp!U@IzbTYzJ!!Y@F;6U{{;*?1@#5^ zy3wG&J=>mE)Up;GJ&9M%l(8VnIgPe=vXe@6Rf_B(;zSi`rr4C8pc+@PgI_%9ZxQE| zf0U9Ju8hXEA~$SD>iau69^vzLPG@};`Q)1{wJNOY8PqJ&qUH~0t}cRu9>n|fk1Q6F zc<&Qvl8hEVyj!vK`=CYMFu$9M?yiiHS;vdgj_0JNC)Q5NwKAnPdXMctBqmB+33JnK zk(vAy`yzNp>tqoGvU5sfQ1KUaWT?U@b*^TXyI4Eo2qyhZJpUqm5Zq?M`V%Eo_>yfa zHye~xZ9AUFpV2C1#K?T7v`Q_|UV5UI=t()d%lg;dYy)G#%NnYE{R^J+3Kp_)qZN!m zGBlxz{}QlMPtUUuTTNoAtP(16>?tOw1h$$v!yPa~9~7%4$dxp}nx%e}{+L96w?nwx zSe686=}qOXvlF8|8k_m#C3DiGwQRpLHD~he9>=@`5FqCfkf5V}cX#IpYp$>65tnn7 z)+aGfPfsgpzd3#>tb-zu-l0+pYFR~5Gd|M>avkrc$vOm@bTn15kon7B)ZcG@!~vBI zZX^4$p6%Tr4nd!evl$HTf8{c{?g=R<5Pr0}xMEZD_E_46pE*{+_s+ZkXok6%-$T{- zwsm+Ylg_0B?+;&31aRlok5f|Vm=gX1*jz{$FTH4(GS%ajBs;w?rggl}C*(>?5FPz%fyfeSj z%W1xQx9y#2cn0fwcr*9=_l}IioHNpiBZ$mr{&@*Zp=vJ{?m;7dY-Qk-Ghhdh;R53^ zk`~VRaopN(i<@A_S{m_i1_8{i;9uDHn)Y>GfAM3uMgLO~M0qTJ5yS|UaT>`MvBiqr z*fcjohfDW7-ll-n z&q{Qtx~c>kHlyBq^Dp?^io7h3d-XL0PwLvT!FZ*rH14~Ig0gfoXy$Bi=o%F{IXh*% znge?fBfF2MCFEI1h)TFKR}F)w+*N~;O;-KHd8yHBHTChGPRNn^Ce;8(_2>Ga$hajRjfj=#&CC- z{S!=p-%%~g{8--IE6NlXG>D?CB^ zRo_vhP@3un$frUdAr?#6R1oUmQ0vr?Zf)EmcAs`>7J#wZqb-#^|L?{|FX`}*x*LIZ zS!9R9I5>nk75o8!WnL6^@OL0|V|PkY9Y6u>0It#bziVO&nvGz|S$fBwp#IcFGMqu4 zRartuJQ!TQdYv7RJgS^YYjny|Gdd#8|Mxc$(HS|(PApvkIV5gFWX%y?fzSC{ikr!7oalg7CZk%*1~kOJa)C$HjnE3|t4&8X98786_Ws|fWbaiFOr}W2mId4~89Yh8 z9C)(?AHlhVnFNZ$2iV>HMae`(VWHAVgtlisKI}OG)NZt4hLb>mpl{{MzVtaKG-&8` z=vYdM+n1Eu?I)J4*v%!*zCbTK1*$dGKMa|gIinxVv6uzNjz1SlSzw-vvat2%86_2nS&yS-Go2DEIflQUZ&O zyQVG`Yi^$eHRFjM&P#VlR>NOk&n_il#O?K^IJ)eZS)5cZQ*l@2w#}-5Jywo-;$XU717LeE+-U(7_k+IhSeRV9)<7NoS|I zp4{Kt&^5aZ>6Xm(g^o2$LG5U2VdLuj`2ln6C3nZK+~O+^X;D#Xs=a;6i}RcPA;@fs z-yH!a7sf2p_%MD)w3evCLyT*1_rZx`)~+SH`F!0!aHrPD5#-)fRxIv%g6IqtJ1#DE z;%WQ76w^QoxTca#qfUW~d^*D==4z%plAufX%a#WJ{Kd|i$&5Uurk7Wj1AEnWoYd6@ z)sTzSs|!DfCoaT;!-^N9T04gs9$c>8NnJWc-yTg;9(POd(m8RS0#~SSNVmU%6(Nia zlmT>mopNBQXu%A9gR_qh?v4Zo){uhM*LyfFC61o5jwXpHdt98maBL0)0&u)3fO03? z8K=xduCHFr31wthm9(C3d>GOlYW$PC=)WGa8M0gzb843~E-?XXdOF4H5#SkJ5XRfw ze)ZDnIx9*?$Tk)cWt0f>Uw#wkLH!$>`a|xs z`!7M5~wA%TFcNiq9hr6QstvG6&& zI*Nf!9ea`#*Z)0+pZdgGckYhFjb$%3mD5%&;d&h&9bf+%I$M~&W=VBpqpaxB3MgJ{ z?0m>}_oO=fb8()=oHhMf7+Jd6g$_0g>YoZ6-NztSvj>} z#|X_Z{#lkrb1c1n;}HCWcSB!ToI%Z(Waz2=Our@2I2w2f44R{%yckiWm%uP7|DA6O zZ7plBM6S9NddL3Ds5=ME@$Iy+JGt6_dd-L8Mo9UET5iP*cM*Z~dfN*wZ7O4gFqt`e z9Z(H6jlRFrNmfp>3dzZp284jgDO0-ro-LG(9;_m-=R;3*|FMIqT%bNOXco%>vVakO zmdK;*lmV2(0rCW4Z3?W_qKessG3-JKuDFhe8~Bqe0mr2tr{EOAfCEUyHLdq^%dg!k zfTCqxy^$6?VD+e`(drlXE+Ux_Z*hfkqnM!KAxEO6&%$wz>nl_0j?^@HarytZ!)BsS!C~cVl%7VJFrY;7% zj&26~dRi#a<`PweUaM@>63LsK`&$sk$rZ*s+T)Jw(3}FdwjHuK{0FRK-*bIAG^!hK ziv$cDR7DS2d_gSld;A)R`DN^ioI#WQTI){snedm7m(5-GBge#dlU>!Xz@cb47>;|e z7CoMz>IB1$Ylz+0_v^|V<_{5l7b$d$>aEIwnt+Fn;K?=^qzY!NvI!mvE(d@LI^OBO zYMb-VeNFJ2a3SC7v2me@;zFN&<(BXT`%BDZNzDx5%;7CsU}@Pi{uigk08f6!p-q!n zL4byi${FcusS^6zlD@yVMDg{HX>2g-T?3%eozf|L6{-@aw7_`+9vH53>|Y84BFlaq z`I-db14fJg5NSZOMcHd>-WYCFutn&RS`f@dfRRt*VbfErKeY$ks_dysQvWvOh22Nj zEZAut)_o_dI1*lX=;n&?0B`8nW6uPl59l2FIq$_43UP$?xv(u?J2UU?>~b)3vR06o zWwCzYz#C%+z~$WNqgj{8z=V@o;LN`IO(eKRIVsGJt*<_|pjQbJmk0=)BrQUu@$inw zCxDu+xf-X2rkWobX4 zJ%rt(63;9%EzU=$_*|HOF8{s zb{c=qTE!j8`W$x5?8i?U-*G?slU(Z$PdV1#Y;S+Wx1H1V8~W9{N&|`}i!#4Wh=|sI zg)9OmML7Uh&#Lkd)Ty)j5MsD~{JIg4OeVB1`|kpD_&Q3(T-qklb(%1H3)@&3{b# zWs9;YPYt2&CbruShUKS}+Ak~&6CpD#APhjt!3x-UA5B5dQyx5IPD^nNsdzL=6YL3I z83JyoH`N$1-y`4~#!Ic0ymE~cj3zdxB>&WFRz`_JoUpv?SJ{ozeTF$kw0fP6g-{LL z-nI69SFHUi9x(6q!M05f=Bj~XjcJb}@|FmeA32U|g$`TEd{o~B4Gp$*kZVX`nKlgF zyP?aKi_s)>a+1kBR@#fxtMsRwx>BfhGJ87h14Q3=yM_Rh zWw;aZM%BURWg#EO}OPp6a|s>N4v$PKo7@ zfsvI~a&z?0|M}ezQ!{o39bYQWXD|YFPGs5XOyKhxeMY+`k}MFPd7`zgzN?ZE0bTN0zf zur?4`5sH5(0O`syQ!Y}QCzn_?2GXFlAW z_~A!@LMXKHZRwSeu|Tdk=~jG}(dQ)|h4l6qYwUk!C29{4Bw4rL!Ew-mhxdLhJ3wOy zPMNQo!D6;6ld79IZeJL@xU3kpu-dqzY>`azmhp9tfGwn4zRNhwRErF?2wk~Gk|q+G zft0#aj%pRkB;6XO7?3F^liiJukc&$LmW(OI zm2Jt@o2?f&W&$wO>z<9;Z-xgDcCFONJJoJ-^P95#X(1;*w*rfI@RE~wOgkC9g7}Pb zh!CRmlKr|x6y9cNKej(yk>t~ou}K?BCwJZ7j_o~ooY@wy==y=CyY1PQTz68y&XnyB zueqm-hTy{H3hIGVI_)x^=Jw1S+4VMw5MjHIi1Zb=1udEX%>sBo-w?D+WQE_U_LB2* zwGKX$YiT7`MLD_>%4Uvb4$bdXUR?UwGHKe-ZOS*cM0*J!Q2PaZc;DFr}~gMY27LKZu?)#mi`y2N6=H;-jH_ zfiw8`CM%ZP$~3YcQq<#6Sa{&F;N`tCWm@)3p~m=I8zTb@z@fwpk5$i)`>}u?_CFX^ z%*;jC@tNqr-5FLq#`Y`!8RX95C$AEnDgW5_Eb#UyBHS(14YXv}iD zWr`4oI5~&wW~k?cPgX$>wy6y}!{19`>c@TLU3u2jz4wMzZy(YQxC<;jYqfEHKjFGX zCy$74qt#Id&I||Z?l6D3Zr3mFkOWqVvQ_D+l!P1W&%NtTb8Utyaa0gViUv?dRJzXg zz6e6}Z*rX@F_W-~f>MI!lj&?p0hi%^bS$+qobmj&Y&a&=LcGh3yZ@>E*A}tT!Fs?q z3VxguQKh8s>7lf(4c;M8e7Z$Q>jL-T^ojxw&=;QFtD!adoCj zn+OF#WTa6H(gVPvwY=;tfqkvUs{6XTZwrrs@Dx9l48Go z9m+Ih5U_I?D(M95t;b;B_!{YCrPM#;sjRH;Lb%#KO|N)B2oD#tc;F+VX65=I{6v## zGtni6wLX~JqRGkWM%9z9X|MZ^)0m zs7(}a;zKn=O!~NJ+KO1$9^M z=xa~YXbrKt;aO^K3Bgd8jpE5Kl6;8}X5y6IxG@MNLPf^oNE~<#;JYfN!VTwaR*tg8 zo$kd4uOGI`CV=((YHQ1WNCdVBe}s0(AW?y9jzoj^BnX`9UYYea;#?Ne#L~xR`E$M{ znwz>D$RD*ueA40~HLJ*vo})1&(>;_kLxuREZ@LQub`o%b3f>2db)r~h#+>-*A~7=^$ts% zD1!dgC%xiTJs#(KI$Dw>z^frgi6B2Gt)Id&|dDq01#JqB8cO&c)H zgKN8)SED4b#-FyMyhiy__BuJ~v|`6Vc{?@uu@KovvVmK{v>L>#i;{YWlS$5o#W=${ zTdDKd-iyb6b(R0DVgch2#l)!~&)_F?i+V(fusdMg%NvfNZa?v`RtMyvbzq#xiT*jd zO~kduuncN|T)s60*VgO+c6xD2t+Lr8rF&8Z_);^)v&TdRnZ;4UzSfR)8m5(O6;dCb zN^ERb-a!Crc%9ZvT_IZT#{0Zs_`^D1Fa`0dU-psoMjN)7nl-aI&h?1Z{~ss@*SU^t zX4^Pd%R*dc~uTQ^q%Lh-{ zO4j{8&b-O!kwF%S~ zjCALL%qv2N$P<)~0F^!;>%Lx+;G|)e_l||no?MOy4+90jIHFcS+kk3S8f4~2qsS&0 zSGqCpt-t|-P$rd+YG;%JS!kNDaTAzqvmL|6R4V_3(CKm;CgFvj>$>Q&pLld{o$o6k zJb}cm((7Dtw1C}$KkE`g_&^d$+Gn5Qoo$t;wBfSgLn|Cr`t**VK0Pk$=6%JbSSVI~)< zgg!sMnSG<}`;KQRyKwKaVpqa(Y+unzY|JnbBb_QQiV^pKqb)4S`TjFw5d+mW3N27g zIcwwEQTzf`vmX9Ptq}(+nt~aADD^cq6^1{r-XTd1W~-CD!tl^3oOl!ria3JBQU6jI zRr>mLXd179@5fYI`p?4wZUUvHdaCjgC)%BsW;_}ZSro>|NnIk9;5#^9f8z*fQIm_( z%1OLI)cul+raz@h0P!{rtD{@vff8_>(C10Vo0a1kO|fbi+7$62Mj+y?{dETL*AS3a zVH+Pq`Tgh=F{ulA`Re4b+hecgb|_TzrW+4YigyVr<~TyBj^r8~A_w}(ixh6L62OLP zPAA`E%}0~9{>(`I<^oy=J@&gJ{-+a+YFP4dq1zDWwqYF^6I0Hz{ZRIhe&+Lq)q3Xhrut)tNxgh5 zn=K_}I@C`Y%Ae?q`a3BFIzj-(+w06*q#vgCqhj z8=PS)iBS5VvB46h-Wts^LbsmJ0>0i+ZB4&Of}?3)c~MjhXn@Mp?n1BA)NoZCwZmj_ zYnm?6jO&?pI%_Z4k3&-SX;>_gow1!E>&0 zYN(VF`|@sw5a|l8NnmgZA6W zlfv(cVQwExsij--Whm7V2(XK_?9B=J`Pd-%5>tq0zEY$wuAfAYl+AL_WKWA*RgQmJ zLh3@jR8O^WD)M0>FjZy!sb8GN7M$}3uwS9W2DkKT<&rq))SsDhnf`n^MGur5#(dYu zJPbEBIsM+-eDk2*1$&nV^pnh#xUFSd`dVq>SdPfYYDD^F!wzN%9#nSqh9&Bv=ECUl zYFc5WeKN9q9iLsh(K+-LMHrc*d#E6cvAQl7x_qteo9wrk4Kb3?)u*bvtf&|o-f>B? z1DDP!7lhhX zllPh|%g&)LKnAOTj9YoFHc7O|^fBr7_Iqtt!Q?{5_a5Eg{Gbjb?YZ!AOp$LjAfzt< zc&S&5>##i3ySKgvCQPm zCW(Y;(U~ND{oM3tHps$*QxAnbqH0pgCUA z1)L!GfE-4qsc4$wiuWY@l1{cv@E*HY^kDKi>wf%PhKRclHISVL=p)!EI6ha!; zU5kZYx3OfWiYq*9c`l=dHd8OuG-jI?j+^9_R zO)5RWkOAoBxFDOaqr|K-P$4=LI1wUNFsL9=8x(bt&tcF~1rSbDof4jE8+=fyn4w7Cv@LAT81Z~#IkXTM<<`&{>n025`_vwDHeY2` ztm@zX(!8h%p|yF@c@e0*me4EpnbKa{L^$er%Q4a2tNM=Wz0f(_HYHaA6=6jG%6z@6 zT!S%FsjEJGg@iKH4n4)KsD~Eit8VD<74Lu~k-{$j?=56P%C?(T>96a=a;QT$9IYr? zM2WJiA1QEsEWbsZ$)x71&$Z2450R2Wz^m0jUZ}(Q__Ngm-}kp;Ee`GNE3tbSozMDN zW_m26p)WW~5Hi(x#+x){ao9l5-4g`(fQfe1#QUYbAC(TeF+7TE;WG}S;91Pq*zB6Q z+)0}(cB0UjG#61cv(w`*Kr)hO^U`Ugwh z)c0?%SDZUuVu(bm$7n9D;f7j4DrXaLar%d>R=3MoJ1p-7V#snelUld7?p{BG{SO$P zUvavhP$o#ZccGa1-ItSB4tYO<<~p6$V%9eAe@S|{P?z1aH2)fu`P51s% z47#Lkeq7V!V~<%c%{4B<{xTj#Q+Hb;^I)D}(!`WEO9@?uN&Tc@*7l5_FtlIQ#SaC; zd7YHiiZb4h70=hl?_IL1G+WD50!!&92v%0Zl#@wq;4Mj zdgI(usHi0b2&VrzH%C&85a4TO%HSy%)Ilw0dpsXhgjx^2Hhx_dTdFDA9=+07#hyr< zLc>5986>4Jp_?|2HT{-Nb*Jn%BcL5<{zQkqFh_jE=KOZ>A_DFRMEHc^$cE@^K|-@| z!6|dT`T+~D-3!t|X4BVu*Fs_Ooilv-72q)0#7Dcv5{L6K4baIbiZom?C7OAjyg;Pj zgoQhpQHxEn{Lr-2V9il~S+PiHTq+kal+YknL`A3{L{b}(=_owrZLXS?96(@N)gmo) ztJsu)FXM>Skb-9hWNAuIa=R7Y&|ZHE)XNwRArg{H%<2DlU^QmY zpX$fOo7+oe+0o74{-@c}D(fX&;I315_6*QscozovLxE!*MQUZw8+I!hW!ut{gdBam z5GhZ@GXD8Cav!vH;h1py47WgOA|H{#4(#teOa>|p-6fBw&2ntV);BIIERoGh{ZX=g zfgfVi>yb@jR&Z&NRCLmztM0fT_8Ywd;9bG3WtfNWu3LIquHV*P)8Cu^6Ud#BxlqY7 zuU&7!Iv`2KBsV~&Y%w8vy%aeEH)4JICA6UDA1ao66oREfaLnIcJ2c@_SHZNTb<{P!kYZ z0~#ORm}VL(vfnZDDF$fT^5W<;=uVzkMy&BBKa|)L(8Bl?@K7F}{Ej-QjMc1Y_l>u| zpmms%f;XQz5aLb5=!fZJakLO`)aV&rmfMcg86<6GrGL{NQ{0UzW0xTx4vZ}4SVz3E zpSABw<<~Pt>E!+XHgNHGpMiuo2EQ8;VGI9rn5eBJPjg`XYa{X(k^^Y$d^1a&WafE zkST*JTiUE-UO zz8iI-`LH}H4I%%%=QDYZ&F&Iv0Qj%2T}-Wu9-ikb!$M1_0^^Vh0o!OOCw6uI!7=p5 z6gAykrt%cqy921!n$P{dk6Bgs8s;|!8G%e=VqdYw5y5DO&mFwr;4kURxOQpr%iD|d zH3+E!V?atTSD*3lEW!)#Rt;w8s;H_-(!G{OT?FO$J*X=9pjIUoVZfGQ>>@UwM(;HM zrxQ@xUh>*-HLq%72~;6)yUw250H;o9WcaHg(u9N{J6q=a?^b#LrG)RKL&KR_B-D8>UdHV1iXAo!lBLvQhHW4yXiEQ& zK(l{layZd>z~Y>KtJzacK<9Xq6?nzlO1wxXX*#rZCevU%rcok+oC|q1V-8xJ-bB+ z&pPo$npgkUd+wZSOz*4@h>xY&)1a}pB(ge!*=)+!KkJv1Ktl>`-n<7hTSyw}AFNjz z9UWGGaB={`2*wxsBs|E4Ae9D^U<>qGn`#_Zn_5M9WF!tNSYG>Sn&8-RY?^6!f<^rB zaN3r4m$3$q+vt@@!dX_m$j zjYnU#++pVm1kiW6{r!nyBN{MjOSR`Wyk^v9_9e;@m~ZJ-)WjVEJ|va03bx3T&5wJC zulzZK1&SAnqWvx(v;~mftBAzYevINlRl3{^k&qY9cdo?V@6N{zboLmxFt@O*{${ej z^ZDX9=7cH2`I#v+`>A@ars1*#c`28)&+`RE<(o%$1ISO1)nYI zw-ZYe`{dW=%Ak47gM?)6XGz?c)x{0U30GnledR?(R@8)o6H%s5OZMq6E-t?NeML3P ziW$PiG~adLdbd7yW6p;fsI}#Usdk-rH_~kX@N&ZDc4v~f?KIqXwG`u5?!#F_i@j%` z4&!=aOAN1c9}D_kWhWA|V}nt0V70!G*vsEuqBvwA<%MXzv+a@c)dW2Vc5=2e)PjW- zG!acnHB<~7p#vF`tIGYj_Q9Lfz=+-KPQXiHBE`2gZ1hXoT})vmGjgAhZnl^W z))%T9rV?^3NjwzmV|npzn-rhLE%I|>>rczxlceM|HsF6sO4BS9tVc1if4bn$_x_Cc zw<&6}jv}X2&6ph?wsZFI@3U=IY4-uaj5N)u3Z|0Ye2uN3pGgQs)*-x*^S7a0{C~C< zO4(tX&1#JYgkOndHe-#^%#l*DUZZF?@8+Vwa+T2y|NORBT#BIgE2rf#j`p)gGD|QTApTCXGZanIn%=pDL zKsEppA8O7wCmt(NWvZ6vTka2t)Rea(xqS*93J$Vl% z9)+-aKKRDF;u!5Cv;tL?g3UPxdj;L^c}A0Gn8eDxSQ2x(SDe*j0yEXV=)`ih+IRra zB2ek__7Tb5)>?Y@hyFq+vnuR!<~PuI(K)LP6O;0*p^%w(9zZ8)Fmcpu630{oPJzmRr z+nV|D#HY-<26$5CXJMYdEmyRY_n0wQ?e+Z9?GJrFn2VV~vqiMTWhQwbm5*ormD|Ek zfVW)TBbdRcbvMi0tv<+{XjJ3@keK;)$0!tsA{I%cEkXs41Lc? zQ`8EdGDN>_;M}A?K@|A>Ko^F-qnhRU#f@q663hczM(D}`7U=nR&q;5tCI|giur1}y z>{i{H(|Vy{$@fz2U$??bw?Y#EN1a_5^~zTcj0V*=`bE`aP6M&omc6I+b2stBP3`Ip zpE%2Tq^XnuRo^uO^BBc9FTD=6920}CJ+Ta-ye98kSA6>Rz93Jx!A-z6Z_ZiMmp zMnca)Q@2fSCLVwH)avrP;03*=;&Ptv0&h8C`&ASIoTG0eE+JQkcgni3={pCtP~L>nK%Mrr9xwjs2hX}0BfX%t~OaTQScxw60uz| z-VtmT4%y(jPl>lsQ&R~gf+Xz2p=Lbrf*X`K6HPw0Vp;ay*RF(FIJZr=Ph8ZD=-N7A zS|a}U%Q|O&e*Dg`5R=PuxR}Z8>Z&+m1oaNJE%@J}mga~;Q|^IFgvickSeYrVHFIeA z_qB!M-x?qE&Xv0-_Iw2;19Q14#`2ym2$Nn@BfC0W3W+j>4EPrd`-iMA%(Uw zX3h4w@#Nb@Whw8e8OeLhWs40+z_X@d2PymhjtDJl(Y>3g1)i*~jJuhs zQ~I=<_(Dd(L4RWmpum*YSnyCISFx2UTw+F(dGV200$wXLn_+YJr`Gc64SI`RN{vO% zB9p$@+!%M94{U{8#j3z9=fxDu6x1n!;<{Z8mG)l58R@-N6+oq=E1rzX#phYz_ZeK0 z^CAf*94IuEx~UCaUit)Xp2?)>+|)bql1Q0AENLno(9LP!21Y7f?lVivmnN(+mPLVe zYXWZwL|+B@L@n*>SZ&&7DZUC-=*Aeenen0mRQ-Z+jMCkH@ONc7RNsPa05`K2V}YOzb;4!j>$WG~@@$ z?B`)waK?CLoUR{7#nMTIZ0N!B`_49JJUf`JNz?VlQn zoW4YdhrwKD5litc5qErXfv6`tKy7;kb zDcgN1zkde|#&cil3GKIo@O$n%2AU|H`-mMK+t0y1&5f1nThX}Sp0~sgAGZRpGt}mR zUp04H^omv3{-#AS0mOWz+kT*I){9AKa=l35dg&DibeQLU@F*aTs27?Ub@Y}vD4VKP%Ji~OOv`%aKSO1) zibei63xFv4_pFLoRC&b3-wIB{fg$eRk{)^q&PZc4nd^MhI=Jt+R^#uWS-A>NEc>P` zqq_!S20EQB3L)5!h1oW<#a{lcV3EX@G!W7U3UdEum;{a-%B?`nB3u`EhH1m_$fs2p zDkH2*IOLTxUxuDas=9CR{43siw!6$IW=6;&r64s@l3K?f6bOB_sHoo8q0ReDXBO!B zz-Ejlpp6v%l`N{!k1B1XbeS4lZ}E805$FnB5Wn!D+bZW6Oz{X=7Zlp1yc*RICa~TP zrrM0oFIl9}4`u991wprU6y}KJXFn(m>jpwkQI0vYSu?aql37F^%g*B+qcT#r_x32Z z60A;63mt643TlR6F>k1=60W&|6;Ws%o;;NH)OORKNeVr<+5M3-%4%5-KrxS2pd!rM z$2$@;c+cx1nvfT#9K2uq4EPBANLn<#6AO*}oyqb-i%b5YL4u}1v*XAwkC{q?fefel z0uEzecx5wBU6wmlG4b2FO|OH-+3QlS*;Y>fwj9)ez;r((5#qnd-^w(UWRu;Ti5UgB zaL8m@`a+K#g@T(TqQolk;OaBirdh9oqPbg#ArXT#2AAKWiC$C>Je@3#7meAlcQv}I zg1~3I31f@T|3t-Dz{`(^+;Vla-ffEw96&Y5D9exUHgM<8``~rn_oR#2)h3h!bBSdR zOw6|vSIfS!z#mSdj9<1syPLI|`o@D(o*i+Mu2&-Vo_IosNZ#lD#oywJbrf=9VqyxN zIbT$f9)4I^tq~ns)T;hdcD8+^rzzM$X7kGzG-!5~CuUsbdTYo?^SezwnHjmEF)5HQi%la|JQ5(^ z3N#-zdB!i``@iSVOe9#cfJUen`r93arGj&$$d*G$4j*U1hLKl)a4*@-t3x%!HXrhZ#}IFn$fICv01zN5`Gdounuu3HeQP%0&q&lrW5_Rp zAY~PHb{nT&bWn2hI$4#dhqs|-Z@V%Dzg-+p^}ZfNhX^#8)m5lK{ED1)>xwfZqO!wk zFl{a&Ty{U)ubIJ?V>o+W;4)$>T1rgd4FfFe8%;kGUKLiV3^UpG_ym<#5PIb`CQOqF+13shtROPkYs4^#jX#=8XcP3C5kKR&J}kaEevnEw1uBy;4`4=bU$sZyU(ycEqcAotoqc%-pr`@QA$o;uN_6N_P^)U2ICs9)-^ z5Tv|u_lpPKVLFne05&uA>q&_#y73 z>f*l(7h|lgxY*|sy4!2A$-xioC&_HeCfZ-;K{#1zSsVPXc!N8_MN8YjRLQTENnfNg z$bf8SfCH&=X!8r9TJaq%l;INcfp~YiA*H~qnzS{U^GJhH%&L$A3KjhgUYs3bxq3VT z%S;bd+0+=gzws86{hiQ}BwLYZ@UgjM!T7h1_|A|=40OUw5$ASRt;W=S#8Ac!K*(Ab0p=1r9l zQEF5qmH#R;M)S!q(r09~h&n?%@+mN5U`SMU^odmPhwc^P0RE=L1-NQL zc#2Ef;yd4*m@l&4GKn89k|s0v5#`UP`Rg({rOiHe3w%*A@S{7Spg|E)OF>gNcmYoz zO*$-%0dhJh96p?Q3+U;ycp>h%Cl=$JDMbRWwM^OPrlP#gE`@`%2tiNZ{Sw_fkAVjmd~yuWp4@)x-L&RH|hG)Z|OnRno4x3cm=@ONTm)85ib9 z(pPABb(MV5I_%;0M0>Zd(6Wfz&e4;0K~gsXPsIiw@=#H+SYfNb;-YYV@={Y5B(s?2 zWX@!14y;ENU3}-Y?|EoJ;n>YIhL%P#DuHN{Z7;n9USw-C$s=VUMWg5Sp$9LgA?-VR z4OX>AbKetU?y-W6ZA%iPZaN&JvSVrnN&1U?mE_<9Z72tSz%Gs)Ut_&ORk>bn&c9=Yj!M&dCWh0@)M8%?#%6NlAabxO0VpMm%Z@b!e zAOOWZAjaJLgdON~GSqzg-BBfKrj$!~HwATyFoT6X`Cu>1n?rvMJ5buYA3Uo6T4s5~ z{b{|P`wl_fw{cegk5F~Hb>slA6Al`zd z*%DgaR6913I@s={^f{VVFMHyOmzER3;4RoPetr#m%-~b=`FEy344VpXBorYnN)|7g z1@Q2_Fg)I1Y8=YEadx~eEY;+&j+haP;`BJpqN*DrRd!T*l-~t z2`aIdt&sS;p&_p?+;h1?1^B`zUL7W#uoVb^y`#E|e7gL2scO@D-b1qkutP4K6D=jQ z{gkf|5mtURz4hz-3QQ3vpK&~QdS3VLarveNR275_7;dH27Ag;Y{vnNORw-MG(MfSW z^sIV=`+Itaq8tfioVn)|d&T}_Xvug$8*@9 z*S@a3ul?xp>SE6Y3&^X-!02NhPl#}mvVxgp>3*1cUy*|W9b`| z!dIS?)CrhvrJ;ZTfc?QN|NZ-~r;($(pY+;P>t-;i04*i6-OEU3uprpxdRB$JHT>IM z3Fhr7u3MpV_vE!cB__~i106H2Q0J{u5b%UQYiScIZi;LF(rxrk`4GX6A2m0(Gv6&b zRhJJAe1yxBMsPq+l39|$S0g+?GdWgZA;jfDk3SE6f~=Wd%~HoN_p6;FAqK%16B8rL zkI=N0msx!7x3wT750ea<;<%vooWX-uOr5^gkuFQgSiH~MUA75qwoPv21{oYa3AF(8 z1&1+AQ8|W(B~UJPUc*X<;LH233?U71BSO?n3rYAwbqe0Vepu0=LRty5(plwPO=Q4u zK(0H_v6?&mS?{8|scS4Vdo#;%(cWm3aaQ{zu=jNmCq)7C>LT(Z)*uf3WKa^4gBw#KB+{-}o@FPg~lO%EFI<0Vw3nBqUOSJ4{Y0@X; z;15;fG^;fAaXSz;x1PK3I%m4SIvxOGwfptaM7y(5| z8AFyU12pM8H^H0ZbDVvx~V;nSdIo#HALkz@;L3fa&44( z`&^Y&F+6uiID#tyYn#WJ{%}Fy@=VAc+{gu!1sW}4v32w8IWlyOD0jPr`Wdo#ZX~a& zgvdwhM}8J4l3CjEn0_W=n=v8`ui4?b-A!%9d6Q{D%UT0}V94&vV7d63@6r{SkxF{z$o99{5(eb)Two8)#Rn$If<-W9$NZMYQZeW5mG9V51| z0>MzJ3*A}6#0ZaCUdgnD;Wt8ezM6b$e%Fa)=(X#Bp)j2YZ**J2^ zSVfkhPvc`cAaMAKi*(3?Q~#YZ+Y!=FOYv0AH5=FVtLJM~Xu(B5SELn@7;i~^lhlr2mbU~aT{^7cBYb?$^kMqE^=sY~{J&8Z%KXCb{fO{F z&bXblw01YmTUEv>e-q?y_qDHm$?Z`6`8>$jtPmBUCeU{uI* z+)o+^xC?jn-X8-)K6Nclt+ZiV{FAli&Q(3>BKFR)m0OHx#o4Ep_zF50@$`(Iq!08S zUo*my1ouy*C9T@L#(pU=6}}|JRa-2oA2R+__{M_z0gqBLjMp5;lS__jvN9nze-N}xuEEvET+JV}7i;G!(B6cM;(Yp&&|sBO!GA^~H8!yP%w9m~ zNh%+TLU#=J@I9^p?aB;WieAm5gx2#mRjFZ&A=zNrko6RbWr|wLFs$Ul1rbiBoN1Ii1&LqqUB|pVk>s`s zZYzHnZU}jfs1jl_c|~6$q+I{~Anpv=v7HKU*Z%mQ;6Q!-Ns`02gijX06yHc9J*Nabf#}S}{ydDl;8fT{+NdjJ$7ka!R zZ_>5BV^!};KO-%#v5C~Eam0KwShBnKZ%24LV|&ruq*=l;#~P-BVXfuMyo#RVyq54V zgie+MP0>aYl~7j}b%0kly=dbWu;i@$zPYhF z-~>iY*QA5L!>%;a9_kcd3DiAz%bU7%0 zlgt_v4c1f%&t%DcyF}1tXy!Y?0m>el(F9*@x(K`BZJq!i2Ka2*%=-lIXqhY3_KdWl z@CO#yKq$+ul`ILkKT8Wgsv}N0o^2)N>-ss9INg*B zo+k}=0o}PKfc8q{wIsMn=Bt{x@XPZARk+>Q&XSG?7)s`fp8pN4W;Rvw&3D`_KCGv1 zf)vBqu%dg%q#gG>qo^!T2I-!judD(iDGmZgxvoZPxXXPs@fd$_2pcI+~iwI zxp!jh?fP*YE!i09*$fX5Tej@DPVuE+>fG(d6624WN;}mZ-Hd3!-<@M-O zszC@QH1H^VWGl71*u2n2(WW%W6cBMmOB!Noc_peW{xFQRjxX3ULSa`zX>V2Z+S!x_ zmrb**+7WvuK$2It9%w{A)IvWDX=lyT>K6^}+*o9-&M7)3#p1^oo36=`*KICPEbxpNSY=xvs_(OH_hXeHkf4zU(o*YM%-S@wZgWywcBmDp8{%6a(WvKOSW%c=sf1B{Dv7N(a?xC&qpDj zLRTFGO4SSSh~Hib{wbe0dZX_)U_lVr7&)>79`aI9VN}GBMJK^<|8BU%wNuYPPHU0y z_Sdr4iyVIn6_t}cGO+W1C-Z96C0u@$bLhWu^idlgYe>>$)V5ey!ZX_Kn06Ki-8Ex@ zIM;XhlIo^$$UoSjBVI`CT*^DbSK{JR_ZCTKeZ>AB*!tR0z@ajQBY>dbFZx4rinoCG zue9c9@=U@+SF8xxn7J67{MO=k05rbCb?S?$DSHulvzXlj! z%7sxu%GEev?9Q6|qw4xs%wQKu4+;3+LQ&x7;|SqMD5}+s5yWa_%Rg|yCO7`_jyz%B z4)DV|uDhgfZ6Y-eu{V=Z^*wl+5%J2dZ`d!kZ<*WpYeW0nmHciR^4wW^Tz5DsHv?VS zmdY6F$punYrF>(Tc4+GuQB@mB9mp6PH7|9f`cs^R3@p}0G-@hbTEGh^7n%#gvs=UZ z_B7ix)t9V12XakG@}bqkP>c0_>3pwr`u?pV-9k4*fIH_s_`Pba8rb~jPZnfhA&K? z^bbX3Eulu&KT7<139LQ15d44VrRh9xg09StgLu6JmoZQMs1Uz-WJp32>8>yLklx&& zpa*kBiX>&3H z+k}ydg;3w(ETxBu9^w<(Dm7)qH{c8rx3Wg>QT;_iNgTVC6Y#B7GS_kj0Y_o>H!hLR zEg(KsN)#G0=p0BR`+1oi*rxrDB3!I#&-;NGgI!j6e>QTx)X=-yGuViT5QkCGG3v1P z@s_P$+vjqT9L^FEy}EnoevsAxdwLoWSuSPZWoz^*qW;l;D!|(ckALWY2kR>EPfDRp zZVFkAb&n@8kN|YVygj+tyLv@y7>~~`4umh1SBK|R(^R`}WbDPj(G!M>lT0&e`JY5E zeo&&3B_EwH{X6A^g>_uYw6HFGR6X9p>|2Y6-)#}Vx>CtS`hye`3A`JZbINxSLC3y# zKPIP0$*}fKPaKN=H?YPzP-D89uxo)FJioKsKg4nt-Wso%IzG|C=Jq8k#uWQhHR-ro z{P*I$k-W>GR}(5SXm<^jwuQ|j@uENMb0xy1%JwxVk#=8ZmFR^`u1(xocgAihshy0f zPban1Vgml}NTT(wT5u<*r%v8z<>Z1(R@iC% zQmcR7Lw6g9m#|myP%~!z;pqal9Ia^@bN~?hTBAob(B-zU@(x+!W4t)_kvFd}#BFmc=v25X%T-}vTX)3E*>hu--7=l+!{Ig53v`yxxl=|A zI^pK+q6~kKBWysc2s}~m<}8m^a&*_)@Y=gg5VYKUrH0~GJt5cMclIhCN|lRvtnrQy ztKMUYA4_^@M(`wy;8X+cW206#Rj;vL$N_EN)oitQd;gO>#lC+Ef>%6q6c@+G!}4Qhy7v{F*Ow3Cvss+P`uW?r6E zX>X@V#OL<;u-QP+Qi3GLaI^*~sWN;#6dhaHTfBJ$@+Bkw>G@O0tZo?T6F=i-`RFqJ z!+ZDg@O=DaOC;Wz&PpQu(6&bt@|{`#LgzHOztQZFhpR*zwU7|73VHiLUQEB>I`ybYqB6aHrwj6z zc=%^fJtvhfkdu>FwtRW>)BAb;E+Nays4G<-Wy( z4j%GL<{Zegx#!=)ukp3I=oM23KjJ+NvX$e-CS8ghge3CpqC9UrR zt2!DF2VnJ`z%Xd+6NT;G#u?$J*{d{UXEv@`c%5E;eHP`TM2w|HOUGuaw?sUiPS>Ok zExXG@kP}RC2!`cZ=Be*V%GhWZfg(~tm=IhI3#wW&?RL-a8?`(L+rx~SPQkC)4I**m zLVRe>8`x1e87%#|2^;~QiW-K_dUbcLR808jec~*%8}y^uObj{Pqfi`UlEH2ohDiN| zhVmU&5ByDK%Si4SwUJnL2Mmd|#7yAqy;<`x&KYh6K=k9hTqLHPJ|BmF*d{{p8W=5e zOHg4Tzp#)S4bRUiJveI)XXkugxH~`nTBdP6w|C+np0p-NKdN#!R$byt|O@z z1~I5(e$-i@Z^yZJ*MA< z8w}gMPm8l<3yb-M1A+Jy$Map|?C6?SdZg}eR&N~f^i)_m>gL@f51cuwI1cZGnW*i9 zGUB(rrD*0cUjchG44moFm;qJ zuh@3i=yl=PZF{g@IJA27Q^tt6a5ixHDASE=erCoB;iilQ z1{I@6Kz$&kV>D(<6)@Bo{>52tb$RQ7HZ~^QM4ZRmFcTc^7C7YloiR!CPxz2x!)_R+lLk%8pf~ z?p�FRoWYUO`jKEm!`Ea&N|H^PxOQo`CeWCPjGP{vQ%TI2w`4(`{>hqhyGibctn* z?Iv(V=)f3mSE#kfN+OXf|4GR9abaHs&^E0ri$RdmpnOR+CQn)NnDMn=@ zm4X;{yM~tI+EZQhz|Me^Mu1qYfz=5Tr1A02J5Sa^-Y+ZYIiWr|xopS6qGRWDGB;(t ztJfVT9mwg8S^IKB!4}g5%^Yg)OYTdRoCIvyU$onGt(pz7Jf@Qj{W7Pms5iy}5ecQO ztbnhsopPAVdBqD_m1#;7cD9p(MYBK}wOtwba)5^JQUy7KL^>DV;9?vlhGL(DzEe3<)@ z+exNO@^|F)CzG$!YszctotM7TKEM6s)zt(>>i??@?-B4K@wOA{IGDF!bNOV2d-Hm^ zGDY!yP5pI~Z)6SmqRXH*!zB8r_^)pD0pZVlKbR|&Hgk5*(qpU8*n(|K#~F)8S6=VX z^C zCdxrK06HkfyZOeyW%A_;!*TIteFJ70i_-FfJ><~}8+o6{l(x-itXBxxu?e|Q^y4(- zu~>0V`cL75S-n`u#{bHrp8@#1dfrEYiow6%TG;#2rYwWHMz(=fGwzOQ-VZHTU37hq ztGbxLF*&U(n|PP8Vz>`N>tP3&#)o4ii@(rzecBt}^e=hvDtUJ*lYWhH^z@^}K37oN z!g)@e(YB0l3Ejf$bM3qm$ysxAx|n!5schSg)r`O~&P>1+8}R_8{|ee_^HaOW5Rs0^ zd?l}Ox6&3C7fG>ll-qi}>C>tvt-YA;_s3Vs%RqC(xnWqgb56nVn=m3l6RKwBl39u| zcM&s?WIMM%u|CZY;;dlrA(+*N8}>gfA54D<9*Tj);->QOHF>X2@$glF_Em$+Rt{(& z(mkj4QG93{an!a;pOA8{=Ls&=qo2`~fw11tK5uTB(c!2&dIC94Da%WbsA^c$qudN4 zJ>}ht8pofG{d>NM6F?2yR!aJ&q?5ZCIQlJD9{vD~f=v)yw85vfvoF_9mm&MXzWl3v z{i;WuZupUWByUZFTp3T4XAMfyb`duolK42zeMO-~24mNKrUmVfhSq{{j7+M!R)lgr zE~)%{vLwB!jX&?Sr}jtn!;f~|9tb3aI( zq;i2E4jL6$sN$BYE*wg#y6GM-zI}eRKe>b94zU6Ur8OHWka&h(+TCLi{d}MM&W~ZE zXz%L%;D2@;0FiVf1S?y;fq}6^yH?VWg}gA1hjMrsM*=)Ar|DBVYGFy2EA!aqF9qd= z_H_FzP7>2AyIt`F4L|$@{7a-yjgn-K*gF`s4)2088R1*+G)Qc+yR<6p%}~QTm;yy3 zLBSfKOx|7!afr=pF^8(;qwz6?RqN|mwAD3_ZFCP@?{YTi2@RpO?~`}>XvvLmbbQo7 zJbR|E^-#^=U`V$Zf~m?eRUat~w^`g2H;`l-m|MT9^PuS8Iu*jVwmd$|-COnF@vCPK z9v?S!Sd8l~B42iRzu6Hw>sx%C=eK)odELY>D7V`KVXpaYNmouEKr$jg=}pbjO6K0A z)Q~rfmG!i&S)uH^rf);)M2Uq5)Aa|N`YuKKh5~ZUNooV5JwSs~Vir+?_FPHLkD{oB zp>>x%-xGLUU(&L(njl2n9(sx_2056YR0_|a3P1Xz+BWRny;-p1eiwK)oPmY+^_P3| z{_E73XzCNPq`NI)1fPU2OK$36&Z6R$b#5s>NpPZ(|0%kFEY-!yc`h%#T=1tMAIdrm zqFndnorQe>H05gQpC%EMP7&fRH9O)32cnu(o#c37D~50s253+;cfnetbqt69blmZw zlbcy)tnjiEb9^Tj;(%zl>I-x_~Xbo>cyKVMk|hv zJ(kE?y`a~MgAI;Prg{O=5?A-us7npn4m(4CS7nu@}|te82qSeZCS* z4}HKLvCh<`?13*>f=s;KU-2Vruyi;_gZZO**uDBaopq*!cBMKB!_|qx5R|p0YDHq=C1>cju_UK5Eg~NMXcb*~1n1;xFdngQmgkJKX}&$?vUqDV_3k zo;H&cDBREXj}58a4HLnfRf_6t=|=2YhcIg8tjrQkUW?s)|5Yb1pk*jC`B6!%xfiGO zx$II(aX%FdoPqyi!j!kBJeozCt3*Mi$d@_;6-`-qsAIQU(;+*oy(CXy3~*ML#zXnzcIJ^thys%gs8tZyyBZ$AO~pB{ zA-Slq4c>j$vga>Jbg!SoAnUATr?rN$K6o0KFw&1E_I;bLzUA z&y|Q+v6m35=?7H-6w6kMgp!&RyAInvp~5kZdoDMu$X!J+M&%|Yz+daGz!t?mbU9rEQjTk)SakmP zhO?<}nMwZTy$gPLdJ9tUI!O!a8-G=ttNJoad6|{z_`Youx)3s(SmvedZwN+W)kK!(HY*J0Rh}L?IN`_%RoGWRi9URz zu-{_jhHr6Xrkkf;DS2t4eKkRthl>PKjQaL*GT1N<%m2;uY zYh&81C_tmS@P$TXX(o#5H>+07;P@q~ku|f90pKxcz(|bmOV!d|>8&ep(qu z&VTDG{e@3`%|HTBa^a3`uM^P|Gcx6kXQd)hllxGmSMlS@k7q_VxY*8EQ2}-*vFF|U z2GzOn+pQ3Xn*PW4_K&)kC@e-Z^$#hx-~jvh1EDkXdR-QX(}gKg!z?K8xDUcyP64xsV>EAu+Z4 zwB3U<|6qW;$9v`l%e|Zl@9Oc3THpDXm2st6aWGvI6O)C7{n!J4=0%ikW>FTH{7>|p zY}o+v4tBCBM>fHhXUADduVtxt%JsC`bxJj$p=M47l)rLYFyKzin(CdQrvo;i0q+pV zX@dtLO`}<_*05H)hCdB`{E;E?iaY*kfNtm9a4hhN-WH-og-Qpo4$To4zS&sy~$&szl4U#w=$u7Id7n-rHiv z`qMc4887@jKIex`jl}FD1SQcj=d4QP4?KNhGiq6^tuOH;7wAtq&__SJKyzs!;Y{3| zI=_H`ti$~GS5q^cx9p|@4}NDhKRxlTemwEJqgulo6z}N9gD%d-(#UQSms+%B)yxD= zU~Uqus#zSr9$}f!{E@Nagm6pX4A^LrAcT6o9I>LwOfmP5OtADji+2>$&zCdZLpmGMSD z5zGkkK$|g%@Trw|6l=;{t=+d-fX0I$%-a_XA;!9a!WgmN$=+d9{*ITQ^k9w^` zoA{})y}gdiLVRe=-O*heNox|)P1x5GvP-}mq(4XSE%lS8B!oNJP@#bRJUypzO;V;{ z6E^#`C;JhxkoTK3=eB3~8fob+Us4g)zzg^HaXX@08(M#OaXv9MXCM$VyQAcyDreLG z{q^OecK^JjKWADqWua!FMk!H&dS|oKI zzP=H%?o%xEE!FhZ`kbkBT!eRwSRs%km})N0Pj))_kcgE63^ocvSGSgAV6Ng+w|+9V z-vDeN&Flej;D_m;A2P8AV|_a=-No+DLE2MF3$e#`(CRyY%a(fT0Ni#%epD$R(!62F zy+Qnvf`j_xgbyXQ^Qtu>LVKS!{3i;U)(*}SC-%-l8dF}ZJxO>>J%pZ)^NF0^C~jeR+1PVo^JO>ax^tTD zb=X?13$+UT4OD$h-vT`Mjz7(LZn`W;r^2kkRouKX8RQT<_ANU%lDpe@#zK`Wy5K=A zcL-T-TatInU%0;6!==u?sa>O#J9wfpp*A@0=YU8&8d*cn@zGv1R+c?_e6n zh}hB88N9((@*BV>=v%E4kYDyjoWRgE75#kpXuudJYJlxPKz;?q1qxbu)v{j6|Am^afP- zY6w0U5*F0*d(*i{vQWB|F0}ov|8Nb8H>cLEDk#O!x#gIDo;G)gKog&J6{Q!hh|7m=3mKFjfoamHGkYzcx-? zFW4hAFWS5WfY&SKDdC@8t + + + + + + +MakeBlock Drive Updated: src/MeCompass.h Source File + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeCompass.h
+
+
+Go to the documentation of this file.
1
+
47/* Define to prevent recursive inclusion -------------------------------------*/
+
48#ifndef MECOMPASS_H
+
49#define MECOMPASS_H
+
50
+
51/* Includes ------------------------------------------------------------------*/
+
52#include <stdint.h>
+
53#include <stdbool.h>
+
54#include <Arduino.h>
+
55#include "MeConfig.h"
+
56
+
57#ifdef ME_PORT_DEFINED
+
58#include "MePort.h"
+
59#endif /* ME_PORT_DEFINED */
+
60
+
61/* Exported macro ------------------------------------------------------------*/
+
62//#define COMPASS_SERIAL_DEBUG
+
63
+
64#define I2C_ERROR (-1)
+
65
+
66// Me Compass only has one address
+
67#define COMPASS_DEFAULT_ADDRESS (0x1E)
+
68
+
69//Me Compass Register Address
+
70#define COMPASS_RA_CONFIG_A (0x00)
+
71#define COMPASS_RA_CONFIG_B (0x01)
+
72#define COMPASS_RA_MODE (0x02)
+
73#define COMPASS_RA_DATAX_H (0x03)
+
74#define COMPASS_RA_DATAX_L (0x04)
+
75#define COMPASS_RA_DATAZ_H (0x05)
+
76#define COMPASS_RA_DATAZ_L (0x06)
+
77#define COMPASS_RA_DATAY_H (0x07)
+
78#define COMPASS_RA_DATAY_L (0x08)
+
79#define COMPASS_RA_STATUS (0x09)
+
80#define COMPASS_RA_ID_A (0x0A)
+
81#define COMPASS_RA_ID_B (0x0B)
+
82#define COMPASS_RA_ID_C (0x0C)
+
83
+
84//define number of samples averaged per measurement
+
85#define COMPASS_AVERAGING_1 (0x00)
+
86#define COMPASS_AVERAGING_2 (0x20)
+
87#define COMPASS_AVERAGING_4 (0x40)
+
88#define COMPASS_AVERAGING_8 (0x60)
+
89
+
90//define data output rate value (Hz)
+
91#define COMPASS_RATE_0P75 (0x00) // 0.75 (Hz)
+
92#define COMPASS_RATE_1P5 (0x40) // 1.5 (Hz)
+
93#define COMPASS_RATE_3 (0x08) // 3 (Hz)
+
94#define COMPASS_RATE_7P5 (0x0C) // 7.5 (Hz)
+
95#define COMPASS_RATE_15 (0x10) // 15 (Hz)
+
96#define COMPASS_RATE_30 (0x14) // 30 (Hz)
+
97#define COMPASS_RATE_75 (0x18) // 75 (Hz)
+
98
+
99//define measurement bias value
+
100#define COMPASS_BIAS_NORMAL (0x00)
+
101#define COMPASS_BIAS_POSITIVE (0x01)
+
102#define COMPASS_BIAS_NEGATIVE (0x02)
+
103
+
104//define magnetic field gain value
+
105/* -+-------------+-----------------
+
106 * | Field Range | Gain (LSB/Gauss)
+
107 * -+-------------+-----------------
+
108 * | +/- 0.88 Ga | 1370
+
109 * | +/- 1.3 Ga | 1090 (Default)
+
110 * | +/- 1.9 Ga | 820
+
111 * | +/- 2.5 Ga | 660
+
112 * | +/- 4.0 Ga | 440
+
113 * | +/- 4.7 Ga | 390
+
114 * | +/- 5.6 Ga | 330
+
115 * | +/- 8.1 Ga | 230
+
116 * -+-------------+-----------------*/
+
117#define COMPASS_GAIN_1370 (0x00)
+
118#define COMPASS_GAIN_1090 (0x20)
+
119#define COMPASS_GAIN_820 (0x40)
+
120#define COMPASS_GAIN_660 (0x60)
+
121#define COMPASS_GAIN_440 (0x80)
+
122#define COMPASS_GAIN_390 (0xA0)
+
123#define COMPASS_GAIN_330 (0xC0)
+
124#define COMPASS_GAIN_220 (0xE0)
+
125
+
126//define measurement mode
+
127#define COMPASS_MODE_CONTINUOUS (0x00)
+
128#define COMPASS_MODE_SINGLE (0x01)
+
129#define COMPASS_MODE_IDLE (0x02)
+
130
+
131//define others parameter
+
132#define COMPASS_PI 3.14159265F
+
133#define START_ADDRESS_OF_EEPROM_BUFFER (int16_t)(0x00)
+
134
+
135/* define a struct to save calibration parameters------------------------------*/
+
+ +
137{
+
138 float X_excursion;
+
139 float Y_excursion;
+
140 float Z_excursion;
+
141 float X_gain;
+
142 float Y_gain;
+
143 float Z_gain;
+
144 uint8_t Rotation_Axis; //1:X_Axis 2:Y_Axis 3:Z_Axis
+
145
+
146 uint8_t verify_flag;
+
147};
+
+
148
+
154#ifndef ME_PORT_DEFINED
+
155class MeCompass
+
156#else // !ME_PORT_DEFINED
+
+
157class MeCompass : public MePort
+
158#endif // !ME_PORT_DEFINED
+
159{
+
160public:
+
161#ifdef ME_PORT_DEFINED
+
166 MeCompass();
+
167
+
174 MeCompass(uint8_t port);
+
175
+
185 MeCompass(uint8_t port, uint8_t address);
+
186#else
+
195 MeCompass(uint8_t keyPin, uint8_t ledPin);
+
196
+
207 MeCompass(uint8_t keyPin, uint8_t ledPin, uint8_t address);
+
208#endif // ME_PORT_DEFINED
+
225 void setpin(uint8_t keyPin, uint8_t ledPin);
+
226
+
241 void begin(void);
+
242
+
257 bool testConnection(void);
+
258
+
273 double getAngle(void);
+
274
+
289 int16_t getHeadingX(void);
+
290
+
305 int16_t getHeadingY(void);
+
306
+
321 int16_t getHeadingZ(void);
+
322
+
341 int16_t getHeading(int16_t *x, int16_t *y, int16_t *z);
+
342private:
+
343 static volatile uint8_t _keyPin;
+
344 static volatile uint8_t _ledPin;
+
345 bool Calibration_Flag;
+
346 uint8_t buffer[6];
+
347 uint8_t Device_Address;
+
348 uint8_t Measurement_Mode;
+
349 struct Compass_Calibration_Parameter Cal_parameter;
+
350
+
374 int8_t writeReg(int16_t reg, uint8_t data);
+
375
+
401 int8_t writeData(uint8_t start, const uint8_t *pData, uint8_t size);
+
402
+
428 int8_t readData(uint8_t start, uint8_t *buffer, uint8_t size);
+
429
+
446 void deviceCalibration(void);
+
447
+
463 void read_EEPROM_Buffer(void);
+
464
+
480 void write_EEPROM_Buffer(struct Compass_Calibration_Parameter *parameter_pointer);
+
481};
+
+
482#endif // MECOMPASS_H
+
Configuration file of library.
+
Header for MePort.cpp module.
+
Driver for MeCompass module.
Definition MeCompass.h:159
+
int16_t getHeading(int16_t *x, int16_t *y, int16_t *z)
Definition MeCompass.cpp:391
+
bool testConnection(void)
Definition MeCompass.cpp:214
+
MeCompass()
Definition MeCompass.cpp:63
+
int16_t getHeadingY(void)
Definition MeCompass.cpp:327
+
double getAngle(void)
Definition MeCompass.cpp:237
+
int16_t getHeadingX(void)
Definition MeCompass.cpp:297
+
void begin(void)
Definition MeCompass.cpp:172
+
int16_t getHeadingZ(void)
Definition MeCompass.cpp:357
+
Port Mapping for RJ25.
Definition MePort.h:128
+
Definition MeCompass.h:137
+
+
+ + + + diff --git a/doc/html/_me_compass_test_8ino-example.html b/doc/html/_me_compass_test_8ino-example.html new file mode 100644 index 00000000..57cc25a9 --- /dev/null +++ b/doc/html/_me_compass_test_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: MeCompassTest.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeCompassTest.ino
+
+
+
+
+ + + + diff --git a/doc/html/_me_config_8h.html b/doc/html/_me_config_8h.html new file mode 100644 index 00000000..306527aa --- /dev/null +++ b/doc/html/_me_config_8h.html @@ -0,0 +1,537 @@ + + + + + + + +MakeBlock Drive Updated: src/MeConfig.h File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeConfig.h File Reference
+
+
+ +

Configuration file of library. +More...

+
#include <utility/Servo.h>
+#include <utility/Wire.h>
+#include <utility/EEPROM.h>
+#include <utility/SoftwareSerial.h>
+#include <utility/SPI.h>
+
+Include dependency graph for MeConfig.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+

Detailed Description

+

Configuration file of library.

+
Copyright (C), 2012-2016, MakeBlock
+
Author
MakeBlock
+
Version
V1.0.4
+
Date
2015/11/03
+

Configuration file of library.

Copyright
+

This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+

Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
Define macro ME_PORT_DEFINED.
+Define other macros if __AVR__ defined.
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan         2015/07/24         1.0.0            Rebuild the old lib.
+Rafael Lee       2015/09/02         1.0.1            Added some comments and macros. Fixed some bug and add some methods.
+Lawrence         2015/09/09         1.0.2            Include some Arduino's official headfiles which path specified.
+Mark Yan         2015/11/02         1.0.3            fix bug on MACOS.
+Mark Yan         2015/11/03         1.0.4            fix Segmentation symbols error for file path.
+
+
+
+ + + + diff --git a/doc/html/_me_config_8h__dep__incl.map b/doc/html/_me_config_8h__dep__incl.map new file mode 100644 index 00000000..b84ee273 --- /dev/null +++ b/doc/html/_me_config_8h__dep__incl.map @@ -0,0 +1,357 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_config_8h__dep__incl.md5 b/doc/html/_me_config_8h__dep__incl.md5 new file mode 100644 index 00000000..2db513da --- /dev/null +++ b/doc/html/_me_config_8h__dep__incl.md5 @@ -0,0 +1 @@ +03fb563ed9746f66c5f30a17a48549e4 \ No newline at end of file diff --git a/doc/html/_me_config_8h__dep__incl.png b/doc/html/_me_config_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..7ffdf6e22e92b08a64f056557e3d069fd99134b4 GIT binary patch literal 745762 zcmdqIcQ~BiyDqK-i7rv21wn{TFbtwg2#MZ%i5R_(-s@;d^cI~&4bd5Oh%%Fq=nMuE zbuikfCwu>X``X`g_Gj<^&spyu?{(epy4G4VYdve-&wB1B;kC9p1?fXlJUl##7aA(M zczBH8@$m3p-zENw;O~Vs|9uhLYO1T?-TvG2sk`z69^NCo7b=SS0r|U2uWAIgLXc;e z+v6U5}onUo}^)A(DLyr=e@K$Dud4rAG^?`H84otN$F3IegfxLOp75gd8}yr z7@yXpkfV(H?k>^2JDGwB`qAM@c<}z^$IEx{l}IWA(3DR5`Q8}t-u`EF(GXVO-`Cf` zzo_+6410;kaF)Nny)Cn3fw6$H$NxW2MzD^EAOe+tD3+4Qt4*m}3xDWsSEX{@`nnnN zV*0G`Oyz(0)xnt*g=csEsX`Y>>F%vExBPPbN>?-d{O;a`5*q8{}I~H ze<}7qR``dH>+t^zJ6ab<8{N)Aai{FKu!{+W!=k|DDK8657Z%=syA#_v8n6@Ax>bSd z-rH*b+m)|L`sPpXk+qtl7-;nS1N!TBE zirA}GVk;8TR76nXKTPz0K=N|^*h0L2Sp4Y>5fQ6bW^PvqlxATt>hgvcdERq-;(nuy z?5;%zpbPvRZ|7U3ZmphyvO2~~-=pe%yHsUshkZX}?aY$cg z-zP6hrBBAcUM$K=bi-xb)@|T7r7U})fh#g^% zWQblHUs&3Dj3IS=Vu|g@Ng|m_=TJ6dav^RLd?WSk>ips@EF}Q$h~j5G7{-FV=V$1# zsXa4kQ3a=kyU^(%*?!#9UMt+skG$?-Na)_}PFN@kW8Ff=W=JOw(gpn#C~d3NP5#pH z-Ftc}#0W(aaArZJa3gg-#E9GTKIb&AWkl^^F2e#QDuu%LT;#-bP0}+-D1$7+dxCaDMa>*XoVu)m2OGKI_|nl?0VA|SbJc=I>X{lS`c(c9p6DA zVofl~!$dl(RaD4dsOwLWPF?>?xKiJ@#H{(z#0O0jXv8zMbY9h6^HfU{I_aL|!x8Ms zA;1ZF-SO)0R{Gyq$Vg?>KkR4nc0Grep$!H;Vg7Gr)E5T>|ADL7!}t!uTAi3GDb5; zlr!dnYUv66{qW>sFzOISZ@oWOpVRlLkl%Y;@4V+H%?gqn=Rd6RfT@dXcd=m3%DSZ` zjQ}QMf^}^mFlO#!Ir6S=eDf(7@x1Uh$FpgDqi%SH3tId-b%)Xz)osDIJb^`4Tp&EG zZa&mpU*Ljg>pUgmL|qo0woW$(#`|WvW54V}UvepBjmSZ6t1c#?H`%3O!R2u+nvV+A z6NnmG;@74|!#1rJE`LImUUdDeTxoT4jga#9knB-E1i9#(U90@xUp-wAsW-jis~A-e&Duy$4o%=5A7Te z17TZ}a^QGBikuW=nTEHrzDDT8Y?tj0Qm|^+7^YzHGZs+1>$rrh_hdBQW?`HZ645~Y zNy=dDtx+kKo3z0ia%DVev%~e&8C#W>T5}-n3J@Pocq#zK>gh^~Ve}2Pq%80lJd5gd z;(%e+<(qb{aCTjd8>MqUyHCD{waX8Co>oDxgD^!*^#}R2yda(7-F*bev~`5oG8#9~ z_xZ>aKX<|w^7phrx6?Y9p8$$xe3o0JugoK$)J2cd8O*wWe%)GJdp=tuX**R{1@oz4 zuWvNz9Lsf`HeYc_Y8AR}J{QrB@M#KYMhz?fxsYK%4Sn+qR z#laXkunC|O3Hg&giHG5L7#XG{_iKdP$!?7(&G^Wc%TAphwEir$cQzgFCX~kKYV-Cu zNq?}HlK2dG!e1)`5_`-lKHt5awC>#PA;oc;BCCnnfb_MHkO!bXmr4#d-gx>0XX;K^ zn7oH4+zr)MVpV55_EFfYZ-EaX-PBvPpN^QPeM}!o?=JbMiCY0EI*HBv+qr)l1Nvydo~=f$7y*Y3t2VysTSnf8+sP8b$#erfZ~qze}16}o3T``-T;-xz@)qbgNMbelkR_Onrl zm~Gp8m|ca~e55qK^nI&f^%T+xSZZ1GBnv}+o-s*p{~D1(b>*cHCw1c@*ZVLcIvL@r z^@>-(K{?2!rvZ2Cxf*+l#nn(cN`{1}a*`GQ9K$XJM{c4(%kCCf$#9a)&4p9s;iQXj zYhBa*bBOnO7_q|5urg)c>9g^?kFS2ET1ch5irvbqs2i3ai~RScsy)medK6}%f0~6@ z0_(AZ)9LDDqQ+ZE+(Lda%dJaJ+bucJO&{u^@w#=~o&Af0%8oPpy5C;(A1Qb9Who)E zK5qv1png%__jivDL=UTV@s2=c^W}`^*^+TIbnU?2g3*xB-CoFh{SC2`O_bm(^@eim zg+H$Y)j5ip^svCL##fYqXA%qo#1AU_Vf~ZM1~^QwpiZ8637Rpk-1+Xbyqit!QDm>p z3<@1~F9_suwMF!c_4QI{@{7xLxgorybo5rZ$|LH8v7mc6aT62cz;4?cauVZn^C1{I zfU$T4dwd08Z8Bfk8Y{x!hhU(>vGX&RMqf;yO$%vWjD~*dZ1cpOHA+<=Irqmf>O)uE zBKiFg{Mud*DxBxm3)`NsRXK^uG6R`45oaG`H$t~shbU#$&hWk`-3E`TO}QD}R3Ps) zdZkA$s|`BCdy99CmtF0r>@sI;oDJKc``*?w32r*r(d#c)zg>vCF-xiqMqcP09Rvvx z=H2lQsYy{m9?=f7+WL9yl!)jKWwk$VKJmsWwx-1@`bc=|Uyy+i~*^ zqnj9|xORP0bfXVjMemad_t!^w%vng^#BAmTzoC+ZKU(DcQfiw!hzCq6m?tm2W=n6e zVy^XMxk`$U3dZKgxV-BQa=d0G&&}IzWY!960nq0D@Euz1-w+E(E%V2pix}yPj>f!w z_)@b9`ZF3y&&F)+wd7yh;n_IBz4$4OxKPMdy!OLsp5#;S7niS?Gb*LE8Yg1EjXZX1 z>w*v2GgIt{%=yTzh)~My)YjP~7%}<{9IlziHq2eR!yTT@f@T%JtG;n-A&1VQ))uT9 z^J=~S&l6)^9OKY6tN6dc>*WW@$g`;0lFP1LpS(9^3i(K$#ikNj@}Xqc)Fp26K9SVx zAtK5k4xhN|Ap7u>xGF}Lz%UP_p^sk>JM%>n+v40k9|kE9HA_qCSsYn=qkCQq)soXI z;;~d1C^$1@>UqYiNHa;&*f|kJ9ufg~zh;*LUhq43x$+-D-UC|lEl*XA*OVdTFjb?G zaw()NuVmE8Q54B%$`!3qm*!yKjVR=Ogdh`D_4C^>$lO;UZ#CDpjvc1$F;V#5OrsAH2)%LoVB4-Y zl>B_W$iyt$DzOXVIVsb7-i#}a4iG2$JI zjvo}*El|d6)1F<8f9+`Xb2(#wm4(D`6PK=3 zBk+TC{urmB1UhBcuTu@t)?4sNHxa`Ar}h3eR`n(jd+7-h|KJ=wUj=%qyi*3zdq zJ!rWq-L8yg3QVKK*t*)u6xt^VckU-{Vp>IaU9|^ZVW8iSn}k#cuxGL zj4gD9=c1y!wC!5nc4wSSlP3Ly13W@of(z?QDeQ{J1;m(n+DRX;dW1M-(7H%as zcb=U_IYRx(r#-W}@Ge@MyF{&g-OOrdb+%_Mcf+ukDX*G~N)Nq}=UI|bhOP{!a+rQg z14I<_8F=UH)hYXqV(^mgH#s4fE&;4VE+X>AY|Pgzl&M=tPL%7uiRo8a{dRlKe$ZVf zOTV-tiEEIxqZX%%OE(Lfr@K$cW`C5%{LGVDreAw^{7K^`A9AdN*-H;LY@^?;?o}Ig z#DazTM}|F1%GaUMX}1h(+~#io34y z5|^4^TOSI4e3oMw#KKJHUT2qnfUD{^up?sQ(zi@&~4Zia2 z*fuw|;|x3#T)M0*22*>#Y9FKQaeQc)u{E1})>Ih#dqL*18Gb$P*Cz>tE&KL%p(}BJ2@iUF+Qtd4!vPfXO@G>P76LAtn>Z()w-u)x##!`ZFiY> zFmrtp3(OIFnCD;Q?w$yL?8C4^3qJzxRD*0>aj!Mdms3bLt^AF(EO|D*q=wbTs$5ZS zR~PDn^m2!nx8Bd0x(w7DcN^EbfXOAY{-+@)4HM3?4HSs}&O;nty{m)(OT%ga1?AyB zMp1ymh2(e>Z?prbSI8S&p~O`YcPL7E!T8mVV`5 z>#?skU*W|y1%}R9uaxhd$Y+jPOPV>EEWR=Z=Z^s<7KMho|hTrd9azxF4 zZ3}=_TKCeLrxR%9s?zKMTu6}3xhSHKiNcGyeP3Is>3=~qYX_JatRjZ&IYJN|L{3`X z9Pyn^=l68JL%Fw_WT@hKCz{Hb^Ch%KphUXWark|kGy{FQA_w8%l!I3asSh?AqkI`( zX50#q^Y{ilhPRXOd%r9~D%2_C2_F1{RLdH4gGN`Cx$)!mMa2Xk_C0kQWLb+Z@2%3z zALIWj_k__J^kI}UmQmSX%?%(uH8(UjI`(;~i<||JUAaIuc~L)d+k!7Zk_905AO-`Z zHA?M2TFpk%jeSlA1h77uCk;0rDZGUsjGFKabt2N#gv1Yq4(N+WdRmk%N-7`yj_G9* zFDXZy+fu*EO%<{=l7@Icl!Sm^`8wK(817>qowzH>s2#IdNeoT@YmqQxu~p*{(6EKf5&f zIMe!%GwPgc5aJ1FQ81=w&3WEd`{rBVbi>e5S-W|*t?%4-Ae&swEJANZnGLavW|-_B zhkA(&CuA-cPfoc|3zikVz$#_T?D&E{ZTwg{&Jk7XR!oBBsHT*9+QO@uhJONJ()Zxi zB-);Z*@wUM&ZiP8ai}M1+GFph_FT1*x1Z%qPW*%SWP7|libzz~6>H9e84t>ob=Bt8(|sosdA~_uVUC;5+3>{tAL5M`tx}6XFym zh#7a4s!Ma59?`>LUivr+Y+qFk-TQrK1+Si~7u<<^SR&=Z-}1)%#MKX>vYv+PV$87I zdiQxZKJ2Y?>tuD;8_>HIQ8~BXD@IiZ=g!aJ$IAip%S;<~;nYd=fv?I{;ceU2v19ZrLAaL8(r^?C);dcl5Vc*W4ljG@j;Hs z)OM*rZfM;eCv~b;Qi&(qKzj}Gmb7O6egDrmiLhY!6ee^ja3Dx^-S6*0vh4aA^v%0A zOZl{RRwS7H35-10W5~gJ{n7j;T6wy_3}e4&=1b`fem^T_<=N9|b_+P5%*!18CBS;v z9X8}V-;{#kJ=UH&fe)XBp+9NL^tAuH+LO2MgLmLe(g*DX7_8`jF02A+_mUe zOm)5x{m_yBOH+iub^3Q6ZqmGupHxaow}1y~V}hFK7AcDx5O6mm(?wh40($$4cFHp^ zIhK3xo~vYyg)zzgAq8ooBKBQ*U z2Nj--wLeqk$6evJ(Vjxe#@E1|QQi4VCs$PB(OKx+w2+hP|LzA2RgU5RE3%$b6~(#G zI@6cFw~!O+7w*NzPKP7x%v|`e@Die_vvF?;|B?0!V@j-nb$NMzT)EQyaBFhgVPr00mj6S1!&eK8%AEU2 zXC!%XrbCWTN|`#{w%iM15-ZU6dRA305Z|-wdcU*0UiMX|bT06V)~#5%wO=LJXIY;o z7p$gdV=yb`lO*F8uiSLc+)olQ8i4uX0b1|bp^8`Ip4I4+?ne(-`Mp4{{t1CUP=eg=HqY{{OO1%?=<0eT0 zOi!XC+dOsGx5Vv`oW)|N6ZfQ51w4{=gFZEkgi6H5G(L!UEh=UwyZOT|PEa#KHb^w4 zWEr8@eR2g}sn)U)Cc%O%POur8ctS@E%G=Z*H2s0SkHhTjbCIRlg!YMD!4iZ?l20q{ zO1p`~`10 z8^J`+TwD*3Zuyh?`G$53|0Z*qiZ8&k&}T~k?&9n5)NNv+E>Y%u5k(S>kwwOA>q z7ZWy^R@a#(Gm-+a)CNgs+y>7``!b?!-#b2ECxZX7UL^k=Pvlfw0@0o$A7xb0UW{jp z-^Z>f`4^sBgDsr7hfBS{*N3vux9WQf^SKLE6MK`VEpNSLo7?y17MDTpc9N}vc?%!* z_C_{O?OgIadkWgRTm#BInikSDX%}@zUJmLOMVZ} zx1MBMwq{vPU`kC0UW29grOWbiFc=P{wPa9?KP6@?rJnV2ile1IA%>axFbrA{sQ1#q z)0r6B@9d2vmr_sNQmQ+$fY+-;Qa<AbGn&nr&G_>H_%|^-S`5`9>#cFOEACfUE=AD#_YmfHS+>Bj z_mKI&?F{vCSlv4)YCH7y8F%_-z|Dj(HR6k_+=H`{0o#UjQ$l8?&5tJa-V6=qH!?kl z)AO&8c23ArS}g(eeJ8SoJrdR->Fq6uAR^9eks{-D530Zcue~EHC*v1_bbzUVEF#r- zutNFhC5N6rERAet(hpAL0fI^QJFf!$(5URuSnY&-@_dwYUoYna9UBMLZa7se7!-{m z@)HzJvXccNHWiC-&j4>1{jGiDUHF6ZiGnX|1JLvn*1u`5oZ92v^JJw@KPJ5j+&08$ z*zNq#6E(e%?I#+=|Tnug|@cwBj6`&*uX`LhDo zCe!ZVMp*MWZ&yR}?#s=Ew}kF)V;gJtqaw52b-3->raV8}(nl{o0jxR*X@n%KhoGmE zabad%u6uRL{5g%&uO{tm0MC%T@2J)%Y>vd*Tttnas=g8Gax+3eD?0`9rY?nV!1r^d zk*lI&Z&`f2>d6waS))D=dw+Adw%ALOSH`KnWsgan&W(GBG3u^LP43(|stcay%n<2V z?YmbNGHuMxTs3oVAIsSa%(cc2cg9VN9rG9e$;(Sib$&(`gk=v=3rT^sHJjJ0Z3WCf zzP)w;(S}6R##@BN?%4g#y2F#1nt;A^Dz2y0*)E}p6Xjr+P1X1Om|6tjU0`5g01NtV z{#Ol5}c91S-_+2WFh3W{{JjSFcFD>U2L} zikTS&zE_=>|zR+7fH8T+)Sb_7gBK6*qZe3k>d?j3L6R}dbrqoe7^H0wu ze3gf`k0{ycbfrUj)+mNJQaP$6s0cO2qLxH$2Gk}oWu@*0rC;#eUaTc)(<7R69^$c}GxL@_2U4ulW z9c)=Hrq_ldEWMy_RXYqs8dAuLYguKC$d(vXWLee<7`TM2824xaD{hB?WSW*>&k%R8 zGM9P%2HP^}#fvci8PzgE<1mhM@wFe|KAQx@fW717P@qMG2)ZeanQL5Wf`E6w>ELX0 z=k(XqMl@kw+$sR>OgWrqHCRNjC@k8-poGi67g3JK9+xn*fzZ?{?oYzJu@_15GSjEd zL^`FaN*@IHL+-9w|Kirp@<-BI_ibTbz$e`_Q{ zwn;UeZFSTJjFXo@md5L)_scI}^b*96r-QSUuVQ^RV&{&~oMnU8Ph+eW8xt1RfSH=I z9b@CucFbIDW9rC<;KU}cOKblYQoR{EUhlTYHJZy)d z2HU@RtloBg!7fzK+%a8jC|G}MyKC%D6lpNVfb8^C5U7i4jUcR-E_);mS)6O_O)=Qb zvvGrXs8PypLXNyfJz7}DC$H{{C|TAK#VKlVJzcablG?}zht$bqp@D-_SvjohTibii$jrAR9qJ(0yqn(nUqKu%t?^$Gquv}J` z@denH?-78&32^7cGZgk9HQ;XkMtFocRv$>Sk{{Wa6}*_QaF2y#xOTm4zJ%OEvdjMH z5RmmZ415wx3v>zFOAT=k%gs!m>a}DkFBxs2w(26h879*)-F%by0eB+r-*b`I!lN?w7T+eOig%H|L z$Iq>MTp2WCXkujhbQ@5;1RQFynWT=}D@ze)w2vin-l*|zg3BpytL&aoXl~FZgKhSt zXFMh^ejZ35S_vH8g{ftQ&AcWZ$+v|06I7_Qju3kJ-r^Pe=El}qWr-1DWg>nA##)Ly zF?~yXfo*{e-xIu$ms@Qih_=y!gk?y z;`04Rhy%v+!Te!^6;BT~9TFCc;Qm8@s9T7ln9Owxx>Z&-5d$V1BrJjR^a`Mlo-C#^ zYF;B<5L6n@HBXw8#Ka_%V`S$IZv!hoF^w8A7r{dNBhS3vA5)Fl zf^mxBwRcrLV%d&l#3ycjX>V(*q6%t-9!l8yRJ4bKcDJN|wgVVMS*HTmU|YSo1|K%F z6;V3&7<}~%ZxCThg1OtPwt&5&gTIkySKsrc*!iK>89sW#z_Fq6xdfP;=EA-i8=yHd zD*JToEUIw_PHm^cAI`K9a!KP{U{>!>mffx1{&k1GRe8GI6ff{`hCrJvcQtKE^T;o~ zN2W32eQh44x2W>60E#H-xZfX!`l(tDkYk8X_VQK}DXs{l3I8T~Di>QZv*RG8?X(jY z7?RGOhltT4hj05944L59f0$AJ3212$K?)!JwyDEw;s22_5m`QyGSF^4BrUM=)9B7d zg^i)M`bHatVJcS&0C~6{ZW{hB>HNmX)pfQdK0df3^>6RRVd&nMjM z1xTVlUn?FzdMZ#;bmLcjow&Nc(7~m?HM=>#WhEUqr%*Q}ws^CZ%W7q2hYJePe9&?v zYyQfJ??q@%fujEl#i%C7OA6F|Lr_xP6W#DG3MNC4as{fd`-}v&*a$d3>h^MlVA%IzP$ITGW~zcH=O}#k}dz zA5w2|`op_;R-000f@`Piu3uJ)^`uh`rvG~n9&TebNT?3tk>KgvL;Kiw>-D#RbHUg5 zO~@4}oQkV8L-K}lx!e$@eN4^9so$rp>$vMYWwx}smG93t1i z;Poe0-8OtQxp)W`6C?Tb>7S0fK@9HQh-tH3&$~+u;__VO0}fny)qeEhn?!K7?3Irb zNy6T3{CAAsxiniiJ)U16d}2|%>MVd@d%)Mm`L6W}&nHC^cwvB9Ue#DGB3{d|jG zpa>ee7-o`nhxdIW$<}b~aRv}tmrB4QzUPBgy$$P?qp$VA8n9!B&%6e}?)IU=yT`JD z1-5KX5B_qD7VniK@$VDJF90e$Y?Do)VTEP(^DpV9%{O<~5Bj)xPoBgfpXS1UbVL>97VN;kC{ld|A zFLi(F#fY~&-{K4YGFT;Wzmz8G!M2W`j}oQ9vol&4M&xU+HYJz#26y@rEYR`6iR7Dk z$Iq?lM}BV}yR$#bYOmJV?9bOkjF~t2*aWdwSd!$$uxJ}Hj4Z0Icw}v!23p~HTAd$! zUa@I4SD|4}bs;x%w`y(qf?k+PT9|BYr&wBSaixDX?(Xio17BVUE~>QdRtybWq998j zRbI}7>{4elepG4U(h|K3OVckCc|^yfpM0IJUq#dKhb8(rs24C2^L8LR@=7_pcwj`g zUE2cW&^$I?SH~p5=>67-^>ucl@+RT5LM{T+dFVfo&$3w1viefD@DFXNSa!hte%|`X zs0O7We5XxcdIQuho|~aJQGUOZR_5>?+>R<(OeEA;Opz^-IkmY8_E{yt%Cw)+@v@}^XkFMU37e}avYV?`baXD&O)&hUSn^P#vOU5gIHNBydJzR{I2Z- zB2B0iaz^xk=70khcd}!g_0D)j^x%yTTighWw-VShQBq)qi$Jm$V)+Rzt2yffR-8!D z2o+S)W*24f@=9oQNR+Eixv)h^pG2Hqp$w3l&NBE9Y}n8f6v4|T-9*dNlk8~?e@a>Z zei?1VV)-2d4qBEakoP*DU9nrSgHXvGH8O=IJ;T1Fyj!4lZV0(LL*8hf-u^zTevH~U z`g`3Tdet1v2)(enB3wcGoMX!nV~-KTc>=AK&`a!T&OBQv+xA}ZVSEASQE&2I;N|e- z5l&GfhPfItFqaTP(saKz*h*+{&e0OqsLW42zb@DHSP(kpSK<9@76#3U|GsG zwO@&dkd4Ay!1uG`=by!n&_@U&rd+Dy?d(O4^e2thm03Rq3&YvB3%fRQz^O4>cM}g59>JR~qFx>-U?|TDsk&^snDJ zFiT~UHIL@UDDeDcTh3Nz_ptB#J>TAe2;MQ0I&I$$Z|HIbjyim@LvUyIZ8~^m*!5vO zS7DxX;r-Hmb4U95UT*jZZb>5WZF}NJ4v7@1O4l}%1Joog_Coqs@VSYIg^;CltexA2 z1H>k}OMnSrOxad{_Qk!R@qhv3ASAl0lUIzL;wQbcUWZAQ3vfBt zR>~u%5}|&!HoZGfys|BF&Y~tgbA1FRU!27O;THk>Ka%->IrLT!whDc|SGJI3Zf%DH zPTX~Ls7s5jC$kZ}O)kwwBFtwW2K1nTmfFs@9@QjALWPw=xm9GKql*PB(0Idcwh%p* zXdVt=R^^vCSQL726mV}#G^(rY00{4(p2r5LwKh&P!Zwr+Q^o7XyuA)pzpvpSVz-)l zxtZ}ByUY69A4tFT3D7xbND!nnuj23ga)QM zyi|tU+hDiC4kHbS8M>xt>ZQE)#m}P+tBz}mVeXdMABw~!L!Cp_Yzx`9g9`L{4C)_j zSCfOk21~NzK-XK2azDNG zFN}uC1g`emJgs08@n^0Q5MYsI@g+UAv-kn)& z;bc@UGd<|~cv%0mz0$SOZl(JETq5T%?CkT!qE&lQmSvp5LW2vL zhowgWGRNhQunAu7uu2dM^RZiME&r7_0zKSWC|T1c%*y;{+0UZUVyC+8t9R$`WR35? zVp)sINkM}qkTI;6&tfdlLFRIKFj$vGIDd*iM8~@Nc%Wd)I(wK7Ypa2j-ED96uzGW0 zvy1A!TwB7Hi%RSWJ@7({_^{|?#V!1$n1nOHBE^bfP(a?&LVYB ztYBEsztAL3|Bb05Zms{+o~K*x>Bf)s_NpZ@Ai&?ROK8?sYRS-%;z!d&{Pgs~#7XHP zO)+F3-KuwT!K9*=>{PShx5ZdBmRU#7Z6`p27I;4U5Yd01B zQ%-%wRUfpxRyq zE#{%LTRS4M;qZ8a^HNl?O4ESki<$R)s@v%o3-6?S7Dm5(9YG}zME!pv0>k?P3_646 zK$`pkpw8Zh(ffXjZS1zB_k8WrW)!#tYVCktZ=DOg!{4+uJ82ge<|w5Up3R&sQDElV(ZpEh%p-*3?a z%fg11j&RkLMg?D|XYL>ZEdW#I@ZJf+(mH1?R^bc+{G|}Xn;-dQe1KpCwgC*LKH7Qc zI3U}nhacaF+sTXE(Mt=+Axshyfia@Xka`-r{0`E|+H|_F_g+MMljVcU$YEduFOV`^ zX@&FSM|}9_MASPM&(0DTlg95}Yk6U7XC;lSHmUEU{)V1Nk*ucn&>riB)wB_6RAJv= z^&8200X`xjbiGNk3)U-izNvNQo}c`#&6d)zXkGZzkLtISebD z8RLkVncn#$iltsO;ZwDEvIc*`*ho6K0=a8m5hG=0kYS}a%cEqYHP#Eq6R6n0%pau` zuBABk`gU7(yy!D2Yh-CYo?jn_(t$*&f6SjP^Josy((^5OwSB9MB%K7xxAguhXp}{z z#VUN?$CZBTd%5xze9s^Ck}$HjV;>N(+XmBC1pBxF|IMlD=J0_Y5klP= zx|}&OEb-hs4jnBbBMy1~W(k~r=Y}hbv$bPqAya<_)27`!_jidq^r9Hv*f2fmG&PXV9CWkB4%T( z-i_ARKEewq*uZVyJ;&2=;K~dQyBoaXVGm1JPhmVdSbuPH+-cPcf36(f3Pp#-ACg&2 z6}1MjDpZifFR zdhIFnbXI?KT9vvTX&oJL`!*DzGkc0pVldQ0G5a+!=#F0k$ZoNS?)u?b0tkJ%zv22p zZqh4Q_7;k`5Lpjo-btu@|4V$bF;f$wryKE$8=lZ-0-+{A|2*txG}JCz3D=hd^n$tj zQ_91NxL9ZA#qAJW%Hl0A6!&7vZArNH#^wY;-vTHf3B9=7)YBEkeAM?kji!Bh`3o{k z%s$A+e*ZkaH%{6KAHJ40b-yq=vdKMcC^Lnun|yvq$UsI7+y2^varGN@JGvnbOQf^Y zwr9QD=^fsLX~-ZOYI!m2=T7ff6qP5}z3N-l1b%nYHY&@WlO?8-KbkBS*J||Kfm(3S zN?+8q^?j?HU>3koO{QmGZJgt`*?8)JKb;wJFyrO94Cy&NDLwu}?xg2mdWBiXx&-nq z;u=YW$caVi)GH9)L%Xbhb-RY-{o#rm=EP5;JQYZM2x;jz(a}fX&zq-ym*=+vixaw# ztFG{G?d+t|;G%bKq7rcW{#gQ6w6L495LW^Fj_>C#q#grMYcke2@o{UfGy@4akX1Pz z4D4e-&}FpeBaS@p`#YA$V(sLrf0ckCKaN5#cJtFoh{rd}uBx)i?E5zz*2XuHV6fl# zWn%TNFkSa_>nn{gCpl0Kf=^|8hJ^=g)%KY^RrCtux>?-_g9<*HXj7IO{|^z zq}1QE+gi3*t~Pl^WuJXtVx_{(x@rw^EI%~52ES0%*$Q~Gu_f(K?i{v^jR@c>(BY*D z8rh50k(`lB!Y|v(cMdTR426&1UA_yJK#kkUBQun4D=jhJ>e?ca%u&=#4<`MYN*<6@ z|EjzRwt{IyG-+lR_%l^V-nUJ+5+@_?Dr?{rWS4^{HDYm}mVmF6-Q5-{hARp9iV#K| z1#u78x!!R-#O76ouQI#)ns#5k$j(wg&g^TOa#dK0@9*!R{u;IxdG}*J z{*J1GrnZ|>%i9fa5>2#o4u)6Dm{Q`~oTU1S?cunXF@KcUWJlm(=fh;*+RNQVRXe;` z9B>81`V2}|x_o+wld0wixydeQeOLDZk}Z!&H^0;Mc3p(DTHhtXqSpRO^(U|bSuRCA z9|Yf#@*(*_(B%DGZV?MErF_~GmbS0MjSU$-U95q6lnJR|x}jXNexXkMx|mK`eU_}! z)BH3{o(L1{X66XxT^RZ|0?prMrlPVQbGj3@(#`$w1O8^z4W^5n$5`M3)2dMg8WOF3 z-tcZi^h=DLi^W+zze$77VpVJQklFA;ruq-7HoUDMs$#V9Ta+w~May9!W`A~46j~93 zX@IU=v`(yKpZa$%$ZMi|Ix%JjlQTx}-t9dHs;!>S_AVlz z-BP31(LPtjk%ClMI}1Zk`qn2TbPE}XRBi@3RIosi*jHE84g^>Fl^ll)gN{_?(CodX z4c_kIb0_qy4D9zA@Wem1qY(WNt8k=yKy<*CKRTvXS7=H!ZiQ$o^5^O_-n`;o&N;f zJ~7=V6IpVkWnPt$x9NQHkYP-^vyrI<#bPY3GT7#n{9MI%M86|2g} z<^@pPQOc-G(wk?f@G*yc4W=1A8sbHip4;RTZqXB>^6&BKw}4$p6Ay+E1&S|>yB>`e zzq9)2K)n#dT1ZgzmWYD%m`cbSY`pqcOhv(GZVh*^?$$Fb?2jQRCPm0Yx>US|WJ|hmz2w z=!CeTg$|_$HR}QTLd(;1{ruOVD3TtGQ&JJ~@N})Cic$QaZ*AzasE}~yc1gm8KiOEH zM^jn{ix!if^$(lXU1@TB#tr}f&;pPX12nKAYO#G!SQ1&rTe8qlPGMQK%zk5n%tR8e z0P9Du)JYqIJrRe7;2Z-6?qB#ItaIV;sN9$5?USx-=b1ba*g$@-Pm>PbI2-4O3yA-q%FvSyV8NhO|PI$YLVPos~m;*??uLhx!L2eY&)-T2!PU#Pubm zm-WSuRcbqZEAxlI4A%AV0oTn9GH0{V0Bb;W=){h(l?pij7K)d`Dm32qh^S5b#gL5M z%HomOESGxO%IQ?c!6SVZaeGq;p#5(aMjgTH1^n{D7CS$IgYawuoS^F$H!0-{!3+yf zCnAi;LhI%cG$k+gaHf8NdrN7*L*U)E2t~CDPfQ$ITDp~X{$muoU>qd5N_pP9L2!Ij z;&fIZnqd+h_+Gd}-rLF6V|_ePL)!~H@qy)j*w(@0-r0hwj=_=S4+NvHJ%OU13le#= zBKrJp7E{%CsV9$`pG@t{o5Li9E9!&`-7E!`x}-an;UG7w(~ms8dknn43QgL!`&IiU zaL9IYzUQH@pMwD}7xMhRPd}Ql;-VVNjwHkc4La7l+S8|PH#muuyxCW@n9Z8Dy9Bpg z_%8Hgd*-{c_jp#nq04+#9k33z7QY_6*l_OC3wL`&w8I3;l%=0UE3~~?As5JaL{~^U z7fH0a>gVs2+gd*iIJPF&XGE)%3{(?wrt?y|MU=8E`k5oF9L)pPt7RGJ1I)E^DC2+x z@v8Hfg$}J-PT&C#El|g_h6pQ1QKd>3r2J zE`Q)|LQk)h*oHxQf^mNe*Kw_sUQ1&;6PscsmX->~$5QZ@3>ktAV1Q z(b3<{n(8x0y(*fFu^!A%f{X0?LRpUr?jx*!*p(=p5h#;BDnQaRZuRSJ^{*pkh`I_J zL6J0&f(X6;(XvswPtKc78ra~|^@jo?{FUX&8|bOJw0iV$U|cq-2oTCZ6#SYfMLPv| zAgN5TeA9C)bdU@~%1vAj-c}BTo#~lf{aYINk_}JQW0ZqlmVMXXba(}d1NLC#Ew}%T zxYW((%CC*D2z9n~3)$7sagJBi=r~Gtk@Z!~wd|GnxC|k9y=nFHC6_32S%7S3j@`t6 zF$k>i*for8?d15w~gb*m7Bx$k1)w|sVe<5Dyn zGE=)>7n;7ylUHFsmUD+%EPy~2um`0EzJC)dDG(L^7C(}t zI07${FSnV(hd7p(2AGH%q}N=s_djX6=wU}U&SdqqPA|J)yxrv7>ArlwCi#4s?~Ryq zD!MjKbq_(_4yQmEDE$6j&@KV9B(jMab3|V?LjD&WZyD59^sfu!?jGDJPO#tqDE=HUo!xH*UGm{>a42~?-3w%GgY>7%LR`{dU#Yx; z#64?}al8tYOpJEY66g5+C3uCHMc&bovt*&ESmO^R$kh;qi!i{8%4`V9SAO@-`HAM{ z5*8xTD3iqb4j%%3rhn;I;Qc7rRPKipR^&`l5g9~5$Q`kb(vpUiicRvajzP{zrSb=c zkHt7a9KcKy+Adn@%v9LHQ)!J%GI==2l4d?q z&*FTUXeQ`G#MXpxt-Et-TD^{Se)39YM@ry05K~Vj)LIM&bjH_` zknfAUGjo_OmJ)v-)LkNK{ox8${;L=rSAwl8&_QuT(S!5(&fX|{9{5Si0x!c+ zKJbVoIl@=VrF_t;nuZc#@@T}H7m#%?m7+WIo?-aUfY0mC~F1DwxQX8cg>Dg z`STL>3^+zL?zI8y9q(571VwZl$7!BhuO>e&7*V0wM;Y=6*3uiwF@PW~!HTIr1pOe!<&E-QFwHj;d?=Tm}eshK} zjW{HPKuVpd&IA#vM-_k_=M#O}V|ZXN8J5Z!_s&9dUK4*gP9(WXla_(JH3LNKL7pu%*`)OoN~1*f1;&Paj&>z>C& zyxu|vHdj=t)aoci6m7d(MI-56K5d+GeYhg7-sy$Trr651rTN z5^9!+b%Z`6!^3Qa{53?vdl6kGPr@tr{lf0i1+ z_F(FPrzY5d!^QM;xVe?G#9q}K#$>GlKe=WrSb^SkA#t#M=xQ6&u zm$weX@Z$#BvSK-JBNRSCzx->->O$X4W=#$EL8fe~px0W_%UtS?*{F+TZFKq@3KNM@ zkGurxF=jU8kDJGTrnOM}AqY*k9mE428yK`JwnwQ;-&U_McL?h^deF$m&#S$|6)#8g zMx5UhNXk{dlYywJa`;VM8XOQ)4^a!*gwnlAR74&+4XBJv?xTOxNpo?7cqr$6;?CBi zwC)T%HneuIKth-(TxqbGwAw>aMk%MQ`QXya|EBF|J758zK-0N_WPlaXwv8WoWX!J! ziI9@#)6DOoptQf_0K0O$bvYoX8spBezD75kwdugLljls=k5U0SDd(ifd18b*R)nt4 za1Pg^^F+_JxoxCS!`+)htyAyxiGMwhOPTx%uYqsBAM!;`c$RQ6J>Ts5Jm@_Xx>(dE_sODOF3@bs}=6<08uHW9W})io6$}tak(&T1684t%DV1=#Uk# zN(^+z5ohuj`JFY-pb)NWNth#)$toR-kNQhdXE?>2yZO_EsOzNiV{@hJ{Z8TbA-{Uq zhvyqy*I=W!P7TptEBuRkHX|0skp;kJ!XZC${WVqVL@e<|jn{ScSL&gjQ@jk%>H=Cb zMHAU=O}DThI?s2Yjc$mLD$hquWE|@qdL%As*rwOeu+P*m%?l?^Np)vKUf;F-5jVoJ zmP;H2$Acm7-W?v4Vfb4w=s0!&#cCPci)65=pSMj)hZ z1E7mV;%kavmK3V*6xH9hK-@+8BjfqWWJzmHZtr4GQq91c~t+uEi(&`UQPT{Xr5^JVE zW^XFm{fnF>OiSRro9uPieoKIo($TF%(F|Q^iGt}ghsDCZs|Rs>Ql6| zpb9LUJ*)PfR2X*k$4t-4TBI~7Ru+*us`d}jAp-NHQW%}kwgc3IUX;o;DuJJE~#*Frtp-E4fZw zelb-ieVLaN6Sy@M`b7!1NQ|8hLH2Ql5ifySYXMCGy3Lm6A2 zgYA0aW%$h;`rbv>ad=fiIEbrKVfingpF(LYdXfS(ps8v-&Re|}PeSB0t}bV5k}t$X z2qDMadaFHS`&P#zYFn*H*>?z>Xm5W97?a8*!LvOAdE{M7+Ui9j4D_d8du1{It$-Ww zaPk$j-aK0bX#ecVuGd59WcD4x3C;nU(R--ioCM&%>gQt@0PHhpxJwTZTXxc#x_Kq| zx2+NONep9c+(^qZ3gr8vZvDBNorXFQD1n}(NEGQpjiXXbI3zl2kK5+6x+qQ>CjGbE z$Ni~Wx5%%pw9J>w;kLxD6aHbkuQyU{!1ufo#s@OI&0+hGH!4|osLWw}c>r^CI?S!` z#Ps|PR}SbQM#wB!-(k7kd&6~uYCtsJKfb3NBH9}8DB3^%SW*#YJJV9}pUs$O5X@!} zl!2*%IfajcxMA$=SbiRv_na$=0W=_-wIA5oH)r?bfc`pQbz@gBl`@X$k6BlDKUGT86!}RuZ0OpYL{il4%a0-Dw8TKXzwxf ze(@taY;koI^piX-I{$DpOun7v&Nnz#NVzEklMr?2iY$dkor%k11KKns_mK}FPIu?W z(0#zb<~xrU+;CH8m@$0cOSY>^@qKR1$GMzFGdbxxzg~4FpFaLRUcXC&dETQmx5?I) zl*Jfo!OPJpu{ra1r`L!4I^3{=lu>8Tg9yo#7WgjP78V90-azfYx!N#A=Lj}%C4C{Q z;8|KG7Kqk^4C@>A+$gMuzq~ki1Vepf@^$Ci0mMlq3wYCl{iE7MhZ900jFa~IOE|pD zbfk3@t@RN08PUoOx~A=aOvVn!aZpd8Q_t$RKuE*l=8=`}yUuHud2>Ir)Zx{#MiHtW z1}+%Xl~q^c(0O9mGf1XqknZlIsA~x`L9M=6>b?&ZMh~O3lPe6$A91|sxM>^u;5OqH z&zW@m#2o+iYs;PlRO+0qSVQqPmJ*J)vR7Ze!?1UQ4;?Mxt~X=Bo6bYYQplAjM++2@ z1t}brrdw^n&m1v4xO#yr1l^VnCURXA0(Ye*)zqH6tZ0XcS_pLz7&unS*y31ZA{||=*M5QxP_OwLN9_&$q8af~r9#RmMcv!4$nKxsIUkZsgtv?5V3z02h6P?tb0HTv z)>C22D?5i_7`RxHeCaz9QG0(${$2z@E_@fbwbH=-8v_4baSC0hJ?C14Yo6tKmPm5PaRW_)_N+3Od6nkKB!H$ovqMfZTT8((`OE zGC>FV;wOR#$i6y39XlmOjxt0v54aOBe0$$baH53=%XmjFoDUi6K*jWSiIWV4$o&$j zKVPWntOS3h&RSmCKK1jaaNKoGHCs{dO^&3u1SyA*d8}DrJx!7!uDcgMxQs4IG<-NP zCaHygFT@m=-xpZpoWArY>pWIC!r9XKWWa*sbNc}Cx9uk*Ct9=BkYpr5RGNL+)^i?V zi&{WKUeniK!TI-H+LxfXrpFavK)BY^8gI^^$OdMU^|7GV!Ju|{)6}P1!=Jiom%`A8 z`#3!>4pV)y(}xm0HTNXR;ze?c@z7ExScvoL4Ut}Z`&4QBY}Zpt4~>V3nGEdkbG=MU z+w!c#m|Uw#Z`H=1F?hg#gRtVZzH9OB&J$k>zGD4voyO(DiNA@jQPWqee|PTaUJ?w% zYeG^dPPwSFEuUEK_2IKCHa(-RRR{hZGtVKYI&fKh) zzb>1qUnC2xIk2MO$;^$*cTK!ky~-U3(zLf3{2s)q{iECX+WI<>#((@2k;mG-Lhvi5 z4Qi^P-(lBN@zFY>ex!2o_mtA2L-^HP@`!np66g9BU++BL+m`2d_SL~uO5ePxqRTZQ za-S^^V8KYfA8sF7MnBi+-NI^4`sxajur`MNcWfHe6*N!c^1s5`E5K~8s?3ilDrx1X zI>5*bGb*Yx?EM2zJg;RR$5Iv=kOT^}weqxl+0qb&a=p#^z62K~{9>Q^!y|u^L2oOR z$OJ(f;%vpBgnbe%JRm8N5$~=XYx-)^W{ypZv^BU1?dzzf6@hj774;$ydocywM?pOo zf%HW5u??AGi#PkdWLRvla*kcBh4GAKyGu9u`FSMsOKBGQI{I=S9 z8-y?#G{&tB6TI0I2WybWcZy*QLzbe3SFM}>*e$0v9Vjr(#_PXcSYylR%N$~%%xwbf#ItCQ2e8Wx+F9*JEPn#xC05<(NG=$G#dd?b7OiXL_f z#yWVSIqTVwkoyI2&Lu90K;I-(pJxGXJwER|36fiAr^-F!qm`!6DaSj$Cwg-V*OHh> zaAr=qzc_bG!St|~2|x$=MQqU$Lw!cM!_-zeqk@r~01$)An3|zKez4cfu+xC$HxrA0 zaG0PY54?Dx5g}gGu0nbeptLR!)P6@^5KkbLo{lW9*MdJpW^ENI&Ua&TMB4_u!F%Lw zJC?w!L!x9&zRPhm=U%l>vE}`o9{5P09bEna&9H!i#g4G4*G5b)iiH}f#*;g1yPVG` z%}|if1>BD{mDD+`Wtr%U<)&PXwW|o%lLAn-471w$5@qYCnwMM+caS3-iWePv=3JML zKLxIvWuDVIW-hPz>cH2oYWHbO(UXEH+JH;=Z>f2x7{8{23sPM9Sie9@@=TG75Iya3WSxGTCx3%X5r#%b$>9Q0UMKB>IR(fpJ9MQ`+2r-M68c&ZonxektgI zxcCE}EtCrG)EcK7(m}WpN{EVrN`M+As?{SIl#)vGy)K;ODw$@{9qr}zia#)xxwGsB z6=I%$ZY_Mb!@_$)yQVwbz5b$0g`EbT&aRKLu?gK?U!*X)xQ$#N*dJ!U{4iYl=-I2r995MgqN^uHd@w_1-e*PWf9F#$?9Xdm+k~ZvmoaIZTWmnx00!brsJX zhRemXuL(NfOr!`gwVC8O2TCY}QPvOPZI1j>|3`b{p6n0d3ga1pkQmaUs`oT@h>Iu! zXex|S#zjgMSO(ZK0WceRzK1CgoB~2hM@N7j`djpfpAR4dHyPavz_0+Lw@w*XZ~u}4 z-5opEl@A-001z_Bb_G1}>i#d#D5*OEacX`TIdtm4B1;8%>T|)lJ{be%hXFE$TojOg z$<}3Oa-5iRY{9f3P=bI*P6Fh<&uJxX<6H!AEelyK-U24hT|J2nv*JWvVzCYnWRrT8 zPNHuW<`WipeE(RUq#+zgGU*%k%DLRcC#eyLgR@E&j2{0EyN9^Txo#dY+(zc>Q`fJl zg<$y&CYL?|ZM`baPMk&s#CJKVMfU%K^94*><{iE!tU?iH{(0X~Cb?qSwK)1O$y+m$ zY;>qQx6!#an0S)|CY<(w`AfOtZr}#@Bh&oAb<9dr^37}P&WY9xujfAZW>a$KhFS`L zSj&X>3TPw@PxCCg`r~YS;{$=VIpm+H<^zGeIiyTf(*fu{4`ASn21Igx%l*2?3r_|u zyKtt5)T)oL0eWCIM~1MBv<-r-Va>KYXqe-CHtjdp9yT7%g<1qwzw8H4v{tFZ0+?;! zotVbp!XW5k9hnzcfmsn$c(@XS1HX{X@kVqbgQ3GxijDItYOmGvuLbgtO%`uZ6poaAY(%%)g8~{2pMr+O4*Cc z9P5wDjZtjvE$H8Wf!#ls(Gp=2N{CZ?9DSYm__e4a_*V(@O}wmY_8Msd6203}@xT}k zJTRM?gUk*`w|=h4ARjSE8Yy$cm!U7V5wd^@vT@{`UFM2Qx(isGu5948_+qfI{f)oX zC7HD$LSuL|T{>~|L1g#c@ita}L&bcf7bDQ0CWu+q&e8NUZ!U!kD73UGZ(gYi1MH%N zHTL~i2vq=Ks_p4+N9%nTz9Z#}kgz1?eS)CFl<2>1?*ihZmznRnfPGfCaJo2($#d(I zZLv5!N^27X=aaBntV4CXl393`5#e@rG8F`tSp(iJ#@o|D@{{Xoq@UMW@EM0Me%v1D zIQb^a)5s;;^+nT0`Em7+#^57G{XIF8B1{%P&idB^f`HKDeJl8-!_)m5eCMyB^#_DL zyALFGbl?X$DzHO2+-?mKMK>l^CvxzSC~GtJcPk`e2>oa16`$;f$hT}~0%vFu?|K66h@ zj1dW+_o?fjD(zKvO-dghh~KA9iIp{2t!dWq#Ti`YecPbhr7Um3+zqjY^_gFr&d$4^ zn!yo*C-CM^WyHI-_}=)lkmq%?2k(^F>*fEUV%J~FTu(XlMqWs*$Sc3yuNV=0VL!}p z8`8Z)Fu*iF>7mU1C;*HlGBlS(JSH|_=8`~|&3gP+V|VKc!^Cgu+2W{5GGG&b~5S?Gm{W&_3L-L}y1 znEITATdddu4;MOzHnx5QQqI})v6%`E@Wh-@SJGdz&uu|+gdMMtS-<6xijzZ(^})#J zZ*PNnK~w#SJC(_fW3@R0+Ox9*w&IuY|!NVAZ5zo85=Klh< zNKVNkJ7*-}X7#ouV@9!f7|F5`B*AjOIbpQtXk+q2*7egd(4DvWDR#G@OZF%_1B?Oq zR~$e1p)pleh35{6^2U zqXO&ZQl`DQVGt|1&MKaG-~zTJmRv3^iBobQC<1w)gvFZ;e&T~iU%D!F_8qWzh9qo$ zto9vE4mo$TJ3-wlYFTCgmFHk!tGi{K+mD-PtZr)KG1dF#0LNJ3h4!x7sA~vo8U&|I zv9t|72C(!$UH~`g9z9Ef)h(rd()?g1(i2cPj=^`gEpJ;&LkGeV>zz-Y&Xd&kh3+IX zS#}+k6><%J{Iq&d{<>Y zV<8@)eiF=)RXg$cg~e=?)*%0Uv4Txag^oRV`&KKtk`_WHtqOHR*`}^ zPGuA|W5+_V7O3_2znUsdqN(pffB%6zFcJ?FhKA#c#E5PoG2|9hdGh-vvm) z-U0el@xA#3qn-p-dV*!0`KdjuKOIQK-f@8rC9)`XVQPg)AUyGAi11n!<;3GLL$f7V z26@k}FvF5Ca!`{m)mq*A94f*$CspDa`pmh!nA_6MbHnInU{eCA2Lyjzy?E`8+@_8c z?@^n4b=!ba-x^6u(gOT3rjSrk?0MB03dgX^-*U5go^0DQQT-tDDsoSuufoaR>LqsO z_j?5-5>K{nCLdO+5kyJ;R9NW?fbc*+g&g&*Si16*AB~)Sx{^sn)*3h^(u6=X+muz| z`~S!&F{aQ8Eeq#80N?}!5=$chojmk|%RAmgD^NiHcM9hlqD56`f)1rk6RW$qmuQQg z*JWyabtYZ*Bu^ks=BxNmp+>TGL*5^~*T?Q07L`5>&~?Z}9?*ev@JHeSw(l6$wO&0DQPUFQ(nHFB7z&Ef4J1FYl%G z9PJ3@6k%5IJAO_-T9F?_ULX8SAG%JPD9&^4aEI)n%ThJ7T>Z$oHr?u~af ztv~u(N*sC^?B@;KOa5s?bzVc6eU>znuuTcqj^7S++vbTD#aKznd8#^nYCj-_t?8JD zPY6Q!`b;Ryr)aS}@L~bxY<DJ$ z&veynKb~SlH{zLAnGNo_+b4r9ar#rEjS*c~uued`J5Q)aW{_k`!z>hOkL*-=MKFM- zLnr@NNyxb9>l5e~r%^cC^T4gE2*u@3ud)580DM%79-A#)aE@9J<sRNCxW=} zm4QuqnoShLtd&nsBwK+4bq*`ap`R&af*u8OD1uy@o%lTx%=z9BaJB{M{o3$TYsh-v z&FS5S{hyV;6tClEx;wq70f*9fnegus(LbH1)`Xwm_K8sG_BS@2GY$qs*Q>Pr0Z&X! zu+sqy`)_3)wQKJm3Dy<&I;}k-7XABb6i^K7zn^xx-nLzk{!Qr=Jq~vJhUCvo_|iY% z;62k){~y9S&i-g>xR}`m|4-uH8OA_1LhzfiLfO-ixmVJSZr33rYQE0;Vp?%Y^eQ4p zsfaTVrw$X+PGs0DjUwC_1<#QQ%ej1nFv61EWj!-TIR`HHymJa5-a@qADgZsy@{t(V zjmB6xAGn>)1VXtKRZ4jO=sTYIkXp!NJT9jfUQ{&JA!NYWS|VsZQe^$1c(pJ!fI5In zNO4|{geuJlZa2UDhO>XuK zNZ$--dG=WgKgQ@v#4sVrRbRc5ci8Y`W8a$~M+D&A4T_u%A|lZEb=(GqSOxSp75Nu zZY?+24%c4IQ>k)3lNM&27pGNk+ZyYBP}^#n)42?&O9(~mk)vvPy6j+c=(y z@c@Nf5&|HPNjnDzZwTDEd*=? z;vsG#f|1uVwOloQv`i&RJ!QXDIecJ4Wlq9Nj_KhfCp4tpLyzSh8L=1W6YQsZHJ#si z2Uz}hn|uy5SG1txbI)lSt$#95vvtWG{N_K`WJ1aijQ4wQTXoPook(2aJ#Oc`IU*n5 z!3Iw;6V6gG`e})+N$#NVlqN!5py_e&4 z0y|&m;q-h%Qjsg3yngNDu%bY7+bNgspkiB?sS&b^JB&tDSYvgy=VvWxz2LJPPjcIf zyFNK)OFrLH&xz~o(mG5e({erGo0np^QDx(8R>Gj~c?MF3NiBQ|2NEe+*7X_l!2YYY zJ9WvPq)JbN^K!s+#pL$CreXdQ+}vUQ8)9vE+@{eV+LFuBpMJ4ndx$GY?J@Lt;ZS?w zvtAWs3)wOr3##lV}GNoTBetMRy1M7_H}uU2|8BWd402fzum*{4@BwJ=jdv zz+Us%dL?T*w@!etk6e9A_&xhMQG&IFZRiX=ySK$5g#pO?-}6;|sBo$kac5NloNaHG;93CZqSkC)F_n+>Cn|a#$kG{MLXj&wl_31=jsaWoP1HI>SgS zKPSg|h$GvBw?o}dkNHT~ujif8KlKl3X*z$wkKD4x3igePr|0dHP1ctj*OQ6#}aN$74XwUp+HO zX7L_0do7~MlRs^SEb*85%i46nt)*|cHP(8+p`uc(mPsYO|2i(W$hc;ruskD+e^+Nx zKWDQhEgW5Pl_>rnhk&rN9MwarWhM5_O}(o?8^fq_R8bf)FB+z@ueC46(W<=EkUV% zDSof3kE+GbebHt1NsDpU?6IZ_AQpsWpHecVY_Akmr(fu^IoT|C{9jV(TK1^Fr0=hi zXddKn4>718hH-GQry_lC_j~~-CY();&7%v+%GuvFNtou&SHjUiC-t1#bO>u)^J4~; z%BM-+V>{huwqmDkMJ26%!yStVAab>^qC>HqH-WgTH)6YfRqJ~k!!D=bH!HfHX^SE9 zcm6hM-b~P9rn$`W7@X4tSPj`Nzljxu^ar%4o_ZV5NT0ya^ZuC<)rlhm&`Ekn&Jxu* zpe2DqF!FYyrCgj6QN}@fa47A|E6P@%?zK^bIG{%g*4#FwG54?dkMR@$KdJlajy$Zf zn+|fXnIGifZJ#1)rnx)oXzMW=g>4?Ps#Z@u-9l($G@N}){+#4}%~bv33*j8-<(Jq8IX6Pk$VU0EY>y{rLPIJC7oAsB!!|1*phf42;vUf=Olqn^IPre1(KUkWj$YFy;n zBL&Rd|0*5d6}@UOBgggcm|Z&`_BCQQ-Ud9JX?TdM7(9N&(O1xD&1#I-i*-iNluEUGsagg&i>Pi@@8 zwNI)Ume{wd@oaE;kZuzWnMQZ>p3qCkhtO}k@t?%v`{#J$_zg?ZDD(W?yh2@X|Ce`1 zPuxHlXnH1cMvhY+fPF`KoEwhP!*B=Oq5}KV_gJU494hOHl*w&GcuPB&5)~orI zY+rIvQR8nmpl;_7$ZlP4JyJyb$w_Dr|M|K4PY`j1f7^Eh)3L<+u?cRCa0Td@yZ6Am z_(?|JOz^etsz2HWp@fcj{l1{9*X=d@F|Mtbu8+XE&uWW3ssSz>`HkIWa~0dB44^m{ zgo+ByY*RU{8Irrdp0EEz#SK1!`w!EW$9*qd8<>aGmv;9ClaqSb&Uw#xD=e!Hbv6+B zBs4ctks_HEhOP3ULiCd)$6Iz=c2F6;cuP%r!TAhkNr@x{<|T+vvkJu&ew~;&^sE5 z*4?97D91KT*^;rKNNjHJFqK}(zwi0j{dF4mV$J=DA~+iP_5GQz_ua1f(`>^((&Arz z0(jVz#pz4CAOloNwk3_|Tica^jylLO-d&RWYfZ|0_(Z8xiRpi!{iWBWI`QIcMv>9V zsP`_?!lHn+WS-SYZWG~9-|S?b${keqkOn_Blqxz}5Q$}Wvlh_f$wsqZ_zP-_2SoYt z#m*?sj;k+vM5wqOa*5v7WDQNZ7Ym}dw(%M~Q4nYLf-5dC6E(RZ^8Dy&vE>#Y0zNNe zTWc8Z)`dwCp(f#@x<47?6zh`Bzu8-Fpj*OYWdJFhrFe(Ru*&IX#qf$Xf_vOIYIVK4uw3=pAvE#aoRy$pK5y zS-I85xfj>){Dmnd=$SII%zpnA%GQyt`rz-dEq2S>EHM~a#Bz5X96t@z$dLLn0(~ME z*4klAv_^>gRmhQ3I8V&-dbIEx)DF1Hedt6ETEX3GLfJ_VTYt9pcPzLCue*9*@JmVe zUxzL)CrRXRZQ|?NOo!CfVz&4zp1*s3xoH~dz7R1iV5jrrY)h@!dlvl+-*r4g{vepD zb{yOxQC_PM*8!RQOkseWifzaD4XW90?WG&>zPTw&jzo7?-UxmwJBwmjom)I^+h_90 zbNfMmwfoG&c^bEQkMfyv_p%$_#n^^OOrlG!%WabGX8~Z(3Wv6M>wO|R4msN0!Ex@* zk|s~(jm?E5_y<~7V9a+?jYc;uD}Xo`Jz?eF!#`g3PMe36BoPj>!nBMVo;60Ac@5F} zWU|-oN6C27S+F!I_eFm8)Ld+Xw~l-8IgpJo?xGc<{R0oWAU8sNZC0ufg}!PpRIA;Jam?}U>eTU zuj6Wu0*x0%=m>tD7cYglO(&vtk42Tt>dUKsK$;_$?vjZj{;$Hnt*%8&_{v&q=&Q^J)s1p+9)jjc~M%*K#cE$EfT5fJ`b zE-5@U3iE@Jg;m_l+;*CWqiK}i*y*Ymz<;ev`Td=QcOg<4jtE$IBVZgeljVUPoh}9q zv57S-Ro-?+QW(&5u?)xG<{z%%YCJH}}d{llX5&=*URQ8+!Tn{aE4#6$|F97h0!!g1J>;JWHD$s%x(t7koo98@E{GtrWOL47uS%n)Ae>nCj83NtUu15nkbW&()U#xz`$>4z zyczd5|Gjw1l;W^((GWk#CYOQHQ_03IGF{Hj%R6>l?9VALu?lJ;l5B-+A6Wt&|9QIu zz7E??vK948?UIMgBzANYz#IAFVpgDZS?8Z|GEgVFwsY7|r30T*={(sW(>;`map}Ca z_{IMI`{jJuK0&%U%)AsJbX>j~x)R0mInivZQj;q_1E^$IHd~4jiA_kFXuu_*j8dy3 zS4l8Cv?2y<=Vj0%o?Sv3U$XegSG!)Nwn$|yr`^D^o~`s9*SX_?mUrblvvVx5QiD@s z$3W6e!OoD&i?PeUQ36VtNLyZrQo-hAqBUnLB$X^UA+JoW82kBi`6zwLG9#>m)@^?E z^B2h{V@i5o%t{n-&udJRL)LDUR`m5Uw}y3c`8SI9n@e9IV^gLoe}qrT&eo_ILbnC^ za##f1GD+eiR4rKM!KGjAblv-T>t|I)kIPzR&ig{!%#P#Z=saMia6RB2uFpa^={iG!l-?p;8+TSehBXjLc>ezRz0l{Jx$oX+&iyBq_>p9h zrI{Pm;7I17zscP#vDZC})4pR^7kNh|WHKOLC_|_%7eb;ugDI3Il!6|B@0@~2x%`oV zQ~2q}r|l}oD7}M%*Cn@K-Z#V@mc;GSFivlww@>sWsYm0mH*?$E`66^*gQC%>QLh@h zycbWyqJn%6yaoV*^qDeWVZknkW;Hqmbv8Iz$*uLgv%Hike3%}282((4qyPlUtxGOR z^Ow8Knk^1;8e~tC!6r5d6f#o}lY}loyY&~*1JX!w;@z!*VflPgZn8K?itvVG>U&KX zHX+8>(P@G&ba~Cn9t>S|nG_35b6xzB#T&;D{Hehi_r7psH^HM9K z*laTg<~?SRyuJVamX@b&tY+9|Yvftv!ADR%WU3ij3^5TlLfurneHDQl86=@F+k*Sl z2^Nm*?1b0-)TC-LAm+~1FwulQwm(fr&XBIk-81T*gId6DFVnBG648bE3{g8qH;EmU za$F;O4n+lYXeUJftUkwmZNsU5`04)i^%$yVMorPKUEqniZM$-JoxLG9q+<6{_`7L~ z1u|lD7W4XubnY2zTD?{OJA~KB>vlQ3pnEXnc59BJQXPl?s#76-#u0k*bn%Rs^7bzQnuHi^rV|$4v``V9|liXv;)q#&PWN`BQ-KN z9hg9QVQO0wb|HCf;ax~C1Rb2)Jj6yRIt6EiL;D_Q3VjRer7`BC9aI|%Nr}t$aXsEy zk#B{|&Y2XTdtQNli!FAN`@|uA4_bK?@?T`9xp&hLbEG?!p*KO_Rb}nIs=q#!=BDGn z_*~(w-{fZKTiEms@&U-5mf|>@0Ts7Rh#R4N5@?YcoL=%4Zcxf{oJLn_%oS8Kd@=W} zm{xg}dSti45Sz2Gv-LZ{vl8sJ`i*B1kF%xR)G(v%q7tU(lm73L>36Wlss7;%#YTvv z5kxY8WM97j5%IBsCroDx#PCG3elPIctFSr`3bW{^%YAvns~Yv*G?L#QRwY{&(4Rsv zd+v%F4*DM*kKa0}oeR3B&y`~-1@Mw{mzd9)mU`YS7NG-0Dt2uB1x>FOKH6M!GUZ*!}%g$9HKg%q8mOY()#ph|+Pg4I#@39^`~s%qeq*@k5-5s$y) z1Noh2kpohQ-0_qjwn}j*RrgJ>oIjRu{%6MtO9g9o?Tj8(&UwxRAWQjAshkxn_|d(1 zV$_bTBjx;UoLkmv#b|QHGJ>KRxdtv?%FXGzdF&VO*pg+q6)WGP8#u+sOfGay6vp=|giF zNhrw_vJU2Vnws`Ia1L2*7k6K#`=06u8zuK<%Mz9^369U-Kur2UH&yQ@r!LIGzIU(fyrT zSrWHf-&?Vu?h|K$qy0?G7bu>VFg|0=-6v0ty^+?ji1*eFD@Ua*!nJqs_kj|r_bdef zlBhxP3lv71VoU<1*iCdI-q4|zaK}EBD6rwUPT{8OZ%S0ZIHbsg@4^(kX#l;1ap4{C znZXHCb*&xa^uRYf9XYlkp}KO_pLBV(f2s~=5K8Q}H7?&QCE$C6n0iI4xQ?zh z*GMIUmO9_c;bW*sY46sq8;-;Is=oU-BzQkFE+_P^^|DWKU2gsL`G~cv^L(XD#pP8m zi?ooYR$)*D*W{&0R|$`*QH)CNg09Kch^x?9T_tKa4-L(z6^O;0Cu4fkUQNQ;!Uk$k z?EZ5nkuCCevfUgC&%(>hob42s0{FvpVnln;Z}Rm$hMib zy5I^s?Am&skCYcY7+@^8UFvcr^_ZQ~Zwr)Uf9$vsb%pu;AYM0wC_S!s;>c@9silrC{46iiceAN@6asTw6Il=R}+C& z+oEe?eMA+F63%sJbTovBtQj9Yc%GvCX6pDaAFE|BwNYmTlfs|ajUo^K7bQN(PvAZ8 z|I2$8fA&H!&EwZ+p2$-25*Dskjc3o?^dd0HyVGOt*_CZK^D-{@HP7549zSpqU9IHD zoBI`6VRBA#GIyV``AVqrb~*`TS&mH;8$uss>x#_zj_$2ZNe;A9dmc68+7sU_xJdYG zZ+Ts5xDEKjFCrZ-aq5;d9zeOJFy0%%#$p}y-_y~I6^iIJY)uG%W=G<;NkTdPDY|fk~#6i z(p6#yHdFOL6=wH^bz1gEj+C3=$#|vG3R=R@7FB zs(a8bvp?Qg8kXVC0oIiLzPA5Pf>aunm%m&U=Y;qRt4A4qV0V4z%$Lyrcm#}=Ns7WXQJPXjGQYk6e}ya zqC52Dpy)-7jYbqVd~hh?BMNAD!Rw{Hel;0FhtnYh!G6MJ!YTJ8+Zg3tqz4q@3DuHN za&H6>2={Tl`%&O-ba$51+h7WQgQ!+xZXSdcb$_2>{CQr1GH%%&>2v~P zxn6T2)Xh>h;KejwEIaD?Pt{pXs`4(F!X}@gLh`Z+-6V$eQv@bo)o1$HLgybxAhDF% zxiEOavvWC`J3Xh^k`~ONz>zy1fS(;)gmB?bDNuaUb*g_mT0y|GKd0}0U$9=nq6)WW zG_7I0n*NCOdu*V7B-@Tf5*sOrp{RN=L206xzDIQHV+5O5x(0X>k%N<-P|I3X-T|8W z(hUQvu^o{8Nhf1)v-n_l6qiOz?dW1Sgyg3^`x`qX<(cQQMdm3;%xTXU%H+k9hyWz> zzC2&AupsDF{Hknc$RNdos_U|GJBH#G#FO3mk3B3|LNR@nK*$kl=Qb{k8MaPoJqc5@ zyCgfJrP)Su%2V(x+;?r-vIrb-F)r+XOG5hImb?!3H|>8D=4L%3c+;bey)vJ2V6aUy z=xcb=$sG+P*IC~Hix=N~Djtm$daPxLfr3Q-hmebdPpNTzum28i``k+!HYap9-g=v? zL;eiqAiKj&SGE6!XhhKDoiilR0G<@nmorC~Z=)*3s{f0zoW37M3)h93^KFwdy^!N% zj=H{TM7$zBRU~LcOu!{>#o*l!+cdwByB7Y1>qzb>QcdT!R^7k~P&!MxJEcTa?6HTY zMl44y--A-v++H&q4$6a%UqLTfy~;Z|B6g=x^O1gr0@TMB$SdL#YQ|V_?j;S4&&t`d zyB|LTG49-Rf{K4BcSPQcs!_NwZIf9fy6g7o%?&W=U#Wnd z^Ul1;F*1M)3Fiv_SsUQ=-5JBcE5&fXIoa#EAyD<%a2^zH(eMkp&U05l5RU4e)NmA@ zLAUv8I(YgtXFk^-?j-sE_pnN{6drkA0C7ibfL9Fh(YnkUiBxzw!9CKzrwG5&4ZZHV zxwe=351|}pWY>oKxuM^dqHOOs*6e6$NfoveIse~%wYR&v+%8T2TAt+?M@WlF(Bc6z zyhosy%s|Nm_RcL*@EBQG4heIRZb)#-v~P+|Efb<_Ds~D}iuH~dz=Q1WLB`c37HNgS z3-MfRt1@K0O*XMt^7CYJWX>Ck@D|R!t&SbUkVt@zV1&S}H07t(KvLgy_Wy|7?5_V7 z)|-=Ok+~g)Fzr_8FQl=0B0N>LJ1sesvbM+7N(UFe!C?#E4H|$JLXJSA&_PI# zDnO|VwXMz7X{lyAa4?9l#RlzoW}1RmLpTdwU#KiV#|sj-v07Y_gkZ!FvCt@?Po55u z42FrMC@CCXrI0fEIN6jM{5bzqp%A_LEUD>O<-rr=Zo^g&z;PSK$;-pt{6Hk}RBqt`{1PeY*x4O8)ny#Z_+lk1#4Z3D~HGU51cM^WD`sVPg zL-!gAM#&xxB;*{D`8>XXa~QorrJl23`tjaAi;n1cdv7dLyCpE(;y&=9KlON3d`X1H z;a26}d3nm={#|YzG^1kCbFEcl;t0u7mI950X&d)0=x?4CshgqWbvnD$X4H|6jUk&{Anmg4P_j#aw;(ob zTZp4@2=+>r&&v%RvNluDt)3SCuALav>7QY5uc1^(yu2o4TR22wt}t<3D|ZVZO}=qtEI&zm z2}Y~Ezo3_a?#)*Lwk_d1!35OIl(wr)D~1I6YS-qbEs@S|=+Aek@up}bboFiOAp4}IUDgGZ zsqVI5e)>^QSo^eu;eG!2O%qs=Z!r0bzHV~ex&Joxe{1^x3JCnSrY$>4%}DjXuK(+W zLaetJL{X!H(iN2HI~>MVAE{YLwpGh}wVBzGuzx@hwe)>o&yu&*isrf`6P=^x=`i`_ z-Z0dDtexW}Ui{;ed=L7J#Wn0b8{P4uuCJln?8Ij+3)vBpr_xvjB(rX%(AtM|t}hvV4l*Q<{`68kU!@rT z1}V)xMw%lx^Dfj}*oUazEGlUn)2TNRVvNZ%-kO+6=W8%0jMkhq#Hg>4_MeDU+HuykyytCK7cbsHwZOy2}Vvlx77;ZsHL@7!4(JLexfQXFn3J8G^wiWFK@D>f_4mcIVrs@I zHT}kMnn(PePKQ#SwUVlDC0V~DR>Y711gZ3$4tQg!c-~;B>H=efP80Ak+6|?c7tzc& z`S$DTVv6^f_%HA2ux}CN<;)k=n+obboU|y(BSjp3T7(=N0l}dfJ?Eh8P&)Dyrj&!) zZ$lMSDT47KpMk6V>h{x6W*9NO!|zS2r^t93iXh{RkGwWC_JhzgT2q9amHaR*|b)Yp5e>gF5l&P0(A=?p1<(fxS-jP6#C+C~YqFpM<7 zDL>olNU+er?-H<={m$6IHB}9AH?`^46icQOV@uy3hE!~!W@{%H8hOO##(fN?VHCg^ z8(v-wB-Ro8k=f}T?5xJ%HF|;)ON!d2WwXp|A=DgGCrFyh^e!LbZ}WlZ?cR)_yN!3b7#qGJvz@B*A`^Fw_obhWi+XkA&_I%%|)NTVD@ajmQ zc3jG;4rC=L$8_!_2bZXFi3-@?kMD}9&n*HbJ)rVIbxv?bQNo~9b;QEu4w~_i zZ(!Xc2BOS)vRZBoO-iAgX%@0v25PB**5r@Nx+9sUSqTB8Dm!F*-^8{7_`_V7wttqiw6QPR}?<4kc1sLm3Pnahd zgmfz;Bl3*9HF!oSBO)5F*Mnx6-D(H35UMsGW{qvx*{H&m2)({cJ$3e2{G&gB>J>E@ zrHjn)6>I32Wz8K3@}(gJ=I$>{y40=j8W0x>2H|eaN@)Df{QD6Zj{Q3fv$J%l8rQ&q z36)-FbC02zYP3?3GVuc9pOgvkMGI4bQ~tIOx(CQ0-Mpo3KC4gqg!y3OnD8m`B4wVB zIIsPO(vw*U;f5eGnO=1gV_QiQ)~xV6Y`XQ7m6i;$5Hn~_ zr2vy;KtAL_gh7eM9qRbsmY}w3p+9;&Z!VqL;?)X0k1I6~A*#^!hY)G#WRGzC81= z0;502Qc|F%IP!d#JbQa_dll>l4K=hK5dVO|L{NgUe7q?D;}sSoZF7WWIa>;Cjq9CP z_}@-PY%g`tVP8Qd$CsjJ^M@X%C0KwiE5O!th>Ij?9iEc=Df{q!tO=?YdTZWYJO$Aw zEK9xZ^CKQF`nm3i-+7K(`0P$nd4?ebXgUidpXB0Ssi))T zNulf8xtBdXh;AgSR+qKi9G;7v`3uhrRu2*#%G%c$2rS}^xk9-zOLcnRGi#w{&z!Zz z&6qwwTTR+!{h#>8-Mlcx#%CyVFft8W7UEIF;XY&IQ?@M0<2r?@GA((RI{P&1)6@!h z_h@|?s({siAy@s>)Y&)%PO*p=<`Jx*Ia2sq+~sKa3(k!O>cYd~ZT7mQ76b3UH_twX zK>oQRbJ)X+Q1nO4Qb~c6_&$0_d0Q_kqTW%#bErL1hAnGq!Hj(!l(!_4i7dKVWp`D>HbpGfBiGykY^8}@jgxrmYjQ;p>wUcvW?OhJ_Ui=7eJaoEO_y=mir z0X@@3HR0%WA^+tVLB6A7K`H-}6aX4y30_J^CJ4 z?xIeyA8U9P{LyJT9NSR%C$Vcr)IL|c3lzBZsX`YMcE*Jk`iuR27GhjROn;l~oM|L{D{&+X?0>q@{NS;qdED&L`Uk=kNXct3gxBn6oP9b^uiDrbDH?j>v5VoBDP{SR+_J$&)%{uT1rsj zknMKwE`}X&(pY5w`|?@-;(sgGXZwEFo;ft_Msvl#3oGy?CMAY~%xf}jd)Z_b?OaO2 z1&y`b)e?OGQI0&Ry_~-#AiA@=$=UjDX*b@|mpZ$j(kesv7+t{KRA2e)7+%XZ(`Jjg zMwbP0BfSd=Qy*XHjPWVTImt~&WFRH8mZnaAs9a@ZC9DuD!=ky^R#cyNJ(Z&ESYqqH z_Co8+DZX7>z6c3aw$NKBZr=6!5~A(4lti34wY2V$V_C^ZdyTmONz2#?LS?bLcziW~ zW>JxZS1Zjm)7=|3dChBq{h#%Gh-6`cJTZ=uGtP# z{C!Dk0+KhyLXgl!h4N49`F+dHnaAY!Zct(np3YglAF#fHAWaQz<4bM-6tqK|!qUXa4mX;oYHcF-Kz7#+n}$z}jVMlw2$(q$Ya8k?0U zujat|=FkLAm_tJayboGja%^`z%|N0^2ItnHU^x&i8ai;J2B@(vtM=;fm=<#WNIkQzzOksJ>$b51>-QpeNO*r=?QYEnta*gxUXjwlo$w^QC?A*P zL~=5(e>lEIuIMl9ER+}}y)kelaUWe|3$dZ6-)l)TZGmKQh{aHNdREww)KS^`>eb)Y zL`=i5wP&GHT~Z}hS_@-jN{|XIs`XLIQxjb zVgu%`x1v0JYtv}G;F*QzCVln0=OazmcB+}>o615jpnuLZ`GMpd{S7?04nm7Ln zP&B72@vq$I_SYDwHO8pG!wqoLQ*}-Gc5zyJLXd>6y>1bE+aT z5k%Q+QHTSH}8G0d{ptZgS5P-L0WHG-z&q`bMNL(U2NxXoOy1` z(d51lsbhuFp6Ne?;H+goa0^E;o+U#Gc;LyPp1Z5{CY(Uu(1I|X)!w&q`l$3Qa5JcV zqV6mbU%=Z=%uZK3b-C_E?hV^sC+9vQj6`v^O**c{MvVoiu1XLOvN%0UQz@DWVPw*o zT@;021R;Pw@}R+bb-j1e3LxFOW;d18fX30d_9{ep4}vsm3$^*8~Q z31^--_I-Wu66zB;Qf5VNpts=x|ADh zq!yf2xErJ_s0O)?c0!x<^g26@xc=n9Fx>t0My$3j!2jbQ$&-HB#;{k!FRM@!ISs9z ztNW1JQ8vJ z0VTvT{l(M~I$kZYuqZ9ZJPJ#Z)+ykpwPS&MFqoh|jk+V}NY{9a!r<REYs)r8P zbV`!em~EFvp5a)Aw?r-WT!D2a5`~lV*w~6nd4v%Aevg? z8&cwwTf|`9G%wkiKO+X#jnj==&Dg2(u-4_5X$e(pen(Yne76!BO&-fMmJ_~5X4maY z(WUoj+{IcPcYZ(5&QOfDpi!l_NNA2quGa%YB~))zG<@GBZrf901c9kdU!;z*69Z2|E%(X@XA4Rq%G~Cfyni+@nIm_!rpDa=6z}TlR?SE?8H+KJ^-!VX@R!VAD zzP8S~Zt&$-<}ZsT_e3|9zy=FoB~@GdHm(zV4}J2)$bRz!D^v=Qhv!WyBORW$kK|Dl z3`vS1Qf%;~atmBz zSWm-BS(28eIcC-_=F6?SGs&3657#nI53jiZ{FUg)D-J5q&nPK@VrTpV0U*Te;%D9S zhZZj|cIz1*_w9T};Hz(9NGdMEmB)XhWVUNR95k=a48kYhL`$gM1g%4C2nU8bCxrn4 zV|yse$+Sa@A_RbydPtK{y%Vg|Pj&^HmBx>XJiJ*tx+~Owf{**(IE<~pr4N3NQYSs= zc1k7rjLz_*mj&zGxT<3NF;(qV5@e|uo2p9$ z`LU;I6`N@#tUPy(2}NBiDBfQljdS?xjHWrt8IZDfeC$P6e08JP@QP&AedNM?3n%Nq zCn0IqQ2rUDIS7b<6(1fiS1)9}CWtl18r`n(z!OWgoMaF0>Skwx-NgQL?Ug`8mao^AO7m zT^-dtYj< zk5EvwT3AT4T^F?d&{U0pB&pR&j0|4jrFX0ak$Q^1JJ~QGdqjhfK>v=3u(eafDY)NP z=ILq6qu%90)}_t-LegL-+@>U7)E}Rtid)3vTG>}|?lApa!s+e*HCE}m?n%P_A3QfW z|BqEjQFg=!(B=AUCE|51>cYUxzNj%-o(BTxJDZtQueI0^N+Q9^}QGgXD;NWZ3_}L!A_0W zsHuqg=&6p+A3p7yDvAaa@6+lQCSw=iORKPgdiEn{3XBB4uYXWjAnnu}1=p zaElq-2KX&LySP%$BrX40!tZGPrFXvwo`x;%ljC?WQe~_w_uOt~;~QziC@g_($5sb& zTH^gOn=K_fc~h>x=%iF;fC;DuyNKSW&xUZ>K1F$15*D1e5z-t+;yF1EFsB?=OsQeH z2M9RVa($m)?h$ZkQfM|GXO4i+7*j{K`<5%%P$W#TfPyQ=-2;D^m2)hodAjYE4fc{v zGQ{fDsW=vRcwo@%)amg~lK14O_BAP%XXaB>7AbvC80t#No%Df>AT-+AB1mJ-5!3zq zdOgOHG?EQY9hD6?`4LCGGVpi}`S3c#S$n>#jBAQF5d+nUbsmsMxWX?%1TvUL`Kpss z$5Y1)guI$qPlIptq9ob6E@TU-?QDP(^=-<@ltc;vFFi{)8rrk7%1^coJ>K)izFsS& zF-&+T?A8Bmuz4o528ClD-pY&~!X%U;NCOR{+N0vh%~1u9+<$R{e4%ptfhUIdN;FEU z){~{_Gc4vZCb;|!Pi{t68`V65XKMC!_IMxu7z&<_$@pf|br%7MGqibs9;>vvdPR?UuXd9C|S5sceKZ}!04uo0_mojg>LkMg=uwPv0J&Z zFzil#M}JUwQ>tjj_jrO>ZmAS&SuKh&Al(%&E9rFOl<9J@Et&6{=SkQ~iu zV1nC_5+D(v`SgH*K8fS~pzF)KAj19Jn3OnDH7-8P>Kq>zfsL6X6wBdbP^hx*L-Yv& zS|KisofxwDAtrrmUG~NwJ}89n6k-TP6hR1Lg8mdge_~kY3A+mTdwF^gw^73)2RxJX z9U2%s6HF}L0HS;S?(v65ZK_8RY%N3)pV+%jF+(Y~Q0s_`%79D9<;R;@F5~$dQ=VH8l|1X&=f-0OP2FF@K`&uA zDpmqpXuTH}77xxsHdhGBXh{*6ZWGoRrAvJ4hMgzcS~&FRisIch&SFMFsjr2*4KH3W zPza?9u|O86U|h3J7mvJ8Y3_|HkSLq;hLnxpbVAE;=^G%{y2y+yP&dcCbQlhDL3$nDd)L!pWVt-# z2AlptkktL<1Ht-J^5cZ`{Y%&-LE-d%$p!=C)3Wn}HVMl^OQa!9i4Xu!_-cHS$epQr6dCvldrO-N;b|=w z{++eem~{HRAVhPsZ}MFs;QGh5dz>&j0aae64>?e5%?oDc;vNaofWR;*0G-H|iN7xa ze0H5ahRfG#%kTER-c?w?tH8`t$s=E>f$XFHl!)~yq&@OM$9QZ;(JA>n`QbCA=Et4l zUb-ZDeD-{?0{^fKRh-(hV}9Q{>@!zoF^4hO&7vUdEid^CQn@+wc zLN-U1HRuaw8~lxY5}G#NVn23}KTopTDAkhEw24(WsZ_RgAt;D!sf6-ejnc@qD4n%1 zu6T;$NSQ6e{cduSs9@-Tvh@wW-k)22>aRfbi5Y_0PcmXOE*8zKYQ2gzq4siQbso|B z{*W_R&)wbfikKQ@bE=vg7o2HN0{~t%ox*?P75=lE;z09pyPMY-1s^=oB*;mp08eX zVrut)DL`FEgTo{L86mn{xASZi3v$g^@k}XkXM)GhlxJ`$*Y)M?bHg6-W~#b5ak_<{ za^;kjTNU%t;dCWVv-7qF^Md*`2K)qnMgBB+U%L*R7>0vTez*|jQc@k2*&MmvYMeAQ zQA0Bs%Yzd}*w% zX0Jd*>nVgxdKQrji)M~`v2%1)ToPDujbXUWhoV}2Qg`3c+6!9*4C~Q%83!$^2A%n99d9gFs(r4gd3qW+iDHSe3M%J)qu(@0 z>Dn69t;y#i^)ACg_peUM;k#)zzME04WE>3?{Qm*d|2-XA&0{Px{uc@PA13l28Hp3} z;6hfmV@B^M;J>0kI3hI^$eK(DtuHFa#T1NhGf{0L%Y%SEi)^mFEKWqjGK>bM1hRoJ zTWEOXAgM@7fAM(wraD{SlR8q@l7c*4xYm?mfT-YNa}05>36)Z$c|(Da+-0L5c*y?|bR*`m>`MtqstKzxD9}z&1XX6pn80>X;uu>0 z2t;98nGKd)Z7Ug68^**6(IDBug1u+XPqJHHijr}Z^2GK(^nUvLtb<#140)uM(g&_I zN6{PIa7GO)>#|>0j^R{Q?ix-OB1QddNeS2plji82T+4e15KCO6Ga6_WK>qBEhM_=0 zk3=%~4x2EF6nhH$DTka*ucy1|ge3;8h>j2GI10J-F(dk`pF~(u@VYV+s=$CdFMbIS zPC9HO`+i#gn^$zbQ29V2F=4OnC;Sd3sut%e{_6k4Hg4ETN;lZCkc=uaKpk71lFdu{fO;DNiY{G&{#8s0qHwDF z9l}_9WW4WaT-veJq_7Zam3@hYMfM37FB@dhfXI0{xeuoFGJHLGx|U1_(`u*i3u5HOyI+nRu~3g`QwL{3lbw3r!R) zsu%H8st4SYc7Cl*VxDtOl`#!haJiq&!M!_dYOglZM^NSaP-ZaDJ1zrr@2r{Xm3zG% z+~XBoSj0x?&(xR_XCqMF0{jdg(W!j1l>q6;=ce|wzkMwAQW!``2HQcG_R-R`MI!je znBZ&lBkNUrHz82h<89>z^lI0WVflD+8C&H=~}H!t8mAYCRoMFY}i}PIg$iMk{;g6W>1aKL&$>$6HUw^jTuNQhMNyso!ZrshU z?Qhy5P&+|4I5=VJ8~md&6bTfqD_w^x;`d>ezZ>d9BE!k$t&uFzpH@K6D%+FM z@&skUf*9dlfq%D!?~+X6)|w9<8>buVt9)?w#7LH#o|cx|>%m9u$j6SmLcyn`^uK3S z^@Gnr+_p1bpAfXxqb}rm!lwjItMo*(eus8HE*(6{{-khCf#x-Xnp#Pk{&dB^SQ%Kq z1|~@BKBKEjmCEDYjJA>CI^)1oL6BIf^FFoH@f;JmKHV|SDqFu>o~z#k159?Ln>^TlVuU{oY#(j}L3r5r3$7`APG5>GaMrHeLx#VABf(nf^u=rZ0$c zIl{6+q=I!aov}sZpx3CkI>QbTM3bB=?jN;(+bj-F9-kCe5m6g~L>0sZ8V;fAb-AeP z!zjYqMbd!3=j~1FrN_snx7En(16B9tg?auJ0ru3;q>1VPE=C}CERlVsE?eB`@>Ok3 zZ;kDHxs;7bO-1ch>k2T;a)tO2XK!N(DbsM4M~^RcOm)$VwIcY~mby{%hs6%E2m{?E z!FXK(GL4zpDTqGOT)1p!wL$c#o*HLN^ZMZ>sf*{w5en0E)|Oa48h%rgcR|Vm#&1n! z)1IzwQ7R=90w^ch2rGkGZy$i6J5YQ()7~kj;LC?E?G!}}ETyapAyHK`9F@U|*fV)PSvCKsuV2Qkol%=s{hSFah?G0wl~&O5+bV$lHmnJ)a#R*ZE6y(-GW^w96?%m z29r|R1yW@bf8JzQ)UGkt%Mi;N0P2+|0dCXbLl-x4JqO3oZhxrlc{K@C{=KyX_`N)aPSc|n=B z$QKIw5AXN+)Q{?6w6JBBMO@&2!tvpiKWdPJ#ONz`G#Qh2GPuT6kcMCBj}0QalifzQ zLh~>AlN%8y`2d=iQ7Oa6`|n|4=G;epP$5_T{f=T;QQMgpJ%`;!z0(`hKh+pS zM;%Zv%xCYK&h_@|E5x-Aan^n_gj(6oqnh7aO!W$gK5{Qb&sQx3puRCU3|5PdRsLyi zZ7Z-~m9Xa>T07fO+-}uW+RoOTjgb0yg)e;Cu7sw4_5lbvvtWNxV0G6p{$L0q zr4#iR6AU3&^I!J_TqN@50Dno8Ym*41>x~zSm}^{`0+;Pw$BTcNKJ_(TE#`ClUU1VA zcrTkGC&VKt)HC0%JTNF#>2s)s{t`R^Dl2k*4@ab5wn^Kxk1=_K4}0BEFWTIMJG7K@HVE1rXyXS6mWS#S15yDj*e z(l>0IjSr_kGI)BqJDqXKQH34HN&)j0!V|YDfuCQ+vdXz2fcWQYfE9dJn<+2hU>IHv zvgwmhi(bMrMCOR=L@K8X;;W+?OIa+B!nTvv{`u+K%fo<8dm~I71$U4S*WwFe?V*^S zPgHNI4u+3@#min{$cFU4pNfy*nYl*6Ar_t&lR&sAwj(?o1YD6`CT3wCE-XY4!$#zPqV{KM@n*5+PRb4JRUnVTtM7zu1Qc zJ}rdd47qZ5XzYnv!zq4qoqWP(34o=}tM{@V_^)&>lBDt7bQ(mBd|UEH?TI8&0Ibly zXWV;H4vk(Bn0<+!lemX{cdj(#$<@yOxQ3j7?ue+kqejFtW#C|_KtyAzp2$hNi=W~w z?_G-(wSE`c9Pvrc7qL-?zWNZo-a;r902a6(wmEf)zB*PoUB;Uqx!c&6fF!#x3C{u? zQQZt;-#*l}+3;ut`aNDpbq-BENJVB8p&?Rq0n5gUHa4rwhsL%34mpwB5!FV_EswvIS%9&x*o{-?6hbFZ}WH5kcQ4q~lpJCSn zQ`<&1psfJeD^R`XPL}sCAYJ9GHuz?@pN*bK#u+XE$J`p=&4tiF4k4_)hirUUYXV#E z0bbiz!}rR%a%CrQYz91-J!K*6pNjQDPR%zhlrCr(s)cF=`dw;z{@d&M{hN@EmeYj@ zYk~l&2M}7sm!VxjIUq(mb}O^b04P&t>PXQIyKA0^AG1JwO9qC+74(!DIa+Dtb0#0A zR#vrvqZp0Qwx@EV%^YQWCKMJUJ zbhqS&2mT9{I2c!6C&953fnHd`3S&-zkn40D!r_qJziyKU4uM06jDoitS`hUpy51h) zvl`_M>*beEe*fZH*)M$4WlE|m2=Rw`| zeXm^vVH4>E*R8x3ro?{wflrD`x<;JD|aP`N$x6rSmDkun-SVj~z!}qo{T1LK{ ze*k6(WsQGoGwl8@2jP}^n*GpIbE}_jlxliR3g)Wkq5+a?fX!|2>bOirP07Hh&yhho zMk=6UnGK4fS_O(GSeMLLfO9lcW)3}8A4;ABX@DP|8mGO@oCK45&KWuE4`rJTnmo_I zZFOrAzKM8^@8$79VZ@fSIgMYi9=tX<^pPnELlCj5ydr9+rDabTYm)d_tHL%OmDfm6 z>`*${&DjJS#fe{NI_$-9Ty$-5P17PdSgu!c@;W2tJX?hfeq zwh?$SmB>gCgTS)M(3iB{Qj+*$sMSW1j+P%<6V9@e-1IFQAWcXMBSTI4pDKGUSUUn5 zCa-R0znED%sL~mCuvV7Vy=Meha?o|uQg08|6BEL|oK?8UMe)u^WI_EKLdGiE!{1Cl zt6%sm61F~#^Dpnz^?U?_!Pno|cE^j(M6@r2R?#$28h2)Aq|!t`2^9Btf40Er?Z>l$ z&+aUwp~Ur2TyFawkbeq$=m4}r<#6)xg+Kb)!v}fdm9fZ`Y`!12#og7Zs=qMa`cP7MAej-KWZ5Qnb^K^cj~fKDi>k{Oy* z@+u)E;bMwfj}*P;^z)91hu4x?xZdS9gBz<#NNmi2fP*0U7@-;O7vB+V{CtboUm~+i ztI{cM!(PnEe8tGF-W*Nas#@!x#G)Zz%vuyL3|wWar?6cB;gQ@6U5za!*3vNFPcOc& zt0D?59^}i6)lnHpjQtu`ICvIDKX@7pEPyUc0(G)_HBQ9ES5l}x=t|8L`DX#VV|BAo z=wE1sRP)!|$a+$assIi^?p z*!rdK@Cxvkm3ds!t>$WgEi%wwr$PpRln+^ZzD=2r6u(mbpRhU~s&#DMta;q6T{^rZ zMtOQ@_yxBjq5sm;JFIoc0nhT0-e8_0=bRpB%c@=Y!)nv8XzR_P@@jo&`cz@gJyp&^ zSJR`eG8D;8k#=AR5G$zLF8FGTd^Ka9qlTY;<_;7ibaSIo6XGQaA#$6f2wHb^EIBpy zZauNLs+zR15`NS*)o%tT6Z6XsWEasBBa|6t5U=b1x9qSKs>wto(na=euz@u%Y~mz ztAt-dVz=dAvQ+wa;ZY)rtY1`w5u2=9eFi+_w9C<g5qZ`+)wo(Lu*e z*E#(k(q2;4Yzum4xqg#2kAzP5icX$h3I!ZfsM4PpAx-(+Z&}Geg+{fuqG%pj3}4dn47kR$bB+=$dFz91Jqvw7Uv7Y~c>)dvtBR~+6gfuJkseJ0Rj`2QV>N>UW zNSZx}o90fgwL-}x03k%D72ug-sg*VU{Ny{d!K`Lthc`W7+W3=S#1yti4Q>Q=tvNQd z*Lbf?fi#Vz-NnhMk2OA`qLXt9Bv7JdI>W#ZkB-r4XpW`S_yTOb*-4e()|H~%h`sDO z=bt>L{`6h>uLX55k++nr2dQ<9zc=WjFXL>h!Oc_36T?_v!Jrpn_nnFh=2-cL)s~LY z_ofDAbAuXYl;W;t496FIZi8e0lC*4{ACByCFe}5WaQ$!@Be?%+H zy!n_kX}Tepl)kkk%d!E4Tu}0}SQ&1pUIpLgOVM{gvhgl(#BexJ8I?#W+$0%8% zpucn07ljESSs_~q1(_juKmOySPwbOD|M;xEi+Gzb#oss(iYS6oU?i@L6U>+VHobr7 zIvoY+#~rnboF`nEvQRzjH9S#t%Nv7}X9OOwjOZUNvVN^9-D+(W=JyLE&U?-k-NQ8y z*@z!m7oN}1vl{htpNOYNz>Ee&28y5&|Ec{t# z{gmOc_=%@)ckH0f`i0dEf(o(^Y(D{mxAy+=kAVpoRH^;Ku0;uFOkW~A7|tAN3iOdh z_q?C-Tdy46zU>MW#j8gK6Pl)04ASW^>Lft+_i7VFad=$JoipYx(#A!JNkQGr$}+8D z=uD-0NWT1@a#%V@(tX(1+P9K^7G8PVqOe3LFA8z)SBjo}j+ zCye#i2i>O-jb0D!h~~6~7U`29AGPJDP_FB-g zsBaNWl$JioEVGi*L~xCZ*`%ufEq-fA<`LcmWWH&Y))H-tRM75Y+06SML`uNHe z7Hm*wX*o0>9W}Iz`tUp2eEE|S(2a6|fvYvZa>x#G?84A$!RY{gwWTvqp!<-4Z!?zb zXKBPFH5lusKvy)2Jt;~54W)eN%fAF5=h)xtULlAyfZc%4%lWK+@7HS*d9+B+Zy{|; zq=KpZ*xAZOr9QVfQz!BgM{m+red2C(7KbIuA z?+VYz)shx_DSyKg6fYl529?T@7&2{->Su|*mP`ixVu>KMHL|{!<@E=2P1BAVxAU7# zGttDv58u9qc0x@Tl%pfSwT4 zy#7VuMLdKn8~?s;bPXZHih05#T1u@S3&_cVCvU1cDUjwOV!jsBU*3|HPt>_IrA{jG z*0c!5vQ9QD`;gCuw7YgTX$R#t#Vn|>j~lGl5i`;b`_A&LvI$C-0KuX?JJ*PIMirgb zlJE84&u`D0PDaPu!-emNSsp?}GANPyZD@VyxYz#23ow-KArGYL=NKUj!eLB4X0GRD z!B@BBmio)h0M;yVT=Au`X$ggF#D;YLmxP9xLrxEe*B8QUw=P7EpA1X4VpLoe9JKt$ zeeav5gj4z578aU+p4c1d(&GHosiDJ}MAx`b9R*eX81}GQLCg2Cb(S-sO z{BoaNN!^J=X(cU*`bu;2mt40{pL{48y_Fs4fLhJk$z^&oeXbtqed=W0@Luy2P0nd0 zRi#}gGN?diMS8W=CM0!yxwt*Mt<>Y^Q4i^>h&@TM?)2O*`;MF6%{MYbXe)y|sVC1n zNNO`e!YYH)BdFES?lW!mMNX*(5_KB#kEISZdoHitaqa$-4d8z*f@LC&FG8J$k(RL4 z`?Ydmm6Q<=bEgW>6Kt^`fOG`>2CGQ}IpYg9i_DwPG}1AzRi87tcqzyI#BUAHK;%&2 zLk7LhXg_md*sVW2ar8a;>@pyyeTj|hpGw2Eo%sKL!jZe8y;yt3|NnYq&b8&ca!){BStob$oZ7XN`OMFl^NPpnfI;h>tI~Mjd<%f=4z6{#sYv6 zryoTxwS7X3P#47pSHT=d97Y3nQ*q<-(SKijm@^&fSE$-Yv#g~`~yS%-v4-+u7n9HuGsm&o3i z#-8;v?qT2SC>wAEc8eU>^6v2` znuI0Bi~{Re$C-9lLZxM>IJ#PIu`sKj6pRN}P(%`e85O-Y_GMsJyRIYD!1 zve39UYUZG_#7iK1ECu_}w^!xN)*iF&uA|!?rP3_sx^>0SrE0xXlo2~P#}knYS4A2A z96y!Afo5Th%m!_aci_`U$q`sgjp#0_MYl4DKLPkhOE@5DBQ~;o3tib#Z-kG)l~m&8 zXQhJy&R!}R@ES_m7&4`Zt=g=DeRzceOK?zTY0;@)Ri_m&GUYHI62fCjP-!_?lyd!< zxX~NI$;QPS2lXYZwoh-8Hu&Fk(`YSdgyUV56wqg8{meE)cl3!pED0|B-Fn=OZC;l| z(d6C)L6fFbR-KO}Ld!ME9k+?AOQqC2%8}Hl#U|lo7Ov~B*L2hdm#$B|j>CA3w1g5Q zvFw6RP71v5F+?r&XnJr3FRbwJ}VP#Y3=&~m{5_h|4jk=swh2 zr1a>43{r-MqOZx2en*DWQVNJrvc-C{H+3j`E3Cevllut?;JVoy7s(J*`MC4luHW{3 zv}4x?dnA@#tEg2>X-7*U%VLMvjUxOFB_=EGjy!(jR_~Sxdw-6bkAfsgOtrz6ecM}*h2^p{v2%OW&7u$!lzF11R@-Q4Eh1`=Ra z8!jGAZx(3sk6YT4DvJ$L$W(vX3#*FSQg@yZHL}70 z$-|D*{j!G;Mw|~1@-W@$#&mva8HQ8}t|3JyXk-xkAQ?j47?=?%6gz96l*f6XrMG18 zu2o4&Up1%x6x_RU%keY=KqLW%wGLL!DybJDB!|QMFc{$ZGpJDYfd@`o4(};v{0w4z!r{4NkisWR? z**avc^-1vitbt5eBTyg8Np6Xpf{yc#LS_DGXZZgNO~?`GH!d5qH^G0n;AN0P^ex?c zl&7uJu(`FcvS!}HtG`W7m(CowuSu=7y+LNs;NAxG$%&6L_lmsL5x>*_PM2&?o-rm4 zH}7h|b-N$Q?yXP%hIe0q>6?fmMgPcR!uKPu$U>iV)>*g@b^QCqzNeFg<*+S=C0dgl zh&iH7b8M90-Rc(<4vmaRY5qGesnJd7D1o(QF!NZw*^&($!GKZn&*}8%GU0hc8LFB9 zWz}mil29}#Dpu6-mH1^CZgjp#x1aX!*O;C3S`jK6Lh$Sj=IE9aa?Jbx;@7_JcZQOm zI>{u{I>#Y0kfapw8aZy7ErZyR)a=*I4sfOu(!{q$oG1wtB@`?fJt{X!n7uyN#nzeJ z1YN!2!E($a%@gtAqAnXNt}dHdcYw^$dz1N~ZB_Z*bHT}bH>p)OxLB(3ciY~v7mtYp zYD~P%N!$!J4zGQ0a%71+Jzc`WiQBuodjH^l{}(r<{Vg>xMApW{HXd^_@Fj2$${#~o zinbJ`qNF%>$(iW9B^Y;gqTttG3LfmMNW+zW*}FLS{Yxu+0}YF_3YQV_jS_|cN^-;6 z<7xdE;AfMt<>erbPef?Olb_cr#9NMsS2a%dwZr86rN{R}ylwwjS9jkZNR)RryXfR^ zJXcCy9#ED)w3u8kKCW6f_r6&gKgE*0&1)ZECC7l(j|=EJ$R&#kW4LYje!xM$7;b38 z9kbHT86;k!Mah#~9a6?F#qBnVpXso*LG zpYyYD)#GQi6Ne0CST;%~9*gDpTf$O;9dM)eh6ne7!_bMs=pcD3u!inya8zQOBj;h( zUSK#-3A0F*K=su7nONsa1_kH2vSRFC!%P=vTcObBZ*V!h$@(>IJ2!VbnBg62=he_A zVmH@*7{#xn4{pe?JJD0i5k$v-D2b}7g<1O~33!yV=@UUqd*b!XDbo3x3|*X;-F`c7 zZW>efbBNb!{^fw)IFZ8mGZ#$#{47!qP2_%8J7wN~-t!X>!HNWMb^p9fx(GMAandlk zI%fJyQNAZ-Na9-Y5&euCs*Bxr80byCw;%p&+~*;${^o{ltuLvojCev(`3?w{^Q8!D6V#H5Q)xLhII}?v~LG zfEaXfRo>hX{a%Sf$^ApU97WFm0y#wedj1%lD2h)|bP&tmo7Oo#I+h7^J>PH6Zq9S* zzyn65$AGjO@rr65c%8N|Rm>&AL$4rz^OWQ$S$}D=fk@_ffvQS~31;Mhbz-IKI%bfZ zz=xVR9t}r)@g9_7@(WShKeTE@zj>e7R}RiS*D+(Hd9?g-G-teptE{=7>=mibf5HabFh z;bDSL5HG#|JtAowSZNNc7*N(E%WU^C?oA46eL+sZ$QxTl$R5gbL&HVHF?l+F^KH3S zu~O(MC#_V%Emy1+v3Ixdk-^mdDKU#6=zjby&cX$4w`G68rjR zM`fr;7%74J$wR{hOzG8&?Y!+H8A(y}hQl8no}cW^QWn1GHVOz$lKx8J{*~hYgli`Y zKY~fjfg?MAynEQycMQ4=%a{3an55QN%(O)I`n@A{k@NE+V!ft}dbI%q*LqF~$(SAk z?!xoI!Oi>!*??`>GB0%q7Ct$K*F8nVVp5jmQS-u8`a>-}o*Msm0s?|Rh9K@IM#z;F zq%IM*sf6oN9Iv6%=h$->T#S3ec7$S`5|)M$M!_Kele-ncVyuXGqpup&LtI};4xh_d zA^V@`vYgfnM8&+;1{B%ltB$Vu$^Yrd4`kOO)+ zm+rSBzWVqQvA*!Dbc;{^6J%c6V*xhW>HRF3`1(Rbud+JT#6MewnlW99-3y$R#)MR& z)9|wUqOyCUKVbO|6GfbS3f#tV1drlDSYN#)Zyx7`Y+%GS5m9eR=1->4!0F^j4LwUj z!s|Dj&RR$2gzVlpX>EBAdG*)_zNQ*x2dMmc18*N?lQ=F*b_nP|=bXLEgX3RQ@^y_6 zKMBFH8;GzqNKOZ(hM7?r;%sez+wb7R>U`DM+sAebZ=sl|Dz(uehz?p|N#tcCWM@>c zLN{SUBXjW)2h?K!P;SfbOsZhL;CtR}tSjzqTd8U1LtK&W7ki4DIox*Kp% z^^<#Y5|*9&QCCTZc9=)Rk-$axy@eG2ClbHwX$>1H2nJUdE@neKI66eRFK3V< zLe>MBhmr-e_w^|S@uc0CZ&&XSUt`4K9%?7(RMwYuTJ|nE<-7fhXBZjT4epq(BJZ|H z@=`Cw?GdPFM9-@t74>W>PgsjjZzNPKDv5isg?zQF+CD&w9(R=3aWU8Ta{v{DF3n`` zn?f%mv8+`BszYk;x{3oNReW9s=Uo;hq_5NAu!x|jF5d()qlAd_XG6C0uZ{f=OoX-t zGVD9=7$2U{KSb@OG(!n)>ljf>l0}#|O$C#kl($EgE~86*m!0|VrtU{_?h>l1nv`XR z7g-E&7hj8Bu-LS+ZBZVJw1&=qy9^p_LUTedD&^1A4zSN@koUm1_}>+Nw8I#c7?E>P zeLjb!Us-Fw<_*-zcv_3XO%ui(<4~CXaMM*g#-||V% zX09%tjW)|)Rly!(U#R;b;5RrI<{R>$3+#(E?+o6WU)VuT$FZw4qE-N_`u-t_)enRK zKT)4`T=Aw+&(G8A(OnY;;!@rlnQ)FSDK4+fgOfRuRiD+|)p(3;`!<{8h6z88uaI~! zzJ(5?D^%na0t+vi5h=wg1w~@AM}bLSl`DC(K*a2X%OHN_aUxN!5a>sK>BK(h*u#x= z{i&pFpd}{0XmHls9r-tj3|16S0mwYTY`@|Zxi*It8=v4c|3n%ta`o`=Y;OR%;+#UQv2l;E#A!FTk@5l z3?Oj^FTEXg|A;G_znSrUxUc;Z@F{Ps;Ia+&gF2O>ObjZB!=^Bm` zIC~?y?LVXF3Y0Np38iNAQ()V8HkuLgG8cBv% z=OC=gGcXoQ8bjWyo%59lCw_GpW`I8jm-nlR7%}Lbt&_w=UJ18qZoz(2wg&ER07^a= zNf3If7**>0s=6+i<)xTxtw^Mx53C_(kVCxeG1pWmy*}jrXulBD?tOok$k^jIWtSSxmAu{zgDBxQa=z0sEPttRX!ohIB&pc%exW$kGcdcG(LQH zn}&QWv6$Ox&<7;4Ti9Q(ytKY+20Gg;6fDeOTkxFyFd=I?>q%HPJ(5Af$x-LbrbG*N z;b-~3*1S0;k6N}qkLU@2xn3At1j|8J_lxf1sqC)Ik-+w zSyceos?ROXqi0`AKo{QoP6@5THfASpf(7=ttT7(clI3aoyGbT1SHDaBs(sXYc-RJ!0YH3JAujTvi<(tRsZ%(CA z_N(*BGZ{o^Q6FPy7EqeijyD>lHeWvBU=EG|lD#DT)k9=S4?vZN6k&?#h}ny6s9rD_ zKcWl`jS-K{$ral|0;$v;z?+xcli{QkIew0}F0qv0^!O76)-K(Ga zyfsE*BV?QkH6PXGgeuof1iG-|f^yiF66!5u7jA(X;;5lb7Hy)f{94x>ei0&*aGa{e+?>@Jaf5uQk(6w9}+8RC}nz3 zOTn4>zVvKYS8u3eaIVC~PfHD2zUC}`H_E1ugvuRUJmPqTgUv54KTX(P!CtFh1Y7AG zD%)8hR6+jROEA)qBpyp_Ff(0GrTXFb5;(R0jq#|-(&Tv1z@poR$YApUs z)3XfG<=UEvM_WR8la(PfGQ&K3fLqk>yO!;2VxE-HsW+mr*=!G^SBq02L=WetRsJ6w z{3fseHqb9P)pbS>XE-Z7T@5Qn)HB_T*#wZ9TH|RyDz2Ie2%?utMF@W)lJaiQ{qj%o zbx8FR&t%Bvh`wTXXAs#s-d}$Tmq_;NG6HYmGyo3pPhmRjWt?2Y+e-dfpVD{7bRE+Q zo#mS>)%g1my%=!=+{M}2Rph%Gk|W0_EOljoJ6OTy8CSc)yD14?a12)8qlEWKI+s04 zpr~O+6D*Z}Jvom>JlfFH=ms3x=-eiRvO}(9$ms|oYn0xCDwUd3Cu<_X_8Yj&)_xwV zLHH*rm?ltA(oVjh0GtUYwawIoCP}Na4)P6Lut-vz+=YEr!1+c^HO}sC$Ms}l`_B;D zcuaBvZu(Hlv*+W^=VpgG6U|H{YVvng$R`3@$^!xXS%%Qj9@)_5oxaLuoW{)VZLb5D z)}9B!Cc)V#Pa^eTO1`b_nrRF^zW}>Sb80>+PQK0uFN>DpZCJbR*(J}2_&Zs~-fn~p zF|!29#u>ls_%cx?9__TJ@uNA(_9R!I^b=PBA6ng=H?(MkUa$o%!V990QGlbK+MF5T z4w3-Fb%tn<#18@6Cd{ruC}}1a)%(ZciSH45nvA6_30^k^M6m%fz+miK(^VNh*IU$P z&1ut!%qm5f5a3dH)rN8Xy=ouU(iF~xaIf`RE!3L^%@6zkiU!a-+X(TzxB=|L|Mm@;VPz;VXL9vn_6C zcguF{is+=($+|Qx=V4q-`rWM;INb4yqvOcXdP)K7X#POFi%j8y`(pcK;GK*U{=_i^ z`Fy~Jo}lOi>?WE4!Ll;J9s7(~0uZojVIZ+-K*y-nJ-Rul_53WkdS6x$#nQ7z+2^U* zjS00vPLWPd|6I|nj{~{lXc0%hTx=QI_uO49#28RP>L(*qtQW8K?iFta?`x8vI=LsPBEsR=1F$ZHdt2Nx;ilu+85Vu zlzoTG+iJMR)ztc|tq|7S52qidNj6i1;WR{ph=vVb>8lMM_%HQ*jlo91p@eon*;Bu0 z6F=LJr1B{gK z!99)ds4Z*XlkBVVo$V)Xo(>-zm5&_;rZc?>P?rk^et$C-(f;&rh1I(O|MjPVms{Rv zrPO4esMidbl97Q1(;B4^=$X`63}2v0`2lP4%j5h%dkv9+R~Wnyws-e3aNAT2V!+=Y zbK|*ra}M6h-5n22iQ8yR)XaIT^nWuxgpuAV)kKGG%+Lq_FPYSV86& zMMF|*kYS-s5!gv};sAt>ja{b9Ej(wKGHeHooXBxhQOS4SOk+1Lr#0N4oIs zi0T-j$)hpjQpQbO_I8M;JYht?Eyb=ABCCsk$x<}?|I$M~-v2)g@@RgRZ-80^h?a5# zsD|f5pz5v9o=HkktMUO7vL_T7qm#XehAFeihchR7)(A$XSbvH*5o7~(!GEci_;KLtY@$L#cmhM%?bdLi}iX+kF`cPf(KxiQid`buh52EnEmW4F_0AthUkj z@Ydg#4bP?u-y@|yVjkFtT0Rv8l=11S8Iv1?QyY!w7*bYOJg=Dni$^@pN1mK5_Asns z{pL3RHT1*>ThOz+H#587`a6Yz>3Hv48Wn1mzXZwCHm)Sk>q-kG{)kh)YMmVPysjqY zb2^>KT*&4O#?sSX!fAP|aWb7=+G-aCOhp}aAWz7!Kd(Wy4UdI_XIW4@k(pQ{PpUW^_0O0(%W$4OJH1LDXiB*iwjoD+Uq}{I%pT4s@?7Xo zg*e-@)w;YN>Pd+%3XJi2IaZBDE(;hsWgCAy7r&n)ds^Os`OnRC)ih}o0To^#asDt! zDiCrUNQ2;)GYx+>m2ENPWR*+JzEAykgnK9{KRkYmw*3{{k7ES%Z)%ihrJyqsjC`*N?PhA#Z!6dhk7-WT`@8ypEr;eKMj5v@H(xa>yfU@;<%G zD|=ip5%3EdFb@6k?yCbFMc!=|Kq^YbF$u5(x|fE@hW`?KaGhO!@gcO2(P~xByH|+C znMO#&x*RSuoRe}hF~WEq-8dLx9ket>7D}U((Z59=L<`~i`Kil%qz;vknJRn!m22yh zv;;UI5^=(vkS&#*Cq8{8UtG@TSqPt%1Fg1qOdjHh=n$Y zv)X}BMOqSZtHQ);EwIc&F`IHPhh?~PfS`2zm|WRN<}=+#rm+M@gttODgf=H|0VqqVx)`dl`z+V>JG$@3pL~Fva+f7JzMwCX;B_Bw3nh zSTxMi2wmsTWcv=2;xL&_&1m^S{C4~t=}*Ur!l$1sD%aVPq`M>j?D6vX{_x`7ubxE( zS8%AMMo}Ck`OPf?FPWxvZbLEG@qj|0wnyk3_6qoHY?!IS4V#Sbevs14K_QjUXEVWL zJCS8N_(d;HFM=cw!%F4W6l+E7atm>}g&jPiJ?sChjp90EY*!z2rRaQ1w2BQNOG0$K zQpq8ry(B%Ra~R;!JsycaeeHPel_uZE54J{c#Kw!bY8-6q3S3V?YInZzT%E>3#)()} z>gf1lbGl9)!PHYcQZ6CZwY%|DgBT3*31 zIT&!ueyn%0e`Bh9`vG1HKvfR$-3I1IEty^C3GKC0phZe-S95?>2E=LD_9ym-&FYZb zrI>f?V}Auj?{TEKFIf~Wp3C_BDfvMrk7$718o2P>C+Y=G1?@)$tk9jwpVl|01Z|Zk z&aW&*9}Nw*|HK@HY!D-*SHHd`zI;s~WlHae_hJ;z;;<%q)O0^uTe;su zoPkM(NhT8JD2p%qzV8)ZUKwCa|9AoDx9iPPKRNrMIyJD~$Rv+nii=MWvzmhTw{ zSFvp5$!J^I&?9a`A7-=Ge%I;TEnlTEc%J2yn&jT+I#Y zIDSfgW=!S$3YGV6IsNao!>c9~+~vbXg~0KmTv2#^1Vp4*RP2SJ2$dc*5{GOj$%=(O z(X5xMs@`u6dCY` zH=aG`^}dSQ+myvu7P$rTC%C$iw3GGrT(rX!S!PE&mhw0I?@>->`01SgzZIc$eogiw@F zEeu3LtgT4ckh7+pw94{j0>yAFm%<6{Z*)#d|EP1sKbb4N?wJr8!>;U{&dQlU;ML|+ zQWwHb+W7Ukkl}b~-C$0QQIuhq&P)ue9XXr?R2tJ!k^RuG4t@d*REsjcimHPZpM6OQ z(d@pD2l7;lfJut2680{$^H<`zYDqjAi62C(NxyK31`+_fX1!JN{^uw);P8!!L)kV*IOCA*KnBT{3#W3Pcfg_|GV8z0dt9!`#-M;lCy4C5%uObsZP>J}J@Ye)!>(3JU60-}xQuTcysnTA2*GUDWy1o*d`>{KyjAGIG&B zun$kMsCsa!$x$Noem`VAIe1p`fjewkSb^-}f4{pp?F~XCCz2&Q`J)h9id8vtUlA4T z+SHc(>^Z!C9B%bqZrPKM6`aB=g%BTn)`wi^UMP1CSaK88Lr2*^ip@vRA;(N`3I3ct z>FuAICXv?whx1Sgn2GpDn5iabgRo|2fJUGdnG!@~ye*S=@vJUf&{n0$R6L5{9e`o( zbMy=0E&!oPbPsQ{Rr>3yUXz^(S9OUN&hW82Z;RGj_9gnjYqNNgB07)Pg!3Pt7V3$< zH+n>w6{F4}9x#l7U#6^yz;Z!^J^$iH%4$SnbzdfZR1ZuLf+Op~5)cVk>8?ghujD8*QcdBKza;lTBqpG75ObR)g&fngT>|9lpF&-)E5Ej z=Y`g|;?Wu-^ff~=LLXgM@TI>OBLYG1sxi$wJFXs;Bq0nkX%&AdsJX ziOg0QAV{6u3p4}fZ2a))-aDi;o*k95GYLH*&lJ=yV?g@7H^WL*MG9}(zkHXJUEc>T zdjy;GnI;Zm5|6ajJHq`-6G|g0L9@HQ)wQ%5VY6Q@>`QRE4)(;)0ad1`2=M}~#T{dC zwQ0l-MldE1AN})3xW{sQ>^d=EBw6=+U)(j)lE9f-Q(RXK?Zg>1R(}C&W9yV-;BX8* zr5ODR;OF-lw^F2iWC+hB7OlbhGB-Aj!sj@p62e-18H8C$iRlE4Mo1Nbdi{>~AKr`% zKly#R$myvfqJ2@Gl}3a73EPNzI5BlQ8%Y@ZpfmL-0S}eG6O!_a$z!P}R3Jy>9fDO+ zPikBR%0~WZ{`=Fb59dt>>g=x?4qHMsMUHC}g|&T9Nk1UG*xGh-PdXne`8!|eD6%M& zHk(AyN*oj;;4x-MSlhsNRC=>am*e|uNt(xc(%ncG*IFIvNJ;q@A)&Z z)2q6^xYq~BAWgm;63d-`jeV1IQ{*?-(@pCKnFsv%oL%!RB!fZ-^I-&@fg|)GG{gMH zPn_>m9P@yzP1tkF*oouWY&oiK>*2;FJ49Z(c#5gWjVbFc2{ z;uGQca5-D;+qiibzbz&XP|(^~B5WJ$85{7+=;`>#lN1fJOgm~4>c6z;iHpY+TBcT+ zWcd6qA`)c5U#9~HSsjms(5^ecJ4H}Jp+dpu&;2(|gj{DDcY89X1@Qt@k$uGS07hXH zNsL0O-?xd?G4IpO>9d}K-Pz$wvS^RW)!F^XF+KU>E2~rw@+_p^wjoPnoaDNU!kOA# z0pekB^ORXGeC6i1#zAm1#Y)BppU3-?V=ivRy(ff4N*j>adLza78&H=18ww92^7th9 zIG>;K(yc7|sM}ZH>7jcK9pCV?S>*dphsUxK_rRprYshGtsMteET|i5^;ssG5BMo zN(LRH-sr!sZ-)rtlOnh2WWN#cM68aJ7OMNSPWrtef#`JZV!=b`WBKWGO`*ckL=j&1 z{VR2uuFn6|)0cTQI1Y0JTbdZCCd$D&ra>=huu6qp?Y4;!-sT+1sHfztk36~^qhf&g z=DuYhA9m`~B(fuXD_1M~W<^t+M;E?3Kd1M&xJ_C%Ux5hD##PT2U0TuJnay6uzLNuS zw1+jpz)9PKc+rh)(YO*DSJyP&7x&l6hlfa=%-e4mMFH)Da6mE!^`&fQ*JhV=hGACv;}jib z-JT~1)s7CVLZio*FcakrMZBZuC#M2+r@2IpL7Cqy@~^Le ztPI2dPr%_){JTFO_x zywpz@B-^L0BO`p%TRU+%ZofTI#&m;%D66MB=?&tIX{-YqC`r8xs7sSW zn8rU)jJQ@@zpDLAB08A4UQBBsuT5+V?Ph17{u^Tn-l5nXgrxOVnPMpaX#)W(+4N18 zmC?WF?xfaYn{X)WzZ{a8gQohwEA~?D97Z+}zNm0Zz;mv(p08K-uY0m;T7% z%tcqFxAC@l*B@*Dbi{fx?GD6iEtOEWP`bk0)aDecXhL=08uqt<_M_EEAVLheLcF4r z09Q;20Pd2)ZJ~hmNvrRKhwP{FUHNKW3JdJAyjus~(rZ&SJ{3zT}Z$xMo zzB%{!Sz6VimVWPmp$j_CzeFDmocO_KKq0~?O>U9L-Bm8CSan9Zt7Z8Mtdtc>d|_0p z7E^^Z({m6Kb7416?-$y33ldoq$&9ukls!-!dL>&Ly- z$GVUr#%yRgCMhfJ?v2aSyQUV<;l|Sl@1u*eMJC^FJ(5g5;>tpHwI^27=R9eJtlf6T z?!+TbpCT!Q;PvjkeBR~dB`(h@LqujPTx3X8KQrU$XZKdgSx{-0 zRK#GsBytET>8Cj$^5`}X*y+cQ~oVeB<4^G8-SWFIwDmu7?tJA?To z!_ki&Jy0?;9-O7azU4AI?%y1=+_TNAJ$+W+6N~#z(_5iU@r`&E*6R_-%;!uOP<=$b zG}uJfE&jr6EWXSiZH;mY8efHE6%qn8QlDq$xHi|%*vy%TwJUF6c~TT))DS)C8j-%H zO(J-zL!K!ntRP1A6odG@Be06_TZ&f?J!vh3s_K*Lo^dz{mPIrTD94ZD?<@S*S_Nc6 z#<*h=(B{qK=5^`a^FD+x%4=Dms0vqkNpzcQ_i(S0ymy7 zMnG+2?~8en?d8$3+(fzRnJMa<;W;|`VUBamn@3SEFm6&PdOH4^c6NH-BwPl0Q$W%^ z^f=Hddu~Vr>Y*;km;P5`>9O)dePw1H6wsNfs-fL~sxIGg0{3$G3HdRaSVJTl;Mqh^ zwu01Q;mcJ^f6-iplisO3NFm|`|Jd;I+jNgESEtRfc-Jg;z}+QqrPa8vWlh=-k!W+v zh}5HRo9w|BFZA-UPyD^C56(pks4K$1@G7Qt?KuS1nuh-c3~?9aZ<|&%MrIFMLvMbjxLnpk(oW*ZuZU;@?#nd}79?GkmfY@U z8lC_NE8r92 zP@#Zxj)1!ZEdADB?|wVe9DwfQ;Saj&WHU3De_zJuB|enjKjku<9Rd`GOweS7!w-8pfH)K5`d*)0vnYV?}oIgdjiEuQ@0_$hwQ{ zkF3Z)IAy;nf4U3fLfJ@-I^ooDniAt9b~S z5x-9x7oe;LeoP_TfR&yLPOGnoxV#iP4;-8;^?%2PlD+MOjM#_CUW+|mSQna%qA2DV zjwzQ(93q~ryB3fK>obO1a+D8NZIpmjYYOJcKq_JF0~Vg~tE7G#csD{RTqTSnIvj_T zJz;J2xf4ON~$p7o9ac^_8nw$5tZksDg*+4toq~BoK#? zd7-Tpv;?d{jhBc(UD`ia{}!3i=@_BP7q1C?xWiT1GJBoO?OQ5XYF*B~qUSOh`Des3 zIrUk$hDWBhy^3=r)Uj&=J7(r*jc;XJ;e8DmxWb`$0H7-^Q-}U^^I+r|5Zm9H(Sgfchb04-5Ae3=x&@9Y^Y>rAfz-@C=m7f zD}_LKdBw{-Bfh*E(Te(&xQfLGdaKzwtk=UMyC%o?aX#TBZSsLn$4QV}6Z>98_2$#L z+EuE>GRuy4>REj+2)^sTaGdssyuqL&^?WPkfy-fCu?>4u?F&wiY$OdWEytv*Nedr% z=lyQ|GMRfKK4MG0{bWYT^tcsfC2SsJvE+%55qTu#+F z^vmDu09*U2=U_8+*sv3-QA^Y>ao{VQC;Vh+R4tIXVk#BGUz7=LNzn2a<4K(mE-opt z3(Z$0D~ubL{Yj^#K6-2 zY<6Rn8Z6JM!kwSd1>}iQ5tm|$88D*WUF-3ZjI3zZC4BYdyX1bNLomK06<>65k0V*M zfCIJ@sBX0(dv2_d6*T*b+MvXm`aVne%d^xV?&l3hf#6?m|C7Z1KV-)K)@KpzT4s;v z0b~z8{!eb_Uh~{p_K$xdz4~35hKwVVQP34Fo@J>3%d0H7*k2^LIC(wZo$51W>HIUhbW8lq3;b;P5Ff9G3BO`CNnpU4CeV_pAy(4;C- z0GznZ!B|d^fT8ZlELX9E75Ald=RmWtpsCsF zn5(4_){LsziR)Y&dl4`3cw#O!M|=f+!rV_7Pqac$2NhQsz)ya2BA6lc`xCo56Ib12 z^D`glwnz3~EeI+ywHa8CVPs&}VPsz22)4>$JLfR>QSHy>u!4R(o|EQ6aH3N3D-%f& zqbHca1d2NE+=`3eI+1PDim`moLg2jigk9sl$#0V9FZ$LGJFL4(?I7_ip3`@HcLgs} zA&3_%JsJNZ$}?JCP(E|I6lD(uE-5{u8Y3-ZkM1>DY3Ft06^7)fG+C~MRHD~2PbB+x zF`A>!b%ob^j#O1wMl-Q3HGTVqRIO?(c<)qeft2TS_F%0>=0rSn|o{r)0pt2 zo9ND|ZYMIw0qM4_U1(i((X@T{68QAGfr6fgPKtY-}+?PKhyDMJQpN%RRNR$sN;UHFBmF#bsRkn5t&7 z6oMbxfF4c=9-ikJv)Q20Cv`(tJbH~(18wGqBacb0GF(HTHy124@D&(p0cL^=?-HIw zP3gQWDmbql!67mGAmylJ`EYX+;h3v6^ZbG@Eiy?BCHberTlont#eXwlcIExu)&#cbfrL2>G18mkAh z!wkQSRSoPm?PI~)T9I#um_k@9-IvVAa(q`-1VVTJh)bJXel`3f-wop$5)S&Q#Y}OV zh8v`{zH}*mD{_1hR*QGih;Q9_tKI^P97wv{)n|D^rh4TZ0m~kC8!dPTKxF zC2RB-{z^l?f^9$n&S1rG+To4ssMYR8u52liK`zKVIg$IAd%XY)8Zga1R=zsaD}Vp8 z$rbg_kg{pDo$Z)8CJN_B9B*EBCr*>)dvp@Cpm}#hdR3dNgPQ36c0{pl*+uT;?a26g zIFLp7l9lv68nA+M-vEDT+BwN6xOy+JyskFVLW(AixL~lWw{X48%OkJPL+nVN7)K-^ zfK8>i_C@Da+qvY;?PIug+GT;lg|Po#_4VP(+h+=Nz1F3GpLtuA; z&zpY~4sg2fk7M!3FYx>@P)hI{PG$tE!I<&2_Hjj5Wu}Ti*rgK4tU(bW#dSiuirLkU zNQN@b!P0rP;38T6ZaK4@9NG&fmVG^hbx>qj4C(ey{N!OligqaQ=~ObRP@p;bnC6_7l3v1L@T^xLRCphSw=f<2E#Gp!7+t{*8u8PnVrGTX zlNb`NZ`nE)N`}~5VL7uSfC)++3dS!K90%l1PlquKDFujzIgrF$#+asz2!nX9oOaNq z(AwD}<2>crHj|Gk=uCU|;Fn8Km2q)9vvJOAf67d|M*dw$Ts3Bu4&Cbu%ACuMhHQ75 zuh?H{n2IpIR$9bJ!=;P5>3$x$Jf2g|IjB!*kvP6ir-9R?g)lTO2IJ0R2-1?SeV=2n z+kLsjwW4)^Tk}O*&e9mqH)+W~qz1>tOcat^^ZQ z-@$ASR}r)rhmXCB@Hz}e?O;PKYyi~B{78u;#8Zh^vy(+gk#;a*b9o_pOIRTlF(L&h z8q4gAb`WnwA2GiOuto*XtA}tAQw5^&F(iw7xUVGUd7Qlu6Je}Idx=ycM+5$2p)k-4OsJ0>9l zpD|_GOM&;D;@+1g1vuAW$us__zF_s^1VSXb8Sf5dsvp{Vzf%JkTp&^XuU_RJKa-E~ z$==?{GqC24sO}u#Dl_Jr0Blks-j-*ejR`}IzxSF~S7gwJ4yMzy(=HGDI()OtwQ;(G zHSq)3F!hO3@(oL^nm)2=a#M-BXt|8y zzG7J74hj5U?qz1FY~d|d!GC!fV`HvJ<1YefXmR@oTS{R&W=LNAA0%eDnG%~Y3s%J9 z-#P~{&B+7yaEa}*w5;ZQ$Dr+ZICuTas|6bT8Vg+-gQ9e$lFhWTOD6;?V7Un5WSF_N zogX&x>sz)X%f_Hh*n5FC&-UwTfAPhmHKi>dRTevfVh_^4$I372a|yj?p^))bTdST{ zTC6++w}}2HxPc6HCJDk$uOR~PKkDcyKH68|$f5SH7=>LuHZsSN^6uMb`b=Va92kae ziF>|ZUeCZ%yb)XvytVQA<;t`8vb1cuw3OcTnfiwpw)fxh&bo+l48ze`ph-KJ?bJIO zFUeyzP&QjA4mMGt*XrnvUiviZL(xXP(@1m7@U9Rm;OSTuaxLL$g4X#)!8?PF6?;M2 z%rhqorOzohY~qiNoqBecqW7*aWM{F-+opUnl;3*20gDXQ5~nx z?_UP*4CtD*8vo={G(~RJjW2Nds3tM7w_rzj(LD8NW5VW{i?I;1%_rD;q65S?F zXJ?@l$u%N!zCM*z^;ywKjcA}tv-WGS?#;cj7e;-_gBT)A z79rhkD+=G3^bopjIF8C2RrFO+^6gGKYLu%#wtszy3F{UNke9bB-gZ2(o8`~QQHjgU z9&9q0ut+A{%LY)*cjV@5>7LWE-`0gpmYzg*krAB?UQ@4J>OH)WAgtLZgyGAKjO}yb zYkYs*`MnBLdH((mm<1OiwA-zgFhdJAnEwGAc5%MiZA7RgL@T*M7{k^RavIvO6Eeyb z$;nm>aFLGd4a_R;DN-YwYG1SNBqUk`gCw2dY4S1oHtHDZ?Bns3#$??K^y zZNyT~>eXT`$k7BK)hLaWCBiDqQ z9YCcG%61*^40slGy*?X~h}rp`A+{Y5FaQ@4zX>QM#r9j*exkl12RQoRrw3+^Jw|PH z;xS76Nr^cc@@CNxIJSyGA#mXe8JDNP%R!c)9;>#Q&35A_Zw=Ps3)U!b<=IatRvk}V zKY8Hi5(4g}Eu=@61?=C9{gzA>bzklCsw(`)9y6W`XD?aZ<%6CCjWK_y=FCtq-_NJAge$2$K}yr{Hx1@TISgUDvk@kr5=A|0;Bd2EFrSK~v0 z@B8n35aFOBF+ZsvCpO*AZwl@O8pZ*1=xTK^lj4ptL4@jFHoA6>llzn$D!Up<~&{T`^{EZ852ot51)?WQO zJm#yG*wBR4afyBk=5M45Q^IMbS*40r^+^`{o5EZeKQGM~i(t9%vyYmGxvM=HgV(k1KI0`?_e1NLb%ZX+v>boZo^DIb zazu#q5_exEPuQH&ZXiJ4V>g{f{Jw1#N;Id+Pc_H>#W{2nxcgr5F)hD1;PpGZ*A;E| zXc1y&UTHPJn;vWm^cH@J=Z@jNh5=yIlqdUbSTXU-Axm-ul5(MIiIa{)H?mJ8XabGL z(4KJJ7CL9(zl*ZoT0h&!{ZjMdA3{*1&SPBD&isoINZ>GaE(7V$axckv;SNP6&pbut zzKpsUfyAyWgKK$|{@x^iPH~FJ31frtgLC%GVYm&`)je)lEyH+r64$N^iE*Tw7)QT$ zvsuOffN-ZC4AtkE*pDo@%)h({)+qg{swZ#CT+&kJbg$dR_=w`?Vl(0bRf*|SW7Pl& z=Ts{ei&8`{`YL7qbOsgU4h<8D)yIk6{r<>~)Xp;b&GCvPO|PFPuusZ17x7)qTtrgO z&SM+6<}I+ckJp9yue5F9P^87Pqx;PLKJ5o)Y#Z!hzYHXu2D{ zAF&6a`uLsPDhvz|kG!ARP#%m^P-pgnkyS<0sBgwOvuhj6`hY;24*jE zCXl86=-%-H{_%D0R~w;8tHg&^XQq`IJf0{riT7`b{U?hc-$Ei6XrU6nga33WQm7ou zm;EDg80cblt@96_$1o}T7G1h?NQ3|Xp`f$#f8->R^=l1(Y=&jaMIvjNGseNw*ADSz zz4ZOFPNt`>SZeUEsiqW^R51ACg1kt0B=m8+l|*D+Sp0ppsb6-q0FX!V4a@&5Of9}!;K^!=zI9oh#_aIy$0B&ao{omLexo;)}ny(r#zGUPwDa(Y;? zS5vch=<>o%``aUJ0M<9QC~`1?{U~_Ng>^$@-Tp_C1Mvj0BT0c{^;HSksdEQxW{^Kh zN@p}TE4=?HDIN+s91DAf|1_F_0BYl%T-D0ixcK75wDF6KyZi0#o5Q_5lcty7_y>Z5 zU8ncnz)raA}^%GTCbMAvhTPTO3 zIpL+33K_*O+L>~mWQ;)mvQ-8BAEw?itgWr<8peuKf)hxQ;_eV2xE3q4xVt-r;!q%H zkm9bzTHK*fJh&BYai>Tj#fyD8=iJZry}$A+*WOusXRR^E7;{YEYgM3nxJ~3c?V?J_ zYR}0(it$-UR3k8tt3xPsByhz4d5{-f@duEA4VOfiQXkcknVk>R01BxE=ozy$HJfME z-84~3wcxZi?+*=-k)w+ese{nNOZ!rf&0i&;PIHd`Ih=iy*4s>Oc1`=nW|_2^OlgE& zjRG%OlJg9iRnq6V3dfO4o?!=Z~ zg2FWbz?;}bJH@TX;I!CLICs-p;r?bL9o#236rB~nj$@rxn7o_9wF@(p)v25M}rB}-20CSdr6)Gz}2liRYCH;w|2!WZ+K z+Oq!+S$!%w_kYjNn4rM#&9Z=16wD+-`p;J`Bww=?_ab5=Jq(2OQof9+&WlEa%`$5Q zcnH_J|DIZNqcFRqCSgk;IL9dqqAaZ1bjZ}Am@6K3)+pL6W!6fR?eIs4Zf17F5B>Ic z4*-!eIa<7neD*{M+a1I%`}T0uZw9*e$%C}PPC-4S_7T0c`d*S0>BI&W%xW~TPae1S>sy2 zPd_l2Et(j>U7-&{+<2RYUqio6v?*XWT1#27z6Zl;iN; z6(A)J_u)}1!<$?I9(W=bj0vKu<*$X$l0onp^OALG=`%oAC^&eX1tTo44@`!>s)1rR z?vagJo}Mlmz(n-RDG&X%Q#$H0CUBX5N*8GK%xGdMb}6<#9sp>WhgB0BwO?HFV{j*! zjkg_0P>g%b3@Gq$8^RTK$1@_0S8gRtRV>D1mh;f3Dj>$z8M_ek{P)8iQd_8D_zdWn z(J8i|OE?kMl)uMZ+RY}#y4$|%pFI{=2AW%rRU=Qx&Y(EK+OvD&&CK_}8O%y?o2C1Q9{d39D6Fr?&i^-`}qP%XNsErZ(?VuYq@c+v4i_JR&6gZ zq9)E$y#mkc34eGcf^_>k?u%_YCkB=QPq^E`mcz-wav~{mWFR9EPyU!nQ`)&t?;Q~> zJ!lML1SRlGQ~c9uJu*FJx8+24t7oyvMSssCJPPM~M0F2vBZv80R-Bv3sZ~_9V9LwC1~oApDt?)0tI^LldM@z>mlTJ}JYy+jZ8~X&)jV-R#tY z5pq|{A^}FkF$1NrIORC^YrYt`#)1m7651P{glvzdBzxa&=br^E#4&o=4^gS}Wk1q- zgZA18eZvQWcsoeFS7~I1&%CgtNbZf{Q;qaeB2$$s^{b$O-6gDJ8*j7L3_5xg>3{N^ z1WeI9AvUs^KJl_2gll{dLmNtd_sq0Nag!O+MENoL||h;M`P--0LorW`=~ z_epP4m?j@+X&cTL1Eji$VQXJYcz>E><>%?KJ%2H;iCfeLd-k@?RR$CUr?xXAp!ffG zU(exN3;AHhPyOb_X>X4JTZ!0O6g{39hd&?X-C6~$oSJ1x;qOZ)f*c~Wwf=i$>>xAR z3uNN^SMr+oAIONlMOrE3KiluSJ|{MTaFlWxx8)t))G}h_FI1hYT?ib0Q<_N2>WTV6 zJ3z`k{-``YP*^;&w9ltCUR^i?(L}UOdU(?xAKf)}kYljBKxDW_D6f!Yn7chtf7R=Bo8;5CH z88;BM63zfNMPK>m2@3y6&)>Swf|21_Mu4m~!kv3Z-um>WZz8RYhs?J1fVnmt^gbsS z`%UBa*8oa3TxMBmO8R$Nmft}(@-Y*4t#Ah-c`?;J{q%A>ix$^8Rp9=KnDp2dK23f? zSm!5!h!sczX9Txck&|CyOyc{rX%4X>UN1pae9i4cMyh^aS^}F3gfDQd?_q~P+827u zFsLc4l;os_l9{>V|3`vz#WfB!RdSdQ!y40APC19Ali~^|(QC+jqu=oBkcU=2eZIo} zfqBy~aNwzXtN-aRm0!i<+X#{DPt2ZABqu9xy_hf=P$`g!5dExsm-zi#f%$#o6$_J2 z^ElrVEz{#}x|}ldFmP`bGe;VP8Ux2LA8x1&W0y&7+hHG|q9ZfMYneS`CA{bR=4>LK zaYN6kCw@=7*AMQxreyx_VEG3hY|R%{EK(Fucn5?Q`y^(1YEngZsPtFcvP=*=GNH`Y zyAnGR7P}@i$g>4^;e&bD_gLAYWkyjjceRweSbylds1)gfFzD&`hXh6=ox0p#^h+H1kZ4a>hg-wM3xA}-iR>&MToiE#p@mtDl-c2vD0pbzwU?KwcEHSedY*(}Re&HNhAdd8kqxcx-2BUDh>=YhMLNna! z*NzzZ1&qf9&m$fjMIWD>KEAAutzWFp%AUE5NQB`uEY{}1|2~ZFF1%*>`|j?vhLvuKuO2NeW%|ND+Nc8l^=uqAlh34sZZ7qe0*hKMzP3b+x zyjgaV!+8FZ(VWZ#Ds2Ft!@;I-=O&X3H^Xo5#7QIR6qoCK0G1ZB^w>kPF2jQ!zj}6M zMdEB%mc}6t#T}BqUK0;rsXF|Gl9N>N(zjckOzQcCcWSw`;Q+mX(HocCgV|N*nVs|3 z_RkA*_>M-wk!oMf+iG8F$6_wj@9RIS$kIyA6z=z>0V0&09wuU6Blt5YZNZ-gWH*8(s;g;=ApB>80RvGj1QlNz!533aU zwIt8BpoSY?2oo1{l7r8L)NSDM^_rTH$DS&RNm+&vda@Bl+bt^tk<2s8&y??|gv6Cb z@OZM91j)?bW+4w5hv3%0oK}CIb#wVMahFm4KqIm zyw2fA#~Rxu`@2fD%F{KaYdUf#{O^O1-*Q|EQBM1Xxg1+(82%!5)7}b|g1MXVJtWt%nnw~68I{h(fM8dEp(?wWF+@givuWhTHJ=_h+*+V5Pq!eSue&(B~NY< z>IH}WB%8$XkFe?;WYy%1RG9`dpHx=pXdXV7 zRr0G(HhIl;WyVd#WdprqB4gMF_f<&QN!JUQ1nK7)9jjCTB33gnn;4ruKbb~=DSPxW z#FAKP5Y{l|Ksi2~Db$ujnFMNQglW2ygXLmMM7Az3RXjJGvj3zUBP=uge9*rFklr4a zwkUv#PJ$G7-$N7Q0hn?CsWK$Q%1`v&ZYa{D@k;7T(rDKUtCFBLoH=AzV=t(-<#<$zKnF!-avOpHZm1IyiCA*^HX{VlrneQY^ zM{hmS5MtYNdH%liHDfWA0zs<2$B_N*_nrPH8;FPy&5d!+53A?Ar!krqC;t*CWoWu% z@9)A`leYep-jeRQ_N;SkKpf`{>?Fc}zfqn(GUim+2y&P9+VGoXm6n3ERjNre zOH2LVH8Wm+LRvy+&alwv-gxRrlvh{nZU|e?HLjbqwk|?|DK$mt>FCW+vM)21b>Q?s zu&nZ)R&VP#V&F|mc};o!-wm1ex7~fqh(Kd_a2Wo^OSl=j*;IT8TZ{;HFcCs{!v%w$ zvPYHp=@>>kd{Y!BwVxbhV}? zd6!Bfc#{dC?e`Vg6umTK{AQ8h_BaxCtRxaZO|m#;*ImRFZ8mfRKFh(dxYrWRmkvDf zA!%PZ{AaO7Xr4IEq*NigKPR8wajbT~N=BAlYyTi5ZaWsatN25P?PkkuQ{AXtU4Y#< zxWi)gaJe%HBMrI#rtNsGf6x2VDIt!ZeW}VZ1@c%e%M!sJPk&j%#|0s z;i7Js61}oK_OdJxxiU;LIJOe9ZpG?E0rh*0gX}yuifr?N<}C2lo)=b5uaBnQqjti+ z#n4R4Twn(|li@8JUz{N^a@Y;gnUx&~s15e)+KM*%@DH>Nj5*ObPO@89)~;{Q{gr&3 zhRD9#?w+jApvLWdO8Pu&wA4%2*&0700AG|n-FriSr2s!92P|S)PHgEKlIXuJ2c~?i zAxeon`r39OD*kzbqWR|1`_|X!bt&rQzvZVZ2*UdQcShC;6^UyY+j@yEyVl2Y8SL-b zG147cY-(6J*cK#{sg=WwmuU+YbkEVW!6n4mkd{oSVM}j_@M3XEg8w zPB$F}ff4zlF*fD&c(!bFUsgI+EI;`Zf@sTK($?;Zf3TWkb@xoSSH8#PQCUTaVc_m_(C{9 zCEsYkzM8)e0q;V~g1*5(CEj z#OKq3C0sMT_6*q#bU&lL%w_tB0%UF8@rp@W^J7n$`-y^l}a68t9A}MxUPx*vk}` z3*(IB(>*iiyLglD(06ZSV)5KdMYCagzgg>H+mrQ?i_{TCFHOsm_kz6dCD)wp-!K~z z6Vbo*B8`bN{0Hs1erCnt_F47;B{um?#<@YH99iWj1daS0!B7>yNR5yz&vfXcMJ?El zeEocAZ;_Rz+cKEXb*Bl!1oI>nkDubz(7gCSjvV!2>tnp(!F7Q%L@28@r#0SMJvp0z zC!S5bW&noMtrWO~`gWq`r<;R23i`aPaHNYXiPx?Vv=yct@lB_OK>t!8|DD}!L2QS^ zela5|1tV$fDZ$EeB-$#XDeal8y%AA31p*)VxGKOUVHHE!&pqdiA?w%qhFYq8TIm(p z3~z@UMgzf51#}S$cGAz{g5J|Vl^sy9)f*;yh00;5AAI?E$qq>fd?%p{>Cq(p^qdpp zoRIG?Hf?Ez1f2-wPCgl4BdTaZLd-X4cOwi>NHV4c4`?Lk*0hqu%pEJOdqhlntBsOD z76g$KxMXH_eNQ7=1-C9xkt+F(NiV`7V#{TFPP8|{f^n%;lWw~s4Z6!-Jzs@1O zP31W!R`0Wd`WK_#2WxYJ@~`I8RLLz%=NgDx{{t%!EWl2znE6!%=Fs=;*wGUm4>JPP zN>ij^X5Hq^H6F%eby1o$LhjTjC!fOmrJJ=sM}L4X$)4hkCH40=F*1HVmY?1JMT>}^ zOt1L=2OC{UB%dPo(g#y>%s(^Q22zgZ63^w%P&(b`BZ_(?PYU-eUPi`|6RbBzV0IO= zc{fV;p%Driq;U%J`7{5Fg|fxiT7)YIK9ktD=eSoRwBJJ))Pj#4_|bmC*0qq8vlVvK zHJdH`%DzfTTV_1v7`o+qwq|(S->0}49 zjOAKcTK{8^N`-Gwg+CJ*Rk}D^*z@-Tok-zt0d`+1=&HXUpy_9wiL$;eBfp(sr@Kc; zGEtEWIW^%=#Z9SlNGkfp~*fzXy|u zxpwiHv6{@rWRw5dco~UnrLK@HSF+IuY{oVAh)8TjYP|v(X?Ny z7(9;_tqIiV07Y&7M1UN!+$E=F1=$!WWDHw&$hryDfz`?Ogae*Jk$SOSX+ajyS73u4T++N27{GLe z7NE~@>_pVpp`o1n4$ek6^dV)mgt>>(PD>Ez3?@TJkhA`P5~Dt zS;koA`^^|p?q=muVbrS{k@N?zr*pv1D_3b8og%l5b*M9P{I!|~pHMcF>1p6^wi7a~ z$W1>@IC_r}cJn+4YzrrRHbo^9{n2Ij)`*Q#+#>*SfE@opf2ziq24tXiYe|aOs)vZgp4hDA|GWTZMFSb#H>h{W@C&;; zLbjaz&2HKI8eq4AFYSF6aQ!2g%?b|bjzGjk2sMK|jNwESEeHcU(Cs#%hc#ry>xtgx zQtZ?_VI3_PZ%G~7`T-AC`}^}*-tw=NoehgLjheGszF?9Y);c|Rnj5h*Z~wq^!$}sB zR+@r`$TjmboL)DSQ&ddK5SO$0;DXwxA44Y>6Kn9rm;bPydD~+>;?D|#?)!ZXY~5!4 zlNlL4`nohCxt3X@wx~@*KX|75JCQHVA858N+8`y^lHD(MYLTewYO7~9`!Zj|*P{Sw z!0w!ZwbBKDnC}S0LqHPt@$=F1DIg+g=d)WY7c*{-<-MkmJ5nYp{Q#HTGJwn=+Qfj}DZ-%7BF4PT1+zUs8G`(Gv0oX^G3adrvouLS{EwDRsDcw7* zJI|J)d=a}Uf{M$RO|}xp15skpp!ZpAMq4$kO6@6hXtWvmgyYDZZz^A+KBe#!=1KEh zDmC}Ny2J&6d#_x0M1LnOX#n!qP@NMSl1|7SX~c18Sr#AuLfqG2cz<%!wmbc}u_v>) zJ9mwT1vD1DCe2h&SpL%pvR+G-8Y-w&$jb#WTWwrbMd6(DU4WReyEIdnKkEicU8v79 zF>_wL)!F7$3!e|Y<45{!A^!a#jbsIS;W+GqW<-tM!LLO1EVt^0AyyR}IgP~dY9_bpC%&GbTT+RjeR81|`JNeY5hnu(o9?mx@-Cyoe>Ly!JA z3t4>uE;F`xR2o|i!s3X}F)0Flb9od$jCKwvc;yZWoC@qY$#J`0{FOu^xt*^L74rSN z}e5IbU&poz7TjrqeyZ`AaVQ7)jagsRHiAIk&{s^5Vvz zHr;k=!~V^_N2=5nm2n~mJC8fsCo_s0rwHr&XVrtGOGQRN=%bU+>onN`EoG|McJ3HO ze3mate*K^LvK?~e$1TxLuxrr_(e6Ym@^nh%$}I()k(JssAE=Ij3E^7y+M5Hx{CN@Djz0&8+~ z!@1)Y!+<8W^QZA+>c;p@9H!I?bhfztYX3*2AUWWp55=x1Ng0`-^a_8iobgKkiru~} zs~p^qSkBFwZhS0d5^4q&r=2P8A7eqRFti=7?boGCb59V7(;6 z@bPHhFX|ZVW`)5i-B`L1uXjw5^`drz@@A2G!%TQ^59m^$<)eMWFrEcpOJmk>}I&o~i-xKGg@a~r1QuN$#m=K$iM`E#nIpZuG zNIYka-(YT=3Mu-$@y*|=IIm6eD?D$~21GGR$!OZ(WC;WUT~u1+tWq!poV+Urh>KXU zzMfIy6!jzl_F=0$PpQb>WU@6*0!$bJkPzi$EEdwpLA*bui`^9=2ZL(a8dO;%G#vJ+ z-6bVG132bsK{%~?pW%3asW8*^{3&dHrbOEabqX2ypE$(xPp$dyf_k9e%%xD{Tnclu}$CQ&}6;MsLmtQ2H%K%hrEQjowCE)G7I)W z)RQ2S(dwt)XGy`41*_S0K`ldiEs;!m(o@HJP2KqG_x-R#ort^lTMsLOLk;qa=C3Sz z3aOb0tCubog{?;Jc;6Mmn1cc<<+)2T0<bT^2QpdS zCx?wx*|QTMq&yeAJSEy*JJ}w7+PL{B_j%!HuDY*jEURCDYe+DbqQruC8*c=fnGn_l zq|7s#$JwXKsaLZH*po#5O4p9&?A!3+cy7a!Q_nghtbbK^410z(hOVCvn${SKYsGxJ zsypnbnH|m2jd9@F1I+Ga0t0?W6zT9)&!3+G3+Xd`;1@QNt$6Jgv#@juu0k6)u}sr+ zgKtgzOtM{XFLABL9a8q~yA(`)fvm9iBvu3{F>ay20KTiuA93{=0CH_!LeR5> zSD=2dt2^PR`xAa(@5+a0Rq{nKQsU%gkAtg@qCF&=N`|BBi)G#c+W%+^Oz# z1%gD-g0;=?i{Ks&x0OxM`&U}7#N0=v6h}EaJnZ=2r*b?{Jtnb!3_|ENACOtG$Rubx z>hsFT6lLe}N4e3m*19228r~`KPQ>%@DC}A(?7L5PT^<9yjcZ=k8#j;LcS&69<0l#` z!N*dc4ll@kc#*V+Mz1)ilWdy;@D-b$#?RP}tzIS**Q(gV7+?a!gMSbJ=1#o8`#P2z z!W5pML`=B-f_V+SGtV93se2|7?xuS0qJF6K;!H}iRNP4gEB=Q%(>0-JpU*I{KxLJHEwYI_QB1;sdS1u4S~nJ#<(3HErRN1t&=`Y zdOxsH-gC|z9J|dD3@v~>;yA@y%Z0NdK~t=6Bi{ED6XNB%kI2MdKm2YJvz+UQ=@mTY z1gm?-waCV>Mqutqny*LTotqN3(H-F_kAe$&VIufh?x2V5ebBDrNY+2Rs%pxL#Blp8 z|LZPDYhS`ciXuOw#dKRq@~xt*Gh=7NCS># z@n@cG2Kk2Z+6j^{fo7pea>bjvb}F{pupZK)#4l7ldf61L{_oOp&e2rK(f9cbGg91q zUsII49TxdRyc$DB-XYXs=3h{~()0BweRuYCrS8ew7rI#<=!fkkjtWyR=C(TZ(KA~R zQwlFCjIamYSe4Noja_ZWDU~ncDe-N!7Fh6=Vx}{iXF7GoN2kf3;Z3&Dc@S@>np`y8QBflS$S> znm<|GP<4{v4&s}kRE{lfqf^7YL6hp<_bq3u&Mv)VL*q1KYv<=Ky)akqK<4z_KDFXF z+MtBNti^GV7k7EOoiiUF*)F{fWYz<-l~HM8Kz?Ok7yE;g4b;6&c2et#9)-Vgn!;UO zl!M<|R@yZ(gJp;kkgxhMqwvn=0`Q`7hSPBjlxN(;Z|{FVX`E`G0UJ~^K2DR%+#btn zhy1HcM2x218DO`2`S}L#i6UbNEleIxIGSWFzEm&0oou)wgW)K5+7C00zZx5Br62fBdoQDG6g(7lJh z;kGV46LB84w24N7g;mGqod2rs|IQd!X6O!?xn|j>z<5AIvaEdg$rdgt4a3wFf&#N9leYTR~)1^${X&O`kBh&q2!>J?XMuHh#BFj$yetpYy7j{ zYc-Saq9{EEdYNfirW27BK)B=aqRdHF(rSnQpt+T=17b1A6rqDuVcS; z=lrYL+V>3DL)9B~In03wF^KPV^4k;ka3KZ8Ajwz)2e6V(u(ni9!aTfuyuuV3xUC`@ zp!?5IfkQ9G+>UPaiTCxATQ$4pph;?=v`@I~%{x^VCc!3A58Jausz_ zRLD0Zef`?~^84mTV+Py$W`nd?!Y$ciG6pv-V5etp2toU(PMjSd?BbL5ZJR!`H8R4d;7*S%-D*k!~y;WU&7?2 zergVDpp;=+4oy1bg1=wo<=Bgd%RT})1`74s6pTAX&sSeBM_74%=QOxbAyGC>+`+m@_gX{o;rXxxPQhs6Fxxw5SF6nDA@ zvbqFH``ouRG!Nf5tKbrgBv5`AFCiu%aIi*3X$#{r*o|kVWyZ)|K=DhHSYV74&fgN| z=ySVULTyvMT4Ia*`s(gq7VqNyf|lDP3>MW7gzB0WdzYa1Ng-K5%w0M?-X)^&^eg%+ zR5y#}S2a;!lL$@&qP>0aAxP@07BNhz`?G`kcUH_80j2(^ziJip`jlt!;gbZqPA>@- zF!@l;d9{6=|Dw5BWP0^c3(X$XgHU*YxmR0lF|*d7DG4RxtbJGcwmE;v^G_{y?gdkA zQv*Sm*RNJ6!pD6Ye(El6Wt%>~&VS^2=<~!jC2mu@1m+ zqv;3w_G-n1_`nG}Zzu?*ZoVrWL%-ZE7x<|V0`FQ1w&A#cc*6=*K_zb?n}1b4Gzb{Ux<)urk zHYxdqY#+44ZeD+jxo?vzJQXK5H4?jjY(?98t9P{)| zSI&I%B&s_um>ayektvd3>+a0EbMV)&pQAI6A;tl}X0=?FZdd6Pdfng?>ib3LL4Rw>`3i38pb9*N^vG;K>HNo+s{&*#BT`4k?x za=D1Dz{-JN!7=Bxi<&3@9vZHs$ghhD$muXqr3>sr=2tBB<14bQ-~oq|T4|ZONkZE7 zbnl~4554<5-lYL7y-GtVQR8giF?PrkMHN!p!G3xy6xk?_1$0c#q!Ye;PB;c8&#ON+ z7d@Kk$Ocv}f|7$Cj|6o`=f*V8HP0<4VI76!wEd#c&_5l8wh5xL%6{tkK!FzA!;N$ESll z z#>+F}EhbK5J%o_&2=JVre0=uW@<6pB^{uegf>W~|GC5Qr!h1T4a$4^~eX_x?`xCZ> z-h{6~tY=*5mX~>N)N~CEuzd`O8!5W8=gthWjGg{sfL;ceRfx`nw)Z;}7SSzMHp+x- zP^#KC6{8fo)JY@!jyDCZ>Te*A#sVbjY4!qzLRH_trJv6rx1?XAjPt>YdGxdV%v_!C z=MZYyR*Hjn>TPCDJ&bT?(m1sS-QU{A-PyO(u7UWvp$VirFC(sVm|(hy+ohA=%1w*i zLsf*JCJRw$sWiE4aLl46Bw%g}E9XyR@h& z57A!;=w<)rG;_fE*!DJ)lGZ3aX2e-DO>tt0Rb6s`Zf*(mV0hL8=ptLV5+-7ZxawfLjeuqm6Ar+1TebN`w66G&)(7(?Js zCSFnCz^w@buH=@LR;1SOYIB`hQtmq<4oZo_a6aCdD;ZdWwXCUD6Vay^v9*Kr9yP6P zAPuGY1;K*+ry81P`@`Fcdw9lP>w$n>#DLAe-jN(Cwj;f zS@J4U{E=MFqVK7wG%aAIH7%eIpZ%jqYj0R}t0LGnlY`^}vOND;&bGXN>bZY4n^rR9 zPVi>6?;VcqYN(jy=vU31Gs{t6^HLi)K9fr5(a{>1#~dM}@oJ7v_>GGO-a+9KBLyx^ zUNLr9d5NaB5lT9rn6KfeeR9;PLCm0v#qCn)82w?x%n_u+Jl$y^9Q#vsxkbT%OC zPt>0R4<`|Eq%@`%#EwjQtIu1nACdo(d_w<^rNOipkX>{qYFHeU-ylH6DmZYbd7PJU z{eC9bfCa-t82efI1a1|Ly=4>UeK%cTC>iZ16m&2AiP<6g82ZRpnK)Tmx)q1IOyh+$ z#egn$MpmkoLsIlIy)st1OQNw7%vN(-Q!U@|JB7^_)}QdOYNTT(z%!i57+{n+Bcjip zjUAMzp>y#@=9gGZKgyWpXX7%*dcOsv&?jKDG{7auw`dG7u4*Q(9p%8S9H~mt#;`$(T}~6oE*DhCnfAKgd(pAA^E28kMtT7E0!;XVk+B|Mw=h zQkeO^A>pu0H)hL)fO6fN@FUV=^dPxM@_Scz3L%~{J8--D<1%sU{|J>mS@qWT=piY zqPH|Whgvvrz@m9Nzvl2C2y%!h~mb zQG@?mfZ`eDCW4hF<7H~q>m>7g&`o$Q0C$# znAoQVPsU6tHF!i?j9&YY6W44E22I$v#@%|&Xln4UVd^Z-wo`8Fk+SM$EP~35+Ls25 z7WjHAAUN6XyT|-dhKH6P&Gj!mZ2I;%)jMzU&_>)LThXFl?-ebTNPP&I@&&eOJ$*Yk zAIGd{TN-PxTvnr%o+A}^-^76cf?${9W>1wf5z3G##QRdN`!U5Mx_=rDND|iHojLT@ zqTAWrx1ZmSP)J!ywUxzxJZ^mLLA#YPakI!TsfJes;ylmYyKGaY@-4fDQgY1KsFAlImuKQiCcvW0^VHT5MSr`Qs-k$ z_<0jewE9wM7T?wuJeIJvU9a4-WH zCzo$qP_!J9`*$|#q%VHucg7ed+Q&TRy+Dr#&m%hABN~tDyK(=I(IS&ASp2D|bn^0dnloikZrAt7M1ojQUL+}2x?>I%C zVkq{UerX+6L&0IoIo!yL`{=`Y!_U)2v*<}HTBTU2x=JmyUojTt9xQNZJ9nOY!fnM- zXJYx4$gUU0)|+a8kI5msCL;4vq{MFe?E%!8ZG36mDCs^=$b+V2w?vzcWCD~vY_Fbf z&~Y-UH6S4p4iB9@a~j8=w>Yw|dtOdiCmA^+|-k(y8#HI8qnfrfz~4zs~r; zPQ8Y%n=?pg$cSUpgqCf;+^x0+ne=h)_9@=|M3TM6r^Y+~XzQkyp8B}Ou`hWifCP{f za9JnPahrmR3|NTv>MwflLnR9^=v-B}S+a#il{Mpd1&<**1;?@C$hF{`{ntwT383^^ zJJXy047-0UmwWhfL|gWXuzY`twgAEwZ1YMqH0G%ZD8lB;uv?pDeQB!)HsCmP{j52| z@BAv~n|T2{eE06kzJ$N6-r@gU(-%B2I`A;*&7`;hxX4UFZx1z6<(n}2)dZsyU75&L zEs;&r&0`mC)_G-Z-8y9}QxyTPb%_Pmc#CuUfdqbPyd(-BA^E{D6r1nneNp>5Kl+Z} zk;|RI=Ch5_EhuLrf@ae4L#St7t}H5Gnl@LIhkq5~>+aNw2@ ztoKDKJg%F1w{h@vxAf+Lwdh&qY27{2j`?J>HaQ^nk9!AM3kWE!#!*S`(1;CSV0!+a z7oY;Ek7kw*i$_pt6~6G2h{Yesx_KC@*7Ct{!2`aCqvWbh`f3if@7I^NkQg@~!TK~D_0_cI(M)r=r{9S=+R>kU;o>KTsQ0q@E5$|GJWnmfMR`4Vm}m$7uL{}OUeDIo zA`?x>o)DyAlKKCPNS%&VZrUKX=x?Kny{}}?r*{)9gk8hF8C#h;C(sB1(hs%_{6r`G zGPXbVXTL*lah|IaUCV6argLj#9wDG+^biDo|5(B@^BykEE66%XrvMp-c=xJVyirgi z!C(-GKzkLG@`P7(Gm|g~qv_=rJ1cgx47KRtRpIENM=n`3P9cnSOiM(|R)`LvBKQH- z(xFQF2O1`2oUbPo-v2@7YZ9?0DZN!n9>`^&$9x24jC7_2TSB3MXirO6Reov9DQ&p1 zmaBzo3{#c1K%Lv^wnGV>xY{7-{{BjZCWR@j4xU0g=BAZL7ofmd1>}G7k{svmgDXDu z30x*x0ZRgkxgZShfjv7_;*XmK9O%Cj4Kgb;iB|uOB*v;~OjG`2i9WVTK8I8rm6_<{^7ginrl-CjPj<~mi?0~KiikIoE%;TYw{27GbmcSOWX$6|jVZc|P zFa(RNRkatZgGeJ;o81M8;v)8^h>O{j-sUsy+oP!?F_?x|(b)HsC4H~6Iu#!Lr5wLC zMg-oTZwkasa9h1+wQ3=T8#h4=%nVk3Sui+LJ`0T;hk2w@gNBm6x!73Nwv@WST4I)=w)`G#=u>+fqMXQ(0} z$#fI6VG?nD#uG5q9daLjHGX+Nkuzdf@ICxb;3#Yz-3NVr=;l5DxBDBclkthQZv&U- z!xrkcL6V_MuK`x$Xi925SYXWESlRf};@(=YicEj}9e8lSr9vvNNu04Pj1inC2l>q#^n0 zpdOOofq`IvG3?x%S57o$7`6UG@~FiJ4Et*4oAux5*><8X(IZQ!X?xQc19hLQhx}AUrBBf!|M(jj(>{h7h1L?@HYOLLC(6WBR`$U0};e)806a1317oFopNiMlOx zmxxHi3fSweXfdF#VbnijJ5cGi!nEylR)_XMnht<%{PHe;-uYejy|X+U$A!VcTUM&l ziY@EslAUE0+&yK4w9E;3c&F#|yxgFmBHdCF0^`E5Pn2ar)2iYC6O+^7RBSTZNXht8 z?#S4lcU5XBMQdT7V=_&7j(irAC9s;bkL@yIew2<1b2tn4`9QfoI|KCIrj>iqW|P(F zMyC_>yx9x7dBjjHW#x#tD8EAqH$E9fl*;|gaH^MSbe8{N&l#?pD~-N#-Gd|IzKB3q z{cTC3=jK7xZ@{@f0M3exPI0K9UeEn{{HU(;bZ#hf z?jimQKYgT!7W@Owk(6R2Up#U&ni}^|dudn%@)pZ$6O;K;Vc*>t{>G=wwb8s${jo@& zs`HCtQN$?nYDh!--i7~`weOP-yJDb8aY(g!r8Rzvuw_HJ%r4>YkGBtZ^SQSurIDJ9 zax#{G7B0Q6tXQL&5{n8|P>VRzJ8_@s{E-ah_{FEb=9XcFySSY-*P$EA7SRFzAUl5@ zxR8>qr}G(CXGGIM##>MRQYC&u94G(#L)1Qhv!qpPb7+We`B^Q%C8BIEJq_JY`0zSq8d+lYT+|EXf;Kea-viEWB4nK+^tP= z2d+(!@3 z$l;(-)RVbP%Fl(mv?7T_Zic-J&E&J|(yo~k?SQwyzlvB$fpuJcJhU7 zoHDasg=ysByl)+-V;f)OxGHvxFKYtzx6W!dDC2LO3(dlk;t}`~$c~Quub(k9DD(ff z=vBl2T$Jy%mOv_l>I}OAxW z%(4=EcAve?#`>hY*|`qc$E~?$LoP(w7dw9#=zRMVBy7!qX=S0g4ShMv2$^yGiXw=k z0s7>%=}l&1JV>U7t4(S<0KF688^Atac=dw+V{#+Wsy=O5CH`NOA=i*6YW+vUS}2FH z<0kVj!$amdOD*|cI%{`Y25*wou7(b$p}}WCV`Oq%+{fZ(`dbt2zbtoaFdJo5+%I2I ztSc;#`E#e~M`tWVe{a-wPGN6Qr3m9@@q0CkSTbO5H)x@2>gRh~%j+Y7*@OAN_l`TU zOQ~rbwCgP2K3~izJ96W}p()EspIV>FOKOm0)>gpd!mm0Cl743CZKm+3#9ou-^u}Dx zgl-52T0)EvPaRpLz?q`nICY47;<(x5H&d=_i8Az_Wlf)$P1`Rk zobHX-B3~M~F29s(nNn?R|h(2`i~OV81`!hTTC6kd1{J$ZWy#)a!uvx@gZv| zbjE6lu2WB&;CxQ@1(kslBQ`#^Bb1Mp->2qlPKqjZ3HpbgX1jHnE>Yn?eJCN`|3}qZ zhD8}}QNz-WbSpB{(A`Lb(%s$CCDIbk(4f){LwCo}FqE`3(nBNCAR+ONo^#&s{eI2A zxn}nB?7h}rd)@mE#N2s+-i~5zP-=cG58q?h-Fv=DPw&*x8alcy?$L@9PNQVL5QURQ z12dg;*}PXcyFh*Ov1=(PyX`~!m+gJ!h(<0azivz)%oVVEgt@F(+$r&_B2%;Ez~sWH z|F_Nv@6`T4nw_nlZ0KPF8RB3SRw!*Ile)x>A7%UZprErnvH-wi7wZ!RImI2#sapZl zddK&5W*O>&Ksk6HGA)|xvr6n5YFndZ>OkRXKC7EHhtrZ&ZJIxGpY8~q7MV}4-68nF zoZ)VI75At9IE$@M?MsrmJ3jKQdH)aNhM>r;;=3@D`w;~^n;U|&q z&s{rjur|0VPsu;8aWK#O60c9M_`D59*$IIaM%^qw4>B?{Idn1NkWL`PM4iw0`yk)P zyEKxG@@a+cIq)2aj|?;HuiQL46H2TUK;U#x*Za4B+BjMa;hjD0_eZaxJ?c0etRoGM zzWBasdpEaARsr3|@P10OywFn#lQbI~U$pxm5tgCJmyeYyChx?qUswFtr8tSl&236i zr&x3Wb4a{vE{i5~=#~@=S&;MXHJXUlxE?R&a2k$D40hFDWOdC3ym&7XK}?jTvm@+o zV#z?Hkiiju1*8wYT;}!j2=H@xo2xAv*}Xm?!|h1CBWE-+n-Xb5@o}4zvMXh|^F(Y( zIX;`iR&3-0u27_L$zpt>*|A04SSNbcv-qufHU)xsOG-_OvIUXHDz0z8ngVfC`%<4D zTIk1c==}iH&cXD8$6R}(_?x4-8w(|Z@VTC!@qX3pKve)GdW;=7rzAoSB>%yP5KFn| z(=~9?cG%uy8n5D#dcQ$t4eFly(Uib>J5IwDM|h=4mk2dCu#<*IF)glwD}$(%MJKck z=jbUHLnoOa~ej$XmS$mv#>cZX9y<_kF7Uc^*+)g zRWhrd8oY+8ZdD&uvg)DsqE+u1>}MW=Hf3&|0Gt-3FW9$XzD)9^21NiRGzcIiI;s?L z$%KhH8T6#GywOnZ%q zXM1wOE*vFso`Uhh>7PXcip=;BM6I%lJA~K5c<&liKhmW^d(OYx^2E*^{^yP+oX>G} zPta;?%+tT96%|@|H}}z`s?W1CprYLLwYr3L+ArYu%abM#a!(%`3Kpd*wOOGjTBq|FUYmUN+(m zx-{D7s}suwUPdu~#!)zQiinmbEYgQeV%mEDDI#b5tTC8vulKVlYe(l;#hRlK9J{e@A zk5nIkZp8(6hlJzH^I$80Xvn$1X(m+!01ih{b#!=uQ7Sgwol$JfmB^z^LcB8Jd-n27 zbM{@tZY;A5Hm+TR-PV0a?sl?-q`yq}{}PUDMdSx0DjCi8$k=JH_XT);tgDkXoANsgkAOv2z<^yf z(>vJOLR9RHb@TI1Gd^Ji0Wq0;2F6Wllo!#8p2xDm4*&2`QBoq4_}W`@WpX4kSN(TF zO3}?;c{s6-e(yL|g%)Y4fnt>(OY))?p{%?Wt7iO&?ZVqzfzV<|O)`YJfMhGJgXc1j zgqy@YKU)Hn0DP@?ARzO@p5XW9Ji5P!S0v-gz3VpVZWrK8{3?}PzyDTY!;uU~RvgQat8}M1m{;kC zP-e0R7{%5b%*l9`+aP?;JkHSN`zlD8oS;;Tbc@QKF@HL??6O~{FU>C$L0ZJbCdc(! z@n~hXWg%Rw@43}*wW!sN95uf21Sij!ViXv zE=kKvNSg6vBWLe{Nx`n+_SR;dIoNV9g-cB@YF806+S(aRS+eHn`tgVmM!3?!Z7byl zgFBUQs3-cCBsP8VfJ0rZiP|%tR|HW1l|L>VU$!~{E628|-7Lo@Q}_T9IF@G4%5Q$I zYH}873%`W3FiqxWgZD09h%5@L@tQwCGZjq?)(Wu`fd%MlMKxHc3RUi`d_AqBt-IYP zJTEkM)IjS5Hx#E%P@Ykz9^&$QV8Q)%Z@~7I@&m1YM(6qhHD2HfX0FDKaIH4T(8+J4 zN1f#3G`IMJ+eym7+}d83>|H#?OQ~DlJnVID!eFSD!F_6X!E!yN1onMf>e4-x>yal7 zoRat=Rv}XNmZR*Lv zcr;lJfw%rtV$%PT=SrQZ!#=6Xan(f6I3NDA&D92?SR3l!T81Km> zsNt9BN#N$Z(uexmN0Z(vOFXXEsp97>YX&h!`+wVS?w0dhS~z< z0WHF;4B~jRv8+k|yw2wtk32ZCg`d(^y?fQjB2d^9HkmFy9RzvMQM&%8u(zQ9dAXpa zob66uKvJa@3z9&P7)Ysx&OYCFdk#iIC5esVXA=8^U3y$Og~q_SVk=gExaF055d<^VWLFM@bM z)IvplEgWi<+y?^Ux|Kk{2PluK=OIa{gnGGzMo?TH>s&GebsSmp zfkU};eVyp<*VRROqr?2}S8c{~QT&3@6{}0zhrTVFeUn-$$R+Z^6(fqF4cH}fao!Wr zyi4_2oo6*70Rr=~lZTS3b1dxIlTh$LXX^#j=-cp)BU#84rWyxZxj}f%i>W~C6i?-Y z&%BovMJvZ#IwSMY&utponq(f5C0?&ga9UoICM;wGsH&7_>Qi7a;l>Wl2jw{MJZ`x0 zbuICndun}Ad-xLLI7seKmwLPo0zZ4)IaDCOdzpIq+8n1>nh1T7AX;yK6f>w!xDGRX zP0f>;P|2)AQ;MZfW)_>BYxNy`f+g{h27&F6S=}-!=2vCQ+Z`wZJUWrt8;XFRQ{q<@ zx;UNJksq#AX86`sgJ<)Z1urdF3N8WfsUgnEW*(uAjCqsSFmlavsFy6^w~A@DaO5v< z^pC%i+RkHhY~7(!3G-;P%fwn}N)59{@=!F{5b#RrLEh+b?HB~IbCOCI-g#&fMS^qg z8IdF3rm2k5&T9uhK0Y{31cpq%7h*zTbg+~ImJzX#&@I~BXvyIWlk85 zCLXmxJOBBU?oRGoS&=%fY59@FeGFDZ*3cY^4~ZAUB+5u*`C-+Y$WTR)L7rXJ;kZ!v z4})~R6c#`RQ}HyxW=>l9<J%3u)KHH}Oa{tmE%4Q(P_|GW ziDVB1Z(W0pn2=^|WtyK9K*I6q$uwS+MWo~H-JN=rgaM!5`S^Uwk7HSk2i&yq_nwY-&=GC)8#tw(?RLA5t-OYw|`!&;2za1LeOcR%-u#ImPRh)Iew($5H{Q zoJSL;x(bc2{#KJnTHkXHi9g6MrgA;iyVe3xDak{aG_-{jzjHb}Vl~A=^s@6lye4t^ zcoeyt$%i`-u4=UyQZH?p2&5(ud`3+oc!S=D$Ns|}z~8xVMP~bw9JAC+?W^=RppAwn zU|a56dBWBvbFN0DCY3^3^HPpf*)#1;5cM9nN(^5?GZ;mRRC%Ut&vk;r&R8Zc%}!lK zKySAuf~l{C>Te^MPI<1m9Zg)7={pj`_}K$38r#o9-qg<|q=N0cm%P8c`E08FEwVyL zIi~i{*mmtMOmA#Ur6d+`xy(3F+c6EMC8W_1ZW!vITW*y;YE&#FsVo3uMEkFLq1Ts# zvNU5}=uAJ-EKe!>!{B-UpP-_6z6FF+&jIM0J+h0bRp(Y#U9rU!3{k!nGZ~%a0YfoI2ygU^2`i z`&>WJxL7ugf82(&2&t8|z^G;sw0ub(_+BgM^eeES2RKryt7hAf6?i(MWtxaVf{Duc zQunq~c7?2ONbVLB77^mJG4cA1W{w^_{q2nd-_RtdVmJwObLFp$Z%d&R@dDFXmlgoQ zSqL^JY~G^EooTc+*pxk*2C&ZtabfX7)1E~sTdw;wwj}QqAp5|#DQE|)81dL>6nwR; zK3<;gZ7J4VtLjRCfzQ;YT9TO7G9e0ABGJ;Af!ZZzfbI=fNM^`M#c9M9t0a_$?t1OypuHe6 z823KNgzz-i5Z?RdB*mWdN@5{8XnhK=3fG(vF0rAPWFH!_n-uKRiOztQb?U;j$p;Jw zS?{f)lmMS{44P-bKggb<1++e9 z0s=p36(IW$W59Y}y#*m@G+|B1r&4b(LG`GyVoC#c6SW#A-0+zD4*hxPua z%+}mr@xzFei9G9&%dLu!v4n%-Rj#ai_ z{-lbCAXJb~*DO*7QM(@&D;^z|V%C(ON3+&M!*zK&obUWNv`d^mq-0ZCzQJ9_Q&Zw_ z4IoZeXoG)1rqC4TbeFM|+W_@U83>E&+Fp7NUg&4O#^Bdyuh+(FulLU>_QmUEME7u#g|q2&vXf3VWC)WE+o$SO|@GLvG#Oge?{BM-`Pja*nc0OeJt8 zW7eiP=Z$m0Hr58nxc91-kg7!!6X$TlSipqKRwj7bB7M%I394b$)85f9`fgXfc)#5` zEnpo9{IU(ZWflXU`v|0Un$@(_F#QD;{ysYaTuRGCaFxQ3uv)`xIcs89lZNyGKr)5! zp<4mao>VQ$ooWX+T(c?5fl8s;j$@tit$?7{$MJ23>WQN;tvG)$Un=j!nwOMU5z?JY zV!h^_i(Ge|8YjKoSN8&3+?(Y*%uf;ot}I)^Uk6b~pwJp-9ZK>o35lP^9|ADE0jXB&PK*nN?I z-70rli+>}SfLd)}coS%*?fg(SmJ zN?jwMYE+tjq^?7h6@gLtt8msWEJ6{? z1S3hI1p9eFLRIr}{9PT9B4# z+e+6?F)G!7IZ=Wf5#g_kJ@JUT=lOzmUQZC#N|mrM%CFS7C(@6cNM_|>K3QQq`1X%T z`5)_&O|ZFc?4-!)J-GrjU1GwTJ*Srcho_(-vo#<@J8CS`;SL2RCVL21cq~+a zfxeDd@lPdMN8{?od@Qf9rW7aP`@Hv9mjJW3*k32hl}9;7Oib{-V~vBgW}{f-N=q{{ z%dz?;W~$T2ANH?Hz<6DzdM$S&6;d^%>$S z7p3gRft{wd*7J;9uc{wlm4$K&R-RdaY!%NN4(qbl=VDss@J9se+u%_Auj=8Re6uOd z@!Qt))w?&n;HP(FGBh(SkG97jj6l)lwER@%2FwivmRg{;D-@=>*(wb_n2mDjRAElT z?0kUq2zb#;DgYbBIoYo{#*#XmTIWZ2Es|{vYo;8qoOd55kxYYKhTVd&lItb!W_1)` zWeCTVwyZms>ATK5%(1+&(nJG>&9AK7p}b7t9!;^7rAl#?R%$s?nrIOT0dV~ENGZD|)27=-6!d@Uh`Y$I02AdnvIhWeq?_IO*22fRSp&Tl z)#Q4p(<*Payer2_{vMzeK}Q)GnR~SA!lR?o`3aL1Vz4`P^p+VKuLIf!4x=F9^UYKIj20vI+aq@eswB59~utf~E4iFzW<0q*Ht86SRbMWo_p(7gJHaslhiFFC93>rETPp0EDmRcc56d_vCT1 z-%oB0wxKVL8@tG*>DtmzpiHpDQreDD4a!r#dAJ7G=_T?c+TR;>>2bZfU)%|t1H8cH%{@l-tF1Rga^~#nlz!tid$bgrku5M~KJB~6<^9eR) zU&z{HYjH-uAPVAQQT5cV0vU#zY8Vcm9Az?^;V?^m>^!q@bIzw0HI6a{xUN3wh{2~m4lVimapP5568K0bhtNm>RHUjP|uS}rN ztDd+=Nz+2vwC-Lc}r>xO)iWGrvsg+Gby z(L-q0D)6ZlXpUx7ejh;kc=AS)P15+#1;>QyuS5YnJ?u%9y9tn@Bea%t-{_qjDQj9A z?6EoyP+4b!nV0f1z=H3-ub$r+xy=+2{bL$cQpWkAiS~_q4_R_sc4Sn@bc|CP!i*!p zky?uIIC#_H*&PpJf@0X^|JDuJwIyXa?i9&eE1Jl)`ezO5BlZq+@qoI%_Rt>$AoE1~ z=CXF9chLIMs*PE=^M;qm`H6;?xbAPJR$v`;|K%)pQ0*i!_pP(#X9cGTn89GUyo=|& z+o!wE zr7f99)UxDkt$(UJ0%#gWctQ)xY2FCiu@A+;7rkHW=_Yq#{Gh=yR_$*#SiLXKoq1o+ zu^67Ypz?FvdIQ&82Be9@EGNP;Qc4wH5IblZ3-Sm32LbdGF54=xSLde_L9jn}9j==G z(~whi+Mj_~2@xMkC%pmwz8iTT=D<~&{eqg!#&P?$ru zfXw}-doKq>2HvLIHm^&r&k=uw z;A9IkeS<0~coc#K&Lp;?5MY~eYAW@sL9c!RWGIEW5=?i^`Q0DtbV00Y zT83}RN&zb2-N=yL0@>lDe`I!6C&>3S9C)Tq3~FoYd`Tq-~5IW($8sTgtLE<}!R zlzGu~uA9fABnx)XwIeV>wn!(I#Vx(^A{_)1eL(suWAm!w_)3qAt|UbQB(dV%NYEFnMOu*Y>I-oK-vO7g7$A8`SGs4T3r82$Q+|G9&Ob(+QP;IQA^kjYt`s~D#G1PBLVk9#-F_Sv{#c9$*iu@;t8lVP+C~2ae zInlmKngbxq<06!zS56R{m6KFLUMWis)ItD1yGl&%UTq3XJ-;z5(Ct%YzfPv%h@gzt zXUT}~sVPZ7k~li0!WTfp6$$CpB^1CmVg2yR=Qi)W{9tj$EIFa{lVSMoN6r*V3$xWg zILUO%KC+rhLZs+@SLq*@if63cRo^wzgkZ6(WJTB(xD9&y(orFtTe}tY*z)X#-WOe+ zQal_>8vECN{K|Xxq-66@gZka3{o-SLt8@zg_^77p5)|e-2Zc+;_^@W+oA37E4uf;n zqybxvU0oJdl82?Ynk!y8UCAl8F{e|s;B7VHzUMZAt>H!)~&HF-Y{&+KVFzuzr9K=@^KD_6X(K#jLVJZC#x*=wYvh|I<`2&SyytC_5?<2S6(;cJ~Dq(_|8M0Q^w+g3)}fCFb@TVZfd zgyDz2=)q&>yrINU2&7o>2qk8XwGd%SA)c~R=o2@4b-HUki4->?zXpN5!1jRz68Svn zllv;bYgyIj5AWY|WaO>KGAx8C{3z#6%FtfN#^q>5r?K(~VSf+(ElVk276Li8FCff{ z#!D1y$TF?jD?_-@_*s(?z~cj03H21Jwm2h!5hF)f-#ixhj7BxB&4Unq`I=tJXY3Vl z`vVmx#nwL|;EGD!%yk3t6qa15?sGze%ST?p=pAqMKi{WxbUa1cDcIeH2n1?nscbKV znt>Y-+5((;@Vvj-^<&p1#Z4#e{-4dXb#k~HQbAAmMAOaIDAwV>n0ehZV?LqY5R4>J zJl^)@!rK?N($3aS4zn?zbT+(txKA7ZlHrV<==ZOT~yABPdUo}yn({`n94=BP{#D@qoq*M^fbJ@^wwv0s3mR;nP1wQ&@V*H# zA`*AlyU8q#$&~YrpmLSupptQB?Td^@^XbLuY(&_x+1iGWiZwP)lfgk%T$}omY=jj}x$_>{RqLL)WbRj559^ zBHY}au5U)9*_$L6da z>h=v7JelZy_C|uf!096LKWblx?k%Ej9BM{WY4>PEgA<;+e}L?15GfBwtR=|-Z@(8L zbaUYCsi*0eMjvKYQkC8{ZL(I^)R%`lo;R`1sf0W76;Bgucj_hJne#R4vWv~t%3ETj z&=EGn9g{!Q3PX#diQmx>3tO7L{(;pWWLo8UZskatq9jPvip~iv`*r;%1nRNglVDsz zwO%AGyQSPcB#KAXHvenAW_KUs2MLxj&qtLElgW0Y$SMU2E#{)P5u&Oru@rFJ6hhL8 zSFw4=1x6G6c=QYYS^iHxP2I_s?^;FAwmqf{)p$OO2{H}L1>~G}eu-hA(=Q;q@3`Ae z8nXc}ZCAZGcGPrH0*D$a%A9>G5%Ff+bGoMaUTRQSNO_$Rp9RdfAr1}GA}caq-FuMW zXZKUFB~uO%m8gE-*#u0!+~VErT6g9y6Jb4csJ1z{$ihTTna?i?+Y(iLD>!Ay{@%>| zBpQ&w_|Tz$m)2$Q`$XSs7bR(v6PxU=P+o#e35b@6THSh~A)TiVdG1pUd=`WpBw2o?*!l;j@dv zyb5?L8C*da#;^=M4fOBr%QtgbFWJmpHnebccv3R{wGq%PbgkK)vzPyue{(3GG)`w8 zK-lU@bfYS#X<5F4^Qk-sUp#jW#_>z4lv1QSA5ztORdam1uendm7@^VM*_F~>eb~=H zP%uld>j97TPC^f7mB=H4aLS+*WuS6dl^H{jbd~|}WLL$IDPrvxnU=1vl@tH}QwqxJ zuOa-C=YaJhla!G6Q#5l*$kRnm7Jt1pCX#ltKu2=TSx+xF9-IDgG{6fvnxFDCW+Nep zQH%m^r*N<0#3UOw&g)$HB%pv>s-;Kvnxo?H)J%F$Y7PC~Jbt{qSIE&{bmcYMj77{JAVr%V9u=7iLo( zG17etQZX%9{R_Y34FB;zo)+69>i4-HI=rxG;x>j`P zTePsA3}W$oxG^tdxyKt>x45B3nao7*Hkph`a~k-IB^kJtzBIRk&{>|w&3;=M{N)Rn3A(+5!~d?np!^& zcbs>>r$m>(DP+whX<5e>PXG24abED&ceA&Br)cNc=j8fwRkQ!&h8vP3F+6xZXG_v# zV)6YX(h&;@)ExALy_kQ>0e;$=njD$@k4iu3I3Iu3j*Zyuq2>Wg46fU9=%QUCu2KJZ z!n5iE=E}cEF*%*)(z&%`>dSq7;~>&Czf5j`q}zHz@bu!e8*neF`RVD`IJX^ELM(#K zL%9)hZA%oT5(AY%cqPtvW#m3$EUv<^x+-4hKzCm;?t85G@Ixp<(Vx`EKfo^t#D(LB zelDx0<~H+xD1@o&_y#sf-~PF-5V<8>qhzBcgctO@aX-gKGJE5zlvJX7Gld`#w>aZ7 z;_e#l#o*^uec9zJSSz8K7-a?G;8O;exxy#$s|^gqNWgHMcVe8wwuNvFGUC!BHW0Li z@(QMyM6PMp2*XkEEBm^mzYbL%)L%-ec{xA6w22O;)^wGEN^dBTxejN9k;0RV;<0IT z;ocxi&G0Jt)fMXt0{|A{`~hd^DrURkJ0;irECS0#Y%YrKmr0>}wD*-+Mx#gOBLD}v zpFDJ&He}G`0q>5OerD($Sd#~LS;Wk5+o!OL>G?MHOwQ-41&rY)8OQF9xB zq(WyfhvY=6s|Sxu!3Bfvjmd~j9KkZX)%_n#bxhA>@Oq>ijb|zio-dV=ZTOdxc4!sW z94g9D4GTPksk9U@eD?Nr>D~)bC_)l!-2Guw?@T&srz_|$GNzC;ZnapxRL!Qk0GWit zN)$9F09l&)DDGhJB?@z*Yo4+ z2byZ;K$Bz--9ds0itDp1R(qbTIv(qu);Ga1brptB^(#)IFP^o?boY>n+7EX4Id%qV znD8C?#|RX6TxJ#AoiL7?2HE4_c9=il3ZE((bLDLaX zEo2M{*B~z~E3(UChd4r*WX2KQvWWFmF@Zh6(_ln#AJVPoE*&9*rQ9M)`IZo3{Hlg? zC~w)#o)!l=9!C>pSMw*Pw(x<1>Z*16g$SC1bVQ;TkTgjIl>RN|rE?04i$*Gwms^TR zvq&HvB0h^S^&e=GDVpQ`%IcYCjG zQLMLUZQPeeMfxkEN=V;sS{pD^z0(rqv{=o0AT}P;w~=7~8XSo5t*mxZ*=)y9qg3By z-GE~{2^~{9Vs$H_Bld;CPvjYdpRtqy!3}gS2rp9G)IK0M8m$GVvKgRW;Q%&Wp;Tzr zkCY_GL(x*BGmI1jh%8^nkdfv{m$LzUIomYvxRFkHU=HW3xQzN9_aRBqXDuo$`a>GI zeq~Pwsa^jteKE-{;h<)*9EEH;VPB*HQzb7afic7`i7Z?+rFfjTh-dtmNn6{H>QGvx z6H%+x#(7WM-vsFF96L31xkR%hn2{ z$WH2n@F1q)k`imDS88HiI3oh3^iLT?)VAusaB;|kJE)2-(5FDmSGwsscsFUOkt7Ym zW5=XQnSS-v}81dp{oHa_vc=ZY*1DGhre}>4chwp}zdP|MluZuMq;O zdRKpVEO+UM0y}j_sfUy{;LUm??}ppMdsn3j`1tRi$c{rZTZT<8bz2}-VoJ;DewE6- zkS@fVtIv7<``|5J+r8>`MywtK&pn!{l-f$RJ-ZrJoSk7>)3*b;{{o1W(`t zah0Zj6;;=bvQpn)Cot8l;rj^StK5K1nKSzZ0;A3(`^IBzj8qg-q9pHJ(mU*)^Vb6Y z{y@u+D*m9pqMPv1Lc$q=X4kFz-CPlGRRH1?4(2L08tF*aD+_#IJl~f$>B3m!G0%g- z3l@~WT|KPNJ&N=N#MV;7O`%eyK5$r9FX@+#SEtA@99Hp~k(hrzd&kU^hi0;GXPnl) zExK#;r>-j;gsC(bAB#q6aPRAFZ!^PANBk4ck0tZdw^Ri=@T8Q$$ZP$urS1IF0tT8d z{~9y%=U%mlcZfBQ^*Si`TCsn1{@j630{Jr9T`QRua&N$Ue*;k;jdAKMI}DY_JI7gg z#)kD>RPl0xcs~@!@vRUn(Y8^d_uD_g?+^Y?WQN(LL*4J+(qYrf=V z|2Y@!V-`*O>>m@hzt&;MH%XEk+K?mcU`Ol6$(mrbk4^K-WKiGZhfw?|+vg)ML1H0< zq>nPmlC3XyINap_Qoq-P=K4DqJx@2M_B**XSAwQ2|53F#bN{|O6cz!F_&x`LKh($^ z^QnOJg<%)4EJK7;V!ys+RL^lN1(k)XZOB3u`pu)=-*QCwCo^-}arD#(b?Dy*Vc(0o zcAnC}%&}?EUk3kmR?1vAA^Z&mv^G9Wec1-b8gLK`=!3_9;$3S+Tx)+aQiW5y=SP`Bji1d{4FdTiq2Qvk>hh!SAu&;T%VEHHCyA|&){dqZq1fr|^rDORv>4>7af)^Cf>0)i! zNno<|2gn`fuEIf&%p41c8pYdNtAPX_{v)9-5I?7xt+tbMPy^apkJM?L!%wQaojsoU zE1IM!V=Z|%gYkWqpOHVRP4oSPZ7?TT_*%di^6~m?Dtfms`H53KUw0z-9#tQ{W^+X? zJ;$9k^DXt;hdT#QL3sz=rcJP(FqMGF5(iEDQj>+bXkic~1%YkPO@?;U5!Fm+VQ~eo zu~w8w3K|O3Jj{0XBAxS{pIsCq??g$2To23v&uCzC z7=?c%6Z8C-(KQu_J!)Yrp_*)2ZF(}{h}eZLa;G`)L<%DWmODptr%pm!zUsmE1y5-c zmQfx(CrU7ow5npG@&z`YvpDD~Iy%rG#X)@fb zZO`knQi*%}x3SRozH@K=FDYMp*hf~%K@603bz`s39n`8y?h1-bDtiVtx^hK#(L+~w zeR5HswFN=tb^#-mHxKD+!Gq9~k|Ncky_U?6F5h3sUzQfd;w&8M0;%-5axt*6S6%!f z$;A!!ua?c#USHdCW)1U$6Y1v&>@*&Of3LlMTYWw@6S#I_v#KjJC$FW*iWM4%M7{it zq8+llyUd+l`-16G0C-x6#TR&J!aZUYvyyo7*-K2ZO4vs&TK8tH%Aa@Bj6JH10IwwQ z)c8lRule$3<56x1KT&M;u=Ha> z&>alO2A98IE|LyLTC7m^39AKIci6;+W>Ivn_z8fw6oi#701L1>dhw#Q(hs#JmRZ3f zA}N_T)0on#tk|4h8UP>}$&Z1(8uiZ(6IANF*0Uu<3oxFdFpmk%;++ob6QSlLkF2g) zYfz?7MbgZyO?26np`-h(FzxZo+3c%1_gR4B^ikR*@@sAUePM*^%(@_jJ5t=>$Uffq zbzfaPX!pQvN%;wbhZ#r|m6Z(~jzsJU`xbU~%2)n^qgW!bNR2bun8LdOMsui$6UXo~ zO^hXb?h@;Cc05+%uxEWKqTH+M(u?}2G;#krcs`$+ zxB#DkogS0VaqOMS4*e)Gx9yv7FCcCT4QEY%*DQJ#g87%jA6H z-)l6Vz*{q#xQBGvb690)KhyK&IiY}R$$$CpI{L5Q0>_v;zA4kF&XQx&P+KbLa2soV zA->!xibFN*4Z$9W^HW5cnT|l`t<;NbP&P|5)lEDJ>_G%;(*0MH*$>|=)Zn$KWi2TyhLM7vCBgpW->;|hu&QIweHW$8pHGgI7Ac=D z?ib*daNb0hK|&M_5Au7Us}I z5YeCUFbig}VdM4obv5=`-WF$Vt=25>lr5$U=cFx#e$}2gn0W8$dyp(7YxQeu7JVN+ z3mIO^aCp&GRe25_TXfpaSQNYe;ihwU z&2G^6P&yMi0|JMw7mRHqT~`%K4~8IJj(+NUD0>vN|b&faR3*H7yOx%IUx%{KSDXe{LGHI*h-JT}WKd;xi)pB-7@r3c6{mf?YUC`yrL+JMf z6QGvJpc}=##CP0##?uoC;Lx{QMO|qn)I)6ZWgd~o+uBi!1sg)i zo3-qDAI_TVkNFcc;sJszw<&vbsDVi|wCa1_u1w!1Vlbtf|KP4YGrK;$z{#dhKe_Sm z(mG-OnBEst)hxnAJ6sd9!9*-%RcS9;TGwZhtG<9?-A(jc;3<+m<~D<`iq0UyV9%m6 z7OzJDe9@u z))=1NJ6aM_5Vl3uJm(Qx;JcKycViexJ8sNRA8M%K7P~i2o|X>%^V+lDB@;9n*(?t+z+n z@SOsL3M6 z9tKB{DT_Gig4nsRWU_fTMn1`aEs!XL_#h|~ZCHsqf0UXzFut1kq~K7=ykN3=YxsI> z_cIH61%HsZ1H)_&Ij_`>3WkU}D|UKKxIN^~rsY`k>tVqMnD(Jum3pan4i#a1kwh?i zlTLGQlF61zLOxxX3d3vzbx>qi*t1Fr%1*>3oNRZ|O#AICp^mB1^Q$8?Bbuh7(sAlC z7HQH=Gy+lrN+*b0aetcWlmyMsjdA@*d*$3B-A~{kiRCv;e7T3XHDD-2E_jf_UF0rx zr1{UFD+hIEVKhxLmd;M>PySyu*qRO+jNsF@`-?EvPpq(ydIKt<`_ADZmKLbiX|HlA zWN?w`dBgF-3F#y0yl{6dggtQ8V|gmA(AV8QG6q-kh$T&GIedz(Z=7(8AG3@X-@cc_ z=R?EC-b88-E=H^R+|UeZCqZ_S@P zjE`KxqehLpMfnwHi!O@dJYJJAi<8pYqA_fWO>^{e!^?o&$*W&!&6c!$7NQon;t(0p1i=(*R6dhWH%-me4NYH32H3Q!$StE`|(FF_Gl^F;Bo zs4@jccH^t{?6;}bCOI>HEEtw!4%4ueej8DAZzJxUNID`WuXuRJ7i)Pm`n`mmi?~%I zK^~>JX`XY2WGCM@Rmw$Fpa-Dj=UVY`e6xvrYskX^$M#m_#}n*rs*I0WzIRL``|VVF z&*{H@cv! zXddOKgMp1#x0~eF-~01g5a(yYc`3s^$7P3$32??|QJY8AM9 z81wI;O5e<)i>P3_ACb^V(+CKs5g$>$IkAcFy4txki|Z}Yr@noqC#h)4^wyCo1fB0^ zhvrEj<~5jdprUE)b?}(u(!B7CUzuy?Xa-WZ+BngQc#@vJ*?v&b64{tjUKKRR0p!Ny|V^Xts3or9vs{{r$VN0e52Hk!? zru?5jJBu-knLTTBl3P^+G!q_zyZpwyjKac+I__v*)Mjf!E508-?aWbJdI;3t{xLd; zHrNucKyxC^*qk?jnybEhbh6o%-~kB3V>!iL!d&^(wlkkhWb6fHhZ1vJdIN#+y{bKf zmnlz`c!1wnztii?txgKJ=88x%ni1b-xP9a6Y7~B^xuGBfA1I`BQ>Nor96aP4qW-*U z?}F1h_FS@H=?s)Pwg@abQT>9Pj3UynN%;P(}$O`+OM6xAY z2>BJ}`pGB6hah6iwVG7yZ6iE{5cBp9uO`KIry<>RmX>Qu(%`b4sg=eX4 zz5N4~?p9!7>F$Olm2hbgL6nZAyQRBXLOPd{5|C0F>7`4MmWD+E>5{t3Iq$jmcmHCB zVFreM>J!iRk;vGHkFU5glmE-5?LJI+;WKgnf#kxtJjril`qM{dpz4?_kF022_nN*b z&2-UUvo)i>HcG7E_qpD4f=UhRy`k&NP)A)Q8%x8Keg69!sATj}+l03J$vm3bPiRD0f!R^&9-`YyVs;~VmbEF|u~8nTf~ zxvcW4B`;R4)iwVLu*WHCPgA?}PC#=+cZCZODNYXzbRgb|uJ4*xk_8-z^SrO+#H#$h zm)72HW!ZgaCzodls{$Aqe=#7A1ZvipEvn_#;ve(_5`y+ly-rkWG+|NsT8^Uf)8ex@ zV=JozIMU6hvk4P_WW6_dCCKF`?;McmBD6?v&uHSTSryhW9Ah=7#IrqdgC?o-Cihh} zx5&6w9>~t^l_ShfFUg7j&PeDcP=;gZED-IEJ|{#-+b6#|BRa)%yqV}eiQ(t6hEot?YcOfV>9Cvs>I9&9YxsfEVu6tY z8i-yzp@eCK0h^adoo8ZfvPQbP1gF11e*_~T)-%$6K|6jG^;C#X4*O}*vfO8-3fYJ# zJL}ZaL&!6;pla{@2bl+B81sHxuT`!Z3rBCXHnE#5zQz!x2<3$ft^g)JgGLsmwt#$K z?sR`Yl(*6K@c)OM@p@+|bPl9g$Z$rMnMd$d+`wNky1}**Fg-cShEL#B)e0Ta2M{!f zn+fWR;XE*{5<}|86KEnKG6Aq(vl5uWKgEs7taVVwEVJfbx^_AleB^cMYUsFS&Nz59dRjm&ytH?mB*o z1TZRq$hCP2YRgN4ijHwB72a5c&jR5jM( z8%{S&T$!4f;&BQ?B?IDunW1vU83rnTs!W5YECrgA_9`qQlTlW&yn`dW3J)K5O>pB~ z|HI})hTLCd}ZzTCo}&n0$8 zeEyPZnt;!^8;@opm; z#l}V55ktd&&m<~WeXmoT2YcIyoAQ zLIYO0btsxCnsjAjMq}YIw^G`#^Zd~=O4J=b#^(W!%FDZ@XznLVeyCHdkWP%DVFo_J zYoN2tHO8Ld;C7+{qiU3%U}#%#c27Y&bMI+fM+@(&#okk@CTn3&3Uu+O;bKoQNw=~{ zR+3`N!Yue43q))#!HQPm(ptg+wvPpT*zP_iMm&1^nVS(|5i=9=N!E1ChJn&D_=TLQH#Tv;l?LSn7K5-9X^VcQqSCQ=7xiuN zT9#o#XKRw{jr0C&eVwZe#D#6$3y=Q_tdE&1U><4vl!Oq6Rzk9|NY@$98` zH{SUC_59Cvx6kK;CaV>29M^`hL^QFoo~RrpjNe^3U9>_MTYa!1-<9Thfv@R~Dx92p zIbC0Onss4BX4;I$1RvEid_FV-u$T#z+H)weRHP4i8cmy{ylh`Og(hZh_NHePQO}{x z@&8mC{`E`@uN@cN3&GWP1;;hE+WjfW<%72;QnnIF>*Rj^= zq}F-Ugi94!S!0XVPhEV9nJy^)ZO+&94d)ndG%YIBe39@h6w`U8Y{?OW!KGa0AkKmL?3g?m!*^`=!|pQ=^E1%yQIRx> z(TZyiV)rj{vUD$*JA9o?!D1Ksb$rSJ++fO6OJ0}osz!faa*+tA2<&|w6AAhp4oTSr zF4Sfu^uKFse}r!;deT{t2$m{kzvVghL6KR;Y<^v#JMrKnJrFEbc<~wSdvDj=@CztH zVR~X$fA{?HF9a9LP6n%9Iu{$uoE@ahmXP`OQfEC&hs~B#X=ksXLn z9RTx?)YTncU4k{ENth=%WL&L9md7mD?*c(n8i9H6%XflHXmHN_jm0km2Z$(QB-c@l zC;DB92le=(*Y#oX^$Fp)33gpHIuAwf&d*OA;ljsDn@i{G&!bh!O1<;Vqh;+NbprXD!9 z|EQ_6Ywh*w0Pi!NB^_N8jbGjZmN8|z;EGGzc?;}fZg+5nLKequ8@E*H+O=L$=Ifro z+dw_YIwb>G08Wf%1@)yAqD-Rf7f7c?UauAC4lbD(5n2Nlv%=jHLXvU7Z}-h?3Oj?4 zZ>j!&hf}$wPKR6sRCoqy?eGR9{Ur#^!C3{fB=-cx@LRVXxgDtcV9z@&^C}m$ z8Sb%Da5`%&A!0qiW$=XrPtWEO_>$&bs{0s2=` zK*h_U<&A2xxUbU^;t&XHyrI{bF}V}hb^JBaWq8GGDk6*@BG~?!_P5aBb6({Pn>J_W zB|t6$s$*fZDq>-YV&$R_E#L95>*IV%D6Uha#C>@Rt;_RQ%D$PmaJBoogH)#!587V} z*~${ETlmS0cO1#Dqq3XaPTi78OuRqw+Qa)a?lUX#E?--JAFc8`>#S7|hUPQ()yfz5 zTP7ZZAV$|G$E7)2@rAA{M!QE{gIPYv;MK4!SC#tOGFi1O?7XJy-Jae;@k{&WQ%Qtz z!=?83$+27rJ*E?qi2dgSAQ!U6{+OpXnhz5rqms3v-YV!pkZOGv^pXkfhT_^cb@L9?Mv*@W6eit5G{QU!2kFg`!}BvnKH?0C_f z2*787Y<1VPPDz_7(VE%EILLdH%wNRUo*aGZv!|@F5^De3AzAHgmO&-@yz+c}es_(W zh?)l-EJ7Uq2Hf@2M%H)PO>)TO0Jf7<8v2>$FQ@uZ8S4C?SIH%8R zP}|VkvQ@95W+x0T+<1GDoauzs{1(*YLo;3RY>&@)0mVZ_OX|a(dB*zt{2$dTSFE*K z@Fu~8)z10TdEw|&laVVE{FS~_KDxGvKrexsmRGlbF3-*KkD|J2u)VU6pFjULv|_ls z9h*yyM8(2@%|L*ONHYax^3@*m`qFC4lCi<=cAO!|tU&(gVMR4}?t*51M$I#*`nB`{-LRL!5)Mpnr; zV^?q1oO&pGhzRak5er_0A^8Tdw`AgfL^k7o?WLpC49+_pi6Ptr{+{RA<(~O#xRe1d zNl_*Jf)T_^BHiu?>e*H#v~UYBBTU}Qa z!2KB`udaS$MRR?mZ$|M7bv$M~>+fwFdTbG0daCcn>u*N)DPT`p1r~{o&H-f39w9|mv4(kzLYS1N z)eO#Wiy3jvJm~fdBhKjxYb&GoFcRdH51F(snvndPyPJl5y@;M$OnJh#_|zP2fE>>N zrfXT6s~@v1uE|ro-1C0aEk=zD)>LNojd6LMO~i6=#? zQB@K5NJXww|F1i)I~T6})_Atj@%?wwQycp9|GWUrFI;2ziXK#EIy+3f&000baK^dj zF%e95lwtJ7nRU`Tm=qc#fE^rOXbaBibiKNAfcTq~1YB{Iv2t>qLH4h}AE05DVeT{c zRI(m6`%x`kO{EPMAbopN8Fq(WFM8cD2Os7bhy!Hl!pWy20Ag_^9Vn>J z_1e&>qx>U1cJ#x|@c&ZJ%x_G#YiPB{7x=l zT-!OpSJ=|gK!d#}(>Hf<*GedSH)Tpu-y7wOS_pYU@P+6=fhFZARLHvm&%YG+xR29E z)YRcs2zu|DLVfxC(v$Ou5`2S5f zgXUJJPHC;m>G{P^|2TwvIS5VoQY)jx{~gsj%*)wBVZFbEh2XyV<%T|w6})q z&&8{U#YNvG*zLe_f5rpNOlU)sI1@6 zbzkOmt;FDfyUA&<-g9dNJ@+0j#0iN>aEl zk$0|T259EHE^fByqW_B0Ylk?-9mJ;wMNzdePtO;522@!#MnoL zeSi#*y*IcC<=x_bo%O?ddTq#r1)b}{?6%7^Lk!kJI&%An=*Lf3x--U_4T{i@S;>3k z@b67+GM$b05m%LMI&V`qAHY&i_UpqR*6Z5#tK*FBvEKg<>}$e~Z+UR?&U~nUI)K{v zM@#E-#skR}TDKWl=fhRU#f%)^+pXoRMU9_3ePLa1v2QjmS-$1it}TGxx1IU8M9IW# zItN3^I`8xR4z?qVOGngGEgroOSYe7@Q1coLH`m2DsaDc(d#8cer9Cc8v7l*x#b+CZujKkf*zXTr!&|mX1#!g#egKiu>~J zI%~#fGI-?KTX;yAs+rMv1Tv4mTffU!o?q*KM6VnAVSB+=rF;08=!aRLXxGWL0%%wY z8L&O`?mY*RVzx|66NXg1tm>{C@AEaKG5=ZB3Uys;?k0g2M;C`OVJaH-OogCmaQEM_ z{Bw^+X-nmMt3g&H&@;Vch1zqcfE9HvVg2npTRGrz0ILMbD)rbj*vIHE~TNnVnr1Ikesi(P(;ZQdn@r+m& zsY?Fe(=F8mqp2CZb|2vVwLVQMBN|$wdI|&yucfwMh`?UUMidMKN^spvv{4B&DEj2S zM!Df_YNk=XvC_$9s01ax9sH|KLk)uBXA5ZLutb|h1qWh$05?H3gc8JExe=gj077Zn z_%B66rVOc`&A$v5xd3vk|KgqcV`VD*-KJTZ&@5+e>SwTU$w^#K3Kz;xpKA;-MG>B& zA7|&T2iSUcx+5uqoo6Xkhp%j-3uI!@vd(>%GC-)sXVfEwP4RR>>gdKHe2gUt%7675`fDT z#3toQj8eo~$>rHC{^JSUSoIq@Dyoa7;xK_+{=}l9ARFQ;W~tQ|#7L`C6ZZAf!mJ`Z zI{d|S7=`529$BkVf`;|kD@|v7@^-gJpHK(XK>3P|G#|~0O%3j8c1wIL4-N9Zb-FP6 z6jO_INqkA1PKtmFk2X(1!F`T{!u|X(TW=SclRKmzrZoZ#IHE+hVQ(NR~h0AvEYSKy+oD~5`qL1;#Q9a-Gj}q3t`P-^lHZ{EG!SUgn1C((4 zXz9?5F>gyp0cSp)6m^D2TINkJ&#-F_ARp6-N!TA3WO~GCUPF4J5j{ul*8WKRR%8(Q zxfXY;ugu$Qz(ZY%Q2GMJFC;?WiKT3(&9@`PY+jaYmmnYyt3EctR@9a^=7hH9a&IEv zmOt03;oj3e^26zOOMS?Nxw~-4x(->jDz&|J+&L0Z7~`+Xf53z6d8HwcgP+g0%vjd! z;9^oq0xxxt7k8t0I#&L)8{ksnn5COF)ceTOv`wtB=7xjMB<8yFkq90+!T^|jtp$pQ z(fJ&6GvKe8pgpX`V|BI-C7A3#G+CDY5jh4W^Ka=TDO@G>S> zj7Yk2HTn1<^VkjZ+lj1?bMZesFC#IWq2W##RHq^nUQB`BDMkX<9GN!BXIA>LBtXbO zxXnU^<1x=1wRvU1>~{T+7bw(3;7YykXE^;xSuSE~;7>!o(eBO4u)69 z1ToLm*EDH61|-H2=Z#Kp0~(`mMz0vn$rxrFI%CR4PZ6uvp)}2tmJz~AUQlWQ(c!D7 z8`@n1IA3?!Lf(dCumoX62S8l;cP87o4$7pQx22RcOk`8>M_J8O6H?b z6sXrJu-khiPM)xpMIyD3t05OwSqJk&#*Suc?c(;k56=_R-u;5I#-w3L7ZEhvf61pG z-(?=OlKYtR!Dw_k$pqwm*8 zonQ*bPM!O`3Q`q*b~0l&1DPRlV>-E`_Z&SC7$)5TB1!L*T^1z+UxL3DXRNT5swwT% z$q~v9x^UNUq}(GRCL2#`w^gCMyzr7bJh)vVwEd$$ECa~u9~F^HxI1C($$r<=^&jI%_|B}VS2)uTC?U1f&fk9JCvk2VvR0BR6sJW00H7$Qgj_G`grUS} z0U{d7+S1ST3ElZ_sh-F#E_H#mM)3gkR!I4lrOnGevwP zNDL7m3YqDB*XH(9F~<~kW^8Bn{=aJd&$w11kF-+Em6gM|i{ND^_*icOOO=Y# zb!fTD1xwNE-l!!W=h?Q~1-CQLQod9(_m;cYASqHSS}e8v=%ay`P~uLlEn*<wW8_VHeRV<^N_BR;+IxAzKY~!#ic)jyA`CpZ+io*&VHfvKA2H!B(RjEp~QNrt{!icwJc*kUR zQX2@%*j0}s^Btn#MJLneD|!p&18c%}jk)`APeojx3U?Xyp1nT^1~?i+v-qKmP)<2h z9hvAlEN|5f$2A(D^M@mi(?k#{TN_3CBW)IAT}@$+u}4#tW{s3NAT;Zz`jo>Gs9#9r zAWO`x!J=e&R=I-`5^)3Kb(9zD|8ePC4pQ~ z5S``u4}4cFJZGBFkdnnGt|F)Z5^jW>fopi-p;zrsHwUb4ck9}Gw%bt?r|XC_YI{uM z6~f%B6slebUlAA8%T1b^Ef=`#`$ApDmU(yU=yhzxG!qM!;u1ba|G_D~@q4eoTCz<3 zp`;s0vJDf~rw^Th&SfCNqh$56k@8G;z>eHayZ-|$Nj7y0D0hkXJ*-7d^hy{-WBCAF>+P+{jiB&65V{1{*f*>l=fvXnC8{2gQJ~XD!5^^@!Y2DNhLc z(9%UoMkq56|1u&dAKe>8_y@nOMtB`v#Q&Ua1ctR?uddc)d1DS-oPINIL6!QVJ@@2& z$%wyL5`AD~ozcc2ta)w)2|^!%&yOGevKwO9bAE*0<9#ON8TA4Fq36+uB;z9Y2b(!p z6BKPckDOb5_Jhp^3A7XJfA>0?o7PwN!4TerE%$fT$06mQV}8yMn|8kN)9ZmC^m~jW ze+{YItqw1X5DKmn8RT!L?y#-|bmCZipExPjT!yrf`z|nMBs_KjI>aj40~jur6L+2e zd8Z(GK|vY(n7QL=;v%Wn#QQDl>-_dm7=OmRQ-XXT6iw5A0ZeYe!uX*wwdPP~6a7|* zjEEGSq=s7RH|hP^RGY)DoJrHyH-C1^u3sXqth=0vsRZ-oZ|B^OSI3*Kd7tk@Bj%>X ze{W;fcwgl}kDC&m>YMmH^zas16<@YE$#7D91X%fFUa_0`Z%K#co8Hd%C3ZH%+-3Or z+agU%YO&W!gieB+m}{(k1QQ1r|A?{5GNA}?AHlD` z%h(R|GjFX!!mRcuY7$LX2l<_O&Xa0|E=bVZ2j2IKr`UKGt}YnP;}bq;^1obrG>iODJ*d>W7+D z7u$)30(lrptPS0-GRKPin~Bm#AZ=f+iBw^}?DU)dn3Bg=PFlmk)|pdFq+A5cwfNdVpYSBxLU_HbvEQ!e z#yI&QN2lPs#{588IMvQC^hN(9TcF9OfLZNagJaz|pzJf0JG;K{HUET%MgA9qC$??E&Np;>x!OJLn!i6BCVo8-cyihH*gUwq6_(blKJ} z13hU!sp*uO$G^zL8RWR#-$(lEg}@z@bxA&w>;e{M4jfQ{7?Pf=%>r@EF`-QLLnD$f zOEP@$6xgEfU#E^6!21gDBf;86v=~q~4z-H0>ek0&gr<$=defn5JYgd~pmfBfF$QWD zFlD%yTO@tPNHKAEiyYYB!0U7qBEOhgN5~y%k*$CG(6SLX9jyV#!~7Y}7|MHkmRT&B zQOvfv`zCUwFwmF6{&@D$DuK9)hVJ3Ue)-HI#j6?QnENW%YZ9nh2oX1zhL456 z(n5&}4(M8T(BcwlrWQA|amM zwwvxV;ajyRN;NT`YD=s667_b^=>d+1|Ep{XMg)A8VrE}@ZnFht6O&KI0gl<@ zZSbwuKb-%fu$loD_ z<{RmV2gkxm)n~B*>);8h+t5Ds@LCvCXnyu_y%e9Ogz;U9x|dxD1%=XTijyekdPB5i zun9eM8hLtzvOU^+h~jvI?EPY4gyHy*vCK|i^-l8}S&$o(8Qmd4bcL0=7!UM zRAP2JfAnJhc(aUmTe>Dw06caF@R7#mxM`~=UxOchS#>^hxky4+op?~1z<53wU;aUe zej%L#iTvi61AnYBg`-yIQ7*9w?Hf8I*C7{JAWg2+M=V0$6s~0Gp1?#lJH-dwDagP+ z-$vXvME{(?(Yk7$Y-6@{T#Y0HgKiG^7GEF@Ge3UZ!uk%;_&9raR9!XBzUH-#Vf+FY z$0*Xa&E21wo18u_V+h=*06Mvj^VHIVzUm-$XcsHuNrN!B#WpW#mn;%_&jeqNk0Mj= zm&!FFI*6h9YS~1V4X5lc7;6utxeTQfw^wS8R+i z|EcbE>u*wHnUg%MA`@5KuYku8?udk97Pr4PFX#Oz8rmDKA2%GRH_5D)d7FFJ2n#SN zl@SSn`|)&005+6H6=btex{=K(v(+DuDK_NFWXAi)H`K+P)SF@+Z@+i`(EWD5?NV&pUCek@FUyk}NlrS-t6(vi0=c+qEl)k|j-_eGNFp*5z zwuT{BvxW z$5)q-MH)|t+?7dK13{6CRSpUA_Oar$2(AB_DtI3arw86W>Q)YCu$-}D0W2{*6?E|e zqFphF8mtcp=;K7Lm@#PA2lr&JbA)`FdbAtVMB0bQJrXR&a86a5@feY45hU!i$N5@g zkK+lw9!TcWvbwvZQ;VE)URVU_CB{V|wdzz` zHZQ84Ac-n+3o5QGj{I>vMPKZ5PigYsF>MNi&POmZWs;wSi#0mZ-_6$^gVa+vyKIH@ zxAaU_`P=yff)_MJ#^AgNeCUEWC9$APYlyLIzWVB=>Dl14Jx;*zltFT_A4ecBU%H%a zpZJhS>GPYC)Ar?dH-eoCx-nITM@l3XBK6n>8gqy7b=Y8>KAa?JAkGjw3=(CLN6W6W zj=}CaSNoVu{;<&JBN_<>>`v;lN8coKB=*hu3v6*R294rT#=^+_KpNB_hf{%$tuUJZ1?C)pdcsl57D2)rdfU)Wts z5k?+P-AfBT`5u3ED&l~{L{`WvIW&<@}F8|DO)cxPJGs_Tr)8a%bvI-et!n z;xd2O4u+YOfoLNJMxe=9g?&v9T@S+;pbH67k~ojdx~{OK^d40yZb znX|N2+CfMxrktWP?f@l88YF|ECSY}mhM}V}TjA6aC@oH0-fb>m;XrAYuoIYJ6Z(D! zVe{5|3kZk2hReh2fKC&w-|-|?sZ4Mx=&N#7f{il~nP3g3@L*izn^EskC39__erYd* z&k-S>_$B`y@Q{7|B1(-Tz4s4`C!@QmHlBsNSB>3T5yqp2V|=Pd zDD3L;rmEgGT+% z+^AIko|rmu6h@dJ5hM>oi?ML%)6KEJH`$2HtVg|R$?#D{0sAxZl6CTyO=k?MK^(sL zNM_(6eT;yWA*(Bk3kQS9A*gl*`u1ZjkfNr4sP{I>FDOso*VDoSomN(8B9j*i4=CIH z(EW4PZ=0T-tNZ_)JHA3h+}gI*>GdDmlDgO%_{9Y-0{)z?p@l1krrT&NJv95ZL=q0V zM8!yk7+@p%SRbVYMZ)8)$wGV&eo@!dO#p;JiA5|+5MGc=-?Iw?KJd!sexS)rkp5;5TMvlDsC`^kzho-E~#ZLJ0s z-M8Kg1Z4Si@6GGUanBWZCir<58#d}^@-?3@#HjZ-cC(*z&R;jLDK`g7KIx*xMIG4! zg*vXF-6CBsq3n({N9}7ZRmVNO?$s<4z0%#czG)T-Lep#d81luHII`t8A&6iR(5&I) z(4zl0HlkVkqqeAP%-tMix{1fL*Qfl+!)xo68MUOoIK zii?E80Q>t$X}r*awwG(N4GF~`hFl_4xHdxlf=KT_FF?Wx0GIBUfzA(3Aq#df(6OZ8 zH>KtbM}^zbxco%A!R(b;1<%-+%?zB&wIycVY{M*DL6`T=t?3E5qXAr=mdQuK0235ke7kLL?;!_+l*780 zf5q@gd^pTIEqSBV3Ymw;G(8m}j?glJAHW@fmSX1ddO*Y%-UltL`S zINeYAm|#NQ>8P{ZFiSt*zn4M8L_BlB5ItUHsSIjE*>|6rN0(&zXZ)Xezd6#MJss{n zwb_l&j}ti`7G=@V@9{Vt1*sD&N!DUO!hA%B>ofqOXJr%Dxn@=Fh8Da8|_T1hXllk+fD`G%FO0y$(R{ zUBEoF-H-1U{2!wk5b^sf=kD@^aNiHBQDQ?RoG;A3qFEEetjV@EK;_}>bvK3tT)I!}PP$AmY8I=F=IdOjaU8 z@V?d*sH?JDyiaS9TAX$i;Q6}K;!mAawN@C$<&5ns^2jVoOni5^i%%q4uZ5Xo_=9T3 z`mffbR3jYFyyHS5Ql@_R)uT2#-(>NbM#>t?H(gxhBYN>5G=z>)$2^rWmLHQ;hHV8B ztoZrzEwCRnEB!?QY=22>N~Y)v+#_0N2?!yA7;+RV!MljOS2Z(PVUa}shw4BP*Zsbm z{A_&*ia;1hzoB>j^61B`>mTE^|JbpATHkenZ#C{RiVE3;w`pq>haj(l4hRD6a{hjN4F|pd~=xlTuZvLJC2Nw!TjTdMRU-K$P;N7`B zv(n)lZPK8xit_RsmMy?Ru1Duk+z9GjtcypxG9N!RO{GNAr>;fJ1d2YL+aB%eTOrqM{XK->F~=5`{{p{rZd(*71ISM2`c%oV5QE9niz81=&t^s zTRQwUe@k|0m^%B`G({1+%!fjnVyyCO%bv%eFw&`=b3S9k$;S$uGbK+VaX_aE7KO@2 z*F_6L1vNB0pM$A#lOu6Or+L)+y`=r)Xe1C=BWSa%mrlgT6MLmS zkz~VX*TM@CA%aYHM*pZPA#YuCb?3@}?H*Qqs}j#PO%x1ttu-psJir7mY;5HEsUoj_ z^_0hvIAAWvH7|5M5ls|jLRl(Dz?eNKMC@-)rWo?Yi-4WE%0W+lZnj7vik_3B)I8=; zRrz!5&;@OIz67$JPF(C$I!8+Cqjrk~F?YuC+{x-1j8a8kF=WneCAibTX;}X-MnlC= z6P39QBr-%g#Ele^lz^dYl+R#k)+nvw9zX$6WFdq+MawN=MDs1CX; zXjfs1PW6rci5w<lodMDdSj6bxaY5Sg^NlJ^Z9^8AjW@;*8wrGu{c9DDN)VT3;<6u)2nW2D7y&jLJ_z+FpWL%G|ey<$O!#%4y z>293qK`4nH6)cZ#wk>{?~otk=;k>!mYv(d;EnV zfgzZ`RR-$a4Yih*$~jo;Uk(@w&9{$k3wHH}`wAeRRr4Npfs#Q*%9AKn-zNHF6+REd zs{LsiMFhW=VaV3nD18h~ z(&p-Kwb$)(;(f8}W45!ZB|`-Hf0)*r;+hT7Sm$7egi<=2IjHpQgrLpO%++iokfBQh zkpjRs0f*n|37plw6r|DSEzLrWUiRq*?X6o+b+ShMv7NXFqMe4P**`t z>;UIy=rroCO=Uo|Z2WBhzgfZ7ZSLJ@8>kZr-;TtNK74SP;sdpo>Y@#^>Z1jY3F_~fBG%vAi06mVK892jDcAy!GGq^zM;0mz zg$s~Qu(zVBVdmDy-E|q`MLPQt`|)3xt=A#BlwoFU*`N`Y zs8VkbgAI5s&_L{X_SRp9r(#`?CS~;}5EE(c{m5X+#y3^k0B}wu;p3n4>wsgz3Zof9 z3n}IKV~?M1_DtYJ#>#sKp($XS8ApXMb(w`R+0Mhw`bfIXprT}s#*f&hY)tUWGmlAf zzoY+|`~Ug!iw>C`D1H_Dqx=|jQUQ6cF`=D@(H;$6rbOLn7uaxt5H)-?w73y(XBtNI z0Mecqk}*Pki!Vh-4bUk&fY-%9OLw9?vJ^KpY3n6fwqG*5=#`C-tGV;;*~{H)S=HR_ zU*?>*gX{VA-Zhn##oM{U0TXrR8b$gGp zq%OQ}lRnQfpCzE5I=KZ#j%iZm^a!c zLD(2B#kzq+y~Eu&w`9^po#KBVLRtM9f~p9WlY0b&;J5^r#JGmDo*ACr$CwBD*0hGX zn-^7wxYQqh1zx5VZ%M#oed>0 zFI!I9;K{@}maI85=`Wv8b|NlHI3)m0+hj}wN{0QO-glu_O~Q_-oGj?Lxr=C%D$V2e z>ivqob%peK%;*5TmoQEt8LWL0f4Zwb-&-zzw@B>_UMrqMTIo5qtQ4LxSeUcd zPW2U!ANNKf=5u^#H~cb9YKqh(n?6GBrDU$wsDX;xuaX(ngN`S268lg)O;=95#IzS2rx~SC!xF zPMXR!$XHnz|cRjd&o9p=}pkoyN;=cLH2^567dc3kKG(M5Fnm>rn`{-^~;bSPzt57T`uRW$d zn>ElIqj1vGBk?ojO0owCe=jLVp{9AmaCYbCV%(&rm%|F)}q1vNa5{&a+wx$z+Ptg^X2c z2UJKT*);lF5``$7Bl23pcWiY|NmriEMqFxRiohwtvh=9 zA(;E&>kjhxD@ZW@*zB%tbbfq7Mni@{PZ|E_G*{_Y%Gj;mfOlcXqt1Kzm5(`3Wa*{@ z%1pwv(NWUTpEtoMbY>l3C_p;0FdVNM@r4C|f}s%LkZ&EzmyKhCvMkf1(g zoBmO=H-usH4trvdCyJ=9f-m#UszDhpB8w4HAHxAEWh^E3=+^_00PB>^8-zr0R&>(E zIP)zHf-)c4$~3|-y?ImdE=6{li3M;n6})NOtmK{LsbCCLxphCJ2xtIQxKVZ0omV)^ z+GVn6z%-e{WvE-9w-9H^%X6f`U$%?P+w&)5I5*axIYnF*3Nxuh02si`HO~0jp0>q zw^D?=AG#3=HAdO~4vlH2X-&jYWQFHb~#E zXh7g(s@%B5e6>3XJu(@`jQS)MJ5rxlhlyaBU-4JWK%ucwGH)5?!j{blj}=_R_Ad(wC$Z!kh7YDNhSu_cb{ae!-M#lVYQ84PL4kU zdWYiB@sz*YtR<&v+P^-ne z$#Wu|&PrJx@t$+Vy!0&4Oeh&@L8s+UNfu=3cg^bfc#?f=Cvs?$ogTU56~48L9T~s= zo#HHwitH34je1K@BB*Qvd-H2I-{N!Z7mzV|{lM(}_{elF%~>`vX>bKQne`{XVha;1 zt2bRwdaTiKui6SKGW$DDqO(!eKkR0G+5;^|fs5+rB0f(FA;178qpxNrs3e`vsHQWJ z6teug)g$XriZZbfTqUsh3RVqE!y6^amC3EzSaz-J-aJB&cmlFJ;VVMhsDi5NT#wiY zr+~k33`dI-GG^Na&8dltaUF;yF2@+5!lqG7* z?(8C=8ZK#+x}>Bgwl1UfuDm%xnAud3?=A%@KzM{{jVc8X`qQMSl~5fBK?(<-kbDS9 zu1u2nRQmyzt!FIdGw8M5KpgiJGzpgfNZ5gRB5}(R&`cz%(#<4B7#7$Ns%FaK_pzOAQi4vg| zW?Zu+ty3U$!pglPo3V>7TcXnSSblE0MeEY*&bXQ!ao(tp-{G;UANfS~?{L=6ZeXG) zP-z8dF0ukrn=qk+|CX0Q3SO`VX;vPT^5E#xQ+5=b9Xh89edoB*XFwJHw?4lXxK91f zek0`?B{BT#T~Hi9i6I?1JEvW8WySP?6R$7BB5`2Cf$8}NG%qB$+N)lC(=TR!<-Jhi zL!5A`QK&4z6|CQ6At}-Qfk}ZD_6;G>UOR!ErCMycl0u9dl|o3aC}Y2+Jh{@=x*7&V zNlOL;vI;<*T>-3fUHvq}tRP}TQ=g^eFP2KtKK$PIZIBMmjMg_0}iGyaWk9co+$|i+z&)y?>i4UE_!+gWis5>Oi>S!Oz1%7rO-i9gQk+ROfJk`_O!KjbF zlr4I&;O$nQdmITWS7G97u;Ufu^7|b{@&SRz!YTB&83^bb*<@iJ(qbc_=flI2JM>N> zvs}$&(91XMdvmtPQSqL;BH9VhI+YLAb%{7Lp2ClQ-1^V130XN6DNf5VR%0*~&cjA%Qkd^}bE zN(E0fR`FQ~ltf9ysu0GTiKRn5C;E%8K?0{^9^|l+w;s|N)SvHPFS8ZLpdU`h!bWJ;>?6 zf&31%NW|$^VnOKXjDv2A_A{kOa0&sfGST?ca32-lg)8Q+ze_#{o^WR>9A6TI^Jd&h zAwaRN%v1u3a6sWurd$zGUVw{pG6+?RkhR7wgMI03Kr3Iivxc<$=T@Y1=&lW z;@VN%Veh{7fx3oJqR*YPM~EKo<_U^xUtrt9N=QY+bo|R~zA{+mY?tT>891esh|lOS zAE%$ML$e8=bUx~85{jA(_}RAKWU*Qr3*GmX*QKkHJQ?`^jTlL+EC$6B(1gL9HIdlC zA$O_Omr4(zGOOaE(!iVA&2~6p= z5Wa3zJ8)b|Asy}eUNd^hM&7??+7H>xQ2Hg+YJmC{A%97t0{fGWxXTSweBS{cE|N z6JW1Yk(~JS(@~m#ZKk|iP7H8`oo`>iDng}&h7k@lxRb-c^eHkao#@bR2Xh9=Xz6&kQ8H&7s`HHQAi zlfd2%^`_ZQV6yx{Xo?W{G)cC9UIX?F;~#?XVD6wEt{W!H-?Y*PW%J(>7PIbGG&5im zHCW;xF+HjSJ6E+e6dGg;am{hv4F0cE`1Hf6P>0!*IZYn_QM?`q??4dI!+Tof&iqny zFV>y&W2rnEN$qKN#O&qwW<85lPN261(K>xn@RWh)3d|&#m5v{nNyT=>aG-|ZC6$5I zO9m6Zn%T12&v*cpD7cm+nnhF(vbb)9FYq)dGw%lp- zMM!&`F~_^>zJMNS_SwSnmKVKBwNJo``JyC!*)>_&kP<0z;~`?tOr7ynV#NfT+4F-3 zKEKp^O?5bDj==JED&nh}qCRSY52}^MV!2Jt@Iy??mO?fk8-z(kRIjg;X-rdH!f`OUcAG9z>^7#(2$Q*f8_lw`R=KF z22g5K}a{avc9gmTEP(?=vv)p9*XD@ zp6j{esxBN!MXtp9T&O2fr6&vIYSGF)%7{y|v=d*q5Qs4zvhAG|r<~e8R{I~BYm5B- zif`}8BTX~9vYW%IHZ~2#e*}M@I)EoO{4o?TlrX$<{C4){zha7Y~o>|bP(Dvm(kS;)2 z0!E+wad;X7HDaiNq_~kUht0A>i;z(!uqemP_}ov1M|2*iVx3PM8dvXFkgWV=NpGGv;AME@4TwQ+gfw1;|Py5$=7D5?C zQOCTafeMh1K`h&ORk~t7$}s=z63Yiy(?ca!{?2B_Y^Y-gkS5g1Os{J4{AFQHJ#nB^ z8$Gsc3dQd_)j###!@Ql`smP&nnIK{M>Xkz}1HsI8t@U_zB7%T^Dbmxu{M~5@5DKMF zUKR>);}dgxyzkRV$|d9`_$Kn4iW|heHTwLQk*2uX&^XE0bvn`cR(sL$sK`3Wc`Bf! z5Y=K_%~ykfIzIm&tGWHdZ~4&y4bWI{Oh(MM5YVMu@uq6k)`OOx-&?wOo80r|b2#e4 zRGad{eRca^+i#Uro+N{xDqj8{z@cyn&PCDHEzMEmQI@^&o z3-&Z)>+f$ygdHsUJt$A=7Zp`WIdF*X+_hHoS)PtNk-SQ8iSfLk3=8*jX3YCp*u1#GTc*qkVGuo{X zyNI9eXA6TyA-_i)dGv|*bgL*$z6h6MAmAzAA69{H!f%P0>5#ZEhY7q1OsoCr2i`7z_Duw>S(YrOD)6E(T==Gj zY&2A(IH%6NM(97kESHC1S($!)S-7?)B8b)f5D!j7hz1qTO%z+gg?&g1=a|Ts>&Dn&jgp+Q}_g>xH2WUM}7sW+& z`zTjzJyJb8%U9;&rH#H##Tifux7tXzSY)Sz1D(hR1K*pS-}90~!; z)>P5D)CKVTPgBZU&yEZXw(_!8C8YRPq0${0;Wv3~k|AP?$n=Rxnmwhq%Sp=-VpBk6iyg-rO>o3FRHDR_m%E zL~p=CYw#`G0C%O>1`hP_+62BC8@1?^K!ec^v398=wGDryrW2KnIP+G&9l3x@rPKG~ z;~tnynpv@{L)nlBd)$LJvCDm!f$9kTi==*kfQ#lAg~kmx_QX2C?vb{hY6U+TCJj{h|jb+`mhwozB%#S!yBO+-^?Sv&by(H^AsWJND;3}2V` zSC;Af*vZ`ORNl|9PaxjN_!S>ZC(qe@O1(!fmRU_ce$Rd=MnyJWA`|5~_i)znt<$xK zie2qL(?d-bwjnn%q8w4dMozgy;DZH>1@-}JvvsO!Ymg4z;=;OiW6 zfWrJZ5#$VgC)jO|7>{{pi%>#vmwWDaKV4#Us-c&mE*`ha{Q+--WHRsE{mLZWvv++p zw?O;zqDwS)Lizm$TwL=gs-=qVy%EE~<6o2yrHA(t3i9v1`i1YBGM-7ABV6<aD##@eKse(l9!U?TbYO1l-oLWxT^EB%lhz*|G&^de(N3j znywbA#a=;ZOSAES27R|@62wo*x=|)tma+~P`_~27*XtFeR~JiHo(Wu0v>>he)?>Rr zD=?d6J)5Mp>n?vAJs^Oc{F+Wa7hIJDIoe!FZ^JfjD`a!1X`@nic9F=l zQZFGSV~VXV2OqKL-5;C&6vPr4m{ereAEz#i$`f{16vO!(_di>ZSwG;ZYJ{4+Mv+0P zP1J>0oeAqL*dHlXje{8}n603$*?j=4=q9V6H-QR0J|Kp#nBlZWVnhyVv|vqrhep{4 z(iu+%#Wlg7LR+ZvaHIud9QD}r;sf3tv+9`$11U!abkS0!&VsH$c(nw^5?}0nzS7<+ z{>=_XbQY9va8MX)Ly-6|cW@gc_kX^C>{ndIRd1>ZXdhT|pp;qPOwtk!|6cp`S}bS* zq2gEHKOST66>+Rx{pBICG>2UpKL0CQA?i^saB_A!SGv6-mbr?)hK~XsQf4Ll_1mI; zu*{-xeMtJ-PJDjx1=$c>lSBi~wH3~2zps+hsvJRy0l&rULpN1`VM<9VB{R~{;Z9MS zQNK~O{nl<&JBP?Kjj&3(#XYnH@>Qocf|pw_quRfp$vAJ{J(%gXjnVhQmSKn{5UKRw z*g2dY@AI%h8!X|=;3-6_7ydo-CylM2doXiOJ+NjUH27#qUlNn4GR9pqrMK z?g=-rGdh{~`@*@;PY?Ke_Q438Y3$|UN6zixlM}Y>3XiVr@|g^hAlF;(=IYNM?58rJ>Kk;sU zV!3yi1$0D!xj@-XnSbQs3>r=t7S{RF=Dg%%Z8`fgG%nltKR_t(WRdvlI7#X%$h9?L zQ1TyC1&|Eo=#~H7rihwk_3DBl3#Zp_<-*2p$jV|hN2nGM1d&+#wlzQ!i+Sn_^x`uL z9-lw#G{?RPJ`;-bpJ?6uoLJV%Huw@TnxS0_lelRssT`*N?htjVn}vCWj)`@xr$0Cj zjHTWOtS3s1`0k8uj0Gxf-Dr129)kZvyX2c+w*+A=GLXidJeP6kj7+hwk#P;&Gs%;C zeJ|*5TUe&QO%@H`1Iy-rnN*}7MtFOyKUs zLh)3&!YO0sK8qINJ=?aedn>Qf){no{I%$~^2Gcb)Xx;^<3*<%Fb?S!S#~aqbMpG{c zEmgTu{#CJZ5^!ssW4w&;&oseWzg#@j-~d%@64gcN;G`yYXD#PI_kV6t{n6BjH<_$M zxaa8lt4h7FETrj$^gu-UxKU$we~%IGh(TqnWD2RFEz!=_bGZ*JRb79}?Z@9f#D|FS zjEFyYfD<@b7^P(24}#~q2&^2+MH8M7`A9=cqM0?tEO*{lPsSBvB7q}uVOyzE^Q6OC zchgr&*oX#r1>)cId52#y#nT+}CX_Q7l{G!aSRcj5){$sNsm$Qlhe ziIKwhhUq>i@>+fHMY!dzEP+-mK3IGJb8@M;U9cSa5;r4*I^_|6c}~=ruui}`$zrL z6gE1adb(4Qbh8iH1HIE&YH)#Gl_2CjVC z%F#=zI)A27zJ1K}?_mDS0hBhCI`3eW*3GKy=}iD(1Qju2`CfO_($b=-PUX&skIUOl zA4FE@AokEKTeT)?(6)6^&@7hrP020XdK~S>3(S#tcT)F^;wfyoUHvI)ce!;Mab4X% zu05&`ic7 z$_LdJk+vC_WvV>Ia^c<(BiY{I@0^4nsmhF-2p((ZS{>mPSqq^;Y-l`q^iy&(cf;IC zVB%rXi@)iDPf3~#a~Fmib1Wj-O$$dXjzc+e&j3HPPkZmVJ7oQDCMg-V1WqEco<0S- zf9W0&L2~UF76mbWU3Qy_v|4CbdF|Wg|Ey58GC;yEz|xi0is>bo!Et44&!bj=o#`#y z`ldKGabMLjKt4oFAWFoZbqhZ27HkEI^!wfSxMQBHPTI((uYn3P#CE!fEa_9DOw-5t zwD|GGC|}#@o6~=KXz=A(Me>cB5UV|Idny?^<*uTw0eX1#eQ_lb?OrrF2(b(c(1m!t;(3yMDm}Bph9qYpjVLO1ASIICsO@i z`=K50&nAGl5SI&D3i58Aj(gR4nl@C>%=???w$04Zs{=1oT0<@Q?*)SBD#l7e&8@D= zSN*Q5Bu^nnzI5f&Tr}5HJsfCe+GVetz_k?_r;zquI;qnkpaTXT)e04cR|@1fem;~d zUV8o?aeDe;6JnV(O}$b6Y!lQnEUt$$=XFTyiD)`NB$L&MiXEfoLq3GmxXyFs5a&7H^lxw6Rr-3C?x?7cIcW z##DA2sbzQtYt$CBmS#RVJh)1x#&sEr{$Ej&cy)YT+! z`Tk&7qg}E|NEZDhd9nBQ<4mPrxLA;c+3#N{9f~Y)4H*)ctOM=A!?sSfjM*+tx1=Ggu={z`h^>?3mjEbK6;+G&U-{dd_R%JS- z=2SLM+zbY*sLLL9Kj!%~^Qn^+?GbB8P%C8noD8r2S-DtmO?PzZ_LsKevYDZ8ON|p~ zl34!X#y2lEWpHHqwOw=P+c$cr7XJ19er5ygk2_;6Pz6;&F8_oGMMQg6sCZC=9HcPY zyYn#QQg0z`nK}e=i__)1H<=bW8*|*;zhWCWzc3%`pSvZsTb#+$Wa&SIRlSqEj+X&tCRyu8D|`6^_6X+3j;DUp_J;QG@lelREt{D0*T zYufoSUrmwvfNlEwPGw#mVxEb*pAlWeRf7nXSQYRBRXhc-B{v};b^~V0(C>Z=wBFjh zQA^)p)|rUdd{*WL)osu)#*1&lB8ye=1or%Oulnu$-csqp=NB79vxf4A_GX{8xDMBv zpZ?sB$qoTp9m)^)#LsAi$RPsN6X3!Anm~-eLh`-sRq7rSl<^>fW7GX>y;)zwENJ<;)`MvOVE+Ue@i z^pT2ACGb@JESv1e@J=H1CQo}cELZM4c$E6;?I{Tz$KN!1@@wJc@LzGd-(REOS|UD% z*X+S5Us{e4SF2Ltrr>@n*;(Z(h(_os*Q((Py?+xSGL{4};wPP5U{tUhApqo-gH~K5 zm=YLjP&mVurTOOgt`-S!ut!2UHynzK*I&^JKhND=a}qy)dS!`u!9sIIUEp$%8q4Z` zh6E&9ue~=7ihMpSF{*%-W);YaF_(9Fyi|Dif)hEzO(&3Jmw423_G#P8onsnnlu3Rl z&A%)33*hI?>Ge|*ijQ!-^msfA=N0>o5Rcj9d((Ircn;hNzu2Ob=LUrBecBSZa*^#2>90`#ll=TP-}hO$0Ph3I=|+?GhnHr5I5 z@CVQLQnfo|UkwQ3gSImD-FOdD0uwpAZX6E6PFGIl3bg#8kv;t3JzwOUInoH+rx;p) zNuPDiNhh)b9)lC8z+24bqex_;4DI#ayM>+OTFj+938|iA5;xGEC&oCSosl9vl!;81 zPh9U}DN*^SzIV%@ae3<=j=uQXuS*TFCGTPOrRpdYe6$WFXdF1C6l8OsY4K^s)V;PqBaj zBm;J0LKu*(1~@-No;6Z5qR>Xjb-eDqU7p;OHGQu?gYAoqSjfOKQj6@*y-IYS?fAlgLmn5P?oc>SalpAb$l2^8dTP* z)dFq-kHi98-CKjoV>r&Z^^9T`VrLOwtnEQJvMm>{$@y7^FeTqFshksJr)$Fof;+f z-VkPvqIum|u^>uGbuHmzNHhWTAHA&707}j-b9w1I+f)d=($4!L9LY8jTA!9f>k=5df%XJ@n9tgLhjU*>)}RuZ zlS8H^4HE2ivm=|i8C}ZhRehEFm-WWPjtBewgFXfcBtG6Zd~E@HwI?($9O@ORi?Ap>h*45D^**pKO(>ka&Vk1Q-*TYGvdW=&S6Eh54j7;!}wr0@}~?GWT1a{0s; z_Q%Ha{dcA{0}C=1D3Q{JDlMYF4O=$B;QfK$&KS3V%nQ`V%JLT_lyaI$!gt*z+{6w9 zUs%3a`c}fX9$vxS@*z`OMDy@l8G%lySxhha9_HdeK~(eWM(Losq##$fd$x~`NzqxR zZGz?*LeiNM1yVeiuT?s*Zr1vJuXJJsw5)8R{C4UX4^?ge4;f0gtyDENZ-#Uz{g7eQ zrxt+xA=}dgoi1iUKcCoi(Ca%^@#ac4R(_uCY>29(+~CD*-Jv@Y#+AGV2Q4@ciMp}$dV=)E(o$Rw#vHZ> zNWA?iDMXz4%cdq&rfuq%25f>hR}WtyCW+~2 zN3gHQnM$N{df5caChU=tU9>K8`Y?bMjz8*L7iA_!#1PMR)^+I6McU4rSDZfn z{=l9u%ZmK+GPt;T%k#Se-6lZ~cc)`#BB5{LqPVSZ(ii(Okt=c&;Pxe<=T&%XqwW|B zK0+VliEW%ORybA2qpOYyhZFTF@48pI1>H0(4Y=l5EGIz~ExwuGcXzMH3HR-0+ z6%|BfmHn`>Nvzk*sd8bFHu5gR&)&17SXm2>F)mDg&kbX9dhdj#u=PqHbL42*SvC(; z1SyL+j!_*>j~>19awRY}5pW%bP@Kvoh_6Awz3eEOMSbi__ScwFaoGG}soYp*5DwDa z5C8FdB+;SNfCU#yn?{vZY!9CQY=*Q`Ery=_cPpJ)wtKyEOvS;JuS4Ah5Bfkk%k~pb zLMJ4NIgfm)maS*~6_Ot`2$ioC^WAvW(2lwlhwOya+n0a2Pxwq4l@>}#zIXUd&PK=C zZ|ZnGg@3wMhBIhQxhFOT1L~z7$}_^3C6Hb569_ytHTzY%DgLlhd&YSILM*K4#wUag zA%cBJYa>(}zLh@PJa7N<#_>+b;p2oOr+~>KC^avYSS%qdr>XHL~KSB9+js01jaWoG>veCV9)sGEw6Fe7AUzs&EGX)Ao2bg6++tDyr zE}2|4<1k<}=LDgDC&I4vD$F4F`C4aLVgB>BK*&_j3q*k>3?*a%gGt?6^!jWOS(i}F zc>KrjhwN|YLa8q{ML-4c9@A|1rS@8gMm;6#fxe9`sQR1qeM5D+hz%0XX0oNh3M_}3 z-0#V9QRkEbo})4(F}PZt;G1%Y#aqNRo+a-bD4a-1v$^iP`ZO#BZ$-{=misAZZH9OV zWH9sOrfus?uzVVs@!;r0_JXIC?dfB;7)94udE28WN625Q2lC_IX{JsbL<)vlpbz5` zy0}m|`E6-$tKA>TJ8gf1ZnA@X$8nff&yU_TxDly5oIAma-z{LU?DWe!m|*OiwUJ~D z^M;cXFb)|c8t_8H&&$)QvGcqMwvC&skdc*;gth;D%0AsbC}TRj5o?XVQ-){H0n@bE zF6!*8>z!j>uxDzOE#UqJElQBb4hnIk5fCwm>Fv_kui^TB*~g_en|J1f9>hDek;JA9 zSarpfIkcBPdNz9<7)}~iNrhz>5p)Gj&_h`K--kSNEn^%H~ZZm7N4m9e+%|Qk@zWIoAZP z;1qRNRkPcBIuN^+->-;2)+81^3M~#=Dyh}_vw44kMmDNisy6c39$v$L&xre0zhcOx z4WukOMoakmKbM7COq?7p!z&qdio@2I|6!GdMaxs!$zMZlgAg5TY~|w@4{Tj zd7n$FF{_|Kki?zeIre{M^&oMfVuO{8;g$W}3Si ztfm|#>JsA1nX=VfT2W;L4a(yXZO67I+Q6-q_FXOT%1xJRQ^|oELu8o3v&qVnFusAd zDeE=&m{H9npQhAM8a#r$_Klds;Vc+iN}l7B+V2aAo{@-sEMnS@!KVica^T)1LpWGe z_RpXB>X*FSckXmPru6Q6i)i)m-kMG>PuJ4pAgdRGSCMvTU=gU$Aq&4=2OhP0(kdRd z@qjhx2rRJT;XI<5KPQz5$g`F$kHbW?i{v7PXFJHR8o*g$#soGmQz??=vyWbW)dfFb zyeD+Vu81DSm0$FBt&n5(cFrp%b@h!PEv1*+fwG?BY=DX`Zv=iFY2>`FH8%p1k2R z|7Qt*wE$U9f%E;KR9B0k-OqaMs%$zM_96de32g*4n?&~YYA?6WZXR{oy7JByiTC~v zhS!3@O~aw$uf*@niOB!S`jN*RlTBSuzh-Bs=|~(!w2&?|nkV1v%L>?eB+*t(r$b@W zhor);@9nnV^||KdwnUDES(LqT+lp{W?t6 zKO`(FfS8Arhtng>CB`3#6OLaEIg}n~&Aaj&kPxmPZqBUUfib(>nes2xW2p;<^X})^ zZWonHK2ICgo}LC3$t7ybBPbX@uso&`!;u-?ETa`Tq-_PQE3JEtGgPg|jT02j2MR*o zFl#6@5ISbCUgygFZgXz^$q+1kd(M+9if2mgocNdV+HuJq3*ZDZZg+Q=Oz}KXDk$jdS(wq_^$SI66m2;TL=?JM8*8yZD_D$5mEadnHX-Rm4IlTwBHmT zs-|Yr@Eyfr*}~)Tz~h4;3d+YR(X>|;Dj4_Pz!!u9kEa4uezau4q*69LR2|Z)eghMB z3y20*lCM#6`*(DIG^64n$B*g$s7T{278h=b|K8#5EB-jVFPGjSi-xj7BBL4vv!a%V?@7sAa487( zMx0jat%DEvN+<5(T`JUz&6uf82j{fuh#9xhg0DzpjI$>vr0)H%YM2Z1TOSx2DC`I% z;O@cFB0Gv_wqz1#&zSKs0xm1 zx_d+q5n9Mcy*+>thL3rJ&{uEeTT6k7Ru->z?ZIE?L^UoTR^%5q>^zL$hcRnjv@|Le zwSqd7)p7Z_T{I$-eF8WuO)`E29C!y-bVA-)U`7x_bimF6+JH1&hp%W7q-3ZjJX*Hs zgEfix)*lv-#MpH`GQN{8_J-xpozs#(J*R4)zx!qZrSVJTB|(EDzwiF=>T~)ecdTbc zZxOq3$(j8UiRD3tt)V^w1_xJcSdT5SRLB@;Sv0biZE|E>C$9etq|AMh0rpdrlE_L*j2KAF{V(!M~VLis@PDQ7c(TQN(-`H-mDU66Og!9T)0BQ7LVTB`a z(p_D5K~!bv9$v^`$K1?8{;iHL#fLzxT}0&%H<291SM%d=b`gn0RSop7+2^zm2Li{%F z1W3%;tm``@DdHbAOfda99h4I3|MU60#%}RLe!*2Zab6anR^Ge83jyd=lK4Ne?O|vB zvsf7J@D2cnarNpcn=bEVngOGC&e|cCiC2)Z;9{IL?|7ISwfZhL03NEFR)7uoq?@oXp}|9at6I=_!ljG zlOkAmG?{a(JC{`i^4(4&8Ha&m=A+iwNYC=X)U4jmuUAqg9Ljf|hGhLqc)U!$efy&q zZ^wsPk1-Kt;I{3_Yzjcl)wBP;kk`D%AuoxHz12U8dK_SJqi%-`v{m`zR{V0>@^1!-_HRdGh3@0?# z*OPqmYV1)K)x_t);v^aY%ez_?>|=Cgk;$UPbKB#3^X+do9G`L^)4Dnl#J1&_l@LtE ztJJ|lT?IP>F>^T@;&vO%6BU z|8RsS!8h)vlWpt0g*ngL+TU(X8_`}3DrvqW`cGK1kMvChDlKLI267s|eIPt$5emk| z$E6A<;%Pr#SXZ54*Rxb4ib9jersVbxD8o}+lFAMpfZUfcPuq-&NqC;NsH^xvceh48 zje5ctQG@CEMsA8h+n+|z58w8S3qKCn8;(A(HNn;88+pa-Eu35%a%Wg?KULjD$XyDl zl8O@D(&ogf^RFG%;GIa2*2XfkXX~}f%R~NZ>ts0D-=}>J|mC( ze(_29{((B#h+0}TQg>BJ$#$eK4a5`K? zmLX7EEBivu;b{FwKXO!!gH55Tq{AB zB5p-J_woe@BtI?+M_NawWFs)-;7#gm(lcH+*Yb>;9QXPlD(A3(ja8CkjDUT_YZXBu zJcC4xR;*Mo@AWwK=qnQmRYPMaqTa$;bK6GuY&jl8N*%}b8W=`zb4_xNt(c!0yO24Q zRdLRfyc1D=L@enbX0XBN9b+_VFrCyda@w*W2L%6}={Uty3$c}Kfl*LJKC$zSTdi}a zBWSRT>WlQKLA^VtH?S1tUmaHVsmiFEs~!IiP7YoOqPtRO&%l*_a`RJ&z(}LS_JtOg zeb>^xQgMTO)%J(BbS3kFG1iUt^#mwU$dB+zd>tbBWC^UhJbVgwNMHH||8Bom`m$0; z3Bub!Ln> zPsW?L^)^2e+-E|IaroE_@D;kNA1nk+G%n2=FIX#mxdA{6|?JRI+mLcKMzp}0_V1EmABBaZi#jH5@MV{u9;#s!#*;TA!5$V(|{QB>6 zq8psT1HPhnlc+LakxbR7_S2p@b|;}PWgS-UguFTcqhWCOzsE7W!)y1?Wt*M|Y?W?~ z2v&@hrn~1NDybu)%HLyz<%QR4F3{S z)qjdm@0JaQ3iGgOa@sr1%6lO?GdH2v({1d~(xUkP*NH__)!KSI6ZFOQo z4{1XFZA}nSOI?eva4+liU~-Vm?IB6n6lQ}S@@UTei1g9C?E8lf$_OZQvUN( z)NS1R;V&Gzk&nSgxf!0-X-ObY324bu>*wKJ#13YVXBsj*%-{0e<1napv1}g-rYCAC z<9`Ih7X%w6K=JMZGCVC3)ap+wa8oU(?xSkhN&Si%XRrF+EUQlPdzaeDqQSjtSEXVz z!HnJ-niqVxAsK8!{9h$4;qpO@x%c@kl{h>P%f~txPFIA>s1?usE_Ga>zdb!mIdP%; zIGp4xPp*o&(gwU3Js$vxTErRoTYgObrn|{qUXi}*{3Q_EkNOrG#+7pkgu(hoZl~Ca0ks8k1;FH zb1xL%R~y#!0_3-(AwEmPBuqQy;QS;=XE(ld+e13H@O8X;=Yts8aD3v%lO>Y?>EF#h zs)}_95@$I*Wwwiq(KniU2g)@O$(a@38Yy7?2({-Po~N(qC??qNSWXteK}ni>(>_KMJ?n*8UUJUWd;Bu`*gJNaQ8xvx8W| zRAwPEjF3B!dyB2$>NjrJScUE4FTx?mnB4N$%tc=8VCsdzw`4>k&b~(-TISz z4?AAs+Ya3c{30+ju&^c}|IQl!Rd$>^BU1WJOa0lE*j;+6D9=p=R~712CU}%$BGKN% z!Ig0@rjovY0ep_Yj#!=)7Q-uSn^n!00d**|y)ZdGmDLnk<3e-6F^Rc&!`->!)gS{W z`8YexweMbmfwyHZImQ^mkSN>^g1V6*t!ByKFQTQ<__6dc7?Z`#NL|;M?ALE>Kl`d> z13u+D2(h($fhtx^Brv?~;oo6tp=sP^5=DY^&~u>PgTAkm`IicPZLTsRw0ol@8q79M zc*Y9%jIVrRy0CW-coB_Ovn^0~Nab)HB8JM2L>L{E9aT7FOLx5@;P|F_$-3pk^P(Wg zpv9jP=r=UPfr6!0t@yx8RbEBm;#b-C6%emEZRHs*Q6JJ+DQ72NjKk+kAokwkfGCPOj1)0L8|30$hXyOFOYT=Ad;vpBGkK6mMtt^5Zy-pNJqE(WeSg z;lb#Rdex9^>w(G%>u^?FUQW9H#sYzv*M$}QuNrTGXouEi8qMurm)CPd@%s?aFEE^{4OCi_YtkIp=e`qsYiB^FvJ^M0E87?#7 zF7VmDp5o7%3Flh$qnv%uZuHS%)NIk(pYU>^F?j?+7yt=pR`IM zf>}l7sgOD1cQ!1BmcPDXMOxC6;0h7RhXYa6ckYl5{_T~9O4ZxPD#@GsM4eP(C`56D z>g3yA!-a7kUI^>Mt5z628?w%($tPq=T#9-0NZIaUc4x&Ra(cd~G28?Cr+e z_-wTUZxlpY#wgj;~_nS z@j&tH1R&inRmYujxMPU|Porl}*G+Yp@!e~ba~3EvUc zMNyF|iAhIi@e*yYm&>jdEVmwi|0FYVtCn-oZ^=ThUjMLO4G;#6n+G zBUmE}PSdcz;c4)O$Tre;XnjW+Std8g#;S#_g{|{kZ+yF-*mUH4n6B=5qgmdiA%x%70-J+<>)cay zUmyw>kTY$?X%iF$LCa&cof%l#;|zEVY*liUoojnVE2O4#`}y^48_dWq(rrI+hJ|wsW|ksN;nXIcynipXGWRVXYCaSXXACXqT(&}K+5May)Sjv5y-nwY6UNPe5)dfq zu%f6DZL*XCA{bZ~bfrzIo^Sqj@^&G8?;Z7i$m9o_$F)+sFl!m*ST)oo-v!cLLW@d^u*2N|KsW{ z!=n1aeqp-1hn5zQ8oEQel~j6Q=#rK$0U1C*xJeG*?3py$m<(aLH!m(BLv7RO=KneMdXk9o(EGOo1J`Bc$@-7(yvkwrvhyV z3CUHxBAp-#hi_?>xqF1s{V$p%zyqk*k-v$p8--OOZ-x4K`%`CfeS6thDp$C#g`}Jt zysHx$)(K-hHBJg)z0|A|DJ&DRXBn=v3Imy=pJK)Tb>x45Vm}xNj2bALtg#PO{&r^>lr|4IA}Da@0+Ne|=03zKV+uDV}c z;b}1Q|`LcinT&~ zxm^i(IH3)AE_>@QlMaJv(q_Nx&6JxE1kAz?uRgL!24z&l65?{63!Po1Jg4mPQpmMd z;uP5>q}g4;&bC{x^j*?Pf^a1TO7O63AidC$J$SuR*iy+Qf-CKFiT?JmCWUv-V$JsG zxJIk0iU zfSq~YM%mu*mo;T|aS=zM>Ja5EQeT$vNsIBeG1G4ILUXH215rBa=QE6Xe2c>HzYvkM)J$mmaL_}x3hET0KR^8c;hySB;iVgy+e)BrJ zfbCr-KN|lZ+~B8&_mRP?x2%*&#EF4;gO6y51jH?Ja+y@>t$&KUB<&(ZNOgD%17Zo~ zt_h3Rg8$iYMKJYH!%cUud9o}@#b+&hNosLtaj~J5sHUMfq`|a*$n6_$o)M!~)KJ%+qg7=H9<^=kF&J=%GDVyiF)6y@*R zt=;!F0A@|-14X5Wq({3m$=S&>!{x)#*(gRw>TGmpGr9j0B2Gw>iESa-C{AD_j&#!S z(+iwS4WY*spC5`wgDGn8L73zqJ_*NSAx75lZaM8^jplg5{ck|o+Hqd9!P@y(hnux=a9BP>!2^);L+cF<|Ay?m7Y zi?{;sMeiYn9nTqHP7F7h+N;NPg@kfC{xdu>5A_6Kx@V&sbdKxTS5OT61C6&= z{Qpm_oH7TpKr)BEi_~>%KDAMjCMilWDwOs z>(`WCqqj_zCe<#>8NWd0$yWjs3hQ~Dc@6KQUes0kJ`(vQBn^}YdubWY45+q}so_7B z-_z}}xM8ymKnky6eN>p%B%df}skuKI{qlkC1SUJF|2RK%b?)YG$CG5gI@!{c+-K7} z%5r-#DMZqMl{&DUTz6H^Y*tWsE zpk>jgR8}vM>1Bl%yb|Fk$|MsL5QaVv9omzi!EKVKx*dskcfwn7o8k5k~6J z@?1~Yksf>bf4OwB?mPF_^JI?E&Gl_S7h}4NX!p-uWC&gm{PLw3tk^B|rZh4SbrtO) za@6*bsqc$MO$bnPj|A zuEzQ1`L#EYY8ic%Yq;)qanqaAD+OkbO8O|KBwhH0!ftJ{jZ+~hKwShtpB4Zmb@VeG zDFLdj+tjGW?tA>H>n9*D-+tNKvE#`s4?PhT$xI|{ecxE>`E~StGY|VYnZYiKBveH* z#WFxBB|&#O=6{i5FprZX+iLPjmF|0~#bW-0#?EMRY$BX9Il(x<2 zw~o<3V8fJ&2-CI}9Cc?KJ02CtXZ%`8?nw+0w%Hnd{Z5XJF27Z~Hhd)$E4E7)Ujk+b z=B2f-i9|P;1&-8%J!1y6NM_1SIVoe$J-<0la`dh9;i=GJu+Za%V_m~O@()>{@saU? zr9b-4KhLqqFm{u=Qr#u|AqM>i2ESK6QXj1?Nmv%Pbn+ejm8!CxHDI!0UT474uF61p zDWag?c&#y4pFw|5H}1YU)%;X8b*v%d(UIxMsKpzz_b;B0dk6F8(3vm|`e5 ze_nBW^(W?5X_nXj92CeWi;oB+a6EGS6C*Cv32XQn32*v|JWB3f(qK&s`@BDKYEJ4S zc6Ap}klb)1Ri*|WI|(5s5n;hyg#HE7jLpdWRBdFVxST(ARc3xAzUq#^9$1>iD7=LJ zZVL=i6ZjfhC|*wp%x#+OfFzq3Y!=()=u$EK;PJ>q;xH`_p?Kj3X$n1iE^8&&7I7dh z7J~s_)M^ynqZkp4XC+;6`o;B+G-qVsg5(dF%0kXUO(rH(;N~^aCw?T+PooLfo#Nq2 z4AeyUzFl4;c7I6ARHNYvX~(JlcM>IBTt9a1MWcEHYDl`ym>0tku$f9stQze0*}R-v z5n*DC11#!LjIfY6#41Rz*S}^c=k@;)D^&xpe`Y$Y&vx>4@otRXNiL)6_q2;ZSlCV{ ziB6Q{%Gn(@br)$jPCV(<#{gz+Byp^6k zNO)K-g-2S8YGI!8yNZ7%))=ryHcK>$uI6|I>CVQV`jqyQIO8tXULk0J0Nraf55Eba zZwo$_MelD%fg^Jn!QL1coW1n)iyl4vFXI?TjzdEI<$+jUS-zSrN&?bs%GQFj?(Bal zq}q;ODc{r^a;^J-XJ;CgtYN9atI@E&rZ>hwJsyM)gz*ufN>|MHP=sOgZdUb$~;gu*}odPiNJ|hEfajqrzOMXpiSh<1b0;IhzLIrR*$R5QBw85(j&1FQJSq9F_~UD1 z&$xcHdB9eg$I{Y4u4}uVd6FBSavw8(N*FSzJbb<%sSH!HEqN79XAe1EeTDU6@L&dM z@M)bMB++Iu0Ob;ghKK@n6?1F2D8G$*f_!xL!}GAT5Od&{)&%O|6|J8fJa72TzQo`h zyKGP~G=pEdHj@7_ahFuLdVc`q7;id@D2!fb_JCYQnEg%}bVYcRkLoZuGEX+*Xr5{| zKuka1NA?HGU{oLn0V30E)3)mAKP?7e0p7}%krUczPw^~`szy%vme%GqaU6x-9Yp-3Dpp(@u^*&Pxg(Gjn?*iS1Nz{D5Yc z*^fjxZsxgix$J_nR&dL*>Cu(G0{9#=mbTzbdX(t)W91{>mr2 z;c|igbyV2;`Q#-^wV&0KS|J7r9c}03@Tmhaiax00h(C zh6I^qhhiW2wx?5ZOfoR6Nb!AF=HZTnpU%71HfsELV)?;3+8a4Wn#)?m| zWCyNw^Dh`aTA?3NXacU_ZA}+{9vYVmuXopOxlz9YI=@@+QpwrL>Gsa^vupO_*(sA2 zmfg4iVE(LTv?GB&{@*fhwc#o1URpHuHkyV86-Cjvhtd3REcn}8`jsP1yQ z5^P{p?!o#HVU+%R#PBG~`e2&4Z)ajbP^evpPZ_>>xi$Co%ih9E^q=B1?h<^@*QI0j z{-x+D9L*!y^MbHpJ6P;_-Tga0Xt+r(E8k;Qi%-{!03TPNkyP{rTq+0Lba<$GvGUM( zpocRUlHl5Wp7(Ghb8t4@-q27Nv~;%&yuQA)0i z)TrC`x!ivFj0N=~&?HbBweZqA__o>HqVhkDv>aq&u`Zr(es!>lVotXd({&)WT3n^J zN_t0|4!An8i+kSQhFOfWuR|L`jy?_h9;T4*{s}!n2fs&44mAv^*%D>F)UIzRs&F-b zOo*4$d`@?#IA%qtSV-wa^6%xNoe}h&yn9UV4^za0Az>DUUB3AuU9=6`HrxVvks$iN z&FuXv?;Dps>ObBLDTmof*qj&E(g|h;H%agOIf@t*{TtQ7%A@+ z95?5c?**Z)@yp(n&%A>;oK%H)O1{`iLsU=syJ3lFajOOASJY;3BLZ&a*6)4Wo0ui@ zB?AseodD_+(y;h&VLE zM+&!0wV;CYbrp109ScMwq{sj%0^KT7(txTJxr{IGrkuX=uUP*|!Y^r2e`f$A`j7rO z?M1rA>#xVOMGNKZ+S`%!Hgjyp_syDN#Gjm?{xT)3QM8Xoy}bISzYbH5`+mNO;g@ol z5mugZn38~9^riJr7-_j!Sj+#ZUml%}cA*3@?2VIQXMlIe(zx3WK8XCX=fJC|Pd&i| z&*&G8abIitpb$cVP_&4#z^?K=V>8o8^Y{Xot9E!iAKcr~&&F~^beo@rW4^FoadNM2 zP5FH6McROZO4JeCcYX3`h5e|j6M1x)?F+q_>R{L;q{O6r?@+NVntJ77iu_-^NWaK% zK1Oh#-D!Nll#Fus*de2L@A&+S14tvkm2AKXvR0ZmxEgzqdgdi)2W6|g3oL$vizMiD$6`dR#1yT(e|SU~(%+H{0jooSeH_<8D4Vx+b$xS8XQ zUWvk~!}B3x+4V`f##F@P6gafmTm}8O(d)q&9#d<;M~2ra;(cdV8NIgn6pZZ+?4$WFG=qwj zsFq^fF^(x$xBW|LtposRtlw%08JMf}+`YY}BhOIxo%MI;h@UH?tEFA(mR88Y6%hok1PudO>fP5cXpBih~>SfRNobHlX>BVzo=RwJ?BjD)|jM?TVxvfdweKldaU zd^~fcBY4-{W5cRKbFS7!a!=@Bys2Ar`)yoX)8v52CY0;fIiZy!8WfEFDLAtm2mb|Z zk=U=ZXLQsgQEOBIm(#NqrapRwfl$3;g)Yq}#@F#=eBK~grzPD+>PO8&^N>10z(@7i zxEO^GR16wJ5>LhY5MYweRm`3UeS~T+)40*^8IHi_!fWcOscv^@m*To;7~GdgP|n}r zm>Ukx?VqN}^6eW1ErmN{S z;lgv~#W)S6#H-*Otm|ju`DO|f<63`h_?m~f+?RFVFs1QvTnZ}gIjH0eai;jT;f_(b z2Odxqk(`hoT;OGL89!(T_KJ9cTt7&q5*q#)4VQ(&d1b_k5{01cPzkSOm*je4&{@*t$f|6mxs@P_N{9PL;<+Z}LO!{&$a z@zsyp!d%gFI?F&U@r85uWU9l+S*j=!SciO-SrdH`y>7=e#0Q{4j<10*MkW2|DBd4# zELo%)8|#fIODwo-m`=pOwsKGP$WN#smcbKhjj|KV6n5$cR-^N^s4_3e5ZxkxWiCjp zv&NA~tQ+vHuzAbPFP+XH(p6*mlTjGqN~HJ#2Ez|B{@e8ChWgtF+YMvS>=(W((&m3x z+(UP2dPPJQVTqPRaUwiD3Bp)OGK0Q97T@K1zX8i|=ixlt{l;Nuk5c&MrRNXig-?1C z;^kz;1LgW?TxoAkl&1fr4$tr1K2%?*YE6C8T=>pzKYMolXFA#AV*b|WV&3+s?$T`U z_Si&85(294eQ12V8T?;wtTza5lL8OxC6(U{7xT`GS67Ksmu?~cPqs-;Z@ii4lOU*8 z;ot{b!T8(5@ot0Bi`+iw9r_2#CCBv(d;I|0?@P?t4JOyvq}Pt5f04-erKdcx8yLoB z@r!_N_Ml>JyGdQD?J2I_bWJR$d#QD4gfwrE$;ff%+C;`Li|Su4nujB&J{Yq|+Nvh2 zCgVPY+jO@DTc_k-%ik;!{6L)*{JB`8&~%4hF3xbW8g?l-yLhV5w6DT@Hv47B>y+6- zUbsi>1Vi<|hY6gVcF#TsRiddH1qS~`cw-(6)s|0m&8!|3N_o@1r_~ZHoBF8H z{S-Uf0sge}X#_!yUp|d5?Fp47<1oBzPIQy~P8`Qv32Bg`9+=9djy5YiyO_pl`oel2 zXb3aL*Duhe(c1wd6@jJbY>?n{c@>IDhhBjZnDiAbbu08`o~D>Xg%qQwa3C5?w1>uE zp9^v1GM#;Rqxj7MCzo)raRtH8TLFA}soz{7msnO1i2-(D{C;2I^0guL{l^-HB-o2a ziYjf(UW@5eZJ9a$%k#Sx2dc8e&{Pp4XN8QvIxL{un{5Br%BVkOvfXN>pQ|caqcu51 znz_J5ayH^fW<`FUT>J8J2_$j18%`%jjFVzq1Q*SXM!_|7@~rX8O)QUtLwUN+N6)?e zi-)PB^*Dktk1=2gS}h6Vbo*yJaG@cWopm|CT!&1ED@}|aPpe^NPc8C^>+tRYDKq~# zT&d}q>n}_aUTvI__5=Ans+enoFs@hn$&`dof}~&U-KlI1wRi^b^miZ!+Z^Bbp0&T; zUMNwUB?q-}JN>kZp+Wx^5X$A!GNCk6Lb>xq?Qw)Eu;O@;?) z?&;A#HN1a$&%R);3O8!4kY2h>>yXwt2-lP;b6oaMv=$T|lJck6PTYhpWZEIZsm#aTWf#_!HB^xW}eTtqmQRb~cR8U|+E@4A~Js+T_xEeb6ZH z_Dt?w4fWO1_wzEz>>C(&qcVH?#(}^CnJD3$O_lum>kOt#?zRzc{bsnDKyVzJjks78 zQOJ#weAPBu*e}bR-d7d}7Y9z!z^qX=d-RGMTDxk{T%pjl z-Xd6$zM)AG0iqx5dKhqzOns-yR;5oVt0D-Y+bU6yqJWR6)*c9zN|v&K>KVxM^|Jv3d8 zh-&szvNuyMR}8p}Wy;NIr9MtmS?y|lZEU^8(=%z?s8=rrlEaUmzHa%o>jVwd&2QtX zI^tW+GJSkp7PGA(nHO!FvU#23>=d)uzc${w`88KE_i3MAuT|SAY=b3UWJA<~x~<<4 z>yjlGy&h>Cc^s==^dy^h{8x+L;a0=KjKYKE|28Q}RI!FVR;T@W?(QqHV;Wj~&9u2@ zwOOw(84V^Gnbc6IK(;enjKr4obeI-6yWjfFync7PxajNl-K?_lZ5-UkOF(-<_P6#8 zo?Dimi?Q%*ygZ>PRlKsO_9KyzEpIQ)wob%U>OyzYFA?`)}^>e7}~iY|#(dDBslND{6L1koM0vm|AJ;HRt|!lrWFq31xoN z;>o?L`dhSZ zIaauqzDu#CR~WoNyf`wMD(erQJnXCgN_!w;Y9~R^^)=?X66@pQmZr|K@GWA62jY*R z#cQ(9zn^32$H1g%vwbNZ5~ydUN541nx?-d^CctXH*|glmXqXA~DJKb2}lt9t+TDbS=(?D%D`a@N+|B~XP! ztMc{Jp0um{#=A{8I0RPUjvocPwdp&llaXk?(@hsiZhKwH5AF&DtHkQM9IS&{g` zS6P7b^upkF#er_@?ov64Kilg^$3t72Pu^qYjWC+~I#05S(VQINv+P|e^=c=RDT*-8 z@nc|p@+C?hQV?^$e->}GeoBSo7s2np1;evKYps`_V=_1fwK!LLnxa-$=~Jo)klT^A zwluBKuWV;2g`hus%Wymh+x}JTabSok-T_ox+wnE&5PS47x>Do~e6Dk3@Pp>@JB2zI z0t(z$o}_%ds-m0q>IZ#lvtR?@75rIOcjtQ}U)YUIZ=0!0? z&daUOO`z9$QeKqE@o#FV3X1?4#dkX{K6{2_Y!$Ril+_XMv+@^LQx7Tv@LjL-wbo$Q zJj?uR0^1vDJjTIBhe#+Cwzugk!X)x>UbImYuFWEyL*{$kMW6t5l0WLYYQ8k_-7~pe z>oS>fd;C76?8j@>0p=npGwtZUd0oYwP(C8*1t%$*J}uWOeX`0=NL$wsC5ZE-RF(0QubQSc&d zrS|PhZ&Yn0nh<;vngDXb-VgJM1#AA9h_Alol(iQNc?80lzzin^eR9ISpfCTGT(wVu zT&`$rC~-w?uA5yJ4^rYYHh!_C%9;G+a}I8mF!Iy_n|Z~HESxky+5ZkxA09&wo3VpHErSidLG3Y?lk*1mrHD4@InE5(-c-%cY_1KB^M_xKJV0+y~sL~$vx-$(B zk$vJ^b0=cXmaViv&qqCJ1!a+2D~+S_GUkf(LtR@Z0{D4*FW~=ib`I zd;fJEloWtF~_NIb#zJg2%jDIL@)#rB)WzVKwCX#EW> zZ(qD;;=u9alCwdXp(Nr`Vt6pqdE?E_9?8<1o9*=`?qP?hjNAW-j|BN)!7_<<$BwQlhgEV4Z#5p^N ziC2LcWDEBi=2=^WG!@ytojz3R?(D1d8^?6baqRf!X&SCeadXexSs9|Jd47?MljhZ# z1Z!)n@0dR1>U8|X0_q{R{PXu#HWI|#H1_WKN9*TGA@3+mcVN7#cRuX{n?=KmUfw9)O4y*4`WZ{MEOL%J6(C&o>oj5UR03ZPVa+%nu4CT+-!m zJ1^KB@dg0$8(_v-drjF`1%Nw+%YLAM+auhSUgk&%lbmTt+)25tgNL__HdIDxUzq$X zoRzpLg>hx=?Z-csJ>$8rGA|oDB#qbe8eF$M_*GbHL@FG93X-l0i%uejd;7?1w?AE6zKO7WrB}C3aXdUKQY)JE{*`uPpAHvTtyJ^v5+%b)mQ;+?aAW<(E-i0d? z^Vg6lLmFoz7q|!5-$hu^z&{*~QhoOyZ&#p?QxqQIe;St4IXil_FeR3OyY!^M(HJ0*H^5qzm}Qs1m!AH+~DA+dCL!s#dMwt!&dWPwAApE z?txF!+Khi<=HM&AxW=ICC*vJ5^dlI#9kStVsq_us=KO=dO}?Z2emUPjMWCzyDvGTc zEeB3?L3mpo&>I@%16su1cypm>Wx4pQjWb-uC8O6jvrIMhtkiDH@S!bYA9(!qJswgApYwdfOuhK=?Al#i(qV$B=M38TbxGfVQcDo^OKB z7M-mtl^IHa+8J=*3r$?ZJIk(cbMc|pQE$vWSMO55Aj~)c$KV57=!MNU=~kmg`Im#o z;=Ci}whRB81%N&=OUs3H5QuW-{37gRgK2Kf|BBNzo->NcPGU}UH2hM9YGwnEfwsb7 zvudpd1u|m{#mQdC9T@b=cQ4?)IlkSXg#M$_nnyaW)v6W`GHV^`_PPG5m(G{+CnyKe zfYBjPZ49qO>lmWarXbCw8r=wI!h|Qa2sNeKsG;p*AA0OB;B^1X-QNNqwJ9d5yg`MGRp^)^Bhy3N=h%z;v ziD#SdY26%})j}LVxeW$Zu30Ct$*xZA286WFW;!@H(i=&( zl@36|(Zhyc>MgPz?3JCn>?uA`ZD7&Wi>OOF!2y!!vA*_HW^J}wL3cA9P-YfhwIlz? zI2p6?@^&qDd=I0eSp62GI4+aXh*8wnv%2)kb{yc0YZDWN(;5N98*!a<%f>4*nJ!uf zytuEtK)HXT+{4XJm8zBD1 zr;g3`q*%+Yc9w-d37}F-pQX=(M6iOwM}wUy>df_j%7ro^YhJQsG|44gSCTZ`= zQ4_(l=YEx;*Eper3b=VB%OsdA!5;4@G3h;}U^>6Mh!;okpK|-VNw$!MF)jA038Ffs1fK$^{0Uh&s)I(`tvkp#-vWcg7%ZzdTqQ^a2_`!J zMJ~c~orgVECU0^;+o{6=UyuW*fb3l3z+^$q)#EmHHVMIvb1BQlNfKr>MV6s{_d zVa59r=l5*<{A_^!MgDkQPtbbq3od!8ni}EA7siQhygU+D}wW!5b`2H6&s;aVy40bB{ zd@k8r8HM_RLyhW&99JRFG?tNnY$`UH#Vmn;v3DqiaNX0 z?zV9eRC6ty08hb)LcJuvVSTBBR1bb0@QF79O@8h#A)Wzc?A@$UyNqOTv00+~T}E%- z=WgHv+23Qhh)a3xEtl!49pt1fGnd6gmI#_n*qTbz8q^WPz+yG(Ys4@PdHWQb%qE-5 zot}>-T~#zH$i(UyT)d{txqU#`uzsOhv4>NWAN^@D;r1N3I@fWL7fVrk zW2t!af<#ZeUxTnVJN+qt(Z0VOYLKGn>WK8wEWEL9DXtm#>uy9}Yry&8?rc=^*D^5jdU3cRHWn7?h&1n)PK**stJHC(FL{+($`%jir~CiuDZ0mHlCQI?72&`L1RL1198<|Q ze-U0K_oX%Mo=ZVFu@d9d(lL)#k&>)*wKzqR<++Hxwd@0mDHXjW(gviYunG+FT)YOPyc{FAj&-?21zX*ZmL@ohHH zD(0(t*NqNk;4M`A=GlDNN_nN8Z@11RAib*Rs%=nHAsBv$0j9t{>^hkpO`AJQDYIvZ zPJ*fYVw^aZ(#-Fi=Si``8bkf6;+jNVmSU6^D0ay!HQjtE)G@GPJW*K0_ds5aWwhOk z>6!tNDfcvu;=(oDt+Zak32=TDs+fY6=jim&|H3JVg}I|GM+Bb5mhuGu!4K&w=p|h+ zvFqE%KFrqKHCM=+0=xq4U~QrJudvU;q1?HuRAOf^-pBzg2mBh66mlEufoxQ$w7!m$THymN;NuElx`y>V$bh&XjF(Y3q5O3&%Bm!9MB`H z=Y!sdle|tpQ6A^!-Wj0$4a`}}#qyxL7}%)?d}&&7sr1zBDbP4}7dqy1^Lp8K|7psL zj^k0_2IZk|VI9^-IKrDhHE>5XV_ba(TAA}@R@Mns=w4)KRe-NV-GbpBKkaZ;mKju) z#BOOKyz(v06mpIpeu)1-s!U9>#uK{Z0;Jv)D}ZDRC$F`1s*)HAk5~VFlyrI?p@TM@ zk{hi&(3iW8nG%p>Nct&5#1W1wXI+4Le8dU#82WVZr4pqh)mQtB*8dJrvK}c#FZ8*` z8Es1t%T`mBVjj84e9mSaGi$@^A74fM0EtXHYkST|$tpL6sZINVTx`sxy_f!rrxXNd zkfOpWu@}GdXvCfmcWTtjeNFHdD8N+)PY zKQdcS*(Er#(Th_e|Cdci;7x}1!##TcTn{0kdXny#QFDcKwhf_I5GLm!qO7*@re#sY ziyS^qn;2*Lp{N9@*7F;eCM0n6#oIwaZ@8E}k!nPW9)^^5#41avk!96Sy(G>rPIT$$ zPf$^DDfzOyXzFq7c7m^6-s%Cd!>cK%0SD$;$#bY z_cE#4+uItVAgKJx`7Q14JXtpA9eZ*R27XO0Ek!+PXl>g*{CR@LnBai7jm>S(3j6TG zp=od+RMNYC3bkk)>J-?p_ogX2OhB=C_4&J!dms7Be5-Aj7e&WbzV?eR zTa~;JwdKl+3fF>}BAJm5zVnby%Qx{k3V>U!&H#e%=hd@Uynsx^iEH@me9uwAiOfk5 zlHB{wDG?LW(f&`zC3x9=U)F)*!f2BGu=jd*|4=PW=#|lrLSuR!^ev=ql7&BeXsgu` zN3hL@hMl?HORTNeSh+#eS5SDPvwhBe;naDY5=F%f|L#^mmm<^zuXPHxd@31TZBX^r zUqYt&Y`py2R9!sV)@l(1Y&<5Ptv>KfEZHqi6q-uQXfHE1k5Oqzlr+MICJ78ps_zmL zMxtR6224Qply4WuHYcXy&FLE-_26y-xyk%m?{cNlUju_~Pogb~x*)m(ZolmxbucY7 ztzO?8Kdo+2;&iP>`YHT7>MOBh-0=RBJIQUoJ3yK5lwTTnV)H154Uj7vr`@WH}E7hOHZ@TUaE+IyHUzzV}-bxu_i;Gn;}Hr*ikgE}kHPBLW|m*L(r}sXSw=qEd&o-@q<>!Y8*YrIgez0u0mH6q zHP1~9OTF5v6pzU7WF%d`c=jMvSn*lz3gnzivT7lp?;l?lm>|Hf8)3S?1suRiGq&l^ zAN3Gscrof7aAr{@6NzzSJv-I|{lKXi3)^Q(G1O!J%IAO`{+1oTI$KNLVwm801IRh7 zP_8A40PIckolAwMewwS*j?|NS|05&{_iP?o$UImh(UNsh___A_pkDd6I?(d_4F`U< zrbT_1Mi(~%A0zmq)@hhUI4R9kd|Q@FDdeT(CEfBrn~%U8b4&armE#PCmlFBS3-*2q z$t2X>wj}mjni;eM5Yl^|;N!N(Ot_!qm6UG-LryZh9)I1G&7RI%eEPHXz)=q;=i)ta zB5H%(=e7ZI$LyVSK)*xke9JnhQQ~4qZ3z6r`yo&eN9rBdpy&t2vMv^q9={{E&r(!p z4Es$58Z9z)N8{g7NdOJ$9`ThtbBFd4$&|!Z;zz+vVo%zmoKUu1GF44?wOB2{=W~KO z#M-fqDq9579xxKfWDSptdo!M`P}J2wV#l-9v{jE=4p}{-HKzFfyQj0i)fTSueS>1< z+w9XdOK=6KG+t+?`IYO$ik>TFT(2ZoA7BCU44!zzq;82_%%)V>a##CCn&}IsX1ce- zvYOY5_*Eopcq`0`PUz^C9N-cm2|_;?KXaN+7g#?~Ykpk;-FO|Ab=&y&FbuH$3T#4? zhn;PbVDWcRJx4(Xl_rc7B%pQQj1K3I(HeIpZ1UT-UH&9XJEY-+cxWpoTc5-XF4-1t8uoA}~N^)dRgL5$h1PNP9%|_%n zpRwvuwXzPxrk^c_lUArW#18!R*#OLeq(^`!LVY+{QLnVJmBUp>A4fzRJoT-(24YOa zq<=m?`1Z8)(-)^2>3+HpJWh#=2r_5GolsJ#($#x;IA;D-F@eUHrcd8E`_hj($cF4% zcEPwEUWemHZDGpvpc)p)cXLCA*d*93PwQQw4a3a>$+mCH&_XhV_TWU+skVlwl{a$2 zhxfxZW0($+s&Ci;lY6muX7_4@#e)mOO}q{F0P}m28oZpXoeN9VCc$*`Q%_<~p_d`E zz#yTk6m(-_*F-B?JfcQkfnuUNDKqe!QriA=|CQp~E{%*|U6Ve4*QYL1+wiS1%MYYU zRQ@C~a@=dhULDJ;3MSQ`_jI&(Cz<}qQP!P!hRcK={$lY}wCRiSRih6?aUu{LH`)p3 zW9}zNhwcmyhfLi0788dzI6LB+cgR%RDMKi9Ibm9U+$lVI#uzpxN0*35NraR>)H4!$sJrf)$>#JDI?+-t$MmRSUEU~VQmxA-aaXnWxY?s~KeOgVvx@1K2?CRkPf zFv$_f)Jj3EVR_q-8<;tG%%dV{(wrN2+(NiF_aO$YxC6Z?*33SdWn}0gb|9wI1Uh(X`z~Cg!yh~5A=C|8kXT{$wOVFQ*5A~LImWpbnYzumfs0HUKBHX)} zF$hr!hfh?_STF9d${YUkKFOiLrg=jbFa+F_^YOMddULCI5d~-#nMMJXz%=W=um0~4IS-%>p5x?~+-lHl1W9@-v52v-D zu9`+j19u1wwA&K$;?AXiGmrkW_BYR=*<7OI2+dC22>t{@2+$WT?Fj0OSHd8@^KfTf zOK%T%vVh*aIhy0?e@DCY7f?l79$DTAwID^i4g(9<)t$voic2!HxK+11-umgW{t6s;EPeq{8?8`lTC zC!R~}v=7`(uajeqOIX~p!O%bZ9&a16l3>)`QeoTbw>0VvbO^s1r`-0`&+AR{|3@+e z#c`XILjn>jsqXlXPwe-ap5%7mX2HhdmqIvH&QrFs6=yZtBg0bcq5QcX<=<=yE5@;yU%<7 zvs(V;=A7Meq|Nz-Ps-N~6P(B0%QlAyIUKhz9ZH;T-4qoRJ<8f^7HPCPVG%#lYjP~eh1m@xN zt}Y4mzv42TcKgk1I^cO0THQ{lt`PY5J>$+OQl6dbHZG)TAs10J3?fU&CvL?CzEH%Mb+4hrfVh>dlOmfD6 ztqNaB^e34rh1dr;LJ0;2UXAL+blYO1iLb$m+$XuS@cYXNJCmaQ+8jVLFhpRBQ3#t` z5$ZKp4E(lz;A~^txYkA(_4;Q5K>w^sy`KH z9@$#2<*Pm&7~$&9fEGHK&XLv18hJZgEdeIa7tUApIx(UM(-p#PCFOYdi0 zw;M*AR9G*4W6Wlh^qv96`D2<8C2uHtWPtgr#+siTy>iM^atSIihIo8qBurz_&r}Rq z^S|+VP!r zI(Bgwwt^-7$Efbh6syJ;6W?)T=?6P6U#NUHuH5aWix8qk`G(J%pdEgdT=hFQ-;ucc zP6~kzRU%I0UnB3X;b)FYB>pvZ;PS;eo=J}AXXI}|<%Ua9+_fc38gR*>t5FlEh4*fS z((rzBIj@2to&{Cu((Amy%#nVqZoloPG)WSynBjWMeD!btk@U~r*Zf*44dn&Fm2i=) z-F;qa1N--Wxukc47v3|EMr>eRmy~twu`-K>PU>KE5q^#IANDM}co-|}5-!TtH8_N@6-woe9g*k~1_=~)Y#QG$OhYYuBC;>;YQXT%pL90x6D-zR4 z{)GE{A4Evh6gQ zzYK&Eg8wuM7&BD8gbf>f?yrl;0G*^o%k<5~oR}ML_~*RyQDx9&K%0D#=Lh<6)lMSK z@)dl4Lp1b-_?OAsR=q2&Z`1nvD%&ZE#r-OY?uZ}$WBN&4e|TiddRxz3M3gG83cgDn zbl}+u5{+G}VXh|e6>#0>;C8;yRURi6qxGo2j3#ANE&l(wddsM`!fp!}ch}(V4#g=H z*W!iZ65Op2q_`8@y+A3@;$B>XTMI=C0gAM^Q>=IMefOMu#@+wO*dru6$$sa0=3MLL z>$K_qMlj@?q4o-@P`XdO`VqLK3YVFvc@@MX6JdtnE;SFLB1-JNPg+RHkdZ+=+VdUb zs^Gmu1OuBuU5sxrE^|e`N=TXx`kK8g-7^SFvCl9A*aR+INXl7sbssB~!+1 z7Nm~kq+obwVJRrUpib0A1D*?*lON!U>(yg0`r=F};RJk4&pH;p$LG{yLmhBmDPR2; z``CjU-_vX%LNw3Rtsj8PN?j+{*`>zf=(xY#^%H(W6p}J$w4u}OWa+()At<~}U4 zybfe7?d+(@KRwR!A($&UaQ$oR&x3BGs~;Salk$4cKL^9+jV8zK#I;UY<*vuLFv1s= zzj=ImXJ%I2{U{h%JFt_aibiPPmE_Sw@jQ3oxu~-iv1aX-i%!SfTemVTYM6WGw}lPA zZ?7JtqGxFW)Jlo%Cr|k&s+9Y*v0k0XxuiCXS(Z`c16e5`&+UYHcx~kLKi`kA8vxL45AJ?v?!&lw&I4)6w)@wauDDB`VSFi^=u{{Ia2(1h81wK z?S~kGP(-Kkk+2*iMrN^A+seLZn?n#e$J(P{2r5_t^8wCz$Iyzv2OntFC33QXN45Hj zZ2aA84LmLXKQ*u{uqkW}5I#bK_ohd3x&Oz0F#;z(rv$}Pzq9ZPwyVfW>5^2V9anRn z7L#^nfqJ$jgrpfg5n%zu#ij-$A#eUj+sh{aC(<;mQit?ZPmAc6CLwQn96W*Ipkn1T zWjCglrz0SD*2tSyWErLEi>(mfLpa;n)>3~(NG#R=qRV6Mw^cWmK~vBfpo%`=G*(aO zL7r5@DhODO`k^ysoTLx9gC+e=P{r5pewh9acs7|E*~$rG{(o5ywJ>R-g-@pel=b|% zm;TDPbU@C76Zdzn#@`Qf{TxxhBU1`>+chy@%T8I+WS#1p;s)2oTCX%YsFi(epf##l zKg$scz)nl+kP=e--2f=S36M*Gnp681PJ|Fj1w{dx1~S3Jk0E&wJ|ey(I>1n#f&(Q*lSp$H9|C<` zSO+V@xKR8|283T{uY3p6ZSLI0<=@{AvujuC*twYcxqt9V@v~n4zMJRO<&&)$^)J#K!g)m&QF0 zR4Mb>s}O2?~IoY;!9;wq4nCW{7py~8I0|Zeg7Vq^T8`!KU=}@ z;F_b*A23+UfRjO|sxvT3FICI7L>|YCTPK2(TV~?OU;i!Chg|O4>j4j+a>T{*Q2249 zwynDSH$*SAIDFYIaRkFwX_D~0LIpVtBDHs<`cw>|M%sNTvaJ@D7f*0?B-}-+KAM5? z_mvaWZXr9^ER*|WJ{-*KeuPi{AJk_vu~<4VN?=)`ew#w9>rBLNY{m$J@fRZNv%^1N z>3Aqv(Idvl5$I*hwng=e#i{9H<4=z=n5vp0cBf@9@H-S!3;EvDSN(aB%6>V+F`SSe zHR`&jxUSF-rQ~y(1jT@~QV8_(b?76-@mfATG7vuedTH_0$H%vRdUS(h2z);obX8$x z_EX((?|(rvRHt3|V9t`462DG1pd0?4z5NEnA-jomh&-_(_AalbTq(d`CcYW04gc6} zTfKfi?E?bx68NDmdfkOG^EWum->Di^@LA#FYDubsjjT>I8fmF#vVGbSm0sE@02bdG zs~BnHRuaKgok3h5ke(~4@1>cF=+Zq)(sfnlNbB)gXGTs>v-sr*k*^cW8NQ1W-UOCtL*Ja z+Zm@==o`hPOg=i5V3DGKj1!ie6&hq*K+4OExQ$!>U{(6pKhv(W&rg;ipK1ebY+H}HoglID%qtwa1 zB>tC4Uw=s7nlhm$u=qK9*+-{Oo=FVF^{M{urHFJcXKY3dPFiBWjiOH8q3#8J-}c9o z|90Y)<^2*VgCdq9^3keFrr*F)2)3Kn1*6WF+$8th00H+PpWK0K%u;3G9OGAPsG-TFn7iJ`!PXmDjICm zHx=LWBhnCNh?6*aTj}i{TH>Z4!7s1aq-0h`^#8jJ?X%iymshmu7OCL_&mWo8rf^`0)fZwSjhdu&D&QmtaP>okl&sWwnyEuEeWuv`SRg`V+)) z%vm=WufK#qD-qi6$g;(6rCuAcFi0(DnH}wC1-yp`g+T{Y!a>+)+6O`IZg>8k5ZG45NKzv#n!{t`fh7ODrTyyIGT13^p7K01!8#rJi25ng53ir)T$^I+*orVpm+m8aF38^G;NV%m-rr z@&`HzpJ`Q{KiK!$K{Ii&_eK-YvqJV4vO-VG(0gVwppPd#v-ZHl8X)Vo<~WFvg>N*X z%^9Meaf=Y+_TbAhT8b$0Z5*sBZELAl0slB6yR#HXtka?jx}`27gYlS4EA1R~ulkoX zIa0K$PWvknlMtUm&r~S?P$RvOcU@(PC$k|wLTL1;<9y#eWs0$USvsYri>aK?H!PPu z#%d~OB2cWU_mRf}C)vFxqZNcg^c*X&IpOY6-xg#TB@O*a!P;Sp@$RZf!{B!hi2bNc zJtSX%c7w{-h4(OhaHt!JL6#MnxVyqKI-MywCk5?b50hbK`#oi|ONvlgw7zx;eGWV7 zoZUWdY3OX-2atM0 z^qZ#9co#l*1cE&NzMb@6Mv;F04)3tZ@&EW@b{VRh&wrxWCe(phnv6tIK=k?B=^r^t zCs)Yl$x1av0#rHv4xv#dtg3m&Is$VuOHlu11Y8yDhx!L|PI#Wp5+Wl|W>PANn{iw! zYTBk=I!H}BXIrlxP42_!`*qf$T)xQHcF7DY?3f(%lbGx$8@mKVIs(29sMG$~X=m z7r_r-@Jl|fnM^I2-Bk+)QMT7r%g0ry@TbPBso%2njRjcp&L(9_>6i9q7-6(QVe zf}9GRV@tl5p7z0~&NKG>(~4clV(8=H4>w_O7IZ%@mjri_WRJtN9EFpwisG0IAjdBs zriKiJR%~1pn-PIm_eXCm8b2+v^_bhluUEn3p8)mmR|8jqysouPnfJYNcszzJe_Yty z(31un96mR7s@35#pCN!$el^4lF*Uzz>{EychpK+u^Y)@v96$*Z&xuXV*749T#KJv~ zglnpotK?n=@e_L;++$QKk?tVj6Q7q9YNtU^DB?B=<4|*TbV}Lxy_B*Cg4-u3Xx6`n zfwLpb`ZW1`#b-1pW_PW!hfX|wv_G!G6%isfcBCXFu_sGM%k8?*A*iPqFvHHyTi8+d zvUjGj%;4r9VamF~lI}d4Do#6jlOOS7T*NH5v%6ETEOIsIbSP7fvE`_QsbkcS7Q+o4 z%04kxsJ>K;1@oA)lzxNxri6dqYyY124kE$7H!Hpzdb&hBE1( zlxy!d<_y>T>Az*k3y9>GJ9C-dtK;sO3~$YF93pxgPDXuMCittC=2x2G&8?KH@eV3- zD4cC=-R3brzEu49yN-va7*+6Up;csUJqw9~U)WeS8foj5%`Ckth93Oaq&@!0-MY+= zfSGkn3Qe>|?}7Uu={@gjitEnB;G6qeznZJstM~e}n8p8M9r&7~fbCAqI6M_Zu6LX= zGCUM2S=j-mq(D{bK*k~@3nEV1&_1L2)KOoyx*WMyCU4aFbD-TsN+kZA#M;$pi1N-R z&nEwO6!RtKfC+YHhjn3b%K~eFS?g3AIkoEr>0Myaoo7C5Brz@7vovM8KSx1Pc6Sr= zqW<%`9frG7kf2SNM<;ZuK_lWl-?O~# z!$=%8S$K_VlE}oUW=w3l7NAYw4SS(2nJ_xB?fb7Uz#HvBElJgVF2wdo_L$Qz#L{My zjnLOzVIjGmHv)>mKLTqP@=UhmixUhhzYL2_iJS9?(VRKKg(Dku8EA)ZF;9v6wQz!i z)(Wd<_HIRD{!YC4Q`A3EdB*8pur*W#svCf0{t4fB-8T~kOdPzB4mvq#*vor+S#Xro zYpUue+SGN1by2`AHVn6clSU#0DudcWG*0V@@xfA&XZ21}Yof`xf3Mitz)xN+?|cO( z#FGfA?X9z*z}6B(A2CLBioavjlP=LOAxPQDerg~b0h_ykXf3^qNc|j|;AGwNSkxy{ zO&-+AVzgqZ^k9k9yRJpSQ!ZdD%&WdKqU1dL_bafn#bRd@zgr~n|8oS6hPUJu>9?bu z;X!9`@MiOGUf&c>7#@s%-YZ10f{FK~^e4uK_$r?k+EpX>xMXTxz}N^baDRLRkh#q- zl~xB~IwWaVSnr}5cLC?)S_JTkYfgtT}NkzpGuf_%&W|#>T7@ zUUuD&)Hkgh{Kz%}-;CW~btx|#gBvpiJhUsnO z(+X$@4}4jP7k!TD^L(KKwN8vlY56Y3N$kLrA~P;fA&e3{VYn6C9Bv*L_$7(%y?0XL zp;wuB3{HZENM4Q2pa*dM^;3| z!r(Z#9rcNYZ>^GU|C~q7B!RKj&*A=+-}Wjrsb^)ONcd1OKqasAbsUfac ztoY>};nqngo{)5hPmTVrZ-cJLiqfM-aLKC&u^dMd$&>bH%@Es4|Px>Q{vQUWgp3MAHD_s&{b))<=aT9{%~XGE`Gtra z>;7#0EbX{uU`}`HojR(8b3uhVcUdV=d-a;$~O2g--I$t`>%*m7r3 z30Mk`E&WXYiXE9}7o_zig9q~-G-#Ev-NGvX>KA$)Eu@tzhg0_2(;!>E86ghG{S1=A zo>N8@{sLvrHidn(Kmx&DNwrisIGQIMs1h7)Em-IoGK>T$Opz#Z$n7>E%Qt$;f9eykQn zy{4{(-*dytgt3{|rQ6>#HouHqYR+@GNTSf8|CTjIOMMnn&0F8c8c8PPdwG}65N!TN zh|@fShkBKXh)FDZQV7Fk7=j0x9<*aaW4+c{lOeumJ1SX%b#YLL^Weg%(s`9nS~mgi6}y_b<6(; zQBi9Ko2^tWJr77g$7j~q+eds~&=VR1F7)h@gR5-Yr|xi{{I(Z7hG+NQCno=cth<E2TI!K_udeK$WoLzW z$k!E#&c6k5|ImWGJyLG8GG~uy;-p$rA^N{{!)POJ6qfssII7uEDAaUH)nPBZNq+tI zC^boPJom}hNpTQT&iBW{IxkC$3x}3QdTYnJN)`-qG#|NG*lP2!BT)~aFO$pG)5m2H z{3+V1+EQWRd0?lAXpF#7^K8j~RTJ_bSM!E4^^)2t9XX6?o zuZ<9^ZL({2_3`(JdV-O~a3E;gfoRU%dz}-zEAq>FjSU5ddm18G?>5<8*qXh?)DNtT z6W=FS;}ZYV&Q1{-mF1V1Vjl(bQr%#V95lC&wX&Zhl%?Oj3#nTb^E7$Gk@Pe2t^rFd zPGI7fqtbA=Fl*v@0+K9I`W3mZeU6mnJdPcEEaM7G$0RE=ZCT%kp-S%zOeCJtQ9kUf zb1c_i(;8&fNo0;xjvL3jS|_-P+eXBUDecK9xJ391KzF?|T4@TR!kf?7FRk-CDciPn zB4(MeW*dvChHF-#UlGwFJSTDaoJc^rQ3mKdwL`HArJOa6h@>wUs(EYtlhmjy7&RHO ziAhE*nbCwPwA7?rlY)o5@uHcru+lyfm68m<;6cIE?UyV5Tse#HmN-B_!1I|d+lWpa zb2y}5kvH8=E}kT0NeApB_u%#fk;}JyIz=`1R`_wTHUi3Jk_Hn*H;bv zmK-&pc+qZBue5bt!f@QPX=dQ)>t7*=?Y^L)_cm}haTx$1hX z+z}q2;O9i0ki3<7gK82Z2;BYW{Xrwfk} z@J+viwO%wmh@-P%|MiA_rACG`Ty3kHht*$_tq;N?}jB`vK_rrwuvQzh1!VKb` z<%7jg@zvE5AD)jmS>3$*=&kYx8B%g{nZ@9DA13N6sJqfbyuHlnt?8#+27c|g5mn0+ z_UWN*WZ(7(^@JQz|JV`j&7UdF%uDtZ=C_8~sso8~KpT@|pLDB^WT>sNoT+qH>`h!$ zuT7qFn^*CTLE3J*ID1pqsL5)6pc58fpTa)99ebA8*Qw8<6}N-^TW&yyh7WAG#SBzP zhDsjJ>peM2D_N$Omtw48zxP~GWesRmVwHq_eTUi zW0kQ8HgQ$CwG$J7_MiHv?hSYIKsr;en%RI&zk@V`rnjT*W^vdcRI&6|uGjVnHGt@g#S@>)nNK2{ z3dzy;U)HxkX?Do0MV)?G8>M$Ha9`MTYG7tr)Qb))^gL_vK8)e}bzsX-u!`=X$r>w; z&AL9wzw3A?mhsLHN-Q@cD64q;l_7G*K5QX=bD|TYr3j;WT{h?H+G+~HqC2Gq{l2S$ zUHdM?t~u>|x{BU6NFY^R5RaCu`i=9d3Wh6<<1lGuOshzAXMh$*Jkr1h^!NGMdTZIw zKaGV7xlnZeeO*(y^XwMbhGei}WbP^~aiw zF)G$M&GAU{bgL29veUmd{h@L6{p?05h0U;lnh1i%HHc<54+c-`DCCE3D@M_^b(1<| zV5rHsGzMMxX)5j|3>^s$p2`l>;^d~PN9@Xz~Qf7vQ;`LUlGJI0# z?;cCYRjopFBtuzHGDQA|3#HS#g+r@0w2L0&1GPFo3>}^mZ`Z z+e>1m0#ryL{st8bRoq;$#GO5<|6LR%T`c2w=dclhrw2KoK`@u`f=+N~RPAOrc@JGsIBPSmT>@6g^aVjrMam)(NDPuQ&)g(~}|G{pz)^l<|bS1{h6Afap);cvFi5bV~<#O!@--w5r%5!H=G zD^cE$K@%_`fyokteB^K}QAy1pQGSz@R^H4Ww|dv zs$B7Bn*eCth@U~l(oK2)c0WDxJ>h+0!!d!e5LZjd`2e<2 z07_vIeX$Mr&)7EP8c-YK6GPRxyWTtV0f6Tmy;PsPmH+V5vSvs)LVhhL0rMJ)+O}UF zx4nqEm+MLB(F}JK>T$1Ujmlh{YDk>o-RmEJ*irlB=NS(Lme%X9DE>#W{WP(w-JbdG zo2{moP3|`L9iD}hFqZ+bUHYvGueF5sMGBc5Coq*>F2G;%)`z)tb6h=~a1LcA;G?&E zS|BNS;=9}>n*(}$&8RDi7(v6eYKoo6?*-fX_!Z)wpWzEAjzTuFx3X$i2rvm2srth< z$faem-j(&oGulu6j-M02S|!paHgay3((yXf2NS1o(Y+;=3$LXF$Mm|HW8wC0r+;*@-$ zlO2f`JLgT$O7H(YXc`=%%oDc%A;uA(wEF^Ebu~@+R5nTr zcn%@vKt%HI%LpxGHq4&+6}gjzy_Hi$F64ShR8rEigE4MIR!)^w)hPuyZyZQbtx%)+l}0)QyyCE)HeQM)c; z0426N{r11s2M`PeS?#w#+*&kR6{(XRyQ0TNKxt6@uhJj}I7(G#zPq}qCG2Du>9*iK zqekS{Az%g+qBt+WYksaATEEU>KfV)W0DZn`m;8IK|Ms%s)L?4p!X1rI=qw2suM{}N zOWaq^G9Nb+v;38|@Q1zMf*~vC%-u0@h7Hvz(px&!UP5UO>S#pJ#ErsFJec*<_ZyY~ zVb5Z?gQ&7Pj;eDQL6(T>=e|>g{i3MihEs2{Llzx*oLuY;%rGg#j^jX~?J1@{XkV;~ZvE<<5W&mm zl~mS%X*AO2mvjR7Pc^b9Od5g1MwAQ!R%NOI)7$&?sF3KzYiVi=Bb1AtX}UVXh$mFi z2tis8C^jeFH&CBMl1_qGiVivx(KhG}MOiwT7C~FLkPe9pQ;~|r_-X%(7_ea)pZDaF zUcVu$3;gf5cum%jfi;*YYy4VQxcfn(07m)eUad{YCkci)XNu|AtqF+B7W@H(QXAY^Xv}}Ir14T z!fZmx4$!-x(qM`RUTm!B__#dllv>#YBb*D|lChsy7xR(~KQ3^G>Q`aj{45205#cpx z$bIR+&@6%eGR1}l<4ya{PQE6~non%t0tZ;!dd?0U!j~jG(hzIpS!}J zS2Jc>?52P(=(y9HfX)R6t@s6u359UZQ#;#}a3E9ES_;i&s7V!u#s;*iH=v5V_b@wNu?P@U2qhje3egc7Qj33Tkb zT{L6bDTKX^8NQg5Z}Yc%>)`Dh$S&qE;*ie9U`m&erOmIUGe8)rkH^}>9gI)TPWJ|L z%94?g)=1?k8^;O~IjI6p3B(SzBw=FH_)eLHZI#2;{3k92Aeh z^cuy1?#rdDHNkNeX*QQd?zdllms??xh?Qq~w8j}uTu|=awk){^;cZ(>SrqQ^UdD84&g)Y^BXfpCu*Dh6->r1*zO@uXY9!Xzv>+Ad=4Mvt#3?I`3zNk^Xp2IVNKNfj?F>O0 zifD5_-ciYX%(N$$uN%C279HL21DZ>uoafmNXF-e6>E$&PP}&0R*AIwiUiGgKUbW`9 z5?{8|g=Z)!RV7G_v&V}MwD)NT4GMn2X6#;aa+BL9hIu2}Lq$|%xR39{`wGAcr8HV8 zOlbW~NtTFmB%bid8|ysv%79c*v(Zv;XQYs_Z0S^E!w34`>{haz6j2<6)bk~%Dz@IoVdx>6HWyHhYuiLX2enqI`K9o*av{Do`0m3qQ1K|&A5@UT$N zE3B(O@=U*4rjHc02a_y6BH*CCPubOgvQ%w?(od(Oyu~}o3I6%Xp>2K8ASqG9sSK@4 z)H#mrz5laXtt0l#2b$Egf|Q%SWw;~SBhmfNAIv`Y*nMf=Z`{I4I*ra7HvkogbI-pu z-jKT2X_{ygHElGeVL1!zyASoo{I=pAptbSt!o|#6UG!@ID0B6c)!d$A4-Cw5h~wA1 z*Ap^8{(^?q&U12q6rM8`zQ+S{XRv9ac7*{O&-dNn{J_KUGVGzdDMWQ%Fa~YoK%0Jv z5qq+F2$t}46W;R0Nltkh>TVVVnU9Crj`_V%FIxP#C5)$eb4nRuNN^WX7LJZ{j2_JB zDMK18wXnEEjm6#dMu=zUjaR{+XTK^R&eVx}`Ogw^U8SBaIo~UZ|KnE0h&)>kJ)<(1(*o^Yj>%?= zhk`WmlNPlfza-FFVtO#hM*by*uOKhGpO}3ah!#x1m6m_obhnXpy_AUl=L)gb^o!$; z;09XoAbbn?@h(t~cWhLg*{EHKO=p{WD1Rykof;d5YK`N6aG7-2FSyN|+SJG`r*$87 zHcugV!__y}+yw}v0x)6y0%oUG`WyI9FhRe3f%Z$J>8Y7jWGxrd$62V4N2vFC-y)#( z-tTOY{&C{)Y*)|SBqhtXOVDEAm2-U?G~Sw^<)z+(Wd*tN@cY#eIHl|hn5m16Z=Zv5)23}~b} z;Qe4@iZ<9G6oaULaq0O_g2!HRellrKI~9Lv1p}Ch_VwS1g&zyU3w`%CL0?aaq#^vM zOGg}EnYR@cfNQvnsP3j4XbiUynD&B2ElxMki99<`*@|B-z2fTf&&VhY+p=yizRa|2 z+GRTnK7SEkKk!&f!*CUE`xbYXz5|fP=54!L1=WM3c2>K?vT0!DvhDcWc4NcbTbE(6 zKl$D+Ha9a%!U+bBxY|bt4PWm|AP4{yGp8_YY4&)~7dQ8VZDro2LEG^0&d;k_D?;|GiqBnaWC4H7?&&^J$1!gOd)&e=jbof+F z#2 z>I8I3W|T@?)!JB^5q`#MiW?W~ zE0DYwqm|I`v1Dl0m8Qk!#X@<(@DX7yT&J17n4PGHC~Vl-OmEi^TNk_kikK+=w!4~u z%v7Xu^fXd&fph@rK|qQre4g5tco1!{F^*tPHG$1?q}aA!phG5NGJmZ0BWdD5)R-EV zDM_f+QXSTuHTO)>ff8B5Kn7OfKAt6CY&zxAiaIjF!nEyN6Auin^$c4J? z=RK{mRM=Uw<)}jMP(2s_pO;=#N?ho!N9yi+;=SXx zJn5!uX4faf%}lr>7ZnBh`u$l zbrb2*q4IJwo0Td6pj-4eBPk0UiipFA1vFoX>3CQVKAoKji;gypQRGWW*=>3Dvl7wf zU&$B!s%f`K^mf_GVet&_$BaCU-hN#`?~HM;O+cmSsO6hTM<4Vf9lwH19+Zp)4ko&A_StIO9e&%e+=46w{xV$N}6KB1#c_g@g zWjw!?xvHp1^^+=00b!O6M>hJb0N#+Jd+!Q>Tt|u!kNf8jZ zBT_JRl5@7#=h8nFu4TFiz7g(pLC<^sX%nBMdJ0$_f1AOnt>|mRi-y;ZHP2+u?kJ2= zo1JSA`{dY1Q`1c69KWR5br724%wa7X9$3-`_AW{p%w-?{^9@hYzgSL1ia>4)--pRe zfM7kU%P*IK&t?F-E6O7TU!Qg5yfj|Gji0rQb6-?P(=tI6_KPCxj9YHHp%0N(#+TMGTKhs%zE<)32(~KxF{%~2io6xbrc;QIP+4n~Zq=i+koB4x?E`HaN zCOZ=S5@A&bp=9+k__sJ-R2>cH47t~_{9r2nv6cJjRCZzwNXL{%!_#=< zmuR52@8l7_d(ty3u8V(uqsaf=y*xbz11{ z*a`3c^2V#bRCRC<)annPXE-aV%ax;+Cz>9(jgj{uh$Q>TI{D#sDMGWQq)YlCmLi1? zM$Tj~IZR!QGpUMH$&hKZapvf zHRi)ENx60@nIb1DaLNKA*w=WLpI3BD;Hz2U2+f~uQE~AY z#*1vO-^af~#%^;g6Sa&|5`NtjJ%>v;yT}_r5EhTNA>o>uhYS5~`=H-WG<#AfgKt$p z7xyI;?|E3Vv=(mWU7iy?j9tT0dlNa%9$5T14>6XRuwoqL_U1n>jM);=3DZ!Ny= zdLz5*Ma}PYDv$3>yd5}_(JqPq@KZ)%?9V}16Zd7^4691LbDx&LaY{S3=VBu*?et<7 z&D*W^GslkwN!!A#=C}p2AS$v`bts+c+R4zP^yZT-`O@xgmIS&rf>oHs1&jl&f)J*v z$y8uL06U@UgY*q)y{zWa|NC2*d^zhAsf2wtAVXTGc{N2m8^txVAmwlpY}Y{z+D=l4 zO8qpP0UBeP_|BIkdDr`g*L9>u$_LjyrGiL%R*x4j%=weDWG0dPhV_IiyrRCSz>>g# ze?s<7v#VTff2XKTYP_ts#Ks2W(D<0v{smHOJ_$sMTO}j*Iy|J^4$l%KYqtFT^M6EA zpfZVA5an&kP|M$y4)QEiu6N-=(w6l({Pt%jdNco|Q*L7Z-~7q8U_VdRc~}qjQ3LYT zo#)HFg+4iW@6FYcA>O?63FcR3ro9x)GfJ9rPItlrd)VK|DCsgZ8ItPM_HGXpza7$l z{Zj)b!r!Id_x+9KV-c42ol+E8IrQpYdfTiPg7ZLn+S)^FvT%6LZCdru5oW;(qgb45 zKnG$WOR#SnPS8#qrjb>^1o_Et-bWU|D?-&VVTatHM+Ykw04qb0q&C`V!8aw`>Jqr;u}c& zOx%6ebkpnCyk65JrT-}kf&Sb>=FMv7={DSFy3s#ED(b8xzUghp-QQlKzw>DEKL1Lz z(=^@oOs!i9*3#!3*6Vf?Wc``1G!dLqjLb{8b|_`2adr3a8)?87Z&Ta?%dL>MxEamN z8OJfF!nF7h#3cUhtt!UrCDQ*DM@cLjI)296WE6EO)ZVq-eaG&;xn7@Gb%L)dUh$o# z5NDf7EbUnfI+APe0qgw z_&i4qH%AAp)+Yag*>=q(7Y$C5&w1W{`SEeG4rP)1pdtAr*;ORrKT$3S$?fS=(dj!N z2J?=!*?{QNSI+M?%~%}-N1&SNoFx3s38L>{55H_#>?B{gTfZ^%uZoCsH1f3)mih3y zp8_cJrIAu7Rl_N)3oN82nAnHtZ?cV{9rdpuh}LDI(p4F+RR=us1npR0Z>%a8^zvQk z1Ev#V{)@NT!bH_g8(eD5HUOoLWBS$L`wOD*A+|{3H}TU^a5zl6pBdW&o$?Rr$GCt{ zjUZyt;y5?{vd}05WoHa;eT>5ivS>*;0&0*lq1;XMpq?)XuV*9&bipv230dxS zgy&wt#WVY7m=N%ZXKiQALdp2>lK-t7DRxGnD2tY|&wT=Mx|cGuv(xI~t$2_S4s(C_ zMpZ+0JjEOvF0QdD_F};PNp8kg6Kq*Sz>x%y8HG0tkmkHGhF=uPVVOuuVU2`xZf8L5 znCro9R7zNOnR@2927<)OM<||=3vFg}W*Yv>o}Ou7vsIu`UtiJRV#Pag{E<{(t&3r{ zF{JHVJQ8@>)1!V(6!5NB-gAw7foV{Th;56Vqi!1 z)#_y8{ukH@kAAG!RTHw5dpN=vvW@=o#P{?2b#Fkg<8{0?9m`)4&RiCvEyjqe3oUyF z`kTT+qXK%kwVW_jNVYtGxWO(p;3)KGP>TGp*L}pSv?C46K!3<5r%blG;t{<-Z#S(- z=Ual$0u1CB3{)d}__s$f?8LE%RIyjPZ!MzHd&NhTo?$ES(=VqCm+-CcHd1Jap%9L< zQs60)q=~%yszd;iI!r{TmVyu8rJbeMO*K@I*UVd32f1i%RP=u*3hDBx?Jh8ClKvkF zH4}_n{CKb`)AE$jRL2id#i3j;b8ezYR;Nb(Kwwz_dU)kQw`E0vZ!*sG{$eRKx3=9# z$O+Z%lgH)IS-a~8jqL_=)K-G&x+|=`wcSGqpoS)<_u>wNOqzAu5NEEYS~k{0B%NlK ziThz9jpZIw0UVNUbVm!+69C%wuCFaK>e9XFnsYu4fN!7{zx@H00m6NFVrgc+T<(_) zYgadzjJc#li}<*n>a?*^!9cHYNQuyFaX#@|zft-o0$WjnU|CMEM+8!? zwAf@O0SyxQ_P)TLm#lJuUXk>6?Tb=vMyda#KtufZ5&!k#?nV|EzrPPRqEsyAP^23P zED$iGCH4_h#?;X_W6X@3kziKSi6nr%ms=%MT&|>G@s}uF;iT&PZDZoU%B!=_*2ykH zU?l}cIdgGgb4U41ggkv3j)?tuD4T$UkGedl%_`o?u3o!P*-ob91kR9z&heB%H%@t} zR^P>4%OoHD8Z$Mj^Aga#gOEKNk~l^hqqdnIB9dVrtgF3=+)2uY z%JyF>PRJn)wwoc&{h?N*gY8}KcfY0fOF%E@p6@=>3gvI2*R%eY%vJts3Ob*l7W7*n zvOs|LMsrZpSH`oYGI#5iMQr%GWjQjEpCOjac9ubYm+d2~()%u7tzY@8 zO_?5=F%8Ot#3KS>gxKK~N|-Y#3R9FLV#BY3fY777G}MU5_GPVA=eiIuELe6v&1>m+ z-BiZQ%N&Q>yxf93D8Ym8_T@x?i)+)wiv^=D0xd~Ek}wQpt&eY(T{Y;1`@aX0fyYJ>rO-jsSa+Z}` z#vV)XIbbK5yF=a7Wlsh>Lt`UYQ5``Z(WYzTL8ii?9fW9DN5Bp39yqUD#7Z(>`v;Gg z47=@y6{x(2Hl5`O37~(}-zw=UPW#^kkoSIrL-`W|xQgONpJ@Fo@#1jVF8jB(9Y7I$ zSa>tfHp0MR?nuP|d9a|a6y!Fq*~qx%^uSR%@nm_rewBm>Jd&&ugm&v-k^KJYRrj&Y zvkj-0_6%;OJZobvaD&r5yepB`Shi&fZjbxu{dPn(EAX%lf775@pckb>HvUUuF0Fqx zW=edgYGVkv-(9f>l#*iGK7=SZ`Zfr#*#O__0yx3sUG&Ww%k3#(#jOG%W5BA7dIpkY zFtIf(YRz$-Dqz>{7%(*+wUx(5Igrx!;`L)ZPdE=5S%n*75n>UUi>Ea(na<0FV}5{f zvPb-~cL|y9KT_(t5b!T6c?t@MSReB|@lMqSwmSA+vv#+R&^mafdVdm2FgOs3l@XZv zs=l{e_@B_vNa>pnf_5~1=*`VkLp~r*#)t-8{~_J#0c|F48!voXsTiAREY9&->PBpFV|S1XaydiUP;jPo%GeiCN!ajQ_T>adeB+omh_Iirhf z>e*zck6qm_hBfk6@3ABIyA-ck`67!45A4fnP(Mw71^y3&&ZDnBndW;#ivpVHPZF*r zH+SByUCTRp+`uLFim0>Xepx$&j@LS@sBW-tTeVFn9&jB4v6*J4466zNT$_ug-Oe;ACxAUP*zXYaY@oNG;VXbQ1P)5~WCL5pOO5kj%H#ldnA z7X>@rK@k_htt2&O%&rer1L4&=T!9c=`1F^oU#kD}&!b%t5MD$CTWU?({dXH1RsfD6 zX(R@`q5H5f8M%Pcfbb1JL0d#=Aoc@LyYoNE#;R+eH#mk(J&EHvOg+8n^z*ujQvY5)9sEMWoDrd7E;r6>rJbr$w5>y?R|71MU2k z^z1U@9Ti1}E95I_e+EVAur zTgbUJEKP+lVR(NySZXAGF<=G;O`M&D1Qt7G!0k4VRr_qJ_E{arGxnYO`rficQ0v-F zLlhAX!`5qT_8XEkvT=i-uOT)nQ0x1FC%-EqcYC}P4KeWAhLbh>Gvff|7cum)Lr{EG z*mjCSqFzO=Q2&M?k+KwY-cPT5KU@>Hgp3v=A73nQkrS%F+*c8DcqS|G&{NvOtb%H( z^krQK0(vzVC@?RM$uz6>aDiOhN0H4gzFZp6d8}UlqKg4xC=k@{fCkB`Xlx}pr@TlnanaKY-+y-ZoSF3M3*-nqgij!2*US}#hsG(!C!d}Joh4~i`f&i zhGNj9v+TGx97RNoyXh-~FjC2w8Wqawi@$`))G;o8$NEq6GrS9CXJO6ANtN$}ZL?{C z>5{$h(IZ^Q$nZx+>;~f-yx2M27g|?l1pfy9eKqwh8anXxOizod&K^n+(<~1%T=5xk z@ztn~ZCMiA*5G1e9NK0D&V9oreUXVk`{__(wIMT88cYFuMRr84G@=$o{9gAoHNj+y zqW`i_OvFYdwd274Oz;>bGU9^Da(@VRWvvEs18cT%`QjV--k8UXK;730Yr4!=o%)4x$ayOai)&p)kZ0#D`?83xOSz|4 z9KHZID?hYS;;7DbHZKg%*bRlKqc4so43l3x{vA4<`638&)@}EmBVO|$jz4kw zFPprJ|0nkpv}L*Sd(tV4`^H%(4V=WVw7Gs9kNUqYX2NwD=MD)zPGrLIzo}Z$Zq!z# zMF)Nc6tzq8-oZOupIf>Qx+Ul*G1)LR)$sHPga;)Qy_`EQ^O&qpt)P%{jD(Ct#?6$1 zw((!oqS`6!!Gq|LgAtER&D!ONgyhikj+2ukr;TQ#&YbZfe!~0E ztsFtdBhH~e^%=_lzQm^wgKv;3PcHDkgFL-) zT!K-8(I3sm_V_XKxmNI-RWGy9e#c++2#BxV*590Z^jimYJfl7Fki7nX!wbH!ixr=uv@pEk*xwUB_V%t2!<%>MND`W%R@UaF ziOHoBAyFPGO5VClB>mV!A=2VMC4#99Rd~HQK#@@S#lK@?u@uz|vk*Gg>q+p>wmc%) zv;>K_`Cq3N4qhWBvD^wIUMSA@t~9maapXS(4pRL_+J_td>(H|8HPw8x9lQo(qY`K0 z|F3D!qIRUgKW1%%et~*ibem;pt#_gFPmX+-P#c*<|A3=wP4Fvjf!8NULH7zmp&pDv zCA_VjHCg|6<=9&@3t1z%@m_LmC;}G<3B2Y?nh+2Nt{?9y2KVVub9U2U1)t;jcBL@| zUPi1-=%h1w6Y^!PzQ1l79*Q8!^UA;J3j0s{+RelN_c2r>DA}KeVJn{ILgiqgG(O93 z9CpF01030t&1(*n&dUEOVA+fdef9S=*B~S)?&w&AosV=&UW?yX!;l;s1FQ%M%+#+J z#NK>EK8gt=r#e;*{iH+oWzqx0_n0yfTwW;*dj9B8Uq^)rA#g*?=MVMy2!ERIBk(9z zS}wG*9_wI`-QZ`CJsq--kNm~g`^I91-tee~0l~qP7dp4aQ6xmWwwX0pK}=I@)pNR6 z<{pD95y?nL(>~HKh+M_UUbPj-3l-Dl7mgF0WZXI0w#BAu)6x|v`_vCONM2MOw--K% z=lGkr`M3a#%yC5)ld;rfw&AQRBOFpB7%y~ou5LSlK?1JBRIKRX0RsR4#Kd+yMzBfu z#RsZ*U9`(sWsT^-oDZ9x>>#)SSB=p3Pfl=fAvfGFl8!0iw_c_WWr7Z4bI!AGH}L6L z&R#K;*FmE@(PV>FLg=S)NCN*Xa=@CbhgXgJmx7(|vzV9;!BGiJYz&4fHiJ(Zrh3HB z9>T6CWhQGIx)-L-EP~E*$7RsLk?6o$_EIKp=GnLC!YEZWVzcwM+pMrsJvsO0=DGQ% zxod-<~cWB@eC}_i3KbKz*uFfhzn;&^##g$kz@QzkFU~G9_Op^3U{s%aF|H`q|Y3FYO7H2 zAg9$Gh#^!uCAqaDp?-5>8C5E-HgJ`vOLmnbv>{`WTE?nfR|*zG?c|){nJUZ!%cm(Q zSLbhTMV+hh*lq6P$OnObymg>ryiFA7b+Z_KVGwLyN6>{Y8@`^!l( z?;BBJmUtQ@1#SvVLf10xDRi0PmI+@d(4YUL64+XL1$XbM!@QXgH2$LkOl3RD4B~e% z1@$xy3uz9D1|T640n!)hth!V|VmVWn%Jk5QUHUdVJX=F?{p_+F(fJ{(Q1(NT+Bh9L z2C+O4N7R~~CF<%;&-WY5m3P~e>UAwLr0YS7$k~uFgAj*2FL**D`3ASh1TyU+y`uRG_=DYB)e%7ts?%|+(#Gnu;RLC4>U<}#L2 zUff_5F=0<8uMD(I(f!K>g>wjh_h{+2{BZR_glzxEzW`k z5G~|2ejLYm!9qDKL&so0U7Vmp^g=BK0c4y;p{COLu!>Hynks(gJ_s41`jSc)W0*R2 zGWDd&pS=caxIO?f&^T0TeUvr#@i5^QmSAQV{7gJ4neKq0<08;o9%Z^aGHIF>?3t35 zbgE^UGyJ^Ey=IT*fe2}pl4cpQ;_n;`m0J5Mw{}su;u|PCb%vH0?t`TE7KDj^ZED_| zzN1LwLHBvLEtN16@s8?@a-K#`-_M~lhn2D^k+ygEF0^l!_6Z>=bKe0>4ac96yZ z8o@krAq;IFW(POn4=gH;E_R~%WlY*=o1qO^08N2n#Dgm#OVfT1=H2;_W!jOE=}ksN z12r3?9lelkkK`Y+9k>!z#;@PZwmw&RmCEo2kWyrqzX#cQ8YPW5jQ%=Rl7Zmx`=-{4 zMcymiZIO_0|L)!m`;odg|2OeOcJB%EfIH~d7G3i$oxZ5NJDHIE=P!_1>e-FH>d4m} z^32v$Zj_=l6T_;alJOu>vtC_#nh^r)%6wTu*&bLNIT3o1{!d;-zOb z#xuKqu>&NT0nccDP`}3p-WXU)S=-9%u$H=&a&8h}3fdM0dnni%U4;9{6Th1!-f2I4 z?7+U4)`F8~H_gqX8O)+Izb{p$1^qpudStkkSG`BU#J&hr_%TS&ny&We_b8`IBxdPk{w}HvV?07x88Apsi`X!H>DWZ;&-3@JuCqOIW)tCBvGU?}qo5q?e zG!~n%d~|W*KPp*)L)nIw(3NV7mZ*s!>DN`Hi4p71R;$C52j6C1-dc)T?R~%ex19Ku zdA{cfYUV{$Vz{zEYX}gJTZ*Te96g8>$M#yLrarhg!m!3USbLw+3>T#LZmtB8)boxXY3#P^_GGB8U8kcy2dJEcS@dDhBM9033 zlaDKnv%T(-Nj_JM@?C3#3KM~cg(axA*KyG1UYV}Bw7%@r;P76a|3!=Gkp$(JqL5Of zteNfmw96&q7{sg1zWnOs_NZ1F{!M4J#^+EMgzy ztEm6lfWQ}Iu;^V zN%wj~>xS4;*k9DS2KgTaub9rEI!d0-gtj^i2+?Z1<}LF0YISm9C)v{ApH%y;-hesH ze|_}s+G>t}#=p_?i%S`^dU!HmJ(-z8;LCDhjdwjE7dhr{WR#t^=S+j)it&jzz1mu* zVVy6+e#4g9s+JFNKEg`>s#AT2&w+fi7@>sc4+>&B6_k5X2q=XQC-mA z@uIJLAD3dUHotbAUb|!;N(}p8-n{H2Hu;!MD{Wv!>>7T_yv>Is!M5l4^|MB@!N>_P z#nZ54zOS+N>Gr6IQbLR5Tgu`|m|T&DeVjtTLUu$sJ`ji^6b5OWm>inw9NthDyFx7+V}h8Z=v6kPJV1OpjqgwblJB=DM#d? zkCKG>+j2G+%8iopQW-EPPQsoxUw;O!OZ~xi&`qFGV@4>nt--(9^4ZXvh{o|Yn>)~bX!F?XQoCMm zC60w@baLR^oJei zJwB2u(F9mUUs8ry$%=LRSqVZYn9Q&{1Z|^@xT~=}Yf2@(g)tG<@B)w$wWK5XA|w6e zIi)2Y&>N-2C<-mW1;}Zf5voP8CQc*TU6`t{wmmXTeD`?`kf3dSemKP)aX}17%+v`8 zSKx%=+G#xbG4_D)QK^;F^$a3!^sV20Lk_33MNFrL`;P2)GB&-!x3-8vj|m?lhNC0m1}sN^YuLw$sssy-(mOtE1sL#}09>!x zy)!Md&6D+pOCvqskJ)x`ey7en{78n{vlH!D=tLcQ`o4I`z|E7%8ACSJjP+|>20eat z*dWV=n#ji{+t0PnNc3QAH6K2ify3;MYe5hW?smyS5p&D5zTufiIXV?tx3Ef`3sb7D zd3Xky#+nkKLyC?em2|d)Y1k>Y_m429Wyazm?4(D4RcypRjV`~_YAd%sd>3z_dj8Db z^x2RoWAO+_{`QVR;IkY^ij@WnKtapKEa@sx z=(4n~NR}`{F%5-tb+OwgrnPp5*DKj3M)9fHQw6l_m@ZPtX!nDkQR1u01oFz~(T3}f zOC$rFt5^V#R%@h5oa8*m$Blb8Ah^`K8wvAP=7(Y^&LIK(-~7=~u%SI7J&*D0gP5%W ztEmTxJ6IRx-4PwN*)3o16B&*DrjyU8&Lx{G4|g6~a_d|c?=DOT1T=$`pf|Jnv>j%a z^RxQvtBY3at2&?Dor1s3D>Hihy?;ZG2q^biK73A(CwuX+X21J%^;-KUBCPUsP3R-w z*VoXqItTHquGzoyE8T5HRN`>v`*Sl7(4*#?^*^h|NB6V)jQ(exUvGQ=7ToPkjsB@P)dbzI=WHaXD=oWI-ju+P8urfY$#`tol;aA0! z(68di^v$Ev8 z^K&lvlG4;Hl@_g1sYp~vUHyHbqis+JzsIq0z;o%3bNrv3YF?pt+YX}b3ZF^oK_BDr z#Pp~aB-m&xg}oV?QXmC%Ze?Ip2vxM=hGp z<}cMx)%%%O328pZ^ci*X*>Me$Qe*a*<^(d`DraQ6<92j$S=TEsDNRy%@ToLE;`k;d zDs~3qORDdD!+fq9Mjjcs|3cb}c`a#NkPGyci$qp^#~bpFjsW*Z9DA{Kih8u5Bz~Ne z%6l3~3}<20po8e5dP4Q+>}PlILy>z zhc7sk)Yv9dt07TOPun9kuAxG3c$%7OAi>+HN6dtt zAq+|NKN@Y)Tu@5lpaUUBu#T4#9^GdqRX9{RJ5jfrY(9IAamaFc{s32`TXpd-o?+9n z_D73~ZLTwm8vTN@378qH7Sa!A`{aDr>=)KN=J(m8&9YfnZXth~zYW))#<)w&ZpwyAIhK1Bp0q-qb9takTsjG zIw|FQVNB9&QagOY#RxB=Ez1OgcKutg`5U8eDlH$P8YkMYz3MlfJD6t-o1?VgF*NM( zh%x;61zItj6LwtUz%%4>aj~r!h)EFLe%V78$qUkMn+h7;&`nUD@SolHf6WZM=bcmM z=117Vdyn6Cf4Za&3|-fT_W|U_SQAVL9ba`T>L*G%FipPp%=+O)x}`xa!i_#eyi8Z9 z0OA><;3)h(a+?qlUt=OSv@^w5{cbQ|oxcu!H7xFJ;g{F|q4X`Y-* zp{GRbio{M#2mfMKeLbZ?qa4M7Ph?m zh8MYCaE@BI54`&(@NPfg?ABhi=Tdo0FXw;QmQG`N-kHL_wxcVuF_tm=y737jgs3HM70M zRVa05L-{@5Hv;uoKw!b7z=tn)IPvLto5$}N}J$^f}d+DZ*1aa@vUpxY0qaFcz zCi2|4RCTPyz{t}N{$XtR^b**M%PQ1B!S^XwpN~W24*@K1sl!Qn4oCI`nK*|@I)&@$ zo@4G(G2`i^&;SIq{NU@U5_21bq}qSLYY|SO{lIff|GWuLT%8V(;zqk-gt`JiDZtu; zS@b|%HXkL50VkQ3%;UA%2UL{>b$~nhyJ;TI?L)D+E>!Sn@feIsxla6TcXSajZujK4 z94mg%hqpK48z}%vZ*&->EYYGOI|cCci2?|)M1;@}>`PJM^@s}CIFNt0-?X!~S=V%; z7X}m4%}Xw-pF--dZR@(Q}LZ3J}vz*WAGh5k}N6|zAxT5p32kpvfJZw374bF`~nx-V93 z^KX@RqGYu6aZu_q@(o_}%s`=3*j*QvH+B#?irDKAHnQNqL90Kb?w6<#rOzVw?A*Q| z#_LB=Q#l%Zs#ZxM1);e;-==1?Y|VP>_O3aCp6kF<;&_z~IXb0ZBm{r>Zfxo66GN9{ zD`0C$h-S3_v~q-XyX&7ka*dU_ujG*7Q*bh{bTKYGv;-8vA-$2k^AIM|G*#nf9Rpl=7i z2aBFW>gQ>gCXm*}_3p42w}q!aD>+4%QrfGh@J%>oHNfn-7xVyg2rIr&t5ZQ(=`V>;v(Jy;m1CpOH2yN?v z` za##+)+IMJ3)rO!4GlAgePd6%6&s2w7NeTalIG=OgzH>te$aT=6s6d=5AHPL?mB-0y z$;FDc`hjbaQ&PJUt@7otOGTr{J7e$za4|w1oknph?<7P>JLJ)nHXDD}x&fhOL8TPD z0t>u+m~Xhd?nyOW=yiC1G%0~WJ3~dCXO4=`@}i5=fA;zd=E;iT&JsO!Cv@o4MNJcK z2LY7G5(R5YW;qCs^cR^KR#yz2vn!)s;0ps3LDAc<7-v$$sBi42QkBL2+i*y-)yy%w zNRYw=m-EaY>O!op?Rw5F8#(zU<^mAkZqD+H0WR6nL2FZHjd#ELT}5=Zl@fh4NM>_C zJX<~5kBDSa26QUp5i3n;1-r`QZ3%PIRi(Mzm z?w+Ta9h+g5Sb{m@C-~i9hdLuZ_09;lsC7x?-I7N>K--3)jsi049lemueEO5s;JAuw zX>Y?~ug?=xGY3iL-brKm(}Ign0L{n(a3VDZuSy?*3zBdn=0OsIkP<$Ru0Bg`CoDeZ zz=>%Vp`LDGI0KBiBX1H18IGhn#(Hl|j9qw3z{Ye?e{jN1Py!0N0~u+rPOc7RUQElO ziduA-;uPE$)p0YxkJ;CjX!EX|ha~)%!k_Y218{JyN#I*?925Aofr;o)qow?~_&CNh zW2e3V?~!w0Ko?AgMqxLtc|rcj1`$!<{~11Yh& zjd{^uq5cwjQnx)E4G2E-59Y5mq*$xUR+g+)GFPV(n8OBPt~z_}7xJHu{c1b69|5+z zdu%)ho5!@h)j6AE5rYO#!Op%3txrV@D6=EWRJQf0^2jl}t^@?^Cz!Zs-D68Oit+bb zM*5MKN#5Xwo)k#(^<9bV<13Mt(Z-i> zKFICbz?b_1o0j=+> zNLmhG*{*%vk_xI=-jzB~nV;`X>Tx9K+L%J#;yU}vbFXQdFJp8(Y@x&ph)(4(%dpb& z6S3zIjJ2I4E3`GWgEu2)fX+P}()Uo2S|kxF_vw{063ne47rs6XZF@fqkKVlf)0~)L zr-li;5%RD=g@vigGccM8O?8`{2q$qQNFb6U*m}|@+X9wAopqz%@;sM47Dl`Zn|oe^ z7HZn&8EXA<2S-br{}3Y%Yx%XP@c=JzVi*XSH59(HYh|BvI6UYeY%dzsm~8m&QJs|4 zaPLm~4~zhOUnV!aHXQpmCQ-8T`)c)cY?zx4PVM&V(VIqmqG*sd{IT6qNs+D2id_pvg9qdKsjV%$^%0;>@`Niy2CA3%qWno#Acb?r zV6vU5C!a`x2_WE{10pOeLe%&OGTiS;oMVyU&+berBQgrmumvy@`j}LPfjK&y+YFAk zWU-c9cJf!lHmUJloYk=}x>aDQH(YMc=mA6E0s4DY=~!z-50jlUb87Jls=2eAAjm*P zN>5?v$s1mB^EMPzFVY3HF2rY~Rst|WNyx?uP3g*`$hBGT9p&x@u(uL6ZAm3=p;f|c z#qR-3JfuC=o7=d0xQ-~H9I+dghusO-A>&-&NBOkUO=>25&^_ix^Eo=%9QDBQrm!jw&gx+Xu8kkev>^n1c^lmQ=nw4=)K2x^ik**WE(8Sy?d-q?G_2XbZ*P+(C%6Jc4e&KB_WDQ~#`_*wIaJPj#fbRV2?VXs%Csh8^??Y^|G5%Tsp&_7@ zk1fyt1c}H(+RjASieg{NJEu<(r(G&cp*_i}4GyOb_aFRX}40dHs67K?*-nNhFW@j~Stq6VPO zLa|ZXxZ0zt&n}C;9<05PQ`XSu)O$kBb@NMJ1I(!SzYPYYtOJb1Tj|x^Um?pgq<(d@ zuO?E8*9$_YzG1vy^gB3H z?HFfOy~EEgD3jlg{JM7+6$6fbL-WcX2_WslMMX zT*quig)h=EKO`|%33lo`sqb;No7<&qs999 zd52>N{CLQxUu5^4brJ-kD~U+WOzDyY8B|ay9se%;!thq#_WEjWCVRptzn~rY&_)Y8 zoj}rW&<75*F}u7NI%X%B?D2NaKyD37Ec=K{rL{Tg(Dz#Gf6RoX+0A1h%77 z{mI_Le!(iqi)mjpilH=up#V`G5uwI?K}7JVKn%pe-e26D+J<^8`Ci*K zk7Zy`ym4wD@I?+hu_+$gnhPwWyU9BbLT;7f)fR=MLW%Pq$&FdImoqQj{zt9ZP25Xg zHF(o${94O#7Sy-Rib?qCC@6~ala&2f2KsrTUyP$LbK4}!U2^d{GvL~GPK@Cn6juNz%WeX)JW%wL}qVjg4GeVnKdmRmv=|>9-G!{ z_Pleai~-}p)ns0m{>6MlYDltA{T;HUp@W*yB9vf^{r-In626I_lmDk{7CEX{TU02H zY&{Qb-mntnPdBzCV|?d^hVyT^&JI*Y$fcj(oyt6%x4!z^hQx4|Km77(sy6ka+JPRv zgWn8icK$ z;p>@90vJv1{ElQd7#Yw^W=q6by73F_w;F>w?m9=XOvc{3pOC*?gE(#R|vX_do)j<>Z0IUQ9OJ? z4aVeBagsoQOy*U-H@?t7Q9hFgE4~6;lJM<$)la)sed-_1pJvi!0$A&B7>D~3sZ#yo z>nWxI61%f7#}P!v(pW!y-W;7$(GjkvR75W!AP+Ag>zbtu8l5EBK5WL;zXkQqc%a12 zZa>ol05h5Uxl|-=sl5wna7-2ljqujs^-CLs9&Pmlq=z^6BOKQjRIC77V{430X3ocW#&3X4`5J-+rRfakXwuGVYA`JN6E0l31YJ0fE&xKsgArkdsj zsSGps4BOjLx5@awr2*q%{xa(=hU=b?lZ$|BxZ=ZcBOO$Avwu6&FeTnEn3*{z+2}=2y1BIE;UwLVR3^c>D z!@$w_SEl#FhKD+svcF_K&Xty<=_g8sV0sBM^bUuE5Yt>P6}j8>%{n+_%G8N&gL>~U zDFORv9Bdv(LjEtdR3#Z&h4V8VlR*yO-8`46!sD5@vda|C|4Fb-?!m~)*Q&eFXDdE& z9H~Q)pd5!m8a}5N5@ zrta`rmbDHWYquG_CAYg*asJ<&vHfdiquz3f7&4eP;;alx5~!MPQp%GC+JfbK47>ZK`&%hc6PR~`|q>By5;h@Ii{8Y!qG;gb%z_EPoiF_wz^#HH6@bfq9p+>QT zDBsr_O6MG2J~5Fj-$-o#vA;Zqr#^i^T4=;EoMXlLsWC&BpDk_-U`mRCw|dKKTA*~h zSl3mFp`_cSk%V}@2N=K_?7ZQJLIry;6aR|)oqG~H z`IOnHNO~@FcCI193%4RKBD0}S)of;6S=ytwJPGz9E_WLxqcC>GWk!Rwv#l?{Fin5M zC%v!xXFq%bL`Mccyr?R1J?4T1!|5`t`}YG5ofO@&c~gU~laSdTeghsTKY{Dsi1OXb zlhiVkEKp4vEf&;B?76&KW026g2_v!k0jBV=q}RSrjJ5xhnxAsd$4)fJGox zBp%q)xlO!BKc>UH-6PL1j!|+Ny&Of(+HZe}pHs%E3nAO(l;#}U-bJwgc>1`Af7ZJ_ zVv=%%S&}m>-OuKZl$`gOL5>vIH?TPM=*}=&F~P1RB5qa&o2VP-`|uD}2Ei^qT1bZf z`!J&=c2q%Axv5U0>MFo@!rLEP5*3zmF_u^K=q4Jc9Ri=Vo+C- zNS8T=>J5GN6_G#Qk7v1v5vDPT1Cg|_1Ws(0G#hq0Qc4q|TEmhPY&@Xrh|R@tn$$A> zWyvYSSqnb#d)hDP=hK!%<=}@kG_r|$v%&`0yVQeZn`HGJx{G72n8j42p3sq_b&*lZ z{4?bD75V5aSjpT9+&H#vP{AgwQAk0(2crnkfFz1&(6}iU=DA%N0DMMV+rq?)zxA-1 zenx~*1=HU+s(tW?KG3+IL|^MI+{tScuSv9MNOE}1u~4K%y#}s)5vJFwZl@p-_(hj@ z;J6uB-ak$F<%8k^OE)Iy*^u-?hf>2aA`s~Csi*nB-vdT`5e+vHf1eC@WkCoS4cB{T$6*Q<||w9JS793yzqxlTtuFNM{yJqb#TUt zz&R%yOuqn82QbKeflqL}DDwS}R{9@#rpz<4czgyRx(N#PY4CD@$MKq$RoewmTVo<9 z9apC);kUu>OU`?d%-S8b+*UG@C8Mm_t)@Ejgo_IxeX4=r1#yV5DkO^~k4=52uoITZ zwnsBgjvOAdYER$Ep@XctYG^kYH6BU^egvM!Q6FC|s(4>shKRf}mYwRhIJrO`0Wb7P ziO{BMotp3F_@@$bFsen%s}hnT?~PiP&yX^xNdw*3KUI4gun!O+X~eYZe}9^bula!& zWs1g4_jcLkGXb6+OeW~oUM%N-h>XrdmA&Gt=@#xr+RjmCv{*z)IA#p+#x6agk?zPD z={}pd#2#!l8gINYLcaXRBCudP{;>LLmv?ta-*)%+ZSvSHx+mjzLw7+$2|G3R zlboJSLh{`PQq;71*=dfIkF+N2`#e;^rvjPiA>v#3 z8_oj`bV0;H;rygOjc?N&#UbMG(>5?A{FF;5C>BkEqDD84`W^C6dqZfy!h_U1y9o>G zOXt>t+p7Jw$FTg*1(t~VOTL; zfl!%+S-?q<6Z;o|OV@|$@PIkC&vgc)!~^7F*h=~Fi!2ncr8)5evHM~y@er}hf++yF zZLt$Eiyb5kH7QYOE1JpCa)5mtR)DWa#)@eUkX1tepuN@?%4h;2@l(OAtIN=#Q{&zx z#pv5_*C&22d5^X}%07-qM23N}Po=_2OV|T8fk)!7g~d_FR)#B}-cC@H0hwMZqE@Nh zJJRC(b_!gr>`Ogo$Lz2^kYJaT5(qa2- zEXID}D$btK74f8z=5-|u+!5B=0YFuG^h|WQfmCr#w#>eZA4;=A2GF1?rq?7*{(i~I zlSpfW+HSoGPQF(1h}y<$ZXIeADT^`UrdRLLZ(j!%oCpM}B-cE{_GNydsxbT8-tQ$8 z{D=KnwP+haYAUZ-Lp#>X!?p zMDYB}qpOt(T6#%<(78X6GQpTkmq4<2@yOSJ$#GPbF&!^VZ~_kOK_?(>>7l*696n|5 zFh29TtOr2jmz<=3JxtrEea5w9k(~toeOU7SgbCeX)cF?}2R5MaI5Hbe?&!^&xb1i;D<^jQN&7RkNG6#zB_u-5I zLyuPP99IbKEfW8#i)8Mr`aJX{UMi!#X1{smuyqt;x+a$v51poY#Dc$J-`J{WhRG$2 zeHzxE#Em$5C8J*K|CRCK zi^RRLGiUqz(4TSw|H%|?Lbo@_EA*m@RF@n&-T@WGYbG-f02xqavjm^#P@8utrtOR;ANdw*7L@Okj5&Hz~))1pK|YVXj!+6Ft*(!uFY zjKQbZf~te9tMN`lIT&t&P-l|vCy&cd`_|d{yFLGGMLr^wNuptJ^sQX!Tt>Pn?=>jb zKc|rM7AkeN5zMAQ)9EJQ#TElBXvAwO71*qK{jWwC@twV)eqI|ZMW92w8(`9|VPU7i z(j+p=qD3*A1N{hUo^&Fc#c{zd{!>uA2BX7QvoCvJGoNGJX%UZk#;4RKV1O!3#20AO z9;vW2bi44ZV+XMpfYY!3TDq_C9i7m3bq$zq1EPS5h|Pzp)UGe6j7-w|;woUc^D~`* zjjEY1t2UhJ_o6m02;TDZe3WBwwA)?I=B{k)LwZq?vI+tDmSqpqzKjrwgfgqH%5uZI zI2uxY4T-)pn)K^hE-JqG4zSeEf~La-q1k=E;`^ORyP&}IvmhMzmqEa1$^r_k>nAcH zll4Z0{0bhZU(R5l5HEOlUZ~$b-It}{#cht0)@s5JJW5@>9t8$sTE5>iK*(e`Q8ncD z&N`hk>#mP|BIS#T0m3k6{+S#8x=h$1BfNp=5g!d`j~C*oRP6R$piG5|*0AZjedGWj zR-L;mp6Q6+Ov36ymEN4E-{gZhZuCMIzE7z`=~n5vhk+ht>_rxiHyl{Xs;tc{_KW-~ z??9Y#M}p#yMaM3+VExL))va)6!L$;+beW}84cPhCXDW@&Tc8WRS7>TZm{$W6DGTto zdPba!R|nLL9PX2yVhgExF7XTV9yf01dLnwNEk@@|6n>emQcfpSs-AU48RLGU{f7_> zzoUyo4EpBBLWgqc4qecfO6uFsy<{H2!0ia^QT_^_p7_dvW3Isrj?VE-V^!piv$TJk z0wW@wOcp>ZGMRP}c-ih0m+`OAv4zV4*0NQi!eHmS9XWr~Ef(M!|Bgm|=GyZu(bIRK^BGgSyRoFAI+9|onM*McnpNvkIa;PaphCtcFLehsTD)%}a*dfpJnTADn?w0Hd^?jND zHA}SS7}<9Hu!i@2S)q$OpzR9{H7_~)wU2DyfzDjGF6K=Tje0lfaZP&;@`7e$3dG)m zq2izWt?xY(AXel0)T_SUY+oqK?`1O|@K?^*2E;_ff}r}```mAp8y?^N&l&cw{b8(k zx1u?3+lKEu*HBmH!s0)xJy^YO=!pt}vk?jh7CE2OJl4W8dwzWwNK&tBU1MqQMp|QT zq)qs8PLjkKeyv7EX(B~a@5ReP-@Gh=bHiS9ku^w;&LyfR<<>RlkVWpv?}3qj_?)pG zH^&)rkEA9hT(Y^;RhSk1!HC;Y!_MyIT@>Rk!!WMf9B=a+0?|4xF1` z{Ll8L-aLcc<9D?tRis^69dPz?a+18*6-n9q28Nq__;ZOh;S(avg%ibu|Lb({pNxF@ z_SaGF3Gle)4%xAqy{3G_G-;HY*f;{_@LN7J z^r5@_8Xm*m&A&~=F@yf0r8zLEw+8+D*m{ANT#-!HMj}?al4}!STU}mtOEF#5SXd8f z`U)JN#7XD++fkh;z<`ThZmPN*;~`$Q2KxFO*+7;4%$?r!)s_q$K*t_s^j^b{{{Jxb z)=^Q1-TL>?-8s@7(nt>=(k+4r(v2V;4hTp~41;vH64KobL#Ief4W;CegM{z!oadb1 z%i=%Qg89yH@B7-HeeJ!+5_hJ5%oj{$fV(%^P(ZNs6t!&$zzk4VQZT4O!9fwJ#HhH` zERQbGC%T+Id7YS%@We(R_oCi^?7^%50#JIZa(PgCksYJ&_{ID9(ed?PL&wFOnJGns zgIZXbsJWca#vFy2%<-mU3*O9RKR;E$xTnT*UpdAsUCRkrcbVoOA5ms)7Se5&Xmj@_ z|Dmn)!6mnflG6XjlZkWKGHx-G)4JL1(f8Q%!#?o8P4aXO^mGd}O%w&$BOVfo_kKJ? z+PS6jx?#%O{5sFM(DHA6C_ZK4PI*Z_>2w#zT+Ykv5LZ{Se`cxRo)AUl6vAUqxm`Ad zt-yoBR>qC->+osGBF=353_r?`Mn$R5{hIabK9KXOA$;q86`Dfk7ItF5i*h7B*8`4K<%kbZ4> zGa+Kn%QBTR@bGXZo>Kao9OoeXwYVe$rlOEps_WsLp^F?TRXfHQoDb81z`jH|PMHPEsQa+_Q?R zQ@w?+qMTZyliJ5AQ<`0~AGd-w)T6m35XsRcwji@78^5bNMdh2fdm*E9 zLCu+Cb^_1f%X`z5Vf6bvz-7mDr30L!^E!h{qzbDhu%Md!Zg}8dUwTT<#wP~%C{-Z= z6;ylj8mObHyldf8w=)yNL>Pli^e=WyQTEziyhS`bV#O$m5uF!r-=NdWU2>L)cg%Q8#~(WN&q>S;zbS7?XN zN)Xp`8VE+7QVm)_i^x0&?sY>qjAA}K=weO`;d1zqGfXH|cD#inDe{%$w zhEfx>F>G6D6UZqP03yVP!vmv|A@nNL@oAej!m;!%q3$|g>V&F}#<{P*h$Os7Hc=`A zy;Eq7j_I$EA!(q1?)~!M-wnQvjP&m|QAty14!CP4=)R4@Aa1)o_vSz^PvR<< zDDC@JhU)p^QOyzkKCaJ^?m~u|z*QXf7K^7}E6fRkkCpL~Bh32znN9o%548<_(>(b? z+usnzh`?e^_i2SRlA-B)a-f54;Fo^eoM8eH5&vXWJtgxL;R4i+?LXE{E5FRo2Qi_gWT)vn+2#1G-?()ZyiTX(y;L7bTw-B1`Zrq}h|`)HhV9gvdrQ*-Bre`_J%? zme=Q|x!*#+MO~wn;F*iVxv)({f#QL1>5oBmD}Hrck*$IWaL;qTzLs#It}YUrcC6a7 zUmxb`WkQ;Db1IgK=g#l5(>^QH#%}q1AS=+#uiM!3tZ< z{aM0ZMf9aF2=pE!aEFt$I#)aNMC&-l&#gmx?^q|*3xZP6a{CtTa({)IO)lnC9Iz)P z{G>BTh?889GIw*Y8fXpmBASd-#;?bZk6Xg%eun(Ekrr_)%AOl-k0{@MX#AaI(p1Kq zwAq1NE4(2`ErOEUWGw2FTrdwC0--kJNSuPjhiuflWz`ee|M$D!!7g?(4kDh1~E5L1f+W-V2V@DzU?dYWNW6=uc#HHR-PXw&uy2_FO=x6{`-h! z$&bH;ucLneWseLV#QdV429(*kkwWd~40^bd7sEW#1iMy_H*E$*i`$xK=Vhg zc3E{!!Sdw`xo8P$hJUoo z-$ABNA6tF2eA}Vo);Yr91-Y0?GJ$PXGI&H9XGyN)|W61!B{?A-S$v^=r^ceAj-4|OX^wtpOU#8X=3 zG8Ak6=*}iNpNjygW%6G)Mu^xA%h-{^ZdfIvPcj%CBrYg(m6(ve9T?Q&=|?uT5Y91)Y~e9+$sVy>0F`82h$2Y1CO0I+hoKwx<&uGV z7WE(tygU=$%oaM~Mem=lk%xJj-gT;tzv5Rj4(3tDZZww^b+Rc?%?ZJ?r%hL4Km!;K zC1{$|VU~Jf&+rqFQ!8|bF_NTUyGhKz3nn0GTT^YH0o%XD+1O?xhN-s&M5NhOpE_W)xLsMglje(Wt7JgIpgFxECt(nrKp za<}yHX{9@U-+dm~)b8y+@9Dy;Ymfk(2j#f0Wd8T-Qp0_hbaw z1T}vP#V2E#64A_|%{z?YX{BOtzWn0-Z^VF)Q9Cr0wzN>$u6Qn}fxv2uvX?d*Bl}Rm z0Qv@c-z5xfz*WkZ)mMko-5xhsgAZ*@g_QEJw}o!;9qg+9c=G{Xdq{Oa_4ipV>C1peu4etP5 zZ2VIB+XhpZKf0w?OKEvOFNOi2Pj4_@)TQM2Xy*63yY1BMkP5zeZ1DaN}34#WQG&28kL40*y;18RxpHG$JEv7C%T&{ zzupPt!_ZKrSroNbLql`DEE%c`Eucj^<(n1g87^$VF8sb+b4yONDXUgCXE!%=QF>&X zqf6H@0Wv5&;3X{dnYk8>>dUCbfOnPV-Ku7-BR0if8``N~t7adc8MMBdyf7Y(PS2Ur zcY*ST0l^v`+0^|L&g0xqAxp6PNevL0O6GKP4CMfU?^l~8tQlBv6x&7KHz9e6i!gpe zukdae97`o~>i+#9liPg^|IdnZcs+L=G&nh%fq-v&A;h8JHqGf1NN%4|h(fc3NP^=v zYss^tR`b74<8niz8im%-Uec~$(8_h;yeuUe%o{1aEa>}35YHfYEOAOtS4tFTAo$&S z`+Ogql#~$njeBkD2@b$2Cmm>S#lYYy6&PN7K{&vQk)YQCI}$HqnAs^1^z;TVo`ixr z&B$;x&N{X+KYXPz?|?hH9J}Y?eX~*><2c9TVsc;l7_aVMlFvkK}6j+(6KHFSlL;It1lp}>E1BI&Sd}JKod>Oi6l_rw5 zy?|YQ_01nrs)k@B%)rktc(vQZjvt5(QaDWlAnse?5aH4}2v7`!F*og;N(6D#UGvic3Ei}HQ{d~)VnjSKxVCM7!TU$j6`V&XYm zf=1H)FKn8NzJIA^k|uxrOyd+~G(L(}A~4#1M6U z4PFoW?HWO9acdVhSo{7SkbyP^bleW3Ecbee8D+@C`q)+TQuw7MJUf0`7Hqs2i0Gli zyT8}z?I&hT1V2B0X$&Ocva$FfIGC8Mw+&+Ky^5lEVn392FRQD!0Q%mj@(jwr7$X^KP}U6}(Hw_a&WaVQIZD zpR%0^+-7uP1C>2GI((RPGdZCZ%=teJ$3DW7Lf7=CArVAJRy|Z-;n(_0e#u3es^0&z z#@*8Z6_`VC6ZhC?bZWs6eIb$k9PX3MgQEnBnvR?vc?pR{eu~zLghVxwMEckN(Ko5r z8?8DppK!Dinu*152e0ZyX(|?=x{em=r+(T*pGa06PgAal<#JXlWE<-|lh&Rn-}OP_ zD=V8%OK9sJT zK8;?(1jnP$wFIGoQfPGF%IoIxQJ^RN&!e%8pklY|`jnqYs+uV=Um@U{JJeb2@DP<0 zZZ8XtjHLc_k(L+q%|vc3+cnugDkRT3&#ckHpn1S2!hordu3cWOogyO>Pd+?`JCb$G zH9q8aoBxAH+xqnKT=BZ<9ntCcfw+UzrK=IwA2ar-tJv8Isc1=biU~EztZr)OYBg5P zdF}Eye_$bGLN68d`D#(*Wi5MG($J~gIavJ_S)E?BTnB|rXe4fb)wC&>b2@!(>Ejhv znR9r>p7FP}O#9@*nqOhy&cR`Qj3!=!(2KRsx^vXI{H6i&5AD!%i|qqneV*>znc@1k zwBv`io!;STlmrSRWCEN-H1Pe{2#B6yypu9Xi z!uV&H0HDug4Q(cwl>v)}mH`rA)|L&(`$df*#+q*r7$vd9u#S16fkkunG)yv*w-wwKV`LF^=NSh9_f9YvL)`CWx^0xt}Fx zf05}&XMP$xcuG@18#SvMTz|E>Ukix)joB8WfWQ6HDZujX78cU4@igWt4$eQQA=0T&C?+8HhO!4Xuoq?Bf*{q?1dqRi z@H+z0r5P8CKS!@(H^HqlOgfHy8MnWc%`eDi5{9VZ(EeFv0lZ5Ob8ww;_!vb$m2ZKz zmDa0yPEmx2?z?8JGsFEGG$v&;6{7;ZD|)4B*6Bbo&INp1WUm$g6H5=90I%%&rWykckM|7`JX&l=^lDmK^7;DrW$U z3VDLHV0pg2rx6KI#i#R6&GaWOX+L3hU@Y>qENoE6?6#rg8Kl=|V(jqqVD-#m;n)Nc z&nEV^j@C_3i}i|y71Kwv6-%jeAsbdvyjqW1|GE(@L{f)yia(3u(pn+Vbs;R>XRtkg3N$ z12AVE%=KzIANws-Y^-JzJ1IJp$7V?TK4njz>(+L64o-@jr{6b* zx8Z(g+^TI?MtE{oxMnF;5I>K%iq&9S-w^PKCp=C3{@6`CY26dt2?cfh7$ApmU4;%JIXnfE?5|>9gsdr z&*1+izLUYPD<<^g<9DGye8UpoUjjBwXlcsXql7hWjD0czH~hkCBWf(HKyhK9njb9hHw!sQ@TLzsE;$MCHMLwfua^PrGWU#jo@u_`T~cE! z$Ulayx{N3uQ_j3vD%4x(scxju!_4QRH&&e&k_mAfI1EvI&||i$75ZZPB-{`#LAFae z61Ke@mxw1pq@Ky-SGNiAGOU8CFeT{A6(9U9rhc^ywcqY%anm$^6ufO32>cl?D7U*X zpL?|{eBj&I@A(mpN()zjIP~5Q1?_yA3t$)mb!cwh{mf3F5@jtCp{dH#z$!5=^;_UR zEJ^|MQtH{{;wvmeo+#lJjzdI9-cgi+I}kMsCnC0+^)g#du6%lb>Y3R`#zI@nQ7twM z2%n%5JU>ZiO!7`1ry^faI-B0MB?YGRz{$>IF0o&4Yk*54T>N=z zxaG`O13}7N>cn|sE6K}Qn=hirgj1Q7a-rm+O-^492d0-3SdOvR|Q$L2oB(1M@wFP{Q=4~ozl9eocGx@qN?7*3YTtYgE*kj z2cz4eZ_QY&>^pdYQsV#PSlb5La1sNTZviAmhq4POSr{aOl0dJ$^kW6CPOE8CJXdRu zomNB=#!OnZeaZ;e-_ZVOcQOl;l}s3Oem`?Nf$WN=n-{2e)84L&o0UkPSxnt%H7<8+POTep z-&Cvobiy&UCE%AxyF=ZI7cVDvw;Z42+Xc(@bd)eq_pE3|&Dqa_zZiG{X{P04)?)q+ zWjZ4-0N>JXk$Hhq$7*j678YZZ=J)?c2if9(^@!cg?3;)+O5X>rOU{OXTihxBAR?XF z)kUcOllxzK#1nqAuVv4$b$2Q*d!2^+Fk%S>=4F!C%^+0jUYoS2Z;kcz3rrDxFtyRu z@~ww*{Qtn!=qR%2cL03ryLjhR>?a|~p#ho|nVY)?DjoHv?`MvInR8+Ju8vuDw%$T1UZu%n;6^D6l^h*zIy)?A^@8tpE< zPw%K;P6^BE-hlK3Cn69-&+6qLymhP;&e>Y<*YKCBAo~0g$)jMd=S|9z<|B|W{F*Y~ z@HEF}K+bRGo>FO!Isxh?HSY|pnb@!(RHD3>J32$RvoG^@X-MfC0_QvDgtTZ71JYuG z=qh5wRXBQb`Bg0pJipXdtIQ77xUUqLJJo(?h_Wc#}3&;V`AP9q`v3CXlu{^P4x& z$?2ySJZeg(A2hlOkS#>H#dAV30ooq zE8}1ceCCg$b>x2NT0+4{78`3f;f_v#4C)SkgksuKdgaufmlr?Yx zy`O~{zkqxE8297B$gIoxz=|=3O8!<#Hwl~Q-r2&o``A#1$HLT=-J#^#{Q$D7-Ok=L z)<_3%zUF3aV_wni)p{hi>in$HiOrn|R?ir8JL!KrrMLz+`#!N}tWK*ag#o`k3-HFD z;QU`NfZt=3m=OP#d$4ERR||-Wh}s&R3BHc2{3{wZB{b_H^*mU926e_P4CHT3(7k=P zodIknnfCS`41Xet{x&9(UkTCszB_cPYHp_A6@4e(vPsJA_{D5&fT_aF{*%n|Ii1PH z&?NFH10!n&P7u%VlW`2!v0~)8wL6^1#OJL#^dC+~EN#cZ07t)aS^3E;7lEluVmZDR za!F?JDlnGAf3hnrgYB|6^Q|`rY@U1UurH9qd4Bk)6Vj~CCuYRklFj^Sm2J_fM$7_c zHbfUWj{=7i=gmDSp-0%UA)@e4BnhkB)(dUln)bl_wz zx#U`5JUr!fmQNW((8@Ft@vCD`-@?MaJNwXAyRl;VyXcv*t0#35u2>KiKUhRk3n4fIGWo33^nTk{ZAYmT!c!_&(5KLJ4#Ck9?b?3T>Oh zpxShWJ`+;W?Qtv~)w>Xf94qtTkP)>JI79MNwWU!$h#pim--PzliRuL@!2);{84Q(Dubg)$h@*AkmKWkfOc;z5u>N zNU8GNppEHk;_n~>Is?n(t+J>Chi`Q+;dOep^ytRO_kjVwwxS1lJUV$@RMD;lHLMOL z?@Ud@2#IJZJqejKu~o`c`%W`$?-n=DE@%E&G@JGJCT+F|kwsVkbWSc5IGY>R=Py+- zK+PH{gfgd;HoY7w7caeh>8vpS#_U4utv~6#y)BTQEm3I=7*k!A1JqFvPpYf6Ac?sx z9Zbw6gT4E#8HLl7!bV?iR%<>}f$!9&tZb~55nr05$EhpzGFERlpM3CAyR=u|2C9*7 zXq8v_eC}=OiUFyu1_!>_bS;~w{q}1~V!BYYkZ54~)-ATJk~sICR3g3p{ZLPUq+ym+ z_^F?6v}nhR%3p-6T(h2Pg-;Tw4Wvtx*|ZmT@x|8qZYnq*OpYYiRdK@4(ZgJ1@?T6) zOH)n?<`DnwY{7-&M<+*rdK2@>5PHR3IOgf?zpon${mqT#v|Q0Vf-D7gt1kLJyxw{W z2NGy`qIzd?Hc?Oozpv%OnN~h=aq;Blp*hWD$hO%_+J1*K2Pm~hb?#BcvRZvb4$~!S z^0$Gvl^;c@yYBKN!74LVp<`s4<1N`jd+QkSnpRzfJ2xYU#HU#FK( zG?<&rL93e*rbl{?#|Kp=L?4w2=E4($4AM76JE%y>A ze+aN{woC(l#2+eu%x1oxB>W$W+P0ml%zC{{fzS?fo;asN;f*E~S}DtXJj|Sf(i_rY zQ$_q;0eC$eg-OR%!;4`ZW7h05k9~H!~VdB1>rPhpC%93cm~_ zRWha^1P}fkQ6&A!)fYp29jHeIvSzNZF7;x4!;_cMpCSl?BSh9TT9!^L38`%@Fd3U( zLIUSL`exO(xAtD?nwS3v zAK|?lrsn zWLD&F8D~PUrsci}@6R(EbuYxqIb00XL<&Io(3B7y(bX(LPSCJ3uot}nWA(G6s`yzE zU8d)%92v>zU`O_waNrKPsMadakh~-qlbB4G5TvVI7_&)w6|y%N{|!(BhzUL<-QZE> zMbbX-?AmQl)ELpT5S((T27lVdnuK}Cr(i8931G+D6C9wUs(HG>p|--yWGHJvOO$}1 zhGd_y4=uOQO<%4c~y-+<(qXi#$039O= z;D=K--3UY;G4(6()uGX9#)mzi<7(D+^!c?#4Znp>2Jo~R2r?uj$p5sulW>{M3LNN0 zb4W+@HeOy8q5cmHCZf>4x)U?#qexdUd%AGUU8y^yV&}AG`-KV>6BXcPMBpIg`bjV{ zO)o-q@Jp%nJ7tcXp@ZyPc6ASYk@R8FBIZyary=c^Zpyz^%D1`&|D=;@(P9<<)?vJ? zwz^;1M9uz}e7Q&>O>#C{CRxx1zTfVb&Il83M*8yhOat^T8gm|6hGM+?@)Yj6CmkrR@2kB zecBiPFKFW(#B8_!tGmOY++wc{muI^vie^;BH;;hdV8&t+2u(KB{3DifGY+omjDf$q z5sL0)?nf!K==9;P|DarIR_ZY$dc}W&%m6eCj35P4MbPsYoMn>J0i~cIrsayv*(eV1 zS{%YPEEey1w*#rX7@RBgpQCF{38(c<#0`2B6>VC^Oni$;jd18?v&3Q-n_uT^m$z|7 zTemkz_uz+7e*Yv2CW%`7;Sr?&C}N@ifL*)tZ$qyIZVz~Ar^WgiFyIGg=Ok+vkCFAp z=O}JS1!!eK%za0-SxDyKrkMUs9F~{Z>DoEmXY6Q{<)r*IYJsd-UmH)*3vubV(OM@D zkE0teh&VB6etn*+Yt28=+3tl3ROjTYha$%nS~2Vsx$@+XSN4vOG-JE1YE;_wLZPGP zv6_2%W=GGIhAIqZbXrv`m^KE8IW+ZaMh)eZz@yn4ntJdpK!=7 zceSI~a=EiL-Z-$i>NP`n#}UO3REElQ!#8IWL*f59yE*Mg87cfzBb7+fRRpPV-AG;kl zibE3h28GF_Y+cpvVld2J)BOXVy@Les(KDC_w0P{~A-24aR^pOT_21pUtsprSbJgH~ z-ULljHj146#crk!Q@Wm_x=X7lY8rTN`e$H=Rug+bw?>efblv5DO3+E~+OsGBOC(6b zzyh2Qq6Rj`UUWz!=EJ%3<<*&OvmdYBV@mQyXo$Yia}Jnor;?%+_cXm+p6OQn($ zra)$gFLWJ4yKk<6j0whN6EjCsWvQ)U;Y#p=f>`PLf1XEy(6I9qY#Fwxm=7$s$G;F7 zzm!de`9wW?$*Sk1!ULzlAc0m>=hPF2^qGA52jxx@B>zT@fz%Ye*q!=%ptKJEaA2Qu zwO2NoqF+Ss1O9GCIe-)Or=?0i%$g-s&t>36_)C&Xmb*?*$e?#`Fs+|uz!G|T*Axy< zfIw=+Hl9yTJ{JuTf?Kp*(>Pe*GssKqb>y8+&x-)W49$@wfB|gLAeBTgfDq`+#EA%I zO$e+Vc(A4Yn0C0UJ!c1b^2(r{IjZ#Pr41Aq;Zj}GX*HLbPBtd)1ia&=v%@ocE@7qB z{Kl$+@3Xa@l4Rspb`3siVL*!9oX8J^2uzxhp5`~KHfqbzZJzE7`l&xX3?WSM5%)#n ztH(+wOh1xHO?{N(J6}NY4)vN_Wkg^J>v1{Fi9DO?h0R6QFz#P>FaTf2(#Gh0D^xG&Nt`U4vqn3D$|<>!z#dOFZ7?WONI_ZaBSH!Ads?p;u55>VsHBWPPHdm?|G5$l2RE8gwSkCSOzSv^Rm9$`$Tdt~Pqynwt zs?1m7r&sAV@m?UG+t>4Q(Qa%bv^;Y+s-?A4u}mWF-IUhxmd&ERt%UJwK{=ON_ACDt zLXRp>D);ex`4D}e4N%+qFwb9qqV1cdv!piP5)q$;Oax}lzH>$Xp_&)di*5I**Jx+> zH?`sE_H5PI?Vpt1SPbxmJl3d;bjyX>v7%fmdm@Bgu@2=Itv}gdm_*Q#FJQQFYF#Zs z7N@zEyE<2;Ia@Q-i{G+4JHhpP_O$O}$7-d4^qHB_1V|D%Iwc0=y)OAK`SJz8EAnAlp+* zd`2x!p8v|%u*b4%szWq=8cEjvb)n^F3Yne74Bd04k*}xhCH}64J#X`jeg5AMdvO`I1lpGY=?HQQ4f6^sCrrWK>&PG^T~9#e54| zC-UIPN}x!Q@yJzIrnoSjg9CL|{f9)HvrzUh%}3;jl&g6OT{r*G=#ufM_1-zX#yAzr zZvt4kIsHJ*QGxWD`{m1K*;%2hsV8plKYAC3Jy2#8)O-41fSJt+v_RDomrbGnY+%}< z+O2#{Ipgq?KSba2A;wFf`d8MzYrm-M1L=V|h9z7qguCMAo6}p0Xf*0`f5$LpjlJ8d`A6PSkhqM~Ns=p-_;G&ZBNGnHT ztT>vmWDH!c*kPDuST;#$q#Om~Ce}TA28*DGfH?{NRBPYB$J0AwLMzD%Fl*2;OE9gd zy+#Kkf?nnOejsCXsm(SwHEFml?iZZ?gp^@Y&g4CDaWz=MEmZfL|e9CS*#@ zEmPuvS%%eamBe}~@*Z2|z`B_pTa1^#w(fUm3v9WZ@ed|=qWEKM*}Z~W`-6wPqzv4D z>b98Ee%WI&cdw}io6&Y`#08dRbcj%c_hI5WM*}FPEGqEoi&aO)wCW*C)Cwae;|tLD zDAffs7eTEaRj(K17{Aw9h1VejnCJYfTw-iN!$AW@wCx;>v6gAqAm75tDG9eZh-pl# zUpjmsV1xXH%#>m9A(e##7=7SaY~Y6^W1m-^RPF_=E81Mwxryg8Kz@%XY)gPOyIF>e zgbD+3QtEK6gt7kQQ@)di-{;;}=$1Fu%yElhST!Q<3(Ni=?O9X1tvd_^4p_8Sfrv1or$*;tc0iv?F#TIO?W=2eyvT_Kd#ttVgSroy8wDq zVdnZ#HDJ}!>`-~58|?sZf!}^Z)>~%ku5rx8jn5ug*vpT}((kyJlD!eXAhx(p`B3v1 z&}G|e^m1)F8e7*Gfk&e6-v4y74shU;!a*06>u&0mLus=&jlVDDqHIS$%f)ix4JqO+ zqeymLpS(P(w9tt=LDdW}0)H4DZqS6Q`|y(Rz!&>E>r%Aa6% z0qt(Cjuw{6%imsD*xkkNVrPl2EtqyH)SvNGk@AVboi)(i21L^8)-+ld0B@>wr%wx%pm;2z$W07@b zxrwK-y8afc0(}y*i8i3JGc0b%3-lfo8b?-5^g@1LONDVvj@QF$Pr+Q4@kMU57Tj>c z%P*Dpf-aS8(yKj$D73Q7_>LV7tYiM4>^m-kToWsej*sPic@Fl!=#~|_m8Y`*gvs`x z?5b&nm%dV;HR`YMe5GrD(5>hj2c?cDfFAx+w;~@!@ud_8UxDG~y^XR#y=V_?g*rWs zA|1cc5Z+kj3r=3!ufiIqU+unDFmFos4J;7(g;j)B6s+f4sLU%FPO~M54rdn8B*Y(B z(Aox={&*n?+$jbaNw8@Y3+Vz)g1YyBcJE~!F2-74VNk!z(entu`d^RaK*pp=# zUL3WVO&{mWGCDs&GRz3j$a6llf0IlfoiUkJEN+f@Wm=j*jan-l@%HWA4M|x^M6)=a-;!}kxJ=P+2 zayxT_q1zx1n^@*hqyoJV&6Nj*8KUVILo6k#V{ui7@8QflGlA?bqn86)Vr|CqApQm; z?i%i@r}yebD-h*z+vB-@NuilI8fz=H6RIKV6yg~cW0bEyncw0MTJh(y`gk0@?u9)J zp0U|n3+;%Olj?}I<3i660=|-LQkitew~^)GoE=h^BPsfM)+c2H9WciC%tI{?ctUn8 zA#qmxQt;wA$lR%RwQ(-OOSP3mK5ZBWPjz({(I8Co$=58r7U`S6kUte0M*KHW(#^Zg z-9qCtgc0W+|J5J4=rwM7!P`JQv(af|bDfhn)iqV%yVLugp$RY(YIRG>BypEdA+x0V z3%TXuANB71Thbd&`Gg+v!1Z&UE{W6)k&(rBsQv_C#NF5^~p2Nft5HUVf;28O$=ecijrA(96>7YWOa%cDjF1 zgj&X?wlDlol#rD_7Yu`w5w(Y^-tSq)#(#Ax;clwS_df@4R#9pzK7|gNbnO=410K(+ z7Pyd^Nj*`kWZ(;g2}5j#PeA8yM#)Qdlg5ZF_AWvYAL16}1%oI3szB_*CNde6?}`Sh zHCGcx5ubkqCi)VJw-L>_PB-{w+=Ednpy5CEE|m3uLgZnzMV0Wo!^F`oZvw*mPOzhZPE)bKFCHUxqvx_=oAG-o~NQ3uoW;28sGl=T%wE@I962dKNTli9P&VHV|!+5i_dVB|JSqZ6M&`nFnr3kqP^?$Q? zLSG4f&*6?P5O%<*4_?^1mJw(n>1Ua@QKPU9{`HbHfNajcMQGEpz&Eb4ZDpf(7rT8& zE$?Fs#N?P!4%f62qiX1UhA%8|cWG!Qir4N@CVA5FS{IvazaFV_jZXMe2i2NBa1$iKBO zTy3Y76gN;Y1jJ3S(L( zdPyf6Z#>neDcU&n2VP*iai}qM5F_!X6W4P`b1_6Fe16{9{qXT!$Li^X{AawJ8(~NL~&rMudm>4^~i=+(ta3Q^mXWz zmC$oB`X4{Ys8=O$0mFg$Ki=8R>{men9q}cPr>+?uHi`T?U_$l*!{Yb;_ByP7O1yDD z6}1L=rMmvj=YJ=Ur+XLqapOAXz#1ib+Cx7HnC9RIIiosPnvtz>Cf<#HUCMw)C^wq7 z-()-d$;ZM{{w&;@21Q1Bv=)KBNMB}KL_opL!& zq)DH!bUf1YS=PVb7CVegP`3D|gJ+u*75{NI$vLaAol2hm-o;*dX8(~m2~0dng)ISK z0=x=sC;ZE?*5R7L4_aPe#18LHoGt<5!Ar1B&Zj-uZ#DJHyR2YRC}G|S57a>*S^;Mw zLo0CSBt8Y5I*LV}TG4}+Ppm@;vGHTr1lE9`pwR7NcP&PA7nWfzH>|$_cyIE!9k>1; z6MO#1#5}UrhhHKQXx8r{1rr?sf?uq4_kx0aD)w&vQv=!hWWB0EdU@Bpi|s6%x&X@f zkA36HBd1qYI2C;=10j}Xb)+`5O_7686IVfFnXXS6Oy&4w+^U%ybdZZgquvrW7)>qsOD6_ zS#_hrh{_#dVMecy>+$(SCJ2}0fqZgH!`7Z@S6cUEi9&Ki` zZnVi@$_EQm)ewbf)Qo=?bTsa&5B&+Tn2`=ORe{eMj}tghgWsqz!pP&1H;PUoR%n6W zGEUEdGLC}J8{JSQ?kWMNBJTGlgDaUY=z%CfQeMhH#foiW#8Wiq$jM|Mdc_A7Pux zJ!Hk&i6EJO38^})%_M|ft=)U;3`kYAaMIo|3-PEO#yW@e?{F^SZvAbM>)kxjr8TaS zHQGCXKqdo>aBh$%at}hcIc!hk{raV%NPj2%Nwy#VVx+cze#vSMN&C>yIQnAcqs@(8 z9@aaxNeCb7Q$=j4zI%bIfAt@B5guljzk-4sRBoNPSZaHT!#R41Sq50jmnhgdtek}# z1WD;f^wgP?1$tIen_NR?DK*|L%_@ml9cVJ77W=;E5l$b3QVfl{;;0GP_Hr)PUisKh zUf;u46IANh$C|#@9^MAX)v3-p?v9UlUax)(+6!Q+w-UpVtPzqJQfDXSkR+d>HA1s; zRZHQdrJ!5EwgeP0>2e4$_1oM%LDWFjp)z@v^m=|Xr1vGMGYkt}P$-r2>sQ8uc1197 zJ-KpikT$;wywOT^^1ERtZVTv1QUw}sy$y2LD352ms#Wg#Q&p{hec}`$LIZ0F`Ay1Z z@E7(qzPS4Pxat{b;FE>2XF1y-uMX+&zdAF8bO=xB!j43aF`8(oJpau^t=ib9rDVO% zq1~cC&pwDlbz*YNwG-f-gBXRu(-54Fz1}Tr#%THV)(M{jF*l*!SE8xve9_y$YU}N{ z0oC~vp|&n>__U%k2r7)q`(kc7f-kr|V8Em~v7r>l@e5FHdVi6}XZ%?PzB)opGR?0q z9frUhY&NBv=Y$KdWysodY7cI%PmTEOVx#~2CAFLI{`J#5n$_T$X;T}EsSimywoguG zx3nVvp-~eUj@wRZK9m2~j$Q4sb!PJCuq(sA>NS6x$}~HoP0Xjst~i%VlW#;)!MN5i zItE_=R@*nw9{gjNKXmf{W9luV+Ulb1@8a&7;_gn-0L9&*xVvkMQ(S|)TMMO7v^d2H zP`psw9g3y6zo*Z=_dnkKAs;dZVI(=(XRbMaYwbQL3ExdD@p0ff#4_AxRm;j}zeAOW zK>K3{Yjw;J(t0ij!Ho4vouq6~Vsr>ouG7iaz?OX(26X$CBeB|-C8F!Jz!s)GMA-(Y zs4yQwR<>_b-%gYlD#2NMhydRQ-}-*g&70o~wHM19+5au8q9wH_ z20uaHN4<$F^T!OIgYPn7c_A%ID_X{5W@Eo&r-13-oxSky@@{d@(;_^c#@}3D1h)LK zZ?g^06dIB%9wKYv1FaAd*xUa$!WD$G-I7*)fBh7G>J_avRFAPu1-wPGzf)t`+1p{j z^`@`cE4MG?Wgmml4I_SV=~^cAI>zJpduPY@n#WZc)8k2}ulHTGuHs-IakAy6WUmR0 zyZ2`HRE;)p>2{R5+)>cP_kY1P=W4{tas7Td=AT2Zcb}U6QJ0fip z3p1q$H#t28a%$u#FEP2h!JRlYtVwg=ZVy9*Pz}SmYrOTpB%MfjT=gv>e|R`(KQYPl zGpqWEJ{TVMu4q#NgM1KFhOT);&hR#aO;uaxt)sF1Ws~a%0or&&2WJZnzq{RRd;j=u~Pr0>05Q>8Q zRDp{`N^~sRtnlrkZ(Z&a&^v*AlCin$%GgCTNw*^0sKlo)D^7=(@l)dlP*>wi{J!M& z(x6Wi3S{0G$UOJwm$EG#Sifw&nO7=C1EMhf3(6$ukn<~|5m{m%Q~H4<8)6D3sCCu>}JMd1`C6UcUA_^+=S8d>ezv zjgx|_W4kNAs6k4VxGWp-s>qscz1{GTQ8q~y9trYimt_?sWMRZr=H27mMuP4so%h)CyU?JW^vfCx8 z;J!EJ#yaM+>K+K*xCwhwJDx=6vIhU*JLXcUD@t3GAkc!{i#Fj>Au;td9Q;w~yB0(Q zOA5pge)xGYHD6N~G_#txXg+Aj@O9L;J~e-PPDP09p76}TJXAEiV5ZZV^z-w=f@Afr9`3&hk?_!73NpKHJ`xmH@tJ9FJqWvcfe z#bAVDpu!;`0BPfg;&J?A-`;n@JVsAJ{S+bvh_!FF-{aT9naZ^a1i!jv*{ZO0b^yW& zzQsf+F~@LB3qJhJ+S}};7S*kf1cl3947f8RD27*^>8;4O-0r;4lbFdj^GnxNh@uq87?CDIa+UFd2f6|Y}bQD)rMQWdJw?55Jrv6?Zu_dVGv-e{1 zf{pJReSQ9*+e#}=>x%+R=>9mXW936JoA|CEBlM$8HTS~KCfEGz($3#RmMPz?ufITR z$kp7f_`?d-a9w`iHv`$`ST%JA+wikwOU`R)A`qfOL>AH&Jol|bo2mqkl57I$QZ{zV z(3(wt7>ulAd)n443~$g%ndM1>S*)@MTs*%M_52Y0y>OOvc~`E~EI~oA)R3McPSoeS zLWh52DDZu-UesiGA}~J-D=BR+Y8>~zm#LGJ#s<21-loU_c~nU`!rDn z8mtbsJ@iu(j^9svqrNm~(QvIqT0^z*P zxpvC5<9k+;QUrXtz@<1vXl<~jZ|lyo>6;8snOXma&24PxN@MIebvb$`216|a24-R% z%Z|3|@);Y_wy=PFOT}%bvcA%Aw0LwW^=M(i`)!JXx_KxqK6@<^LdkbOK2zv%*@}ta z>D`7~S_nBRp^h6@Q1(Unj6We7=Q)JIl&nRi6qC1G4C@c4pCyK3;ee_sV?E=e4kYq< zQb+Csp(!tkhc`?C1@g0JO#6*)jLb1<<>uSH0XY#B@?ztd?RlMhn+{gZY?fvA+0jXdRxKp8nRA2Y$2ws&5g7==>%wCtCY8~me;Rm3(8H+mA* zbdQwYoEWA~*n1SwvdJns2TXYT7|Eg@Cdj8~-ZPc~=0@&0JjbfUU(P1-0-a|N;&qvu z@i{A^=Gs2{4%UtHn-peDWJ%G%t9$zUg0dOu+KbD8vQa<(&axu<)z_sRpCX>yM7kgCL1{!6C_NY< zOhiyiJDIpZT0ArvF5Yd{u-khu#{L^4q`a{O!rC{vL2|Jy;bS{j5wGoQdj$sGxjDmR zonxJ*hs4hoi+|E?lk;WD;-}B!9xbDcume94|XT%`7w+xuw!M@LfJ?U;X(Q+O%e+>V_vCWj3o*v(kM*^y1%63N|F$HX=< z{A~ogZ?fCK>c?Fm1rOa0(6q(=K1Bv$TQ;ITl-q7ROo)!{DOO_We-sJuXq9qL{8ZMv zuE1YY*|_&l;FNn5DDg$E#QBnKJ&nJ=E&%k@KQ&-5@`9R~va|IjYw;9#DvHtw8wbo{AIy1@M6-@q1z zy#b3|TcQrQi56~$O)ZFWNLq;a00OC~%JI4T`c{A+*fgKuzr~l!Y`pPXjXjBY%|uH7 z%T&CtMxuaB9*M+{ritLR{XOWw7)$Bf2ziFChVqGL*7cLv9Eu~LaPQ3usQ?>4H5qnD zth?m0UbR$(Nr`7+*>S4Cn1=dVC#P`}MAsq?xb5w~Hc|mPQ9i=@>RTtyZFML~V4&)^ zAiDMOTcmO0!cz23 z_Pc+2mQ^~-D<>!?e9|lv#Y!(SxafY_J|^^DtDxeU2(c<)5N{a7SczMTTZGOZ3~pGW z9=wsKDmBt<6{PG>N#UkGiRjcMMas68z9k6Lk_n9*B$A!(yR;^h31$Yt^G4K_6$;Tt zrDN&Rq)H?9%2GihWXTC>Jw9#49z3`Gjg8nQkDUy#Dv0e)E#qP<9L|@UREgxW4ktlI zXXXmw#j*LTv(5a58R=_h#Y%BHuABx^x?EWN5p!}0KNDhEHf}Z_h!U9gt!^2D>p$Zb zftz#u@H)~ObNE2ex7%D|D_&{J!Lp}V(8Zf!=90wMzcDPavg8942eP{F4G9IZ?htpizxq#cgx+H!lp_n)~^%hEjP8X>0?Zh3ZmLIBr0xhh|pShehlz{x5tjgcAk7S!buRm&| zx#oS-s9Je;5|J{tV%%@P%FR-1;4VAJrNuu?XosQ}-CdyVXSR{k&mvsoN--{RL|mW1 zplhetg$1gbmsn&vvw1s2d%}89Huhl}Q^kc3aKQ**2#mWhx?sO#e|?C+>;1&k&+)Gx z5b{sRmBH+9CV3%VXhEDZy;R7eNFDf7*N*|d&h4gWaZRk%*^?LwvcKX-NDgt}x@EmL z6lm~m)BPtg#=cNT6g}|@)>$@7tq=Wbl}36No=DN3h|$^Ijkv-M;Ay6A-lJpR|0g&= zwIs%w1cCX;ls}QFNNgAQ$=>8cJH890ZBiiXp_#hL{fws)u__?=W6Nu8`&+JHdoz3j zCLT*^p5WKTZ{ii9=l1Sz4xBg*Fv?$5vDLP7-s{OW0|)c(s^nw`Bl?7!{d8cls$4}Z z9}j*CCcn*AdAZ1g`$W(gkA8W|(;hXVgt4|$mg?Md6!B9b?m`Abf;*|%Fd=NjXx*G5 z+8@XKmhag?t~2;JKlvcH7R@&cMCJOmzBciO6d3#>H(-afZyA`xPvz3}t1$oP1y!6b z$I{n2v&>if@apjEaJfLm6I&Ma2z}40O5z?H>E1pXa)DZ6fCHC@nAhHM>u`D{bLsc8 zHqZf0OQz!3MzrUmgOEtME)X1hLu(e%r(IV{!n{%9(=B2NUc!7?pmZ@`^FxyOw<`1N zGEKq?=of$ZVsww_nXLey@gYL~)1Pfqn13+fxwz5}n453~+ZlPUJE0u&lL9$u;M z6+ToieVHG<1)rnGzKKli9+zJi$kJ~!7<5hc0X>2&)?N9wZ3PEf)Y4&}rA=BWq#Afq zV$Ng2nn!T^2?+^tf9bGCU;fKYu-gLxW+8-g&MUw)m|z^o7f|UJyfBSCn5#^lJs(P#!W6- zl1i?HWYQ4V^HV5|u>T0P7wRN+BCVfF;`fVm1K+i+`o1;ABVS$j;nzOzoRd$a<&WM+ zp7OoLdIWV*k@ME>L;IrNm26rK`$Ot`+_)R^lR*!2mf@ z2LcCw6HPBt&Lw@xP5VU4a5O_SS=I3pEhTdzt#o)S#AO&PR=97RXxpQ^Wm-TKDaTzy z(k&p9m@Yb8g@XyK*x@r;vS?C{v> zDAU_?PJt@q9ww6^=?El29~DY@Mj??s))u~SjGd8p8pKT%)c#yJ4B1Bs11dogE|t+! zA5SEV@8n*KJm5_EEO%6Y{96HTZf%xTW_UNOFG*SyjJ*)zVdM}cI%FyhC8w+sIMgXB zheE1wvk-o_;jhC@i|EEWja{Y^#mF_4&BIp^#A1c2k{Y4#KGHu2?jdhOn#@#&i%{Vn zEL1$>W53N97$xLTcuJTFXUa63Ie%-Rh&1$mr||kC)T;!XzsJ1n3D}rfA=K zupKFT!hIEANFyjGt8L!ALhys|!l76P@?byg&Q|6Bmbiocw8X2AY`1A|nm#CZEqh53 zc(RHk1Y+J+?HP7>lox*eC!3HSQH2%*IG>k@n%x)+_mAHD2TQ^wDXs9&7&zC{Zwplb zMVCH}9{TeXM5J#Zt^;Yk5mO?&W)PEy33s!&gs=0@KH< zT*C(`;6J*=XZp9ALCtC^>$&zi#F$vC1P*A0n`tDr$yeE6m0vGS7c2q5aRH&9~+c4 zIrb^TN8?K3%gTevnuiIz%35(1OTgejfQc{0*F;ZeMa)m9RpN-C)X_%`XYL2EOm0Su z=3!jobsvm-O#e`987fKlX$LtR8v9a|=>)4+>MiCepqDt<93r?-amI|fJ&~Wkt3);_ z&%;SOA?V)yh4|G-O-J~V4o@WI&p@h4Wx@umZ8s#BJras(zuUIJud@P=o zqVdH6zoQkG`kcoNe8k6}8N+0!CGyV(ROT(0bImqkL@bV~YvG}(Y@>1Sm#i!mLLbXz zW+#Fw<#|eLmj!*$ad%XkG7h5eAO+d^^anpB~>2z&KV<5YiGzU*}cUjqjg z^)+U6QU6&1T}mi#IMUyI8|WySq?K4$^ti9amLxgOEj;D;JkO^RSuUE0bz^7ul8yW? z1rLZfA`7mT0bjENDp*OfIoBE`GX~L2?Y0s~-BN|}+_8MA&gpt_IyzeInxRvF1dmk0 zC3+eM*HJVZ0BT-4hLAh$S2iYa{AF0lR`|9hlZf$7?TPl?M#O1WK zrBNmSyjfseu!feGzjlhZX2RkBz4U$t))~D8C|tp8^UB4#Sv!zBG0oU_gnBQ5{=#?v zWFL)ds&DrI%FlroWO6PT4deim1u@7xe>^785*KC!>cIS9`;bb1oUgb!p##|S3`7?O z+=?HC-l1QS*D;ZS)7&3LDDHc2SYnu8+GZ~zt!&0F^lf#kG8G?L&gI|MLfm{OyAz0R z1|YV_SKAh-0&13lZHK*K3HdOpK0KQg5EtLJiXZv87oPxI|I!}Y?V>YkfF-u-)5+K3 z7>ok_M32giHxVAan|CF)&VIcDlrho`iDK9c7o$HLI_nv1oF8lxuJ)RGd4?DaHa~m~ zag5}?;UyrN=)3X#Ii^|3eXYZwZbRs4`b{GqsFKn&k05=_$$_*|IuaokD(?sc>8I_c zLtiiaTBOr7f7^a^QkGD?(Qob8ktS1Y{WK~mlRrr~@ZeH`5h z=0wMKq6nVK5vj*UZ+xg`m{bC$P4=<2@r_c*O=#Jm^-isl6yo)BhdYN*aDk1O9^Z_#oQE$KPyD;|p zMv>k3Co#tY`%U+5-G1}J`H7a~XJJ-6B6Q0FJ^gIa2EEO|QdG?dq>;DuRPN-43SRaD z$x^CX*vLfJIq5hT2KbC%xhQI#WIlT4ba!Mmxjq?uW?oJDGW*gGpi4A=qU**&g_`MI z*=XT*w1+`Brgo(6{%JVxc1#MEgQLR|ujYL?{_jT|F)!4p+AlNs{07KbKZu9t(i-Ox z77hQlmR?r=PTRn3xHJx(s)ML+zP9A0S+|~TIp7UXdiB1i*5)w)eGb!mOP%wxZ(VY# zG0m*z?-_~+<*}C2V9DIjUAx-NnzQKR@1F->y zw;ZLJ)C3fW!Hm=JEA{0Q!71}{g*||o!9ZF&cwq>chv$OV3VXnncz@0(F)%sTIo^J; zItPev|E3kbEYETFqE(EI%@XhBL=NG8aam$^H$Jl0rXXDq^S9bfe zTA8>Y+b{Ry)5-JOdS0eu8Jj^v zqIY_KwLn~1`|KcP%n9D@>ijF5$yZ4uzGL8y&RgL+r<#e_{};#Q1ORXKETlWjUSHd; z<)01_>Az@A;Nn<=7LCv5*ZwoTdjvKPRq(PVXWNsa67C5gTq7Q^T*2kU9AE4h2G9_L zptFXiS(qT*yH{tglyGm%R~Uy}oYtHJ{;oo^+eRJ?b>A^}VRvHPHtrcdXaT_!- zNlxBY$oYFp8cJtDVq%Bv1%G9%j;+BrJpZjS1HWiBWf4volmVF}x1OCf+2_?wcI&+8 zDTk8Bq+V^qbzqAikj&8DBpNDxoT!=*sR0>ZWJz?MS=ePCf#zA&f^Jiqn&<}&HiQ67I!Y~pmT z8@qSvT9Y(%Wt#|ugZ*Ix`|o+XQp36v!|^RGZ3}fd{PQ**V#sp;9J2v}sEgFi<9RcN z=@rzdxHkX6mW0>t?9cF>C>b$!dhtPX0+^D9bn6TECQ$@&)LU~QZi>Cf*mKlyWEMBf z%|pQCIkRmjMhNrF1ZZM!usP2f7uFnSBRDVYbamnjS_ep5`e^j zyi57D6bbe@B2wE1LPej+Agix4k9J9OKXwokMtqOEx~M@={M#i=@c&qVNvUCds;T`1 zPSC2-%zoTK6F)@`?R}!H)b!VPZr<26M7CVuVRTO9(o2Rs#XSg-=T66LIKKv6=*-fMpBM#-r zuDOS-E2*Nu_w$XQQYunXq7PJ&X^>T}xTu4dqYQ5qyYV+i5&)THytTK(639$!m7h&M znF^^d&0BH*wZdJv67owk$XbZ0U~-2xPcb}(wtjH<+4XzU(F^%WJjU%)Yv>%0-)yfJGFZVhQc4~an+x+E-Wv-14uPL|zN^`e&zVOpG(<3dX$>*HsMSFdJ)ls=zy zC*RpVa)3ANQ|+q*-fg&80niOo$+sVAL;FXqTZn&?^zdqgwR*NmMaLVJ69pI+{61+l z)R(OH$M1+?pe@hElL|{varDLz|HQZ^PXFudALGf(-Y-PuAx>99ThQ}ld;Dq%i2Mg{ z{`z(`xBa6KbVu&Oltbc)21qCA5S3Tm+_@|}xHi@Thu2Eo@AQ<6ZQXM=n%-Jmn!52W zq_gbRET+FVUM~HN&t`2bi<;o~UwKFm&7SUQA`|%XWgh5gOd{C9H}Y6nc(k2Uzsc_b zeitt1HUpDLXJShs^}1wDhEOx*PFK|emvCH14TBM;P@MPgJv=|uyqAvWO!h7C%4dP0 z_Zkq_U~tnVFl{H$B6RNir6G|6+mvm%Q)jENL*UV#;qvlSsqIGT-s_3N(;FAvsx=na z``*b^v^BAmM_T`rdAKSx-sH&-?_qB84Orh+s*eV!Pu`k%eQVkQ%a@j>3X&RQJ;EjH zd>Q{(R+YD0;T7<0{S%*Y)F@&W4JQ-C;W5#DrApy*E47)V!GA74##8w~s)7?;GISvJ2{~37NhJIg>c2E-V2>;Sa0Oy zf`?PKGt)hP4EO$lI+4%?womHC-eCC+pD9aA*jmTGjNKvK2Er;63ED;98fPu;gD8P7 z2J1E|wKN>$DkUA%6jpj=;3cVbj%33$!gIJg&1mvFNe)t`cL(4guCbJT!tY5+wG%0s z{0ZsFPbOx{5XEw6evMeNbNoUo?5p3}u7Cfj9)1VSvC`n~&YGNFx{$uJYZ5aHMsFhI z8X|kbgFeR0tNxk%VyaG`PSjTH1N$!ol+xP$h8B+f<^eAy_nz4OUxoWCxRZk=(_UFl z0`{?9-{C1L37gVPUiJ#D$`e>eHEhrdnYOLLx{PXlJXGqRf#EH>q#198H%Z;6x*U@; zdCW_YbK?*Z!Vx_z9B*CGX|W&?)Giw2C)#rKZ+n<+JRK%esKX)Ds<*EjsBaZ4F!5{9 z0{BYj&2i;h{QS{8d$0+_B7(kCna`4=L>AdNwZ8(iGQ}~j~QxCEezVt8)eu>+gN+A+NNg!vFA<)Ysr9(kue&tZrIJ+RF6ei29b-^CK`$4+&InoVd%#$*@D=yCDfO z8gFDs*_kNIkRKYOtP*6qTb7(4uUU+mywZ*EO4DrkX&u*LRnoU&71sXP7I820`j$c1 zij8Fm!QLUxgGRx=r5JA|VR!TfRJ%b;Hrz7!xUEw4nUQr+} z+FUwo$;&3{0JGk+@dXZ;Q}`;ry3n>Bc42GV-1Q#JCjWePy)yFFeJoXf3&ID^Cm8n& zb2bqhLs*EdS4R85xz^{Fc;y%RKl%cA^h&ZXI5tCI1MV|<|3WRbp!nyh4Wpiq9PQCg zcEB|9-zNTTyv~CQ-|fjh^3zSy8A!89NTqYNXJObKH4UUfwj%(WOF?4DM(r_W<0PW= zkNVi{ghtp|&^B)X=ei3dXW96N+9VhA#)pkafZB0%@%m3M{SP2zhA!SvKIi(=Cjih- zaN)qXzT!Ld0P6JhsF;4 z0UXse2*E{ad_1Hxrycr}Aq1sQ*ub(F69;ALB=` zXIrzbo*zuMFKnj!>}X4QNLxYaNiJv>LKdnnFu%0E-yt@{CTy`+Bw*Fz_u93x@!{`k zO?EaxC=>t}@NQm7*w-{Ul|R6S2-IIen2LnRVKUd^R=Wi9)P+L%J!i4Q$f428i-YT# z7ZEoA>Q{$+R{iuGu(jaQK%He-<>6DUKU!T4e7Xh0y z)1&NH=O@%9yL+*G#n*Gkky#e8aIs^QDa7#4c~B|(t{C817c1}Wr_ZdpFo*|SdyaQ~AS z_PvrUXe8qz_h?~}b`}EmbLOGuG}|a+*ch6a*UYJALh7QN_iHn1Z~>{m!D4z3s4?*J zTKOCvaPFaD?iOg0G1F+^WGo6E_2rAR?bx>VY@h$Bb$;>ml8vIyPoqR;XT?5X@8>!R z1?J<N~gt}BpEmVS-%YShAnC^IPGcJMUk*4x;} zh}w$UORz!Dp&c9%zt0d1xm}g>Wk#LJtxCP1e~_pkQkvZ-8y79JOB08|HBJHtg!`>X zzEu#e4?cgV%YIxtFMJWS_@3(_4cLb7kI(ehDznz^Z36;JyUps~Me1gF+YIbefE}O) zloJ9%1Rknh1yAm!-6p?F=RXb3w9GBKHAr+^s}=ka!^wsLZqCE>bZ0ZHwOp4(1SVm7 z?3GyM+O<-cd(ef&k&6Sk+u9o}0|5JYce*)C3s_s0e5Z{47qTFITgm)864#`p^UeeKL1L^Sg0TY`QnoUMB2E{mZ~R4& zE=+KpIg<7syOT9U7c01f!R8j2u9WWRbPsPi%LbDB=O?0Zod@Q}@ih+7N*=HQJB62(8vVnKj)e|Ejc^sNO~kso%umR7nGZFEyN_ml z*23tP+((Vr#2L zx&_gUuHf-Jmq~h;#2kj#r&EXY_DFHYQMpDn-_6u+y#B|a)RBL)an}=naDX9v97@{=;@($YJLKI{?L&|VRvp)NAuJ5-4ph@eetkm?f zF%qrpa~&o6z%O(RctpsuLP|liSvfp7>apfsUg^r|3h71*YpmR<5kaM>bRP7U*$VeL zjMdVk%$+R`=2KEs)A0vQ#Un6)D{7nPmJ2 zGI{aT_FZHuxCc>MKn~?6^s|!MrN->vx%{fM_7&T@3KPVIzR`|35fUJCK0UTJ5_i<* zkyrcAXS`4~j_|;9r;&V@15Zi3V&(1z^_aANQ=Dy;1<*a&dV|V8_I1N95P?%{C^zp} z5FW`}&D^`g1tf;U>mSc<{}GL>dtU7}`i_M*DGNa?=bn96!6=q?I%!J`)0rw>AC2>3 zgem`748Jq-Ly=;mAbhBQA$()L9*OzQIKF)lGdT6(=oh~8sx{Zb#L1Hj>35IY|Hy&& zmLu*#V%(^Y=vEbXUz$%BOj0+e1I=Eb1OL0mTwWVqsmCP2=?Ts+ecb(L^k8v(MG6kN zEs`DVbh{#B7o(e;`8rQ~iufE=XYJp&mbNHv-HS(V=kzwNm}TdV;%yutLaGVfHXp;SN) z{9DsN%@q1E(Th+@94J-rgkqV~5v?$wbA5zHTZ6?sJdLAY-#wXaoP~UbwGP3Qp9=gN z37qKhNfXB3Gy}3KmvuUd!4Wq2qwWf*b?@D!9=|Agd<^PWWNdXC+ec?ysH75Nt z@cbJSi^-i1lNm+ncya7N=tdcUZPo&s52i%l#8zVKLMCH)c6WJ z5gyXG3fbBF2{@ojnrAXPzCvHxfESM)0)kkkpE>r^m$NxveJwA;4i5Ggsn9qT~dL zR5qe#Y-K39c)7TLBgC9)%K$W)3p3i7j}cp2sFJ!?6^>AC(Dm{BHqZ^<4fi_N$>kya zSs=-{#qh9sI|QL-L*?=3~Y zGBz^XWP$eKWY&?X9K3MC1|d31KG@H4k$_u;wTgPcB&I{Aa;s@Vnt}P=0dbBfqJ*io z)5jb@*$_^@*|qIu8I!o&r5EIZRNQ>e#g)*dzpLfhkGv*;)6?+fxJ~X9#zTzerR`v z_?QAaxFi3^kP}toS6wdJ2wAgN#&1#ovLLmG3JhQubEFlY%#He4)^y?gFGYxf4>{Ho zIOxED4R8Krh+-fWXLrp+0?E<$`hv=8iIzfFw4iBAzjv9~b&d&KI__)?tw2qR0VRo@-$99~LeUOK{j-38>~Qv)_{uKYir0}uXc zA1&Aos*WiD=QI9+!sE)Zt%A$8Z39QO6G0#G@h9XgZSz6({fem3gXur?wqT>5@f{os z$V?pv#>Gc;pu7H6gup385>l1tbX+0-ko_OG>k>l+Fn&~2n^wjL17e_|(Q-D0$`V-# zglk~i5iQ?_Vf#OddbcweFnKf-yQ+Q@<6nFt`>*{&9qtUNS^04{S7eztW8d(1sS~1^ zp*IeZHXiJMYodal2ehGjrqHujsxu}SKU{z8VKFRn>ATRlU-L?>XVQ?z3!n)wsP8e| zWg6NH%A2zD=pQB65KH|~i#=@+WGhcC8^?EcYac5V%ijl*@fSGPLH$O1vU#d+LY4p1 z#6mj`LRS8)Nt-}|H&^o+S3R$OIeyia<~W?bgT!r9a462$>9^buQ)m`D>RWL;P}gU~ z3R<-rs3l6gHM?9sHoL8NcUKYhlpi|m(}p0ax<5>ZaU_kYuk+}h_y@kn53f#jO9kjW zQqhB9f>^;>^B_cBI)0CC&DlKzB4XaPv5)-1R$tSRhr;%?a_k!wBtzG>c0an`QyxB* zDRr4L#k#B`+-{qjsn0Mmp>qXP+gnc#69Izgr?o~7k&mm!TZ@z^EEFC81g-%{IX`{? zBw6esKx6KYia4wZmPt5ptF^LEpW4lz56TM-pZpqTB2c(NGmsy`+^q5s|o<)P6F3MDh6 zVoPF_mn!EqcDMSU{b-Btt|{gd>gG55`r*M8-t6xy)la>BmsD@G>P9JTei9l5 zIwjOMF&_2qfhX@!rA~Rvq$P1@ZKfCwc;j6ImMFY!irFl@M`jjrOuQsr+x|6ZU2CNj z;5bO@7=-zOgc#s-(Y;#L`m`M_UYG?nIm;m2-IY=r_HrpQG#Vky-2HwE3l=*VXuQZd z_Rqg?3;E@^N^1idjE&$jBNrzHd$!*+s>A@iLSJ>>-+;51HBhISa*D!@0rRslPb600V;vorNOEN zt0DxG^^RrF{bXm?viW|0$f~W{sU$M3$0Tc9rnO>;cxxCJ#C&pEISMwG>zhPu+a2tG zKj6KfIkU5F1;IX*wGIAE@VDr@jqF9qbv$tbvKi^BIa*F;)~#b-qn}g>f4m#Gc38Nc z0W^3u{p@;R4C@~?Ae%T^pvmNcL?dL5bSwLv3e+b@O4y zz9|4iK(}Qe=`9dVz1i(h9HIjvt>neYB7_&_g-!fw$MzMOHrAV__sqRN`%+E4pt}K;2rX_u%io@Y!$0c^LjdHXpMTJ%qHZNWVGRq2h`boqp9S#Ra&S zONkgX-zSn*GAjz;uj#A&{M)7f08RxyUoJf-oVeN1-Gdd6%)vhj!CJ?*xPe+Rav&oN z2j5aeKmqK!DOQs#g&TuY8Xb4AzZ>zwWQltq>22vv=Wl(fpUmU^dNV)u=WXo!N78$NA+=5>WDgmWb)Hi*%Ju!0A}cp>N{ zBb`Jrh~d6vY|Oxj2}d6{pk#c z?$Ve%zbB#mN5umN+&Jy4 z4Q=nHMG>D6t+bZUbtNb5Q?Y#ov3(mR0`Fee3Wt*Q|BB1kxU1ia)6NEeXUYoyOe73P zQZ_(Dj7Vhl(7P$lEpME{z2xl=<)To3iyT2?z4S$(tS>ex z(Z^J{P{v89+TL-fC>+tyYLY=7iPR>EO_)YbR{C;i`A=*=(D}(#U~M4~^V1xzFj9Q~ z17T)UNciMM!#qa-Vn8E}0WlgEyK_K5XZ?)~QTa{`EhiD+k0cGh>VCBZ^hP#&fB3s$ zOi|Wl8?L7Kdf!h--Mz5akJL`4J2;cNvdio|gzuC}J!b0vL9;87dlN#^b-2DXbdshl zQu^10)rfQ*=U})1j=|cBhLAP@tJ4@}^Aay|*6;_s-|2n2>358$qc?Ayw?#6_)AF-s z)^;P1Zp)!u#GZH@K!C>D`Fnl@D~xU?-wyZn#W7q{sS%;zEyR}Kr_=vAJsIQOs*7U%n| z0_{o%lMc<=%-iyr`updWA1dLa>WB5vsH)~h`KLh$n0m35kCO!!Xy|!5TY3Pj*S_O&K=sh5tV>yNtbMhaWl?B9;#4Ls#C{2jlE9hYYTK6= z7p!s&w5!We7sP)zsiT8iPGr3H(oU-(s!rW685mjNes^(clc!@mHAogj=oa;M^e*B` z3H6T~SH+H9lSm>=;hT?{~&`W*V(36aT!B4-m1D~4T;{l z8;WAMw(qiv2jw5>Dy0Jz6lfm)3}FJ{+UilmQZ;M;VThJBk0T`C$z>Cjc9;*<^6es~ zGOC{v*TaRF8l|$MfPM34ebOrjJvcY+?PRdT&;oh9zZxd*o|Xf`kPn<4?)VeEfR!^y zNrH-iAT5uGZO7CP#l~b%M_M z#~!kerd=U1FK??Jw*mfgbFqbS-W`-|(pCZ4U{d^2oT9Q4*WCAaZRXA;|; zzByvWp^_rZg+&Z-Hg*XxuAZjzwOYt{&3!|fhR7yy^x!A{9}AFROE7NAFDkFB#J_!* z|7)~lf?ljES!%cdN9dPvkL2H1qo@Ib+P`e6QStuzq9^T&jZ3of?k1y+xtAP@l?p5P zK)1{?nK}&YNn6X4|D}52)6S?#J{>T5o3^j>0URd0rUv1VdHCk> z?QDQC+5-yTr;peG;X~hmiL#yi4uq2NwOa>2dyd6N?DzYKLGp^U7NVDE>NyriC#|OM zvI$a*kzaGR4+*6`U*#agP)y&HPQLB;`8($B#cCNP4}7bcS)Q3B7npnUE(^xy;!l54 zI_Q^ubm z$H|UnO*3TiL-MSZpo}NW?@1p=U+a1^`5}9Je8PWdoE8suPUVr*Z92%(dc?y#LDQf2T+qImcpacjRIa%$(8{el031@YL6DSt)jj}m zgJa5Tb=k##_;{CisQ<-b77N)7!L+CG`?F&J?>bLH#M0GQXe+_Avqpz!>=W}k4_5T9 zsv-4c0V&BV;IJUe!PvQAom#EZYKWT>I}y9fmj+$ng=BWh8BLA`mBPOCW*HjYIT{ZH zY^4(SAS>jlW6t}+Q|t8}qC%Lc3Fi{M&xANU$tWvSX&MHaHnS6$sI%?{cu3V>jV&lC zUz^VVWeh^PjSyV>?VjO6v3Z9RZ#4IXR#zrgD}7j7Dh%K6C(>t925cp6rOq<~duGY> zSK4&-FIs%%GV?>`m$(B2hNwuNQLqeomI$B7uO?A`2py20nDR4064QkaAakZ=zkQ}R z%RSH6*s9xHn;1tua`DIB<}(hd3^*Y6*3O`A$yVT@=gxQ&$jF=VTHzFCb=D6-vTTmk zd`(ZUIz(A&k2~dOmRFV0>lfNZKXANT%RwJ3vy_uA|j;iGOt4( zdUBYFJO1_b6`1tNGJR3b;VCTrDaeIhDThTVwMAUO*0|m>EtTuiT?t-IG1dUNg4*`=m`pyq z)&IxSSw}_rec_%?=^VPdyGu$MLAqlE=@5nx3F%>wZjc6%7(hb025Atbdk{oGx&-9D ze1G@em$jIGW@gPh>&)4EKhJ0HBjK&(FDt#j9)eRM9HK_N*Vjaaq`>TJ?&@7rjg-eG zY`8LuuF>=VXv%G9(jV$&^?QS~Z>V>1roKoGIGGO@%1LT1CvAv{`n%<0@6m4Lla#cu z;xxV!eD;O4hJ^r??~0VZJYD0MVA}Cf9!kZie?C@JTh5{Zcme1g-%8fl78fsRrWp5w z*Apmw1#SA}28VjtF`h!taM1dua2doQE40bFx+jSzO#Mb@@3pwL3iS9`s2#1;iGx>? z;2`)Abb_~jYxjoEOJKRoVSb1uYUtha^29GycV+hz#Lo7!J1NFD#(IuV76?BzVh}NS zIsW`5)2Y67hLwf3jPW2+8RwPkEO4s3|GHT659cSrRTEq1tK>PjTkiQ3$E(iW0@muT zDv$4h;nf!}0uEh>}ohE)=P(X)g>o zO!=g+=k-cs1@SF zXREmE#M*@r#)wMV+ooKm|8B=>46R*OFyOT8f+bUf^05eUA>98r35Z} z;ud?w9;Z%AJwDN&8Bbp8p_H6lw+e+#fqvAFeeoReyhfePf0-Nasu!E*Ms0i@p{UQf zf|cEpK5pjNZ<_o)gYr87=+! zVzlIrSO1%er5Hsiu`s(xh$agjW;B*s9NH6&uZCJZUhQi=#g6AVUkJ!QpA=xlVqjx- zaS+mH>Ia=$jSie~mG(@GV?TS)uag^<1x8LpMR&TVjapM3p?@T(V>wq&#+iEp2Im!s zX4?0P4XH-cagJsGfszJs@P_t`@|{x*DWyQUDd#k>CQ3=Zz8gldpV@sa_5}yagx|1E zSLg%js+5IJ%3{n6bSB9~(&cK}qeS|?o2D7>i{`hT4LfDdRgGZASQRIl(AvJOPtsSv z-y(F}1mwbr2?V6l8|cpqy;T#6vP(D_zlx2pN#F%4q15WL6VnC%@XYis{U6QZ#0qpRvmp@Fu|^PaBm1Vc4C!+eMA zsaPR(Lc{HhRO1Q8``J*3HU!zs`b!{FG7*xdW4=F80Rnd~^zCpPy!%`CYrcn$=4VEv zUFil&&qT=GGK;@<_G6Nv$Dit?;j6~0oESetc>E@@srUhv5Cqf*Y<@frDvt^~?+*r{ ziw?!!E$A*O(JDIZzqo)5qnnVBK^t|=W8c_cXvCir%uR|uB)W`!Qg`e}{3my$H#7=e zRmIxX-oQ>WAxyw--g{6vnQCl)A5B>val`R%u3+5urS0 z2KrmK!etX14@J3eL16rsyCRJZn$*jKY>e_=h_X+Sf8ALVi>VK{#Tu!Zj*Hk;ohd0; zG`8q)h*k*CFDXwWM(7Wg=9Tv$U3D>Ir>|vnVN^bRAA3eypy!a!x?c!Sfbs4+4E)6d zOB}T##ThRyv4I?@R5%+~8_ZbbI;aA3lj6rHdQGp7IoY?6oZX+Iw%LR`@0;nWRurz9 z>7!QR5_`k`l&? zJ-f0M^P-Drk~tM}8WcZ%OKwQ#^zAaD-)@%1+ePmxMD+I6?gem5%*IR8@S1#;4`i-n zqpzeM*8+)-OJPpA({biyb7yl)4fTsJOU6J4%Was)IWHX!)H@xHc@VsDrkV})%aGTd z@kYsknI6yE_jgFisA#P|+I=xVYev<_343+ib|sf0INP7n=n%bfM&(lnqRIirjL2eA zp*-uW=_Mm9JcbSD03%7B>v*ZB1jc~WP5J^ke@k|M6&qk0nUu~8@+?znpRYG^O+m77 zQmSq7W|0mq{2eqUUgjH09v-7{ur39c53)#8=9uAh5_rcImRsTuYVE--9==WE^C**zWcd?q@ALfNHN%G9~vC zN#8CljUEV7%;Kqe0mT`5Xm|H$w@CV1OZc;qtS{9m*V=X;<9obZkzUxJMBh2~uw3^L zytvdaCGouA(dFUav;av`8hSa4>^Mya9l z`iLX$Tprh*-2Gh5ogvxpFgMm%h1qL_^wwO-?CKX*7`{7t%QJUvc7tzcZ|pQ!`fd?X zy#W_I>{=B*>LsyF&tXj@yJkWcGPK!GsWmEyryS*2k)X3X3xwzh#?;E^Y$^@EKcqSF zp#)NvhywZJ-BMQ*A0V4LCl@j;Y^V0iut_9Brc07MvHW(9`wb@`Zy|cY6;{v{edpP% z<2xLgdtu=Odx*GZI%e_a^bX9o1ZKI~msU`nA2UGr!>`CLWdl%Z*yqHI;m&fkpeJK? zrEim*=a^#YzdIo{Rr-;Ad}3LySkn;@5s8Uxvu&YwozUZ;if~)>3IK)h+HRd|#GtD*>xWHY@BAdHtBvC%@$gsnjQ3l$<_;8vl ziSd4KkyEodlhcroi7rA(`?Jq9Z~sjw@iOa|i;EWZNdrF|dtsN0%_9qMG0tF@!-zQ* z{e6Q8NS4QQxV|tut~0KF_49GPi{uo2j%@dQHZIO>dmZs%V^z3vF--S+ca)vZH&15H zUGbx!3249v`ci@!2lX2AuuPXg1nPb{{|luMQ^7+=W&sh4PiD+lTSK8_W?0{$72JFA zli|Y7>4M_FAR^l@3bZ`Q^7Y71s~U&juW@-JUXz}YxP>HM_vaw$H3p2mhd9^+E4X<7 zRIG4vT`^CJsJ4raI;ZDV>ZnUIPw}r3mU%_}l)_Alu$x?z`|jgoDT>W-_eR!u89>03Fk5XSM=riZTaQH+ox1K zmI%hSW+2R+fz3om3S-0cR1{pYR6Amw&;*2#4nb>)hPi8kN}pi5)CeMRTJbC!N@mJj zIEGZgbf!EHpj)s9i6rla&@+J{kLp2Zx}VWI@e9=34=E{;ec*Wh?(ABm&s!$&FCa$y z&X3%fb8PRD{9O-2LYrMxGCZc-dWB2%mh$K1@VB#Lv-KauiJ`w{BhMTxlaV9wU?&DL zzfZvX+K-6o(Y`mL@CBmmrR(fjay}LfP|h9O6ei7=Cllpx7?7Uj3!5HOs@QOpDONTV zwbDDrlDab{g|_~O)ja--?|Ur!y3??Q>Qa#M1g48~p~L6Fl@*4G1ariv9A31E^Ks_| zg&1L0w$6;8L!>EiJI(2})E&Qh4|8Ya0suW|((JLO3iRb}_zvC2#k3&GYdbo3_~$4l z@!8P}iAoCfQD&5F<5F?-0H?;Uys^SQ%4e7zaXUF$*V8FnlCH>!kAci<7pP+vV zcZ?lLF(fqE&P}GTwl;}#Yj760x2GPZ45*=RGP-2f;e$|yvAN$9@fcUAUSh~upl1CO zpKkVIwu;D{ILhU!(D};BLvb=thqXAM>!a`=wm8{&JfYIX3g3p@MqA;^e9noc>7iV(~F zwa{671cJ;cyq~0S=NQUavfDJl8RI5L(xr%=aEFo#gPDapxwnNCXyKEkvqL4d?`V(7 z;=QC3@pdWjxNs4aKk=e7*(bT;pAe3gEZarb6e!X54Q_>l4qbt~C@*?<>9}t@(k_zZ z2{CE&%+oyH4<3A~UrpSfpO!xzKS%8K>d;k63ma`2|Hc3O5^YxW-vrs9Y9PK%OY=si zV^&|C4ZH>=U@8o1%Au0#FQCkJB*o2Km$7>vXU%p^!hjXWf(egzePVMhW5A`@D)f!{ z!&w8%@vqzUxpCgT&(}cm;$D1ERq#f1i&bhgoRckpn*1fm+zC&Hp8Fqbp?1;6+nBfj zJy!h0FhLp7sR^p%B^PpZn;yOLAs8bIPx?k9S2uJYu=$L9^K^FWFLv zbNL%@sU!XIc(unsn}gsBW?>cqhHT>%on#+F2+?o<2yBRNC@mQXim304&TIGnNk=LT zWE>P~?zbT+M?9^jf&@rF4sqJQ1h*atjvr0wZa4WZez@j6rB4;vmun~qButo$N}NvoyuM`l1mu-nnbgqo!aW~V}b zN%HPVk+K{Z2Amsk{vEB5Mo=0#mgmp0<=aQm+Yv5`b97;XANeJjsRfEn(p0XS`D?6Ow;q!o{1@J#WcwZDJ; zqW`*Qcz~-DT)JaHbft#&k5}(4w1;*=dOj&BxFZTU+x_pT*6o2N?8SVQdG&OW^`e0@ ztp=}p_?K95&WtVdcp@=A_ygU9<8DdIvm*6S%aKb@sJ#FA01b`6F}ED6uMPrIKP)2=W$x@VyG$3oVtk=XuY+k} zMY2*4WSbP$Z>4B#A z=UdAHBZ{@1-@-Dc+8kmg8+CaCtoafUR*WcmRGqJ;-<@o1lhbniwb^aZk?5D1vg4>2 z5LuwEmCtlB}{5TJj$2~)b6VNn|p5(eAU3Tb6yRG%0drgJ4}0Fn$5)H%!D*_slPaI;zQ&b znHUO%N)3dhe-mkAmQ!L}Xh&2>y<5j`X32#sAmhRKTc!MKE&<9yokLKtV6Kl?hzr~% zcX`?DxZ(tYB%^H1w?Va6^?GN4tw$?N-mHd}`?|4+cFtIG1F z9kd%L3E=d5n1v>AnL16MsWhYi1m~0FXx>>Nf(M(TKFRhpcvglq)q0Yu9hrKl` z^s1w?#rJ3pRM%oSi^(x`=@+6yI2}EsDYiW;`PzSL<+LfEeGo;Wfg45ZNtcQwF77#y z&?iz)j@*kMcrOQL-d(h3)9L%9WdMFU9u3nmB+QxF8q%J08JXObQ)A z8E!f}#_(OWa_W;cp9oUkP{FgK&ymc2Rchx~nQk@zN6wap;Sdpf_gm;77|M^kK$-VK zFZ4HqiMf}c*QCg#RF;s5boc`Eqvm-nswmtJL@Z8rsj$t3mg}o$t!j?(`u_YViO?+;RL`s`;63-XX@jzG*!%l~b zzWg_`sQ0rsve3hw#T3t}T+1Mtf1&?lY8)K&2uK$tH5bt;IR0+o0m7iZwwGT zQ9V}X&Tqvz>SxNXG~J0qOMp;K7lpLthWCXCFzV`lT3~a`H)yiimAbBiCX?a$wxC{d z217RL_T6p6N)v;+3|jTPbfo9dj4#379@Zvb50O`1V}hP_g_aq zYr&xoa(LZcYk(w;wP66H7K%V>v7MDm5F8uyk%SRO*;piw?AQtN=EEcZ--I3x8gsSq zM9swExB_a+$5LYqPB}3=I0$6~in{^QntaGhIV=U?|GqET8##n+_KDF3A|vC{{ZXv} zq%yvYtpGdjhUeCI<^#92{OdjhSzoR1^fum*0uA$L)m~Qihc~c&vv$|oNt4KW{54j% zNX~YXBeRtPLz_oIf(#T}c+I)+BT#HQK8iLDiyRrt%>UM;J<0D-PN>L_N8!}^N^hBI z&H+tk8G_m_%_-oDo>iy9L9hEB zOpLmfM%`)l#yc%4Lhao>ns^Qv#gXf|sIe!o0T!a|BrsXjXx=p)ooqUMexqXk2F<)7 zui4B4wIlUsrxcy?Px!{8S-qxb&Z2BCq8x-bIipa|fAuZz$m^A_ zC}ZKK;V*HcJNT(5;=rQ0xY2|B9Jv`dTTfPD#`Xye>?gm=R|cJSv)T09?GpTSwDLZo zq>FDYf29oy0rlea!rtZju`|4W^^TJhuRmS_6zyb@V zT5roO4xyS_&iR|}O4BKE7MLSZHk`57Zjx!B>q3^y2f@ivq0i}$-IEZs?B#fx&m!N# z_j|{ndsh(t3=uztf=tv&sTfES)Z0C7H!gxJwVbF`aLoc{04L=gwdH>v6T*^0RfvkE zj%oa@EV2G5d_pb{pH8v6>6^_&VCO)wXARz6n8158RpR0{94Xoc7s6(3dmZT!s5!<= zl^Aw-fvTS^S;sdH>K9VhWB-o@h<$zs{| z?SmeTv+Eg~A5+A#7RznHWkYu}q4#~Nk*(k3ZWZ5fK%gpG#T(EO}oP>hWW_D~nlT9SITLrQ|`o3J{i}+N0eEEk}C*?Sf ztsZZrr{Qt7I^+AW{rPHtE!3Y~+&tUdf$`o&f9i4W4c8|I{h@pBIuqSxaQlCudu@I8 zUyFo#zC722pa|yU-+pr@E!RsADIHg-(`XlCnnDVdh=1H^PKi-XjG|;bl_mTD%}@5P z({O5@DJWr|58impqyXIk!t>l7CcXSO2_Ky3axX`HT&Pkp6Zb1~20X3&b<-sc7y)P^ zgwUla3%y<*0lxvW56wt_QC9efie>rccEA1a1Kq7o)K4M68}#d4$NBfEc=Vs^`+1o3 zq;dVXvc_tiVIK~dV&7RvHGd{ST>=KM*ce=QuO)0*=CkY`vZVMI?w?A&@b_9 zULzDp5Bv%afb-P8Jq6Lq`ZR8!#W#%`GU->E>qQYzSKO?)&^qiUmUb0I9rzH*2cF^_ zx!DpX`zXoN`9|kQwb8*<4WNL=udIDqV1-q_m(LLn?82K|3Ksv)XM8J**S|XAw9iKU z)XfqVnJ8!Ypb?X!NrG5${dOM>Vv{FdVybsmuP3_Ks8kkIuU92fmt+9xqzGr&RXG^; z%tBo_v;E2OIApobH)*(>j}}3oAFh;Sz4gDnkFZ*SZa8Q!^J^Qh=C?()KdpLUEF`{7te)6IVy{N>A zOLFLzo{yq4%Yg6NdbgVKkR>@gyVS7BCUN{);aFDtwA+eyT9_;r(0U)7I`7Yir4);z z5r8z_1;Mo>4*2V6MMEXOn?-A~|2-0|FssVb%;6ygu!UfX;OcIPI|qyBLg?5w10Mx5N9&*c3BP&WDXA{U<9I@kY{UIB7{!w>)Y#6ft-lfPP) zxxl-r>rJRne75Pv1bRGXmPSoAc>Mk3%)4!}#;z$1wxK@*O_y>*hs8)U>*t4^?(iFI zw-BLtas*kwU*sB_^zS-_GAwK+S^lYR9zLU=HzVvKyFd)izH)nkJP# z!K2_Ixwu0%AXF&zTzKC=dIiGLISHf@1LB1!QabNsWDqk@&db-+GAT?@@X$fiE zqn{E*=$yGr`FQ&IfLY>z&msvNOr3Mp_bdFD7tVUQ70V!6ZmDIWIhS|rzdY4MzhWi@ zW{XarybY184~;@2M##0nXN_Mtz!e+*@kSHbtWv9yzn1n=Zie{&t}~*Bgi}pG76%gb zI+;#HaBXy`1sSAz3pepbiLy#5_8j^)`awUX6&`#=)Uf_OBf*2_;v(4jC)HT6i*cIO zU;)qlWvK8poc%+%w0dLZjAb0Lw{G#UNR3z>lScL;?TOO(n@^nadWr^TCin>JSB}~IZM*}FaVvan()lR2UAVDy!M`cYN|{$aa%EC{!Qz1pJMjR-Vi74 z$Afi^6IPnmM-BJe&|S^ON8^OR)sUonfK(#L(3wpb-}-ZY&DK;UOS;I_BGldXoi_1! zrAQhJ#5BF;Wnrk(#(_=tYO2Ckhj*;aAv`=pj6(?XX@WZv?`5b(;Vy>lo@lM6FPFS} z_M;rqAlcdZ44?~tR{RQfN0sQ!n)~zd`yNxK0NmNVC4AJ*KCwtg!9=`de zdRI?@VvFV7|(K7(m=~ipgNCdKO zhv$H`{!EBB!>OV?o7qtU@g&}eKo4#gEc|qf91Cyr93_O{^6Nqrgu+pBi^8t{s`JT# zF2(8S38`N4$i!n685tPdHa_UwJJd_wSA&&@nY^(eR~c?gC+LHm*{QhrGEF-V%uYFr z$a#11*#=iMaVJ(?pY6}*ME@E8r6=f*z{Ien|3*wwZsCD_ai6mkAk-3fyG@}cXTzm4 z9L_-c$LEmWvHLXQyzG>?lzDKRZ0vKi2Q??L&BTR#eZOg)-zNKI#;LrG@Ad#t?yDUV zLgD~>!lm#Ep%E^L(j#u>48uO^9t}>6i_*MuOOVQimFbAKLXfqXU+;(R-SdTg>nW z(WZ`=U$VF!cd37&h6I-5&uSKd?khYuhCN|7nhWu$L;yUYXH7o#W_jB2R*x+^sB`?l z^VPS{HgY(jN9QaGVV~Y;Sf@?u_GJi=2s3Ppg#+dn{?YbxyK2x|9CADf z6e5n0YfpjVm?d=&wY##g`1?f{L@Ilj31&J|0GR0KHA!dHTMt6g~piim7 zoTPuHlMUXsEZcPu?SCZGI<9_n?sKvvU|*U4qVAn(CpJ>crrX`-PsnAh2Cld19qF;P zS#QyS0x79Zhfcn%8??T_?5g)^Bx~Bv(e4RC9B3X~S=nhJdd@-dOaY`I_dLhSqwSoS zE6ZgU1l5mxE61(3IF#rQ&Im~hi#A2dfgH%nN}17@r?O@q-t6{rcV+S7QYOi2eTVUb zcDJtWb3MLsYm-cYp8arq+{EXClYR)w%^8GDsQfd}i=7wo6T+f~ zJ6&pkZd?FblgVxMy6c_rH=8~rR-WT5lq~8?Ezj|7`-iDdq?D*HQ|(QjIhh45mC8vM zUdB7d3_tp?O=+#Ua3zPrzECKBgvz%VTo3|Oseq{8nz|oE{(a3;kiNkuxa0U{-_r}V zLjCPGFLk2j0=Q$zLG{oeR3Zn9X77#Ge2=ZPBvK#y&kuDhn&{}e;Lbk-g*Yo;o*Bu8 zNKsA64F-YpHNMizrWur`q7|y$jne7k7iR97g70M3^#31*nu@ zisDIs{h|PI_6nim_%S$xw7gsl)eC4osx6hT|G4@g8X_@fxCj8E)JcvA4p7hsa2KU? zn>ivD#cNB^J9NKU<3_o&3Y10!L~U$mIXgt~{KT-s?qvK#BY_O>=3<1IMbBV&+LYNV z+KXo!yo76Efq=#Il27;zda+{Of%L^?O)c;G$sipg;I#WR=3Qy?v6AODXG3~7{&i$6 zOr6r%{EwosdGsd|>8RSjl0RiW`9!_Iy6~#O++mFTqzSS@PUh$Ee7Q<;}{wvPaCrEPBr-Kthv^wj8KJs1k;V(cFROE)`P)(PZj|JxAJDt5Xy;B9;w*C6mta}$XfNjVJdVB2SJ97M4Qb% zQGMj5bxZrptA1S=OZ~-XA>bk8l{*sD6in2?PQa4($2Z@hj5MM8V;PPfNtyM}I+9W~ zF*frLIX{t=NA0jLL(23Dy-1x00K%|_n5xJ24ORnAn-Hy3)WA@604;D}ZDrJI+p!dC zhiuX=LJOlApl<_J)RgUw$@5B4%wc%nq8raCMlxsDW3EU*>U2zh^G}-dN(p`m%_Nl$ zRQ?LU?W7U_x@~O=ReHBIw~6}*@3GPG{F7C=!u9enxp>;%>9O*(`TJKSzD_oQN>lbP zJaQ|bKs2h+YXpSSk`_Nx@;4)9D_)&zRbvvXyo~@dVZ8rnTv#_)E{$QVY{Ez+sfm!b z^*q@e#-^Gw5x#HWkPBkRO1?}|7C|u1TuAjcJA}`?*pV6ls*lc9b~9_c@issLpx+C@ zY3MX03V}D-$KTJm&3NIq{$ zs>%G3pn{FToDzV5lzGCUWeo(KMv*lhIJFNwf*m7m+V(u2KRNA4i7nvVFg}@7$HoSw zJ8D<HxS35l(ykZ0 z=UM=8ZZP7y?6MKvP&mx{eRcK2QKO%2wcy5&c%G7&&w+82T zHGUIdtTFq~Mf6-_fiKv>H&!ubPHl-lHyOz#L+A6$X!HEPkSU^s>JuGx9m#|Q0or1R z-lU`>>iOyZ>R?mD${L%e?1e$XUh!fL{)zctL6u=oqI z=~8i_LEK62e$UU(7HYtRe>SuCu4{~8u!&k0qi67hjr;O49@lo{&xw#akb@@ZYIUy+ zN#lV*t|U`IgJ^}o956?vx_={fl!c2Lzw-1r;*Ooaae8|-XgA1)Fybs^gs*ZBqY}=T zq%$qP_*zzco&>sm*rV2CZpFEN|L&3uwquMpzR89sdN~Y66BW`^9uM!f1lz8l0;w-* z0BQ)EO^cmx*I43e?qFR=eZ$W3Ty+(_R_%Mztdjo3=TxVZ+5}p{T5O{Pqu(Fy+T$eE zeDJv@PQogsahlaz!K(PM%&(dX+kVv#HYMyiPp&ZK#q?E`&rW(DeSYhH-}oN%%e)f} zUf#pa6o#uz@sGcBMP&DHg|rdw`%_oBYG2LA#MO0dA39hDes{YuQoRu@eX~%=V#5IQ z@$mn{n0_tS&}&yZm<13@L@~io5@@0y$i4H=g!s3|Z9Nu`yH#K`lw~_{)JUK-|Gl8h z>P9H^jM&eKO~;?<3oh2L@^%>QPhtt)?Gy3q=c&JTJZ9E5mvO+W+>yAm3cC>9_o_PV+l{(d6?Wum?Ke>%>#}g0 zsPxG8bnNHUF+yZ(w7AfB%7#uA!ldM@2146XxmYGzCCg9-{A5|-FE~@5LuTBVdwM8- z_4-VQ$c)dxTuc)J{0_28hvZhHp9Q>*{=D5S_phwfk#Ekk2B7Y3M%(d1x)VuEN#|B< z`mW>q)X6LzbTi4K+?%w3>1jvyv|ByGK!4Z?H$w-|N|$#8aa4cgJ6#xGR@y1Y*!Rog z?7MozJxq#Cx&V|oS-alhh0fpG{g_EWw`Vt6*rwtR5b3zAQ@^(GpS1OB^Ch94^u8wqrNH8m@SDUGwKQ}tEmw!ZkW zVHGOKqQ!&`+ci7l<6o^?B+%{Skv7Ky{%-2K>9QR^!~q(P{}THmQwvVs2Fgxe;6c_2 zO!d&$K(uwnT>z|uW>9kCdd@X^CI6_TFFVC(xe7bHwcsE1?yeu4i|73!>|_dHQ+rM+ zG;|(Q9tuQEjMlAFw_`jg#PiknP$KOJ3%lGtBKei|xzQ+OdARg{(##IT5MbN)oJkOo zn)%y@;m!$Z*$cjb?6O-WoxrfTB1=ivS1+l0{1B}sCQC2R==H~s|7*>Hllo8`U)9#$ z4XKhWp;UQ%yNSDvkjy>V%g6{Y?RKQW{k;Do>4f0JDs&0(S_VRg{Xczww30(XW;|v{ zxz(+e&q)(A5#W>6di2Iu}YoD)Rm6wCVOD-^|vBp+s<#LGv%13d&Kggv%1==Lwle zYm6@U+O>S0)3!lHfB=4wv#GZPdNWAX#`~mZLw4-OmGhY$VbT4A=Bl@sDGT>!95%g> z!t<_^P?n)Fwc~G^iAU-N7;@R0s#MB%`yZlPx>-f?G(rBnaqb*!a#(Q=FQwwy)Xfn- z+Mv#3(nidNJ*w_W=EyfVzsAY?FAF_)&0?qP~SGI0mOM9CD9cvQnCs4}0sg*$r-mHb>Q+j=!uxbxuier@HNDw1kf@UCi zIbR;^4cal@^Ld(S|6-?YQ!_^S-hm~@!=24HWu}FYm|{c>^%a2nt6Jdax(srF9H;(2 zKa2||B4$az=*Q`At`zmAo5k!@k3k_(W^5Du5e)( z61;YsAeeLA!6%iv{9x6Zy216baa|Lw8?iv+Fz1*|&bicL5J-(CXeCEPYhlSFZMl zkl&UXTK^+*KAlVH_sKc7^nIdZ5if8(d%~ELfCKbBX*M<;iWe&8Ue7mv&du>(;X@|l z_IDF8cU#yx>q8H75KxMg>BHq?tE-1a*|TG*sneB*!a(&zN&dCNL5=`YrT|S?MC@i=;2YIwV$gxP1o6Y=z8aRhuqYgu{O+gDu!N& zrh|tZ0{up$Th>&%SY9>T88Pmy7(_Q*Z>YenyxEREUr8(#|MB96cu%vgP{`8=)p04jLhy{AfgzGe5JHk(H10VjG>Fn(f-x!HS;)SKbStIvm&(<%PVRF~5V zAuRMSXFFLB1U=C_u{;NN?-V??hDnK>Xo3X241IhA*_BhDDMLk`gSAdMw7Hwgk3(!p zZFZmEzxn;oAZW;rE>+5D4Jc^UO|$pcJ-n$)^Vqr~SV=@lMPOX z4kbZR$qrFy@jh`S)1l?mJy|w(B}y@4AZwJY*jvsl zB*7Q_h=Dj;YB_e~vqU&MqaPbfFy8n z|9GedM2+zTFh3sJs|g4r@qk&>$&bJ6Ez&3f@SM>lO36|I3s{! zv8KbnW)xjBHML)#a^@4){Y%ooWIkA4sRj{nF#F>&mxm6Q4p+M}UNUNjaXPqHS=9EY zKI=pu9v+xDvCX?C!dx+W+tii4f6emWrHB2Zh9b|bf1hCOHx!s4gRg@Q%RVU^OzE~L&Y!5}(-kuhw1x-Jz4cYEZPhZF9WO$) z#VADclua8l^YZ#GCfaR}=wSO(k);pKsG2#U9u3`6g>sI2kFaTvw>?8JQ#I%zc&m5I z@C66HBFIo&9mY5Cm8HE51pXfjp!Zr4-0S4Pbrzo{Tk4U_WqbttEbysI>DHib9Pj@z>MJXX_G@TQ^@T*)k*2M=9`2Xj8}= zN_tTvUiazU4fR>7(9|F%cswl|yECD0YuW=cGgTmBBX(UdIGMdrjTTU-Dg0D7jf0ck zNJj^T*}Y+6zgcUiW%k~x&e*3;kbyrfMhKUjL%kkX*=%8#Y#5&)KNR(WOlQ=~xXmjAKjW%tb7^WCTX5L>N`WjVmIuKH0L#&o-B2e}}l*eGj%UKlVgmn9y%S( zqncSnVt4Z8{i!kRZ7t&pRV4y8Ok+aO-Cdc)94m^O@Kul{4Vw1yy|*dXceO8O29P30 z%#Oc9U%shDsUCv!?xUfu;81e- z*LQ`zZCa6u?~`dXOIDy~7(RUpq72Gw*T}nJh|JNXTan}Km)^F%jo=N7JGu_-ciJyG(}quFZCA?zL7!T} zO$+`wQZQ7iZ=9T;>~Gy{-k9 zAv;q4xMFAum8$0byu^xK&!n2p4_fhcc5^;6Xd7xa+QIN+b;<5B8JoWzR{BJEZSW|0 zC*NwZXqQfOHEYIOsr!oWmS=&Lo?kkz+~NCXrb< z<9^6fp&p{+$^Gj2U0k(gZ>(UxxU;9gwRdqWwu6#ubYVNB%7_ zjVp$O#*+X`M!_-!_v6p0Io*<70gdlHWC1ETZ#o^?@+M}N2GAL|Aic}NnbFdP&o)Rl zhT+tTHm^$$$9>{RIF&BcCrl%0^G|N$hI+@nlaE__wd3wZWS$oP7?(fTdxB$L?)N-o zK^Yahgr?=-{g=A2HjcYO0W^WWDZv0ccdVA3!%hVjmaTkbojL`*j)=HTuQ8d?3AotE zSw~n{e7rn|P)FSHW9Qd571d9P6k01O7Q7sY5dTmvWfwdU|1b^&y$?LSUOsrcVf-L+ zNloY)QGcF3Oy{iZQjs!xl4_V4;Gq-Wm$j*zAhL%p6RsCE5UBuFK*1awH{_x|`YtE} zz<1pN_yM2;;S(*p10UFpvXZ!WJ(|Mnk3koK;vcI7)m>W+e}7017uog87=0r6F4^#v zvP%m|uKU+SWF^LYEDaS~L{xFLW^CuCy2h7H_21oobjC^@(lU|Mhia?MMFc8a_6#$U zK0TxD(x^Vd_l8Z2Pd{8((++jDnB0RpA z4eE==VGpH(>Vy245=h8|@CXw6dnnvoo_<1AWn$e_I&E)@z$KIF%!xhT{b>-iTKe<* zE1ejLlknzUhO|J?zX#z9_Px*SWWQwcbX*V#OX9g7RqF6Iv<83lWv+*aC+c;6Gwc4WA>>2Jl#z)LR z3FD>Jb{IE{tg+-?2v&X3nN9tia z&HsG>Bj_2^Pn1KM7w<`Jz06)E|CDL@U*ZF=c=Z`id$g^8&=SL|kIErqBauwPUXHZ4 z6w?U8!}yL1NG^P}+k`sNuPcFY<6ei1m-6xS`rd2?_0ql*jPJOmV^mB_edEUPy@qcx zkZsL<>kPZ&dgcD8#i)Cc}dv@Q~d7bBZUDrFF4@LKGV4U_a%sqOcB?e9>p|Gr+op<#~+aY{|5; zM+Dl94lvn_J`4UAwu-lkmq4En;l&clMT3SAJF#p_pHSv8IDEMm2 z%Tcf>MS6hGrN}sr@kf1M?Fx%z=Gu(;%G_@=KtI92ObRy;BS+OnYi#K7$WdDSd0HMv zL14@5i=f17l0zEwQLb83c<`}qJ5Rem;k*(DwkkARj4JhxPIviFHE;jgX z0R1{=G@t9z)K+5ROALG2^W#y&q-71@mX6Uxo?r>IS4d})uJDQswWPTAE80(=VGQcEG9#0@_?I2Peq15g<`L&s$DM%11Qrt zqv-6b69!VdU)x*)mlHQ1KT0|E;w&K!pr@dAxp#OZ76uc#d<_)&3sa&dn3pKy1$nz4 zqKdo?1}J7Y?}OH;KZE!A_xNkB96!a^8Ale&L6k z89Clczps^`u~}PGhfjc~1Lhn~T%2-!q>h2IijGGI{uz;a*lbvS951-R7FgM^B zEin3HCkC_z2T{V%9`{y~&(YE53&v%Z`)OEa5;v)M& z=3gtP{ED>Y*4no@NQ`MfNux~CWwW#XBrUS_uT#E=)Nj7A;$_3AHu5wLJcnC=SmKfB zrypt|)~OW)LWqVhR#0y1;M9Pv6}N_Q=2*q@zo`;9iipe@L{wPyg;S@df8tHO9VT=h z66VqZ5~4fTVz4SS`*zOR*Ckez%cG;-Nd{p!_Pa9n>qxltto~e8_eF+WWF2?6s0b6X zym#F17WY5h?I6FX3ZEyF=qm5{iCQWNXV}cC#8G!7k7~x*Uqt6JqFJxTW2eT?PVQCJg0#6?XTh zuw%}eINDM9Myj&>D*CVU=gGL8dww_*BLNFEjEgdU`Q)5OKU&$dn8c>$t@Uq4Ox${3 zcPN)7L`>vjgzE(9P%8HAZA*XXXgd^m&QozzPA>kUT!gij(;ApXI62t_BPZsZHE<9o zyF7o19V#L$(4v;Z$lQhu@i|yueaSywpOlxqHSCC*>CiBHkiHS@-7^M#f7XwI0_R#t zhh@*qANJwcp(DG6{vR2LR-))3?nt2IwS{+8qs=^3b}~#cO9}^y!mJR0qy;rpsF9SZ zdXM})n~*yIsN=>)oYU&tf#ty=Q%q_)N>HSTral;)AF}Mu0PciKZznhK+(S`j2=lDf zj^sd+Apk$&26TgoqacEE#(!i_*dgmNQy7uH7i}q)&mLQcRhuZ7fch@4y4V-CPcMk!d2!GQlxt;?!4pW&s6{I zb4*7pVbj@|M@}fp#$&RW%^q976kWA{_vvy$=Prq$>KuoveGd;N3oD$C2~e*agC0WNSrZ#BlEA8DPx3fqv!|809lQYeN=UX`JqXai07CT*9T z9_*)!O4M_aP?B)DmqdC##0iFng@an6S2X+)XDPacV@UI^|79WK#R_Q0+LgfteTqL` z|E%z4nP?jaTtK}HdhB68^@lnd3!GWDu-$RGi@vm<((upjzF_F_Kr9~B)HPR38NNw> zr{d;go?(`|AD(H4$(@fTEY=JkA~OOsKT zZn(R;T4UEE^vWNkk3Wy;|RXbKU=iDi1Xsz`+*N=#(eUzpGZ_4!_NhQM7v; zMTXC`$A55-iPin>N4bEuIWO`3YOy#t%0za#Uo>+tG-8BeA#pDm{GAvs;;a zd1DtDb?Iesnem%nLDl|boYD39z8{auQC~r3{8^iWcxQtenm)Ky9N&m!87g&^OTvY#$0VOPUk%DT z8EX{*GNAQ0pDaqzU7qF0LG3|UtkicH_r>MgOQPa>ggCyH{l8=I&E@f4^(D^yk+uK5 zOOZ3P^e3U3XS5UGm7y9JCvR8b&Lg=VD*S0 zy|*yFzrclK7fZ4oPca_psAxdq8EL6sN#yC`j(EMbtr`Ag+q2t`XDnMU2FQdzWPPSG z!aJ@2&EZ^*%_ll!iOj&Yp$u#1qEC1&i;Ks?Iw^j;L9gjBms|7pnrFPwCox24o5T9P zO&`a-dEGfghrL67Y%yX&zyHeF_O+s{eKRt8dUsO6HY|u+$xvgM>$&Er%PocRfeRnY zxtd9g8=ny0M{_LO-RtMDytSiC`5vziOHi)_KrMRmOxSvVE>g(8YU|18t2rDw#s1+3gDqAj zI8*lGa!W@>D^m2zpYv2&L3LWQQ#dq^fkhcZy+hHI7rw*_ViElCi# zH?U~aXG1_B0%&Ao_c>)L;)H|9f^>Wcsl2$r>Y`Xr#yvB+aG!d3`RZ5b)`lE2jSDvy$_cZ8neMC=x>XX7gj8j9} zQNh8W-hUWln}^M55`M^9&m2fw-kQBsO97kdnlL$gk4 z&+gyJCV%fxjT$0*?9*UtPhIN$kP|v*y>Q)fC6Rm>8u#tcG=t_GuY)|63b$nvdfqds zT=y-tUN?ET;#2H1A_hI&bz(6?Y+bA(f#-kjDQ$@inQ>LQZ5ghP;76{$B+K%%su_^A zc=ZLa%MqZ-+$WB-qIgp8aZZfOPa|8{G-9r85?zSxXYa-MjO$zPG+ZyY8t zwch=v^*%>tGcMn!gVCBAmpO*!emweJ1}BgErh7xZuDUMP>$E87QDh>PF`lg5e5C9N zA(7e2_pxP06QVxyc?c^+fbD496I2R)yAJ%8@aqALl! zYJkd>OzX>|x%v&x-93Wc626C!Qtiq3%p8MQ5BM{DbsUruKI!8Z91nN#)vh7^q$*Vz zv@fe1XGP)uk=qcF<+k7Ii-GBEuT|kDHtC+*rdhl%w&)+eo5_5jL_u85=*=MCa-<%% z91F>|_IHS?XPT#t{-uF!nK(+!8C%+7QmfOOOy|Lg@Wr$Z9z~GF$7NtC4!v*v`(f@^ zNfaEbTt=j71y{vJS!k4ej2#)Hccj*-9Z*xDEsR|sEiJc&n3u`?rV9|~{+e_obewLu z!y9V9!V0NYVeEy>T9B@nHg{R5cPF>_U@Ile9$|ndA5;I3z8_Uu=F|)>E9;Dmumy%0 z2qGus!ZrDFS&N1_FC2C}gMqd?kk1TX+260nFcwPI(;;))x#hFmo!R`w9c}IbE!d;z z$A1xrNabu?LeSSw9IpzIixH`yCGhd9dsYX(H&(oCQ`&)Gm>q=iUiFSILc)ux+lRvB z-q$kZ61#}Q3beg^TT&-k_D*BjR~@khYkP(Y$L$tXD06Raf~!+=+Nhe^N=@9!RU1{O zm%z(%`NyU@8NfI{krydm4*7q$S7rN5qfYRl0DMl z3Meq?S)JyW6z@R_Fd$G{q%T~TNNCc1LrX?$X~Re%)?MWU=;yyryw+N!B$f|k zdz0)N-(eQ|hqJtdtj28DK$xxoNKZD`Y!1ZrPGpk4Nd^_(`6}8HwKh&7={X-Amn>b& z^mTQ~2dsz&Z~DN!i8+2E#gr5tU>$@hYik4#B=0LQ{X1C$ejmvPl6m#JcbQVr+f=~9 z!GVan2~9j^%=lRZ;<()pNs;*Mz$^Y(_rQQ+E1&Yvh=vBeE>-hYWg)(~T=OgTIbrt} zG+c-NmxlJBhz7X4?-l$NR5J=~M^g+r*TK^yctWKS5pBmz_+f@&f_E*DK!|iWZzN-H z^~+eUe&$DW5uqTVQtgtZgofUWqCb$ROp3676UD0EV%X??C{jqUS@`4cGpAiWb^~HA zLF`BlKuCL*WneO)Jv1%`y)5TTZx$P`12^OVVXH_%!B$=3IGw>tx+g96hv}>*l;dkPu2WOC`Tn7?nSDv3w2hwL@r4kQ*lCymD zvn}0Qe8wAD{jL6@-RqtYOCh&b(yEQu-YUv*F$hM{pCYoEqO*ioC|GHikfw%B{@EmB zll}gpAUW!1G+Hb=nai=dW5_bL_@qqOUAs8ayKWxdirUgnSg%ue8uncF{uiwH^Ohmr zPb>xhd+5^ALr)qF|J!-?aRcmjRK|kh&*q{Z!MLE$H7*}>8;Z5%tv{5zz=In4cvz_! zg08KbNGmzTcIapr;CO2BL?F+n5PGpQqMzEGR4Fq5_P)i60uqdD1L{ZGDO2FboB%F+ zFFw<3x$C#5S=n~`#R7!4OYZrUpuB%jBnRbrW8PiXGBx0gUEgbMV=W-sN@cZ(%V76t z2v=|Gb&ZOuD(j05HM|7!EdY|7VdF#Fe!g3&l7MIoE1_1ETT;c(6OK%SEdI|60D964 z%*(|!{}^$BPqJwo0lP2o#=1HyOklk2`sDwJ5SO|VlcM(+DAbmWwncCboxk@(d=C;I ze$TC@wyE6ZYfp*E?L%~I35Vd=tb$l?qPhh)5(4V6va(Tpvfy{8UT>&8&Yk}?a=@d2 zJ*onf)HQdf$CVBls4Bde{y5YtYppA)IoKt&7``oA9=~5-Vv@vFi2EMUOrqNoIR&hP zwDm&;6G*n?0Ko?PxbWZeyzD(=4&CJ6r>0MPS3sQ%4pbqZi>FMzSd9J$RY|sW8BCi) ztELi5mvL!UV-BS9>WSv{jckNAWM_eIC6<(H7iw9;vyANYe(i9o%J5JV^Cp@1#l!=` zjHEcJLRh?2c(P3sHWm(%Kp80)U4a0SQSY8gj$Zx;G%jX)f_{nTozME7mkW!eBj}kP zv)hxW_T4mNZ=<-Zp66t-D;NXbC@+?|1P^3%P&4={X%#=AJs@8%r6qo~x|if$_#*V2 zV13I$XYB_eUditWBdnr>{SCH1o0p95BH!?{g4@%z#bAOW)K}NNBxSl{kVjx*%Wowi z@rLckYN3~rl2A$2JmoyqyekQ(9%|PvqMu8uKga3%{)Mo=glz=GnDlPk8%M&TZWn2w z4A}PgDztCxDehtQ+e9Nl*g5oV3Zy=!P+ipu)jT*WRFc;;G8?rX(_3HBmC+JHGb8`& z4yJKq)fa+?qa%#XGeI=mfPaetFGUj{ooN%JOjM#TTpZr{DRSEyPElsuW1|+Nyif=8 zd{x4<^OS3JhcLwEMwy|jckPGq#Hz4*?T2Z0NA+NeH1QqrQmKdmI^sEL>HPRfCdKFW zqt8+hO4WYR&#AGBB+wOhF8!X{Z7+;vX^Jmii3zW)o11){KiiTmH#eC6NZw~94hU{0 zE+=uIp?}1|{*phd+@?Cny5|;#Fk)S`RgP1vt49DXu4+r!d;vG4EYMKGS zXWqwDf)~zIyI|WlG)@&n?`cuB)B_3c%cKoENAa}Yx)2QJvz!{iNJevqDe{-;|I z2;v7t@V=3E`92kxhCDfK4-9VHf_)PIgiD8t`BNxWPww#BQ$D@6pRRZa{y5$iWRy1< zJuhI)kG#HcpfkH8Mm`L$N(NG=7xebv__k5~QDkj4dzI#}*@a((OUEIJ!hl0#z6{x# zuXzIY6cR24F(8ALpGBem$9_1|dn$s;eNB7j(qdIwu33bA6Ecn(m1jX+pG#DJoUdO| z)%o?}a;`qC3kAe-cQGU*UUlIK?hG>c2%s*R*IWJ(3xaf5bbK@DqlW{Wu?H{c_JV-XB5Lihbs820&@DoFSOJ9 z%WyC_qz@{Gdw&@7-63`Qj^Ot*r-{dVNG%>61IiX<@BK-(-#Z^W|6u+Q>Z&Z&;}{U< zo4mj@LVX8s8X_1IQo-8lO|W`$K3%EgfxJ=Z{o611d(OWmWd{7j+f|4LF~W^a_-d5O-oCm|B7_JDA~*xxr)!j1ndU7=FBu|AY&Ue zq>?Y}MpZnY@-RKLK?8gO)A+nV_7b2;;$dayNU66;R>$R%GC#edf>0y2-aJqoL86#} zOv|(VQu zxEO?TUAE8c7@zpsd(SxkbfL1Kt=WW{r}ynLh&tQ2U(YE@23G5?j@oev$jI}gnL!2k1mYc*w5a|28Tt&+!E4DO<^6e-;c3CBxb zWf8OStcgwY@}MreysI!%KE9qbaWUFx*T{O7dI@~9iQxR(1gHxqhx(oOfLCWLgsRvk z+BoffqtyM{&0M8@?ajS1Qt|xyuF?$q()Q{7Iv^z}(A=_PO}ZyYRvWqM%~*(>w^4Q| zS(|^y_r}cUG4y|7gY^4co?m30yg3`W&no24e^gI*fktSy6M@D}oO!Nsr&K+n7+oO2 z6v%U(6W^`qT?2Y#1U0y-@-Xmz`$Hfhc8K`^?Kn<4tcs2hTJp|tow!pskfnFzP8}-@ zL}J|eo9EK?PCOBu(Qy*xtF2wFGfA7vi&43m*)w;@uI$C(KlZK zN?wgqSqo=`edHcx9u9ijFvVHNJeod_Fv3c!`*;XX-rPTR$Zxkh&YYU=iR+&Py|&N=k(v$BRv4+db1J zNpiAZg~h^b5ZVcjm?-#PU?xbnbO2j7yO(0g46`e-gT#ChjjN!#nRb(!Isxyv2gmIA z6^!fk-z?EF*_53%qWr%cE@8~OQ7YyZjs zs6L<6uEWu9>!XFtw0skXEXSz#3ivwota|*PeoM(|u}s`RcoU})*}PyUNqw$O#oJOO zjd~d(Ddn*4`-I|3p6wMS&^R*)E){{ZTe1n*GM})ZdM95@SKHd;0|eA;2|ux)LAdD| zZEW7vzuph)$94LWKn=(P<;6L-hQjHS&u{MZZ@Q3)PLGSYJ^n9(b0TW_EF1k?kjyRm zU7mXsIaaD05gouF6L{+^GcA=Ab}h12O5Uw5GJ=fYK6)czoU_W%dFkWOD91aykau>m zk)BvM-qmjKn$Z%|J~!g|nPW*y=^PpL)1a{yuDQ3dY+8{ry#Ts<5zDr%h?u@GWiO&K z;2i5W&x*>cF=?f*JmCtndKE2=U z0M@%N(OZO4qrAmIX#s3sl{w-yAPS^YDPV=*qa5)B6fMBE0C?wJ#i5dt6lm6gpc!X$ z{M#;gjH!kkufL__-*BhUX9A zhB7VqnyfwBJc~t1#?zl2XU!<9jzcjkfF^nRav_*-Oo~nx8RgL_twSXOQ*|T$FnNxHX6vRvdAXfd#aEyI&;buOK`CJ>f1#;iXT@M9{1L zBD=oi>%i-PAV!`yoUA_Z%YJ{X+&2eQfB;Sw*x3Ba+^2MOiVW5$5w>6hh@NvxPJ{_b z+UN5_s9LCV&6BFf$Q)ij*Tec@3@Vu*nP4aeum%rIb(-)}B%#+-!S`7{O0doGy=3NW zV9f=l^a_H8tFc58c)R6f_9eTs4xa<{YhUE2=6xF6jteVm%y_+^aCm2~7w+3GZwHC> zA6bVlKN8jv{&jT~&WKD*{ThQlKyLFNHb*>J^ZXe%Ps_Cs+?TOGGItGo2THD2k41k& zLnYctwM%eIDWn0n0W>ahTWkUqBEBv&5bO>z+8ORu$9?)UH~~#2nR_=|6O*c^~rFd`KcUo6K~XR8nE4;yO`|;O&)6N}=MK!k6W|c9hKCCV95YPuA%7ix#!=bVuvf4xW8 z{a)lXTd#0)ipq>k`QiOx<+xE7wuVoxEUxnWS#cn;UThCD(gbqQg+R^X6L z(wE0T)rKmm1`N}IwR5nCLR`LI;J-6ncD!A`P!vPC{%2QM2M+IwhzU4U>Ob2(tp?os zKTlYL#rk8&>w6#(KVUzR5n}`p5=t3(Av~`?QU51mc$TL>s7`<6^88*;X8i&-;I+)W z&*27KvM1-{20#DtY>7^K`3PQ|p^11~3=jn8sUk(7{4^O>t9ov?0U0AyX8s)otK-Sz)87XL^`QH3Ra zo7?w5Jb!-ljw;VW!MFTW??Sh-buhssYQZKll^)2|&Idg((&z(cHZ~h<_MNj$}6@2~Zv*B%%<9COD;S;h95kr0W}tKfnwCh08WA zKfkz5x#F*+=#+6W*@+Z0*b>wMu|2ne0z3}<9m4Oa0oBd~|HX30DJficmrqSn1<&OM z7%a>3c*zXjhH}^$ArpPeER0^n{Joyb_zV7bESo;kzaLWEu30OEE&|0wqT{ynAH0FX z(seSRi;_;ymD5e4Wbhj)wjrbMr6*S9JNb~L_}h)F>@-fI^DG~=53Hp`{D$h~;_LUc z=~bc9-p1X!^wOnM)(<^!gefs>3{2p<;ty#>Q1Q9Dl=YGrR@;Z5KOq_uK3<8TIiSe3 zd}{}aXW0Uv^v2h7OLvxq04sh;r`Uf1RmbZ;K__F^df`32SCjcV*S1IR|6Y!;!)T{Y+pbLNKwn*x-+NznnZP0so; zta_q2mnRg2*#qc4g(+{bQJ+TO(=v_fDg^92EUhBaA|cSiQXz-*?pvW4Sf!v*6V zSF&SGPPD}&kZGL80~fuocrI&rPj#PtJjFajaN*9&o?WwL2d{|ar_A#VsShJ^*7!GG zo+m|4Rm&jkrX3o#irnuY^DASTvke|)6%qX^<&-P)9{cs$jTR|d8gVUR+y(eCw`CFW z8QXUrO@!~R406r%k6oX7!Wi07{#|lcs#rojg@G-N^O;KGik;1u?*CuO9&F`+dP^aA z;C2aLw%6-ZfFw(rR^3roA-gYX=b-n2bqX|2r&>?Sfz^2papU_p;=(u_`q}sI-0EC- z-yC~0BlG*6K4~ZQqI;@XH~;)uky}UibL@AbusDhEngBOP4NhnNgfr@)Q?57zOaQqj zV9mY!?2iq+6jau`(VN6^zS19htF3~4yhV1y1I)X`b;ZBr2DPWem>b4y9$78LEN zWv2cn`Zs-4`q52g>DbvB$wT*HRg`3|o0E03e}u^=iV`G_??Nz38mSPJN~L zK@*M6Bp@12FOlEkBe{~O8~tFeo^!#xpM&qc(W5xPK+Y9G{=wqAjlx8Sin?4$^s(`< zmDWq-NpI`ZpC^t5tpEgjiF`TboQaFT-G=eqc598n;(;nP)dW$f=4WKQCY7xyk1Qk| zt{O6an)Wty{DEpV0}IH4DlS5Wil6}X0sbIC1!Pg)v<6AF6cjKsj)-U+(9z<$ znmBjeDxyk)OAfHjWo5Jldv>meb&PfAn%KK1kPyIplt@cQd-u074x4*c~>b$}s zg&WV9o!7B&PD@NGX??qwt-Ik>k5^|v^lQjr4T>HFTKk?JExvq?a2QM8bE77FZ@-uS z>xg)(23s)`LvF5}zey`jgwL*n!`|tIhN{AIo+4zCAwx$i;44-f6x0$vqH?&{olO7d zA@7dwPw$I{@V0CdYY zd6BO`sN=ZmyaK5HO9#nC%eEJXWmN&BJ6~#7znJ8CKLd&)U*h+Cu4+2Z*QN%5gYZWx zh|X0`NIFJn45MC>c3HAM94{70%j83Z#l&?6|MzKhn=BzdqoQ2%am3~AenD`Exo^(x z%0!Oll-bnf_0!K@&aZoGylCGz=4m<_^u`arSmb(xHTc@t!2jB@^UGJZWqqGTF7}%C zo_jU(lG#*5&)c34(waI%VwausH0iiIih3*bD30g6N!Ohc|C-aZeeGl^Hs-vQzdgE< ze{vmGw0#jW%;6VU2|gY(wp0!25SZxBsg%Y}DXTNR#SST}e@7H~ytvxu&U}q^{6IMw z^@0ip!M$6ghQv-1BMBmU>n~PCSDRFAXra7M$-^xbR?aG9XCopaAex3su<8JctEat! z#Dv9TAtguzwNl*E{>e}e7?O_q?0Z1JA_7889PA{Ib$n7a?_Wt%pZVkA)vUqcy>6T1 z3YdY1dreo?@78uL&4PZjJWK;r2q(3rsm?{1X_jurp6Yg6bUPz-qGqJ8yf3g93xBubQ*$2Y1zh3JQ~J1W_)j&Ux4m@&E z|3)KTy?jw|{GLY;7z*vmF|9#bNK?&$I2x&GkfL7k)_&=1?lMY!B#WaLz&UPdE!LeT z=qW}TH|9p2_fP9y`Kpa=#vqGRJh5c*A zu#wx3-ur_RvWvbKFerELZa^&Sxf$$o%2(jEew7IvLr>tAF72?+%Aoi#X@2o@3fWNN ztVag?e#9JeoZi_?NTVFhtG!bE9@-@X)_S(n#jr}B4u;!``gaL94-*4kW-V_sPP7Yp zA6hst;XCyd80Z7DTo3z<4c|NWKySN0segSI;tm^WT^>Cpo^>D=>2^}bs-wg_HGvzR ztL`hQM7X zj1AnyJo{ia#`@Qfiak#LUN~P*i>tj#B+4TO;}`7q>7b>LghZCD(*q@3P%?(A0g83gQqXzM`bB2Hyb)H0 zQ@eer`U1{=jtul)I={eAE9COypR@aiq9|W$6MOI5sJJXw8-(@Eeds%pS-7+qVpwdB zG45P?IlQpo%}X++u4DLNyK-4XxW2}DG%|a*voB`fr!w1yhM1-xwem0 zJ>uB~3A{$d5c6*k&WZIiPhoI}1cR+HB8|zjYi_X=2SnBNN)pwmLG_qEP9V=iE?7n8 zW`oqP?c;>zjRfyqx7p1=3Dk0a5c7~u<$BZD7tK$2N7a%-#dPut6XQ->&;0*UkT^*s z@nwTYB|M2d6js?KA@Vi|Q)<2HZ?-D!;flMedjC9v7o+8ruD@!ae|M!wpd&WAz9Nr0 zT2ZDt8gasmyGpsmp+TmfA4SoAzg>q z2A(NdxqkihoGsf^QDk|cex*_lmxn>~TdlsGF1c2O5OxKp;Rwbi5dQlGiXP2{+84Mqv0s`o;R_x zhw@o|wsC{W*@j@vuai7|T_#%tKnY+Srdt(%|HM50elAn|z9*g~dO$h4f>N&)@zaOi zkce={J)O1_i;F)~WU zNfMj*5!H>Ayy8Md|G=0r~4bsEc-WXDu&5fJcLg>HF0Q*NKgAc;K+W}_vQrGfOo3f(?_vxY&|)k zP6KS;3A9?-hc?&keWN@h{kS@>G-;BdT{85vWJi?%64SZ^2enJK>~tz4++!1x^qUxY zFi&Z|*b$Kj-`_7)SnyA?DlT4tz_dwT3iR!lM56~CI*)oFFZZ$Jr^zDHpp;vAr66WH z7X&}ub;n-AWODt(#rYp1N8htNV`QM}G+1q*6;Bv>^kRuiM8v4qiPKxQA zcBJyulHi8)szm@SRVG{LW9?X=9+T2wMBcVZ;-X{aD%JC}IG_1U>q;xIFza+slBDXj z*uG%C8DnSb`(Gda&nzw-** z$jTH*bXvU>Fioy5)neD}gHPpZ9yE*^5Rm>H2Pm*C8Dam6j&izI6jRp>DQaD|-r?Ou-Y|!{K6#I2_mTY{UHY;^UI7+yv=d0#Q@!Mm? zy6cm6D723x3vTOYQ*U$QH^O=z428$jCl~}P0po?YY%TXM(+bKl9f367AHlSReACYH ziubDG5}J3-{TGxSFs9b=LIHo3v`FrkH`-v*O_Rxxn74sZXSeq{W6)Mx$5lR(FCSL_ zxR4GZ$KbB(K#RmB8{{o=t4NIY#APz`JQ+NUAe>eV-@LzDIh){IRSSUq|892^SDwD@ zbGD^4n<~28jaN*qmBM&A0t3|2E)Ssq9wTV|MVVx@VM3;4kj$#G|0sF>G_*c-ow0x= zx|Z_~nUe)(?nbzX@6&7>emDukw!lPlc5p*-iG~lkK@FP=LQWSNcw=m@Q21#<7m6fv z%F8ne<(TtX*;q4Jt*sZRVbyN7mU{JwcO)Ryq{`SI6{fEq&dfnE# z6sjZbvad(E)ZMFibaYRF+yy6$l^C70dEy#wby!iFpl<%{ha>e-fo5K-2Q@f2q$bUw zWOAjyzk>LJmN8c>J*(dy z;K){V@Gt>`$B@&O-(DJade*FJcLqY5@VxGzi>=h++31|0;&iO@9@ujn1KWiUAZz#)smcXqFQW9zRJ6ovb z-!iPjeDf|*#s5wg0gW$ReX(;N+9j))54@Tdx zp0{jy&6rMiJi(O%lLr&1SOTYj3Q(!T1xZjAq@ezh+uDP^cc1sN!~J^cs@|o8aULT* zd&{h;5bOHX1u6AFWF;S0PrQ8wbofSudpD8%qV)dSX-UENPPv6Ej$Qw$FgFpIq4J*$ zgFbdY>1)k)s@4C!;sOqucbqbMV9Te1l8q92%94km>*Z-*YPfT)Q44ek6x%cJS;j|kXcyT0in<)o*O?5b3^2Sj?_o9j5Jmpj$Jy1 zu9P_SK5BJ~uEJ&9^cuDNMguDPn8n7`@*lvQtU;HQW@8<~-zdDZ`g* zjBx(7XSeMsY`x)O{XUBf$!FdAcs+7+xp*29Am=dbbXHiT-NlCIEItS~_s-c1+LCPy z<@7r~?AWt_s4S%^2+so%^NA-8nbD}omG`*V_h;gSzerr%jEZ&|9x!jkbdN_CCN7zm z5@|s4sfj(`n~x);38a}|ky7MI>!-@yZ?h}rHx%8NwXZS%2P9b9K0j}(sVByGnZUdA zeh29K5?A>O9T)4zpS+*=`uMu;fIlzU``;t?-Se()H-tN|9mc6c!>!Zb^}1#a%Tkpn zt&;>K9iGdHboZ=3TFm@C59|}%o(p?!#81R^2-h>w{Ctd5M30RN-$-+6`6F^G@eQdc zejKslzy0p%i=3#c|4CShb{MTZ&~BX{|N1jBT>ul@DJg)Jb_fs)oy|Gk+*?F~615RQ zG-2qB4~FXr#{q>hIZ3iOQ_<8Sh4)sJ`cGB8g2D2X;nzeo&dK*gg92f{Bnu-7X?) zi(GIaTJZ&3O7C4Bs5*ivD<^A-=0%y$&B5AoBlF^_Fo>{_p!Rjnd6V zN_ULWDbh%a64H%yGo(R!fT(l|N_Qh6F$PEq(nw7}BnMJb_r>S?|2??(lz3g+uIqgs z=Mm@m*@^P8pB&~7o`++W@!G0mkFmW@2mvn)$XWFL9G;7Tb!RG<`_S7@S*5KTGj5!O zjP$|MAkznDoY_2Y;9XsAXFH$K0~S`Xh|s}#fkV)SDy39hJj{Uy&AO~a(GmU{x*|R= zG$F}WOpl}g7oIHR`2 z=lzmErRYB=JPuCzBz;Do%O4?uXQ~w_O&HkIs{W&x@b~G zCP>^hyZm$OXx097;xKd3*3*&V=Y*lt77&QSuGK$sM?4#ZxeH5R}rr15Jo;_oA z92ppeW?-%LKPKE@@o5WNG>}ane?o=(;tLg!#7PX_##P8p9q^cXHEyO?&4H(YyYjA| zYlL>*2fO{wJ}rA+vTC3#@0N;rcj9n*g3=Y*)*@;{dOjB_U0kObM#dm8(RdxP67Yn|jZ1N{bk(aQ`B$_p9E5})eZhix2hEq%-$t4G zMH33{Sm(nS@ok4z2XZ_`;0&_kVZ`m5uQmaRRkNSJ_=XObBB z@YWq4e~fq0JgI7E%vb?1o?5bSzZbB!9177!zQUU}%XG-sSGj(7fTju+PYWzF;bkq=RQx%tvq6 zB%t|Qx^j6ZepR)nccEM(cYD&A&T!Oxcm1a=Vsvm&Q8_ZAbs^hb&g7^4tGpOHQRoCU zGlkhc{fllJN$8u=&^0ppba}psta6LkcH*%2E zt4_kUtqAa?(2T$Dzl=M<-Nrub=~z9$&OZ;kjX_`k)w0kj{Sq4<-mCQ=&F23k6yjb8 ziEU}lFvKSIS$JgZL6S2q5Fi5@uAQ9JFP0oh@@iSna=a*6ahzJ|u>+!!wBpi8PBU?p z*t(tP2LYrH{(FIB0iLlDFTmQ&2%rvi0ct=*V%7;(azR)Jkd0w`BhnebRXzWZ)RQv8 zdN$L&=&sm&JGORWVxpz+{Zh^9onoaFl8fV()S_YYF50ZSCHP}k`hR8pLlLh4VqGy_ ztlzALc{B+R)7;?s=ZT>UdEruio7xiA7<%3`C}N$Xu;IR2WQ_?Q=P@o06VCW5c~nD9 zZd&jMhV{R}<}Nqjz77bfHU&3S7m zb)DfM#fn^Mnd$(A0&z49SoO<_|2MyHMmmY?d?S$|7Ksj<`lwjcaet(L6t<7UCF;AN zy#J7M8M+CAnTlT`wWBojK35HYDbk~la~&)U05Bm6=YeUz+^37c0R&wv zkM)Ni-F=eWSZwi;hEjXnd5#^=e3Z@K&#SZ9#_fvyg>BJwKflyXOv2qTMmMIMZ>!sZcmu#jEt%9_1REq$7aWofjh%W8u7W+ zwEFC5>@_hc!IXtoljbEz0lO$t2#;x_x$j>l_f}?a$9pQWe*WbHzp^LB7#(y5~#f|uVwQx$p4r0f|44Igc zCib$?(uXgwcu^xcBB9sI28r;x^5&9%AjqP!K_=KGkS$M{;hwacLPR_87ipLMitBwJ zx%d`+bZizRHDJw@ky9Zy7_AaF0HVbd+yKMV9Dbw=uGQ|y&mDRa(dK;rm7pMv)Ksft z;6`ue-wRex#)2Ps$q7%ux%C9lR@{g`zRc%WC*@&Sw_r&|V@ITSYy2vc?k~Bt`vUe} zTOOGa9)LX)d6=PAB{);hu|cnT%~hw4)Quf%^C@)sadUX_aIM;y=Hx2qz`(d#7kky+ z)$U1HJk-DajyL2XD!n0Y4D>rBKs7X4L~X0?rSRaIgy1rWX|O4DIQ4Z212blK6y#x> z4AsU`h_}G8vV4vfRr=OK*y-yad4R8H|1lc8rizF~JL@nZVTE1_X*>LV%Z%%dU=!JN zthPD%M6O^c9N{r%+@q%ktOaLHjxOD=r35=mwv_|VgkC>wyHrxkgjhMy{(ow^*0j()NBdM9o#}7bgM;HL}&y)e%!+o?brlhV;n)krzd;$`R=^( zVQ+UIO8SF#$3Im&)V~-a535>oe)covB+d@a0eRqhhWk;X1Br(}J7~K*4(goY@1yn7 zrSjDkZq(((S#fqMa3Uk8^-Uq%+x8GJTn~V-j%DK zGK}1sn!h^H@|=<^oYFQGgp@>_Bi8TOIESxH^TH)&=~6E&zK+8rEb;@nkcKDnht&{U z$EvLAM%6l(!r7z*UNLQwxl7fxjLiD6=-4O7uKy%Lx50M;l{O5*D-R)p?)g!WafD*NNETyW=SzLwLA zMn87qpDF*{v4c4JG?v*b@m8aZ{HdYB$__(OF?x8|X2{bgiLEbX7C+=ya z&>ggq_4!RkKP9E$Uxb*T4u^fcLBHOAf4YE;2-;7Xb6ibg3OcF@=vp^sOF^B^aqU*q zX5sal+kWU}k17X2*+s}8olH$e;TfJLLa-GtCz5}Eu(AHdY;1q{Xr6lzBZ-aDLV)oc zAB^`@GW#FB#%uj1fg^@afNSe~ND@z-)19p!f9y5FnFxPs+J1uVak4e+ zJ3;jS3i>sb;Vu(2J$q!6?|4tBJbC;1R*9JOgkPZMQPOeTjhdx4ODkKvsPJMdSo(SYN2G`G&@+OD>0f7)-$69?u z9CfL5e)!o%QSV5^z5_ql^@K&?*7DIAxs8Tp;v5M(&^islufpRUmQAuvVI+)PH;5RwK8m`0+G>&S-F+&~WTNuS0$jd8LBnzc! z_*l(IrFCou^@e?7J(u9$eTSp7$5dsshAy~A>&Eba)qu49y~7(^BBJgdCn-<)qbOgG zAA(i0G7&-Hd>oo72^08z()&C-sVB41vTs_)eXUIp7TSJVJNHU2B*Tq@nR}wKIi!6* z$Jw`@FaND%hY(^V{e^QUs%`{PG$mWPmk5$6E%b~KB`j;r(Y3w|!ax3)GxMOF?XA9E#fXZ|JG67h^RyWnqJU}3#}I_SgxaoCea znAjt)u&eMxJtJCT%>?1#GrvbCgBKOysh^~SzeTvk;vKbE`=Z~bN+X~i`Pq+d zL)0faexQf7b9df9{sl{HnzmlXfs4;Q5%f>oNK$ZaNG9f0k73k{8Z^Gd`!Bv8ixc;F zFm+Vv7xo+`OD|gwwwifp!GX`>5^tK{eA`PTMU<@7S40%ab(QGEZT_E&FRWjmWGyT# z0}C<3O(F@@g1Hz`f>qzS$Q5w@Fxu`Um<4$k+O`2|ZT3LHDCPcFfX4SYKbHptlh}Ea zbVugH!w`<*GSw4~S%i(2PU-3R|G=~c_^`)bB``mvMB)6N=FMer$J9LPzB`l!JpV#+%FCjw2kcUP|2{YTJ;?qw0~E;*CRW zF}(JBVVR*u;v!%zFH*DD=rC#C65j?G0PmqKN-=haMVTaiZy=Zhb|24SY-4$_8Eza+ zT4kEz`Z8PQ{*H3EX7l98*K=tE>uSjU0W}*y1I2$2%1Rxn8RP zX4UiHc}Q7|!Kb4OogKG!%;Qm<)lyO>%HG)b2U76+xx2m`=5e9K`Noj0l>2s*%HB{C z!9Or}wgl(Z8Qit)gR{MJ%#WxC!(Nc&R7EG*6D~|y+Ab&K(e*G`iF{{Wb;Y&0bCgA6qmtdu0K6sd80V$CSd(lan0 zGmSv`2D)((8QIZv)oqwJtK_wAO-5blTCaY%_#0WE_dp zPBhuY?w-DNJ@J`eI+`_Tk+$|vA8#}d0q-_wj`=^irranv^48zgT4wgYIP^94iJw!J zI);01_)T5lNmru`4yA>YYzIsBwR}hEi(lWJ7sOhrjaqwDco&8e|Mr6^9QHy-FXWE& zY}ryu+~msa1}Z`H#8B~H!n4u!-r!x3tv!68V;r6aBHRxZF&mgcrEQTCsl@M`$V|sf8Kgoj5)r1nbXUC}ICx0Wc~ZetjOjsK-dm_x)XP9;_I(X> zTI1wtMt8>iiG^Bq4_gsf!wgRJB1dw>jf9_LD_zr#Iucpof`7%1%N_HvS;rde z3vNh-$=focN2)e?KRg0bR$fsvsFfDJD8^7PF__F!RlKpLo4(9vBzvoFlU#3p(9-4g zimIN2rL|45PJW2*EML%j+sCOA>ZIzr-&XSr34`Q0$NX1HfqR$n{zyT-YuFz6G#>UX2Mb=q##r=8Yo2stcn>GW(^@1?r5RG3tg7j)`SYvZiAj zjkE>9;4=6I(Dp;)5Yi+4Ub%Ie1GDaVl2YlK{QD4)C*Zg=(*lna*?BXbZ}wy7_#)xMY* z5vJ-?R=8i$(BsHdB{QcU4`)d%QARe=HF|M|`N5jx=pim=vs9<4RO7v$)}g{*l)TO# zyptGVi0ai>BvhrMrR}FY^nZYQ7vDcg!U@vu!9-a2z?P_qInT&!GR*w3mXxe5xW27l zYzxb3Dh&qJ35|w!gSS~$P=wTZ@e(Po@Wib;<6xK<9qpaQUnX1pw=@6cwb>LK`MIY*sP;NsKrFDI)m)1&_tsU$HMC5o<2M| zryn^cK#|>UnpF733C0j5r-QeugKFxcy5f0+haad*NI%fi?xl>3&#~&H^pIl#yn|e8 z1jrl+Q-%XWzVBME6C59K-UU7LVvrk{Kv_5gT%@C*=lq&RFR#sY_a1K$^qvR+I0)J? ztB>Hsmt%5P*mcirUIf13n(8|91BlNz*;y$gejp?4V&dCBbYX9e13d&MO0OWk!pJrn z-Kt-&;P_8~&0xY+%|PvS9khP9BKZp5TTC&cgt`p*vR&x`Sm0903O-zjC0STp`r zP}uNM^f7(-0ALKrO8`j&h=Ms4_PFkgtW6@GO+je>na-MJxImmxh6=2%bZ)uGxtdb; z8BM*=*{j0gv(vb7mT#w#^dT%`#636lpsx)4Hh6#sYZH;VP46p!q1r;{tLXL=FD0fp z*Q1W^V*PP&%}$I^r~Dwiee$1=xW%~3|IZ;S$uqFRk^Cq?r`;G3# z{K~!e=?e8vs%b3boK+V#FiP3u2PeLw3v5@wiM`H6s6_~^Km2*S67BK1(nQs$UW-$>*J56|S)-#} zwv1Z%QAsR4dW(pp_utEhk&wvzhyODXo(FmW1i^5;hs~wTT9GlF^q!#-*1Hk}K=qc2 z76-EG?evN=wijOhTkqw^w#B`iwBmG~u1M9^cd( zFswZh*41y(TM4)U=;#^H4TQUnMC;8fbiP0J%5&FQN)T3&y>@1tHd-GXO8}Q)L#N+R zeA5^{1_^4cb)_$d&{YMvpE~$jc#vmTG!1+|=Q@I(bOgz0`6oe@1m`y5yVSSvqW_>^?gH_1^Pi70d& zn&LeX=THZpRv$DbEBrjzF1D2!&wqVW{~V(OM+S2CXo3OBa3)IMaaiC;d_xhI<`4rX zWjTfj;+@&bver8bhme|kDSh^ii2?CJERe>7r`lq0FYhcXB#tb0R{bqXGI{2qK;r;^-|I9iF@5w^H>!T< z&b`abzDQrQ<8Yd}SadDtm85D{A?C@LSYfZS(&$G;- zytS0^s0LAaCu?;?wDEAxSY~+>jXEV?0eEXA6`kk5$XMw!^n29ty~!3L8GMGk%vG}? z6txGBmcmARJ8u1E-g}cdQHf&VGt3_*ggC6+;U+nVYVJwYPcWQm>}AX|i_^WbzO&lr zVBiLNUb?jY1xRKhWDdd6a|v4=Ch3({tMW-|UZ=??lAkb$1qiM@(Ma-GhL!04Ani{2 zjPo_mw#g86=MBv2 zFQkJr!Rkfl82N_EYGbkg`WXm(tFXTG1G2ueH>{M;feVyA-U}mjLl#~|7~S~28H*%N zu9t_tPwJ|EAwRRj8W2k2##s>53x$i#O?;Gb_0JCEX^X}CFJ*x9mn)RgeoFmY_=QD04DfnoZx%O zBE8N0$mEghkwIxRGf9j?et3Az5wVCS?kaD}{5=|YeE00$v~+E0TU1+_Kq@ zfTxSc;z<}j@@3Sb6Euv;c`p)0uN!Xpc(V6D$b#M;q+)K8$p1aEfqfVlki>PpTHr|@ zdABG?NKOIg>LZDbQt1m1rz|adxyvq|wz)89!1y#gRw(`0XRR>a{&V1&aRo2}8}L?8 z*I~V7BQX4BqFrJ8ho?LB30Qc1?QAOUXU?C@FHi9?|7a(BJ$+QOx1JbTjmzZW`fKr) z3||Ti99oAY(cA-kZMTZjnOQW3E^xM$^*$N9heaGmB(l~&VD+Ipkl#TrI<=BV4d>A_$bKGA6rxcC8WW{ zvT08Yz2|0B#!$fAR6xHchEmsRdeaH>W>>|uWvJz`&6V|eKimUbq<wxy7#_3nXB-eYR0KXS?Wj!E+lcV&9xJ3c`|7DwFk=g@84hk1I@V; zjv1;KJ1@bcnp7XQ7eatPVKgx;M<@5Y_bQ~TRn^qCS{hf!l7a05{rwzkrBb~jY=iZX zIA*f}Z4)|$U2RWTSK1z}hc5D7qgK^Y$nR1E3X%vh+QFSanWN3TGo_7H2nd}2+EQ+3 zsO&Y|-!2kVFPyU(m~b4P1~+g#n;>3M68!5dx~I<+t^mo!2Byvr-8mc+utGcJHeX zf9%UB4T#qQ;08fH-fOMXv_xLG@+ZD3r|JiIrOKWgKnHtWVWX~U-JFhn60s8*#yBLs zxuGV?MuW=fQNWy_3+@)RNh$d4Pf+=SV;+b;M0Tf$NL4=xCb{Hv$50)JzKF3ycl3%F zYCQAsms*jYJc-*Ep#cZi^V_UG^{XoXFVivH?l78`xt|!17-%EKqDN~P%xYB0c!vAM zNBaLS=wcK;LCEWMvEBQ{e}?h?(5A4()3?M>9@P;J$lUx|1+IUA#5*AtHLG8Ec=BXN zc4=n!5j&q*KdUUX@|-PSIJWk~)?#tjia#CTz#aY0mI-jT+QO7x*?>B`1CvTFzu5iK z4O`vq$?2h|sHN}xNLCx0a*QmWOl-eLU=H4Cd^GgR;SRmUJ=jq@Ul=Dtq(}R=QJd%h zjOMsBP#6P|Pigppk8M(nV=r!-*;XI^Xd6bYUe;ZTloWMwP- zoUV(*L;D;TD&9sS)D)NT&j8-_NqL-}R+w!M76bN{!bZ8uDh*`8q=m+M_(1ezLRs~_ z)Iy{I0P32(^8hS=5Zjmh2muEwjlI->3Ho#^L*e){I#Kg%YP+VoKw*MFuKwDEcI=5y zey!lu>~xLGGwyz`EQY9uZCbsVzv(Hpkdz$-nmG`~BG9?Dl}tWMui&b>ZEK)kVTbv= zHHnO)UES65S}_2^vgp8h9+sqdq2N5--$$sdq}{NpG1MYj(PNs@Tk}eF{ZCxA(@iab zU;M~PGh)0kaZZ96Mz(C3KfxAf1f0Gz7f(Agxc;x zwa8_RScuFsF%6i?LA+1qUe}_Dp@LZ18z=6`#|k&EJU_VqGIDY{1949GeL!4d#jmDa z-_aYqf?6j`yC=WB2pQPMX9sN3K%aJ7HY@=2JQA8U;6$>MqhxEYqX#zjt`Aa{1ETkL zcW+AQ8OJh@Cb|T-!VIKlf8Z^4&s~H_>~spbGl>F?ne+@PLYuV;B2~YwOe8^a5F2NOsUxA29C;vVdV1r48P9; zPQ}09$$S`M7o4H|c~M3a;6v(##9$QO|KvRd0IB259k1xusTz1Ld2dBZZDnPResa69 zj_rLtS6Te?k+E*(SnoFTy%hj(-WV-6y>$G-l8?*#jnyz0uq4_iIQxD<+}T_=@z32> z|7SUS5&3Yl-E7iG>Rq36HF?`6d7|&RT2kMyyKB+&hEkOB$kFeVqaR}|6O zUAoF1;eDOC(x zT=vhP)Xl#7s-UyMa6MP>7X7BRxaAjMyOS{?FaqevMFYLhPsd=(VuJtk-2>5$`@Gf$ zmxw$|z0DBW0Z1!p<2Lx<%3=8p+UjYX=>Y(e%abd)*b|&E#I~N90quN=bj`sAq23)s z=BtgXE7Bw8a&f3SZF<#@A8?|4oRv8H)SwFLr{`~Q`qOF&^L?IBrH!{{;CbJD57AOc z9wPMRr=rRkv-SZjhX);fXVkSnghfE{5D`xAQ4mjtzKCj;B|>NjG8aTFJZ1F>!F_ip z)g)oB{^_A)xZ{sHQYR_~5mcF3HiJ{&dfo2S#$zZ6#H>ifOc{^l5zzxKXw4D5%whs; zi2&yF+w8fF30%#|1xt#ez>yvJQO=W>iC(7Ll#B_U+M)vtXAWXM?BelJKVPkU`S?t# zpP{5fcp46_86mvy_4GUXt7Y?pbc#>Jwv??$?h^pceP{k?63b3s z^`x}?fcEHtQmE|Y#`0Fpg5o`Lyxv!ty?*^stYph+kuuW`=P$?qtaME{);T86A|Yjv zDDm%U4!^*v8+CH-k?RR#Zx&?P5a|~%K%D^m)9q%Sj2r#1?Vp_StK=IWk1wm}wc30B zvs7+GZ8d;~`YDeVNq=C?Y(0|$&H6n3KT`x&O)r$c9KV8$Z$|6XimaIjNc+@l)%;C@ z)L`DnBVmP~qwxrX7gR#*1R{Z&j!ybJCvXb1h`s{pV>ru(vAB+OF z>14T!t6VWtNMn3D0lQhdwY&fd3Um2<9y1V-uI8#%Vf$2d-8oM+j=Cp};v^fM zmC;3DHSZdK{0P2lo_a$codqV7VB$O@cEf}YchzivTtAR7KtD&O#tFr>D{asxE0rK5 zB2?_jE18BQ-7BW9%uqo+__&os@xnXi4WTPItraWfve4O{dzHX z&K`C!$CQR)#G2o;-eKR~(ombs!^jh=19r!rHVed~OLi=TOfvvG(R3o?@jNHtbDPI8 z3>Ipg?ps-}-Y9iK$nXlVHPD(#i4JvSLlSYB-!~EzC_oOmO&2aC+kV2)-r-*{n2SRYisgc^7&;AEFMqP!LtPHC}oo^i-PaK{35u?@KONbJ*_-7&S1ac3P-De&?@T7f?svJM^v(L;dn1(A&`QgZc?jcoo}fWy>JMhx+% zu29=V1Pw!rbdfkojtE`3cH)gwK~9Be?^+_KJg%!43g6G~gWuooA^Vzom;IJ=@#9~W&o z-JaKYR9R~k+FSm$Mi{ z$e@!LnkI2@^z;bBDYk1<8&U#|&>2b}(!R<*d1SHKghr6JV~ z&gSY1u}vx73~dsB`bxg0_|>a%oc&DRDP+C&uh*N63$vzTbCJ&4EJ!T`5!3-|`e;^e zV#N5BARjBl`I+0#x52@7e|^mVF$*XJ9BtW4TSq=rgY=08`Ur3}fE{|hlb~LhHh4BA zQn`n3l8d&?+56g3d-Y_sf8<1p6a~eTlXP;_FPjS9_n!%2~nq6ey2l}5> zX!u&zLUTa=E|J=wR1EEGcE+95zn^F{-jNI+MD3BDD=n4$YzJ0d+g61&;vpQsyQ2k( zegm($z9~F)Tu6R|(hYF0n(7&qEH!;IOnbA`G_nK;?GTeEIP@*85@;f_I{#f`-g8us3T8LaZL@um+JYE@Qag+-9#|pU) zpy+N)okQ2K^M@Yq^!3V3@D%XI-?dE-ujN=rQh68Y>3zI(_&`o)_ZOVNd#czQ<1tR26hoYJ&)*@bc`5CGjoUMBYHLERtxIiUxx zYKm5Jc0;hqO*XYnJA<(EaV6^^S+c9_A6_+~zfay@z9Bp%v1>;{(UgWH8&#paG>`>WmmOb?fRBQpN>NA2CVHPo z%=Htv4FB!lT(#f8s;#$QxWF9Pw%0t<5#Szh+%y_a$r|orlLH^?@t4)#yCL_GJ0!r% z@d#c2LIkmWu;QsCZV~!Dzjt5>bg0g7oWx2O4k{v#d$`eEj_UxjihF>>Q2gs?#rfi-jB>)s&=j3?3kUB3oO}{yZ4sZ_08oG)66wb zAG~IQB_<7`Sp2WY92gH%JY1@lG6=T!B1%FYE z`m-BIXL}bec}R#GmHkR?ncKDv8yF5YIG+p3f10V?4Dxkl5(cYW;Tb%P$gw+FBot;! z9m&y{v+;-%^ddg^^~k)>4C}(oq$Z6igSI>a2vb*^2kBQVlzqBuz5?Mn5c z+;}77u?l-%r{|;s(BjtEXca>s8{Q4@hjC~T9r4WYbFt)4xmtD8R*AqKIu{#4q{H0j zS+9AD2^$}2V(S=AFpK&6to^swT<_n<2O?<&h-_sk;RyK$47TIBU)584quPmLgHM$2 z2G`=(1XE!^GT88MpTPmdJ&{N}d_evTvt za+=bViHu$oeeGwelW4yffLuWMU6vuLdlq1Qc;^`BA2t_FdsXM85-P-ALb@@Q2^d7t zm2gP~-37Ve;e_$#OK$B`*^{WaW)T^+eZ5Sh4|bo4x^<} z*4O8@tR#dHm0t6SAd)>~8Kf+^ou720>)p3sLeK1uggH%ececDEJYb;@^F3)`8}<`9 zL+SmSoE4kGUxSm~h(!*bf3#{xuD|Z%6VwVoh$@gu;d;0?kk=2xPiyMOBbsZBnWLNY zOjfC%J8>e7MoqbD6obF=XIxG9R#lerSbT=ho5Fn&#$O#47csm<#>6&h+6%zDlt_+p zJBmfdE#To4Mb2FGQWr0hjseQW6lnp5(VT_rs$;a4@|K|m0;%FgIBR|~h zv9b-&jsFt+<_(VSeFex!>lw#GRTL5#c02{V$l4hqDjN)g*4YRt7;CcQ+RW_==50hh zUOf^nc7y7ir|%L3zDz06oN|%zC%GIDVq3cWcva4PvOPW+GF<4vtTf3Te_nsgL6uT4 zTk0J~w}7$z(eQY}52_a~P4u?#URbZBS}s4zu2cRSIsh9>yYnJ|l&PeW^@?c@FJb#4och}>|C(F0oF{BPvx|yWEW06WhV*PF0wNAzwqN^WTw%l~cWweU7NniHdl1_c z1d|mh(w#EMtbUN;OtOyapn;3dR#!L6c+|22lFCiX;;@$GS%5DYcM9Sg14hR@%eM76 zL!fXqb{QB?f+ADg-z<>+Ce>cVP&=e_S1?k*VbH-ZP6BXX>kl7Qh6%}j2?HrYkJ_*t ztL9#U__UB-GL~QJ(!%3TuT)pn;LvADZ)TsGN(*5;tjw9`UzOU|_{kh_bMzbv4%W+FOt&D!ru(M!-92Jk)UlJ~Gnt<7m?GyIm&O*g2Jg%J&+0&uS3mq zLdzp!_h4Id6pDYh!qnxPa&pTZr1JT&~kv zFhQn_awCnGLF?%qjtlvPs6YJOle?|qLe|f}8NaQ$G(%Gm$2lHpuRVRNV#@|_h+Akq zAXXEcT4wK%yCZ4V?b$Npe{B?!@oA!;HbO1V=cFD~!!A)V0&+x3K{9qoa$_xh0%MOxhpf041I%(qU+zXN9KbRuy3W2Cv!V)sg1hf@}^1E~TCp92nNaa<*V zAY(R^iP@}GReZA5&pyKHdWnrc0`BG|RZ%1^;l%ds;u61MPreKik9^3ZUYFsNPt@P( z8w=Q)FDXPhr(BMRiESLyuW80ly+(ibrSbkl4RF!p1>{DVBhjCI+ex7Mr9GcpHO@pHB znH%xGu;woFzy7UEA{?Logg7X|Er#n?0skN72sf~a>oqX@(*Kd}mLz$$-5d7zU)68$ zNo`&GaQbN#^4_sez9%b)_J5;?yEJ6wa(NZlSh?MLt@1~~PB^e9*3K*{<4T_J8W&dB z7^z+UWc`_T1GiL7+pHA{89E7+F6ni9o?N*mPZmnTiT8=1QVx+WlPF5Y1;$` zw!pz{6z8g}*IUU_XTg*8e(6QLc^iG(+EmznJ-Td3*Q{w{&Hx+Zjo`*zA-tB%SJ8MI zsE_8gNBE!6MxD2L&g8Y9nR&>EDn`@fKuY-MR;F`OmUQ@|9j-h1V|&ZrF;f{j6CX_g z&lkR@Z5p0K?|TXl-Jy+yM}KfQ#1h=y3m#*QPbh!{8(B#jaKM47>f!a4jWPFQ=^2#`Hd&T9M` zw8aB&YxIGu;~yuI8Wq(=oCNpaTBI6B)IU?z=AG-5c^bq?4^(`uABt*|XRd0oc=XzG zn$^lOBaV#%X4}A#K@*)OtzAa}bFiVA`|Pr6CDJNrF#GX=cynCXw~JD?e1%`fPaNlp zPcr`Gs=w)o-~pWAqJuPN%FEhf3#zL)MeWF6H(%{T@j~+pl|$d!wQSQZMSfwTk}GPY z+IHz7cBo1l3HWyG>g6Hp55N&(TF5tGWG4JQWeIzmRu2e2mq@DzDx~WPn#Xb#)90Iy zsW+*UvT-%YT}0n3gt7*^r$k??d}9!O^LYWefyA)F&CSj(-3-8o6=;ADXJAIic)||JU$V6Rs#C70i}ncpRxdC;eyhVEy6d}M%Ks6R%v6u_pMls`Ct8J zU=Hq&`rOl`&PMz9L%g&49M8)Vw6`%IdKa)=ztsI%TU$^!yJqmY-QQ7n+0i<>I|6+P zqe00)b3FU9>;U049xb_wD~~B_d-NF?HzfPJ?a7nZ?%YP{W<{$tVKofvVxXjP_`6^J}oX5CEYU>&A(354ee8)R_UoG>G zPFaF!{pLL&X!o)~l)T~^b7J)47O9z>KcX+X0&#u{kzitVya^Dp)K9H_?evf`j zM%qYI+1iR^=PVvbmpn&Gh}>}4#Hn0bvm;k+NZ7RCo{UIo8>i(>c4)&G{S@d|*eO2V z+NPcfEbtkXr}WKQQCET)wr7urtn3>!iQu8{NE@pOmCSIP&AH-PY#;xM@KVo5E$=m| z6SxiU9ie_r9xFKegqXC95-5f)}C8dj@Igb{cYXNi>mB- z+EeJq|Im~_jtdhbL4yYMIa zp>hx+^1nuZs8?QL#ap3BoZLq7F5&g?#BPfJr}4$^?q}^TS-MS97oyh{5gtKO(RO)f z?H#I$uePQll+7Grf(oVu59S??x#e=SHJ*ciff1qc;?2%RWklXV`|x^1AG_d+y5y$T z>r0HUmvRHO0Kludq5DfAr}w=#I)Fg}8&gKi5!=t+?!3aA>wpz#v2Wi~A#kMS7!}#q z-^MVUX64v&slX(_MLAOzkG$eQzZXrftIUa|yPBa7;s zeaFN1q}4R6N(lb}f0MPd6j8h-O!eQh7gdG4H{AYf9iNv2W`B2$RwUqW4Ar^v(7(RU znsNm7A@v8}Ia*{5B@dKZDJDbCfJXx> zn7~6EI@2Cp$~H+QZk{qvC}CDAg~iR#?xBth6^2F$jPc3Otc)Kch$7`DpJ*48G`n1PlD z7#E5-_zPCc0VIO$2GX@-0AWI*X7Zv?p#bq9g77MTaq8OW)vaE2zzxCNug=?w>ie($ z@mewQ@4#Z#Ncrx;ScNm+zI%a|I%4T-D|)W!Q*jcs#0(M;lnM5vF=~`ZvMOP3%GGQ6 z=9fc*7L+WK3_P2Px_onDYry2PdJllM=ch-~EK*w`Y`Se8^b30rAR=zuI#B@BK7hI; zpb<>I5Pf6x$F)JBVL8z(qR?}Z(qlm_@sC#Hk>LEo>gHQA+yu|iG+{^(43oxp({ZHs zqai8f@C*j$H>i1t)^tYe`BfC$gO=CzF4ZCTH*v~YSI`*Z{le6&h&%>?PBsP?$3Q2? zJgHcMA#?0(5?+zwUeE4F5Zz+ps^COB1*ZXe60fv&Rx)3l$Taog&w1|HfE zr$D_)?iOQfO+f>by=O&CALgt7b3HNY*55%YT_&!uYWodsSMB8@wYACcxTB-6p;EZO6 zPa={7laix5Pnt-4+p_(F%(sz1uXOhopw48B=Q-;+MlYb39BOlONygf0UN~hyTaJEw&YiHC)C% zaepvf`MgD|2~_jqmWApM%M-w6$V78FvxQ2(U?%3&<{j+`WuC#DXhF=TQMWpCD|sJ> zcs!tF8+7>OHerjnAcX=s4{PWmMLqH_O|5}bi72US(~t`RTAApwD@d?F!G&Io*p|`2{=EJ$VOQYC~CaxL<1|jq)mq`;D=hD zlilx^8t+@x-%nq7eS6}G5#hq;Hnhft!in)FgpwE`=fC+4VM{!^i|mXf@#--0qkwk8hU<=43^|`VA1oqDZ8rRD)-XV=H{?96JH7diQmshM~VY3(+_> ztbZ87qBeg=MPvZrq);$t#-5Rp#)^gW3sowgSj&Sx;&q%d6!@VBZU=kd15njZ18Jef zOf|Y#(7Gmyd&OUk-kA{P5bRrJqq-yvk*tq(8~O5&cnc2DSm}%Uzco-YjMRUHq-eWpKSWF`PU#lM zErmg&ohE03eQ|g;CKaMJ{FPn;*)-O`#KO^?TI)oE7!etU^`3K&XET^&OQg$7haG0X z`($h|v_|}4fGi@Z$!q1jLA^S~lfCHI5yhJ{F6d9LlSkL&znCJ>3HR4qnS-hFPdVyW ziNKJp*vYvPuSC4x_*bs8`zLEh5pW%cVfD-()K|R-mbg$r4;%IJ=PLvViBWGVYzw&e zaC2y(eB23=W&dz}0G`+|QCo~Vmm0_YPJjKBdh**AHu!^&*)FnGtC3+9Ct{l%8EH1U zv=KnKf>Fs$x28qCjt_dbs(#D#{%SG}aywePLo|4%%h3Z+GJMp$EI=F6O|*?M!I}4s zW@opytCbOvJXEsH$FzoUR`u78X83SHD1dMSl<_zWD&&*gk4kbZpWJ{4{~cQ-5C_!` zO%(NV(K$cGpqjR9YDd~K_Ub?ep}YTDN0ahdK=JdAujVr;dCd(M3%Fsut-f=j`oOOi zIUvGBKL66F0Oa1W&x@));{A!t_&S*7pss}7t}1MQN>D7=gQH-JMAY;)H-DH@8vf(S z|1l<_3}iat$6xZ>oJ%|al@-}+$dN83Z5_|jgAXEuVQ*sg@hqCc;zf_d^vLaF>#D~< zt#=EF(U^DmwGqhSBi5ft8ji740 z_bLXXC@;LdVW8#4(J-a5B!_kNk%9Ndt@J#Tz86bp=bi;wR)X_^OaxANv1o?8v1_u& zC4H~D^+)Q7Vk5R6@QuR5um+_DZr*f*z!C4uauze|O>*S>#XxYb6mTFt5<1dUYco7TQWEt&k+{L-5g^2wJ2SV@~E4kDA*;gyr zj~cfem|0%sA8X`s3+Br zL2lKWziLm<-B(Zg^9ys7XOAC?KFgW!eW1$s6gf2&uG5p4&$@${cTGA%Y^KY;A)^a(cl#|zl!d$y!Bf?+|qBi!*`v`hwfba&iYTZw%9QE zs?JHzTq_c#hDAxSH1Bvj0m=K#HRX$A9I2t-gz+qw907>p6^Lz_J21(EK-a55eqwYU zwcu8^Ng@b~Zi35IgHkd%VB1U4WYrkkk8DJ#d3deRKd?$?}j}aaMglaCOPDCF2$dY$ zdHaJqFh%&-!^{`HvjBA&q_tY`;78`fxkI7QWdJ4Ywe|1khI51aO0N&9iI?~1cwM(2 z^1g1mQXW*jsp^wh#ZykJj;LO0lv9qU;mt!6e{N^Z#95kp^`irNjeL!?^rGI7-MIH4 zW^eKDPQuA={ne{U1GE=X{vxv+=Vb&efmZ5-8+XFr<%XkXQJLRc&EC_ zyAyEz1Nbjd$<310l1L&*&=`^>!E&RUYX$b(r=#yw`1sR?)8p*vpI95S6se+=%_YB) z!~jbxzA;)O46E(e#+D4wP++%_B%XiBVslEH?ftCV1#CZb>P$SP)F3E^D2qq!8)VrF zi+g?`{7#&s`J$q3K1Bd>>|pOC_8@8c`^bk^ng8PYs8QN6(E~|nzoaYb8xCfNKl6Ch z6O;-O%KGbs>svo zdu5OoElbxhP8Pr$=cNVovhG$z;FR?c=zOl>aa<75M2ldcXwga9|0j79%x`r+xs4b` zjBcKr>X(o9cv+Rjpw)dg`ZY_an{F3T2fQ;*oEx4L=Xlh-oI{3KD+DPQd!2Qyf2D>N zj2^-xgNxz(i5sxnmrGVM)scB#lxXoBoIEWyATFM&z2Apf!xnM8m8tTVYGQrPjge90 zZKx5)O~u3B3U7(wn==sas&`Vve+p8=3zb8k@7bp?cKgmTSsY)M;#FqgaPfDx`S)0x zXC_`pJhqhHLN@MZj&y0uqmPX=dp07*9Dvds$T*}bUO-;Uxf=Y)V+GODCT z$eS$Et@zTvLoJ8to#-SS3y#n=tZK^G5%-kVw}NaszFB7g;Iv%%#8t*&UWWO1_fn|H zD#oqAgM;g1mb9cZ_Z+{x|K^ENE8{Q5^vzr3^%=?`f@jzbOZgUBQ{epqWY7>t4B!B9 zpHZXPgJQ6+6DJ0OKFFkT)rrBcmv_^Z)SUj^n#!_@>D!8kHOrPPTNV-ea`bHmrRPPJ zIs~N4nC@goj{gYx^*{K{NW9}mD8gt9Zm`5+V{2QcUkhFok%sm`k1pfVg|`ZaIi}pH@H5bjyf!Fs+SC;; zILxOiil2`~dt;eE>ZaIb1r6-z+UO;}BCR=9SMMrT&hFgo^dIV4^0_r;Ic}k11ztSL z6ptpb5=r{lSAKP5hC7Sl&ACn_a$Ium(@{$qF(@)4H0B&Gz?6wYjHvC+M}F=V98{t>jp~qYcU!)vkXbF_T5?FB zQx(9C9j6&JZL&?oRc)0`lI@D`Z{`r&>s=f1JRUR;{71vANDd{S&l0 zq^IX+dT~EUFyMmX`@F%9$=rj4_W9h%aHV*SX4c(($h@tJE*?qj$fw_mGGmf`8keRA zoc?uglRBNArSmt&tdGn2Wz$_X1ZrY@Rik8k4y7F8eRimgv_%}QcC$p{ux~juksyBn zxqtb5Akw$=#;KL&f0wv|)C)457`T$kuf4HF2Qt5{TY!lA-Non2-;YGPhrW>-)kVzW zT6@gZ(|Y(Ro1USIrY2tBmdjg|Gl<@*yl{3I4y^gd3UAXY*(Q%@&Zui0u!SX?aGpo>k-N6% zgsT02?Oefy%^K0JPw$Ux#l ziUr06)`i)+UstIzgPkwUP%pWEg6u7!J0%Qd{lXP%Kl3-!_d8tT@6aHwI<6eB{dAK? z1B6?DWM|P|Qh&{-?C;U06~+O>MK!-zb9j{}u#L#cngyyWMwdwQG>)BrmN($sd(`W^ zi#E|EERn8O#Sw9TK!zn^I$4&Sb0Dbo1Ld^iub@A2<21j1yHQR1k+LX-cUP6XR`in^ zGzCb$J;?!0zAz4ZOm)8(gdXspR|-hCys8}3;lgZQ>8&`x2zaqOH@$#!``s_AD`aqA zsZD9k08GoeFjXu}c6w4oI0~s2Idx2E8?vEKOB)NDBUhV$D2F=5c28Ly8~cCezlNyb zqec@3B7&@dq5hk*z{CjUkOj+BXVo6wApy#ZNA`INuPTTTV`1!IaB2&C?+1V)cLSaw z*4y0_P9gW}|CmA`MZdg3`R0v;6D%5#EcAYzT@nFz{R4~(ihqG@F&v^!?#p>M z3cuUUN4{P=L~W>UOVC9S{fnN?ryZa&R)@E3tc!%=`xeTrcuu`|!FHg=z=5pmsCPO_ zOtw;G=);r`B= z+g&4|s1{YEr*3^7{ymaJf*;3y{s80=SL7j5fZN8k!}2 zsiCSFq^79BoIDYy71E)F0BAU-S&6>=NKwc72{alR2iQ0~O-rW-I)UbiT58}IAb191 z00~KA_hugfNWA~S#iD~s}VrQc1t1GB?qoo+|D~xWS@y-qL4F6UATMB3~ zyQ4xH)>#{1WyHr|nqH^KLw`vsG-rRRr>7Olh|uJ-+-Zu=ABD>;xc}feu9F7fTG8}H zty?Jc6$Yw*b#;RP#Nh?p&HPc!L1sP>@;WV9Bg0Hg;5t@f%TthlA*g12Y&+A!!qE+d z220I(_{AQPdy7hMcjncq$NyaDx1o4r6>*m6Z3vDEwvv+)gE1(+3F5=k5hRDrU^b zz|soRg*^2N^^}bhHd;qE$+(BdU;5;AI87B5MF67O4PhZL|5N!hlgS=Em z51xj_b*uT?ulY)9ET*Ry#8uC~XbSe?6I4y^mK;OzR&z zRXq#YnI&@~a;%|zKlaGFI_7J6=16P)Du=iN_jnWP_YgAw>|^${RtW4>Iu+|*tr$N3 zeC2#7kV{%5eZhamIZTB>5^15DIJ{YINGuIxPwCL%O2l7gk;O`(55@y@KF0 ziCS}mlf##(_!kjbEb2xSW(CIC1n>W_gu&sRoGSX2R#lXxdaxt?>)zt#P%8NFdYnHH zwsv$YPZn2;?V>`$L*n9-OG)gZFR7kDEBhbngDD+V4Q284o6X4Ui# zj=z4`bo~vCXqDpbeV+uF(vJQbBl$PsQAGIyKp`t$32%M;@A59IR4&7(&g#D;u&S2? zhJ1eeg-_;ts5>TiFB04czgXd{YXsZ7`R03OURvI&7UY!7-6eK~PBY^?n->=$*_~V0 zMwt`XWX6$+!vSdxE^s@EXgY|3?BjUz={<=7n+b_G6C(@ol;C>f)&jDz%1(oHNu}82 z2|8`ee^U(?Yz_5nv0u4#a6O{Di%M9`IM4R{i4gmfF3n||Aj&5LKLxjzrYY`Ce$ian zrePHP;Vuem{ZrTp3?1EC6VA-@P(w=ytwGT(Dy`PheI}(dDaHOvP&wi zX2H;#&b2}!Zwm482o|%Gc+qezyWldup=qZrC%}-FCX+kxnxHM|L!L$X(N$}M^c_#A zW0AvR?E&rP@u_GCvfGcq3OWfdg(AIIK&fZ;SBz|?l|8!m(Ed_XS%R50rNQxt7l~B@ z@Gqt%IX9vNkFO$eNkjWXUUM6c-)+8;MTTm2m6!AtVpib!lS@kS#rn~c(I1Y*fsWJT zXt3!$rG|Ej$=}j$$iGpMKHp5pn_BA<^9^G~&L@fD9!PYtG}Pub%k^pdVY=eJj<0`s&AwxZA z_QjHF!<7vh^R;SSqyGz6kD#Gg6DLw*DimvAEXmo|-8&Q!C#n}9))vS}ioe4-21~$4GdkcGkZw7jqYJQoK>}BpObw(zavA(F@isEkhXN}jg zxIt-~o15-Qo;8Uf#7_Pw%NO#$QYlz-F^D-_j5}XcD5*%HK@XuYChS~qWfNKQ*{9}=Air5R61=zeD}2tHeFlUV-TNf$B+HkAlCY4ZN#Eq zN)aNKbk?PP$cafL|sxAK%OGJp|4Hpc%=Q>egEPV;8Z^=G4kJNyp zMs5nXr>BaG|G`$^?0C_~Y+eEnOsDYzed{R-HYr!<*m_AQ%O4^{ivyxuPhK?<9Nkjd0Zbp7p;< z^a_8wd;U1xajn~H<%2GX^1$LwzWK=`I|AtPKOj>Q^9}lPevG`eJQ9Cg{ZcHQLN+jR z&c;|tvQ$#6%_$74C?exK#C~avC1ceh+<@VL$z)%XHN|rD9E&XHn@jCD%B`zgbDRe_ z5M~3?EfZH4d+C*T>5HX}YjR*H+$xT7eB=EM*G>7z)9yo=2qXRm_xcpTML8G@_MZdA zYu&|;WDIgIf>SSXC#K0>Dbet0X!@`5V)}~*^O5dBwgm2M4~i)fbi=khGqv_Mkr#Ic z=Hx>RXTLE{aUxff-tRPUh+5M_7wfYj;dXy}wa=Mz<{0k0NyA&@XVvuyr7*nB0DmwD zXP(wPwSN@53$tsJj5D^sUtC2gse~Mxca>Y+!?G#u`s-gUgr?;BKl0mX`syzNFE))n zdi8iEM`6F$M!?NLd9krh95(@Xe`0PgpV-+1u}uwMHenL!LoM(8)kn*NpEg@e(uH&m zCSf%f$mE;2o9@z;&A|f85U(L{WS5upmws~Ov2&b9(QJd~BB}fPvn`*q8Ly*O;DlWMasPP8B%Y1I0-dtddkQBJ{o)}v)Kw9c89Mq4# zJlBKRLwVYR^TDtKFc{o}hw;;q(zzMn)43RE7^WUV5$aDLeAay^PAyQ(6MB!T%x_#0 zfT0I^qP7)iH*yXp^@R{a|Z-wVE|0%bZ$0*Xsq#ytpb(?BzO>{1Z9Tg_gc}0MQ zjK1Bw9MO+JYO^_BM46hM>!En=~@kk~txE{U;gNO(?7Z9iF*`x{r$LdeHQt43aW`p5rG!kprb@z4?Hpmw>! zGQ{Y9W=^Gwb;G1ZJ&?F%fPv8X$>3dH&QBrNi}t4e8_`m+p3)6=<7DQ*_e&O!hX&~p z$z>HV!Qq!(hNI-Lb%7P?T$J-$W78<(GVWuTO&gnSCC^WXIIha7JE$!eHmN6Re5w_+ z_zQ&(7jCAY|I(!>%D>@f%GJ}7C)ZBvP(zdfTpu1X%vE@7vfrc6g>E)eVb7w)tBH^J zNpT_+WN%k}DWE@h+9DLTNFO=}dO~T5MB~UQdzJ9}H#r!Ei%_q*!0BODyEyX*{b5!m z2lq6t1LSm5ACCmL@+37?v_W;8o;{PM*TZETX~R85Oz$Z%0F}dl5AQR!{16q#!_xgfk-{k4oIHApK^ZlpS zWFKcJJmW_t=+wk`mHZR!6*W&z{maE9|$XHMO|D5ZL2{uCVlEb{; z6j5zIUN+M=CZ-Gh`~Jm<53#B3=#$QIP$Ug>Hc)alu-0$%pC2=?+p{JD@|2EWl z^WU`C{b*yCd`M;ly0{aR)wbjMVCzmuF7sd2dVeZj!4g4G>MO#3X{2pcMc^vho&`!^ z%=>M!{|L9;N-9VLP?YRvD7ELsma{#`k43DJ>|+FCh7~0 zN)`;F?)!9pgcHn3qrGX@cvi>iYVqr{Pb^?3J0NLOHbv};JYyW%sS`avUMvP3p zI}Mbf-U@M1877@6Bs2^Ckxh=zI?xtogR2`_KCQuB39*zMomMJ-Y1YeCh7pP2yv}6N zpKRRyjOxS*-2Kf;fLgN@C}HD{0WjS$eh`I5M=+{Bu<@j! z%rxSZ0JaB$VB#&$^?HULqdfa(z>_(l-ER8)shc+?rMm0p`Tl;)#tQAe$7$uWai+1e zRFED$d`r-`M?~s z{8l#J$(x%Y;dE7LghhJ>;nR6%bHrTUJuzN;yNTw|Ro+Ii2m*wVz3tbbMShJ@)@B@G zgM)dV3z|s5P}B?SMdVTQs!zD1qfE^p=0k_1ci^5xn735<3ei`d?TkYl-Hx*EghB+V zZtC0k7S$l{qT`cj+E#Ldu_n}8YD+FiigR^Gb3IZYJI7o`zr-%wd`Yl+R0G6w-7h_z z8GLmksaZ|@IRjm+;1l!O;Yg2X_CaOCr-VPk{$B0~r#NU`zt&_1iL)GH2+!d`8OLQ_ zW#3Bgf0~ua$k0r@wnFAxRqsdpR4EleM?1j*smR*zVJ7@ZAlTB`}K z+sB6!yd49hGNKnac$|1d)X}>5-FL8r;pi5cXya3>8uqtNAW>N8)W~QDn=&gCeT2V# z{p7d~)rXl-XBLbof{loNZYDs`fE#dYZn z439cI^e!~9udo8Fi(^psX!1hV?^4l&2+J))FXSc8#RgqDByyd!1;V4&NChul`Z2*C zE1~BHL*l_wcB%j*^WZaPt;dHmfpO+JB~%ODcA^b}Uj6kHa7?1t5ExonHlEJz0lT{#26G<%f6Aks{ z??z(w`HhyCGiwrO!0$~G%Y$ZxkcC#aVk4&ZgB6aySD=s30hPLHMqtJ1Gmq(H>t)~Z z<)OroxD6><;FqHEjxOMOTdq8kuL-*X>pSH2#7 zUl8DvNqc;a)=8j+J!@d3S)HD=qtp8e^%KIxVAb=9{-_9d*Zcmit&3(g8vbct6!|zF z)1*$jNwc8}K8aOe9u7;(8Y>CkdA)9fH}xvms#^1U7G3W{4kLdzOy8dZM=$qBeEOr6 z#AkP^tx~t2Z>hx;JLj@;Ab|cT4GHr8Dx3Qqw{d;efP}@vc z_=#O-c$;ovqe&v&RKXS97gt{=D0^cit+K%B78oXA+ zTSZIakx;zruMG;Bk<}EspGO$!TgHAI#T<7QjdY8OT-0TDiH1SPIMs zG-TFvHXc=8ORP}=7q8mHdU&$4WC%_!&rWRDQ=oFq=;j8V z*J=>XgecCYW?HIF$&WUOZKzO?5@3BV!3-x9A*3dkyLAkWc@QG9h3yN47jwK)XZxA4 z*vO&sfkv}>O{&9W;}D{H=d4f^BzA`6JyDFIR_K;A={yBLuYMLqfV{-N#9kCO;WHpb zE^p?yHguSXk+Nk;%h7ucgDFzHoNw+t#KmJsc8I*PLM2%SxcaOacM4~mr)@v``{~Tv z&!FUMMdCr%j-Q?%JmwwzzeR3tTE{0O+$Yl0RTxUzVx^!b5^u~sU>e~c@%Tg?<9EM{ zLa?NTl@2?1NYbF}>Akgoi=o#+yudE~9{4kO=LSWnjO0Wt$KF6G&b&H%gDoQ=^_sq| zE~oMc#d-xl@?R<4 z3*$R_`FfuZX+ov5X=5fZwg@#aCtp5`e#s4dsYEbu7 z>$8ITU>Jqoh?F&vnSC)b`=h0ZRdaWX&9m~=Q}u`>876BtcX<)bS4EUBW!(L}9V`Wr zyfndN>d)F(uxbdo{DMPf+w8fW1-iT8H`CbpySt`$MDC5KSk)O!NVQFejU7!LrT4nG z1Q)wz1cqlE8~7!8As^~`4I1sN#wQOujU^zPtBhzK7QG`6026n?B7dVSM-Do zPW}d>ffU|U9^tZ}^K4feW|z?+MSMrHHSRObot+sP86SU~S+xHYa#bRi&?TZQY14>6?UU{K#g4v(?FPvZ~FER?t>a1T7MSCPh4AWbOPc&LY7z5gOqJA{dbCV{HoZ^fc}>thx3;1^W1h1~CkRK)x<<0!B_u5gq5ZJ?tf z6XIbQj#jAQ$6<@jzYl(|{Khtw5$9P<(RHg~#B3Tw6PdG(EC$80&A3Ilh5+Qi@tzND z9_9NJm0Qb2ZY!WJd8{5~|7rwPr@+Cwxo$nw?-Zq{d}JEAzpYb5B2cCSyRLqZ@2jdp z4ow!Rwa|Rw&?;OPN)5`~*QQnK&CDL$k_Ek{Pt$zbhHNm`Ue1wv>8gin_Jh8X9g!{? zu=iJ0;v66)gr|@}2~8+Gki1r#2Eq`X6uLn2)konm{B9@D38MN&_B-CRo|50BnuvNn z{rI16@U~x33H7VEG{IJ#dMq#upJJUyPXg;!)4UH?7FAt+Q;zd>%V~P2s=^|@UG+IBp&gi@b)IA$d|pFV z#9TnP3^LPCS-{Qh52KkSwtk25mK@|z4U+YZ=I{AGFThOIU2LTE@zu8DpOpA0qo#q6 znS@6r{@>)@z7*x}+Ri#Wm^&vl$VtU^L7>8ky>k^)hC^WWW{HuEOYy4RkqWOx z_cB^t+S~JV6xA>O0 zSyfG6xFRb+v(%&kp9mRH6WyjJ3d0B_$UdW2a9VdR6KjQQ)5HK%Ttw#bwzOAYzi%yk zf_{8EGAnc;F9<&Wq7~X^Q`AMB;K^=W*Dn*w5LI}yD$KdLqEMLK$cJO*Dkg}Y+3SnP z!spq84}0)t#E2C610h6cCVWD~&1gX#m1P>8{CFiE@E|Z*)v2#o=p}+iGQC-)P-sB$ zS)Q=r4@%}H$Ry~?F4fT9k~U?=7gNg&BVf@Q2a>iX3+`N8gRx8oktqi?m77IE0{_m( zPpJ~4u*!>*Z^I>Xu^SITJPIlV)nUpREQwxENv{9ejH?x`@54h}E@Vf#70f&Swas35 z=-F*30$*{N{k@`x%3Hw=p^nJ;OaI3IMo=`@@}p3`Z@ZUqx!HCVSJ6-X7lXBN$u$<2 zShj(Bpc9VBRIfmPDPc%mUm}Zxld@}5{~OJ);;)<4cdhac*GdA9xu*G27agngUU@v0 z8e1JFmU>?wj&214;Fm4a&#ewEH{L-CuR_&%#qgB}xgzwBs&RS4Xr_Y;u~jStJKRiv z5#yMEIw)jhHHIq)hswsnZ*2ZpF{@bC7O^$!t$!Cqp8!3TyY~r#PzXz{Qs>fW;{~G0 zC^nMuD2~{BUrW}G@O2w(d3&L-Z1Vk$jj2xm0351rdB$@F1SxhI5?!uX4L^eq?r$n@ z5Dk9+cK7uAosJ-7#ti9uz`V0ISsr-IX011UG;zAi;(lmjIVF9|ScJ%j53iB7v4JO7 zpv==0`CW6}3XkW4*G3O>v{7|EBRnf5D18P$_MK)zc;TzurZ;o8V8TK|jdv9yiRy56 zpIz|ni#x;%Oy0k@>REU*?oy3A#6&-?`NV*lp?i_)+$MqCXMDoCW*f2!FJl}UZ`lW zuq=6(2I29OR?ie24*4YN;qysSHq-E0kMc9i6l6wZ^noz2d{RL|z3`rxpZ~$((jo2W z5Op1CTTLoJ3NwX~@j}5(+vp~p{P&sF1_2YV2N7~G!rr}k(z)H`_8+iw0BaFZkq@JA znMl8}r`#=>ITK)`@2ytG&i*99>gSN zB;tG)MdDe9P*GQ62)BbyHH9&06HlCqEb;v0W-;zyQUMi-GbmqKfnwM{k9R0bTODEpiC~NK~+9AtV-PaSD zZUdXQ;o998JLT@^jID(Gt7O7&MKq!b>yT`1HL@Cc+aGi4?;lL@u^ZuT$zW-{>|pu< zN6!E7w*@>xFLV26HyVF7q960ZQr%`7*mS|6jxlVfCy(}oRc`y56Z*ETF#G`3ev00q5`o1%!bh+~ zm&9sj;PvX6^kq;M)LrW+D!y7E-BI;3^FYm9;f0omZi55+X)A@vgjqRae<+8+hDf+@ zSW==~MLA5+4O{k^mPe9uLs?4#qX3RVn@JGD143mu3>HdBp0W#L)TON<+Viv4qrK+# zABf>V@<~QYGg;i3k}A}?kVtvEm~$>B`tR_escv0~2R}?*nTK{8sC2#(#6}gXH*X6h zw%$M@bjaqFI(w9wbpV}B0B-=B8{=U?<0^fHAtOye z4P@B;w<~T~r@+%%?+?8IgUmL$h3$(o^_u&L-RvW-58?(@J0elJFC2u`&W1m^&M*Mm zT;r;oa;n`U49hKZ;&}*jq|-7F&GAf;Fc{l*_1Y9%aFdd7LSzN0=^$2?R4w|m9R`pxJ;rZH@obqE1Q&yRgci1%BtTTI=dlTBpt;AOyqu!Q3Cp&1z zT!edYQ|+SISUVp&Ygy*&ZM=b@ycq7yg1xB|SFsTXzwt$XJo&a;b3|R{}Lh?o?If48p$P z_J`v^9Y3XLk}aQ3{3!JOhw8C(O!phF3Dc!R5-+(@|-U$j`o)HmE`e<2Lw(&gbP0tENL*9xN~&Uk6McX_DxRp;M&>tz@4&?42V_I?)i zQ^e0dJs(%_B}u(7TuF3oByUHUz9y!{?Mst_xzO#U&*Sucn^6`Lnoz7#P=j9kR@ve- zObQVwd<_f1y3(Z-hV=ZDU3jONjbISlKNfuK8Bp40?kASssh$oAx)pG*fQW3-F;*p0 zUMa0acp|Rre8#1|A)LsHH_UG11Zvwbt*Le9Gj0yJ`4=-i>^tP57lXD7*DWC;Fv3~I zM-$&B!IQw91(?p{dmAn3XHNnabS$AxT~ABgU$e99ZrK(S(Gc+Q`N7^#LW^I&|1RdI zkW7MR%zogc!&2P^6NDxM@f%}tU+t-EEZ>*kUIRy+06?Qg;hA;!-Jn>cIy$H4S$z9X zhi+_mGK2KL5-zS1Z4e&tDi{Cw{HdUL27SHrRqlCyT{f414NzTv;;tg=6WWYmHF9VK zb-d42S5>zDik?kur>LYs^-{C_(=c&Ts2HT)l7?H0D@1<+yQ9Gj&OCxjhB1Kp5uiwh zf%_hj0WQU4l(VxmWM)}*nEO3EavV&P}6hSBLZkrmWV%vjL!Yj5jB7R%O5v!*meBD8u0VI7O^p@A`C zIVkNoQ$&jG2GIg8^wfEM8DLJu8#xU4E>td&K552pD*R;nnek!hyQ;8Mh_uze?Un*U zjqpf300?t52ukYotS%4r)Tt^kMBl!P`m}BT^ABZ6Xt8dBro@KxI!K(|>zHZrZD1a% z8*71C4s$&_+tfu3>__hhCN|<*eX(GPpojwPLaPlC!An;gSs^#)JDvLIuqtJB<`m{& zsSKk#ubrzRF;jY7Q%iw~zor!7{m$=lrE@>Lem?wam2qLPFZ3xzdYwlr)HEclGtl^f z2rUkO6q9uf_ZCTQ1DuI|l+E!ec~%$&SRr1fc&Av!)vjb@}xB11AXUC7L&31 z&NPFoK44@r71pE|t%g7@SJ{xI<}-5iLVfPQ#)$d>B+YoLMZpA(y$8d zL1+RGbPInBjxLMn>EQQE=;`uafIEHCBs1IV4eRv~J*uXv*S=+ce*FQ&l()TG)lq|< zK2KssAB22g96a#$wk)S4hG;B1%UcC_7FC9|!#g zxnwhEJeFdxXuE2&l6sFwR$u$`e!$MZzc2W9o%SD`eqAz1I#Si^C>xz#eV&DS3YY(S zRez(}>zH3h>Q@tm~gm@@97 zDza>TE;n-6tGv8c`77UJyAjAy_Mv_j#k-9gjQA;f(kd^uXrqfp4|jT zuHTX#!|DWUXNm*_yWdoI0Vt39y=B*=@LH)JDPx_OT&4$Yq8`a#WCWg@#qNT#5jIO?cRVgaRQS{CCNireoVgp{XVw3Q zsK1QLqiNcPQQV#2?gV!W8a%kWyE~jn2=4Cg2^!qpU4pw?a3?r>xbElO-~402T1>C* z>8eAjs%YIl=?Vd}RVL!|2O~jy>q$I_V?Q5=$ng79SKU zIE5gvuLq0c@hp!0l4dlDxH%kY)J&c4>+36I2PH(EQ^ix^DTxeufHOlNVtj_9^hifR zqPe2j!Vby{dX(_c&D9yD_aTE3gXJ>Gjx)z>C}Gw{!&?`0z}~7Tl4uwTh4@7@5Ds`K zP(#}MC!@C~CCBK?GLS)%4f)@{sx3{$OSO4U8CmlY#G&8ejY4j4_7?oayY{iTpU-Ca zAD2|GnZ&Cf3_n5b(F+O+7ar@pEyOk|u;o7An;b5Z_dioFIUU^@6At%9-DaZj5uEOA z_KFDp`D9hTw=0X=sd57PQ{-Go*R&I~{KAmcOL0|?%Mw4LUy3Q4CR5=U-u;tDIZCwK zh1RD3(#M&N*{%2!`NoLeufmGlOx0#|T(}qY?f4x0vD**SjG>tjuUCK*78i>d=4l~^ zj2eY6rL4yWsSQIWwiq9S84`EA(Ih^5$J6?@3qv8c=v{!L3n$y_NH8h3E2*r~{9EWX zGSF<2GUBeb3T497W?tL_Yi>0y!zsx zGqPe;oYHH=nydt=?;ZYmoh8*ZEGo6$*E~6teSII1_Lc>ndc;vQ^x{)99%uw^Gd$F{ zJ7y>3^&NwTX9s?3QtTKrHtvJ)E`G@977)%rfadB~AZgQe?{BpwqWYkBPMV2}W0$LX znO{Q;7+Yk^Omyo}fD-~xO~I&T)A=UB z^V+v!Y#vWndV_pR9v!9J`DCx*g*P7iZT|y&f%BHVAko-bD;fPt8fevJ)WV%RI)-C& ze+mX>#k79>v=A?BpqBReN3@%#HicrrPdFU}HZvm!k}t)o?;6RE+C$RW@ifhd85p@757jdNT@oNmsX41 zM+-|t6XwONst^qY;gYos7KU`|!iyzTke#Sebg zE?pJ5H29#5aP}Fc8GjWk1Z^wfWxB7>)e1&&a7XIAdRt&2#fmw%(UgCI?xjCIu055Z z3QICo*KUj4_D0Y8aQeSlPP$eSFq!RWsx@^F zc<{p9-`EPYn!hSE2-f=R8iHLGvA!4|5qdU!iJjH@pXSyz0FU>s-lOYTJz*EfCs;AA zoMwlV+6MmQjW+5{ugga~%rrgQ?}#&+imreAc@y>VQL$GRXAFr`Rx}+YE2b_50IW>a z@JnIUp9y#N#RzZ0sp19UDT;K`?31jH>*I&oGUv8~675~7P%@*cYg#kp1Q=mH7qt1>!cEkq_YoUDmqrw>Lh^(t16ynT{9+9=cUnegVqHn_dWE zg!p6Ov%LQlcpyb@lw%srQ?G}kQ_U~JZ|3C4F@F+&-R!+=#!nzcdws)F{9L_GhXq5& zI@xul!a6XNqG`74n*6c-9SNU%v1ncV@~1II{f*SAwTHcTGd>^ca(&Y&oVjvSdcWzLi6!I%QxNlxA50BZ-PivY5zm%M~(`ULWdeONjJ>C@Vd1yM4E63vQ}!u z{C+;)0^9hU$7Wj+aoDKBAK#%&BbAnJoko>{2Y0v~Mni|SfLNh!7AuT(!g+EBc8R4+W5!-$AsRkyy{eF@Jywi$Ev6#n6+#BzCv zfMoCKS(Wp}2ay%wsGh`Qg6&xF>`2vXoy1vI@h=oah2C%daqHK8Ao?5Db=+U236(5* zSv6~zj!)qDLy*6#N4h0!mQ{<}Hw=D|?4qb?)dv_MOCw<#m8ePPEtC|{^^xVYoH-?i2WbH8v+7qU!leS zWyGA%Yxq%`oeaG={;2~)cIuwoKXWKh^(Nmy`bGG(^O1_g5b|jI8^@3@Ma56>zzxv- z2W;@MH%i5<{)>|b!>FZyIBg;N;Fjzb(aO#d!l{#k_xkgCH&a$;vH;zw$Py#+Y30AV z;wEez)6~B>Vh@oB+&JdLuN_X~AnI>EH$;Y5MwJ>QhixL_qFBCK7LV!N%jGs7@DU&< z2c3T+Xn-B=3`^=mj(+-}+GOg3iPuH$RWhhQuYviHC}R1ZXq@W5PcShTKUhYJ{%8^B67$k-p&;Z z{~!4Er^G{yxMP=~6~hHzQ;ri6;s2-8I2e$ZW3we_NZm`q;Pd`Jp~5ZXG*6%5QpPZY z7Bv&igZlWTOIVTJ-vI2W`}+vlx%?b7$Um76bL@NfkbmgF)cdVD8py+0FFocq^f8{6 z8?1`Vr;SuJCmNum$9gdYrVzToCzZDITUnZDv`Jj#!*hQ2Vq|r$83d^eM-HJOH=RA= z7>fShzqz^=gbjGoAnhOxblJUo!uo$Yatn9tmmk3~H;*8LZP?)S>+;ES8eom+%_^c< zN{%f)OTc&z1b^jM+);uZ6YV#%YxP@`{}@$;M!I)oB<%gedD!OSV#q7wkr!to^W%pK zf1COEUl)qo(hLgsrnvvf{y2V+oiI!hYH2c&E&i$7w=NgLAo;v;gt6yue`f=Xv(1sZ zhTth)e1RRp8N1%AoXO8evygy(8+RN#fJDh_KOZIFDy{X6yLL7pD2~DpJZ06AC?B$8 zB;~-+JW@n`X)_bHbY{B%U0-dO0a$n=POMe?@TG(c5jXoQC8=(WAG&Cu8du~ce@Y(i zMqNYuD&BUo`Qt7NI$aXJE9~` z@`}maKKiQ_rt3?~XeKzW7*3q#-2`OOd4RXPGo`Jk8Ic0>l1f1T&n;x#EWa(`v*JzRB7TE}bVWDj8oQdlfBFSa+_HKV+1+Fs%2oFdc z#H9QejW=CSfol-(eV8lr&eP38Oa3LjgwGOo2}_WZfM6#;A~2@{mBv$=I7H-JAQg(h^Sn;X#Qu^bvE%fM1T~(@3-uG-$r^ z5%0aDn8Ey?NZj7U`*FFZ3_|Zz6sASb8hC1Mc?R#RKj;)pQdy3CI0yGEij)T1HV5Fv zWH<@KdsVaY=HY&S`?O{QqLQ{%Fg5yS5oYf)RL)Vz_@CN#nJ8#>xa}ns6@Hgk+I3y+&O)x z4Tlxm|J_J_8$KJ-R)~@mT742vu2@{od6b}pSU=s z3Omwl{QL!B6w(szr5hH8`620AEDBuxWrXMb5jd*Nl`Nuff3C0Y@saXNuOPGQa3vZA zevP0N5Qv;{nh?jva0jh*d6cs5o$qQQlk+s%v3n$=Acrnjg+%r8*47eiAjYZ#f?6=b zRQ;X6)g|yq`5aXJaT4qc{>bT}er-Vsbml2ie@$;f>j%Pc74SN(sbYzyd&%WLY>3{W z*Gj7=@ehQ!BsWe*1t}6&3t$x~USY|R6wR8g@J$`4s~mBD{cL0t#%KKfH!Q5ylcnwp z&yS?`uO%4!Qe#}-O%z?`^33aboE5`5);X5|EK#3Gi&vr8zHZ`1b z^%DD>!gE(!9LtF_l+ghX?aV zQzPQ4H&9rS8P+%O2LFb-YX1$?{zgOopA7z|h{nzo%PnrhhP$9MKnLmjX$t(U;MnSD$?- zH~(G=+8;zE>p;&E4hH<5n`vsUAA32OpM~iZ!SguoCR;%42JUoc3?M9Xcx; zR36Fl@S%@%XkhZ-T;bQ0A)5yl!?5e$+fUi#QqgSuEoiFt%QXM3O9Wjj`K#lAj{qvE zwgO9h-+{}bRl@oNs_Fw-^$e^(sBFvv%j&wCEDIQs5{CIg5#qAWONGp{n--lf^qmT- zKA52omVb_*HY$aXg7j9EoDGKNuWg}Q?`Q7Mwx<)0-(smhM0iV*LJFf0YaX0^a`a#M zNH#T|nLP!sjP2E3=-=%`TQIgEx*@8oRigvoo2)e3>T;z?HQxhizSeM@A^($AGTpeBZc1{;p3iXxF5mLDtm_Khbf)S#A)% zg#`UBDGu%nRwII{_MtC*irvE!9hqPjhab`RyQT`Wj=^LyBvSAqJiB;+2)gl%lKy6# z6_W19f}K{xA`uj>jz`aeUi|x0_CHnBQ>aGpHZ(yDvrq&b)si{1)r5qH5}`=lI*nr} zcy<-!x_&mu?L?l%mT$p#5anuGvy1z%LvePV${ZJ zRa1FA`D9x7O%4axMd|(Na6cu6xjO!|%g|udb65 ztj;#8qZN08b?c$2|F))WT-6i6p#q-twiZS{N1au^H3=(n!|^A6)P#h5-v{f;Xip*g z-Jr3%GnNckJM0=>6oXg&h2{_=jRnwFQvn8um{_SloYKTMd}9am9NjGcPHBetgt(q5 z$4_2k1stXzixN%UNJtLrp9wTYLu#ekMn2;eR6TX>-#n1+`hSEAc%W{^z{wPuA&eF#%Rcus2Xs#ey)s8ru5In<95 z-F|c`uB*RQHk%4<&cKs(J46uK^MvgyE^5)apG*9_~wP1}TJT1&|UxuZ%&GfYIcmfu@d z+}_=^bI_!&2Jy2(ZQpQPw}oS2fEODe)dR2F0$Q$xI^4$Blm!GT+C#2$*PXJbn5L&9 zE|a>&AJeaOJ(6n58Q_jv2H}^5ev+!ZeXp?lxZrx%$i8x2qFk;A$ZAc~Lr1fI`0je$ z3Vg6|!>P7jTPm&tX(WfhmGdb?D$n5x@JRqh8`vxqw+lcdbBdu5Zx92XMK)j_P}6KS^) z1UtXv4!6-ouYr<=SJJ*?72KRp=9)`GjtqTk)sseBA)fdlg-8^~7d)H47Y@`&pzb3T ze~$X*eKYL(noRqA(R_8fO7s1KS|I^_>b8Kg@G6epwG8)7CK${SZhvvah#2%2p_K1D z(L3ys$}2$O0nxFRZqcnVoA(2D*|b3Q@vAWn!FR8RR6}TPmmeO9ofq0m>*r+rKD?pY zvJZ0VekF>hHU}7~B~p21A&XLHYDX?d6nRJ9ZucOKkJ_KIyQ>I|p$kG!PwPg#ZdJr$ z0yF$xymN0sWZYBxM!Y4s_Rpi4WwwNHnS2Dc0w18cLHG05%HE&dC|Ei5WY>VsvhgrQk_ zc|SROJh=L%9*-g=V-msR|CGoo%gKUgRtDf@o!T}}fogHXx?b}nRA?@pCEKKlM15m# zhSmRhk>J?%@@EhG(GO2WLE3rav|~Hc5^I^JSVw+jqG^9C;WHT~y{e_Vp%4?JSk#i8 zIOc=l619<2vvKfb?KWm6qU4%9OR$9qZYsY5-N?-VJpej@ueTdi z9wnNVH_AgHTg?%{F&N1*qF0W;UHz<8(vNO!tFcYNuo|VTMPhFAWav)4!y_yC|0%xf zQ)9(`N<98)Rpr$Z4CPee7SC;Pb|1X`HM?>WI@h>VE(_qGEsuhb2xG70RSu5diK2?` zZgHUQaIG7?FRj%uObuR_ST5`(P7>(0_g}YO!bGV#4Dvq>Z<;dxKaaNMBY!Vame(|R z(&BtIu~`S|0`r8Siort%022Mg$J{`o7)R>qOf1M`>sZz~5-J_#%7%qlTzEh!4T6yE zY1N&2>;tLxl9LqPUlL&izYyF5%zo_zbje1tUPA_HV-}v?f96`{aH2{`aYe_s6S%lV zA*KysPEQ9)k{j_zl-u@)_p693Xn$p?T_{Ng3SxvQ$j`z|i<$#a4q5m8=<){%)%Hoh zLXP^nE&N*yQ*_vlQ{bsk#KEwB`9@pn|LSJ+H9RLbUaEe4$DbPLpt}!2!i?G6z;EbS z7gSj5g`Yc{1iO|oOmWS7&M-6y4wJF}Oh^ISJcidjK}8&jK_xTrA64E;I^uX!_GZWU ze)X6CQN!aC&6kocbe<|wmC1|aPUna_6>E@4(Cq>nyz$$-6pn_zcTlr4A+9p zf;2})2m=?&OFk0A$;vw}V&ynGr%{9%KKLJVNbuXN6~}aueGlr+Jy@rL<@G8*vX-c_9@aR!XoanRytLS*e0OakYGIK~BC37#6(ugqn zjOD+`4c4XB=6N2lm4G-wS}ZoDylu3_k3}picksV5rP?XYxc~Er#lg1Q1c`@ZymjTN z3PoT0DNXiY*3*__Nk~XD4{oiY+F#ARB7A{zhd&iwF0BT}+d;Nf)Q%w}2lkyFpZ3Oy z^<@+4qaewkIEgUeln-PGm+FUKvyc|7eG1U<>2>f&ggVbi>Q&gaGq!54a}3V0M%Ezn zK`%yD4X*y0{BDC5kkj269xRew*$Y{w3&&54a?_#7SRWQDjVZudxtP$Hvsg7)k-}^N zw1YmJgw-#FC>y}i65GQ97Whf4Ss793o}i@1F^{Yt90?XCsPw#)HRDvdLn6rl0=aBW zl}F=kV}0l^%Gy8)Z`oR8?NB#zIAH~TRdarULfG}b7>akaq^{93x?1O4<|eyF1xr0? zpn}^FFaoyp4Qk)ZhL@47|A!qK{I%GFtVjqy!O3-fXjY!D{PsmzmJ*M~#!5B^+uWq+jIe9We zQ6|z7hCe6!uW|B5wL7ycZxTPGkoT#LmZ2fFB&_N5{h!HTBGKlqP z88b2o>8~$uOWrG18AXXBlnegP-yqF@n?pR%STIP=9^lu z_)_UwV!e?0Y1iBkWpJhvO=FF7U4Oz|_einjE9UsV`&J-EuTa{_mAgXCmh$kt>ut$`RA6Xi4Y!uGg zu-{IPBgRdq@t4EJv#cpxT|jBQ2y@qwsGv7*Ik^0I^sFk7$c9N#sj7EoI*AItlNWc) zuT3-*UC%WG`Jv-a7gK7Qla^dMBfjIGKrywtjUuLv6U4}=Ud*QzriTs_1{YC|MY*O0 z+o5zi9PX0(;pXKi>#g$w^2+gIpU6?H48v=vAG#(PJskYtT$f@C3p~crhQCcJbad@) z>hK(X{54NO=XTOzN;A9d#~R~or07>2x*BJPQklR+6u?$+qzln>kg%x*izGNC=@UO? zT1+RIR}DwNBY~9%(~r9Xb1IMz)7WFfGthO79WG%F@6Y1D_f28OaW8b|@S*qBf#6#(KX)L4R4%bB`{V#7#+v=5q=<`Q20B`tAg~5kRd5qy zCtz4q1>uyT=pb%*O$;tYXw3}qZgfqq)7qrC4T;r9r}T!U@?@`1?#2XR;31#I5b?9&#h5nfm^#1pz2x(@m}FTd{HeX}Z$ z4Db5zi6XDuZ=jqph2ZmL6&P?9GHT?FqjkoQsScOU$IqsF#P<>8y3HbbR7aleP%bW^ zukLYu@GGz?T%sB%c3ujFTqqAXk1Qp9AexbQP&7>j3uFma4%pY9X?^0CM$BcUF-#pG zwXZhqFo*iqC%R@{iOWeA{%U3+`XdD5`O#a#q|Ed<1nkao!#i#6y}?JpcTV?)Kkx|> zcJH}7+q72$CLofsX8KId<#6_OtUBaLNCZD2$O()wn%DTD0FPhamt88ZVlHw{=FA{i zh<9=Ct=Zfls&>)^8W6ZLUv|&`9OGx6Oq#ebMe*K+0^76^NOS*%L5|(4ut1;U8;Th} zD|I3d3C7~<#?7|oJtv1{ALi4>UWEEk7tZi|MPB5>HVLh!ER@XFN(2IyBug1Rr!`fI7rZ%{%@s5c7Iy)C67y zr_Z^BV4DnrUJ9t0N7va!sS4Rj?)}?1hBvzrYn7_FjMFs|s=G$YI5Uy{>+ zfCwSLx}#&@O$x`hpu66PM*3x(HNL_7w&9Il0l7e~O=Plua>mb|WOwZ6r(59Ffbf;s zb5TkI+++>S+({vk3&kk0nEM3RWX~ABL%T&nsKdS6EvYotlFgwnND%H~6=LL)*pOtkm`! zjoAdwWUNm1k%LQ2)I5WraRoLx%G_S4D0pgWtBWF#9}3VDD-wn|9i*hcvuW-E8VJ_# zlY>pX5+9XPU+x!xF>?xKPZ_Vas3TJ5N_&orK?;6=zckvy={}^~u#jN9EZAkSxI%iC zaW5Pv@tLlVg}~XS677NldP8mUgkH7DhG8SqU<0u&v~Llqli{Jfr`TrfY{Ygj$wnHJ zg~vp!)Q9VIr~)Rfo+V9{^N2^|WiGei8Suw#i&Z$u?;pIkDe}&Ros{c3Z-AwWU#e4ix2Ss}4;0nD^r@SDsc8{p#475?nkc4EFV>Yt>CHQxknAT~bU z;4SGu8T1Eg7TrwP%2}R#kfLQJH%C@2QIOmTHiz|JmXCcRRXOO&Pu%M@VnQaOhjRtqPD{Ca^}i^n>0(G~*c5 z6jQR`JP94&mD|uW|GJN3{(`Uh`c}6`I2MCp9HCmJ?ytX}?R4dfdC|v%S#{xBx8*_Y zOXB?S+EX&pH1!x~TamzDg&qTA;JRdz>q5S)D_)%r!L{%G!wkrbe&breZJgm-;AZ)A zGe074ecoan0u@m7?|R5JY19#%T^h!g%HUv*vo{dhuwehl`K?2illlL=0EV``dl(n( zrdS%)Cld-Qs z+>c7{A8ZSozrY@Or5mRn1r;Gl_Jj{!S|V#IjlF%b$s#7kvIcC6_a z|2DQVGnk=RS6*H;+HnIqf;)S5V)oR+!2aEF6})-7m@Bg4M9hFj8DZdwp;&$i_ zML*n0H;(EhDEclo=&+6(%fP#-KWd-%5v|i{W=d>WDpQxt1_Lp=oFlDdIpev2w_1mW zG{Q|Y$RcMZGV{%XwP8|U05xJVN)s%cB zs4|Z*j#!szn8nstkM~uw$wEtF1$-pU$PO&l+tUh;HcXM&w;>KNj+l<&TV#P`baEWwD+72M^O6ELeg^tiu`?fih~03VFOO7I5Yx-GLIkzXaCWXO7`ZJ{-})f z`!?Gl_B~Jl$OXyQ4@6W#{8{}R&M7e*x|{i{o-Xn22w|EG(5EK=LNK7@GI7rUHpPTN zpfzsLNB%FdEIGX^HdCaZ$w=Pi<_mT95x)Da34hMyD=V;YQCfr z8$)w#&xI&C{dt;A$kB<6*C>~MTQChg%1Bfk52I59#saCq}egoaG{yJZxtMp)p06ZHn?s{W}5c!GF=57YzGV0`!Qe6&s8C9%r? zLvtli@?be!N*CCU8tbk$XCD3uYMf40hOL-~>yJr&VEVaFgYxnzY4$97mxBEM9RMT? zFmDP=Zdp0F8p6GRnq+OZ*ZIP2>K!BVtGQX^r}*HHbXGZI07gd5UQ&PU0)N3&cyWyG z$8SoTZ*kB1Kv2P~Z<5tu3W`VG*@Ft#4eRLvU@|zyq8{Mbe2+Gy<4L?_85|SAGIFY0 z`^dl9YdElXa;Vr(mpdEv{^S)91rsJSuw+nbg7_7WtMDNk!7{zrrc1u09$uHmZW~e< z!R$vY!_4~cn4%vmG5r|c|Ci|3Q<$l=#M{lYg&atOR<3KZ?}+vp6>j)byu@eeX$mGy zs@;SyW45Ans}{4A6gn*?fg((4rmB^y;dR-}%_zBCPMS>vt2Sf5>xYn^dp>rR&cTIfFFve{1^B*zq}@kzuj45^*3GWM`?9KgT7lx8$co@r=)-zJd;o^0r)%nI_UGQX z+0tnM*S_(IVMNdBIQt~%%f^ND8{O*F)8{wyOAU>e2GN(Z9Ib_ojtcq|8(WLCNaO?f z4KmQ6e@63|UdzUNHa&x-;sNItj%xTMWOAB)fA%`{8LU%X4 z^Sbtc^RJ`JgF|2}#Kpi#=uXFk^KR8j9|*%Z zrpJujxWEP&j%}$S%Q3}bgyD_s)q|P4Nn5jF21Te#&|JEskYDYJAr&ar&USo(jouZw8xfWe3IX z=pdXXHn(OGe1kOs~SP7*gezpWn;g4ooukmmn;2B)w0-2sW@nWQoyP3xcy&LSq(;U9>3H zu=sA;KxL6|Jc@m`QEtSOF`q)jr4Y*@%fuyfi8hfh#+gy>dFxS&dRMI?Z6+IRfs1^R zmSYWsIesr@z*%FyxJ3HGhk)n5i|4LMQ^*)Zfu4|ifx#A`x5$0!NZWF+GAqb`6htv4 zgnLVjQqPcl2ayOM7XJ72IY*qzw&NOEu|MJDV*v8b7)HLU1v`_?XRCY?7Z`)RHDhUofA@j zs{HWq!n`?}dMfp)f@B?$^2ql0S^Rz`>5%(R)m>q%&B0r^)-*wBxuhxM$~&-YC?YNU zY|x`f3CHL~+0ni-f&jWmLalIvxsb{vI>Ariq4(z$yr6-Gy$1la{XU-8QtLlri)r?Q zo&iS($OsPLzBYpn**vif8D{Sz?pYtfJWx(8u`;C@W$KELnqsfpz6EHp-BClH@#KXn z2fRI5E9^7E1y%pO7skcO|9=6`5&6%X9rLTJwQq3r)RvZ(dHMN9uL{1`iEC)=kaPrY zjd+~h@!j0lBZdWhWmitk=xG$1#3wt~^1aCA#_W z2iJNpCR@$A=(uhuS)&r)m!h8ik5`<_N8I^E<;?1+b)v+(pH0^`pbZ$KSYufJk^h27 zT})YJt|PKw!VEuF^h|uALmKrb>JG$}S#6sBB+GY^eH_Zkci@~I4glW%7V^Xp@%WNX zBp;lm2qg!{_eQ%H!TE5xqYTr%zGi&|RuW5w-^F*K6KQH0(um2ZC$>92LtCzp#lO~i zOEp%$0L9Kp&12+&Dtv9s8$`QN4Q^KX15T5;Fc(xq%~i(Dg9|7#YtW85LQj%P9TtuR~8RxHe7Z$l0XQN zUs1;%kxkFHl^XAH=Et1IOA9bGKKJ#aG|Tm=-Fcakf@Gx^)+R=WZd1g-?Psk+-@z+s zs4UwD0Orfk?iUY$eoSHCMdW^m0O2^g+2ILIE^16ijTmp`bOw^A)Va zjU1>KuRd-YEA*&yN8S#h)dPHu#=mjvL|NOB5el%s(rXZFzWuS4xal8ybdkTakWt4n z^N%9%r&;%f`*%PvU#^z-I}0t;3U_wg41cf`g!#_|M4o4JIq)MQ@==B<%uj!%q7Pxm z2fPLhBsz#(xWh0y&zkk7{8}vmB*O7yrh&k0s(>_r#3|BE}(zV*VmKh_p_rd;``;9mY+#ro`&-%fe6Q;WIe?eoW zj$&spD%$?jNU1d+0WX&6>%ce(A!Q1^|0n9-?nAN8j-FZ0*jnFmfG2eY`V zCC2pat1j{kY!P)^fi4i7wyX>rdaQd?DD>X=bT?$`qyZGmm|7apw0+Hm=Kw1|h^c_R z!|U=;j`)M~z4+I7j*P8Pm52&qsEq$(HyJJ}m`9UCA(>_9&!J>Sz9JKxp|Ney5chPP z6U5GM&=7PU5omA=FWdrZDu^iOfaR_3FUM-4f{Rrh3VqbgrgO`uUD++p@Mr(FlToeY zDidd31#V2_e%8iC;a$xw+`K;q-l2HE6BfDsr>zU-oh%t6ZggA!wMeOkj;2`|b8S4| z;__2u?PH8JIvieY;ZHEQ=x|WajfnNLhK2LUa>fbXx z&DKOiR-CE2BT^2oV*nSwOMqOZrJEsp%s*};?LL#GIG@}ps{i<`)h*ecW%G6wr7H<^$6*W7GOSBX9Ab2RGWE!jd#{0kN zXbzLqesx3o%i3@aGuwe@+sG}fp`~wOzbEY*88Ym2yd#T0qQEYPOZox+?0DNn)IjF$ zEjL~{n$6d0YL-)YINY}ne(F|pLw1~dibeiwR*(~UCu{nLaH-EpOs zSAkGeC9i8c?>UpN`fdNpQI_cca=Lk_H> zwI;X#Bmxiwt9IFKb4Y#b@;b+w-_O}rAtlIjh{ z3+v&_pT^RNm!Hb=3MY5ilK;%UpNSgmB}fkrAk#4-ICX?8n26~$^BeRd`8Z8Yfg3;q z<42MoSGowT=2~!tpycD4sR(zUAj4OH4Ze(E)Y5J5>_+j zdfj8)FzosX-1#q5i+8?5yBim(a$Jc}KPzGNo%)Nhr|N%kbO!j@KZLaYfb!MSvDYyF zl9NxVRWcr>?h?+BW2KG$4GB-m&gB9M8e=@S1RC;%ss(1r2=TcXlD=&q7z z77K*8fE~oaZIeTD??1FQUwJogjgd+ejBSR8+g;B@^s}QrPjoV{B#gaHCd`$e5$lXP zxx@M=!fT#vJriJhQ#g*zkaT4rYOMck{(TMu-wkVas3f@-M(}{@VV!-~DtY$q z&T58asBQ0KMJO)#qU}GKN`ZW>1Uz*Mzb}u;{5E9()TS>DsdyE z1X>>2-pb){#RtRv|Hso=M@9WbYoG4!?(QLnmIf&)N$HXva-g` zp+IO6c4zIDZB4Q~$Jr<9BQX&mCnH)pi(UxsjkTX5Bc-l^7w6^LxZ=U;l{?gTaT}ZKsW8qO5~Yz z)OOBD0=vl3EngfqxFq2t(e+C$;f;no;d`SdI~p9GeR3LuVMtAmtMWh30N=RYTF9cqVtL@JSQFGC(;@?({L& zf5Q7(qk|AEU-ZGheN|665xPQuffhE@A21Le-t$2s18Tns8JDM97-A22ln?SNc6byW z8oWGf*aW8A4Z-9-iRfevUwgl3%e5bM*8^2#=&A?zua2dre;#T2<9+Z(h()`~_zP20 zW=g)(>AUwZlJaoZxbrvL30pJ^)Z510rjeQl!$(g&HNR%ROEOjn00w;_Duzo zx%|Z+{6Sd21}cY%sJ;M8{?cLC*NywT!hf=gl&0(Qnc~v zm!Yp`O?JA?jK5LPgdHRRB8eDLwo%HF4jdkeVG}2aSb_tnncyYCPc;x-Q1M3RmEP~d z5uZvZCgK<})bDM7d|I3DCR-JQsnn9Dh?g*aqVI>b`YKCj^eM^ zjwTp>q57CoCrnOdzf*j1j6izC>~>VN-qf^|cKC2REg`^+-@|jeRyS25r*a6|&_%M$ zpVMPk_jBbk3CTLivu10bLFYv3BLZj^SS@|;LHbPVvn5Hj4m95{27FkvcYpO34Gj&? zs>Yrb`eTj--F;Nad}j{&pw;aS6MMZT;86l{1pgb}6W$LrC$;mjw!Mv|Ha4 zk6+2Y5BL#nF7ZpBw(dBpO7+nMUWu?li;hPE+aQEE|HO!lDk}>cu+by-(WhdcU{GdB zu%=6($&jOwV@3VG5GaJT#g?7<@Z7b#x4k$kURk|Td}CnRT#lA*aZ_XP)stz&C*~b~ z-g=7+UUhlY`NBw}Ybvr(@0zNDO+_MdyD+*v<815<(t)*&M`FU)D3_jV)F|jbO@65N z53)`onx8Dk_XXi4kPOjcNK|Dw|D2~HA|iUR81u+>KT2wk!9_AElw-t2p;F>P@jI@) z<>ZCpW98Hvty)1)XBQe_#;k_QoS;!4iKxu0T-2{33x;AYSx{-BxEzoQB7ZdOuT`l} zJ{=>y76e8imS}4B@saDwS1Ad^h2zKLL~XZ>3>+6Y9Q^wdFG{5Zj@e%Z4t?K#ggc;E zrvCxNr{Y5X?u$o_VdSIbhfm)OHARk*)xAYTRZ=UJ)86TI+J#^Sz=^xdL`nMs*I$ zb&`RWe?woHtt*p0t)e6nGe}ryL>)^~swSJ8AQtc?26xL%rZA-yp8a;+z2+$U!?6us z#Uu@6{{gs2@Lt{GwXx0{0j<&9afS@`>;r&hnv!Wvq6z`#c9S#o-NdmKCI)p>3WPEu zcfO*X3*IcEV==vU$3&$QM=kr*2vUpnIxgwi%+PVdUb^Oq=hnZMV|=fXOBF;R5oBY%mRaH2+ux7#3z8Xc778VQyRMPAkLYT16{qz( zP4LF<_t*=c%RV!rM4ykSKK2hhU71b8s!N!QZzO)bzIqK$zc?zZ!U%!Ug&OM*OCZh? zo~Isry;gUOtUGx_an}Y?r#9<0*tMdn#wR_9#o%@?a7>B2CUdl~(d~^&r_S}l^tEb< zl>G1ht-cVxDfzJ3J9$mgV$Q_y;T(>fsGC?@B8Us()b26sX(OsOML^M>(3u-WBV%K+ zUGbP3mh}NzshgKZ8C{L;wBP%*O<vB=lyIWPLT#$<>o zdcVyea(*9I@)zL}A}(k&A)uX$aLLF&$pjR}s?%=kHCIP6La9wvVPWPQ&xd{g$U4_1 zm#s$0`(;p}z!^ocXCc3fb zuCx3J4yBC9;Hla2gtl6SN@P?Yqj0v9jWY;c2LH8U0}%x(!LW*jdfP zr)r{744JqWJCXg~Va;aFs@E?>qXuu?oH3n|`?>D}>TvrIh}rp7`X`_{;-{(1RPOVE z#5O#s)-=uuI$1lk3?Hnj2<5h;tXr_2XoDL;-pNa1|BU>0NkThuug=y*63G4pN7jJiV&lIuzdjH%tse1MWSHgSw9#;N0PB<=xTXrx4um^{NyqLJR?Yum}m z{s#`B@3d5%owKk1H&Ss9MFcRl3)thSp!+05CHVC^r=KLh}Y@#NVOU#^XD_M`P zR@zZ8a=Y%h5Own$MC4<(TtWt(DoK<&DZS`^zw!^|28d!q#FrJP=Bek_w*P`TZlsh* zVjl?#)Ju!HO&pmSswF3i7}`A7S4(O)2tt>KK0Jg{~99ImZ288?5_f&3tDQP8;Q)dXo2lA{;w z9_H1%{=X~$M6~LE4F#Hnv*hrnjftNObABy^Hw+xIWDe`P5|@?0`dmZfirrD zg_k*im_U+J7!suy+IDBTM!RFMI_QQ)-ITr*tKK86-PdO=iybOgyO`=XB)b%d0tKndW6@t`V>VO| zaV+tTe$+v>V<+$nvBUSF;smus&0?hI*cPSD0ga)(XHvhbu~_u{a_Wt2dArhLpJSqy5XV`91FAe>g^l9q7(bAN@(^MeO&*79G!~dayMY;* zlHW1_Icp8xL#;p@Ib&-S5Yx!58ldNpRuBUDmc8^=tcJKi37MPnZ}>5i>-k8gCkvl0 zcZ)kMZL8;?eH@b2_0ebOZa6*LOYjRN_TASARytr&BXY)Voq6CrjM&bXUi}Vv#YC;Q zAKup{l?ysJjAC7@{b!?_-!iUB^|)}thW?503&tsIkN7|s$kD>kJgZ&NOlj=jHj4*9 z)tj8`iHjhP=Nz@^sR3RuXGB2iF!9rk!~vWH%}7VyT#UXpA(LC-Z=W4sMuc53I>0g6 zpR7KbkiGrQDjceU`9mXs&ZZ^lfW8``1AGUW4W;3f;#3(L4(s2_ICr;c2NvTwy&7d^ z`nOvDtdP9@S$QCRW7_b}I2BD=G+L^q4^OQ`YN4JEkID@(Vm=-Ja3GenepCH*Y~}1QL0C`SBh*^Qc;2kDyrQSJx3QuT=M}; z*)D8a^K8-L8(Qk&mz0l|@>=!#;_3yW{6Eo}$t2{HnrK1}Kn@slotjL(iKe~?-yg0h z0>Nq*QI7X3-Cv1}6vd0~36loAR=rGV^ZvqkPETe3@Mwv~XEs-IipT>{Xh{HQORGen zEP9XV&J?04-nV_P5(aNjq>I10{62BuOQx)AtJ0&K9{u(M-w3Z&QJ3X|G2iT5G7%!B zk5m}zG<>Q;S)fk3;QU*Dvks%41I^Xab0@dQx%lS9wKz%UllkVU(dyNdz8vY>-x97P zttZw*wfovXYY;2kw$|rce{KR|r0o!fK|~7e`&DYb4uS{F(rJqcnLau*RALIkXK51* zzINMIxPNr+5iR4Ax!KDgwkn7J46f9ni-jMv>{@zPb}2-KBlcG~hB`vJ!C?tKShjU* zcv38#ScXyr&sW6;$cVWF#(9s$U#>Tw6X!|fdAL@c(kf<QYsUmbN-#gbiQ$93tG@thSIHJ5-nomw1VJSAbwe#yZh^DFRl4 zZywp8=+ds8_~HHnA$D)cPbUf7sd~<@athkJ7*&Zw3EC`FbD|op^or({KvQbTlN(Rb z7WKM1ZPd(1KXlO@bCj|Ah?1!>$f$CCCqH`8Z(x>RF3`)$zo4jsoIx?^7&axN%nx>PpJK{2U-e zwP7DM#Q51bIUuP&t0pv&izrwI)OG0d=Z3OR4tQS}w>+S65JSS-^5NL2^Gu`v*50gM z>gNjQJHEFem^I9Bv7wQz7f!my+elb`FW7h{%Iuy6UGt!CnX^5WODe5CVbJgUgYB1} zwJWWTh8(CmK;cqLuwmNMfd2arNE_19NuI`HRrGV*f?;(*?*uxRAW(_XvguO zDnA9Yri*RisWG#uk79M*Jit%r6n!9E&i$N2fg`J*4F#l-LJ$f)}T zeNyTXt?799y}{Y2PN+`E^1e38pCH-f(*_v4?61*dF>fKy58$C^NhVwx!*8skHq6=e zAOHn`!7h>&-uAS@0UxGHoSj)@_22;#fbih`jzDQVmAt=sFxAy!#|IU-nOes#O@3co z13S129Su(~kiI>{r1VX8^WY`i%|WY&*6znk7P5UNinqT5sSogG@+SA&st>$xE?&Lm zLDV>#@){Vlf}h&75eE9F98k^3ngE@RZGm+`4-hJ$0Ts!%L##A>_+UrZ&6NJ>y|k71 z9A7Q}a|4tT-xBo35|8{e0X0AJx-Kdsn6`0*LW$U_CJZwd4t)(Fw67bS4ObG;OYI@3 z+1|0Kt5D z>$PnCKmf|+(B#Y9Iw7)~47xB388e9}gcL0bA0-l&vQVhz5*iw0Bk@6>w4iMJ=T=Y= z{L5SOZa;drc0(`XK?T<3J$8|_J`TM~2+N|o0s)GDYFauOsWG#9JwSv3FX=AszHADs z#>OZQUM8{NC3wk@V)t-8Xb1}@XfJQlh|tY0<-e*=fkbnOQe~QO0O0vgDBbFtx_1D@ zLsuQW1o<^5&QuwG4#`J8vdHMHH@X3pj~s*X1oaXci%hXs92)u8y5`O9P15ipGj_yG z>)h0Xc=yP!RG#zlkqmn%IQDMc75D?UF-LRfuMjJo){Fq_zRbW$@dKy@n^?et%c*Z~ z)EIh_Bas@QFs7w>Fh?Nv-$8&vk=HT>TM56O$y#7+pf`?GPS0kAkK|j+GGt>5Km(vd zk=U!80qixeQ7xKAz?N_w7zgHS8#iwiS1j=W^0W1HA3i6kH5TnW`V^n`9(9qL>fE07 z5BOQ8EP7qBAZGYq3v!kT(TjXv$6#KuZa|%JMRk>4b_-lLA}rQox!yVJk#ppuW8puy z(4m0$W>;szz8noq1~M{6zFzw8HXigA{t)LI`MOTsi()-)f3vNGXbs_}9D2mnk?W(p zphQpJAgqRSdp-W3*W>!ZpSvi~UuLr1tkRE_JKH1%n2KS6k}9W=ez|7STa_SB4EK&Q zeLadmHZ(=|qkH|2xtks3qc);7*`r>Jjr%-&+Xm0gkFoKjMW`K>Rrjuv0 z8yzjqF!3>>-pH4K{kIZm5jV#ZXX@uLlXFHtg5;AYTJ^mk~qA3ZqnVWkAsFmbx03WIYzkkN}Js*;7tnO^k z%g#A#N4P+y=8p0chSf^i+4Ub@6_Cdjvu1AH1?eNM9uPzJk$VVv_AkxDSo~)OXP-)Y z99yn*9TL}mQ!waAdO(2b8`Q@~_rYZidOo0A>N>vP{bh;g>^sH{>ZHXzTO5$g23M`Nqq9vJ;OsvGvM=&^Ed6+yx5@s3R^dHs{_*!Zk={weDCY z1TCE3<{CNXw-W9h9Y|M*f!iUp&F(v~Zq1~>5Mb&f$%?`#r3_g>D^oGv>`s%jma~La z-_YaGO&|rr|g1y~U24zic$!5gUX;^95 zW4_@qM z41dvYP(b`LliC`8t{nutpXZIzbE@%i%60D+aqR+y8XCOOwSV+ZJiAmcWf(B|L%vNp zWM}=|;pzghUpSPAPkr)3{E%{Z)U&#dYt0_b;?eQVG>+W&3>jg>$hn+u6%t5)DGAj2 zDf9l_dohut*=a&oKbdh^;U_A{J|gpTKWROie{i$TfPDt&9tkT;&7hCtt^rJ2e73RJ zR@8gTU5H57B!v~Q|GUygV+C{T{$1oLh?H$4Tg^DUmET>83o~pXL>2p`>N1<@A?16ft1aY<-gn?{K=m7x!?zG%a{A{~t6n~6_k~#1acm_T}$z+~;2$cSs+a^b- znvPHW5B7a}-zemm-!iy5LMsIpoBFguBRXI!lT)R!+Dj2*wY;|D|5u?SK0W7BHbCyT zg2@`$aDq>~YVHI+_Avh7or0B* z-c-SEp4>d)0 zmut>+9MRu_1Si<`*WN8IOyl<>^c%?2xaZ(;u5%*3f#Hecp znOU`&rQ++!r)XXiR-}pJF?@J(Uu5I{7{u zcqJE9`&j+GXy-zscOby|CF`v!>w`FW6#A$BYR>Lx?)pkVn|wU<+eSo>EI0r_yfTOx z8;0R+SFFQ**|LOBoSC#F~3)j8D8&hgYm~N2^TmVhpXwdPlDS`W{af@d6;V6G zAmNx+h>-Ca280w}c$0ZyOrY&ACPY5xOl?(dyLF7#hp%69yA|)|-kCOR*#F?3B;eMp zOCs}pf{W`4wbuFYHV-(^1Dz_~uNtoO~_cajip zPW9x^aqU@=nO>bB#>GP%rdVejiI~V7@l6U%29nmSb*6Cts3XuqKKXNDBeJ^99 zLmS-HNUwh_Ift$b$iU-f)%H>>314O+@mHM?2MUEofrsiFZ7`*WI9RmRgLgvEvlG^& zGjnUGr$Qb_u-=+^2?d1t%+pMl-2wlUNeWO*19gNLH-M1RG2mF_tL5MwbzU4&C;p}V zY$uUA>W#P7Q9T%hwEA#^R)wO&6Q>d1q{doXU#%^%_R8?6?@bb!wLQw+aqpr@;q}93 zWJ7c8913iutp;KI8}dXeheu`K|E%d)LF2l6m-neObL;0sEiVr%eF}Jn`Zki%YL<#> zwz@12`pEeU17%OOsRNDBexv_B7Yj+^W+EO1wxz;qWFVReyNT?t3;8o!7jh%RdO~N{jG#LQ1wPxK z&ae0@4dqg=R8yN?e1nS6Yyo<-b}AI?aY!{Z(ygHL=QaXErbKm2Y~o@s0CVkJ);2LP z0XqU_q@{3GECpOW8D57Np>3*uq*dVlLN;d`-bY*O10)bpHTuW6H!&Myb2enCTbe8+ zB`ZqY8q;%c$+!@N9niw*@-;ppBEK(Y29pBj4i=x2Q@`uFMBV!J;Z_L@LB5BJCn=Mm#kN~d6@kJ8=oewum7G;M@iNOU%tu9*KK4S`;8>_p!slOVQ!l{>2Lxq2IyW5UI)7WPq}GcKJ70h7?o{S``{Q>}$DP2K z``&M3`wsN8{^i18ueS91BuulDX}aPa66ow@4~aDee1eEEZ6i68av>*DlM`3dxN^IK zn%T5=rNZxfy(dup4G%eqXlHp*WEi)j3Ad@pP07bmKHgMhs>WAmCnfSOKf@D4=qKoS z*+$q^ev)xM#DolhD^$QtF=wG)wjN{h$B;E_N=tCpNF-NFZ_D6JwgDC#YJ8E~Nd-}I z)a6hyYBH+c!NED_BJ%B<=ADP99SP7dyPb@TT+G{VH4=ZG`uxVKJYTb#>|6Bc-51a^ zHbfdYK78TAi^sYK1&2|Ra-i5?6a>2`=WqNcOS-T`IqZcmlT zRl?(jPOwBNNFo}g(A#vB2@xDHLw^*0S-k?r4+O#Q5LrCAiXjAmUNBu9Q+~ktA*_~V*g@? zWj6*KU;^GQeCw0Qa|_UHUS>JlIF#*Zr|%M)7eB&J0|yL)zu6E-AW3Lt(NEu&hV(h_ zG;rpBv8DYrLMgXsyU63th`?3{K$iKLk3w?5Ig_@Rm9ZEeC{I1B8N7Kdp=~!y{7Zq! zZKl`-jER)N9&H?bO}_i&!XD`R5wqU}ix}2t`1~`M!~&_jeoM|1UVO~9~BOw zhHu=1U#$oBOc)Rg7Syo(7@4UM5F3mmW<(0*0IA-S+%MTLe7C~7o+IzxDPY~{Z^%qM zx*8I9twy{DF?@Ur?POY8{g&&$$D3B=N;N7ME`=S;0}=qs=t&uRWg?%b2i%`j@18u` zIu?*v&WyVoW!u5lC4Ugl{DO5gn)tTsO*zD+oP;;;@XW3GN$K=slX!@$@bZG=Xxf!l zfjEOn>)h++uala^G@qz%c2mKcn&on{jTyR(dQyPTfPu!^ON7EaU*~Hw77iL9zMSNuH#Rfh?Yn+%T1&v zZ?|;!vBza+*DN$mdroHkJkc#=fu{4k61gV(tko^s64`#?OUbZ9yq(W*w1^p_q3Xg- zBi1+!C_*s~?xYr>r5SW;{~LtUOMU7rH`a%#$n|}llJFI$_HQ#Vdf~45uDK_n8L8|V{YO2Kb(2V0CSxU8kBP1G zTcToX0U~k=^{KJ$AQyGO1Y{$8N1YFfT|M!NX+LidTe)%U%^wFi1?)8z#0P+>EB8YxTyHM-m3$aoFs4#FZe-9~EpTuXPtsnRXk5dB_CDZii z%!xDboOrIGukbb`WKgVh7LNLuZ*295$p?>!muZ)w9VDb6w@L!?NU_@|{B8EFgyQNz-?T@s_nspSJ9_wp3O0B()Y0%sa@ z@0(>)t^d&h0F&O)C9W35>dn8$dH$P?#fW7v64pDxBhAANQcruyW&iSI&GK7L5wmd2 zg0p4wyu$%I*{5>?vEPzYFMs7ESDXov0{WD`lHxC`OP2z!UK7NNviV_wK`sh!}B6JpT8{rs@&d=e_8#d zN-1~GRL9SOJ(^=T2f)}TET|twfTnLw{dc~n??`ct&IqUu=lgQnx2a**r_u&p3;m?< zl~RNcE6bildRyp$Ui_CeLxgWrk9B_BCB!wmIw+Q1nbkgr$sHtMg6>!+0Z4DDS^GoX zpA>VmaxVP(s=QyE;s_c-?rHl<;k4wmW{?%bPJR;W$!`9hog!SlsPR2`*80=e)9sg8 z%pLc(YXGgS5^TAf-TpwkXHAZM(Vh6bMUePojR|KPNZ2Kpz7Tc7pB(B-tmO?Vo ze$+dCx*+|_HZYFs4TW!e9PTMIf4Be z5JQA}BgYUHtJJU^B$*XYimw9$POh@WT;JYyYdHRP6iz+jP|GeNlktF)ay{^#wOq?| zaeD9GEDPc=c9fc5#L0wJGW`t6?ZKRi`s*Zpi3`0)`x0<=w<+rwJwPU>@UwkHh8?O)dd{M>ywbO5FO3bt1L-nVZ;vNPPL& zTvfcgK;P%1h50~W?U1ovzpuh!fDBDog0p$)-@Eu23Xs&gsGyEG=rdpSLSEvmd%syv zspFc}RCQwi;+Kk&1Rf5w`oYzVGbdm5rs}BDU&*)2AUYu{IEYG(mW~&cMeQjHf>Ks$ zVF**7*LzwK9f4oM4ZuaB^*wzCMiC$OVk)~FCH~ZBWTyDl&0N7Z0&@53n9>2Bh+01> z1GrxtuF6Im2MA+it<}_CwAB>s-6{FMEI^Y%SQJPaK1>?gD_!o|Yf6qBGtPS(A~US> z9{=84*Ly{MOLZYYsIK{faja;V@~89tz@KsOf=ph>eFmbL+~i_qSn3(~>h?0CeNGjc zjMK>sgk&}!WOu**HgD6UKmL^hTU3=g9Ly}+O+u~g=llN)cbs(Wd|Gc&Wc+wPhS#)w zwGb0}&JPH6^Gz91Iecmoa_vrQ$|LHomPx84l94eefkS9|w5YeC;JP6<1vAw`NTBk| zdZZX?AFQ6S2=%!^^?DW;t*0;gM1K52c1kgCvQk703>nJkIC{z+lpjSV z-D|(?0k8_B;@p6^Y!>*(`J!8i#Jx$T!jkEQHeoOer4Em}m%xLx~5(LeAp*3lR`)_>5;>a%dese~qVamdar zq7v6HZajGUWl5HK1yHxJ#caD<=TgW~GdCZR)a2DCx~hX5+kK_I`WX_G>sul)yEt1U zxvl+2OlV(POI05j)tDYZ=KN*c@&#O9`#gP%+0tD6f)`uUVIG$M5>&d{YFE=uMP#8% z#rSzl#7fo7wkGC@RRxPgUSZvt^UlF7BTW(LV=tt?oZ+4P4J9{P=@a|@dbD9igfTai zS;1D1E}re34v9uBGw+n1y?&jt{;IVU(YSqk0y$FRs9}GL8W99!MyE+TNU2HlM6p8!?&{J0yGg4__C9_jT$=OTbjge1 z8S~7WbKH}$n5_cPM<>C(9yVLt=Nf)OKiY)MMq_QiUUR0}QPlB};PDug1kQ#MN{FVq z@69C1%6`+GeFDo672ms9`yF()i8G#=VHywKOgPg@=Slmih4QZK)@~$;ct0#U-CRu> znFRwa8^InPl64(lwT~+=z}U8F5S2(l6=J`6ov#M*Jr?xSpcC*9tM#DPuVn`E-Dlbm z#9VOS+l2lr`HlJUkFhy;UtjElq@(Lc4_SeeEIJYsxywM(o7A2MEh3vaKJXwUZWGKk ze9_(2HGue_q4*t@tp+=}XV^{;AIdbp0OVRqhE&F>xdC89LOgdYELJ{N2keHx zwh)l zgEF*K3do`zRYY_i(C1>)!|T@0TO-TpI7ScRZ=k&U8`&FvROx17M<1zQ4acJ5NuNlu zjq6#q)${>kWGH{{H(EZmVkSVd9;{Y;0mIsCxBX0tj}tvE#?fKjY+a5X#$P_gU0z1S zNK48Z7c`CD8;Xqyd})g}&Qyj1=mbO$<_J-bOK#$hHlH<`&d5`ZW0wnc76pHvib#{J zF6JEP(I%qePD}>$^}C+L9N0SMpiFvh`CtUGmNH(ix6R~S&Z-2o!xIn%x8Enzx)v&4zHK>2I zuQsUcvRzannGPT_Du&R0y|t54*D#)YaT*6>5Jp9SDc9Z z5fU=b#}|o{x1{n>pEk|VZI5Sq!o%KUSj1Sh@cMVYT@B2_={NSi_UI+tLb*_4-+}J! zIvJrKa39?VknDy11EII^G4PsLn=~K9fz+d<9rWOA7%4E+4MF7@bg36u2d)aG=fpGB zKQ%73X|3aq1C7>4P>b^6BAgq42&T6~Zf{s#8f5Eculx|GqFOOZo>nEI1lVO+7fDj& z?I^F3QBSaM4s8*c3yIsf3D;|=GM2y-a~<4ilN{`*^>#=m-W)a<`V%l43z7}me6nXQ zu64Eot7>kTWj=~nQjxKPP;iy|h+`H+v3kg^hTao>!9pRA0_xWj79?));||`YKctuyQrCa$O?f zXkt~3Zo>(7dPE_A!1`MRj|Q}Hs%`h_Y@ZqL`sJFmO*JEDam+IhdhSMvgB_2^x!i+e zrE=>>m}imdCqAh8%g2N?j1C{XwaT;&D%e?MX(21gVHQ=dUR)05C$9eW6PR=AZqH=g zuE8KJ{kK&{N@aoroKhlc5!@Y~H1C)WWIdu+L)lvt@2v*(i;(*t!iNi@h5_z&XZcsB z`N^k2l2ja8EU}5{CQ`)NGIY$kAHB`Xp50mB8*tZtM4C8tujnlfC<7>+~-{CO~fal(I6${U7^E0bT!0US_Mdouy z)4tfE*nG~6&6y_^LAgi&DK|SgR7o+azB4|A7=?XD%Y8IT9 zQSU;Z_c#r`yWYD1+A?Py0ktbsNMb_R6|m2nAuMxvZY*PMG1q6X<#n6&?^S*S;dUuRV$z2h;ZGB`Tram_7kkm}-@-=lcc2`RSB&>ob zNQWP*#%Znh;C8yU3T;2A$MC?pDhEmCimJemqMI7y2VJep!VFiZO{yUCGC^=lNPS3P z$36q0XuzIM)XvyxM~hTiu(Qp)Y@p@vMbHj-$dJ=6S76ZpfcBivq!nfGUbfqx0y$BFJm7hXe2^NLVz zdBJ4CL?}RnNvR%HM)ZOn^CD)oQ@?Im>w}~GC?DEz3{#u^ss){pFx;S9lHNRxxfhbKAbYD$`whx_2%ma{#i949LNLGm>`W}CZi^QmO&1cIDJoTjz)Xx z)&oWeqF5id(b>9pR=?{IWLUZECLW#S?*N-zi#LScS2+7orO7-j;)ZgSjkI`gen{JZ z+h*rgFXHu!e|3jM8oI<^3}{w6^VrVQh_xZhxx$;VOaeKzPUr8A?15fh)`*d#HW`9IK1Nkj;TD z1E6{({ZYTpR$hgZgJn73|f3BHgfbC$lbFdepr7{5+Ugd$Ksx8PG8_ zoUV z`@2*^Yt7XE+;Oi^FXH(%^Gyj+?68&jIUZbP#^|i#KVpIX7&nv1A&7)#=Li9cil+DH)Qo z5jnm2%#2vV=P#CH!ers8gpu@77)lHnXPbOuI?BZ|QQNx)rv?Ez^{7;*ws9(drRF@6 z3o}EU|4d3u9t88h2`pYU&?yKTAqlc(S*WrFHoQTA;y>hxNBct!2of_bDte0BW57$f zuzpq{vhXo`^@bacxsZQ|yP>yZ|KY2)M_+3-MzRL}Sp)aUf@apyw#Vv(i>u_uLG8CU znEG#AT@RWkfE!Q=tB}iSBgQSE{yswa(J_e?yjP9Ex98Z{9)|8mp6_Pcize_Tw3IL7 z$f^JyaZGX-)HjDtv*rR4A1{WH_zT;VRi*0;>U_6sX`89qAj+C?Tv>hgJZRwz! zP2YlFZV0^+M&K#3VG#Z9;}1_O+W@VmH}_H7&ogc=H>uPo=%Gg+FK7C%5{H^x!@L}t zb-cVt*S$aVL0!vTwfc+-rABCr5nUQ@2;M!}h?dk>CLhYSAx&^bWTQSG$ui~eN-g zKfK4I9U*g>)>$1zQGcMyA;j0Q+?>Cb!#Ceuu;en51$KwYsX3{<=)eM7*HqV>9KvPM zVdr~Ob~lf2VO8yY=O`WvFP;llMWP6wk{>k_{44#*_J>q|*Khi{+28 z7*-0l5skZ3Uqkws0ZcGNNuob8#nHroNkDaqaI|=}(!S&)<>!!>+wB{BP z>rv}}QA?wDCIh#7qbU6xH?diGMC|&6W8`|2U)tbLx7%Bh7Hx<|n23>EsZswP5;A_0 zkwRzaAlrIW9#*t?>#&li(9&=(PnVfBka>XrimWO}M?Ha+%sMg$t)=5|a3EjvaEj}3 z2aQFB5^^C#UTmeuazIbCNi5tquocy9Pn1A)4*yVkXbK5;Dm(9bk$j|q;;0zbAYuw% zZ@FsNkm+QL&$a7`6aFZLDOp`0GZ*Ba#@+nUKit+$?@!veT8vs?_4w7sn+fg6zdby0>6AoEqXr4qIuo+e!D0++Y~WlDY;COb9|780B@e}VK(fs zStCfR+qu)&Cm43XE*Dv!>Rl}2V&%3snJjA(uM+y>1ryEVFgTIVu;jbufa*_lIvZ{Q zOHkUQW67ULrd5eK-BNwg;a|?lt?{bVNjjo0M>8jPp{fv7Sehdp>tuXV9&b~|i<-75 zqWjD0Rch-mutpuXjQTO?*YWyH#rwp9A-b(o1ja4^b;(|oXCGakv3OnF_`Y$b7PC84(GirjV64H z{S3IN?`MiPLHop(bG+9VZ>xtbn7~3VMgddCc{)D^A9JANaZzwKlI?Nf$dyAneEyE) zXft^A$Y_zUz#oT}s(Q`B%Y2QNT9h}T=7f@LJ926{UmT3? zouS+eo5lUQw1MqlYdXGzBwsjPyZWLu_arHA&q8mme1H{ov>*}>%6Wr+F#XYg}J(vd2^VC5o8}1jxR~Ms|ADva*X^*ye8F*EO`7r+f z5c`f1q=5QvlRc4;>T&{Y>Xlt8+CSOJm*v}QF2g+vl!02NN2FF#k1|abNR>*?7we5F zs#R3%sUkgba?Y)go`VdKrtKxr2!p#1+Zz|d$8mM(!VNH`E{v&Qs#@WPqVZY42in@< zr|M)C$Dqj4^CgilI}pzn6Y3sWT>ABbVP~=J3aF z|JHnRJlyM*Tc>jk{>J1;LO`-L(GleGd#VD}B+OU$163=4kcCB~tAdIspPM>BjtE8= z4Yw2!_Ry-@Yw7a5jT2{?XjtnTkk`g%zhWeUF@Axx?~rFL zYNfjK>D$9)mVdzSG@1^r%c_cc0N-~1w${f|BfO(F|ka2FY+)@zLziG zgcu{ClMn)CR8l7!Usv)MG1vb>IpoFCT?Uf3TG9J@L&&&7nL$7F{0A3N?0-Fl=wt4p zSEx!Rw-T1ktHR5kx@tQPvyus7jYOvhS0Qex@@^l$5p6x>Cg@N#9(c%~{3`8H9j_+# zqaKn?8fxD}c zBYy*jiNUf0fn2F?XOL!T9Rs$(Tsfmr1Y*V;X42F^E;(wQ-*%7mNlq1S_EFluePe#9 zt|roA8U+(4(RgTPq$5zmyC1<`V)UA~^H6A+tM9#&udewJ>x;L=kwhqVndgghLnh(o z53Du<^njt!0w>c~?0-KDPB3v1n@NJy-3)6TlTZ^h67s0+x)+pL?xvx?Zs}g;$#LjA zScmRaQ{2;|6cCv*2!Ts?m4kmM1%)@qrJxJ_@XoA2e*229LwnK?P^do{T9HF1L#0PU zjx*Rb2+NZVK{8$pD zH{}qy@_9J)HhzBTd729R@LT4w+!LN;ID?UrBj>x$@!x)(FJ$1tDQ z7eq2oQf#-b&Ihncao1Fr_$@J2nKcW21bmt0QhL3uUOTA#kJ3bp;j**7} zB_<@zl2`GG1#4ejvyA`g-Np|g_mOCw!~)Qr_Y~EFNfK;V8&h~zyUBm?3E;`jLEjgv zM8_yWNyU#%wR%yw15vzkE3K651W46XyS2bt$zPn{hfVH%>i$MpBZDg zxu^rIQmh`C_i#$ALD2a&i2D!u#>Ehnx$1CgpSiFTO&168T0xT(MIzw*YW8xXE-V?9 zN!AxF_PC-?-DB6cD>Xs87!%Q39`V&6Kk!>c5I3+MGS)LMoOb#~|GBClx?eoiRE;n^ zYmjhza>V`PH~$g82m&yA$ACse;3quCjBn4e4PXQ{vUs}?b)~O`EARSImd>fP$Ux&@ zP{p)PV8KUk$T2j_Vaiz|+2U@U$%Tim#RFWWq%&Ofn<&L#=;Aw(mnhfQ98qb=QZEg+ zG!G@&@a5k&yqtvSc#j_tAV}~br-W&|hjDg+yC6RwE84xybiE7*`?ghDs(#D4$4_b* z#+AzZ%BR_QrvUq!b;zIrHZfRXd@Yp-uaGC-jB_83g7EZ) zHz&KFh9l_=5QZPAO*06wJUp<%Uo94k?DM-ME5*Rk4I3g+&ebU8xY|d* zVP+`W4cYC7!-0cCc7dLwuhRYZs8ciksH-bo0s=(HbAb5t_74^}^r*?Oq zA3xEZuBGPD7sBGL$>9Znr11BkUY?N}i%?$Sb)PMrq|aHcFNNN|O{jKnt)O^wvTELG zRNti*fR+P{F>1?@(SK&CBxTGLfxrizT*VY8cg(PAES8%xz%I-dyJ zQ{q+yZA^7J9Wl~#Q-1M&m_zupnEZ?@xXymF{N<}$=jiVB4Zvw(P|&O^nJG4=_h(|a zk{Y)86Z!zXV~+6+KELppmL;ulp>YZ{%{}~v87GF^o@qt@#Q$!Q zxd%oG{=Rc-s*91kWWK0mV>l^1Gw?ZGAj!|(A|3>qw>MRYI%;jrHOz6PJnH7LeMVQ` zbfAu5?OH!5EhdV4*{*L6;4zQ5ho=^dDNG^p6S_%IshI;{ngdqg zR%QtQ4e517@=dRMeqKgi{x(oJNr06ehjwJP?Sw;^kt*PnSR-3f&uZ7(op#1kNLXqV zjD|hpl^X#?zH&qf$KqsEP}1PiZ4-zxK#0U53t)*CAUzk+7mI)l1)tGfbNhm1`22m> zS_P9je8~3A1gmm1Q0`Tm3_TIG#OcT|zwyhq*|g)LtM|)Xoz*fP@{_rNUc8RZnBd0} z?~_#pg8A2rqNuFYQL$kT`Zm>srfCBZpaaLxo*}}O@K*&qNwQGO zLWukEBzF2twY~n^-;<2fl~*iwuu8GveVYh}tH&JF$LmjE6O+kv%YNcirAm5q-KGV! z9kWzt=JA~O+LWYHP#N@NW-eOu)25*1XO=IQ+E)418J~VC+W00jn`Q&5u%UJv>Oe}|(EeVD zdpa{J#l?%}y@6M)P?!+M4YWQ9LLSHQ#E>vEpDc;1;NP_gRxw52jCy%pIRIlFF`Swe zM{*|aF;(^FOgkYfJAIC~8yvfYs#PTBD*F z!WMaSF+8udbYUTdoh`aDRfciQTYQ=QnKUoX#*#d~n_(s1`90UywJNX9Ni$6x3MOMnNF%7RxIu6QNM(xzp|Pf-&n%WXtaSB;+b?@HQ^f&Az>2{D^HvZiK~py}J9Fj8S{z z2SE!WoH?ATZ3t;w~W%tpnr&d6>Qc2_iv+ftL#u!kRV<&z1U z5F`t{)TjDbO!|;ztv$nt$a#TN`5?O0JN988DVP_@ot6=QM!ayo;P#B?=-1xX=y$A9 zw3cCkChE9ad>}S{vYUJ2<`7wRhVT?7U_oRL2O@R&z zO(2qu=8woGfBZVB7qsWEG=i4IRk3;svb9O$046OSZ^0z%;L8!2HcpC{@B^n>E+|VvKZUNmeX)2i}fTFz|dlK)qJ?J{7R-kqVS4p7qe} z{RIE)lcuw^Mj6&S$FBCd(L2W-i^q;@$?0kL;!Gs^2eYbXU zI5(p(2i~0wtwx_sVLg~AkSL`xd-i?)K0mDY;CeM+NZUf~&@3}h8G$aG8E{woxE9nM zSZqz8>0`#|kGK*w_1|C<$zP1kj8aBH=9NP%Uj6)o2!5MD+2XUoGACu+U2QJ$5*3MH z;hR?opGoJtXvCBOPP6m;?|-tcaiYKkwfb*fb=}V!`W(2fbhi9!mvq{$J><-gM$Vau zITb-ssrh~?qeCCr?D^1i8$%dtF!Ud!|FT+7Iu*`wVoi_*yZRz#_$CTtT@$hWc%Gmi zP1Lmt(c9_{RQkgp#-`*5ZNX~6xB51Jy0-Tc>%C7V^IYPcK6f?i&ItFrIYKUqEBS%H z-cCNp@KpY{#Wz6RMns`V!QwH0MW)os*XmNP`3{M;{vUQr80{o_C@x@Uz}@gPbWNB4 zf>8hZD|2Cj!my~!n%&~D4sH~GbP0HQ=msV=>ht>#O=fD5!5|)F2aAyynwIAJT$t&i zM+o6r-TG6`R-gGbTW(rbC`IM6#L&iK%k0QCR9*MM#&elTtv_|N(DENeW*1h0C)rib z^hhZny98tI+hm)b^3%j@k(^la;j`}QKf25_z(iSSQ+TLN1%%8=SCSo%&LD)Tflksi zmE7oMs*b@omuCHJ$A%F?mlvPH7!joDPkS;JatxUySK6^YIqJ|{aAs$>#td|;6i7)? zRbQIcX!3F$!U}_dGf|FZbP~F7>>j2%p1bE+)U;*~fv={|GF&09g9W2kcmXdFO;uMO zq8l>Jf^RY`{ARwJItlGc77b)xev1NIHGoPJ3st$8Uk*?cJXOrisU0L|%nrc&H1+m= zoE7ltgVAX*m_Vk-vL{9Rv$n6!x=-5|BjKf;i2(E^9bemvgvGcF+PJ1S7lG4%R2Eyy zw4{u_3?>Ps&T3KlXT|jxY{ucI!Z>L;`iJbzI8~n*lubl3wV!{r)UNG^`qdWe}4nOk{(S*4aQXDPF%U zOH|Z0s(F&MNKgBbVP8?s8w&#t%l+b-SjrN)T-vx7UxzgIxd;C zRJVT-$gUxYa%T#QoGE_q2=dlb>P#P^4D>mSU?2iYU=lLMc!TXE`_?fYIoYL7tH3MH zsH~%*vuCj-`TmC~rf(;?^CiMW9h9iIEv4AU+?H-odLLAut#J6|?y$1%05Bnh^9IkS zOQKUXWcu1F#%(F`$H5vsa>2COc~|jUXg-hb(f8LA#l%EUq4SY*|i)vx8PYxIRB5)NZT4?}#mfc+ut8+1n?E?NPNBxf zPfn5YHO!w)u4R90a*=*p;I!ixyAfZ>YcA>OyuJy{5?mrbruNTxZM5F1ZE+r_fNAHa zA(r=j?fTO^{3Q_*aK0N{8Lv&+1m2<86@#2YG{TRBM&rd0?Gq}Y&)GJ|kEvvi-g8pX zVGAWQT`VPacc?-#*V?5R43>SjK;;pFv?5cAB2y+2i@trbEt_TXB*8DLXcV0j;E#WH zy&J0yDxbbD^iUe*Gzk&?Xg6B*SX36wwSk#xl?|k6mAq%o5$r4GG&0(4iFu|p$(4N@c*q3?+>?oi4b~ zcUK0;RkJKnk)HlTVT9NVp>?4Hf$5C30J!+5Cmwd@4(%Nr2|>H&wukvIObOGmxzt%MkNh;U-8 zpOeqf#{J0Q&kt`6B|=(9${K46-dhL&YQ!730hSgy0}AP`@18YUZivuac9Z!(X&WnH z=inKoT=M$?3D@#UHUEDTjU~eT1WV$+a_Di4H+mx1cjDQo<&Vfr#&yGLSd`?r)ql?X z8eH3dY_4c>HYxmp3w4xCD|44Teq(_|=TxruR(Yn#hX=v@ldMKkh7ru>l5@)YVjyF# zv3<;#_|(v*@WH#kGna~%y?j54V-m4OlKHwgNr>ts(s^CX^fIAPX)ZSD1nG?F-CczR zSJu(M!m#Hk1;1=45$eDwfR%bo7oLjqRz$Fjo6Cobg?G=mwxHo`wO_5o+_JVo**mQE z<4|`?WA1)~(hl%@Nd8WA!EL1}&|HG4KvsGI{4PJehL@iz-E2glX7s!&Bjlp#G5V{Y zrk1xrIcE(cnDHU4B~HsOzS7fQAwRE+Nsd=UDrMY%k3gZ1xmM)GLDmdRQ?EQ-^E9Mi zSZPs=*D=9j3cs+TV>8I3U8+bB1#4A8eev}qF9>D$-1H~))1zx%2SO0Cn(ewu>_4;w z!&h|U9DSs~8JguY^9tKb_9`p+{dvBXdmjR}2r`ckw|E9>iN=#+k9Lvke&H>L>%X1p zJZHrst23@@1_9E2#+0Ri;BECpiw|8Y4vQt?UJ~^0YBQGRl7H=SUp&K(s_#;CcqcyV zQ9g+3NUfDL2<$c}j||~D!y_o|e<=T{U;s=gu8v_+5l_16l*fU!F#OS_(LW&DI1f?hAqZr86K7S z%7>)Z4b9cbmslM5YtAFSYgczUKF}Voy#0?Z!qjtUqXMunNC`wxJ&Mh{G&A{BomgUM zGMoZkeG|FdA6nv&OaG`x{~1h&)NsMWjk=j&yAbVj3yd0nOa579ZWNRji$~%ns(i5{ z$^oruD>q%Sbx62U`r)aQ3)$U<7X{%mY1g)ivPC zN(-OGlYJ=5T{I;%4LlF}h8?n9pF8WEeO5l8Rtf`dVGB?{kyHy}GX6xvqh_wK^5nX- z+$wpE8j_zt{gP}`BVX2vs|V+uh&V@X1(L0oq3BQK)NBE)J!GPN0m3d?XcD0m_$vsS zpkYlWAy}~hD)HY1u?)P!$r6ofIVT62Vg_BV2fUn5^O{Wy*ZSAMMMtOZBstjynw6qcA@F8DMg8ZVF! z`RLA0bz5XzfvoaF&iqsF5X`;;#Su;CT!2$h?)8O@H@pw?|Gi|6jYG{)VU|kCqh}^| z&eXtsR;?bzj_kvC-u+x>DPAwZy;(?A8onOPn|yktVK)R-$Q?QQCMMqG;P(% z9d46mIl;>kZv`&VeIJA#2@Ms#0#Vbm;MzoU){iBP5m4A6q)=1jKH)arWfp%xBncD( zhIicnCtV*atm1s{h|N^f&yy=2{N!?s5f*Y$esA!liHuvFO)pxJ*F}NZFc+PgbSYD> z6*sDCNVnITx-0gnlBD3Lo5ECF?QyxNdZ{1d&$M4nFMThm1%8)IYPfov08qbH%0+zt zdax@tx}1={_h8IRol{q%x>_fPIXvESWZxC;TanjFIm3$;8cPX$(WV2+>i*UlL(i&V z(-GgLXz@8Ga($hs$AA!5C*YT`79WA>@|dU7=a4yS%fEjbTv39o(7jKe^3rYXA~F%z z1Un*|ZToXIvnrs&Fo}0ittZDR^IrBU(K;1V2(5Gbr!+dr3s1RUQX3*tl}OL~Lz3(b zi_-`!@9*2RDH%>_XdIaEN!NXi;)FJ1g4kbDzZP(JaUveTH%Vl*l9qqPllA!)E?+s_ zu)}iRAa~*Id<9`F?{{&J&DQFm7LddmD_@3CYFm?6)jIzfwCK1@bjVLo<0N@}F1@|D zWxn(0T?9uQqfU^;cQ<;M%dV2od2L}hI+3sF6U1=D~j3 z(PlG>l3>sp(0T8nD-Mc>;HSQ)_G)6swHj~pvd>w8b}m;LrLvqPtp zr_qTP8$4$r$PVc~Df^C{2|2;bXOt6CYyKk~Vx{iu9Q(dxDGV)hqGzJAT^1*{NKfS7 zZW#T7y=%WRJVbn@Y_+D>C@siHYKCsm!dZBPj@BGFY2-EMUIeab07qa5ImDgH?ja|$ zqpULON9xk_Y>CK8eH)BYk;$Q30~Hk+o|*jNC|C@kW*cvu_>np+9Ca~Gam19NIGSSt z(v23{2tv{i97^{oif`ZIP7N|*9)-5{_0BVYxZmJdxbUFlpRg*Qc2?Omx$kVshuTV7s%e7QWc2%(xYx2*@)EN?|%Sa2y% z*eg89MwZo3@bIEocsCIcqnh@l`ce!l?Z@Zjr(bUuN`Nu9GAyiQCwzdpxR{`Em_e`a zqXFJDz_io@>_L+On4pKahT6+3TeD9>ztx$(fLrG>elXlD8U%jB9dvwAQP5m*>=jLy~Nj7}ny6>2}#)p+>u($(fyYx5D|b$Ps9!Q5LxRRbgS| zt+A%c1b>7az~^+NoqvR-hqq7!{-|sF8BQ21@FUVaknIw}>nt+Il_Qpjm_*e9bfLjhws!U`%e!iQYJ2ZsPa9`hO_ zu!G^TdEYU<@mPd0HC+2jQSrK;PJWsAjv(A(1Jg|>-Pf^2 zFtpmUQ7j1^QCyg8S0+@h8utF}nD`eS!`MAIqQlrSKRS7pad9p8@uGuEvFqP)5;)2U z$L!+IXlJRNZNmH+A#(#QtZ|#@%A%$cf1FrBRQu>3cq~&Uanr>7zLCJutH8bVh>IUN z>?Soo=U#S1>IZ;tffI0Uf_gsh-+_ap%R4JlJSzD{h0;%%J;m(nM~J6-##tD#&f>b= zo<*U}5lYA1=gS$tta&g5?akw#5B=FPbKF6q{P~aqK7M8+JZ2-=$Wd)W#{v%{b`xz` z-eitk#ejGl%J?sKQrZ;5jLK7wvvk6if7>MO1pFRrpX)w}gjcednCys$x?cV%lxF+! znG>MZSf1qiu4xu9&`(1$)bFi$?^VZDY~A!Y#u_?a?QMzk5%v^RVWPqhRL#F%s4PxG z+`A=zdQFg+iyw>z?m=Q1qobkoXyzz>?x^S0ZQ$Yu_FA)u^lQbxXl>zMN)*aI zx944afzrc`6F{mbw_&;!vsP3e!+W=FavJ01C$1u;HrlVbW3le|FiilxY4qiSy>mbC zE0{%Gtj}z!89LV+82VKqgyM_nqT7iKts4IGx6!Ko%pxQ1;D;Gj2T5Z#IHK76E_YNY zkweBsHm$aMyj0mCz#P!X5NR?OS5G4|2@}Ueq2M-T22So;c?hp2xPMga~LRq;rwYMetuqa>2##lZ7BB=%36toip z3|4(6JJw)m27D6akE19@xEj)J?TTms<5VH42*)(lM0SX{CfKO}@PjFe`eW}bHK6$P znV?(B)}E(mEAFn~0}iJ?-C&i~lq;WGoZH&+tFDI>w{o;jHhly6hCEktdMe5(0K<2^#0$!CWkG80RWP11zNOn{s$OMkNKc98i~0u%IRbFH^38f5UJ z0880Bo~)3d5{u(-m}&9eDV&r*19w}O_hzzAPLUM(4UFeNFjK@Nxlrva_fGFNj(}I{ zyEs#Lgkexr(D=ayO`5~@6+j&ac=%vFHiFn6O2L{eOILB)wl{pt67KwED>G)nwmP0f zD&iR9;CPICoOz7Iq*BKqAm-hl;^}6bXKZl!*&yN$E#ueRlvtFv?DvQVC*sc3C(Ou) zNVWK_!?VLn9)(G2^Ck_3-}2+ao2_ zkA$}lag%m>6Ly}i`Y;$B@-dU`qraJdfF=cp7Xw4O8iFHwNgw2Sa%!=CF~#>J3S9e8 zborC@`kjzn1+e1_XI?qBUK3dlq)T|Z7^@N66ibg31X#0>DQd-+GILM9Ugmb)aFg$P-Ee+5gC$N@SKF6$1S-j; zKE{lo1prUV2G7^fz4VNW+e3eY*;GDkxIGfxEac%p0v^*Fp~8jF)`|yo4Nf3^CxU&*Gr1(4W``f2MCdI>qq^9p=slZF`s}>w zOrOlR6((Z`%9&#Z z>1uqJ8Y4Qlaox=%bJuw^o1taCd;7{9p&T!smPg}seUW@I_PpSLa#|tfi?tmVdu|sS z3QBaOwk^)imf0r;euTNQ{;Z{v#!+&uBi)xjj!AH(UmX+<@HS3f9O1YbTI0gYTE55phv+VQUU@GrAykPof9_@O8pe4dk{h zJ1bp3o?)_X=w+}y$t1G;yXKl8_xR}dIN*pmDMUqfSY2q;o*<&?XNgrpaMGfc`zhdK z49<>VJdh3)g6VDoHsf0c6zJPnvcf7-Ne_hM8G>{^RC24ZL9f&!j;o&E(jYV;^03*1 z;jH37^R}_9=H9W+S8H}Gxn&@#Xzo1wO>rc;Av|d(#}WO-Ip_qVc2t*XI?YHQK!IWg zWoSz(A|8L$C4aJDt0%f&G~XJ1a3_C^l|`k|B+6rJPZL(3#<=}3pKH@}E{1Q4^^WyK zy&-x0NPN@>x3%(Bmths;}nDmtSW z#g>XNiZISb*^mY{SZ9~`C#`}ATdBJ!7o9PQ$*4=~{;7tzZ9a#<_RkT&x=OY|#P_td zP+up-Z64|f;p@=gdSI7_@zm%97DHlWDV%U}%!NMjM)uCu0!ut0kgqjhDuP!pHt}{S zuZ)aTykb+~y|8+~`8v$EAR2xeW)6L7uQaU>~;AmWeHWv7;IdNyIHqU zT;udfQLM-M8=*~IBK`rR2%6D+E^hv#i8#1M0nv9@9UM6UV5tZDONmAUB-4 zWkypl!-E(|RUC8Im$_r0vSAjvTokH%+QEm-yTi3mI#X8+Q)9J971AnigWzOvFM6J9 zf=?aMv?oL-k|R9Q?Bc0{+F#Uhilu9|}3a&)R{zTO>7=sb*0-DMhk`QXNm zlEX%7-MBf%_Y2{|KdJ5cQ$XF@e&)$SiTg*2cSbcimIUKtuY{^KG^Lm4_gF#ALmv64 zL=o}U5G}Q_LGLAkt&*cHRcH5G;Mz+-JKGO0yUKH#tQH&RSn01|z=4-tqd&K?PpSV- z=5HHmj9bT(_Z>!(b-~W?cX+mOr&2Q$&It~_j}~b?a?ASnTi|D4MfFHcD~?Ra4ARW0 zVD^&ZTcGezMEucB34shG3bsVDtAQ5J*9#2rxr+zbH3|}cFcp*NkUFF~q^c-<;Jtt? z@{O{Sl5aSuf@%|+k5oU576t0n7!~T4O6!k&@e;%c`Gx%|Ce;j^RGSnO>hSE>0^!Fy zdU#l!r?%uOsBrj&?0nkAKZzv z^6|ss^Pwm)$F9d_hBC*W&{Bve2~qJ9>|u<5W#&n~t<3K}CEysn0;j1A^pBq3t>i!w zYsp0^@Kw!lOTyVs*fq88O^7lrl&GRX>L+;LB zmFUk0a$X_i#XE~rZU^(lFuM|stiW(Qc&IGBGr!bm7S>;n5nUt)pE2$-(d}?-#0(?F zw_WMw4xhvzldv-bh>YYk)-)%bxXysgfC;`@?oKWEPdn62Y`KiMx!}F>RW`C|Kn}Sq zxN$(}rT-B_(!xfK>Ra4}rRKn+bO?(?A-BnFcV=jPYN4BvVUfqzWuZl{RtHccz>d=% zcWMzd5-QR8eWAUYq2wPF3Ik9U1!Ay&oik=6bVXIm%qEMT=*Y1dO=yx+PgzR+V4BJ=hE$aFc1aQJuLDs~XL#xBrVaM7CXAhobef z+(q}&Uq6sKE#E66g;thq3)T!OLpz9qbw-Av_57y;;TpMVa19wKfrjg#k$8dZ&j-{+ z&)tO8#YiZE`dpX!x!qw&Ik188)})O#%G+;Tk3DS7uUdSvw}+^*wIM?Sp@sNKCS>zB zlb?6qv*XJ=$a2SlDyF8yJxchI4=Wiy=>gyaqZ|;ySf}9`i>!KsA0|UieZZh>#p)FI zf=nu8*ncE5;Pv2@;0F1v7m`KH_F0CTHg(u*v^IFMhlXs+8N=xR$4viKf|!d&Y^rAn zQk`&yA6A4;zK95&Go=U->pmdIIv>6QnPrdRRw=F*U`Iz>Y&{oRt z*-6X4GW4I=t^$V?6hhxzQPIs47Q@4%QUa`zCQ5B z;QKlI=y!FmL;_;EjtHh(Q^R03M34foO37afsBoFKQkJQR8WtyZ1NOq7O%LNB!awSS zG?@xTOvneE?jzw54g2#`b-96X#Ka>b+TYATo^Tow7HJ6Xh2`-Y*0&X`Fm;*;?L>mz zJjtO#k447tgcxi1kj#Yv zBFPpW{mzX1oi3gY7t)6z)e6op2OLgp4(jm00k0qvJ-ImLv0^Fs7>c8dC&3 zmzZy|aV}M&Sy8s=Xqx3k(hihjn{cVlsg@pdOsQb;+4vov#pq`2H=fO!<>(IXC3we$ z$}H0xWjk&q%%WG~9wv;&t{v(dThGpHy_-7-een2 zMt*wBtNXCLq!o{EjBlkyYcnu!u>?Q2^Xs`#Oq1t;F#mnpX%7>ZIyM&7w8QwdHK!pK zDIZu;F^O_#1@XJ__nIFgr&{0Ln&eI@t*I7q#ayKUYr8Wq7AGISnW?OvSxMjH!vuBX z-@KB=Z@ZHfBYSF7cNs;#sqX~M<~F`i|HeboR{|2R;WFlAn4Uen9eZN2M9Ih9h)8d| zK)*|Kep~FxG-_xh1t!7lkP})u0}Z$!Xl85_2&w7uFzOycJX(~$)`05S;T{|&*m)?+c~pRMBb1luk0XR`D_YiQEu<`X*-}rR zmAr?ct&r9KOjH9`ZHT|2&jMoIxC=aaF-LAB?r}Ect9c6c#FYl$} zNdzA>N099wB~du5&J5ilV1uB#SbSK*-K*564>BU zJknd`82rQI=^QO9n8qXeYUeSeJzh-OZy@3Yp1!wwKaBBz$_Fd@5c!EvE^Qr5OaY$NDigdGtKe2x%9kx3|&}!I#_^o zLH-O9t;o{T+m8(A&0DK|C9uwj->Tb8d1m%`cXjTUp=9c_X;u6TY}1gEelpaTzI^Iw zgWd|O_;@VxS2u1rJ{7W;tj~g0q zdz_turMLF_uJ`i^43SZ8gMSwA>s;5L`6N5|m&!M#C9S_FZ$&T>&MkYa1;DhPZjQsnU|JRQr6J zD^lQ==<8cStpwgsU7k&=qOE%QN_?qt&0`-C&|A%!;K%GHgPIhT z?^=#u?zkWvnEpC&oV{j?+8YBY6kgQQw2}u>Y^;9kX&*weBiP1Q&!Dr5gwg-?U!M{{ z_fqTmq0~mXFqaWBh-WI8D4_6npd%i}qGEPJvgp>jgpl+12|R%_t}ru)cXrB4V}v4M z?eKvtDMwsFTF#w4WWf|WHSais6$mUk>%j2C&(ApjRfcA40ud-)NG`PiP798s0j&R6 z8l^!=sf3}i;tKX6W`2xvMbly z=+_VM4sLKZnhr^Sop-d5A0c1*pl$oSB_%@PA&2-Ei)Hf#o{Qf*b#wb70{`d*x4T6v zCAzwPM!0B6=lhx-6|$@Hpkz`xL^j_3D};Zt>>|H)+LnI0QcknRD9L`dJ+v#cqu7(C zzu8h;G7`)^%kv%&TB~FF9OS-&$6sM|F;BUOyhpS@$If_g8{mvsr$fT|Zqd0n_>E%r z^{&U4uXf)_-d&u}?z1+zy~Alr$ghHdD>NDfA|A=IKyqQ6;2z5XhTF&3i&{jOWuVUr z7g59Fq*Ip;sm2JuL~+Fn(!xtFViof|^$5T;!$OdPU;JG0BFPmTa?*MP7;fYj!e>iauWnd?(9sG)V zgF?ffJi5XO`z(Hdc5CZ`vb632g@XM#$z&Nt8zY#|h25M$`xm2XAQnbd%3e`om13@9 z?vlZhM9)a31KYQ{u_9M?Y4Vt_R*hp1O_s;-qrzI3dg4*f{1Dr=hfdFnfM#14#lH5t z=oO`}D4@lE5Ft=_q>-)1_QdOx3GJZ%foj^v_^5Q9BY?MV9Qe_{2jAcC(%(45lc}sg z>LSRS)11Bz@lwti83|#RiqZue^TE1}@M~z(|IP_h4VWm$H8ElKGL9}Lw0#Gz1p4r~ z9UQ6nu=vdCta$mFj0AhotRbUHZ!+5XCkth+KfUqT&?y@dwbh>aMQ2;THf*cFyi93ewF|&hFIgey>U{V zQI&$7zdDKqp=^R=&m%|lsN1PSD42U-8xY_~k_GK5@7Xu(2!PnOdWjMsm@J4tlxh-} z4GQF@f#GMTJcMbu8WiP{84fV({VK};P?%?q6~#*s>Di?x`I*$MI%d4R1S|7Z@<_LM z()%xOIwmwLiPjc>3clVs)ZJ9M%K^NO52Z|pOur`B>iR4ReW$T@0 zlv~$d_6~y$iZCqil^yiGmM7;7C!kOogGY^q-e{;xi#s(fjE>x5^49sC@4k#iAFePi z`wmHd)i`+DQN%VlOmj>y&13Ivy>UH#N_yCw!@fS~wItmwus(3WgAPrG-5bU`;V$R} z{P})%*iFs8p>cre-mK3}0A<$F!Uf7*LOTEp$7@qradmWdCL-h!&ENZ+$vtUv-feK7 zU#Bv#lnM3kdZaz(r?RA(stWp(kpEVw4u<_31Wa4h1{sJ}Qkc*_(4BL05jTRZTfH{T z=mA7TaEm_Ozln-j_TY__pslEy`;n>dB6ZS%#s{e|2(Rrw-7OYP z2@?q4Nx$yA*Y^oi_|~cWmvj@;VR`)`sQ2H^{)fO%6V5QWS9$p16|7F>DF}Uvf5D*# zdhP4|j{3^#Hu`qMv_-i%MclLOpz6jWwZco%Bu|LKS@MzY>$J1Db<{N_COdLJke(Aa z4)~&)EKgYYHE;F2-Ek(rAua?bwLGtGySK#cyq{mbjzHK|H|gg4s-g^Y_2+YG?A~ny z0#%+0EbY1o;Xmutxss70{hYK?4fbIWtQS;yJ2Y33?}b7fNK5N;@%Udae=0$oyg7X} z>-){#8J29Nm zbCXbfNH;qVd0<_oENqn}#n9V9;F;lX5ghY2_F_wNOZYZQyk@#~J3eqSJUB0A^6QAp zgBp;dtmTxl)+5ijM@caqaBri9I4u2lU9RFg$%bB*h7Ef4sBaBWokZ-cg>uuSIAOB4 zIH>GdYZ=15x1am+ata7XLey-QEjj#o&9_?aNd4k6H`_02!6tsogN+Mu5T%siK<`CJ;IaAhh!N_ zk_Y+xijEf;t?0JLQBWhqtN@8suk&1`c%!lUjc5M(rRIUcfR}Xd*t=($ZX+A^gV%1N zoWJCw$c|{<$b(}D?8cu}{iiYs;#^<7`_2DgI6_?SE)zg|i94}~XFsdDK0kon@^jSe zi3ug>EQi3Qqv`u=Dkoe=w~?Jy*FM>AAwPY+e?LT);&IqXt>1?TF2wNWZ91%NA+-|T zQ%%19YYwHy@RnQMAfF8D1MT2DQp~i?l%svfAk3?oc$(0BwzT0a|NW=>3C^wW4 zn%oeDq`+}S6DK|j!rlde%vZ-~|M48%OUXd8 zNbhv8zf;M_ELq8253?09rIJ)Nyk(;7VLhYOIF$0l&Jt~+ZMUo8d|(370$7XF@=1YS zAqOi;5UXG3jyarYv_w8fAYa)sw8b@gbvs2H<94a03R_gXC&f|b2CtW(#59hT_>|$IY-pL$d|6GsrgL4I z{E6|67~y^gYwL_OJ*~vfx_S4-9%`4hKHOdD^6{9=pq>r$22DyN+KuRX`0*MK=DB9V zMX(3v6!UrIQLH%zJM3l!SK*uu18iccsjVfCDRxe23v)7D=hW*l0vr=^=>ZXawY)pYQwQAO7JO$MNibuKT>sxGufUCT?<% zk(ZX%ZEBrvAqpl41?nA~YTRlp4q2yV>}6GY?AQMk)?jKWL5VTj%}49`G7*GoiU_QY z+YXw=y0^^B4`69nu{&H~x8*U@r9c_eDqP`cH|Kvi=iNVeWzWw48kkE=+WvA<7^iO# zvIt5W_UqGJmdd%+`FBTgS8+x-i`do6<@r?yyHaSb`EM4UX=A|9J6J=lcYSXn#Ofwg z2{Tbkjnx)&lEJQ_CcZFC0d|zw8-3|K+xFDHW${hNd+-+n&w(mBr9A2*NB{14!I7yL zh`5+H-CMz#>AHHGjmCQ>a_o%et*6Cxd6-j(_omZ{ZH;L{)BCaiiKEnCk898k@;?pT z;s?`R&w7vW_Ky*aY~I|^HrK^)^%x^i)~2)RVHiP4vUvIiv)S*Xo;;Is^7hBB>ew*x z$n&W4PQm3@JQK-{%Vp@0i?2+Y*bXLtu&sIdGC;CMwQ|;(QAP8!Q}D35u7?6#D`fjz zSYnDiuL^&ieRV;IMJr2Q0A2<+j|E@QYUb8f*Y?I2D_wk(nXmc$KinO*#m#;_QBz&= zdUMb2vMZf!)TG@0c9Q{gwH|#F>nvhh^C6JhbW?@z3yYMXf26{y7)m47^&FW|QCmYW zL!?>lagOx^-$q3G{R@8Jo$S;r_U4HpFF(YE)wvh@XhkRQo=kC`oURDYHuo#yzrq&I zn&qhn^yx+nh+reu9NNtsVqffl5g8CbC!2VwK!@p&%$nv=uA|SZtA$e&W%GfyGn<2E1f|Ryz#E;K1=I{? zc<=3EJn_R6u(Ugo$g7$_+2ghLO=e)*wfvKNi>-8O|w%; zSl~OP6s`4VHL`}>H?mhv_(Xa%8$|(?@E|Q=+Ulnmr&4=Ozn<-QjcYeGgzlKhfqVnh z%nTudd|k(m4oU4y)(_dN3S%Q0jZ>^CP@WW3P4t)B8}`M^8XqS zvZ-^M@BV2Yi~^34A1!S{S^f8Y@!J>*7G;YjUSS&cNH*6k)|Rb&PO$7I3eZB~p$UWk zB8T3npmSfS+|hMTUf=GPx@yvBe_?}Q_5LxJAFhbytvwfFEG3}FpT ziRL(7!H}GD4)f;E%Y?V`*D>o5V1KU4=BO@TSIrXsq65^g<_T3!1{V}f@0U+%6f-c1`lg!PXZ z`}bM#00b{SI5jL z-MWYi-%l{vrn3;rxiqxr6)6p0K6!V@(bN9>S?JfJ32Axd>#fW>n|AUz<_vUOd-3p> zHD#9CsVt9|dsT(&IX2|P8O<2aF1o&ZGBJqikirfJL~hHEJo&HHV>>K&|ED4R-Z%%4 zkctr)a_4n4WM3W1H$S&GfZ;M4=6)7`IQY<)0M?D^2 zeg1QS<@}@@j$vCO00nr(fWnBiFTQWs1tXB(Qm$RKdgM-?g2{`=UAWw~y3OtMY~P=r zxVS%>LrQPZ>Wg|#v~oo`1|CRS<`H(nDSu$mbZ|eAVXl`vW^)4fJ3XgzAi3j{a)r#k zIm{X!#5%^=n4sb(yUspfoJ>YTFy^x4tp}aa-qeM927ex=z3->sOX8)BVd)W*-sd)I z&H`f{SBMKu&?#%`F~0~&np{Ms^jiDI;Ar@iRy}WUqBRbl1ahYaS2Dgh+tlZfMHWXD z_B2m2KKotS0;3>p2N(o0dDp&VqSB*e=fN7iA5-c@9|XU;)JZ!q&H|YCAlFIyU((ng z28ITU6c~wPG^ZT;zs&N?NX>r+6>jCK!MUHFfz1qZ3aBE_ZL9m67BzP?Q`r1E%_`*7 z;c_7w{~_s1GB%=AGud&VilKz+^_R~zx{qCOi_bnWtt*yFu0Qq$ch7Cn<1v7}c(xWY zvA@kyICC-)M###1K)giitm|@fmqw^OhGlC+gw5Oih{pe$-nYu&LaT4SFi%~kV|m?W z{qT$zOwnyR?e@6t(E$I^LF+devAkX*^*X9V*xO2-h>{D-Jo_FE%p6gaC}0yL1bK)+ z@pXA_Jh~(OyAi>6KVo?k9ZP^kOjf-#{jG48)@so$ghioN54M#o{e>rWn{3d6gX}5p zO9?Qj=K2F%BSs2|Q61qBe3*oycKw^QI5!0Ey6^_nlT1 zD<_U?atS@=95k&r7Sq3c#b)#08Du*+lnoo#9BB1G6;;HMA*5}XUF_&@TOop2Y1o&z zmwL;k!YBQ{DZDdZJ^mf{B!yJ209{v+$vo7C`Qv9yG2pFB0P_StB^eTd$g@w2NniM< zNWDnaqc+`W#}U`LmGix`tTAP*|A)dRGUaoevUe|7bo)ov>F_51&kHab+!+D+qf_{T zqE*bkvXf2B@DJZ#3S;SxXH9mS@m7BoXC7L2+XdK;Uq_u%z2F5Pe56pa(dYg3(Xy12 zS-V&nR^z3&iKuZY?bibN7w=z$ksS8kAkuCd?;Xl>QOZRQ2*1?;76h99x#^CBzN4zc zmb~kBE5lL_uD8$sxZFaV77>8;yt=euS&=mnhX}80&h8%M8EfC&pI}*zrb~yHuk@p>c zsDA*Tpsc&Kc9?IOF}8`hKd)7S%EG|tl;^3x6~tsyAF+7CEYI;k;xNbqiA-J6=L}6F zB9U%99AxaL9ZXA*gW$Ht<-WF>un_0TIF?XgL(gWKA+EH{%2VVoB7$+<4rH1L%Q2KtN z3e#ujdc#ZKn#4;QtdFX4$iNlgy+W2R?1}Aw({{nmO9exB_sfuN%_5kFuY;2Dt2#f{zk689)F=q&2))#yhm=%@gF+Naq zkVU)Im~)cNDDrFlzxEEXM{T+jfagZ@+Fgl? z!f`p(PkR+=QD8X^6n=^`BjHMQxa-O|PCL$Zbv0hrHD5-E9}x#FPM9Ds z8N|CcU>V>ld_*Uj#jZ@Qi)I5w%92_-{ZGS$d8E{s)z%?7`U zjsB7h40>~;{zE0|(P}l`8tU`RYVNhNGt(>9iZ%E{jEb&Dsrvg@*>2pW^<`wP{Q93> zSBW4D(p8Oqwtxv{M1p!S-0NLyBkKjM6>|`CJ7_Rd|0C~a*5mSabv)2a&z>I_e>>t! zO9po*za{Z|$bkI3|9y1J+X#r-)z1GENR!#_~* z*nHvJfIV(00ozL;d)GGC%}P4s>PD@1iVuO^{8n(F7G1a>2GgkEi5T(m=Hm`?V7S{f z+_9EULkz}FVbtvKDtyAqCp0hr&!$=cu27fs zsz^*+1yYsLw(v~xKHf;gYnkZ^tLxP$T1#9M1Xo+>d>>uh4TTss%|MG!_My;Xzf>QP zvhXS*pmL7qAMu^9Rj6{iL2*AC^5(Zr8d$%!;lW%=d>7hSm5qtt=d?O(eJr7-pVlGC zAt}~#jdtL^Rfw`-+Q`96(~Flj^H3JutzK@=IoUixw;Lc9!JCC+BoB@PxxO8YjZ!J4 z{fX`HnTw@n)3hZCn5dB)t&?3b4XVg?;Cj+%+_5laxhG*BWds)x9FTflwtTi`B^i9; zl&cVP{N&r!3tH%>&WGZO(`MNt5!Efuq%Nt?>;#e$wt}JhDQa zYUNBq+qcM3x<&! z3=rhWONS02&HZhT;`{Nj6Ac_%%g_QEk_%pl6oftUo z$wGwuwvAAiRg*Z7c7MzNLW`Bx)H7X9Tg8KR2zvWhU-CkD4omI{MOK|u?I>t?rZ^(H zA^SIX7o*HFD0UERJ5#W;+dxpR$19EdfH;Y z{=B3z8=zmk;BMhl`!J6%BMb9o5sQ6pp^J3!vyCJ|@&)OaL45Z|H7Bg>I-R|C{zG=Q zET(H;-cXR7Rye+}40?8CcM^M-#=G_<*H&^B(eP{$7AlvoRs82Sli>XM5%|!9#i(fS zD84&r8L#O#cXx=b@QT6R&1uLUvbjCjX)Yj)%s|P<@^(l(4+t|0JJQ$4bh3L;gvFwl zu<*({Apj&g?Iv^i11rk4|A8YWaekRxWVb`Nv^} z@KulbMMh!6nTZ16Um}^gQHXy^uGXt8!s`Fh0kFKTMEeXAnR|vHoVXH>+BgWBINkkUXgt+-?R)xL-R{1L=p^-2fO_a3 zJm`d({>I*fX(Lu9Pw<-_wc?L2*qH%cp~vOJ!U{*#{S+Q=qo}r-e&)BDmnc=Bc<^(w zI8SLaK|v=xPp*1GMJ103p6NbHjaqsV|Gpubcwus++jhugXv`J^%gdL(j!LP8w!fu=ZT=kMrr=%ef!R&ABDz?o~==|D|<8I+-gg!E!HF z?R`{%J0TRuNIc6Qru~;r+BdBXi{RY=wF3o?u-gT;%Uy7_$LtH36VqaKOM3feh~HXpDIiJ3C&xRL>Q{|LkFGLd|kc4FN@5Ky8TyxS$|z7tW>! zW16Kz?K0#YnN^1Ez)hs=K+y#ijokW`;nO|f**~k!R={|=TdM9cDL56srPGQh0Eq`^ zqT=0-aRToz0br;xhU0zrab>Zd$EKSsJC3$E-K_4KURfwtxB-SS%E|xj`te^9=zlS~ zr~tB6jf6(!c)u^O*G^AU=5F@&D=kLuP)#ePN35#pT_p|vVtYD|UA1}K_yTbMIKewX z;`+q~-~}Jsj5Y85?_rBl;TYu(^E zUcZ|0_$Bgy%;ljy86@3x&blb|7&Ft=m9aW5edBaISua6o zXISsuxp95ayKKpK_Z$*-O_T7z7UrwcbO{QBGJXr3QhY_cH!V(V3+#us4X;$;Qe%VT zvnmSf;dun-fyjH+kRvws1@n@dH*2lh3^r|BHkEoi6>o#qFTgZEgPb+D;f-NrC=#jLW5GQ&dy~+OufEsoiS_`VR zR@XPw;rKCKrE)ksCXzyLR@Wa;7yuG79xhsCMzf zEh!nk{i}UA=M^EZ9l*&zN@wQq)HzSh)K*gLh1ABD`^!Xuw#(1?8yU;qLRl+9R0l-#h%?z|r2tisP@j zu9x;VUe}AY^dG?YZ|b82W^A+9$KImH`Jc2%B?{voH9O=e32!JJ(C@eR7b+HiyEJ11M0EYP; zy+9N_Q8I8#Pf(rVIFOVw+9N-XFWF%Hp}r^PIP?<_UvEC#INbN`k->ZGv&tdwz1h#I zNZV?MqV!)x#e#bJAY~HjgR&NYxAUAfyS~ran}r zDjL#>td(7_p3-E+wx?$jf&v+V`CD9bJRrcO5^h8x8!utX6#38$*xso)^TXFO>G`s)(0sLum-mYgRIr~B4=@cQsmA&c4 zYI|r;xB;S%xB>H5%$_TyihKlP3%imEy)?EUP*?JzI!I2mbeO z^rc5*C>&&|PK*7z7*5BhpZivU+=elnrAV2%#DYT`qv#Wb{OPiF$3<8ITtcf{;EC(F z{-ZaBGA2I;s;x(k#BpHPY=x&WHmQhvG0dd_m$6?d~DP|okCHN(; zQu*JJ=2L&*F;kBPsHxYDE0E6)%wpCPo_O}#!h^>B+`!yHX>KNy8WotcNCzsFMl<)j z9$gRbthw2Et~8ob2|pcHej~UC6vJATozwWF(q$qQ7uPA0|7aNtv!;*GA5!9XEy z=juSIvDt#+2ByfzQmp)ky&su{ny77TK4?8OV&xUFX%wEgq6an}g!kQjp1&KZXwfdk z_xY3%RM$1n#+)YmVs~z7^7Lm6JS?8EwBTdK(?rP_jPJ((8`t%!c8&4_ClT;$*(Zx&vmrRgGI+-F1^K83 z9*ePYg65IjB0mcA1U_)q6m=X7oBv#2r}C^rmDYAqp2g|FwnafnSF z6NvG#OvOi%MUjb?yqNoxrk#Yj1nu0{i}S-ed8lFl6OnmaSH6vgQz5Ix34$wFMfpU@ z;e!s*a)-~tiVr>ns;1$wAI|M^R}4b;s1~U42%;QfQL7#4gnWfx5#?W(DixykSeJP^ zn0{qmQTs0ZCYLqZKCShvuhM?1;>w-~VNT^u-~~vL9nvj(9EZN@k#~*jJOR3C)s+*e zB?tWEA{pw`R;V%szL5a-_#2uCl2iP|LFao*ng{1ti%y%HVPLJAfqp&MOZyo8h$X9dWijsTK zE8SBfq?!}GL!BR0AJ-$nz>CEJ48 z)o!=Up^f=yvLnneMhll)u#Z@u5@S;Cp1h*S-n0zCJ#Gg8wMK`&@i25;y0dm5#)(T5 z`1vDJDkCjNgOt^V7VWOg0BrUBp(sP9Fxj}}oabl4#YGfJLkag1z2!w-%vqd{Co-v~ z4c#jOPKRDM+`+;6=!5=+U|iZ#7*SWdR0BW2 zwVP@&8f~5!Qb=4^ECR;VEC$JnWN;Eh7UA`wR5egvI>%?WE)KWokXe2LbP6i+aZ*8m z)}^WcvOD=m8vV&Vd=(y00k#`k*n6aayhCw*2pv8+`wfDv@DW661KA#dWHZ2?k0K4% zXUyc97mWnjB=ZuZ-vvleEU&CMzAEW!a7hOR2^y3zwXj9|=^Q$gfNnyc#ez?Z@sOtmSF$j(ksFopu0(xtfN`;$omiXkY&tbhVXIph{P0VDSbOGlJ|i&NF9{WJU?`c zJUD9SM+Srl%L-lEjw{ew<|W}Pkq|V-G>gWBF3$kc=#e5ab&R^6rly0b&EtxxLm$9d zkCBhvzna9NPGkoFx7s``xiIYBeB$XK<#%xdc9RXVy{vSDEMTt?E>vD7e)bM8)SJh2 zg0|Ov+jxj5eEgIq6{$fWv{x=XX%fM$Xv8XNSCs5luCN-DCr+ib$cL1L8$!cD0ps#| zn;>X_ZNT87t6JtRAnh{D{Suo1@kpxaA4+fvmj%zi!Y^0x zQ{8k_Xv=dmjYcu^D;@%^nqOAB{veELo7p z<@8rSdG7Ben+B~c4^xVxLzZOd&e-=pfV(B)g0=FS9bE2io38wn-K;TiOrKZeCdu{N zu+4afy01$t=V6+QmzEbNvP$vj*Ouna>o8i>r!F=a+R-Xa#p5`6h4rEe?cUg;O+hSM zf7rCf8sAp(aCxq0@$aXT9&iOB=;8x&2WM1!-F{Os@(1Q6p;S9-W0%x8demRWu|at+ zkN3u!eShBX;|3z|xp&f4vWD%kO><=}eM}TsZ2|XrGA1K+85m?~QGa8KgqM5PZx4}m zb9KA|J=Un^QVco!1S@U)-841ZCH^1G(~d5b`!zupyqZ>t>&N(&sGDms6|xHLp@(<7 z;RXmW$kfO1(@DoFV^$o6$^W4WnTW!U%K|tggdgp`@FKl$?4JKq``HTf7-mh7f~k+v zy~}vs8mIW;RwkP7-hioIB$WaSL}?4h%_x5r@Kpk-Ha$0WNK8I*P?0fXhjJ|kQf@p@ zXTKqG!hiIT8DR^RqMfBXE;f;@Tw>NM-GDo zC2)DXrlD=tTdXN=cq(B;bwqtkMOl41#Qh^8Cbx0M%72+igqwC##ns6G`!Mf!EMaj^ z7dG0;p^NcN({Du|)uqJzOvbU-=Wcv|hd~zguS=CJ_x`ew>&**1_e9m_JFNuKB)Cv; zx1l10=~rQN2{g4?+CkT397!mNw+&C)&9M;!0BSb$uv4pX&`& zPy=!7gk71!S>_CB=H_I&82J^Ta!YrXKke4U&B=UN0*sb*>*l8#?4<4x5VjU*RtRER zdv^V5?B6T%i`SJ_GwVcJ9!Yu>{WYCYigIQmZ$sHzzN#=UC(i~GE;QQilA6fFJRMLn z2V6GiYRRr_is%lx$jyEc?fhnIFcg4nAb?!^Zq1TDKvAz#M+wZ}$1CWU_^x<=PFMqo zm!lP{RC4MUvbV1c;Nn;z5lRWy%g!{TjT#G>>2E=&4;=81-@)T8#M_Q$J8S}>k&}U4 z0AvtVd!TsRo0`BkzXg!ma?cUR5+V3~pSlMB_WT2udz><~uTBG_=c!PizI^w--%t&N zh*(vAXicHu{7Wj&&|&Z7awvUR{Cpr7gH!d^FRA+GdlnBdA4iT^nr0p4$A5e$u=z;1 zv2_PwEhoc?yC`0@Q#I|3U-Z6;x#qZj(5grzKwr*11DWB+l%)}nJdnFRAQ?Q)yB9p* zCfZ`h6}P05M?yO!lSb{~mu*a$B8~hDe^<#P??FmTysd{*TVw3Pms-i=78QTD%?L~g zqkOD}aKMXIkEB|l{VwqE%@}3)C3f6%PFHJ^e{4m4FNlC)$NlMesJ){mM`eD(%%?Gb zr?x~7;LkBMW`;-5ME=xHgomrXsr-VjcP><;K)_FcnU?es(?o)fQ|z{0quxsYNP_X> zCV2%_ZiaC+U3JCsbD|CE^ab6S1l{Rkjx3S7jOAU^v3O!|x*%%9Sk&4DEMjzEso_UR z2Yvamtx(ov-gXl&V7S3@+o(%4MUi2q*K8$}70i*>&C`fe_kEgt?dF%0CTFb^b*1l= znA`=?UW)lKK+Q%E4(qi%5lv|HwrtuUhxV1FcU# z&Ie2#DW5F!4)SaEtWQHfEf{d7X zbpSsgKejy5*Bm$ViFUkiA}|{{##-V1u#tuWmRZ%)k@Q$Z zOZ@B1>~QpVd+JcO#;9#H1{4&?wqy$n#jwPY$r{K+r%5+JcL?yQrrUWp|HA5cHt!8I zpu(P^rCfz?^wTFERSgrj@w-d;;Umlw+MVD4ib8Z4yz<>9ipkrnbiztKc=c1qBo#o- z8IJc!-~kDbfulaZXAG5ov9)liBTXbcqG8`oV9@5mj`fd4aHApe;Zlfe)_!!xD=uB9 zi`_tANz_Gr9Kd9#XVD?AuIAC>E0r(og9JA^fA*!WSM`4kg*L)M6;vEb&H<`|vd>DS z;)D)pPmxwUozAdWa=#FnxBuq__-nmcsBxP<26~hf{L|@Cr9sKIs>Xd1o$S2SK}=ad z&tEK5&?eucVmd;xcrQ=}5f_>o+$vHrwmK+u^la{m=IyfH6FWTVU=)Fr%G)AB3LQ{U zswO$ITBqGS#Uj1iJp8`-(~Z3%Kf4i>9!&gWLah4ZFEWQs(!?M~5C>Xc=xs)~MRqh* z0oZbr1#a$YE0{38xH%-()6vHX%oq6LBh-*@Z7XhyJtpg3p4_SBOICp)Q@e4-5fIr_ zD}Ut8!G`r^OKN3|bFuQRB%(SZfalPc>~{B~r&xRoeh-lccuqANlc);8QMsxsVWoj8WcX~#ZY zCy3sonTaNXEW&%_=Nq24i?;rz7p1eI8hd$682Uwz>@Tx#7h{VVr;Y~< zu4o9=4p;)^z^b1HF0vaysv{@QyKs@Ihp%o1X?p5^?wz~72>me-DqEFxvnL1U_wChf zuBn8budu$d|2aS!^gHvhb6xqUTe9)6P2Ddac2NRTlF%)?iAlL8Fu5lZl8=DI@e{dbr$LqO;@Y9FOC^6Iud8|IBYnr(SOH}Nh}uec+FW9vdpT|a~$!AEkMHPPPQ5-7A4 zWk~B|Q(c9NAfyK8c}DO@&Rw(A8ftX6VQTi3MQ{r|J8P4M0h^-@>_vddSu?V1h19IS zX8k$5TkW4Bz3bmp)8TD|Uc-9W~GKW|0cx^6a z0@;G=2w06rMGYd<2w7q!!Uxm}cGmS{f!{>n2?}k&XqssDVKkrwcP<89JpEL_*KX49 z>CobZx@z z{i_Urnj_Cq%g~9Bi~4iHhQ#+zw&3i~Ph5FHv9be;&DoV7Smi1?7LC@i(*%xHenJV< z42ipE$F<`gw0eZ}EV>|SS5HH;P%cg-RJ1Ila4nX^zfn{+sXYoN32}_e3;n|o^s#5k zd*(Tix9SXLd|?&7Pdo8=63%Js1c~m7JuachR%)^SL$_tFhMe{yd%kj zoi#(KLBa&JjWztz)B8#;zsWhJVyV8!E@B2q4=5^ub4?mU?h3Y!tg<$#C?SgCxL+jf z%sMXYH1;K%ADLYJSew$TCf4ptHKoyZC`o4}c|ivfno4_4r&NO>O@GS^>9mF7GW@~G zEkH@af5u#g<8^aj43n(MS3b-AIj_ktw)#c)Fni7SIRIPXbs^1R>UeNtUa%=F~ec zgBAl(({^rYC306^%vmqwkaNbz8i1^;tKUQO&#o^_7}Q0M=B6HdNubAS>3`&=)dmFW z%lp{XE^IMbrCl*9ouL`j0jhqR^O!Yym;7~^fwREJzMhQ@muj|{mqztNE7tOKMT^Bf z^y0*iM1IC1-FG->Wz$ASm~waVCVvn1(Z z=$+lZ6oB$f3H&wWg2+w=iB)331;Ix)Y$PxQG&PRLY!boAeGaC%DCDTZ>9K4KmQfod zwG2OKkmzC-`e&Xp%BdY#C>*F9HLCL-a z@98(>`nABE93F16tvAdidz;qZ1a<$iu3i{QeS`Bo@}BwUwT3dena%Pi!=qQJjW~UC zD~|VOdw-#^#A+FP5wh@CFoI~ZZOCv)_!`s(|8nE1v9_^=m1eFFLnc`a`<0XM0bXQv z2z1657uQMRfy5x=jA^gYkV!~Zr5$A;yi!n#j1!}QSIOf_XNGS|y z9b7ue>qPSP$I4_p;*A-r>IQ5*|3oND31-hYaL_v@EF!Nq~Zb z{3xH?*Z2TPjITVkDKX<})KmmD_YzCZViSIYr4w5^;y4LuR{^U_%6}x0-IVm6XqiWj z#&|Q{_*J-DpT!svYi{BRA#7>ih{|;q}uxoaEY_{W5;khq^(i9-yS5Sdf+ zP;UtLk<$tBL2l9xm)2JF+a4OiO*4@Nsm+R}5{B5>m<5=s=^O9Mm>alr_Ql-gA*rfVxSns-*ThZQzElKls6pWlgyZ|x; z&24d|SE+!R7cwVnE&t-0b7p%cw#Ca7nk`G}zpb^y&cjrvYd27R*<~zJ$h7-8Z#qUo zikSM55ZzjcRyz&wPcKpL=*g4G3Z~IDl2YYa(b>^e3y(0X>EZVui^nZhqyo(}=XT&9 zvUR7(Qd)gZdX(_NxbYG+c3LnE5dmW#BAOEMfkN&EP!L`o2~r+tjiyJCx=it;sO-FR z*nbkLWp#c!F@Aiale!pF?kmbSb;%dK8@0U^DyqXG4aNgoE*+^!^BfXzB^*bJ_aXDB z1Vh3eY`G7g*cC}E;W2UJy<0QCSadE$=_0IMrb6*!VWVix_q=8uhhu3W;0qlcdFD6h zYoKG3kz-LJsg=a>V|>83f+)4ozUZjfVC$N-CibzsUqs^g+(oovaL;5gQH`@~u3COX zkJ@B%a%8DoUdolLS14?KDd`T-REN&sKVlwDc`ZHQ&?0_-^wlqaI`HLfLZm{tLlf9s zX(46d)^qpnbXdvsuYb-fxBDFI1zrQ!?&|Ww_WflHWG%)DEqH!65Uq99RYz#_QlVE86z=t%-JE1 zG3`3GxVIoRhna}#$Ty87T1Lt|IGOD_bsSr-Ri(DBXZw1m2*}SnnHOqWM<6X$`2s%+ ziNK|5@U&zcR;T0_+vR_Pfimdy5Sb8pr}O|@o@V2wVVp}8XyCk58zc^{<;96zZE5Yy zk5ALS4cgV3@E;8AhZ#iGMye!=`(^kJ8PflcVC;9IFZWHA2Rm{-frz~ic4BX01uHpy zVf)PI7(|z!O;w!+*i{I4=orzYiE}`zr>Bk{Q z{9A0JeZo{=ZL1xQi=vhB+ebsss7o$)C>Qw9{e!W)$wiM|crmd!oI2C`ixjwDaY)#P z<_zLUO$yHo03_4okVf4*Avr2DtUr31Pc0!M#XZ(>9js_1=6an$^#x_({-aI`AAgCr z$p8*Z9BcCXlp3$(W|(ZQQNro&pF2eK)w`%bcC}=7;vmuAx&R%q_d(T|EnIYQ#Vf%Q!9>=25jisYijO}$Zn)GOU0})(*fG6+MhQlT@ ze*Z5R+>GNSCWCq+C6?I{%_lTL0u z>wo9x)R{;J@a=%RhhR3;xKnbtJ3O`BLTGNcTfmhcsp@yRe(u2Vu`4bG@?4aqQ{-u| z>~WDsn!+LLuj-(R-cyW#xF}n=aE-&Dh{UI6aIj72h{#CztFrz8mPyWbdaSVp@jtRF z$%BHMMpDfH_hr*t1$iaO9%o3MwgHY;Q{+6$Dd9yXsjX#G)HQ* zm4b^8?pN5X;`~Fvg5GfY88}Nm2X*cSS^!^2AzfnJhWF?Ye0K?M5+!m|hKynPiZ_fS z3Ls>eflx{AjJ~wcMjGpgMiWjYnX`ud`(XX~Vb07MGCnCzxn=&?K;aZ{ftEakClGB) zg?vu?l7&xAyRy(2#7Y{6e}msx0I{M^#SEZrYlPUEnx<|oYH8VDbRgWCj+|3v#4x;i zuA8B?g{LoH2|nATKB?>^&+Kf8;k6&5`aagH%|*_|T~OGrXEf{TV&@<0S0x_g#a_GXza|r< zFEE|aU1~g8TVT-QIdZ1?p9DX@hqJEhX8V3!z7NAr#+rf?(OVB-8LA35YJbtrq^=mI zv;1qTVPkSi-%tmepIdL_TIVTKNbCHaBGdA>TD{^cSzptj_?2gSe`kT{U;ESTq->07 zks~$GpFOYDj^$PkF53SGNP*{m7^USLIX)&MF~u0rGhiRQT>!L@U;v9biK)R~ve9PV zSncE5@e+j+RNuUP2ZWLEvB{#CA+ikq-QVT)?bp=){MKUl52m8xpW~2#lZ4Hve$?{S z`DRrRgC7WuZvyoFqy(hO1*qN0c?%@sEY*2y2!u4KKk+~lhLh)q-NhhPnp%Zr_`pGC zDJm(lZHYhC1%OE`Cpm<0zfZIU{ulg4rfz7nP05NFvevI;WhXq%!pLlYZ=Ovw!;%a2 zsDCfQEkcGK{pRU2&$N`w3vv_7TWfVrBW!dLBc@W!!7A;%E`e!9UhfX*gttn*WCh{K z<)ioTDzganmlY(2Eer{$1O7)mnymK~Hm|G?wzvOi|EKG-{*xqw(T@^eG}?LTJzpsm z@v*9&DMGWsWL#fT4*$I&Wux^vE@>@&Q|gWXYk!U`;SIq!9BG*4_y^-BQDz7r$EUB- zV0IHZJC>p+9_6GBR3-tDWBOTCGureB0_!x1s>Hf-wD#|89vZ|GeUg2dLU5`XW#kG} zSa!!H4EBG}-1X^hcmP!2%{mxtWOJhECX{4mIEYyv&0R4KCD5qE$?w7+wi@1%9@Zk! z${=dZPf)(nz^YS=lj9`8@t;BbQAx$Fd5qtmfFF>grQja}oYWua4EQ?8CRHMZ;ynr; zVo~2W(46AIENvG~xISlwuL7`~+|VezicxFAwu@}`ud z`m9zQRX+xUo&KQXZ|3i1l>`T+HACg>L0le7T z`=eypQ7B2S)5NQnOxz@U?@Imfrrkn=Nxi>4h^w`gVAN48vUGfRX8>>0Yp$~L=))}Oq{;B=a}|Fgh9bI1}3oSa0<&v9893nMy&5Nw5woDKGa~$1^2~K zjBwR+b4OxTEx|=4)vqt{92YmVaz6HQthXXx+OLM>c1BpDLFa_!3*H)L1!HsYKbzCV z;@+p5)_$jk;e>C`^eJoCQk$2c27Iz^J7<|xi4xzqSaKiRlG|du(jr9Rc|^ZMXMQe) z@^JCg7{e@&c34D(vaS$>0p`J^SXX=^%u)d*9w%VrZ;`4It^!&F9mB{eUo;8OE;BD1 zl-xW4bt6I8@sATrqufW@xQDH%l}sgsJoNGCtE{y4MXba}Z`bffI=BR(qD&vM+Sz&0 ziqxp=1Y#hwdib8Y7nK3MD4Ij%d_mZ@l^4hpm70mbyBM?j)NEGH`&0P z1wZ$gBZG%0nz=a^1y7D)@CsUO3iRgZ6i_9ZwN{WR zkvyd1JmVtX@pI(U>~rGB=)ZXi-{Ds-^1yV3AM58Q(%4f@pa+`V%^)W@3s^;X;%(@# z-pzA_^ZRox%HV)~6lGZEqFZW|czy!ZXH1G3CV_~QcO7>FmnTNrMyjS?X-YM?kDqQ@ z?y;rhYjZ(6sUX17fQeCNj1#0@=&6^P&%$3{iZqPph2EcamF6d{ot}nn00+67U&f`c zJW*pyl&ou>S*VY*J-9(yTPE9%WR>%n;75d2eu!}n#WbS1klNKRVyjyQ6%p!BZsVcg z`xPfQ$_&c2`)i|vnkep>I|)oerCT<>TXI{%sV`up^NHi36aIxP{eTRl1N7LUQ4G3~ znZQfH47xouOB7FIpho3SJbaY3bHc5BU;CeEU&2cuN3u!)A`FEM)%D)pU2Js({-GWE zN5>>zsY2+-AWQ3KG4Y?RnqW{ex3GBj`Mo7R)eNr1G;GX>1?^k=8Ra)Y(w$Qc@v~(s z-JEfH5@Nt9UH}6PDcNbiDPHrCD7DQ=D*Ni34_GC6FK@ZSySN~ZW#>i%s+pQhNfN1< z1$nC^y3zK&LS$<({4@Sh``K?V{%}@Hf^N0QppzGd%jQ$b26iw1CjeI&yB0M|C>V*w zIO#h8&`!^b91*Xe^+}MkqJ$m87?Wj;drI7PatPw{)=$|H>T7%~<5qW$=%EqqwnfgW z|LY%yvcY~=}<{WnoxWcYGkd<~_82<}do z76~+{@nS?S@d7k&s$2u5(~~!SA6NeNaa;AYSjb_u^UFlfLCUT}BQN4uUKpN89JLt> zTVj=DEygq}M2VWJ>8r|2OH36yFXxQc261RfOjhxjDa0(AT!4)9rHfFz*$dWhS}&AB z&VcLe0Bv%Fv(|$3L^5*+RR^7=^D%B>Hq*voq9m3bhME1$hnXNIkI^(yn95m8(|k|~ zoA5j@Kp-4SB6m_G#c;yoI5G%ewii_ECU9;$5R=@=u*PlzMmxe2Q_mJOXF#asra_E+ziJx5J}&{#|IcpG>hB1YO`qT${QnGL zmAYMM#n*i3Lb^8H>8KZ*&XhjuS&YujBU#M3yV-(6v;xHhWP7`2d*y! z5Kq}p9iGv?x_w(yufOw^5RW-B#GlHZanI^aMS7}vx23bM33ZUAhJ=GIQm}HHfTfe;FHuupUc5BHgUgbh1c0_Gmw2;y4UA2Fe{h)OPvj!p&eoD&M#=X- zC#%x%LuYtk$<`G&CTlZvKeO9juc8KT~UMjpj;P*8k z$o6GBW}zf4Y)jfr9MT0C0+kEXK@ zYx;fPKHXhzba##J?naQ397uPk(m7hX6p#`Lk!~0Rq@^XKyK9vC%+K%p{J&%D81LQp zd7anmye{qwMsKtf6*GrmlUy%7aJ;pSRo?-V=K@CJ@T-#?fLF@f^Mp)^sV<)r&1O2X zd%+;;5GHnL3bN>cT9m_IL$SJlH#)931vJ4cwm808$)miXaZDDqwgwm5MgOJ#F?>4|-u zYr=gzpB&%G-EfMFw)S3k@m4Ga0T~7>!`O^lS7d2DUbn8-w+2rU@@$oE&ubocSs8CE z?d=HfTTK1-hHx~%0O-pKZf!4H@!)np4=c^TjZ zTIt+*H-!ROjwouY`sF-d2{d_>VOO`(G{}rb~&G5^vaai(Xa0DN<&`+sVrDh?lW8{&$cIOQLT_=c$HbBZP7X>E{6wz z6O>?-6W@i+DAB-Z6eWa= zylfWRb20ec6CxE0n4fO93`hfr604o2Cv@T#|B_xFuQ?KvU{)5<3{QQ7^K^!Cc68Pt z-F&*1Ugp!CZ58zBH zI9Kv^<`Qu{tHxNt%S~-`)FzA<@b(>k!pLsCd{cLW%zunhta1>iC|bRJ=zaF=7X+@OQjZq%e@v90l!n;T!mEK zAMLMCt&awK)Y)Fy45{o|0ycR_76Il=Z5f`@Cx~IP4gKQ5MwTv9^R<~7Jiq#4WcC~; z0@)(sg7vS?w)^%Bk;*#F&+isF-tgLScxM z$3l|d`P9~SFA1mvK#t3sgxIv+R{qxGNYyuEjo!rG`)S$#pzv_QxM0*Wz^~&*B%X)?X52rP+(6 zU$w;~=#MMfhX%dsLr8b15}C$P;0J4)S;%md=D3wTmyemhO;OKrOib`Ag|Cvn+MUGRgNQaPX6BvcKCvW0!GG zpl%LO6onXOmXP&X(sfYDwYN!ipXrY%3?BeD8E31AJe!`N5^4oa74TCa%a&OeHpXX! zUua^as!2gE70-hLf5{Y!tx9bN>Q@kw!B7{O!-ADBETXh4OB0Otr2Z1=rQL(=o(DJE zer_jg^@x)X_fY5Jo~TN34`-Y07O*k7n^!Kd4)Y;t;z@+dCxnD|8u7Jg3!hm65vK8+ zNP#H(9$0WavCZVd=to=TQp#lmVm-yP9*9skCS=WS_{VLq+oV^~3sJx~(yy<64YjdF z3Uf)iI(&I*Lo^T_ny(%KyuPp)_0S`Q7>SJc@CMu^jg4tnaw*G^>!l*mr6l3wK$86Sv?Z(HA9{C#B4*T5+DROOb zfv#RIP@P;?&c*7I#{~`4-osVmhmXrYj>37fS!^=Xmcg?aUbxQPplY(0$J<#3>X2I17g%aruFieV z#%Nsm{_upp5hR#h@7!8HU*lnb{6B+Pu#PtM+!=xUI(ou=b;m9zyCp(=Nj;yI2?fH2 zaHxiwWxz5|Jlzs232f-^8W0HOS)jzLVKMoypN{YI*o~R{%+bfu?&w9f?<*@`P+7lrQj5)a^RC;!Zs5=|Fn@?CvM@U?0i4Z^3EjlduEnPyqi&leI<_-U$ zW>d`TUxOQ^^$|X_K2}0VdJ`vbPY$(Sb^9Ob@4!aMXOp*us?cR0;vwQ!{ z5O#Jg8tn`xfDEB+t-bA6iCSNp2^sdgn@e~^IAaJqpA zK#v6DfGwUGDrdIwZdxIdrXNWKa`BQ8tB71h5Q9A0%Z>uA9DVSfzPOCuF%8p`0<97k zUB%phh{~&>*M=R7NlQ86+doS+J!)J)wZK}3@lha74ssHq?L!}(3W|0aLX|}?mXoqi8NQUt^Kq4)$LT?Yu0H9665Z2#QbagDdhqTg zwf6ohu5~+yy(p5-XS#F}bSGckA94%eZgD`^;7mh5lJkY#WV1<*zfRG~CmDuT2<7r6 zH&5iILp-HG=X`*T(zpL8+@YG3|8{%Zi#({@3zydx2ByH&dUe-{Z~|$=Q`S zd^!VQ?x^w&e_wndWP0F&%P{G!#L&EIZH+L{6z|#!H4FnORQPzC5 zNIj@G+2gn0%wzIGKy?$jY*S7q>=gWE^i!7o1W^v-jblkKE}n(BWSH5lA*K*sU75t1 zGu3cJvl#aFS2F*P4NXQHuM~Sa5Emyu7ok3E$H{*Nt+8Wf_Rx^7*HAc^k)h+w1QA>2 z%&f_O$6kwf9_e}ZrF-Osn&1WX1wN$SVB@oa>HED3%Vr_8^wC-d7<%-! zlAiO2heU!c%_pdNT&_&b_cSlb_$W&=suc>PVz*s4dXWOg*f*TM=^fC@^SjdnZ22UdwXwvZhT-(whJR+teR!XJ`)-*$%7lm|* z5^I;&{0UQ_kCRUB&DVjjR}?LDmt}()iaX;2!Rp1V3ga#LzC|41D4Q6+WOgBK%@54$ z;`7IoU^S&+D~c=Yp%vzHFI33hBqPKUx?XO%6BLwKpE``HYyJlVK7+#LYHa1BLp(UC-HlxhA=2OJLKms)yfX_Q@3;C-p^CtOQ5i;wJ@v2CSE)Pa1L}OS~hk z8orznHeP8V89ZQ#_Ji~GQ$+F1gI=#gShbquxqkXd6!)fG761rsp5cg>MU3aO)$SJf zl_sF?nWlvcQV>C$>2W93Hn1@>SH3vz9U8zL&-9?}lOU@ty#999J=;PZlNAWPWm@B` zbsVs>%fZ2oCpC+*iTmGEkT-_!&bVXA2)XTB)Ty&KU}+KQe1$We8^0-ntu&Zqv9sjY zAQxHQvqu7<(t5`5%-A50@`rRD+lovXm9-=iq-NI{%>96(dz*83p?hNMl~|xA8(#kI zq*!*D4XY)e&{J;-71Yfa%k*ZAMJ73v4h=med4dnV3md>I-r#NyJ90Tj<`KUwa6 z!Qow5$FEAJyySsmfp}8buA;V|6Wj#7XhN@5Xtt@XFy1O|rTjGe^IDv=dqt$CqCP)p zCu#3eP%qqB&*U$YZJ)xQ07zmDu1t|{8lTfMx%qjQvV#?U{lPx3t=Q@MuU)qa_E z(0j=ZL(-CZ(s$BSixQ$=7Q4*x_a&wzNj+hm*wS6EqC5Wlg$CkH>2_^5*4X^<;ruA{ z=4vb{ydCHAOWeBaG$iZT&(~a;>q4@xIS^l%4rnct%KeD}34Mi2!fFUXc*)7%}~ z(1vQX{k|OYVKhCIKqAfEeQ}i4U8}D97sfO7_UH8bM=c}u4D2# z`H&+Q>swRlRfkj3`b%;j>8-_yHi=O-H`35CaE~x)h{2EZIKjya&pOg;@*b|kpXF5d z=$Oa>UmTt1e^!*C7d^+tekM=Y=tguyG`{VKf&jy z<`tsn0}YkR0h?=Fgh@p-#3F)`Qz37wB;JPd-_B=}>~mjB=X3HL>$zFb`3s}-SvJWVK%TP+M3!YG0I3;ICohc ziL<7vG_QOo|E<2aMO!?-N3Z>bG~sJ+;!}>a+S0tT1^+PAdrx%>e>^e4p0n5oEp$tB zOT^g{1BGwplCqW!TPqj*(ej+lXYpTPNNraC+;!R5ta(!CovPdB<*3|gq{&?a?{X7i ztx6%|St*~THc#;S)KA{$g{Ig~0EK(423$p*Na=Z2Hd{pHs|F9*w=5XvXdqhx_ce-O=AbV9hhp21B zl8GExu!Yhn$?*Q1N%10u=4ruls8~^(?4Mk)fX>^S%Q|OdP&7-PRST&a8qS>jpc1}| z1eZY-`QedU1MhEoSicw0=op$_=WGp-TbHU>>DfIBESzvH`!mK`@k`2+8B~8dHe8$= zSVjD03ZDs(D351;_%i&pT0h$mr^_9Wt(62{w%~Iyq}_|v`B37OsHjhj0>d6=#5Nit z{L8cdut1|3XvbI|vKvfOG=+{7D>!+znebmCrR+&?IR`2C(Zl~|TC&iBf)PVaA2Cmn}VuO{uU&oBN= zdZMy@peV8la>taR-=!bv?rg?zJt2l2yybB!&E{GS6 zw|v_5vBtVH>eNyyW2`akYa*pl3u5=vTgFS-1>Viis#}!RrKrby{zcRYZz6Z2F?OHO zKZkU*Kb@ui1Z;oKt3_+Li0dms)y>@xFtT!y%|F`?ZsKy|9a(>o#BL?}Q%jI@?D{EQ zw>>^pGuo%93jQgXhXtu=rgP0C)9Tzwh$_a-h&1l@gAxsa00@^&Hxs>VT_GaFQ7G=3 zb9}V>Pkoh{`6QV0lf^r8mkVD7Sb`Fvv ze1CfoA#&l*f(+ERtcdNh?16OCc3ZE`@AH7EBTdrZFHPR&hBdPc`?OJ-xVz7y6ZGKY znL#m)t=^>S-pa5kewKJ2ViW%h?GIWY6&MvJTlmZ*G6lu>mdGh#m?e^hQhxdS_t4#J zn~Yq`sL&d3@@a2G+aK!hKp>3?Y2yAr{b|6;+* zC$7Xv85UbtaD6&x0R4{4DZ0#8C_Ct})7C>v0MN7sTA?3k**GXa?M?d_k{Y2je}9dl zg^BS7?@gc0AkJ|KH#1{Ng!Bib;g_2>q5czFnTud_(jCse_YfQ8eEpbk|w$8E_%h#{#m zLM=!C)8RmZKywCoBO!f4`x}f;Y%T())TmypJ+E85=Tpm$_2cCFehZ;?fk0E z1_gh#P6ry3)*b%`#a$NPTD33u(~d92z2-o&1nZOheG-mr{9CoT^}(@Zf@oZe_OLZV zFv7vEwgf+@{MF~3;xNAb4(c3Je&{n2LrV9HnTSj2-TOcN`7LLVl!sf)7(@oU z79>o1$d1fqL%?iwIeQoCaQlQ2amG)vbWRhBNIK)FDIiDnaQv{*4wfQOO7U;U_cPZf z#P7QRO6wk@zYc@hgJ@z_Up@q5j?`A7DIVU|qO?`XN;O{u$V_?G<#&P4FwD`6Re~_S zM5KFHgpbl+6CLhO;#E*OG}DnSL^k_-t2Y_Uh7kGva8|!pEZLcNpSAp+f@S=D9IyEVv{b zMZ`A{1my^>m(+T^wcm0GhZ7~69s`^AG>jNZMSyIpWEB}=rND|G+eG5VD9q_qEsbdz zoFxf|Z;-i`pETsTSi-Xm8AyPJn&D#vH1fc#L;r{GOkK#dH4|0ZJr0NG4)H{MCrzHk6LspS{47xEvAa=m zrt_hA+-Br$;0PXPU)){J@FD3=l3eTZBKK99pEtryWbv8-2?X2S?1w%q+Nu<$9*!q}eyL3ne!VARVZC*2Z*F5#^nhuQWvhdX18my(O$nHMB2G01=c~rbH0n?I z5hG66*#36!aozFEsZacTr=X?HDETFw{uHw4hFV3Qb{m}#m8gXT$3 zX@bkU*cJP6U9eLFoo##ZVvxH+g>Apk0g9BU^(wts3BN-#ZchP~jqOnF$5PaP_cD;5 zH)C4^MeL*-4Rud-7NBE3)*@@i`Y@~Ja;$7^C$JmO*lTcb2a|wQ~75+TP|2jo-eJ;s@Y5(I<33F z{i81V9`)1dh;_wxtliU$$EgdhRQmVxBg%WCSAT<4|f8iL)syBQ(t zxi-op9vx@Y4BEMJRXzb#pNuINz!yUP{GCyjz5De3Lb71FDqv0Kj3dL;waO7=XEg(9e1)n{xtg*)fA*`m3#F?dQ>942PmBA^vY(#BxyQ3I+ny&f^$D?l%(ArUle!L zrYe{XyMWJ-=|Mi4M}BNqMcjQhB)u`-db!X5oA5M;Rfo~vS0_}rW1c6Uf%evnw7{|6 zGS(XLDFuro1zgXy_UOI=w8DTi4p7fBhwqK$~mv_@FI6i6{ptDI7gv zbVsD0BEhY4?y5}GEd1xsih9&u^w43d*048?-TdUkR{F|Au&;()+LQzWrJ?Yt}f6fzM(;Z|1YK1b3u5v^WP9{DDC+7tC$Xi_UDT zt4b4b%sO=DeJI5j_QlqvhJn;cUZrui6LGx}wpi0iFPmB{6-cc4E)o^C$GGgfPNexz zd#@VU{GX3J$zIeR>76~uuY165qi_G9_l5VPMux;c+~psiv{%cdAilZ@vxSe@9Wt)v z+0G@*XH0Zj6fwt58~>jL*qR2=Y5^cBQm^(rqm_hZY**zrL(}t3Y+!{@^TwYUjj#AG zN7Eri9Nz&nPxSMu>?zmmpxc%iJMn6DtpzP)7K~r8_!u8*`x~{L#z^(#IGJm_0!10n zV+(US!3J33dY+x_YKBM}$wTD2Ca<)7q*@uoV?Ul=rY!TY;^IS^x{$IK?960;$Kg>;!P|-E%)!s%zJT}`yPDxrO z_TWy363VKJvr;C?WsskRjw!a3MP)kR9$<+=AwwWi;50-H0n)?D^%|DtnPR{ zNxQ>F3i46IbAR{Zo=ea_uktp<G}Xz%w8M4={X!J6^Rg=wk21!;_>lmfk2p6Jvob9 zTWeJ6lB$m_Vk}}2EnpWi-^$m*R`GB_pz-CjgX}W3ue$HAM0+fsR;=mE>aQE4wHo-* zHel8P{slF$c_q9U8%V$H%r*J!fdH$U{amo4+7{7aZZmI$Bv~;8^~g@y8cS0v_Orm0 zABFXsm?yj@&!>i5{G3dP{%0Pp$McI(dOoh)ea>8LE@T0SoydE1#hsZT8IUv8*ORbV zwmCbpFPLOoEy^I<1Y{qwk`?JNioHBW4)b>}gfq#2$(5WDUs)vSgzhsKT<(s{%^=;CfK=t&8}trYC(z9N2gD7=0gm3LYHhEkz}zh!fov#nQNDzwd( z?w^@f!}$kQjH=OlLf9X^x%&4byOY#kzo=j6yr}-_&zaDo*|k7RePz|JcbL1Abs;}) zC#lfA9ptfqND9cIdX8wWAEaEp87U1NF{l}Zb46mM@m|Njz|Z%@fhi~o#FBc((Z#%o zx1pw`+w(&rWCDm`-s>M!`w$q!7eMH}fr@Jka-61A_M1D^8py-x&9d z92p1*t06PMdplA#p3j@RXTKPxe6e1-O4ER$|51D5``CgFLQK`z4*t_QO zuu6}K9NZUfdjpM$>h`CYp_K2?eAPl_1Mp;feoGrIdZ3;7P>TDw6^eYI8#vA< z;qjO?i?T|UI&c4N7V@Y!{MxI2Qh(gOpVn${UR6Oc)TL7<`aa;gP=b8FazR8I{rNhd z<*t`Cck3WVM0f$1Tm|`jEch4%ZTh$c{rOQbvHRw4BheiUt`_&cFR?M zPqtCQ@WT-f6OO*LOM`EkxuT_#^r;)7AqJ3J#>|v?KaKXi#48y1oW9Iaf{vU09VMPm zkw9p+2hOfg z@r0M|>9g+xgB`|%CnLVqD7Nq0>M)c5Cdjq8e_@yHZ|iJ0S+g|^LfnHUQDox1RJ{LM ztT(lgJjq-&BVL??Atqe1t;IHp*sc^MI3Z@Rr3Hw2kKW{VsVP`YA;q)pVh1kH#>?3Ui zwjz3it#ozUCJ2o%1i$nE(EV64*D0*E>2>q{#Y&32@XGsFlQ%gR*Rg*eJB-P0+XEVXDFReuzftjjB2R zYWzLXN4nk4$j$}cy^tmjqyJ9qSCc6=$S@SPJvL8hE0NY}NoM10!l}1wYkZs$-`DQh zu+=7c%|#Ap=PgERP3=%Lv2@q<0E$~e`w$I6tbmD|Od~4Ur{STy??SYX1sXv5dB!N^ zNKNcT3|ZtBtQMibGg)(C7zfc$@x7dI!pVhr9l!jzuGAez8D;M?N1rd?N9=>u?5!OQcXR#YR{MzU z7gH21_LlGCo|6d-A)?q~AG%2f?R{}#3ujU*hp7hTjLinqL_3(K%-QyaQ({-j7qZ!I_I-=jC4R94a?BF~l~;qTw?);{rSXJq?Tee%ye+Kg9`RZ_eP za}_C@k@6GE7x>kzqR{h^pbUAcu$-W>ctch%=b7tPlJnKi!8O&Y#zUPR2UJ9VptwBs zlksLFG8+aOz6|u;q=2o=mJo_H+!TU2e*ZB6frHrZyXHx9idY80(t#q@c(kxJP8 zT{u2i-Y3JwokYl_YRtLuVtIi|h_(CiHu~qGJ&ugvwiD5TBBF`_-xM6&mI@vYo->7} zNMpM)RRRWQ!mD!1@(>?~LV^3JZO2Na_ZR*ND^julc91E|-Qnc2c+I|Rb#3Bo8Ec^0 z@s4X^#%#Pj{vo>ELFR&BAhb|bN;bF~O|r1Dsi}aC6|K4+p|LshQPx`Yg~L*;1ig4* zetpYm9z_$hA|p-JF9ijpHRRTM!PI=RKnP%eHR9P$jt9w1^w3H0 z%)A@=XG?F`Y`ww_kXmcuTEYvzk4_XK{V));wpM6ts-)HJjxfJz>vSU>a)@Orht(n- zdSbuCIlpZ0(x&qVTi*(|cnPGmmnPaLxw{%GHt!1p-npuXZcXVt5?e`=B=#D){_yyI z-;uy&WMwOxd$wKe_=xCuJ%zI^a5rWlS_w_BxPIPrM#@?>K~swVs~tp>Wc*V1_IwHf zacCo0**LXK=jjK@c~@)I~6 z`q0pszAJ)kD8nYH1i|@^HUohg_&@}&QK6q1TPu$m(@QE?fo$F%-Ve0~Pp1j{VWsvW z`^55DsqPmDkA{}BW7mmrs3zeH#<7!0<~qV=m_aWxR$$cWNW2RCB2NM0x9P~{x#;mR z@@y(>rDKpVOW&=GVX30J#K}-4V|0IS&&N6Ge98BSv0`<^e0E)l-_k zcUhl<96Kfp5RO5xJI%y{M83tiIUPOugu1>~lR{a)Ina+{?<<8;w^9+%2g}EVW>fT? zwXOW-?t#eEF`zqI<+r=MEG$ilufM#Gib-dZcpaj1PHLTj+mJ}6M?8#YA{<5VSc3tS zsf#FHUK$r9MO2yrVDlIKo$glP5LTa)0?{LYgL$l%ID@e#0e@s5mMX&ZHGVkwpZrGAXDkOyX>lUi%{7Fgwv&t+^g8QaAG7o9@afp zbntReLt(;qERG%Z(PxJf&A&S5aFt4qyuZ{%6tm)Fjpv@>gbrnilohCe?QS_gio}mn zr%jFWr=(Q#=C)m9C?^P1(xw9WltTc&*up}}DDNFtzQz~FMU-<>CzuCG;zcXvYPF5X zgG6b99If@%hdA#v%v`a9k8|{azOs3zJJq0Vi|E+y#qoP|uu}hOmC>khFgO}l&sJuY zZ7iJe0}OIhyZJuGmfH5aA7B?b3*i5$mD`7Ki299h1myIv6qRP!CR6M0VA>-_FpNd0WTbiixUdY$}oU(?;{jHDJrCX5Md(fuu=3_^L z2x!m5-fb)F@|0OexC2HaL;*~re5EdEY+w0}Odg@<8O%}K{L5NDf?TNI_W@v0rjuBv z{H-@>eRu=E4rR6Q9<3{nkUi2wnNlk$%QQA`=ZPqH(C{`7hi0McYaw-dj`30;-~_28k^UNQFsZ=b~OR!mdelQFVhZyP}=}BPJP{Q3BSDBvng> z$V2}+oZ^!{u%O6mESC#GtloNFL;}#?M~bmAtcCIe_kX?AJ;+$5*}ehRA`PMSbKeJB zOJTx^*rn^M^Qr{O^&DX!vy&EE^%`O?+KQ_aEst$}Tlh{>o?BnW<^)AzUd z{K02DuYVzFwZRycjW)Z?|AgijYW_M97eWk$Edh+i&U(0(L^^m@YL z5IYOt)K`H8e%Qt5jI^mP?QdD9D~7V+97-e&IS+bd-O=N-6DE%H~Bp+H--3w4}yUo7JcIPnHH8j&qEdn}7* z)@91JcBz*<2euY-i@5Nk>hwi^#+-wE7MwygI=F{~oUzZ|Gh<_E~ z$fZl9G6HIcN^QJ?5Jd6xbt9&e3C@NUl56*vt=t#^Tk}kiciyaW+!xeyx4b|yTe$^7 z_py(&r1}r8YlJmVJ~~OAFn)2It;as&>X;=eUSnJIe%yp`@L5zIRj7!F4}V$?&4D0; zW!zF^g>%c0sAWN>Y;PS9PNL_b$(V#86~1>AqyR4)shi|Dyk47aB;ZYfPJA*v*8v&E z0?1+Znx=(L@wb3osS*M=Jm)kZ8eho^+LgEdq8EFDdj0+($o&M1KP&!X-h0@Gf^Wf3 zt==mL!s)1@OpN37i5)~MlZ2w@hIXldGwIoYIjre~fBRFp<=8s)+OxXZA}8PBlLB5? z--b@o!_~*GVa(NiR*QtofWB&087sCwk80=XZfhS5yv(u8UZ~oWgyU^drL~Da)vi>0-Hg-6s^q=Q!ci`L8+80L@ z2*7jJIc(|@*DI-uD#To3RVKt-;-}OUp)ZIY!j^Jj>OKaL4s#vj8OL$3O)?nQt?BYH z2!SEA3i)J1e0G95ArBZHqT8pONVQf1ONYrtd&^ERL<4A4LKh97mfiUTgw8-j!HP|x9PCO&jxq7MUKRp;o=W%Y?1ZLQ_$)VSg z`#ga=c(22KZ-Qei!BH{_&uzG>z5gLIaA(;lQj5ReS`OLSCf{#ENc1j%WT>K6pg_v) zLn!9HlaG{Jij`5Hu7|nPx@T2(yMA%Ul71Ya^!{Xw%rzQ;LC#&}>u?XW5}Y!f?{eZe zeX*!}HQaN(_?&W7cO)A)79`yiNS9$adMTEqMF44%ZjM|;zZLGu)JPK~Zf9;!AH_UxsKk*JBVFk*DmUPRQM#x6rswLM7IgUa!i{(uJkuX=To?Csh-K=@8=SO z`ZBcaQxx3H1ebl%0kA-F#2`S;_!nLK;)4E}fu6S^miLd%3)1$f)HC?y8v!D8j#r0L^Zh~Vm2cqO&x&_QX3M>7 z29S8KP}d3Y)18gPH{h2Ak<EMc|C050RnGv0YkOfQIzkdJloxG0=BEMNKW)LUB z$)Qa4at--uhX%L_PW_tU;UBrJ=8yFo$pTf2Gglv!lvJk)FqZwW!aWJqu)I3>isnAbm!Q~@V# zzN0sl*V-V)TE8bbiipI{sM64CXZSRo#ID}9{Xss(IcPkFIjp)}A9r9}zs&apn^kRi zhM(aOV>&sW)V9RB#j$_-^}sgPVps8>a&^2W>x^8Gqulf^-g%hX8C!j?YFYqeDz2^M z!I&!E6LF{oHH_BL`a?$em#V`5{D(3}qv8tYMk&mhawL%RfFsHt%7l|V@@DG{-Z!j# z?q_LB1MmCwq%bt58Cv-q^fqPwd!4@&76Nyh2SU1)aNk!nn)|NYO9fv#g33}r!@_+p zqlVB>zdfPD)xIGQi;3d&i7~176>EP?bERuYvi5F3Z5*TiubnlE^TnY?07HC{bV0iw znF>9i=!&W5UDfEx?k|0Vy5jamLTlW5q*hOrB=|Ter;qnXucD0x?#Jn>2c%xOo*hOv zn(g1W)cr8$XkD`k@ zmETC!xJX?;dSIkg%+J>{;;8Gp)+LRM1`4WE88!#7ti5 zA;h-BPQ1rOj}HenRc%>6$i=7V_$f7=4^%1zc<&n0WN+ zK5f50TT6(oi+ePtdvE_^B|JVAFH7(SSX(+%3ZA9fbxIJh@7eQe%tG3Pa9*>-c2&#U z_}A*8nOS^Yqc$W{6sTVET!NT?&7LAKvV~Zl$9BT<|0uK-yO$bnn*Bt}&i!RwYKe(r zsr@PPqlbSH5hRpU(K7lI>#%@|8vZ++*TdmW<6$@$3h09NBTiuDr_4{AJHM*X6nRn2 z(`>OoN{!-(^_}EiD4Bg!Q3*3z5aLwOb_`?Yh~ct{QYqNLN@JW!&^Fm&vVbP!9cwp# zvs^qvdWpe$vFgk_p%N8fI&$q~qi=`y{W;r|X7-8@u4>_*I9*0X`!#%49=74^g7Rac z$4W`&wzn}Cr(4j~IIGII;5g`4H54aK&;31W;FiMKPc*>f%wIDxGL|{4 zpIHZIi7hHqLHC(5DgEg**SE^1UAcVwR7Knl35J->I$j&&JfK{u}ni``JhM;bDDe>@Kt<1vuJJ)TU6wtb{8UK-7uVF%md)R%bPis9&C?4 zlfqMm>B)enhkO_Drw#>M9HUFry~tMglnrxHn$ZUKFs=LU6o9z6n6<$+zIX;yc7>s+=~=L>7TiS}((MaKi)n?w_n+zR z?iLdwEklNCLRvvOmGM>E%#hO5azk34in#Pg;V98k7&JdnGnBf7EkAsNiJKV6l?!sX zJA(&J;T{~=g26_QKazihbVq_L}$(Ay%P;#Y(Zt*lMN(CmgV`I?i|pF5KC}E zNgKC|$doHY4jpzOk#@Qy7|}pX-dR>A4Dj?rDh?F-0_AAI=j}yMmdLCvD?v3-6O0YW zgB7#cA)mgg|Ifa9BEkM{B>0JCq<7*Wq9x({HWA|m~UPf`*fof4mHT&JaapK09N zXo{Igw|j`u#NWT`5V`BI8>+>|D2O*}l5StBF!key_;&?K?A&`MGM6^RZo)`~vhAl_cpvOE%6w z)7+t2Hr!0WUHb^=FD$f+AT~NFl**@P??n^La)r(dMuwV7v%*!~hcApA#9ga0m?uHN z6~`e3&JI@oOF}g{hOLI-NRfwGew>l}_t8~N#*>1diiCryugGH$xn5@)8atY&dAQ&E zp_Whq8Nw%RjVNs8J6~gl3V2%&CUPJ4wxf+W-jZ@^qMx`A@I$Zt@IzYuk{M@+-Ie!I zi#Gq2zU<(NB$7N>yUhYD&8t<1$L!ss2>A)9nA{STKp!>zB0SXY$+e7;}f zdG}=NV|5UI2}KQbc;j4sM4ROT=&uO!AZS3o{ynszbcl<7poiK>UPA&~2~3NBYAa!W z)&$DwURAH5Ju?(hKm3ALOl9L6GpbOFGu|l2F8~9bi-=w`@*c;7ic@IZfcXDd0CXxP z$5fBe%iZxhT$A~twF^s*8!$8v42FYtFRg$F8p3kF#wFSIf)wD*b1%C7kLJNEK$1}B zdhDJIc)go;JX`)G(fsW{W{Qpo*p}r+)sux2bA(KVx8{1;S9lmE7-4zN?kuu6m>8am znWP|QpVV1Z{g@fjw&ss5HUL@phAFbKkLRXPq1F`&la9P33pd5JJ3DrDv>p92&B(Bs zaf&NwVWQd=yb)?(u02_{{2HWWwOZ~E?8Lw3p2p2f5Q>q(TrrEIBuN$pAcIFu!3ETx z4sWx+W;lz`VC!eQi=%!eUrKN<=>M{9DX``paSmPpK%dph#0W{lQx!q8H>vNRy}9Uc7e`Wb(9euD1h5} z9Js2=YG-w zFJVZlrl5r%SfI`87H{<}KoIsn$;B({aPJ?r9mAvNn41J=mf^k*Y%hTq*k#}R+AFY| z4i)O}Y?;E<%al>1_3_b8sd(M7lWu=WC)QRJ)9FsGHjiz&hCbq%Ux8=TeR0RFt6NOp zVjtZ2281&Z6yz(RMu0MiU2CW^Bl4*KxQyLjMHj4}Z{RV?zaX(bstrYgw4nY{RrT&e zj)QvQuu^O~8^KFH284H)J_^A=Aan!13k8~5xoVM207DX+>0vd~V`i2!mDtIEc%Tx> zIK&}*AzkBoxh9FPCbj{ZAPX!*QZ;0by62i5^F!0!v)9+{D7I`ANwo zIdhMaz{@zTnTdYZpQ{5`TByml-T)v3lS{z@pYtR^xI2?Q{ z@hoZ700*TT&NVtkBqh_n3KsP}Q5`A8S8ZeaW;^mp9KfpjtuS~~fVpL1|RP-~{kW1`C zA>k)jAePXVtK2vAUQCAGh_uZp3-ei5T0`=>?s)MGvC-{$C`$;Y-d^W8umY)|sDZ9g z$|{p-sc_Z`COzMr66iQLi+RVI8dQH75bqq47<0Gk_9wr&H+FmcczR6AaVXxo-Tpwx zE-?W^{YQuuQDR8PPv69gf&npZ`3V7Yno#iGzaSL**OfEdrL;{UW+`LecytL;c=lmZ z6m`{CxA_s0SGeJ_ffyz3euIXTLB0MdW94}vESl}semZr-%^1y6y|AYBQzYLEb$;2HVq9EZJ{r0eLVBkFBp1t z8Cbn~8`Z+@5Os?|C<^ECulE)#TM+0bd_YW!a;$50{uLyKuVp3j2tVNOG3&%-Y6u+hW0^L&0A?c!?cls!lyDyUod*bk8KsqVU^d^mfY-DaE~s8q|9i>ynxP?(V%WoeRAH>MAG3sZiPbk`Pl4cQ0Nbq3u% zE(a?94OAQl?n_2-hv}*3*&uFt;cu=sV9aF z`v%6JZ{d}>$iyr)F?(FR9xV1UUdSdqfBX6XnQ z@`zyOmrtWP9tX;;lhg~sLfR1KuyD{>tmv6Gwud`$4h>;c!5D=W_SaDQ?@`QHBOr?s zS>&x;tscf5Q_YVqGokWsod1g$I}clTH1F8K=PTcu5qeReu5rfNwd+-b2viVEl zmme1G53Z{I1r9tapyb&8AXhJrIQ2OQiQ)3*~7V@J}FdsP?l|EDe?uk#xH~3(18U$03 zbF2^sr5to`JYt10HQ@tHJZc|6JV+3DmO@=DldxrKAX6MJv3E}LwM18m#heENd^1$ zTCb1@P#+f)R=^^4I@pzyx4BOmS8Q$Oar0!I)F_re@5e`wUJ##Wh8sE4)JH)~?^sV2 zK~2{>-Y8yo@G8preHtE12>m}wLEa?n5E}1;Bb4OEe(TJ;P;2J2TKZfpf&w z7IcgE1ffY@tlN(bfxCcGb8jMq(LTRwn;R$kMK27jL>V2|_MJP{ww~M}sES6C{r&cS zxkT-61>J(!>AP$*-61o^>rM3=f_~-<7)SsLPMj_WYgH6j_c26)Z}bTaLWesle^NaM zcu@0FBJ&1`g_fNXxfp5WY~xaEr{Ka;8ynf38W<+gzcpI#nKs!kT=@U~o&3G3(>A>Y z#Fy~5r>@7gqq_R<`Nc`qckuoz>6_w?Q(V2iutcY%-Sigy&tRQrf^8R2Xzw!i%ezg{7!7N{_9 zGo+cQRYIF8UsA+m%SVqhkf*TFj+!}u81!hw-sz%imGxyLPO(be5@IV*T=#CM%3*Mo z<`11!8#=U;gx|e2+m|HP$1a5hX8F>4T8P43S0}_E@)6>wAIijl z83E41e7kGr4;+fz1^+Fn6mFKMQlyxaA_ywR~mox;6_pT%j-lkllUt^^ zni+z=gQUcR<*ni5-r&S;vDx~~9<%my_&|jbJIF)7=1}5y(@*smx6$;*U0;mpCD=xP zvv;m6sLzpPLO*k3x*-AY7KYID))GRoyTifp;9s?mStHgtBdy;j#qUK;Tt@JQs9`wa zHrWUsR>HV^dV-^pW)2_ml*}WC1HbK>-sQ#x=N}h7PU^1CK@gQ@`WRvpPmo1FTrR;A88ODu5xxt)RPT6Rd33$wy)j^Ne@nP;j@IQ)Oy7BXtf(y+{o}50l{c4F zk|*SjYZSVg+Y`0j;KLym-Bd(1a- z6gqxdcAp@EY$0lw--Z&xp)Xg=6?sHChJRBJefuD=-O4K9^7BCtPA10cD4s=EKN4^7 zHigCzx2`Q;z^t_bJlNlpkKwi!Qz}9(Lf8lw6M;)s_T%DO)}DyZV)~*=h46;_k@tmG zsPCDw|9ZzhTp)ajA{fem1CG8N#TTv;A5{TGK=sfsGJ9AtBb)BQ=RX^7&!>pr4}T^! z(7weS{wBi=x|3(N_%X)JmaH@is{+mjMuZ13<`JZDp8&_sS0Vs#Fqc+b> zU{}suI}O!461%VT#?8@(q4*;PMnfrL)aC*+B3O4n%BqO!77~%(%<~T$;x2_un~e(K ziF})vxc0( zUQkRl`4ptJ{F@tYGiuh$WIm{ew5?g>gEYJ$Eu)M9Ciu1F3r8|c!AK^Hv$mT#XIDCW z-v9m(i=}f`KkFOD!Y%d^;# z0~tp4`K|!B!iYmREt~|ey09^+IW3$r4~N46PjbYLYKV!mAABW#IJy;VO*8L2#fUY0 z_?Em$2qHjB@;8^yxR--Q4WfY+T=%&C9LT~a7mf?lV$TynOj7I{Eza=Mnxh#M?iqMB z>n)>8G2=+(u#}^Vp8$Pxq|tgjQCfdUqzd{Au}9?B$AP{yXa~%UWq)n(l_yDtzS@er zWG%~<0=7XIV zf_TP2e0DX1@9B^X1ep>-m)Atjl8aM5EEd$KO`?$lR31tHBW4J>wq}U_{$|u*#y^Xr zKkive+KWsPu~cS(bHkOyp^fUG)wA62M2F5M7yG>@`id+vm-!95%XUZC^$bL@E(`B< zD7Kz%it=lNtY4a`+1C>Vk4Tiz2J0b=ahUfn|4vQlcwJF}D@fglk)aHk_=Rja-ay5Q+$hF3EEj z8%f2B!L8f2A{AF3ecHhPneB6CzjhP($Im&atQ4p!Z01Z2sfH+Ffoz4L|LTpV7O8No@VIs zbR87t%+qRm9H6m4isUes(`?&13m}ahLis>X;tto%subKdTjzN*YW0reWB#OjYQGH$ zF*AwqE5dGF#aNDIXsq;K2VDW@ERMx%^o43h!M=jY2T!O_S3>E0*JqtvUHtNEK=-dc z?}oPSUS3Ggf=|yY8KD~gzqe=VVdZE0onX577x8&71RKy?qVKV)@CH(s+Q@3?HHv3` zemHU{GVN}dOlr(sb%oKlD95(xE!IfCXT{9vmQJQUHPy5)H9v5N#TH?%G3#g{$I3{N zOnTS5i@Y8|;`T!rFbWhP;p0dtx^I*GfiE%(7Lycd=+~m0d8nRoaT#(Mf?W*v?2uXX za2ik-x|%PdoOJO5g|IZPMjjjjTPSXEv)_AI1-{R9sq!1l@Mi>OCGY*ZEu}gzRNu|p z_pJ>v2W(KHCLhscm!ow}hEDO}S(R;HZ>4&!rQ+~O>o1@{5~eK=Y_t7ZQL|ZRiU@ag zb*U0C@$@Uj%q27rc93PyPobg4DNR;F1r{EDsQvWwseDhujao^G5(lsFmN)71&-?L4 zC&FsN8_ez;MW~O7eU;-`{)oBkQo7WsuHon7zeV$-UR53yj zgL;}yoe#D6=bFr3MqUW0fvwWC0^W^iOQdB)3rE$8|T+c<);tHzh7d*a0_$I zB50z@Qrsx?VX(7pEQpF(4eM{n(=}QhZ%~m;Z96xb62zkNm=z){JL_*|yG2WS){g;> zUUMn-bP&3F#-XQ+(YAH5&3v@bEAj<0(g1Jbi_4Fy4{dd|}mW6)YN6)bGHn=@h5rA+J*mZ)+5;g9_s{*7Xs7&INhN+-;V~F^C-2N<#57co!EbOV z4IxRx;O%S*6f-bhDXJCUyc9 z^w`{J90&4eAawwU`^)_*_Xf}Ur_HGf=K~07KE;jO7d(4n zzs*HvdVCvVTHW&1y}9pcUL8K=zU&&z71~3TR-CXv`g(2g&9Xm@+$02@)+UfzF ziFZEj&cs)kLjhrv*m_f|;kQ-p+@qKg_9W$a7G#G~ES%!8KnZ^8R)VkFODojZbNyre zY=)J;tVR?2tYl38QsN16IyQOZzZk`B&n||hs|L2~1%48tOva8}S=|SBhYCa2C@MJ} zecY0hQFo!c1n>qg%@0S%CC!+ASGe_apS`ds=7s&rAJSf2W?RR7H5$$e-LZzX_2u|u z=UpSeNEHmREe2>)IqNVJ1H^DKML9lWXZ5x_`di15X69KH!<+oFcFc2fYH_KaDIgG8 zCc7u)n!%PFGESoJOGi~Zls~c%OEzrTZX@hckmk9A`cvo<#PVjYkbC+wy9 z@J@;x(j*T~we~gwH?Z4HoPa%0UwNFScGg$MAoEcY7Bx;ZhtBLq+>twDQ3OGKW4lM^kNW?*sec%FXQX1 zs$cru!HM1P!($jF#lC|uKiQr&tvakN3k+&9?b^>k1tqlhMwy@GpWrg3Hbx^{2vEUX zqUk_y>}}B#rJd3Ia1M0tGj;s@gCn*PFQcSsu)5Fm*Of2vKJ|?Uy;K`nXX!Y9C@rV0 zwq5J`=mdLL&9djh^mU*jyt)$Q?_r^X+y@vpP(NqagAd1O2-P2nbo?55$D74iNt?D& z9axe-BZTG!j*q*x7G4G9=rP^Za)xmatMQkdSx+NDT{e=eY!tZgM}=PjdvDp^E71%nmtj zzc;lWAr57w4@L;I)kp{_%UxMy{qCF+6S^pJ;4!R&nWWF>XVj%2`2|>3GUbwW*7#rL z{u|z_c{zY70Gb}eH~X*Z)RoPnNPsHQ+i=e^TnSR@dBbi1Fmc#}syL*Ba2WcPdK_Lo zbSbqIgF@syITYE!BAiB36&V%Y3JJvCM8Vfnk(<7h3MF#sr6Y>Pq$Q2bfq{gfrjdJ| zoUj7FYE$elS}b1YY!s5QM=ZM;MKJvVv*hw;9^Cn|#fyZ;`E_L`glb(xHTo*Sp}Yv? zlR|@A?0w{f2SNY2o`lH(G&t*U-Z|wcEp*~J|z!|^icBw;aL=)TR^qc3Y)_o zGx;3)Q7UkXf|J(g9XNHD)DH|HT}@E%-Ixu!)?Gksuy0uj4S~&>dbs)7?sEmUbkKymc4o}bAS{n$X3S%X@+b+gNipN23Aw9 zCF4+gK9&eu(U_S{jhd4di5p23gT60x0e4j`ksZ4Y54aU-bMG+=$bK-Lr*IyfR$TG|OVDGR-tm)_ELf3Fopn_U)yJ{iOR7*N5(Q2T6YsP^ZS zV0-Oz&c(#QeQ&4Vxt#q&yDHs9GJ-q^*yA+!H-Ca;D<`8cx%6pyKbFdqv`zM|L%7TA zOp&ilu~?{)`+n(|Eh)CKIid0`hhpZM)3f%83Qn zMP|TJnsSdj#*?-*?nyaTbz-9lVrt45IiJH)`t1!66q;-f@;9)13vxv5qV-mM{zNKF zPM63>a63sXa6!31Tzf`H$SD_XRJ&3?C>(Cd!u%Q~p!kQBmY(X!B{dx*JcJC96~@vg zw9i13gIt)JT)g*`FD7kyclA?vrk&oBJhTkeLx6Kb0G?p})8JP1(ii*jb&*EqX|eHYm;Yk{1h|pi zv8)6}gb^CJ=`j^Za=EE88(9whZVm)iQ(frLrIfFi0@4Pj!xI$_8k$C1@ggmJA5U?5 zSBYVy?}P}FG@ek;LLu&UavLH+!FeSi#n%g!uo@gYluG!wqM?APqs)i)xB`@5GQxIO z4VwO^YG`j7;XhvPN%1?*0~JMALWjKZVnj<3hKV0`p5$;VJ3~q>Ny$pOyKj=D zQ}ygd6F^@UTAagUFyFsa=2TxI4F_B=vA)2;Ktz|CO?!-yq4RYD(-ed<|1?muEztZ! zLZl6%9L*K_1zM)sNP%RS^*=NmD zVZJnV{XnLE@>{09knMKB`%u-gc$Y2}yT35WfgF#fVUN(1f&YrUlLAXE-#oT;Rt<^l14wuA}>LI4E-gk2+fko8`N!fVR zW^H<|{4?EscA_h1zZnC>aNdceUcr(s!k6QKs$7~VzH@Z{G|SuDR%2Oj(>r|3`khm< z5^$iQ6Y?WgWQ#RSZwnDrKvqL%YqQ_wvz3um7M$%i^$M*7MFJ>=Gg>aO_&*Nkex$>? zhMiDq3#Ozcad$xwU_=@qXH{V5RRoZl!n0cK225WU3r|bu$&b@3M} zWv=20Q_T`>MwDz;rnxz10oYdnb;-O0&X0{= z&2cMWsVYoI{e9Ltum~TMPW(PQ3Bkv;vYZ|BMtN+Vb=Qbtc&zlIR5|%Y8)wp?!GMEp zIF_IUwl|<$Eqb@@USdgIYV&?k4>Mhh9$kd9Iy5mlh<=qkjl87>O$fSU5jAU19z7^< z`4ID+!YJ_o$=?xw@i>XhP)+DV@S#zd7tiL7ELTj@^2{{A5Ne!EY;@9jWn-O@QisG3 zzW_Ki1hAcsvnJcqwE#YY%2U(S!`hvv$tK@qyxqYwup!|O!b!>hWWBosZ=$++_k(QL zkz$16SE0*9p#$MRw zE$uF!ie5!s)-HDb6>3y)ZcJE6JX)Y5ttXZW)klfoC=D2M1hbT@(aD3As<@R`)gPFS ze3NnC@k2>7;q7pfUhZjvk0>NXdg75+IGY-0WS{Aw;nh^}sNK1PY)V75~IJ zuBrt`+e`I;LL>Qo76cX7&+iQWogn`xUVu#3C%Lsx#Fq#(WnEfUfNtQW=I=1`1~c|q z80bba@`oT9_P#;J3%;4}E`FKf!sD`H%w))5Ze$?=KV@PX7sD_+)xv)l1?}i6{)hWc z)Pnm-5=j9A;=!uppG{qEwMm1#qWSe`2L=_mqH!KhG;=EDTi>lEbB=@^k^gdwpav7ZAke*IVfM@;WW@g@|K0iXQGLh$7dud z|5n~ioZv3Gv3ZYX|3!rYGcR=49x-J^OG#sAHnMjVug)AMC3b3wWtZ^!Y~U!BWPpV4 z()I(C=1jNmx2Fw^Vdr9W0;KS;m1-ABbp5g@C(gI^%87b&_sW679%s$8`Hv+>VxI$l z+Eyt{hon1}3(AbE6wV#)TcqDRaR^b>NoD+#-Q#}zJHTXqOwj2lNf;ws$@DANo*Y*V z+m|O*Ej((--60XG<_})nw^{&rT|!AV*F*UafYUOt5l|Oo6Y@QC&(}x!`QGNb1`zW7 zyIV_-&5yZR+r^~&ymc8KqWal;dI!-Jr;S&v15GWc=6aU^TapQlv#rPirXTK zYQth8EvAy;LXI%wW&>aiMk~r_KBJ6PIg$N`3&q{u_h3x|P370zMwM-Y*>sZLuNDa| z|JX2Zg#zOI>85ICe^dVMdHA!y(&UX}6K3Pty;EqdOy!n$AsaS7<~Pj}xm2zZZ&`&a zPoa^0SibS#^RdR1rELX$3R?TMhXL4kh79sxC}M)H3bS4-`tRl{0BPr4|T} zIiT{Z=bs>RKo>J`+{#QdiP$sd>Q9lTCKoQ|N5b=LiQsZ0R6G2DB`7~L!6%EpYHVB zht6bIdD~^30@I#8Z{2EN{ZSc-E0xPS;q0V%INvjW`Y1rBPNvu7*+3KJm+5Iq?aWBv z(Mo@bV(A5&A8U&CBOF!?k!La77RaMEgOvKsPg*N#n=OoStU_5r0~?wpP$)u*jsV!m zi6o&Bo3}+K=-`HY&06Hd|Up2`)jS7;aw3s3arymi`TE|+0}Gb)8uC9We%!sgG`jdeAmx#xcTLW_};8j}Cp)xfN**~#1z zPvE_VXJMVn9V%m^;O6p$1s+|I!xMaZ1tgI*2Zi0B{>vK7q2F#7LZmxYQNL)x9xJr~ zP;(?gD;3$bJ-QrAj>BVIc7oV!2g5TDP}Jy&HL{GrJ9M+ufO#d#nHV+KHPlpef9(v1z5Zo)oHM0%H5={{y@X|A-@&wM5-EE8BM5cc_N z<0#QxFj!j?#$6Gq45kZ)gzqQ~D1Z4)*bFX3V@p>dS(;mXl#~E9MGu<8MI-D(gLd2w z0SWogTv*GCRL9#FU+2-0FXOu@@i)K&BKkXu?VQmxa#4+-WlhzN2lh42A`BCJFaJYW z+}p{S<%{)R+Aly1Vnp_h50)kMI?dA2kb-(+_w+me;!eXIy zVJQDGs}n0@#>%yM&n2H^bPc|%P`YlVV5Jj5^^bX<)&}p}>EeeRd)%XRb^hPuH2O4lV~`ajY>@<3oD= zA`#y3R#Uy^fc5&$#`rt4GWH6ZGggGG#tx-IJRzx*L6zZ9*^M&{pBE>-QPH`Bt1t28)%8 z&S!HdMIw1--?aE~?A&0Lqz2W!PwRb(Z&Gw4(PLK0NO;BvxoII~vh~F+3f(_8vMrXU z!Y5aA$?dAmO9qc3gDCAAjXUYW%S!-3bGXZ-#uTGxA#u{(#npX`KWO5?1D8Z6%a^1n z<3;qm@yZV5F-k-B7%6cygx~*eTRav1f7`}-vV1trN*M6WVS`EK z1KnItm;T+X+H}5vJOX(Wo{ZD2e@AWOebNlfx1U`LmDYbeBZC504ZIH?;f(K@6gq*4 z)AwM8e>24?AXngwJ|hoj;}J)`wQvvZmDyJ3#>1Q!cf7=sQP)Q%<{dQrOn?cEyV#Es znCjOed`Y8~krI6Ia$~Pd^>4A0HYQ1J;TF~_n9n3_qC5-hVvDV+dyZ6W?Cr)=?hv>w z{Jw14XE|_4p6=j16Pbhu*T1uPh6stHa20Gb7%A;jifkL?48=sc$Jk%u(ze2adU2}) zLt;aUC|CWom*PW$wl8_NG4aS_&-+!-lWD@av9raFx_6W)l}P%6*E;~$FfWFkuQ_;d z+?K2nnMUz!!n>ieWM>o>gW1Em`xIk^y_rTRGH?ilPx9=_iVzwF2_wKehH`*Lag!~b z1b`6o+%Kliz4;J#4aF8Hd*jRP+L%?%RmTW(@TadNypzt|*ADw$HN&V;9BKnrIlJs( zP}upqm&NhA=S2ynTS#DUlbtBVG38%-VL*ZOkbszXZR+6Bu#`SEkSEjXE;YW%jDEeTLSbro={fTM{UwpLpS z+8w!!&3?vyQuK7<6D=7I$eEh82HU3I<+ z3(j=+5}jolRpBTzP8vyVAi%E$gnmr2I0GlaDAB;4M6UeQN+Gc686-&Yr~q0)mGv#o z2w^2NAFPpFmO~qrON=1}JEs+L&KM|4Us0T@>>zVMD`7tpz@T~=MDZQ`z`LL}@Av5S zqnLjMBot%u#luq{TacgsDkSWFg!@pvRHAHr4%5-A2>%|CCyLuxPri6$#d(oPX}96u zBHq%wYTRa&oO_j@)PA>o1?F}67`RR8;Kkp?{9rw5V%*vrk$pTt^0ljgYdP5Dl5(qa za^);DU91ZlyEALlX5`BApt5xzioEx*_O06a+&cMG%5m0IBraAhyw_~OHbnfN-sj-( zpH@D@=s69&S`fCRmh(p)W|im`&oeLzmo=yo zy)s<`t@5;0KJ?AghxnF%W0@X{%*%MwNb`8<3$-X`_(AUHBSPFK*a)z@#d#qFs>!Dp zHE(TN9TZwv^CO|aL${x3_-oK`gC!HVIHBXuXhZP`@mjD=ppvf-7bN<7ayIIMvp4ua|)Aj#;Ym@wGZX1(L>8cC=$aNrGt!WY=6*~^bf3crCL-h zNC_cA& z1fvZ6i-PI$xYq@ysz!_DKo5<8r6$|(VIgUH{Awu-%|n#ge(U%n`c4taLYiyZxql2F zbc(YiZJ)G;Xq^Cz#u-#I8hBzq-wl@@y<`-J29u|%NU}y93^+Aeaj+m^c;YJZgW*Qr zMe~~ft?{?f$%eA>#qUxDGXt@r(>Z0ut#z{9zSa{K5==vl*|7<=I__e!X#RbHLTlp^ zSjs1WOPeSmVrR|T^K!z31s1P}N@9^hzfQ-9oMzv|efmsU;3hN4;O}%pFh7QBtNu`O zTY(|iEWv*l2%YqC|1v~Am6hlgo=LIBbag$}7E)0V;~Mn)CP7VykJo$mz3IErKtyI} za2{j-_q;3W%CK=znl<{OTYmo=H=r-!t*2(HM|63x%6_LAnD`3!fKKdr@xRui7~y$m zTGs;|ety$LIK73Cs+I3MR1&Q8u^fd#Hxg+ps-U)hWCZ?j(Qogf8!cuBTbmBK!WSLY zm-Wy2K~gw0Wa-=jFtrHG1uT$lvq9jjMQ0pw=sBGw0>>U*9RVc$$otY+Oj1|Q9E~nE zK}Qj*z!QUjW& z&SF?ChLQ>4lgl|K?y(g}7YpsD4YdT3G{+eyP42J@W=E|Uz#rz_VLqDvqJHXC$*zfXAJ!r!tP$+`@Du$ zW9U=soF97c(Rcg5Hui42+{iGJE5lqpbl>*UkOq#VnSY{l!CsMi1ySw7F=O4;2tQJ< zN*3~~OvBHu>7;fsAlLOQ`r@%pe3vkHiXU&k93x360^OLog_zT2LPekKKO0rp0FaCJ z7mA_r)2~3MCgiv^DrN_l_+sM=z>j80?`XlgM~gVm z^6m4nyG>o5q5{=N z>~J?hjt@((m7+S?&LV6dXfu??^CR2m)`19C}*H6-HDp^gQ_t>S9z06DkZu zYru{4m|FPqfZWGy``g_x=`H3@d?a!yp8Xi!1SCVqKfHd$qTGn$*wG8`T9Su<#9F|$ zdf!XdI8LEZI|5|K*R|F8+`KJq#Jkd4RIV zDUwX-XwV-q4690=fLxC6UwwqJOLJCHQhs)vrIi0>oZ4sI`$72UR${r8Y0i>wONd&_ z^|DY#@(d=L4W292?gxlQde%gE<^ndMT`5{{Ce!4jY&FIDAK>uKcG@BV&u9hNLTdZ7 z&Tuf&=_t&XJ&GXwAkbRE>vn#hUVl<^vd}s8hIT|Rx!%bbvsK&>6H4#Xo5zTLX6v#B z)5!~)QLVsMbzdXWIg`#cc1%^+6W9Ua$BD<5TfYjDBMvJT!JOySx`-mTKF$v9Z~B{F zClzTUKfrn~q$QK_uQzrxQQgndg9iXy!#*MY8(Big^I!hEKi0|4A(`os^6>ZZ?4yCz zh@p0-aMM79rPwQ+hQ`i>QS26j0jSbRM&6Dx8i@Q`WlOf`aL)7To4|$m=clrI^YX!K zZqLg+0GHy3lZ?sxD7!NRD&8dou>(uby1tSaqu0O?KJ^~U9~Kc7`J|^`%%(WYu7lgG zqmncU?cQrAC{%2UM0jv+p!X4hm_nHljAMbthy1~w6_lA+kvv=vD%>1Og?2Hp;z*Jj z_brteQ)4Iir}LW3ZvJP&Q!;7?$9gv%AdL!;k9tJOy^@7o20D0eYY`F1fQ zPY-!fxToNX4g&E<>Jf5_vlNp9LhZ^1ADjMVO^O(Ke9!4V>{ViWw+H*3d`-`5O$4_g zOjZr5mi_7@MhIz!QrfU>|9N_Y;kAZXONiAKx2l{D_mB(b>@Y|4p2)oymp3cM2`rG0Y^j{e@&+O1oyR@RF_zK#7en0nJ zN_r?y^1B-zr<(E7`9s=ceOX%SeAmkqAVx^(-|?xm%D4Yh>MjPU9ZdP8XEdVrks-aU zhEmZ0FUgFu7+|CcX$EcvLtaeue`xyda5n$2``UZY*qhpWHTK@ru03jRs8?WR6f#NSb%P1)}HJS zrS1mNVB%{Ram47D(e?-BJ4#(6QDgjP$)O|B&sF1;Y@G>n|2v$gU}E-}Y~B4&`FR(a zh?zEJ7L>en=}eeHgX_z_3+xkMiiZ+IF73<%E?uR=lEy5l3K$c)-`Tk{ zg1=QRd#GvOhRUZo0T3;>;TFo*_0sKHH~HEi;U)X1J|!J+Vo7^k@?2cI(4}}xcpaS* zQvu$QlJq^>Mn-P@J#j*I?Lw2txTt?D#1j7>Gs*aXG?{dEbH-O3Tg+mNVw`q>S0<=9 z$vdMd)hu}J!HkdJvXp(3AqORKbz~dXHkm>>kds}xZCM>^(*td?X}M9t$Vb|5yBnFA z%anez+NLxSe}MCR2LWxbpP?4kIA;&PZ`m+R2;Y)ub8623M|IJaHi>o0nUVR{x;$?@O#*Z}~ku8P^ zZF)+zby49DTe3n{t&7SlL2g?BVnMB&MDPO3AS=W6l&tvf>w={O0FpP?i;_jW`wyhl z``j{%Al)R=r@7n2aOV+s&}Q$-?C)Q84JGKv1@J^>3?fC2zm|+`#d+NFEFH9Ex7rca z#qqkqs_d?NcfzHxgmTUnn?Z?(@Gc8AGt>6_XTbNjFhg0PQEbB)G`V@!VHamon^rP@hTLG1$cP?hte zRcD6=g(9BW96I+6Hud)XaFsa-JZL|(ZpH5eTK2@)xmuS3zZ-w49KUb43VB- zsASbwE6j$)&w@^apDPM?gZ_hXI}T@Z?}oTE6S=>9FFEAkqEN{Nk1X8~_!_e&+h}rBud(5(jD3 z7c$Yh7ttr$g21w;-U+_OOh(t0@A;321@gGP; z1OkIXOUYsG(Xr>M0icVH&rVGoMOJC4c5h%nwZY`3m>6V6`1yk#h)i%U4Vv+9LiUxkF$U- z_l_aw#Pg@^lV193LkP1(>g;ztlMj&cP>H(kM;&ctaO?65F6XeCs}Eoy!6H|?qNLx9 z_$WVP4tp=ZGzs!M<)4;)LeD=>GcBZjq82T!6Y?m$zg&cBPaIsj6-2_m$3L@tv~>=T zSi#V_Hcm0$rvv;;1FgLHi?A;&lW$kopaS;sb^L&Y#M2$yVBh4R(EJJ<^&C)9!?QTP zNaE}-iW0&{^( zI*xby2z{Cs3F7<7{T=OufJ%%?ZV^V@#TbK1DQH6x2>%3WeRf23eGnAo`Z-#T2wsW!ay*o^;A>7d_j9p4=S_j^g zi}-XJ#uYu-{r+)>_AcLxWPWlWfY~D=aP-`x)?~Lp2aQeJvr`MfO+Ah+F!wiMSdD|d zxzSc$%svNp5%}@K0Jre@WiH!!g&~r0gns0sv#27vjFU^8=1aVEc6}udaQC}N^9*z+ zoVUmP{Fk__=!Sp2e2Ts84j$YZ{B8)mr&A@z`K;gep*XzLE`UBw2zh2LhGHAPVh`lJ>J`Ui8 zi;1I&o~Oqz)~fgFn_i}&BcSsAkD!hs`QP4;hu#;SE9=)4?n0gRWXkzpM0&i*;{;;B zvmaSW3uYwapz)*FUS-e^bsI-lYYGeNyI!Nsr!4oH3nB6)7a2jVQ!Ab&JyY^0p}%$` zim|{|hgi-NV%j~uR+t4fkV@Vjg~&hc#O+xs7u*uR zlEQ@-Pm5m#>H@sFHyDjy*8hxz({C^=kV?1W%%yWmtl_5jr|S?({`f^Pn;M~*{*odg zo`MG8-BecBl^((E{mH4r(|Nxq-$5jYyXOl^eo-AE>h{`1gQ{SYK!!YjyRn7|z#O$h z8EK&=gRbKeUY|PQc#VBz{L2@0FkMcO70n6LkEowhC$&J|tOE9MX^UoU(>FxAZ#OB8 zM5j;vlErp7UO9*X+&pFox{18FC8iBWP1s`@|9IH`{l(l=?{G~&uU}qTk&ewggBW!E zri9N$5BAr`82zQyFl`cRG%0@lZ~Qu!6Pu3r@7n9MpIpKBTQVt2-tbja+xwI8h)Kx* zz6t)pv^rlpBam%4TuhL3T*LZ3*t{!K_Q=@Q3th64!Jxs~%{M#bfXc)WO56XVO?DVs z>HHw;hrOwU;G4k<_wC;4B%vBxaI28g{~pmq^p&08rsgK^%q~etT&Vq@as8iEYJTq- zF>KF#`rkL|j@=d1bxJ{~KN&FYTY!Tf;#|f7lZGeJDTS}=UOo4}*31}9r&;S(pATb~ zCl04RBfu;zXU0A5jv%`+CoiHh@w;pas;lq6Rf+RNA-3DY9reH7z=*%ub@P?Z;X0df zs0cNj|Kv*W)ur-ZT}e>n)OxjIZ5NMOs2SJvf^+BB+?aW9ta+v7o1C+%D|B7-b*pY2 zh0T?mk>c6|)2lH#BDRue2{0?-U|392yA%}*tv2L270XDnM>#sCN)m}8uc9IOq^$K! z?F^^9FlJ<#Dfcy4U94V-AN>HeEw6*VDb#>lp`O+Xb-DIbUOfyNQBZwNRf%cfl4zFR zbM)J{m0}d-_+3hdAHUzDTS|Kr$75sV;pLF0+(dHI6{EJnaDRFUnICY#qGBM<_BHIC zo^-EzKhGjM3vf;qwx?Gz^b&I{kZCX1E6}TxW$qyN=R8%4U79t6-0QBbde+i6Ocb54 zPzMuZyxU)mX2f3YL7DM!1Rt27#D}}(Rt;@EDkpe8ZZqM`=b{8y%-D*+*rpY>$i{Q+ zupKw1!zP%Yaz`9}W&)XRYP6bY)6Ki(kc!Q zgDx|T9JBe0`=~NfpVfVu3_4wrGhK@$>j8spyp-1J5JU2TLEJmoSoRIr;Ge|ot@tWQ zb(>&z9lACK({-ad^vv;G7eBVoPzW|)mWdj*1-cxP zcXW~;trRZ|-;*766izD!q9z7kC)$@mF~~{uDHZByxlD!W{8dtRboevQp2tdWkBRoC z@7Ax|iC{+Y-jbiLpJq9xF?%7(zeI+;D8%*hD%Y z8=Onr2_>x`u%@phBQh(n&*I}Gh((4eLn416*y5tDPj6oUbP2zy%Z}fMlAjb304W)o zJ5}in_-M%&$aO)LXtU!YSQ#oHv0$_YPRs{l1Q3!!E;ja$6zHsslU$bgB9U9qdCFqc zK+tpEOGw_nRO|4iJyYpu*(_vuJ481vb@I$YgMP|<@b-!>P0hG$OeaXZopS zaT$@rBwI>~XD|LK0+TQTScqf)`HjuD3Uv}J8cubJ3g&dMxeFGljMT~JBwK>ckT0lL zr-=U%GSZ_`dox2rJ4Rxq$Ec_e6s{C2p=IR%o;NkA1J^T$%da+S9dJG_P{t9x_(W;N z^u+<^C@O+b5=Y(whM(ZZrNR|T)aBf&6I8HAcm4{EIH*UFtAaUbf@63kbD^x}ekmvL zNG`jx^L1T5k$9+o7E}YT^LJ%*+j`6O{WzXxB5OG7b$Fm(B@W;b5da#c2oB z$pyHMVUV`C!lqbpedj;m>Klu&j5Cv2xCJUO>Bt<;L|2#TS7 zv_lQx!W_uthi&bLNpO7SFGZ6b*X?S-H<}av){4y))RB0%o{-F# z26eK3|LV+NX>?WwOS^d(u{XjY26fiXzXWc=iLu9yXG17&si3ZzOTGktt_&BcFY4Q+ z{*&tqU=iWGBSAQeMZVrRf>;B%y(3Y5>|eM&1dRI=Fs=iN-8J5%`7OLuC_!0=OO?i4Yr%T6au1R! z_I&*y8dK9sZxLr7r?yENM@kq^KbM11yF-?{l1)Wb|jhB z@vio}+ugE$N-^7;Ox*nB*?F4@+4avy^JA$cfHM5FSd(Un+B4p z0vfv04P?%er_SzR^0p_jp}Qc0rpAz_pLWMGOk^BZ!9r4+4~(bO@E<#B*GP88V9Od* z+~6dvG6p;DimA7=GV?q9^X=OTu0|HJ=?7t@t)^$d5~`!#x*5sJ2CFVJJz6`Fvv3o8 zOXqG(99KoQDF#SZf2L84Li&a7q>rb($O)6PhoFXpS)yXZs@F|JZHY|1J$Ek@q? z0!l)ybIBwOA9W_9ZEu#hLoA7vp|})hg-TiCdw=X>GhFRc`Op~>I1TcZnPbK#e|IQ3 z%8DYY?EA?Jrf5?*usLEQ$7nw~6KaNvu7*B>hRt%(71XuGe6@ZSVw2l3;EYc0dnRq z{02p#CLmIdRe z0WqY~i0rJv`}(4{=mNBFi_C^rko)q&FFVeB^!8J8PZ%ze56IfgF=Dq6C2KuukxxRSPD?udwn^RFY5f~%b zKQR5t!pC*GijLgpwop}eiREaR7rRq4R53HPbUML}{j&B5zLdJ8=eY3f2-Z@ASpI!} zRBT~?W3f+R+pOL8##rXvUzp}#E<0bI2WhcR$ma9pJNl{^Y*f7VPlna*CZ`3JZhz^U z(Z_M4fxoWZaU%bX5<1jFS&S)R!8k97-I4-w1M6AB8^q_tq!O^OFEB6kQ0M)HaJ;{D zeF=BkN2Hk&3I&xseZ7y)^=zl=)Ok%Rn`Sa*X3{Q+>8}Ou_@Fd4<3q@*V_Dj#`jw25 z%wjU8x$RIdh>$~d2FR?GqilA@hAOo_yodB1HC@JfYX5#VGvkzE95V^2l@g|X=QJGg zpEYAtfkp4W>~MTC^{Z^y!O7Z5$LE#CeqXz9Td(wh=LgtSVzBeEb*>qcYjaB7zHtv= z=#4(^jcAJKUAw5VzeFaqz1m96ej6}Zjp(;nsJ8oXYkneAt~|$Jr#aO9vU$xgRv*Vx z*TFFs#sS%%%w;n`h2?S`IM2D@x)dv7le1>f5lMV|+y7Onf`^;DG&6;K;GabQ5H;+W znQ~2U{3gGlJ!edA3iX-R-}h8jyep`!QakV}>GX9;kyiSe@Y(9_1)eI2uS>?-MPa2t z&mvWdoJy`Gq};zFTr`frm2E1R;KZJ z*j|WkT6G3%$R!DP#yf#ixvGM6Y?m-Vo*^;18(_p%Pem55bisAreEPyr#qCpwD+N!P z6f58jJ?lDZcZ`M5C0ZEU3=O>vZ5X@3H<}E!*3rF7rbO=cBp*jdYtdxfA|{xw1vaWjn$0Yk?m79`g| zWq5oGd^a9KG&)Kt~6T{@Zq8E^|oQrG>TE#ILt-&cg<``W53ooEBLY>ouS zRpI0F#)HGuYm3fG5PxH<8nehP9c$#n#iahuhx{8fsNozSyB2hw2>S~cAOs3YZv%(nRqchWfYNQhTk;6s>xD1 z*vvyU&FR|G^m(t4;xMe36nO=wOrSWCe_uNCg7!RO1wj$JtvCUt1v6B{tomWIVJyDV zz>SO5-hKF_yGrb~6#U-B8^?1_(&UjnVzg8;kr_X`_N9qb)~tX_ZwNIi+!c$p)%b(V zv3CBA!TYl=sKT)6!ysr=NZ{9}?qL7mcJ~|>I&+L5v?;RuO-XI9TH0@>sFtli`RczO z6p(h@Vc$W!z^jm|0@*2SngXl{B?;P98_zTgUbUpA#}Oq=iU6S| z)%K;?(ocFtUwZaAOasKTZne;27OcW#>14#9MNeF$B8DuJ=-S0Jj=ofNW<~9 zah}S4TcP44oTC|0xWgt04=hFhw`Hv?-$(=kpor|0Bq`&#)+f-sc^M~uB>iFSrnKOD zzhMHSqJJ2vSSEJ=Tfn%U$E88unaW8APLn`txrS((?Lzf((%aV%VL^14OfnMq8ONr- z7*j(M&fxicKGW{4=F2c|Oc%2JrKl~)Jn!_Y4P8e0?7Eq-?G7AJ_3*_-qE(LNLUp?K z1HrUsu>tDFj}&bdW3=jU@8P<-Zl*v=< zUmj_mCyGtPq=*;c6EU%3e$fxAb|8L- zB3f9^)DXt~`V`;(yB*$9N3rRF^i;TT@}KL0v%gb*rv(_ea!d!M>vL~PBFf043SPu0 z(1V%A4i{^<4mMr^76IbuHsm$YzG?AGdNNIywiAuHW7{2URgZSc2<{%%B?L^}7pS;r zcZ&@LJtm;g*gW(Y8Ccgf4!)0x^0kFEq~DxWaMqZFopW%#86NiwnN%#SpS}pphVs8# zJDVHV2`1M)Vh7J+O6-8Fi)t~rCalNEY$gv>P*Joy{G3_{6RoAZee|HYl@MfNIkB4&9*X;B^`|4Lw5gTk$X?$ zDC@PZ0YrXxnNJ(egxwPmRQX8tEOwnI>5{rrscGg=nX!X1#aYJDk|SK?q;mw&$9s!= z+73C9?wGBVql>$BdiFnEIpvI9lWphXU5DXjGOTs4tY7@o7=k+qr{}ES00?E%OzF9GyUO20{JH!bg(wsoXmVZy0>qFr)8-29ryBS zzZ3tbMI;_{J0*H{bnddKY-jG1L2N?tkYQ4JWz@n z*&8=hx%f5mvlCk}p8RLlv^+{n;Wgo5N~kK30x$m=5eGIyQrDN9D7Khc3j<*UZ9vb* zS_(pCuanZB1Nj%P#n#{N4J^g&X}8*SadZ`y5$wI+OLFSs(*0E9*dOF3{T_-fY+CFt zT9KD4=#>Ai4Jxk9Wnp=Q7RDJm{N#4ROrj2?$x8Nm=h|N^dj#9Q&(?t-o!rNKL6dX zz_^41Zdm*G%+3=@fD@&{{cIm$;=Nge)0x$pA7|Mzi8{>Sbw{-x6f=4Ad(M|= zuB|PPRV6mM+Gr5vX-%^n)3Zyk9@XW(+=kRo>xn$SsCT-1#7F2RJk7P%qG7Gz z=iJq{@V0WS@VOF?1eG~Y@&R3l7}uzi7CK{GC>FV~8^c>wEm1~rC{2=t`(TF(7}S8J z#H~X&N#bgzU6v?@1 zyW@7FoaD2+H#mE8G5Qa`)tt(3vgxfj_q(yw!v*(Oy(Q_6)&$lnq$^QcoAPmQ<|S(D zC>43X+DD;2CdBlb?*F_1YwfwC5)tCJNeM7SC9#n!oC6#R83o(_;Q(t*x*2M&Et28q zy%APy3>ChMu2=1FAt~j_rWRVA?aSPJjWf-<#Md+h@b({<2ZVV#$p-%}|E?@v{VBFA z1y!3&&4<0jCdtRKCfP_grr1d9e|+AjkKb9XbMeBmJ$3Z#I~(vL`h)7@+UtwQh^Wb# zXedTz4bTrU4_!}J=^v1wH#a5Ww{faG`!xo$79=Y*eeR6C}VcqBM4KW{}4#nxLwV~@Y!Ierba63xU-pse^}gpJigL~;e<$}J<7j)|$@e(V>7 zt%?TIABiVkh!|6pfyJVE0lpg{1JFTR;D@n`X%t~K+)N!ogFFvcpn)WWTRWPaVj&v% zX^ACLcf;K~pP0+HyB+=Dlpfa@=nyRpsk}iL-Y=W-xCi#{g(GvT;Xcyk(;}JMF&iM>$AlUSLShGNfaP4@63}e|PO<%cCD)Y4HBmUo^ z>}CCFtsjOS`0At2Trh^m;4|5@>F6NV+34GFMMCds_x)RShVMUeJJIhyE4wrL{lJzb zZVTD8C*;D;)3FDTt&~C+tW$G^$bPXMPG>MN zH)(KxmH#rp{JsDwI0WW?`G_x#YY=)i{dow z(}w!VZjcnMPvyR>}c<$ZOa>3Fsiv2cOvM~h8e z0*R&8w<85-`8PlZI05!5rchU|_wSz%NA?$IV<)p)vAaUL;b@={Xev8vcTlbWW2nSj zFv(T|(J`m?hN?uQ;uHpHN6PbIk#{tvGEQCYpQdXW+LoTlJAveJ3-#anRUr6*+^GHM zUf)=F9DMCu3?jyU*nUi?#ntl=Td*rd zOMD5wquuTldWw%=cdpxrRq(`6xZ=E)iHYM||tqI*CGqA9+ysDekyZxm0nHqFRL zqNmFampPSAMoFWXxn**NoLs%$lIefJQg9mz$79qGD+2?Hs$GqI-hxab;MmFQc;>{! z>T9UhLDQ>=u=0{T3)%vOs#6I;7Q0XEQF}dQ1YH~)9j9^UUK4c<7pVW2`qops56Qr= z8{*#{Sjg@#$SPllE{uG05;6(d)de217f%4Dm>O+xQ*$(cIA|3pxX}# z+N6XMf}g7kFQ2A8uWC|lmMl`*A$k$bvb)q2@ch(K; zz5Gt@L_{$wTtP9pjF2A|jE(tih5dqa9R{Lss*L-#nJb0cv-6@aGV3?Pz7uWD2;H#J zrp^@i+Aw~SxwDtQqtmMtx%CNLJ`}p$K;6dksy+N@krW*!r|&8L1@5qiHw5@fgTj4M zcRKAa@63lyd(KEvrAv=1vLm4BaRE2=Ca2#upGG8%@!XC0-L<1`WpUie zAn>G9?S#d;t40-LGdoaz4OAEOE)3=rX&kYh31{P+ohPGhf{udYkJ$>GpN^+m`CX5Es)6Ga3y=4gR@Q&D7RnerfU=BCBFTrZ;z zZh*-!?@;=r+k1n6qAG+zESmB+YRssFyI;?mjMF<|Nksh=m_r{T3QX>p;h5Uk7{ui4 z?HQ`Vs;AVd-rqT|xz2o1sZdLvc*_<8NYQ^3KVO2Ky#PvUr@q3ud`|UXu^2os&oVWn z(gaZn&Lblfg}iU#=FMpG7y13JTJh-m@ph#{JiQ(mF$gGUz_mnMlh)8E-fi?t4@_rzNaEpBuH69$lXshlhHBmzV%iwx?HcP>hk>bG!YE;4GiS#Y-J;kT-x5{>-US8{ROy&&v#IULfu*lzdfuzYn|}m&bH0%;`gNGozty!li?BRp zcM-z-XX}9uJMWG8%P8sTGbZen=MrVXnYCHY<#cHG1(!q->x}OlYnjr@YRW=i7DnG{p`uCrAXOJ?rPwVz_&!q4x;Ye)mz;{qx3bEa66{!Foj z!}0rd;u(nSZp#@bpVO~jQY-n2x&-UvZUscN0@urEJ(+B8IeLAL2 zUqjbHl647^P|Rg4mrrC6l8ITFCk+@DH%TtY47;(V2;16II}%f5_2(Oikkd%YARg*q z^W#yaS4Uei7M~Wq#>K}jTBmqnE?({3@`V^7ceV3XNgVf}$ceY~&lLw$++;i}6rl(8 z#BL}6nZgf~a`YY`ytc18r`H)`zTI>TUft|%@eFhR?>0$u(#b%PUFTw)^R#~tD{Nsk zYZr{fI%d!Ft%t(_Ip{fg{&_Iqz*Q>-$OK&F^@b=Na?SPl^!5MR42S3#8xx`n@t_Ag zKA4<-jY|wCQIMg&$w4_8Sb8)a9R~V3(Z7x+3(lznX>XbuhBI2K-!p3-hPvCbl4lqY zAq8p)#12RM>BZQ<#xYg2V*GQ+3a$hO^{)}X*>huVp6C9%g~dM@68&m9Y$lGEqVaH# zwZ#dOgSm`$0Yxq*XDXBd2d*_T< z+Jo+}V0PPqI=By9BjeCfxTFNRkRm5QJ(4yv3V(r~?gqZJKRO7p{xa;ozUG;~s4FLH zf#ROf!HKUQP(b*oX1jPQ<5QKI@x(1>Nc~{P8e~!K!7in<><@2P_u9n^YKwL=^U>RE zs3gr9c!nc5=&1n?2v=;JmZ{fwEViLNBw9ebF+Kl`laAtpSr4|;qkmyX?m+$pud;pr zzIH(;U=iBjl8fHJYU$dWXeflW^#Ai!cpU@PK1Bv0y5?miN_NHii7=JE3G^2kDNJar zu5CRL*iw$Yf#aFE?76;5xL%U1!;1zZS6(7Z{7(W)eYz{}&aM;l{}&udb)r4-LaN9% z%n5tjMgOc_@LZ+0kr9fwza|n7AFn_vZAElDg{0_%scv8N&-a@^ty~@|pll#CpPBo7MLQ)S)clL*##)_DXYqi+HJly^1S|OX zv^GF42}!!x!0@&Ik(=S+C}zAo?&=(Bol4Df%o#O2z7W7 zZQo+|$lr}6M(A1Mlic3R(8trnFdRl2Mi^`{@^fm^tLxuQk84VU!z?3n(=`++SvT|D zKb#2k4Pxa{eVaLBYfMMr)}>K7c9!DuKn}(1rEqEkN7Y=lGU%PnpqfF6&a|5`3!YmL zTNg713BfBY0XsVwa=AlnRpBF>CtV4fMEaC`&UUwpgL<9g0Xx0@Un4$^qE2$DnJ|xW zBRyRv4GG~z7&_DhjGAk7?cPZZf4Tc#`I|to>S&<)$AvY{bLzXC&umdhHcn7SSKG0S#^C$d<>bbm7F>|EiiCPs zAarx>lQ&RqJ_4iU`?kl5hS)bbGOuu&O*t**i7=k|$zPNYb6E2I2KRvvmy_?>zjuo< zS#rn*^}QDvU*f)H^)uI#_-Fg4ST^X1+w{cRsqX)SeG!2OF7}PV$Yyt=^2z|w4RfIu zY61;@t+>7TPwpmw?RO?%@>5v%b$A`>HB)zajNrg+nMFtoUN}53W`EShCdpN#SP94u zqFxfMNuc2i-*^;R*Ar_-Idn}B{D8nB*Lsr0MN90!=U3gAuI1Q~_Ge&VnmuwcxHYFM{<`n!p1+Vl0qzKPr|xlE!1k%RGE z4iP*NHTV}*gHOS^RY$CTJ~tfc!Jo!d%?EHiX@X>Dwg>Y)NTy@Tc(07@6R88 z52f);StW;{!0fs_JW+c>0WJ{1HPI7v9*pZbI7Lp7v z=Paeafz=j%J1pj-wy9Y@ljMesPN%7bw~XLQj=ROyAfq879RFx zl~=-r^v(R5GEbNKpoXHoT=?zE#0bdxUONH|-}@(~{8`O1U-sNCw(4wpau;1Uqn){2 zI9iz;|3Mikr{}6Y$$puqweWIW4-PiB-F<<4@Aii;(k$0#cq%;iXXo_%f|>g9V+K{} z2cttsJ_nkW6aFgiG8fe!RAx1pui1p-?Hrp2?j}@1Skdjsa2f+_VR2BcOR6Z8TyFL9 ztNF{Lx0lZGvo{%DNUCCHMSRVXXKLh%FK>Ufs>zzv;#$Or;KQH>IdSl$~2=N@j4T!RnIcjncx>)i%Gy;;WNC z36{z+RWCs(vxdE>ItJYNLN|NHo?}V{1G>ld7{+tfkFK;;8fT9?M;wGJtJ^xp`Huj7 znUVH)Eb-Wk57vr7O-0MgqlQnhGjX*u07YLt^=L^aUL$dWXKZ9t_SIq)c=|zbeuOxJ zGDN>W7k_B+inf)$)bC`-*0oz;25jUFP7-AE1sDlpWfZWDN>Ry53_9y(eQozkr_;)q zrF>M(wzi<`Vq^i~YX)_&=qF?6S5Xc5;QFdJkW<8LNhg1}aqe)0SeR1kEJhRvbUV8D|5at>Xe!?Tdo*F5kNcTGFqx93yz zDJ_<2iOgm^OV1RGzG_Anc?Oc{lNg!Mu^Fk}%C0ICk{56hotV_g=rk1x+a=r&dA1>= z5+v`A!8lAHQ>%Gks2q(uU}l`a5?qLjfimThu4>^jCV6vkkU)vgy{05i4-jw6jZ-E? z{lSnM(xgQKT+ek$Na7ig9|?^_&b;Nt6@22HF2qlN@2Gzd!Tgo20!KN$hQHt1AcQdK ztzpes<||^`g|lbL1`S3LdN4I|R7Qa=s8FXvewC9+Y+!KEsfEem(Bh$6@TvEgrOx&5 zgeu2o=n6DqAY+oBt7AD4mDrZu(II)o>Bb{juk)r zbT#>YpgLY!(jCaUo|*K47T}s2uJvH29;cI!iuEQKRBVaS1(u}N;rd_2JKuMkKt|bB zv3rx;k_4iosA zp3j57I1-JmOC+A}CkPHxE8@x1L0Rgd&JB%bf$DKTc1B<(s;rSd@4q&)p#RF=ieh`o z`a{^~CoY2zDFzYlRgCaxZKviajHIjaON`-B#s_ui7u)v?cC|5!N@pu))86vp^!YQp znQaAld1KaLSl6)m(WSiGE~yGXAYQa&+nyCRcfD6D-#ME31lgt(aemA-Q& ze!>$R>m1ZobLz%b_miajC7z!A+10c)d62QYa z!>Wtf*+I;K#dGE|1%tRa4-yJwuGY@Ti!w9=CJjdU4I2)TP8ekij8+iWQCC%0?>v_% z{@$w&i?ujTbjcK9ep#@`fm{C;?I(7GZ7X*LplE2V^#h1ke3^<+cDB3hB8Y6}#BpVG zmiemLb`>HJWJwU&HUi3e ze)RQ}eI4*5uQ`aGqz#o*!(7*O5XGQahgtUiLH}{~pFh217&5M$z^w7+vpaJ>Fp2;# zRWIOsr8BodQgo{muG-F&1kNF(B`g~$;iC;0yC|S3uJf%SxhCCsAAR-u8#E;A;>4(R^7MR1$WeZeg9h^p7+UoFV-WI*C&^kP?T) zUK-kgpD>K_y;s-ldSWl4Mg2gTN#y55o{XYbJ!^#F0HnV;V$t{eN-^`F&iSLWf z)^msP2`I)vjj!R&2VciyJwOr2>up$45|T#Mi3hAEv(r@trgR$(0i`DkTOhx%)M+D)E6(W#cbPZRTSM@>uILdF47`$R`@RHhP} z&SiWo=_AqeuSH{LLFHy**Nu+v);v#;KLP9uB+urPyaU!!Eq>R8Al%Mm(j>FL?NJKJ z3n5*U_0Q@@ZhwF%>}8&Gc71z~z%m@VzTe7_{DX)94Cvv{F(;P;`_;vmgwGI&+x9B8DBSQ- zh@DmENUv4BlXP)oP|*(Q#gHoV7rV45)*Y*z+_YE+vz@Rg>T;A_f~bWsa>u?jQ3&I^ z-ows+L+uq_IG{p@Wx5HDOYZxJWA*PEJ>c<>A~Uli;IOQnaJHZEvZh}%xjF{WGYy3ggZ|ts+2M@_>zbc zKF@6$6TQDk3#KtXg?s5N2F2V9^AV1%#<~_Q#Ut?m26=mD#e(PMO*r%kOR9Go-#1{0 zu&;ne+clE4`NKc!Ac_Y@cMg&DWn0#q{Zy>DaqCsG0<40GCAOxfiUe-;`!|8Dji~DO zQh}MnNk5mqbLaoO0C?SKYl#*%R4w%bIJiA^k0CoCkzcqBBT55v7`m~u40E8~_5|f2 zaVIwvcdRdrb#J{+*&G6V7Xh-c*VpO)ab-YR1yB+06Mo4aq0*By^W z!af#mkS6!s1+Gi{+`Br9MAYE0p^4A3-%YVBPv_FM)0q9=QKcmV zYXapOZcJ*oPj@{ke~0sTff`7HK_hVAOFUeYLuPObrkJPm) zJ^sJvxTioh^mI=-=ni~xO^GwUa7gdK?fSOa8`1r@>*nKl43G-B_rIv3V!nsdWhxk)MC z=y3a+I3SoB?rKAQo-PAFda++klCyA_JbAHUHG$q{?ZB52DDwis!#w$=4y8?4^yizj zK$(&kg8(Bi(7-;(v>*`g32uYWx%rvOp6w%+E$vH{_0K5r3O$&Dl_TOe!PlHe(m!qk zg}0IL8BncE4f`1oW4?G!@}(qyMqwv8{Y!#OHZ3CDQuZFPzyr`VF%wfLVj<)C|M88T zzz~fgS!8iVR@S!Fo%o1!ASdDskjTi8_h+VF)2{}m=d@qXII84Ic?>=L0a>FV0uLr- zDnb-ImOKbU5@|J&gvpH?1RxT*uJ4CxL!P>p4Ca#YN=E6Us$8g-G7A=)y*M=GKpGRtAzJdZJ}=$zJ^1OsJcGe7sCCS^lSNxkv1KoYi)QIWgl&h1xx*r-L_RXCuK=zc zs8mthuO_`Bh5Fv=Sz!8Re`jgXwM#}%t$3@c#`N1K2iO*Ks^$Y8mQg-#K{?6KKbABD z^+d=w?meNLXZHC)wI>r!o<329G~14H8qbUHuMKJ4!r~~|%r$t4**J)_3}zEZ0pP+z z#*doT!%d`c{C;W-Pi(&|I6mnLuJN&0*7W7Rg>O#4IxtC7?>iX~C+xTx`;OzEHAraQ ztkqa;{)>bfWXohGC*z{;oD`Wm6Gb%nD6`qV#hrGcLzupNM`a7C_Ljed(KjuqXMtrz= zb$#-BTpWj`cusPXeZJq^#9FjU68=(3416HU=dYvWtY5^QH!!K0w!CIzefP-{R1(}LGFMW9C*brphL z*6!@wu9dFqOw~69{sAC@bKVH=i2>g@4#YWKVWMHC6X5wkYjkVvvVdJ@e8pvzEaBM^ zmu(QNnR0|b-SVTUGt!Dpy|UdG@m443)JVgd0zaWVC_5>Tv@jYyHYk8F1hz!u2?Hnb zkQL=`;;W&q%h7Sy`l>9D9#T6hKLEWJ-^N+Reids~>mmktR!C9*)LhD(sKP+`7&uLm zexfTN^BXd`^Gb85&mzJQetU294YS>!2!-nvu*jTqBhheBIdM{>dv@v%pq&Jl0UKqh z4dT^vPqqybH}O|_EJiy!n^*uP^6 z=G{SK%DApr$zw|T#I}G{@Cxq2Rsa|i=?CgtrK%VkofnK;Jc;F=&>w_%7p44o ztW-2POlybiW|&_y>MwLSTFpoQ(q~@a{eZ;#d!nK*Z$Hg(Z^Ku`Yy`KQP<~EeN$}L1 zWXyD{-pq-YN0v&J^A|dFpL+aT7_iBk3bpY(IQIapSDWO1Ub-25A;s>mTDUJE=7;y$ zj^K855Em>k3^m+wGo~sw1_Q1mBKkYwzhc({7z z77pYH%QmMZ)C8JfhV}gza%b$4(@V6<0{ZI}8M~tiT5CqWlj29d)5Q$QJkr+LOYNpP zs~{e*Pn~%pfRYPoyij0z^Xd-c+{lHaj$rW{%;qRbImf_YfGtdy*e3oc^lbbhB1-h< zUO%N`GTjBz4;;7|v)S^(SV@#oQv&LM4E_YF3bHKp?l9c^#-JeP)vug3tqMoz1SME7 z)$45*Mgd!`TT9DtaLA1(ZQVQRk+_s=NliGKDTB=EW=Z%6L{%U-kDRZAPUd3pUQM|w zg443Kt`D*Vsqs7u6Ih<41@%;c$eiJ5CL@pe4h6ik6bJE??%95i9COT&Q2|A8V<-RX!o!Q%?W0)3eHD;3Xjeh zX*yp8HmvU|h-@zko9*9s9A>o5U%wyNN3FOXSw8&p{PDVjE66c7Fwkm{LzV0H?)&2E zqRm&)1x6D|pvSkg7G+&^ePw*vwGJiHd^m2Ov|I(?jbzpqwX&SkMoy=tsfLux`N5wS zzmT3`AG|d(#1Udj zG0`|(aBPEP3>sXJ5_-y-LHa{a*8>XqDxG`Q@WOabP5-ZAwU5IpV|#A>X3H3KQ70s& z5HB+|@yTFtP$D(9CA^M|+B;rCUxa&B7KQ!|e}Xs8B!k)WN6zt=2Kh+>J!uBMdUVQ= zmx^)zMw?z4aj4^vLow#o0Z2+-`3y;1{M#+ZVpyNO5rf9BaKki`iA7?o=xn$?Zc&ks zEaRhya3obe>kW2fgD9P1LZm2=eug6VM@kkx;W#-9WrT8#MxVn)O z?L7)TlQ8^v;I5;8%qORiK(xtGKdMZO**Q-Xh6?8%6#E6YTMItxaDJ(^|87JubAUHvf&s*P6 zo~6^WDe*(u`?t}li8-8}9C_JBMq>i(+Nslh0B9;DOKMq2YWe`IH&#r21!fCKn)d?B0;R%TBL9XEdfOSQsu+r z-fD)$A2?54m*w&={-l}A5 zTu{jr#qmOsL4pIsdraL?)E=vmAp4y6fjOn|K?eYRpn$036+0RM#Uh))&&IcZnf>2r z+yEoMQf#$441e$litjE(e`4*~a3dSaNjwGK5?L-KJ0#}vT=cL(G&X}s_uo(d*`s7> zSb_LjcZD^q13Y3ilvs$Zi&vG>``P(iY0_{FD1q3xQ@cKd`bXN`xx6(;_qMPEX66da zRTr%stEg3*wR(lctv^YC{mnmz>=(Vb0bSiyeBScpJLnbL;yh0Dzg%)cY2cAI2@vUS zfPxOp{v)LYPf*)LGm(X#Mv(Wy2y=r(`rdLXK5p%sas=`5r5_Wq9|PH%zLFZ#kUX09 zQG}_EoG+t`uB`l_9M>})6igHXVSB|v63{bYp%dRD8G1#Tt-WBleYj)wj+MQO!|$|o z0!@NETf5WG8puV&4gnLGsJH+zzdn|#4vW1=2ebo~TBhlRP?xtNvb zhIx|gRV5mROp3ls?p4H+05yy6H#pDS#E`C0+*98y)@!x&83@S;hGhKh>TP{(WXnMy zw6p^~esEm*9h6+rYuu~lPZ>lF{tnTl@x(8xJk9A;su<5gT?L4Oq_H1AL!C9kw^R6= z=~xdnf8o?j=TstQmq~zwnWOOLMXH(|@tj64c(EwVZ|==~z9Ju^Sc{^^Vw_8CUmHR1 z?fBp5|5+s^V&TZ#j?hW@~=y zKLC9Bi+{>z3$YIMB^V0YRSW67&_ZJ!r94t<`G$#EirsS7EJv`DXn?DIuNq;-EOHxh zA@#N{Mv*tNsRidJu?NNjh(@6~ON?EO^b=!^Bm~57VOK*T;s_DVs?@tYY%*7?M_AsodN8#;Oebl9d*%9tkT~k2S>8A=VNE#zUFEh5zuLCr|e8j1ur9br*%x z_WMcYYQ9|O2o}9AeD5;Qm8Tc@GX^X}0e!zJw;{jKll=v<>x<#r&)!;RU(j5ur`8g6p_ExC8u)iN zu339hnKqV@`!8|5$GoxJTx0MS)VpHgEKwH6ntzsdC{Rye1LC_FWeWL&fNo zFsPLC6!~2GG)p>%Y~@>6P@lv!|MbpPs(aqQu_qKhv(=JUn)KhB*SUkXv@whB@B1X) zf0;d&k~?Y;ezjOPW4z~rqH+GX5T1M70T1|u5Y`^<`-EZ7F0fq3RnSIa>mImOfMmX2 zD+GVF;q$_j%%|av9!sEx@|S+k>AIGf`v9==E<3?vUFMzJ=K-i}Yx9NwA3O!goNb04 z5t8R`Uaf!45xWY}H>bEU0;N@~)ug*DfJ?vKW`9)~H?3cR(kNBNWksJU^IlsENS85+ zgHC-k=tM2-JCnFxC7;NvF^~3WU8+Z(e)_w%66t5DIVq_>CL}l+xIx0hFD_^rNWqCT zYIYUy4os)zCnnF9$|t?Q2Ki^3q@eC+Et?j=ZAQlLvnU^H>t2P5EmUTGJ48kt&<<7j zjNfOyiLbDE^3!f}aYi4p8O<6@{N6T+FppIG!6p#Av^@G8uxS$L^m%yZ_2*U_6+F09 zYOVJSx7=V54ZkQ-@ImptsW;sM$0zs)$~F{HRQPtz4IjRVpU?TZ&9T#PF-)Z+aq(SK z+%(t3Vu2|9^??B$olsdodOJUzOyj{298KnwC;RdoITXG-PoBHXEkZ(c=7Kiv&PKg4VZMDTn;VmNr(VDL)?3Whx|Z{I z)9wrYwzzQS`v%-k!UY%R+3J^JB8h>2E;3Z8F;T#h4MAE4ur)AVF+ubL;Y}H1j zYqdTG5PdoK)u;Cneh^5cmOUEna!G_S^??uO#@pdAothJUX z6r^X(+zNc()tEqkMlG(~lLpill_RRo@9X_BI~_w1i%q6N>7Uav(HkJKaGg+R>i8RR}KQ_^^ zX8Qg%VPA5M%xT0rW7bn9bw+j3^&C;`de(5x{c);AxC55+vmK1eBVcfVx}Ra)Vme($16F zLU86#n&;tm*5KC}urTGgi7RUfJM~;E1D*y=PRxP;Uv3+PQv|+Tb0c)I!K|lUa<5mc zf3XBv(t_@3Mf-COWdzk|PP>={9LSf0hh1W4rSlFURXFCvhTG#VKDQTVsEF2c5RBC( z6)GwAD#g~Yr+fF`YV+2qn1U3fl_3^osiy{(uE+sd5X|8W(D>%sqzbjFcL8B0XM?&B z?QDZrAI=n8Mfvz@=;wx4Z(k1VuY5Sgb<1yfJ60DEP)hHg!09Sh`NU{!0q`e1JRv?m z(E@}>ruEKZ7~qdzP4}^t=UEnn%>R2{=shQ-Ad6D4sl(Et2=Z zK<~^W^neV$ERT?P%?~%|qhQ(wn|}9)jlTk)6@GYV8i|Zup!ZW?;ZtrTZqmp5Oclo? z4jeWw@@CRS)dfMgt~{4c zD=DOZXyU1Yt`};;KmgnCGWd_tGc^t5K&!caQl>4aBfHC#LH-Ls8ZD5VrNfx|VfL>u4l8^vveXLMzaq&z-W%k(RUPmEt9MKEt_VqdtGbK~J|2 zp)$8*if06Fxtcmh*+7OE!sv?1I_kqxjVXx2k?0c&`B3fUZLzr-dfuR*B7J8?{~X%H z+hp8^WLUx^@HRjfwtbSLXzlYNgf=iAWn$n*v%}c-$-q;JVn5}=hJ3l|k37fp%x3Q- z!bHp2?Y@SBXv|P)_P4(@AnQrjC+B0I@J9ccUhz5_LN7IvaUPP6N>NnfMDgeq86YH= zwqceqc5leLg3!2{n=z z&3Oa1fWQSUO+=DI|JFa%d{{aLn9nGG2{e+_-%Z59Ovj0iYQX6yd4XYQuf>w3@+DM_ zfmEd~-G-rS@0Cp*;K9yWlR7D5X{ntrxc4Vf;O^2s*{M@fcSbpn;XqF#0YOqJd?n9u zzMbIdCv-pbjmBz=S8I39w7|dWp(O$&BaE4Z3j2c;dzv%O{_voraJPl_t!Fk2>FCpv zI={zp-;#?R8%!t8gHm#LIs4tQ6j=j2?8w73q&MR}#z>tbGY7XXi`9 zeR~&fv9eY;EsL(QWqSv5&9Pzv$#{_<%-#NONHDZ%@F)>x&?{F zALRYmSSdgM?~m)}l_BNyUQE*~Noa~Glz%F%aZ)#5&`)fs3~ALvk%pl*5yb)Hg&-$U z2{GIYk~A%zO)Y4aJ--O%%THfu9o^HxmisZk73=<`5Naf^=2%)089D34XudmSe%pHFS zye%(q)~@N4ebIQ$hl_vhgzE>C3fm6Ao5@raSuCU~WD5$LX_u4@e~>V2#wXMB6|1uC zSWmul*a=wd7G0(uez?=+oA2ztFoJ>BZ{IdAV%R~HeNFLL|InPvhLQ{Qto|4XSCFQg zu&NCp*$}+bdn5C(RV?P-$V(6uSO>_JepK6jxLy3&^oQWD7xfDd8ieLy299a4#l4Y1-LTlENBMa;C?VJh*_-oXEdD<3*`ad z6V}Ub?;jvp52J`F)=vT4UR#)%)_A`tI5n%fs1g>X4oX9spv0F-yo;kCTnkD4N_{MF zjphu_+9JCVg*5%DZt^4Kmr^P8)sOgc*LkWT^!8)>C$Cj?;(>HiEV>Ja8mi;Veep?7 z|C2}2&1t-;X^ftYk!?Hvtx?36`BwR{xdt+3`=%-Ct)46-Bw6Ba!ltI-pNjB_eeJMn ztA~4>>Wo5XDYjyQe|7oKeqM~}z9WpV;vF15?OYC?y_ETQiF50Khj~+Z5X(OIFqcgX2ZezmuC|6Nxh=X`U!k)#}sr>(${HDK6-#rSPXT;It z6hjMbVOM!xP{qpeR9o1+yBFwtF34!DNyz~dvN3Q+X4|vKYNi(NiGO2ZOU_Iep5cUS zd?7xl5s`j~SYMJYR`f-MLtWj|R=jwcw1NuGgS&0Fse2+GE~Q(8+$t4>_M~bO42iG9 zS3)nsRr3UT%c2U&n}T($5mu9Hb^B-4(_!OCx*z0F&384gra8H`zK2yF?7e?3>U^gE zc8er;D}(fF9rvRejGcnGIC}j5SOAo2%?V1DX$L{XjOrLKoqK}w@_<)3Kg7m}%1Ag+ z&P(vvMVJ(j?`(^WqJ-GlzE+|UBzeGu&rsP(8u8=P33LO z3M?_P_sRYo)b?zSu$oYIaSOVTJY^sI>U~owtDSK6 zgP`jZwVp@P^?|{{ULZZC`@9H8b>+5!QxMX04F9_7`Rik}V3(P^3*r5e46~7(*_s?9 z%zfq=xo-+H(-pX(L^gAvBqak~`h$;~h^S*-9J;#>u7hgfZZ;W)-7F2ajscR(Bm#oO zoEYa2>!JfbkZF1en(L6%fauwS>>lf_~O5XAs)-=W7ZJ2*)h?Z&=r!EHg&<`DJ8l2|@ zWrP>Ib%;DpbUv>Icth{9Po--3D1%s3XA!oqDWX81LHNMENPg3W4!vviE1keHSZ3)m z=iT3@Uk7i^%0Ybuamjpn9QGW_fH#EF-^&|L1{L=g2BO_C^lXdaBR{ zbyJ2~8tF%r{L7zcwoQbdi0=67*Ed&KT*%4U##K$UobE;AZV4$$)b&*tx|FGC0S*sC zzvkG--oHXqk#o!5B?G!&?S7BjQMQm>0^dhu2ym2<#62QCs>BlKeW-4 z-5sSTbB z50XHGDzUCNjF#(wa!Mkbj{{M|yA%B=a^aK=$i@a{S3(q@Utn;M(N&!4#eHYT{W^le z!GPN-24LAYUk(ka!Bs$}splotbHgj{`#k?}eEqk<9LqebV(8Y>KO@S#^uqR`5gbf8 zZcZ`r(xX{|qV;u-ZJ{qlguxhSlUmd~P_}EGv20zzM^hp@FHTIgfFryqvepRbh7w;!aWuA8^Jt}B9+AV15e*1kx629E??g4QW8NL1*(N)0FCa=!>B+S($XqR znvXZ@JZI_>x9qw6_q)&amys+|Thh~4Xr#jEA;bCm`v>pY-QDB3{Mk%!Am(Ca^^vKMnMv!y>jp`k4E>M_H5P}Co; zjdr-_+DypLx4i57dZW`bY&h5FdMfxq`+N(%#m@yH>hw}|o24nbl^7MAb4{|g;1k8>SeF+xcPk-A&sgSfr zY(G?nqef17iDI+;=7LjbQ%ZSpAPKAMLLHk_05y>(?)m_jdU_>07C+tP6$EN=sD|JK zG}s`HT29y^tSW(&q|;7ZAc)@8BDk@cc%-Q5v*UT&IKyVoTZ8d<)0DRCVEQN(>AO@{JR?F1J(tGO}yPXkL+KE{N?*s1NfrDd4?kKv;?Qo zNJ+Z{`XLv;wcaJg;rMo;ndKffWPj-6wV|$8L=J9PhWdHB`_>NuByXISf+%MyE0ImD zQj6nprjj9CWJ$iJNSUOr4K6~~H`@RwsguNtm7CuRjD?E-l0=@N-MtQ)#!P?Wsm@z9 zDJK{eu52NfQKdYvWOeV>%a3*24!55qlemx2X~=&Wxds_AT&=~T(IJk6~Q=2erlU0ghlS?wSB_d7r8_41Xl32S$0 zK{c!V77~S>e~z+ahkXKB(VSn|4p7Hs;%)1c~0sr-e;IOkX*^`Xu|cc0NjvJ+hk@ zRIz1j2{V6E<6LpFr&vin1N>lP3a$#PKrn#(7L0}b#V zu7Mj|Xb8{ke3U`1@2b6fy6xTL`4Opw-9{XW=o#gs=2im`61>nG?NT*5kv>aFmWL!A z!~!A%{FTn-Jo$kiPIFLcrDT5$I^rq|2-~p2zOo)-ZJ>INnMLl$I7yAx{U*Mf^M=rD zuBO2)(JQYy`Z_1XLS)Z%i4M* zc(7&t4@ml@=gxB2Z}cgvs!^YJnUHDXsf*mMea{5Oq`wu>EZ=B`n@A|Q^E~SI0;M9# zIy8M#A(&zK8W)lg0I4?!vp&0G3W5=r5SAHs<|G*O94NZ7&`&ii=X^?%&pVuqbs4vk zWD?O1{8XNn_B&09+AbZiNb+61~s4V1w|LL&bytVf~e86c$Xp&}MO)FJwSV8QM@VECo5@Bt`M*{2o zU_}^p-_ci|E`4X)zke3;Vth4r+DYNOHt{ytNuJzYVX7D_sr38vmZZ1&Z*T%_O7z>m4o0eR$ajRE4L;B zRam|+@D>`YC>`jpT}D}!2kHj?cvIL-3#tG09;BrsN?B`s6flIdyud>k@|wmQD(2du2l%9JP=M7z(_T zDnbi!TcIm&P17b>`uY)Oo>gCpo##6}yvoA8Av~s2Up(Kboz5E427Q=BM2ln1ZGrFZ zZViA#FT(mW;EZkJdmBzpm}A5qddtoGf*6bXL+p~N<>{375@=rXNX<|pe5V>NBl=A_ zE^E_n0=NY90c-!^WlfwcM$K;+@OHW}F@V;&NWHO>u6)l%$rq=Zzk0HAO0FfKdQ$%d z{j}S;5zq*?n&-;TWH_^@5pM;Zhg{Ib0{@2H(o?>9B&yJ{8P=W3!@C1)2J32~HUy%^}$im!-B`~aRDJR)C z9brnjhj19a3niVkzwo6WWc#K#Dv7;WGO58p3cCjrG-Q(<;i4N!RG5pfoM>I}8{5T4 zREg;%FUFRW2!3b;&^pqjEvX@`MNO-B!D$dXQAXN@UlD!pzI5>+q&*goVym6`^zXOG zTJA52lzcC((X2=8!3{owb!0hj>MM)m53N9SlbLyNToMH0mHemW@p;I*iFclFmKFmS z-ITYcW&cvTAnZri?l%Ue1#y9gp5@jq+1BNH%j;Ors{FXWTjN!4sy77TZ226lGG5&$ z693fzG-N^LvV+~f%l_$ny5fGC5DtB&i^N8}H?$h)(+F35EPjw#7JC&x@9nvFT;S`K zy9+h$Jes;a#9eDe`;sJ3Otnt$1WGY!ccU-fxI-ij3@sJ3hlXzxJkP!pEj9saSM0tE z{E9`)f)(z|_uTI8lO-N#N$ULLQOaj9VO5@t6U;5}fjRpW$M}*?-`B!25ph=5e4j|) zQu|Uf)rFh4)PbOs|C#$j^3I308Q+I@i5yXcaq{G;`eHqtd1d^9 zJ>f5_zJk2i6uKjm%X$~3S?e!YgK^fTy;rd1XAm9CUPbMvK@6Wt&I3uvWYV0cqG}7a zP>@EYaK2&wWWD70

##PG-HV-nrT78GXb_LO~5Juq_{!+&I)8rQx=m&X18l(+j;j zlkP|AMkht0!N;4SCPVs66oK=*%Kpu?l8#1w z4R(#j%Q2J#B&m7FcDkZ55v=j$TgWMH)^H7_9Pxy~(L}@Y z&1x?=2y{;|#4i}V7R3o12V~g1LFct_Iaa%rvJMTe-jnAPjcb0N zluq^LFgwwy6_On*gcZFaO5}<4N*oxY1W@tyL*CGjsuV1-=tnbK9yatLAwPVL&A9M2 za_G@yXfezL7kPw-glEe6dPXDX)qWN;D4m9$A(BCtRq93`vv)-9vd5%=Z^05nja=P2H?PU*YR^0Stp@%Hp#6F+WWT4V~egW=F0V}UC zn{QDc_T24KD>v~Yd@<^<7IMHD)t7{CJ+8_Bt|h@1WLVyae8vg&{d8h z5>@igO?d`|a>zf7B$(1AO~(`hv1gF?V?)_x_Iz`jfO8{2N|ptY7%E@`qjf_Z3}W!- zJWr65n{tu18!047v16u{UzZT5A&2IYu&)=6YVO^!#8t$-nu!DKePJub`((aLS#DDD)TX z!Y`ROZ8`(@8)=HZ()_=W!8V|G3r$i&Doc+N!v^q>>oE$i>G!BUZLqt zyu-59xxwvEc905^(x&e?$5SXd^ci^U)&;9@PBt+~D~Y=#r4r(6E<2(KBofV~z2;g{ z1k;PM;iIVwh4njnx^vX};&r9KwwRE4O1*MZRv;P?-^n+k1#{JTsH{@T zNhW?7RZ_R%SZKKm0W)n10S`N)?0v|pxs{NkEK<9rL$q&osWc42Aa_M~l-A9qSf>OV zQWp0c;@spm3`+z~3H%j>GO}(Hjy^N2)Q=Vs7b((HATsYKx5vCU%xEp@q1Hb;>h{`ftcE%Fau=OXh(GvGQR@352lE z@6+L?t3$*xnUMT<#}J#&AIDnBcKcpcUkNc0q0Y6AL1BG zlWf~zTPBX2It$Nj8n%ZXVwr4+BAg2F<1f^y^dR0DCL%>*H%uWl?!y1-2teitIC%s` zV2WkV*jn_W)L+VFdvw8M;mVlL!`;MHFSVQOxu&*Yy?b;Y5W$+zdFJFyjnNn*_4St?etK4 zX!i`Kf04{|F7~c@A&g+6r*{!@@@vPqZ&{2acc}3&V*&p#YFXLigP!cEDEF*b#537M znt=Zn_d{Dya+NHC5Yj$|_VFdCY=Mxt?IgHGH^Z>4Qj~JH*aT=>LaTrp>~gqZHO$m2Am-=8QbghR-A9 zLdyF1T)}>|&l~R%{09p*GtKyGrZQf=*#Dejk+Y$@thi*LmJk9oQY3lyRRQ#}H~+o( zXFSl^0M1hOEm4%Nyx@qtL~-l!KDVLs=11psCJCl|Tk>thTrM`S z=LUueR>p&1uwPf$QFm2vHm~xk2aGn{gstb~N6_W^Yma^P-q_-A95NIuN$tUivgRL} zlNCQm6@r$>c()eSvLLkt91*AJN(9qwZS}XB1e-a_Tmk2$HI4lGE_hJ1j=vzFvqE~8 zb->^YdR6Y%dgJsHuhoqu20Qb!0H|BFOmm=HriGD)pHg3HB31X_c&=a^`QlSdnpZcy zgg5m$A+y1Q`(gC*H)j33kZ|yi8xaTHei>JNP4qXW5=k zr0@+Nt{*q#;6lFZ=HAAmZ`=Xb*?eY1E9FJ*>8W2Z*#k;NRTrU6#v&WGG40uEp_=4^ z&b%t~$*bSKF0K}Yr{qb@K7=-5ePFChfp1W9c7OHGF{bnNLPZw*BVdEKjSZn!nGs&? z?nC{G2sY?jWRE}$hAIvc(V$WZetO?)|GtD5A!(8Bv*S$?MBud z#GkUM<$y2oJzt;x>z-KPe>Iw*5u}f^tPgDJ(6_7E-e@YQ(2L1d+USrQ6|g15 z`J=CL2iRAqMI*qz$!bt7kXElvM(a7o>IL429F~gq#TmlaGtmkJcrZ&rtZTAu(nNzo?-4}$l3jk6 zIhOVDzh;ng1}7zA!!DYDHi31OE*>z~6J#BBaf3*^^9xPi z+3(iw?}Hobn8COartAMeA9LLsRd5s0-(7^2Zq!=wINnDa>*Vn0BD0W@p%{4e1bQ(;7C z-;l3E+AB1Nn)P23LLKrx@~xxbW8K-B`|C^TT7-^1MSvJa=0hf)dp32QUuI((bqpO3!9Tf^6cRX@g-VlQM7 zOKOPN`Y^?d9(Z*%7yx#c|0?pI{=ViCNfZ_ms1*j$7G>|(f8G<=KKQgcBV@X0$dZb*zA-;coq;p`(K3WQa*Lo)0_$C{nBZQIyi6>d0@6`G}GR{smY?TxkM zQg2m{zZAFRl60amfnJdBc&sP6avz~2PUgeRFw`LYUD34i9OvP7~MC*HkwhhBv7-{TsoS`F@?a8-BW>^L~>J10Om1%70)b-r@ zy9@?c^V&U3DK=~Nyo75MSxKtlNOAn|P?V1^6+uz6i!>eZEy8Te;pF`Y%7}o^lC7H|=a zZE1(x=#7o+j*C_i$Y zgEleyLimhOp`mJxlBQno(f03=9CMODjIb#6S$(|0Am#J;IA1~QjQ!md^{!WBNVbSS zUnBR+bleg>MEuUL@Y&TIVIfCuz=*;jVndrG5&n!*LzEsc`Lksb(NAqqk>Qc;;rET+ zJiiDSMo_qZp^)Xp-Vj4f6a*}}5W|C*3|>Fd9)KDG#GHCgX?SoPce$@LVaSG_(Ll&8U4X`qB?t?nb;j9rp-a2J$m`SAjicdi^tZ3DLTZ3VHzvV9)M6 za!zDFFJN7ei9t_Ds&B}wb3Cd}}<4>prq&vL1i5DsUvz7kcG3gz&U%Gy1sC!D*N=aCW9>!xmQ{~qk$6$oQn6e?0ObcJAL?ElBKK2E!P47bQF{D-Lh+l(4x z`Eu{_5GKi!q+1faIc;E;bLT5!?D)fKBLriGO0vERT>1sgNW!D8 zFs}cqw?BjWwE$mqk23d8`~9m`W;f=GYqTY69jw<928GVfUFr*BP&$RLL~&T>v4}kQ zrvr|y(EQF^3;s_BccCT9Le$fAvC!`>$TgPuS_)cyS!!5;zf5vT-2Gv%_+Cjak&C9e z3jn$7nkZJr#{>4AC-1wvom5@)4sqWS3jAVmQF{sTK*0AnZ5~NBny`j_$eV_1u=Y1L zfrX2!;MzQoVvS8x#O7NwJrutti5mDKfRYnPJ6XFDtgNrBPg%~~GUh!p zm>j$?*z{l#P^EWtj=efKJgEUPo1I5P!oLbtGlLpNkuQ-2HcY|Vv8JOigzU9M;o*6} z)s?>S*i5f2Cv(7&ipJ*1{{k#^GatznEmL64ub{Z%#Cb^mB6=fEaVcQU)9vK z7=yojq)gG?6|}$mOu2~bXyII2%Szy)k@IDLW29+FWnjSYpW|1JI9xp;mW3s$qx)~j zb(t>TVqo|F5oIQJ&+CjmKHPrX^-MPEP3InWu~nc?-VZ2(+?OV{C*gUNk0E2jTr0qUeH*At105t`W+x`E3(ct`B=WdA?VNP4Ah z_7l=w7)=YVXY&h0jVALC5T=c7CvK;`&=(R6AL@%R)HIhca>Kdkx(q=M854*sB~bpa zDUpmmJ_6m70W3^F`Ka;F*=2gS{{2P4z42$XyWA>=$0NP9%$S__*ur@_K?FKxz$g6r zBt~*qv&#P}56WH#SeID4AMUx$PRH4L?r~yJa-HlPY2^XLMF#9f^10ty!RAcDhR3d3 zXyHW>cSIfK`a9fh6A0pLK>-sD?(+O+&MWI=gwo=3+0SE!>ftbYQ&JF5oghmP<=WRY zA-S8&k__(tuF8`eI>N6tJ-3j2_t~}z`|)>{bhPa{LM7s2h@v7|h+RE)5j2exU2BT_ zDb7vc^ct?y%I$CIynd5^B#1Fc_8bHWK+tWsmjX$MPfI2MeSt{gxrTip(e8^tTw5Ik zIj|S;@7PlhB5gSSc(>ELX8-lW+U=~S$T)QZ{*zit)+ELxE6djBDV?e7*O7z zu>v2V0Z&i=+6o)q0#7xxO>%lM-%@bv`2SwUeB0umjdKMrixdl598%Ds{%u%T4cCU6gg`tz~>j`z^-G$2tV^H|FszV?0@yZ3MHK zCoEy}4++ede4((nAg3<`FN!Xu1|M&hqUC--4fEF zbPnAe64E&grE~~LDGgEr62lBgOG`6!4@e2>Gu-d{`w!-GxHxC;?_PVY%=4dAU|%xl zJUBsU74$CzWNYHk=Ag{Htc360$H8eRY?vg>kf339a-BI8D_d0KkdrpfOKsN-3%8eb2n!R%&PGmQ&$SppC z*V3?-@JXq}awPcUoF9<#&5NL#Lo3oVX>_frh3!iv=YDH@XOj3;!W%hD)UECuL=yr! z5wW*UY>u+S>_Gd?+g*P*KQ|kAt-Lbs$Q4E1ZR4 z&u+)UUOK`K(a14x`9Qd|6cw+8Ofx4d$&ej6(&WF^zpcB4Np*D3xsCFh)gO7y{|-Mg znyt5}{^V8sb!y$ckz-~D#L3Le=JHjP+voIH?Pu@~u5&lBRg!M&hbvn(bwp4V=GI{V zZZSHhbpFfz%m&AH`48cC)Ue)|dx$H+HO4JlWd1IP$HBj^NZ0GJ{EDUh)_%U&?2op} zuX`A^m0yZkN#m@}pIUqPH=$E|aW%2oOw7XV5y$;4u0z5k&e@<`?dsEcgLVcr*Ev&4!$fu9L~G9LJi)O@4%ODDqrpk zV!v7bQI!~VJyv*{uHO15GWFrb=_k$K%e;sNO8k=*b$fkvdVWu7eB>p(Nb>ndoI>BJ z8`1|9j*LMW1;02JlR&hgq(iP|&xB%IxPpl7TrO=gQ$v&o&yUs^p3u%u>KXPWO+VkqGv$CY#R<0u ze=%h{`?7r2GC9d&kHT|Hn%rJQy_))^YA%Cyxt3J;9#*eE@fvw^S8t`xTjHLFIk(AA zj}pYh{GR4$kN7eQMk%#PY_B#DojSYyul;i8WTeeVC=rn7s)fDM6rk z-uH8hS4c{M*}z7j7i5QwM+gjzeg!Wh?Ti^3(s2(c(kfq$mo(T`bsi@}Zs?Da!O&Z| zdAik4Fsz#t@zzj#9H3fB)D9=_oSk)h@(Ks>cXcz?e>6y6XPx`+)IG-`6}$2_7h{Z$J?UHqg+XT z3!;c?Q(R)OTJ^!FwB_xsFBaRbz(nm#DagcH3aFi>+%Xz?fRt)P_b z4*gO^xF^NNhRINea4p>~Z+?MW7#4&G=vpAdH+f$B8P1^9xdh?p=fH@GWV5sSGOs*z zm`-wAEFGWtz1hpfsErBMV}!uBx*LP_JDf^7RX z6R{M0pmJO$2sqG@--KNVa<7e9;HReZysF!_$0!Zoi7LcRh_3a1j8-ScE%s-Kb-mgg z>?%-3ElQ)E&ho)SgcqXXos3c;a+iHa;X#XXLrY^6Gmwv&LYbXOxJdtASjhsK%BjPvr7xm5rJqsY21Lb&icJLS2P*Xk9WU!k5(iU^U$ zU9?Ej*otmj`^4#Bl+A(cpQ|`=B*v;pkT49$3PqNn!@m2j7!K{7h_U5k_Z9T$aN;EG zOUJKH561-_$i>WS4t6|u*qteJEN)PFBxim7xKn$36^~ej7!51|N9n9MVZ?y-*6_YR zdR;IhWIsA)9zm~yyhyBenZ{-Yv&8?T*kTF|ffTI7H@x_7^Ei2P+IeranRAB=Cf~;~ z7`~Ma{^q9Ci=OW+#QwulQ8qgn&yi5V%F3e_XZj>Po>#0gQkn}uQ-FKJGuZZ2L@Wm(#iWnA`*JzZY{Fsc5tI5(_d{#YV={j!!?G%qiqLjF>pPUxsNeS%+2 zjy2er`AW%b(nmGcQsm~%46uy0EW0W42zrqG<(-$ZS92bA*3v16h#~BeNw!NehoKrr zH|MSXM26>BO^--VDW^H0bMj)n|? z_KWxL|Dvt9>uwKk#UPzd4OG_iyr2QG$UN6A73;t^LCsk!`r%&eXSxziW46@Tog)YR zA(}ig5rl#u=#tmg%U3#u$|`nvgfmfJ4W?OUHdV8O?X=lwtQ_Esu8a%#0TAg$fp|-w z#Q2Riwn#7$E#vyZ2<3s$R0Fs-;N8PgJdY&{SyLKUakdp$nF6rTsgzz7(C^hUVPz zYXLDTh^3a)7^sVBQbaPhY>K6vHi4FyjR}D8k?vneUWG)|{P(WlS$g>3Zrg*jko@l+ zYK5gR9HL)RipOL*GY+f-EOUAn~?`Lrw*iF*(JZWkcM;yeSPgKc9Wz9F6y z7M>V8?D;!tKtVG+Y`WP+7^aviaX^skSGoBTA`^8OLp^at6!-P5ODIo(vLX@K^#--SY=y@n){4++z17lH5S4QZ|ju<+L7kh&0jP2|();_6X)T5MnKMSb-Voqh$^ArVS^MWcC#VPw{^%n19bOIisXi$fO<~c#rn* z*)P44FT+EVzBB`YOZ!jqLH=)3QFv3{hPjJcDkQ$2t>0w!UE}(VZdjisT$(|(Wc1Xj z=YV`YLWsO#*nQp}nya(g=@I>BW#H!P9nrke@Cy#*0`F&YaoEv1!e=i$0-(e>6CE}T zTj^r8O+J;Mj_5;52h^kSiJXb7TV5}Y+)<->haG0_7&`^#B3--_N*@w2p11zi5}oFD zCSEqRH~3m$$(%ZI7qQ8{iFDIt zY-)}-FDh>te=_LOGx zCeV^&SKf0GUu^?!%@ekx#}z$WZMD$oiN7#=_1KMK6>s8?OTf(`^NPUndQYJxePrnT z(CFGznRxk_;S>6HA|o@A{v+7sGV>Y*jr|#-Oiz*pr&0!`u{?-YQBM9$hE=pXc`CgfBV@P0B0WAWWk zqG5^zp_6^2>5UW98TepRV$C9^jyffP$=?x~6p`AzuCp}Y6%%UQYy+6}Lcb_i6!<03 zjf!qjNC^b5gpzR7F>-NK^x< z;TPzoVbo_;)#zlp<~ZbL5|sRo(j^@i)9>lD?Npi*1yB=+;~{?T9u^5J?r-Ha@VS}j zL=w05!i^dH*>y!E2_=ht{TYFslxKqM}X1;Kw;Ly`vU5L-Q z@;LXSN)L_sQ-jlF=C(1vbv1F}opzuY7gKVCfLVpn4swuwKeo4GRS`Oogb&XVCxmXV zz3us_#HhpPX>zt48A*KSz9~iiw#_5Dp69j`nOrDb@$@qc*LOFu24rvsp*DKM$fQPF zz4xIZ9wkrabwV(2hY9|WfUS{>CDU!vnllhBsvpc(|KC{tJ98otJ zXBYV4ANN8-%>Kv@Z~cswT`Y_QQ$$+s<4m1B3GfzYu>DUzlhQYln>&`4Rd;AqqID=% zcHCMBRz%5~l!3jptRMtFZp>fXwpd?y`Gr6^lS%r(*pUrv+XiXIVc^Y ze?NA#E=}oB1A@kI(}r%Q5UE$jK#^n(Y(cZmSKe+(l!|8(Z@84f?ssvZbD(tDv>58#$}3gNlr`8^kpR0?J*SNFiB82?X6NBCSp3 z9}Yj0wllJbB;!nu^cm01l^d8)k(b$irz|}lF3-m_sC)e@uOeeuQ^=TIfKudIbIH4* zfBmDPjd>cgAR#21G4m&AMirY zIn;Or=sr_`y!JId8wRbg#LC=GOOVoiPoTFGVrLP_Wqmf`!v^AynSjSbin`i~-8m;T zOdiCtnOqTt$X4n=Zub2T2i(~U(a^ltd?Xg4Uz3LI2Sn+gGo-USEnqhb5fqzplknmd zsH$=z^GXRMu)Gq?PvMmP_a z=(J7p4bA*0qRqbl?jfXUwH%hnqc8mYs@Q~t#(VqysFjK``_>XpIhz{H2bFC9a71+w zlkvq2sh+xl4`jwbuHSlhlsH7*5sHlw{Cf2VI#uH$A9-#Lj=R-Mmopy>UkEIkA2ib= zoRgHM)3F^gcKP{q9q{%Wq4W^mD&FHK&|BI#g+lI)d5sajcj!DKqVZP~A}fOcznmDB zgIbc&@@R?$O;cuBJr<+0K^m5%tk+@jo)eUs4PQ7vz4XgPAx!!xnaB{S9Y-5RiBmEV zMXe^Dor)lo-vLadKznhz34ic?!)0Oa=*YX}15}LIv-1j(`$|D&a3EdMn+CC8)|(fQ zRh$99Qwn3X$9xv$2ZLC=rK#2n#E%G^5%IRZpHqtZRFkBY>0Kw`2A4n4>lPE3fJrzJ zG&ogbtX0Qp4+8S9?bUvyWfl;39W|MSXmhNXg?kLA&RR*(KFw7`WP?kt?*4WfKHIK#gKpbbc;95FMU;KvTU?>M98 z3%&}|Uwf9UXrH*9B6iSH*u$cNd;`?oS9F1DCq&W!+G1_ZtQ<8*9(gpH#pa&CDO?cO=yBf~H zhrDKfzH#EftRk(x*=!(KLziT@t3b{a2$)?b!)LDmZ3idg?WzTJ~ab;$e zf+Bb6!fJoXSupEIUc4wkHiCLCSrxc89xSfhVx391g*SjsoZQ&@t2g5ZHv=Q(Tz-b# z_5>Tinax3v?!C(!yI+zOGJydW(UT6Ga@e07M`Ih~|^4Hu%KopXr4G}qz69sG-; z?1{#>Rj;~xsr+8cFSJ(S(Rut+%P%)e=A)B<6clWqVg#8gPg(2P$d`GAWP_DdR)Z^4 zv&}q~aB~j<=hDT0UPKN5-J@b;lWo_sH<_H-vRzDmbwXEb{r0Im!gBRd10K0*d{8Rk zq}34sXCi+X2Rtp|9ifvb!w9>4!%AyanXQN2z=^V2;?)ew(1DLyA_F7M*Y2PhgM4~0 z<7%gpNEWJq1_N~nf(~D;kDA2o8BZB!%P6RHYdLPI?Sw9@p)OV)<*9nxm1Lg61i-|J z;j#$@N2OTpd59+4R>+i}$g(g~C-qb7m%q=fVXfZVuYd@W3y=%y}m3VKBo_xvFO|chQP!-VS9S`4g*n=w5 zzOxm8yHJ^=au$ezX$!9k%tjDS`<;WSV}#avo6GV%cYU-QT5=noFKW4ns2Yr40nwSs zAG>UUlm77f#ii_uP|ss4H*F(%yl@Oe%%)pRb@OJOor2u~tnT8GQv{wbH$YPE8%rP)R9fUd>{v1U9M$jBeE{ z>Y3{dD0%m#M^_A-n{^t#A|zZT;7cpL`o~N>kzfB=RAl0+3Bt%rwRE22&j-gfSp6N* zPo~`9l$yMP@3W#Rv&e7#nOErVm@PKXxir-s3lev@dhC3`CLyLEEo!k3VuT(~C(?Sp*kXFTZUseF%K-M0IJ2 z&L`TL!Xgl&06pEiZ$uQd((@BN69^Vp3H?oEOCRmtMcX{Vu<|^#kS*P=$_^jr&m8Mt z-@1l`Qo;~(hesy6iJMZIQXBaVCV{Kzbg8zsT1NQH?$v4RE|Zp2^G6*C+`p9Yx7}aw ziV@Sntq#Qk*FF`=$I+azLBuxahkG{&A!KM}rWI+Ck*>R}!MhFfee zP+r~Z4hNhbY!4yx>14LP==Q8{UNf!R+R5$Vgu_ZluE=R`7mcs75m18~8YgYpr@!f3 zq10@sH5?KzEP!H-UZg2`cEi$c>p>>#uw6DFt5BH4scBY>Iu$6~fGGf|AogvvjlHdt z&Y5)9%KhGZ(alPjrHzlta{LX8h2wlJgH@w>kw~b5DAn96vZh*qQcQDol7I`CkVqGc zd5_!>O~|gHo>K>A$|X??m8i)I!cq-jM5@#SOX#Uze9txcZ(^JZf>5X)#^B;# zN3n;}SFO9VCBeX9in2LwA^7DvkcLL64NB`oCb|4u`sppw>gs`Xp33&4r@vf{_4O9m zIB zfNxc@$gU*0FXzAs`|;KxY6(VrKH?(;h?QPdQa|(%_&plkCCwpl5p@$cCSk@2#Gf4U zp#@xvO!iK!Ne{!nFzF}al7HOAY;RbFKc}Wb{`a&0Ds8WGX>WWVCaaFu%yiiXdTS2Y zkPrQM^R-h)A?RYH#p$7#t?e7JB%HasI}h+vdL&v~SbF?!spUTCIFn{+rXPFZ_{(}L zXqx?3R|Av0m6v@0CZ+akiqT9TwhJbf0aMKIKXb@Hu(&bwmf=&4?MyaY^@6;dWVM1$ z5XoJmiBRs6iKsANlsnGo_fN3|6%;D?z~&C_X};g%OUGqXA1dZL2V-h>tdmx_>C6eJ zGsc^#^=z(D!t`n?tNjQ-Z`$x!}jE|g>-}5)Rh&(*4^|htv%9vb9a!QVP zv7?ZUy*zXUC%O8R^QYq~;c9QsatZf2H?O3zYV+bTLBlH{SyTiY=oQ&Nk&+P|*mJ6e zxp%)0i;S~YOC0UZYio#ES;NsDsMsH(sYzufLd>ALNO8rC;{b+xhs4cZ+TS^&p)DLB zakBl;R&wzf{T0d(oC$>)UPuc1O2dSXdP0s(NU8R4lbkpR<^>q!H`iF{Xe#JR6=X&F zeK$Cd5Kcsr9MdFP`9 zD{SYoQ64#O3>oc;3!*5ta2!ib*p_Uf$x@FXu4(5f~mytKQ&Jf{?SR-DSc}RWW(I?_o#1nL}HAX=sf4X{l4#hI#@iJ`|-> zs(XN=iNPzX<&~A zS(4(tjPRvg5E1qtnlSe6o*5gFku!kI;>-3BMhTin8#LAvcy{d)z?`p7cdcwHo#7Z}`cNjEc2_GDDXf96(Cl3gxK4bms1 zBRoW3k4+NyIZUR<)Z$XSy<$Ztv$3}Yv|)W_W$QK1G`0vowfiuq*hHWC2_hP!-9MVp zE^=@qpQoj7|Jp9Y@bc$Lcr!6TENQbU9u2)=j3qMae_8-(*_=$n;CkpxjVqeT6T z?_`KOd!zsh&CV~JzJ1Uu%&FhWoLQnw`hI736c^{m|oe(db&3ML*h`~8F9u`@r=^|Yp)B4me<%@C=>2Q*2 zewtsQ20jV5`34%M-^6T1p`7_;u)%9%HAT_%1J1lJ!RlqJ4I$rn#cxiPPg-0;?Cedp zmjegU19~r{>1N%I5Zc%J$HSu3ZqL3r&4ua#gA_zMP~1d-_%UX%Hc2S@E|xTI=+N0x zz!G5qFIceQx*Kzis9QEbrecLFfa1gFs^l{S%cIS}-2k$|X{4JB-X3&e@r@q5--L8( zCejvOcw{wef=jOhT0&)0#@^xWh2~LTH8paGLX~PNJxDz!K|lRtA5RvJJ)EUr5pb*t z4ZLwph%3{iC{RFXF-8hH>f1^Yf)#=W_f3Wshty?Ugv}dP!)s&9hDvR(@iN ziGMzPO&@j6$-=duGA834Uv_DRLe!EqjvjEOVjjj3VjHlx+7wENk-$E5Nm95(&Q!;F zZkV<@IkKYulCeL5WkM#9OR`;1ib{_`|EBx?uLGEey5sO=?6(dUg3I)y{YI|uh%i1@ z@@1i^O8F$hQk!Rk?~)0{AL}Bf#8$?*){J-XKeNqh>#0T;80NF)296US254 zs2HjbmZPc8!EsR^x~tz!N#nx*?{&fw=&;T6<%jm%%|$^XlBViAtH>U5@saNzolpew z94*e8-_Zkf|8QPh$xj8sIdYMYj+iF%;%Mj02ihh6X0p5ADVRaX3D@n*rzxlWlnKT+ z0pF_>%=Yk)r_Y$T3(34S8NIuaQ}IWijjNoX`Ri+hxrjiT9J@D1UO#0NOc*eMAs*Sa zEY5uPpsm(cH#6)PKDXK1Z{!pn`SQDoI$1OWn7D4yJ>q*VKmhG;(5HR!iqJJv1Ayho&uH97@4TFFSC01HUl2z0rAIj+Xu zf&Ig8H7*y`VuyokO57sX1_<$_I-H~5>XH4ed{$&B-?m-}ZRQo(hT;5hlYKwgcfS(D=d3G!zDg{rsnq^b zms5281%1*b3pW1#*N4=ea>*{fxhD97j=HfX4ft@+hqDM0fD&7jPDhmK%y6_mfWuCn z-RPt-{>O(k=0=SNgnrNfroyr=iv+8(9=mcJy+P?D$tHkM2aqj9Z-(;7iz{yadUkWz z%y(LQD#m=X^+6`hiBW(qGB2}Az$M$b@}yk}t3GF-`J~##bvEFt=rqlL!na-4e?qd5 z#K@UWNf0OtUV6!SBG7)eK0%&ccGl?-tE>N=UVkn{$XZX6Ieq|({Py+HD@upX$TT{) zE75y29Y4|0*|?b<)oc*w_7{-?_5$0|v1rkbHxmc%kfw|F0R;!Y)T&9($V-m1W}+)* z38z0ZT;nqA$MOszm+WK8l~lz41>uwkA=trO>`W3%1?;lYOo1tCb{~E5@^y{-Bh~2o zi6BA#9#>E>rAaf~<=@+mMXu2NIH`7VuWtMhiV%zt0=Pja(wX!VpNd+>0bm544-sr|<^!VWh} z{$|nK|My0Nz=N;3&8lnv_Z>d%ThvD(fVp?Ex5b!T1K#sI5b}x;&?ak;fWOroSAHac zx3h2EAUZ>6!LeeQdBC48!&?}$)@8mswrLwf&2NX2mSTOIH+@Bzq)jW5aJEr~IWy6d zdKr0j+bBUy{O;F8AVQ}eujTL+(=&v&>eGlIpz~<`O;}9#N1hs z!F`O?$7`DVG5mJyybbnU<~tq{B@zk4e|Mq5rOD4ZB~SY>+E`y-CkMjgGo&&BKNC#P z^YW9792gSwNQd=BnlG`G2Yfnb16ZvMlj8eWYRoy5w=PL8zC$gsy%XZm#UM;93z~Wk zx6SP3fEgdjiPcIhzr-cT8l;S}iug1n9vx4Z`5+|Tw#V?z_}Qw;t?IK++5zwI2wpt% zb&B&PQklH?lVtOK$-XS#bEQ*cFsak`z3${Ik*QDtV{Q^Fmogr~2fis1`Jo{)VmsLo zH%g1#z6m^hlTV-8a}Mw0Xk!kAols_XhrZB?zym`pw+dM8m3geOg6t6H2)ZEJ9?;S* zxwWpLbk7VRuL5{3AdTErviaGtDv0f(EB6fu4OB#hTU6I zBJS_r@N%rGW~X>qkEz0nxi=3CQcPY69n_xTI}}v#3n{!#QscD2Sm$i6vk4DqfiVOt9f^{qYb;WI{D~%b5gJ;xUI!V`5~VezfN3WsSaTrsYPTk8NH9f_ z+tJ_TO!M?G)|EYsRZQvUp63b7z3?5!GPcwT!RM3^w38J?^bCl^FebxE2U3aN;Nzm_ zn^9}m-ESk2oXZ8f8N;!hrtS-2?K_>;5V3+LRMlr$0Cu5w*ahsm;*!)rs*LnK=VCnn z5aRsgOap4%;#UNuCPbJj``9mjRHRn9b9@{f&zN}Z+asfK<>~qn6XJUGXBtS`{Nv^L zb3C;U|Bqf#(LKcJueR4m(<@KE%gw?Zoh-FncDnLN&MAidolN|LhgB~xNDJlu&BtgQ zZB)(k)h8Xl$|wtbUsV;_ZeLeB#{;%%Ydci$pURc6aPNW{5tKT_lMCL za9K53iVNS%wEAbyzP*S5wWZxaT>#xQ@PZA}yWYtqF+!X!ntYFhC~L=()RNe6S@M0Q z9%g@YWF#>n$(DDU)ZZg;I}=!`**1sL@s6#v6xU10DbH!(?wQD-960k>^#z+{vNb~( z0oIPD5Bp>+h~527c8&iu%Zgy4pe}pq0HU((eCeQ(b!ZxvVS4_nHM9qJ zR`7{3(dQTYkMkEW^!IT0FJQ2QkRqB=IdNkq=6MRohVLIXr5Q`#?2Q1_edzEOv8qY? z{*Aj>_xqEj7s7p&fva$KS#ie<&s{Qx=h#mW_fLRsSwAh-75k(hsg!hDKi3*;+`bd_ z`l6u9)|%oiJ5NxGle0Km!nk(@!}^IbRx7M(>~-K;%CAvjnhqK(rO zS#7aj^zBXrP0|p1E3?7_P#GFD)uE?ok{FRD{Mf>;WQB;nBhVy0vcX$LkfzqYBh;H4 zuJBPQfhl4?yGmxDLwHEqr(1SQ!qun{>P^6FR2zjaDPQ2dY5`Bk{^4G_NpU+C$#^|? znT)!8X6YFBK^=GvqCk1pn{%;Fy`}*W;aJ07b+*oU*4M4kue7pq<<9Dg;iiCrWUv^+wR=nSCL{XT)k>d43qzar6C_ z*r&7l?VWMH$h@c^Cj!x=kRaxvyOBT}1W_cw>{}sQ+OT^dCKN`njw>5~SEBR<-Kwv|1wAt zBLX>)r~lbAtP3ViM&&(CE3o@gutB6Vr62w_WBR=LO&xr?Qfs#)g8W<*@i1d-mreU` zb$)nJy%4>T<%1+F;c-C>12D%F%lw}0+m{`I;_7!BsOC|wSf^wioG^sK`^dY?in%;W zxF2W?Nca)E88_AGHTr7sM+lY;;qwIAY;3k2@hL8!@=v&bdi7A~qtjw0;u(l_G2{oI zL=5zy{3XW}zf%QJe-obZOb$?bey&L2o66rUq^S&ret-`kmSkiNJ?TG~Zs_K-!rU1x zV|;nGwc{LQ;hP2wdLvgJ?ceNs>HVDMwrT>upjoX>khfQQ9*QSyNE6FuUxxt&RJCJgx21$D{D+&%F_wy=FK zN32l7S3XY3VD;`M=A*s2D>F{!w=1_dN+gUl#ZCk`d~P^%WWQOQ@O1eA zLO;uv(zCDkM?!w_UY#zJt^-$Xw_fVhmQHF?NTTOC`WTLX8*j1Q_TkK&Vw_1V4^05d z*wYVzM4kR+?58{FTvP>0&qJh$CTH}&%}MDO0kNZPNcK&W)r;U|epjhlz>Tbepo6tEVPV-{^x4pq}(GeR)CF#9Awu?UmxrmRB)NM$;Ml7s)ZCF ze15UhEhhj6Q(m1CgXbbG77k~zB!U6~`x-uV_QiV~v~RoY`y%Yx8f7vxp?c9@b0k(^ z)~EeYvU+5|V8Mkq7WL>A*I41bef)@l5~ey8f3O=7__h$qzaJ+{ggOn2#_wJKvr}zrJ&v|ZrIGR9KlvMQwKo=|l!BSOg7B$c7}xRP_^A3kyjSC^3DGr2?{3 zSd%C!m{XoDM+i#;-jFilZA&wfVEWnV0UDywN|<8j=+`(Mz`7`<7-jQl0rNLoyo1%` z*iWhvS-rKVUQR@e_wjiW=PTADLOM4kC)#-_ zPxc0PCyhxJwIY?JXO(r!H$anuM2<>zJ*+k66G)EecO^-zb4;(KbiLxI=iS0~dw<^z zrUaW!W&XA17 zgcqZ^{X&FE1n~}Zx_6jUae)^Bkz|&{xt@x%)lb({D>; z_X~WP%0f!>IXx&n#F~fsXn-I!6c^cNA`&#?v+S99GkMCB%5_F*c?Gy#AyXDUJsX?! zNjCPPFI0*YU2sA*s%Z-G-E@rKCv`G_GnJBh?NDY?k-36ODT7&eE~Z9VsjE79xi=_( zVj`VSM)$HZw}WzjnAIrLeW->S(P-DUxH(n%WQk1ni;TfmV$3jvRU<|vZ@oW}u8=L+ z#Xj2C6*MLk)+yoI`R1_@_eZOSw(P43Tg67;qzuJ}wj2))WGL#9xK4%{Xgyjp2H>>= zWz$0LeKcaR$&aMUa!L>aqDBJ{^#uaX&XzoKvK0(^0&#Y!1w9PlH3Ce(P}~0Uk$F=u z3b`J(*Juf}_>OENq15IJhek;X8b*^$i-dcWAReTSOHfEY;ONhIL7mk7%!f*yS;ugs zQ+)pvhkT2D^qSF`FXLy^PD4#Abn1NHuH-S?D%xt4SQ>g#g~1U0ZRf6h58BUF8$XK5 z5<_*18Z&HU0A4>ZWuu$xjceZY;8lG=q7uZQ_%LZwrVwbj*;Qzb6HAu~*JVu{9u zwgFk^5Wp19GofZqKcX_HNPS@RB{&jic|Ri^Ed_j~Uh^stP0#SzhrA?gaFyx6wfmet zW_2ErN@xr+N>gn=u2iHZG&oWaB-g|kf(Pe;%p%E{td&s7C&7#HW`{W6|3_>A0GOqy zBbh($m!9P~x>b27D<{+Kwr}Z$hBwzr)W_QBE>{mj5lIuDhWH0FuXc2#nSnY1lh~3Q zPkNE;d(Zc)8%s|OSxr#SfMXR6wu^ZKrGiur_>U&xC{-gID|QM!R7Aedqi^l^OF@hO z57}r+(IzwQ@Ni2R8qsXB37hRsT?bZ7L@gd%tY=$ZZ$Ot?kxCqi1^8#%fDuWLS`9oS zmk~l+`Q&gKy=>ZjJTI(0+(<8|1a8%pSX^XgttwHnKYI*T=(t&?(QKTZ>bhpKW`vWU zf*T}oH)=pP^mi&20@n$%(2*E(8rBVXm|Rw zNrds!Y^RdcWb3P3P zA^n1BXf`JiPKI}GKFDJoseG(V-ar>G*eA}h0^a^N$6!LPLCC$b++o-c%cI65vVm!A z``H8ai0OIlD^QWD_Mvxix1;`SNQEGr^Y7ZOsqgWt8|^NbM2Wtek6E3}iM#zYv8-7E zOc=?M@TZZS1^F3|(}%WV8Vui(TnbLTtP_JBIbeChQffS0*8xoKS2$<|&LZ#ho->72 z$|{sz`owFIgx(YOOl?;5VysH-eZ~IMZV8Cf1qtrYO)Iw3pTm* z2PWox>BfW`jTL&TA!}mmCYO3$Ezmid)hLTe8n*9VX4C&f4!B}R{}VaTdGmYCh86o3 zLe?TmZqwR`ygg?%*YA=cDr;+&GOv#zWPk~+3bQKd__vAcnH&qT(`A1`3CYK zD>SXNM-q|w`eEV92x&kG_ea^k@7+%-g$chUi5yxZI**b9_^8;tm8cO)y1&jL0tX#3UWnCI1@g(7Bk*|AT`v@mhqF)Z-!{ zY)VUXCmg6H8GlKqh5X4 zRRgj*FI`*WT;=IJxaqtc3Pj`Xo!%r1Oo*x-)#6mitjDY?i%$`d`BBJ3RY$|d5gCc~ zUCPtdX7Z(AMA0JMj0T&?436c6nW_#rDbki&Nzk^?Hj#(M4JRnWIc!RxgvtF(^Qm1U zpKOk6l`C>rQrPhTU2TWTas1Nu6h>rF6YoQ+%oO&hcT+fWk)+Eqx=VgnId&0+8aj69 zo9zWr$zMpmm3=pc(64mvjlm;gM)I?r-*-i{^)wwOgqL4o=2NC)(tkwk2WsbwC8xhv+HalP9O2O9L3siQhI6X#`#mHrAw!W z2{u4yv*MUJKg5(s_E2uoL{$kH#641md|xpa>G;srQ)bdSkwJ8|&BL;x9$*+~Rp=rkcnsFGxf{SfUz5xB;!FlnSV?E-snyrwK71w5+&*}o@=^`ZyyPKd z>uYgu>$H{T^`C4xKgyI-SjsxCIJa)zd+aU&VgU_gQ^d?hn^`;khDqJ%(q5X2guA53 z&poWFG%*U>M0Di=DR)4`Ed)w04ta+l1Y#FSvnGRS!)2UT%~&0@wVx(5k`3sQgq?90 zU%g0Hli`zo62G1HD9r{&Dz$m>wwzu(QJ1k)k_SYLL8l} zYi#Bhq)PqblAPEBD=Z~zj4!^(pzg#j$4R}3uD#6jpWCj5*4(OPhZYFYk-~r+m~0he zo3!V#4^6Zdlw{Bq@}m&`D1h%Age**dY0>)?)a<^KqM&s zpqwjft(J&iu5X0|u`_Tinvt+K!DnTShCQEcMMpHKDI|dyY@jO|a~m-Co*Yw}5E7ks zLASoirTEMQ8fG zMrEgh#RlwiCTrY`(2Yr&KI3M}O&+aQV`o>SPJqoO`3gX5GgmJ%HWR7hHs6dJAcZb! zTc{|`TMQ?1Uq?kum$cs2H)C5b$35*Xy_upX$sO$^@THCZFrB!>4UgQEXSjVYBmZgh zJyJL8EpqovsqX4Y-@k##V3THeH~AjxxY_af|Fi%|R3?E`La?g%_V+#WuwR)WLFu(C zc00zZr4ynv)+tBRk;?q2R-ptQ?|DY&OPbcnw?jt%k%aoiRRdI`sD_Kq`duFV9H8ZH zU*iC_L}3~M`3Uo5y+TP$ zm`!jXVwvra)kd2dY?lExCOPn=!Y#}r95*ECD%2r~=8u$!p(bp{FA)i$YPQ0iGK4{2*-YMp*gmrtL!@%(f; zwcwR*RTrRdw^F4xQ(S0$QzEh2KZ zeFsd;=})}zkl8nQ)s*ysV32wbqJf_NWIvusuk4F`#U$e5*2&Uid&3^aOx{;jjCq9b_mbQ3PzG}1GcBR+Z z!i@G?QC*J~QOH&rTTz~%1SPeq{E~S^FDPxewTSwh?wgnk*K>axzBWF=xH-cR%wRU15Xe2ut4IB3N5t2)~Sk2gZAGEazZWR6m%w}5QB!_n&90Yk^W=VSD z;{Lit`9803O*Z);VB2r2zjc$L+DO|=HiWC{FElz35IQBKMqI83&8R%kcBDPH`Za+; zo?f0}{^jM_FutVqwrKp`&snmh^TRkPB4zT;Y?^d7CTdw!4+~3Z>ue=SL>+4}g?%&7 zzDXr1_of@X7N^TN1*Jp*@TQN`$`6j`A85&UtrPh_<^9T@B_(jbG(!t~>UzAW$ zNcZQ&YVSYH;!QnPfwgw)!bGCGd}?W3Dk`BPu3qG_;*9J+qEPo6NY&GK*Kd@Ry5L5j<+raw!OA+w+p12lrzHJmEh@OhMp%waf`?uEV z@{sUBxf*gGXrJ(PqgPv_&dxor_~DD>w;rBt-wKYJDaE?nyk-rZAB!Ot9A4Toe;tI6 z(*3_w}&S3pS6DXz3z1f79@Ri zz3?pqlSdOL3BWvyMquN0rb#geh|KAGQeb>;@hMUV{NVQajZ}D zv8^fkXS*+BudWl3WdTIv-l%bSNUl4C2 z-jgtpE&hA$DeDn?)s8e@u5!`b3NbsfwA+4a&<1_T#M;Co-wgr#+Pj!H0>USeNeRbW(Hy>fIM{lM{O9w%23y3krkpS znnTlNmly}GJ~L(Iq&tkv+)H{nNyEN@o`@;oE*f+PJM-8AE#FC#mOQtZ51Xefs*OV>X7TBl$i zLjO_c*i5*D^74`y5zRaddsBo3ndodv?ln#T$u9(SOy6{)xI(7$O&dNYs_GY(>KU@q zH*)qqYM{fTE2+H$Z<;JEThHIyWA}ssW!YsU-fkzL7@~7+%Tc3k0*bqA2X%4#YtuCt zna~UT_t{_cT~IE36b*M`3wOz`x`WD*IUOaXhz^Q5^{{On9!mapIsvXk9_b+L_>3NT zNClDjWY57lp)F!#Q~Sr|3VG^>*3%lwX)i#bVnkFd3`ojAO7N>Cnfdphy>yGRo*{77 zMfZ`FG77J~#On$ykL9oL;JesaUyrPs=fl7)Ow;tHe*so*fjIXh7tY`q_4()0PfZU8 zYx<|-qKgRvz)Vrk=xx)he$NhH3~Of;lgb~oxNjEbKcDI{OfA6x`rJBDpZ_Jxb+ro5+65}w)jAL&$=2))LpA)VH`D8a_`}< z+l^9A%=qXVqLFkP{Z7j&llZb930RSOVBxf28>z7=+ z+d%lGtm`e4+Ul|^3qGyGy_Lq2%+IMgNPNtukWO#+nBwnhn1!)_&J{UkntBa#0HMTDq6^65s#`p5XS!aedVCDPVv&(I2i zm*5W)xDt#YmL!n9xFB1-G4tIo)JfX-9C)V5v?rxUGsGHPMxac1ySaa|h9gk~=$nV| z4Di4wMYE+Gesfy)kJx(NV^~Wti`Jx-MsgIZm5u{$P}=QCb^?slMKgtj#Xo2&6nr{4 zceT~}MIYuZ?hS>-Sv}*Is(91G;N?A|qv1EDT<5@mY_wV5{61D2 zv4}Anvz02yd+y~+-pK>!G8-pME-qoE>(dFzz`ICp!n=EZn%tuwRaJw|52xbd@%LyR z<#Gb&tpdZMt^b}_D1SFYP$jjpw@2gK~CS_@n%rdx17`m(k`^Da>&rSNJ5s{I5d)sL8u_0b`JlMq%`6)3$2p-J% z2{@%6Pz+NdcbPnp)hA_w6qKjehd9ReQh##_{|e;aETf;!Jpu^o)|pnuw|{IvC_+DD zIuIaY59qb;`GxohVEwGe)yS2=m&89Zx7pH9p^S7xbC9DOQ%O0&NlrjB5~ffTX9Yk8 zNhE;>ip=t$79^&{u{45rf+KOr!sXV;QTMsSt#0`GB-jR@~k_6L%K_V`erffM?w^hfo_@cV*P^m zOFoTaehi2Tx)yeg;n`w%A&4m&8LO-ZC4%MXX;jp&6@Ql<8IuavI><398avv&#kF5@ z%XSE+kY^nJ>wyE6Bf8m)LPJPdr}dIkzJTVx8#Rl1c~%*aE@AtVaT))@>J-*|rM0Le z-`<}7>r2X&yncn=XH~i@-O*L*okS;x1^ODMUsG(XK^ABWEOZmUP>6L?x?=>DKE{HG zG?kDh@dsIp)wHW#Uy;ib8p%Qj!sO)V8{_l@tWk9u(ssDOW%{L%sO~9+<3c(aAeW<$ z*GU&9r~D}6tNU5<<-_7-su#2Z^WRLkI$exqZ!U5bPi}`!pqD`(M9hYfo=XoRuILGE z4!#G;XIhSDB0o^B5nrzCa!ZI%-{u;)&qkzs%DLnpf#2X)j*F6bVwFv)51~ZvRpM*s zsncN=R&2-ot%yCp5H@;vnVF*iY@iHrW#p)O{)3kRuV7-3Ym~6j>&*QJe%OQQ zWW&QNZisiZfYy~q1(5?dn*bG;(R?z;a+;ZF@Mp!_Q?(w^$quY&Yce%Bj#U{H`eV=$ z4P#S(y2)CrmrHJ|s-BO>HU0?WMKM5aFmHEz^e5z?6PM%E+thA1fqW$A(v0@< zuO{>;C10d-VUMH&^T-e7+BiCp=yBgqy z`ieTInh5{e0`jnN?|&Ios(Y(1nGEAT(75Kh zgc2gHJdEzKH(-1dZ+e?l=b4FKIi7DT&RIS8%)LF|{}e`sV;m#!g?&1aXc^`BdGphU z3t(Si!r_L(&CfO8n&kWJ?Ka#^M4vpv^PLz;NqFhH9B~DE=YO#3fK&<0#U5)A*hpG& zOFD(e;pB~tG?i_JuXzp{@R<=3-~OZWyaOug`dRa@lupH=?QaL%^U*6mZDF-89#@vS7dzIC*E-*uMM^U) zcsHco=l#T>&2>~uI*sDVdW{pfg#nVYp3s-KGHB&&waLa~48dzhS;725e-JG#-`mkMtAzK1n3xCtyJJY2CKJ@B+CR?D-;3`0QBdh!ukzbmW4GwEkQB~!8?mPBN21Z9 zNXhVRZ$`}}9rA#?jHym@knp^he!@?{)FZ+jHAfju|L%4&h5R^i7>z$X-VjIYlP6e0 zIWKYP9`iB(NdHKd=Bti#p%5P)JGQs_xIzYeBfXk~0{TuZqSY2P^5)0x9nEYUv7I1t z7u!KA#?~10%oNqfdhT${bPU^BheqWKj*^2GdFz#8JR9=4yz47LWxvm?RGl`AN${Ao z&0!z=`O#*dikA2F4Y~*GpuKJ>gRjhBGsP01JqeAGXzKpdka6(b_64p z-E0Q>Ptt!As8|Y|iUHX*TMHSu>Dh_z#ZRYr3KzCaie~B1(jsfq(F}q{CGhMf9_&hv z{r{mCp5fId(UE};Oi`Ha;PYzCWtBvqSCYl}{i0>2a-|cmg}!c!Ec|1Mbl8sAj&qp- z3z@c z>S)eP=HK^)@=3SxswgE;Y`M4=2Z+C1rrIvvg_n~rlX9dO>g%G{0&ve|qB|=r$+@xH z#=1fQ0vnXCG)97KJUih*OBKjWiuu^#Hr(X6F32-ULzdWitH2YjVoB`fvwmg0ZxyHgyX%yFF8#52yc1=a|0We)1gzXFkqVRztdCBu8r&IV>%dv!*dH&WZ?+UBIwI(+K{uXGcCm` z%e54KQ#mVRfT>@MaKykw=EN%cQA%#RK4CU&lbhUYmRGJ=3Ya;@5MXQNnz}x1h_rJx zOU8V#PH5INnmOV#Y<=`NQ5V{rY;x^dlcZ*JvV#J-vvs~WT`n*~we}-&Q2++qRf238 zRo-Q|Wvy{3-XsG|?dcw8S_=yu>U_4P%Yfi3oSeCwWgJSHm`$cjK^G;5dQ5!+vvGc6 z#oxO}cTgSiie-LVzngh8u1sDh;c9qUw|H%+keTMCDH0*TEf~gazYxSi&a_YImKw1p zCm3SZCR-lNo;1q3Zc@BTtIjtiMk-1O8--lduR{|$D1g=~r8C9o$|8j{;0?myS9GNc zz~~g=D*aeQ{T$tL56$|u86C+T@gJIe+~+MGlBfJfZ}@V~fn~}JHcFLujB%GC13K`5 zxls;H1HZ5mwK8d`+|8eQI_boB7Pvu*)`(D7nm@Ntw5JE#o{(os2P4P>;UQ7(;WR^j zRv-!bNzV`>65cGl*}E) zS4>J5e|;x!%ZLdU|6kD6dAHQO{;dUKvLfDX1N(j47N@@jHek z!w1tDq|Hjp%!?`r4>}1Ja6^qe?xrGjEh#QC!TSmeS^_K`p@TM!1oGSaFgI=L{N5u9 z)3w%0jZE01BQYN(Mj$&l`Yp#8Mxf2hZ0i*kU;V>mN^n0MD5b^b6sicVBUtwuVqO<1 z@N!lp@ulPbUohZF;DLsi`Uj(t0#-PXT||l+|rRBM-owfEge zI}LZCt&*sU+4e(uM#pJUETs11RnxSPY1@G2#DLtTn(pS@GSl~sM)-7tsu3fm}= zjLc4HlDAa5VWdlXlKkTMuTcv`119I~FjsU-m+739lJ9U{XD$4Vb&?&&Nt5H6EnaYD zS{B4p*8nm)<+Ei}s_9rODI$Ft6*^DXS^`p}Km$h@-Az>^2M0LR!!D70SQ@@#+bVfQ zA!4j%fJ@W|4=sDfHrtb#UZo^R?pYU3&#Nmyn}0*fZChsFipBoTnmAft-gJex($v#> z7KFNFfxil>?sSUw6pqtG)y+~vYY=NN4;83Y-z-XPI$K3x}p=L+oymOpyUs3@~sA?4W7oHPOmJjP7x7J?eM^fQ9$e?xN@^R zRZJ1lD+Rr)Dl7E?^?<;-|9UlWDG}3S$*li4!T@Og!8!}#Eb2GjG9O2MrsAiSwLWcI z3qQ}T*Hw2EzqqV>{SUB7vpv%xNN?_GU~B>htWcGQ=-J5FETB1>dGoBsW2uO_&bys>5Ye}vqAm*bNj~; z0+BYJ7U|qyTOw~c5c10+A``SVg!640C{e?n3#;J0J~WSvFm2&RriUV{!L6|_26W`m z^Uh^Scl=_LX{#Nq^LoSCqtCL1BF|yhv)e0;LtWD1)8$CN4Pgdmax_WY`V(BBxvfND~t-DLL>Hhw?zmdxbaEG#c>oMIwH zQ>F#8n+gWNV6oKjo;~r=wFdk(L8B$@-U5TkJ|MQe@(^23+u>!QK&y% zA`vEVjB7W_^re?#&0$b%rCXQG>e)SV0;8xX6d?Rg`y0K@w2l~JbTEo2^%2Q4gyJ}M zRcBI_wwv%x;WECuN!F@a6wQp!{J1bRk^Jk~2KvpmgR&*>e%f4?f4o-$-Viyw<&}jQA{G%^1csgG5F&g5#3Hob$QxB-QT5cdGWAQlhlH+;Q z1#^?%(VaQEewB=(IoJR1b`W|_8u*LdjS7pAvR_Qh`tdFJMMFK02f0_Xs^$J=5%)H7 zNO&8`xf4OK-fe!35q8eB$?1ta6coZT<%|!$a&{KOo7v}=(m;rPMZV4nUl9Gb9j+E> zES;OQs=1Azn%eK;p{V1A?Cj(vs6Vvr_PTiaxOUZ`#ekOo6gNt4JR5}2_&573ic_2D z4OWKD5C#?fe*_!vKl!r(PU|#ty}A3}@$iGlN;Vm>B}zRcUtNAy3Ow;hgrA0SXD1^p z)3|#!x`BfJI-JWQ0oP6LU;RIngRXrBrTU02vjHaF2$6DOrqDNVl(D#IYPl28nT`;3 zO!W1&&Bg^^8(B%u{2O=D!j$o=gr6&UKj1}aM|OEcd8|5yxj=&@Vj;;8bj)-MPU{8D zT?FFlil*LgIIxy%S#~|3;Ge7%YF-=u=@xn0;Z17^*#8)E^+`lTZO+`cnkW?qzOmIh zj(muS<5n{oIsep*%0GaCd!+nZQ%Nesg{Su@Lw~_M^~(c~*4J!rjr`ML zF;W=|cls{|<_I(>G+-N=G4VfL>ni)t!RZUehs)-i4^nvbO<|W$qG*`@ZCNDsn$-N_ z`P!CL{+|*@k7B8*6VCS+tH+}R>)v*DCOv2Y7-^kW>@f8iA&y8IjG@oFcH1NX-oss? zu|WS-u|hF@I`fHBadU!mneHL*HKud3cm(=(LwL+2XcUYt{@VZRY|*Ky*#{hToN4@g z#|y1NF@!Swp%Iidh81yx?LkEnA$rxN<~V7DUizlt!1`>huC~Jip{kjDvTw&g$ zdhW9u64wU5hqbk!ba-#MU31Z0@bix(Xw8DFH!O~TBtl(Z;j$EuJUl!%z3Q?Q8s{Zz zXMJU=#J5nV%eGfP2;YEf^!>9r?wD)YxRNaCQyNCzFVjfB5f#L?qpt{6N7}hX=(vyY z6s1DMNGbFUBOtlrZ{tiFbpdkRxfW^UiOe-$34*@3_k-;SFiwkq3j?R&9dO;*`b{3&Va~ik0fO#sUG{B4gI4_jn;qdQ~f@n#FTx|M@yA! zdDh-gcn&TJHb=!f&gJUC@@mSYDlg#8=9@FX{?)=x6<^h-D*9~4EXEpO4L7-;0jAR= zTUI4u8Be$$b*#^Zwqb)$P8lz7<8+D5wKMJ0mvb6Sx8&5y*B-XS+la_4Xe~-2z#O<- zwMiIVDS-G#AkSy7v59=<(w>Vn-*OkU4YC9d6f;!55-?8(A;NPd)X`q&A2NfaUEDJ__ibQQz34$-O~MZjsTU&HMb5Ty@s)>RvQ@dKjXitJtG!;G&~x z#Kt2cBIVrvVqsK^)pi#fZ@_nNe8Vjs%aAH>CLct0m|~C*q{` z-B=HZzVadax&RadIAok=G&Knbx4@wBfkyHilpOQ6IY!^yx9MKL}))^nY=5QZb2U@G(6#- zspXmCbc;1;DgV7sf_|f^=ozg0w0yPZ>qC6$3EqB?D6(CWN9$aZ^GkBluD;`Cjt&pV$3R~|bu;kdTS^ie57L3S{ z&CYmQqG$9gAI5!^@9H7<{c~vPHaRj81g$}}I~xMH6CL3>U)2n2TFz6+(`ANbe;)gc zRc2g5P%c;KB{1I2CPYOvLu8J~PfjF!az!&4i;}Hkh2EOAZW5i|&&nlsz~mXezTy7Z zdL5d$BUvH|bwT+6q}dx%x8;k*2zx?|l9>2}{j^+>x4TbXVA`4^byHFLWF9#6rN< zW{E#ajN&5M2E$*p$+V5dnQfOu$9mIBEDJ5)r8j8{#fz_X8I@a$p|Xhzi3$a>xJkKt z-8lV;_-UIK;L;JW8~d{)PA7@=*v1v&x9~Zb{MolR1ZI%muSdd?k5ud^=t@I*4!IM4 z^wqBv=jx5bk>bp03C_fAiq2td4PmsiBD*L{FvHl1v?oC0{)IfB5mzu!7zJNNDV69( zX1$>hqWsu2>$j4!_s}I^?SR7W@VUF{1EQOGPT173N-rxU(wW3bozrUX+I0B6R^S&e zTmx!0L8E;UGpp`GWQ%)I8K9dfv_7Z%PamAH!-(xxiTB4^drS+x92R!ihjdc_%gqw+ zRj3EDMT2OQ9QH+dw{TC0y9;H?KTvdY*kt*ei-0y>n~y7WUu~3s3klHOyZ z->Ql$TGf`9noW0SFgu>yA>~2dq0zJx?#pxRBM!DfuVQW2kF5W6zV{FdUVv-kxFPJK z?wVzi&3%XU@8>Nrq?UfXcQ`rsSDXU;>tGq0 zinYF?HU7XrhbV!~L@V)50lqx8Y&wv~^MZa`0y|n651XbDAu0jK2|uM6+HpY=^+a;; zTjw>UQw4Qd;LjhC0DA;Gwg)F4{E)w;D4G7!yNXeizqm?cbY5>2IsBPR7!^HAN?f6! z{^uSj&(<)C-ZaF~RGu%Yo(%_o>~0E~V!rh%84=SBe)KD#RDO;eVD7(D1J8tZ4VeE| zs|LU|npAZVW#Yne! zBKBCcm%kXi=s@7@Z*+`60o;FfMJb3xJR@??k^FFD+8|`up>^HDY>FjFA&Agq*&?u1 zzO6jm@zmc5M^Wh1tcR9OgsfsPrU9e=xv}|ZOtFq0Yuhx({9wNEDNXVs^bllEyo;$b znm;g)#q0egDRa}pY>q4f1d-#4?;8F~s?8)HW)CHor=$L?ir6HS4tu!A=(GJry$n8#3n3It!3oEG8`F(Ul#VkWeoe4 zpdqj}w%f>MpnzkMI0*-eOj)_60aB>;QQ7?@+*BaiasKPVaoC=EzeOj7$ zMrG=-GVQHRt94o?lgGI>p@u@A7>Q+LM?FwyMLmotOe*rpOJ`-QP&@D6mA+#w@Qxt_ z8-#oB=D8(#y$}>bYCIX`WtxsqH_b|J*vGK)3-Zq0Mb)nT&I1C@YO9^by(CC|X{J~O zSn_A=pnEgBNs?uJ@t+p9QJq%V1h{KI@(T3NGXhyg-X(yFXK#4n?iYn^dDRdrijqGZ zrf-HHhouiUSHEQzxaQ(sfC2cL*3|=g1A$?BkpE03KeMO)URfQp{WeUXd>i6ow)@%B z=`VjQb>Og&X?r=@H=cOQt#R6l+>5+9q)LvPGaxT0WEhG_}?NnRBkpa>2pL5>R_7e6* z2K!6y7Xy?=4C!Jp?)Ha78Oj*ZcQ2Sva$faUmcG*b@4d{uE)ccY4cZPuVj4u&Hb!ue zpo3M`WnHX<*x;p_`I24dI~1axC;5XP&LxybH$l?wC$(b;@W4Ntzj=w9x7Ka`evG$l z6NO_}7iOFF{A4YkT*BCGNByB;;3YP&yQ%#9b<0n}TDM+#>`P1;N5Q^O$`WW5Iw-#J+d2n`D{pt_WibQZ z?YkJL=Y=4*4}%FItnWmA%wS1YR4>81syGE@=dxh9A3)5o)n%cTJhXwhvcbq{jrG_! zZ|yg8BrgtC0t+W}y<0cb7Fy)Z(D`tp$Duuzg&L+qC5}F-;n(yqRpz1jQW1O>8p+;Z)_;-B`@2h6<}# zS>&C~XbdLBSz;a+9G%K?D^;-lxEmuq@1!tNx_X0 zdCX1d%%5bEu$=nBxwRs6wQ$JRif-HnMn=h2=3Cw<8Vq3O742Tm9X@KzmKFGA%f%uX zMXSxX^(SgzhQY>6c-L1VQnKJAcWSuZ28SP->N|plqKw0j(vVHq=~f&q9XLO{WR(2@ z*zr$t+fpy*EN4K6SDfq(K1v0}sR%~Z{1L0@I#xP){kt4Q80y?RK?SjxhVLnfH&i2R z*tWJ;i%qPvE!_xc+V(uP`>hQBwq}B%@<^Y_@`}OIc=7dsq30au2+X()B8o&Y z-{Q}hoDO_@D`)8bPR)c8aB>zvKa>I@B?mByejh-J+FM2%V7TULj%CCbf@Nm}%3uf} zQ?s#i;^P?dMI7_3Fkc3Ir`yPQJ{Kq>(oP2SkoJ?A8I`?0{ds!*n?y5)wcWj}j8O5#26F17S;Jx_>{pm>p)afcR(C#D5b zFCA!n`=1cm7G2h>!3!(ZF!aLlU3*yxg-mJ+^SusWquCJ zmlB3B$YcxpO4Ldm9MMQ5QLo}?D?0i;;>g#h_bwo87|qP?pl#H{-vI~OMUE0%(NYc) z^fJB3@1p34n5cqw{&cLdO#!_%( zBw{Z+vt`t}2m@rz6e)|^pYY-Q^+`r$kjtA=gvpI3nxRysPjROXLrnw>&Pq!|jgeNU ze2Sz)dCFMMZ5T*kc_sGJ$w7b90Z=hE@H2kHxec0WK_Djk9g3d?llEF%sL!G%*$7rdK{^ZTkE=fZ#o)u2FP{ke;)U(iRIcGc~VfU zky!r*LQzW~99r`hYGdeY;wAXSi1l=0N;=Q7e#wV~^xBEDwypICwK`@fz z52pf!5XSukh40l)r*%>Q zIr0T%;!dgn=eI`6>NK`CzPkm)eN|UCNiZb-uF^EvjTLcv!Lj7_oA-&(1fW3b)rhy~ z#MzHnGj#7$xHIYMhm+QTXAN0pt|$r2M~+DU%zFz}A`Y|;&<4$jHTA-6#*Utjvr#@pt5{mfdI+#h1h9(E;%qLEFL6VD4i(*i2uFk))o(Jk9n>+c zXVnI0$39{Pc9|npeZ{^&qo%PI=*0A8>3J1R?BwL_+uHLHWRoQ!755i1eFROrWd6NN z!9{IPw|`Xh%CpcD{BcuV)Sgi(r8k{hpd_i(E{#X|nP}&{r=}|}lw&D-O44ktzGlZt z>v~s%D?0+8j?xZXt(d+dUI6Z4c>~{dMPW$a{=>3&V1sa()&Lq>-?`EpMYH9yAf=Ho zV@tfADtq#&X(~0>^?WtcQ$m95smJ(-p!S7T1maOl7%|+sX#&eOaqFBk=l)IZkb4z~ zjx(JO1AjjMC8%`F^%@gD>y#0?TIgC$oUG;7un)I$Q;l$;OKBg`t{h2(Ha+Tfh4P2a z48S`Mxc=SF7j9>&#aDIykNBD4P`SG_Qbz$`KJV1?3YCH?eRE#?OGfz3TA%$2s1=_z z8m%c~AC3L zKx5J!by$I%eK@XJ!$m+Q>Z#k@hqp}%LbXX4I0&v|{P&;M;QSmQtl=vC$hA1F;-3hQ zH3=4LjnLnvdTU=o^Yz^)EhleI95v=&eBaR)3E#$947T4a1+xFn!lB=VyrIwg-T5(8 zb%U27wG4t;iTqS6t2ghg)F&Zt?=wy=92H<5NzW^e`$))JOC!*U`T}~Knqx03;(Ae= z&q(^|>-gyK*y~eK3$NOI3a?S&7-2c2OG;kX~$ee(BdmMVKFgg!`8p^c0h zidGnu6~5d#?ga>#zia3+*=ui@4LwNrnhjaq$GpI+7 za4>&WRWi$X!O#AUHwk1F`ZNXaQk`nW=3j3*T+l!Q!^>2{Qu{;4?j7?F!hiZ`y1?C+ zX1JB$OG@$Ni@Qh^`}Y^wmL@1B$vs6Ql|#>P%|Ax|U+wJ?PZe%QxD3arbx}0)`ZfM( z^?aUhP!by8iYk0mBktD^KX};prQq%sTzH_>TsjtpTXfzG2}ID=JAR$fUON8v^``^c znt{lVbDEQxvljNYa?R8J+a)DuvCnhVrSIS(jti!=z$bqmqu}Zu!_iCPn*%tOwX+*q zxX*T?)m3JrsaMk9uDUHWM$ZuC=&mF!`w=l_993+-yCPr+HDlvsp+65I0pB*sPs~;=-_B* zOT%k%+B}%H>E!CNh0_dafP~_dtm;yC95tS8Sbz zl?q^q(t`I)16933SL>o={dWIq!Hz6(2B%Cl$YmpOn-J43s-y87*T6YvcJUYdm!E>j=p5uUX(-R3 z7z1Apna=n|9#`9?-ot;h8wt`B)qXN}K~IaxD%}9I71Zu-1KC@8d{4X>I4?GnO8!N> z@Pn_FpTpaJMzn@Rqn`s~U{S3YsVukgpdNu^j%}U6f4Y}RZZ3egWT&3&NZ~ip()tF9 z_pa37W7p6V1P6LVfFo8$rQ9bH9gm;TQF|<0C3sv-?(>;T)3+Xxgf7Q{+rck}N=S@y z`O|1BbV2v6S{WKIT6ueS@r!6f%H-M`N60&p=s~K?*WM*}4G| zK{2!k&I03$pbIC?UM}l{0U(G0_GyxmFjbtK2z`Le)zm;?)^g*x!<462umOW z;<~}F{#?pwrEbj&zsNS5eBAV0Al+rv052a6+P6-|`?quLmXE)3Z)#|Tovf?k)T&ad zfZ7=y_`H+hU4)VKY6=;$Z}n^mmV}|*C_YWniR8Hi2UBiHC~bJmd=0v9T6CD`(U`tZ zMdA(DM2rm$MS-C>wdavGwQNjIxC|Fr6LNbsJbOJjd#Q-2lN-pZQ&bUEJ!i z0x{9#PkxqYJAiXz!EEeY+>tt#xz|%m$lz9=dXo7t;-o!60W*d8-+g{@?_s%rgiRMB zjZBN&i~eloTy~ms1mtuIaN0-f8GfA$3^A~#_h^e-a-sMuRuC@`&*3Ct)}uNic1aU= zmvbp4M`Wx7H)s@DKHFlP6(o5kb(BJ64ozgDC_=mc4Tx3aPAF2_qv8)n_B+=l`Z<=w zq&2_=WX|)vV)kb#!So7%$j;41yBe;Is^lQOs*SaVyAn^BIIC0qE!yc!dm!y&`?f}8 z!`|72PA(*7>uaiUVlXYXZbXWoQrulS#pnI1jLJzcVVoYAct=PN1!Vq%u7LcdlAIe$ zD%*y}1OwTQ9ujb2nc1&H@qo2Wu+0~AC4yPptv6W6lmKK)F_b$z?c-wanE6|1`JKB5 z5h5-^a_hIV!aR#k)D#id%>`(g1vq50%g_Q87{Wt8uGlfftiJDFrq9O_u{werWvd`W zf70QU8}*22Aj;+SdPtNlo+zfBJC`@@&jZqV9E^>YtS6U5K<5*#a-)ftI&@# z*Lc8fwW}XYjnOE0qxk~3_V7O-HgJ$f-w|%34xt50?YRf4>-mfn(i~F6o)#Y@V~$15 zEQi>XJzVY+FvIsEeHbpkx6Z%0_zAZWu@jKgr(@Yw3+V3rlaVkv3d&4NR;wuo{d4zR z$8kBBeoa;prrRtqdt@Sqi$vq_({#t}?9G#zT#=;cW!KJsOnx6n$1l$^{#$9~M!%Zs z7SsPo=?OG>`$tUR`_zFUw3nM9HcGm9V{tOBfw21k%Y+hKDp#N z?eBcY$@zemNm}O=9!ZE~^EsM89q~z-kT1T?3-Ixe8;PW3{(J^e&7^t!N_?CwvX~NB z_#vvc6=E!+L{0>&z24A}sm^q_KLPw0i!;W%0gevaqOh%eNF#X8-)~3+-v5`kva`j8oV#E~Xa0&xViIvq-G> zHU9OBoNR*ekKbb3=S=T-d0;K*e5mAz=DTbO&FP%zsDk5@Y$I=2$|PvR*seN@tOdpYWrij6!=~>~aB=^%3f!JX7ce_?>#;UrZ+ zcoLZ`f9$B$+TC01p91h(#y6ow5w3VLXkE)H5S2h1kUVLjbvZcFY`GY;o%Kcyk0r4J z@ObCX2FIU0r-xq2^&I$J$L-|XJmE`t@(F2hiX3sT#!BtGEN{ins{J^XxR3`#aG!s7Wyz_X3-w)ldEulT>m5g{- zjh`ZGnj$Vxd<|^xsLV6LMl5~r_=eE~`=XX@Xyj_yb&AS2m*Nf?E=-@+3`u^IUo<~{ z=UGBQmXgrM3eAlTWcqgd`=Vc?sE7~&nuVdXXQB}le8a!SckBP}33+xn`^orzNCZ`2 z2wQooMZv~IVnVh%FV5Y3QQ~6!&uvv6gK$g%xlI07PV&&Q?!TcKRS(_)i<~o z&#!-KzctwC^sV`|={@5=ef`{PadR>I`Ow*cL-=BF{W2EnZ+pGwlIuQ5;RUmxf2+-Vz9aSOPw5C*Oi)Y)=A5`iiYl^wa%!8Blm;^yMDsU zrps=+^WTMkuwHR_m9BF23-385w!YOoI0B!#3>>Atm-8{aKz2&PkN8AJC4=Hh=xXol z<-}>LBwJE%t;dkqi&m&}O@GbAKM7`9LTJUm+DIbZ<$pH0Mw*Xkjb?}5@Y|IK46R$KywEW+k8~R4AZ*U zd=tBxeomF8S5RbbJV5{u^rX8DMIZAnCZ+jmRcUTSEbRu(!*@sHVcE-mP8bjtI4fvy zh93JlX2dyjLTQ%?Wh#@l@ovp5X&Vi!-PN(TTo8OH#T}SeAE}>v!FXf$*E_NyHas$M z4)Q}C;EDh70(>~pRp%c=+)jR4T2Vgilw_^(eSP!95+dN!O(qRNz7|rw4|;dr)0zHJ88!5)f8xuWXbzIm-7jg2ktdJUP^>)%&xMg z)ns8|evELy8qD*6(0ZYiCD2*s@Ad%&O&^K3`ALAn2!|*l2RT+25DAJ#k*A1NhsHu; z;}Fs1rK}VR3A}JjQo?Q7ha3Xd3B$eHvOP^SDqN9!J?puCFA};QqwMmO0f_VI^jvyY z&bR53kd62kFLVpV^N6lpzy%}&Z}mQMVs9l0OuNOk2~@l3=7B>Z|9r{jX2i_{p2^Rd zgua7h62#BfgoI?% zIoAbdVW*^y+Nxarc(>E$7F+m)^H%r-+LJOFMr~^x&n@I8<3J5#uqYc*bw(K+z5fYaG86D|#1STz_#B%st^ijXsL13LgZ+OOI zF*}`a>2{*r2{u-fyBj?MX8?vx2`h$@qo!w(6IoAG#@$|>Rmz7?tPzYy1@qMj{iqSs7!Av)j5 zZcO{xS7;le_@h>2GST)Msz#IKa2vHMqC=R-R`P znmM{7Uq>WK4;OCqmp{$n90mu^FL6~n9%vg>y3%+HwCyO^kxwx5FfkQrAfej=VuK;< z1zq-FI{V-g0@f)Tt4~w*ey>f7lA<1x5#SjL)y3-hH<_ zsr2fJUZvR@TJGnd*N-PAF2%Q(5B04k={`PJ@@UdLpt2~Gh6K!)(;;$;^vmH0P$S}S zcHr>m=RTBo$VKW{&(IF*5WQNQPdP6|;rx}ZhM$Lw%#inZ8h%1|DtcS_|(jZNoxEEwUxvkzJ0ii6^e}69(MX){RZk*EMVzM zcYKe+Fu7g_w>P)Eo}-&lh-g@8?PvVjJmIBm;X=>PgzzKf69wgloCgm(v+h1=a}0Vj zR(T@zf4>h&Lc%(?d8G;tw20o%yv+*tO6<0yv)1MmgKA*R?I4XZq>N0ecnZR5cjHvD z-~Mii4=#)oroD4UTra@4Oz_vn3|W`syPSB;1uUHBIVUGmq(cXzFbB^CDPbK$_QdJ@ zzhI{8a`aL1dnAWf2aZX6W8Fw!INTBUQrYChlGY+}GKTA0?q%Y6sSm5g_+6AK5yg2L zCEoAeH-=v;B5{oDA(xw%BB|(zjSzyZnu;dD07SCg1sg*O8g4n9!J#Vu3Y0Vy75iU< ze>~Zdhgm+eN1I3tU;07GxY%@??>5!%KyvV}BfuwjZlA=Bk+_VtaLW~|>B+4)!?JUg zNK?dQ=i|W|kXC2=P3x>9w(RdqT9~1N; zatXm43NA)-T$_+@+RitNGAwISehdAUeeT(r72bBj%R49&@rpOPc zOL(=Sf>NtBm+fnc{CUO$d@p=NUVA&D|>%O*uuehiq zLJjSJZtQz8IWC*_xUO$D&(PKU_S)^bf;8B2EIP~Z+7BcjU5=bdcFhnDOj}03wODrv z0n*)Z5aL?71;;l-Ly0j}E)VitdHVcv{H{rYJycA37PsPK+$=PVAN07Kr;TGFakPiVBQMn=$3+H_nc$-@^*Q`z90HUC?XlfbMtVX z=e($)WvSIkHWj5=C%udf1Ij( zGwM=~d~sb+U#MYUdxf4&PyNc_zYQ&*n^-_xT|4763#viI&7~=5_I_`&ptXd&DX^Fv z*S)@6$G!mx->M$WEsj}d+YPiDr2KCy4oS|=>|HOv;FWuDru&4=s|CxR87rg>ilptxISmX+bC@8CGFtK}~?^sIA z<8FC0^T{3VA2vbWaJ!*y!0v=SEPp8=q$A#O$Gf`|K1zu>f*1zZ?vhNQ4I65P+{ z=O;9xtekR>g7&(a%-8|;2NrWc#RE9@(J znKQKt--^6Kvc_Mja%L^Ai2AOzSdJzzrAD>FRDU1PqHRX$aLv%%tH}us@gbg4F@PKFm zZ8~Jza!fZHO*5F?u<1oFNe59*j7gEE@2+bPkFkrOQU!}$^6O!f(b0a+&>(yJy4H|# zX2d0%rN9N0x}q9k?@0TRB3{wi8?%$tVs2y}9la-vao zg=>&gvpp+b9cjqz8s7SHMSdlalU?Dn4BAWvf&sUmjRnxA0D}VH5g9-#Kut%<!` zdb)$XODp`e46pfJ9q}MJk^DD5+|;rfl?U*fhNx7PKXPFYxPVCo*3=O#2*?}=HGW$7 zq1mu(qoV4h6_cl6u_&QNR8A733^B5P5L4P8y5a$ZCT0T+_~2-67zYc2RbN89n)py4 zsEX!`mA>9KK6Rl^w#&p3*yW=-m7-|1r-nghza9r*P_MlxpWt9h$^FVCOST(ZDNZ3} z#O?f-uhB4@5g!AEj^Vz96CV?3%z`Z&3-@alNgU#UHHt4z4iFWmj2*f({F#K@-o>`+ z>kj`bF*c=i9E_)s*ZHu$X|Hr5V&2}vi^PWTiEeM*<3#a9-QqmTe76y8gWY~p>MvW{ zLTV%r)_xx7E11;Zh`NQd|C@LoVhz=hYip|vG=A$|KO14#`^3E<5h8+W?|TX8X5Pv*U? z7BgZpqH2Ncy`E5Hvoj-rKTJe}X_A`}kUTzH#}Yl9m<`|vb@^y0G*4;s2A!N^5$eoj zYWcYg4^9QfX3GEEu8&j9EFu1Wr&iGlBgXr=)sI!~8(+-PYfXAj>f?bs^$bd4)m zF0+>4Zxi{m!TFCvf%cVNowYdYo^}63=Aey)AQ== z;bC+OvdsQqW)%EiHnFOhWyvXMvq;-RFsVq^Za}|5PJqOyA4ip12ob1eDNITrtMZeX zAXZ(_$pt|EN{rp1*B)N?%47U#F9>$R$j>)h)?UN{rIC%1td*1y#+k$p_PmFnKN~_M zaP6(@s2CGql_%o!dX~4Q*~i)Q#Iuw4#oy>ZjL0uo5T`xKk*dvc=F6B~tu8FmwIWOw zBI=f(OW)p9cCTWFB@w^P8WpnQk3v}_@|*2kro=A$d5k)X`C^$(5V{EgI@R%Dv;+v` zNzc7UNqJmYMGr&8_udQ{iF$a4+53$mp~+DFO}0Suiy(9D=lWqkBP6={{cnCXSSe}A z!4G_939|>uq=<+%)YyKK$MNnR2(1_eLj4>yC`g%@ zD%vgh$XtYVc8V5AAS_hBDpdSY0HT87MX?2tU|muN*k({;cL82R2aPZP2ocBndF{FA zucTa+{88ZNuSKCanrTg4^ZMgy$EEXMt%S5FAq1kwpL2mP%#q6vf6lbM4;i$51g#wy;eZ@4t(SWSkKIqyr$VN?sI()^S&*wMj-cO7O z(mW@ldBAs&gsalPFyr*-ZjjAsP=T~%8X~ptw)=d!06LcVxQi@4?dj4tBxtBRc zaJ1|G4=`by%v$1fLPso1bKw4(X`{sms_}3!>a63;Wh70c6A(pSHIy8D+!tfHP&!$wHx)->1-9&OqMvJ6Nuj;`?$iGi^|TS$i-{qSeh73ID-cUN!@ zz%9xBoLpoSAqgl+^nipcHoD?O`lV*Gc&XI6MU6aulrQ5 z#rto$%wa!wkfV36fT1ba?B#Vug*98_lo?aj3~ODceG#z6BKiP|#*-^~NBG*9=9D`m zO3dYyWVn0-wmS8&`CkLf`oICXD9iDiG&#~Qz>AO0bM?H?7|=xeM;JQ#QCQ`4vxpY; z3<&+=x#4q^czeAXaQ;y2v?aZ&z?qc(UD?t0?T4?l^UxY%s1q>CxvBLEM_PIs%(PG2 zYSltuRltg+|3(PW@`da$abDrOH5(y_f8i6#Co7@2`GP~hsDOJh8e@-yw*=h60nADy z6S>MrG|G)mD&@la)>OINin3Dj6%m`%kH#9)%i4)9bF~j+qm;^5pF&MU(ATJ4wfe&3 z4|r0_gap^Dj$xRYzNRlU8S8h2z%4EgEYH)yBzTmjl}TrVZPpne<4jLx2OpfqVSOT- z_Q})Ul(RO|fV;`RkO-`P0y#5RvI}rbpYtc1g$b#k(4w2<)+!*(NFG7{JOe~&b$o&U zDqe6*Hv1V4^d;lB-_|x(A9ZqL%l1fIzasbW9IR<>f7;GFzMU#tI{nFURU=elu(#L` z>NhWC5A|-_d-)$Ay@73F4XMr1U*9_Uu|@spyn{DwXqtuY$76p=%DkD^%^&4Ru$<*C zbFxcpw7AtHU+)dKo0Q|jH?wz~v$W~WJpDJr*|GNFJsHIp0PTi6J0doGIeMs&-2Mtffk0XEm2)1>8Yz4oKbyQ^iQ zwA&2P2!k>wH zjWK^5F`}8vO8!nnUz0L7QoedzU5buL)6BP<_md;bPYOzUBS}poK0P1#8{dmTdBy^PqL>|+=@0~agSH;N?as-O*Ty$o2 zlbE**zxlzTB?dz)2;necoQ*A)5GZb#aPWt@@hk0;*+w@w2}zsSbD8WM6t*btkcS%>B-WF11$ICQxB)!{mBzEwoxdK zg^Y33k+6NjT_jNed(7U?kdhT;djN{z9x|Bb0 zY{vyO?oxbj$BND@-S%Mnv{ESo`_&Q>6QX(X8UURx_~>jdwSF#R?#1;pBQ75VkmI$r zg%%SrjO#H6=>z1SB;UzAkxJBszmspS{~z#s5v?567mlw+BXZwlks~6#ZP;QcYSd@i z#|Cv}+VT=kxuX1J&*I#n$*WHNgz|cKD0KVhhs&&--uauJDeya{mk!s&V86O`PyT?r z;Le{^p;irR;822~3fI*iTmuCg-FzEjPdEV}%x^dC~Ck}w$*gURR z7G9w!!IV^YIVVMp*E_~!7deXn7M0MQmV=&*&pHY5oE$jHrx=|x ztQENwbY>4#`tfghA%*uR6lu;+oj&$3}66Am4UIboJuQu!c?^F;#>KcK~nL4xxeJ?S0Xia3w^ zYy*0~{QNFit=#cz*d`)_@bQ;wScd#KlPf+92eQyFU@OTzE6^KP4iCwTD~lRu%5xy% zRW$jOPl84k*f{As19g}Q&?bAmPHb4d51E{i)y8uuNvbS3G$PTZ9%pfEYGF}6^uulSY zECA|OA_&U1zH=g&~M*F1*8F0YvjB&Qt(BzA4It=zvHSa!o4U zfa-|T4_y2Q*^%s3s@n7;2ZaIziUlR(3HeN<^Vs6J9)L~ju%sF{>HbhpxK`Uf?x~gT{sxvO$sp z!cO43ncTCLlC!e+MzEHL&n~iES1kd*hvx~@33~&|Hak_Ux)fIqDmRnQ zD2d(Tvj$oA%M|<76kG&T#H^wVCGAYMffm11VE|&uPIShVO-!z@uRAr|B_Ep=F1!^+2Oh z`FG%C?qW$6VWd=BB+%gCqZyi0)vvhz_cNc%D4(m*Fg|S3+N#u|d6ifM7}+G{lNahs zkxn~(GBZZq`+DIbK1QcK!Nik26|gpyiO;k(X3VGQG63+LH~BcngI&;1H65#9^;IlB z3$Zy$VYr)0Z1}@KDcUq?SO`Prl86p`v21n~iULlF{XTVXS4}c);ujvt@3unQt@SU7 zIMEd-BnqITpI7dqd#$soM3*yPSL130ReY z15L9}!naaquQCSqwx1tu{CL(R1)*-~5O`=$QJt{B>|3)^>G?tbB@>6sf`QB$t1iC~ z-GQOZ&E6W)FNEONp+JLM=EdL-BP&>$x}WjWz>NZWxtxTkM;u#|2B*l2$Jhxw)V2Pg zIK20Zo3@Bfu`0m78ifn|ZZ7})x0&2p_UdJ}-Wc6K|BFTRxYn`gAD;gOG{aWr2!8gm zb<>x+dQ#Kys)CHEDYaK4%r5~4S#zEiPwKF!5D%bLhpp85pb*-l@w5kRp6m+U6Rzws z^jKv|JG3pmRddaej*qu5Hp%QwS~ILy#^;lT59#aOt6eVowV-j=G*qD@2|qz z5nB0tUl@?Mf_zvb*pg6tFo5o~yWI4z4q&%#yb<64zEv24&sj1;k*t3ZN=7M9|2Vev ztg?IVxDV*WPwCJ3S}pTKY8v5WZU=%P%P9XamK@SulYNC3q7YPaI2BAFpv25#!ZyZ< zAGW|SY$(9y&>Uw=RSUb%CD6Ad_*FDW7I3M(pAAVmB+8l*P9h*~rVWZk+yPl7R?>y!a@SB3%5Y(mq)6e^Syvk7c zo<7O9SSfk&1K3hA(;tN-k)TkJ5vxCGU^r8GH#W{al1vJ`>%YaU769DgsFT;X7IiMm z45vhxIS|zs9;Fh=HWhGQeV$Lq$Jt@9_f0ChmpEb;=a`c0!f43XNGmEu9Q%;OXw%Nh zM9#l>okqI!aX+hnd`hM3^hDjv4ru;tlx0akn z@xn-}+xhRoW=Ybq>zzO8ps!J)A2+=V4KwxXLkr>^Ifra4hSFu{hU@@7 zkT06#21Jpo?tXsY`K#&Y;~;}lv6A6~h-x*HICt`c#(vqzcReevke8aU>u>0O9!10| zdFOw73^MloBFSY~pf|D0gmqtIP|Up{24OMJDCPzAKQwTsX>Yd59o?SAFK98K`I1lVGlR@4w2Y~2s|{X%SQU@37Jy8xzPi)a$d#LH`mA=U0R zDjAkpde5Ml1lJsZ!C;|k)*vt!@k0*l?|KwF;a_vnPm6k7m!FymB`=KR)RpCIt9Dn8 zceKw}+rLc3{vS0Zy~7Y0n%*Js5hAnoAYR?YvpBc$r)T|_&Y0&9G6QnNTy3HPcDnrW zx1|xmGk#u#z0Gq^Ej2vYqeetBnuhDE=uT-XOBMg5y8e57r@cs)kdH~sEcrlyR)xT% zhbSw->|%tc=f&?l$CDi@;n!3z_@vhHzOH?T(hYgni0{+I7YpNW7kEb>dY{$)Zr0sd zKFe-X81pYXf5ZrQ4gN&q8}zZThlkx<1u{#OPosjEp~U0`50RN7mZQpRb(!dxoiuZ$7Z{ z3G>y91Hb)7!n<}DJ^U3z68HH}YNJC@@-|ua()kh=iC@YN+EItzp4<)}B!59@B4oCw zbC9)$5n(T|NvNU7QhK|>RqC$AJ=tSc!@YI*=CjyPPPi(@L+SQJ-FW&XZ?g^BYd&?S zid8MxoN0K!;F~*Meix33g0SE<;uhRWXib<@|cq7gOXdY&MGFBPuEszc z6KM7-n}OS01IB}*d#o64CBR`3J{tTJ8k)UzoqZxN19YRHNkNH3q22Dd`SJq#4Hczz~$kNK! zbom4g^k&1N3WJs+14R<9?L*D~^77upPtWk1%@*zJMRbcWWjPb4U1mG>|43Og-24|H zy~KHZ!f{nEUHD~o)BLiQlyQRIpU|#xiz1!UgvC(tw`bKctvv2}||^ zpBCW`1;;V`hWHO$*@D-@*Tc^~d>Lx2<+d?^`kMOvN9+Df4Fmx^N(&fMoX2 z0Z-wy7Ltlz%XwU&KWgaw;e!tHa+6`w$Ox4bDFR1AEt2G01VXN)fp#9Yf790X5@_&n zVCa3o+(022vMr86O0%pO8WEhO;wr-t6ar%4Z26ZgQg8`-B{{%J*wVOCGp;Kub_f>w zq?TZJgq{Z1&92EwyrS14Ke4)6Bzaj?;u?qGd%iR(q-d@%+)0E&i>>YR$fD&ie>9Vc zx8Fc?1^g?Sl(}91t8>nKa`7fEZfUy0aRVKxO}iE{4YVMcc{)hKzon_G-hRRi4{``R z9b%;UC)FfCnMBY)xExkl=ZkG@_%6~MeHjj>hJq(5C6f2Ru z&?X&z1}X8i4FUu}8wufrxs0O?WdI%)aGoP(#s4R|qpERSSTZx1Qj-S|1$v{72*{H~ zVceXTzw_GHS2kJ$Z2v1AJCc%HI)KgpXKx%tN^V>DhxPD8ql|uqB=ZsTDgeCvSlDl3M8g!NDPq%z(g>`9}YCa`Y$LKyE!d4d)XEX8#a@55LN1us?8D zZg0$RT;W%QY|~v0Ka@H)BNOJUc<)45m{@rS{!+ffO72LK5;K}<&xAZ}{_n2_H*f4K zN)0-T+H(}=B^fric6pIls`YtKdoK|7nbA)DhF(uY5Na33paAucOrr@I8wC7`2~))% z^h1Mn>|okSvcUGkD6c9=b#Z4`aOtZk3MmZsgBH>52o(iBCFGVdsVuV# zbT6K$B3|e^;)_OUQ+ldtQ|kmX);g;`3*OM;K`zSkI!G;Du52~LDL+tcBhw<#2>6X9 zkVX!JZKD7>()q^z3Oq=IxrINxC}#?6$=}e@umY6CYM!6R;U36xl?#kPs?uk}SY|ew zqp15VmLYayZ%MTP^R**u9}PC}1FA*zr=%x2!AQLR1}yl>o&t#%;~LMCr40Kv9fTEK zfc3JDM*L3R+}#0&(waY&zk)zfq0l>_F+`$#i@F2uFa$}&FFQT+*1HtD1cYNqJG-B8 ze;g?f@zsWszdZ=~a`Chr;ax@NiJ!#GfK&G!VY4RwtC5f(TOiD0+8y|bG>I1#`H`K- zm1M&L62*T@dD4JnPN!Mv*Fbu^@Qv>*TQ3L|DS0nFm14c?Up4)xsb7M1v<^V*<#SQepz%ap zo7-1RXkIBFu8(%hm-st67mq@>5Ee%thv*3$Hv>Oj1mXa|!w>%|$dG3QJ`k7upkjnG zHgIZV>TdW*4KBD&P;cZq`q6J3JN}`umzm6E{G~iqMxWP(p9N@Tc_xme22k_Y9N_9F zBGzXx0XB)$h#G{)f^r!)L_>5q-z8#z%(@)QF^)9FpFko!%Kl z1vs=Q4r0G6R>mya~xpsW}@~aQ0tQK1x1C0wICmL0L29N@b zu=@!PLFGI41HY;(iwfu>{{Edl%0(qJj1+YeT6x)VSgZ!*N-*>V?szCrCcH3?}(?q3VcmT3)`9ge3L*b zaEbML6rLN`4MzDo=2o^wFw*D^)}Uj4nL&9A?XW-rez(99w}%u8JSMOszaKjnJxPS~ zX4p}NL=H*rl0?%w;DXt?uILE<62*s(tv?-v?qU}l6VQvFM&T$;7K~ z=;f5-KjpR(o}-#E-X{&%T|w-mf2?Up_pZ%#>z=;}ri2ze>aT}p?>?}igm(ES2LFb8 z1BxDsaPN-42_7)^^CFrH+}El*o~SlAp2Mk&^SAX>1}?qhZ>Av9l;UDNb}@CAaN4K~ zH=TiIu%qh>)YEs<;vF1>S5lsRMG6_*q0U)ak+S>SLs7N#bZb99%v4_wOr{Zl`apKOG&iG|4KYjQicthCkZgGn(ZhNrK7TO zR&mTB1vVy^8|u8lc6Xf&Q=)RDel`(o_!kbY^*h_@jz*_+2Md(IrA35s=7=Gv%GN=U z_~-YfKODKIP@$Kg5det$McPjCFYEo89Ab0bc4Y>F2$oBQ-S5@2ho3+E^32;!Wo#f) z)6-tLv)(1FC0o=1e6$m&tao)~a*Do;tZ+!mNfNKaoYU?#Vp@iEuNP10lJ|g;5 z*VXEp*iHTAq<%_JmlQWo9yPL|LAu=q=CX!vmf@xYkKO}YbW176vo}Wm4%p- zl;8h0ZD04aJJS&qOyQ5*!x~y50pVrwohYc9$e4`5sTuwU@Dcbx zinkgGdFU9U*Fa0kXM?pdgT2?g%t{$v1Zp#n5=k6Qm+^m!_Fja=mJIo3fqz#nNftEPl;9G8eL%G-a*Y~VTCpeD#FF%Tlu>#oBF2;un93CO_bGf37!8yB_vW!@zCir3 zcC5d&_F4oBb=Dbv$WoFF)}bX=`?Y_FRFek?~!S*JSV=pO4h^K zUiyz|S1XhGzC{1_b#0@0&hagm;rpeol)&%|5fRVnAdLy*b{&zNd*TKRSV2tm!>>k` z*Z(Fe5RjAI!#@h>o30fgMsJ~A86sC$L`%kA7~ihcH-P9$MMbj{^#Jh7)co(oGD=zm z{@G=Ta9A?nYh!^(d8S$1Y&rjBKQv4moLB=5f;l-ODpO*QRBTU^>~!}VxBx)P7DeQY zZ}j-{C~RG{ubqDdOa3!wK^kwg6WSFjP{XUF5C$sbt>yyJt|rM1+0ayQr}N=(J!wYM zgd}HL(}oz&TP{T|)kJJ+_zrg6fiD~a_#ESfzXwKlK1r>NVDQn2%JI?5;7~E3aH3BQ z2F)_;Bh6ZT1MQ5_A>&4#T^XlA_=crhi(Pxb9&cqhH~fC?i20ZC8A-N?f>5nU2Er;Q z3-x|wj-q3-;j1U&BxSm5T@-_ln0gEPpdfB_nwd9jK8FIhQYcP$qN|*{Wou~CYqY{R;i?O++Izj z*bSFvY6?OK7sFrsD`kIBV#&@FPr*+7-{&rXXEb89dAJ%1*iCzzk08YdK4N~Hx))cZ zspPU3H~vrRTMqf7opd(5098n4c9!w`EvmavBfa$qz%W6@X$aTXpED&^? zsS$JcnqM7n%YU{Fv^=V@?y4g*=Ef3-6_g7vlSEc|Zs@UT^JTdvBBYSU2_GpFzm+|W zy(R2!5N~4}^c7YLvrXCse6#z4;7*wai~u_2YyXwEL1^GBs4+75YI*n&8^fD(ztOTR zx-SI1`_|bo`*+#TFeOP)#dBE%h}IEyqa!zP@H?m_ZEehMV2wrtTb-B?Eo`iB2$_ zA$~MC6WK-y3%T?-edLI^$sW3U?^eB*sNfg!iX-sL_~#c0;CZ+ejzjFP{r+m03-L=c z5v2i&?{&1LAUvOH#j4xx+$Y`pN_H@z;A`?NqmLDi)3=FMUc3UL)hvV1_qqF3ueA72 zT`T|GRax^@;)_r~fDw3aam5~CIC}tQBt|O}3t}J}nFTvq36G713YZk!xQfQ~pA0Qu zv4(?!6Ib7=Cc@2}{?#>#e3GOPqt&evaR+rriwnU&zd_h*3@q<3aV0joJ1puoAWxOg zX)y-x8PnV5KVsfDvv+b0jN5-LUnFNSM>_xfkUf@wVTIKw@h-Q(rvFXhMm>dp+JL&{ zlg9=S**_Ok9i4GeIStAq?+0PDpBPuUB8*Yy^FTp}(#c%Ttp#4v4L4>0v{1mAK!#)y zkjhRFg1bLi?|Ql)^)Vc_{WM^%6I%j!M~tH|8VAL5CB}(Yfu-{?Yb)$?f<{TA3tH*+ zNe3I<8Tj_q4*Wc95hy?t3u7VQH&1Fyjo0N zbTgLON%w9fcT_jj1J6*L`?>*N609v+bQ)KVO9jRZ56e$*QR*>%{a08?e{#URcBBFR z<8wK%_tRc=|FTJVPhvz}w1)oqW?BBYWS{jOa=&W$)6{*6di7}mXL}bY*~lZMhO|4y z!VQS{?0V(2<&_X@^Co+1j$HrTCwK{rEmGS^=~%GdAkV2IY5`G)Yoh*n&i6(iCT}&H z%Iqa3BgxRiDg;@>=oACZ_bfIk{YC2*N08V z`Cnja`xv8l&pMHJS@&>3n={m@@16YUax}G3R{SxE#b`Ux6yS|z(7Z)^{K>P-NuGaD z+G5`8_O@sH2{xvs>R@qLgg*CDnvrvDm@3)2s8I%ktV!9DLmrQSX~>jUr`YC63pF|- zwe#__#iJuPMqKff;YR5aM?xW;>R|dQ%a4!eQrp|KM?dI4BZO~!L708I>8y9U%Rk!4 zxssd}+rIi2A|3fPQs1m{x#*c{%wV@1_J$N~A#TNoKT>v3e_TYxke*1sjl(kBgyd&; zrgNR#O2UIp>}2hPCIwSq;JW1_srjG&k=5+(dTz59Bef#ttf9kGP0RY zMuN7LW$C;~Kb6U0{gQ>AL`q7rhf-Ft#@lKH$=-o8UriU| zGLRg-3*s4?3QE3?&A?mJ=3ulW|9VHZt+#PZneqIJi{vE?xyYulU1Zews2d84&AsHt z8-=)4@3=6m0%R7Xb-jD!^wQG$i@kAcd}+g}+FuS;8|WJ-Cqy=~Yy*++C^=8qvriY> z)JH}tZxd{XNG+rq-e?L+P}uzYN%>tU?VMBZ8vpvlfw(OfB@_S_n|-U*D>plIVW&59 zfjaRxvym2%fR&7Bz?;oZ61iCb9mp;BZZVutU^6&y+7SC^$S@Ep9gujU@qnmj-k~wbi{2BZEVYtOFmA#M)3fh|T7R+;F>_ z)#UP}D-huzEr4{wAUsFWusr?TOJp*$>w`>T1I8|wMF@yd=F)LDnf5AwenTOmw10%b zB(%cNb(Ij;4zDD$BPXSbhL2S_eiowL=DXODkW)@*t@?*zi?-^jvx%8vZ069)mFEI8 zx50{g(6frmwf(uM{z2d>-NBMULF_`&L}TT(HJw({qqT;%!*|D1^xNZy&Cg9Tv6I-r zM4D_*73$jhf2|2z&<~MTF*K{1EMPeKQrb(F(xV!@cl)aDLdDZ;t_(E;n;GVYf;xYb zZbUsfy|bg%71)PHY?c$6bfe7gd|yY7_F2fGYT1oOmPYMA82!o|#{qT>Gme$H&^tbk zM^T=mQ(TKQj>%xpUpg^e8IB==VU-ZRkwM+r;nF~ptG7B9laFOAOJ(9Af=BPCSq7sv z50MrW?DZxK2$tAtut+caLQbCd869?tmyCx_$Uev*XN+#dHOWWaARYe_KoX{Q0>o}~ z@j$uT&&8?R&l>v8b^TJ@(XIaeH9+3`^zmnScU=H;kxrUXIL9}Z$~`qf zlqzE)Ck^kO`9_Z`tm!xm+TXx)Q8I%k_c`g;xVDVHo|hhX9@FO-jYu{o380XFjO<5?-H3O#69wp9 zGOQeCd$;D{+dSFqcW-<`1NhIqahY#nQlFo~S>*;Zz73RgakR3%u`9}ThG@BEO1d3jxG%Qeoq!+OSADx4}=7-cwP^KRAyw}NES z%z|}L`ZGoAFN_l%`9$qcLdxpyVMcujQ%7!80~nx)yOs{NK;77?pDrjcFi);MwKWB^ zX&@P;DqV}E17XpY9Jdzt#O>!McKn?@1?jnAI;LUQ%Dvvvz{gG50B6`M(eT(t7 zXs^cntmtn=8h#vo$APSB1uk^c;-0A(D(MFJltp(>E}GwpbrVHl!z{TMCNWqyZ@Y|) zhRMafDg^xOfpac-h*~i$W2tme!ZUs#Hbf0Fo8o12#nt!=;X(1#c0EkWp?ckiU=U+_ zDZh5NQ(T$d!3O{_mM(cxsa6z{_MKi)f4`e|j@|o`gvenL_qfuV@fh)p$AHdholeS4 zG@Khu`I2D=wz#>Kt9-X*erh5-0mZcODm6lpSsp~Cgk#OSD{*$5rL*9}_u7Jr%0w7O z^js=$-tjf!7wM%5n{2PULy)uy*4%9=)H_}SOTvBhxDdsKb}@IvziuF$1u$jPnc^T4 zfLr(D>E$0hEer}|;JJC)KK(l+lt5zXlaaR5d754_ zmi`oDrG2i&C}xgjczN?ypwoQ5G=T2O+l6#r=G-M7(VKK2s zpYa#SK5o=OT@zm&{N2Bhu(dllNkq@z5yr(Xk-fa7U72BML(fNgZ`W6GFkJfV(4)(Z zEj9mWZZEN|eh|HB!3V$5s6Htq@UYmPz@GPBwey~}R-ItB4R7%XX7wnq+%L}QtQ7^w zJLCottb(WH0n8&`t~%p-d_^?>CVc%#@TXH#?3O&j_kQo|f(M zY+26S^$QvGHHBI`bP%z40o^yd?0e&&EPz4{4;X?h>zHMaTaKNJoEyo%<>)9eQK0BQ zf>E!)uxF@R#) zFtwwTX{y5x?N{8B$zI3)b%&kb{JLElCQxcyVovJB6a7?xguV?=Fhk(K#vBT{7 ze^$S(V*iALY85*-XGx5@y&D5VlKtgBeC}F5?wYdbzTe1V$i>S|GCr@7{m9)g6c}9Y zBan)vEJBokf(zrL(A^975fQ7O0P3VXVvAn^t*pJ6hWRv zuUJ93B<%|pw<(A%PeXl9F872_fylZhL>)93eo*Q_=F%&gDcx%b?A&e?mPbHCY={0gVf zF*57aVdZD5awQS4a&*HfKI3L2+PGILRNoXJiKe@=!Yb4*)JBRcV%Lr|_Tjoav$rPC z8-o!}4}wb6I{{z2{oonOUmOd1NR&93)S)!$>Ls2Ca`}1q?%e`lOtFUQV!pC$S;Q#n zWbc0n+V0Eg(OH-`{nZvBJ(`FWnOrNPCdXw z(-Vx`)k!ZM$rx7TBbAg>lcxfYI6IN&D!k=rb9n%$3<90}mWM+rl_yotKE)YR5Q<#w zS$-C{0K;Zx3bHbnWzR{UP}k^ycp_J*H$n#NqdYnESsWZ%D3ol|jeB5Ck@TJPl=zlx zM*`bh*)GI(FhJ6TF0^+tWUpeWY-(QQwoe)XAjcDpGf8!A3gBrN+tHZX!_vuW#$)X9 z2!`)`e+?or)S3FT!|qKG8YgYt>`P$&rx>WPO&8jl&*6BtCsk`+EGHGtCH<+03r-Co z42V_G8Wi)M$8&V?ira_aSuhUqRS&D9vxT|R=U3Gz`O7_a?-`Mp43CaN%cF1OWEo9> z^=(3@F*dOx@ia5n!u!RAXM3Fws`J4=p}B5%|CkZA1}5Ef^%vtcbNFoV{4VYuC!}(a z#OF9fWrTUOh(Dp9l!bP9ImlOjm}DMDjpw4q-o5(d$B3*TUOttLPQFtByIxORn`d zC3rENQh1%kP?5>%WM68qqmG+cqjS@nbxZ}MQnNYUxNx1Y(9cK#T>~Bq;9@p3|2Q7F z^3>|F%jOYYyyr-zX#N4Wdtm2ey;oZ({zEzI%a%x0zYaK%kE55rw`6G(`Ow%qA>~&g zIIexxl=8I?^Hgm=N7N*u1>-;Pp9?=Lm(q$E=m2=i2A-a<=LwwQg8wb7 zGeS6P3O-CU5NUD|__Sa3i}(I|{KV|A0H@4j=izac5ZhH!fnz6hK{DJxg04Lx3Ij5E#j zq!OUu~!af+A=V%2c$jlYJQD32hfXi+~LM@z5wXZ~<)p|fSHpQFWx zn@=p@8^<*I~+#5_RT_Gx9;B+^EF ztti|#XJ7(8XU|gcEi06J5NWr+Q!&Uw{ee{No2}@Yt&yqTDwawsQ^vs6KzEsYK9mQW zEboF_E^Lb1*}mGjx;7tLxW1sEcRKs3g3yiIlKN3a{73tb@K@J@c$XJMLPo%;Nd|OIJS+MUd#K3+)mk9N z(|Q8^|bMaONkf#C2IbbNc z*7PH75LDVC%j^c)tZ)*BrEzfo-cir%_ zRX;U4NKQ>as-94RZCc;E8$jK?n*i^mt|RuN2`k2E2xhK{$J0(3^cn`kzU&baVAgX<}cDdvzPIf5|4x{^F@gsK+YkjA={ulvMbgHI)XQGfONvl5*XdZ z3$qTTZMaY^ge`&He7sSxmcwd!Z<#*P`s1ZPY{#phoIx#}j5S<28=drN2q*X~6e~nv zL$%F#l}4ew?7QCFu6-CGqHawii>;Or?_`(%T)|AC6xL8H>~9V7VB)DJY7ERnn;p!XfCkDzS)e z`&K5A+0awViG^s`-!Lf1(Ud7Z{}zskKDkDR($rZAm^Suc(%{4CZe zIuJ5vPh5g&iv3{vv!%hlU!4rYwilU92oByNf`CK~1zrrg06M421l`?6|B4i|`5Z@M z4O86>r+Y6lcwZwST%DcU_=RKLYT7tj!tJOYU1R1&dpNJ$pn>G0XDP$JaVQulNy$>< zj%4DCcfUxbdF)K7e|7a-Sn}2fE!s=_ye|iHTk}n*BTf0*LuzG}c%bm4_hrgg;5P3n zytk-1`jKx&st!|BH@(3jQG?!29{GYNOCZf_f}M;6uGXA4_!YjL7ex~`_>TAS>7JVPNq)`~YqzIvpsSH3*Zd8mWDqrf)u~iIu}Uqe2Xk63iFCWLznGzeTntP@wnz9+5 z7`EJS2<4W6ERoOQQAWBC#f^(`fl1M!yAWL~uBR&yYY^iQVebhE4>HJ~2B%6VFtM!w zZX{E2Tr!yk#FF-&X_ofxrNa}f(P2RkoYe}MRK$&eOe3ja0lV*&zH<&#f%rd0UBiDj zL5Lk3!az4nPvSZ-&`bQ5ot90$9j(K}eEtO8Sz&um`fk->`rGREuVWH1ZbkGQEo4oGL4=uh*GB>dhURS9# z(pZ*#+&kdP(b@6;KtZ%U6~!Mp*BDZZ$|L;T$p*m9HPS+|6iGVZz!IH!_*o?*hrZQH(c> zvmF(EKg*jz8{QDgDIOPs&@OuAULQhDaJy15s7NUGWk)lLHq_*727-=+pf*u*itFd7 zKUSy{%2a%Nx>bb2K=`|1!hx&-1W3sLZ9|mwXpB$YU${}zCGW9~QUR5v5_yK+AxJp` zTuKIoWn}!3&Mg3E%quUm@C%&ZrlrCE_=5WE>g7)z-_q;Sf1;&xWlZL(ZaK8hrE*ch zW!RY=I3v5DnChJ&$#i8}dHOiVRf?(q5Q~a#&yQ273eOVD$#TM7e0pw-D8>F(XLW(S z=xF0Lxc;kr)2Qy`n7^iY*qP3eODP&ughLb~;kB8-l%q%Pa#6#ou4n(Irg-N_z_{%i z$lU<&CaY!x63Pid< zI5;}gr+*PDTh6vVdl!?Bk$%w{F}R2Bh|>u;rhedL{IaLBnR5~%T-6_gSOp14-kOq# z;ICwTv@%(Cp4rz1{W0=55d*|j*nRSE_)+TXQvbq+Gigv`6~tMqy2lxm$qms=(SHzQ zIhLhHSO%VL3ZSk!Ek6G9CYb$jvo8@W81EsKGvpRsE>^q13U2Zh0{V&q!ND+Z2gdBh=0+PZrxRA$`so7i?HIOrquP;=61(8=F2#(xgc zCs;+Axg{d<-Ymyn7;YNPGgk}SXXVqm3OW~Wl0wNy#oc+HB65;M|CpXX{~O-swjygp zmk;BKcbFUJzy=s@?|Sih{g;hl?2@L)DwmS!eF{}-C8^yWT9Fs%$Y_)M%puaCE~7NE ze^x3JsB&$?a)p=iskL%}+865Rz5uu$oY`1qncbvmqf;KHg3QYnZ-0s90~Y9fcy7bl zih0U1)J5&xk5J>Q)P(W0sgzZKnEK_={T)*JE^Dp@M-zNBY&3lM3}Jf_7b6`<0k|MJ z&^7pBS*K=NngT4bA~?C#6j&u_#`H2Qj1J!-L>F7B%c%)*vM|r;)i8`=sMW2#3>h3e z;PL%kTG)xwxe}`4B1d^Pa7wi{H=*|UH#_FcSItve^j%Pd43{kfZ;)W~(Ww!jGkSLq z8vW{DQV@@;7fT?2iZ>l%glwhfrPM9vllX4yOiQ(_*?EQeLp-gB1>aO;P*G-fsq~ct z`k;An*YY>x$*{<#bqmWVkh0aD@4%)tYAT>)2z*D+NBHXOT?y^%pj!g-6B?T;<+EcL z4>2GrCoCF;)i)CKFhX=U47kddd1bA6pl%Z^{(Ru5OAv+IYs%~n5+w@v5wbE`Ka5`4k-6)oX+ zDoa{9tUV;RG126phIaBI?kn#uh*fHUkI7nTy)3;Q9=WbQi!C>eAccsAimm$I^^(z$ zN}))WxOa?l{hz?04_N|x1oH~SHPfLFg4-_Ljl}Huu zclDSrFn=ifF|n!6qD9E|p%2h>l<@dj7O+AoTi7dKdSOIEMy!+zDFnW=vm_l4aB^hp zRxB)n&;Vdx!mR)NE=^TmOWUN$O!|Ww99Kh%Ye`fY|8jD9L_eEkN=nE(rrVl2vlc5? zHgB^|N06BRRIHHNsTJFq>~&@Eo)S;d@2!5!lt=NgUbdq4M{f6Ec`AmhFg?U1O~e-RW4N* z`moYo-cr`m@<_+lmpZ1wsmw3^eB9`5Eu_^n{!v_idE5GYI*vy}VigcSKF0!B*JT&S zuyIP5vqWRwuCbr5v1XJDx3#V<3zs?@GnUqlrC$i)`0244e<(`gl+4>j3gN@rJCq<8rEA(c++*KhnUJLiv6bi@>pR8*p`w^lmkg%Uoxw2Y`0?adiOcG4%7M!y7b+&^RH?B1S2+WKIphIqrr%7RNy4I7lDy z)he0PeuFBtn0oxxvhb`=7fak6H?G$4%THeRCGlM~`!q8ZQ7c29Azgea*H|?V(-)Ah{)cVl;jBfGSly7E4vle&%y#m4q;_8d@F*(*F170Pu?n&PkEyxCd~W!l{B*RzV2SI zDHJ>17DEX$Yv~KuYz0^hh7n1I(^89!DJCq&j0m9|D}opN30Getd3uot4#o3Mg35Jx z$~v$Ikwc)1I zjDFeC;@Y}yl{(R99%j81;#_N==zqv~z5)t_bMiCJauQuQL6~8h$jbk;00cL^kN)X( zXU^=iZyk8ERmR>>2DXwZI+)h6+=D+_7NLIqB&3W5BN6MU$j=t zRc0gn!ViWw!Scp&Dy4BWMu;N#nexVN)u&uyQ5TK}jSkf?rv3fWJ{bQ-Ft5+H>c{sr zVht*L=>0_nUxD36|52dcD6tK8klzlBN6tgH%Y=e)DM;rou@vM94C6eW?Uje(l5P>M z;@6WRZ4eXKeS_gEnYW~V4?ffSby~HJ4K~^NAH9!+5hjY4*v%)thqAijslS;JR3b z(7pLJU8*bF#8VFZd9nrW?FRyw2yjtU&}UK1 zpd9X98Pq;sLX_eSes%Z=2&M|>M}YTMJa;2@W0uszN$>8>`F-5d)P=54tui zW6bM#;@NVB77WIqiHCBi1VWCl8wGxxR-qmD(6P^d*`-Zk-CYpwwB)R3pB-~}y*YNN z-fYro;^ob-O|5`m7-E%2BEAFh@&!$Ka_Ci7U$S>Q(LXj4;R&xmK5wn8NOso!&B6O0 z2FxN)CwB|F8aZ&T(YtESrmMZIGyV=nLJp6eYiTvTEf}W{%d>;908KF#GWuuRB{NaN z9tW=XBV+)$RpP-5`@9AiW50kny({e+ZM#c7vrV0Ml`zzU<=ZZ_W%%kZM=${nCx=J> zydEZ{ht*vB`HojRN7E-hHEkLIF&ll=U)LSAR1jv0b>tZ30PY#P{WJ@}YrCfx*SrOB z!Zz5v;_E}NX~}dwfGLPS2=pJx({kxzJ6ScWjIj4TWu_A7P-1)~wEQ=^ks>QkAXeFx zRY&COI&=vH_ZDp#K2D*1Z90QU>(x&BMLZ-SBm-g#ywBGMleKR^!FpBW72&0mbTH`q zz&t{U+~u9=!d_5)ZclP@;`#C`YeU28JN5K!`|Vz1vhg&JWr@FbXn-Dj$eyUQDp>_Y z4X_Q20uNT$cG*V3Iy-y9X=R@2t$+~yaLo^jv{}1^F7KoZ>=eQ@;Qth5vQ`Pf@m;Xw zXw9Lh_iku5R1UH@gymszy~-I;)+*Ux04oveqRjnBejm><)w9uv71#cLoqs1<87-q? z^7nPW*?%E^ZfJ;#-(1(nAHC3OySmV%+x`oT{#eDk`XPY#b0HlDc8J63YO@17O6pX& z`O<~Nd&%Q!VY&12SW)Qh&FJw+YhJQ+lvM!Yl0kQ#;$w-AOfAXax?i`F0EQ zIYigH?;&;gGru@nhE2x~5<7mrsp(eWD;nw`9>P_ z>c_Vdw{f?APOSZYZBy3$tTzL*s}O{Zy0Q$`{%D7yLJ^DMFv&!P?d=a?dVlUMkdgh> zRKl>iu981DuavFd=HcP4D(~n1cJ&v~vvD3%xgD2g>&M3HJUVia6?@#V}=87{8n*rRyTnpN3Z zbmnm`VYf5OZG0d*Crr9GgY6riD&vGd3C98!I!Gg{@*-(^Yn3P?`io~+|VmX*Xf}+m-pxqxAO#ucQMfJ0CS<^ih)4sMm1RD%YO_- z8x=Lhbm-wo8#-k@sskJZiGgIcj`l-7NR|B}m9TnlL z;kkrxS6p1Az>b?2NtvF7rJ1%F(Y1Uyx&V>X-ae~TL5z06hkW=~Fae~pj`|PG63jyB zLeWC~0`+g<^Woo&3$}FDV`obhQur+jrgYYaXYEst+c9WRqZ8xNRF14us)pV$b|5&b zKtupesLM+BVpqsmua6qzG6zp9=SIVy%OkBul0J2ipS7ou?FKw`S9TiDA6sA#E;(yj zc=B}n%8-qQ;_n&C#{C?(A}p}p@A5TY`TI((x8go-JYq^~p0|{A%ZOOqJ;00x5xi2g zO0`mvl3D1SMlLh$%S>`@1HFjNuaXXy&GpU1F0zAnv~J(aq(DmQeR0 zftp9v?{f)ln=p<61%nHNU3P~|i}J!%SllQTBqT{{HQAr=;^i;6T&NT0{zwg+=&@~F z;TyWyq?ceqPM1Dwd3`Zso4{_|x-#l`@jC8!Ns|jx!@-VzvxkGzVzg7Mo#S{112$ue z!qV(DKj7n>>GrIWYx{13iC*wA^{6bXe%$y(=wA|F5Qa|q8^^(q8PZ`hM&(DCh|__9 z)qCpl+x-aTdI+JN{Lj|35l0_c)Ar&LmYR|Z8U`%8@mTTf`RsEO?J2j0oWDH`UL1U; zVO?#*5*l`~xpKFK*Md*uCy!qh|Mn-?kzekBKEj!v2s~K+T zi0c2YI8nQG7c^lh__P-60~HmoYBH4p8IN-=NM6ZWm-LgIS|0kj9Dt-O7#X9^t!zUP znm8KN5W{KICep%mJxn^Q@M2$N>zpRWW|QM zu2NHt#o`P88D-zS&7{N(Qm`t>mwk5=*zPc$~9{1i_qk|33KE z){&-cn=ZixW1qH`(0!-RXjV}pilH-I#-7p^>>i#H^khsu0&G-0WMphT6bw{V0t|Fr z0s?GZY)NTb=+nP#rU~1Wud}K<^7O~RI*pINqvz$NA zn`AzpGIYRX+MV)P*_~!u5$?q{$2U*L#!E>^SaK&}p-Rm2lAUG}?loUbJL+ige;rd{ z5s=sAb8?9z%(JqHpvJP)%Bx`HWC_ZHWE6M^xq3ap&zcD^KIIv`WxK&8xYAW|v7;~B zmB@i`Bm`Dc*L|wX;;ws;{3WtSy4f;6TBiAav}5q{`hrn5g{Pr<|B$jmmrtkrdcWdb zyAuFR#uj|MN|6=J+^Tn&Se>ftbA1LG_OJ)uv_ow4X|_ib-5BP-JMGM`!$nte_T0zy zbv@l2URRFFkG(#Ko@43XzvK%z4hHz1&V;P>B}Y;Qr9#aCjqYh4hF7MOFOwf$8CyXPY1?0znzkjd>@u4bNU-~-%oS6 znA(pU{fa4bgxqh}%le#l!V*dfVya(eCjl^qFPAGaJ3a@gFMSUU9}42xRNqF4A_O2M z`6LXws%;m~)8D4n_!NY$FV+D`6;Vdix4jMqw_#0&hAc)ee#kJUq@UmS+Va==-Tu0z z3*P<_Z3l1_pTHGdgGJ-)zWqv`4`C$IVzpr)Yu9+{)1;ji!p{NkQ2cP2&y z9qyAL!rfoqiraRjUz|pT!rUPk_Q$K1{cCJgxA(Jr$#t&R+><~tReT%@KF7B-w(6lQ zVd|O^t4F5VnGT2gzny#Cbf439?&9dS^Y021V87(n2z|)CzlAJe=ND6&ue^XI-qT~| zU((pbxyk0|*%{ET`O7%yJYqS55*wl(0{R#aZbhvW@0hR+_+Fo@uDgM6(kF(i8A2xe zk(C~X@Al8X@{!&9V6*F9y+_+j)&?cyz0aSc@v*i)F8(~Oy{eu zo~2IM+it1ySIky%WJ1S|4zDP!(is@=)JvyKk#;9rc(pMF8=Xzs%m^;~gUiW6W_*t) zEUSgC$6Y*9^PKE$EDWUGU3a>K-m;4v2yC)PL+bc@5AX*c>~}z@kA{DTj2_JsdCY1S z3jdKvIRu=Qpvir0=M!N!TWUx4lhJYfKEdaugw4C3XGv^K(^XaeClPINFW+hZ0{2HP zu|JOU0$$cf)83r-?qmAikC)jP$KO_n1z+B}*UvoqxGeV-Rh(kKO)4kM^cFCe3I;4< zG8u6A0J<#Y^V`cj=YNG87gM>5v4Y~(pP<@Org39=yH6~)ly#IJmS(O9{nlaH-VWpI z3?A-^EVfLcMBZ}#D?-B8inVHUm>c{DBAQT7LXg~p34$DO|GSmAFaj)yC!{7PoGn;GN z$1-gXJ#CJw>eG&vE>0mw-BSP- zC%v)b3Sy$RD$n`$@L-k$Q=Tx>g8?OP9h=);LtoyP&u=^$lHL}(r-}hq^BX5Kymg&- zlc=p`N9j5D>*G7GTWz)PrZU^HGe*fECmn;rL9}Vw>TOBLJ>8Sc$4=M`TAAWO zYu8PFSOvIZWje$A*JH|+1mn3F_1rcQMOhq9eDmeOreBRhcK2iC#s9%5qND>I|LPC!PXZ(OCBmj* zh>%8U-XCpBdWGz!v`a9^r$0k3Vfp_c0K|_v3*ymxGPcve;=Lkb)1urKLq(kaa5clw1!;SjL*+Fd#w#ek= z(VR^lr^xer9|?YcMJ35i*Kz|Q{gmk~VM21U>vO(^J5|P_|Hl5NdQUO{f|mI#^7SNM zmtx#KEKXuA1HPf7B3@tCKJf)YX!V$_;B_Cr?`4Ba(D@BV+OgJ>nO!f;HYagzfCb~b z^8T6F!}$=;nuE$}Wt#j5P@^Ew7V+2tg-z2T`O~f<*yDq*pkW{0LeL8ph)fHQ8d37-2aiTDju;3os8QQ` zY!?f@GW0=&D4L~K`piyAj2K7CUc?R-;iQdZ$`ZHl-`z9$a`u$`Y)+G4H9`J0T4Xj< zlra?e2mK{S?1EMxxmk;hZlc$Fp(+2>Bu1DeTvIa5tsk%EQ894fT1A0$3KaYU(W{Q1&!3xWras;HE7W4Wp7V2vHmvy0!+E=)1>aS6( zu*T5LcvN5blc2UsV6< zDdCg>xLIPG(rzFR)NoK^Q{TWB@1&xji-kpA>^xS(anf{?)e{-_z-m1LIZh|!eKs;f zZd-j7WJC&U41F69CNr27LKn~l3(_j!%VLy*S#!)b2QD!?u0NskHe9p-IK$!~9io7F z%B}3|jpk#>jW_`_zfZVD$5Yj!i+-rLm;ILjLCV1y*sPUJ8-n_8qKA=J-+RJE&QCAyP8w;(?SbRm7P=WB~}$c-D=?qFlVc%u}0 z5#B>%(54ej5teh4eiE;_g0e-7 zQP5kT0e%E*7oDJ=IZ554LAA`V5}Px@eb}%ZIQ|RbR+ITbjU%t?%}M6b%eJbI>w5Ni zBoSjvmc)NP6_Hr!@%kt&0mD2A(=z89v$8Siw3vn?hx&%2$XfOgC>}987=n|bJ&7=q zIuO7mZ7i>@uS|nHD8XWUKv!WsZ)wD%xjR+tr~I#u%d5O8`6fZ1N*!vhp|HOphnR5B zH47B2!dn&@K??UHqFd-x6q;{?X8Z3-3ZZGFv)sY06oIv3Wo>y%WrL;DgAJXE-|yn0 z)*lz&4Pkmfv-sG2HxdOGQ&FB*mSP7PR#f<6&&Zb8b}JDU5C8*?x(!lR7F zP|gWuo6q|Fp0jSTOQ_6gvihmJxSoY<;8+mPitzs34m|8~B6UV<7lm&lBMCePXHZCq z5-9*P?+Ugm#$1v1;`{m+yPmncJaJQlIht(Ld=c1cdmHLQyJm~SdN&Y^oR_J3-@4V< zxam&$0#28gU9|Tx+Yl~uO*dICHZ7o6xeR@Zcx=e6;$F6v0Z;Z9gM@~uyv)WuE_?h2 zcMTJLsrQB2h@E%bWNBv#F;kjA>|emXs|#7QbjJ0-~yTW-v36`pYcUJk;Bw zObJ`g$nqGrQujRrYZjc?@t`H}bb&jkOC*M)pG*0eX0yq&lz(vt3XH7Y<>=W9KeGUJ z3KA9RxeZlXpTYVXL#W<5$CLd`kYnZgJ&*f1-5umEO{k_Uz!xNS?*KIg*3W&dGi_Iv zs4#~NAET9HmWfgyiK-%-loB*7Y|<69{uFulqY*-rt4lY<8uOuC#oVY4vvRRfa-rg? zqHKF(yAK(9P2Cyx#^|a2sQ)R4{LU%iBfiWv2^knno%-2wjA69c1}e-_kodm#QB-8q z)V^d|^+*$o(bKH-*DE<=-K-E4KGswUxIpA;6Y(t#&_jVP@%V_hMU{*+BY!wk+1=%t zmhvycDC!mofD;3M)#hbwnmMOSOSS4KdPk2T&d*DKCD?gK5T5W?@!2tNPatmtmG84~Z2;(3Wyo@TpWx!kUT8hBnT`*Q*v z2ZC{(^(oV781`$C2gTA#kQm6@A4b?e^)vQEzBImygD$>Cw+<114% zuIl#=rCK~PuG!nR!|(7|^F4i3=>{NA=Dx7_zq{~_vUY6w^W``rJ^>Tsn(S9jp_VSH z7+**)s>XY#fqn2~hQim9+GT(pjB(T2`tPaO1+Ep<96N2># zS}&ZqD0DYAuiPes))un_u23>`>Z}naVye>CeU~~67sXdLjA*H_ud0y;LU$8_)5Bk? zH4S8tBFkE0*H5LExwS_9=&e0k`(2|v*L|Le$shC++kN9CcQD{oQX7sxWY9aMOw3be z4>#x@gA(|Z>Xu}h)~(s&d<(kvhl3;hx=NXW=>DhBkN;)}RV0&KR9(m3@?@a0FpB;Q z3SZfMDgu+ch+*cg32a^Ng^6?cd@GWW@LSlPG?T$s!oMqS1}}U72=-O5I#0J(6={*19I zj99=dG|suw@_s#5x*PntUOLB8eJ$*=`QJtmAcZJH<2afb+Y@!SV6zMm9Xc2-J_`K( zdr)D#utRpIP6V;Ny7+tVg*hR9az^k)b8?>B#)K|hrHysO2W$VVm}FH@z-Q679@-E0 zlqCn>!26n-eE@JM3S(7uo*)v%?|B6ML7h9YFsl6tIK#B+xXGyNzISejYI-hL(sB4D z&2H1mj0hSebku;{MF8Xq;|7N)MrW9zaUv(2IYX)L3vI6ayHxY80d4h6R`f!QBJ+*9;JwVsFntx-xa{BKh zaAbh}1>vG>+<(75pZbO7VzerG3Hei%hwkH06EMc(G`<<>Gy^YCHlI-rh?244(&i41O4wpqD(79CZTU_r+((TX3MpR?<1i1OpziZ57 z`XGFvo|Gg*HqrGQ=S=N}p&9?YZwuD3Dy!^rw0Oz7&8O%*c!ajKkH4dIyFC$Qz6G5Q z#`GZZe*+E;^!0hAHwFCd@YoQDJD3FaM1JK#7yv@~+Ab=@;nzBYml70aFebEj*5C=h#hJRbHrdglmyccv&}8#Te^8cDDJ z$U@3Im>SBxjB~cHFjx1|kr8W=WkTC4Elqh(-@#w(l&M;NaB4=}y<0v1pB7+;x*|uz zZ5eT;Q0`YWSpet81~l#nj%n;zwQ2mTVCFm>G^0a@>a`W0#BwO1svd;}aQF_^qGWGb zv3gdtN8wPt(o2@(XYH|pa-|wicOn9-oa@EMicg-;L!3kJLQuqlm48{Xr`g41-bm=) zmWScXp+52J9Ya4EWPr@%u9c9bCMTtoddOS1@qMwTVAFNbmM+&#mHBOtK=ndK{iJSX z)R<~UrqLf`@&0V}wS+=c;fM1GLS^AUP|MN4B9S`4`d-A60wg8bMJNygJ01$n_=k4} z`e1@-O5w)?FR&X$K*_2Yex`$QhFcVseR2p8uDk85Y+mmr)YPgJHMWCw6 z3cbWixmb^Q(MKIco<<*@99?j8ZPzXsNp&s$rSF>Y?X<%#U#?8M=}^my^TIP0VZ6J9 z*J_--lus0c_Ofu?758uO@l`(&;)40phbtSIzWn`f)tPV$ts?9axIf=dl?x?}dJq$M zuV$}#@9OXG5j-uPRvYKe&CD4l+$1`)bc4=&6cUYN4HddxCl3>_7@r3lpBn`(v|?!@ z>T(|Q>gWaUXD-Q5n>kC-B;DIS4uT#7E=Wg>?~jQzba$)(58z|8x2r!vX_<_Fcy{oW z7)M}l?}7b;{^7Pq92rCnq;?#u*y8nqB&Zp8ig#>1cQ$U!M$Vdlf$^sT=wG@#sVXH~ zkayjasM|x>=XwzvA{U{Uev0ot$cpb0^t`f*Z}dJ!c`a*EfbFT~;-8yT9Tb|7>|1Ws zv-|`7Aat?9r8gQidi6zk)gp)Y5Vg%-(eJR^46rwr4(By)8qnwdbi!q7h;wzm^NaE2 z{qfp=4v_63u=-dKhkFzlacvP%BXGUJ>Gjt%=43ovZvrKMum<;Co8#d=?TFXZ2=ax8 zmpy7^G0$?FNNM$-eX@YxR#`LU$f1$hh$oE4*G=t<-T}zuve=oJ~!8=lAK((&&8=b*Xtw>uO18lPDt0WI3e(=w<^h_ zW~57^@hdO>&Uj0v5jgGrtkEb7zA@x2m{Gt?y14qG%2qW;JPtG(w&k5vwV5V&>PLt? zPvkDwffPW=4(cgivGP)?df}?K1Q;`^KVTU%g=JFvK!9Hfc_gAnx4>I21FTgD&xL>o zFE|If(GeUr37?+VN}7@#@s5kw6v6iP@9$sT<%U&`Xu|vkk#eR3=$dP*o!npqJVKVjETtS}C1fBp>k&vYfQ&?m#I{1*+TY zmmID?>of42so2*1$9(LGqxLm7f3m_YlXU&MvVpKy1Jm~zw|h|1&W5J`R8+rgc3b1( zb>l?Evx0!|f?lnov1JeaOkX%IYP?>%WJ7l!Giok>e*M2=ZJ~u?f<#bJ&?$ z37MGSIt1)FgdqNYL6}BpBr;{?*`Ln0_kGM2YKiF1b~3G_BHp&ZFv~FMc~kVTyQogD ztv_J47@~TAyckvN*sq2fS6%^fq#yM=s~yGKqbLXyiVA%ck3S}D@k`2FE4P=)w3pR@ zJCPM%Eu@|2LDGZ?UGF+~-XBm(Q5n8v!U;LuTgr4|J65+In3L5v)Rc}89h>;JTw|c# zd2s%g_fO^8T=_tL(uK^?Hr9l_vN~nnK#Pz#XF7x zQvaTdyBrz|nZQUPIlFgeg%Ivp*3@|a^2;OW6~A}(VJ*Rqa(o8x-Eqalr&0mpE3^im z`@Em1ivQ&Xe(Dz#tn5Ew>lBJuFpTp@->VdClaMgdYIL8LQ)s$J(e1VBWj<`AbML|l zRav0l;~YI#o!Dy*7vLrN#=H0+J(;pQGvQu^;1nLaY{Mwg-`5S8P>&3Gg=Uh?NQ#o? zugjgm*+7Ild!z&EtMiwO2ta7m@C?a{Yx)&kh%bJ7y&Nfk=ndHe4X&mEApn46v8LUiy*{)_8h?#>kR&%8L*qV@OOj@Um`vf{WV`b%QL`SE2K!kEKBtKskh`(^uYx%tb+C3bOBBGB`&%|j6JG4pTz|D+%^;Nt(lb~bKWxOMZ6s~{e@EQaDeXI zO!vE6#dxTFT6rUb{vd+pqICZC#{WI#f5th~5B9Kr1BBi>qywThs0VVp;I$bEyJRUy0BqVQo1Eo1cnBY20;)dq@{*IN}jXY>$#QI$3Uk zGA0Z;s6~7gfNLJ;W6y~niiXBuh=$W7{2#lc(+;sbg3G3iY6mIJ(VkN{<*=ZKTC$>1 z% z#67G<<8jWwDUFyL&*+9U&oBm|03)=jlSYC9G;$*M$Bi$rZPcIG$CAvLnFv;z|wsa@4 zKQD}X`rhl^hbQ|u`{|(J=!&1zFWyT^z2bi~3r$Mug4XL}(H0+uLti&O0f5tgExc#H zHViK;ux;@k{@Po?o_X>2lXn#8HWVUa++6E#jT5iPc3l&$&RSvu|2D;x6r~Mwwk%RF zH2-+_BGESOf5!4(kHTr_QhF_tGRnf{x3#V7W6!l{|Ki?YA}PpsHO_T_Xke}?4r~(E zKycesmo*kNRI&O$qcB(f$n@|KVWG^gf!^Zf+Oe~ZwNmD-uGO8(=QEDjM~SqilenFe zfiQNy9VX@T-C%a&@_KHb*!TYa*xvu5+oml3=bD3YVL!IoeEJB1Xed*>;HvHw*Z?&S zr;Qky@k@e?$rxo4N#@Io^GSnLAC}xs0>B=m62wt&cVKl`Soz6ToPJ7{Eq%#znsUkf zrJAm+=(+Akxp)f)Yf|-}Jji1NOimT1%^PizLkCXZvRr=3MV>OC)SV9SN=n_NKpo6MXh2 z>&9?ZnQbAS3LU>ac~&H3l+E|Qr+T1bn?a0q_V5m4q(m<^kK|!ZbpV*V8SEVCoD0O z<(WDk?}5ETXB+tj_>R}~KfUkoa=3Xu#VYAGC?`hKl#bf8DX<-5Q$`s}Yjzg|_0B$O z=uQG|16axu$TgKf`3tcM#8@xfw3pKMv7vDAv*2%=`_TZ*{kG>W2FCe;$0)PvJN@6u z5QV0#1!bZO6W@Dal9|4ms-&`=H+_!b=n)d#2?cg;AK3CUNHnPhw$wMpGyBh) zQH_;Y|9uJdF<4mOEZceLGBCi9FF}G=;!?-yiS3KMNU>b+?{D`m|Cm7OJOlJ-932_T zCGE7J#e2!j`~Udqd@Z-SiInxw56pAb0E&UjDXt0D~6k7 zpbsT!{{PQf+{Z=ofWpoVE5s<1KeyOmcSq)zM;FqGHRBhayqLPpPerMe* zEJG82Fi|?MTeReFd3C1bRgcdU05jTuN{_J{l4DRx;V)xfsKO#pl&m{!kR!s$fsOj* zPs5S&Vn^g|&1lHh8xGUvNqND$s$NHT$eUKSt%^WLm&|n*3OgwL{m&&T-YEeqJPxyz zC+DipGi&|voJ6=X6LWBmP$uLHPyQG3jf%QR?&-$ zI`El7ky696ZGC0Up(9e+!{UTG#$S!Q9@GlLqH6Z}R!n__ilKvnu6134DEBBF(NqZql+ddK#4%n!R2WXIt#( z-xDrTK7OV|xp!a9pbBhZX5HeaF8IRXN4%?Wp7vA65!4mPm=0B++hRh<^yqcj@G$%4 zfufvvPt^r1lAC{arT4V^!q6Lx>#WuQHph`w6wEKA<6qZpQ~>S;_fO1M9+vQHPDQG^ zL1%re7H`ui1JhoujsA%&m?YwJlLO1^s|fkDuT3t-=D+Lg#LxarZ84hG)Us|>_zm-a zwf*#@oz|!9=a#tM+|gtS_nIx(cbt3i^1WQ9 zo9Vpjn4a9}wCL3e=c(%=du=I{+moHLjLH(a;7;GCB z)Sqn6yld#64-9u#o4rK!Q}kBmqfN;Zval$9uEc&K9!o+K3&@)k#pe-1N>3@=Fq(-S zvj6N=sX0q*q8$kXof2?OdxapO&YAkwexZItI={CxDLwp(c`%>BOD?PngQ?^~0)kFv zlQo8XjCRM1_~!7h1CBoO5#&ObBMbR7tZflVfmgr@;FW_5l`D_6ZGk+Ga)N<-@Lv5D^`1t$VCr_c`t)`Qr~gYw@25@>vRosR~#k_ z$>-5Xal?FAX=7n z_({$EdraZ$@m%w%svA%G5*AXoM_FFDZ;AIMFkgj>6D|CER@}Kzs;5xvk7n>apJ?kB zY!eJEs@Y=q;3>32H|^yn(-BgiPN8NL#QIaZAbX@$GQt6!VyGCycV0Wf_F#>RYepoL zc^JyaF(j@t;IHo?&3Bs{kd-*EMBc`k4xCXNeRQ+GI*}`WC{Q88%Sh?Lv-&pn#wNYT z!Xq%CCGm)%>))!pekWb~uOex^CKq%w>ZnMdcT8~8Q!lzgZ%Xbfo?K1L_qy1UuVB=& z>c)!OEz93CtyKln6ns|z;J*c|E>mHd*=XymlX|>XpqZJ**p%r>>%zL`Cp$U6Q`)m( zRkZ+*GS>*STMceXfobJ!?P0fRsg1XOI`o0J<}wP))t^_t5qJ3?Zi!oNR(BoK6I(K7 z4CqNUSepUQ;eC$tf|gnc6Vi*e*0u<8d1JRqzl9>I_bRu;*nKS~v#lQ`KutHb%I1SK z*!YlILiVg+EWO39?Z=nGy!se^%=qF5)+f!|%eMPO3Jp!Qx?ou(-={d@An1cel7?<) z{ZY5HcU)W%pxXya$1WN)Xmi2Y{fT`JC$>R%rXBOusnjxwv{8l7m|Qw-Fm7dxeT(%q z#e~dnQjbjC3y^rAnxD92H3{7tqRMn@#~qIaOx3ZPc44}tv=h>N4VdsVnh^1hdA)(e zwu)C=uv!sHOIX&&mdbQdc*V7#rtmq|QLwbg;28#N{H>$a7pc){RuxI0$Oe5aUX&+y z+nkrlG}fP{aE`Gr9z3gA_oT%r0fAlbnOT2+xPIp4YCUVVgH(t_=S5N?^(Z|}(N1+f zJFdrGRc#~5dIrAxSxk>shG#0~H9zap!(Tqb3J+m=&0c*wu7ia%7tYjg(+f$` zt;Flb>)1Qh{H?z@^U-O$^_wiURpY?^ujUYqauyBTmhJM4m~)2JPicg=^QaugU;{!mb)Ehez7 z-;-7tBb>`<1gBsR6?&vgAPJMl-zJgTI#VER1cHoRa12*^)qTM?LgJlKxi4XQxRdGZ zLDiqVLtEPm9Dznci5tG=e{Y2_z)96q9L!x!;()e|2#om>;Q^u+V-GK-`Tvx!AuS+B-}>ewAVH=}Catg>=tw#SI; zuQyl!0$q92B8xxr2#+Z+geIif%*(Ivtkr_slP+a25x(jz+m!9~ye6gHyDXIU$Tj3? z$iCo`J-_6&GPTxOFQ$FqqGtBImC4*R(#mmXAa5vmW#Kc7DZbmw?f5TpB zi0OqbyWeQ_212%&j3MO*UTlbOvx1*~9aYD=yiP*HNf1|a+>*nf_QG|?x+>xB6t4FO zcS}(3mIsZ|?G(zTEK7|YZAJ#v^nyC$vF`YRg|p&BHd24~G!sAXvha+w5o&qycQ)Vd zZY`R7@f>8tlQ;^^%M^z9WbTQ@JKiN--dY&(X&V4{sKSo6!XS}rAF?E zLh61Vaxh%P7kyPleDn7|7J}4wtF%lOC`MxwkvnXNz0VwK%#Pr*NtoC}l%e6@y+B>rCDZ*<@8rJfX zrd)4!^<<_hvs+fu5sj1lHGBONcrm=aF+#0tmRz&nqtQ+^E@FDb0f(dfG=}ftg$Yvq z6IR~yVOlX+a43CGm9yMMcaF4$5x-F@1j&4JX17x~W$x4F(lfcCSY#e&XX#^)gshY# z)RBjKd@tIzv$U8At88Dt5;Xy@mXUrlhgw7lkL~3l2Pa9_W&)5gY|aDUwR%mv8RJ_R z3yA!A<11WM5(1<4VIx=(6=HRXcFqsJuTF0sUuI6<0$&>u}bu>tygP!xZu1)+q>3S?Lt3hdqL9S!7(}g@>Lp3Fip6QMT47#@< z->c`W{**`3x3-|{@ww}1P)Nhjb*6C7Fp8JIbmfiu>K{Tjxt>4R;_n&`R$Vk1I`%D^ z74*4KCP(>0qFBqTy>`rBBevXqcU;d7qkWt4AJe)dCfQ0O#Q(yj_Br_#RW}KM8WHxZ(J2$>ZTL$v^GJ2jCQG5>petD@5OV^tpXhbAOM#! zJ&Xetvy#JAn#pBw!0&$-6Z&RfHx>G*Jg@tLJn?O_{1Wvu#--<0HsZ1?j`#LEb{Xm> zZQ~5=-o4}BZ?XM@x-nq5-cCc1%J6mNtcEfp1W7OH{HBiJRn#;G+|H=Yeoz+{*$$+A zr9~?0)XOl7q}#?k&2nPN{3!~}bvgTYjuz@DG*r0hWWW2QsxE}0AgA<*w+&0D^W1uy zpng%X+n-T`;A(2?GSsdlsfFvb6*vN(+0%TS@b|EtrFW$Cn71n3wp59j=CBE(w^tQK zMz}M3$h&2gmA138>owHPN^ngh2HF;js*&7RrK9|#*c!NBwW|*S4pW-rJP{MhoN-Qf z%^#U!J92(DRu#bbMVa0+@vu!#E8x=pCn)0$i|_J&j0=isy$)8AEwq~@5Xe$}7M4$qs3wM6gR->KH#lhCb=H6u`vA5N+RV$gVGz`2G z%7zbD={9=L`B4%t_#(o@>ch2MIZaITHwC5jGA?=^L2%|@t3-0_+CSOc=~UTWj~0%v z^tM?Y-OkN?@}xZmUAq8A!{SI+*=1Ro#kDpsAu;hOu!lbBskTP)17)HEF`@ z;&##-!QwJ?w^~;-c2$YytHIYRvAxrr%;eTJbdSkYz$GzulyW!RfKW7m@;T=B1!dMK-Yvni~Ugm#xK3;Y%)_Se41QlI%j zm%G8L*b=dHFIv%rkXlo1LxLVOX3{zK@-t)sqx7`ZPrIVdKqyvqLm1yTgh_=_$1E_z zmiRm3>z~&M^BW&$3V*50@&`p`vQg(GpCV2%GI^C0t>(+et|;elq$<3*7fFgUL%B~f z%8^Bc9L9orm)CslMJh2EB+jAg7sfAwv_D}2zMW|4!3Sp*Wfgj|IpUVR0f+h8*hCx; zg(*Y%*0w&k&RxrCyNuueNU9Q`JqVZA{rx9b`a zvKG}U0UxahGY&nn@2DFp3M)QHJtDzHh*$DZxJo*7-!LibVD<-HBBEL|fNLabe>Fd0 z@;**NiQSQ4ORl1`-(O3=+_V?1z&EItANCxHu|{1r zfR+0m@uL%)(vvLnu5T~diZ3>5(>ZrpfDoL;xrRsz7_yy%?;5pVf@NoG`_w}cJC+AM zHynV>Go-IW#S{m30lAk{;6ya!cFMCu7naK)Ec?8bXg+D|)QaP&S^#*e>%Vrbok5EbX#*^n2?z zWP?(miGLDb7z!>#!fKr5Y7{D^|2E$hB``7=ziVs1@Xp}D@BWqMct=yU2Wqres5JKK zyQzqg?QUV#(;WVu-SfTsmrnndGfg)mmu}_kU-t}o*tb^>T*O!troH6uns(eNmt$tV zkpbzisH^=NufB@a^sy=m#Xn3QxB%ls{jWFtIiL$8UI$4|H3&}&NG@rRhKhgu%zb{toHiD=@i zOUzCn)Q!_9$;j!}7{}y_C8?hZXpdIqOOViH5S#)Ki~@ zx`%}@b*70mLfa2g{6p8Bt3<-v!zy!09%=fN&|qpNcv=oDxrjr?3F&p1SLKDOf1 zC>wEDa?SZ8KTQ4fXZSU=t^EV&W^+O( z1kX>{^efSS4f(f+Msci;pVB;O4`)Lukaxc;{a#jTH@mg&yX?La{avEx-L>YwU-VBb z6-`Z2&p#p7B?spjad>Q-R7iJ#I!GwcfViq!N=xCnv`Xy3^~3iQlX>5 zT)zY`_9%4+2*huMh<_5bO?bt4>P%&UOfy@7_WLs9X?i1aGqawhuE5$Gp)mm{T|1sh znmntckGnu!&(bqCK8PipNnI`h5)zrC!&H6yGlYLvTpJ4J{sGNiseFNs$C=>#5qj&Q z$8=UllX!STQ}6Xf2y$3Grz~w!wI%;Evj0k_Je~BDFL&9XkI2GdfyQJ(_Y8RlHc(y^ zEyc*K8eW}jQx)K0iMHzfd>9Q}J#;0XH}@jfiC55J1=a5S{Y5%qI}_7Yik*aiTW-ap5i8BdQ=uhxdzXcrUgiu6bmXo6Niojvk272O+q5ced2 z^J6+g;#vJm$zW*(pVGo@q*zVjpA{NM_#=LAFmx*!QeG75yjWP?H|9|qme$Z-;n#7|(*T&fe*5lVaG(;385;4*j@e?qMSiicvyJas;$PFJ0w)3|Dkq)T z9jV5+F&*(y>VJMo<0mq#T-X8i=KM1+tP0koipOPIhjz5V7PFd97rX?%;pVEYO-V?VgBxZ7^S>6+@Zi3$U@MD=L=c z6Lvr$r+qKydX*sN%)_fOV!Nx^tH*``m4XV((lODTEqaMnfjp>w{{D+CPboN99lvS# zTN=>YI|yScY62SKp-d_=_vznS!Y$+ZcnjP|@q_RqyqAFXpg9*L2gV;V3RJiX|6V8A z^lfO6s>#_5N*^V$3S{v-~i9$pLWmr zpt$Vc|KcObV;F0lXel0%f}G9~2k~TqE(!U<11Sa%M$M^p%|2n|#lC@zk9qHB>xfRk zlqK@g@j`#mpm#Xy#n4XW{2!CPpw&E_`}4HWS5l8l&pLZ>|B#2C6(?`yX*RV#A-wSu zyy62bq9St}>Y`mLZr$D_xc(yTK5d7wAfn8n36euvJw=*cfkbQ-F`Z2ns}Z@J+sMN8 zVSVRlPpQIVDZb;DpNK0Wq1GhRInht{yR|EsdzuWQ3d^lL?{{=aUQYicX9n_n&d5%g zZ`#b=-Ci>Ym~5shrQPRj)gEo5NFQR;N=CXskat$Nf0k0tw(Hryh)!SX`kPhH7U$Vp z0UhPcOK-$0{j(nmrY64>sTNAKws=lmHIZE_a8tdYpO`N$!N(4uwxr0-k)v|saM~Nb z*#wI)u@*89GDUKqV1|U($CQBLth_59`Q!vV6hoP_?$$!9I+jnI=VMD4A# zD%&@pVZE*2;zG&Dt{galafWB0E(9;Y%EEoOVI7P2xp=*F*4-!T&_9@)7Nx>E`e#J!}b{a zuZz2CC?o+XN@QGw{yVeA>d-Lk_QfJU<;-Qi#prEDU_!*3zOA*iuX4IXsTDa1$%lza zC3fvwCnaFS79Mpwy-9g#y#2e>7z|+!PE=i8u_MqmFLZ@U{ljO$8+zlhMN4RGV#?d^ zfEfbQOYc#F(+#gi7w)af_ePr@UP5MQjas990$^IutZgao)Rlzx0B$Ae#?1)xclC2c zz9Q~6RgEf1Y8jnj3phZ5C|>Uii7d`(hD0J|7ZlFgFB`nT`0r>oQ$IHHyYITAh; zr7Y)MSFJq2X>_3KLBCkzUtm5vU>u3A@@(8H|53N5o7^aI+6qY9fg^iGn2!K2J)gWzh@uK#^e5fpe>iIGbWtZzPKTY>nb%hnEA{YYm>QNI(AA zvTmDj^dojEw}nZrB!qG3n7%2gL0Kg8=woT&x@PPdhb5>!eY;8TSfN$=oY!bNU~r27#&&4Pm&sEZXw_+0(2 zZTm)972Or^PDKK-?<0ju;Sm5F58j- z?asAO3uT0w$41M2vx;4h_TYBLae4*cH67e{bD4ce6I4T)Wm_$DY%qgu--|@bP5c>$ zD`7;FwW0p7%90i{2esiWQjWMiG$GBs&YyLQ0ucqX@D{}{ux?@$9#&TXq*!kuxI4&= zr{&dM-9LRUKzVlRbKzNK@kja}j_qj(;;-{d0HzcnXq&+KmcnJ)+gHo(rJ0BU z*dQnLCIm&9gGCx`3kO|Skn01&a`65htSiQZrE-FoR zW0mj@7i==rv^p}W%+#Jp;VHQFKs@YG$>^*h<6-s4$qj|VqCG0KlNJr+^DI6^whDDO zJGE`!(XS!(*IW(;vgZ3Ps{F@>$f-l5^E}+_>bb7LNVh4!{b~%*t(Mq!0;Gz+0~d9J zKyd%W+>ukXCzD6nUtQ^}gO<;Y`T=dcb!s_f#r`*$7Q)UL$tg|=nd zi_6M*^0MNs4H%*Q$&&N@TgoSpiX9 z0lYujL6+$oy@K9$;*AP|^{Km~{`3}M9Z!Jjn257AcR-oRTNL*-RXF4CalA|SR$DuR z#I|-e=BqixVKi6$)T$|vL!qU50XM`uHluieyrh2xH{Kek3E)B-WYV+)^(!ylf{`sK zWEDVq3@fqqke<{=m&ro`IxHo^YjW~MX0QbQ9`>ln7pcE`DNn|iTRBNDjmxd_<_1Q*o5YhXQhj=*x8n2= zl@-&;VP3w&ywcKTsBx2}W}cg`fqF?J_)^?AJ7yTughXrrg<{D&(0tJijaH82eV5x3 zqv9_eQJKqfLK7dq>hYCf`I^U~HQTizR;V?>cHQ7M!sT|&w`?3}!Uc}_JLI@0aMRM} zAHM_`^P8FrL^_guUqA@(u*z2+BQ!?~D{)8gJXEb@@deTJ514Ihi~^d|N**(R0hY=*9b0P(wq;y?S@C{z=)UOAQF% zJU1u7R~{Gc+Xj<{XnBUrrlOpU$n$FjYw>?3k$Jd1P&rq+K84p@S_VmI_mIjBn|6=px=4926JED#I_t{UE zb6w|wWi#kJ{5S~$A+2JG`NFyWJqbm$Q5|IHI(glj+3_;i0A!GCu#g&x(Ta$fS z6R3N<${E4SU7WKSa=To)%TAiDYPyDZ>UAL+DeI&cSk z9gf=3?xO30HSu4U3OlUC^+JYm54*L0R{^84^xL#*h3#D^iZ3Ehe9A35>4p;|>kZ%k z3$Q`A;&Z@i%@7I+d}X*K>_2lhaAe=*yS@DIjgZ^3a0O4#?`0-&?xt9MjM>#~A=-)z zU_ji^A!v-$M{bO$TvZ-eznrSG6h2FAJ*10pF*;~cO@Qt>1CD_c?N4$DW-HHa87A5x zRhBN`W3S6b5jAZ$WTJ53aWjf+mUsuLCiZ!;mb~hDSp|?`w(Gh2$@bT;5{@Rfw#<_% zrHChiLIkF@QzFox&=+S$x0OKSnPsD;twJYTN*S?hE)B}LzL7}BY%F9ACi0s09un$` zZ;|AmsC}Ryp>&V6$sK1^^++(xeh|(@81FnyDHmM2sKj{USHz&ZMmV7M<%OrM)uPg; zBCh8x_-Cj9Xt;{>GyQgm7`@Mn8R;^2A^p?-Xn|T-47X}AjRSt}wQ#dLDp;;5_->@P zPi|rCUdW>nPLiOz^Nr&7X^m9j#Kt$j2XN`aw_>l)W#0D0No?2~l=s3*8WBFRMgX&? z8j;NH4?#HsBAMsz8@Tw34x6L!jBkftLzmD*t9Y)PT6`(JghwfGZ?QLL518{vzyyW;B|H+FmF%GvB6I&-D3eScr_YX- zIog&a^>#vg?|=9iv4@FLh2ieF=MUqy@_xZwRTXSb1qZ{ge?r_lWK6?N|3mr$UZ{}e zp7$TfXB>wUEa%s)qR|!Redtgbk4Lxq@;Dyu%Q~Vzi)>?FrZu@qJEi?-EM676Fe(gY zxc?EI@_qUbJFr0>Qb`yiIIR7NaH*lGY(h1Jd8sr%p%^=j>K4cC*~f}fdl+#DRf*s; zKE`*{NwfEQj*3_Rmucyt{pmtL0ND5buw($BiGPw9R8qVSTv+i~#`(}2j2W=(Ih`-o zb#;Y9-lp-d31G$kB~bqMUQq2SCHalOTjP9!aZc49Q$jwT)u7S^AmY#yu1Cr1c9 zEW~_+iS;$8Xz3IhH4{o^ z*ZcjW6^1z7X1@`1+IVgZ5swx+eVnTF$_32~dSi(~jQNMJjQz&!B`jYWU`FUT+bMm) zxh&0`DXJ;1;&+nQa3^+HdQR@4qI0mCy-Bxx1(3@CXxsxRTkx2|7u$JweW3gm6%tNpIAL0rrO&!-O#h)w|Z z-8V6Cdxen|e{qs5z#F%V{I>?b>?^8O#e|7^Zv6oY=&|7M!jasG#0 zuSzgvxZwNVU1U)=nTIfsFIR29!pG#&o8;5(q}l|w-J$RMtL&#Aoiu%(u&7D84H*?H z@u%@`RG9Z$bu9M~^uwWD1|0ya$Q%?=obDkiX)I|3!Iz{G4&Z4}ED(0!h2Q|GhGJK_*R%%1os9k*hBgxYk1b`sE4~5(PaYgl8qRbiQ?8? z5jN+Kr4pO!GtdKgeY*{p)3 ztMaox-X=&_qqgE`9#_=o?;IqIme{l(z5n>f7BTzA-6DBPr+{DWS$~MOV|NrWHIqsF zFwS54Jdst&Kek+QRx+4$?T1hnBynq*tMWWA8#icRgmzt+_L`~60L;zDE4>@PtA-W- zJD4J3AgkZ~2lS#(O9tFh)v-38HY^~7g1?6s1wLrFnOQ~4w!!SHQtNd%2B(4}{V9_Z zoKng=6;PIOVyeBCD<4uR72k4>zwopvA*9qze%kLA5?PG6Wl0VZA~&TFz=kutd?3fD zf%{t4{MCly6v=T^6;qC0w$g{@l4C-tl70_HAEqQ`CWH53CbT{})6mg0GM`ahyIwe| zY^|H!eN<9QO$aUv%ds-I$b9;W?j^A0C!zjx4aH{Zm>z{cAvjb6gpp0sF_9_7t0n14fke)5NmI)t0+L}(CWXd{4ItGM7 zKRy0;RN~eHlWA)xl=I6%PbO=nSIWz-0m6Czp!h)Mc)X@Z!ZY;TZnP;K2}9F|I#ZR& z=gphvk$M@G%80VfCq?~MXoqmHFWOf24`6w;k1h*!V%y&zAtI*Kg2L_cY$k&_ap^JK`8y6_uAHC8cU#z6u@A z@<_V?}?U;M@s@!T|oPguhHiq4FN-K9TU{Un4$&IBco*nq)ja))tWL) zKrPsEHD!CDUAg3R3w3;afjOk1&E@Qxwq+d{cxuqaH?pG_1AvT!wPFTsxr0t_)>29fc@d&4lq&AK&g8F_;sf& zd)_nfW%8$WL3@)`hyG1k>Q?w@w)zPI>*L^)sWOYxawyaX`f7V_PC;8cDS%82%tUfh zG63-882tU{8%lTR0()ut68-SSbV59VQZV~}>?@_mjq%yD2Pp~6nF;bCZ;Mqu!#GMX zo<#}uF=Z|R{~#P=0(?n+OzJPQ$FC?k$4DcH_<}zF9%;vq$j0~Q%+k!ko8seZ?HYbR z!#9#gq8?dgoUrgcl84I2!s|1U`-XFR4r+`8^6|zF58${Izp@-XA zs~;bDJ6~YFNNI`;UQ1vu>UYN%#tdETX_O>iq@P?O< zx2L`mXgTul#eNC^1TRV&0cHJrzvML6vKd47KR!s_uiEDV6l$v?`HXXNZ3%RLTh+4vbdC)X6@YWZ#)OB&Q9+W){{e%mhSbi$&-avCMd1)`mF8eQ=~AN~GdwYwU< z2Mi!r?!kp0mdwm}8Av&XFpwgt4*Hs;)Vt$v0N9T~ zw|$^oDA*Ved>T*X$h}6GAWuz#S9q9GrtSIB>h6_Dk8rU1vH-jew#VK)uIts~+*o>} z-}n@`v4gSy^yr4Z^8vdGXkqA?V)tK!O4)WL%Rh(Lyj!-=d`IjngoLHJd1iEO|CA$f zW;|6&j;s>aP+<}2PAKXO{AUH}J#g83e9qvzgLWOyw;*xVNzpb!TJ|~U2J`Y=7rK(r zPQ98_jRoQ&Tj*zv0mlh@mX-qI{L{gl%}G4tOMNGh!IQ?GGk zOQehvg=Kv?2KxkQ2l%wiF?rbageX#u=WI7r!qmFf2eApc0l7y*g}Ly@kUYQNOq=cP z*{|BqezTfD+*)`DC103VIWLoSy!8-%ll1u&|9&*oM_dHBWlXVJBaUbn`u;ojq3?J% zAk+rhEF{?NVbZ1UGh%70VnhrJ*W8pQKhSCOhy{c~o4=~Jr$mF_im9qLjOXVNCfPuR zqNEqYBqZwcvUKQL7aWnwbTmFMjz!4i>pZrZI7_N+RYa2!LjO)Ew6cvVO$68A2v zRX8T5gopO-%zHRRq|aglwhK>Cd--z2M{_zPpEoVHI}{E3k)Wv15_NqH5n1v1x%D|0 z6-R@k$qA~eeH&f>If#{&?>ET!UtG=GRCl2*@2o`@tI@Dg_P6on>sJ>)gfqN{eKS*l z7vPl0gQGsV0uX%ypWsv8AKylEV&&hMPh(h+`A|s&*N`{qZoL1E!34d7^hng8wJoAT zG6jeK9IUwofSlTBmw(G==HF20Hht%1#t>(H+S#sf;mp}wa{Ms<_%sjajI2F~N^J*gDNz41v!8+Y^!-^`$bA`)yLFnd7nfnt$Cdaod%^D7h!%r5nGM{jtWjA2@Mx=%xGjxI@g&x*P z5S)Gs)X}}GT~O-K#m@Y^ib0=@%I4C&e*7p@Hq?WBM!}{&VELPe zX8Z34Ve8{A?S#>`Fq;YB=&rx4?M>31xkvC4pCZVUPDeh+k;S?9?4*14DOjiWdasfK!!d9(|>x-XKTjI;XF zgLdG|m{aaxK8Vd6*!Xa&(JB9H=2;N5Qj?hqEsed?g?|SR)!Ycp&WFfp@I)@nMC0NECNU`ggw@2~!M!S&s;)7#s{q?+vp8^#oNI{%(c_0-YC9fQU(g?^9 z@w+Prz1_9<#wH8-C??lr=`i`*pzQD^5>ySeGDUlx1#cBvu}o zvQA_qTgXZr<`xFz=aR%5JYihY<@dFI=D+f5)n1(yVPQRhp0|BuzYP??TAf(VPxWaf zSakfDNA1w+|6q|Y&IWILcziO7_vyuUH~v?-!jdAC#EHq99G+S}6#pe_$!9^93Q6!u z14^P`N2pW{yZovJn=X!{Y;KO#w48YB3S2&zn9cI^OR?_&wbZ&;4nYmmFK~ z;&b-XXw5>n=gDGdPKh%)?}&|x16=BGeA0rxJRq0Qxq7M>7TYn6J4>GXgXh}i4^K*c zk^(XQOV&K2bw?de6dBQ{P50o>W>X)8z+lhvYtubt2C@-6_Qf=0cI=nugkZ2Xf|l0s zY2{p#Q{7xey#ldV0|B=vHUWY2yvB(*LT*?K?LsaiIPPqaLM)0&uzEP1^AF(>+Vm(s z!He%ti^^9ib~^dU-n4(llYu2&{DXWZc<}vO`d8t)qmQ3zHVOQwbR&35Eo5eW zCZ$F3jMsanTK=Qhjl`PBKLa7v_Os0VeWtMBbo?_z-}N7zhZKkT01z{nQ=o zS6wGw(-hLw%hknT!34!m{5B)G5r>kx?y?ZN7-kgYIk;lYf9Q%!QT}ixp;!`pCkT4aN(X$;p zfzXFp{aq$Pe4e>JkR>uQCstR3FYi3F4HK)SlI2Zr8edhnJ&db=u$=|2Q&5Uretc~a z$6=HC82exOM=v(~*eNA_Cz#tn;2SF+HfBoXo$+*b!L?(e-OQ}Z4q{H)NaD&bi+fGF zxL`bk>yhU;gt2&hm4!Y@cF>@7_45zSD^WfE$rU>S6U}A$;Dedw%*Baxx~J(xQ`q2B z$qY`xHVzmlH12vfy3Ri4!!S*Sy5>#cI}v89Vl8y71}+ubUotS^EN>{?`5k4BH-FS4 zCydIau}CG6sK!t1n?UPBUD&X2v2Yk3C&T%itiPLk);w+{x=yBWB-^5!ZN ze3cvN`X?xK*`8_eDL0DT=7Hihpp-d`oJw@;0ks!p`k9ZfkTbwwhb9}h_ z0hpYvPs1NE@WTWL`juvAHvvT+9`U0|I-e+UO4Axno6z%@P}&Nb1+q6wlA0m9T)b4O zsZ-5wMmzJ?F9?E(6h(O2C<7lX>Myd5&^K zxiqU`hm5M}j$f`I_=}T_ydXVJ!3b-F73tKMQt|CyD@aH0Q&S?2+^_Wi4hT0p%4qT< z0lnn+VyZlaU-jsQmv63v$_3wxGsFnvmRAMEd)sP0q&{5PQi|*N82nnKv}ctaFHvWzqlAqa>@C1hh5fyy-O&^a_{Zs2EkuhB!KC7O!q?ETwSj!uo=TYG*4YuH}?d-?*~4y5Rd1! z_bdCGnHX>!!f|2c>orTYH-Y+}vM%4b`%HOu4~rXcfM7EG1aRFPUl`2sy}pxVn5-d= zM0f|vRHKYhVFXYnLNS&w;Cd~7vS6oR2kZ5*;jNo?6~PwDZ)X4y4BIQ(+CMVDcWs34 z_9i4)B!K}gV6U??KLG=bHOew^|W0|^0Ci2)Z#o(p;l4JtG_ z@Iz}^mcF3G33f{X{b9~xbuun@7M2y459HX|S~VL#$dqh1Cn~%H;RsPCs4xmGtY?G> zio3SYvc>k*75l|6@<6vyI;_wn%4&oc-8|29DbM}#9BJ!&-kJu@qWxRrh_7F$6!&*Vu!rboCk3Mf91-3NEKek$W~o{c){5odZ<{TT?Kv?6hLBEpOEG}H zI4Zm|VEz^mEaNrAib7rlwXn|3GV8YUhQBa(K)_B&LZL{;_9?>fg_?TpwT~rLxOq{P zd~FZN7I2VLQ?H){t`y)<}B9m$T&qQAz~uLojfrW zqN1E<;Yv}yt2s`oY0we@S0N$bs#1m$Rwxof9Ee~kRd7Wp1tKW%KE*4_)@IleO(Xe& z0KHKNy*gJv4@3%o@0bJH6!J#sQY8hXMR-#okJ7G?6(NbxBffpO153^dodz-pJ=W4q zh@9kU*9^Hu=gWQ>*E?^CPEh4;lzZ!D4(|8fmk@Z>!e<5UtgDjEdt07>fPqlGOvkC^ zm#X}B(JcAp-j-)qR4>zUVz~!+V9`t#4OPE$AJIxj`K^URjdE(;Z29|8^}Qo%mgor> z7NFczS0%q5uJc^kprdojm&J0^f+~4)xX!aJd!$GPz@jRypSO%MgkRS*=*)#x@_2ua zyYE6t&0nswJ&(sjAsTAx^^}D(w?B#hZYIN5ZBfnhpKP;Dt*6C%~QX#@3ZbKdHM2sy~@IZM1p64llHK<0Ykt&SAB0<&AHck z89&GY7+7TiRfes)YQVwG-B|!D7 zLQMlX>a`1{9iaoI2S{S*P^BB_5$G179ZQdeq(CR)SFK0ru?}rELyyUm+}6<7*~!(3 z1jjqV!&g15ANc7ufg1q_A2>-9`y>Bb?~Yi$10P1Pfg zd+K*Y`s4}@2pA}LerDl&^TPiFj1D5!U6uAlv*hp{y+3EM#>&b#LM?=I4Mt&8P0~xV~4h+8Wqh~(6Hp7?RvUVQ80MdaCw}60MGGXQ4lXyI)E+3Gc zBs$#@B4CyJg)`-mUA4XPAswH0neG{m63a1anBu?~RZ10NB7_RbAj0@Mkg*C!`-%_n z08b&2D6FCV>U3%Z&qCfP8TAX)wF8YPFC%=qdWpWcXtvxo;4dd2V31t*tBqf;t{D9b z$smfK*=m4$(wBxsuz-L*bmoMXk_kL<^{wSKGio*ql&;NewaNDvBLqR|0ecl|9Ogfg zd#uLD2`JGVY*{h)ck1;FONL3jfc=DT{P?*mbC&msA7r=vP1nu`)Y_qxrz=p ze-A0RpN_zCnix(?B=|*5gKp^h*ceKNQPhCF%d_P?d3=98F{O||9WIFGxnN$sT7?(A zb0UFXO+de?UaB<$A5*AWaIUlfT>4ub;Y2x398LtLi7+0^D3lQeU42yiVyZ5RgWx+X zh6?M%-c3|tB2z&{@l^2eeHC-oPhyfOBzg{^lmPKQqGj-HsErslC^U-tkH7{MqDFaW zmmg4QSLJJ6o&2oe;~5aJ&!E1kt6vl@r*flQk%KF0>Qz6}xp~zOFC4Mc<1$uwqsyTp zY^jJSVH22^1NIKS33)&^2N4)+;X4?<^Sy6B`qwXg|H5IDFW|tTq?GT8a;7S0ESe>o zFI}vYoKoInlw$>^DNImhv_Kg`ktz|vkC|Eve(J=&v4Fk0Fu?+OQF;(M)UpY~DuI{s zmOnef(>u!fvMbcmTJR?x5CTb0`AGFm7rmQFlTI7VxdVokPGD4j8>{ad^S)4?mYSu? zr+eDh|L7w-%o!gL@HW;?=f8n7tZ-^jXeD4@=hI6xlDEXuA&OBN*-4R%w;>pX$!hpR zO}%nOKHvJYa|T;aGhnYEY(N>;ucm^daB^ZTnL>pPU=t<#7Q4yM^#3%7p&5HZakKd9g5m=dW*F|I*DD_4n|A zfFZ)qGdhsXb&)8wHT7Bx=(XML>u>pJus07FdTN&G`$VZz<@-BJ=v`Z@X5&eerVXxy zDIrJ57>WfVo)UM2sI|mYh#8>__<{;nl(jYW`W=K4wS^)TfZ*^$8a zVJZg5g70sTFC;?i<3p>$_5Kr*>No9HB_~3=3ONH^R!NJHLRg2A2ig#FKzDEP3bk~q z|5}F#S%IX1WZoewdD_#K{N1yqb2z^L1A&W{XhIDS0nL%~+B25R5E&8&g6gIEei0S}-L7!zf|>HlQ1rVq z<}KHw)MJS%PjzzFs$zuk~jTDts9DE$5xLHIgA9U|-?E2YKkCuYBu) zOKNAM96zW&lz)lvtimRRO(LupkF{!e(|z!oZ)FBo;AYgEGbae2>8*h*} z>?6gSkDc)~5w1ij8elgHbPJ?Z=mt7b+JRPuW`rgKjab%+utsvMT5zuP4E?7G=*#>i zdZ=f39C*XYaY3&`dBETp$oDyKsotW(r$u?JZYF0S(y!=A74bOnM8o(U7GVzm;?to%6Brw_U40S6dOP4LV!0O3!q&`2gj4Z;^uMiuHl z>{>}BaNX@P?s{tlCVm`Kte4g3JHWVfrLU45JxCODHb8FN-JvH$~q!op3%&$jcGSCK27I zf0}?@@!*4?deP-e_5Z1G>~Nnhl+P0K{P7d+eV+IK!d@2F%Ms3J2zj|JZNr84w;q=% zw0ryU{&ATt{YSGs7!4Be?6>^>_m=MN?+E;S6(FjK&Ou{lwgwZ0Dt0jR@gr8s_q~NNb(`u*p zMFkL4EUE@EidrQjLKY#dmZbQFlbXfQ2yF5!jSA~N^R7u|ZoPN5W0Y2csqp&`yS*lY-`1qjv z5&nwh84Q02=V<6Hjuq&<0|rdN4kM}`LRD&(Q=`gvMA@2QryoVHL`bV|kKQDPb=Kow z0xyZn-@-00{^WG&9*lUGH0Wp-j#1@UBfLW_QxGZ(PTD0#iKq|)41&jlW6i;ad{Bf zdA7;z;jfun1fI9TAJpSdp%8yvaF%ooW-jcAm-D%Qza8-FDi@`?7}4F#=*}j}yIUC1 z)l5ZqGZoz}RCKpclG>$NF zD;mMZ^6@m4j$>o#I2tP^&{#Hs&BY_p!gvdLIjk{w;_&r*u3>E3I{)BTUqx51dGqr7 zdu|Zns|rW9>q65ax?L4lCoqg<;l&Iq&g@|Zl*ZhNuuz)B-KGlx)WpjUH2g1 zK&Nm`Uh$y)Bq5Ge<(*bJUJXYJOhK8549;!hxIJ{Gp zNg|9IjLiYCs$9Qtmc)aYs)LY%FCuXK)eq~NDLBSB93>7@u}lQUpo|1c5sC_N5)o0X znw|R#h+-||MaU>51v-FDYI)NbR-(MD!m|sjcw;EyPUb(ZW3`9#Eu0A)1ylmX3ZVh} zn+Z9Ts~66cIsk?L3a*d6Kr%_@$)|bZtm;|!U-84XjKfK4`2Y^bh-I7#r3|b%P+!*m z&nGLdFWtN`@Jl&Z>2qK0PxI=fdc6q$Ey_i8v*cI9E#AIFkQ-}w$U0$qqQ&H#5IHwO z&Iyrq!sJ~4FBvH&?}W$}-pe^*lF?#vy=@Bb^@NN3|EDr+9yxJSI$q-8+g^89Puk1B ze(=$f^NPE>Ukd!J_aS=yq94%jm^f!x;SA$(g8H#ir3fYH;A{LAbu_>B!;g(VJh<)y z_A3ha_N#uck7cubOyGm69ELDbgg8p5P!xMGcqcsl;KEPUo-9a3 zav*uU>gfb}5QMD90bSWdjkl(1!@DS3eI- z24C-)Md(t<3v^nGXAB+c+kD&b{S4Ywu_zr1d4w*tZ@8uFx_k!*78jJ>}#(X36TkEz`b05JMXIw+hH~FE!6IZX$ z%50XKRrweUDEP+PX(BOI{~xs$>v?MPo_N_j`AiNkoh93oHR)uAY-d_C9Vxn7Qqr}t zhn`Joa+$!BF<@9|Z*TwjefQnx0aQ2WMJV48n6k?Q{lJ@6Rn{1xRDDP07!cWoqFhm| zLRN&d2tBHF3v{5gVQ5j3Hu zQa#NPegjnOZl?-rtcT;}Y&f0D#k<t<5=lytUaOFA}X5^bBZiMFO}S!-jqyk+gcqt^otG(IkV;&J9I)^JIJj~5aP9I}h? zm>1;*6`le{sZuGzXkb*~ukUddXvQz5u}Op`6$da6+c2JI-CQ~!&ZaykpSO{8ch>Q88qTEhp-d|8csUzOc4nP?)ck@{rPqydWT*eEhl3uK*BOl6TY*E+dTsYI?Mbb&HxT7`iW>dDLvnANG4nIE> zcmiPFBl=5q`S>7%+ulxZf)TYCYt`iQHk|Fr#k!%-(6ike(F z;^adSCl`u1UMS+^+=!D8M@&8xc04ESv|mU2!DW_y7OU8L z7*_p&&0Im()}Q8k48=fH!NDSfx*AmxLB(1XwQ4+19WU>>xs(^mq`XMFCl~MO z%)~odGb5YV^pv%(PmO9?)iY-8%RN(G|I4r#6$AEpJ}9TV+nTbaZB5y5rYER$6fj);P~eHnAJkbk z%>4{90rsvC6jk;0Liwy0OC_`M&X!Es<_*cwjc;^KdF}c3cf7E?b;QQi!QOiRV$1qu z-ctRxHQX??dPP+ypVx3Eosagkr$=mF*Il{hmCkp(uzb^rkKfnqc==$R8SoZ5%E!F$ z`Fol~l@oyDP!2%`WFJ$MX9~qDDnu#T&hZu{iJ?uDjVi3xJa34@KPCVNH zotZ>iQ>vnMU9w{1npEYwSCZq_{Ik2Fd3`3<(-GK(hk7d&RpSjjVFCuit%!`s9;xd^I09yv^qVIwd3EWpF852(>^hwwQ@>v%jn4^ z-DRWWp5qz-QLCb4J!9O#7LnTtYCt8Q!|`%nIMb7hcXwpUTGl5=Hm^xmu6wnsq4o2(LNpq;jKHL+O-_q`Pt^pS5l-YaN@n;cVJ7*29-ci513eIMtOmg`{NR zY|2Jb-8-E-)ENHy-t#J(CLWdOEFB%|EFTr`iI+#cP{rnGfka&+U$uF0=H+jiJXPqdF&|F6`( zx^K(Gik+tMhsRnf4~e!^PK}@R$NM(!$#r+z$noLwmi5`;K2J6rGb_%!W>-%#PT!CY@;8xWDPuKQ7>1{;;0xIow~c7Y!MrR^5Egi>5lW<;@$CmFr(=Klc|m zzCQNNmwJZsJloP)J|?tr{Nb^U;|?oQ$MAurb&bP$KJdrB=eTkZ`X6kub6mMZPsj;N z5GseDUo~DXU((r{nYik2trK7WOWWi({@O9|jTgE{Z&;ZY^>(=a{mkN)vy+JtvA6c- zuR&E1HO`g^-SIpdOKwh=wr%REXnwQ1V$<55(;xitnhC4_(XSYV{?Ju6I@Db{GSrnA z73wM-8A=vcgp-MiP)TP?_Wkt>hka}w47_sOX{FDe`ib!!6_v5}vN5sliZStI@rY+ zMG#c6mcCjH%~^QEPGh5bO3K~eUHbLI8Ydi?XdZuPqOE*fu@?$E0Af8g*6McG#RZ&v z&i?l$lOArIcvO7l(I=NRPCPQvIQbp!n}@zDt3stJC4(*)?r&HAY~V}QVYOSv+Mk^y z-=aV90s9c1> zO~bk`&4y!U{nU3B9rDUE`;31>XZe^=^O&j8P2&!Yw~w3KeLLQyC0xJDhvs2H>#8g2z-iw_naLI=oKgsvJsEX;*hn<7z|^v zOhgz5j0Yyro6yB418e}+qpSlORd~|~jVi43Jk}?>*l^#4G9)^VntDysU%RZ5MR4)` zNIikuZn>arWUQxuvH73AZ}T~+l5*d-NL3wc6#*+o`hMr4N+^@cMSD84MV+nbvbM&a zl8%=2S@(Z`dp=#3SAob0yYOqp0T?)9V5!*3)>hJzdh?oEo`tbys=Ix}K9Cy>snhFaB}Z z@8tpeE-H?^a@;AUuOD|>#rp9_C7Q<`nrN@6jA!Ge;aoWETE`Xjl?g+Ml|27mcaHo5 zK;Z)56GM82fIUvz$cf>`Nkqrz$&x=SiTp5vNSywvUW*-1y@ zPCgVhsiM-57Ydt9q{z)hqHf*|n{=!sWF6OJqD5{l6mhH*a99EU;2vb>!a7tY)=UycKQ zI3&FWybTpc)*SY(qL+?4edMYmrjOV(ep*R)>F8K0S{$~ah~v4AfQSkVbJ{-jl<(g$ zOFnlnUH1X|HqDiXME^1U>{0(bamMJzafg?6Cq~9{(V|e^2^lpGhz__O-T=vZS>Aug zdGc&&%kB3&6K-> zaT?HHQt?vf@6%_G_}lbz$G&;!@fDq=qvE+}aVYP)4#p4l0Ji2D7<#&_<SUrt4nV4?G^CCr*>KFshGWJWBbj(2 z1dxuGgseF9?uV@7N;VSr-;0)n)Cjpy)U}RlJlB=pJyAAVG}yv^y|(jil$;7#fh3Az z=s}q*Fj0jjl;5k85}_MkN7$uGUZKMX)++6NAAt@LJkQXn9=T|aZZCqh9v3Lo0!HDS zMKk4ZgOvR(%zZ>FU6=n*)XkE=?`^sE z6@uKL0Yl7|9H%>?x(2~?NL*&6(W38l^WpPDEDR!^ZHxEVIW-ksE!DET#DrygfR%$F07J8Lw%lI zv3JU}`2*%UlpBGR!Vg@yeZfrGWq`<44{LeO<$o3C2)uxBQ$EZC+pDm3S%Xd&GsE(k0s{6ha~7*poZxffCtVt~tM)d`X}6ytj}?xsNR%^KJSM3!9>Z9L z(O5+ma8&hS8Xla zpgHb$qMR?5ldWYMhA~)5LPbn8exhmxX<-k~AoI<%M<%J67ZN~bKsQxO|6AG!v7u`->xOb)b6JB!K_?pJVPJ~F=NDB`x2?RFG-y$Aj&LSQx$6?OI}TyBlnF#I#8FCA2_uvW zM641=C=mz?l&YW5K87D?8!kM?=trV^5mKt8@%O1&{Ci`MK*lQVgkjSYspOL^EMx7@|&|mb_0c`hj|=}4B8S4sE5QVezO68(_l za63xb&f2Nrnng3@)@@&(vshzgWgKB)2A1O#CWumrf6s}j5>aqPciXW)4fNpa+FI1t zK_?YD6*4GYB6K5UP&!oTF_2OJo|RT5Wg#PZ;u<3CcsLd&h-I{K8H+MOg;9mIS`iRY zOGE@$6i0pOckdGjibYjW5j^o7cXFx)haW>HN+-~&!bZokS`904czMDTycp=v_fKkT zHN5uUcpZODvrEz*?~EHxRKr=ovDQ*4hLT>r^ll}O_g5wsA%}lGbs}t3!|TRlr9!Jh z+m?CK($>58m=t1D?dfu`C4~$a1eg3)M~C9PBru{s?XBf#F`OiDCc-<#GFF8I6l^iO zIp)=OUH23+B6O?LsY0tGyeY~*@`h)#8~M}S7fX=XVjp3CyPBmM+!)@Y zFh=}!=71Af7lQAtDp@gfs$~;~bq>6ewlt)>cr?(z96Zcx&_h(Y8MvU3B&*-^kO&*< zs$_iM*XAtNaB(ryjNwEJ#|TV8nIghil!}5LVB2#jN=l(kgeG8(!Yjb5zy=2zLlM>t zrnu>q4LUlfJOOm(T&nIoQ(AY_cFtmrnHWbUqMWE6$5}X3U=%{BDhcuTdtv;&ol!vs zvsT$sSP$|7S%I__I>ge7p;;}B#;^h9O@&6sV|_kE>z?v6ng5)IoTjabInoAK!dnZW zIT>7a-(DC^EoHjRF33QU>Rat5Y6u&D57PHoDHL9P3jztJ${Kf+xQIHVY(GXgA7wg-rsTC_O6J-oT)@9IoVyp}Wuj zEy~ucheDT9I3^E{OQ~8$Tf<0!G8M*%FdmO_B8*We?IYWl7S57y5ArJ-6xH>5xd=@Q ztK^~KKG$VS^i<>UFntp;DIUI_yj7r4{e+jzC@o^xq_9aXEkJWdX}o*(zO}cgsn=<$ zEEgI6gwyILD$Jv#5jqq$8UOqGmxY%^cvT(NZEH`uq(O^ZkICXPL6iv!6GfS%mMO+C z*(&42*DHh4Xe_7QcDB4W+@ELOQoTTh=)#%u%i%uPzRuj`daUEI92hf%=YK> z7d(&IcbpygP7MjFGH)4|tMWh4uOxYWjwK7+vT&AM5B{F4q>Pb9eVh0eTRDt1!c>Jr zfXVE@CuE4QfCp^APg$H>Em&eVhnW>#AhcuG-CAriVEmKR}qx0LNBAXSSpEs=l4I z)ml0Q#ujXByYAG`BuXoOL5$wLrw6PDR->#ESgnRt)?>9%R(B>@x3B5vE^p9ttnwWU zS1g<%PY%a9F00pf3EYkHrA4#k{^2+W6!b-wdl616{O)h{{qgO*f?^8KWXtP2!XIs( z_=(v=I*@r*0mE}~j}QK+AM5LR4O*v`8Vvoj?<=Yh5m9E1Ls=R;UOy096{N-xu_18d=QGRgSOqT8LIp-|aSVMwsN~ zm|zU!5yqg5QK8&eDy%RQj!SmMrgH`CdXl&RXl|; zqP!b89_Tj8QY$P&*tnhb;W+&DVPE}d8fAkBD-{~?_qvU}{=9_PFzE?a?@6DI>Uv!z z{Vy(6C_~Gu2>-FDN|p}jTub!lV)!HjT{A1q#!%hgJ=u<^sn-f%nhJ*j(~RXX6^=$Z zw4k%j3w*S0raZ7a=Q-Gzvshy#amL~@Szv+{COdG1S`I}Rfs#Oo7ySKti>wR?^{>>t z_&$GaVpuJfXVmbR7@BRK!R%d{QNBDe%EJEmu+%Kon}KT!_N;-hS(MMz&GL&B1RPj= zcCp5~OE|`ZqY;inI09uH%9vhXZ3TDGX%ZES@3XoZ;VIxOv|n?!mxGyi?qm%Uuy^U5 zJB`DUDjcRTMTGI<$D>yi^oK?GzSCh5oSnsL_NA~F^ME`;21}}7&uIr*1R7O&Q(Rsb z;l;W$iNl|)(l1?!G2D0C47qSOWC%D2sa~ct#BvKz zDZ;$ED*5%^mg%5ERjzu3GEZ^xF%skm8AGu^#8cv1;*Oxm7{Vwe3NFI`XYb9!>niVi z-_P$|duvOwMh|$v#>QZ5Y=#h~kg+6yZIU!iTQ^N8T(BLdB;~g0Iq7*ynjYVK+BCVR z?P=4VCMCA%O)fn>&eRklY#=yu2$%o?8%O|y=UKBQ?Y-Cgy??xGNn5fkZ4I74-{;Yz zX=$yswby#r@BO{sp&sER8qIKtUM`dTzJlZ#O5mfVe3VI)p-)ec>ZZDq_3AbP53Q|N zUlhL118u3!$c#4c!*;3W#GuVN^0A{W)feSsrYOs`IBvjkt$Ah;cwkwqyp+J?d0zxN z%-HSWrzVDd#tAUT_txKJ*O&Rfm_P|qKOq%ZOyH|uiervEjn>C~a*V9UIVeg3%nBIY zh}Ohc=m{BLnp43GyL!s(V?*8>*WbI;elnJGn!p5xLwb+U&D(qhZ+BuLf!|zfM#WI! zcV$9J54Q*CFmXV}Q}X=td6hh|_IfL>+NARO(Z-?mH!&M~<9Tzv(eaT7)L4~cUV5EI zus|?VqOP}(GeXXPKNupc3B^EnctqMGVV}c$hia6Qh`;ysD?!mpVT%kyn>{Pnt}_T+dTZ_UFx&wJi0@qXalggN|u=K1Wpn{D@a z9;;lOR)Okmk7!D^$R~l16O6GQHgTVfrr|E4RZY4A$DaWoAT+GMj`+8>c79kYqADes zN?Z!OXvSCLm~Y*Cvu!_#FK+@9IAvJ9SvMwT4VRy2n<{0ssgo+0E12VBW=9d{ zc`@6>6d8>MbrLmZR9i5I%px);dg=;fMiEb5MzL$zcwM5{3B0RW$ncY0neXrQ4s)|Z3sm}5a4_6B=v|wsmkEdFW$kaJD0@KWxBA8-gs?x8+b9xG4k!GL(G!`5&I1C&~ zJ`Q6XA_#Pj07tzzB5^dT;K=NVBNKC|vlA;H)Y~yWZLo|WNUs1eqbPCb`en9mtjD;k zNx9ApQ+f&V!N_2iiAG=Ybz*KX8;%>_j|+Ms5rrnkj?D&py|J&Hke3x3RaIBZ|BdlU z;HMIQx?#EfXsoaEWa0KLs*HMA3;ZXHtrB-{SY}&JXWe7U9asbAxxhIT7jA5)7qBM9xi3feE1l?Q-lTW}6ew#2LPKUY4g%#`r5X?5Hb;cx#Dg|?iA+KQtrjW<*2C+hr zRFP1#xn83djyJ0v1RaF;xix)H4Vp^`K&^ylT&FoYQ{uWjMQ=Dfu|$0oaW0|}F-cH| zQ7@=(Lv?5x7R*6>UX!WASi4Kf*c{)@fQ{0l?OK?MK4VVQk!;Lq=TK#e^SOI*a|@>~U6Dwt!T zzY?W?JgQMry@pFYX0%Ei66|)4r!bmkXV^N?cX@qa)h1m7d;xJSp@tuRoG~6ke0U^; zxfL5#Q9GI0#4Hpnh~Pr+x!B-5jB^Oase@jv2`T*uu-A;8N{ob)p3Giv>>Df~dgUXU zZ$%yj3X$>tdzRV@<(_Z9{d`-sxhN3&yNsO6C8Ymus>v|h!L*`rk#k%u&rFHQ7KC%v z=BbnmYfc(N5Lj|6r)G7jK*=W`>HHwZ@F)b-Ifvw_Aem1P<{zboXIVyS#5*>`^oa^e z(VDEe^&y$B4ER~W#6WSuWEq!^$W#t6XcpX){J&ZU{$9}I!Z{odQ7!m&!LL~uE6X+0 z7;;25D82NswZfRVy=#Jl>LlV%wmJj zA}$$$h^$TGRvXYiGKVAP{c@~e2m=Ngk2-i%8l)Ft)XI}HM~)DZJPk3;IT{7kq(+dz zbhdn?ft<-0=pgn%v}sAr;w^;Fjpw*FaNKG`iGfiPR-0~DBAP zOdRG7k*wreHa@j}sr_|1$2rxwb+gXNi0==@DJct~|K!bhP9fBJhC&GYup!<9_M>#b z9Z&~&g=+`s6(2&l#t%!pW5aTLaZInFOsv|huj8p&zuew?Dvo!iV#P*9wUe0}6<9#T zyS(QQDc`g>t;hb^IldK#XZD+uI^`kMb^U*cBL3>0QUgFj|Dup(zC81R3k@#t#sY&&p^UJBK6v0I z#N!xy7+~0(X<*kIB^dr>VAW>*2jcxDff4&K{sY*gZoa$W1J*v=K2C&$5Ag+zRf9Ye zhr;vgm)YVWw~%bjW@f}N$2{jN!+VMO4WPE{ql8+s17p7#&qzEG8&A22mp8nJ9sT+Z zlC9j#PYtdeYJU>HyJ4AaOn=mSA0#0*67w zALX@EH9xy!v#yQcZzSFZ{9^qwJE3-GJg{<;9!vhOkK_2`@eJfh*PATnvRGUi!EZ5y z7U@KgXAcoCA%1D_Lo>FwwzBU*Eu6|Je zTgLC0(IwB9yyJh|yR>`*o;x2FZVF$d1}z2xJjUh6@{7 z`JndMi8u>GqX2jlpQ{poHQbuy>Ibz}j=NF6dB+K1Mgeim#D~7T+%}Km{DwsmaQt6@ zPXIZIJ2ou0e>oY)8i+fZwAeYG1sr0BIo9L&ZlOS3CSoRHhQv9}F;!xU84X_4n=vWr zIaG=yFm$AAc42-P19=lYGCBzSvZEdjM#hfV^8#XTzvX{-ieC4eUhh#n|mVJ2PTmODDV1@$7VA%~oZLEzGf) zC5Xkq5@0!D-D|jeGR8P;@aL_qtRKyow0e{7kXTpNdmDPg4){hP!^egS>Mq5ahgBcP zEF=lTaGnJii##l_grjP~fH`j>qolVeL(X&C8$HNi#YR=t*E7S5c@}uRvoOv_%mt? zdH!Z3HTdcW^_$-D^)g>?Oju92FUs@D34@)p3u`uMWK~b*-@R_1V)4v8&y?Z z!>mliVi^mZnCD@ZiE|K>anvSUJweAs2YrU4s1*FPQO!7f-q@FPs;#b2x6)P)5fxq#~cY z_q}%aXwGi}Z(Jljpu2(h0RQ2QKNv~x}`oOKNG^0wQ z(FMPgDxlI7wowvlVHUQPsB$FRrCPEOo>#@l*M(C(SvR7qS6>zaDw-3WMt5(Bg@Qq= z65fGX;1yW%dns)1T-YvlH0SbkjYVhnkq6XRD>t(#liv?z(hNLezVQ7RA&&wz} zX!FLak@$f#z8zKY^P$!&hckvZ$HsLx*@s5-qF#r%qe;^eFP{rshK0(rNRD|)AF;up zN}dW?*>&6SP%pQz3us2{RmAfc-^&$wx+miBXt-m;h5>{SfH~NN=3)XP$BK=bTvN}2 z$a8Hhu64%6IHo6t-4zKxV?>(MUi4kLo)9?QrC=WYvLZHTV;(9v4sE!}_KtMd!`&AW zk8D_OH;(w6CvZk$#YRo8nZhEM=UsAKV`70|8lGC`$VxaIHkKYv;uVwfHCi!t$n!&s zctEgYu-@fx7;=sSSUGF>6F95!kq6XRS;-F@FxOqt$*2b{=J5;!4GgAzq_l+HWS zm*V>PPU+kOzzmc6_DSL$0N@;vO8rVijU{V&$$C&JC%YCUoLxIk^HHt`MmcC92?y=f zR9J5?AF0Pc@^$Jx0HR$ATz9i%A0@gBiGp*1-z@0CC%TLh4z!H+D2!pf{sX>%uS)pS zBjH1zYOLC%3k5eg<0grB6W+TY0bh-C{D1#)y>$<>i{r5JAd09>+PJF=6Yts@ws3h6_s>lacU0J__2_a;^d0c#94LiTR6j{};xPQRhTA0jD zzg%-Tm7qLf-5(Ury?N-|xk{Kh{;(sT>$s&g48x}1ekKo+mMIj&{4XDXF47j^9heB$ zFS=fUo4SFBzndGdL1V2(yOLsPAUUa&Cm3PbFYyT%J5+)Yr`M9N_iVmwL2SW35d-1& znP2UHuz=)AT6>1<+`CwqgP@qbj~l0UQKeYBQ<@X`NX%qAnLmk~#dWMgTFlAQ_`4vX z-+q@)mh9d&@S(Vw?HWqW{_^&4x+Fij0A!1<@3n`PTQvQTFt!XYyQQ@?MXUhz$UN7; zn4QYr-YMOdz)si>6Z#&gKPdoo0nAYus2iA4HGl;rmAKeC8vqOJCBL~MabK-ywge(R zK|-7k>33Zm1Yy9=)A!ohprYR@c)y>aaN&&Dd8y!wb#K0S8two3j%wA3F~xk=Yy^!! zT#j53`@4v^K%fx0ioY1fzegQRl-H!G(W-3_t-Uu{Gx0NA-ox-$&``o4fkI;q&{5r& zvI915=XmcSOU)m?VwnLqp9eJ2e_ct#iH4K$LswR&z6Z#LqKEOEYghOuyuQGQV8($px{LmFq$h8~VAR&CG3?M~(-Yd>h{2ja2Q=Z*P04e15V zR*5J7_ieBqA|2-wy3+8q%Z0EvF_|z%x@s^7YoM?Qw0||H_EM0O4V{Clcz%h-Et);a z*z{5Y0bQ2(!e(O(3IDwHe}d>B$Z&9bPR#ozdVQ*=caWb8!vvr-HC_*s6J>rHdQZMR z6ff>gcopXC{zeQJYD{V}8Vi9PC{;8T@xp6#fG8ehgwafTzSn=*9})f>T0O+76#hT> ztB>D=RsQ2e9{FlYKY30kRaU^AB*O^h7kBO{NbOyfeQ z5zN)4pDuMEut0fKA&{pRiaJ!-o}8(&F`Elx!xqOzy_99+TfvVH7miqh2)~wE;Yc=C z;G|718Nn$V4zm!Me1UlL>NzOyVi)v)42n|nT5BiXM40zNUB>D?d3lgMxm_H@jkykU zSG+`tUeZo*IByQUEEA1%r{cwux6gNVI}0F3_X<7Vvb_}#X~E;pxT5_p}IF$dV4>xc_+tRsRzQL zK6*HG%=dXNfl`Wmw4DZ1c~*xOBP~jD;8cj0`J_)*@s-UEHnhWcY_T;`+)Z>Aa?#_) z+FkKhmX+S2j9Dm3utafCxtJrVk{)}>mCqH&p+gN9HcfoIflVBNQv{HO0oqY6sN7hb z>}g}u3hhyFLp}&35ov5mZ3chzT$wK9v!3>^?W^?kklH^v_ye5wg zPs>5l;@Q|AB~Mz{`4SnERaNLHv2%O#2dNKD>1>Pi-j{o7Xf zPcT9vWFHmGBE-Vo9? z00jAEd+QX^P)^^XCM%hSf>ZgTaPl!D`)@a(H|B#kdgO1`AyQV7&Zl^%`94S`@Zi;) z7jHq@3pRCOy30guj$Z&~!vY&Uu4=|?mh6b^jMIFlJlt}gmn;sp_cmO3WyWtRBf6N9 za!PRbb@_-ns4TK6n`L6|fYXbmyI#Aasy*k%B@Y4jDxWcl&GeMfZBs|>9MYq0CHP}U z@tkQZ8e_j;GCZ6_Zk9Q$t5-(gJU0{Q+gWXiZGpOWT=XY4H5AP0hvW|EPZ$X#C?H#$ zcH*_NeSys6QrF!Zn1nf$&b4oTVKgG-Y-oq3&0oa-hmd(Zhj76j_vHiAu7g#fLNLo@ zv{#?wir|%4nRx#~T_5?WXL2=VN^I?Whl8_%p`v})!4PryjN!NhItnpd=zInm*YpgS}nhknVKwQS!v&q zo_vo&Ab3d3N!<~{k@S-~Vg$uE;;E9sg55lnF1RpIqoP_vZT)osCxves`tTm}<%yyOZ*=V4VZcheY2-epi~5i2 zIo=wDg{i&Nk)ah13bAd(Q;oIH8H2aKUxIv#V{z@;ty0VgVbu!S+8Sr?uT+lj!r#Hj z8!!-^M31(v@7@TSPQVs^yLa6mwIKn`ms4c`ygHoS1&TbRXs4sUrKQ*AJye5#|Du=- zrhDF<8yR_|%NMypJfCaUhbJC|wq)zZm*nR0UBy4Y=NHNOh4Da!tjTQm0lY!F4p*bDOf%qC1 zLHCH*#~hxkqUzfp%aQ+ewbDa=s2lX(2L6TDMp6AUWqqQ7Jsx;$?Uihz*RGYW0<4>K z>IpJecvq=mMAkJbraM>dkrAoxp6UdAV!HY{hEe;81E%4V%VkK+j-k~8J zuEx4Fg~-sj_BmO!dQ?e?t)1zEL}1OO3)u8j3Hvo7xUrV~(iZL4>hgk0u0O>nJwB@7 z7H3b}2J39zlG@gq_00)G9Q%fBFC*?6ARjdkz!6xnH)&tPF^${}3|9Lu*ml>7v#Axi zP{{qKEg*kzK2~H7?2<9kpd=O?WUZ{d6Ye=8(i|hdN64DyF zg^~DxB%5Q)R~OU0j$YPy1*Rt3_B{RBjEJ>J5eY>j{$y%YOsit*l6eT4^o3jJS)hq>er zK~|^CXiilN8zc<77Wr`@$cn!c?K(BjVo)(Zr248mPt}Kax>; z2SGw!)UlqXO$)h{ApFJWRA7-w+gz_`s(r!O|5ylAeXjA_bMP@ zX_NmVzx0g^LBugoKmIx4hz|~B0!{q~@(}u93@q*UWt_1pLJBbHEZg26O0DBS@HvI6 ztIG?k`au!urxv>)AEIVb*X3M=ph6lu5QtqeEDv~jMT<%okOkz0-$vQwiCK9E6w-}7 z1nfL^PBlF^e75%8O;qpeob!Xsy7|k)k$uVbaQCRUF8ba*!`>KJAZJg|ZVn}FyNbVL z@KsuO#gG*z!<>Mq-K}&Td)USTgXng+bdWJR?+7$us)X3^5rZf ztm|5)<$Qdk(aep`_5|{XGy)m{u;73xZ>2;?{JX#l)sHp5fnDAHKj1iGwCAQ)RNB0m z^Ld8*ZB8!krXNX8#Him>l$BqkRDj77cU{t5T835D6*4{u=DKM7JyU`x-Qn$FML%RR z2-7n+Ymf-1THWHj`Z5mZgL(|Bhrew+GcY=&siz9yW7NWxJESvfTk92Dc+`d`B5zR; z*ocZiZYXvNraQ~=9Y2hzxL?EELXtwYe@i*0bWA67GN{I=w(WF}eqElw@3C~i5F&5a zZG9PL)!KvE$iQEDKA5As(UnPi$LH&nPk-p8B4ofFxl$1&{Z=gua5%>}4OW-u(6dx4 zo=zpa=TlCQTnBMG4SOSPx;b#)=c^%MjsI#ne0;78@Sr&Rv@H=wPQT zb&_@N9u6?Mkd5grlgZ_mq#zDfls;>VzBOs^%41=i$zyCe41CUS=jYC)BHDEhXa=NB zR$_7ha=T-2G(|h!>djM#lqsc zM9%*Bjvx83o-dJ5N`*ed#4EZAqKGV#+JAv4R3{kF9}U?ddmgoB1rDHO3@Mfs@YU!U zE>?2xUe&BvC~I!%$CZYOC%6M`5Go>Bh_I#?Zn`bC=#=OdmZ134^y*!jyT+vohcTz! zHnX@Tw%bP(`-fj&mKtftwk7d z`>1h#1z^b%7Ju-tQA+r=RQ9Ff7{4lOX7yS7a^VH}0+af^PSr6j&IzdJNhD4SxuumZ zm|5*=gIbb)UzcNe+D^l+;EdZ-j|F)7rI8jc{qVOyS0{SQBTmZk!uMr*HE5(Y0udq>FEPb}%-+6<>fAz{$~?&%DowHIq_-ZWw6=V$}ZnS0a`Zw7x1Ak!U{bAD2^`UTTSn$iI&A8S`tor>fH(4#I&22y71e z^ZYhaq@`9@TS8~?68~Qrk<=$>BF`uOE4qx4B)N#)q)RbpvC{=2sgH;~XUHx97*CxQ zR!z-RejYS-R!Ssffn^|ftcivHZDG%3p*{3>;#JRVun{7BwXO0OSvJ=+o^!r4wBz5zuxN}; zlEt3FHw7sjbrbB`QqV6wz|?k_eXJHl7^3w>zmSm#bOA-7YaG9QD!n*w0!ae#3tQcG z{CYD)Nc5K1@h#*5+b!ynwosDT3P#xM^FQ2{9vhFq}$YeS73~H#@1a%_cIR z2E57AfT=h1%|xwmAk4(CAMzWfSS|VgT7Z7x5y_;p+~JuxuS5YXWW^yrH$(+b>&F|G zKge4BH5+0z^mS3^&5J)P3idLCzIH5X*h`ce4=ebBXh9hFc)5;(5_HnIxsxth2P3bO zq)2Q_SqW?C<{bHtF+*3y>hAt&8YKbFT5OR-RT>KzKbu@^YJhmt3VS7&KB^w4Tzpon zur`ks;N}ynD%%{#+H=+(C)H2SOW*{GL4p+rx&%eXjps=$J>z21_-n8HX9i?mJ}pM# z{QapidA$W{_0~|di?q(c&U8I>@SZb!jY{Ew_m@B|{~T_|y8FvdJ0L zd`q&66$sNJ6YDOT0dT#_*0U?-15F1j)iH^d?Fc zq1&9F4XH0wOMhAHWl)Yn^P&X*&kIVX%93gYSwq$Rs`Po*qo^6~(cC~B{nfC#^iSLD z^bAq(EgsNsmQIcLoMg%-#HcCJe&_;`9(#j+-Ym;86%tt$Zg)mz%4$eoZ=w8bcKcom zA5AV{(G3XjpN48|f5s5-J)SHVTY7fEcawb*y7Z+Jh$V4QlUF5YdC%bNH&Di(>>UWE zWQJ%phOg>poy0FtV8%<-4AofBKrm;>hMK(C4>_y>_b)(P`y_>A+;jY)lnmB)NgQ$U z4jZPgV|B^3(;uuE^aM^DiEg76>|6nnBgL!o$x-6X`ahGre@ZHo&e#?v{W?(Hyxll4 z%9+W8}%hyCV*WUU0(?zquw4N02EJUz69QSYzGreD0C^R+7{sVD)*f=*fO??u#J zvnDQu16#H6;w3+W?NbFy*-gZi->?8n90V(TGE%`+p1pd3N20kQnI$Aj(G{3A!Ut*o zPn~n6a09DzWZ0G^syQUd{6}Hahmcu-B3l z92UHrf%wHobN+4)LJKz75w7A-Wj-4v{|-?Kr~A{wkBl5(QYVPfWgB#_rqA(lDB_&n zz`I@j6vA`4Pc5`)u?pMrzcD_2nd)$mxLg=VFR6Ss z9$Wm=WoM+y;wwbVu)gB^7ikj%k!zRL8+zt*)=K6LhYN)CgkUdP;|{<}42wrVZ~e_C z8jApIKMzNU^!X72N$g}m|ChRRZhY%**aQ~~cYjWxKD}Lj3HskQMs`#{qU^G1X&AsBR;dp*@EI3vwf!dS4A@IqaQCZNglX2rKM&} zI>tdVniCehR5$rTr|UlE#Fcr4ZmpL<-xxYEj{21e0wjS8bG}z8VXf zCat7icVq1fmdMLF=%<8cS3)awHXhyxsvOvygy(p7lAASn{U%k7pq018+q6&~zooj! zE$V-TO;5ZK)E9YO<+3UDW?=uTC*B0HLP5{sw*i97$91%bXr!PBgeOk$(k!j-2%zw zY+MWO{()(Xh}^IuGL;3c)DxtqKp9cV)RzT?0>V~(Dk@46RITJ}1YiK(f*~5Yq>fD% zR220k15saeY9)mcjD|SHnW}0_I()7Wd`S-2wZ+Bhsp6tW-f6-T;NK{QcL9@2SeB3y3f-I&6K1<@; z{_|7mZ4?m(rZt5gA=|IxB)l zxaco;>!HHK=dt9@2LATqTQA`+Ur$;HA_4+JJx;?R)BHDX7uc+@YsRxUjg+1UOl*H1 zbe`e6$csoTS7W_%Srf)=g=g_|Q7!C-EI|5C4OO<8D!yDKQKFo-?nq>g8AQ&WEkHrS z<4^-64D#+9Kx5p*s14S^oxJHBV2GRe%(xB+(vcTz~!^QDc;oK4vD?}$3 z^)87P-vD_14!fE39f#HN-rkVUUtBc&fOIjJ|B`th@X?&wN1515hsWcMp5;_FP;o+M z;x&*$C4UdJr)H5p0%l&h84DRSbvdbse=iikD%ZmFg-v$2&*LBKXjHg6c7o6$abW-TkXj~~p zUpN1pO2{rT`UP60L3`(FZr{=$=o_%a+iZ_ z+l#-4RrS!n332m3KkKocE_()*#+>pPveduHf&&FY_w93=_D*XWuZ*?H|2qc5VbohD zzMqYhjgh@)-##rd+jk8J5BNE|a|$^=?>qI(C(sc#-G_$-Ac}%9o_z%$e*XuK(GN*r zERsm`*f!YQN)LY$IICaI?ouk-!#3+@#pj`U$E7VIvJF4>RiD;K>;A74R8AQ)o$fZ7 z@P&3v38+KG(782BP>ULk2AD*$KP7czWr#Q9=c6XrR2D?1RgC6&k0$hJb+f<{;)I<) zh@nuH{RfD6z@ntlEz>apnV303B!L{OVQ*uN^BW)6K)iK5>+vx+ zVJ`NUjJb8$2YBlo-UUEomV-~q%++dlv}n)zig=z|_0_}H1*+wQ^%Vaj06AEU9kRpi z0}nfvfC<|-)*ylZ;mSDqe;^{4}XD|!~qIfs2{t?VDyq$6H9+aIO}q)e~!2vWc>;*_W`H2 zZnR=PS4c|m(Ta#>0Su&~8l2L(uW6gUEV>K(g`NrbohMRcW*fd zC@RKZfBebE5YS{&iD2f)PobIZJeMVQhPStJoD%t=^0N4JN$vWVnGB3qsBH-K%YK(Q z2sp^{_+Ftk(#Yy{W&fX;W#KFo_aJT@TRh+M$IU&y$nwJG(-YE98Cz%c7o1T;k*XNr zYIYLk^KzxciokTE)0>;#q6(8)j$Da6+o5=HcHCGM-&ud%l=rz-qg1?vawhW~ZlJH~ z*UUF4p9z&3oqCGQnS$@cOktdMEqN&-`x=+PKPw@U5lI5Rp^{W<^Q9KrnF+xYhE^7i zP{)1?0jjbTpUc!e+rs`h{~79J#Vuz{-hz0qNtAO2qCl6Ae*DQ|X8#4kimOwqEstHV zqDAB$>M)m$cvzOPR%zH0pKI#>0=x ztNu39h@krKqonzrFif z@kcR5Llv%2c%?>%%IZ!WCD6E=+kazwMDFN!$u|v5K+nQ6S)@2kwW$GWkDe<8NhD{@ z8e6ogruFRo8ugB&$g;Jt8`x{e?7zRS8qh|U`5II7_U2P7VcRrm+ec*q{v^e9|FoH) zUJByB-+ntuZjKl^OB&U}SxGv#^k0k_g=U?zd&Lb93#>D>CwbA3g*j_Hpx;!DpCaNK zQgJlkbFWN4biQn#f}0J(-VajUmrR{C__&MfACF}az99!M=AMzmx%&-eTY*8_0SZYm zmcxuCmWZA*Ro@J#-oQ!rnRK{T%~--cO8_lfmU;tH6%jaX!LS?X9Y&Ji$W<(pW!E?C z=hOYk8Hu5elKZ>1JXL*={sIk-#^{e?;Tdc<2|Ev>x8<(M;9HPJYy$WEJ2`ec1aj!S zG3UI+a`p{MUbv3q6 z;yA;H-&nqqc`x(8v{f)RiQ!v?a(dC6%FbY~5?`w-2>OpIl;1ahk2L*cQH z7>$bNF9vOUE-G;OxTwg>@anO3fn|_BATbhCH4);9%dnV|^Bev3JBpw7N^J^x;VL(= zAgqEVPSIa(1jcr+By6FAy(T@XbY4Uo)HO?Y?y!~CcR}?I@1&I(q3J3UDSK-QI{rxm z1~yF;_)c>St_|xLNL<~XH~=@A1}6DF+eN6v6iUQOaQ`Z4!;@*ybf)^Hna^**EVtlx zq)O$^EEBtqk+jm2rL@Q~Obg;nG;Q}l><<>U%Fc3xE!)L@s78ues$JbWegPLb=9J5d zQy=?h`vs6%Fy}tUc9pH)FUP(K)V_BY6bE#D+6yZR@Mn_9aJJSijccY#HSfup{Abbn z_1m_amq(U>((hzVWBx#8sgZF8it@a)Be?%Q&%NBDkZNl^;09QIMo?=$-|# zI*o@Ul6&DJNI}QRy5rT+Y>2eIVqdNRldlzGnBjH%yr4qJ>+)pEvXm4&F(TIOR{OE7 zSvi~JVP0g83b4A`vMC=;G1Y!|k;tGTGjGytxO@ZXi?Y8$j+HD{+y`r68iks-_J*?q zVWj68WEz>^sO{zf2hv{F&wnch&k_)kigS$UO>o`t{XcA8g7k07Wn`+eorY&TN^X1e zzP!XqNZ8t)v)?pwk~~9tm#lOa*w7FPq?inpZf7&VBZPI zG>Hby`Aa84jE?Q*8CtoS_!gL0d_21WdHB~qoAxdEf>yo%aahoa_k}(o!=T#+fc=1l z1Iw5jtFYfl!KuJW@ z`%)B|&)Im%#wxJ5x<_#I`xn_2P|3QIT(+#P(02d-=IL_yWpgYIrw; zW(HlrZ{QXMFUlo)MAmM=Bt(8E@@HnRXG(>x(vHnZ7RJ!19GW3|qC9$)hSLk6cdT(1 zO!tMIz&~lBMbdI)jH75p=fvuqEYkZk!VPNG$r`l;@d7t7i<@NL!!$c zCL_VKSZBJgPZN-q#$2f%#KZ*@JBt~9BiO0#hFN+#U^giWBX^F%e$AI@pOC_vd6S{q zV(_fZcL)&ECpE~qaJZxYJtufWGg7`#VO#IJNdOyq1WCP(LwXjH1^d*B<&6gemn=%Q zhzC3w5gjL2={UioU5;to?qblcFuvmvw}Y!jQ{wJC{MT+jt*1<%0zRAeO+*K3YvBea z&hHD6?t9ZHo^}WLnL82eBOAYh%V7Bx^yJAR1afVF4*{U zu<>4TuFIWYnxe}0Pe;6K(HvH0wi-z<4ysK*9j`Q-WyC%iUpjX5A7hEDB5FsKD8N@I zwj*$2c_!#3y$#o^Wa62D7hz#hm-VmT)k#spuuuNjVGNqYGO7~|OBA)8a>)%!DAxeB z_?GRcq$WnP@h8Y9zMn!QSr9_ujd$n#g_8>I$(t%~+7m2C)FTe9-vbvDw`)i2^H>9`F}y$LNz$U(&~$_N zwGd{sTl$5h{1T={8kl)`_vV#^{L5>5z+dLqd}wK#rA%J-7vISnqh9nChmW>l%`k^I zmWZu%?|aF0zoVStVdPg9DTYgBBQS?oqeWx6(1SfvF5{e-{#yL<3SNlB{u3w|HUUVtZIipREbP^h5X?g6mDgc;3}s@l6gFWgdRZC7Ec|*G~+S z`M^Wzoey72CLw0Ir}BTk>;aXS6|X2LZ32tv*Jgo9gjLdxI{W9O#6(5fu;x%|Q|#nd zlnT~`@eW`s{Tk)%>$hbee7p;L1Gh zLZTBOBq|+Vk@OYse5gapr5J1T>EqS9q*~p5=gGs`M$KQE9vf@w7bu?vRaMigMw^&| zl3*>^YDSVt_-;vLW2ADMD)B;Mjj$ZisR_O~1Og#Oo4CbvrNhL`3xw&o)6wX?dNmX6 zt}9{7O)49X8%u-!Q}$%P?C)dmIqb2g?yu5^5)?t%&xb);UvYmMp7c~-ub+JQcpXX+ z_eoc{QAOChPQZsT$tWMLRS@fr_S0oBorCS4MUAfNwvNp}k;8dYZ?Dm2Ye`Dn^KBmm z(E�uqAJ!n1j~(wBRkRPA6+duez6jfPE&BU*@KWwn^IA1#ktR`3FCu9s5Q!44iKh zIAm9>NARmy#hlM<=T^Dx z&z6DfY>)}-aqufqDjNkmizEtK)dS2I8f;oQ5tH6Y2;aU+K3}}|L!B!j0wV^c00~rV z-*OGbN8&H*EiRpf)2*>@CFZ+bz%@MltOf3ojY(sd9lG0?c<5RT1Sl0MH#|S`L6Xxc zcZiK%Wtq4e`*Yv$bU+^LE;1%6U$pYqCP5*OB zpiQeig;*G_e{ur@{Qw>Mjhx`q+tFoOHLj}oF3mNJS`msTJQ8y+;`?#(WnKiQQ*hf# z|I_qidZNch2}ygUPRMq68cXP7O3=}{k0^KRxt^vkp7(6JPg7wr?0C_h&f}+G;ll99 z&8kPQQgt#I?*4bE2xZDHKULJ;ivZa*PGX|7GGIznD+%5ts6EV^0D&d zqH`P5Vbjm4mg(9jOC{##qZQ!wv;~?=F{KF(u4<7_DuWN6TH!-&z_p|^;Rh-p7D1jj z$(Byx`N7WUhV(@<#Qm9ACg$e4AFBL)#dlKPS#aj`pf7Jl^j(T~QXI*QzcF7Zvn}dh zSpCb>k1|d3PxHYv2TWo9CU5Q1hRK1{li+hsr=X8N^4{T%vCZQQ7y>H5R_Xq|Pb)4i zaJa_hmiD3H>Wyeo#tnv3QJZy2W7_B*-R~cZJihfG-({^RqxQ_iRTWLcugha|f=^Pu zT`eqsKa1;erKZ`@5;z|8K01NAwFuBw1RU)y>ufpKXSN4DQ?!gy-9`?0{%}*&cgyM+ zkoo9e^SIaH(cE8%+4ypaGV!w9An0m?y9^#MVZmt_IMHr}4V5LehTWtpCXI>~4m8Fb zZ)R}PRHU&%J<*=|A6-|@Z9Fp13CBK_;E`-^e98kK;o21idj!g)BuoCY3Ua@v4Z%A5 z&Q4tezf2k@7wkJpFf;veg8_LIk%p%$ zsKFXxgkKWsnqP*lhrYUb{H6C4T-WpO{;IkvIP6%`Uh~K1LQZ4!Xr}@12l|n*d+{hy z7EvO|44c`6Nn9gFBSX*b8-c?3hPJA(`t{hydgO)8f>Y&e9wP0UUR@nu`;{K7a`+6I zM^OesaY4DbM322ae;fk2^E)FP9O;opu)4$zf_5$;ZmTJDwfY)ukM4s57n|n-! z{Qi2U=j1mdZ(Pj`Ap*pG|Mrc7-qqdb^GM%C9>+nC)qAu&^sc&+*X*C~T(3m3*p7V^ zjWGAnYIPmRpzntHA&$iAsP9J)-X`W!Upw9rD{3x17T-k&sWOxhk9LWwI7h<1-DPggH;0sUQ`6!2G$z4$$SNs zBtyFBZgUpPRUW<bMSsF>7Pn*1BzOhZ!c zG6zSw^$fH36A3V8DrAd5i@vDd!~6ueNrkmu@HpyjWhs49e^Mn=x*zUwe|k|Da!eRY zNKS00)~WeijgDI>)r1=NO3sE}@aBq=qVZ0SMD7O;ha|h1`(SB5ZE8;>5%zi3i>ouX z=sKksz8Oy>_%Z|$_R$Kqb#G*wKU~o{`ry>U95(eQ$eWe|U4FM`FZ9ba1Vs@u9Pv** zTnSeY<(qB`La2GF<&ou_R>zMlqNx5z(!5e;PfRJfLl>@Il^F;^V2i;RLC=RlZ&yN3 zYKX2+7AU>GqPI!4%xm?mz?uQ|S`)+O*#v0TFS*7UJyDKT4k|F=E~LE3kwjS|_>|Ko zr$wD9#zaQF7tkUK)fi;)!CsITtY_1&7KSS#UjBDJ-r!@eWtc?7jqWfFrQ5{5UMc&| z$1I6%r8uxaAfFYfBng8|tXG4<*8X2&R_nJksYgL`2`1@r8~*!N_j9dli{A_Wx_H{s zB-XMz`v@+Wl}b?7r27vLe;aUt=rk=u4EN~udVVUFDAo@HaX}34C`&3TP08F=2BZV) zvf>t7AxB+?Bb4scI}6&+Ym&fo?qT1!w-T-GJqef9rz{vAgj)mw*6wi_X0_2I`DAUV z6F3st8g@Pb8+~-57@(HXuxxM9go|w`=ln}4M#lUQ?hU%t4>g4L4mLz0Ax{Mq*Mbyw z9*u7+$lJIb)rFzv#b=BI?P9On;+RFFzYQp;(tAJDNi)UfP$u(5dcX7*6$oWJdrk1@ zfae^x?u`gGilG~avQ-Iw3qyUOJ5iZnKv}36B>R)ggWK*=m6cy8SUS`O3CC9*3W zf}2~!aZYcLm`@9A3 z0eN>(Ulf(~O(pO?bzu0z53<7E^z3UiZPzGkg-U=njonK&ya+?x2=Khx1F$<9hYkPG(9CQfuve?QS zxG9h8JE7jDtHU}DE?@etZ)%KX{%^E^6n2noDC+e0#i?eTr&=(g`J@%ixU-(7tA(BL zf$KCB&g#Wo)ra=fw=`_6HUDb$zY8hc?4|+-Fp*r*P~At;{49>74SxdIr8E}EWg_5M zZGz7)*p$YwapawFUZY|I^Je9DcsGF;=+}5V?J1!~uuSIdddY{?uj5betakh-i8PTv z{|)}QCMR z1Ztoc1Sas${prp8zb8D0(uB}3&q$u-kvNPD)7~=1IV8#?cG3FKUxRyINxWIb81Fsi zOqq)FgbC3*qfrc^%v`iwi8K{EY94=n?&alI(B=H;0zM(Tb%P_34{#9r-FE3k*sEv; zycpR&1~huU(osN|T-=kSb7fi7S8AgDE zWeHk|W%0c0m+%gvrk*hUfiQFmFZlcmr6Nc#-ju`WwLz(2cmfACKK)RQxuqW?9aW5Hg5M7MBCMI1HQfgfVTvnB zQQd8qa*n%8h3j30Oc71rg~_u7GDpXF)k!T4cqr8sesBtV5|_ShdFV@C0IT+Y7nqu zC_}&lI$oOvjFh})+sm#~AI9+|ua!i!duF!u94J0jvCycde=tK}?Rxz3W?p<|gR-Tl zRa+{)Ov4iib?Ha((-iJmu1yod@L>oLk6VnId|Vets=5r!#b_AoZ9vNTT*EheX{GIN zE2uKR{}kskQ=1fYO1T25DTqh709wcqDHeD&Of#x?c^GtgOwZJX8yVjJY{4FreV%6{1HgnMjhmExvkkRov}QFC!PUP92a+^wuV+MG29cBqoS{ z)3sqvnOALh5aKyDB3vMQD%c?k2bvP272F2qpn<CTx7WhT?F=Hf7<$n!zLIEGO;})SfYQ4JE2qP9BaQ$VT_d%%ei{Z$D=Tl)iE=V zVNvRo-5=!+86f+H*So@08`UoQ7Xvegi);V&XMzO_)lR+1N;ZC`5}CLl%24L4NqlUx zGx4AKyEROdN3Mst?KC`|k_IbD)7~9x4)*E&0I|n@Qvt0}f0Q#zp;NoE!82+Mf8DUNIrFFs!nq4uKIQVu=XR9c2fs+YDFbcw~K!rg=ZgB{j31j2@>GCr@GM^umX0)Y5 zE_i*4H;!S6g>z8``k+!Ak2_VQeeGu$h7u9R#_<)f;*;X^b317Mi#ilW^r5^1Hqx=V zVRMMWrXiVdJ*;BHuhuw-DR3-^;0~AYKD6prRk;UP>)Tjc?MP%1uXX;)=F6+nBG&K0 z@s{us5VHM-+;JZTcOf>{+b$L26ECn4^vIs2u}##RO8E^!&Y)QnoLNvB`kc4h4!qcU z?b)p&%=ShR$I&Ne3fw>N|Q|GJ{r zr26m4poLs2g z&8|ee8Q!NK=`ew5+opW$(aq;7t9#g0HzyXO0(XiW3ib@#Ys#s<-{w*n56te5-8q-22SunZY#kfPysmXu>2tsZz9i6ftmHcLD z?e6A$;y#U%0t*~XESDia{_NNIhc3q?C>Y_SlfGfXaZ)T<7DT%Z@X(dZ9}>mC7)>0S zTDVUCt0=L%YSIjNWkXS#$NLhlk3UTdY+>f}-WGeY5`J$GZ=*5yszR z=rpd!Z{IZXHZghSsN5%_o9!sQwlor(bRMA=)6gSM*={@cOj&SzA z@ILu_MDi9Dne;+W@u-;3Y?fMX+7IG{32nSVLT>mC#y}moG44Pb`!%zTJJb zD*DQ=H!;o6S@?-NkYLLv7TaCWMBPTLFv9$|x)3u~-HS(5W{BntVO26XZcpCEq&Mj| zLp@UnHKI=uQ7;{oOw*M=?e|P_7a)Li$5I=)gZiJP1i6owt#=`l?flTB*qY&-$aXYA zLKw(f0UBm=m`2%1ToiP3Os#zJCc4pyWQ&_WbLvK^emayGk+<_Q#;HaM*;>2nvT~A| zn(`a%87}BKH7g3gTmaT8aA{p`0{xWp%PCCnyQbxMiEkt#PiCL$Wx7y*;c%kfx-*{~g({B=#+g7ffS9T+U3_0#-S3kHlGCU8UO6c|8Dkr3Z^Psk{CsD=cpDA#kCU2`*a+D5pdK(8QF3MAR(jeriF8=il(X$vK|5dbDya20X(}qx;HKxZXNY)22#A{E?qr-=^T~(`o+ynYZAwj1dmwEn2m&FH@Yc1Xy zVQB5TwlyjK{Dr*26aG)mNv?s}Uu-ikoAHzc=fBjDV|<@K>N~txeDn7wV53(TJ-UA{tr4;+5C6{2f+|v$h4+Hj2E;MJ7w-MV^V42k z`J(T$$0fXY8&i@9F0#wt8{(2|HogVJKi2ZCYeNVf%ZIb#7uKfVuF7<*PR$=346#V7 zC$eTDt`S3!vxD;}=cQhAYmD`QiE9&&)0~*L6&SB`7ZTq5KbpRREy}J7SLyDUp}T9y zAw;@C5$T~j1O^akBqfIKRzN~pK^kVYB?8Kj3U;qZRvoS*Pq``LS~b+0@8bnz>> z>dou80sEx9T72=L13UXYK4-V8aY{B)QNQ;fy@UE=hj4-3TD5I^^7qGaEdm)4-d|WG z%*LCu5~UInvpM&UbBop$ViXNWz5Xk@30UH)UvI5OKEdUyv! zp58jf=&i|_B}w$l9270_y3O65g~URR0y|>=V&NU>@`rsxLRozYA4AYBd+^~@^(CjF z=Rxho(-22kUCk$chFu3H*G!+vk8=~5H?_4JsWu5M70sM%xvUhO8JBMq*!p*dmte{T z6n(YbWsd&Bed}$++B1YF#1$Wo_txQIchOyf{+r0BHmVo%3)W8;d4S%ms*Yz>znL9F zT&)U3t^F56N)2iH>m%(OhcF@S$DJ)M47v4=0`do>4DqgdypIFt4 zXobrt?FRPh=ncXnhF!iY1xlMd&LOUB6o-h*z*&L;F=WbAdbLM6@>8MY4k(6hHk zJ;8)kCid-F&3u*hz|6Veirxa}e}liaoj7m>=oP$zW_q&ZnAviINQl|dc1wdA)mg7EWhx0-k`h^KzrI9=O37@LBu$3Qtk&AZ zYUS*Y-7r%l^n%8vDmroYf;T>dRC8dTZlKMsLW#XVp$ptB3 zJ?EYCFd~FPdotn)E1+kvtB$!~wo&Yje%C$F?*7Hz1ccSjgvtYAYs*lJ6xc+Bi(H_8 zIGF#2lUormB*~atF?XS&-a1Y;X?qf0&-3y=^=dgLJK+YASXsH$?LQ#J?70Yo^45{o zzEIjI-}v0)r6HBd?(5b=f>;`WE$SSDYBU5ZkAKr8Ee?X$L#j`gJC&4TGxY3mkKA+>x#0pX8%>)^pzRb!OBD{iHJ8wzpfc-rC`E6GzzRl`UYr z9rM*W2_j$byFOBzm@(8lyE{oWnSQ+)l7!L=Ya0iV26Yzz7EQ?}wfYn0U6b0kC;@xRNZndG90Q*2nof9-L%N=exEccfNBHIU5L}+Q{H0KULlV zw)ndFCfU?x#ytt&t(kWih-J$?4(Nw1S&KzR2EcmE-)Hi=ztb6E@e%!E#@7EaJm6uE z_7hCf+ee1u`J+BC3FBM{d!e8f-J4((R}5XAfLln(Ten=xt(|m~KrCT;*(-E&L613z zx#rz$ILCK2LxEN@Unk{{bJ3J|d=m8-f=3^+;#PicB#x5dg348zN$ztPBv^MO=SY%Z zDas}uq&ry8{77%hdr&x^!hH=wGx%S=0lUwGik*v*s;4kptBrYTWAqb8_D0i9iL2^YFJI zYig6dM&C)!=>J!iIL(YpDz_qGx!kb>a2oPak1g9&CdC*}FHBw0@1SoSa8`(rdwT(v zj?qRIi{Li?WRn ze8q_Y{olsR*edyJM!jevA7%!SZ_tRx$XS4=iOvQ{P0q*D+^m_XMC^gZIe&#QN$y_+ zChu=S@gNmwk$6RO=xvP|uqzc*aCo&-z&dsTh0O2OAw#PEB&_I#ZSt8a2c%JTbak0h^h5ZEwl5iM?YX z=ii!jC}Z^5rS$maQv{pb_q}hdMok+#SYDNaCNvy-anH|GvAD-1BEBL8I7}WD^q9s% zDa@6ac_d>2Jpko%9ZihfC=8C>eEjDJCW%mTEObf()6b)pl*x0T7%Waujo8kMv=}cZ zfjSAa?dul2Xe|7+nn(|4GVaP}Hdw5lph?*tNwgQtp5oMH{2l_ma@@iU==?iapg1-u z)T2aMOCx2WJN~H~zAUGYP=I#(GncDmEs3#R%|Q_sKzANVG#~|k(LxBsQY;}NUy@pamtTgcuoYefk-weI`fQ6M27v6`-b1!Gdkkzc?k8?b$5`w6@d!GxdtSBEpso+fwIfx13(-+a20KUjD;|%BzpRBSPt7jmrQ0WMj?S zV(@N|{FpOEZjhTpPG~OpaMTgiH*zJb#L&qXMgK=G1(2kQr$(N$xpy4<+Z4Xi1h;N)zV#!PwrKS zdS%RteS&f;K8KK&K2v?U$t7>*tSnK06o$k3)N ztHzyd7ILlyBGu7)G`5I#SUltUZRKB|1=_#1er;uaM8nehJ2plJYw|hS?@9`@p=JPj z4%gB6QjV9D)#m6ehhSM>= zNb1^w+x`I>Rz%E+SON&Pf-~0d2O}c?!1F6@=Sv7-JHV0&ONAh+5-wLUq9!Q}!GmP+ za0EYH?r5wvYq!_0W!we^pQ=xg{J|6A0_=QWJ&xxiQ|;N5_X(zvaPq4K2&NX_!^2C*In(a?N{-{9FBO7CgCz*1jI$bP7cRh@a<1 zw*zgy-atEW=&B@aT2_RN)HmKahRupZp!#9%YAq_Q0VCI^^@NbOX0k_(x0;;J8sUJx zNI$fK8O&$o*rmDshJSMR*C%d4~CezKl8taWA&STy%) z?U!=y=SoszcI5cUei+p|U@X>b;R(eDW7uH0l8T370)7@gLQ^Sh(lGYi`rhcH#8-b6 ziUZ~oyE8E)AQ?Z>%2-(Wv_+^`qIMcWV>3qMST9^WV$4RJ@=k)9*s(&wg8e%X@uC|J zoEPjJEHQlJwleVt;2Djw)iTtkC4WuS`M7j*mZQ;S`D=yA6{l-$VZ+9k-yszGH6Y~D zEP!4rC~=0ge-L_a&lpLfM%FxltY2dpoPe#hhdPU^1Vj)jGuV4b!*k33NZVY~HH26v z#LxlAUp5=`3KAbon_wnnqqO_G0(~ok-tW0^XyL-zwA%4~d7V1pzIZ6H|GVp!rY0>q zY`c){M__#Oo!q)=zx$JPL@HU6pIXlyA7iZO3BR>K!Vwb%pW^_(-)&&z9ZMYp`nERS|1 zXQJd`QD%+impO~z0*fnUM3`UKjzB*P-a7`A1x_Bw!XlBDU{I}~ZpP@d;0Kvr4w1Ep zyrg3bd_lZUqQI|dsPs?4@Pv8B<$tesslwOMA3$)~jplxuvw-iUwWE)6p+U?jeJt#o zONhrp)ZB10kwd$|%4#$qn7cJ=vD$NmHqYyEg|N z=a5m8%ga?0I!j9HccN=(_u>uNwnA1$uLqpHJ^}TWv7iT=#w{%lQTS~>XtWjCJLej7 z5)vQxcz%R-qaFJ_VG5r0wTUllYEZB?&>Hc*P2g(KGheMOl_B8u5S-N0=~wv zpBS+qpIdHrM;RUrq-HCUSN}!#SrX`_U8v}r??Z5W^ERd4HY%}afW|g&2nsXs5{Y(N z@aM*sdFVh_<39Zvlo(8gG6WpHKeJSZhxnc|-2L3hqK|ne{J>p@>uU_RAq%<79j#v~?+dJgt@+j6yt{{#)W<33Er z*u33Z#^{VjFzmbF1V#VDJ5W5x9S7SCx>b*ChM>zv6&A+b>2m9;z32vck+%Mx|D*5s z?`K%tkF3wX_xhoK;K!UKocr32>h@@9lE3qz-aJ2ci!ElyK?q~}x z;DqB|Dyo754gTEjKyWYQELi5%F0Xx~)%_Cd)#Cc(d225P>-C3wfu2`eTS)R!fN^>U zamTv9{SsXD($S1WIT$i9SVH_Vur|o9Q+86-$H~|}Py>!#cGspPu$UY3iPFf)+Kzxv zGp}(Vj7Wrv*<>bbX~-K+p(mc(TH3O*`!<@1wSoIMmGuRW90OX(nwitcJX}xEYO%d* zXHKXV)wt<$qxg55?f-KDZVx-dkSd&LbeXy9bg9UhL0X=?tXFiCjSDBXti5;wV`iow zq7^~NPYb;zw-2lSaXnWbkC`79RF9gvLb+8w!P_e4oNCHTPm)(}r#4ELbP zZu~cHXT3D>)=HH!ZvvaO>NrFURO{)c>{QyyFS-R;V*@Zj?+PHcisV)?$e3KVw_&tJ z>8N0?FtOg$R_1q;DI4TK@%0Ez-*hQ^FahppX~5V113j+m)dO~mka%w! z*R*;v3q8Ss!Iu&@r2O`xcq2~QTi{U1*$wt6qwk`Zq!(kY9UMFuf^o0$6D~ z@(Z(hXYyEOjcVXM^u0cfamA2uoNIk|Da1{N$EKy{jWb|RQ^jOb|3s>B%&{iK{hJ5_ zO!nc%p9#o5u3GTl#8kGfGU%8s9@iN0Q*r7zE@6?`C*bh-hP9=h|^K_?m)H)6ud=rZYg(tYn z%1lZf)2@t$m!%!ZgweGwQ|99#*Bi@&@0u%g!p4;1;tD z=JYmgdg)g{WmJT)qR(@$VxM}qnS0;o%}I4f4K<`3*Vzq`&PI1Yi#Mah_Hi_qK2ddY z#oogYkMI9Pn#kpBwI|rzv7HH?k6CeRRWthT^!WCZVD9CyWY8Q|soA9XHi2=Z zQve!kHLQK=8n4#=z}Mu@9=Dqw`UfnO0sacj08KwxxUx}x{jWd|5Fw_-G<_yAyi9TX z^9sqKGJYO!GjBB_FDn*g5gqBvI+!pxE4((8!&jEu?H@ykMSC*nFJr;uKVKZy*G<|_ zir@axS3FK;LArnQw%|ORn1`-4PXCXJxRK6Jm|M%v#;s*l=Av4!C5QQVoE{_d$(G^= zFIQ*!vrx_^1^s!}dGh-*OU0!le-5uObM?VHVfd5Dmng#0f)RV&@#613=~ak)+;^2$ z_IcIf<$ex)S2S@=SC+XDa^wa3$tR#7&uO6K$yn14im(4a7HB z^Zfal(vv}`5TcF!`r)Ee;$@3wJhku-qiy>zTB~P2vlv~hZiSrT_+*ndGKp9H1x|4X zT}y$-Z$yjkt@46IIkTNm|+9)Qe`ruZoIQj(qh}SO#RP&se*q{9d}yyBX-u5_oPM0cd&8?ZQE_PBHzc; z1+$)~)hII~qhkEgTGFDo;rV0FVzZdO#M*o%BlJr*C3G{~5br+(b93aLuGuKv^0V?x zv)E)Si)-PNXxz!seeeF_j4s&0@JtN9o&+EIZi~#a2^T6vZWhbOUMI@t!6_2QF8ADk zXUJLBz!>eDn20ovHwELPzxwz)V8>2L9w}Ne^E9t!FJ$e$=6Pf4F9Ro#gFD9OQ-zf* z5Tc3ESb&<>$gS?Jj?qDXXihcwcSvc}I7H(?dHe4zy@u^&gMFSbm~@r<+Lz-NmjDi1 zo5n%!U?pfzhS~balv0U3k*)Zfq44VFjX{4)b}`TO=zdU4u$LUPQmGC2&c4xc1kC=L ztY4B7?6L(0PO6|*pWO{^{(0FkXzzJ!9vzwGwepBrU79VeusvwI61xaPk8CS{uHo=B zMgo-7f0d93X5ZdInnSVP6N^j?3>o7S5yfmlxS&Lc`z4r{dxY|?0;G#;XO_tT*T8hb zM7WjGnAZj!?i?4q$|-lhGUVH!s)dH5->*hMfQ7Amfx%fzpNeYdp(6w$sR+cWww$eh zh^5BV#9X|&ed*RX6^YNU^`T>7URq=s}*DG@ms2D!SIHNW5#h<{>LqVg;sJ>;x8p@sh9G2P|9K zv(}%V(+0BAgwV1UKCX25T<>+JKk=q$MgHS({RUX|I}*gNQ5dE_2?T)JezwU#dU@CG z!DC7+&Ekb;25gE;K4($4m2>-CILsRg-#hI)0AmuC=BbL9&nfDLe6{T9^akFN{&SKZ zY9?v_q5^x5#h`bY8WS9e+mnb7I^=|jnEUk5pQ>!R!~;(Jqy58Dzj>QjDs$I0(ipQ+ zXYR2~bMFdMvzkVv;z*Yb&)}azt$HmrsQk{J^Jppkf#So+IBQT=c|$K{$fvjuAE#~0 zoV0*DwB;r^W(i_bcKXzBCcfAT)T~51W;3O-L*Mgan5^zfS$fl?Mf1V;jSeg9f4K^f zAnoNcovx)VbV<@?#F!v5>Ykfe>f}V9g@>k(kxHG~Q=j7ATq4j)6fu8m3&G;X2>aFC z3M7!YqGq_EU$$1B8vb(=k<+XxTFI`$9PaIx<+-74_9;Ych}Bq7$HtFP=|UaO~t*9K7M zP6srrt`*WS8^ipH=1Q-H)Qj+DP(`?i(dVKAQ=60+{ z5xNAdx8YEhUMK{x&*rffw$M8cwusF${oQ@D;HiE8ALvhyc>ekC({k()(h#)mZ8~vC z)lx~+b^asdRnk!fg(#nFABRMsc#YIS*+&CVj zv0*#*ceEQv6g`fO<`424^C2e}>2*!dLJ}u*2pX=DmYZd4$rhWuvGA5PI7l$v2)53s zc>NCw0K0mCRVFfpu{@KNB`|0jhMM<=a>C}5aLRNsa;+!QWJL@dSnw>ZVw=-)>8pe# zUc2a6H}FT#7u9lEtm~s~3&Tk%VHz69GBT4|rJ=2*C^@%@w^gq=Zp*Iyt?5{El2)EE z>G0V@_&8o|KcsvPAI3UCP>5yrZjW}Qs@&f}b*JRSE?n?o3P~wIOmaW`zwTHh#i^gi zBh}D{En{uP(ast=&7*0h@Oti87%!VdNnp<2dc|2a_|({5q?hUnS7Ey0nJBT}WFkxB zn0krN%h;?v$e{g^5vqJr72s9rVqt*|g|p%>DtQe0BYu=lqEm8k6)ziH>JMRW$jZPl zRJ*cy44fAWJz6=#N;gfhf6OtqsD~iV?Z`x&`Y#?9{b?}V^l63NE}s@>mfjLp&-tgW zm?BC~MJz_UruQsb_CI>)$Tn2O8m4hSNa8EmTi5b@=JRI_xT68{=;$^_nlcUi3(aQ` z1&7~o5_-Mb>y%xBha1x|qXfiQ>-3~TmCI4D5nSjs^Q~`u@+RBm*ox3k7}u+%H)e$H zBlAkaXxjF3Gn2)^^#%k2Ljye%O3=J+(w(gd=x^=c>RaWd2$jHps2DfL3?k1J>)^f1mruiMekF90XRzf%to_<~B37tsiG;P()R zd0u|GGM#)91sv^Keud3tG_YXJXT?47&yPc!d<&Yxh8LDUZrBRxkelUEQp?Dw!_|4{ z7y&!8klM;8k<`kRTH8of0=(K7t`g(cA~`@qE>Yq0n20F-GDy-v1y0^>1JFaO|$y6Lp92c9=$;0bwHW)fXG!@==4g;-deLI z!bowMZP=}|(MCxsNk@e;bS>{VR4LB0Xk920XTl0z1IU05#bCYaUo**5XV}M0_5a}^ zQ{CSztAvfxBQh40j+JW$YG=gWFI3Q)T|-_p!MARzB`@{2;xMqr_Rrq|G{;fsx#jPU zWloA>sBLB3w<5Dp3d6o%%CnE3`saJTu5i@86E!P3y7#y@qwG_wS1h)96M|NSnV@!1 z-;F^3chEBXBJeS@amh1y5az(J=G^si*+o#|KadD6?Dq4oHZeBIT?t5u7sS|Xl`eFYPhq0Hj zQXLD2`DC4;b+91!=Gso0p{!*MWB(mPNVXO4bWB!xus$-!b#~T*V2ueQY z$9*Koy}t2(e#O0$>pqAHl-NYxqj~5!9TCZLKA|^T^OAEKL5EAMAOMZTA-UR-bw?pN#fqnJK)v#rlNFMTVVsMvUd41rO@c%S~cxQ$zmBk1uw~Sn_F)6Cj&QV4thT{G&nz(nR^_Pss z8}z#EeH()(UN4CP4dFkv0!Lx)GJ%O5GF^q2r`A{kr@2qnxPclfSGPVE@@DJTf5iHI zzq}_}(i!X3$@FZ!^`MP&MTQ?zs}%5*o@sEM`_iu~zj^E*eR6%mP{=oo;4@F~3uy*D z&8FlDzG;0i1B`ksqj)1yG?(Js^>^K8e|tY#>m=_bOR|*NFPhAH@r}1=>n&`Dttg4b ze@fvZ6$mynS;!yUO)oE{Y5FQtuPmUmKCm57nrQ7>`{)>y_tXAEDgI}3!J53SgD*w>0)6B<}N;* z1RUm`-Kp2eK9Mo4Eukc4U_oCH-1_SydK~E}U!CxHZoY4U=kK$xay|PO%0X#PKM)tM z1<3xy;|hwx0KEYp^zG94riq3l8mRs?I}VbD+bHKVe>l*kb@OhL1xVl?b+<$(dD;T8 z#|D>jP}lDnTxvz1=7ShR zva*g@**<-WNkaWe<}^z2umm^<+6FTYvBt(B`!- zHLWT@a(yYsc&MO$91)ogZ=XXlj0Z%o4>eaa4auHI zPS-I7hA;a#L-lw~M}Yf;;u}GUbM{qfyTV9nQ8dCVq&Exh*(B#t$-I{e$@s!|5Fj>K zXJqC)XYeGrA0}hG&7m_8xN5dD=IYW%e5mVUYUe}xsF6L9HGcoQ;c3^RJ!@PVZw)Cp z6ax#|&Vzn*D@}9)ktt)XwUPiLDzARmTHFDM@ZEEq+(JcG)NPW$@TR@zqe($yhwd9z+-JKGW$n<5yQIdKTvc1WtGim$WJSe9}7>` zaQ4TP(j0ql+7*mnTn3j?D+{#LG|E{}H0%tdUMGnt%>i)M`U-D+;Xv2eF%!gyp|Cf1 zM?>O6x?9bU)14GlDd4v&Jf~!TJ~TzLAh+HYbH(GwA!wXt`%QAqAc!2@Gqq?2p!yMk zI0D;=)X&zfkM%=71B&9*>)0xYaLHoLqEG ziHF* zc^SSKAQP9(wh&a**~j#{1?xC`;i4)PPH-P$bzl>*DOnHcq((3DtqXXt0b zs{eVNYccJ}jqFT;%C!3QLZ5_aA2vA1MgD#pXw_gP&5U~95%_W4%E8V^1pNYdiH(YYQhHKAnj8V zx-de=DJT%BlX^D0EQxY}{65UW`&a+Y#rqQx5c9aLjd6XC|H7;c8@|^~+@h}11%7Yx zyB~uX1F;&Lr!_v6+FUW9zBJG)7IjE#5om8Uqj|yHSCnXic3W*Nz9^lPHY^ks z(eT53resD>8+)+AmMYqcAcCaRAOS;nif|{MO%90K`9QwTg^USKXXbRhlBw2|X!uOGHakCI)H#xz)EH1vZQib&h4lZ_Cuk^mb{giuvxGtXAa>4e z9eGWNTdeF|9^19v*t#a}c9(7PfFmEJ*H6q0>!U7BVB9`o#!g52K zDON9O&TZMqMgNul86rXZPRKPuH*-;# z+IFo!^sATBd{G>~C90SF?}r#IeCu5y z1j##e;{MiYFSOY-CHnyRhOj?L1v6yLE|0Y_@6q3*&(^tp_V{>VuR^Wfjyqax`i|*< zxEOaxXCJpBbeToSzu_Fvfu=2hp(j!PHBfpZU|LIM7$Q_R`w3A0BBdm{1^hu&0*yq) zEsFVcw>O>?|jLM zWPG#>EA~dFXy3Pv6NbTsquuPS!$jMsBG|K1j1vc%qHpM#!IjqCGQ)2eR@P%t= zAiU1pv3yuYFnG})zIVX5T89^ZP=k~;4<&JpR3#I?EMamjS>YxM<4MLR7iC$RRYFJ& z4l4fBVlG-3`%J8YZwMKwn`*h#pO5?3fvp&p@DwlmRW6lxB3(Hwv{V53z-K51;KIk3 zV%H(#S28ZqQSYA24KB5|LH1rDjZx)N(;UD6qMz8!ebG zrQGPVlI_dRF6pG;%ZtDj!VMk|%;qR4=8dlcB*B9}4#J!0@%K|lP2gVR_j-`MM(4z2 ze^rw^*#4wYx%p+aSxD@oz+R!qfhe5sxk86(TeQ)0XHZ>^@;rMH<~+_Up94$l;s>$T z&ofEN971qCH~ow_<+o^WDY@{4H3P_Rnt#3^#X0uArUOVnxaFjdr_VR3?Ca_%zyP4u z-`c){fcev^TG)Q`>Ujz7tHLncN>i1wc4tG5|`VWuh< z&gI9i3vGsF`|qRCPE5BcHSPupQ%KA~jLPd>{`5Up{PEsxZavD1Me7!DC`0_~tUMZC zei8ISM$;WkdoGo_ZZVM}PupS0sIcdNtv6n({aDJG+s10MkeOu6UO_4EmNxRXRG_eGM!GD(y}S;~vPbHIC8Xwh@n25A4i- zYh|?Ibqnih&Wl(-ejkB=TIlQ>5|B^;3?^_o%PO8xV)9T8PeVNS&(wsAOF9Pk$CmfY z?KH4R*hcJa|N2c4C?|^w9pz;I8viu)`Q1ozZaV{xQjGSQA0OI9V~EK8?IMXS^PySs zWQ_610PSB&O@K>t#WHC{(~jUUbZ#M(ltpzIT;SZW!C|t13bIhQ9=kNhHXa1U^A0KR z6(gE6Ocl^7N-c-)^@bP0hpNRfq&+WxZ_=7**)%Mss>HlM%h^%seLatAV$qbmaQwD! z(30-&R`@N905f@zXy(gD{OWVr)&5dQo#m9JIy|K(g+-GigU?2U+GWJ(M;@hRcK4f> z5zk_I^O1^v*=t?y>~DaV3BJSvu5WuI|8}{!G{ zezDHDk@@kH$I9=n6qMg?c6fZ3`$^J`><IUs%GhI1ZI7Nj)06N01AHeMYa2YF z;dpd-TdyhZ2rjLjMA^&>RJ^r^SDB7cl~$9>_z3Po17`q94Osf{3=*?CSI76ayek0$ZgUJT>Bs6E8W@0T7 zvTnuK6cW(k{*w z6TA{mD9eXX6TX$Uv}UYhw24|>AlpPrXV(5^Z$*7P!$M*@*yRzPG`!KAtzLJbMA(y3 zAB4noYmx~@4dGwl39b>~qNW7@7R%o!_Zz-E)4glzkUf?toDN{u8NRk#NwOwIRFYZn z*#!nuqwgP>&yF$tYlrud9K*Icvf_?RH#pxAe|_E_O)D$I?>oP-{4?zE`oB)ejt*zb zLx@Q2AhA=TlM(rmzQ@I$Tq2O!#Nq_an$(7}o@c5~4i_XKp)9Es@M^x>NT@#f5@t-s zx%vue^xJC8kVnR1R#5gKt@Bgv_IWKUEelJ}VBvN7zn<}evem6wCw&f%o5AQ;IjHbg zFI}G!K@f}~kj<4>XClMRe<;jp{U`d7Ilz!}Y{nndcQ1~g+GHiM6GpT$0@*O6-y<;` znP7O0$XENE7$nbHKemARlBnH&>w_IkJ+H2t)H;V8rcQ3N6fS2+HsH*rWn|UfXe!%< zqt4V6u0}h+3xrI#z6)h^NRIw}lv7Y!zr5z}!%bJ3(p)S-+;7Z!8F(E1PAWTzPYRj~P72-mwk%5vQ zy-C`rWkb~-vvv|g)X-K$JWsu>d_jsKn?LyjYriwKY$^-wC<%9voMqQ1sqQok1y+yT zzkI}`x(u82Ki9l{7k7WvmdB2Ho&5NZ_3~itmBpj)HY`eEBAIA2*?OEm;?0`QCvLtD z4A)wV`@pUs6=)S%*G<3bp@=knU$MoUdX7v4>Nz=MKPcdNGoPzh zGC#l7P+S`=&jK9wtqz4oHAOyZ&d24VjQRqO76>v>x2mivgOWH=V*p)So^F^-*BVEJ zcA1(&uRB_%aI-6r`Uum$LdXjjK8$lrxYa|H(6;%0@65h^T6mVcwmtTm}M?}T!>apPEhkX&VWGocp0Fa1yHgiV$q%v(_*!De78rhUDT*wZCP*13&+Io1ocZ^JMt z5nY4Nu-prS*?0+V572x0@i5xs9Gm{j6>PW7m`j?1KKD^>c8#8LE+G|LDFA{rii8Bf zA?%us@Oyq;>RE&qknFGF_wBd%O#4r_i6#hfs8|fI`uf%zl1wiYy0F0~ znpL!KE#>cNCOguL$-RK_#Z;2=RzEE1*f)p9paIgCb8j~gKaeW>+=6C3P&XhP$E|Tb z+oi>-915HisYSFS_-`%@GqQwT#^d^;7i`DALg$?vK?Cu~NYg=AWh&FHo8ezuSHUq~ zmp55uJXI9Gau6q->BJOc5UKhxSXCee0h<4&QhKX5Kbc&sEV~)JQ{itVJ!YwMO;C*& zej4RD;3>~XbX&U+3qkHzeKeQ_AVJV9ABavVeHUxDh0Jgv{xx3T)pyG=$VXops|>iQ z%7}o5jP8aj+5G43L&_TkK>?4STppwQ6}6C!ZG5^jm0ny|mHN3jJIdLxdggM{-&{gt z1{!KXpUotEro#2RHf0{8$h6istoqvmWzXmC_?{BA!Ad2ZgO_bDmxs=Zln#nobeoMg?S zO}^yJ*M{y3g4HLt@@(}|m<;rH;^5vuLAQ;TJnOJ0tJ`Q=;NScAC+$9gFr?n{t;$Y7 zdmrhOXVu6*@TCLKCi^$xksZWRbGUD|H~rL=*Z@^V9Rg0NTw^oFx0 zc#Cp1A21+4yZyqcix-MaX|QRN&(K$4@&wjM-+O2zK5@N;r9$cHe(pMB0-ec5b%?jHJqBU7i z-7Pxyi5dZqO*g=37iDqx?l72)p7lLjuNArKAFnro~m$c2OVZRNr@H5g0Z0H26 zA)IFS3I9MMW}WO(ZRiYQ?uJ%Nuq4u(6MrznT?h3HLcIVEn1aUJe)#R>9D;#6HhFEi zcaeH!>G9g0Yyi&amBBTw_YG&H+E zC@;A-5qo@*a}eXonRfPM4N#$Kh?QfXmx&mB=tT>ekD&H~{v~GoK|3EE{7+pQ7Oj}J zm?>0>twq;Q#_)ULkK#2%>d7W$zgxdYncNVkLVOQgG0G10gT`ytVyo|*N<21?kCx2 zF$wB=(#X#V=oC?SN#A@vun0naWIE!j@edy_zqR_lxqYqQ@5~}l#cd-A-t=JI<|AD! zH~dY9li1a?l`N8D9ao{H#VbTP?XGN}`V=gtBgG4%L}Mk>hrQ`yssBte$~R`4_EFr5 z^E3vJ(|3}02NgepH!r;8VVPmnWZOt;#SY+QcHp+Hf=ju$8@(>JO$?6g+g_nY)6 zk69oame3&|^4a#A6PfQZ$ne}~G03isxyM%w$4Qe`!}@Q0)ajA?$Lt;oZxk=`+ZmHg-S zp2?5rg&CorfGTBm&45?7G9?1Kr^1nc2Yp@#mHi#;h{ke7uW?UN5;5H@@)O@zgZ@(tA?hTW$B1J@_*wTWS zdP`aWf1bC>^Zz|8SEklAAJFE;yY^K}tVYvkp#;v+_ha5F_baFG|6&nyS6*Q4E^-@4v)&6P3dt27RuEyoL+go^ui0wj zAESXqwSZKY0V;g#Af%WQD~9-)?V^>A&*<3(Tl8K=*TZ<0T*zr$jyWSsnx$~1?wc4? z7~7)o_QxrbaxPD~qOe>j0q&)-FhUMS3djIxutky;DJ@5A6wr9e8NQgS-&BuoWY^GQ zLHtyXNl(y|o^!nGOuS-sjwziJm3vs(I{T1FughAeGSP}T4`m+XSKhO=1q}+RD14>} zI-&&ul6A!n%}Bm0FE(SI$_Nxel5!zR#5Gy=9AjWGiV{kZ52h3tPq5Q}oYEqxrB=u_l=AwciBjf7VF0bQSaL?J(O>3>3o?I$ zDunyZ?dn5FZBkgvZs7i_{fCeo36p>X>rTgi^sSFX$ztCVx&mOu3M%;=2xjDKice!% zXDUO0V ztDo4Er|Z2ZQHYg|>B%7ACJUd1*g7Qtw)+Yb;egA`dtc-Z_ENzy#^WmY9bQ2#&O#A zpah(RT=c@k4J^o~@lezJeK~rGZzJJx_|4o?mp7i2HlXA&wS5gtY9Bx^=99f3b)Xkq z=tT+h&262PfK)vR>*)2v2hBBfH^49jd{Jo9{s#s3CK{_viOj-1K$TQKoV2C8Ur0a> zl;*jjkoWFq@cS-SLFc4Vrvd?-i(IEXYU?sx?m{7IQ3FuO&>~KxlaV*GJp`abb$`L0 z!G8IvTUU846eYW1)_r%6+3c~eXfmr23PFfc9gCUorShCH3*H}X?dgn3GeQz-9Kw6h zlK{d6BUEQw06G(7*E(YNal=kk)}IMcorQZKk51{$k-8RsNGYq3!*vkaLbG+ zqe3C%?&cChB$9p-!6>K9Fkobf!0(TK9dg>62o)Un;%`#!oBrwMbH$FVhb*l0xZ5+(5u z)qH+F4ophC7L0#o@Gq5dG2|@KVEK)LohU>?WPDKKAzZBZJ@~n}EO^@BYZ6~yUFGRp z1weoN%le=qziloA|6Rd9TwURhdiR_k|6~0ljK7oK|8IZhBlb^k^CRB5knA^~Vm;ap z`zi54nzwe$Z#(DpnD#%J*s?$%vQNel#36(IQ5?bvW)m2rDR1d7;@F*&6xZ?2<5?gV zmb#dTU2|qEDY6n^D+V@j{M|{x{l)w&W7EV7z+Ym#ki+*vB$fixg%L>}8MTa23zTB+ zVjx-YKCB`W1{Jwc-Eg`dOBf?*{u~KO;8tQ(A~Vm=+^olI2|j|M}jRu$9lfaAa{__^-d zS1Sp`bQl>$8BKEo+6KN)%7bV|H%`caOny8*_o^dvj+kz_Fx@_=*I^evh;zNRm3_ghOIaUn5DfntyyT7>;VfT?U8X8__cwLN?hN-qp7Ui|< z!eq(<)6s=PCkxRxlGsy+x#Ebq5#6Lg1u>4b%oO)(!deI@t>H#L%LWSu^(dAsnIjfL zZe}duMsKSHPQe08F|ru~n;~bZSz@zVXY==d*>)A=+39=f;O{s_H`O`>N6m2-#Tagy zSQXR=t<_~1F-~XxpUkv_&$&e|+r}&Te7FVFQ~#mpfAp>gO*6LSLb0VJifUc26Of7L z1^WcUGXBA5AGZJHR?bDgc=XFUB60k)58F3x<@t~NvF`5oJIbx zPk+oV+^J)|-PlD~588S2GcsPy;A$QT7zYC!l5vQ(;ORbdvScrpp_n7v-(%715tBC% z4G}I3-pP-sBQEsTDheZ@)dkM>>;1F@?EBaE3Y>ZoF3jos>JRLYqecR`MgEgdf7Jf( z-Ou!`$D>c_HxT=t_^AD(y*{VMFylYQuj%JZd@hJTtipwjj1S{x8h;%ZVg6Gy{ZcJv$1f9TmF2*yMAuvf~95E%Y<%}DQ8VpMu!}f0ezK0Ny z<096ZW^O(w@42s&Ok*&X1uJGOCUNlnGX78V+TDgKEC*PR>umI{+pRibgCim1#}xUH z;Df1Fy($-HSTIqtz|kGZ&(MRx>%~lU;qM}gz<)km;kSS17wqgEJYU=5<4@_o2L1>7 zXX8!5pFHsq`^avubLzAz<5TPl;&6-iTJ(Y1b4cf2c^mh&n6nHng}_U_wcb;wH9RrN zt8%h;_wfqM_DW*G0KZ7$|!7=@8Qg*^F|f?c>Ih?MSf~-it!L$8-4}j>t=i{1fKf+U$k?O z%%WhTB#x@g5#&NUQS3`b5YviGo7a^`)6XzaO`_eq8sSLfAyAKzMiL0FVQk@lH%&B? zktM0ecNCaS_1vBpBTu!10I7c-=_gRPft%P}H8*XXGv`?~BIK!>T(Q6qFo7|FT780E z4DS-DhSd36Nfi6_5-a%Bld5h7-ri^YcJ>0@Yzv+Pp2dxBo;zCQ`Nx0Gnvb7R>FT=k z)Ej}(SfSF{cd!m42?D|Lwy3*cA_UK`TRjM%wO1*k!!)-OUtnTbUUQp5Oc9vE$CGd@ zQcaP1Ft!9^$)J^FSXl^I+>2P3_cRS*7W}tF3`VZR|Fa@TY>&pkUND4~FfMx(T2w-c z+z2Zg$}G8+r)U+lbH%JCeExsr%U|T zJdex)@|;bp_%RnE@&L-1tV7i@_96CL_i|3Owt2s%cE6_daXlyAoH;aY-BL z{4GTn*5ANdeBupdY*e>cECn|1HfH4$PwH4B<7CN=^d3;)ejR`Td0SSh3YIhAFX0WUE?d^We8w z9&l><$75g6zDCA-v%vf0CZ+GEjYp~h-vj=_;5$)#dsKXTx4EgPo%j1+F0$tE&Zf3W z_oVM!BN&zX_cw23upq;N-M~bkgJ;njJ-mzF<0+vo{iyC^GN!b1wm542K8py^m@+qK z8co++8Ey@aF^HQ8wXoifgK{ijF>kc;OiP&QJ~@33tv+!*-Cmb-D;yi>IGhdhK1dCp z<90KUE;tZ7hV|f<`+mH*i}Au9cr95^zpwB6h-H;_HfFFIc||uioER9y-F`gw6;0+j z??SvEco)Wf=C#EcU=nMY2$Z8}|q zr9Q;G!Q~rrw+HCrA&Hql3%6K;t{T>z4bNY;Fjf^= z493}LTnKIoJ>QF=e=F>h2Qi4-jo&(>v8|i~G&l(CPx?xS6xeUx*LEX}_D^S@stL@Q zab1zi$wcX5%6TqExU9g1wPjW&Mwv3>a5N6!yqV&4599r>{lGD{8&zBuTtr+Va4DI< zFC-p$Zjsyq6NrO|{i21L*e}?hdiK_H%-0bYNhTeF%W|Cb6~Tp2;>xE#WLNLX34bev zWS{sG4k%|ok%L$ZQ{j!!se;%tQT2IoWIT%*ZZMmT>rH1STI zR%LRG1HiGgo*W5@hi;DBJxCjS)M=`7iDcMe;#`FD87$JF~Be`nEMWP!)Ew6EHP>Z;;F(_`|L?lPW z`w2Xd!!ZKK0vwkM1{}we!^w`PYyjsaE{4FBn6n-N&4fZJnV1yJCh-0Vx&hehxG?rQ zZ2^p7iE%S#=q8=c0T%`516+_dWzPlU0)flT5|;>bn6QxU7n681d7K?cs3r%=0UI)EA+i-6=n&0a+wSy3<_j=I0h%vB6vko)cw(^yoahy>O@N6(5&MTPKJ}!k8}0&k zUx=Jk;6B{x^svN%V9dw~RAWYeu)_|~6f^@gM9XZ$C`8DL*XmDV-gVp-O~9@(8(D0D ze7tCV&l`fj@m0-Mn;a_KNmEm`*gO@#kJ6DpCBW;3`36wekTU&q-#h^aws66r z>xe}QT$Y=lot1bg4)GVAZiIsv#I3}s)2fUPb6-|+AeaJg50U$2?8iY#!-@Q{BVpMf zM$t4UA+JX{$Tf&18H*SjM9MOTlPKL`jHBEEGFZ`w9W=5Aal7%@7c|nSFk3QaC1wh!(oUtZ>?<)R9IC5bCc;iit?Ht`J$d?Vz1 z>&Q2G_4Nk4pE|8t!Y~h(X+oc114ND(4jhs1 zN%toJ!6BSL-AQ=JlgMoZf+-1`xsdqn5G$i4F-Y@yd;#M;#@PTbMfhHIgBK2bhl{WG ze08(&sV7x!#%__0f}GuXpVgVPti4}~h7o(nC_N@100l{_>v4UEDiTxHNiuOE&@O_F zL6xvgP-GhcB?(l8j^~-Q{aD%F$ZZkJ-;9xn*hO8YB>gK|_P1--v5(y;<_G2OlGMvmF1eq1awl2I|mj4b0Awo1Kvjmc0A+&Cn z62Uu5{|8#)-+MN0=!l3V!C)s07s8JSV(@t;CX#K$Yg;i2wXTh>NAEYjA{YvRO3bNRU_?f=NJ&nT9lP*D;`iF=Ap=yNjHcfBi56<48uA_2Rp%$UU%=rJk)StQA-SFo0&$1mpk{A zyO>M1gzIsmjeVl^zwIPakt&yucQnWdsaN3Zb_H|8 zjaI&v$ON}FDJ24=NOP{yFry(@x0uAjjQJ?$f^pU08iA|LCf^Gg7e|}7Z@AGTEO}Du z65D%#_Pp!DImtYuQ^4=U*LdyfPcqpoaU^e#k=FOu0j52UZ6on+rJhtyTZDLs9%1z) zWU@h|PTO>*gpuLjli!ZFX;Qay2p3zbK{7@0dceBD24a=KDlQhf0xSq>3axGc03ZNK zL_t*6XmW`_!vagu^AZPJv793e)s3BMQHuRS9OpEpOo>padDe3Nc{d25A!E?(>&tTX;sE&I7TB0y>*Uh zpR?|x8^qr=u1WKj1zrgi&NdrVtjR$$4lA%97e_yY*dO7r`JV59wZ%8VPf|^(e`1k! zgG~iC18k(^swt6Yq8Zz@>=At3nh2gVj-)-vC?ul?qfFcM;a0*$x_#XgfSk?~q# zs$>z#l5o0OBId=u96_}uwAG%MitnUUvrE=Ge$XC8&HMNKyTdwisXN~{5iUaX z9YiC#5Y{q45KGa>&CL>kV;pH3hl7ix z9>Q~#L-Ks(Xz<%JU9VuwBd#H?1h^WFs|l=r1#vY-t_?M~x{)zd4NNvNrf}iqBPI?- z@ymEFvuvI_kCTijQ?BXr*^RI1G$r3KB*(xk8?4A!P5}F5BJ(k@U}7m@U6w7flp8Bn zVyU#rN;PA(-`IWRjHZUy{m2?+rlQZvU1BndZ84UXc)QP|vj#?BBqs6p;Op5KFd8HG z8N3f;M3H$juA1kDmgWe<#XyGAc^b#-VTI6SAzVjq?d}a5{YdcwLQ5>qzwEuQF}}t* zPHe-Bx`{1BO&N7_F~OMU)Geb#q+%Ia5+NRvs0QClSJR%S%Fe=)ds%t9AMZJEv8?sS zws=0Wfmm13uQV1yWI z9F4|(h=U<;utSiqX>JD$o=C&s%v(d8g3sOKHlA6GSyyFuDq3u74mcqH~q9>QC;=) zAwoO%O*pAN3y|Mr)bRajMr;Y}R;}G@Z{Q+6i?|5nHHunRY>W3;ry;gjOX9x!EpSlq zF2p8G~;a%P6o%d9;4l(sNv$~g;;5W;QNe(RjAMwP2O$)P>9tnQV7xEIO>E^UBbm9 z{kur@_+V62n0|;!gW0rp^b)OeGwLydwavY|FcfKWbHmTbg1PzW#XRy-fbW%t`E%Q1 zxe3R6>nFh51os#3nd$_K<^u4W(Z}{Q@b(*>ge1E7niwq6Z&J-h)4u zF@G;G{pRJ*=^6}Xn__nQIMqfxemqm5!RxNzBQYB};Z4F2bSwMxMi6HgPk8pWy!3%*aD41poRbP^98ioTyN zTVcv;sa}2O#G7(_9UJL<#nv_ASjcau`s*a(AZ{#E0@fs64e-ra;v3|Ab2RdUo7oe0 znq74E224!H;J=mr#+b(E)LsKbNcd)hjp%i>S%aZ8#|ty&9%g(Kr#{cofIXd8>yyo>oU(z_AKOSQALlm~CfP4qU1)Y2HpQmwNp zW5S}>Ow2gYM~pnj_cXadVN$t$e=6!2%Vx|gGOs|B$bVpPUB*9_8@QQ7#WKutMu3@A z(?0|)k%rN(S50dJa0zi$Bw?YuXnyfGzogNz29?6_hz8{l7*hxSDDgW`GNDLo({T&T zL~$aCB~9a;%A&5h32dZ2-)3|{esBXh$2FPn8PlP3?-y?&QVqE1-zlvx-reXnT*x7r zlZuQ$hFW_|pF5IxY%-qMW-|JQjlzhsy*KDIuekBb?f>`MQ0j;5^d70VY-w-a##$9G z<&VitG!&?ldQuh%~c07jOGsU?as2*IgQ~ z>Zs}NI_A98`}}?jI~6aH zw{VI{^SEVZ-TAY0z}Aw{oCr5?pm+QNUGuQzYTB^8DjDL*D~ z$9*=gP5i!$4VLECkOn6x+i7 zsg`HJL|TuFdfu&Ef9v=>vWeKjk^sBUNo&#TbSvrD7XdI(!yfB zr@v>=l(F3EIg7dIHS8+|*W4o4)sf4@$Yv-}iaxf-gByU%C~&}XCY3QA#B8hH@AG)o z0wqOCX07#QC$r+)j?~NCIS&^(uA#9hQR~T#a|1=^7nFfvInK48X-gMBe<$(&PW;Ie zAGS+(<1-K9trwsCqNeM{L>=~*GafYK-9#S1I4Ut~ZdU2|dN(o4ytQ^$t~;eUF3NL2 zgFeQqN$Uo$3+i zClN=?#a3tVKFM&Zb2=|;j|QVR69uL;-QH>Z*YQ2xk|n*y8|kbxs$6_4^6&@YQPl0X z0*9@{yNJ9;;+vg@Sjtn6xP`rGC|72G?ZN6o`49>CBjo#sPD^ zf?nf`Be0FPwSsGlTm$9}R!nT>#-_D-*CpKabQafc+LwOzv%OBV3|zsn_17i84O|yo zlM8`g2d;niV|M)xoa(o9eDaH$Zk9N*ZH#r?#%~{|yOvYOwP1GSct+#$i9h4Yn@wk8 z5QBIl#^YyHI@jQUB8NgUkTAIch8ahr+_1=uLtU71uPTF^gafS>>$A1_@zd!! zz4iCjv00i&cQQNNh@AhUkJ$|kTnBOY;_hyu-h$BrBzF?DE!}o-av|#6dF~f+Anlb9 zSWYT5g}~e>V$6I(I04%lSZfBWanAHWLnTo}^be z$N|T7oE&TN=46$fghQYip%!p5s*IS3E(N)@Fp{_tfpHyJOFv7vaKu_Fn6D%N)0)Iu z2&^fxsK8nfYl^I?!g6VomBmfg?snL?uoztgv{I1KVB1eW@J>!qj35;roY=f* z$&FKm;SMZDW3iO6*xX?8jUoy*h&N~S6IhI5Uoeg;azAj)U>0*AU;=uM?6ra1;;ZaN zT-p9S1tX8pG#B;T1lG*+y9LBmWn4vE&W-1?$Xv)-QkCW5I!gnf&LD0!3IKMk!f-#q zQ4`a00hr+(h{ZGPyjN)#oarzG>{oP7B%RK}b7_X_Z+6p!N58Bimh(Xc9Fn$t0 zUv=Om;A!A#!Ly1y^LjUOAN{<>!w^3e#a}fSQ2TMbh6pe(@k}uOQpR@;o@rKi_78r} zwtnl3#%dePT8VuY*_Q|Qg=AVJm^CqL#y+(h-ZQWroKF%8HCT|C0~QGG%#GhSpILJ1 zhJ{AX{Ms4|1B0PK{IErr&_h2!LJ|{Zd&92@Y#Ir45-0%`q6?+ojQHlS9Xp`t~^qAU^*F2gqR<5^&W8zRE**B9&Ue0KibqmW_ zPDz2`-1|{&;)@GWwH_NFL@|*WQ_+PChs=o|!x&?TVI0gkgabM&xIshj7>*K63p5f5 zu9?WTp~I*l;Dp(7BFMMM&;>C%CJ^*p2aKizddqfH3jtoWPQ%W1=T4@)^*k>9WuYY^ z(Dm@`kKBI7gEO&H885wqbv?87R|g^c#)1QbxU-Q&B3dFBF4~<((MX~QHC!BSBZzq! zD~MIWrnx|VZ#{Jb=-xB;m~6zD2(z6J39NPW+KCM+l`@+-RI|W%gsLK@j3LXZDp0k^ zs5z-^C`N`VjsF?TkcG?@)1*?{XNzH{0@-+99L!hEal|Y3^g^)yj z)HY6%!EG77CgBu>2;`~O+Y~fHGEX*RMUmwYxGr%WaVZ4O39dB*SK<~6Lw;^Hn!`+F zHA;D4)-sO8$O9$gz8E=5;3(n%j$ey+y1@gw0l+SCh9U242$09swAQIAtFOKNxcL+h`aViTZBfI=Cd0J zNYx}3%~;qAV6W4d{*6R*edLU$!WQoN@EXLk zf=@R~{NX?Ukj;bFDyms~JQTSqKp_ZK{25~pF<*>Z8cQ-Pz>y>bGfYke7l{f6RTD#k z@zkTAq}`);fd^v<7lZBWpNh7*7?$YPY24j4^7W2kG!TteUSzDBW54`3U4%7HX-_Tn zWrIOfU>!G%D5X!ff(wipMoy$g62XxhJ_U>E^BH;Tyod@ef`a*30Vd_5`p3f6>`R7U<5H~MkN-;6Xw@RG6XBh1u8NELl)go zEY%bCHvipDSWDE##k=m@D;J_U5f|8KTBIRk)1aP<4a;aEWd6Qoi86t5GWZ+A=Yy=Z zp7vhjH^0wwtU#nL7q40~u@c?HbSc1=xgf@dj1AlfYC}dT_?YXeyQIEsR}|tV24jLl z=EU`5=Hs!1V?-8Y%ptA><687S?_tDyfEmObf#-2tDD)9g={gPl-PrF$o4t58_JgYhQ1 z4hC^=!i;8A*EKJLhT8LpRA75ua3z=OMh2aA7 zJ-!I!7TsvgioI|uPRbbWC}ehu@!tGr6&niF5jB+RT#g|IuS?WrEu+_#;GDIEvs(2r zOV5+MK33q20Yds;jI2?n5$e>3nv`p0-l@QSEmE1+eNLwLU&edn&jHUOULo-Pp>-~A zj!`W&8IBoKmNTY|L&`ahaZpaIJ`jv)i3yAeoDVaMsHz9&dNb3C8BIJl+%jV$idA!R z-eU0jV?$6j-xJOV_F>GJ*YdW(f>Iq|85d4|4dZ#sdB!rHslgBa@L^l;cN`!8lKxx7 z-#6Hx$xp@#%LRTT1b#vAU!)@VR}*$`&w}vu5CrMq{PdCoZ->a>QZr`g{W2T;QDIwpF*IXUzwZkVuN{vGx9!iqJ$JEs&i z%b1H^n^}{H=0ZHCn6W5h4Uyv_k#D0L54i}uqC_0W*f8TU3ge)5y{k^- z_doM7`_!$Tk2?{c_>%r7iN8y#%gS?%A}9C;KDHj9jqPXx7lBvx|FidQF_LZPec$g} zyDr^beVd-1>$&n!6lqeTE_7@qRuIUNEnAj?0Lf7v1R69E9E1Xxmn07X@^BvW?!-(~_sgqEQa|FajWP^%9Q>1uEYR-MGeZSUa@Ac2aw^r4z>gt}JIWy;4-=Hy7 z)zwwIcJ00Pcm4h0wE(XnUQ^-sA4udwvVZt5SPPLg6Ke)*>6pHbcoMiOamoCgTTSsm zhttKnPI()SadF`vOS~40x1)F~Ku<2j*#MS;xD*3VnsJSaYX+C)x$OG-GBB|#I3#d{ z94d_qgy$2`@SH|FMhA@s@6B!E;-?LBF^P8%Z1(TT{bFCcdlID?N9kI0h}RDKW)7qW z_T+imZG*#DF$f_E|9al2tBPI`IEayB3I>8sf+zkr2EU5W2}F55<*qrT1BqjU8w&hL z;>U$}CmOf2&#v58>>}44IY={uX-BukN-#Py7H|mb*xF{6#NXtxa{4?TH>bx49O7~G zu3$G92NBw4{H!8h0Di_?eDyUPz`BOdXC9jIJ&ZqB#Sbi;3bA~wCJ{*@qo+Q{_*5|d zdwG5A35&@S_v4~x-iy5s!+f6b-m5!^dj#&8!$h z*nqM1UQL<<@#lD-OOW@--j>o3x#$!4Q^cRi_%jp#`n>=Sf9VyiHu`)riq9E*R`5A< zLFi|3|HAwG%>9;}*UtTNk9+&FJ^zx{RxWTQmaGOBk9dN>n#4uKB?~N@n3wlCuheo` zZAQ7y^W;>77^M7ekGjBx|7;<433OF)V1YyPT5YcLG^6)4T?yiH@|#w05NmV%jgT=E zvp=nNa%je`#1?SR;9e9vA#h2N{|IAQ;{Oitzo_7jRWwyln9oyP#kfM`I>u#;Uo`I- zS!djLJi>jW+c@;#rd$l`9l_lQw~EN!dFTxatY5IGK66FEd|n@i(CLuGDn@y_H5@*@ zNTd@2ZNVa!#%D*w+ZvtbWosSbB!xsN0Dx|`SK zB1X?#d@B22M^=l+WE_w|!Tve>a)A_wUl{8N*d3G4`Zf;zxGAwipldGfiA0%d;{I}? zA)}PhFfkvDBFcrXQto>mXjmj9k@9(90kMFwAfFRhJY|2ybd8PRH6aO0@nbMw-+VPb zecxq~k6H*g{k?!H<-AD#WWnUQY*dOInz4tmLu419P1}!R-;CWDIkw}9b zVN^4}M7^Ka1u611V)VawM`DA5d#%Xr(x?a=MXU8;3}~v&RqOGI5cq5bpDV;w0#7J% zW%&8LKHb%5);7cLT@cr6QX!oidA~kbw#QEZ0l7{dQQEgT=jdzRAj*Y1lMmI+kAeG0 z02U}nLg}XI=Ttfdrit*)2ct=>eTV)EV>NMU9Q-O50UpnHPl^alij#W2Fr@9Y+H>mL zGY(7lHFEqjJqn+7(o&r=S(VojiD;h9jFxhsW@$U!kqN;F>6|N4KTe3G9A@Brb=e2V z84l0aKxHoS>O!%>dk}1N{!YSrhrNvXcr!l|V}vrTLzr_r9v1Q*@mfsFY&gT)L)s&XKFNY{k4uC~qSr@6SJ zD5O9uOv!)d{V`>Gr}opGQX6exCjgHi+BRiwMW+k+uADf=?bKd{CY%(Nc%RHgM<&cB z1(=4vV2_c%=H~qqCm_x8HRIsKYsh;M&3nC;BdnPBC#=YCuQJ-lMachGwYwtnH;S~2mr%E;eD z{7lNduge)Ib39Dm$xy2DmC7|pOFmgPQ3~!5xMgAkV^yfQhx>sCib?DuaFlv(dk9H1LZBJNoOvv_ zBv>&QNuJDK9V?4nr)yR)HUyhk61;}ZD*Ek4$>!I7lg$~+Wo8d!zw@$|=fnjwu2q36 z4daO_@|3}og6qLpi()mMpDwigp!NKRwB$bzOsOV2nrX}HLEU<|xX$KzYFaa4fe*fY z@muN?B}>4iqTmS=>#^W+DESlxPs&B^FXDoUbE$W}0R)|+U*%LgU)<+;f>Bq^w0NW| zXLD^L?wPn99rU_ocw7Q(Re{YQHd`f||MWL)d&=v~>?3S1d_xP378eKb6oDsI@lz6? zBJd0@DnAq$GVjd|wLI6Ou``Z&a{;ph#D?ImiA@FWTE#mAw({C)34s2%XNqPvvk$Yq z@EtY7CKvjV3qf2^V0Fk`aYoSv8v(R0LSk$9?eW>`QM|Azv1!IVEZt7mm@=^2tSGC% zfJh+tHPytrC2j}CMZ`Lpi#LVkB^Pbll(B2Dhf?2Ipp@rUTLx{3PO8!5?Vrpy4R9fa zOw+9t>R|+;}%%g|5FMdm%`M|{(xg^hbUaavCFESE7xdcPe zu%V@6>>kEVBKL3~=9Y=OxG>4BO5AN$-2K{b*~WYQ`DQk=kD9&kZLRdh zQLGzWPV4g(ya(}e`l;uq4)I>RI|jF+aoZxdQ|;nzh`duq?*74VaOd6TjWS~|cr123 z^TZI(Sm3EBE}E|=t2kqIGN;~4Jpp}H z`!co*e|&q;VEYe$m94Wr_m}^#?UxZ5!9(q&@?&YIcGX7*vS7rw321RGxf03ZNKL_t)QIAE!QGd-6(d<=t~@!ae&cFjrm>k zX475y;Kf0R98`h6HP|82ZTC4oFWg~fkIugMEp^&(85e?Bm$;;q_%LsXxCC632V3jd z6exi)AktN!Z{Ap3nh$=3RD_zt#a>Qps2^Y)ndr#@QDyK(M&XT^O<8KnH`*!rf10nE zfoHooxc?{xKL@~(TxesL$WesDEWm;J?+UStIb5PSU}xiq!}BKZ$COk4e6?4_h+Za%(k#yhHbyV2o?y~tZL?c@;uqxLhG!JHV#bQZf(#KB{I`Jl$3!GQ&K71c%;%5avZ}2%h2Ur3>2L2u5y9TdT;)e$Z{N#T7 z{Y$TCE(};Z?U*^mC%6VDhZ?w#KQO7Z{ZSENnc2)t8h=lE1{sVV+%#Lqs1@;-IGmNQ0(E0}TgIAJ!rcnCJ&Mj9$FlAn-Pk*Cc)<@mf*x z+VA}quYXvY`zM7a`o^-_qnKYMt3~qSED|ak<=@P~AxpLUZNjLoGCAxe=-Bvox2(F@ zgt0oz3;F=&O6_kOFgEnnPTz5U^U1-ohZ&lCHzqhaP(^~ik3Hf;u{-i1*8jY? zcp(SPG-b5#2GS-zSTlYMdp>4>7qu2epG9Vn|qqf)5!*xj&zWWJ?m14TqUmY1lBP&ry<(4{vU*(Aev?6SzG;W%OG= zUd{(2o!P^g$79~q7YS2`FlYAu*l5tcrj&y8-T=)@)xMjluvLFfdxXma!E zf;S%|rh4JqT8WXh=m5qwt5`D|32MmWlT}6#{rb-dGan4^8uX$AB`bVwCxILqCR)*$ zHy=Vf?K-lD4=NlbFrPzw0}Udr1PyDM9|vtY@Wq8T-VHqDK`jAx4TnWUzg9(zC}F_? z8!c+rCtQGJ%Z$4w?wIjTCEhXPb%VF4*r#A%CHqyIvT@8_W06MpkcFbj)ynhNPY5oX zHx6FGYcp4wsLhxQmv7@Wq&^Nr76%di8!6Jc0Mdm}w z2a-MQWhWjvk7<+Qy&2g%O?OWs^?ccr`2ZBSyp#?%=?8gj* z)v({E{#`Co16P?5VjQn4*8vT+?OCn+U-H*kPw=5E5Ht^I^>VNo> z(Jo;*K{8qa7Ucf>94;c)HXkOR+-FL@Vr8O=hNX0~(sl2V!sF91*G;#FfCUR2%C9XB zTS=l*a^Z_X+R}YFWC+WUmWas#m_KhWo)Ul`nDJ*-^JOG7{WB0Rtq?1J!=RcoUksiZLpvG`XV(Buj8KO7x<-9W=yAf}I)rP>g~RXqz2crQZK2m(fMAF?usPc)bYSM&4iFy-a* z^+=Y$7(k_y>vc4Du^Xw5T$0x#z`XyXNUt-3;`w^p8s4q_uD)K`NIVZ*z~JQd!r!Ak z7W?|&HnFn>LudBr?0oa)WWUjSX5#R>50FHfQm>jE92Qe=Tr|&R<|=Bm5meLt&ha(4 zH};Oc)r zuB#U4;B}i8_dlaEXw?y&<1pw7dB3L_+lV{Sdp>Vr+`vT#{s)XdRK*`?p8a|p@Q+^B zr4aaEf&W;>Ki=QvzpdBfzxuM;hYc>8Sc?@G%{-rF#=0UGWy2xHoa4%a?UO#$033*c zLteHqwr!#Z57?UM%h;|D{k{02!rT8ozd+=-Wc()Z1z-!~Ur2nj7x~{;=84^k%c0L@ zD_F0h3tnJcF|khInu)9O+|C6id+kL`Vz4lMKz|?Oj>J1b+>yhTZ>7(6vw&M#Wg{NY zq2#$>JV)eugloZgPA>5BbZsA1>2;fUJt&%SN5&0sww{o1eF56?cN9@;?Iqp2RPI z{qNhW|K+!Ic_5w@JZta?j872x1P+mZhS7J^#{nzb(Kwb-hV0*I2=83NA(Us$PSh>R zMIOA~;yLJOfw=_JUcl!Tb_83&fqe@E+C)}T-pY>;zb-%it8;?y8N;|tjB+x*DGn^m zFnVM|k+%GqhxzPBCaUpau~95L_UQcz43+`dAIrmo90p+9Ty8mDQE@YF> zJjD~z)iX6;XF1HGIgPo+PY}zyO8@9fk!BS@{zQhgRI+he_8lsi*A!y4cLAuQw7?&(AF+3iBDrIb6`g z^Rk9GH)vHyj+&w@ksyEx;dN1p#p{YZjah1jf&Mi7OdLtp`M5%;Cm4c4Of6%Bh~ zP4wh&|2r}^h-`(x7INXB5IBnFbV?EMQBfXfxaBJw}a;q_JOXs zsCbon@eHGoXeIw;!2*l;8tFowCv9w2EzhQ%HMjotziT%i$3B|bN5_8WWi5B$k{Oo= z1(%A*^(wMv1?%QBVAtiszN>i7V<>Jx@}VDJS+T%M46FtvaSLaltQtNifX@T0 znx*?*mpUQ%iRUHqY|#$M-A)7hh3h^O&oB%-XlQv?= zUcgvGtl%v9g~V??8SS6t*LpqW$RfKKTX-+#fyC}m*aEf%yTN;Ec2%$&B0Gxg#sRzc z6(g7ID}T)DpvkH#R;?HbPf1(|#;RP%c7Z(;_o8vr;2p#k zzK(8KNFugkb5OC_y29p+JN41Fk82a&hsLIWB{E#jo7hGW=c|l=pIsbYbs*6taER#Q zLk}%{5IYNGT$*^>0iugBNKJP_G;#H~$>!!Bu82LgNI-I;XU_A?W;U~rl0E;DTFc8U zs=+EHOBPs6%{5ChS7tW=|j^S-!9v@}B4t(3Cf&H6&VQEW&Vb@iZ&(^JEV=LL8d0 zqa?zCL;v^iMyMk*wuyc_8hbMKRdN*C9Jae`Hv&h!%f$X2A3!X^2&h&6k#SLRsMvc6 z-?t}+2{atMp;j-5UIu$iI>ClTOLz z0W3Gfg|gua+rzb|rmj6vY{);;Ae8l@!#0c!^6nyb^KEJLGZPY+*~8e2uc&dm&srI{ zD6xiEQ{-Y4SAuap7*``)GH<9`#m}J*Q$Sj2{hxMDjRq@5BWDlSRN~E$mAr61Fjw+D zGKcN$5ZQ zUL)Ie!0Y1@-T3mK=sJdzW0Lx3RCRD z^yA~fi}_9NzMrBcGn?7Fv3&jnc`ZO$+%d)X_o)%|5c`;mZ^?804qcASo6#}P54F=U z<3l%ID-UKEl|@QH7vsPjhOiaI9gGbEhe2#akI@$a^lNuO=nu>Yg5oP)^LM~n*FHq4o2JGA-$ma#8}P+3D9)u0;%q4ru1%Rcm* z6!Kxy46|+H0;mH33v}@By-FbKmY^3LKG=zoLJ3l+n&?LewA1V6_gpcs1S*PR2u7~k z5|hJ%c0v@X$t1Y>Jv7w@hDbw-*ibn3NFzaufm}@Z7#y0cNFxmvMFI_TU}sy<3NE(M zFi}MRKR-9{u)rG!iB&k1ypMm!J#$F=vAJ;U5#k8g#IJ>2MuHB9xB&7_oHoD*q+!1k z!;0BX8`^tN3w`>{$kaxUs=-{V@7MS4JaZZ_*YKS6Tp5|Og0@BGEf1*%Kc6Lk%#67T z8aRY{E>&xEkSE;EIfOgNvzYJA+^raG=Hbv1h~c7eE$) zVmPE;JgPyPnLR=qCXewLKRq^lu8CCDEeveyTmv)hq)if7zp|n zIlza!4+!j=aZtcc<=3TX74rmE@HN#3!i;rX9PHxQXEk;a_b~35H-X-jxNC4%fj6nR zXU07>#)p|(6$dsr|9Vz6n2QCgMagPUTxlBDV_?n1#b~S%Ss<`%E_$^HESe1=NYe!} zlF)YUJj*n&1XX)j&`eC%@JdjbQ7WQf#OT+0|6Xf=3JU~93IdjZl^L4z*g*<-4moOc zee-qFI5Mw$4&*hXLvsjJsRUO5dKg0?3mNOcLb@L0wSGb7YrTyhH$s#N2%ZJ3d=}U! z(tdDw$7!&-EL7m&57psl<{*m3`?Zb^*Y!LMZ49WWi+1%51`(7*9E3O3D^>N(M3DPM z0T=RUnqM;-W`yLQH`4KxA?$@YZ0g*;PFmK=R2$4|NfmsJ$bjsaKraacKNJ)b?sLi9 zAB%_ulLJfAdNz;I5RiPnHfPt}ADN}kHb`q>X+}3jj?AI2ec+xY0Nl`5$bTCX;K697 zW48bnaNo!90f$cV!8-=an(oJRF?LPtU~Ee4V(c2+i?Au!wu;SW!CNJ4%^O?&_egy7 zcV5G5P&)oOznL}`TlJ^b{g$u`C%GV${0#lkcJyMtKRt_mV6=vW^q{a zCuUet{ax}ZHS@S1*vyYTw-LD7~+Zwkep4XB8n} ziiG4Va{^cw|xCG;%Pm)H$qls^v8 zD2*#YJQ2kw5l>s-I+0J~@ew4Lu#7G)3bSORx>`wsMJV!?6}(C0Ed|~jh#SqqA!6#Y zKNm+(GKqz%!S!fd4scz8OR?g5FfIwMBQ9fHW4xcILJs7YI0%8BL}{WC&Ep8%uUW)c zWm5djw|^Ul0_+9jP@*TL`33h6mhry4i@<8~mrsvP92&nT7ic)fMGg)P4x@3D^65wB zJ&?!9^BYMd^El_*30$x^rH9sramR3&S`ND_@VLqlEje7IopQ&`5Lk_oMZ}VMTx$kp z^jVF*i9ueo(`#mt)j}>1WbTZ(DB1A6EuH%x=6s(GuX}y@^|@=2(gH^c94m5c9!pYq zezPf(GUG25d7Z#t_TeYVBDa75rg|Gi)1Uw`ROSqVM<*x)|^Uishtp8f4pzx#)<7rvuraXZyZ zn>71{-)>a2Vp?Mi+EoI97Zn{r2jjoS_^jYA1>X*l1;Ir{e!;w6a0eGOoF~#^B(nGL zb*ztrd7PdFLM=V!cRhb5MnaM~a#&0`*F$;!wkHv661MDqcOykP4Qe2=RIlved8MNS zN}mdHN`8J}MiE6Ln8(BN>+Kw(X&x^?jw8;l|Q;2(MLNH+ah6s@$Ku4ZIfM4NZZl4qq=&5~0>=#%sgxc8b|FQQ^}+Kr8tooiqzHhp(?4CIpO=PvW_6zy5axH}D*IN#HW#6Y_oi z7dC?1nP8dIz`cHcFAeXV+{O;4!6!dRrc?*;&k$-ccOVI|4xdQ^42vrG^(78tNIAfp zn&@yK)ke~5$cC^$OL>5Y%_BT2>&x@IP0OO`4D;iax!{6nRMQD4)qc*u-C0n2km8mj z9BO@_$R=RVgDMVqA{1OiT#3edh^#5FhFHXB<~m9O z9xO+AZf$gM?Y@fmXQY0hv!3hFa-V-2UfF9g*R-5|nQA{-+`zAwzSd-s5*r@R zmh#0Z&yDZDW_sZQk2xP11ob0rzIcxbPy}4WY-rQOwIIXfZI}o0d!c?2Ax^~5k0BeD z-nY!|BMfV!S@@zZ)KQ|LxV%z6APY<7$1R=5etokcSU>xkjan?6g;y;7U!=dO*LfRy zoV`LB>hBw&Gmd{3UiMG(U~BB7&SUx-Hc&mMYAII}hdv3GuOYq(1vc#ecwhakRDY%wKCT@z_qi4+R?vz)fuJsLy!pZKjAy1W^)Biq8ppDo%<@1UPJVPl`%h`3}1? z2F!=YzVc077&LiKnK|S!@pFjha3PG`8!?(~@;Lbh;)Vrolr6qr7ykXY*^4hK-2M-_ z7ArnCDEYh<{Je=z0axTR&uyaDaydIM{Gq6Ert3%c=iOfp^yQ*|ImQy^JSzFT$!W6~ zU7UHcTl?9^ITQoA=-~*=A89JkG%+t&FrQ<1sJXGT#4Z}|QE$}DKKS{qN9f>3X`6Q>k7dl*Q5^CycJgPi$WAo2TY>G(U3MM^Bjw{@kBM#K z9FyAdmYK^lk&>Cs?A_T5-%&Gcav{Q68M$D_S~@q^Vn{uZ>3;fI2QD))ABNWfHf$sW zxnXcu#s*?T#zqm@h~jQ6*f`i_q*|it1MGx@4t9`@~#u1+P+O)tXk$V^$!+cns+Z))9O}5VCgP!); zPFo*q+=hI8zRdJKiayR_sPGJ zzNX@E8fcy44X-~V0001BWNklZ}MGBS_StYP!k;Uju^vf8l7Fm=F1}riHGUxl#fZ}!A zF&`v6!W(B?Ou#r&WZQgr;|PcR9a^NKfC`Qp-bzmNrkh3#D2NtfDMH&^2xOkfTvBsu zry+nPdHS6^29u))Qw46f({=?0exJZa*pU>!>!NcWW%I89vR^y0lp zP1mED0!#)$SmeQnIAqA84+hC$f_=oX1&*Q*;O+pM@?q*bCT<7gM+7#iz+St{_Qnx= zfArfnIb1cfnVo81eOc{6!AjRyX^7>R)^sx#ai47oVhj88L)F?WC; z8T>H%w*Q2{jWY1sAO4zcKCW&1;;sYhx1_ zibo`ne?C{2fHfSRegTK6&f~y^4lpN}4|RAr)ey3p+)8 zIDXy&EkrjBVzkrt4bn9yZ+qKnwGxdBcNAzS{6Q@zmhE(b(RXJ%jB+9a6GNdu3mi(L zp*CYQC@0@HbzzQusWx2a;Dj;JL759u)gMbke?wm|f&X_Vp3{$v3n&!EktSd-61#Qi zx%H@88Xp9#M6bS1KmU^Em)5w(zy}$|it;t_Sk4fOrPd^8scC7lK@PZCz^!RQOfSBo z##=p>)nL{7tWdBNU^$9qGggRPj)66ctN^R2aec|46CHxQfD1&l%pMYm>y5enluONm z8%H?cZ9n-xhcY%12SM!7;I1kTNTOsppDM9yk!~|`_)+oopMOd7>kG{FTFm26V~Udb z+|Yp~@r~$$(_tjIGY4Su=jL4a8A2T{(gF1~V3`L8X^abX)J1seLLCk|aaamNpvoM^ zT&nLnoF}qWU*pXMly;FfgyKRg+j60!9jiEsfo|at_0l43S%O46%zFXo$oEBu3TeZ(eV3I`AUH?<)e8G91X0cNRnt zgtS%{K@I?_?Z6Mq(RY;gmCTST`Uw`^$o0NdC$4{<0kEH%OgEzgF^B%2#c?0e9E3CJ zM~?fblj0Ll633wr7TAdzJ9ZB1@ZqwgAKIh$ofP}310aUJX32BZ00Y4sIDm_g4k5X? z-+0T!J;Cb+uOsfL;8tw1-72^_7>s=9BC@Or5uK`H(L#y=jd?RxB(5UX@nP|0jAa=s zCRWXdAvNWFlh#3uu zMKhM=03HWFdhS_pLTK;3uwmSktV9#Q5KI2oxb0hQf5_K}opifl9&0Wo=;0c$nsS#J zUEWW%vNDa*H6-TG@cWNY%4wz^4-4!d_5}xK90(2z<8~Fr)7}xOsufni#xk~$E zTVl%`K)p*~Uk>&g)S;6S%K?h0Q4Rzbx>x{6`QMz6c(=z%Deqax(6xxwn$G>cm_FQ| z1&B&H0ImyEGOFPI_`r-ZI@D<(f%#e(@N3GPmu;vlGB3yPnLPFgCK?LN8<>Qp>&$!Z zH;W;t3-j6(8u_+z5>(C26=ZOfF?4MH9=9x8UTu@6Xm*f4a38!b{ zo(%#Wp>Ww4>qlwTuJ!tU`Ua zb>(81_e`lD&qWjS5LAIfX|7>hNI9)(`|Sw0i?}7&GWVNy3=U;Ua488Nngef_A?0J; zN4t>nva3wL?hbIDaR;$$#!dppc)w9#N8Y!(Yf1bB*p=9A8he|&>`xBOP1^6iqQ!2H zUkc)vG5(g|m+^Dw7RJ9s{3|p5<&*y}|Ms+j*)P4KxiDaD+8{5HHH>FuTs8lk7X>Tk zb=1k6_<$tz9Y;MVSv;|ci+r>>39s~eQgkSB*6fL*5j+((66?(N{^wmhPnX0SEyX+% zF+exvKaUmYs^U07q7Tg2RAi3^yQ(-)#Q`mrOfF`e`q|b);0fT89H>+mwCV?sf##CP z#!=eeEgO#`C+&byzwCa>-|i#!qYp#wn|X|Y*UZdB2!SG&G(*8$bdk|jBG)Z&4Y*9? zB7sFT_5AW{+4(>t!jGQ=M&jO^=Fsh%(YTXh`(2D3i|hoU5SSkronSmiS|Bt6*KCD1+Bi3u7)+%vDAw zicd;h55|*b{B=dz8RTlBl*i1+K`hBX$8oAnHZfXO%gF;I5O>ZS88zWIDP2cq-sDt! z|CfiEebmjv++m;P3A5TYB0YcTk4m*`+W3L$uy@amW++%MU1v%YlCKHtcwX+dLC;1a zj6I3v^xF3TEHJQ0k4Yg?u}>JUr^iS)*hEe%aD;q*0LWsL$L6uYawVQF#B=8B?lUPj zacIV?65mt78v%Y&i48TAuv*1W2k}O8z?O>9tdbfWSmfC%@;_m0#FGEc3J!w{QFK(& z3dUS1E`-2^BJflN*UWv$HF>_LVkAfxPV5`=|HxV-?!%+vQM7B`)EQj zL9h&>Ecrg7sgOW6Mzr(AF^|`TXRY!-kA!kfq#Dl5ILOpDeOz#~Ny;|`2+_qevpqKW z_1JnoDk6=2bE+j{^7Hiw>!s;@kIAQTpLNv7(!P$R5Ls^cwyi|5ELaZ4YK*K{@cZU*(Xx3j*#*3JA;(J7=cxo1D5L0E>QzYJR{=Bv zG%BwLG%QdMDIVlpJ;m~|KFk%!eMscOY(bt=4pY|UcVnJHOt1GYKf|N3ybh!sXnI8W z^~S|u9KZ#UAQw@}!aG0`0CN$)0|kzw3pE_2>&)<4W8UX>BKDMFVdS5W2`nVhhROA0 zC{&sRy;`_Pwj~jBKi}i{-zkjGJSc-x>SoEm9$9ImT5Eoa(v0HxehiZ{da+iI3tqtq z8i}N39O78+*z!L3s9UZL_yQf1nvF=;Wv1){K|grEeUHF_#C8xz3T&IP5i9lz<8I}3 z)8lCL6U69J2y`M`GtVKd0Z&@wn#N(=o957*n`Yb;+*9Nh#(vY-8`SE>Ce|(0G9_9u z-8P>^TQs8;y)UeR&!Wx8NGJFl>jD|Zm*?ct%&Tm)woOyU{+L?MA4qk7Yb0(a8~L=7 zQ6?X(tQ})sU-a9S{ODG?78jO9NxVneMISZHSs{m|X7SiZbAEb`k~B+|*If4v0)2~= za_Dir3v&5KF12dd-ZMphKi1qh-dTiI#jVpG#}{GVZ5#3>peF zi39>!5aKIiJtt^0C{J^Yp20P&kOaN*+<8|@=aanS6ozsRhnE+ zYrsl~T$D3wmecvZEMrlT1+&E0G3FF$h2Zf}w09ksPPZgFmimG`*N}QBN&QGQ0fR~F z;taQel0RgAPBoQ#rB41`nd+dMh%JmwU`t+)*{TECfvtYY=J7FG_p4FP?7=K^payNO zT8|4=i*mH`ltR_pLb$eAi$*dJpiHO#zYT`P{sofBo-ptIiFX*@x3!_=eV*<60@M z1+O))OI*ZzM_u40IQLA@G5P!uqIi@7vcp&shJpDh=Ty$ApOyzdGKUK93AWAqqwa>t z+tY-ECT9j`HnWeqedU|FFbH%)!D965+XXWg1s#hl;-V6ZCVvd)PSu%*xgYDa+3AS0 zoVGD`&DhI5SfoBI;k{Z>>=edPSwbjKFsu|sAr=U%Dzch-rB;E9CN9P#eg-U=SUQm} zb}LN`6ox|ECWgHpr^QdsHWa%!hhi^pFNsy9$R5T{Ft(%8{{`FaF5Ca~AFwmKCO)`5 z|B_mZi>#=@YO`XsvecuM*oS7U2v&nwjp=vT7;j`+y?2r|GWACq{r~%apN-k~H?x_Y z-+t$1EjNv|BAt_ohvICYk;uig|EIBYM?#RWh1eDx1n)gQkk}9AV$(8?iBvLT;XT)@ zxKP6)(2-~*F7BMcs{C3p9|OzgvpsE2^40HaN`3kmUAZ9lf%y#80ZQ8)*pdsa-3ldl z3EXT&Ucb^||6IPNWMBDXR;xBkg8_>nuvqH}STysWbWO}W;*~Um=;DhbM(i{nx+Jj{ zabI~i1n-H)d!v136y`#p6U9n^HNka^C(*E9@@VTt{3yT=W&G%=Hm}co>X|*L zeSp*WGkctt!JYNth?I=Go)vryuE~eFFW>_!)0A5e1iNX0E)gsGCy%wt z9CB5W+jerGa8gw>3wUe-8##fCL+pl*WfYqhJ;^&0*O=MNX7+Kl7rw0(Di(+=#DdkT zV$li~5>$58U?CODRxp;*?M{NlE!YS&yNo;SXF2XC1O&`Mqet?lo_+H{z${*|lVP)! z=*~s@1H-IA6)J3CsX5yR^4exB#>ip_w2}j!A!AEsG*WV+DNmR=bj*gspyvf848=8a zfksd!NO})T@Cnfm!GDMRcfmM{E+*1f!EW&D)oyNB4sh7)(ys$lKGK$gsooqHRI*z5 zaNR1#N=`7zJh`M%(3F3c)BmU00nk-y=m=gouKN&08b)yVjuN2mlr6>mid{4I69B<6#$P*tpk1c;V{Z|0^H!XL&YZ~V_qG%lVaHVAAP>`Cm&xTDDJ5V)zx zcJRiUZWY*WtZ{GFl=tzmFTJ9<(B&BlJ{u~2PR6GUo>fv@O_0P^^mFK}7*r{y=$pgL zcMa}EaZ`aG8+_jee7EZG_8B^AsScAxJYCz20mfplfYAqiv2^#1LB4m zH=?*fgBxG}RbG3qi>P1z6I~DDGg17s!DoO^r=O=8HNEWuH-H<6*DP?uA~yyFHx74r z@Y$U8<4uNq%46NBmaO(ooAtWcR`@tJaM~&G@SR*)ua2sQ5 zcZ==WI`;nC^Dn8jzTn^MAkc{|AD&Dxt5puM90E~dOmSpj$)F*>LaqX&Sg-?NVqrKy z=lPX9eB}ViaY*PQd3fH2>q-+ZFuohhVgwN{GJ*|r9N@zchiQ8TSQ0phRPw(iiAa`a z%p(>fSP@u`ktKt+1(qZhO>|@@K&VylnD$6;fH3oI2krD22u?tg&sztN;djF(%&B7LLgW`u?_%s!OP)$md0KP zKCnM26mi_)cs2y`?(89iHLh~f&(7D1n}S=D4d0VZvim#SIq$$(UC<%N31krmam4~F zF|rcGm1tZv(Mf>ARk<)n%b+FC0k?Vg1KSbLY4u40t>*BsV}pH(V{=H?4sb}p0g=rr zvQZfOD%dsuo5RxBGtr$JaIkSi_v18_F)7rMMLGcPC)6=1(g6<5<}9I(aiN~`2w0zG zl`+g2_Cy+rbMc}KYuk|v&Fq@{$j7AoYb9bslnS(BKvoSwK*$H4Ef|ed7g$hC4Lh(T zSX7{c|88FXS?5B^2a7aZjm{2lQ?e7Iba z52NEl?EW44@OiKdNJ!AA;r$FM$yxnu@4rtlv-j8p`51g;(4(;zf4oQ35PWQm1kM?q z2Yxpl`w2{St^wLOwiHzz_)Zz&X6My&^-SQdTcGsKTPr zJS{hvYIX3MIiQk3O{|>P_d9Bd6@ZIRWHSrpDiZH~xkMkbZa?O6yc5!G?K>{qN@2xOs$Y@vs zyqGtoHg$3!B?A2vZ+27M)J=Y1Pk|#7+a|g(UGI}mI3}uUhADCp<8PYrHxPy32f!Q-SMqm#uwj8dXG%wLEq z0bWk4hn>eNT*RXwf%<}I%8#uP#LBnj2=^BcFt(!DM(kU`n?y2bW*@*(eib0q^Q#2i z+6BnMegH9YK+|LFcGqKZ>oE8yzhYxzkCXP|iwbZ45`Wv^ADZ!>$>a2I0{^Ex&w0OI z%E|c9V?zf3-^IACz&@T!ybByQ@Ekxi`c`tm3fh7>MV2v^f}f|W25kcE7+E&4i18$F zEsbyPBf84sEDrN%S-|wThN@@wp|Hp025B@@Pwg!n1gqiux-aA)Q;q+*d;E$nRHC6P z1tEzaD5l43_*v?H;-mXmlRN4CjLANTmJxvO-bxSq=;J`kLFxnX9|yf2XE6!$>r+Dx z<8PSzBW-+OzG;z`LK3TcknM}a<2vr&Trr0qURB@|h$r>`v-c)Hl4aSM-|yV_%*@Sak0Hm(%B&R0Caaqp zk&9LXS_o2u0MUY0NuWVcqPQra2=IT%|DhKG2%%dL(VOH#pjaq?O$oIS&_H(+XlcQr zx>;G3^Ar(2m`^sm`)P5`eeb!4d4$K58JTGZh;VnaXK%9m?mfeIzE9k|jPr|Yb#VeG zjs6hFaW3NelZiDF8#u1?R`1{CTUq)H?gIBr7n)j6fGLSN(2(2wMx7nQx+8g0HJP2L z8I@-4tI1^DuQ@^-;NsE~j0u?|xo>+whpnC9KGkayzmE7dj907B?Kj9S3gEW><7Im&AjV>zUX6_> zF`u8>KRW-Mi+zZqp-4_z9CGT_Dk+B{A=^n72a*!_uu^mpl zI52C4xtE%{XRVNNx!kAM)lcNL^=S&9U%uY2sUxj(GFQ(P4WkD7@b&e1FkM*7{Yfc4 z(M7Ry&o?A;R{TvXs#=6?GoqFY0vJYZekW^PKL)zWCX~FX$3_D@r)hK~7{zZZeLqLQ zXA(zd+%@rj zC5~mBTj0ax0dbOlW@L_qEA@k?mnV68`Gu8z!z|*Y>(y*72_9eE(bDmic=CDSn`Nt9 z=(Dj)v5nf7A98nlLgkVFezb2x%t#Tp`*S1`3&a$dN9^91F$*84MlQaK=dVV1ul6W= z&#mVaE?Q$^kzIUtVMQ?7J+y`pg%ntd`ng=Zs1BhDdz>7_^2-gMT@<09OxNowLbO7T zXPSkm#hk#jNyrj&bK#97n5LLJvgfL6bI~+QevEH%?MI1;RS;e7c4iv(3NzAjy`3qn@@Ze)b-JwTbS9llhKdfVO4&=Spho~cw zHRGTWr?s_nhs?jPlw62xloRVE&bWk;zr}K&>S4XqOUco{`)~R5TfwdIO}F3I zC)`TL3skI2yp&lDGvMe;gz zsl}QZm3)reVcA^e*r#*weZ=6l5Fr>uy=vJUcZg$$?pRl^ybIjR>Ehq2xl@a~4-(8= z+5PrE{$IMe)^Ix~b{Co3wf7EhB3?wSoA=4>n&UpVfh~!#85@Fea({1#*T53bst=*W zWnFxbai6wPVE9cfMh--hF-*otTFUn~4_~kqe>RpAe8-w_U_O^SZ=cWK_eyVU`Im!$ zR^s04WA;~Mre806>m7~vw%KhmFXf6?Epw}?xS`AqiCgkHd&dg@6Kt9H9gT3Y;HTg7 z8Dl<`zM+0NeX&l}TEvAcdyl}cV;m@RkbFFU9-^9G5WU~Tn64}K&oX!abB*$pn>#2 z-nbHLJTS%-&i|)4e>3i?h;j79E)=m<#5+e4hqZCUoWno<@9jR3^OZf^-g-yljSY5& zHM_Y9QHu~b!Pu49oJsjb001BWNklu?y$_ zxR(?6{`dcudn>Vvm96Z-_WM84THUZ?Q+7z~G@Ss=j=@fb9gH2z>_nWkW5y1#4gTyd z6W%+)IL7m1XNb9Z4ts%-11C8^WP{p#4MrE=?Uh~2-hNx@ z|Y_DyPr_diz+AP#3?fwP0A>g_v#>c8RJgsSgetQ;4F$| z%NpAk=0q%|x#bI7k@g@P2Pw0kz0u?#8T*Td1FJb057}Q$v@2WL%2pN@#mjkOBO4nj zg-VoW;#`^2lsL>m zsAk3y;#}ewW0EsxRmHI_oIqjJFrVF^S)5ZBqFk;Z8tW70l4G0Rdn_jxyDqU3o1+Zqp!CAJf6%Oa5T z0C^V|d)bBy|CX9yl3Wa9Zlb|KaEol@BvKH24e)@t!kY`W9{^Hwa7Xz*F9AHv3zLiN zq@jz-ILi(5WDL|JD~iB;OR$-YHTgAc$j9Ig-I&|6juh`fCON^#0vCVr;N6&!Th(gIgF2D~Ps0lN%2eVk87EmBo3W4ag);jXcg*;xB)+q8WN?(=M8@f0&O!4M z$1A~&ZNAc;6_b_F#>)D(OkAUo`vSMG64)>wqt^$QI`DgH{>)9~ z0BUd0a}x0s0EhvZp}Zl@N!SW8(*brVEb$^>5oUlDL(v?1A=!ztW)kl+F2oUBQMmY~~ao04JZ=lmi2H6Kv#A*hW22 zfD@RNzaLa|@dgENqRwVik?UF`nh@np4F`B3BB^&p5)#%cX-{5?*nGMiD>(~i&4a;-_Q%7+fop6G$MGI3;=)i%~ z$L8nfBr={~n3$3Cf;CGaVBrK`Q~c!X0G?vW*Jy)AjbFDV7P%uVYVTJxg73z;CF|~O zGHV-KQuwMw5x2z7{ofzk-j(rwg8z*1;bOr@gBLjXx;>jKdp7pN zA8Bt<^U5Qv6E82>&4o3B@M0cQoD`v#}VnU1hcxVq{{=9N;(tcGLvG!njp( zREQlC8Fvj7ZdE z27ROn)d+>Bo8{L%l|)oFWag#@^eYdRsQMPr5Igc|eL8;p$SD3|8{)fWuB z{9aGEu2>-fzO-qd+{(A}bDQ*E%R<%{zbo4&4swrpFo3H&h?fMnP24i$Rl&GY;$w`@3_exn7dWu?=azVPG2~}YJNNSkf2OUp#x054GH#~q;-i9_X52(B-e4|B zT5w^@8W4_gtk#7FN{PFOQzhO=;x{pV9dVb$|C!;B|J85Vzk8b3b6xx4kF+-|yAD&k-M+@oqN$#xg%8@i7hW*_@B_Mptjk3tk-t@mrJG zq@t1-B6clAIV5kQGPN~}b#>(7TfJ-C3u2r)!KN86Ww>RY=bPhLl(~AO%9a_a69TK$ zwl05T$ts)3RT-^2hMD6xQ~Ykxz53-7GzOVs-z|b(hwSs{fB5?4r|dN^Ie!v!!beV! zb0#HYlwp*d4D<}g7sYPKRs^%$C#zx{8uW5#_Y+c;=D-{|&qe$k;K%X&TnfThAO9m0 zLm4t-Dls$1fIW%8&ezu-Cl^`1x5sBuQ2W_3diw7X$eC6RpPll&yg6)v(M|L-M%6-c)&TATypmfsJ)La z7TG5_{<5z>#zFGfx;u|Y*+G!Q(3=b5twu&N_bw8iBdPRg#Js|NXdh~sq;7r^LApn# zQHpt~%x%QH=9s?36#@gjInBTOZXazf!Y+~!CUyI|isYokChbr8cxrHQfhLY4OH{cN z(kny`Db}K7E*h62UbpgiVK}1iQNA&?q!F@2?tT7#qUNr4GneBfJ>P1~Zsg1jOYEBap10+(Pq{}8#vQ?a5+~Vxi%~SYzf4zG zzXQB0_`8(&Y0mt8uK3$w!<}l;#coH5=31DLz(PYu4p+^1%`%CK?>6qk-=Jbkb8h0f z@NFYVa>S-3)&ygNfn0#D%1|X*!fK1bW?$|!u*AOnxoBl8`^KBV=hg@LM;)nJ@x2wk zO8I>%wSwfux2VWL5NFglrrXTd2CQdsE5U0y^O_ki8oZ#3BF%Sj4DN?! zd?fLaWqwv|@c+%{Jdn7&KI5pe2XAw>!P)=z-`G_`_D{u@VN{m&c3NO@gI~a3i|r)F z7sO&N_H|x&ez@2Jc&Vq;T%_il#CdXJ>vMS=os$??Vv%7ji?u2-$YR5y7cgo|P7Z90 zEwhd>G8km<)qC`;qR71*R}uO`+4J&NdN-bR^yl-ZldihY)%i1E_vOagj|Ei7dRT=v zIr%lnIX-*q-xiA4CQ;^4@w)&l<|y^*)%eoTM?ZzPSwj7$!ow^<}6h#dIwpg%tWF-JB=;3u4zurcE}djF?ERyZ{$q@3AByv3nh@cLZdOD{`~yU3Yi2F%qk zUz_{b`(OTC*HnkjOm-6Gj?`Lz~oey8cb{d6HVe+F^fdv?F@!ri0 zCtS{n!vuF^+#_?6D(1PNF$+wp*fh@}??ivgHXV`ORei;Mk?pRxSRBX+W)D$I_IZ|# zrcNj?ocMf^7*=BIvZ$T~hMlL}+w|Q5pRdT#pI`gIpKHA`M$MQTi*xpjc6{VEj`wu`QjFx!MkRY@&xFh|HnNNh zHX2zOO9^G?EK1mYK9zs?A}r~mIS0}SVj}l{?xn;R5}yJe3O>0!mL~_?`P1LA>xr?*lWA6`~e$ zE~Arp?*!O4IL_k4JXf@zGRF&XqKZ5+8f!?iiroY+AZ{7Fke$C~J2@ukhB*h^I-V2t zIf|CY?2*hufDrEuoR~NuagsA9245)gd7qC@uzw$xJ^Dvi@ywH1;oIov^!vTk_r;~x zD(D~vj@LL-9_=>WDsNxy-d zo99@UQ^VJeLuK|;>Nx$%Pl?02=5XF{Fm5>P=bigpL#5yT5|6~1iE)|#xX4Z0pZ^}j zN!#(z_UA(D>Xui{hb>paHGSi^-&T76pYT#8-pJw&Li_^bb%Qs6*SRQy@geXF#CuBo z+~60Md2a!~cw>zZS99>nzAXD@m4sLJ+*uLVP~wJ+8-%!qtZkNF_HP%TLs$!g7&CZ1>5_<*U806z?S*!;c?OFguc9OBC z%tinQ)_Abu9ncb5p5Ot(AqCiF9GF6g!o>~FV9 zZmqL%o~UiemS(I~6=O16*{IC}oSMW|xh_1}Sj(@w#{4}qFD~QChI@EZ`IcQz7@^n^ z9tSAHBPxKwh_tL%Z14Xs+7r9&9s@LMx0j_L!9({6p4v;yqPh~nVksw z*8_kv5bU*$1lB5MUQ77J+!s@?-PQrFB0X-?^`-mLN5AH5EX>F4xxBIKB#Zq7`|^g} z&$ENfPw;}+A;!euq=6HwIT$t^&(1mfm;ZxJ9(3rHJwNu=I~s1S^Br5`SFGVTB>sVn zSIvtkH{zKdnfvuu641nOa^Qh6GZ$?+06xR`82E+3-^~*LzN-28(*pWmMYP=)XL`)U zKU_-wn~MOQKdb=IPk60BHY@wxA8UI}?4<#FO=d5-VAzeEdC?Ltn|J}^mc$KUhs0KL zVA1`4$<>Vq0?sf_aPqkciBmbqeu|UoBsE=P+F&gJ>rP_o@qUTllO7_Xv($Xel9eWb zLb~hVxKmuD;27i3#6kA8x*tI7HrnWMiJfU2@h`K z^Zy30Mu^2lvG}IkkK2$JPipQbxLRg2BDTTvX%pO+n#zewrplb+jV@EcQ2_)*9&9FY zoHECPsfHXrj9mJMKhoZL&G)Jxzcct=kl=j}c#Vte+oysLlJTL$`x5VCe2Dmfiub-Q zAiN*^xz^8NFC}hNbrko#;qAty!dDR$?*Cg>FgzsIdC3VS&Bf-9lbD3??;JQx6;m}# zl{hw$vI`3@6`4>^WWt<`sNaOVgM;;lQP4ykk>h|O&fvm@b^Ln}kmg}_;D-qDBj5KS zUKpK)UytAjqv?_F41)l*QKGiQNfxP=H*?7wD(2CMSIgsK%;R%!;&R}&Qi7blky=h6 z>G!O}O@6P&DaNdN4cs`XY0!mTXtI2=hV0JDz3|@^zuSe^4~+Jj4y+?iK8PYSX6=0j zI-&JiEu>+!w?pd9$5^>61KS8E(EW}J)$yf&NjE0ys*8LukwDw!7rI|;^e!Vf3B z5|2hY)i?Kfyoj&1@$1~gF^PRLpOW|>!TWi^dsFeV;gDaf4LDkfbALPSt#>ru+2p3x z+-fqnOxz;sVL>i@BRe4Qa^3859%)WTFnpIj*>L=A;;tp`nsIL-?k?copZu1c@FiGj zDm<&$Nia%@&8A_qHr6t1lUOHngTzgYO)@(Wg3BpHmOZ{7%Rwb|Agdx;E78I&+`>la(OwrFO4pkJ&)?x2nwW7%1TGy7=d zlI33Y@7dG7e=B5UgNCC)L4XLRZ}=tXt<}*A7oZvO?6DuMnnQ1oWRbnA0YiUS; z$M+i&Lvzu$LDWs_UVg)4d24H-*Q$wzb>f+D5I(^%Fc(aNK&FX$J8C$NIsXJPPfqM{ z9`)5@fb0Tr!#v=;T5v0i?_j)cnK#Y&l>m&N06)k0Ys6214;tgW)T2jB#;)?k>yR-{ z*5=^W!l$k>+_tEusbQR)eSgQ`zXDz}@o#03f9y3W8PwVH^nGsv*Yv31^Yv{;MeXW#*aE}O40b@=fJ#~L!Zl3$H?Bl35AF~-J##+lhZYw+< z+OqrWgBduMi?U7(jzka``m=Iu=CMm^m{2p%4eM56WCjMK#v2hv80)^;V=`|jN31Jx zgUn4}H*f>VM9xlLvjAq{Ur8a57d~zcLBiu!J@YT~@?xPLN#HX&VyQL9v77K+a&|v( z9&XdZg0xCb_CA-PWSnPFkwXyDSOkH4@u8g1!I0cHO{P}Zbtw3bj9210xo5^_G2ZUS zNZI`u7lSQb-L&#;u#8<4!LlIWX+2PLV!0kZ#pE>@p6$?D8BlVqojs3h!ZV5`p1Tm` zsuQxF2nSApXcp`GqnNcZea7Sag*@)ZM3!}AkFm~3j=Rg|K7_}d);^zur!rnjj=+HI zWIJWz$H^V45GFGGJc=mMqg;Q6z!y3(^qdg&!1KPjpJoG2 zww{6Hf*ciBldP2MM&<;4v98Rc=25T|i`e&ELB^K6D3uX|$f0ZigJjgo3}p;@^QP$P zStY-NJ?y+z_U$wGfjTl!3!ls9i6+N5vYKozH&%Qou-=*;#4j!B{L>-^?4G;a%Q-F} z#AhPTi5O}`)H2L*8WXwy?xc1w$(doqib%}V<(kX!=GKe%uCOYOvxc>E#TsG*kK+od z@TmWxm}^}uM@+*Hof2ZyQD2@LEOhlbj4*DQ3u}+@&wpX!b9wXb{kPDZxU~H{F;ZrP zF~k^}yk-!!gCV_n#GFucisK}wh^Zyc<8Sxb`~$U&U7UvLIO@S>|>IO$ax#c|y%sYuJog6d`OUCX`%2SO#LC!Vga&_6S; z)3wCj3fg}w{(J#IO6A>ulN)U|kp!5t3hc zCQQtf+PO~F<&nNBEA>4ok{KnBP=u|r^=c58$NX3AxIe?=7ZT@~+g!+`^Ucrbp1*T* z!3dO?#(BMti$3pT{GG&yW=yc?tuf9mbCMJ1=HEbvYsyhe_shE=N^NiyIWm!YQBqjjUabO@Up~96ug1w?T&#{^K)$EbBOTV=bFTT z#E^o|RNJHQmClLJt;HA>s04D67dFHDzLg^K3LoyF_t9gM1wKCJ;gOZGX?PuXh?7ot z^Q*66M}qz2Sej3OPZE5bjrT0`sa1Szna}o*`20_Q#~vsi@igoQf2G0VfY|z z;`?$#|%qA&b6T5gU zxJlGwqR(?^v_x*DA8kn2oA>ZI(EZU_av`s|)CxP!@%sKkiD}eE7AnFY-s3qSljX7Y zn)&vXV9gSZU?Yj46j-G2p<5r`1-EN61_Dc-JAaz%c8f0|=G6qsMnjJLV}i&H*IME; z1WC{tUTc`*HM0{k)3{F)gP9VGoH;b8Q(|V`i$V6@+y?(XYG5sA>Xg_p?`?H*Q38LC2c`wU(7U#)(Hz#r-(FTt(PBG@zcn;qZQ;E%- zc?IL8WW1`(PUMk}5QkAkyXZKZ&3!<}?S%|Db3V)=;vVK)7yV3-0 zPT5MuZrNs+<82~l3$ymW_O*i1Zuc0qf(x~S@_X#7tt_2y;=bY6y8vb~CMNDl+%@A znsFn;cZ>@-S8$Qh;~<8efqxezzmyKL}`Sl*{Ii(}stZEwZBa_shZi{BIb821kEvA^Oz`f}_Cf2p0}88;?F z*3*z%wqTUt1&l#%xIu6~sA1iVt?*5^t@zoVD;>)inb(R6v2Y=rOoY(n4mRyi-p$fCiP_S-d6X%TC18%W|R5@}PCvvWo87@p< z=E6~4XY>2I!E*7+#}bVBm;aPcd{+Ku*dP5^qh`hni!mFGaWlDa%59soxv1E#T>NK@ z1qTW22}TLl1?$QT6Ku(-=tQ8Zh%fB11uV)Pe)@yc*AumQhPfpd{4z0B=`(jeJ0Rm;_Fq8_bZAZ_Ofd+PLx~jy1VLl?G6;<(Spye$s9=B8zlBe znS1}@w{7~=@6O7uWpDpP_2;MDS`4|JGq=sy$?$?T?8)(|H%RPAY$e#sF4{B3TzoaVrWX@bcy4qk+PcWaBYKYg zzMMt)uBXXy*++7+`nyVeo-!X^HLp$%`0UHb&8=)@k7|9f-^=9Kr9Z#V6Qt`4{XUF0 z2rdi!UY9UioK=~5GGsXLqTu|Jm>AqK<3Pq;;BFEhNgOxgq^da175fQJh7~8P-s>l~x86~8Yn|=F zWiqJQYK%>5*umJ53z2OJHYIi~gjkZXC9#Q*Rbi^`ux%yb;_ehy4oGFXrzH|aH{5iW8uLaZgP;cv*#_o`Z< z@HyoOm|($2<~%wRyq~NUxJZe^!u_p=yhzL{u`scoD#nfXz3(I!+Fs9@9rJZ~-AbJ6 zJO?g1<++$GtmPbi*m+Lk{u~<|1sBsXa4d0b#zEALj^*5C6A}kBOco1{*VZ_G5HHK4 z+VB5FYpLOtUjN}MgpjT|PU20B*SMHp*$3XG)T5*SkeYYDTk-x%1Y>2-i>-=KD|>G3 z5B^MBT4PrWcB`5_Wp*)k4fbU0Cb6p!)G%XLVwX-}V_7pb7C~T!d9qfKD&Z5jFS1+& zg!gQL7owyNq`Fke)I8`s7O_Big7U894!s#if+LB;1V`C8O2+=eI9d~j=R=O37BTP2 zR<^R0eVgoef2{4TinUqACJVOY%?Dd%Y+7baVk>7h1NgX2k9-z6;j=lpA51xX7t8Q-TZxI5KaLJj5GD_mek@9meZNazc<}5ltsf4supVM*5wKDK?srz&F|M1PUx{`M1!mzPxblQMZ4>7mz6jVLW*<5 zQ8Ff3Oj5;NdE)&ri8~jH1wAF{zTm)v$f8&F<=9*AXuP+_FEulMotj?*ewoa7WV~P& z^S&38`yk`xrT{(|Q=CBmK;jECKC;Z;H^yI&8~)$LOZ@$_BDZ|&9gT19u$3FOa>Z^I z+lVa^TR6GXPOM>Dk$BrO*p@eZZo!3rSJ{!pxCbT)4&@Dh6Z7QZL~w*Sz#Et*mYI;4 zOP)OpID-1!6+MJ#Afn!YSR)MWVYnZr(=@G{}O}bjRl3o;*oP?>Y6+q#FvBI$VCOt zA~$duo#oY`aTjJBS;Dfcy->(2lD|;OK!=Gq#a>}m`;a61i%Sn7E!)wWS zC7L_?1lvxeCMIT_22dj7qItBmTbdA``LC$DmEt=)GqTy`~ zYk|y9LKstkmQH3TluI+0697ysu|OQleV!amhG4#ZN;HjVV*Wmlcv6USs~AhZos6-$ zaMuVY4O$qCRj5p0y?9`zxUYVHw!w*Ul>OcX_@~6;n>#%rl|6mCN_5e@2KF-WitZO%TqZaJ?l*sO z-DZw@!N*UF==o{dTkmLiYn_dzW^GY3F3tHxtQgNxRh9b{8$pP)F0qpwT)rvybH?#p zkK`f_12e|v`L|ItarTLro{jljkj=Z57IKomLikY{Z;581DnXVLa8*V$+j_G%N+H_o zjgb$}c|4jewlvzf?5RNy=|o}i+=JZOb|&SR3P_(tli8=3L+tOjrA3@Ld1m6 zwfws%jmZ}2z+K`>QFqhU?w|>+Wv*Ts^C&$@g8jM`e!OD1K7=UF#x&z{BRZ zLRyVs7XOc(vFY-KC^c3H`R zhuElfg42b-E90b-f|jE=%LSy|ujtmzBo|P>&Rntx->w|9Aw#TDR{Rub*J~GgydDXm z!e?v+B&|Qk_U6cvxBDvRL3N@e7AH_hBt6b9`84P@`ZmwkUqfI0vF&-d)}D7#CV+2% z3C|CejCq+8+I&_Uzc_AUDkn{vnneR~$>&+?f7k6#pR20YKezji?SwW?;N+qJo;$c5 z_0o^IIydpK3#-ksBRBE7{Q}1k-oKEit- zcC)dD9CsZ4k}NSroC(e?$l}cVLm)9i49sg7Tag!^2RYuu{VUp-`}wHveR*qTAr@=! zXQeU6BsFp}^l9X4PUYWoGBGt{M8f3xm|DUTG)fGzJjZFUkvqYgVaapi-%$#`*z30L zmwTO=5T)~+hA9N(V}5+1{O$ALf_&5Lf%i1lzt+)zcF&eXn{SuNMXj@sLtkTky)C)< zLChaj)EMB=$hP`+ir7 zII|(=i!-Jh#;I*Ezlx;m5B`l_A@lvziJ!lT_=mu+(BXJm(h>`AIOM0x_Ini} z8^)R$<7K35CdRp9hs+v@b-dSY%`$r=)_{?Tai%3_+~9hT=K`OL7SZFD@%c(Ag@}oZ zN#)3)4kABU2Tnwi<8mJ9TfS&H))%vq+wS}hvm&th=)#tL>x3x9!psR&m1#)G+|PCa zz*yx>#$&N|$cT{zfS1cRLp-19B_E45Eriq+;v43oTDjZvh3`h{iF8;Qk1=kPQHb&q z94DmI##Ciz6)vdK<`)deomjosTK(jr+}MtT@_n`6eShC=r1b>fU0V;M_eei%Zx3=_ zgwNvrm#)~pjTax)tj+JXCoX%Ye$t~@6Y-pnk5U8l|8o2Nm37Xs9FOWp_3!VOdd=41 zH>SWD&Y|$B;Nt|pm^b`<1p7H5xp2hG%6!L+7Y%M@aWgm{wz;&<8Z6X}u4UNiVui%+ z2%O``j3Z_CF(%e~jm#u))<*;5^n8J(F{zp|RAN_|-N1A25~8hw-N>J{|APByyyRSR zoXJ#wOB96K^ZJ$$I=YHI__k*l@G#0IGMBkE7> z+#0pAN7?U_gx(9Yz?3O^=|dDunWL0A4Sod|uycWd#>B9JaT4n!suGvb^)j-on^FKIY!@(63d9 zivi9?e5aaIQ+w}2YSM@Oy#|>r{?{tlLY5@57tZ`x8-E+8=Dx*d&##jwk2+u zkISWaKZ8YfOmV5TfY&Q(a}3jcS744&J2be%BM7cc4!E-tE_!zM_S>rO{Fl5oU1Mia zv!f|5*Mt~M5n4BH8f;{-ZsMklbrWl(R$OO*7?Ma7F^gx20egtG0xy=BXBQZqDdtWb z+m%F!1c{NvnmM1;{k~$vJj*V{JpX?p=MlMU;tPz=fsd8BLz!27tlu-ZHyg3P;ucxi zmuWxvD-Eho**qVxnZ(G9osut2?tc%>*vy$tbE57YMIQBn*ss@vM~EG|9`@^SDHP)H zV?4e&#QRXrvp7h;Hk@Eg5=;e0g_o+yoYq3Bv7DKuMAbA=2m9$8h15I>N<-k8%EygNTg}a^j$(6S%F0&u46UpuML?c8gOu2$ zVUQD>7z4}k)7OlFVAG6ocE0O%HSAhqBsu4zb)1sxgjhKqn+>B*dab#-wIX)r!e%~i zdyI63$I!=7cRDhdD|1vO7L9R~GD(Re^V-&V_I$@&-fLETUCg=ZlDu}f#YJ(an>?7? zX1TBv!DSg7ml%`AI87NBjL%G~gc`5}l{KiTSTm3RcT9}4SdU!b*kC>QJIBN}5NqOt zt>p>Ca}Q@YH*68{Jiv1w6I|S4Up--q%pjPVTLDRBi3@qQq;Jcqtp- zHF(*?tAba7SAg$ukxOujb4Yw-#z#0m(}#jj3_eH|@9ppN(escOS=q|2W6wk3W@RgT z>h|{AN+0}VcB{-@kjd^vFuSYryRmDToowuw7sj@6BEUVIX!a^F%oLbKqBBP#xUxuc zazFV+-x{n{!m@B)mTnt`xf5Vw4#GMhagWSBgCnK3sBoCYK_w0wII_fq1(TsTT9Gub zY-KB3+0(Nh{z!X8g)udu=$jcwfozbB-Rwc%Iv(H-C3ekPQGiWz;-bBl_|w_|_c{qv za3IDEaY&H1n{g~B^f|E1EW?R)LKXYC+U`k)6U)q0aflcC_SKLz%$GVhPD$C)UX=yg0NO!Tvhe z7a}RPj|0RG@Wy~6jJb*90%k@oxM3k|U`{wS!wISv1;}iP17)%$4$A$oDa}wEH6!xV zR9`IiAob|*Qy!=sjkuXYrBbjbZ%*0ZI)wj)l;A<+a=vYYaTdkm6En`EDenm5(ER?L zkhqtPJ4sBkxQqC#GWMIAGcxB7Q*r;jztG0!oMAI!YhlzjW5+5|fQ6DWyFg`$?UFP~ zVn=XOiEW7;GZ!y0v1wu`Pwdw?VX-HQ{7RoDIpEdi1$!@q`_EHlX3030Cr4%&hmq*n z&thWYPBIP^Kq?A}G#q7ESj~YN=4*3~>%{4bNd4*ATkmMRb&Ky-Gyaj_`-p!aPY&G{ z?3l5xQY3mfKw0MGIr9Kp90LaiUu5wfiJw;Rx2pIL|LcEepM43Jcfo%6BkeUKw$!kt z%oY_}%IucHNWw)nLJ4;V3*ikfjBMjVKt6{rw>eHGcYw7jy%WSlaz$Pgf*UR#HL*~< zwZz0KCe@V5x0xLJ+hT9MqiS!=-fZNAze(&BplF8MmGKgATMjVUHU}bYoBJW_x~c$h zH3)hU&*eNB6N#e$7~KWFAoCf2a^?jRw@KUvZX~gnU5R^)7Zle5 zKr+CaB9fd`D+TcTQFCt!M5C;zX-6Zw!CWwpMEkjnQ!@9=ivtH0e3BdPrHW4ye2`{* z_|hhyt<;*o-S)#DX>UH@OxcPjI^@aSjU<0t?2e`QMquSu|Ii#WiI)5$3?WDLtDD+@j%D7Pl~7G;zy}n=)=8ZVGN0yg*0V(zguU1@4reX57u0FOqRb#+`(VYAkB* z4vo*3YxfrK+#<6h&wC6Zz-LbgkZl{aI?~K6pZ{j& z&)l)#NXEUC`P{^NHsI4H^LZow^8h|!&f)6$_-5KNaSel)$-I)2i)!e8ag7(ae@%9v zN;G0U2)J+XaW+0F;;UDk+aLUywnmlv^Yb;&HJ10ZV7G#e6#jlrysGSkc*)qvA7xAz#_pcd&6dF)XIoc8H*&&F(w(#Lm0XdPEM2(XN{8pPt7>XB9WL&43ijU7**b2 zPnP?r$r#E7%0}istCOFLQH)`Nuzw8)trbFxHNs!S0>tJ7>Vs&WdvqZf#l3957Qag? zz{xYPPN*XK9pm{hiu_y=(ov8gmGRv*Nz*o^r^qunfkr3z<>WID83!t&6J6836D!Ao z&sQUcdFXZ$DPPiItUgsWC%Y?cebhXUZrU(#5D@9^< zn&KetL!8Xvz>I0RW_f*noc!97jDdN+YLGLd5H0y04xFEue{NvzI}|M3wE_Bpc>^cO zD&#SZqE;P~W+#jU3g3O85V|TiDg3-IZ5|aU6|zrZ+2aA>zFVJUs3RnK#6v_3FLP4K zWZncZ5;V!{Xs2@FRxHTAKNpUTuJFpb$B?gKoI z8RTdhFYe-bD~RFe-PS5(Osyke%*r7>VUg|VNP99sf&qygWrmjc0(|L_s6)`tiG+eM zAwKUI&W>ofACnZn#=2n``{5}Fq<)Fk=7~B_s&m(u&v;*(YkP?4z8CEB4REuIzw0rd z-IYB{d#aA>{d;f6MCY@XCNfLb&Qlf}7EIN$=S6CRiq>D~{wijXk4hINmv73mx3ZP3 zY-KC^s?4zsGqZ@l)snPc+RU-k0A_3oUO?Q%2@g6e*z4uTO27`rO~H2Zi0BK6Pt9wq z_xobL+7-g-N-#_wuZ$^V9bV5F#CkdkyvYbB6JBEp0lRrDTm*=x@)${UHG+X0bFo1W z*J#FBV8qOv2x2R641aINf5iAH9oZG~TH5~v+$Hm`NZeQNvdpwe_cwuCW(Q*vxSikz z#>+BZMcj-{P7-`1xFaXb`cM`mzPeb$wuI#c8>tgGASF_U4YJ3N03mX4fzZnw3(}EZ zh{}wOT>2c;#`q;RD&nD8ncD1`#@@@uss+pI(<7G((RLEq6e8Q*_v|sL=h-uv6!j?2 zu~|!cJH!QA*5noW2JhLJ6QUm%Vn)vylzX=s8PYRz!n!VJeyKhsx*S8izlu{UOr#){9QH|4bFj01kuQ7?$LdUH)81vjPx5UESr}Esa->*`)s8QtY{XFVxV<(N#|rn#$!KX@89pY*7`o&q-|hESG+%eAVy(| zh(wJnQJ8B3NUmdPUQ0s9yq4uS2VWCAe#Cj29cwh5^6dNe^JvWTu`bM`hDl@e?xsed zcS*#;@F4+~S}O^K8pE7Y;F;d!M$KF^V}>#T#v~>tj6&%41mVQsT#a)QV=JQGDQJ}_ z%fKv)&^PDF?&JTm*~>nDAFRvirnpg|q|=!qNk4Y0NPAq%o$3>+H_ zLxlMlasHx+8(bu*%`cAbY8cbzE{u$A-Qq#9pp*{1WIO>-rBB5JfaF}q{lG09gl0uw zlmUq%83%qE*%Lub=v#7p6<$}=s4IfwyfG-$+@#`d=cbr1o5!pSQn&l;Y$oS@aud9_ zo!j8@7P(sBmlopV-_+csca+@V@&q^&;oM*pxu@gv12ZOxEef_IF-U&?o$q2i;2M() zVy-a%nF2SWDs(Ibx8!n6A?6ih7-RQPVjQopLuHsM|5+9sj}{F7`@b#gdn=o`I?Uuh z{~viU>hPf4;$brO6dqc|UJ~|;5adnpK%5V>XRxi%ONl+aX0k)pkI6>!Uh8=~6PT-_ zwZ@KI?k=Bi;&|8v&NrFGzbQWcEurQ}7Z@E?y2 zS-))JeTb~LINCx>LeFK%uDVfTuX0|jgw`PS++nrpJ9wT7Zh+Y(8(9Dt2cF(DP_I4p zF$U)R+ihvgD{d8$Z@Ho4&2vz~`5{wak&Kx*A7mVVJC!g{0xDBRYRr={QSWz7DkutL zBn4%P`7`Fre(e8#%#m5|bPpdtZZeEG!*jAxj3Hx;G0KVgxH2(gBF4m&rFvg*Vn(8% zBgy;9;#?OILz8kyVk>G2hZ@>KtQu`R;O04SiW^wuTHA!E^@W**|L*%Yy;O4x{h7Ab zDiJ4T%2Mz7k+UQr*0I#`e6pJCqma?ua!LR;X)VtEl|cTw-=Ad3FHK0 zD$2-QnBz=b(BcFq#T=`Po}7>i#@Up^n2Iq8;jbyiNR_!PIjedsmvAzelK%d`FURc- zx94A!tzzlNnN1`}ZW@t|B#8Mqn@QwzKs?_{qWwHHiS!|NGv;WL>JYU>;%`wHPxw#5 zpab=D5J|S1b>u`lp3lj4J?BQk-J3IcHD>e&zb^CJ?%;2JVh7zB{bfmi#mL1A?Hy6S zM$FI84#sveo~Y3mjY3Fb8)b(?2Vr0?e$o{O9ldE&yOP|nGZxXig!dU#8JTu{3jMKOt z&kEtxU}O^O#EMZ8jt6s&PnL}S!GE|ZfUJxE?0>eOr{tGX!7nKMd`f&_<%-) z@McjsU)L`KkTfyinT7)x=d@C7iFXpqOeePZ}Lo#1s6 zPCCkKgy+D?vf^bYaZ)6Xo(?$M7;?P7@qy1htuBr8ZWWvX5YWyG304CZo#rPa}e)0N7-C(GF zZU64C^8BhC_Ip3Jy+MbA`JDZ-;6Q|ZgYSs(FDLk`2HzInmpy#^>{^&|-5YtULB?lM z*o2P}3xv5OCP^3*X5I)VV!T==UKGMB6+T^dd1VuhnDdk0`@1r{m;KsA9pC%0?d>I> zS0+MFdkttstJXDYY^Rv73!_M09|S-Oo{;DSNOM2PXN9_v@18&zM3}eYxe!&BjP%-IHW&fVsd8Q=I2ldjQ5NKGt_|P%2Z>3rM&P~?R{$_7 zQL2=JyxtbYY{Zr%PP$3H20<(YO{A7xAQN)i_fv3=R>?-vriSo6i(ByWB5Kj9#uul0-k86EJz`}7Jeq0u#Xckm)#@+1< zL_(m=oTz7UjaDAH#8y0`)18pm+v|8@uPXZ5!sQI*Heq4-FTkO$LLgxs#1%p&hh@%mIyCn zJgGwLYEDCt&THa?3tv=mEJ>h5sVsrHiAlmx&1+;QDQIlB#ILyyQkzb9;u{kn88}8y&gM382C}g#0w-Gf|;z3EnNO>6@R^;4~Ki7LUboE{fk@h7$^<&UK8W z!ZNMy$kK$aLX~pQw^c_sW2w^Q&Xz#bO*|y|JZnlRi5^gxlBg&|>C-kp3NsuNME!HF zBJh7T;ldVqO?ENdR7|Oe`zA0&K92cXX0_K9xu^Ns<-&(yo<7w1d!B<*yfzEjni*vb zFf9)Q5UKGT`9lS-^WP-8vx!Z-UEC$#S~c5f#`~NLG<91e8z=d?ElD%asI+=xNfC{E z%&h)M`zlOM{8pMYlW+2*pT`@m;tRz)y{`L)s z5Yo+ce2H8}>N;%m)9Wi2#cRL5`#F!z7Wjm^9#rSb5^Ioz=5?gWW%D&_#&o15K1F-1 z&RYyq*tUt_wfjb0H){Uo>#qXnnlKSxOIw}e;h!I`A#$;7DlV~}Ugp=E=dcpVsDFpP zzVjN=bs}G@qOk3{S}tJZvF-l)pqr?TmEm6Rp;fKT5LYMqBXyl3?uCneqv*da#W8uy z$nh4qV88?y+cXmv0^_JV7>?hmqR*GjEpu+SXpgTXH=n%gfkmw>_q#=mZ<+8nfWLv8 zy1p{wp96n^@I~vb9pFF4F*W}UE--b~$?J>oEgYNmErV~1ivu9SxrM2XxS+|{d<@(X z7k=pB+<+cJ2V+aLHcDSxe`xi(a<$t3=CvI&NGr8%C`4ECwXZ8IYT&u#(JnXUF-+>e zH@(VubL*P>Ds$-eqHHsgeTb2B35z~Ywm`^+@69yUUf)_hKU&?#y0l`y=V*)co4&zVt%>Eg~|p-xB1+KH96pwxcXQZE?V!a*HD%mhj7hS){4EG*YcMT>$BB$ z+1lf!!9`UU{x0HuAhXNc>%`n=7v5LoKAk8tJO{ztoT%I48RT!OHhRkQrp6vePp)7U z-&Ft_ecXCIYF3*b(Hg;;=V|ilb?0ppmr98-9pwM+cO&_8V?L>SOz-^5`5CO2igR94 zvU+S-nDg{zW{lMsnQ$teQ!h}?#5hY8ic+buRe60*%{6?A;KCOe+fmahfIXZOvnTL~ zb(|$*j&O=_ig5<+H)sku9Gf+`2=&0jzJ4x6@ z*cW3@g#DD*SLe1L;Cz&Q@jBI7G0G6x9Sckh=Hj(EH=Ol3yCcqv>*4w&JGKrV@BGtq zyrxx&W2?s`7D?W!-;pK0_Hj;L?QB!o2Y9 z4vq?Cg7flcxNz%9%_$bnCGj!|LzD%sJF~O}rY@M;OM&sd6yQ1kO6^Ss;xiH?g;zrXVTf<*W9gcqQS7iED=j{WJY#=l5@U2wRl_gIR zwj}Y;5`8Jyx5Pk%9a9FH*hUzb>);JSzh>K@r%Ep+dg60kX-27mMdnR&!aL;q8C#UR zFXp#q3upNT+h4@kSnDkbOcG3D44-2xOjs5MmC_a1He*K`asQnVLccT~S!4oN^=!m> z{$q9F`%{BsF z#vBEKN-C^Uib7dhqLk>h1HCIW$99r25aBQkF1AGI;pWeG;Q+4oNY}l<*L`_Dorxdw zslix;i6w@r3?*@1xw+sm#+M=t6O2%X#e!2QI4gUc-NhVi6IaJY9oe>qof(H&zwV+& z60N_pYN&XVUfp_~h08ig>kSq|ckbspyx8crY~pR>`+s8l#SG0ljww-;7QFMsZVH16 zjBOJ{#SJP_Vn;kT>{{e*X3k|-7+ByG#Eo8vd{lsKoc~ecT9@$Vnlf_}sxY;jd!?Y^ zz2e538o64=innViSH%LDnJ^PLi9Bd5uE}>?K_!l{8Yjp0ImV^ITWHjE3Ukd*6W1i% zF{3BKK8?m@*60~rvp+e`aWlaa8lB1$^L%lRaUS)xIlezj%UP;2w?t2Tt*HWKs!&n3 zfsVkQ(b6FGnnyMwyvbx^5&L#(zBV2Kr?HPCfm3r{)X3m8&fUn8|DIq}7$=LwRC|n; zaAFnHfAF_tbc=KH-p6l$Vmq@L&rqIXJQnyU!4vU+A6eoF!V_GxWaq-$PjT~$7Y08S zcy90$6`rTWXR3VGulRhU{k@5w#rPR(pKM|iUv2#06D$9+V!woaTXIksdkOYXb|tZc za3HXkq%Lsn;)}gqj2#j7%-F{ldsi*;5{*-An--Bpdvf!AeOL%Aw~FJ}9MYT+KqOoP z#W*n+&m2Zk?c7`x{UpJN#2DesgtH3)et3YTt)ZA=kC2Iq~t>X zUCc_LDHJSY?#=GiRTK#l%83}3f|!%fjkt5Q8Jwt_ns}o?I5QVXIxAqA66bVSD2zH& z=A|;eDmniCpV&TAI?FzLxgke{I(1dLghfx&ko3gELHqkS0 z(03&Zf8Py!kVRXn48#a<$P#0OMDfRucZ~6>fKziP(+MtII>UvAD-}+yB3YM{_H}a6 z$mP2D{-4->TCl5yJ3Uvzz8ZT;>8tWs7CcJ@dj^LX`{ITHy;$${ROp!(`?~mbax*xg zP40e&5e=CPI5513X23E8L6+hKwK>@+#z|@;s6`x44Cd;<*&~E`a^To=j0M_=I;($o zzE)JmNu03OtvHv318-lAIsJoQm$hKp_bGno$JRS9_(fgvi_+n*oAFl#J~DWSv5y5X zKx(km)!(HHR~c@KG6N>&#u`TmU!=sRqWlZ1_%nn5>%aTk^71P>%r}bP{KO7q&Ms9r zqr;vWdnOD5pm=~cTL%V%7;6XOuFgAn^K=_82=869DZ`tj=jKJ$Q9K@*3y+`W{6%sR zHbuh`MxqQ;;#`eUCo#IqxUh-$Gwy1#A+T#O5Wg<(1{`ZlHqOn(rN`!`6GMYzfiF$? z32RI?ZVOEL?LW5f%#4pJ;jeYzu^Eq3;;|@)0c_k6VaFVd)CKwo9ZPfq#9811rJ7n~ z_P3Z>YBP?QGpcB)ECSFx$LH;tx{&YGaF_7}Lrsiv!>mbymxVAlFYM3E_|kfe`y;-* zZq4#_MB9X-EnuBy49c=L6WC9NqNr5vaBoUiqp_7;-N6CTmQ5F;X(-S`qtTQCgyO)@ z+!)Ji&koTfiR<@n<}gjn%}MBp8y2}xm#;obT$racYVcY%iE4+jTDMxz5Kxx5V0DKe z>?HAX7=ozR)x+)*2^i53@Mi(g)#!qDj5UH-!or-G@8C6`f0yFdB09l7j{8mx+TVJXYnI7~eAE8E)wJRAA2>(ANtRp4$D4v1`K`fN@e6H>t$I z!V`mq!g+E)#Ms>Q$ANvqQRU+P$Er+H;)_a{Z!h@i$e8{9-;vL5v;DTQL{+l2EFBnM z&XH7jEhqMKU|#zo*MaH}3BV^nZ90krrgJ?gz@59eQ9>u?;6aF#&=M@cqAn7D*DxOf zCnI%DLhRm&8gDXZ+<*8y?P2wtR|}`a_go9(3$+lw_nR`wl$IEu&zJAIKb^s|02MKR z#WB@pQH1d=fVEAh{Bb?+iZI9X$Q*S}Xu??YoC!-3XZ3RhC#2eVW2ze4iuzOix;bZC z$>-(Dm|dLDzWXEVKH6q5RZ8iyD@#;_{Uiv919jtp15p&%w?v7s+XA6&h2Ty$5*~=J zS#q5+uOSccap8blh6ocgresquug5Kb(*Pn5MX|QovKgi@qd-Ya<8>VhI%+H`C!X~s zQJ5l{SXRap6P9A}oSU$1#dpvZiM55f84O<6&beEG_e=}*u}`=_h6;vKTZF8+Mvdz# zHMfiW8CQ+$vij5pz_E$1CGJ2d`Vb?NYV)nw{(1GA-tp;J-GMCcVy)+_{aTSA47aR# zq94^3&cAwdE_iP^k;JknqZldb|H&EyoR!zcIv|;aIJXl{YVmIKeb69LyYRgqfq;v8 z-yrC?iA{W?;=(%lZtpda5JH7|n5e~c4A7RaC;}n$zKOSqb(2CPz*T2O`DJ1*K3><- z*Tt&%QU2#*bW)3iW;5OtA70+O@UJk%B7buerb&#~B3=WmnwK)O#;B<_qA<@5=eUVV zHlOGMoe+j7@SL|NE=1J3qUMmyaStwhs#M~SmpD&` z`bDC^y+$kF@$*1ai*4=Kidm?cV>4Rs86nNN1ZI}%dN1wzZ7Wv$kgZy7Y-2)ezoN(W zZwvgI`MmtU7RK+I@@ad&tZWG(FZd;t{{rKeG5)E*4~uO+nOA(wlz**IzHRUwgujmQ zR}7xDmWn4Le4Y}oMLEO!H^)WAJSk>DhBc!sh3(|IXeajLK$?EVmJziU&q=o>jJuLw zXFUniAiIBqz&8m)Nv?LeB96V3Y}DcRbRh{vy?0Wt@*Mv#jUL$uUwerdOS9YjS0E5uad|Ya|fZkO+VmgHl(TFu`1AR>R&~)TUzgU^JriHAay?_ zwVroz%jmDPM4eO22Le$i^nP_A(wLg(eUJGeg*a?2E*s&3vG3y?ennijs~^x|{A`D` z#=KkzX@7B>yyvb_=jwGOF`}Kjn_y~GmPN&#cR9oP`!6UMrX}aH#>7H}p{1)0!~{-L zK_#ua^U4mgTKB&50m6({UHn~#8C_8h6FgA(wg~@{8Q%e(80^J)tysg|GUpN<zhJ=XFCQb65O03o+*ciqcQUR`eLl=%sgptFXQuF4I4l1oBaSO*7JuDHQmn?V~Z+<+EOPPy*&*RwAsd-Omi8^N>CC&>) z%(;a%Pd2_EF*ox7VPM&S+I3b6pr>(-n%4)r+%RiJ4dD9Y^4{0nTy%RR!Wd(0!a0c( zQBITpJQ3qXf}=t?OJ37W1r!NNt=vqkQg+2nEDl83!#M?e__}#7gl_lodh2=-aX*)H z%Y4yX0}GQ2aUs^L?#&xbF4hW1E5{$QXmsW}O@v;zBfh3D&Ch-2xBA*Lj9%Yr=kKuo3Ji^#U$@NeVm!^b zIh9oRSDo|G)I;wSG4^IXlQE$kVXhG|!kA*r#RY`tC>3rr5^Z&kS$#ZNK)jF77q=Esk9)qt=N?B#zCz0a$U7;P;u8diB-;25=&DmGiFgMoYK_S z6TYUaGGEsW&A5nI+ja09zqBwswVMqYAhcD?I9Ja#MhJ5;7G{ir%7le@{%y%vG>*@X z>vMNeBy`*gGYWNmrQQ{D(BaxWxg6R2W`g5&X862#u5P4ek!K>*_+&M&pmcGbwTe=T zQN%tdxb7T2NAAYCyDi5%>-wD#ylygY-nF3@$@N(>M}AD;UDP#m&J|9V#ANlSI0#mPu!WZZ|2B6W4-_YAOJ~3K~!Md zi*AGlhYDNC*cKP=I+SZ%zgv+Pp~TNd#NZ}DP+z2ZFC~bI*S_2vTDj18YQ|Jyl$2vh zoFkl}yrkmXV64jdMTfAYOsrtsn{qrEFxgD}o7luAHu3(%Z~Uq##jjK<#Qu#AfwcUn7cS}w?!YOQJl#Fy?$P#ChsrI zI2Uyzj{u;Y;?2n+KsM+Q7$sqz4G@yCr1W#so4VM;t1+jCdpwyh*wHeCNR3AnJe7)m z5LEXB4vlDlxXDCcjIHEOv|BiUK)IWH_todam?R~siwaZ*=i&vb6E)_h90LoCkr{Ih zVPO*{0T!M{0elw4@Og6Q(?wBmp3g-VAFg_&AO5PG{N^Wi(4Em=mh`pa5Mw(jeW}ZK2GCY9oM>jHy@)*xC}6j{P_* zTI52l7%saG^=KQi0L&_uzxyA^*>C)@4Z6lJApA|>Ulrl6rNlGfL0tb{;DpYNpdJUf zB@-%3EY-#6N8(M&*9Kph@GnaEvq4}`z?FF#Pn-S7R__6EwJ@`mp|iCtjZ!eGN- z5J01yXlxAvu)Svv)EUITY*cvNz2e1RCpn%Fh8rTB3Y=!c4U7|k^JMj0LG z$;J$rW1N~W6gWb8C5acw8|$Z+z%eBg64T%PRi58QX#3K!{;73}FW6bA8-!TNUnvrg z7RDo#XSnF|BT4L;(gzO2=!VHbDK22tu|$Ukq@TsV?p2iA1d}X3?Bl)xRS0>c05FOe z^8g?wTsXsM#%Kuua7DiV9bK8p1!{?|2$kiAlON1&oZGM7cLzny&9|Sh0DSqrB%1vV z9ZC`|kmTS>PzzGHWnqrn5nt{S+0-t_iU=32dDEx`%(8$JCiL+AD$VGNvW2nD1!B4R zTKq)aJ^l>iRe%T1aB=ygWDKR`3xOBnbMUk(eIC|1^Gi|gWvsz8=hHNA?V5r~?#Q|E8^C=_prEGi{&yR#!+~FKy5o^ni zx$uKp0DuGJT;|7sCLc?-Z~#SVqwL@fM#QD?oFCPhP8KqY3Y`IAFaduGqU2g*0ZS zOj-i44N+58Oq&o^=Ke2>cUf1;dYMYq<>;?hKi(x)5TM%DTkldFzQL6$cYni`z z4pf;G7pA6SPSPn5ssN_-@T{c*x;T)|$wrCoAZBIaT%Myf)~TJ?v3D(M+9u;$Uhmg} zQhpcZzq_ePBh+K&0z*@v60J>CT*SxovAp)J#07j%2h>&B1UNux9iSKBy`890Zkdbh zt%SLt=~>j2&Jm8p*WBYESdA_5T7=JP^Wz*sM~yDVA{8qJE>sCEqz*(Sc zE`eqKleoY!H0vCTwW$e^eEV6XNU@sSpT!eRf*gD2?O(rdOPnyL z;*W)vz+`NXRN*ho_;VHh_o`LLzSyHpiE}#C#^eg4&a@F{eKltE2fr@26Knk%BO58g1;g$I z4^{Y2Fuo_k6NLW*;eR0U7Z}?rND}@HjQN3Y$d(QmbF&y#%ZKS(oP^-`1ru#+n+}{g0uW z*u*9_v58G=;+;g)AE+^%t94Qr&lVcdb*pQS>+;lEJTK}L`J>%1&#{Ji&EV$lS0S3H z*C)xsj1|Z4Ebtt)BGxdGyNbE7*Xk$w_PSx9)i&}I++?eiY~<=sWZXnsOw_D}9XA*B z%qD;Nc$&43*JjGVUJ{4>p~Qm5+%`Y1bDa?G$hpv5jA>j$OEV^>EY(;f7mYc?@v~io zN|FoenDEGiZ;A1M3#Ey;<|e?A37?7Z|CsTq3eU~>RD>_`YukBP#zyDo-iI9Q`+sVk z#S0Fs-{pJ!1DY_ulF0p` z_G7v5{N=YeRyn`4b)MfL25J-Q!~6Vs&hZuSwS0JS+|2@YUYH5z;{3TYOAMvt6-%b3 zRI2nWIerM|6g&_&gZ`LR(VP+RslaDud}hL@Vtj`1)2iar)Z_Et|99o}J3J5XeSG&v z*57@=M=bbQ)bZRTK2ELQQJx5V`x4g5Z>)^*{xrd#6~<38&RgK~Bs~9+MRwok$h_kA z-zuY6_AlcAb-@n0iX$>NDz0B^!j?iQi5*CS3 z=64lgudd05hF_;A)w^u1k zNfZKQU0E@R2-{S2%#BrcL~9Z8j3L;?F;lzZc!P{DxXt-#GVJSLl}wq5F*VmQ znBW);$Be@e&m~R}UQuz9oNF;e7>hANIkN?`qQi2Wu)a`M#-S*OSzioXk0ohnjfLhI z!Xb^|>r<|(FJ@6!uc0jit5igFOK`mP;EEdH%#33ZjtHLVI+F{#XTI}I@q;$H)CyoVEGj;^T zl&-iIj*6QHV=jEFt#kTT(YgSeZqZdp#`WO_Ko;0SVH&-i2?Vw zGJPCJSel=MPVi;!jvw>`s!W+{Vu~^j(c^Pme`P2ILlUPbGZ7}$l9?z=^}bUnZtSv~ zymtT4j6*f{&CMyC7@-W83eQ_bfl z^T4DwQ^_LRUITh_zV;9whmQ%ooEb@BoRmt0DV1}>VqP_aaq!LOrj+U;*d6g6py$`# zvn_C=u8u{oFPGdUSLoA+#u*5`ezejy#$QKwN>ixI@Xe7Tmxum z!bDxyY*+|mgmI;ub}P>3Qzm!SpxDIM6It&DVAiFN#<;a)SA{YOLaO!kYJCn9`Wj=L z`I?~!PIERMsP#9bWgu+Eo;uE5XiN$^WUY=>^WV$~e$%L+#!$GnpKs$FH)~7?V{?t0 ziTe67ndeERI99obF+=Ibyio?{NrMMcV02JQ8Uw$~58gJR2z|QS_Oj;)6G<%aKK$Hp z9kb-Q*<77(izzd4j_pzsWz;JQ9B0tQO@Q4hp2S#oA2i_U`Kd58ICF1tBabh}+6=wpf8Ip@;SXb2qwkGQN| zI>q=LcpjQ@pKI%PgXeVk{OpLIe%&~zO>E+u5}RW7CN}Xi8hPSI*(#RwFPd&>i0@o9 z-XM$e7!QNEx{Zru?aR#thl))3_d;og4q;ASylG4_nqKGiul0rB!rTGw%zTkC1&&lX zG8fA`QR7t>xG{I&ouEuDajY%~HLYEDe~sb0D70^46Pwt?ChkAJ|A)3+2)$YqU_nQf zopntMq!ydq4bp!uNcmjo&MKaS&@piGk&Yld;G<4WihfF*>2O5J>8YOrOA5(TX&s>DD#EG^7B!nkBBo0n+* z-GyqmtvPlt?#W66=S~J45xEdG#~4MiDHr#K0YW}ASc)-8?qcfaux)DK1}EJFkSL@; zFbXraq(G_Ijbhn>!IlU+BJ@MhVJ{jv+tJLr?z=T}!GZ-2(s04F6zywoYHJb-5{BB}Jh?L8sxz$2^T~wN{jcRgE)D9FVlCVvHn$!VLE=Jn8y@NN?`cRWr zy8?wNA`TeKLZbQS2NxF*k9m$E3z|V=haPQqtS??cR8m2<|nq*ANjqRO%BUBk_yj#Qu4eA0Bg)U>U_!x@q6GTq?*(t>{<%( z31NR_9g^zz`o|gvtjdHQtgHd0$t%nW=li_daU$X0RbKZ^Lv%8kkwiH&b72p0aOjB` zV_8EeHovd0HZZV8Nd97|0|nNug(8lxdLrkAYY(oSE3SKQm>gcS-M0=|HB@=;BLij< zl!dfJz!RMoC=l^Euzp;{^Fff?3PG0od4qw%z?804wGm=hgs#BAe6H-7I@ppd0KVq> z7Z;nUlEu7Zn1mo_h>d39iX8W1EZOV;jchD6iMWXmT?{x#BCW?6Ql46`sIpLx`4P{> ze^0pZ&)mYCK!qj3DTykPcSqnl`&*bQ--ZM<*QH(#R; zST|=lFl?FY6l!3Knb!fivF~-6omWL)%5Y$kSqNK-GK)Ge=lE$VDy;`1rs z^{kuwZ#PAr&zk-A`oNnIE*9~5OLak|1tI1sFhy9#IjCq%J0?-X%LJ#f6iida85$y> z!fWxh^ZC+PiZZlL%zufOgE5n(Fc)F`YRu^${JK|Fh(@I0& z$gkskJwGydBw?m>;Uns`qX;ik;-x4ruviOwuk%YaUZ;XrgC(!uN8_*W{>b_}JM2i8 zU752l%1#gocJcgoM}>j;;{ynCim@B(!~t%Sy~EA*W(Pid&HPO8Ua@(tc_NJ&rD;3| zOp~F7GO8+ODAS^%pk$sr=iM@`&D;P;4uEXLD=HLiz}X=jymw(=x1|M!H0YYKt!^x% z2|D7(?)Rvhm2BtQp9!MSGee_hnb#g)xwul)b3f3`{TmQ1^M=+B@Lb8FzJ5R7P=nA| zu?Pqu`26$s+sOtK^~0Or8=I*h1mhEkl1ToX#plMcTNpiQh&n0`Oun+#WX*Br9ziC+ z$;yjD7AH3mT4Iu$xbL{Xt2h7VJ)kTan#hJnDf02Wrcc%~ZNP=eo4S6O@j`8QTbTdu z#foNqXVHHw;+k>MK=JD)`HxPJEluJztwZ04mfur|Ffm`lwyy``I+#ZOb-8b)j3RgQ z??&lJqKEjJJ(*+d#QSkscs0d(L-9KLg2cHAJ@LN!PsI4A$?KT_s4z}YDQsb3vIa|c z=Akd%d+H}A2KFM?8Hli*ydT(+mI%*Foh6pFBOqYpKX}n0r zupEXIIva)$`X5`?BMsX6R8qA<|cX_vT=oPXLVieBS$hf3i_(&{5D3W z9Yfj@Cje5LS+`>%T&@ipjhM)#Xc?fIQR)Sg4e|T*(wJ$58w2V^jDWFY@C$1E>%brh z|F6J57UeJ7$DoN>6?iR$2WC7pc!&#AdRiOC$gKPx~guRp0S7=WP?~Lm;J=pna?dD|0;1 zkifR&*PD~Umlz`nqdQz2s|c~9O1<{fF>x}zdEc=k4Mu2PZtFyO$1u(6--W3qP9$Sp z9m_Nk$2gstT+!EdEb3a!VZ@20wOGY(A^gA`gZ+<1`FY@P#`+}^e2ExhN}F&DMnwlF#8G7c#p+_?!O5+e~8y~fv$v*h?K z!A&fF*^GVh>pFjy87veQ2~ao7Ti=s^(|Ii4snPXc>B;9h)Ej*4HJfY32d}L;<~!KYv5!*p0EdsOpraj!P1X!l$=flj}*Mi&2=~-#ogBZ%)+x z&1`gHh+RK`8*y(a^}Vr7fvZVwNL>ZKyb>Xi;@)wth#6FpTD3n7Gdln95jS8w%~(c% z;M!={e!q$^7gQa@J-Z{qAO!LT_}Xd*=idxitq~i>SYU2$_T>igE<$T~4)D1OpPKNO z0-u{*s-3=RG)BsI2(zZAaNEdu(!0Dz*3`>y6AAWZz37-?YmBj_{*G2(`*tSU_Yp;XCpr^*tCcpZMnTx70q6$5c$!z~ed$+43~ysp3; zOZArL>B=y#ZDhPa7RmGR8blJBl#JhOI8JYXgRb)`rLyE4ArltS^PI-|XGG+lCQQXS z$^}A44NXeNT;RPEV`U$&C2Zrp=!>~$g?}$|Ni0m91EIl}ML-ggya(2a^_Syo)ayUd zJGrVl=Z32-`~`v8Q6O_i#cF6#4Ye^tRl!or098@TykhRTFXt2SN)FIgi+Lyc&L+N* zQP;<4<(Xb|$XArH+Dnx@|Co!+U%Jl3>swWfMXsmdHI6yCkMCv#^O)1lMHrg06k};# z$C`*;>I-L4%_fr9CRdKB;DpusX{FNCTiaZOC7cYV{@SMl&R)Qljp)pUJ?l}}k^@nc z#6e*c3HAg^l-D>Dtu{(%^_rQKsU;vS$eA$*;AsxrpmX zV3ZOQ5h|%ziqfmH$wYyuW4-(0*ye5sUS~Yjz%s5z5KA0L*mDbPrOcV|bydyzFvr&P z0yizugDAw1;31a?SPG8RI||DNzW30b5;ss;nAZ>|_*!I+F$@0h$Y3GLxmAorS*FAc z@9E6N#f>XmSiX$0qa#Ks1>GvKRro#C6R(-?n9)c7!;+Uh;ST7!lW4Df~ij%U#vVxf!3rmzz(v>A03id7W*kB)JPmBj~FYG7S73To; zxqE%Nve3f7h0{-Q(}C9_yhz4#F=g!7&XggJ?>xfV+|xKt&1EnxIiNXgh1=d1a6={aK;7ctNI z{GDqE(bJro*O|^^Z9c+Hz(?X^#ysjwB0i3I9_;5eC8G>p$QGWDl{8}IT^f_Ao5D3x zF6bfMRV(G9=Ht^p<>bD!0lvwR&7x{^n2N)!3m|Uv)D4r0jCtJ^p_>x>SwGB-J@GZj z9&TjO!!ez?UUyTtNPWv7%q(yK&hZ-JrWO#q-TMza6_AOJ~3K~z}7ABbzz1ggrI6i_C` z)U|E9z#{mD9aR>|bp$$Uq~y2`wL~ErYp_IDgstRy0&TORi$+B|+=2HmUQ3$AF^&x8 z;<^{}BqVkIi`T+@ZmY~OK1m$gZZVH(Y&ZYw;dr2x8vPBCHM86p0!HSV2czhzkIZXD z)952EaelXn*ZWnVNJfcb=DbZ2=p@etx-_`&-dmiv%Nl+bbJ809zAyn?)$Ut2Z-vg+ z`^xS8(BrrM$POo69%;p+LU~y0`v?yOo|rY5b90{dLoVkNS)b^&!3%-cV!TeuYi;Qi zi5uj-{J6)E-c;=4bx?xSr6lY;%Sq)%eo5(ldEQ=%`*VKTPG z7w7vph^24tw3kIq_7L{)M0(qB*W_zA>`6lg5M)fz?HU(Z5ZT{&Q{g*Vvw)r93-R-C zBt92+vOW!v%@<-!vSYUh^W?7|sWR7!AsrUQjI+sr$?yG&tQD)<#3nYeiA{XC@%=xs z{bGhLwwfYf7FH1GRngE@;lP}pv6TUCxd

OhLPeqhaFVg`ItX0D^i^ECUc5(BYf9 zjklu>l&i1+IS5Or!LqfuX}bU@VPFx*I!+GIEm3ADP|?AgDjLq@Bb1VgE*e0nAbdf9 z0s&J>5{0S@hFhXkZ+2(mQm<7A%>}KyxW(qUSlCkW2GtxddM=X}{wkqHG-lvrSEA`| zVWMJQ$n3=atruu)Vvd6qrwB81H`-287Lt$vK$M0XhZvL^-=h)W$_B*NBa6g&0lb3?!R#S)#n+3s+4oha z`9#762_#7X@IoXjTJ?pwKu3|XKtZAu2lkaASa8>KcGp;1BS`PxtFR2fWo1tOSXhF% zUo6&|9d*F!0;wTXX2L@K{@l6%=-$Gw&?SD~^zwO*^V^H>s}^do7CH6x-ZYd5Far+fFlw#r3Omg86n5dsrSBvND` zlyR_(B9(;{StM2$Ji9r0ZkA`gasJcmPbz{{DT_8U0A4cU@qoh^TGw5=DD+ z1>oNT*b&444?t9QjmH9xi`9U} zvCP5}HSnkp+RTYrRg*kOP35{I(By!2LzT z{Zw(^oYyglBWL5j!F_jLjq&Fd)O5QF$a_kND43dWov4EI$Wr`mJTlY&$B#Jtv=}CR z`EB3dJnQbB`Nk?JEH&NV1E-ofpREeO2e!$)j)2tLB(}^sC}M=bR(5tsY*;5+czMoI zjj@P%EE6Gyudyu~EVD>0%PbMDA}T({sDs2`mwO1njS1Hq(sjalSB2eZ()Cn?y}S5m z!>vDaln0A8?{jYYb!LJ!F95HAQWZd1 z|LbMXEX>lLgUEM1>;J|jx>3h{>Tz>8A`qHM*uJdsZo7XC61r^6nZ~$q6r_Y>%hV)J zvP>xsUB+u?7>h!La+oLMJm&zL>3%&;IycAA5u2>$XjJ1bn=!?0;!9um&HG!|ufrAt z%m+7vDy`|6hh6o2CN*|534C2}w>;J;FWgBLuV&b?%$^(j3ATbPwC8XTgrIfd(%O~# zs=lZk{@g-%EXR0j7DU^Odw+y-HZ8Fo;CtPVAsTBiaIKe;JA)V_B=~70a|W&&ss(T{ z-C{g#t51c5yFTN!bDb3?a{pa-@zTe$CNkFMEbYg%%V~%VSg8-)*7O>R09*H1C-&95*4^TJ5PS5tx$pHm z&P#jFK9cASSYA$7Sw~4w&`bTZU582dZ|Q~Hth{ZB>h}%m6D@I;S@penf(40LkZK1Z zF1C!`>ll&oB=qHMcxGfWdwRpvYrC!%(Kwu&a}1nN@xD6`%{e78&2X9$r!0A7&ch5R zL-_8n?s_j?bCO55>oL3x27f>IYksgC@&(U)0pknq{1C=pG3N`c_5;pw{*c5U;e6AK zZ)WG41NgnK{e-={{<&ZJx>xtN9^dC*HjEgB8JjV&%pS%L&Q3Na$=D&YV~I)5>{#TP z7?Tikop23-G00~#*E;eXI5!d07M7S7;aWE?QbW$F5znj=$-@%0=gW1@77w95*sGrS zyulA36W+e5Zi9qmA6VuQ@Pn?J+IQk56>tzewS)*SoADV%4D-2!X_*tAKxX+ZebVgsC=My@fqD_DT)miYVK+I!9~Uj>tU1cpo@4c&9NQ0FROk4j<&2 z?~XF>Rz1PF#+iTZr|c%9zp*TRX)>U89ler?Jjb|VP4-;YT6cNoUA*j3M1eEeRc~*QDM48~t{7oo@%~es z&tTj~ec^A@%|o?uy~t@H>0bNU&S_wUgipG>-N)CwZjxbW2GLK_Cj zojQoZ5Q0YWJ?9SQnQg1MZxS`x1}1Lo^KbZpi2a2k|hWcbA!Mtf_}QITrO387@)ZKBlf=bmyFKRWm#rUu9p3SBZoKj&HAV0=`l$$? zJ9c4~JJHF$F^PJ-!^nxYqg*7RQ|HvXn!^u9{`99#yRI3An8jA~0?T)o?`jA^bb8l> zhp0iMC&SpNa{ixpl)6}VOpBnIcDA$}?(Svv=85}L4}6H`+%ZphY5<9ZPXoJJ&fyXn zfR=t#ZO+0Znp*+Gn0F-DLx>M++%LHH8k6`4I`M<(7ptcgy{>0SKReUBZY};&tsBSTh?WWQZVgq5~h!N`&q8nI=0{G&SP1#tK{yO#W%R>P>@69 zRMq@+X`i3>ddA6Cgz>#Kd}*?JUrRT#B?^|e#%WwQb@3*2T@HO!)Op-%y(ZVaR9b7d z!KZ(`q8#%uqbt{jA`KQ87d zSLpaZstM2Iduqhf8UV|jsgm-KCd3knJZBWs*M=8y?`yqf%HSZwUTWA10qL3`Yfls~-hV8o0cNue+sm0WsV>b>HeBhbyRPc@`-miyzcR1s_7Zu^}_FY?>KJdzuXN=y&hMLKLwEQw>PK!u%qNlB}a3U zN#Bx^Uun&s?DD)OevjmmQ1fn`oGAhRT{ ze-9%9RKqu9K-T4L%IzwXIPUPab)%>g6l{f-YTfy~)n{0&3&<@OTD)iV24+YQeCf&y zWjLZ7q{*2jGVUn-{MsF>jGTp`YLB}+mW-iyy!#bycVMF{Ge%@-cX&LGYOI6EsjF*` zPsh)>vIb1K+*R|w{Vx|W&{L0(vw3(FKudCOkZV@3wMG1t6;vF9=b z*mszi_>0@9UauPe%?HwZHIHkLn8`$aZsGzJKEWx@kqcjQ0z6E{1DE*kG&xgGZws%-2T>}BV^8LuUHCBrL5i&xu5dC2&t?Yd!mYj-XzG4;$T;wevEyqOQo z`9AQ0!{Isyc)Z}^@BEu~_}DM`ghk=R%tve@6FRC|xS5<=@og*w%iY*a@mO4s9nJ3@~=e#t{i{nL`M%&PrYNybyd z>@>+@9@H9Q3#~VcehsemlgGA~d+xTzO#LWzf@y4P(J5*B`EDHIRDrcLlp9zvLUm`5 z5({7>XO;;ziZD1`FKyx)we0erNSQ zJb+v2l-y1je$~w60^x`cEwCt_IsCMX!vE}V`1WL}`MN&__lrqRc z-hoShRpVz*Pr!<~98pV4Q4dqzK8g3PYRdHudu>Hy?P;{eu8U&c3UD0joR*Wys{UMO z^z0nFlau%Jc({nF{?U_`r8RQ7RO;Sr5rqS7`@P=nAeY^FLB~flQ|9i*tF=@ zILy7`d{A>y)y#^i;Zq#PyLe9V<+pufH0QwKm0~FAs=FNkub6Y-i37q=vOJDz;p=1A zIl@#v#ChLMMi)8B_`;lr+4!JJJn)(a$5S5u%Foyn^=j_oF7D!^iI=L-br*MW7oXlJ z&EKmQ`0gB}-XgxgxOWj@x6If!IB*rNHXQcsHjTvqZ#j^ZD3^x9a|isIM6h!d29_?7 zqx1OvIG#T;6`9V-JZcit$~eld0+S~d&606QW|@afOF`+*74ZBoH|aFkNzIWFqj5 z5!GcA;_u4<(;LGj47xPKJ+nk+7|KsPzzYF*Z~-Z@g*)!0L&G zWhzX9ojK!{$Z?G|2p? zHsjjnj{EZ;pH`Yt&las=hRKAcHPvuqE5XPMsX*szfVD!GGDgvPtz0CP>aq8OKv_+Y zCp^Zh9Dg_77mC$m88xgjBCX}#YYa728+4tu=O6$;-P%pp(&}2SJTD-2ZEN?8uZcUY zKhF!k#{#%0(546>^Jr)(QY$Q-k*M1G`C$H`7s7NHEL2$ zJ#!44yMziJTH<{g-Xrm7y;)wsN+0(o`7eCK$8~0_G_=!_35j8rSXGsr-2mTjr^Kio zlXQ)1RYU^H~9) zIw^7nf%UGd)y$GeMmvqOnGzdL4|tZ?h<(|>**0U#m78BB!n~vtuscV>a!U*FrpW~F z%#E`E5f-D@skw+ZHy-k04*Qs}7ciHueEv=I|Fg#GI;ec%FodMQ^h1^994+A_Au46H9SC^4`8 zeiefL^~M`7HnR7`;ea9(y0R~3_}YzA1pBLY{^|C=TC(umdg4XiGncnvA-fWU_Lc=f**sVlR*mq-} zB^wxfZrn@84#vJa_nocQV1KQczr8c(h5X~gsg2!n0f!>9~0|2#K$8X=&3*xrIBvVvW{R>Uhlnq zY3KhChPHS^veoBr6S>WzO5UNoqMv81Z+jCY&8FlO?T<`k7Fi~63t;Yp2w(y1Tz7xP^!lAXW;}GnzqRK- zk~_2vDW-eNV}AA?aI@T#A|<%$b?%&dF;kS>j06kxp$pS0V`hDGPLuiP+6D-mo!j}b z#|W~zgC`j_RnaG@qOw#)UD^OkPRd;^ z#*9`p;G@5fo>x5kby()qlHcaiOer~n(XO5Km63b-74;l@IfTvJRbOlO9aIZ=@=xMw zv&rWimZQI%*o=8+jB?wBi|jH8l6(>2_#{L*KUUULH>{6+?MF3SVercJm=Qj1Zbh(F zbMzSXgfW*a){M*07Y;k1|5=W^w_TR-*6{I$Pow-@=k zCJL@JId3|=6=az=J;a0zJ&v#_Z?3(41`_uPd_gf)*aWgWzX$x^!2jgVum8QDv=7P~ zf8iTGJ{xea${aNDJ;Zmeh#Bek&vIG7V21M!@NSTy-$}jS9o{Xyv0wVv?VV>mPA@vX z{I+kTIX`3Yw}3x~^T#B9ALkr+3+FSIc(W&(){r?T39n)@)-B?uL!6-}8Q1fexyzNU zLS8a{2OspTnJhIGZ?Ph&aa;3X?{?QkMr8VorieP4E>U{k*bcNC0T|{)f zxdx~ct&ow#igm=2smEI|JJ;tEs#lfz@LAv^&Rqt`MHqC3h}VDC_1Hg2@ZF4XA7q*! zF|Xvk2D_wd#?Q+_aBEMmU_!5YzQu!Hag6pul(rQdx6b6^ql^Y5{z&AqmRXw2;1a4K zrC77p=8>xwK~bkNqq;Ibw6+FXgt#tTbJua1*RzkWJj*K zFPnPJyC6{u%V9zwk*)!y=c%=}1%Bfrs~7j8h-MA>I=`wfGbvyJE7`*qHcm_8^kZ_qul9osc`=M)*Ess1ZLwTt+Dm{)7h zGZQ9g8)F-Bo+h4{;O%4Oyv#uV*D2H-j#<=B1wB@ z?7FyIJM;|qJVZ?`hslXXu0ij*zVwl%wMQM8Ib#hwP|CA_nFRCuW-I0QkNUoN;^_5Y zll`f3If~<60lv*m-St(z@MphuI>?iNe&i#sApEd|_q665dtwml$=jZnVieOKSDqd&V&F9kPmC%VgE?WK zk##?eDkJBHEjI?17ISjC71Jaa#yylw9X!h_Uf8$WvZidrQ?5Dd-cvd+7H_}(md1C+c;41fx;6#jV)I<)+uYW6SB)78z8->CReq1xdX7H6 z34<_qZ;d@_G@gqiAu;O|HCAz7G`_5wEqmmux(Amya~Jk+k@daVf=d<$+v2(>M6}B| zS_DBWx?Ja(u!}JP$-KuY>ya0KZ^gIt7oIQTOHJ#x$bPg&D_dY5=Tzc-a~JFE!2nI{GR@%e0JYO0a&OFJ?tH#KY z6M59~hX6@Ez)^NaCiBt_X!E+q#nTT*uKsQChmRc|RnGSt^=Q5WybC? zlsve8H{`ONm?<3M9J+C6=>H^P>rTA%B@~YS^4q?#dB*1125C@gm^C{|ecW+V=G@?= zc;RLBxE}88o7Ov98OAAf9IYPrS%R{vuSpnFIqfK^Z~Ua=?2^vxDYt9K)aFl6a)h$> zyd}@vHTUJHJ=GrOr`BCV8TE<@EYBipDa!rC53XIJnvT}V3lbZqT(QifyQ#Mp&K;h< zw=wLXJjx=ks$528W4b=O_}l(QD7$(903ZNKL_t)c_S(BmEar{fHs3r>l$@$8^1X*W zFFCk=x86Heeu*bO?pU0=_&7y(@%ZCjqL+O%d4d_U>@6p{Mr$Mq`xc(0G$_syx4d@M ze$G9Ulj=lAk>d-OQuq&j;|WyPNYQ@11)k3`%P7;gX~By5)X_IAuWK>Yk|j2%;d=D@}I-Ne{M^^Z+t zK5(0RzcXWfT;8Yk=nRP$Uzl_5!bnXmaYE*}%=-xQen{pVIM2q38>e0e7JdZd1>=RW zZHa?5;q_PDc*8QUxpB|5-(yeWv6?gCn)T3)94c>XiBlK<{ldi&KXN!U^%lPC#>0}Q zv;ymi!_y<)`<0)u7mlBQn)tb2^8lc-%*?jc?t z!so6&*G~U+)_cr5f%Nt2u8B$H6jN`4*gn@Z~oLbdG zd!9xUeT=S*cJzJinC37~oo>vsH-=~L*VFp-IN=L&?8`L96Ubf9h{VhT-{6^LRq1oh zXqu$lt4eH+r<|V;8JV*+XqYymn9njh*%(w|$YhB`tl>*7%}rVu^mS8=J=BMi`O@kb zS#-&YUfqzV(>Z8doJ2!46hpWVNBFr0&1*GU(|VGoT)`t0!{_8Z9D_ZbkJx7=^CXC^Sb(t?fxn#mjYh zjA{%=(Gxn1`TVF{f037;pqk;SJIj=q=G+-nAPu2eN?eqAsp#Q8IOpucG-ADr=NDi3 zZ6BtG9AtQ<&Kx8-$Vq0v$UyJF!wi_tW>t)@QPFz_R3^YfBFWf-%m^714B|fUXc$0d z*d&IP0K^3dxM7K50K_)|5^eF`kgzj6y?ES<4vz*!Ax8+f=PZ(O5x|Nwj5C+u=!rvZ zS=T0jJ2{1jVwMZGz2}mWNr$8E~$XKX02?iW_j6ca)Qt<&jLa*mlp`QdN zOvx|f=56ne` z&KiHWxDEvRIC5Z+jttISVi8jk)9joi5dc4M0YM(b^>Av5BZD)~O!JWGc*fx;@mv+a zRWU@%bG8QqMp?kSjZ}boP+4k$-Wq3&y=an7qCvWe#W*H%z4@vU)(!=nZPC0IDDdg# zRBgk#gPD`96Pm9J@Hj|K=90#*&y_*fpzUh`5#k#RvGlqZbJ3RzDd zHn7!syO7mhy6}?yW$jzww?C210S~g+i}>s$uz_7ufg{M`?aO;&T;+LR7j*O@h_sN{bB^t7_pC;f#v-bX}u}Vht9@wz=!WFQ^6Vtu4e>_o^0y`JwQ7Y)2fJ=BS$83 z;(n44(J+7*TP9(oQI;4@ig}}uhEkB2OgP{dbg##N-p*;(8{>;e%JUg#`eMiKL1duI z(H+ghR_5-Qvs(g30Hd`&)ix!H!3`2|LZ*G@sTI+xVs~z}{*1w=6()%>TbrSSta^9bcqKf6XY)$G_Yeb zI#?f1RzzK`N4O=$_}&}KKli`z{jYx2UP!KX7av`e`T)RuL+i`Zdxx%eZ^mZI+-oFQ z^aCXJOommjpgH@%V3M6(TQfY3I=}+L)VJi8nok;xtpEjY@^ogXnIO`cbK;u4&XG{^ zJl2~_B%;+s4&1n7))Dhk{64U<2Gu;g5oF};AlPi9dubD67(}@z+h&oe7g0BBkO6_m zJSwq}Rnd@=E97$2dgGGCIwm<-7=FBzYm{e=-a5I6VHL3<@4cwlZJPV@5z2bZCaLd2 zm+yI@W?x^QZ_K#x%mv1YJLf5JmNVx_nDZQOfy62LNMlP_5O>Cr*G^pIj|n1kZlU~l zOc-XH$a@l(f4Utk=1T5Pof3^ZwL6PcgfpFG>34*W&7bD6b!x3Awe(VRp`|{RO_!9_I-vV;! zRtRx^t}`zcE+~h9zhmSK?pfy~m3pX*np1qoODj>oSnuJOP3)0JR4T&7>zIn z<_z4TcATlgnd!qnHl_b6lbI#LRLoJIWfoW&_b>`D2}h?80KCWb=QF!A55Wl$UiDeY zjDbrSU=a1Mp{WL6aDgv^pwU> zmGk{9Qu>isygSIe*9qOUYttN-?e7s_W}job1oFk#k- z2V8oFXA+G0SVzedqORsqSHp`zWa)T4qo{Cv*G)I3@CLg7iUH0tuqaC;?l(4LBZU4I zNbKpvBxH~?fmw~ZArd=ErW*XfiRXmz+>8OkP)+{%je)|GE@B%z_GQyy940^K7$=r_ z=sj^*bEak6qla=HJ5D(>4o$8afVr?+DRrhp{hGk#2+>@0&u1%@*)kR+++axVa?KaM z=O011Ohtu1GICPAq>lTy!C6`{Wz~GNOfU;mri&aVI~dE9Ira*-h6{sHmZ;x>!#{`f z!}RY{qc|RN9O~!Y!^Pa)CJ#$eRLr;uyW@5%Lt2R7Hu$`SP#I@WoVI?+mVr+pw zbY~;R%waMH+1WrCy&=#4u5~)B@xq|a!VoW`57NXOouS3Rk0a08^vh$-(sewKaULd# zDA#CQ+I9FG@Je7OzMV7w1mkyy6@QeSZ}vYZ8+P=*If(vfu~UBCHQ9eOUgLK4 zXZIg!FUL=5kMpID7crJxxw2i07#aN*uf1XO?yk2_U<7Xu$~fLT%OB>{*X!GQ0hbP|w;yxuA)leTomOX@TM8B0{2|Kz+Eg1+Ac>CQ@n1w z7pOmZj@H@_uQ0ecT+#99;qJC;9zKhp>CgU#Z%>x0+w}!V3*QJJtLLdYZCAJI^Nw0B zk$Hy=b6OGSPVh2gNkXFds_3OeW&v#FdU{&UwFD(~&CJcQEHO#4FwfbAqiRehxR9x0 zJ&=%qb7e(@`nF-rT*j#9I5SI}xwCMYmDVJVTLIf53h!D|q{OkqoXoiekD+povs3$s zfoGlx$MP}b5zP)9}#AQUdMPe(2es@f3pKV7y#ANJ5e_;29 zuRCpjoYN4~JVQp$IdZoJu=Ipk);cE)gvJh=CM};0WD>iJdZ*Xb#+Ml9z>Lfc8EKix z6r@fbre~@*)Mee*8q)|fGmIWcWgS;;=!E%bhwB@`y>1Kl*-KqH>YwDb ze70?d`jc}Jycm31i}Cle-id9XtzXjOAN$+YZl}}sz*gSpPbU)F-@PLCo2<>yNFM7j zk2OT}h1p~IZUWC%4E1U(>NU;@-ov{& z3#+&Q9=XJg=N{`Lb7sC~*oAhi6ER+mW6x{m!F?0W)$P25eE}eGo{dZM$l!vLDzNeM zhWeL&+D7p~a%!lX%tANh#R2ksA$} zoI?A?HCm6cFsjgTa6)uE5j^pyk7AVAn)0IF>CzzwkDur_&CT%~rWMu`cqdFNya@R# zjy=oVtC%cX@Hw+nH&72Uqcp&CjWJ*=_@aB+Nv3-v0ei)0*@S`JE@Jp5zWcz0bsB^8 z1EYtxkIw7Um{-(sY%UCD2&cHr&QZ(>Q^LH$gyCLB9$19J&r)KM8jc#L9yuqUCVuLz zA`BE}iGhvSNzRze7RBg5+@^u+JXWT$zwkjf;vV02=|C2fJmr*H)0K72t&A%oiqL(@ zZ40jS(6zokM!kqBDY(lTOIsrggyTQ8FtRXb)(p59TySz$vG}il($)<|0r-V)__)p; z*5IOIFAXCHT{29mcb|uG0YKlh2b8D77t>K&Hx=#UAuelfNpnKa zwWbphPb$=Zn^@0>WHzqvKc^T%^bN=R{Pj%ZVeD$^Ik!A=lQxaV`%f+Db2FS-*0`P$ z7fmtt>g8bBsTpY8%uDiS({1BpusQpiXINibt#8Ow=EIe98yx8}7h2!gHO`}@SbGbj zB~2+h<4Ke5$k@GuXN23M1$w>o#JL`=~d?-XG==FuCkalkK0w;*t_@y#?Qa)lj)Sbs$$QKy$W_4V=o!|E={35*Eq8WdQE68l%K0| z%mwsJE#MFtJQb6_M}CEFL>}_!mw()5SA5=G+{ImdisP;cdlz?c7kBXj<4a%n>i!nH z&47)1z$P_20T$RV#rfhE+PZ@(Ioxn((~=1M4)>7Y?QRjuh(+cgn!t~b4pdeahL3le z?!WyeN9W7241oHDIkg*SWEN(expQHOb9YYNm>OK9%p-?|!@CH)du*Mncau!T%qDSC z#OOZECd*yi#a-ORUEIZsiuI-htTiTpwsF%7&+PXB-njM#3zTk8tUls(tu2J`;ulwl! z7Te93ou*-A#-1A+u5oNHIU^)sRs@R=2x0#KUyhQo@3iFFUDO!e*i%3oagg~`h5NB$}VTQBhOx>AU;>c=Fn<3MA&Gb4D!lyNgVaJ6rPGjXHRc6-mPX-8Bg$r~upb-BBuDVv-l1@Bk9w5qv33%9;uHPxfG7G#vLuROF8D^FlSP_GZ za5d=LaXvdEb1XS2ClQt#5o$*P9^53cg|lZ8h#$Fte`7aBmh~9dgZ>h{H!pceeCNhj#&dWuWi#d#>ODw z4%<010k)H~lbuOQY&&e52|zaB2choO%(`NleLl z3^=ZwV@sUQ7MyNuF#XzJwMzi(yLf(4#@rH(Q`MWRB$U2^gkHojr&TaQa(2BpuXPN@tOXlY^Gz;~d=(>qdoFMKdNp@44q^f5W%8VS7=X>z6+ z&Qju-%&8})0jfQ&jgtgt1LN#@9fvQ!?HhT@y}^+CVQla!#(g*LrOdr-+&AKJxNpY2 zE5^A6@X(A0F0r}~kjdf0 z8f+>@>(_|gsk{dmx4xKO66haRji3tg1Hg=wbGJrH)~hu;6DwjmPTx4Om@D?zT~`^q z-Zlzgx0{DekGUS3Sz??s%anqIEWrF0oq6NLL|Eysr37f!TK)sz0h#wx;$1f$Si?Kb z2Hzhx{7E(E)V5jv?H{+tjyoSlwDq!H9_Katm0>MmAI#QEPt*Tg10;iRXDsC8aAq?DKiS)wUa0Hp~SDTHyAdvpS6oj}v$3?E+Fcw9lM z|58T;Y^%s#tj~4s6JR}(?}xUL?zkmtMC4pJT$ph|;?y$J42L8hCTE(R4{**r@jZ8r zD|lo^Q`a;pY0MY`jYQDg5(lOBV;V~~3c<#W%@COvW+r~8kPuZby2tH^GKG{hi+p~^ zoP#)?Cun`Iyxy5$?3FRajM`oEYJ$UTJTm9ZX$4Vd+1W^mJ$JSu|C*qB$rduT8lp8$ zb*r5HV;IrXsG}D#i#1Z0qc}$-f!KpMG_lNQ9e&uHKNI!6CGbsy|BK8&%>({vhCfK@ za&5(Gk{Nqh#NPd^^S^JI*HYq@?CiU-Z{C9KRZm{O9z;GlLUY0?#)(U?^u!V;LDW4l zI6*yt<7}KH^>YS@xb;}lp(PGz_$iFPj!cXGN3Zzr$vhUzl#CzB&R@g%S4?%n|24y} zyYYXfPOM;J@Md=2G>PZG8Rpb)qMz7ZP7MA8_+vA^=g#*`_v5z>&T?kT@aFtEj{ni9 zzIokql4!20gMZ~$eXAbuFPQO{9R9MwzYM&B&cp9w{3gb4H6#A#U;c4By7DuA+lR9w zb_cMR8V=}@EG)B^;V+o+H_7}1s~F+Dg-ixsF=yLv5H2y9104e=Q9nHjg4>Ckt_RPY zq$GjqEaL4+v*d)t>1M<6lMuSU^mX6dn{Y2D?g6j5^M)mU(BPjn_{@A zBKuok`nr#H_PM_%uzi(D#AmrIu5t*xi+6^6>*jn{8AN>Lw|$r&@)z9s%NT#joxfr- zb*+Klb>p{iekVKs_?Q0;`_uBifA=5yKS;*LFMiSf`inXqH^nb}!^dX>?p-BD?(lhs zA26-EUPo)M)oWkl-~tihB%C4{*sl@wiS^MUdLD*Erz%qoyB|wJgwWyp zk%N8!e9NEEyy+QC+F#}B+;8C;V>c{BwjBP%jXy}4-*aI;PLkH#5?T{ZW#642Fo|9N z0IPMc4{*MP@$LBkTLyn>iEri1xBu=>*rV(A??uPI{}27ox$`9w|BlOK?GF?D56zPQ zW^8R3#qIG8-ea{nDFX=7U zy63ZzvwRB&oJqp~03ZNKL_t*J|IN-HB;&!_R-G2%MHkMam?%}i*oC#+Yt*ATz&P;C zRx-9tLReeT>+bjWJr#_qw>zH z_4?_f$ZfB!TbDeKq8};o)2r7WFETVIXTr!jL=u--rWK7#z-(@+t1eB~1zDmnGczt? z-mQ}}Y``q7)nsI5e2D|#tKzbHOzXT6#(m3-vP{SZbmmZ(506J3TKn>{=0|sNMZ|s5 zo%J#wf7t8s+k9ULtXdC~;*hM2P9MW-(?ev{5;??83lE?+-TzJW5sG>Bg-Osn$J*)K zHBV?f(D-}m9d7^tOEkI0lklgBGT%6r8=Fb@_6{0{HVvxmj7@xFGg>^V%n4Iqm@-vh zz6P;BgInW{9&=oP);uzfOC590!aH-N8sYGlX3Qf`J9n8)o|!T8MwnQac{@nFYXf0o zwoF)=Jva7O<}Bmbop*8GG2{CVe+;~1#`m)GJ#TpDmw%G?N`3dMU-k6fkFw_#drf9k z@IeOS(%WjZ4Vsr~wo+o0#j)CG1;e!eyXE+~vuUMgVN~99*gUJ)DX)uqcBuJaa(qx>tKq8AXjD=~vIm_M(pI#tr z*9n=OlXERk_ zXsp?T(4Dx>p!4dOx@yIzNRaRX$VtNAbsVd*md3R97@IN7E_1Z_zN>S0&3ieH|CRVS zcP>mq;Kvw8WFBEWaCrZc$%Sz^s3n^AcfZKtb-lWu`!zpk#_U`ycx^o5Gc0*48?Tx3 z87kf&%;w4!7txDN~p#>k6ObyaBk6y&T#CB2L@9sJ?6|gl?1Udh9Q#bD+11| zSRV*ZO*}Wiy1c&#yXx?EMimkJYx72#U#>G^eX`JcPW^A?KNoavZ=4TvNnHH)F_`?hViGcW2V200BUPk(FvlK+-#mg zAd<{EN#?l(ud)@ct+}XbW*6IByino35CmQ(wzIJvg15q=>K@*hvRa28OBSX+ zonc!U!zz;jdU9iAx-)Jos9d6m^j;EH&Z;e(l$MJs7GWHPAP^Z`3$b}TW;nTaKK9d<1<$$^&+Jn95tQ70}#gPq_6--NM0 zM;Nb#m3331L8d09j*$!oS!q^zt!P?!`!S` z6mJvC$7*D<<2lFtX@T$Z=y5;pQ*__WOkBmI46~#;;t;J#rzYL2nF~WC10>aWXYO1i znM9oXg7cAcvMwV0H@@M!;{lUu$;1cjcxIo(PPsP>UUTQZRqUH{;F$wU?7GZ=B-9?} zvRCfJ5SdhdI!O0<-d}a-v6LpfwQ;R#t+3`|8aQ4k) zDAVH4i%|&>W+j_(!25GgxlV|Ai8yCB87|!>vUgmshR%#3qh6^&U6N(Mm*}OaYkDnpGB|{`R@VQSPwPE8kxmCk10(bSBGl%^OT_!k}Ci#gGYBjU$UG z)8h=8V&5;BGTp|IDLY%K(+Ayh*zDCyLHEJa^Ln)QZY;2JNtlPyPX*171vBMz^&I0_ zjZ3<@s-2V8uBS7j)kZpt=bg;Vgm=rxd})kvW-yMeZGe=WoSe!N7CEO`F^dn=7c!Hm zZ*L*rcWe1#)u`4-28Yg6!m z$yB$^jf^gE9?dHbKW+TqySR(Hc(HNU*1e0nxQn~^ghbyRxyl^$7vN>_eWS>Lgp+pT zwOgbR9Z<1pga}8EYZ3rz7^V)Sh(9e@`gUKIqd6`RoV8$+C2B-3NNPm5bCx6)d7AZ@ zgl^TKIQv*MuQ~}T*#xWUVRGvvGG4Kv-K0s*nXV3SP zI~LK`Y)&1d4~avFK({afjC1@xGrec&nQ1inYlB%d8Y?%Fi4-8fldjK?tzt#8D$-0Wa?20NJS-bdAXZqyTu<`~Jp)(V}9K=WM4T zV>0_aK-P}I*gcF1MUdai0&h=<2AIP^fHk)RWL&`HkBb@+V$WSd`9}`(04PpPq^F}E zz_tM7PqI_T8fED+Vi546=Cm18k7pd-nFd~tb@7C<7A^t`z^h~?UNN!EYi`^#0rAG3 z7~|}O7~XaBNTFB2O(2UPLIn9?>dsNJ5U+)Y*?2Drv|j}Jk_;jRD4f&WtQc zD8@6JCV+Sm5iRB#79tHFwwOy1AHV##Kq&$ShRD6agHyXxUhy9#xNP@7_*$C?ss_yI&+Ey5MA!%2>>>F3;h|$ym*>nqU|}`o+lY7H|WY zv2;2K#*BH0qIpf|1QiQ1Z87P%XcS@Zt@2ZllZ$9J0hp~3yCE#RTR_J_qB+b?3YrAq z>L9y-(8QdW)P&ecWtl+^B3_6LE#g9XYq2M6;K1NjbJEio7udW=ZJXsHX4$;nlH~OY zzE)c@(lOBYnV}E^2olO=1q%uxzA*>4HF3_=$$?`H{Vruc-X1;ft$eqDcWZri|;0~U`_y8wG zuBTWFvfGo`PALd#nVszYp|>S&4JvjdCS>M~b=S&i2E&5ol#afZ`ed9gjvo8t`Mpbq zbO809nbfiUe}O{qvm*jV21f|b_Zxj+dEbEI=$=b&ed+Jhx$E2XdKLtEBy$w7ysb>O zo(XF)#3^81==weH6j9`7eo5Er0q?tu(DM5^+0WSoUN=Hm*^M$^6TA+*R>AA@F|VE_ z;{9HWQva6PchE4ZE3T1wQkfs9;3aKO45KWy;*5>G_Ge9MeIGN!~bzJ6SUY$DtorY6iIB=*fsdNzS= zi3y3r(hroFYrw2(7*nx8T?DY2Wy9fQ}Cc%?CJn|LdUH}jA;>nU#x7kFiH#@65XNjtMwbDpp+u|J%W z^FGeWy6F({8f9Pb@VxdYQP^x{3vcf@Q3i4^mUA{B7RHa>x0Mm?Rz1mofd!bpXkQ0=9Utl`od4x zuO0vQpZ>Demf#QO#D665$z=S&$nBeCyphFg30_0olCM>(B-T)CWVZ@oN_ckvWjE@6 zHSdJRx$s|4?&v(mnZX&)Rc){Y>B;y-fJN!FfbjJDI<~V|D=I8K- z1vl+%fv?tB;>_C3uaQq7{y4_Vz+amgKYtmr%5%S{n;P;&7Ec;HmEmzS-jDIPGVe3v z3E)Y**6hbNE>!nc9Gf@g*V`MFcype4Z7}AopZ_u5y6Cz3*ANcA!n=YH&vB#hILS1n%TaPKnhJD*1lkqrfwC0vO*x zd=ukaz&DlnR&My#Gr!Gu?$A=zcKjl zhzs$)n8k|;UMKNd$-8&&@a+dFO7@q2RUb^^&j8N?e*pLn@PAgu-~G8y*}uEgbA4HV zJSDyY{GDI;wEfl7?o;wB%X~tKk0Cw|{1AQ~d0w0NI^ydUeEt3ZjDOo-|333Yjc%;7 z(bR0rhCDN>`M^B$Of}&9%=nNpPg=!#c5%ufnM!W#^-f+(l8b-N1c%Ak&Tt#!O~h+5 zUXgg!GT*7h?;RL#l)n96{3p6G5|1nMn8D+CZ{cw>ei-o|03VX$Df4-Avbd(E<|ee; zGWHT|lG(~)6Js~#6Bw-FqLGW{B4Y#8;#sbl7|2DM7t8{8aW7%fLyF8h@St~F*BUui z7V|zuLa`pcli~fqCgz7zxoFK{Hm2q#1O_bPy`g1gR6fHAZf z!BNbLE;~!URP+SST%6kX$hoP-n^tYd)BCZPG1ZmC+`>Fb-j6v{m^I)gVmZNXPBdmn z4NV9^WsGbtXt*Gs8y9hxA_6mz8_o>qaK)#aGCWG*Vli%NVvbu$nO#-vSY|tmTb0+R zZ`+XD%(<1tTUz7I@Ip053&Xo*+Tp( z)+!k&m-%HeTJU!KABOb3a3N=pn!-Wp&36@;r1)J}2p|gO5T1gg7?UFyEZ9yiiggrs z(wh^@*sUBxv_ivyMyxhsDK(g7Rw`qmfu$x4K9h5OmIZ?pm{@raKFPU0V`T<-kEOyG z10yrW+1E0kb(kBuilYVx4=nr~s^cVXh#VqJAZC&MOyf8R*ozvd&rNZoKrypKjnA~C z%wB?Bt7vk=7J&s->aca@g1ZesuKf7qIeD=Ok*rh1C!hO8Ej5Y9sCWW+4CAJWn-Wi! zzk!>G_eZ^Z6bt3%;diX-0q-cYW3ZKt1Irv3?4-nA?&YkxhjqYv+~e*kk6|2*VS?)t zE4Z=c3gWt%V@rGY_3t-KOYv)TE`o=0QULHl<0sCG8e^~YMgr5fPbOzy56TL7C>R7b z!~|8svE>l^k7K#3n7d+r|195+D)XA$4f(A2I)t(Dy@Z>*t8Qr|d@o5*ua_*U^qgFhOy>4GdlVCUd`Xw_g94Hz=6*Ny3VzSOvms&uu@H0og*Z=!X1<4z{o1-aeO~>E1VeLqelSA7#9O( z!Aj(Q7d=<|A!u`vUEE~G&j+8;?8a+v#^>@qvNHhaFtcLI63Ss{Ar~?~z~{U>W;9J= zrwB*B6P&s--|OGj3IQLvF+_oJobJ%C`Q_SYr7MC_a@@y_dFTZP1{rQ{XLsdHqXD+aaVKf z74tCZvFMN0@^#701jog;24v0HUC7k;D&l)Daa?QYIJYucXa~u4h+2)I-tE1< z&ow+xJ6E9Dyf?Rt@4rp--)3>U-R8$e%JVILgh;Y_|G9 ziOtsC@5tevuni49r}Vyl@$N{OEBOOXh~E%eXlC ziaJ61g#0yRT#vnGoeS=z*6}*#aYK#gOASZ+8UycmUVyvddQcO@PMkyg_;H_N>`Lq< zKc}|oIM|y-Y+DuE<|Y{XR36Gnj4$N;G^V&67!VU%Q<)o@tqbuik#VF$h_>YPkfE-hmOa1MB=pB z!wG#sU%yr=?~5)fu|{UeT$^S=V#U;Q*2iWn$uZX>3w=R+MmDl@417+D-ab+EUK;t? zUgk25x#6$RpnPo^3&$nk8bC|YPb+No<;Z0f*#G-A+Bq-!H4gC}y1)HBZujoo_HE;D z7tJq!_xOWlU1^`H*T3bMNkqSgt79e=DYHiv209H{qwe+dl!HZeum4Vq?U(fkU_N9c zS6I$e17D9QW;*_%dio1JT?Q#~9y(KzlFtBG>iU!tYlva;8fRU;Ck+Xs5_1#jVq&qR z`=9U5AuQWEKD*&{x5Yf7vBJIey{(<=o`tQsaJVkQVen)2@pGZUHLDuv&Kr5%QVcAM znNlsUy$6KZcX?j(9>G8{dr6+FXTdmdT!Unc$Ql`}d(4lT-KYW7?u+uRbq_yo#&1*ZA2lYrH*TWdQ3o zW8G4i>ACsjwU*=TMpA3$x!8)i+2k6X!Npm+6J`H8%iv;%FuK4s5OylZ-)<|j{k>!k zc@Hw=ZYnV_cl#b7HjLimyr>=E!!s9SzFesNKQ2JzIsV8??uzDwo*Hjz%o5BpOw9#* z4snr#i5U|z`y>u5yOX$LAakUUzDp5(C6Ia*S8)|raTQl_u{g^->?~oV9JiaXD7e-( z;uF_#@w!EPkb9BbWR3$Z%HVE7a>6ghVGF1fSqU>I8eyW66JG|193+?#4ssX;800Kr z-HXQ2K>(aO*gtis-y6K0Hq`GA1~kA@%_sngLm4aX-@zDIHm86t$wAJ8%EiVouN#CSyOj(C#c5dsyW7 zZgep#VB1>kRTWi+!64J9Vwp@5$P#Of7$rYfhZdk!iBS-i*Kn}FnrOj;P9AaK$p9`q zq%YU-9%628#!(yWw4h))m?T6*Yh2jU2cIE+nP4YFZHX;1^E_m)7zLgtK=<7o&pxjW zo3Tp6Diy2d<{8&Wtl~hRRTZpyeBL-#eD@U|kH7|a>M)B)tpKoM;`8z3SY8HXlz z!~Ag%2Z7%SveH%(d-CJGZGHWoN$E@4gpbKzR=H;obuvsg$j>g`}o-?Iiv3@x)5gxkLOYBAb44;a~s z3qZTCD98c>y7rP!S;7IWw?q59&vDr7=IyF2qy?N=Kq#uaalMM+(_-tKe>(v%>;1!AV(<9P$<2LFh(aIBt-Gf=!>px{ ze@?t^U);L9<}q>oreR{E&X^@NXgEIt+~chM;%C3Cah+Le1}xMA77K_HvDBK3WrhW$ zrXn&PrX&*AtcZwpOiaB2iYso16 zxac`_-yyLR--i+Z1u1-LfQh6OVn>SIxZ8t|2-H^7Ud$*T0!!>|1B3<3u2tH#>8Nf#hnneyerW`uxTBseO2(s z4E{83qVR7FzQmNj->mV<;y#NrW33r78aTLoNyZIjJ_02Ebsd2IEvX~L>H;_8+c(299LTVNs2cC1EXn)-V-l-Y$R{o$vTnv& z5K=}sDLL_o%}Y*%lYBBR(sd}`$0sHZvWq!w8r+t+EqE(cylyqGG3J$Km+zb=kkJ|~ zoo_@?_J^As7g%r+zT0NJDmPwgiTM3}qB1rwV!ZU+uj=kw< z6M*imU&lqD7qao^fj=j)Q%qVmH*Bco?FLzs~rWL~~sLe1x&*WlGDKPclzB|Zs!68JF3&dUnE{v|!2goGU;fu+E_Q(Nn28%%+%WG~uOwqtVi~baVkET!1ecmy6J}qbJ=xY8 zA<$Mt8_OR0Xs_4(h`h@bg1j!~Pz?^aA;7)e)iaROuI`Fn!TzAi4 zr)ij^G5a-aFHD#`NE5}M`6XSO5BbO$CKylC^?Z*A*;_G@O1wB}_??TcOF#Q%jSmyw zFY$vUKAOcx4SpYPpivBgroit2-;(&2C4L9vo4Mv&f9EId?FaSQA7p&yi&|V=6X zb3^9+2ZQzOqB>7tJQ4l#bzn`#vNDyW~2a!{_Mnc2!`R z>z;Q1ZNweHEpwBAO?qo{i0R$Q4Vw~o2FB*JVzY1V^|`O;zXtv{jKA~?pR)g>-2PX- zqK{|zQ;46!_@lVkQUrSsRG8R8Y9pTsfqy1@o7-%TX#XMRc7 zrUQN|%=LZ@*p&Fcfxq{KPxD*%C8YB!`qO6o1H|Wl;ZNHCc#+3E_m8z+*Zi<~Zv6?o zHuzzDzug1A348%Oq}+ zSx;iAaS7x-9c7|XaoO$vcU#Bz4=v&-e6C+}ad6Ywxi4nl-I#BOSgDVbRo6HDwz z{%CZ9l8?zTy~4krZT#G*%-D!t4f6Hl1&M#lfUjA@zZ%v2&SV*tYyPvpruUKgn8C*- z|B3Mj=)@M^23`VIFn)-Jf1rwAGk^UB^Y#0NxzWLb+?Z({7)NfnE*B75;T+Qx{0$dF z3Kvg48IFl`d~(?j8*^+~V`3I_h{ag1ORYDe2yFInqLxVN3@zT1;Z0q#QgnHMlqwsA3=85Gz z^53oLW_h_Y8loz~b-3UcsTBz?*eNW`n&Ksf>V&=u4hhr=hsA7dJsxXP7!CMY+BY3| zkhqf>j*ajhR%RArc0-KHTvTgl&RZDKUnhO_o+-Z{=liFHn~)8Af4iuh=O_y%mPqkl9ZPL-T@TE~ ztgE=c=Lp_EHgl2oBsct^oq^}LM&HA^-&MRj5p}3zn4(A2=H9|GU?m&!b8Q~ynwbmW z(>}JVbrNa~V=i6C$9pP*t4*oR&6s5uZJy!W&3%Kd+>LZdodOi7_!3G#;2pR5UtF}8@1=O=Q>Aou6}rJRHIga*n2U7=Q7XzON{`2jY=KXv-BA5B?_luAMarl zOboz|`T0G?IIx}(oOMF4?fn%7a6N67xx`))b@cwTMr`+Mjz>wK;`kz+5I_rezGjG@koE&N#R;yA)xh2f;!u*z>YHp%Q-Vz+MCC9!J*wgwY+#ud94 zF(`eI@!T(JsWQg>Tr z|7C(}ElrfD&Fi?%oDmKzIN!NOdBAMoxb3!Pm9dz5Ie65zWnCK!))HZ&<^AActn;hp z{jkcM!@ZJR+hBnIU76Pml`Kpe--(c~_ZV5lw6VkBI+n2DLjr4_{Bs|{iIl`W@+XU@ zPF7}Yo`dz*rWV@6G=(}Zp8J}H)f-1^^_j7zafgo^G^d!L!FoR4GtjY~fw7T#-QcEStuj`! zF|@?MGNZtsmfrgSSju8Cb^Y_9iDffVc2m15CB}jQT}@Jzc}|-L7DM%SE8GxqE?=o+ zUW3f(^gZ?ngRFSOuJ!ph$2hMBJ2`iJOoJWl2tRYjIP!OE036YBZvcWj+2wj+URM4r z#Bo;7M$?cG1l>L4~oU}WV z3n-N)&1FKRJNBTOD(Ae=%)C)J!3PKjIN{>Ja)>b{W@H!iHDgB(^w^Fj%T9s=%k1X> zxU~Q_v7ZvNx@MNf?B_XovGHcY_p+1nRb0hYT*XyfML!;x0f(E0mBI8iE(WaYhS7;B zV#jbGXG&}cvy;sMYZ5aPqGCpN@e<6zrOMRFhc2VO&|(>=0~dAg23pbAdyTUV zJWg}-296KjfnkDq6JXcmppl^n5$wc>3>mC)B8FLN1vD!Yi@1yV$c)A8A|{LYFnigI zA(_P>NGt|0=2F7ga*~#h{{oCILh$0OEb=r;>VuBL&~pINJZ?E8w>c*mJH${~PWsv* zwP4j5eq4s}Sti+yVJZnro}ZQ+J1HTYjFT)=Q8{=AF~kXWIY6w#00UX%_d_$9c+CRh zDd5y9zRL@e6Wr!moj7w50WY8> zxp_k!!`w6L5KqnueW2eq%_z0dV5QZhCI;C)RU0IEW)VLby2&e@AjMgc?Z1>kWP2X+@i z%9bUh%%*uxxYYu|3Ya;JMg-H8nB;~*s;IMh9^VLQ&PWyYz*tdcV2QOJQQQdz=0?sT z3OT^V8;={5UE?S)>~1l~iAQrOc3vj|Rq9N7jz@zV3>^eOY!3&n>>xIiaa)Nkt9fIV zxHB?duN$^(z}8%Bzt@ET?j@dmUK`bvqyZZ_Qw_vgnFq8&0m*@V<@`1m6RU6|mdfBU zx!CVU^!``yb7Tnz1dgqMH!m4x%yV`^q}h>7EU=#USR2dDIdEeQCv!Owu^8_hnD3X8 z?ybHbbThTgVJ`iGV{sZ`@;>4ODE`#27RYw7I4N9k{@r`v(+fWT5mL(CBDuKT z`S-VD%yYLyu_iH(%mz*v`y zsXcZ~5csrQwaW=kiWI*lc-=a2;?3Cq-@K}a?ms^Nd8If1P;2Z!I~Oj0&seCct`Dbf zCJaDQ>;n3i78A}plOD+I}NDoL5bPr#n z%sO&!qhe}Iw+`bo;e@Y!lh_010W2Q_huKA+7NRyu1|wzWSgdcpE-ad8vVX?P05VI_ zryR8Fmy7yUTs9v(tC#6J<{Zxr4@peS_nAAT7A)ieE-vREJxw(V+ z>uqLZl3W;a;dt%KNm68g=5(El|oSUTmA^*U&+NohO*WiXDBx|FZt6j za5e)Tad90BVLQW(vMnTf#v2%K3f@AzX~r8iV$0_INEUw{@t*>_ z5?`t+{^sBQ3Hz7#`#to9#0@^K#K&+0jqj&3TAJfxpa(dH>Lz~f9w7cdjNiogt!BhO zy{w?{{l;g1MZa#wi@)$``z!bI_*0A(K7pHu7;fb7b%U=8{<&Z~iSMH?dhFuAPsG#B z5UQcVVqz&!v`=P zCj`*t0^W~vTu>$iTcf5t?Y$i0y|i2A0*H6;eg2kmn0$o5b(Pr6b2bl+&C3vTp8aJ# zSq=EZmiYw6kK)I0(O^%;3uOK+#& zXFbVD>}7kNT9~KE*h~%Es@MSzBrLhWy>e!SFuRa(!`yV>2EG+9PP^DaLJ z4^l&;#2|@L_V>6H=fJYO$FXiAh`@uPQv2yuE`71K8JCTpBm>buvV%#M2m>Ex+@wCK~bk|G9jRIaa!DKZzEnJ@e<-C!Aq5R$!cEuxu3FI_xoP%7RL=c zfRE$i@jpmcTWtaVo-pYUd?Ohz7jM7$>BZCvPM7q72V77M^IW{n$o zUeKR0WZX>SO^jD1-UMDT*fTeJn+m2?#ey21EIEL|Q*v{*v-bX};C6!TEb5d%4MxS1 z#0L$MeDB0{MB{%XJYwh4>nB%+RSdgc)3^@hgFPJ6oo6hCp z_%9fIUB}EdQf9MB+_uCp)%-{{e%#c)>E?$i_F+aF8m#4~`gZKtCrJzcr}&7ne0w3Zc0V9S->8 z3I3XVUh>ZkK8W!+u%2)M5b@AWBO7@iYnKqCRE|ELi;pZ|VP<&`&y5R8Oq6NNpJTy% zE_SjX@?d*P!o|%dxM|jF*6@2WzMYNR20K-zA+y^6X~0eqJ}aU^IkO(`c@@v+S8y{2 zpY8ct`515wubGy3*f>CA9(I$_bCFIXC+B|^zE&mwUWS%fH1CZK&5i0t@;=pqxp>d;p60>U)_QmQ z#AT0D5rzr@A3%^oi$1N#lX@1YkJpV;h9j|_SYqKN0OuNh0A#UcJrP8O;M&o*$By-c7qh4t9L2DV8uo17ipxI`JnUt} zQ~R@n3kaw7XM_t}L?pY5DaK*+Joe*w6|PG$2$UrTCUTfOn*rHEoG=XSEX3Qh3;MZ$ zyM-~A_nFC#PjI2ohiwe%Sc!S$Qf>m^x6dNCFnmw-?!Fr>^mB&F9IH{pN&Pd@ik1%I z%B?7$v0DR9kDj?Gc*1LjCwq4{v}v{4>ys-nWKhIF>et0ZtAMn8o{cGcZNI z-{tw=(NW=7p8j}6YFS9W*#%at_ znzNECMr1Zp5vzTt%q;wSpG2L!o88oKuFL_}9^YbMWGH$JFo^uxjTnrvd7iOG;Z~d- z`-B)Lh2sFbCKuyWh;I_&oR-2JCx%BG$Puf*JWoV=SW>4H=g+@7c$DH;2({p3@mg9hUcL#rQchkYl=MVIXU` zICW!1OdIOl&G(9l=^C9GPg{S*nz(YxjP1UnS1*;gc>Zzm7igJ4)@3aZI&&$wJpWyE zM&j1{x4UU4l;~k;djH4S?MKd)*97qd~j7qmHB`>qlP*}A_I><r;)K68^$$=@8EDX9H3y}KU6Ju!BH+p*=8AmOJSQqSe?w=4 z*Tl@CHqj_?fb$U>V5;Db*~vPx+lON910Z+juo<&j%&WvmnQTHDU=>u#2mZ<-)sB-Rb0jK_}MROTxXW%LpGX* z#j0X4i)*D$PsTP{r5^fWVeHz;Vl9-xA85_=|(hqOq!m`NEvN$ufG_H_`|4s0@`%3=^Ab&G;Q za==g$LFhEb<^~cD^vw4tB5-fXV@H%Q8o22Lfd?=GlQCa~ybkh=Y%(26cw*ApRYeH7kpQB=$)hl6X^M&oVPIyUl>N zQVO!mF<{rD0_Hew&~%zeJRKS4hQVWUz}7Ni!(bzZ?hE*uc;4FK8nK;Ve==ioh|xu8y{TAeB+6)vHhJt$Z}d{DZ{eOSZBbJatKr=mIBbet|HX$B2ug7!rRN) z1-F(cpXu&^bMV~j05>PviayLl#%2K9_N@C1I{|>(YKaH|WUJ(&IU2EDKrD~SI`=T* zv;R=5gE1>=Sk-`4Wj4%Mkpmi5bd72#nQ@|fn#XpqQtMM^b;4C5kFZHa3IM2w&3O9ZIU9GE&t z#s(evU;*FDR)WN|&c%DBn{=Sza{cdH7V-H3XzVS8`L z>>_3r&pxjO4%irsxMrDa%53DswInv=qP81RyKTf;aSg)6$A6xd+s*M@bsMo|##WA> z0chLC*fJMF*fz0MH*AeYZ12z6y4p|g9>sVDV7lM{rYf^0Q4z!$>r4+SOChu#K-f5+ zE9>9a1$!1OvnD5!I54(=>b>q8nIH4Z5L%9hgQorcIN4R8L{47M2nT^DFH))WaD>q^ zUN`2bk>*i)xPc3?-r!{JRtxSJ+$R1L+%Y#Iyd}9nuqAFMaoga| zICJN3{G?66#p9|sPKtIEGpysc_ep{M=o19{(V7cI^wuZvv5oh>yjzj6T7j z7gkPiy6*@ZBCuG=Hb6+?=WJALMh8m(?{Gl{285m*gjvF(SLx=> z_b!z7D1=mqs^|3_!&Er>mJjUnhA51SwF(7+*v0%p+)iPp$K`~DV#V$9wIKesbDOC1 z-j=a#@M`2SoAG|UcFXMMgp&742g%K3M%hW$Db5j*`MjWrR}`VBcU{Q$tcZSn5%!zm$7U)QJl@2( zlf^Bo_zszu2gchN2Tenh5{pgdCdEiY+$8asxwzO95|49Kw6p=608)|qzo9 z`Q>`pM0`VGzJz$u5--*xUiiCz!Vb@Q`n$%F8ja5IBD>+m`$F*Jr1?b{MgXsq!bDWv z@vPwWgUrhpJ@0<@%Np+wxG}1Eq8{?$X3qCl6(6fmb|iu9MdgH83+V z3!$(%2J(6PiX9j9Fs3<#hs^>n;(62pz6TfM;M1ZppGO>EylvvGY}~@QQ;E$CFJtUx zkrJ$#xOR%M);0OQ`#7hseTO)4ej2^wQKH4Po4LT_AwjZ_jzvXaVp3ul!i)u5^H9Tz zQF0NE_aey>XZE_Y+-$JM^8u3>oY9{_u#-IB9m;c<0dPm+Uz_n&CH^@LcZy-|7k-@A z@3tRaG)`MjWqhBBA4Yr_>-uVeVfvQ54t%Y@J`Cr)_#i|J{_?Nr^D_Pi!JqrWr|ti_ z-{&jw+*kE`a75}Vi_@$rwG{5yAzT?0AkM%=p_zmE9 z$7B9vpIH8xFKV=Uoexk)pDNa5Wq#0%k5c9~{{Ct+l%cZHS9uuMLMMdp??E)#NS1pT zvUlip@!8HiFbO*;vzJ5YxH6WrcntAG?|sy`k%L#Y=U<`dATqc&CCF zJ#G#fGt?)dW-c@OLGL}DdkmtVa^gNQ3!fn-N*tJ|QS^qrpEHbVV+ah*>yTwSGvlEk z+5HIYD+FIW*K^@IF~!_Oz_%P`29{koX@GxUtJaxoG|_uH{vPIX+}2E)Y}Sbr_xdko zO~3yLGX-T(3T}}xH-&+{e~071(G1IDF7e&XsVj-JEs<-=8-SYZ%K4gG1aD<58>S%Q@P_ z^*zP0YTL<8aCZc67`$nTI}&>r!K&SFjdPlD*Od{*_jY{diyE!0^F-C~eiBb$yiab5 z`IO)(6Hi*=DTycO)%U?0c^%`mevJ>jZpN!5UQh7a{Td0}Z#?&lTB@v@f6s?(6k*8Y zLU|=OX==u4$cl-lfa{3sh}D$5mxT*ruE7#}LTHIkfYfnP41Pm?S3O$7+LF zE_v25F-QP)__}@!Q2U-!yr7GEhG;z*3p0;*$}Hr8MeMCuVH)^KekA`lp92b94L2Hf zT?Qah+Svc@lHDWwgBisd z#gzOzk&FMiQRTgTH)SSP=9S>*buM%0$ZLyG_XN?HV^bTFo0rDp4&}Mdp=FxvIo=HK z(;vo*O%V%~Fo`-juJ$OtSyU!ga$?=YQs7i78RHOhu5gj*0iO3P1+JqQbR>Dtql$bv z;Uf2T*JD-8(B!{aoRjbIx%=7CnZfyqT+Y4Ib1>n@bgnSHGtV#fmDo4O^UiT&uU!&T z8YY(5S6`@=RtVBXxIItr&H>}Va_{fVK^}B}Tf1SRo?=8>GIaE`5-+7XKy_}e_jd4I`D&sb=uf!hNaRwoD{1!l6 zGfQI^PaV`us@l)v?UT4px(K)R1Yb#RzO-+N84Zn`tKdci ziCOaceT1K93AyG>7#56hzTd_L-@{bKb`m>s%-;;>5*=jUb7z*>lTjx*4>P6U)jFPg zF7E@ni2_GO&RdLpUnJPCg>^U~W?rEX2(}}9mj`8NH^uV?f`>DYt!Zk6X{mqaVeBg@ z-Y>D==a})-=DjkD_lDFOU5yNsqo-q+?d^z0o^aKk?xGN^c7u$9Zp-Ja9rqD!U(559 zCVE^%4%p!5oaZbBzvXile^)WvYSUU#^*GPO`u*;uJZ^Z_#Cvb>_4P3NFLN{YBqs7X z*W6$$`hK%)9GKWjVJu;Riv`aYOg$66bkvx_dIo#eGXsL7Yq2de|6UZg{j1MwMf(h! z0Sonj#eU7*nlE@?druFK6 zurfZEHNyDIoKuprn1<;11Y9#9J2q@NtynP?OG3*L z9Lb_%SqSn#A%W0Arxi1?kwy@}Kwk1dBoE0;0vHKmp*0x^0tA#_3>kzd$zbHPg4k|G ziqvFF>gG(|fw%6h`P7;AxAL&oxA#7$s_w12yd(Q8pirkyonfDSzWsgQTI)YZPJm)> zGst^L6UNcsP&_X#)$z;qp3UdRkqI4h@}!FAm2TQCq3PgrxX;N(Hz`P(z(<`lhB&Wq zEO`vnqVszih7?F;RIwj*^?jVDb={1y!L|y?!l=a5e`{iof>Aan&Sn$$V~^J4#Q|8G z_OPhe;Z`}xO%dpp4a1XZ&PjFMMoe=~%y}YpuR&Qf-;WglrYsiD6P0+qMX`zJFEOc= zv8;Km@%qnVif=o{*qs~mz5u4`y(a&4>-xa$hR_e*9{}q6{rtZXwIQM5JtALc5@VAv z+wrlypH1#!?C!jNoTJJ0|DhhvoX_&O?b+OgqptI#;;J_$sk<^^) ztzkSOHNUdrDp?q9iO{mTzUjQ;E`KwHt)ELNNrDG=P<9a^NgdvW*Tgy8NPoZ?oj#R|b190CNF7D}+<4HSwOx5vHr zegE?7s4KGy7JcWt_}7B%c)!&I)2aTk{HOz1Q^*3)Vmb8WFBJ9N+zSB{+(or(;f5SXn+x` zG{;B$`P*#&a|=C5e?vlanwE8undlgXgh*ycOf&bah#gCG@6a&E8|(>%?H{X~-O-Sk z_nQB*C@I}CWE?8IlB731*X-nXKM0rBaT(fP-N~2G-_}GMkO8qWDh0vRr z3C)WqrtCdqK6)j-IDbta7BDgehp?#Mk7SQ<-A;c}D6xs7<}}YMud!qc0lUB-LT67o z;3*9kFymVSJ9;zGLhB3ie&upw~EMmveKRALrT)6AX zLdFc}6Otb^L$&RYVE?6w8id@nCifIRV*FbGBt#o|%aGK{2Gde2xiT4O$6T5OAAV1W zR{UgSX@6WO!&*_;d(2InG>W9^@bDHw&nGGHEZST+Kd%g2s01#^dc*u3U<_oewl=m5 zFxj(_TRU*rro!j~^j$JB#WxNLq0hW!y&qr&l;;dO9jv@+e>B4?xJ*W?$!gqCx%3c8 zTEr{YmhSQVnpymMDjt={JLrA>JtejJ;1~Ii(LeT*@e{f?;6-s#)!uH6|?1&BaZmDUDH3GYTp;s*E? z(Dl(bjJ#R{6iID_g_)^{2DAXL4$J?ktPG%BKO5L*B@Y6>#gDf?~r zh5&_W2X-7T(XO&+=A>99yrP$aS+FIsH1`lb2+g}QDK!2Z*-B`nhjUZ$ISNS-ZnPS; z>>`F5sUJS3;jB7(&^g??Vr1GW5&U#z^{uK$%CO6QA+wp4r4AX#<55Y3NwxHW=`7u? z2?GEA+;o@$3K`w<(F5BvAyrMq%>!`|p8Y<8_Nw6pK>O~(Vtzy66>IOKwtGjF4~H=g zXIhOQ9SC6(-H|P>5AB%A>~E$3v2$&8D33HVq@c%l+4?Xw_WcQ)FwbV5(d4+iiM203 zm>LcFM$Y6C)m7+R$)Ep^TG1{{v?zOSp)9jtmzqQ_SI$8=z={Ba$p~O1Ay3#iYue3& zkPz0b=4gI{(gyqkVaSrZ{w&cOTAjG<&jfxXvQG)7$%5mH;k>=+Y+o4F>}l4qqM|%- zjNH9jMj1g2En+bXw)RXUPf1G`$DqyJUz}q zk8&)HpjeU3v>dw1RR>I%WYab>e9e239&D9JLg>q&ibhOe8%4U>cH5mKVjIQDf1Q*X zXM43>AjLBM55PNm8)*LF3Qr@GLUdr*C!aV*1NQqZ$NQV65kxqGmSj5+>;(MuoXr&L zAK!l!DMr}KqH+R&zaX04EU$A#KACO!48iWGFuxo-%_AH%qRMtFcJvJZ zgWLnmD$uc5EcFl>omwh+fL1Hn(6G_TZD?e2Yy0HUC@m|3R!WO+(Ij7L$g~7V=HwN5 zw@%`mmnP~;lc<*sz?HnlV$-%?B|OCMoP-ODf-W9U9SBdE zo`%*_l`@`L3K$Hzk<U0{zY9E3K5Y*UJHqPh?gdyM$zWpg$~e%OHI2f33ICwPl7|!@?6zzvA>+u!noFkaG!u$OS|2#dMuh6AKgbkCU%vFk>M` za$<$r;VGH6Ao3h-CjZn;zV!igtx`hP5IV7;Y1$16934q(57;q2 zPY&u4pW&F|J6qdaD~&0b-)0-Wb|wm=ymm#huDxY+yPnSC<)%# zeXt`Q=K9a3fHi={Lt28LT-wN-zqa`Ft#VIOjI~s6$=^K0eIu1Q>1JkjceM9l%r3?w zDB42zaqf`E^6l67vlOF-6{Frfu+xhYq2DH}t-sZ;1%i**yE(>23UNIT(>hw`9RkIX za(E@&c++ia&%d@x9CCr_#49T!LSz-$7fJ8~^v(vr%4?h{r|>?nR=|iM(%lO+XKVDa zIJwB()_kP#qboL*t@*d>;uzQ1W*a-v_ABV4Ssy!AyrmQ8CJ3HhE=lR{jLz=1?> z#!lTnOU$sC%#Ud{etYew2}t@buq_bd1RN}hJ68=y#r`x#~&8(@Pn>5M?Lg?uabI(~$cV z$4bCmPvu=?NZ*z?EJcf#ePGw&?*$;47cn++5Mkl1J&lPqsST%w1B`Um#IA)zdWA$E z%YPzMte(>ggU0Q?ZpnmAm1GZv^S}_1$1K}@Ja6xlr}L6iB#(5nf=UyPNj^^G{5hTI$p=9PNS6~@?*DJD1XshRs?|Ik-ZYozXIq=?jp2UN1rjT~T zpM8Cz4cmqLFZRgtWo99?g{N%@_Xd$2 zym&Bwvqb5L4HN!04e44?_e5zp+1Yoxf1|BQi1PK*+UJHx z-VRgdufNhvhm#u@@5gb|@FbH?g~v(80_4D-2}_1FKhlk*iS5pXVVe_QGY^nvr*WTV z;Lz1jVQcMF<`1rRYs20bE13Osjl?0VSN!C_vZrz4jjO9LzOnGSl?B49X2XKFRsJcK z`I-Mf2eE#kw9uXTJp4g96?xN=>|9InVl8~`cJ^qiq)Xz=bti#JkFYX+d+i~{)ld`@ zST;0tUiT|A-5~k%_W<5cjVLiFFM@!u9W450Gm*((T>+KP0qap#H zk>k=c0r9k9h1GYMl%?MZQ#v(vyuGu!Vbx*lQbfnMG*}vz4%XCbx$ISygI9&#P|I|{ z+{X93@1%6(@d6?+c5(lukeQh}L0x@3YKN#Xk-_J<>Zx3xugFgzC(X(1LfmPw6P*;S z=E)wBhnsnuX(1s=geZ)Cm_E^p#7-Y`i;{3GM$d-r#{Z2Rpys<6In7iM5xV3qEkkQV zrTpf-a2eOErjpsiZ9ba@>R7jt11~-f+3?g?GN?!{A0EpQYH-w*_t|YKdX>WHa2ym(C&*d@EFV_Kh_#O95i6$MMlL9?BCsru*tGCtV## zW2@bKQ)5uQ$Q#4+I`TsGJA(BJVi&5SD^tjZ_*l%fB)e)Y64tDHIrVkLJX#}VA&?y(@B1B-+yM7nSmqnXTu~5!+%yrJoweHoyy&LDe35AqP5q)dckKB0 zojc>Rr+)9W1Ji1#3%Hq>m0?R9nG-0*cU+Y$PDc~-_08qduBO(|u?A#D@VsZaVe)7M z^A5Kw4)I+LYKdLSyeoI;YCA_=C}hKEid|@e*sT#Qm2?wH&b1QlxwVULLvPL>`uCvd zot2O{(#ddi_RkL35Fb0~`f8GmeV6&W+y}Ob202;VPp^@94c8~2>$VPNxwkC18RIAp zFF!q}dh0mH)~Iv2L}Uije@~M#Fpjp8E!o{Nop)36r-RaOvF1F~+y&)SU*=hEm#nED zVe1DgEmlKz(VK+F9&}32+3=NyC4AqK%m^vfrW$=yP>)Fs2o>GFdArpy3|fPQ;iAnedyrSJO}_Dr$PU!DANVS#@YaYXVMC7g z-+bgq!TFc2JCsz}Il?+_`v+ls#Ke=ar(!9y%HGM}cbUFtQh-pN7mR-g>+TA4)5%*H zA->z_s?oQ(zAZUN<~<%ScUqW6A2UyL(TvbJ!h7f8WL5SpBqJ91k(TwjOp&r`_$MW$ zo8~{!aWn~t+RqB;8VxMMk;f~p)FWYY{X$f9D8{PITA@--w7!pbhMhi|OhW@jt}DWA zo_gicR0sF3<_O3U#yeM)roV%AUa5R+JyIFe1Qws7H{*K;sV^nw7 z06CF2Ve*C6rd@-944=*i8m726u!YnF!+(F^o%m#4{sYHAv`hXaZ%E-`u2s%k7w@Br#ix7PX7U9{s)nyRI8tSnKI=}7q*7{EN5CG634(q9gT`&C@&_qh!xU3k&H+G zVE9upf0qg3o}o%=X>Jt5+mRvq3n0nC{@4Chm%cz!oHd7@i0I2Q;{LrF>zu`r*e5j- zztgRQFhWr^UC}9;po7`?82qQ-^{JJ6)Gm+j_)dBbpbm1wJ?e`FHkKj5 z5!@oHY^?_IWoV$V(Wd@G#h>gv4Da__OFwCp3;ON(Cx78%4GYVy(#vj(52FRVk2EYc zPe(~vt>VXOteeLO*lh&VzPuePdpXr;<84;y*GIjN;h0%{W*vu)pn7+Yg8n(=5Ob-b zemX0wwS~PluT-6!xn7mbBt~vBCD?;35e05SKs>DtK>;NcgYTumZMG;3E*t$x(n{L* z%SVOZmH%Wx$;#T9QeIXgQilZ)$JHGD+(%j=hrWe{>rP?(BS8X=z3-8#^_wtr5NCZp zx^k{2TJ|e-fcxo93(Jz*I{yZG6=y+HHu^nH1r%_xwQknA61KehKLhjCVX%8_n4TXCgil)8gX(V` zP-LLD6$;OzsyW1@`Ne=GBvgJ!rO8nC!&pXbPY>)n!5EhnQQ^!OA|wd?KmwAB64r=h zRl$WJg}?0CFte|6TZRlLwcyo*vlaD`Lj-5*to60?kl%C3G3*)}*h`W8^BQlHCU z$Yj#bnQTJDXc&KcE3J73vCJ0$0y&i68m5rRTi1pV@$G=ZvQ$c@&(sbAPF zUnDq0S=zmo_X{v{o~J?X6SW_f(Y9ZsWy)R-L{;)evA#^~aDB^@ z5?PT>o!d(kAXeo5u4F7)Q6aYiWwE(Cf~yYjumu*`AP-zPc)7D&8{&rna!?$$rYnAF z*}!$Mj9h^BhP-O`9PiCZB?hD#dKH6GIOXMxKBqd4)8T4BSw9F{M$X;u4a%BQK$aVCdVs6-{n*pvH;3I(F>t_*uWP8}M!e>A z5`|3c%qJ^&U-1N{C-$?MxyPg7 zz`#83kjcFM$S!)KHpCp)2#(HMIx0S)@mLW)oqw64z%PcS7U$C@cq|s39MCX>Z5@xfqw~c75!NbD2EZ zYhkuehT9*;>D^3Q&nWggd|=pv8$6_I?|%lb~}+Vu%&Gm z0!Hv8lof`BNw-XdBtPUmE`2ZjB%73L^=&~}{_(jKt|$6vRs$o5ul;?(*P-h7M6f$Y zbGNo@b7x8Utz_)dG)Nn(C5fk5N`8k^7i=`PTkM(lv|oNV1AzxKOgDM*!YmaIK?2gC z=W|~FHDGg_-{o2t{5f)+Y%^SCd`0_V-CP3a&z0YlP`lrCi`n7t|Fm_3rPfoX_0D6R zA0_iQbahMK1<0kGW0EUM*d;oE1BI6NrU-VA<%}=31LC*wrHNA+_~gys;`M1u8pcFt zLqEaVFpPdKs*L--n7l?iF*=3ZwBt5{W7h9Sp1roae#$O{(!X@Ix?|;`?Tj5f6>Aty*>^RL~HUa3Vtgx(lwkEPeu%c{DmgMqiB9z2|)-m z&R==?Ei!K^(w+#PeD;6}-{23M%?dGkEEO{*tDAjBeL$9c-q)k_=oH$!zKdjU z&gh#z%jh0D_uRc&$hJUOOx9a_xszwqKufvk*;zcL&mP|Ac|y{!v+CA0$T4)B*t7X% zV&o115C&qtF5*z@&5N1YyohLl5-rqThwK{XWThp(H>g0F`$Dlg=1M=C$LQgLpIshP z#plQ%%;RkgKEZ%QH{M8{14UnpF=$ds3DvzQzMKMZ;%n@w>hDZ1CfU_u6lqwnt5H3C zYuv4^AlY~W zkHewbFPf@jbyL|Yz@btcAiZ^4)sCJfw}MPRo1JP~`~9fT2S-r#lg6Y0nbPV2MwJ_; zQ8Xf#lX=>(O!%6ZLcMU)S9gPHogZ2++|J>e?TYuo!8(~eG92o@Q3~1OMia+sS44|^pzh!*geCnUSb$Y#ye%@^Z-pzlN{h|E% z$S|jb+(+wBa`50)-Feuko??`4yj}P3;b&_b__X0@!1x~FQ8>ADCcz1U?KrN_$pdmg z8ehECl7o7OSBs~}x+^GH1%MvH3!>j#^_C&8PNd>=D)XMU?nZYn*M?ew^Pj=Bdk0c$ zT~?^Rc4@McnhED)uWFyP9tj8p93zsP)~@?RP9Zknf+sgXB{DBWsxTy^h1VeUPy6!Y zFEY8evSJ^7+N`IEZPjvzYWo=zqoO1P7A7T>&$lk}+|F9!5LCHP11Y$GrCp+cQ(GeZ zG}v3F5epeN9E|o>^_dV|T<2fp?IsiCuNWeT4`vQBo#j#=A*l0?c)<&;QJlwjp42Ca z_e#J@5mD%4J1QmnnxWi;Bu!@yvN zQ_DlJ?s_1w&p;_H&<)~5*w?6`@c4QaB|0M@^l!g89mnrgyx(s!!c`L)zzR#v93;XS z^5Pe!*OD?yuePTzu0Xo~1d`Q0{6UVR(E# z$bi$M`Z&26`=L2N`g;a)8^r6J;e@d3-H$I4gp=KYVrkCL-@pi5@oi>8!b8hoqaicG zNg|x36&5k=Eb!WFX3WIBrQ0?7;m6v-m>*?k{j(vZMjP-bcQ9HN)tyxRQK3&{s#@F3 zaSW<@&&ao=aNVKa3LXf;6Cl>gs9e_=+@;uiO&D_%RuF~nn=S+lgcM{=Q zXsXS3F1iVA+kMTDg(C;o?Q zaMN}NjOus(f1HEc@zf-hTNJa6t0ns*kusKzE{(!B%(Z*HswVFK1|PRcCKOh!Ya$zo z2xFee=ls$WG?O80vPr5do{ZYl)lG(FF;#3k>%2DsljRZ;t=uRL*&SbK+%JEj1QYy> z6(O*}b4aJI?BQ99Sbj+~trjpE^9v0=#j5w&URw!#WC#rUAG~oIO={8<#9p86{)Wen zh5Q)!Dd*+5x9DFvW08tz2sdSnJm0?mq_LneIPT_6Tf#*HV;AChq_Z=TpV)53Tb>`n zvDJTW4i&?)$hLJeAQ+%u6H(1G)p^|RV=xnwiFs~A<sUc--$<-iWmzAD5x*! zkZG7aOAKNH!4BChUJK zIb`KxMQjJM?x*DqYA47>DjcBJ$d+XhR^kuD1oT+w!a06o($-REcc9Y3X|@IA58-Pb zqetepA!1k0dc-NRTqR$oaA5?09I8DyiCT17g}}N?6y*hqK^8Bg1cmjPi1}!ZM6bs! z<)RIJF^!ayIQE#;5YD72DhqQ7`@Ed>6`x$CS~Gq@{APq-OW6_D#xPpH>)1Ifxj!L& z$7==5E6fNc*UKDKQ9Ti6)rdcO>F!%R_eLm{=bM4&ZI7vc8L-q5{d*xRu^3gXw0Ri{ zlo;r8@96Os5i!|B@6qt=A|pBEQx2Aj{t9EpmA|A-x_fT-AtF8C{ebq5}QY7T}SlEW&!&3}|-|0R;K6yca zw)g?wiOpkf|0#J!c>-A}Bxdfld9k3X`fF?FVPHaI5te3atPLX478XEjRNvTqED?v=v>C4HnReqOl$xe!KR67oP0vNrmry_#dy^A+nu0QN^`S9 zcKgUA{;F;4mN$b>()RB^yZOaa7rjpak@@pl-nO@OOme=ctFa~!doU3I36!BIHRR#> zG?vwGY|P%b;Kt))7eG>uRsFq~N@ zT(0WLn&$U8+-)%(JEd&9Om!47mKJm+UG{=wwjsR|)O$hdO@S}oh=@k>|Il9)o#A+% zC97%HEO(OAj%mQSV-A8euFLM3$TqGxo%<=6Is${gGm8k@g}-#C5k<$KFJ#bM_w+z( zrj|HkYyuqI6+qK}MLC>hLdsxrQ4YZES;b00La9ti64upFylt__Fz=H)l>2aouyrQcygt&==XF}ewO`GZ7%?{I}vZfkd@K|puUQKphwJm>;b%x6@8xTAwA$O-As(* z*WtncjV3UolgyGDL9jv0fd5g^_XV%-oBNwVcH%qd?c)a_GrHH3pT}EpO0xdL@2Xim zjl+&TDZ35&snVWgLav1EbN<7$ZyJap2sgpFX(&#_^^CkjwAIs2U&0Mffx+Avt;DmJ z(D0rRrce08FO;|wPF%D`K?6C7@kVH|*eb;K1Ij&`Ca*qBY)S)4C2+1_ilqvFd6l&(?zF1_rT1C`e~$PZ!Ka6qy6a!* zzar?>zGvRPyXy+Mex}ubKkt5*9}4Nd6L|vead}6xhEZgcc}y=pQQHiiQppT<`8O|| zs5dUF8C{DhTqkwtT&1D!%DMfP-$2(DWtUKyB_-z%e!Z#6>Z%gDfeAy?(&_}Cb>Uc& zZ*QaVUd3J&z!fDt9CK8$tMjQGq#0pMNYLLm$}fy^Eh1yT|60lpxhp< z){qq8aT^71PQ}*N4vhd(CucInU(nI*O?xEO7W`u&(y?1?Xlhy1PAYHY)Y(Y`O79_l z+S;K*7clh{3jU_s>zVk?Ai!+nu7cOI)RFG-$MF(pqO!U;-CZ9Z@Sc2X7 zo6-I2JdD;OuZ2r#1uUVDWRxi$47U5sv?ivh&l>h?_yeFg<{Hsov=KbGQNWoy2~A3W z{X7!53?3nx-VRQcy#Jim_R0-A#FqC<0D&DkG|t-qd{FK78txnC7IJ><_0VF7=#Irv zBHNu5usM?xZPi(mI4tQ3T6bp9**ve@ztq=Aol(PRbuP)hdf0yHxvp&vpWrL(z48S1 zRuzefslQ1B%5LZm91q5(@afD@NPI;zB9a!|uI;3VVi_5fjB4^Y`GRZJ-kIyIQfZRy z?=$L8hw1H17Aw@|LWWvbOWswo~4`&}N8h?nSddOBDCf_gmB*}U|dpzZCgOq;`> z=jn|;jihxCz@?95C02--_lVf=bt=o+{Y7c+)$#nzHN0*?YOg6rsXo8ikU4BLCY+sL z1x8l@l-(>BZ@1U|m>NiX_D5k)`x}LJ$_U+f-_R7Mw`s*xQ3H{Dh&FHutd4EurMvCg zFA_cRB18`x5%zl*>bF{O{wzD`THidC2l=~9R{73@{I{M(@>smj_Gh|hGkrIBKU@K} z_t1efE=kWO+71{?%q#9w9C!{kLi5k+Q0oJ?*l`WAWSfk)y3HOYw=tcwk*<=H2;qSJ z-iZ^Za-IyYctMvBVcS1fA|v;hPhoX&#FRImccrUh3)_`kqcSa$M(Xc6E5}p$!O0|p z{;{n`(@Di0sVQi=XB4E-yP&0(YCs2IQPgC9W7p&(7`JwfgT3fCChOp-?TExKcchh%bRy_Wy_5Gp@s{0PaJLpqO&0WCCW0-3KZ&=0@hpk< z2aj6xtTj2E5W$pfLuRbyyXmTsZAEgV;C(Z)2+Y;6MOqc0kUl3i54 ze7~4KHzaDQzdSsg-U9U3mNXLYKh=5WDFu(nM`p2MCb6;E0UDb{foop0eg8(D`OiDn z5bYQlk?q4HYR`K<86LV4Bz@my=M*V=2_boBxZW!LEim$&U7LBGOIi!v|AR^E63}*C z=vwrox1a490Hq8i&@fi3cNwtD3BWyODVjmVV{_SZvpO8b1eZ!WF_5*vgQmI~5<2Gj zCxuVE;E_=571pNbm0AI$p_UHrj!$5(!>;9p);<((Tb021`I5)qP3ccu^E}HsxnC<~ z*cS8KXueQQWFcBM0dT=D1tUISvzxLgWC}IuyV|REp0yxa# z9H=|ogQTY8s&{+B`8D3OZ~1b5(yj>7`iXeGsGa&&`1`E{h1jBSb*W8=7Wq_ADg}9B zCkI&|qq)wefY9{ZVl)QXZ`@w(Zc5h9(u5NMxB&-Lm=gFqKYWVqRW18c%%Aw?5^#%) z`4E(Te0V1$O+@l@N59SL1>wm2U+cdGGrtOLSKlpZ!b>{eZ5Ue%Q6PRI?&bbr+Zen> z+hyj~Y-~`*ZNjA?u+sqr_rUOp!l$|$y}+$a_>(VEI|+B2{D!8SKJqi=4uV{I2BFFs zSJiSXnI)&wEP9EIZ>$(>a)vJ~-XUz$0^Y&-?vgz=<5af^*H%dgx`AV4JhzVcKNq=3 zx)|{byMH<}yysb>^uHGu3MZw-pY(=fp=VpyVEea62oF>%e-x>f?4w2boWiPtWb6Q_fSV-+uo9s<9xv!1@&&;PiPG>+c4XQ8NkFnNTrFQ z@3Q^G+@EVG(o;BG!S*P*Pu&58FP6H`5^A_zwcZ{px92DsMuyuOM+hY2QZy!&Jr7Ie z7k$0QDi-3FJo7|~HRf`@OKR?Et$Kg^#y5;{R%}K>DU*64^~yq1YMm1PB$Vrxa6WQ5 z)fg{5ONPJ#AOpp|mX^pi552=9;{oayISa{%e%Q1fw0N$1bZP0$4s?^uraA^hV(RFl zxXRAzeeGusViOpf?6?Nh;B&*F87VRRexhC+K+7L_Psp5Al}TT8tL{yPYnRy=%q@&3zi&BeD6%ZQEXzXH`-_yrKiWFDdLMXu zxLw$t8y5t`2LF=$P;|f<&uZr*X?1?z1Pq@CjR!1?e=SAF(`SynT~c!f`|wzVeo6hI;!d+h#9|c(gl!lVwv{XtKeD)nOx> zU8uM2IhEqwSS|z^8wwf#7oq*)>+856zI@bJj zpnY@fX+JOBd(m%SL<|wR260NMP`!SSl*G(M^n8#kO>)ku!DAN7zyWX-WP-peAphgBAB?o=+JV(9X-fyS3<#dfo_vv8d5ybuVVQvOVM0_uh zZApx|jgFZtcWm?HYHXQEhf1$i?ag-7#X??(AVfj-)3ctCnLGBA2A2G!vFrzR+wWyu zNqLah2U{+Adav{CoO{3NS1xbcpUVu4zz###Avu&_76Sw|irPh=i$$U%zA%X_u#o3vk+|6_%W6FNNBf}&icY` z5>oN7XtjInk+z{f66UB}zh#tr8YCvB5`~jh8PL$XU-{=p!}a1TPS5(lV$l?~`Mu2U z)QpRD6kHqLDq~M!A1joob9~Dz5?My=31o6f?m*0Gp(dp|w^6V~&3;hZ!0_kf?otj2 zKO@25U+B}jFYsw;Vt8p&mfqjep2kT2PY=31aV7~9@(yJLI)IhxUOIKfZg@m9$p{4D zcpaU6JY!4t%4MgBxzKQ@vk?cBlgHNj)%%qsOQSOC!OsvQL|LcYJRXbq#8-p#3uh1b z_mb35@8cm?9*!prMuy}b7a!wB#|L;(a zEm>&~6mhfrzY(4PDnjI`G|QG%Of+cTOkq09*RK>KNd!0VX|`PVrw8h=-SGyvdacya7zx~sIw;n(T{ zFS(=ryMg>ev0G~0sGDWknNmPhDfwTc=+&#$6$4mV^rQJ)r~kVXG?(v>1Jnl;)Mh!{ zq%WSen`7DPqA(Y9!Y=NYsg@#~ddF%J1kJOPs?@EYFmL_|yj1Afj1ZF_d3GrQLz07- zEL_+Qi|xS`L;^~SQ?53mJEN7A;s5;Y&yn%Kr!A^RQ~$0(Jv_tYp(GZp#^*HH>x5aHk7tlH% zS#9#S9?j&}9Dj&10E;L8wkVR0;E_j6h_1sxJUsxwUL-}GAV$Wv$but)LmklUs>BKI z+39co^dTWa3||uC5^b@_>pTqyJ*~E89YrcECuOmKRal4WyD;6HaMf6b_gt&>Cyfsb z+?x}xfZ{5a`0W;@Mch=1uPoxDYVg4ANfC73g!X>I&X#B7Qwfopc1v?BS zAw3bKDhMdS^>Lw~pU1{y92|N;ZadbaYPj~M0xImYu9DGXJ1@Y!2 z`oD+C(c70%@3t^qUUF0XmNJvHK@?32C0&q#1|u?6b$+$8WNI!*w$C@QerR6t*I6xQ z3`e%P%-Zy-)SE?+v1o{DhrPICL_hKI$^}IH zKnyt&Uft!q=tUPd#x8V7Mkjvw#Uo0q(7)%zQ#~?H#8?cnon&*c0Jk8AGFtiz?1_}< z?39nJrr1g2#$NQfEFt(01=m}AwCQ&sX}cCHL)S!$8WjC*ZVvjCVE5=q&R}N0ECh?c z2!xI2wyHS`^Ph3qQ&}P1^wwr_ZrIB6vnK@nxw|${ug`B{^&swyYT|sEV@`G~U%zcj z#C3WnF6f_#plaW`;x*BLEt1*b)q&0YS|T-V+;W@di2Y10{K5$pf79*!7gylzBa>dx}|&S zHt(PsIs1ulgYeYXHWk2o9}{=S>lpl?Nq8?Cw$OrHuZ!A~!u!rwO~IRMad`1*!&92B zgJ?DTK*1X?y`5y(rmGM2POLkTsQy+Q%rB~hGjuf%m<`Sd3iWttlQKj>vS47W&2muA zJNvqFMwPfqMtjF^_C@3?of-uhmVF!LM5$k#oWLR_9wu3y*^x>Vk4U50V!;0HmGE(X zY$@kyv_4IXL6oiobp-}oewaY~{J)?%EZrLzf3>V2`}rYtO5lVR?ynd)1Mcg;K8iYJi#~TNRsx(d z1M79(K7Q*MJ<1ZkdT+UVMhT^2b1Un1Pn0qI{Um%X#1SwJzt8PYvkRfR79m-iz7thX zc_{QE+NOq4)Lh-qDM{`WxX#bgP6mNQC#M{LjO!4G76o)i-V_wY$ndO+{}#0Kdkdd# z-PBB$a@&XClM_=Ga?oZDny*T^J?o)WisX5mH~Awod+G z0l_`AMQ!vGPbt*QS{h&Wyda>q#D;LKLwS4bo`-_Xt`gSU0a#>-IW|i^&PjY~1e|%8 z?!X%^o%kL~8d68@6R>CGFS4$L%>bSSXP9uR7u~0Id?yRZeZ#A_Z+7AEKpu(GkZ_=3 z3?9;v>ABfd-;(6be#>K<6LElv7=H1mF}cYG9@pPyZ_byUA_$Zsb(?&(1YPgBv(x0? zm)r!++jSA^edAwY0+S!*p02LnIkii>bZvA{^F%$q&RW-}+a|UtlO5#l-w<@?mAc?r zdrMGqk{doUT{$!?=W>o0nG9WY?saTw@&-vApqJ8{!>)(GT#V)eP)^uLl~)z}jqwcV zqSAF`qS5RiI`i|{RsM#ANJ+}^1;xI^Mst6m4d=y6n3>@T(plzCb^AA>;X-$e>36zv z>qb5EG-VOVh3n+KY4FhM#;zo9xs1geXJikd7VU7 zd~)&eV28nBOIGPV9IP!y111asau4r}g*P53bU#KDUr1MO41SNedifG6s2NluI>W!I zj8QUtrMTfc{EffY?u7NEn5_F|s*fdCW=c8i&y`yn_YJzF%S%3Y@*^gpHZZLI_yQOG z_v&s1K>4n}2cu&*k-mKqXJ9}n`DXb?^LG+y2Jnxcg+^;rctnBs{(XU=BAOQkJ(42u zALVbg>f1Il>?IZ5hyD%DpI@PD+Yzm)dTC1e8)KCaZkMaF1UWM+jVesr_J?6FS2Dlm z^qCrNUL=~(mK;9tCz1k=n9(X0#^j#Nr_Yf z+vT_oX2@^;dy+%DW5yAJM{b4hqtcXnS~k%PJ_pr_?;u;$gyQu0`(vGzkbyyZBbsgV zd*vRh*72al@oPrU*khlVQx#$c7IIXYyeqDj*%}mgA#%pyzByiMxIEnTkcjowwS*;( zZi-a&vzW^Ye4OCLa+XRHTP*N*GS^KE)bO880?zYTi)}@8Z4%v=nq2){jXUh{53qy2 z8`vLw1})0I`?r@?s87WdPa9&77B_U~4<-rD!n@aNY5~m28=RaD)^4yS`s7mOr}`#B zfG)ZA8xqi%OHm^W5%MgA+Ag4z7C1pj4mnP?V~PiAeza}XAY>kLdbo3*md6=Ma@z)M zrHp3z4;|Rb#GD#!LDmNaawh^B<_SVm`3odiCF#C>p$WMSnNd`F0HrGIu`KF~@pR*M z8}*wN1h|@?czhmg`?I=v+~=YGAT7h$M)5~`tEZk8PM3cc$K3nV@NvV)GF@AG7_x>K zRWj5&qwdvy%7pFWmkek=yPG$mcH4Pru1dPf$MC3!#PEMsvq>b26ltkm1SZI;!+Y*R zxgcSpr+@Ku(=clk%DSjUmn7Z)l@Yi3bO$S7pY3#NY2O2vE^9c>+T3*u2{I-bBFMmc z?u%f+Tiq4rkN;S1{MaD{u~TMM?m^X zS%ZFT^=BsksX3mwQtvAXV*RH8U7)bzsk)MRaHpUStbg_HKjO?(c^}}j+|&S%#?@rX zin-3y$&wF6FEQggAuH4It1S*LN8k#<+{2qGq_Q;G+1>3u2MHrsz34|#InmqeEAb)D z@2l=lD){A?f^qbCl~? z42?h#8rIle;*UW9HZ?|$FMXm7E^Sk1h8hLqQkBb3bT!fH*iQB~Xy9ZB^-9qP2b4|> zpW)d5N7Y+}Me&D!!!(kTvb1z}O9@D~NJ=juA+^#e(kvh#ok~kCAt|{mwSWlHveyRdiZOvNhz(#5(+gDPP^a5f$usdZc1PgKM~)O zKax~%W^`Iy8pS{^JC~{LG~+L9g&4c_W6FmHk*CT_wESuXs9Rds?Sx#4u%e{>S3miC z?p31kt>@CdR6`fGGcdYPdt+)`8m=7!f@Jn;E@H`;uPMO_BAUcz@X1Egm!^-cRlh8d zOrSzz70hzv!q*(>rYCK}$06&L2njDiHmN5S7K(+!_U zO!j;~W)BT)cFo&;%?ldNy#!Ax;>U$5`o#tJ+y^OaOd%nGk8)$fj{y%aQ1(=AH;wfIF&o+X(?|_$*JB+`8t)r1_jSX@0Vt{l^o+c6DAkr zod|MD0`(#sU_C5D*lv${SZFbel=qoKBg_DLBk^tOaF zBdHg~{eWa(R|c;d6=CHkgumXxYhMFBkt5;?Uf}A}-#=`hGq~iM_`a$C&#cN^$k|%= zy!_^VDYX5m_Rrnk!@%CUuf69dd$)1J!p}cqJ>ho4`Q-GWSudH!?Ip2dJrgnh5QWfC z+z@H(#!14Xc-B3-r3~g)hs=ygqZr_+y#y&6UgEqs=f_F_mb%Vh2G096{3qQl^78Vt z=LcO|=jTImb}nZA{)Xp!@F}=gQ9|Cq)c81j{OY*75Yy+gT35x)2=Njw7kGvY^~1ih zTDrFB{JfHps6DqU==XNwqTVX)+{J4J9QCn?0J zer`u0ib*YT!~pKWBRDITka#-OFJ90#z5VrKFFefJdR)wa;Y85EZ^}^Q;xy|r$Q<0v zu&!84^VhY6G(@<62!vDAQ$`%OGd1UEkam6*#$zZlxH_=h0|>J9{Q4al;t^7?9h=Wk zUsw<(DskBO2h<+$mUUWXs7y*msmg~bd}Y+n1i1cy{(MZR6U8s=9aWrckb|n|%=T;q zS5nx_u66wVopTq>e2kskkp0|Tv$U4=$1mZQsi3tYl6NC_2SFRm8{Np@K++QWmKCv( z5bNGwO2N`P`m>SVD^A@u`xaT<$n3!|&Nk#cJZPb}(Zlwqln~KSMve567;op=?l*No zN6J8@uGK#o9RKVcvUU3`ui!uJrgjB%l`XGE4emRBj(zS(93DRI<3Tgoc!iDCzq{%% zxDW7z8K3n+evcWRI+Nfg|96*U3+T1%`eW^X|L21J2_!*XRGD5$gi=X{$m_(k#m%5$ zeH`W&H9C*$)5>N+Y&67g@XkU?=BgUe#-h%cb-5ZgJD&zk+@Ka^ysPwo`#6-9NP~ zcKL=Z{3A5*zjqKs+%jO2g#ED$r};a!uo{Xj-?+ubEy(u$U2uz8ay#1L!+-Mo1*+0s zp{hUQ+PaT<5Z+Eza^H3JtDx?2PG=#kuGW#`SDou3smjc$=xcQUG%_uujBo;bc9eWE?~x$Mx)Xv99FXtkCzm9j0&AaJkBzcjKi za-~pIG=pTsS>lWWNEM$g_Ys$TgQ)*;424{jAl4zXeF43{4Jud)`3Hg;leis^S{-#bo1pWk_A-@UD&$(#ffo+=bS zL8+SI*nQ7yvY??`aO>Y zx3LBaaES;}F1U&}rz{4lJ4MJ&!58%LGpL}t!c8+oF&6ejibgaF0I-idxXn8@{DD7C z>*%o}f)`~G>sgH@Ke9c^ZrS4+R}``w?m2y-RGT`wP%|6;6?f0ZQ$nd-u3D00hrFgG zYBV`9#hc_`Vj&+l$Ed!N=nw;y1G{>1Pu4f{7G8D}TH(SC!BqRlvV zOHr*KIgH6(Fp1e|M~cZ1fvABBWjrhKZTvEl8zogH%?aKWCIu03zEPjzLjZnhfXugj zB&cA1lY?+nO3Mz5pc_9y08&;Q*~c}FeKesweTIoF`D6LhERWG6wMI3MnnXAdHDrUB zA6hNMGS`z~h?)`ftreJ;z~>)deS_*wWYpzIU7seXQ-8D7G2LZ)BIQua^L2S_h@3#z zdP>RLX1L>piyR(6S_l%en81V-7e@6ZHNO7l6%ZkD#s%Xh&njF^hgSdjB#A7sEGVW0bUQ)xX2ynk0xYj>k9ugz-%Wj~nto77KxO*4>P4usYxm)drY)3D%(wd+PAw&`?70(ESR#Olk(J0gv)7 zg}4En6Lf3)H8A}5M3=%p^b4C8?+l4?l+|=sldwEni;2JgJn8TQm^XWn(+8YJe{Z7;u*tnW05@wk*lGyeNQtTi^=qvd` zZvGGO_Xloa4wfb;Fq%-`dfbr=$fuH(@@`;tZ=aM$KbZ--7K4v|=Pu&D`svHFbdTen zzbgrWT44{t9}3vN1{jcNF=aPIq{5>!8Sj7@g+U)}o>zA!9CI!|HB)3Fm)@8@YZ zks~2_&)%3TyC2#$CY2mmqO5#Px|(v6dsMhv-b~Rtq0drnNSWyA%iU)EiF-ob(ApXb zQjt;2S&c#R&fj-;ADtM zYw@r=3UxL_n)x1WPgWv|E{jeBDyXBd>wf7zVr#wTd2Jb^BCf-S*LnN?FZFKh=yv!5 zc;m^ z9^I-A?R?tba}Phw;V#WZ?S zAGloGal|=i?`>ej)OxQC&+TB2f3O9*P@mB;45zQe9B)Gl!5Hn$jjXsob=@y$$E;?u z7{bMp!X4Q4grd5%vH(u_p^PI1>2L_cZ23_-vo;Xg3J&@RMU@&#e%p| z-TJIN9qvb82Wq3uCxfJh9=tz0Q)ITc*O6le)VkeOW%7qr0H({;jRnOP5EFo?p}7EEW$;=sH=UP3YXe+UE9@sU z4M#aH%_Nc&o%H-I>HpONNP#zYOm9#*5zD=SnqDE$?Y@S)t!Iz7^LeNh;?aE6(=I{t zRED`7G;PQ7Z{Z)&`L9wj@6@?GpxB5}{*M+(g%RhW9$>$}0JsI>&sfyqr_(#T%Oq)Y zex>YT(BzeI7!{JkxA5(ze828yIH=)rVOz{D><+)))9ct&Lg@=p$!%6i`{8(f0bEm*xR>ME=T~Ulr3-9uTE?ZQ@OtY>amvJ#UHoA?knJ|=i}j}eGSG^R@i(Th zP1YxSI;XD;{{Avp1R3r^Y0iRVU-$kLV0=Xu($f=Ibcpi{hN~du4EuEPD36sui8$qA zuNW*N)bxfvA>{O{_^yk!IE1TUF!_;8b{#yw^XFP2D;YX81T1U+Bz}8(^FzX8Y{NXe z>k09QjT_4#(35!ACZ|MYp@;f%R<%7#1gkST?dqtzZAQLvame~JA%tyFk`A-pyro*f zkJB8uEC^$mSp<_j&R3l~uLEu1Zk&$!FfGdtrPIrddQNnBt+QOUx)9{ZeXk6^^F1Jy zsG_?6r#uIunx43r=zomUICjxTaX&q)d*f2$AAwds?Nvr-az>21=!uC&On@6Jpvpb7 zNN1V5%*g6K@*DllzU!=#wm#q5k;~!8a-PvJztrHxmLS$=8a*zsiKQUE*hGsRbmLun zNpt(SZ|{YAMY|I6^rOQtN6`M3C0LWv5Ze$ZEkDTUu24Cl&9NSJF^nrd!U>x>^8jTQ zayFKnI*QBYr-j` zLh)}CmoQQ^ADA^^`-A*Prfq{eAQZkaTIVRd+ai#iD38n z+qqh4W3?UVfADroion{s=js-~-?V=rU$Cv98^B`%KTvRI!Yz8M!I^Gm1QC$sZ87^~ zq(q_syZ%<0%{H>gHx(!wYvPaRDuN181Ys}t@-@|u;eUQ_E8L?Z^YWnRZ&jF};6>-N z)4^Z& z(c{)<0mCf&U9POd9Y5U|JNp0fHXKGdc4f+28v+?;bYUF()r2oPviuW}+i%F)dPu6>-MSNI^8yymmw&%Vr+l+pYjoV{6)ssk? z^Q}dA%BwB^rlKtuy7)GuM$IfuJ$DNojkF}w+D@8%M=5vSf+dTz{M|~Ziw|ht5#Al6 zEa95y&Vo>dg`!+^yqLD6Cf|Peuo=F`@h!`-=N%}Tk%%1T^Mfu^dl2=fR?m8hugRDP z)aFW$Pg*wL>M=#9^n5RUu?_y7YG`i(Qnhz$sI#|_rzo)_>f)gqYx3KL8<$HOeQMaL z?D6L7ldc)-0x79SQO>*Y791Iy^%k8K<-p0;*XW4dxu-8*Nej@nlm>)t7QY5fz5q)Q zw#tI)O8iHvVT3Dk&UsylC9HHohdeLwpTU|dRsvE z>6`20<>qq%K0UUt5+0gsEmlDC*(2F6s5)_0KFmjMzWs$SQ^vVgnT)YcAOBi^SYEzZ z`}O#*%fjKmC)ev5zxO`5E6Hgfrr8ywRkU4Nyt(L*%a;3w zFZN1|7R&L@3K^{F=Q8Z+GP!M?(%W_mQvBsPtW$g`IW}^|X@^X(3`sBQG<(LT5t*jG zkl-WzEss_tKH67qa9IlbaQ6g(SQmU=Q`t=b8_6fkR22afP%``e(D75R&P~Tvp zn=|x6bUS&KO7@>KL#?}63kM1scsLebQt$GvT7Ll(rS73UI~^SS%0z{ft~;&)@qU=* z-Tu#;Kj7QAPBMiGEqyyPkfOC=`U&9YasHy&624LqRlSl5`ryl;huW9kvtxGWYw% z<>M`a{mwiS#u1dqoVavFvxWplOtIj8rFUfY>(NuV1vh}BW!^$~`47Z$ zg^*uDtg&4WIh&$JFLSJ??9MD~orp)6>E3m?r!V`Jd$uy*I$WdgOhS6&hZkkLP}l9w zfOyTqZ}C^1!05cCQHN+Z*t4Y)^8qWJb#o_u`bMeC#DCiK6vt+wrg%hfcTmKTl)C-6kE*C%`fC$0!js#T;O8#Zrgve^VxPB9u^3-I z-kQ#>7b}(;vxTxh@r@jzvwL+|k9#+J9xtve6lBe@9uRr7EhA>rXF0rXGv4wSeV{S zPG`U<`ZlTF`r$GEvlH7Useg_9Z)yME*AFOwFz5B4@{yC-8Zh`LW~=YlTS#exW&0L> zY&pevti}s-YPwyV(I)pAY{$mm_^X_Bzh6raJ@jB$koW%}wq2C8mW2?j{7}JC5KLM= zHxGg|JtCX?K_d!Nk;FoF(2$CeAARv<9?T-%OdxqSWZWG0u}SloJ=VD)=S$0`yKwA~ zfv?CfPeTIZ9wtb8;jL9j;!xi$D1hPUe~^WTZxfHaq>~JKlhx)38;D7H>fu@Qr8!?0 zU(oasga#)X5{v64@*8K;gIOXqfR(jnn}}^HnY~V7P`e+$wB1#7jNHCtbR?J3R`fi) zaCP@umcm7zgbS%5d%>dV7ip2f6#PuA zO#URV?2ssc%-~(ca{wnT=tmzeaf;~#=_d;wli%uEL;ADu!g3$6qbfFMzo$E|AsE$? ziSnlww55{RH@zD!ZlEFGZgRoL_Sv{oLt#Q#HD#*qnI!KFv0iXU3Nv+x4-P;HDK@%4 z2#qYoX2r>V^qI@+W-h0YZ_oeGl@wgKXo!u-=REt#WbYXa^Ez!2VV))&T~Do6m-7tY2Gg01Cw;;h@9!8I?8YHOrHXd7*3=TflT8%AJ7yh5b^3YPU+qz_#XS zyYA7LoUw6A|GcGfRKNOMqo>e*R!8dENALdl04_V*QkLy6Ji zS1l~Uf^OLBIfDtj200|@(@c-TMQ}H!neoHiXMf!L9p=B?VQAE2^rkubD$`EBTdAg` z75i$|6Aj$3)5vf6e0HawVidi_S@q9%Vx%LPLdPIZ%Hv*-%|nil81t4|Kn_POFGxvH zYu4c}a4ZsL4AR-!+wZ2x(7iUGz)3;>8w7BTmE?_w-Rxx6Xq^yOuN2B2AM_$qEfW*j zB%u(t*lNl+t_YLm4L+DxgxC_(yE$_p--`|LEY^H%4ceFkE)@~3>?})S(Vee8KyG`X zn82wWTs+SLYIbsT@ZskH(d7ND!CXR@J)}#my!s}=VtPU59tXJ-Y5j1opfzy^kt>H5Qqy~35JUb`Tmf1Y;T`J?_&)|9HT8P72Vp~N0p5S$1^p}Z4NQCJ`89$h<@;zeVH*^E z!O=TuCA_fFP5MrXgV}zQR=gTdSe9U~2O=~(NNC7|pphHdR(QGIcvEN7=fR31S2zD? zg~&ujH{MGd;1xXW!A{X(KdS zVSi}Mw)NGf@wTjdoSt+O;!9F#4;0 zwKSxyT}mNgk%n+BYI*&z(8}x+ZeNTcbJ*@T4o=ig%3(@gKU zXmAA1i8W*o2ISPulA8#gMK*jE=rNx3WYw;ht9zj%Ou9_~GvV=i;pi1%E5k6EZcHZs zC$mH!BfY+M1TWoaTvibAHKJdTu!g|fKV8Uh-#yPW4|v>he14yi(m$-OAI5;Tgg#W0 z60j0((1a-toVTQ9MM}?)MQSGYoz_N9t#{OxTs$PuRD14RLA-2@2`C zIavrgO)+dyutJRKD0t=ZI4fifn-D2^!hqr|66lX_Mnj%&oqZ9e+3F32NOK3j4WNbcU7<;jr zY-IqXvo5hzQ*02eEU;8o9J}edAqxYqQ8KBsNT%1QZiaBIpUZAP1pm6& z(~&l}Gp`liz;LtBq%fYX=u_pW#y}S6!l4ayc`zmqOd_QBCN}=-=;O)Vg}9EUAL6p0!iig&BW0e;iybvzgb0da#$sUY=td zz?wLje(2zTmt}LW^J>!Oh-cQS^F%(U{-{`Ng9f%-cu_U-qLaiM^Ml%Ke`jUkdRm~Z zb;6n{`Qsx=f+SNnQOQcEUe1e3@kk@Rtl~(OUnp)7tVnLxyYGD%(AiJss~ftc{}3=u z7&q-bB~0Y0())!YkFdQPGx7C2y`b`)&ZcLnbPPX;N!N8jSU#(RpXohzL4m6Ga29U=}j6JZ>eBtG6oj#Lkp&f(eMY-pJ`8Q#0 zbfl6h#9%2B!!-6zP>=snr<_2@Sg! z^$iPoEE3|l-=36~2@;clR5KykHru&+4TsxJCfmBRHVyzT3Xj968drLmI?7lFSC(nP zja(P{&b{-E!S$hFt5=y>m(f@GO{SA7n(uXESGBma)4K6D_O~*PK^no7o-DLU~C5Pg|T~$K<6d7c??&*F_ z_cwMondHKnw`M^{bwKmIkJCJkHkJZ^19mP22)+|dB%p)(*_i99$bzGibWx|fnx>#7 zFd^D%p225~i7q0M-Z&5=_mgsdb0uvOKZ?h%4(z~G(DyA{9{J+9b3;4|tdr_6Xm6hw zQT3bKtoKTtX)#~-VT7C_9kABBz{9Ui^8enPhHEwtY{I z#KLHwAqI!v@x?68<&z1O0q(n3rdVSIKv4i%bU3Ib-uL0}Qp{x1>l&+zRE4a_Nr=<6 zD~!Stpwf9_4-+oH+5I zHjlVlC6(w9k(Fds3wWb1bY`^eJ@WW~6H;Q63u>g2-+`2DmNGP-KVbF&VjuSr2F>VF z=i)l**JF^6Ie2NDKmk`_OUFdG`y(Z91g1AQ+@A80@*_`VI{gSed8X_q*$g(4535_j zX~l_&tIx~xu9sWs^?)Z|QhE7pOFS?g(rwuV;vYK6W)jL^r*xEakTy&l+ms^3Ja~e` znHyE|2P=Ju;`Vvod$4wroKb)<^_W&?kqk5AT(GK$sfCW9dO~^8XFh~qCj8Aj zj;V{bddCW+v*KV$!XguYgAH7~Mey-y2q0VC*|Fx5g^97KTn-R9!!b#D7eHD+>FJ@~ zcxVP63tu%k9TxS(ubf9}v^HEI0}6+ZUp1(%E%>h9oNN>?h}D2ngqMqeZ@qm>9sibg z>V{MvzZfiO6D(PC&l}|C6`@kGj6<_$iHkqQurk|IYxW@JG@r*EjgBr z3d+lZ<9P@>-q5>cbQ15sF&SsKJG2&4L2fcnGUQ~-YQn&->{H>!>Vkn~EvFdUWS;Wn zDYHvKp9|!HvDL16o3r2klslZki(oa(N!l>j%Vcdyp(4#eKs+1nktQ=~0t=GVm~$cJ z*v>_M5RfhZ-a$PUO&5=}CO}=D7Wn?+j!wK>lpIJo)JQ@Wh>b5lNJ6*P>!-)l7{v+#lQ9Hb{OtVTc@a&0?OX{Y0u>HJ& zRZdOj?wgG3Rz#Mp*6R5uaed-L;sFxk_Qup`-8sjSkI8QO)~<+MDWJ^u6>0LMB&&*&C#ZFdDO5-@K~ zxR&T5pia4a0qud5_qZ_6CWtp+NnX)7E4PjOWzhcwsoXP%6`}yMaT5aiWXqMQk=+ZX zUIBIy-g1fiXBZ!VJSa1-Q1jZ>A0<+QvGpyqV)^5{mb^c}hu0A>I?z3={U2G|5s3ha zxO@D;GAX&M_A5(l(6AHJmo703Wf5s>+!p;KHNxhJ1+X4xm#S1&+U~@YBp8u!QI6FO zt-bY{p^a{i6YO*uiSt&2yMc{mSXbvdpyUlL5Ld6ozo?PnQFhsw=+FG*vkAt^Akn(K zn;pB>OOLkyM-2PgK?&u4w>?m^|7W>-*hpJvq)z^3$ihx=Ikl!paZY6Pr~Y!1@<`=` z&U^ONEwbRDisg7~A0_jEj0agXxCoieqI(CP55oWYCzUI9uawpXQeq2NmtE{S2@p!q zI2@|-G8BlV11136hEem;z(2gloT-mg9H3e-6>-?oTJX8A=CK1+X!iH0*YZy*a^J7E z+P`akC|$YLE+Fx;{NGz~EBdmr*6#aQ2=N*LPZ4mQ}2al98PuaVjo3OpSr(`_elI;U_T)rCrCoi3(EyiZkC{&XJpW@O}nte z>nS6og|=i^EPq;o(^RZcCxZZ~r$nST-A2Vt$C4!cSc#FTw5spO|A1gFFZohml=fWl zFs%MfFK+7Vrbx=qEqkCK

SV4Cj~Frvwcc1xHd2rYMDM+|lL%0P^_~7lV+N&vEEX zT1jk}XunEbR)2;CaWqJLBai|wIwq6yt0<+m%cTFeD5N}{6q~5)(lE79dKNv>Zcg@0 z1%^$m@)_$_0j{JwXbArSzl}p}b|uCPK6NXHih_OJF>RGw8@0GQ%=6teBg|u!{g?Qg z5$vSdTI)O|34q$|zITUlAmeCno#$vt0j)GU*M&7HU?EwK&Bq$<4OZ0PrD1D$H*Oq zn6)@~31j=NG^|Kn8VKID+}V0aJBuD7MUr-pZTFQG(pxzuKt32}%1I)PqzFwBxljwW z1_J_cs8lFYX~@Z1sH%`j%vxTJ;`dBr3#gBn?Hc$Y6`Wf|ug;0C1zKMH>0SoF~v@sh`$C4_gb?bakS%PrB@28@EpFtmFK!S)c zVz0xTRJ!=??Rt;hNX<3d!=U*=cUR#H^dW<~d`cl7%tP_mHE0#Ai9S5>m1S%GmPT@6 z+Xnq5xZWQmKVUkLg=b!msxM2DiQISHTV*$Hm*_omwqZHHOi1eYqFnMK!!7=7lgvWx z2#prl>~lr?;hU$Xm>cNC$A>3&_?PR^QP3Z0eep*)n+*sLRm!z@Qan_NB^@O!k# z{dNhY)|L4@B5C>_sA#ir3OveQ4TdM>7-yPC2KJS1OJnRc>N=A>66R69zI8mUm(nG)mXCKF5 zpPg=EyK|5Bq<_>W*{`~H(8+He5o-(Tq+4*q~usr6{(+tqOn-R%>2{WH+d8ZRJnb_K_1oUiRMzyBCyY#tD7> zS_lec*8r`v?eK*ff3MB2FgsCr_!*(pwX{oEvFm2C$k+3$kE|JJ%fu3_2%N)d_stEh zFfwF2{{^h> zNrBwh{TGIAe#VZ+h#z*^rV98 zZ%2|tPUKtYYrsPDA~!?`G8@kfol3F!wvmEf^0XtpA;NTWzyXe1`5SzyJBL*lwRST@ zog)#JJ|v^l%NTj?Vl=#y7kW?V86)p@cMKaa zK2&LjllK#c5vf&q4HbnJxJG(9R3fg(@qLTTVn}a222AZ<9PQdeb> zHTP+ez9QRXcjM-*olXkH;4}dY5KuxD_6dqisNX^@t%dyC2mkxFDYZ`7t5iKIDAV{X zVms6&OgGP*%+?f??i^-*hww3TmLWesLr2yuX9f;f=Gvl?qS6Vg2-QlEfnyuc;b=J=XM%TX2I- zlDCqwF%-8Uhbvwyz_q#?tAc`ZCLX$$4O16+dctU2T|Ek*b7~C9#)Pa+ zDt*waBLG5dQ;f=xJsbD{5m;0Aq;wGUFk5s6-)eF6$b;UhuLethCGYimX8o!oZAONb zI^;Z8Wy7=8!>nYXfel7*xC!cH`JqWVzCFNjGr4$kshApBb|IIY+($}#$OX}J;eyiT z;3QkNRdMUS$M8Msn=fp+QLu|Z*=*9_=|H?P8|C6%_OMr|9(sp0rh2kA-%c<&jSvda z{ysvd_Mu$B*jcQnljqnP|!nnqyv16M>!N_zRPm zYk71g>%Z*(s|6@Z)vg=4F{x-w_+~r*%!3AO{piYRB=;MRM^{BJ}k!I}NIR_?<#f8^pTD@7pQ4!P;WP=4}U(SuHl zeLwtV;P7uos)iO8pBp#pb%Q(@CNeqa%Nq_?p6-ZZ3r?D$q1l-7PJ3d3Nr6Pkr~5r!U++h#qtNuCn3s*P3<9_vF(FdNHW% z!JMax$-Zm+tlnPb^L_!KScF=!6o%VX&QnO;esYl&%8Rhk-&Wj#`#Bc{ zyEnQVYl8;!cG9HGVM#wWc1H=}w%-f_TE77ZWxLN`Xq8m$w@W4sFw= z@&&iWojSEw^Dl1SKIyefSl_ruC-*g^RE&d+H6O?Z_mP@|4(H)* z!iOWeUwE}%7mktLE*E}X2Ic7&5LczT`9y!nSQu9$H+M|w{Xu30Wmj56li2-QzFNGV z^s+0KFl{ukn=I;m0&#dx#=FdOY@JeYc(v?18TfV=kc|M?jtDlk-v-nc{j8d-2)I6d zop{hwmHSdMJit;W@WkKftXHB9wnaTC`s+)vF-k7mD4X$hIb4YrD2`lx3``cqwLWS4 ze|#q*0LpIJ`TyHMSL4xkJ=OlqK^gCyJl)5VzdxXa^w~w+ZTLos{B*{j8?-tBxsc)% zXI%@b96w*6Vcj1JeJKdjb6w>^h#T=!_PRe`WYR7FVg0;*NmIJt%XU}tgnw8nMo&0^ z#NHsAFX#gsb{y&RJ+`RM#F1X6SI;09Hsl72x@?XDbn*%~)x!~Amkc$sW%D@$sPwv? zRtj?C(R2N(R<6Y6T5Gnr{vV!pm2ifuHq)YkyRK049e@AXMC=;}uX%_dX8rrDphQ$TAB7;Kf_;SaznN7<}(>f<# zdI$s7PhAxjX1vdyPa$69`IhV;B4AWz_r&cYl%x(b*2)89<+PUiQ+R{|E;NB@zn+8A8n z=Q@hF%J;MfyS6lK_NY(rJ+!4g-1W6dui6DDCi z5lhl6muIt7LU%78btN}NPbVs`x$?X!fmgQluFmyf4Ttq0r71N~Z=0m$c<0g)XY0ZM z)^XHtWHA2>N`z1^NAvc-Q*-A2+L8UDfqB)qD(S7epLnx7cP5LbX(jo9s*lex|MMbC z-9#cAN*tgry{|Jnc%ey_#LU*s z0d=)=MY!~}fUH@J6*3iXRLKHSC^1+Nc=Y0MK<*$bSBjp}A|8t_PHlhJV9{7|5KQe? zaTf7wvSEipUtt;nef5-)*bnnAh`cJ*gMRSjbU1)AxYUUh!-x0XDWzlBLaC}+@X@d_ekRv)zK^!rDi4MWj40T(X_&bn5cNw1n&W2n5;8fDy|HM(T4a{36_P z9H1|kVlXX)?0|8cZ!VZhlkky_IX;nvO2qAt=?iqabHeA20*%e zoJ1pTc|BHkdOv~Pf{X6HuMlBN0W}}s9SDf4C6M9t(z2F7z92st-2PV6hEW%Org?Du zg-zm{3Cs^sMiohn=3(E!WF&4tk|ICLVMc4(&Mk9LIF4y^i9D0|d8{ANxry;;^jmtm z(wY~K;63IZ;LBZlhlejAr7Dhg`1`t2oGzD*9C`0K6E2jz?l`7KP-8&-~Nh%PGtLuw42K zrdc3H@Rhxe4iS#m*9pq~t5KyaN7Dw>RlKKEZ`8BB%p|ajjZi#VH+rL$q^@R_-u5(RqV&pY<}r)K+^QlO{mlIx)?6Hb&G7{rOT98 z`T5xc#o!k%L_ji`jz*vK>~@L`31sNfMK&LJ#Kqk*%eUFWIFoK_u=)$H2V+ z())J21Ub>}5q@z)!r-aUZvp~~77wYn>ZTqM9ErmwvV$eyvvH{D1F9pMBhsUC=;PeU ztw-MpjCMEz@$Vgl6aQ@VEi8HEUPOGo2q;>Tyby$y5!^eihZocS*rpLX^7OPsQGSRQ z6-EZ{XH7Benkhv}19>|sUQ-|gg?!Zz&tTs=JJ-@5MCA(E!oCw-n6$(^E>c}tHLw`qw5_C8R!GYn$ysVj*bSbPUR zHc5R9O33`O!ULB23(&3x)~S@p%xm=AwMR~QX_xy;KY%;}jE|3Gfik6U8opyfS8J>C zo(PtR_cqaUP;5S^^(}_ayJ$>|Tz!WM4eoHT-=gEWA2tbbQ zi*|MxgT1@Ln+8BsC51c5im-$Qc#s^U2-k(n6OmcuAG_O@9>2yvBz+fOLN-{@98}6& z7epVX5$8eEnYKZo;vx~KB(+(6}-W_a`r;SBb;7`7fiawUs+G(GXy@qXXQn$mh?A@$mSvPq|I!a}C;x*mC1 znt`jJJNhq7b-grdS9n zBLpfY82We|%OdMZaUudX$+gD=^WxvMlycm_0>VN6fb@hA=^|I78N}F4{!~2Q2Mr%x z*b@W~{{{WP$mD}WAx-}#)3+qjNPnP9SJIdcJN|(k zq_Qqk%x&P=iTwV`Zj)DW1~LlY)wx9#j0*44cOY@s!xYo#+icy!1^&~b`7(Z)4KDi5 z&1+%0+tZl5A{RbcW6ohbgRy!!eezUY7D+ejy!zMhkXB9UExnfgten+BWGI=a{Bx`naCyi#$ z-uoA&GFg0jgbB^a_)D1WNzu{y{*r0ET|TWo?S5V4x@dGH3wf0*mBjFqcW89=$e#B; zY-sc{jf!c(rx1)J9jPQ)$l)&#Q_n>1RW=AMZ@9Ub!T02U=*jCxh;#wNUz%T7p1j;X z-8-+UEAZU0?WEKLP3oMC?su{2(LSs4ng%`reF~&Mz9d0=f{}VVt@1ODojaqxICJB7 zd%03DJgL{VF`jpq(!+&k4cyb@65P%$8;_qiYy7y1Af`O8 z=UDcZR&?DvSarbFTf>zYiI-;lWd^91i0|p+IX^Uh@p}G*`)O}uu(uJQXF6D@IG271 z9?-MvrC&Y3HI=MhbO=s36q@yWwexp&Jp2HKPsMGM^4{|; zo(*JPGZ%v%uP!}Tir*QLp8nS%Ht@1%TOqi0`DTeh^E^8%_oK}Zr4fv?(Zsm`(`SB| zL?kS>g66i#@op(KT-W*Pt7DI^PA((I=Yl_2;SoPeq%;-&C{`)fBiuIkPgD#j92;D<|~WgeH;0$j=3H$P596e790^|pI~h}4>NpDu#Fy@YjWW1cs_>5#N@=v+AO_?-&IMFx1A@mEy8TO!M7_sh;=(#Q zeoblAyv!Ff6rytK)~CJ1__88e2E^E7L2WRVVe)0FvZu0qQK4#9M@OHbkQ+rc(4Zt1 z_n9`f&KPOEJHAu%Vy!A3cj(JItLi``|5uYYL=_W4`*=m@$# zsq3&M2m=M=o}&FIA4zijfmdk2tzMzTfShWkK9jMoOryr?pqZ?Xiilmv#shRe2B(?*a)P=5_zcey}cq zZrekVyN%;Va6LP*umwrRv~!X}PO`U9tdSclWMDW&8;{Kh#g2d1PVL_gWLlB_EJ!Gk zF9n=UIoMD?(L)C&mB_)GkCzTBn-1yvs!!%!EAeMMjP=bb@#jF5J8mJb$rKAj6o{U? z4OM-&T|RSblzAJ*E%-=PT$w0I*PU@VQp%Wh6_I)8Q_F&V_T!JUpv)RyL|t;NK=3uF z*~Ui}FFP95mzU;1@Ti`nunqF|-{%25AYfxA-Cl+sIPiH4d&N(sMiH!NopAotHT5Ne zm(hjVy;e(3LXm#@jjhjlDz~h9|j+B?7?x-51&UWO-4ssznkB% zhSkc>z5QQQy;W3P;npmQyKCca!CiwpgrLFQ-9zK%xJz(I2e-@K z|M}0o_icUs^o_Ab&oygS)hzz2`$N2aUrA zV!bm62U4$7jyH*6n2ASAgL2LdwWZUTUm*NoFNFb^)o)P#);2&mW={ zs4SZ$Aso&?tI!7MTH%t_SNDoO+vG!hAVMx{r9tF5xe$XC_1D<$i2$Ow1}`) zs4I_O8prc4Jss?z0#(W_$etJ@oDnf~c0mJvmy9q1>@oX{7YXB9Ztmzmp)h8yG@m3m zde9!;1pF>`{@@2n1V2BR#EN(>PhS@hDUmPk7G%u!>cVITG9G82+Smp!;Z>2q`Fz4V z8mo@3@wr`Rh-KIX@Ut;A*Nhe;tEA_CQgMRA9$)v8w2_Iu`7@Pe5!e&jX!+E7m}WaI zGv29wS7H{CZAQMmH`~mUZk2Fw`cg&@QdZ3%VPsmSWaTXxzb60fl%rKdijm$a_;ZB6><5%cwu&$>5h|CW1^0*_8p%K|?5hh&9)-*bE7T^^eFtbX%iiHS` z#Q9F!nsJocLeY`=qiiq79z(e6`&0r5KGhlPs9Dal zU4Z@dZa=o9)J>++JVXWq@vdWhXKDc=Y)kS?Wl11i!_@K^BcJ{Kcy*mg-K8&OPG-d1 z{O1jy2x%J*R{pMPPL`4JMI|2{lSLlA$p1a^obF{m&$%{^b)~u850hMTpXpOG+@Rr| zadBx&O+ZG(Ru15cwSA9;7c&;GN^l;%3+?!H7R3^ts>cN7ihbvvhcaS}^k)Zb&l?|R z*4>_%M<_vSsIS?%TODy*Q@cf5V3^&;K%JtQoY|^TPDKpsXDVT+;M+y8UE}8DDQ5&^ zC*&I_fX2NG@Ru2?_%2`F)#ySUCk4TG`ffzUR^$U@>#v^gHpVLCQ%A^XuoTbomb3CG zji+{nOrp!MiLgmv#J}e~)mxA#h;KBx`+;ur4{7B3`Jc_%x$JR2_(C3_ z07T3gR7OuJCl<0i8oL3{L9J$gZM0qbt}NUXaMy{g{Q?z_~r#R&Oq`t z|B&n1`Cr2hEyZKCanqOY;u)iFSkLzOZ__iBZ#TWqYyZcgS_M{Uxh_L0QrlH<+^eZn z^F6}kcOk0yYPjP`my?HMB-r_7WbNCv@=ULV{FhQSw|p6L^(Z-t4qcMdE}L(0?6vx- zjTKo8lzf)PIpb;9DZQAs!VQ&JGQ$Mt&uB!v)dvH*d_E1etek+ zBM&b<#JQXF-tGrPaJ~JGj{}N-G80aE+Tp z9ujTdn3r>~;q(86%Q_`-{!@$f!l?y&oo~a-teU^J{rCAINv$L#@IQ*z+_vaH z`B^jh!K6%^CaGhqHJ(e=8=bJ9d>X_9y?GkPR87zS#aRXcs>+rwZ|^!{{ApwXRAZ(G z;{=p2*KaL%E)r>0cLiHVKD0b77smX=Gl{(P(ReJW3z|4xMASbW@%3^AKKZ_w;WZ(W zAW(r0NyD7)skZlq8`1T+5-TE&Pb2xv(9^nBE56zTO81T9YsolEGfCYWK8_q8H#GR$ z$mcgw1s%!C+E_1D^!QcUGWJXQ=*Y>-%YzO^g$JO0%!ut?=DwvV9E~3&#`C9ggu~n~ zgxSI^8ZdDSo|JdIwrZ5vuBobIQZDeBPt{7gW;L^A)`r3D@GIpn&zI?NE=>!%F7QkX z0cvOhnzmi}SrCLogiF(SFx9_b%x)tqqP9SvtA{=6GA?XFVXCYg|8Py5 zVZ@nsBhf%p6Jl4#7=wbc&8|&bvum$EneR#zY&~P5nZ+w(L>-~{`QshOIkT{Wj~p4* z6;NMZ`+zQ6TTe4w^1KQ&SSn;M_}(ZuUhXfUVbwSl#jP;!Th!)jB6FfcKV5EpNjr}j_PcLKmb!=oMD*O;wu#!n)(DGz zJ+2RMvPWq^nD~wac;27YQFl7!x7LVv99${^{3=0++{h^=-@XjW`28(Ar2j}(HmdPk zXn|-&mzoxI-|K~WR&`n>fbAtuDe3bk&$+ca^<4<(-~w)}Sxx9xqam~&bJy_QcyUSa z3%(&+T~#h|(%5i z&^hH^ZaLx5`$(;Sj~uIH=SN5G_wsnc(Uf~>kAhY45IM+Or8n6{!+)Lu%xqs>^i>DAMIM`;tTDZv4{phFTn{)m3l`ofaMU*X95 zmmRgh8PEOOJzor# zj@Q8Lrz=OJZ`}qIz8$mkCpx{Zs}7?%_Q7}aCjsft_mf#P~q191}Y(tb$b7vb%n z|EmSCn-C3LaWNEcB)fC~Jq4*JQ@&r~&s^DfUU<-ta)tjr{^x-sbl{EM`OmNTSMNz> zol4X=UPU6_bR0x%Jts!~C4%4k(w|Vp{)>Y=fd|I3@ny(sZY}yAs^$cn&xR9U=W1J^Y8aRNepe2 zDI`Nvrp2Kx^7vok!WKc=AEH$U{ZQ<84KOCt=RuXU6%6oVvGp)=(HZ+T-#S_%F1o>iBYYD>!+m7*B$%%#L=g1C@9YU{Dv7P;jnES7I6o-y(XxR6ql z(a(9tFzlg1dSj_IzRZE%q${e?s-HQjX+CU)6S%U0BkylSZhD{Du8Z9l6~tpUf`&xs zRHvq&)yxy?6fyYgDg=-qIc?)bhlbJap{^Klqh7u><{+@kZ)wM8P7Ob*jF*@JyqBWE z7UnjB(WvyEmLB&qCP-x2qD5UNG?O>m9ZqB8!rg?V2`d>m$SmV%GcqaW;j4l&F;L6M z^t;Se-Qd~@)o3;Ln~uY!81`;@IcYr7X;VqYlrUZm>=$HR7TWH*zT^7mMQ^%_Q8v4T zim2v{4nLh_!UdJS)2lQG#YKZ7M9gK#*Unw%A4Cu7k5fmZNTfgpcoD>{HUu&xkt{dU z-jVcQ-}?D8WA5Cfy)+_w*&D3$5rmXV!`65{c#b4*(6y1_ z_xxN&4_yTsp9XNQgKK4EmuN)0Y3r zX#FgsQeLn2RG6%x^7tdt`B`ox`vR%O%E$&)7Y5LgLjfT-P`Rc3jT8YhfylsHsqVQ$ zEhCG9IL}NAn;?)PWx+3x6&^hS#F4>+k=39dzD$|G5e(K>dD5+PE9Ie|Q;L}8yD;G9 zPHGNeszyfVQYJH)m~^`mooUz#1;&JI)PsA#3De|{JeAiCgr@wwA(%aa!)20bHb z`ulMJN6PNn`kKubb=y$>_&Q%_m&GpUe7ev1Z%veUtZA@?Wz7+0*AG2r!6v@*n^@Lm z3E8Xc2e*usdfKSEs}SyJqqn*{5%R9LhxFw7f==of9E z?LSD2U$>oZk57BDm&fr^MasF6K~{%>ubcMJ?n_ynWh1U6Aq_lOOL4bd;~zL1jX{cG0r3cNXSQW>@Utu_r62ljR>r6YDZ&6RRbJw!^Bo z6tS|>^o0PjRYyJB@uB};&uWb_Wn+3XCuom;&oni&Yvr9v%F*G0{zt%Rs(hgz5y^IBE9fGz$?@IIpwx15752D8$aToGlhb0iB19w=9 z4!=FUJU;yG&=xm^W-JCQ(^6?|%fw*AOT=%f_zw;s_G1SqTz!;#JqvzG=)1MKxRbjE z3*KlOLyO?w2(QH7H>XIjR6Z~1293Gozg)~`6YH>#l>XWv@j4XcrGM?;Zoz$R!3+A1 z6|g{iIewXi3?8SfwRgh(4cJZ$xtmUmi!ral@N*Ocdwo7M=V7e0A@>>6qR2;+jTK>+ zSJ9L4lv3MNSpOmraV_#2#?nm!-~!uxJWi@>4VQUjsszI2PAqY#aHLs;@39>Dnx$zf z<~=ffaa8DhVVWBDlI9x;_m$J38U2^nthDWOTGC!0kGIwF(Ol{nu-p*}#Lnuj4~z z#?Oy}d?Gxr_#|%yL!2bfWC?G=s`pzL-oW94-5iM}Nx^$bOsbLlY&mh8P*X+NV6E_h zp?k_J895X6NlXVyj>L22GX$XCRdE7lxHqlgeLk3!OWi6(+MFZINk|lQdYHrXgK3%H zk~8iFrV-VI`#KKML~yUIEY3Fgl($`QUBDRD%gyIYUrT<#kVg#m4dBbteqYf4C zuT-HGzWrr#&WZgU82k3>XwcX96FCl6LMOgTW_zRg&>dZj7RUvFl#<_|qRQoQXeNDGt7&MdJhlPWr*-u&y`u|yq z-9fniK{ESu9FY?qg3D>Ry<%q++%leS`e=NffG$oBN2Po>IbYNG2D{pvjSKVTQ+*^+_VZ3rs!fC<=Gw!VsJ-{afyPGV}_`7jY^3Y%8q|p&{b>{3_O~l0&Gf0{ex28kRP4gDhEO+eb6O>&$H>&rxKZZy#Fu@ zMvJw&t&;Oh9~>Nvw^p(4Mx_a(cp8h_n2tFD4nB6-^kPw^PufguX<0}B8euuU;i_1PiorD;Hq`hAK`NB zp2XK|30cv`sRrvcjRc|ud&Q^ywQM6=^r*&A@EgwrlwP=oP#1I3>gQHB4`{RY0AI^PE9~W-3-!Me` zOn9h2cGv*1)rV>vtumpzHYFOKr>GX$dmwtsle61(z8^hoIC>i87$CKX=&(Cu0YVX) z1yJm$%a!FT{&r=8VT|szZ^&2T#P07kKT8WZV@iLLe}IuIg+rcWj$eH`XcJ-+asF~% zvcA#0$uG)kC+^zgc;<^#3dQ008QhnxZ$7SiDu%F!YsN6l) z%vNv+$J^md+8eA*!3~4rdHQ$%{QM6uc_i*Xkd_a?FVKotZNaE46S_hcC6KSLO{HoY7jW zeTGS9?V;)=k(@`DomYV^<6*Lx4i1Mu14`z}&i#X2&A~>j1^8Qoxqkk8>EfQ4>^&SD zJ^1HG>=iHv#)gkj9>{LmWw%`i5dzQ~A{7`oi%s@!H}7X)`B?Cc2q+wX(r%(lrg zkdQYvu^%(9c^@Ia`9+EvT8%CdZ8{+qq+}6EHp6DJcB)|XnggJs^Ple`pcmtU$cF$& z!MZlb{Q)Jc)7u+pc9~<0e^vIbr|U!)Ded%h1!P=OanGfq|4GljK^XXAX-4@sUU-Wd zhMCd0FZv@!NJ%U+wlHPo(G7_3X5+AM^Qe(Co7RE15-DA=`z_Ff#}umb`x7OK1Nu6n z$2*$rG)Bfk7pgPXY9k&EWhA#FJi_q?L$ZvIrW*P@!mKd~CI2~oSKMk}d_{<&arEl_ zyqSCD!zaG9$maDAHBRqOuY#BOQ6jI|#R<@cUyR}|uG zBmU`=B^xiNf)La&$AP>?8nuOf*RNzJb!*%VRb`*RYt>L_|2*jCPBEF%l@r{t<>uoo z#MV$?YHhgbbm(p73NK&jA+=HXb0GJ1G?aS3*RvnS}{pZL1YhAt}SDA=GPIkO0Xs z(+x3~Z{bEFej!9%&QG~dxLikNpDfi;c{^>GKH7f)(HG`97ropZIP*0X7evYJe`l~- zsWe?ZPA*&|K1ZUFCW``$`EggU$!TPrjW*zh0{Q5N`)OIxSTZKppwe8egKb_opDf@l z70YoFq+xsqb#mGT`7G&!D>1_JPKh7#(F89QEh2= zJfhS+k(SVKXN(s`W`{hfu~B;f=B|b6z$~twU)+8pW-KV@aRMDtcSApM^pjmYcrpO$ zO<`oi1YMvI?ui?O=T{>o3Fy}A8LphctVew)`mGdMI;=Vx%lE~&&IBt->J%w32u@j^ z-G(~&v%ONo%7TEbU0sAIq;*IV%8y;9_-3>CLP>Nt!$0D8BxUg1FPg!_%p38F<=NUM zaz4z`aT9OG$vLo(*T8Zm(8Vvnm7CQ|Em0PfUlK<2EZ@KNZB{exa`H0qcv;}BVz!B% z4x-a7>s^Of(Q_9LWRel^?@zonLT!rAZMCM$4ahQhWKHx&Kxm|6{WwL>e<~?@Xzw#k zBr$t1Jm=@KVsBacoD0dcE&9TSO6~3$k~6E5kFGXZ+ugNLlN-Kml^PrEYi!j|r8jac zo?p!90hf^0^*g3rLLx01*(n#&Dqt6`*CPbyGUdqcPb4%NJfLI-F%yj2pp9%m0_euy zR#>_JYG20QTe)P}vqNmJWObr#jCTd&7IM#OR*s~X=pqyUYpoqm{@j@Ox5GcG}>v;C>Xd!~J*E%~>Zkvn5gnSpWB_0~Ms0x14 zVnJW$1c=JpmF!~jKI+%)~f=T zt@zZ-%S&kEz^ktzsk)E3;%&uS{CRA%+@uW+WuYJDodz#u8c^NkB#6DcN)3e`#GpmI6M!p5x#M+@>e6QVA=1jPzZdli<_qb^l=E*$?4jPt1t~n3rJqv zO_hY^ti{xOCD!2qOw4BJcNrC!@Dv8cK^&k@w1QT>aX^wixzQ=%d$-^$GF^|Cc~pdm z@vv*Y)NxBvvTS7g-Xi_*5^{ul9v0P+{UP?SQw-q4G>WtDVKRU9SKqXs;Wo4ZLe;3h zfmA`1A4Z{Fmo}g~#I3S-$oCpTH9#`7{GWHQ?jT+=$eDMK;G)g3&B^czv$tkF^!D=Y z^9t1Gk>sHt{G4cTrf0_Vo&$6_PKaO2%`RxE(`0E8y~O8_d>LLu!tDB25}Cv@o*V~& zAIp;zHv7%OWHt$jh%Wq}Pflkb-E%;qrfDTYR85gc+N@{a+~J7wO{^%GPv*NQTM&s z@DQTFZ8Ji8$p1B(-?M^g&7!d;k>!b@78094hwtCI!!o0Q@@c}dLhT&9&K1yMSQ{TS zeV*Nn*o%H0vAv@`OT{$OhsuTF#_mU@V57>WDf=Gu+u7idzkgVSZ?+}Yd7}W3h)E?5 zbC(GvlNAUJwz^Wz{(CHnirQyb{_FP}GEmM^{AO{$7W3`+Ki|U_@svMs&}Xe{WXFB!~02Ki^_#-nM+)ZKWHc+82j2?j7>0k$dT7XW1n;S zeuVke9_5(yB$u$AYAKsi0HrExZ2q*~{F$9rA{yBzr0D1fcNVv4!FE0Ex@qpVYu-oO z4eKv~U@-r)0r?+?zr&hB*FmmgJ4EGgHcv0#-^A&XeI{*5J@l|4UfKu+2%g-OwS$VRl z65lj|aH>Y#`~|bO$nHuUy;pblmdmJSzrYltgoNuAsQd${<@xHLK~U!3|h%FW1+zJST`Yj&uKj*BX8 zN)G5reOL5paM^Rd*F>80LECt_W`Z*N1OKuAr?nhDI@$xL3G-S1YtIg%?4a!s?y8uC zK2ARmV3T|dFcOcdo>)I>eNG4zH{Nsqw6fxzQEqGa*MZ%T=MEbo7z=!+McR^2VYFQY zxuU6GR5C)qhqLtRk9`IA`xON59HA&fuY>K6P0w$JQ9;y*UXg!11uJM}&@(*VQ?{Y_ zkSne*F%xp6#u5xXrX34@JO~UW3{&>3L<(FdwUf@IFqP_2SITy%# ztT3QJH)@dtGE06D4HNc+YJ9GP`_W0@4wcxxp*yrS{@)k$Fnir>{u~MH`u?BeBvoxX zGqVG2idy_5bII#y4anI$2NHkB*ZUPIZgX5u47gpMoO6n{jF}dAcQC8Qe}tOdI8o>O zrucboF>6}XGm;L9*u2{JR7r1#HP^c|aup>XvID9TpCGy7O$B~0JV(c3+V{TTx~7o@ zSFBFPk#LRPE#q{H-{9=ZRhz-_9fnda>qqDRrWKu&rC z^Mo6TNOVW&>vswx1>Vr~mTpr^(GBEm$NW|29*|pEOZ|fzr2XTK^R#1JN0$%(NT7{y zO+Dr0Q)5p7bvn0%5^QpPsr4Wq4nsN|G0G-ITpAT zA-9PEZ!d+C+iWk;abeU`aO)kE$LrjID6ffsCU4*~*Kf>lxMr`|k2Y;u<()acG)G=; zAirkQ{l&boM~c@*C?M=(-eMW0K@}s(%mj19MDV#{BAx<&$Vf~qj)REOpg6&T zR~8M9H8#6DQxz`?;D{G)hCxWe%*7`d`gPBidlVo`{D^06=8zzyGzuxT^b>Z)2z<-? zX@u4CB~h(&#=x{ReZwG~FpoQ>zC?yLv_`~&hgYq8G{uT$__3SxcvT{>19JXVHtI|o(W1#pZN!j|X{*gp5?j<0rNU7Bb;3HdQ)+Pt6Iu;P7w9Yt z#HzIRq+j7pX^QhogsRX>K!-7;`P8C?27*Q9HY_cwNhb31;%@R%RiGlWtSD!d_GB0yj5 zQW*9ST_wV#Qport7IO7@fD?=ul>d&;4F{hJiTjXFtgvvW*N#Ql^B8H|1@0OUycH!{ zN@P!xmm-nvC;^ENKmqc`G^Y#g^01*oBNM?U-qlS2Ne-^&ljnz~u>_rX^wDh&H_>Ld z)rF3hbJ~b@7cGVF+qAjT78$a@T6$0ZXCdtL?Z(lyMmXk-tfwt_M|ka-k5q@VP0TSg z1<`+S4fU>$V%GyUA%x$ucmccPr0|-C9K5A}U%MvHOTW5!nZy2D!+s#a3^4`^?X!`k zcM)#QnNwi7mZ@3iE`yT~^~QvunGbY6D{1|6AN=?4XO{5fTZqm|a6)T!&9_rPhYC~&BtM^OqSX_{PA+>b68?y?C zP+alc5mq~YrDB{Kw)jnEakf;Mkj`+L)tR$~AA_9U`OGk6inw?73$KwE)cQ7_@9MyN zys)6=rB<}I9V{6ji16wYPhP9n-%pZmkgr#sB$K%`EiETEromlIO6jx2D?ct1lslmS zz9-pc8KSchV{T50?mqPN=f4`3A)`H{@p%d>0*Dds^bFlgVa;W8GNe@euNFX?JUJnm zPCWG9+5rCk6c8M8-#+T|Gx|Z-^r4d-Q{eeO6_4*Q+|%YS)rezjVvg9ZC}O}-@B`o0 zxB+YXdxcp$h`3|@%Lketj1I+yr79*QFNB%32*4Ih3lfm;mmms$H7siG`%ft52PDSvo@9fhCsl|ZQc1SPIvXb1;od5?UrG+CzFUpc zR=}~wC4k`*kS0Uy==B6W)1fKSMDuzUA&o7CnZ}WmcxG$waCO8ddhiBAfQ=Y%4_Mlu2~L14t>X194rwOuLLF)z~5vb>b$t0AD; z6t_`Y{Q9%X$sGV;xEkA9Vw4eg*mOAvrc&Ly5!mh75IBo{%cANfIlMXAQ5mQ$I1Z_j zL&J}G&Pc$fE*u6D010xBWSl|Gy@|ONdOSxgcoJ425O^`M=QDAK2H{TB6m9{bSP*O~ zez@fW`RX)`VA)&1r>ky66KpM$YI9fSTMi4w#R%r|6m-pPxwGe_W_Ynl`?*KdU2Dy4 z#NC6GpsYNnKBK`K5x3LYqFui`eeZAg>yXy&E|BGyD{1iRjRBMjG?h zT4Ngel7&{D-qfk1B`+4kE!=tn=yTnnFdW3X7qHC~K2f_DMt1l2$%Mb~p|YXoaKn2W z)qzrQ@7)W>P{;+;yvm+NI@Pi1{ov|jf@G2bj2)ap;#>gTj2N5r{s|b_*o6#~%qeYG zmEPlk=JDRsSO9xRcBc=P+l@z0AFU@%jpTZKD1Xpwwr(q-y&5k*I}dRp?Aaa!zCghD z+@ZvEhu>CZ+H$$#85n`W3l_owVxCs1F&a}vPq@J*x&^}R)F?xai`E~0CxDCe9)yGM z0ts*r$YY!W^4Ej~<%o26o(cslSp_}g|DLMh;p68K-9Ip!2m;kWNxpV7-CeO(K$%DF ztTAIS`{rl$h7l4yRbHy|_q~UB*eG!!(oP_VMySa2N0k}u*uxTkLZri+NjngrNF{L& zLQ-|)gsGUygP=UxzHJ_>05xh^AAE8ck7&{P#bS{)h?`1trI-u3pEnDDzvgTr!P-0i zv{c7@g>aQ>79hKO#8n8I#=ypr7`=Bff0om^ej&VO`t1~R;x$^P{oI?7{1bEMO@LB8 za($2!xkId&JnGN*o$|@{-$$oN_lQo^=SZ|y#nelD)|&nIr1VZzS(Rap`-hIUp1$U2oHxm-H;;TrTBzJtg4O=7)j-{|?ECEG zMab2|miKmxz4*ClE_af=y+!!aLKRNEa4HFnr_AqVGiJd7Od(U}>2>;kRZy<$yI8N_ zD5t+1`%-Q3GUH^d3lpWPp+#86SME$q@Q+G~mX_1ckwYU<-jhE!5f7yNt)A^w?dg!? zC82MJ(yc-%T~pSR;p6es8V}86+s=BbH#Mj;46?ucioG%VT&!3!x+FQFPX&!3eSY94YP&PhF=C3ur!HnG->F!d~QZv~sm#q*QS zhr3l)O%w-edm4dMwB@rodUhS=sj0)qthDz&V57_G?QsKKL}J={hD}YHqDAK4o;3*a zHH{?H*E#u9+ITErnR+(&g1CR+39($>)JJqmF~Bp>yMfiaFy}%4?u#^H4R(RBnDXp` z*hnWrL6G+0@t169n zzZUmPSaQyiR?`>~ODFB3tUS``oM}(yN$=_Xi&x1n)`~8|(ZW$afPa`f4~zs?W8|4Z zvF5at+x#W|`c)9xI-_Q-*(`0k89B00zI-L(nFcRAhg;pIa~}83D~VI zYEClYgzq!+GIx<92~rU+d8MP7o%o%YYy!cu;`!Y~T29A9x6D-tet^FW^l>BdFbJIe z^8t>M{7-MBWrBU~R*kB*iGaI_H7TdIjW)ph-=l27iCvrTl_W*)>yOM~T$>ATXzsp6 z!`%u}J3LX&@uPfnQwmf#1l^*w;RPV(pdI zxfXP)DYq(buk=(rDy-vYlfuUk_Msd`v6oSFFu7=d+#&l!U-@YF1IYL&niz~+CIlKK zsNQ)pDD%SfZ`%8?gy4cfn@xh4iYF+U*;V7Ic$bKbLgILw?Ob8mo`Js}84%=W(Lc+7 zKI^_auUZ}z>>uVR`F&w4=Oj|S%W!qN^{YB=s?BR05i)GXty@}W+z|{qY#d`K=`)wQ(jyM5 z$052)oj01QxmykB%yG5bIm&iV^u>w+kW?i{j^2j(J)q@cI;)5_E8+teU&2L)0{qW@ z)p1b5IEMZ0KAnz$w#Ew&+Z@s7%wNJsbTv^v-&JCnds;p*Tjjop5w0_~^EcxN7ynt9 zg;Qv5;aue2yO|+BlaucD|Bo>7|Ddw#Tj|dxC;#{OKM$MIz{9-mF9~Z(>&GGI%gwqd z-l8OH{NIpK)L_<-iqtvKw7}}0u z!}EeZNYUybwL}T&h2WpLzc(+Rnj?q1I#Bl`etxO7NF3CCxRl+TO7G(aq?42w^IX!B z8C!e4TH)BZIC$IDU+E$FpXB!2;@?|MFbG}=aS4_wAX>`ZO55%l@LMXIpxc|y&|y$C zdOqhBwel+c{ph#eIDtTe2~b57@K8jS)SmA*QDL0OL$dz2U5;xEJtx@5H8XY@l~5dx zi!!4VbOl)OMqI_`InC}0xP%3lPXLJLt^SU?(AtRlj*SRlnaSUK$nyL{9Wsr#faFgE z=pn-qVxVEw4oX&Z;1cCz5VC$7xYSEMr~fmSfN6mznv>@b!(4flMs)5YAVB!O>lOcu zTj3Yv%zd@ovG+Zh@pA*u)gG--m~bi1*$+iA3ZaY{0{HVHhLd=Xe0^pUo|5W$*~&w2 zV)b)&|3H_G4Y}P*{}_FXGm34^!w2F~>D`TkCPKQhUxZ_w%(bnO<`zr_-L6L2dW^7) zHg!Ia#zV5^nUC5ol3dD_0{WesuPT+^4o~{Ll>mn=2!CGS>Fs3NBaXpb(|hZ7;&0vT zDvOf{u)u@usZr(=)UIbBc-9+TC~C3#<#6#9Qf}3H!3dQRsU-0UbrCfw`S;}Xv>CxB zN38kyvW{tUvU$W|*M->ze4BR(uP6shDoE!kP;ZtPPbSy43JSy~4KJyMX@v@#t)> zOmoYyZcZ-Q0U>148=z0cU+1@wf5jYQvGbrd>5_SKx#Va-Li>am8kW|@O%&dRIEJf& zzP#66jrQK2c@%K0a$^qXpcEH%rmtaLQU$RTB&UN>4XaOD7BNcjc=A}+RZ+lKM#4#;bGo|)JAF9l_}dul%ue_K=h-d3HU?JZE#~s-*K^I%=o*xf8`!X zcKHLHN=v9SR8x}oZw`s+gS0aP8i|4_kgE{$a&eIP8z)8J1=P@a-X0y*Cls)#2PCWj)1&C?;n_CT2ceT-dB!m0v z!xcPw0Jgh~#dt!|mwkAf04|c1b+|(Qd)5SE%pkUE3#O(Pe1ZPZYoXmhykt0RO9C5J z!mdwdTeQfXutC#K*?)*ANyTD7exytUvdaE+eqLQOM+GW!oC|XB@vaL-&<$~wL&2=0 zc<5J7cULq5MU$%6XokC@co)kLmKGLa0Lui1Td+{3Q2SuXQ0l0xN!c=}G0VqXEN!(? zCj7|yxgz$GI8>r`4BKj*{F6`v)xmb%V6lI!>06Y%LMYQTP?-|$$^`#&4l>t!<1}Tt zfznHR-yHj{Ui`du>KiYn`)*RQJ|!)B%Kg%@-z@rRogV&sh1*}l@5LLP;=byR&0>CF{nRxSk~QUQ z()kmbm1qZ&`9kQ+2l$+G{hmf({!TM+f#C1k+U;G0+P@2^|EqH}?8JS`pr6S?)}b;d zw>Tp?Q{cw3_#k+k3`Ci>3>&}ho{?b_@ajc0Qdm!OpSmilaq(1fn+kZCn(OQzm`Z#f zlg#iT^ln|f|BX7kre&nWGNn5yktyjSCltjJujyOHt57v)u6TC!pN0C^I%h(%iar2e zr;1wri6ZhxTuSeoc4$ars;2K#R!M)cZ|iT%g;SvhvF&}S?xNgqdNIJMMOd=fH{kk` zb`8oj8%s#!Gwll_!**7z(>KFs2p{96E}EYVCZHeT;QgRdf+wq3Ss`V{vOL_`)1{P+ z4Lbvi#8(1tBhjM8EouzlJBNC24`Rf3>Q{FS8P=KW-HRPg6vu$LWaIvbHT&%2R5&U- z-HRDos{T0wcv=cu&lo{_ZyyG@cM)h7$+ zG0JI>{*So@sp%uOLxG-|MR4S8C%%!jMC-Xf$7*Hn8=linqbs+OyTogMh!4y+bR-fY z;v|*De9viiQv@jKE8+;)-v}>$I0kC;^LVVv{2}u7%!s|=JB%n5p6m2wyIldfnaA<` z@m;GXmqTH~X=9v!qTt159(O?x`dNu*;_a;b6it_5{$ykyikFn-i)RNN)~~-JFLF5f zwm{MIWtexa10lmhyerQ>o)EeUroKjtBRCNY85R9k>wtj4fEKP35M*YTic5?R`*BEy zSnWLtrUo&IAO|m-Hpxmg9HN#~n)mP-VH~!yjZEj#VA|YL{FH_^>+t%g8swEOV+?Ob zDZvQ_JDVE?B$;}{N0~Mnh1kwk+2m*$^VV-OvqF;F%y{$#(`|D`-{)9+CRzkfRSPib zjx)|p_B-B^WPB)lX=WoIPZ$+ZD_)yB2QE(p(t?6^l>3?-+D1Oyj$uQ*KV%e=KEIPu z5bemuE#>S}w&E6KD^ ziUTz}CXd0PM?$zoQ$Hi^98rH=Us1qdEB^{|%%mHHuO2mU;U~!JI^tG8ym7Wg|{LPW@4VRk`4Jv-ZRb(u`S0s2H%4M25Xn-qtJP zs|a=d%56>Yk0eF{JpyuffVAxz;nPiZ;Dz4UMbqD>Zc5y(n3M-fpXmP?auaX&!ZX1O z)O9X<&NCXd>^?VF%1H+fiNE^7q8WpuXY%`a@ngknH?l zhT;DsVu51#WJ0_OlCEQJ3OtIjXOKPXnZFU74jg6qH(E7jGh$2gps2##rEFRvNXyU)4$8&4mis=DMU@XY*%jK1 zW@n|Mq;vFZ(1!mkR*ss{=MtA&h;21wjl~4#a;2cUTu4kt=zEqOF_R9T=((A>_yvXq z|8nP_ksSM|L>;{W*8?la*NOFrb+6-$XG@h70Xatga7(6!F?TBv2gg)ajIN zS6Hhu>v&aKa)WFdVg6A@73ms|9X-U3*ijB&=5zrS4MIz%4;wT#FqBFDIriKdWNs4y$SR8Vj8u!zbez1@S51ogDTox%91bT{>T!$5UYg|nRoCEir+@Cf?!8~13U zXr#k-H13t$8BRdEnKYp~j5`&U0b3Inhv`d;yucn75J!!+nk-{(`3%rdN4;eCsRp9W zORJt6FKf)4Eh~~aTGoF6;$xe*{3!V5AqAZHf>VQOWXE+?IULC_o%)$kE<5k73%Bwv zPgUM|QxL6_=4QdwK-$lL1DC^qu1OFrp1>pZb1ZT-ilvtv67e1zH8;1~a0ZaZ{3nAP zOBPYN*C?~~_8+PsP(yp*pSeA8IYe+f0=57m)=p-# z$SM45&z^1C_I0&t)Xl4>j~$pb#(!E-`%PTX4N_l~Q2I@bJ@PMKS{|eC(Eh6_kFLvn zUo2@RD*xrZ1B;xh&!w7jHo|D9ZFUajAN@Ym_QyL`XS8iW!QkLIsQcS8?i5g?m6F``(I|yp6tvsliBN8@>_ME9v5P4)$lvyU3EfIC%(|T=<<@s_mC>)2fo__ z4J~cO{qv*5%tblc1-KT=NK0K18|gvfalZAlx#e{rr){`j`fK0aSzmgm9-QapAlg;* z1yo5GxA;Od?%)JVEL1Y%9j>2+e!i317$-CuGCM*)%>nL0LR&`V306lqd0)&pnD%H; ztmL}?NcATa-vWEtBSzi_M-w>7H4?A!1?mo9%1$nGac2PjD)i-r7tk~0;C;02O-6o5 zvQaB_(}{(5z+x7PO&tWDY9eBV=PiAF6p}OQIx=zMLyD5rG<+x7QdIkkClvOy#WD&z z@{}(`e-=?vIGs*^S@c*KAp{Nm-ZFB{|MLpcG5ak?@6k*|nA7BSH#|bT^4zcP*WJf; zbe4b^E#kbW%XoRN=R#)z+Y+cIjB3?6imy@NO7oDtm+@}C05+kfeC&N{K5ud2%TtTb z=BKuT0RJS)f~t&Z-^fH+^G7clufSnn3rzNFocYf6gU_EkGa*Smmn-tzA&JZjNT0-{ ziEe);N`02<_xFcdk& zMpgh&smZm3hez`~2w9NFd|*UUckTD-C}TzJf!?VL=lU@%Z?ro!O&vOuKDT!NSXV^K zj9-D|GJ5~5{GPJ!it=J`9L28hnf(iA;zKc5Q|X!Kf_uyEQs9%ySFL^{t7SjMi&n{h z(=jhFoXi*B8uv8O8Y{!6X{kITd-nqq(nl2KvKDnll*O5 z$ZC{9mx6r=6gy%g=1`mS7Vv3xmir&Qh{CI_80l~`;>R}T5a<_+#%ivjZcyN%PmAss zG4lj+^b>%X!j2mvg?u-uuS^5pP}h!aoS9s4nof3_<-n6tR5topJHX*NU;ln>y@Yrq zK0n*-gSf91iP*<)I>kRmMG%jxjQOzv7ZRn@4>en2@z6g#v3UeZm`NXEY}X*miK%%2 zK`wLtZU6kMxrVJM`>mF5uPKJ_4m?vQIB(?9uqt_LyVt;>{-ikazmnYEuJZ+ogn^RS zN;fIL89u^`>B%q~$)=h{xm9DW{n^}Ic!$PkQ~lQzWgP~Z$e+Yq?1?X!nwQqu-#vcg z+G3=0J>R=0+Futm-N<>pj&tO%Xa3lzuuTUM+r~v??4>1a@k&)FeR4Y6CC)(eKW!xC1NGumcf9ud5d`Z3G$XO!-;$DzS>xv3 zC(`@8($j>ACp-s7Qd$NMZ4rgN4-~xH9DTq_MqRAm;Wgc9?Sf32!3VPiPTMZADwn7r zAf2Aj{j6{K+noyHx$3zxSt|Isbt{wp03OZY-CM#5lS(v_cLGVg z#ES$8)vqCz_BqfOU#!{u@yZ|I4#y3lAjFktN)w8g%S`EgWs{sOz-&L2dR;0OUZ9*EIA{P*JZV zFKBCMvNUr3FL$oHDJOY>UO>d|4COtjHq@TjEA^ zyLvtf1fgOf!(Q9F-D;mW_M60BQx?IrAd6(e+X&oQ!3rF_+rG4T@Nb-rMspACSCkk92&R_5yHmTWv0&}#~K-8bI%I|(x-gQn1N0$&u zp%S6k9$eaP%ariL@lpy+KM%t=P+eSTJ-{ElDA&NW=0Si>wzJS+&rN+6_kD}4D2RrxLwd8nZmz1%QE`y1*XGt&$D1R9Ze5pPr>XbMb@`;J7JPjBZ zW_dVAtzEfXo;$zNsxVNsRHIA6`|Rd)$Uh*2kh=w8)+;HXEc!s5fj=u-0>LGfRx9If z9F>Boe6K{%Wi@J+qQ}|QU%B-o!bKkMphcu0(fh?zgGs`2VfV^H;lEqby6BqO{q`Xb znz3&SC*?Zz)-wwh!H%tX$$*CFa6yIM)X{oz6S1KE&%Kp6Epeu^OE?mHq7IVb@H!0% zazAErwU!|5;6w_b+{i@-hY*G{)kNH!(4>PyUh9h&W|rf}IyCJXqWN3%AFySe2S4<6 z(VACgVrd$Pt8cr@-_xNIlOG%RFn@ksxsdq-#$!Xf6*Ag2b=YksT%>_Hr6N5W5^3#Z=%&Xr%nD<75>HO%XxWOqFt-F>v zv-@ruQEb)+;9~VW>@ndMQ!(w=H*S|HGXB7gc^o@|l^&=zpjC-wlC#Hm@B2?FD$}Kt)lFpNrnit^XBbYCtzv z$Y6@=0GMd4HKa(m00j{5j*Zp#TxZt&YkWr}>IMot%lUkO8P#H1JG?Ngzj{vhvD|&; zL^Xt~%hA(Pr9yJ+=sU427C&Ean+;G2xmF5?t3+->16@lGx6X5snmF%=sdU`+`Uj^S z12nu93^xWO!Jm1atwd$%CYmDWiFP8YEeG6g^LT9Sd-gX^KS5Sx=>riD&|;MUFEG9I)Z6q%7qXdq zkymih{!-AC-+9(7xQ5saM?m0{aW{~|d>Ijkw1M0B8&j%EYv$FTj5ybh%oLSW^+i_g z2U=z4R`-&A1vd=Tm9I29T>!mi0jJt{M5hz|nX?L*2xnr|GGb*9zw`3|j`hCJufDOy5Qg+H4`B53PexC#5#f~(p@mPtH|8WuG--ZQLbjgwg= z07As&B_)l}gH*IMN?Qx(;Ie7A5Q}sB;BayhZN;YvRa;-eAf1(~_`gIGPFSUP%IF^2?gob@A0Zvasd>2s;YJU*gV9FkyHWWvpxA-cS}D<~K)8FrQItZlX_uo`byE`+M{1 zBGhd0hI|)>j;_6mc=E&t22QQ}dI_8=Ek#z_dmWL9r+X>t4u3GHefdiVVaBU&yd((; z!hTBZe_|rO@fQvj;4?>`vVoYGyWTP_)!OHhf|29$;}5-frhBr+L;^8=HC(aW7TJ2D zn|H+8yyEINUCV%D!ACy6R0_TP2)zWChKQSJ-H3f}NPi!ugHl6Y962{TWhV2>wKPfR!@$LB<+ZL z=K#|!#VP6%MYcu~S$I5xaAP6^HM&KLC!QkKW}LFnLV8mQwMYP)?jkgO+`mNPMYPu~ z>@09(ary+}&i86!EJ*7au757eWz#`Cz=eJ&lFbILkJue}{+(hSozt`RrZ7DeQ{`_?7ZEwcI8?s+HnIcPeMeL5oO6>r*n`+;1&UB;Y2BH*Se68e%e#^%etuUk_;=G8vzNdST1#JX!OaX=_i$-xpE z6nA|HL$vO*a9L?9dvqyfD*{E4ZZ76^L09+NXm-8Hcm}TBv1Hhg0^2p>#O+u-SPhi3 zp*Km(jXme!5gb>Emx5}G_x{k)hdJL$vdgOtiv46bq}o3_@oNO&r&6J$_HnqooOVSB zH_bSqk-`Lh#5G&uFxkSzC9q@QGoPSsvae~dX+r_zBL{*I-rqF&MSS03aEk**iNnYU zR#xz-r6|5aaP!S*dajumL|GwUb(Jk+@!X} zY`#&xX$54tpqzXR*|zJ`wHcZU{OcF+H^)$`Qnu}s!?UTa`?&YtS=;9L+9kb>-?y=v zfJyv>IowFiMke;m*@#FrLKN$sk7es&r*(;#d;h+3l}Eq-wl8J)9&}DW1O=eXkBB6K z%WHnFK7A{iY$}OJ+nt=pd;U=DUjFWj;d=Y+sJP3Ix*15TPZ&crWSK*MUmra_JMIM4 zLs~Pm?_O@wJKqX6fqi$IAxX1m3xG6opk(i_%m%z%XprLD6m|Vk%F>Irtza!ay<7?shkZn9czLT z879FC>#D0==!BEEy@JOGp*8h#LdbL0d`t`c8P1ooG^@9B$FhP{hW(gEcYOBa$gBEi zd^Z_kFFubhG1_U*hp^S@i=f9p}!NK}+MwFmjZ{}ButR|$Lyc}_Zk_Fc#P5%VdI ztGOZcutXkV^R|U6*a#~S7z3X@mq7Iv3#Pw3;y>YEsbTlLoeGd(w7mSPaPIq2d5YeZ zc@eo-Ai4|;@~$K@>^s!hGay1;uWJGd)J3_dFMLI=IE(a$Uvu>FH)dD;9R)AJ{#~1W zTa;Zqx9vjS-V6PZDLRleb`V+6iH!E&XK@1)EXFbJXrvCZ$iEHfg5>AKV;}sQFqy}~ zQpY?!M*<7&4Ivt#hM@&>%cxf!OZKuo0A@@9`c7()gaToBwtloa%uHfoj_eF|*mNTO ze6Iux860e2%R}~)NcYwKp!eX>r9oR;)vL`4sFCYRtI1?IJDXe8I(n;tG)|w_Jx;#d z%a$!qQZ}Ix&g+p3WaAL@J3CE%&C?^@;mp7(o4bFT%9}2F@9tp+$T*yjfkUeQ+~D^- z7Mfox1oSb$ka&G>9zdPB_djR|e$w6>v6o`jmH5TBEqp~_-ZMKpGQQvy*c(V?gx$a~ z%Q&N0v%Ta~&xd4eEgpX(HX}HDez!bwEURqcTyajcf`dc!wL{U~tiFn2ape5&w{ z8v@uGUm9G>G$9RkVPY5AD-PF5O+{3|rGI6Uf4&39V-PT%P^H_e!!>@+VEah4Jgv?5 zIVLo%6os1ja2y3SCH-%IJQbN%34(&NOhChB>wv|+mTUk9WHqO)AmV#TwP7jA9tbpA zfQ^&*SL~b{03ma+Lqb_R@f6sWF9m zmU?2xU$+sdDrv=9lNN`Cs)a;70#SeV+)>dE2V&EYU~czq7^+tmF~>RSt<+%yKOnPbCUg_x|Y`t+X%aelL}w9d}fJxw0K zx4nP0ezn2>IpaSc%q1Nndj9Lg|7+P~-TkqDJ~wCG%@tXSxyh2E*G=mVH0%_(|^&w)fCO_T`uU~uw15TPf$FO!|cvU>onSA6M3L4S;$7K z3FaL|HP`s9Fi?o{k1LraHAw*%e2^0%9NXaZy4C?JF~eo!@>9G{;eAg0tdMU@DxYJa zo(dg(&tr!(-FJ2J40{*8k6*ujWe@$+KX%uQHxhl8mq{hYtr|TI|ErD+Mkjs%PttY? zzx&Vo!*^Vo7OO=(oms*0cwiI9%o*dcWj-A0m$BjF91QovwN+EN(#q0?;;sV=m*Wq9 z;l*|#p#zL!D^Mk+Es=%NPZY>3*<2PV>_$K0wjnW(JXN^uw^j6(!`G|T4(V2YP%Co88)_-T7d(DxT&e zMRR*NuZ1ZO*StZLyQ&>({nIYA<-H&RWdALxWNT|&9MZ|JSt(K!CDuI$rD!va>z4P& zl1_$cqq@gTwlUN>v?*Y`jHCQtY$ehE^j%>!KNSv7;$;e(6nId5>Ie6r1kn=P`n$gr z3i|>jU5o9jR=D_s=6RjOUfazIK%c7xyCp7u7<9th#!U=^35N3HIu3xN@_5Zx-b+n! zD@=Q7%13NgQ(&78?gO%o=y&gYbQbdK5_0Rrawa@Y>sON4PWuL058BKF8&%5XQSiFV zHM^ZS*0N2~>nU8h-!*e>l1R;W>tV1Bq5=NABZxls3(EMw$gKfJCcS}9M^Lt<>ipMo z9*}Xe)jHUVSAf>3VmEIONtm?6x*#pFMO+}+N+FQ-=mT^kU4;uXBHev{Lw}2dq29td z(q`<3AtaYRJGz5=aphBfSN?W#p4Q&3EsD10g1%`KbZ*4h--yg~WSQ^%bP?KodkwkZ z9)D2S%A@UG7*dYtI2LKONVHRo1kjt>mq|Mj#KKAV-j7-`I`TN_odkE8+5+vU6^OV^N zIX%FUhv(1Wy~&3@0`O*hY8%Yvm$%io?UD1fm#fNFweI&xq*+y5OuT(|bhHcynm@oi z`eil(vOn^bfI**!ywB^_ucl(mA?lBI7oxU|ur!bNM%rPJ8H=kSas7Vs<|vSHo+)P6v*O<4m?CYvYc$qh z#;6Ty*26Pb}?B51QQ-8P0-2qIJjId6hW&I4anRm@v0F}&4Zxh z#e-9RWC<{1bX>zi8TR(ZBck`dftC>k7p5=z&$51!t9p?A zV+a{PXt}R-*?lURTk5^#U+mrAZ;M}9h$59?iH*{bfF_^Tb#1(#)IM2ssZ6e--d@*9 zepXh!pvu`ZgueNL9Z3%uxp{4(iQbo_JZmF5yz&1)+vCnyi`!%MBtmiG;1zU6YdPe~ zmAB*0B8yD^(@6N)C=B4D);{PlElz~&6A0CP+@pMvWWUP)X|si;sP#dW+qI3xC(o^I zXuV&Y;Vje5=T8mSWfPbvjMuiC>9Q2joNd^{7|8x-76Yzc&Y)p~o#SoWBH5_D$j=0Q zkeX4Yoi}zHFhbBVI57~@fB73*v~WXnnijpCs{NDe02qqPnF@>zH^lcN7TO$dzlfv! z7uZ~MHJX0JK?&kdGD6+p6hb0Ppg8u$5Xz)l8PSoP$$B`BaQWdiM6VPgu@s2fp7D=> z6E-U&bG-dW%haFG&yi-;19sJ`O8O^%fYA#q1{M%7P4iyLm!$WpAL0<1J#KhFLi`S) zk^1Frg1wj(q0!I)ceO92$K{oswj*+K%%A>!RY8YzgCbgTmN1ryZ8(7mz&{XiS9loW zA|iZ50bm6y%+hY?aT1)>qmwc$eF=yOWlO?M_zOajm|jz)fHxRn30NC8p+y4KB8_Xv zs_Q-vFNzSk-1yDEcW`j=lAG#<8Cy?K5MuLU;@J-k-Jf$26X_1SQRr{qXCJlYB&Ajc z7s>v!zJ(2)|LpYv;a(l;)PqB%puZtauDduY8Gi*xbb5Y9d?uz*Ae=Y=V5Y=0md56c zL|W_Dg_8*_Xd{ks?J0qZ?|WSJhBJ_Pt=BbIU{(rhix^gK z+p(M)#TTeEtchY?cw1;yA}{X{690lG?p?T*Rk2HCUCpsf@`tfp9ZQ(kkDX%fSwVY@_K-Y15cBR6ZGD4( ze{e8yl1x>f2wZ_d?nDTicp{gk*fy&OV9Xw=LO=NW;=Kdv?BUDe!F(_AmVXH1)T!Zx zV5R;9o5_I{B=32-n8=L;F%*cYRWL4$ZhHWSwqfFa<|~Er*06Z^wix<4*_P$-4!Leq z9s*{)Pk~Av%ObQIGNBU(4rm)0S9v0P!qF&KGfaXz(=R`Vg1epUr?5S9);?41%B(99 z<6m`-(?@a(D^cBAgW!Gh{OcxHz0;k!KW`>J`K3xs9)HG|53Hz9Vp1a)9NrWt>4zr? znq!LpzyQ529f@2(v*P@OLCB;#wF#T`FH=9XfM&a*bvn1hK~UGZSLS~M%>TxgZ87Hc z+`<0?JpX&W)}-g`=AA0w>;v(9544L;(L~HO{kvC(H%?Q+mpKWMZYD&@aG5h=*Nryz zlpTS|;EJ%6W|NDF0)%0u0=YP$OFUN}LPzt#YZwVB<)Khw=}fqa>a7O~RHn4ouming z(%v}&>&PGMa)Qe)N#4D%p)?M*z7_oe#=>Fasd-RVOsX=33WVb&GQ5gwt zf_NPfv<)BcpPZciS8fb!Cd4MVcU_7<(rdvoHPH-CoI{0S26Qgyax}=h3vq2e!Gy5+ zHi7>wWAvp8p)}|)qJoRoSqAn@^x#E9*>zIdh>x#|B#|`5?C^Gk;MIR^BRNVBv& zhB7WzsZtGds{{l?`C z(GTiG*~-8VbneektVb>xm5VA%`*01L;-ycFW>akM)-AM9hOmkHHdkm@ENQf|6+mpI z(VbvbedYslVEb&b&QCj>VHY@gOm;3X7T+p=xxWg()30Mnkfwu_v{=WJ%%70H4?%FI zXeRR_ zQ&b%3WE1!^HBNXaXH->RV5ElH#5$Tj4L`v;qh5hc?niS=R+@G61xpe6Pe)GlvQpe; zo|I)nId{HG@u-UzyH3wMviAf)#feq{V0ty}lB=!a#Kd^}SaUjAwu-1QbF_Du%D5md zG4lLd!AwS~))z=S;g$lMdH844%B zHG&sBGE=A-g#Z(QSZiE;!K#Pn4G33gKN{oi0+tZ+!ZD$5g78jq%Y2P>V9dBgwg%yo z<{U)<$(uH(yWF4`#X>zFx2SFDe7zm%nrJ(*SlfohrB)2+X&X0e-jCM)>^K&^SUt+U>g;AUU$W8B|1kCs*dU1pF2FrMI%2 zjN|5EWBzSYR`ObW^BL1Q$2Z{c`f&bvvFP;UyYRTvhWRS=lX80E;>O~5GB{_X5{1Yn${ff%{0br^{hcK9C znUY-FQ@EazT*p+##VvP&+RE0Tykmv(G5%i-k2waS-NdB!bVgW9t(SQ)`}=edOzLs# zvriBw{Lg6agT@iNfbP?zws}LHqLC3*8jt0LX-rc5*(YgHcc%S9AbWq^yLq(UXy;=t zx(C<(4`yp%t)TU}`*uXKWbN}VIbk(7-Iq0jEv&e%G}JwAkLH;uqb3q}ThN%;yMp0K zw^y3n;=?TxyY~D#Jy-K^pVU`)_ttW9{2ma}g;(ACoB_ETKVa~R>Zn}Qk`UYwY)qI< zPL<~3hyvdjxtj~`s{;_riO~TG;m9AbVL#i5W%fni>kbrUUy}Xn06rf+GFXTldEETP z4!M8xe_GvqrIdI)D061^PB>h#E85K}3?`;{OpOra!XJ*!=WLz~2)=o_m1#K|oc=yY zB5A4+tdS~un&Qs7+69pGJgWZN)qC9KGLiMkYyD~p z2orwYx5wMTeooq$BflJ%-wI&=i1f_+XZNzr!eNBS1yB5T85EIa?te%rc{zmlwxBJk z3!fN7b}Jo+9C2B^MIA^607m)_fcHy%>sF>Zx<-mNH5gW7q`qQD{9d07p5G^-ON4;d zsbR~jU&HCMJ%hne$LUl`q!Hdml884>Bj*V`!<26Ol$&cmp?(s{EQjZwvo^WKDhbv1 zoweKtr?un5419ml=G{=aYenf8EWKDLEaS>XSk!+Keu5#y5`60@#B7-Ug`l~@vA0#{@0aj(!Zg;hE0fLjs$b;LD;=@tI!gGWC!(h3@G z4uE!jssOkN7@&BffsyoR{cg|jMhy1at$-K1hi(B3|9&RjAawx4*$MA%l)W{k$e(2P;G;$Y^G~kre5v0YrwDjzRy{JUXV&S36LHj+4G59wm&`SNR z)Og!_=(H-V!)#%KVDaO@;f?UXFq(K4x0a%`#(rwXvLBODAoztppS3EJd zPu9ZgMvo6B5H>7H<}xFURO#?_wr@eZzA|$S0s}sic{*0|yq4}x(UJnAb~KfT4*cOF z4V#!nF9GL#y>|-VL%9ix%XqYq!%0uh;rK9;aWK*@Sz}Xmtiq*gikG{O+E|K|iU8J^%RrQEI^(!<7-M*$ zj1oPLoGepCH6;n9NgjJ~Vi$c>qiSG(G)8+H9kOX*sNJSCD7JO5TzFwt&J7@`eBt zpG!cjEl)Y)=-G;|lv=rxpC--Ek<)iV&nGF50sl%Ukj1iAQ zCuCUQ@qT|t@{}^av6(P}ptKW*By$JCL4d7(-IzWtr|oXS#$lhq;PjAy`Q7zomNV_6`}YX}2u!2pHo`?BfY{1OpK4gEN#Yk^ z3cTD)Jht@ygjVeFs((2h#3~q!tYD{n=d-NRk4V6J_g7#5g+M z_cDKr3~WJ~zs~w_wfk$5Fm3k8{XbakZDNC*Km?hjVRZE^px+|6~#ptcAmL2ai=YMYd z`EQz%Z>oLQs&^LS!4m!^JwaX<%W^mPu9E3N5dJOUDt|+)A5Hxp@>%uf*u`7Og^Owc zw;Gq~2fqS`AG1lcXZ+h4K;mscF5hI@EH+je(;OYH_O!y3dZLFO~+JY!e$)wU&df7g2wE}w{csttajb7FI1Ujjre3d?b&Mm zd%8t$?nqv*tQPQJ4>0NUBXW^=XcZ_o*+Q9ObTKZtC(wR%vQlEN47Fzu_{E{yWbyiq zt#kuFJO(}tv5+F?eAT#?*CFl)T>I$!lfI33c^rKrn{N;w5EjYr;oN>O+D~UnL)=Y?HhnUI@7_diE9Vbb z`>%#^-6pP{pQG22Wp-tz1ARQMOi(x%q;*-n1hB)oqXa9c+r>pvF zX3hZf;TNPgi&X8*Ms;g^Q71!?p1|~hLTKdY9}@4dc}0~iLzwry3NJ!fWH(mycUfN6 z#85c>_`z_RIg00{&`)7$P7f4E&DRr8{6j0Y(SsZvHtGqG=L9IBDnE*0qTM93e6BL! z%eL*dZ>NLj4oPTxmaqz4gY(aw#^9jh&p+`$Sm{#X4S;0`uKQ8skO+QL!*CCO`*vpo zHB|)A^`qmKKlH4spCkL8IABjx0&+%JCP$gVW3@deJWQ%u4U;5Q^*dHe9-LN&JPuZy zIhS_*9Sbh&5gVlEhc=gCa&Lwz_@&4ec*QpICjpF7f-r;b){x~{PfZ#EJ)9l!VNIUetmn>NS>o&WzZ(tqixW)>~d z^Z$RO*Sp5+Afs=kr~5_Q&%;<^$V$Lc03}pj#-1$;v8S6?fJB)qS{|`;ZrPfFggOGm zU<<-~###UU5u%2YzPBRHrl?M`@Q$b&rLsd~fHY-1GDUh)*A?mZ7~xb)o~3yx3MyLJ zYa2RqgFAbLqZbg07@`j;6*_RZa&nj-lwVM#YcK}c%_MnCGt>rhxU%B)OTl6Cf`wO+ z%z}AYbLSL+o6*_~5mjvDGdnIPIDKy{^S2l%W8I9Zz?9<>SP)QUGXrBb5w;<(SJ!g3 zgmD(LW09*ARX$ODLU+z$msgJwX8|>&H^NN6;yBS7n^({ZDYlf#r}uxn({ZnOySdNBt#Oe&5n?BxWn4D#~@I9?(pJ)s$0ror>$7*>9u) zUN79T1?8nBG=e_}D#CJ>qNiOv<@GRRDBfJrlT8ftX*cu7Ua0)kGV#pZ!eC1o>Lzu_ zcb*=2hBV0S-bz<)4(^r2^4vtKziP$F_odU2E^(^PO&2w zXBi{Pfclj!!C|&+>)u4Vng_3p3gOh`Xq6m9FU$AkuT&Gp=PWu&akduOs;WsLlhT*k zN+c(>F&NFg58M`~4cI!kH5fS&5Hwe*96wQDb{b36k~6I~BMH$gUSte_hDT`+Y{Roi zY6<2-ixVGTZc(xb-Q7xPwQk@=s#s5j>d#S5+w8!XwEJtc?;d z?MQewr8Y;&t;Hs&dR6mXb2P`vA@wpENQB)BwV~l1;{y?YKA$kWU@u<+@FJnRM?@PB z!GQqNy>4-`KaenRL;1A0_Jqw0_GP0>r@?&^Obj^>dzX z3fsx~Tmh9TAStSzL4*Jagr|C}_#2#aO~tWa3PYmrj)J*vaiVy!1uSE3apFcw&r+vE z9v2sB-jV@KqApENZb#S(>hcn&#UQ4WV{;SgcGD<{cx#O&*EU^PKxsQ;|4Vp4Sir?w z-qJOkE7E(>&pxJkiW@`hepes#PV(lg?{fXKi#oF@`PX-B0{wj+bm{c=cjT=NrXKFGzF4d}viwG0Ix(F~cAs zUza{VpUW?K%yq*z)Gfq1)YpwfMxVHEpS9bSALbA{*d)O+dK;HfjVu{*3B!os^J^9H zy`)-WM*}Qc5-nyxlIVZ9_6YwPS@a)o%z)%scxo zPnys03Z5Rp41hm!CyGCi#mjT?215RNXIHAoRYJ&;*@{unTpA22)aj_<8Yv{J`Uxa# ziE6@g?g0gF4cdLc%xv_=hUMTk6}BQ8A?<5)Lw#;CDIb0M z^TGtj-z-$}Fhc9$EC>Umu8D>XDemE>H`(4VsQC|jRg=md6TWL3-FbYQ%QL;L4F8-$ zJ#bgKLD|GMY=@@Bv0)!nGLv8i3SB5E{JYD3IPar#y#5Ptb{*u{AvFrwZ_c#<%#xF+ z9;H?S>4}W(*%;IB-fx}(^*XzO{pN}NicGpDV2vCO?gbq(;p71e&t@o-9@JP-n}5GM z=D-yAEw_t@smusl0c^Dnhj{f+$LG?ZSWIa-LNf@H=bnC^=wQx@wOl|Df!^ix3ehz3 zd(iE06G1W8W9ofII#cIE- zkULEuL{WIa7+*hCqkcmn8Bsw<#yLPCoZzZV5;fJM`#gl>$(9(wZ#7wE6n-RPRxAC= z!Q9F}*`shFq!X8jkiI?)FtP?%GP18K?Kj(NF?c*mgAXOJ5{3Ad`O4@TNE4+I-&=|m zmpoiHA*-hS={h@%?f@g5L80i7hEu zhG|M=sp#&diIRn(zTDg+Lf#z_v)l{Y{wWjJm*|A0qqVTR3yGnMdOW4lH3}k#QE`9~ zuEy-XBE7ts(YtoW#V$*9xMe*il>FtWIw_~53}kG zM)_G~?tm{MOv9LdCngBCco$_Nck;K>{1%_pW#Jg4;A}A*FQOe&tkU5^Y2cxNbGAer zY&>6>zxRla{lXt)9rq066bJ$TcBNt=Oc@l4bt!ep4q6D|F7c^k5i@~-jfJ9ZTX!&( zljZ#ly`{_*)qb#i`jWqn=Z*c0&)iZal2!+@NEd`!M-C_n(cM^?DlQLWN4O0_w#F5{ z0u+if#4@$9ia2(-zEG!{@x~ua8^U6sp3o?S(*S7Y1=yegim5c~jGVIwaeV*0SdFXd zbH~v@ypfmtGI1ib48K-a3Gjda-{!RcMNIhz9V%$<{l^*ifBV$_&&sM=44rF>!o!j> z<*W0gP3z{UkK)8`^HbIcEY$BznYLrpibsw3%S4P=B9xTeN(Bpb0!Ms+HGY^a2PrR+ znvQ`m14t7t49}}Mms?*#ZN)GkiIHv3cK)k@N+yy6lp-%!kU&qn`3tiPWZz*Gq;`S8 z9gc#QC})*g?$qdSta4qAIh2RROP~ZQg8!oaEa=_3_&Xr)acyTLX!Y0;=MTKU{hKN> zg_zBpTE5~hw!G*@wGga1yK0Ztv77m)YC&atjhul7?ttr(>F*Dhe-1v%P!n@lwh$AH zVf5tO>oRJMNmG`2imRgY;q|IkA#iAJRAK(ohRR+U=-eSuZn*%t6nNfgO$^NTj#j};t|fOan!@$ z5RjFs@F0K3o2yUb)f>*Nt^SlIGvpsGB;wF~QWRnCOXB zPGd;vHt6Z7rQ17Nj%=C=XSBrvJ%n1|zmhge%15v3kEj>0U<<`r!DU_$XT>R~C8W^~ zsYJyI`FALFhEHP%C(Wd#Gtc1O-u$KCr&#`+*E$oNrBkbc0#HQOkfag(Id+4A*|v_T~%b^W%w{;CXU z@TYB%xgdhhZiv>4#ggCddo5sxrJ11s8;wlMx?Yb3QiGNIiYv?9KiMM0+`E>J98i#$ zTVDD)t2WM5EJ;{n1=cnt}SYHSU1qx@^wb z86zSjhArNbt26v3*;;xY6OI|USSqFO3<;SizX@iqf@=WmR~elNfWUoi4Z87~tN$p@ zNVwM6p}lBW!P)4NKujvd2R%3Wa-5deYa~UNj*%$sDmumml(Jqb2EVhP;hXqQU&Q0P zft;)dpM3zYkJzhW&hH5r&9Nc-eoO~eeoU{X16$$A)}$ea1xO`^2Z?ju3d-lIiJFO` zb>oNy>+j965mWhf*|1TfL~1RD41e*)hLrYfMd}?&K{d*~W+*4dUoC!`m^ZZcj%U^V zZa7F~ZZ= zWl|T-GFahBo@4R~U<%-nUhTW^!jcNo37|L`j}eB|PQ~7^a$7#W3&}m6&eL!qR}QO7 zwyi1`7~6Wz=17d}SL8efICoo1{i-D}G{jT`D+da#cA=bb`)oXVK>VP25W^l#KE{PX z+#O(z^&sOe@NV4j%CyCQoB8A;Q}B)WtwnF<$n(P8AHOZJi>H3cs!T(M%=+DqADx%K zf{)K%%HDRj`|d5e4MtR<2yY@U3wK0mFB6+j=dbxOZ+oWZ)gJasl{g&CvrAr_9o~pjoe$=4EL`6X^4wIc~?dKf7KA+gTRJ&0l3@d6DX%0AS z`Nr7Uf&YiPua0V~>H5Xpp)C~mLXptm-WDm|;_h19-D!bB@uCT|MGF+S;1mcHEv`Wt zAUKo&!E<@OZ@uq&<+=C&J8NZ~1DdWp|yqBWAmS^}5y zdzuoxyCr{XM-T_JZKtjMehw`)*=r90lJb&IHaHbOU?BfpMbJUOJ-TfRW%T+Cq@oagZlgz+`}|#%cq?>n`B-+l1-(39$pl|$PKlRD2`!|WxkG7i znc*ABxW9O7eJ!rVVq8?IKJGEUK`@aFeInoWtW6CmDDewOxnbj1pN(3=CEl_Rk42!L zz=mJ^jHr3`ZI~O{f3w(vna3PXEXKbqV)HRgO~0nN+x`iJ!{%dRhxO96m|mM?x3`_; zcPZN=xSZFq;V*Wrw|;(^Hmn{ai8ib@55)D+bOR(wteQC&PoG)1xjm7XaJc;CFpV!D zg4Tw-?jna83(wX~qM0`=ZkwQXS1f-;T566l-uub1i&(`UB;w<)#Cw7}q%F$`vHAYPU zWACQ_i5!Tc!&v@hWBd5Va*$_9-MML$?x z={anx`A-g#aJM{rFL00VVMedS zewy?;nou(D9GvzVc`Y~bBkz{S_ZI`q9hNLP<{RXB{)iwY zE=c3CVjIb$YE4G3b-nj96VWe!Uj2IFpeBmP*>Dn9gj?(p|ldkRW8O{!lg-Wb(^$5WJTJYL_>MBv(Q)(Xfv zY$LWP$hyL%p_W7=R+wM2NdeSE$&YBaMnblM<+8+6#~G2Uv2@d^>3UWZKI!hzSXKDt ztA3^BjCr8+EYGOap$e$Ny7*PCmeanA+%|R%*>g_pPb4SuT^Q46I(3-6nzl69CEYFR zz%KIL=9#mKFs;Ft9u&&AK;znWAM>f`SnN6Ch zFEcHxzg>M}rPc)yRwR=oKBo#WRV3V~qY2{ppnGJe`~DVhB3tOo+tm`uroHX*D*vmb z0KWOoFAZCTA1UozW<8h9#}3!JXN?lboB{Lc$ycnY^e%bP766Nf0HqVd3RX5EBH#z8 z-C-$PNBS-jE0)Zb=RB6>igxfQ!AQczhJ*mHWlc@AUOF8KZ9KX7&YMplt=}rlObu2$ z$jFx6-~1i+9fSJwN_13NuIF35>msHrmyp@VOCpanm!sjR+tZFW#|}db-2jpuNYYl8 zjHJsV?EuDOGB+0SX^BBGT>{xF?pPz7oBWZfFW!L{5@)_@t4>#K!tS4;v?0ZvpVePR zwK*}jO^oy4CCl+n1>91ghfH+kDUsQd@n>r`HNEnT^kFJY%#w*bTkYjt@rl+0@JSI{ zXD;pK%AoeYvo!zLZMyrh{N6?Kx2EX*1s(5I@viZ6_E(?b?KihE1!^z+f!xL`-#fS# zZinkJAzoUGFGt?-dX{nsdc~%d*{-}$r5GA~`LjK7fg-1HXhukqXvA`4`WKbF8$kAc z3&jKVzT{7(MMDf~mXsFxITLy=v`ISLNn`3c^p}!obpe9hX9cS9RynwpSEiqAd9=hy ze9O()D@J2}KJI)o(_Az}=f>f=&=-zBl>5_kMw5K`_?V;53AnT6cK-dXVe%(@jyOH$ z?GNz{Vw~QHUSYe#F0{gpGFjoQ z{NYa7FV&iA@+t2OEk)1=U23hD?pzz9{t=Xo1|JAURD)A{0pL_dqUx7mcf{M!B@ zrwu{xvSRn`_+rT-DZv!WHRf(DEAMPssvmypWNlcA12B~c=C-^Y4 zq$$HiICX-kI-MmrUq$D!$M}p3=5af==Ei4!^io#mQknzA5T7Bt#xCN`9d2B{JKvDZ zb|vs4{k~+Yujb($&(DjSv%O!dwkZ-`#t54RMB@*!i1M(0hys0o<{Bh8Bi93AC{n#Eu+)!-` zkMs>0`pG>716wJ{*M?N?9}aZ2G}y=ri4Oo_8%OIkhwhYajM|r5apa14Jpq)lA4x`& zWdSzTRn0gtwjbo2;(n3u-aLNtk63^&0tJNDKNY&RwV}526z};k>;`C)w7-VLjbxBf zr(5#iJnOf;_?=tWin`CnRf|)fGq877yheCsUz3)$9n7_*y#UEbn*c7f@Gm!1RUQ#D zdQ>OsVK^VIcjsqRA{c{Gh47kK5F`qh9WogJ;%qiWK#&(QC*Lx&yAHDc+>K4^b+%Dr zoKP&bxBce#T)JfjA5)OQrvDbofiMHo{6`xC!|ALnZJHM)%lBlbq_uL<%9wF$)qcEB zfbYXGmB)2#V*mhjanE7?wT&exuVfA-x%P2V2}1d{A$Zm!<%jRwUlxGpyBV$kJ|%np z8dV?chu$`z9HM6>DW4et?1rRJ6-9gM&sKQ&0VCPi61&gZy*R&prcqNn3*A++Fs~9H z=@|xxk^TnEs_*A)S6B*0hxKJqZY%%6`dUEeY&VwAc00d5SuNvoI~;m6RGEtx&^PjN zh{jN{a;TukhESo77k%iDVaC>2I2^eeZ~N6Gw7^zeKPN$>TY)#a79_)V`@dWF;JKw% z_SfZC_inT7O;94E=2}fnIu&=s{Z1hO6GcdA515D{x>hKa0U99tL(TpsCw_Hcp6vD` z%0RmKFZI<*SLfy7OnZ>`Q}!fv7Ux7%&-C(r)q{|k_TTiXAXd88ybIxbhCYetdYC}C ztW4+eVERyIvZpi|q)_MNm)5N}<0DW_w`ZScApLsFS_`CShmj;Cq)b$qrnrYQT0^nv ze$jt*(lkD22O|EOr%s3%SvI`qwXE2EM6Us_5qb;MJontR95ic}^M)ppvSrztDu4#o zjj{l<8kHuNGWL~5Jy+5Ch9UF&xM`;M*WLJvyuSMB< zCDAS(mm2vj$ZIWd081hjP>1g72u?`lZ#%layR9~xK^=OJjezLL9wbZ{zIT=Fd(nrF zMM!ZU#q?5}Nd=oQm%2R!#`y;z|Qirvmc$kNUaT9e!^lIEeU<~ajz^|shJcbiNw5I@G#3V3SqquX1$T7atYh9^fZ z98ZdD^d;SIMUptov5f=#;zMHojE~HJ9CLf60`M#R!#BM@mgoQ%TL?uz744`x@Oc!9 zM1`8(X7e)x^L1T5q2SBjKceMpa+NPbTa=lE5(ffLGA>xSb)OJY4-!6T*T}B<2=uZU z)}H$F@Ea-k=abMLKC$zXbECwNRVRqXgaijJQkDfbdeuL!XC6sY7BX)65G*%j7o53T zyvUB5Am<^@?!|z`-RS+8Eml|E0UAayEo#$TUbc#M)?XxXpAKF{O>ir_gx?E=zTVf* zy6CZll--hn<^!uzm+S0wos>m&<{V0|6QZZrEVRkUtzZ|+!$1q8^rGK{MRDuDn)bww zDCU&Tl$z?U7l#31g2O9=X8CF1; z;MZ@?J}YndR*TOI>X-973kLF9Hb=J@==yFtH&m+XOCy4VN{_Nn$K+KJ>4#vglk2dj z0bz)4@m{0a2Bvh=Oj;dl2l#5RD z&3QR+Y+PboGJ#jGgTwAspkv|(A8AbsDQciTU)S|M#b~@+qK7^buL9}C3!H_;eL)t< zm7q?pM0ysYywhEAo(>fH4Jm8f)?c>T9t_NSBp2_fo@6&A?sR1I+T%GDwicrovc|H&OuJYI=Dw4a2Ju zHZ~kJ>kynwC{MEWu+%5bpmVeQ4p$wjlT82jY?0@;Uxp3$7}#@X#Ihlq{=~>YG4ed^ zCLZED{@lzpRbFdCrs2tlpsa54=9Yrk={@pTh+2~uM zXAET|DG+Lo%%v~neRh%(#iwitEIgr^m!?gW#+|ITK1_U^IJ0b3!{$3inkl)6N1o_~ z=q;(vF2pnMlHKt>ux`LL_VA0Q{7N9? z<%X$|+MC#Pqk1|ui^VTo&sC-(8|1tPbhw?o-!k(_`H!4QqvO4_Ek56n16N7%5$R{ZY)f?^E|}NG*f2L`38c`5aohI?F1*FB#6fR& zL)@F}<$~k`1#w2H()!jN-S}RI(TzQIn^8|fw$2fguJM)NqlHG?wVRovYxr5A?r@0> z(*Wo<%e2NZhBeWhI$*?RcVsUUiyT83lWo$SH6SV5H0l9HjJzUQ)DeIPDurmwBnQ$+oW`GvTkgB+CEgr3p5#j zJ>rdT@IuuiJB8xjRwBbQHz{WSy&vn@KUdMX&gnaV zEDpTGS6{QUcJ@~PoPil<=eS)n4$~=<>1rvJcTyzEjSB6DUm{HRUFKH&a>;mJ^@?7C z_G+x5N$)Zed)V~=<=YYf+?4TT8!!BW6L9GT*C=F32Dc0_%(yufSj~nj`=m5!Xwk>S zEBWSf=3 zt;$$3IqB7$pPqVGGoSw9h2>V25F6AH*4}a>~1KC_` zN9D(Ab^a&}>RWW_3wp2+pZY+Huv3&o9~Qu%T{+D!CdwZg_Civ?eXE&z-tlFeE@2J<>Y z3y?Sx76NNCh%$(=2_emHS2~DwnHx*D@}l(4@9U;cmLSBJt{s%({1VsO+GA3*=FoA1 z27C$^h>W8j=fiE1Vf8Skatq*giYv8r9A~%-@Eu~_!l5S)y-y5O*Eu%j*`H_r2NzU| znJ?MydOZD6EHa$ktzFc?o`^Q${ny z?JpZh&d32+^{0WX5+5-NSoe)BrObcdO|2C#Z9e{-z8UGeYTVgOi)bVY)EjL@wW+DU z>bb+D-Hdq8d1aAj`6V<{DxhR(A@jg{=`i$Q^Qdv?Vl(h9q2fKu{p&Zuwr@2Lcpw{m zMF_2diF+#0Dgy@i%@c8aGG>EF8L{&{x@)Vx!$rc<*n&TQn$hX~KUb>MRQimmYOZ1$ zAHXO0a1TP>j#2Y6^$$AJ(q~c~yQNSGx!Aa1I_Ib9R*5I_$t)3MSSG*U~|&b&0Tq(Y>$9)Kg7>X zi#uEzS-4t0j8ov%ihQWNRT*?;Cha$z{G!q~J?S#)e5CSI^sX$*!FO#ztGZDI9R_E)lQD4R9Cj;JNwWep(B}?A`d8S@m)9Ol9zAI?@{!!hGRJsufj= zmwq3xVAjN#Q;&dBUOrBv`5e@>jLxoigO-#!EGEBF!DyX(540R-3obfOl(7_hEJs%J z=%d;ATu@JdzOvs_xDjn_u&^D);ySgssW7i z-iT?i9Pbf@A${LXgG!=V{!H-OJOWm;sVt6#3TjPRnXPTfqXo>c&EQUmh)r>O-owG8 zNLsDk!L91h?We4;URNx`S4Z#q1~cj4%S!cxu2e+8CIGYuH6n`C`oclIz{Xi@dX`an zpY;rVoX8avJvupR-V6cy9lcAGQ9GEy|CR#^^?y-wBdfg8r|lI7C(yIofhhxJy$Xk1 z+u5~#GD9;DA<`Qg)I#@$FF~rO`G)vh4o2mACDzk!t-z~CS}G6AwUr8Wv|faz^8V_S zP`nl}4ty^FP&Emi3DgxqoR@V)hS+D(41vEJH0>}(4%<2xulXPnn9Uy-VXyzUSk3ej{~S;f-l zza?YsB9{-3$}zfLc_2)`o_!b`vLimp!TCgSsH^zas)MVs;(S;A$r1l)R``B23ODrl z&;T&vJX@Z!;+u^N?KbvVhVC0UxIoJT$&0L2YbYCg2CX$~T&C><3yN1gRQ!a-#@7eO zv&E1>->FX8)W+V1xy7cB$4AgvcsTG^drQc@P!UM)KX0B5ACbI}5$RpD=}#@?kWZl^ z{uJsTC-PI9?1e0z!V*(3bjYo87dwtp$r0-Qf7{$U^9A5)#r4yqS;zEPj*-5~e)hC^RV_GWdd zm0q0q?=V>034k{+Rh2KFRr+MR-<@mX%YF9w?0!ckebRbB^A?)h3{PG*62zREBGKUv zjwZ6<_m@?FLFAW}{*EGX21K%EFHY$k6>TCAK4O+UeAR-&P6@ml8OQyLU|^Byph z9QR1$Be(7Gc~msE9>SeoPWy%%nE|tt$t*y{PF#*gYZT1WG_#*(!Z-BJ{Mw-NN$Xqcc+?HxAEYQ6Lu)1aq9qw_ z*`J?0qTaxH0HOIRd@6X-&z>?m$@Du`FMCUXhp>Rv-v~8IuT!OLfFUW`KJ74MN1;FQROLYr+U{Wh3YIUY7U#ot^`8DOOv_#ve z;8f60d5om*Qz}bV)eM4hw;aq8Jp)b-%b~;IPFOr^QBp64hJ3R9Z_O7enh3ab0kC>e zbN#7Etf;G0eZiy3YiY3MVS$C+RqTd)=xXy#nZ}rqdfz7XEHtutXjP=rS{f=vD5D*b ztbE!rOPXut)JmGL)0`SD=n`Zp5^yK;IBz1)viehFkCsl>*=d{E&jFu$pF5*SknPjk zu?ntx-Y{w)rvnS;4jZ~@2#pX%RQLFE(%R*e1>XoxaNf6F^;yMOPxysNJ~0_Ux_TpW zbjKSI4Z$(JMV=K0Ng^{@t)2R^K_Pd@{TLU zah$MPtkhCHuiaM{8_@QOq2kzdasWF!VkJyJ^fsEh%J|Iog;4glZYGtN9@)dm#sLD! z$nxzuLKBa6*QENf+R_7HvCJdJbgC!QMetn``20u0HU0Xd%N9^H+b3I9CsfCr?Nj)I^Bf7=s>c>zXb>iQ!7z1vCus)>cB~Rv;kk?;!Jty5=fMB8kfORWA{z=QniZj zlEejSUM1Le*}BE@*nxGXnmth^LhCCswV0)@u{VrBU4}{q_cfv3)$R8_j7+K>9P&yN z+kWs_N|i|dV;8tfpsMV7pJiT%#w5qGWAu_{1hzH{OlFM*9lFL7I4Up}DS=Om&vZ$B zpZ!IYtW1J7S)%gpBK&qBWM?%D$%QJtx3x49-0wCUhc5ku&4W?c;b0o|+P?liP!2t{ z*e+Ll!5awh87)8L-0VI>eN8A6Uc^iAQK6PJXN~wN&96HoMnUTz6`wF$r~}N_;L|1x z5-vIz@`oNhSbzblJT89w9`XnH#d^T`PMg3*@+QNeT{b>seL~daC~SQAOha|jN|%Yy zUgKB4mzMW8sWeG6_XfgB$UXJ2zJ6=bsYk}xA8vYT>i$hM#5yp@FiL%vDSHc1a!;ii zYr}@GE8Tm^Cy9Sgq!U%3zOGzZL;v=CPHW!GWRn{`!(z4bawf3TtAfxlPabmIhn1`Z zT^tG6sDY=>RdiD)4m2WzaNQ-P{orq2MH*%fB2b;*0!3&~J}tr^z$P1dMmnFEN%q)B-U_pCTZQwVwpglgW`uaDg`sM6Wc z&x;0p0Pe2D`lR1!tkFq8n2$%W$6svN#LAtfSr%@M@an^i$ir{6?rg$>u7?vui|^O- zgYUx5tM4u?uGfxkWq>P#gg55?0ljO!mdnf7C3`JKK1tD@k1cnVz(+gU&H-yNJ|EAs z!z$3KcWBAsGzR+d5uF!8?&%+7oYOdQ@^4SkW64PGQ~EP!bh>-BexmA&J=$+dW137i zPf9q(c3^p+8n%+poAml=Tp4{t(D_7uwdYsO-fioeEB47Jp-A@0;%&H_1Xq!Be;s*{ ztMg9o<=~{_Kmd{aA(YO83N+;iN?U9iKWWOh{HDRxJgOe;xeXX5e6*X5osVzRh4YI{ zL^i*~@1UZ|=q1{$G`<#Ip*w?9_*)2XI#H%ZF^GI8UdmY%SByz(VE&wp{wQp_!Uy{^ zeX@)-Yh!=aS|UHbDk`HLDDGmU8uyFz>s^`4z)yng(bZ=u{;JKjzrZ>qFD&2d1h*dL zY%YNoC&7APW`7(l6p>y&gbqjWplFA&0)xTWk^vc-MQea;kQ#{_p4n5-j?MzMqv%}d=0**k^DCSMwD@2oH&hzlN;V-9IvHd*+ZOhl)DD8 z`_dMfFd;_nMglQ&K}PU|d2hf`K^FV%*2@JgeJV@Ij*`Y@*+UJpC$1Mep$vO6-t_x% zkTbq;3#(YOK1;!@dXqaNH!b?R&x;(Suprz0#m{|i>a{CUGJzNao+%Nm<8IA--*vu} zTto#LE-}HLeh>`UqRzhh8Yr&J3dm~U)<+@=3OQ!!RsVP z1UO+!=1p@3-#4RoH=2$JIt`#8bGt<@wLr%dSabvD8F)i2aHHg)<#I`Kn3HjpwP8VI zD5nD}y9lmzlgpo6|1ABq8BgmJiXK#?iA?og~MxTyh5u3 zIDV6Fh-R#LZe7|=s^i7|nIiy;7B>lfD7a|a@t3Lo&yrf9^KYmWWva1RwU6bnwmgzby&Z>W3>SCp4~yjr9%LW#ayO2qsF}H}LN0kl&O0mV%hW+VJGK}Oz z0^I;r$#qQ+8y6n==M6L@EIw>3x`(>6egJawsE}VcEaVy#5?+YwY?MLwt6@jUGDIf| z_WAl@CAFgfXOrVxAHL^?+ThPIlK74t{EmU(r6O<%aw3@7>sRa8Dr{(uxP3w-PWTsp z1NqBO?Vu;vc|PIk#~baMXjwiT2NNUzHd5%GB0+<6!TEfhILq@pfT_J$B7!E!-I0X4 z>(tMiD0&U-1-&clSfdg-eNQeoSA_Fas9NVh*3jAJabm0AF2)oCW8++)+>eHvd>LFy zX`q9W;}xXzhoYu5J~@HME;KbzuI#zG3Sko8#*qVq0XrG3hj?DUaMFzWiwz+8!4()> z^lmNkHjc_l^-k;z%&T-)kQ>US?UzLEJ8 z(O0kU()dvf9wi>4FT|b`R$5jXquYd_v<@Bd4mnX%N&KWw2WGeyUU9Pwm4WE_Zk+=` zR60!@jYKNR|*Yx`kU@Z;K4h_Nw&jHh3 z;W{>7BTRmN%s*DRHJY@$30}CEDKyjPc2UuEsW)&r$1w@Vw?xJNb(({%_ z9@TNdEq>w!+y!KTR};n%_YtF!Eo~!ibOOM;giHk297+#aJ~yX0RS{-Z-S&E*_3XFZ z!Rn*$YG)P~C_iajZ;Jr_JnHJ=m>M2B1f7R9G?o5(i-C4u8R6~iN5~LEr|daG>yX!- zD^+c@K^m=`pXTLeOtgijg_Ej9Vn?T^;k|bw=nnCeBY3v@)F$wkt|ChjeYAMM;kxiR z>LDH_Ut87n{^qljkSUiANQ0jm>eyHPr{Y^;kP_PH9~8?Sby;zxMA(#6rq)Nh4wBuDLmE(yQ&+L2h=8;yu8th~Nr4roe3fc!DOz{2 zag0iui!8^JArfGB+?0h#0nsw*3UGtWkaEWDH(195omXA4?D>6a%CO^ zO>A+E7Qen#tG>`^IYhen-&7@(bi_M9G0OrUm7L$|l|teJ+YyKsximISY*|pg=6$#0m{m(}>0#JGw7z_m} z3eR;HkQv?9q8-kg-GmE~~SsOVKT?$Yi5>Dvb6m zu-qlDMHni0h5W*Gw2jd@0V@R2z2dAP?;eENp~K>?HifX3jyyM?wAXMsR6?~1jvq}= z`UVkYn_+n)jta$o^2(lrjwe9WHnIf%)DgiHA#H^1;Apq-ppmeJeAvO34K)1&KYmob zsx5XzcS$M7y#3hH77kVq7`ztqI4rlD?DghBn>`c{*u*w(n~@fHGfE!10jSF$DPrqD zYp;YFa+~3qEaXGLRZeGzN*T>`(_qnpj2?kK7Ypp<1DVFNLzqk>dB4}k!(YL3U%{g{ z*BA!%v(64kzdIP}NzmNg?D8|81n?bo(1GnRQ`fzhslnfG#?zKQL`qR8HBiA< zvwx`+QG9d?JNMRCPEr-X&~nw9qL}v{-?6{8b6K6^JuoYRKX<1t`ZSN651zx0r4vOn z_1Ao?qg!1-z6obychCoqj>83TF3~2dD1N!OtBqLqiwzoR%wY+MuVfPT2Fi=K6ipW0 z4;p;pJx}rlJf>5}-OEbLjyiQ?-asbQKeVZjV|=0M_l%uZB2^>zs2pFE>%ho2?__1E zbiR!_2o;)e7aYqtD#638$*YQ0Y~S&|tK$4~o%6xwFv-!r%`l?+9MtqkJ5=jv*Ra&Q zNrf}NSjmrUWU?*pu*FEVEaT}>pJRHof;ev%GY0WK^rnq?$Lwo~y61H5dJXN;zUy5@g2D4#>Dg*j&)BmY8Q)snZ>}?U zFvr;Q*}{z*dvBEIg46v_9pBK0Y5a^=tm*qy80dPYiq6#tlMTmzMF8%zpMn+g+(pu> zTI#lY--kM$r1cN^br(4{UFI6ia2oSzRFf|lujt|ss|}$w@5;nz~eOH5#9`^+rw0%)E~WO zgyApQe5835?qX%t{V>-zN@#2_SmYZctBJ<#vec0>U(%1}G<2?oeKT42JOfhxgV~%0 zXo~PunMiaBI(B^d%$SUdHa2u=NkObwvZx3ni}1Ae$%TSL>${#8(zuVEb`PThPeqMT z%A(l?bRBE&60qn*>04sH)G&mEME<&5Q+pdd=b`>H>p}e z7He0Sh>iVyX4lGit3Ia~c5i)GidUrqk(RmqL&6xfZL$w862GU+{(SkFNTkOKi2qSM zA#x^#ibsS{L7LOdE3wgwD$mBTy4vW zkdSYDxa~xS=9vh1iWS*|_qbX;iIVhRhW226xZZ^t!d{A(pbn0PQDS;ud+|g5FCAO~ z6$bfZ)jX%kJEL8jk4vu2z8P#DPno37qo4axv(LzblND#8y2nPbq`KOuY#}&LiFPW^ zFRVuJ1`-w%w|U;o^Ofu@Yg6RM)729Qi8uCgpas|gK=D5rPjI4v!bSq3E9q14oU|S84 z%ZQhOT$W6twFM2y%tCxYR{R_>{&!{ZTio9WmLKcEXt@h8d z-}z_=H!>`bCc+*kja=YdEGNo|AOfK2W(FNC z->-vZ3|dyJ3h%&T$-~pp*RKs+j$+Y6bLQ7_G9GWCtf@NWpd4>1OnA5 zZ9CR(2ZTO}amLdPsn|Sp&04*)Yiry{6D-fWz>ARNCL=oVpQ%KPMGTn#V8$3REZtH; ziJ4H5l zPv43qBx`xclIAhzCnuNws?aHALat`M|8(sq%_+u9{83^dwHLT(OQoWjr2Eibwt(YX z;v$FIuKH4*fo49AlWfN-bWQBf>`^^xC3rSCS>fNx2J63vO57vi^e1gyjtOax2C2Nk zz4cc3p0B`tp}%${p_fVX_9MRg@0$t(q^y_Tw2O71vf$vIHsqQ3Ho(m#w-!>?E8YNx z;y-83)r6bh0r!R7G!$+`-wdUdJ?O>A&~IGr@2T1OS~ITn;TPrP75@~S@V@2B(*)r5 z4a`D+H=^?iW;9AF)d4?nA>nToE*T8O`iJzHKI*c@H1> z1RVKIyR(NjF|OrpHWoa>Pk2Ra_89QnHa*=vd^C6MLCcc+&3Hn3zK@2Iq1hjunT%9= z=T9i=Z`17NK!+K&haa0gemG8RRRZ&bnkc0(L~S-A89}w=D+Yu+sMk@jWa&E1ZEhW* z(sFR4W>sQpZ@H0NZG6w*cMVMiRbGHPmQET`(HjP0rQ@FVS3NH8gC#)p%Y9o=_mP=c zZ?-WIy~8)0SpMfRs&vvRB)y<>we+@nn@nMGpGqMrA?A*uDMKp6aop*_l9Sc zNeoBrTv?um+`QHI2WS|+&WChM`pOw6OHD@?@x$a5dh5uBr}>(xiyS9D2=XB<+Yf6O z+L*Q1Kz?;pG2RoN+~Z<%si$&zOT)0hOG{>Q>W_Ttwd*|3l~r~pE5}SRN~q);>Th!o zq~ex0W=Bdcn-=tGr;cr>?{@72PW=%9NJ3!$h!L0t-^xP-O0cXqT` znsu`D=u+Q&=#l86&IqEVu@`rb70qsZ`2<^P4tI2*y|x1UOcS;@hwOzVdv!S3y51HQ`vWW`^b2y zfkO}uTqo9n_MVW@CAGkCl)T+qQ1|AuBz&zoJRSzBdZ}RkrWssR_+-3zkJ7pJ_n(nV zx`N{@1FZ0>s*AY@Zt-e*mjGL08&h2UuR558HzYhM>3el+vdB8=!~qa<>4g%k?>-@j z^wIDoQtwMBYeJd%psV(6+vD&Ppq$!Tg~s(u#{yrXUQh!en&&c{?dc6)A;YK6O`!ODmlMo@aZa#GtA-9Gs$p$EL^!+vn{_Yny|nax^8 zcIJVoKe-NmAu8;b3zVa>#8$B15vn5MOs&O`lyh@yQL`dGw{Fmh$TOLOhjk4BXqrz~#8y9m0tkx9oNzgtJSS=NtT3*4T3Poru&Z@>N$ zU3=guE1*Q6s~N;?*mlVeaUBsE>!Mh+P!)D~QP78Bho@Hi%<@F^hTV2VN#t}~7pgrn{ z)!z5Khd-9p1OChMLu2Gd`uz6Hw&dfQ9P-h$y_(IWR-nivQD*q3FEm2BZ!6{ZI z?KDJH&Ny3`h4Y~?n0_nfCa*1PIeTl3z2oe$8wS$+)|@7yf7vrnOATvdLjc0nLhaoS zc$)BdYzmZS%rYJp7PvDomX@1Qu0ahbC#|stlfzhyqH&9|#b67*!}EQP=EqVf#Z{AV z5T|b?smDw{@z!wj+5k}9cp|Th{EjiK6C1OHiGz81$?CfyMMx#8bTnM7EABGFDl^=n zUJj)vev6;=)Y<<^^IO~VTh){r> z(}8X@@y*IGU+?P8z}@Vk5Pf?1iT|BRXT$AWf&W!oSboR8q)(Rrf^(x)pn2oo-F4?t z7QfAeBwq#foTn=~Wfx}|9ppK2YQX5HGc4oYX5K_X{*7#9;HudXqWML*!%X*AHo7wE(agAq6I>QWkZ;jxQ1JR(lVk|d3cO@;a3GqG|tiUjBg{ig&`vL zlw2L%rxC@XO8!^zbSJ_SbU2CbjDS~In3j1u_fdwBg9+Na#)Dlq zkRgb9HIW*HixkqVoJ!gq!{b>;?bJvMopzaIvlN*asuAL6-eO7i-04i>93@NN>}1z& z)o5-v+g*h$Z4H7BAUGSdPI5K&zacopy_@BmdDcn0|GFulp))(sv`~DKN6BQ_;!uW9Hh=Ue6UZ z9&9V*?3cBc4aXJwZND#&V=tS7BfrrtbtH;mXes8m8*13#mg>Yno`jn^HKP(vSHR?b z3Ui+~HB$U{MZkphpNfDIQtG9Ap$J}=3tzBH4ZPO{2JS9=*@~rB-d@L@Q?zX{V>jO1Ji9uj!IWWf3B5c$|id(>M%O z%TJ1}us(9KC&RKh!m|Z?KSQjQ zk@_t4RI4u7b4%Gw+Ox}eF{(%~Vfjn9nU`A005BgJI*h~$B|~>QE?2ZxU79!TCty*n z^aYtURgSmaAWK5GbuHXGJ3EKYh?(>m+mh^Hv$aF^+<&^z73V*TxhW`9vq~5Wx-LiE z5C0Sw1XnpRPX_ue_z2b|Ax8H)EwW&-p{uvSZz8S{VD#4`i_^tB))~SUxijl+$)OOF z`@yiRILr|A%J;ZxuFLAhN4w#+5m|`KrG;N8!F>qXK;!qheCMwQ8O7Y_Li=jI`DyQX zxsxu~n+_7=y5OvXGlZt(np$URy0A4MIpJ+`Ftmh+mco*#*AH@LM3Wmu~Y2s{yd~ zF5j&2xer`gL7z8T1_5^^Yq~sA9T=*we}|qdb@d4}0nXz84HNpywVA>3^4~k5!UkRl zieA4L(!(e4X#0h^O4n7Wg^8T??K61(_Zm&h1Kwc?LDpft{y|B<#uGjrI%gqsw_wxE z9$qNaj+(`kE$qQz<(iAR_;?n`r$^ARq~}BLRx$g0yZmLf&5U5Zp!q|felVeKqNArL z#g`?^$edt73?0RmmDLb~7+^vcfw^y|3`VR?eM0n`QBTc^VVqx*%8b{T_4?@ME+pgK z_i&_xg>8OsgdYO8rA5oOjOg~E>7?OR1V#39`k8&fu#UDu>ikOQy(kbYd8>7)M|@syMho6cJiDO^oK ziB_trd*tr(>dokC$e}Hx;Nv1>t0_&uQ3=9(#fQi=$iJ-9TpGN)nh@ydyWa|%@rsWd zy#0*auh^?Py8a7t7=G3Ahj(tE&0Nsj=PF_LhzoUFVOlM)*E!Rr-C4nu#bgZ*IFdAE8^f|V>|iEbQP$d*|v8bHgTT^ZFaWt7FPY}5yX)>zd1~-v8vo4%Rg&x)i+BS zA^T7NM8hj-hq?$I@z7_4L0vK!Lcd%vV}nIHBr zhdfAW);c>2+N;=|Yme0(5CB&18C%S7-ap~QYma<0pU^Yu;m)@Z<}1jl?EbyFx#OLZ z8E?FOSxxOBx7+_UH0)DwGqNOjVpCQt=iw-_J?0}hgly&Ps@Y}L)NUb*A6;R}{NGIy z_{u@|cVe5{Z(j?TJA)zbLSe|je5+yEdjx)5Cuz?ZZ4h~HT+H0>NZ7a+9CGWdeYo}T zuf9~VBT(Q_EqNn32Cx1BIjuUpMl7s~dGh-#IA6yaa<3iECLlZI+}rnB5N$(Vf+k#M za1?Cw%73CJVawMHm7T?S#5#@tk0<)iV=6LcNg(3Cg?!)Flm3u<+{iJ0YYze#RGMWwf1^Jgk;gp^nR&n4v1RR{ku)&7sz4(0x4^!-)s(>DNZ zh?cI!|J=lcXSS5^H;r9(U;n?f;qTh@k8|V&X|{j!WB<=ngCGCHW&ck}{y*M8JpX?1 z{-Ys(dlYl?S;GC-fW&`P0I67(2|Mn=54nFeo6$fD%gf8%+elt^otbp`E-9w$)dwx% zZchsRxob@r;H9L@LE(oVGm-miA(z?qw^EvRVDY{#w)UYY-S5s;f7%+H&AE zcvfD%OMc(DcS-T6IWtN9`;Kfa1Vuwf?gs8};X_GvA*Jf+LAR?OD354l7X8|xTM zy+soNuk^W#piU1tSTO?sZ{_p<{Yfv>E!tk4dpz&5%^&0c3 + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_config_8h__incl.md5 b/doc/html/_me_config_8h__incl.md5 new file mode 100644 index 00000000..48d9eb4d --- /dev/null +++ b/doc/html/_me_config_8h__incl.md5 @@ -0,0 +1 @@ +07e0944954ec2a6187399cafd5d8177e \ No newline at end of file diff --git a/doc/html/_me_config_8h__incl.png b/doc/html/_me_config_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..b27f30ae345d117e6961f858b3300baa05e4b914 GIT binary patch literal 15012 zcma)j1yEdF(OmGkG7Tn!6kU$s+@CFYqgS$I>dB5GN zf4Ba>YKzJc>fX8Mp3~h=cR$@7sj04jg-(VJ2M33xq$sNm2ZxXW{J#?o1^DFD4V4Fe zp}bd7kcE4G`N{7tO@f1a1E(Y_rR$x2xa8vxvYtOVUGZSFGtS2l)$_D+l@mZFDEjNk z7#ejqLEA7lR>VS!Or3&CEf@Q%lD+3n8TUh`l0$)_iLB3GM!t`AP}(;f63na(uacJ< z-dfvbjcSOpNaX1+=J;) zWMpJlLqoqJe=#IvyK`!8kCV~W3C3X9P-S_Wmx>PE>vHvc*%|870-^Ftq=_mia<~^3E z`tKWU2>)L`WJefX2Y zwr<0hFpp;t>9;YkOi7+L{m1sWc8l)_4pMIib>F@`me8_}a|2|$66(&it&9?Gzr$0W#v*6X!&BmGxO8%Lx}NZB&tmQlIRRqbuNwv&5onba!vMHwx8)v1Tk!;Mf0%YHKuuPe(SD(ql?XDqLGjIm6It zt`1&LJYcOqbVS7s0j$dWvYA2MH~X}L!0~j90LO!nG7{qlR=sR^5ddp4L+W7qn}6>D z#BrLgfEfEp?xErcbwvE`mA5Hv7Vf1~;9}C32`h zD2mm28}AZfwFoOjmeH&R9-eMXQ5g-tD?j}Zy?DnoU}cc8oaP=U?<4IOgye1|-{^Tt z@AJFzoD|$Y{9--FW9s{H%~02XS5T`}#W#pz%urSe{i6V!ASZjg)@0Wo3zwRZO574S zL1irBX4O<;6<5yQ#L=q3ln#@URA&Tp#9ZRFA-@%w=-K1l7?_C7fsn*Mwe0b51UKgS zG6jV;f=?6vP2MvB&M~i0U(AU?5Zo?57{6UOf24nSh(JBvd#TczU@xxMa)Ya}VN97f ze6rFPgf2$kFUHk5_~}%1c+?(Ld4F|rLWzslC#lJ)HZu~Xo#X78b##QrblI$|0D1g8 zi+rTF^SYprft6g@BM_{5TL);U4&FScUg$7$5+nyg{Q8JsXRal7TBT&9u?MA?_4KVR z2I$okLYk+i+wZ6h?K8VcDTWNA#)S(+^$^D7NrEG-G-s|%#vtZPAJnPf@(XMwZ>pVl zMv*Rlyo|NUBG}-V=NGf|{^nYIlv-}7ZH_UcYZ0`H1@T*U`ko0zj7a_vn^VB>_X5qM zO@7tT!mcQ*R!}2NEigxNhn}ypKrLP`oEkm}N#w`cw@@8e(4&x79MPc$JnriFg-7-A zj@$Nwop$2<^&m;mi+PYH_z$js+}*_HV#<#BVW7V|X4?EV@=Pxj6=_Uka8o02NQ+a+ zMqjKriLy<4tq`qO{??P1G5(fxz-QmRwAz$np%$AGxr^mw$nD1ReGE$+V6Ew0KLH)t zwe09)LC-6Su_YAbFF(Ji&t^Em&sSJ8sn&8rW3^;yrN@WUQz{a|T6>1OuWTrj|6m_C zd@dEjm+$b%*T;#@6?uXR!RBq6*H#(~34eL4)NkWzKRF8ZoqYsJWN(}k=a3Z)_YXL` zo5N?i6Ry|<=7kE;Bm8{{tf1MHwN8~%CEKq&Db|VerLNsG9b9}SDaVtdHfNctlxe89 z!3E_?Iks^d5rL-rOmH5LK~s);f27hXd2C!>U}ibB@?JZnRr6@f)BLW!X+rU3X<=;1 z*9Gu5i2caJWnu*GAkAeZn;Aei?H{~t+MzhbUJ7k&qN448qmh@Qr`xo>cFJKlpb;~8 z%8IJL*Ah>LH6D}c_Et(IJbLVTkt9x(UL3jfCWzP`iUFNV{)9IWwAxN+s|mP)ey8mY zLnbi;HuUA_r-)#+pL?gjeI4?HA83ZXCXERZdosPk=H)Rq6AacNow`QTIs7X8)VF?N;awH7#)6=@4DmQ!6P1Bbv)DkfTgl7 zekRHzspBH76Y}(r?NI=6qK@IUE#YqQE5O!(FRGFxjk5O=yL0JJid6g9kcV&Zn)(gl zrNN-6gSsMs<&|>}#F=8;3IxUOHw!dIo`0rB;1ceiC6c$+n{dTq8U?gR6QhHet(G4o zb0ag7?q&>%;Ahfb|Kj8b;Wka)?St3-KE}+Kx}Sau zZZ`~#hLl1ul6aJmDQ6XR-zNew%!?32t3_v6hp?Js3>X4uVpx!YeY42SM`9qR61nXN zx)%Jo_Es-9nNu;Qm1mrb9o7M+#ujnR3kA(9GcB%Go9$BeJdPaiOl4`ExD{y zJ#HHr?u%{i7p#qksz?p#p-*R8*@S+S^5U9%O`>!7f^IU1J-UpDqLa>#-5(bWyRACJ z$lbH0vYOSIgcfcf%-irdQ6sk;lbg%=8?43l8oZ7D9r=Fsj=Xv0^1#k@Lb^Qh>S5~3 z1ut-mXmF{9-tL~~mth`hT8e0tcnp4fDJ;VC{%XP;8-!^H8R5%;p{a`%rIeK-#H4E@|7}^Z5!~FQZ)o%a+JG) zIOxUWfqEQ<6GuPHgavT)X)71G6BG7uK@A|Cav8JQTtTmZCm1CPhoGAP>kH&A=%NEB zOlr}$K2i#IT(Gh}@>fR0r$LO+JsVa7z)xvBj2-ff;m+n?$q&Vv{`+XFv~|*e(Sf+4 zV~s%A0PNVUT9u}M=Be}bA>cS`!Yr8>LBR3padld6XfFJkNABYO^!GA7<^%&0U*TeE z5O&O&!?c5#f$+63DWjB_{=I z{#0+&{7kZP=qm_Q2P-q#tfH^7>&?i8V6YeLSu5GBRam|V?kkl}&CAM`eff9g7f00( zV*RESReR-@9{g(3r^Xw;)xRCr#a6ZRb=E|yd5rMfL9ic*qY0HI02HQ-Z^|x&{<`^@ zsH&5Ia?pi~cm>PJ5%f(%jf95fZ&V?jCadG6bM-?iK&A#m*0bt~v%zs}ihQXKRtG}s zab5dl_f&d4T>Utow;KdIqMUY%n*VqTv4+}%fKzTjRkqhP<;80Z(a6~w zPKwD1pi(*%XVilfV#$XLK977RmTj*qHv9V}u5yuH+qa-kqseO>YT+w;E3eWGIyA8$ zEc*L`s1h5KABkyoFjaWfK49J;KapAxho;Hi1iw>2`AaNk4W4if(|SSOjx3E<^%Q;? zan9U7!+rjc0J(Pim^1J_0`%jI{Sq7AnvriS_NWrF++3$eg_z(Rc=RO7c*0b#!o#Q< z;#S=RIh3}FvQR2vF`37p>UVb)MqYb&@WlY{)U#Wj!lv9su_mOnUJYl@^(F|Rl({Mq zb9(`gWk99KowB?7Ac4Zm_Ooar&uvq$mR=by`%bRn?$GP4!%sNoElRQr8G*N}$?Hqut_5Bf!VisRfMOQTrI@v_=l9Xo)^Mceov z($I+!HOdE&2bw)Iz3BgtDcIS3rPr}gS5YOpr8Hn*vy!?FOI|K;`NC?@Ix`abq(Dw} zi>dXuqNp-J9CYpki24hE%@k#3=}49tg+m_~>;+Hd9CX9t_SF*%x`oo_&18&A%T&;P zN>vP!l{hZX?q!Wj3rA5I;Utd^Hf>uZEG@?zCtV9E1>l<(mRQ_vc@hWd!2VAo>&+))d%*Le(L`%H@OC!~$flYG!1UzUh_hdP3Uywz`y} z+l@r;Ys9_k%{w80Xo-`t5d3fy1MhkqeB@ImP4;2A`R}U;PLsz7+A;!XO^^v;?j{@m zNH*&4o2iGWAZ_J$eHqBz@mzsaD0elR5uxIO8AvBo2oVQ~Ix)1m)SQXK<7w#=wQfH~ zN()i}9u`wgk8FlpAtjGaR?}WfGu*CP%Z~cyghJ(gHd@SHkn2Ami;Oi=IN-a;WRBCD zbJg6@C=_a(7R{XHR|90!GP!Rvn$;B)I_6}Zqj}(1yPB=}I{%t2KK;i-I%>`-xdouI zl7{Fc@fcCQ^Cn~wU8YLgWzCk3GmU6*cN@|iaJ`dI$Re~yMuLSYVx2o?besV}6RGa| z=A%;FR5brYFRp9p4E;e+~lWLQB2xu)B{y#H>XNvBo}v);eZ$ zVBth;!&}m%`6oI3cCtUd!K|f-&1g$;Zs+~!+4%0D=`xz?*gZGXXV+hkm(81AbgD}7 zFznuqN|abOk5*Nzq`QupQiOX%XS7AWIZjzDyPR*z&r0D-%vs1ij{6s>T!6ULBRz8< z6H%JsTaJgmR3A!PG5pQ*@o&WI1ZdsgD!?qCzwzJNEA9${)>!9zvRp)2%aYb^QtjMo zsq6I`yp8vN7Go8(KFXJA4AS#2p2xJ_84o-a_va4yqwx0W6RU#=l29L_YK^fzl%-1_ zTMe|5vw|#B3jKfUaT1VBAD5H%X?@rwdO8m)>%tvn;|{K;pX^crlE&Su30f!%>xZ$U zBCiMJ596hk14vv6GrQ=mSXmZVj8di-oEi;*dG|MMu^Ald09?(t#Rg4w7L7UFPu2SY z$>b}M8hd=_+2|i@Q50aFPrL8}h(lZ5b)786FE`Kq9%2|EFi598;px+|&O$5vB(4Bt z2|f@$llN|=<1|?`K&Y{t`eBw-=q<)US-T0>Nntskdl$Z3|5PcuBxc@bdHBZ9xQ$Aw(Y(8WeOcQ_6Cl|B zN0hzDvvXWl|M-#1)9X_e*6k~KAXz;2{8S-tC^i+37#f54&1D*!bEWk%c_f%2Bg|;u zUAic`^0TZn-OS15x8t;p+C+hxssn!ao!rbd_~h#e6Q_h8$hkAEPKGd==w=clMLv_q{S74*syOR?yoDVgF`m0LVGDI@X-SaGokdHy9|77%a ziwf`dSdL%zeup^@Ey)HKWupouYJfd;Ik~8^gBMA0GkCAab4a9m!S!u3SRS{$@@J%D zD`jp)B^+&>?32qh+0w;_<%J00xbsP545DPK!=LS+wgZkEHi~o)cH^C~om_a%DdnhkDQTm(6F; z3j6|x<$A}F1g+cO1O=*H4P8bHjq9h<&f^t0R$Sj~5ntNE-Bc0YgnurCJpSO5%4k@< z6{Yt5HI;Kko;I67<-H0Inl*(_rXL2FrZ!X0c~}!7wopDnI8G~~C(C?+x!)mwuJ?Lm zA|-WxOUu>NlIOxV??T9NP|D)Y-%Nc%$893Df69`Y*6Y$|gj*-3uNW^1aRi zp6YPxi$kQzVlUnqhYCl$HHOs{wA!|lhPJM%e#TWo1s_sa%J16qvk+oxv-c}l#e7p< zefj&FzjH)et>811&l0+*cNKC(RzD+F9o;!T-d!?i@WRK5>@k;UyncD=KbiuTpawK3cErwD03BN z*7E&d&NQ9&g=P8=DF@_tFL(WS%-yX-CrEaphra;zK8Pz$RFh_COadSgyEG5>NxZB4 zb48~%qBsic*sPaA7p+C->Kj}A^ceM9U_qv5+Wcu=sVFUAfwD|4I69cu66L{z z4CN%$!>ZrYl$Vb9$F@-3cH9NeZC5TNe)!V&teeBH(?_A*OcHuZrh~f#lj@BejL~g5 z!k$G)+!rqCG7{E{cjMgu{+?|!6Z~K>=27uFmp%iL&Hm~b^8EX9EBxiT*NJhZT2xVTX6Ohn-t03ktRxI@1rwYQCF4YCu+K1`+xe* z<2V2Er7N=>b0>R{Y$}UkD0#9LOGpXr>9Qnh){fK_Ey3tW`ScHj8X?q)(j9mxxqkGn zn4SlqARG^Ko?38SFGj$kOKq)opdAcPcIi^O=dyBQTR*YRG!5lRe2O?T<+>C3QkbeL zMqVVB7qg;3Lh9B`vP(0H7xQOJ;v)ug9)?{Fj$6I6ehrD+&$o*{=+)^)bUu{DBtr(} z#BtgzMMv0rr6{8EHRpu*mBV=}v&9Kh;r?;9VFs#3I3A;Go654EngioE=VX5JC*E0K zmU9=k1rnGLD{F-nDDp<*{@|*V&dfXyIMA%tq0?e9CA0aUKL#7#A8#yI4P~rMS^V;0 znP={@kYc1~J#jQ&(ke924wJ~Crxr|KJKZx^p&)GLUZKSzIX-BWGVqmhqnkU;?t@L* z_CnEtE#^Q#K8D(Il-ia2nZF9RO6}JUQNtWom=F)2TX7dBmY!Lv>P;<0Pq6&^I@d0l zpH7z})Rxscp(jNQpX!veVLy>F--CzwuQ+A{eh&WgJU7tICG&Iba-T#gCPjb#6H95w zesjT|Li-OxWteVD@q^g*`GYdou^a3D!KY8drKsg|ZqSsrP2ZrX$M43&m#?6e>ab6b z%*p1~J4Rl&n!OPy_o8{v*X!AI0Y?@bY6Fy|UuXGstIWFN)}F=$m;KHBNK$l`IOucz z#}4Hl(Hh-YO}He-Ll;x`uaw!3-B|YDL+2}pV(4oU0&O?Xy$n-Sa-iF{p@7;$x!*3q z{xwcUF=?LDp-StBnA5E3C8)KviFj32>}*A`dMNF1)rB;7%E+D*tf8TrN`Ge1VOqQN zh4X(Q*8iuv$IHcBa`*M|#r98+F@|0F}%PWGA)N$UVMiu7?JzFio^6_(~7}6#l!EmHS<@^Ezrezv&K*7q?RMxT1(23-X^0<(ZdpNjy~8qORPh zNBT|)KmX1%4rCseym20nBbOEz7eD`e3PG;B=D}a08+!lBB2viM+1;H7 zRe=5ODBqq&h+pR8OO$L}Kc>e~`PEG}UK+I@_B(sK9XyFuQTwh&-nUcVJoqf$2606@ z2HHd$(4=-M-#amf-Jc34Wz?;N=UgyIVu+-^pSKy5_~1Ah%!^GfYxGB(i`d&^@rB6o zOGh3>#(vjMe&b{16}aHvWO!~9`P*r7i89+?|JVSGL+kSlv@t)kkq z0jpPg+A6vvFld)rjiiD}63vbzNex+{2r?B@yRQ)>@1o_wnaS;FT2JqYICXm_b{*~B ziq%jz{`Gi{IN{QZbFNPF6GNX2QIzQvDCedlO~OH;RHqnIZ8H|0so+TS(}01XJwaAE3qnduF^`uLl(J57%6~`YDoid!?H%8DtP9lL z`m5P&l!u43^uz#0xgD+z{loawDePxbkyS7c`CoTu4{z-?6@Zs8t2j^h5-pYSsy^Ie z4AFq!W&;1gb64G>Y@FHsP#Ud4t4eH*!i@`iIj znC9&R!pBZYwhDVcl&73fzVStom|6$6MLKdBqTQt0te&#{nazfMHZPWZq#P|4Z3L)D zw1;_qEO%|Yx-0A2y!5G*dJv#giP8@lhfkv~1Q|iOct5AwovG3mS88n`q*~oscq+%c z`?et$pa}7hCP^YwCP9Frh>Q(Eo>YbuaVf%v<`bv#CwZfu519{3@k0I;)bVd9w7+bS zZLq2E1~hpmI_5MQ+jij2#FG!(eXStWYjS%mYwWC3+|Ca@ zELKlsl^ZY)=(V|N?yq64x9VOznr+u>Gt2+znHAVq%k{^eP-9m(&ZV36dIsIRiQ4MB zJ*d3%a*7u#JpsbP%+GvH>#qR{T;f&BJ>{dK-XAJtuE(QXAXzc=@`1y%i!E$=lbsm@ zRqh=Vb;yZ}bF}V2i$za@1R+F!4joSKS~sAuoSdk!Ew6(!q=s+_4E>ljdI$hFQOVqX zY%uFN+HSA>*(FfzH)$y`0SB6&ANF$eR^q;6?8#{T1d_|HAA3DU zv^w;=ruSZpA52ZrJC%=tp*jp6X(oxJUuBik;OdW@;tY9Bb1&~7u1Y(zfDK6Xa-Td8lkuRooB!EZ4R0KUiRWXvHkh&mj%!aQa?1yZAv|; z6^!7!%u|f2FVC{_!4(35<7iy6uP+Oo->*^D)E$2-b7a4~RrM(^qMz&-L2OXFQLb+2 zX-UljG(+Ql$^H*s3Rd4D-@?T=9^4+Z>{@IbdhHIWkS$I_Um4xy6TT8RUeW6NuJWqa zut(ZaRe4zIn+?|#B88hk8v;JKEZ4n+Fi-Jey;OKESx}r~E+d0+`ND;ui+o#F4lZXA zZq3f3Y6peB4q8><)CrpSY8wRt5S&Sm81o{&b!ZN3D+#-IX>TYt%LH-|^ZhO1cWJC6 zKP&@zS#egX-V(#Xk*U4(0w7an<&pjM$V3;M@N<>qAWa(j68Gv&!k;YMD;0TITR!+z z_p%!NI^Ag#GAT$$@x%#5m$VHb{s!7p5GxMCYvUuuKlWng zwf>!`x=}9M`Gjt%%{ZVyoX5_EM5&?A&vCX4kb@&rbxqDoozY1=w>}d*utddO83eDE zADe7aLwNGBcH-=Xi|8?4A*2|E+6~nQ6?)I4YX~~4hooz4U(#{SBHSvdu?~F;*HXy=+g3(XOxXC#&p(zb z$JGd4DEYY~0)voKv{8-AOhip27@JX*?C)hvOv7vMHwbxlad(}{?-=$a>BJD3gai2c z<=XO50{sH29@4(Bw%)CYh_OP`zQlY_e{Ym%ghHf|IJ?!fzgy!nI|#mIbg`b`!O|^{ z?h-6&)-v5fbbx$<2C$T>QufBUpBD1qjv>`xh~#pAFfQdM?`%_Dd#{)2;JN(}MRm27 z1mf#&_LBGh=A>H($Wp83a=_I`HWZP3*5RY@5AdiWVAiCOt^0Dc4`|^@i8`>O{0-8v zh3Ky98cIPTnzzwid9CVRdw-$QA*A0xE!P1cV@{4=1CgaodaGqts@OOpscv3Q#@9Rg zPAGA>1qBSOBVXcJs=^lNxg*hUh_}2Xb+C_weVr<(MfFhL|(v6t6du%IQtc0FcU%F{boF-R# zcLr*Q!20&l%*$Hz@VZ`Ckgg%KUf<#NstqYqW>Ky+ViY#8?s&%pv9b)i0}Ub*c_}Dc zknk(0&2Qn756UyFp}-?*0QK(PLi|p zG?hrNN((kFbhC8mUL>4B;={ZwywsgX=t_6}i1P{GOn|X*lpcJhOj~Umeb#wHHs&09 z`?60r(@k;Fqo^KN1CthRE=N?hTGB1&tckfCpnYjP=H_7q}zd zq%2Ua731~aokq}6P`JMyj7et5ux2Jr5yfNa)=jRoDZM!2u8EuzJZ~rcFvfX?{oqdk zB6T(}C-!mvFxj1V^gg3cLH6c7FF;(^$lFgbJMHbQv*M1S1d_Rn!7OIT#M|U=n_2PY z%A6yI|K@{PZBw}Ex?a;%Q^&X2b7U}fu@AHB+%Jw;k5i1i!e$3lKOX(ujemaTcNq3# z?iII6NIP?EWOAy1!gUYws56oGZwQ!J9_Cyu6u(lFLto4E$G5Q0K=aYau#=;km#Mn6 zjZ+X#!zvj}G{ovaX;6#FPX}r}%j)6$8->4qcUp#4pC8O^QzXr^Rcm~C*md5E;MMeF z^CExaG>Qw**aaeW%iA3hvVn#oRUBHs|7NpL3`N`(zQ@DzemNQ%TLU$PWXd=TS})36B(Zj6OFdkS#szn3Y5VP-Sok6 zLk^F`KB&udnisUku?`+x`wfaIySg_mkVwyNjPUJ5tqf9k_Q3xgjFj}4W&-v0B8HuG z==T?gH?S6>oDD#YavAkJbs{?T$JpWE7h|wgDmm5bG7VzypCyQ^p2GP3Qh#1FR6jI9 z+2x}Z3s?Cb-Nghn2ZWfsmM`aR{F8R0RCM8(uSa>cZ^GTnI{H%eT9iKinl}mcPb*2p z*Z?#_m*o;X=tjx!MB)4`JE1C#@MR$_C8ZJ$O9F)ZxUEiRawI3f?TZ2k$^!J9EHsR~ z5hlgffyon&9qS7){^<|{>JkGSy97X}fVbupQd$&N$R_?BY3{qV@JWSL1S(~;`8ta@ z6YV0hm=PNVW?OW zWY&lTCk3er8L8MPj;ilV#GTpV1}@;G0Hvc-nV#sbae&dMGaW_6>r2VW@n<@?FDIt` zr^bLLdwG5sKINffyV-6j3;TR`$+BV(O1dmg2U?@w&B8rGV{=$-wOsr=&6Z*e#CIPR ze0Yqw8o$K-yeUjH=KbjDqsSfw9h6n>t%5?sJRbv8x)({@Rf}7I01H_kjtw{irDM3K z5?N(~)w4!btXhSRHe~Nwbf#AMV)41MM`Ep-aWwNh?p)t|S}&B0oSA@SU46J?1DK@o zK1@(*Xfq9-uRk8utTGHxsItwwf_^%LAtcIh9y&`Un+SSvgGlboZJ!5FqUmimdm?pL z4J36;xK<2{5fWRd_TNh*Y!K5b$SfV+0NiR$Wwr`3V+P=p5-Zse%_7<;=Ec;ga70S9 z$%N<@LuEb((G|U}DZ2nxs<^nLffn`|Nex+!D$b>kel4F*aYhKjx4Z=uiE+pKp~XGZ z{YX4YALN7#BFxpajwfpqU9Q2vvwPH>;6eEwx(~TCI_wCVsP~rF17O226dMxvvHvtB z^_|skhsh3aWu~FYyYtwgvluk5Z=;$t#n4y7%zlhuH+5cCHjeKHIt-UGlvMDZ!ax*` zB|-#7x8}&8ne=aR7i`(hAPq+yjEAAGe#r-)O&$m=1%QcrrEg?CjY@kiWdlq%yB7~k zhCYrvZrmy!dpD^7@r$8t%Wm60c0}-b$UQodBbt|axKE7PtlZeJ<8N;bHeybsb!8rZ zxg{$QmhEo6&R=KZ%Y?qi50Ylh{gZ(pXz=%@u;6Xc1yZPW-~PAk8K8!{8`KMcLt4GJ zG8bX`b@l@Oy8o5Zq$$@MG}QF$>8o7my;WLd6~{%j^Pm3OgRN4>1JoI zZM#w51#xlWW$ncjq0;e9d3!pPIQm+psEIV4ra$4ONDnw9)#D>^VmJf%!wiw0F7L!H zfhis3`d@zS`zDZ8b98h2*x|E-!%u&F0myJ}FmuA@?eTvLFu<(rNK_GhyT5sSBzDrH ztoi!8bs{h6s3VglkRAj`lT_fybVTYGV6XMejQkrO_*YM2hJcc#b%FD4t{AKs%)pv*^POeQYWow4H)c`8s7nz(J&r7`{T~=_-cLap56*vMNi(_j0R7=p` zeLS>pn`EtxCU^*0XQ|fudLg>}2QL!TltkxwaVk(Qh$$QrC^Y7sEUM~^hpEH|u-CvL z&{!d)JdYGZb@d%OT6g$hrDTJwSi~Rq2hUZ=)U>42B^5nl9eva;a`;<5n4-+Gy2sq_ zCf=$WlzRT;DXs$84HoXrx3s1Ax148GL@$Yk+FGMfcD&oSckxb=<;S^Js&Ut%Ej>hK zW0#*sCjp zEDZB}K?p0kn%bV@Xq_QtoZW|6RO7v34!@Nb7ev>eQZcGy8Th-#e{$cc-k-=vLp@2- z&u2_KvejW-?S{0DF2FjM?mH66u`S4mywwf2e>VdYtoaCfE~*5|VHKd@L}<)b_S)cl zDk1>5)ykFBX6ce@9c0>frjX6AI0R4juWUkJr>?u*XnorN+43to!;jIIly|S08EVjla1?oAcz% zmuxJXZJOS4*ZrGK8UOMVtX11L^Uk5_<$MY-jl4$0w>&Zbj-b){!%9-}J#>#e_r$=0 zAc_rp#V!&Gdual4-Do2cGD#k}>WNp$%KUN3*CIU^bMmJw`A!S{r6pm}`w224r8st3 z)rm_4a1?qg!F;(6pxWk)pvG60pfS{oxTFYa;b?E_KHP^_zA8Fci!vNp0u z@_6fyO@W}ok&pVFN5_3Da=xfF(G%62@!$MW!|CgAh5k*nqU!%kUM6Ac0aRsiVVh$d z*=w`4W8UFZ%u9>$+_{HAR#x4KF_A&h!j;McWHT%jd4~wvQVcS|vNxGP7cS=!IA@pi=gI^2aPrvlwJU0WwD3^{VYvA%)mMco2ENUIp^KBF&z;b{ZaxBm2}o7d z^9KA(UK)0MZC&Fj*DaUY{JXN5mN1)t-M5|6YmKeu9K|^$bF6bu*Aj(?H3?LVd;v9E zRF2#fPZl*!@zDRdBTr5u^^f_016{Z39z9+6f6@N>jSMbj3ixCvNFER>iy~4x@bw38 zdp)9c{@aK_@tCNFOXU;^y+_0xNq#3*ED66g+}Syrry=j-Y*?!@lSt||s{kvu>h>o} zXQ@LTp08;C9jfyfSKS-a07vRe$qoN~ZDz2U?3e0}e-l8K0onYw#w0*r6Q!~G&s;aW zF=4990j_0oB(+de0L2d!{5iDj^xG(`J0tNt_z!gV&IOzHiCu0fWK^ZUU5_--B+Pi% zZ$|@J;Kq<^Z=pZw*PfYrt%~g20M!lUCE)5VkgEAit}#HGzo`-x&wJcjG?-!A$3jDa z?9jlFYtwSg>#+<8eWhr{&;df_(azQPRW(wmzZQi)eW~JscXXD)VYuo|EKANDVl{$} zR`yeIWnDc#<2?$lfmku0oKdR6M;+h&&Dta$;p$C@Pm%LKH^|I+Bvy=Ne?-?0x~#g{ znSI`MgWFSAPvoY(j3sr2tAKdUsA6)=xD=n(#78&86or%QvE~GcP!94DHw}khBWXy% ztp{LuMnY|NP2B@Ki+)0mJG(jF>}9P^Zx6{t?(Uoopp4AcuXk zQVpbX2fgYim=-v_Wj*MN?fw0FU*Uz)A-ziy?At&mw~qM2)XM+buWk*}1BE@c9T z+||R6SfL(5!Er>oZzfxh%Boh9Ns8D^45b4DC zGClG)81c0FRe&xR?e0q0AMza!4U*gQEWrrH;lrjTRYKqa$UgNV_a1Z=7ZSB2{rVX6 zH0Fy4?pl3sXI{o6llNyBD%`o(o$IZEfL2(Q#55w-Z*i%^5EzOq~;NK>UK4-=LI zpDW84OIAbg&kl$H%B31V$JCA)wmkA%LB(ss_^~T%%`Eg9p1-YFh1a%qxAZg8!gbum zgkO#irgeFLtudI+SuGY&riR!RIMjjHIf`F`&t_-RRjGH|W4sFR^Rr0AxB~V;nGQ{Hdo@xM2TPJfUkvyp8Ch? zwCB@1iho@b_*S&P=b~lKvvBI07^e#zKl{GJAqVgP+sX!ux}#GHUC>o?>WIayo+PU& zZSk>;k0E8QLo5p4#qbTl$)Q5x;ZRZAZJK~lk;cT!W_y9EX;JL8$}<3IwfQZy49nz8#yju+T!M zv|J2i!Uv6&ZvvZup#wa-oGR#&P_f-Gg=p$A%>mBmGXj@F=8^8bEju8Iw6bp_y5Uvt zohAq`h>AWjS~ccc=cd!yyVK%GyjqC zvIfTby!8e#VhF9f(C_VVTE~qG^UTHcs5taufIjZGoobS7ya)Y{$XSi@l6xHws4m4A zBSh09h-Oql00;hNqmJU{&F2dhZoT1%;OOY6eCO+IHd^d&nsnTVD!hma!_ zso(_Wmf#F%h4v0p_m;*!*e_NybbfW5cU`HK=<+*|aCPPFUa(n5!=I9KAz{-jtfPZ6 z6Us;PqLk@bGY!#vgQf!`8*U`6;NY_gNjfdZ$JYsy&MKoj)m>sMwIsIrl!Mb6ZMJSSB|! z<@qO$jV0F7nem2G2YOG?gp38_Nc?IO6m)8+KCfte61%b3-EN`q-6@En65l-QEjnb-|CPg%4f}9|b-CmT&qIq{CDBY$i0=MN#tEsOkmw$X86zPtN@R&TIW! zxBM?dU8Ar620cHv-WweCzXrFLC0|!)n<+FyQ&$v6{((xiDtnu=uJL;pOy$LDcZ~<8 zG(JDwpKm5MnsF1ZRXo9tD8N@cV|-2%$KJ@rA))6lR-m48UFpQK`N%95tFh;BQv z+v3x8{ALfRYVGM>$+-x zf|3q>k8%q3qGyLN_k?ciQb)g%@75+1;7z^{w99~U8&d8(hh{!5BvapGriINOSDJrw+Vn?C>uz!D{2?KmsjAE0JiH^I?H;AG_p3v<={QE3a|XeAj_BMW9Y=8f$k@v; z+)D|68yMwFM^Dl4$^`z@VSQ;^FNoTW;u}n6x~z6>{w&1LCZfscQG?AP{Exs&J(c`PYT@K|+U&X`=?LMIj7 z2vvAT`T#Ti3H&2;C$ZL${eo@zgUbKp`~Ug&)9rW=3Z-;2Yt|z8eCzksE$_b_2mkYj dZrU@BvT>5h!JYmkFm?*3B&RN0BW>~Je*rQ#fFu9_ literal 0 HcmV?d00001 diff --git a/doc/html/_me_config_8h_source.html b/doc/html/_me_config_8h_source.html new file mode 100644 index 00000000..c79e3b49 --- /dev/null +++ b/doc/html/_me_config_8h_source.html @@ -0,0 +1,137 @@ + + + + + + + +MakeBlock Drive Updated: src/MeConfig.h Source File + + + + + + + + + + + + + +

+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeConfig.h
+
+
+Go to the documentation of this file.
1
+
93#ifndef MeConfig_H
+
94#define MeConfig_H
+
95
+
96#include <utility/Servo.h>
+
97#include <utility/Wire.h>
+
98#include <utility/EEPROM.h>
+
99#include <utility/SoftwareSerial.h>
+
100#include <utility/SPI.h>
+
101
+
102#define ME_PORT_DEFINED
+
103
+
104#if defined(__AVR__)
+
105#define MePIN_TO_BASEREG(pin) ( portInputRegister (digitalPinToPort (pin) ) )
+
106#define MePIN_TO_BITMASK(pin) ( digitalPinToBitMask (pin) )
+
107#define MeIO_REG_TYPE uint8_t
+
108#define MeIO_REG_ASM asm ("r30")
+
109#define MeDIRECT_READ(base, mask) ( ( (*(base) ) & (mask) ) ? 1 : 0)
+
110#define MeDIRECT_MODE_INPUT(base, mask) ( (*( (base) + 1) ) &= ~(mask) ), ( (*( (base) + 2) ) |= (mask) ) // INPUT_PULLUP
+
111#define MeDIRECT_MODE_OUTPUT(base, mask) ( (*( (base) + 1) ) |= (mask) )
+
112#define MeDIRECT_WRITE_LOW(base, mask) ( (*( (base) + 2) ) &= ~(mask) )
+
113#define MeDIRECT_WRITE_HIGH(base, mask) ( (*( (base) + 2) ) |= (mask) )
+
114#endif // __AVR__
+
115
+
116#endif // MeConfig_H
+
117
+
+
+ + + + diff --git a/doc/html/_me_d_c_motor_8cpp.html b/doc/html/_me_d_c_motor_8cpp.html new file mode 100644 index 00000000..ab66d0f6 --- /dev/null +++ b/doc/html/_me_d_c_motor_8cpp.html @@ -0,0 +1,192 @@ + + + + + + + +MakeBlock Drive Updated: src/MeDCMotor.cpp File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeDCMotor.cpp File Reference
+
+
+ +

Driver for Me DC motor device. +More...

+
#include "MeDCMotor.h"
+
+Include dependency graph for MeDCMotor.cpp:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+

Detailed Description

+

Driver for Me DC motor device.

+
Author
MakeBlock
+
Version
V1.0.2
+
Date
2017/05/18
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for Me DC motor device.
+
Method List:
+
    +
  1. void MeDCMotor::setpin(uint8_t dir_pin,uint8_t pwm_pin)
  2. +
  3. void MeDCMotor::run(int16_t speed)
  4. +
  5. void MeDCMotor::stop(void)
  6. +
  7. void MeDCMotor::reset(uint8_t port)
  8. +
  9. void MeDCMotor::reset(uint8_t port, uint8_t slot)
  10. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan         2015/09/09     1.0.0            Rebuild the old lib.
+Mark Yan         2016/04/07     1.0.1            fix motor reset issue.
+Zzipeng          2017/05/18     1.0.2            set all timer frequency at 970HZ.
+
+
+
+ + + + diff --git a/doc/html/_me_d_c_motor_8cpp__incl.map b/doc/html/_me_d_c_motor_8cpp__incl.map new file mode 100644 index 00000000..d2fceb84 --- /dev/null +++ b/doc/html/_me_d_c_motor_8cpp__incl.map @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_d_c_motor_8cpp__incl.md5 b/doc/html/_me_d_c_motor_8cpp__incl.md5 new file mode 100644 index 00000000..8626ca8b --- /dev/null +++ b/doc/html/_me_d_c_motor_8cpp__incl.md5 @@ -0,0 +1 @@ +437b6e8bc214d10280a0eeb4590a077c \ No newline at end of file diff --git a/doc/html/_me_d_c_motor_8cpp__incl.png b/doc/html/_me_d_c_motor_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..98227787175414c41228f5066a0f023bc40b0731 GIT binary patch literal 47719 zcmeFYWl$Yo@GXkFTW}}1yGI~E@Ze5xf^(3-L4QDS4Xz0u++7Y34#9&%a1ZWoZ-D%7 z)vZ_ey{h;5O+KV*7-shF?!CHuttM1ONd^;*6b%Lj22)N}>H`c60vHAcHVp*{xTDUV z-VgkTWFjvk1@rLu?^|oZR~Q&-7&)oe>Yvkh=RLgQ*Bc*>hR+n<{7&?1{@}Ds{sK}O zM0sXaTLVGBsjd57s)?2o6LvqRTkNJhJfd5gP$aJL_T`EX2Bk8g!b`vPzfLx+rRbrP zEVMQDGOXbV>?iu|l03hO@qh88Fs67dmQS^qZFp?7l~c=a^m`i#hWx)@vXwrS zUJPc6i(+9!Heqd@Ob(_AmeXw0N=eZRqGfZuk^-(KPNML6;xEfIs#7%HdN>HaNLawL zxVXKTLE^N)b*E?Bes^wqdAR)e!1zvi`;eYPD`EK4Ga1y|aE~u}yy(FM=l`>?HQeW4 zetdz4)W_(5_hl(nr|BN=0au*N|NZe%y2VSVpv387#{5*u(H{vBkb~Cdj_u<*?jk!W zae=EhH3}}i42iXV&bdFBk|Ibrqp_gijEMjbH}?MB^M_n!>mYgcwV0qkY4te}87V2V zZ_l6QfpM+5`_am-lQE-Is|fa&m+@E8g6@?JA-pp9QINy_$>8d0XF$wuaW=sQ_@o`7 zl!4#l%GWe!D@jGC$K{bM{n5i5 zO96|bk?WS{Z=rveD%;uWyPUske1VHQgZu9x<3ILxVJuR=-RN;~V;8SV)MA z6f5}A{z%DXwyWEv>_(zw^>!7N)eEo0OG|mrY{8|hC;M!Wdy{Cz#}m|AnpV!Hj5bT_7j!*N1_d9~l(+E#+rFJ`c>KuYbsX~S z3ShgjV%blNm&(PS);W0G&CrMcM-Kx#`riYBIiv~Z(QsQS7YpF%NHW29247B9(**3o znh*eQbN>rMZQ?K3wsQ?mft{H|b^ZI&%ir;_(F}E~`ULOoK;vhpgcfx#w@CrBxwHL? z$SQNUzMjAeT0gpt1Z~stGr*5huf?A%^?%v~aGyS!>B*0eOX{UV`~M$*cJKeAW&VYe ztb6>Vr>!ivxxe>c@So-V+g}k>@Z}C*ZWpgE&rd`O^)CCYgn(7qpItiYkWg^zP7}eK zLju!7J^8E{y#tC_bqBg6+?3w4`;L+dKg!zni6f` z007AS-vbX8bCs+8qHT}&9RBB*>X-+;Urp~z)7f&Yw1f0wffv^N&(GYZ2=t=A@(ic{ zI>R0mIy>o^{UeKpkBb}n?_g|Q%r%TfP6rzXBr7cgz~nFc3{0oskGR-yR9=6jO~8;vJy@EnjnM-+D% z{WxGj^#2xQC}fNyk78vFwJo7g{W%&Uj|Z$J@E=~HC#;sH41A&tZsr-522g_h+5B;W zVr!X+REJr(Nsnjp=@Q?t4~>`nuUXmvfE8Kw)1+^Y=%=Ep>XgwO9nutKixMt*RB3!? z^g!uKF=K3DQ&d#cM&e2VU`ji|Kdh80uc$bz5xMmLsd5-cJe?+UXz36= zXsO0idBg{Uf3N{VEb7KKmaiDzgwdG$ARnrV=j5z(f_0# zm++Lczn(icPZ`Bw;;W+S05dJ^zcneC-TnKRfUKXkK_s*JTVu$$n?8P;;NIBgLfVIYY zWhXqP@X?(=U-<3bCfB`I0@Dl*L4Uc4&l>LZwV)*fiHq~eA+)sfqYIUr1|DtIQ_Y?Z z4wGXu;AYVR;1dGYWJ%AC2>Cy!@3Uvn+{&qoVxMJIedyO3&?X^Ogys7}qiDN4lR9Sm zcKj?fM0PRvU%H4!yT87<80(UBEg;JoxJvI5w!p|nQO@Il!9a(Xq{k{Chw)fLkcX-*hlJk{f|K_V~gt;T8Vx zkdZZRQX7fk;^ZwMF5FnySIQAkAt9%5;m_$S zbRk_BWca>dEO^bfv(wQ7I zrVD4mMP{UMsl&gG3kgmSaDxveRqxydZ;A8^0iNI}Ns@?;m-yF8t(# zoR+AK*$*q;zI`3>r6{znNz}C74r_17DuA0<=CwS?YDv6>;g;JpFZFGBh}7GEcpvuY zQ+7msBz=q)3@=t4lOIw0%DK01j5!0o>w5w3T2pRl|UDjYTvU29GeKY*-&^!V@G>S#0$px;*o@wk`4 zz%4CKm2W1AUaMruUYSEQh!@{O?d;t*HK)faQ~JFeD^lq=IO|!V(84I?Ici> z#{7e#5@z`;1RI?UP$8M1`*@ONTHkwYO{#uH3wkb=IH%&R-di-VNV#n#HujqpEGJ{y z3eiKx^q}w6e<22+TUhVnnzHc+zt^vnIOX(ybDBl{I2d4+F1a9Z_D+$O_Ud2TaH_4- zN@W2Z_Wywu&a~8-idyF^bHH4B_PV=!4lCV$C}ra7-hJle_lg4WdmC{97p5K@p20{p zze)(0SbkndeSDxZO{wz2vpMR~0=9HHD8xZd2t!P|bpaF#@+dXk5t5Ddfv;%z2#F)R zkdK@l5Y>QaiTxKXby9uq?yE8z={AS@B5P^&N|iEh=WSs@Z8l9YH-29SF5kG$C7R_> z28qv9mQE@ERp3oV`01G03Dm1>Ev{kw>s6URjQ(C+{>?Q;&{WOp?EGTM; za3~$D412IF_Sex@D7o9aG^OedH7*I$b58w*RlDC0FJ|NDf1}GJEd?q4b$_oR(zxhc^+$1Z zAm0GB;54r&ia!=I906RYY}E7na4p!*#L-4?f2W@~-v4!U8Z-l!G_NL1-Du4>3@&Bf zh0Cf()o<8N&I0}ToeU6Af6_Pjc=TEatlYE_=5S{N)F*^yNnImnvT4@VE|BeS@2BefwOynK?eE-u>5mDX8)CIYtt-)G2WJRl z$hGPb{4RiS;;VK-c}H@H%QHI=3;R-aGpmLeG%t+0+UD{r?}Tx-h!S(#em%VLPlh~s zn~s`E`!A(hgPaP+c6!oV6j0l?<4g9}GWbK{+?$z2%;)cauCMDO)BGmZ^|6OpKu*;~ ze&t`CUG#Gyq{sp{^ve?}#KLBqd_R~G3!zE|Wp+`qEv>B4gIfw#6DK`O8j{oebcok` z8|D*(oSUUTD&P0rwu_Tpid1k`%taJA;$NJeGdp-2%)m>~6Ayg<&I>iJ=^_TbGmRLS zt0MZ0Xa$!j%7=s~W+dLR5LWgHcT4d(%#Zc0OR-rvEU*q8ENoFS4kmv#(vi)Izqj#L zIa1mGDNMM^+S_m^g3jQc)|q*$rMpu}^EQP*h?hbsC$D_a8;O6yiE>OJ-#5AXm-{Ta zsR9m{NFcXAuSj4H#`)0PF{RR1WH#(?+!)rRV#$_1{0j@wHIBGj|GIAvwvnYVlq*DN z8zfR%T0gcF+nEsEd&-680Wm!UnAf(#ofA@)r-uAj9&KTafIAp5!9VQQ9sK z64SqdoP-Xr?~s!^X(B*DTQP(IZ!?>>2*8|uP0~nc&tJXM&+aH# z*2mtp8>-zAaCCJzon$gv$q^egS$aT=jBC66sPi$}CAX!c=L=U?dbJ-7F?NHR2L9&9 z(pSBiPemyrIc_I0ZxkQ#>QF3XKSl2zt^_6%UK0U!xZFT~?7yu#hN^7o> zsfqW65bkQ5HiSU~-_DhDC;`qeq&r!Ye`N9uDkh#+A>)=09HCUopIRs>0o+3ooBnB? zigUuhqa6IEU0w(@OUE^L2}Qz>=(eWL~z!A3j2LUi}>sCvGoduC&Z4 zv!kAVE%~j>A7&b+1%VGXl30;w)qMhgx0GpzXbbx}N1fuAULSj5YwsN1E&S~t`?HHA z+5LU;EoI1FcSMm>U2XkFA5xI`CbTwZ)M2ND1HDhD+N^Ng&A+ug=eN%W2=9Z0QQ}iy+zqFIGH*rADkk=37 ze~0O_sx)zpIoEF7l$TSctZT)ZEPM0M60doQt{KtLEa#hGjD3jDpUdD|7mnCCjC>nw0^3~s8aoZ9rDDHM0KYK$HbBR__pTb zuHh~T&%xZbMCI+_gS4Ac+$J^)&|3h$vn<(QSx&`k+i`5{{iyPMfP;N7ZyT%Fj4+$? z$*At6FHaC(dRr30vy=w8$8r^t+!|Cn%DqtMIQg&LeuK+B%6Zjl$!dwoSjewy7FO&< zXEg*=>9<*fCVMUNd|q+W3=XoC$lAGtup0W&F5Nh8Ok6WnQ8&Hp5Yg zD@OV~qnUV&iX{K1b=vvMbl{p9SSX3V7m^@*CE4uMCcF;O6tuTl=;W_gu5N#4kan7x zQ3m(Po2^9?Ru1d=H1#Ia(!H*xv+%XTs{4LCQ_~*YNtrxYNnt(~m|+g9uP;868D5ep zLPZf?Ih`Tc71Im!9}nS0iMA}|C#zyhbc{4XP^Wt6UcKr#{iv>a9NmN>DOv1WPtK>;&WM9*b0@JYf-+D7YvdAtd6r{VY&LAy%$T zZe2L)#b2PuvfipVvF(|oktNaqoN_JHX5q-Mf}r1O^NTYZz+YXRz8*5MrNdue&J>1w zGI2uVjbQcB2;lU1?o@qnoOEa@Qm@tABg%l_v@tKxy*gN8 zy9ox5S(2=!srva&#voc&i=Ofro_Xm*I>O=0A&nhD z$Kp3sTV;>0ZcL#YB;I)Q+)MS9LrHcV4F}C` z)asxK8EQ|m&8VW?^>GRG%4gi$Lsvfc_5pSZUQ#}BdR=wuEBZR7Pot<7Y!ajV?snl0 z?pD;X$f9J#ksXM|uik&Brd7TwZ^fGP)Ln=V)07*EG-MU53PM^}vLQ1sXxHu{J zlQy5i8hb3`H=G>nwz&z^l1Ify=RTV4)YeJQ_`vb0oOAg4Y+z6R;X3n~!$^9$>Si~7 zw)TF7Mlyz&RgRYj;LF0BC}T5|Czj|iI8^`AHCEV>B?m=dMpkY_K#5ZtZz+}3cI=F^ zK8L+axe7oIe4!AMiEoq^-RIaG^ni(UEGWxt+Oxc z8*Mtai7pnV*!C96_tjQ;wij7cc{6T{NL4W$#Zdi)UF0`?Ib=kB@7;y8|9i_|bk>67 zVme*MPe{R}6>NK#MOc=HK~ z=o#)aVgOh(y+tS(H~vBP;-c2!gS?HnroIBdV?K$cM$cZ`Lb}8G?#$TW?!rQPj^2N8 zC}}xmD|B;r{QzHA{3z?TTTI@(=3WIu6qbguBnv}9?V7T(92#t=2K87gzo^%U;Uq#q z7>@K6tQ84~hnvy%2>vJh!QV1IraHj|KTPj>J(MxmwVibXZ2s2%!o|JMR?fg~KOrF@ z)%8stb&<)VTy`A*O1kQ)w_U*t?sw9JEl^LIeych)F$tuh)7OysS99?B42&}?`h()& z^Id(#2?s!F=G?}k#~#SCE%uw?-MQ<7X)}eku7_J6dp=yWjdLm->shQ1Iq+hCTc;xX zvJd^v=YZ`8EHwMA%xg1PBqR_LnGw7ERsEmYKdz@EG8Zdaaa5V!=QD0bTF;>xW#{c7 z;IKg&@n)$CSNc|F{qqh;{@swl2GwFi$^#M<37YHibvIOhNYZ|;L0@T#lX*ARwl7d( zF*)Oy?9C_yln8FK2?x@*bJ@mQhuJo%=0#M09 zyD9+1vu;j{-WPkV*(XvmACBEyT_!@E8`#0{YS}usi)R_}*y9jc$|SDM)#io@t53^q6pRL(KFa6JJX? zwwv65rU6??RNk@9cD^t4IU9cskt+7Anpif>l09OGC?0dvq+J)ZN4t`nMQWgJWyUn+ zEqHB*h*odpxInXHz9enT0A>At^nRJh@JFh}fo(JU*te_QIn4~Cr~2fVUu`KTcG?vQ z`{D}&w^vkqk9Bx_G-^h-PpA=qeW&QVqWe2D<^J{9~Cy1Ed2)`X`?;S zmsdR)T~`dy_t+i`7A;k7;;fHEit3br%2T?Hg=JPf$TBk3x8&-JOdAcj9JxKJ69BgL zGWOUP^*h$*g?h(N6V`P!+o@8y2RZ=b3^O&Xz3omUaALQ#J&`8NsCpnd-V2=nIHzXJ z2KH?cBp!Y%B0zY7H9vprW0l=u!<|UlLh*%M4Zj}!=Iw8_g{3TbN~i~|!Ot~PL~+_G z{6}^QD4#uIHkf!bdm8FX7O0f?E^&bjLfb0y#KvHtfQYUDS?+-^;)r|**IwZVM`b8b z2ILpo>_kWfWbG?aK+9z?HX^Q8?bOEkU4#EAUEtHi1#&(57mtNboKsrVkq)n0&(&Lx zzRe+kVFCh;{u45Vi%PTPe&kWJb1CDKxn&KD^*0dLF%2v80M>sUV!ks4GE|9q_$j>O(rxDRq{1Eit)fZR&zhyWXWyr=ME-u;E3frwJ+s-1oH+LcgIqTL z4DFU=mObYZ4?2Jk^OyGz_lI(=RX=jYv>e6#EUe<%-fV)fr~y*0bM}!<`AjYZDCRqN zrCII*f4BPXXz!%Yq`Z}ju*&U>~HgM2SYxLC8)WTHre!f^I{ zl_GLtBpUD+Ypwgbw`g|eqrNwKpdq#w1b7X$1%=*E9#8=63#p`!Jr+fel(&zXodp1BG}eywv#uo7ujkNf zR|kmWf()Byo_`$R`FXaRnu<+Au@wt+5F#pLP$$%Oe-zqmqZ9lMk)j*hw0-}`Yuq{) zpP10DOB%Lk8gV4sZvh^&R(7vfU8l2K1!VA89|piDKofmkbJEh`L(Di8KV5TAewseE z1TGk3gTH6a*jV$&JFS^2^pJ58Ym(h(Sgrdl2ny`5gVc6+-yQ&H6WYWPTZgoAv@QCq zr;c)}1NL5S9&p}#52{ObT4-{mzqx7W(qcP;uglkgBY?h<_?rIbK?!q*-A=iGTPZrD ztfjr4jO%8z4diz9qBzRUvbKYi*HGTU!gUb9mty=-Go6j8zukaL=Ac5@N!7P=SL8}| zDQ7X8B)jHT7g>DvKCAAcZem18G&QGs_Lp<*%JWFUsRy7JO~F6REdsQ+=A!|}*pMc{ zkjo-Gu=sYWr`{|~Uh%N|xu@m9jy1(R>VGYVreL@NlL$xRZ9l@-wCe}3Hjai}pE0#f zhe)FRsY3~Op$ANdMrItORHcmdid5y_gTN?Vrq*=Ca3dXK-6 zfygb|w2;C*yHH)dIS;TpkA*_XF@r?k*e!YTZUqyUk{onzqHw40iw^UH`X4#rl207Q z$9wp@^My8X3xs@LzWXg6C!b(}`l;h}>M|cM57#?99{M12h@jq!oEU~5h$@(~RVbv}|!ou&*!Um%nW zh)HDEOqxQYKtH>o zT&M9$O!Xko;x>#{iCOuoaf0Fe)p+f{X%K+20K}bB(R6uUNu+ywXyc8foa=^B+{qi- zbu~;PAvP@JlZ30UkKir0_;seP_T|avmR9g1dsIn_g|bW?j0+oa=m+l@1r?r;Tqb_~ z662ceut>B#wQ_WMBKd@cro8Mhh~S*t&}_ieCJVrD2~wE8~yM0NQ#9QCi! zb9Ayb%ZP{8H~~F7MoYYh*Uxn6w%L3*ECC^62h>3FcPm~yus7whdq%=CN!MhOSjBaN&{cZ`cH$e-(@c(S$JM4u*iG->+@s%p9Re| z^?ywM;O%t81^3YW!;jnT{_2e81kR05?i{cj?-QrbRFlS^ctubuDw2~fCGt`W+2>0} zvKm%p$vc;EhWCjYk=3P;EZ%7BA3(w`cUXHRct2ChfP$vi`HeFTM2R5korvB#u(p5j?q?Uhzv_brsC*%s9C%Z+r_l^i zI_oVmGl*t7zeNc~WIhb(TTAm~i|*SW`O0n{g<|W~I6D*<6{YU) zdpvBK*Co#+v9hpyl04N_?*$BeH{Z$LnmU+$yUA1j(M^EEwYGC%MRK= za2YB(fe1c&;L%IkeN$d9sWLdk?FFFQtM64=k3h@1tvFz80+C0V6%O`pN57!Okd zbJNq9>bM2ajMnA7sT}fQr^!q|@Yu6vm;C@_C6W&Vs7Ux$9ubHVT%S8XS`$}QFwTZP zW)V#(5=YbuK}Sv~zxdUk{v9u0?9T++f`uu=t_)_(dfRlRDOv->S`_u`^Q9lb>}Njl zWY}WVcJKypS;Nnnz9G%@`3^RWsn((OyU{zW|)_&X&L)dOj@a=!5yVp7TJ;^6>M3npGArcf zP;MIX1YsTtq?YJPxX+UrmL`DQrYN>JlVCb3ig$KT7?C!ptq4h~rYH)-P=9h-u1p`% zjpHaV28&QJml6Ky;O`UhxGwwuf&1+*cb7uKUx4Y{Kp-zFsFpQ1CBii+C7h zm;)1FD2>^A8<_eqs^Zr2Xr&_T^sw-v_&l7hhc>3470IsjG=E@BqLQoxa&}iTPc=9= z`YmgRM)D_P&x%60eJET2NnJP{(Th{ZM9b1<_dK5ce3|G&7%)xoABivKayyES3Xmvw z1{+UQyWcEMpc8);h=Pq05DH7|QGxg;)THxWkV8R8!&s*h?;8cG7qHPHnlS+FB0aTX zp3qg1_AcXzuiHulCbaSzlF|JRV0Vz-8)Z)N6sLTEpjQ%)6}|k^w2)a{H5$-PKFm0u z5+h7>XGZ;PqVg{?!I9*QKI#X}14a{l3$6)W&3Cs|9ys;GR1RrX+&&xe`FRj7Y@r{` zn0olklK9D45o+UP?O6EC?Kllsve5Ij7F$01g%qI946|t4g{IV$sCaaw>k95GBu@9Y ziu+2i>g{$7lB8_`J_T*K~+90t!~8v&&fg?HeJhh4lf5#F7E^kU6ZTBoh=G*EQjnHI_^}KAVKIQL2|GskDaW$NuYVKED@Iu?7*bF-Ezq=#5xBcSB^YdbNWnSy;4TS<%!x5c$Kp2^p^ z|0qIXGF!BCU@W;9YXz9o%yBn_+#tVsd#W$;80cd!qqrZ5Qd>RP(=T1e5S@M4es<_V z5#zL8EKxc#kN59=#COZ_Kt}qn&<1boc_RCl(xCR=EGDLy>CKA)hmBrU?4kXiDq>Qu@>dz$lG`)te zKrsRuNCvUO0sI2T^mS`i`&(`BP!Y|JS6%mHI9Wu%WA*79Mjq+8XF9I-c8XsH+)KL5 zKO*M^@l-O%UsQuk!14Z3D&KCBx<-Fu)keQR&yk&2Z}nGCF5keHK4LqwFsIN9pnz%xZV2$@;?=5#Vd|Dmm!#OOGNg!loiWpl_ILcz}trUZOS9X@6ICKa*W1kTj|8@e}>w< z;+q*hc%iP68khV3Nh+w7>f?kjgX2(6oaUb=p?d*%LNmYdGzgL+RQ_=eXST0p!9GM6 z$o1d5=k`?agzz^M>lOiklIq*>tB+$4VAV5qb6!CA&r0L=ofjF}LodeWk%{r0_?Ta7 zE3At-w>nhH|8-AUbxKg>5z-Pj5U_Iah=c zG8D&sNH%f$AiGR1xBOYkfi9;k686@9<}D6`27&KZ6AtMhRETP3~;9>A~%!z zl;H~`vuPZ``d^&jD(05IVD2>9bhyZGn%uXO_wU(z!J0br*hgD{Zja+R-L>P`D*LO2 z?Jem)7{c8$4uy64@m`PiMFR7zt4cq}j0(()Rq-9c81_^l;`Q0;l|O^?$H=kC9S+N} zdf?vrVIsA=eun$(to94Pwb8CxQsfai$lOg7oHx@`dj%u`{_&dUDP-VkPS=^))&LC} z@_+!lm@e3x8QN6Fl<>bP(|b|-(JR`gL%(d(uERRkAp!2)NNw+khIrugpbD`A5{2scNbK`CXFHzCry(7Py^yjl zWRGm@wxBa;j zvEQE_@P-HllxrkS!>dkI(QQt7j39HrT#kn`LVyd-+n8(ffyX`#Dz$>wxcacjXuDw+ zFf0-=Y}+*(b|MOwNW!L9AI1306_X|aoPL!kKV&TEowbp!9OJ0g6M0Nhct4V~X$hg+ zxb^yWu|Bf_jH*q4i@D*x5Asus`?`B%H^l-Bs2kNex}=$o2$G3yRMZGYOCOY^ocX8> z2q6n0a|vz;IxMHo7R(ss6f(vhXTc>2r8ibjsLu007FBtE?J3+pMC|1~O{0d29f*@X&z%#zR)CD0Xyl38m1zxO-J4AA1_Disp>&w^y%;aDT)P(dSWH zp`pdQSdb#jNFml|K`{|=&0`q`6>M0knZthz@QxAvhf+0-hNvenql*)SW?i}U^n7I74OFC$Tw%L{eT+~tN6o4)%d`$01A zkky~gUoSV%K|m?d_bNk6;ujGn5j-&t_TJI3FuQgJ7N+9m&tNGW(#$nxTls@V8@;`Lcbgtn~x8HeGEcYZ*ZuW zx$Ku^8XdHqq#zF#^$VEz{!&6Z@iOBp_f=<@IIw{M6g<00gYjkOB?S##9FEXnv%E!* z_3%I4O{UbZ-Uo7*^hv!&4x)*IF@s$2@qa>j!AZC7OXfgxa zpEM^)3w=)taZKnG4zRWrCy0%w3_tF1NmX7`dwZmVirLh8;BT25sD}2VP^4O?2QhGq zB^`Aav4qInU$3v_(#)gx;8p<|jNi_~>U&>+>m`GHu`xFM)3Mlkv}z<_KvU@LQZ_W^ z7J85#(Tn`g`hL|Pnlu{w1)Uny6Q)$!Y`i`0X9pOrXZ%KU`x4R2;mpnQiP+V(>#XUp zH`J)UHm&QX`h*V`A1eBHsZv6h!=?#{t{Q_%)cC%?C_1!>KQYyC4wyQkMJ;`Oc{lCc z2bzazmaLU`Iq>U$W6b(ODHA`g{W@dJSXxbFB#4Bm0NpnF7^M?#YJF08;y7{fDka*C zEJ!O{r8LFq08Z?`(ULcyN}@|TxmJ|R1hlEWYZN0gRMxbJt#Cqc1UEF<9>oZaQcImh#_P!&uuZT)-rg6W+=jjA?+u5<57xyR{4cUy8>gk2TB*8Q@ z@gc`k4VJ~VUuNhP$iDAliiFgg&@}Qea)0%dIK0!Al}HT#96%_yU01}0v#f?<+5O)! zayy7LEcGR3M3Gq>1Y?Q77~P-f#YR24`w(_tv(KiLgtO-RdX|9UAN`?GUFsTcnxECE zgQ_Z~^S#W&+fJlph3wL2xD*#oL>WzQO}Z&fBe?Tr2Nkw(qmEgZP?i!uER)fBn8-Pp zju0BYno$hg96jK*-e;~_IM4^<8RSzHWPmgpaF{e`3|9{Ozu=oiE;hOnDs5x<3)6bF zb2CW}ew?F1O~*s;^=}Ll);?p`t*T2ff;A#smx-kDNyaX&_)?TFS6@ip9m+C*g95jQ z67GLx+Aq5{i&h+4)@GQ&F9RxUQ2#n}>_PmS;>yNF|Yw?3yb$XB7MsKy#6=Rjr2yOlN-95+AchFBL#4?a1RKH*=!1; zUN|cDs+X(zk-)G9QWFpk4l=?<@ghNyQO-GNQ_wfZb-+$uC~dz$@WIw6L+_mek%-2P zrj45)d`=+G>Th@(Yd7a5-j_iph&$ACV_#vxHn!I{>h;>df|?w&rL->ta{DvqahwQSr}=9dNr#!zui^fqekv0<@s@W(y~+C3CeZ-=sL_ku z92YtQqb=)TI-un84o@t(@}pzm#q;KIEJUIDCN}5I<|*`@G1O7iQOg+o>CWC_&Y(WO zpA&A%VNUjK8xc~roVd6d8fU|1Zs!W_`edoruZPT{TtnN zwK7IOeP{YD5ciCPL?WF`T9;m4VQd$o1zxzajX10( zkKHMh@Gr3{>feA~UC!)&yPY|hyT;ea&Vn*9IBs%8^Nf{u>d^o2l?m-GTC?=|NmT@T zu_ds_z{gC^&=&z^Y3x5pZ&5KSA4;VYA{CMk7B7GuFWnZs@<1;3tLi+23Lh%)}o z3-zONkR_r$ynSTQ+JVpJR2FdR)ip<9(nFoyO5Xb%xGO=|{(HtCIQ4pUcg2D$RL4X} zRTN*+Kn9EQ&8Koi>i?Mq$Vk%a>~~S#GERkrqGi!k|7ZQ%bOeAjj7yTvyvlF->#hrT zKlBP`3*L5eja?vX9}=elS!KzGMCWZZ*0e+<;w!5 zDfU`_hBgUahO1!i!j-(W!qwhD3tv%Nqk@WaU+U=3vUzEM6O!+O{epvt0j;L^ zP%n@b=}i2}b`no~+O?7DGgpN;zt6c?k@YA$3#-R4Za(4h@LS7O3;*T}H;bsi%8^Zu zQ9E7vR2#G(c ztfqP{PgD$FnQ1BV!5I-PM?k;LaSv=^Yv<}e zhG@Y=j#i?vY%j+vsL8Gj)EQed9_&r7daV4Z*1ztoms|rINsX1fs#@0EedeX(ND=Kn zG%!=H!Lc%>nwUQwnwP^tUq$424y2;g%#|un*F!nRqHRQb&P9k?|H}h0_FfN$I=!w= zY~OTb#ZeDdTU9gb<;s;1D#BB85_60-gOW*pKio0sZ=4vmQ+}I3VSP(|cp*R&j~!H$ zGI*`iv+NI)7zA&}7Mm>QS@$Y%i1(PXI8WgwRR-Q~f7bYV0 zmY$l;QWqR@pf6~(5N-b(4eMX^FHc4SGmARyAT5>A&Pr`%QalzQ?aCe?L-eY}=KA0* zJI9myo3nVa6UDb*WlX7HTCsVmXkuu!>^2X&vnsd*;)CXQ8}jA)-)T5EnO#>z$aoM3 zvzoltN$wZ>qUM%+PUY`w#oFOzT|_3go#el0KPM|K(fVzUd>QOQus+Aar4z3csc|gY z4m$1%j?AF=Bz478!QMxQf)2MgH_D|rd6kiKWyG&YN^H;@ie|)ca&yn%Pe!=0Chw5t z_`X=GQGR*fpg%=5q}$!}`Z(zTh1l2DSJNw}lLxRjI7dbENON~IW5;$a2f2qdqp?R-sEEp*@e_GNoDyxU9WecO;;vD(WPk9W3DIcf z_}jeLiDJMqQeCE{{?Q$KovLiRpiJ0_ zuFFoHz|eP}i`<2^53z-$tlYM~8nLvl{zqY{a`9 z&cB(-{N1H}`e6yxc*Yo-jjgWuHBm$JxWLcR?E-gwMn4h8Zf`H0%OSNzLf;9DulV;h zhnGfRwZFSmVDab&5`@ejhLJy=+Qw6a1IX&60abicS69p}Qto(3r17MI%HfAi=gv=^T%CV@d$%Z9C;5x?>MS{=!G(9g~gPsuE;_b5CO(WmS?mMLqU= zB8Y+M0mVgS-L;Y}{kJI&2Yxb3=c3<^XkYT?g;~*ew1QJue^b>z6zjP&8gWH-Bi#O) ziLj>Q%hO&Im{f9GblGBmh~vtyGQyLpx(C3$e7p}{7lgPYxjq`pq(PxaF(s#r^1jkZ z+xISxsc1$>=SZ2jd2&IE>z@*`NE*u8W&C?o+sKOJZf<|&RWHHU*v`o+Rw^{}(Iq`+ z#*YH5c`~dDRv3MetrVbr+WGv_z<$4QLPNLsazRZw5Y`xZMH@6byb2{as9CHNzws}F zvthXX{55Pjtu1;De0dXxj3^d3W^3f6rp|fv8!2*e-z%Ae$*JP%bEf=kuNOiqUHScL z+Umbn!Ci70)F~6%aD^z=FFr{(;#>xzWDRbj%EsoFNjJPCiZ8w$>b9B5RB4C*4^pBn zy8$2gRYZsS$5O~~l6D9k`c)=5)=0dP%f~NF1+Y}enlLBwL9_N~eQ6Q}mQBeCzq`gd zqZvR(i;NtLHYJHNpiG(f(QXL{6)v{I1+#9i)P9vr1H~{DBWD+(wEY_b+}`etx2qgb zO}0$Fo7V7Q!-4ThkM{OxijN|$si-Q6uA-7PI8QcEnI0wOKljdXW|ARvo`)Y7noba%f8 zzrXu=|K9_%XJ)SJQ!{J);~c)aLL=#8M7gZOWwYPw1-rH3GGD}5rMx-kn^G!{cO5t? z+Xu{J060D8JtR!qY;Jlnn*5H5b9;F zEiBYy_I6sT3(qYm*tbeS;x&BZ8-+It;>vL(?2V{PVsISPf=k`>s|bGvzWqLV(+EFw zY3F6UIt$R+p(9@xruYdUzDM0qstKP6SCYF{CvN;B8|aYUIg`Ix_*B|tHyKs6&A&*h zhhT-u_T2Zl(;`o13S^FF7+=plv-0*RxuSjj^BnlQ0;6(=`;Y1@`~m|0*54PUR%i6T zZOfa|*`Ou-Z*i+H4lbd)3rG;S(mc7%i%^abWT3J`)Ou z^=*B1%Eipg_Gnpb_yTeA$io^&-{P8=EiP|3p~=MCl`oLk@_7HAk&&xnYefAfHn>KN`L;IpsQD|+`CN^ zj(|M^d9!WNnxC`&m3Iq^XcgT)K@Ka&O_mz_G_P&03va-{W({Qo_@HHxygV7*SD^|{ zCcdo_#Z)_m1Vs+p|?5ZDgWLj<>uG8mDHw=WEjdt zyQq{!mF~Puf_Ggn1p<`FM}ku;^S>=%&#n_r+e!e7bYqjTY$AS$RIdIyjb^&ANQ6{R zxF=4!%1_i38D@F)L-evD(NU+2Jd{%^9 zH-UmaAl^&T*-2btSoM9U`C6=Z$P!)5()($V0DWi&*tOc5)T_gc)zn60A8p)gW7=Y9 z!G^2g-25DA9ay}lynj}3!%Mo%aV?n^9^=vE8|}>Bp&+ShqOj^*s^#IO)|kGZ&mvPM zy>8%c@@~}*uc>AU!7R2u;$jgbGrI{lRO=Qo=xEKq<@ z+2?f_aZ^MfEGS!s0SWS&W61tE=tEfkTk%S9iC>(<;r$+DSMnfuCpdDm{E0ysNmD0f zQzan&wEXK&W+rfd`9d}@1LZYMrREBT8}$+w5GiCL8U^>8MAd@v;Bw+!=2&rwsCW&rhC8*pEM%`CL+b(%58SdeCowrI+{qyicB@ z2MS0oU3;~2U2hZc=|!-#bmr0k21sFLz7?4y6}RMgnfYnu1!}H#qC`ZWPJMAr%U)z) zTWFhATZoVBb;YI8tUOIe8N1D3`9_}k6aA^WL!>U!yeFnrdv+JQVi+3yh_dIc3Dm*y zhBk9NCtMv^Fh78=&H@ywSNfkdxdXfZ>Lh_W6#shX7&w;#Jb46{JX$)M(FSfIS9DEK zbennQ5cY&d%^g_?TwZ+02?<_eLh+7948&`gg;?R+0LD zpqC{7qf|Ko;bl{PabyEy3a{=^V{mkwgQgI+xm&XiTb0zO$#+HI7+JZrFChFhgh|L~ z?RK=*wcVTUaw>&gHc3pei$q*ubsX4L%Y8neVeb0>GGJONQ?`8>Q*=bYO4X23qr`Q& zxuYOhYKprlAhy^|AsLQxg_v@?l-e#4mpCdnM^6}!_b^JQ_YB$6{|>jv;0}~d&`TM_ zBBMv}*)7}u|2Wh1RqkMK?KoD4ou6+90f3j7e3W^XWN_bN6#7_)sbiL`F8pvh6 z5YFbx82(T6#If{g7o}A%Iyc;hpGDaRDEb1TPyoQ?xs4$NJvWvS0%9tPyXu}q#46V5 znu^An1O$sYPKFL&KIv)>7KawMSA0YOX-Lk(@s{*8o-m!pW>cCjuqYL-YFWF53=|4&V`ndh4qZHEQN1pr+H{|H2l#A?WJem13XFi4( zc#}!jdqq|ZYAtrMx4bWEI8wBp5|-wkA7KyqmBd%kS9lS7NxMg&6@vp{sr|L z)2y!uVLZ#7NI-)@tTv3F+?`S~Hhpgr3wjA{FIJb;^ya{kVj3ZARt(gkHflFVJR?$0 zx$^PZ|82eW!?}fOHpL%J%(x?q-Dc~9(>a;Sc4<`~MZWwNSVvyC_v+M-PR%2(P#k#? zQ1fDe@22)lU37+MgVK74hVGYf#hLNjTgVB^lNo%K>QF*bw(*@6FgNrGv=e6sqJ0~? znS!jh>-^fQ2+iZ};B9<_@;e<{lZ&9W#Kdap1rF`mLpF$B3=_`+onDgkGd1Oc`%g`z`a2Nv~>8f6pXbI+Li#8i=Rt()!36CxvI| z9A)om_V<|nL5U(|nbIyp$B6w#MCgWh$WR$M+a{}sN1WrjPQ{nL!Ux0@4g@FM+__=> z0ekj4E2n2*rVg-#=qlRpAfrpIvR=EGVHbjI8BawsD+_fK%Kg>?C2+vRy@|Q#lL!-F z`u9uKt(dJ7e3sWtftN#we&5@8GITm2NvQ`&J>bd3>KeVPYE-wDWBy(;glhDTytG&W z3eP_9jg1^K$5;lvtfA;v`U@U3?6TnpEZ^qZ_mmeR#d(mbWp6E5h^Krq(2m8^flAAq zS*gfY6D--nMGGw8avZB>XjiD_8!THeDn_mi861KWvvOqUhI929d1*e=l62BtAZFEY z;~Nn89-P)EF5L$%bu(Lb ziZWtc$ctCA+rfs1jgt$80jJ+;og}=U2r0;3`bHZwp^9GBmT4ImR{V7EEB^UlW+8jK zJX`;l*PB&E9Zavl;95it(Rp0pct2#^9>-5GNDf9OjX!<=N&o1UJoBrS5q zgj9r39-_q}8;Q>Wxal^oPjaKrFMhz;WaaO1Fn_Y&+Bd)D_uh7CcZc!;&cfSw{B7D- z9wIF*XDifEho!Sx^CySyF$=X;S7Rdi4((kJ`je^HGoHF3jMiWqu~vuIxQ%Y{~uTG3#LYL8K?@$NdHC{HXs^$5nv%Q{PV5qgji~URi$rhl;Z0!~WLJ zx-ml~IN||4Ite6Srpv-mF{Fv3`>;kp#4Pb`Q6ry-^1JJkHG1QtBYb_=bb{pda=RJV zQyRFwNaw+b!&H2x>fzgk;eMJSUG;DMlELI;7t`00r%~2om&u>zwq?0piy@P7A^z}h za1~CBSb4CPQ#;K6)i*?!?YuCTQ6UiY&wh6j7*_ z^nMqg1}Qu&dqYsA)fxgH&T^hCHz7&cgE!~J5+gH)P6u9@zGth!*iBtekJfCC3#`C- zziJ}IvxPYCoQ({l#b%nDt3wdk{?Uoo zA{9J04ihrrr+2~_A`i-V@u4yDLb7^|m`DFVavjALI%I{d^SnDAp^K%b4QQsXO2P}T zB{(dE7F^%dh~lg+r;W4)rvQ71@jvh~klIVT5C8o5IV)u%5=6EK+xq*tO!XQsIsL%_ zoiA=bnEbH9c7nV50|}4%|NWa6#a$*8W_r(1ct^TI(GkZyrhJjqxa`h{z-HOyh=RBFUux*-k{k)nG?q z0DsYQjv_(%f1_KkL6(#YdnO}(86pbepimAp`{vL-u*twD49EeR9{S?yrXsb)?SI01 zHqMUEv21|p(a!Z~EUck*i{j81ZRxQ6XnFmKvdT5atUVy&&qmz2FJj=q}OoQvm0G3Uh-I3LPMm965D!MXozz{utV&<2Sj{Nf?^nw zL9lwHCXwn6iAg_Kk-)#XTTjc5;1(lr5|)riJ={~*@22Nmg_F<{-TJmyU`dgCUCdzO-OH ze)~0-)$dq&@H%75rL9%(-)Hd_M{kikNZEtVpTP|1?tvi|-MEhS28Pt0>KwwbMfA8xi8X%i)g*mB97G%vd^m}mA&PkjaR zR`6h3an{E80HW%Muu}d{dmKU!Hl|pIGUvs8C|ThC-7|Z!BuathBmcKs)^LBv)+f<) z|B+P{(aYp)NBq1uGglPAqtT3dnSUxgRy5hjIwKnQEbhGz;xa!=cR05Cm%%t~ub7j$ z%obXJL2pQI=~e|1+O$=jk|-zGa76tikn6u3^zEwM6JfoC;~&XjeYzBhGurkabF0GI zJLqpqdGQn05pZB*ertl<1{GTwPVF< z(WCq9(GDRlp$k7mzo*)V3NYjxZc(DLMBFY|PhDW&!9F$2U1Wwn_U1{nwsdu7b$_g? ztYgsZDED6N&bc!ZXgJuTB)3<~?m9hu1p0{dpT%as?W6aYo22L9(ID|^=}v6)9ieAU zn;~=R39p4eb9@d^jYiA$pS7dRajLJ!>+*_6(JwZgO!~P8{!s_fKU#0CIiC)Xd=VeK zO`W~(R;0yNBu`oKgKbZRzFFLTTAMcwhCV(Tf9>e#@-xo)(Aq@3AG|t;Ugyg-m6Pyz zSTN$XFX_5{R2%H2T)Wu(Kmq|DzE33kEhHdd5`cCf1Z?-Yq$FQi@~W3b-lTSTdV0F2 zFA@iCy~WzPOpG|z)8dAkoJoMjvJ~~R(r^Gj)lWV9N(9vcxXp~yc!JvKvnGYgwzJ8g zVsY9FWg}N4o{lK1cl`g=-6c22rQLhR`i#c`1Qc6z-XO2Y zfz1HU^Z5;pITqoth=K

?5jAn6m(lp^pWKsvvr_L)7;6rYE70+HW10_r#lf&kj6? zMOxetDK8n2U(p5ZTD25T_^@DYA@$YV#>yyU=0L1fFOBSY50gg$f~X52V~eP_Mwjr* zwyE@c039LL@+H6SLRYI6i%1BR@FcOb7wR@xP~=@bbzMa_8Q`XgeeO%vNF`2x;-Q9f zP@MtPD38$a{3s=KAB5Zv8ptQG=WNhRs1;ZNIlv*6{s{heI-eap9s}k6o`882S0I`X zdcQ>YF!6fq+#3VHjP5M+MUIUWyGSUciJx*p2nR{UhU*PUn+)*K{ELDV{mN{YZ??tc zGzke$XFIHLu%cEE8m~J3j8ZO>R^5w+S;H)DU~($rWC65LjZ54LQ^5V#N#R$i1nPdMT8OeqJI0h&`=jNb&OhFNB>XHeg~+2B4(xCfGMc^_Kh zOF8{%je#=24h+uw>2s5$*Ru2XC6b-~qCgP5Nx{V))F(qRMUX|W>bF9L@7d$s(H8A! z{g}9tt*x!K#R7~8#3*Pv3d9M-w@$ZIR0dTc*@-Z!+ToJg|XluFXn@YkaXd? z-|4f#Q#xg`KFu$-{HMc4Rrx%wKUFQ>bT;QW_@@&kS1m1`UA|L)6*e{| z1w7c*JB59wTU$ah#+`#(Jh@zO@*ymMtAOa_qNg|BiWa>n^qrO_bXEHzgUtM!ipWn5J%YAB8;vrp}?pDqHM+ss_s=ed42Wf zgHnFfoH76=dn5ykCv36OMRc++MW}#M5m|K3w0bg-E7KW6pt`LcO4Nc6zZ2X-eIRMtzGC$&{%YOy(a#SK>!#(2PF z5^YiB!p9>{YkH}jTkC7zo19TQ7Jt-~C>Tew{{~mgoBevslY}FF>IgB#78Tk1Pjw04 znKH{c*P(y`*PH_(I>`M4|Jz@wdBFI1b^M#Z56?Vv!<8FiiwHyB?^_7n_UN4M&q%cR zhc;dMht^(nfO8+(vhq;>Q?5ka-_`3n;+i?>k;HOp7|~OcBSk?dPrvk{1?ixbBi4M_ zlJhD8s%W*#?qc?{atqw8iROe>s7{!y_pQY|{(i9h+F15EZFj*qB#CMRIA&xWF$Tc& zB_)Z%SA>WDoV5N5W?JH?oI(KiB%@rFP2gY;adWJbYDMLvR_ei&YQOF8d9V+puIc>? zk<<|a8Hae5ju;|^?H!bE*HE#)Nd5H=XV#WA&jB8cgy%RGX+OgYEU8pDaujl;{cJHy zvE#(v$(UnpQeF3+mA}ZFOGX<4^#&d|Va&LyGN^G({FN^W%jy^bo!iKf5AekzBv}Ly zY!LNg01wvFV0D+hJ$*YCt$0v+VguY^ALP&m2oi64czQ-QH-Eb5=<^hf%WBStXp*82 zG5K$Oh$11OM(repCDz8)r9cCU0rh^aL~#b~9+2Ruyhw)eC7$=`ZyW#?ByIM-jp-94 z8nDsZBge3RQK(^}W8PSh#-<-r&t039uZ&-(PVQLf?&46%w{GCDlz((yYA)CPh;8%q6>jLS-(LrJ!7n%55o7GKy`O#zH znTr0lSh7_Exzf|U5l$`ge^}C>^L%EgeOh>FbK$bWq*Rf%KeR`O(W5~~#9HB}yMuG<=1M7oa zgK813$|pFRKDX~ND1_y-lB^elq||U>G5mSlIsQ~+77;5XBkv7h$Jn@CbHs^coxtMW zHIOXWtBcf2&{sKmj;0lrgaSbV)fabehLt?XIzso+HvV8HAvg`6hhjM$#G`mQHh%i2`OUMsPwnLx6YuDEM{;NS|=E z5~}WcAms!5Z0C8O#Q|=&VW6?ao0}+T?Wp38?&fiF?@ev)&(0W|h<{#}Y=LVd7DSNy zL5=?O&!?ixGS zb&Tr|liX8ZgakRfc(2{U&mSs#6rU4$%hS(?FDHT%xLUYZ$N3&mu^9 z_Mp-(b?#CTc6uK3i3mKD9VQ^X2g0lw#JQaPC*-emJ&D(*P8t5YN~ z_8l#SX0go~5qz@@^0X)E_ODFhXa(VwC7kZ~+m<8~1vyRg?p(3RIdi8?i(koTcF1dz zAs+lBEgBN;KI0wGf_Nr&7?OMhwll&)oO1QLgJKDM)v0K19S$tzxqU)cv9)IHtzx<8 zt1sH$Bb&UgpSKES29A$&AXEk3P#eeJL1U~f&{h5FlXOT*%(<~pe4E9!Jk*IAS54SgPv)k618X0tCVH|GrP z4L+2d9O)C`RZ3YXDa}o%>mVs7>6RZRP;+(-UT#mr6>G4Se{7jlqWjFJXaGFr?4mUkvn zITGi<+NmGH6#dp<*F!v5r&(LBoxQl!-T&&8f7g{NcM$_DO65`@H4jM zsRJ+wGCqSY9fKDIOXk!Nf)ZklmUIc{iVV+VEwDGO^#Q?MwIwPcR(Dq!>GB0a5B;i_ zu+LskS1Ji-N>eT1u5I^NW;7A~dB`84{{|-nGv&R)Kqms|llYbl2TDZjn z65wl~H;}C$4;@?0&2*vZy7{BUD3X$W?Q~3_FT?(AP`305VVx?~l=@C+bi!Wp?zUTc z^9xl6j3F@qY4;C4bD5Xln`Bus-LY^|f@Ou|0eFOD^bRrNv`(<%rxpBhVnKy{$=df1 zEG}-Os0;Ppc&fWdiS6WJr@X%Is_K+yK)4e>@NBZC4WkR)cksyf3o{U6fybU^pP@j6 zA0>nt;pYD-T&`B^n?*aU%Auw3-?CMfz?k9o3CXULk9)bUXAi20tgy@ckcwgSXwDPIYP?VDd zfhS%n5ei6}Jza&AM;~xA=*J-o`I$f-Yvg$;a{)F=X)o3K+g3*8+P@`rb{&c_SHj6m z|6(`)yu68hX4`?tVHv$t#xw{0oL`iuSO7oK52~YvW0`TYqwJo?Cf3GaM>%3OXPNUXoY*z*F-o%X|M?q@kE{=es zd7GuhKE*zRhzPIy6{KOI?szUj#Q{JQ10VuHn5PQ!T$Rn`8dt3_Pp>!=k>IHdeGc1R z)PA$y0u~)H;+(%{Z;tjHhY8)77YR%Jlp1`jEvipH!?4oxqU-m*B-Z-rP3DXxSZ0s2 z>9kwZ8{}0rysMI-&!x$5;kJ^!>Fzl8N|O4Ak`NAkSF_FZed!B!rIgb?KtIs={su6I9<6QP zv8Ev6JpT0{1+a_lBt2zm#m35-I;Q9Qebk0C%{KgPGqs)wG3%b^8X=ntC{(+`mpe{B zTMN<@{)ez={4%~cjFF~(lp6b)_cm!zF?8}d=HtJWX!o2Cv7%EeKb7fF{B%FcKvef) zds2u88dL}vf|`U;#j~{6^H=xM`Q^kD61$bSyk{czr#Y@_%o# zfO6;-L3=^Hid_48!Rz6#8Gr&y;-mD2nmeN`BA)5-kQQ(l;MAMtt_>m>bRx#9;xBEM z#8N>Su9AQZDYC&F`DaRgM8Lu`x3*9}JQgYT1=2-F+Jd@gIUx^ZpHC}NYN-`EwQ>u%Xp6l_ z2JwmZ<}8#cw@YnL?HtI&^9dv30`kj6xJA$y@~JqJ3ZBMMNudw54*nw?X)mhSJ92jI&0C0K z6$(RxLXzEI?cq;Ackidkvd%|2IxsqPP{RQF8|z#UgTbH=1$)j*QMSw6j>2AAHH*}I z3qUm)svRvFTI1HB7|4r4zGOH%YoWB#X|g?KhFUcm{y2Tk{^m@M`ZS5zdHy?A1V$O2 zu*&4}h_3)r^1gT~yUL;OoNwGL8byJo<6mxEA@UL-6EhP%ilD_b=}RraqOpX6@crl* zeiKNunn;kBFuvdc=sFf{0A+(;J&JxC?oGmwIj$sg{hpQ9;@=cj0xks2{}4bspNcqA z$^o3Vr*slQOkGbpJ$AOr7^%rWKOYNP{tCW|{0?QMw3-Nd)N!g|@vSuu-=?H*1U!6E z1DK;rN16A$Kv~6W$?q}=sQoK19;S}G*wmCHK%VV1&A?X znw0J^?dra-ecp*&CWBo4{eY~%#T@-hg2nFux4Ntr?-(1nq0hZct;2_MSl~Jm_ zcd~#r>r|GKQY#*DF$53=TNjQpPmK>=Es3n2CiYwb8%PPrrwKfVn&!<3ab7kNeAIx= z1ILNx#!5&^{>AO<;9TCb1IFO7MCeSDTxMhJkX_=+x3>3`IJrowhOpQAA*0}&i z`u+NRg7=0KkZ0aJP4apHJas@<9wW

{OSxG)Lnj0>6Bq7OC1doBPpHb%28St#Y%$ zdj1`n@;%jf&XC5eS>o>E#~_;^kpi%=z0tdPZ z*N_AoWUDwmXKGY2N^=7r)P=EU!In9OiM=U$IMrkd*e?_m%?Cw@2uG6U~M4lu>ZYT)$M zQzjlJ6xl!qZHZLxG`*{tF;Bj+o(U)=RBH=q=Q=!iSL`%%(Q_<$=63*bGFNtTOi$hY zKX7C}LthbN0<0e6D^LP7lG>1b+y%*5dw;YjOQr%p)liO7a+-|DLO}Urv#4PhQWtx+ zFMl-2m1*y->p0!?Q8qV;Oh-s5F=zjjSfXy)Cb-$GtsxZ8I|c>&OMdgW5 z9oZpARcyerev(U?RPhUZPz3%t~da}l+5i4hDz&)y?Z zpp0>piLy!k8YT{cbJ*cUGJGVEh zO*URm1Kdkhg~97Q(s0Om z#*^gH1U}x=#EAqwLSUr}P3R`?s#Gp;xPgG0*M7F={>9{`U(O`2__LncSV>+6ar##> zZt+*0TJ{A2X(RPnL?U6P=+SM~pyBs}drflHSl&IQ+D|vzOCX)_!WL~4I``t|Bp?{~NdJ$e%L?j+eB>?tA5VAKw?A=B zq`~Dsyl3PGe()gyN-A~wj<$5qC=BtWYNeNWt6cB?iVX&RTz069WM038|{28fsc06hHQ6 z3ck70VRJ-YbL$1d;yCDY1<9{gps}(ZfS`*^r=Ob*GGNrbxIODLqRYfuC^Gur*^xcL zkFSt58Xb(RLBRM=d;cFAS^Ugb+sIdssbogOuEtXFNPV?cgc0tovpWlVI!pulq2HMX;$wp}v2r}F ze>2CuHEs$%~%F7^m*|9hJdh*5L%%s5N5__za2ZjtmGIGZrd#%T5> zOrDr`8~zQUYwDL!F`DF-SyT9m62}?84_N3yW~>7Nda?~Vp=7=F`rP9}4A+6l2rE~u zzU5^G!+X||U~~vP+Td$mZ{sko0a_X^`Lijv%9V>ZGey%FDWPKY>z{|+i2isgWyuIs zlxEe`|IG1MT6LZr^>E=$#B^EhdV*8wq!O_NgM(vV{4#$Y%0dqL4qJ zRU_ERlpPXnfVR$X$O>sx!#+FSJFl1yEn)hfq7r1Mi$Ea5VYFy7}&O!5w!0FnS^}Au^>hY%;*Qc09v{0l2 zSygk515}Rz?CPU6h(M51Fok;pru`IiTT7OXL&fWHXklX1Pe)NG7!6U8)(( z4v&u6rCAJAUV6^vsInJ{KhGNthZqol`A;p6+IWvCHpyPGs<@4P=95eSk3qzLd^LFu z!b5CihDU1CSUzN38(*;g)y<=C@)q@7qtV*reC%5Zl0u=kK?m>V9VTcQaMg2|KujRP z8bbY-MyI8r1XHjtV!AGAjpQTZI&AL?dRt+E`+H!v0pf%xi0;xn^v50Z?<$UjWbJAR z;y)w^!$A%QcOeSNp<-V7`EMh6_>w%29QAiONvzO7I4A2neu;eHwxbKax zJYK}dNXDlsmK4|j77;-asaRGsl>-M(kh*Cdu{lD;l-r0AW%@BYrr6q zwHR4vy7r;oX)l&N5qZ&5|5zAHNuvt5pEHbXEHPG$aSlUTxdr#TW$xCCHk}h1d-awD z=T?@43*fYqq)A7KPVDZsB^Sh&*0F@qO_&q2riMX!7gFf(h}KzFlJVlWG+EdA#C0u2 ziJ`{l!bPmqy-0uZ+CG`J%^FYS!V^wDsa>caN-$hYl z{`~j25vSn9Jscdymt@ThllR6*aX$<>S*~RT*=I%)bVh{x-gA3bdy^plG&9VJ97(s1 z8sg(X-%pAmU{Qu6s~*IN4HXmG&ex?_X$^nU4J*IiIPK6%>I2_iPLza4rYT!8(znWh^OMJnDHQf#?iyWL7@e7j1+9$12jpk5QX!V_p*|>VD{(JYvt_+I^DH9mrqBVETmIgD09LsL;>@#7}pNy7(L145&`FeM_D9!tNJzQE$ns&X8p6dpXQS0`yy6ePEq`h}27 zlz_5`?ZvjhdnP<^x|-ItCoA;HnQ?*4Q zkw*Jlm#Gn-`0-(bnGA=dkWomVjG#>W9NM;~c{Jl#*)fltSCbFM*nFtDe~GQmQ=6)P zF1sE)mQ;#lO5610cGXo)mqa_lZ}s=wOh_2CqL{CDgxGNIEHcJz>STK zwl|r-w#HsBJqCuK9zGca-1(nB>??hLD{)7T95Fz|W8FdZr0X9saNFovVd`fQ;k&2X z`F)9k-^Vy!^Ms`4by>Rz#I9pT&S6cTrjbaCJVzP?SwdQfC>(PktJE9hidevY?WUla1~ zT_PYe5&|BqOA5+SNsXT(bjN}SZmO4(N0ji=vNe5Y0`s2dWOCxJHR9#crw>ebO#8(r zuRltF=c<9W4KykZ%qBZve8dS%YaoQxTZ-)Ce+7;Sx@qjJNp^W1(y8M-*jAym>8G){%%l=*UcP`lx!-cz(^hPdRo@NG z+&W#FgI9iJnj|#!16k%Aal(SO7xHXV{#!pLLx%l=W0$fS8#KB3LEu-Kv?bD5IqvOr_TDy0nkz=`*CL$A7 z@m>;sDLY3Gw0HVr>wod)ydQsUx<>V4tcGV455N2Oh5z7q>ir;*$aVVs@h2ruUh}CDQ%ZP%-Ok%~zKgQ`#-vj+()ITxyqmrH`NISDIda63^Pd zJ>67tW8YtRJXF1c(&b;dB2M#69ZB=WQjIt#{Jz_EG7RS1qGA_uzcUR>8FXAZh~2m* zm+#s?GMa_9=61t<6wH(EB3JuHHmEJ!`$J)~Qx#TwYKs67sF99$_%qU+5yD?%U}a_gJ7QwJ5Q8 zGq-Nddt{Nj64t(`el!-d^ryS18+!HFS#5cBV@8zhUNs-Dm-80!prGr{ro_rc;SDg5 z&aGJO<4;s=>^w-~vn|=vBy+i31BHL+VSUs+$m^Q5;(BQa9VQ}LGsPeLifRh|erIcM zKgimapr;2VQ`l2HI5_b(rf*={tX#6L+}(7=elPnH6qA=X!;|T7Nj!8XZyog&R%hYi z$?dlvvtg9{`}X(vyZUNm!!7k&^pIOSO#XN>o;WlLKiD>#yVU zo<%=JnR!`v%Cg+3G5E6(iE(;ex?e9{5Z!djd(E8%aO546K zd1O&Im_<=N$1#1kxKW(FUU)TTHhg~Xc)B3D6>AxjVy`t>=D&)*JD<2Wka`aSb{|}u zj3(YCin0c}&uE_FCw{R4Mjt9MnDTBWpH)(F+? z=`;aX&s9f(09SkpKWgsm?;mA^0fS*m9!(~adYh8=@KRz7D2v~UVV)n;aFL&gI$I}{ zZ}ySYfua*CHuW@Y1}?nyiz<94;_iAkt71(S>Q)6Q@>@Eaf25u4b!xaP?S?bYWtX5y zIvT{YgmNYQzOiVjv!+5j!%6lw{sJt9cxJNDKh66)ghePN?lt@b;I!U^I{0+tc4@)! zqoI2r+68h|u_1dO+9QXOTNefXg9XcWHOvc7?mI8RK?o=&BQKlmQyPriV`#>1(D9JG zz0a?rd+^LTz-G9Ma>QSCnwzH7u5c^K(tk{6&PAE->=s7JF;{~f3=nd#kdaYW%4IZ( zg|fASvg|NrIQHoM`-h>rH!t|o5E6Noo)fh|Ue6x{Tyr_7DiG^w90?40HZ1*fvKWFE z&R#E&y=3Uk&YrV9-E_>m2{|xKDBquDBX6o!DVyVZQT7`?89JH}+wn}QHCg`#IyJET z@f2VO7Q@#~nc0F*Jd+zN3(fR;bG3$o_NE!yEaw(w`EQ#MRJH9pC@qvtc4suOQZ)bM zisNFb0}nB7$N36P83doIxD$7VYgHRV{P|h}V-+W9qENS}NxZlPag$ zoYOSq=io-33qM!U@%BtR4P8SR^=-0LMnOZVbVhYTQsdc1r@sj|vghAt9#&+>H<0S4 zwN2?Dz@EeXVw_91<6C~6GJIXl^PL+&o+8!W7db>rM@VWFg#b7W$fO(ch5DBI7~>d2 z(a<@{M%cWGF;a|uf!Ja~YK_h39XN}PQx=v46xIRlX)82|MqN z9jcU?R>SvzmuBPXl=SN?!<$2+(oiyHd<>-tk8gZy-JEDBwwSVNSbhqB!@k?o(eym$ z@p*I9y#^*B(HPJ1qb$v#a{@vyDq^uZO}jH)D);1JJhEQ0p=gOmb^;U4==v2I#YAIq z0bW;F06?%rYBQ!Vo~1eYCK{g~uN-u%JzG$w24{MiOQ=@5{&lqChRHbNktX(G?cL3` zL}{yw#72X~l7eYV)M3n3CZ>}(tn2>g`si?M7q=P3$fv&= z`(ztO(@iTjlfA=3Rl~I;$k=Nzxp@x9L0^?tto2%zTzSCnQQ$9#_s~EWlOisPHSM>? z4jJWiP0GrNo*-8A0>~HiAO@cOpy@U?<3MuxJxhfQSGWl)VAO7qQzfLeXQ!vDhlN@6tI|59+Nq36v?t*w3`=vF;+A7QWGoZ>Z&ADp zSbTdhL8F(xFFYx(b&Az(wm1{me|)86KCYngb<{}1AU@XlPf()n)t!fwUOg|PhkY#xX%j_fucAQx*-1H_`okhD zYy=Vb;t<4BZDwfBwNwD*Nse(KUp{XcNKWuIN0EymJ^NHX0m@abFPjm&K(Phc4}!L4 zw|cbe$;0xJUjvZ}JibYl!UHQm*wD7%R#1^QNUQC*b9DdYc1>u;^yNtl`O4|k_PTExo92+g0*W!E%iC!q26yQg2j>a()9+2Z0MCA>Uee-;>O z!`pGJ5%NHin#&vATZcSY1dKMQ`*02L&3Cy!(wT|}dI`lK1eEapWLUohCR;1ZzWSS( zw=zFznX<2_ZZ#?2zDU_&UvrVDsYbDxP8xD~{yru4(_CGu)~~QV{=yq3pp2cksx2uS z>^X<`ty#@Z7PKieM-t#7u){aOllu0mRlX=wK-EE&^+JVR!MIzQ3Cc0VbHC%ee$0W} zhFe1{sFJ%We<3-Ls*Ems?jIVvhv;&NVj4hJqb2ydUehR@iIeaWBNu?8c=X43t7sbj z+C-~iJGY-}ZmM`Q8F~$RJQI^pqN|3Dn@5v9CTo{`_2%+@gnARGD;!P76rybu=aG{z zWiQGZBY`tlDZ^|#%h?LCGAX0L$xCsVW&7+1*0hQ+zwYnw@W3s6Gov-5Ii&kHDTZ>^ z(zBE6Yu0Qx`dv3TcIHQAD~0_h>9JhN z>DxJFjf$wrU*IDiFb3>Uz&-2BGo(=B1jW3s?6}t+#*$saz0mFwke;7pSI+LdvUzQd z4a$$N?D#FHE!CY_FLo%)3&xgqC*it#U2@~F4yysTzR>mVW-Ze?i*o?xoLgQPg6Ejc zPR7%Cpe_@DVHBiE$(|C%-DsRZn)fxEO)85y7P#Tei)QxTYdz0hYb{ukCf->MAYck& z*nfK3ryrLx0&GkF;78~np%vQ1rwolPiMIid4k9!a=wRqTd()X zClxXwH31cB()$TIzFUx~9aoGi6&K^2<_*4a8R}ToYTE#AnT~Y}r&hg5bR5*e=(M>q zQ?HI9#AyjUwC0?_^sMvEOh$Am-8Y`?4X(-T?(lY`x(ccxhTrU*N-3VU-B)#hQ6hyr zq+^YO`c~hSZv}u+GmBa&jhT9#n^7|fetZ6qQZZHH{lInknd!P2!bpLCR->hUQ^nzK zg*iQ`?8m21e)_n`DQS1z`7O#Py2OMH?qv$d$dJoKugmUMceVNL>oX- zHf?oY^oNSfATgLOtrz}W`qQRe_9|rockv@ImkHERCbJSbB?Ja~B1-<5ojOD{jrr1w? zMd7`xZ_BMYNW=V1A;6B%>%4(ol|1oeqw`8-fuf@K1lPqe3!4J9ljE1-3uMsx&*J+F zQ+=B44)&hFTyZu;@hc49D31Gdv}RfbQz4Uk$AB$SN%BFgLG1 z7wL##D=HkSZUjMk!U!Y)uJ+PY1T52T?vwZVW4#UOCo9moXazs{ay2l+jSP{od*pxn zU)jESm}<&3gpmDM`%?o@W9tjGy4_s}QCh&;`NL24@0#9ey{%GR>gwKtL)DBR;mu{N zWEfcf_^4eb;Lkkh+@vGptNG@}Xg-K7cxcdb+I9}z4xsW0>p7=ZH@(c1L zvA$z|pIf%U`v!yj_axJX`v1{n10y428%!Ay5vE7dKEF$5|}5~2jHxT|hVib`48g;}c-2$uQ9Kvylp{4L z-x+q#Zq>pK104o*6LzqRT)!zW;CRbr!DUr77Tp#ObRSqk(jg2UFpcPrpmxuW_io^c z(9yy+x&{$Z$M^RRouenQ`M|Deq6Qxf(OgzkZX6yg0|XJT5l#*5TVB|D=EYG5?hfH? zf@YFiO+K3cYN<wd;ABm`*9;4eIH20tEfZDyALOF+i?0F%Ta8HlHs+(|E!&le zV)ULr-z*UZa>G~c;ER0ZiN`}gY$uAWyH!Aw=mt-Zs)APb){=biJ0jRgvqD=~9DHFC ze!!DLXZpQ@1p}m5eZ)Jypw6~*b!@p~wE&g{Q`W8~S?85KL*y@mA($&IhuR?VWWYH^ z`1Fyx@-Xu{aNl@?GqDAag-IW4leist@`ehv8Uwq;N&raj4jEQZ5ggs(90yoU{sXGzSUgDt`qbK5!nXKlrm;nkk<e?| z-LD{hK>_l`zzgpGUmf&Y<(i~L8=l>v8ts6oLc+FmdNMqHs8GN+v=(&Q z!V1#*7BNQ7`wLQGgNw@+9ou%N^BZbx9+QBSnZ+Q~#}E8xD2unRZImqj(lPuw3X=(k zU>q#jV+Qz)!98%a1SBQE;lR)$f@SU-WcDCCuWfJ@F`O2OZ;rkI^j0OGIFwJ z7K^)Kh8tiBt@o1_cIQuL=PBRfW6~MP>;%AL zGTZl3&IIc6tsZw#Fk!EmG4=t-%4unX3x)B&?eoTWkv;bJhDr7#LmhMdDp3NCgbhEj zgzt?IqyC9S2_-uK-zZD<9Xoeme(-H4Q$f@yO?bk_9GF$KEsqhC-VC~M2LoR!0#BZl z!4DQ`+X5m1qr~_QZjhlr8spjDv^><}?2!q5LqJ!^(1eWL&?aEgWobfHV44tBZ|3D*?18gijo?6$kB$^0wG@=9UwjmgOiKu1bI15 zHQLoS?YfEv6;^50x$!$zbadZsTnL7qyWaskLHC6!cRJJEAy5nsWh!I|2p7@S@qyd0 z9^<7fQ%+p(az^ad)1?=rybD}fBs|46BT<^OB3#x z>>EHg(-x|tp4Ud!^2C90A41rZKj9OUIozI3KR$p^t&1)fu274M%$}Li>xiry`25}* zmZD(DmVFn#k90^%U3cYLBWZsCP}g@f9|sZ_4JgOomL1mDZ>QT#!pO$gwJw|m7%B1^ z#WZxEY%6@jN%&(abn^_Q8#`5l;xlGb+1qL_2)@?8yQm5hSDp+HF&-Eu648fW=42yw zB1s^7!V-YaljvuiB(mWu+VF&QMA6^qlhfHH-V+-U4Y5;1zKzEJ*-ouvJ;_gPHa-;Y z4(~X9!8SteLd8>wV3R*5-Y<29~;ct+D=&%G@uh^`K z`TT1xG6x1#yKwDHG}jTYV#>oEd#Y7Rqc#J0%u8Jtc{hwrR55;4!|!VF{g@rTu!;8; z+-`;8#2$s-0h{*{<*5e=zvkbmf}`cku&b?g2tejrwsoErmb;+5Cr#Wuax77<6Y!yU zVcpY>U-NHT+RFlz2Trb40a}j7VyN?jt<;$cam*)R`k__Gmy6c6^xHIwaYtr{D2{ow zQ!OhusNd@s2HKvmlno=cYywV~3Cza}u3Q#ogKsAuFt=G^V)=_nTuhUL)c|jouOqSE zSY{pPS1>9sOVVnwezjcC=Bb-o-NB|39FSrqwbV1$v2I`Zx<}0Z#F) z_!2Y@S5^h4__cq=ANgnmO59^31pJ%)KA6k3Yrmc&YN&hN=H31Zv&D->hDn{kZ^3*= zl48aGlaQMJi;(71;CN#o`4ahh-Th6~=(`t__n*X1%37QPjgP5w^=&NGqLb&(Eia`_ zK+=2tNw8WKAZqn|l!_i9uNOA_2Ql+J^^DeLVw@BG&d`_|7uNvFK z;*40O3j8}*d%UC@-tOCqk>TKkKoG5cy7%rm*E(ccow1)n4(gBq4K**_QR)TmSCer# zeY8VfEA4{pLcZ>Ux+m$7l%}%MVJ+EX`XJOcb6Pu!%ZojL?tgzv5+aBn1511a(IARK z`4r$5`~4W--woEOzr|v62xH3@M^nMUT=|?8k9QAYEIU^PtSjG*{%E5o(1eUj`-mm` z+hsg`k-@EYRSglq+vj}38n%%ltu6{Sr`iv9kZ4IMN^Xv==e%UAV59x42o$muK;Nmw za)pa59Ua6;+2R4w6Mk&x0PKJye+F|hsbwpJ@uYqL+MaVHY(9)?N6MUY?6B(Na&#?VXnus4G+2JwVVeM*_$+cdzn2ZvG=BWi$zS6y{cp*mW)t?*%X~ zX#$3VQ4fP2CPZ$kst-O$s7yd#VWE4neelvX#*Tt>$~yJiF;4BsTz9o5Ha(MC}a?@5629AKir_tEDc#h_Ek;OUW$Fb zIq;^`9KK=e53=HTiZK~_2;Bqy`RHa?QK_g@hAn%nVr(P8Sin-bE$)BS25#WJiA$0) zGl>p?*iC$m_W6~S8swx<548izk5Yp}m|uSTkjN56G1!=CIB=MfbM37WW^`7`nd?!I znOxP-i!AaRh!kF1(IW5LLqxibqsliGHphAm{<)g%`(W84l?#&IU|4ftqUG{tFox69#syssOGY6>$pA_@$OYg zc{Z{H4T`wFF@TEMg@KF#UMbUhBvwJ10TG{Zk)~svpQ6 zTS`=DB)R}%eP7y*#%pP7Pl+M8g zmgK`PotK1SW}+I8C3mbOuUpc~lmZ<@IM-GKeY&gjW4U)20pfz#fp8yzeYQBNYXo_J zTHD$WH!PK%-6M9S#s9Otk~qEALt}_siR)-x`;Ix$^(M8}BkH$W6VVyQ!SO#*!5E&3>b-X>!-2 zDvrDI7N{T4^I5**5`yS3BHB?HV}hiJd@;{QjHP)}fx6wsmwPADW2m5bujJHpi$EfBZTG}b-yD!KcH-@~gl zfJhM%!P;J7W2KPNA@f%Y*Jhmgcvy4W1$hOx}P zjojoMINrQD9Pk)uy=E*&ree_iL#T$h;@mN!7W!+fBR9z#1fp6{kdf4cW1c$-Fe1HR z(d;%q%n{*MO(&|4KtlMF@qQ?b?_Ug&E+u|uX@)Z)oN?z!1+pN(wl-D`YT>t3izf~e zgS}?H`TM|-4uZTJKcGvg$1!0c#J*M5MvcRej^sx5F$k-o~diz`m`n+`02-(TAsCVcAn2BQ;I@Xvm zC0fxvayI~T22G>#EZqGe1Gx%bm)D%~^}zooYI2q05^lr{@97jt>B|hqH?$R2QP-k8 zSVt?m58RJkxPg0k=I+~+i63yOSJl6DW^$MkB&r8T9*^pT9_AoG;{B__Hvp0MYsb(& zO?&mNO7_etkX2T9wk16#m~VV-ZGy-l9m^8Dtgij&83N+II(`%&eMy&=+uyx zv95}h&|_-&EB;m3Zp0aw#;2{P!RJ8hf3VZ25tapli#d*g<8olImAg88&xy73Q==?) zh;1EXOWEUZYzr2BB>-q>3en*yH7n8~+&ED5?SkQLk}|`;RNjEU=r2^`dKGitPzBt_ zopJa&>&36b(UtElU_u9%rL~8x2H3Vyqw$IOw+9Xqx69_uEQ&?1tf=;Klp^j1F#_MC zdV{}{dq^&ua{J+#i?)@IFIqS@pb0cKr!@yV&zknX1jfSZ2O=1o1Bru?w=fRIrn8Tv zru(^VQd7+0;n%NNWriB(ICPrFGdIEodaMzS9<+Zr*cSuu?Y}Q}IjY5Be+A`38~sh7 z!pZ=f_a8bmi2OPNIAj9$bsLe&&$aN_UTr$Q$=0xcs>mI$1iTMiE*N7@@}$_Zr>%UR zPX4p0n~K$m@wEe*Vspok)<<7_&NkmgUO^^lbFvbkE={ozFt2*1JCp56E!wCkTA;N#@y2i;L)YX)tPUM6Z4>vw2aB~ERG#T#({5vT&*-yky{>7#$5}^w@d#gpe_J@!{^+bz4>Y9u0C*TKOFpKy1^Dr$v6B2|$Bn<*fto(ho%#=DI`Vx&mw_n7P_}fiXhBflN;DN`KcUUY zGErIVdH?4-w0oJ__94N(KH2zQ;h|{e;{!Dcwa0BaQSCi7eCEv|t5h-M!0gfpNF!0T zCjvF_Xir)CE&`$GyD+B)KPNld!h~%i{NMQH^B* zRZ3G&*{46?(m_Hho&0w+P+h<#^lE{_K~?k~nt@YrA0FDz1*0`Pe<{;-Ka(F3J%}Gg zxj`h-^+fnT`4M_6wUE*po&wFE6Eyh!aIUQwINv6K z3VR)ixxycSQ79+)jekbsGa$krb2(754RMES5E&n8}q^HX^PK1K?-{!Txy z$q=@V5#ohTflR4%(;Yb~4^-K=QAvw3vuRTX_s#0p%7<;k-!ujJjYfPq&-4(BH45xo zJ&YJ1{fkuO%EOP&0`joy#uEy2TJTqs~;F{L1Km3gc5^SI{?vvkh!VUJTM$k*20kzTwdE(f+U~?Ovn}Sn^BX zm8uto#`}W(vWoPxghxArIDFF1Ep40Uf&B{jR%@~h4Q5NOT!fY21V2CF#wPOv7Gb0+ z#Oi7pWeW{bg!2=XilZ;FL~ROgAe$H>x;vrA73JqC$ zYp`#{RN4L6#DR=(as;yG|D_MK!{!0`V`gW0T&aHv2y1qq$1-D+n1mDJk?LfXwm_p) z-02iF;^5}j3a}_ieg;gQz$-Ni6l+r+6-8u1#(ik-*(~=zBzKNfh3mfQMv2D>1|dn? zgb{ym!=kxP-yZz&l-sLph^YJ9A?X7B?Lm#~&#qz_@W@|>Jo4frL;-k?+1vbg%J)!Z zg04>JS7cE;>+BQ{DIqcQ=1qluf!PSTI8^fm(*bn5BU||z9g2Zw z$lB1qpj1rS12|lkh6vvcx;8Nw|31HX!dOO?qF$pFsp?;ww8gtRF;&F^bH$ZsgG&Y> zZo632J#13@N?fW#i>!v1Mqm2{Ed0V;vF>Rp0}MN4lu0s{bHG>_CcGTJ4}wH`i}a98 z5$7k*XamXw!qkJtq)}Cr{kqXtRQUHo>r?@-Vx)6!m6QxZA%MN=NL%(`=#9c2d3M;w ztdTq$d1yng-U;~PV?s@|j6={a*DUUJ1B=VzVL)pH!pT$YV;)tE#(#(vFPq{{|D{%x zTK>d{nI$HHq)N@(mHD>{U-l^3-!wd<{k%1%oyzV(e!7yWCR40Ne$se`ChIxBZfakS zsRSh)H>EY#;_dt7@P77*${B)FD?4TIKfC}`<(Rbk>8o_9%2qk``waS;CXzg2Q!smG zaQJ;4j16g76+R;YU{kpT*`U&m@4JwNb4_vjuX^-)v_}+vIUU?oM)+`?Qvgg9F$qO&+zzwN!>uq zi`SI{z-7^B>~7z@&+V;lf#CoPks``tk~-ScJUdW}fYig%dO9Mhil6L+k}nZ%A*xL$ zHontI7S&v%lzyDe!si2IFp??#Z#i3Ouv}YTsMpRlsfp~XFKjLPU;j>d6~aB4oq%&q zdGTxV^(@MeAPmih`km?P`{i4&`?GveGEqb8X!W8Gb#VNvfC<2wDf0Ww(NS>3Rd+;n zFF29o1)!87`82cHje+6x8GS%Vk2W2p3m-UbN+qnJ*RpxD*V$0Bn~ZZ0WO^l*K>3n7 zU>&-eZL>H3y9mvuN0``=1AFWcJpRgXP~@sJA1Havtv z5_Dc{OzQHmvY@1E_&bLA0`UQp%n5_8T#Z6mBgx5c>+V6WC+6F4jpm$H?^~k)lm$Y; zNIG(7S;OIzBgXi>*Tt8KD8j0_!=Ul>wj?Y|#&=fp*L`vgK9DHos9qd3Umey?8`1+& zB1$O2k|(k!`yF+dFb5tkE7rA!4e|kbi|(#ZR_if#&{>I;E#4tVkAk5k9?V^R%`TlC zzB#iGKw;12$j;DNbb?wi)pvaNIB6u1{ezNT$Qi?JQPoBNgS^xwu;Q?Y{N-#b<|7}= zy0~AfzcJNiKiWOdif!nS&X_{UJ|Ot5x)*Z(?8u(6A19&5NCTz_xTc|Yex>_)9S8e8 zcQwQsCbGT~C`EI2y!Wf=vSQZ>@r^%M1`*%M%eEF{<7}di3Vq%Ahq>H9vC4M2!H4JL zzmL`%=AW})!8EfTB7O_xP5cOHV$^}gMp^&CL$O*V(7N6HP&B%am+9W}dqCo$XHo~Y z@9!|UxMrmN%wS%NSOk1`s)hXl0=BYN*x)Hzvz_QWrH91;6ThUt>Ne(R`y~T%d3^BW z*NaRMd$5`XP_;2uGt=i~lcF-}p3Ci}?9Q@rH3D1c0xg&w0GU7;y$eL6p1wr~ z@*N(;;U{YS6ZA+QC#4+ocN}(-FAj7(gY8fU?1h z)$w!gw1a&cHV?&5R-x&Uiwb`OU0cKtqlF*|6LEcbhDh@W1w-ZH%lSVG{&V2Z0<>AZ z+8wND9$(JuV{PHpks9eLI*df`Mo8Mh^n+bTvsQtR^z+m>8MBoDIZ7T_4f+*}fRJH+ z`(lZ>#o@?h>W^#bUz>}SgW9EdG%R(kRf*BfKmLXCf9w4tN!cxv;A_8 zYaQRDYO{A&Nw4Wf(oFY-K8E0C5WZpK3=bR|8+R?dhwBYd=N`|}BW~2kv(F0EB(JYW z@y>~~mz_A?&$u z=7sl*YOgSkRwrnFVra>F$_-2k&HvWH%pp~WNTq-zG&Yy@Q1W^GO<9mISbxJg$81Jn zbjK~GP)$(InX>o`|0^UH*kf_FdRH$c*DC31e&~d#gWYFvggvF>4zR?njE3-lJeDP*ZYxMl zhFkqS;~{3>F7wFmO}uWCxoo{do8RxOM@We5Fiv&OM_+cgQI#3XSYkaIcoaT8UDTToA-8|g?+0Bb;^e|?+1?1iCNAY)kN?}W?zz>4hQvP% z2v;)^{?Pcco#Xm?Jw-7m57I@w!0C2A&qs0YMI_xvT3F8?BSld_>IksrKBo`s*zE5J z1?>vi@-prOdv92XLi0UhhO!F_ReWRGUT7P{62{*4@3X^h#IoVW=XB#-`(Q)W#78;8 zAlQcLYCgIKtZ+^2F9s&p1c|_~77LD&V^C4so&BDl)H2)h(EiPL0{3) z!xN-}KFo<66V@zbdBu(fcFf5%g$<{8aD6a)D_u@3nK#PswV# zSS~wD5>lEMG26dAxIJig>nl$9b641Neb#sWqM6Tr&RwqjrBG(+)U^ArXQ1Q#EWaeb z=@QS?=lrJJy2XmW{TxE35VNhO3JhG_TVv1gT-;5!gPT1(JD@H`(Swr&B{|j_Ocwk< z-efIMZYw19^z`WFJJ`pb7H*gHvCUB}sT2X{I=RyinnYZ@@$tDXg-s=eIL}XK1&lj% z4~M^he_`S2>j}3(GB*kXM>&@YO+CBe==oB4a55f!MlbOGYU-O&>E0N9_l@dBa5{wQ zM6dYp)VKI?aY6sY7@OHEFS)O@Z_6E@y*KYr>eiNc{Labgur`Q~geB^BM%{NidaaHceLrT!*^lMBW|dr(Hp0AgE{&Q;+-s*?zf{G*dZ_EJ$IJMYYU;E>(qws~P*P&zg8uh~ zYlg6h4qO5PYbz_ZjW@aa&4$QBrz(PD#3fu0`|8E`JJ)gjViH!B4)t7U@%TIH^Yz|Fe ziDc*bjf=yziGd6{d2Xs4zAh`PZ$>nxe5dg>LiuT`%FnfVtAy+#{3x4E$`h_!vb=s@ zk06F_uFi^I7j@i>IGMbCs}PC7+4jR&l>-kCZ{z0|CIt$nadL8UUf-`TZ-RA-$G<{Q zc#Rz#J}+~Ei;Ii(p%JSsM?q>Ge&Sm<0{$#rlf?#S#|@kt-)S16jp~MMsne>p3nE6Y zT8^Oor-wc{V<{=gbd4tBR27%?7e&UXsHj2VG0nymn6HNmu)rYTjZp36`O#Gz5ua_} zD6izmBJefRs4F2D?36Q;?xfq;VRQL`5_Oa&`Ne)u9_Qmqz`wWW*0_R?4Z9) zHcGK^ZwhQ4-mQ6(HY#MR2pvo)sn!Gi{NTp(d{ZQ*7qhdoKRtEB?YM3hq|VJW{S)&$ z|FDnaVhctU%O<6~i0q7&JZRYPXu*B!Dz!YD?fzC5qQo1~8;;?ri%4414hKB4UJ7+o z9{`d~!`!G6PYrz`JS4JhypZh$3bY4NQ|onxdf0~F2c}0@KC_nYG|V0>+0DP*XX$^! z5XBluCZB@tUjm%vsc)Hw>em z$fYsiWPfrryl5!@nClsrm*N}vgC|*8y-x3Y(<~D58^^!NnnGh)OrEjp5kBteibO%{ zf~zDEOY}r|T;_#aBUd`loWBE=Q9f}Bl~m^Q>cjg_{kKgkFxf&4tlk>%eP@&A3dbAz)GN#bd<-}T`B O=M-dBWXhzBKl~SovbJad literal 0 HcmV?d00001 diff --git a/doc/html/_me_d_c_motor_8h.html b/doc/html/_me_d_c_motor_8h.html new file mode 100644 index 00000000..f98feef9 --- /dev/null +++ b/doc/html/_me_d_c_motor_8h.html @@ -0,0 +1,232 @@ + + + + + + + +MakeBlock Drive Updated: src/MeDCMotor.h File Reference + + + + + + + + + + + + + +

+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ + + + diff --git a/doc/html/_me_d_c_motor_8h.js b/doc/html/_me_d_c_motor_8h.js new file mode 100644 index 00000000..82cdfce9 --- /dev/null +++ b/doc/html/_me_d_c_motor_8h.js @@ -0,0 +1,4 @@ +var _me_d_c_motor_8h = +[ + [ "MeDCMotor", "class_me_d_c_motor.html", "class_me_d_c_motor" ] +]; \ No newline at end of file diff --git a/doc/html/_me_d_c_motor_8h__dep__incl.map b/doc/html/_me_d_c_motor_8h__dep__incl.map new file mode 100644 index 00000000..c2ede20f --- /dev/null +++ b/doc/html/_me_d_c_motor_8h__dep__incl.map @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_d_c_motor_8h__dep__incl.md5 b/doc/html/_me_d_c_motor_8h__dep__incl.md5 new file mode 100644 index 00000000..395eaf73 --- /dev/null +++ b/doc/html/_me_d_c_motor_8h__dep__incl.md5 @@ -0,0 +1 @@ +6058b3766341cce836092618ebed7515 \ No newline at end of file diff --git a/doc/html/_me_d_c_motor_8h__dep__incl.png b/doc/html/_me_d_c_motor_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..36690c07c971531b746e4ed48dff91d242fd947f GIT binary patch literal 17696 zcmajH1yq#XyEaY;h?K%B(g+gL4Bd#Jbcb{eCEcAOp>)>(B15-yqeu@WAYBeHba(!r z!T0x_^Z(Ab)*04f2AWo2TXR(6V*fZ|(E)t?V3Sx2ILjyM`sZpZRMPjSs}0KGjQyO0lq@ zl_!$(F6Z;)v8lXMv0@pa<3_mLfVg*f1_$ZV`qI)`vSXyF?BWw##1bwn)*!?($aEy%L#l650_EZYw>g%r|Bh`YV-3Mrva{$p~6tbdJdd&|5|;6 z&G?_;^s&%GfcxFQ=qeH&3I9D1*P`}A_CE&><^Jadn3WcT>AAO**3J5-lV>kd?81Cn z^x=I4FQb`&hjhu`UlB)vo2Wu+|8=!))?RoM{N`)nj175yjR&QO)VPuq}Y*ig6f zBa*wJ^!NfzK#sQR@3Z^+U*%cdB=xMS%_NT+{j&T59d|sHK8*#rga4_3dTC zUJo1aygVi)94n;$~mPz*^>mu_BqVrUXs)6dKSc*Xj1g%z!h8zOngBGDz+i_oVGMHBv`27}0%rIy&N-dsPvg<3C>-rhmKRB@z(X|1IRkg>HD=vJK?+KQ zx8@QLUr_)n@Cvm1VhPbh?|CjiQ0h~dZB%PLQEPEJ-xcvJMxutWc4xL8zPqQ_?(gR^ zUUk1;-iIP3`i~UJeoIIo=xO2i21xAZNi^@RS>NWc>+#4d79x@T36|~ELU__Ib&q;w zY-SyW4&k}R$Bd)e;7KXU6yWlg_w&a1gPm3VVxAVSfcEC@5yT_asg0a^>l65d?UtgO zk9(INf!Hc3dy!t4r#->vV|!>ujENdx-7SpE?kq4y^Bjtm`(s&HwFkL9nEq~5iQ^6z zBCJKTAIn2Z-3pQI`>|VdUvdVs2|Vr)Yg3(37%}Rf$NGJ)6{`dSOlcw{;X9anX!$6z z&t35uIlmV^Xc}Dq{8AsOF_QP&tuKST?wkn~M%S(2Vj)aN(tQz%)gYL`y0W*OLcV6g zcW91)uAF}uSevXbv+4GF#@YFu?Mn{?TPLII7qv7fJfzYG_TlN1Cvg&gS6Z;qBqEzI z#zl7>Mr)Q#S|A9cJppmw#HEj~ER87I<0Kw8J>f@4QymuNoBzhHw4NyT!tj2n2DR;p zX}&JoyCS6-16e$X-Oo)>M0XA+Z&6t%LGD2Q``JI_w?8E!a=Vy;JiWartvW3%pEY{*pE2AJ0op*{6Hi@!I{x4`^HxPw+B`dxTPdTsYPxE~dLY27rV zV%ksLQ(z+VLVNSB;{#RdqYFib)pdT{L|ZxRZ@1#pOLiTzu#PC|DJXmo-P2-{ z%3E0sOWwUejBq2s$EYWMe#zv{CxzCsW3-Vn+kJE8QtM8gpLhvkKJ=Z%KoD4X%$3G4DQj`c!4{EdkrDzJ-SpmN%>fewXUFn5^HnzBBayv~TdvNTO@y_E{@V0*wi+N#DXpMj!7Dzp_cfc~QD%A6W{y zk=e|Lr=pi1#P6o|j?UJdIqlZWn$FG~*Nyj5DL5W3tza_9QF zC~gY`C!thCSy|Zpt_nqL^=D_T6^14p=(A(gJ?jav>C{3;=-@VCc}ENKpR%v~$meU$ zkJ3ISn)jcgH4!Flx4;Qm&i4!fYo)PrjL8n{t&1cVu8nX>ijA}yg6M1U&t_^yHuYY< z%JI|5W^o~`r-2~?5x7IAxt3g%ooX!8H>mJCm~Ske&EyP7J$Y02nvdK5dA*pJ^v>*Z zLN(Q&?5kOag+@I;mJ}i1pG(kg>swn^%bz?o7vdo_DLNe~1lx$&kj-~B?ioF2r~5h{ zV)n)x2u_mCM$8WEpk^|g?U^9H_f`iU%?D2*)s+;dX)_!T^ryAWGn{=%1h+C`4_{yx zU68m4a3$>RFTP*=sNor2kWv0E_##>nn3VRtL5R1!P-1vG3;PtxCdM7h*Yced(C6YePY4x-zyAY$0}FlzjHD=-4un!UCT+tZ7#Heju7ns%Tp zS3E;wF5H^&bvEzC;)_=fq_0bPxKQdO$4k^8Zjgu#XTl(yNEL6aVqV zv-2+!UgQO*``Gur!s178klSnv2iw)VmtpxVe8)mNr{(N&NlkO;<`-GYs6B$d9?=PmG4dRvE?sXWQ$`aGfg=6dw zN_}W=1vlQf7iyQ=9Q7p?!ST|^Wm4AC1Q$yoy;xZCrmK>Y8N)c41mvZt3~}i@k`K@L zH1*tQVnkz`i0^EI17x#TPnw?eOp(!D)Tgz7;a%iz6`NXfSjWDo``+x59<@T3KqM$Q z=@bCB5U*j z4^_L#T|+NGXEd{0*n8yjb3^DH%iW>ncRZN18E~{#_YN-J9eHE^ZdROB%23GL4#0}d!aKPei?UoLyHN_AvjKGI1L=G_V&efJuaUrat0AzGI*%jU4n5z z{dJLsE=}_~yyM$xqs2A{5v)tO0`I^d!-!1qsg^)+yRDQNa7d)d^V&f}K{qmCSX!Fq zpX82D=))#+WLtSo^N)O(9I)K#FZpg6_s^i8XECjJDbbXVyBp7k==n;sbW3Khx9P6Q zhX}baT*G1rFvX`;z$vKXb|<83taY(nIaO0jXiJJ4WoLr61dtu7%6YIW4_j6Fvgp$F zM)PO0?2qF*9S0kVK2E3c_GSzGG`v^-S(FLiQ~_s6ajzTj*LKzKlmvqk&=KREe%f5s z@t4`}Rlad2V5-+oSjOs}*gUCB)nJ;VHKr|s{-oj;LRY3wM$0{_3G+0CKKoXp+rrGF zi}&NPJDD%EYDO39Ds6(m=gqm#ElkpyGZ`I$f(3H-D&`mm_2CAOEc@el-G!Q;&dHck z_V?R~f!5b%P{fvt%=ABi2U@(H+Qxv`(~3yWIlY8;PLv4M-UEl?%qg@0xURA)WqpQkbil0 zReS3A6xTP4t!3Mo@28`YSH5JG0sp`_!G>CdE#w7@p=&u+74M5$A8()oLUEEtMkGu) zEPDt1nh#*ksjJr?I7L%wG%vPLW77DIPwym8&NDcWD#ckHMB z6g=o|25F(N1QIzmQOvLzA34d^wOPY>;eFfL^86V5F1Pk;9Ot$)gb&X#Nzbf z2Y4Rrdx*1@1H&OX4QDk4rPY3No#HBJ#UAkJlZVmV2fGL_Ry1w;#p^vKi&x;|gi#n__T_dfVo zv7cQy$d&q^Fuyb%xs8=BF=o#kh@7&P`1aFVLd(#s^u{M-5raCZ6NR4Q`?xx*j#P)| zI|JKYRiCSN?X!P*xRux1hzN-IzgTF%zmnLVgXT01kX`Ap!kb7=H z$j~g=aC&O(1ASaIS%2y3Aq2xu0pr2e=~sStlU;4S{>i29R_6cdyR!4tIHmVsgNTFT zkUG6P_4kWsSg>%^=mQyWl0ob=5axi@^BrkWYuBy?Ifw$a9CViVfnJI;~Q5?#MI;aYor z3G2u^RCv#>ZGHwdE|1t|{bjR-Xh(2}99_ly+5w_jkOeyek64J6tKqQ#w#=VxG5ybE zm7)rVBiamZ(#*nX;!<~oR1m}^%Onn3mX1f`PRzaukg~F3b465Dwx`+L zytg{?+SPyW7}D7sB;}1cw`LZb!0C8*7l^+aP)|_AdR~RZ7r2sxWwTXg<78Sbe?@XW9`>jLl^h34Jx^xQ#RP{ zdv`Ccy2rjP3MO{8ei&OGF-cCZ{bz5r$~0YKY;sf4U;kVDfXK=t?&LV;IPWL$f?ZpD z#{Jw;9zCPRK}O70g_y6Xhj?ZFnkb6}cbbQWo1isfc=1O!ySDF3mz^vdd3h;bS2Lm3 z%~eYhP`Pcf5p6po>b@8wV7gsIto-mt5c3YYB~=%`u>Bq1#9yoOMSP6Zw*4fs@4#?4PD z2x(ug{M;H5)oyNL+I#dH{eR3B^VkdC&gD8GBN^fDuL^>Y5Y}!_9BB*h9hWKlk>wFm z63T@5>-)D%bR1a*Pc|kV~F9nO>u>Gr~O6hX*;M#*l7-&dycP}Ct%kYKL5Y)b$kS}YPQVgmQfnGBU~y4&`lUcDk0hP1-X2GTa=>_M_jQE;I3`b$Hx@mt<$5Wu;E_pBmXLKJA5&F zJ8OJP=pA@KNKjS?ri}7Wk8Y35vzT!UyWYPP4Mrmm;lA9cjUT=chE%pOD z*GA57cQotx|8U}1yOm_8f7CKg7uJ+M!FH|>)oP>q@gv`w_?aH|yMRr-Ysm+`Jij}I zV>Z!~y;-x};p!cXWFJCMB{y6~PzA6zP?=SgUA~kTgAp;z z9yq@~<-wRGu!$k4uBxai)Crd!a&0{Ol$@)Tdnmm~G?T(qE~ZATiDjC*&Q;6hr&1D{%KU>uY@Iy$76!hV8b0M*+|<1x z3wB6#nY;}ie`<4=JKAe6WZ$jXLGIKfV$4lL9#OU7SspqI5rOn}dgz;m(c*dI;#GZH zn5JlK9Emz=Axn!0kBmlI01TDc?J6SWl^V`I$m2Cqm|JQDcaIuN%ixDj`NXq7+g(%O z%ARGN$obvvPxRB=qf?@W7D+35cGW%k3YO9II^zWtyS8c`jWJAN5rPCMYDI&N27i4` zQ70jH`GbWAB3naR!R~uGwHwUBByJGZBAXL=T>ppHznZ;n0WA*&DbHjm}>9^vEXCaPnyfqsmf>03u$NlCB<-W+?1afbP z1Nvf2CamAt_Cr=l(%HFJ6-il#SVXmNC*f5^A(#v&tv#ufG@v3;ZR|kbJUt<7W3u1X zsL%t2v4CIj*E42gAB^iiHkzl+FTv3>{dWEz+_=RZm6RE?mBKpjhG-|o2$l%&h4Gqj z-SY?LJpPDO=Y%3obXjQOpOCACPO`7Wh|CncH>_p&SL%*8?H!>h@!k?EM)UJx^r^jR zIn^&qD0Y0iA5z2x3CFZv=c6rU!@TcGfdMxv5^mdhTf+z z=0q^19i0d3v{y2GQ$YB#NUgPxk+Xod@A|P)4?bfq7j}_C(E^PzV^LbI@SrCHk9#-K zHU#u(-iD(}iYMlk6qFON!*NdX*m-}Fbw2gRvwn;1qN;ps`9!*Z86Qmx%-S6g zosvf4H&J_a{k$)JM90KYu!z(>=C!r^Tc)!-rWyc-BiWDXKmaBOuG*unQ0{P+z)Wb1 zww6)lE16^$Bb5Jg90;q!ST1dZlpuS_E)~_N=?RvGVLf&(hsz`@zThX)gx=T?(VLT~ z%}~Z3o3z~UL_Q!HfZ8(UXb5fAUE==GcrOhY8MK9D|7b!1pSg8dTea8%hqd*8b9#B~ zD0hJe;Na7aX^o-Q!owf)o3rQb9fJbY_N7&`U-64b3?|nSSTdtJvQcZJCVrE-DX20d z^5KpB_DWfrKYUR+QO{rO|5KEKI@<$A4(zMLxJa~q1?4Wexrw)GL|{46Af~7(KVcFF z5MP--wbw<*EddeAng4(#)>(gOQwZQldRBiY|CO=Lz5Xz2NI`J!d$8>y0Mb&uUwUKu z|MOjLs`Y(2qW)ZGQHVClPSx4%B=v&*J(7UvqaYx9CUH~fvi%Ah-rx?~YTp;=Mzn?BkK8|xz0@7C| zUCFtV47{IX8B|Iy^D1adp0RtjsLC2k#sKP8Zz3K=hq{WfF37|z!>?|7H?m(u<+OHIw z-oez2$&^wgn=x#~*!zBSuvPCC!dW#>%ETzAaA5={(>oKVGQa@SLy7Og$&DQ0zo!YD zBMbws-T{hKC7`*{W~~{xe2oSMH}U~S4m8-88M2YI_-e54i1uhnG80xdz3DM$NUI!#c37i~`Yr-&iZ%^WJKDIH( z2*$Sal(|xh;4mg?^F&y_Kq-(rhtOD>rF06mB$WzJq&W*fc7jIZ3ZasI!k9?#Z`h#s zVwbfq{po0?Azq27#awH7e^#W>kh2N^ygX1U5mx^|r@56fJEq#BQT*RsP*lpds<`6& zT+XBvrJSMGdOCN_R!L|Oz^RAAB_ko}2{D;Ss1v&Y3#5cK#HoCF1@ewpJi)}E&NS=K{XTRobjnRQTe0f*{p(oLPsjwd2Ol#Qh{E}_sai`>jP@fwL z_AXMBDv22eJwbqAZ0N!0a;7&)e$MWt2R-%los>@-O2NJEo zEC@?8`v-yw393dBU~1LjsKl8HI^x-n?D1r9bl+YarW%YSjKc*ihnb2Wp&WOhdUd{e zwq!Bs%VT~v;Z{h6mI{+0uz@n=H_gN*RwmXfW0eS|c0oev?BEnR@=%VkS^C!Exvp1% zM~}N1xMzB{oR7dJnh|%hR<@|_r`Ej+oG=0L{Ub$n)lYxgBNNO{#8Q8OeL$tOSMc-)?b7(MMXP|1WtQ{=dW-4#?(VN#3N6S z_dl|ae_njP>X>FxS|mm?V)C{?cy?piDam0~+Ms!uAf8p0AG?jB5QPe3W`253V{n*P z*mfIm8AfOx#=iXSgl=2xl?%Yw-c8nD$v(xV(Rxn)A1(kN>d~NfIjK)>{iR_xWvGTF zFXb@o^W4M9|CR*n=vaJw_yDJ4+RvF4t9E9qJ0; zoobl(o@4_e)WMopEz8Ro0$zj>q_omAPZv!S=h3^+Mo}9+wFebBN0KmykrUMpioNgG zSV&?|Xzo`Fa0uu)uafXtvQ-0qEgcjlLJIlK{Q@3U9B?MKZThh_ZO$cUtM6RUo#jZBQ)SFR`4 zalc4%Z@-ZX2I3F;F96UqmJbqkRpLju;s}WPc~}{GPt+5QWrTJdLCFN&^X}%~yh`aT zKWKU2!ZZM(Ake~}JYz3Yip8<~FE6Bc`Ga6;WrRvR?TROXK^G`6f|jUZ7u%s^dgN{* z@V*&4s>RtsyAG^Ca=^3e0oKO;9)Rb6W>U&oKrEoC*dtv4;B2qy9r|hoFaD3K8-aH` z?uZG2Hd6lO-6Uvx|aJk43C9KTLx|@FQ5=5WHjIN9H2DT_WoE z1r~)NfWA~QsW))Wk9%MjAy#;Uu_*ZTdJS|BN(IJ&y7i2Py_@!`BUrt*42VRW`sT@W zFKWoM(Zoiz?Xn|;pw6}b+T4$&52McVEOpu*)D&) zQe?*h&NmF=Y{c-$=fy`{UqYJN6-jqvonFwSVt=_%p^fRelp9te9F zkR+8xH2eV^OVU{Wp<7r9#loV7oyQx>G0(}7Kh#ce9A+B|;b30M$=4XU1#2tx9l*2% z*l@KUPc55`lkP&&Ztp%GCv$i)zduhD6rS@GQaI%4se(t#Z>wl5MX&CZcK*I+G`l~})gw#DO18znM$4-GcZc+zcz3EXXV9|i3&XstFVo`z9?D4= z>>3DLeyIY!?D02F7yI4Hmp8tYe(XWG*7J)onkESZA7d7X64UF7Fp4E!%fu_ zU*>(RCN}-LD%vIrz;nUe{0|Ft+Q+FPgct;Yh}&p$h+xjEVb&|gzBsZKa6T2Z6On-T z!Lj-mBD7XABm*{~bHA%ayiC~_gg+fqQj*Aa*YvE>k+bIW@MC3c#yJ1Ee_?BMx+G#$ zKo#+|FY`6I`_&niQ`408P;s1yomS`$0dsBk!Dyjs&Y#?TEy> z+I5FMIUEQM65lH=SU!pEf)24%4^xjrTEcOEwOq4Cvo0Mzs^oT2TtY%c%QRWP2U$pm z6CLB7Y{GxlH$vmFIA5tT;Zy4FwzS{@ausu=i0zn$zqMQ{3e5=`^_r0s$&msdG?WiA zzWb3!^b)?!u7i@zBH36q0_n0_L zA|qNj!yB#6ioxCluU^oLb|}|_y=qaKtcD`FHQwyIn`!hL2ZY@g6$&~|oh?TgnC>8FM>n|e3OK|ZkchiK)x zNbp#Qp>ObH$6xKu2gMFw?qnM+6Q?4Zvx{V745hO4Xz7CXwUv%+vKE@wKGnfK-h`&} zQUIwStl+c>By9D9mUmtm1_SP|P)fNUNDtL!=5|8MV3FU^2y~XZ(d5}8nov@QlJc&0VcS(*6MUEFoWE)nJ3GvE-M> z`hRj7=ydpMZrel(`rxapAoS~yenq)qH#@P$U(*k-`IlP%CN$2aFzd`$z@VRn0g1W} zf)i(KQHkv>*wy0lb&;T#lP*wVlFjHyp@q#0Hgxu{u&eOI>^*+Er4 z5>hUbQkFx`gz#^@R*<_=L#^v8>R9^>(32ti|wDD4ATQj^CzSMTqUvE z#Y6s}%8|&BU4_@Hj`R-yjXfkRL~G z@_%?6I&{6pLFI7DKhC_A9AbbD8gfmL=2Z8}RJgChhK0gH+Dg`u@wns-IFAId7jM8w zbzSJ(xJhi!!~sw&ce7RgGJG27E+G(aA2Wsd;5f>8CvM>;*fEUCbdMj6oh1EO^AxNPE!XJz`WuE83PL_vP9VXqLB$o z?}rp8MQlb=^|Xma);?O134M+*ZwvF?RY&zf&iNK$8|Di^X!jthF;0PYyUQ6zE@n^piS$_W-ts0#? z|4eSMZ$KVdpH3TsZIj<@Y{v1sK;MmnSk^J#7RYhX8vzFH$p9V3H;b1iDT;d@q$6L# z7;Ao{m|fzV<@**4EH6BQKo(XCF;jy^bLhV0$Wn-_)iIJg2KhO37KF| zoQDF2&xX8YC#w(~|HInqNPhkzNSMGwc<*A3OZYJ`T4#RS19jFfq2P>Y2ee)5(mG38 zd{s=&S1yOJNM~L~4s;|xtQpMu2q@n5o5Ts?TxmfXM&EB3ssap*`XiQBz5z!dn+)!6 zbfR>P%gS5%kHHT4+EKOYm{Zj-oS|D>WWI@4HkR{ZVF0|PH6^dw!+uf!->|ahE>BF~ zHm48wht*vi%+LE$pA&g#@k~tJ05S%HS4I5|MU*0h+iL{|YUQlF{2RH}?QlY;0WD~@V?o#Q+MFdUqs zG`XGveqkx*qQvyP#NCR27%rmnf6LXu3_#b8q;s#A^o`N{2A0w4d?N9AeK`W$*!<&2 z`B8W~iaNx&>pm*Ud-S$8=`oPv?cBaq9zkpA%gHaAp#m&2sUDu4*l?!S7g|ykw;r|G zCvFPy;{0|8*cIIkiLoWs7InL>=Q-qe-abh?Q9^I~29Yxs6@?_}G~_9}9F7YbX}KJF zevsB!R!RSDe{`NjS1k*zcqVGF8ZXonpzd95Z)~~d4dTX@NMeJ}g0KsCZGP*Mgf1IN zKZ%S~di)@}eWz}gYJ1NI`An=#Zm@*6COSAr5QmdE)(~|la&mqeb=%Q03}c(qGR*Go zw?x*>#vN5>7%hEo$?dL&_${6TO%l`Rn;ZXpQZROP#QCt~pHgqy)y#8F2I^+S9S z@!fR1<|{UGKHHbQpCd}%Rou2T4>SL4I~ruj=ApSL&sgk=rWSv?-L!X62xro=sPmX_ za>MWnu(h&EeQ#m(@@HENCw!b=`D|=~uXEAyG;-;?-X3DL6`+~6C8p^dHMwo^S%?`S zt(k|5R`%LT+EFJsJ)y_j)A0-Gj?M4Vi!DxE4vGXU+85vaZ!Tw$=zhl!?a1mmK^y@r zL}}?ltE_QKX98v>Nv6H4Lg`Xpg}!OPwnKZ~u|GW%dMkC;l|Kz`r;f$xLVfFw9hfL> zrRznE$ZL{N@^|(}jDIRz>Uy-pU5JMSNf0fVN2Wz>aeMNxchAe{oZsH|6H)`f+}Kp0XqEqxxpIsq`g$2sU}e$H?D+fr#pR zROoP$3&a^>6X4I_&S@sEa5$NVUP*<}WP;WUQ+tU{Ticn-&Ptr@E6;Mlgi55q+A&$F#2W$c zG^Mvaca&Re%~XNkxA2wGlu73{h7vH96`ixlHn{%O*4DyOK`(~mEc3)3(~8Fwh~t+4u49ELmD+{)i8H>Vz4t+C#_QCn z`KX>@!-K;=f}-B-%uj+_sqs=B;|Y&{be>fjZ}h-Ct=EFLwZ{1Fx$sPH0XnQ`2i4Lp zY*NeNFria!$OGYv-%<%t{~DqE2n?@Hrkhx_!P@VHP1*n0O0fA*NUbp0|Y2H287Mn(_K+T z`EG+*Pj!?IMHyhFi!rYwHXG8wF)KdtT*P2bBw=4fw0<@3F`RR94`IWabTl=&I6Lx{ zqBA6R;HqgMK-#_~CgpWDzx6d9K|+Bd!o z0||^A9FYz?8nt82_&10PL-vxsnNo*!PAi|bISamJ2b&AXnQU9$`8K{R06_+>Y!-WX z=6WU;{avQ>^}8dx<(GTp17>56&(d4{8eg7*QX|@`qF4N^Ma1s%&gTf~Vs5EA9b>rX z5d4d98V-6lzkumrKe6#T@RLrN{!L7BmFXBe0T5noh1yVYa)0VN3pGd@7+&4riCMjV zH+5n+355-M*Vv-XA4l=wRe>8nF<^vWoyo(3Tf0|;>b`Pnf!p`aB9^OSv;?D;$;t@91`Sm7L1|VAR)0b>ii^b)SmF+ z*m0A5$~b84Frr_KCUTR2CI!4E6#mvFQcW`wkeYb^^0rIO?Aj$s=#0gey)(*;7t`<1gsDX_h6{(&E<+k)Fk0;DfAHo=|(SN*rXoHwoQ#G4df$E{i@ zY#QM7DLc~S0fH>Q0cnj!?!BhY{pTOJ%i@_pXOs)i*Cr~M{EzoFpOSq^*Po?cT&j3H z@8-&Pezy%atq~U=hqJ64i5d2cJ0=Z~B>u{GdYM-~*S#-u#yvHhbc8YM_`U`A#-)kI zKzo%Blinlmbk6b*`5#A{-%0mEj zQa}7%DZ1b5TH<~5_uJ@<;VI`&j7PQ06dr|U5{ub8!qF}_hD^*MP68CUUi0MJ(E*K- zH_jSLU{B~?MW@#urCehSX;jK}bV?iv>#j3(fC?Ef0Vfay9K*Bg9B>SFZCUj4HwZK}i8X5v9lo-P$*@uA zB)x;1TuXRGe$T06GZT41DIR=d%f85wa*(1b2Y0L-mcE2Uubt$LcefeJNBH0p)MYRG zItTpIl}2D1zd06wSXO=i^Dx6)C9u;RpMv4UJFMjLMdDB7i0upOhx3w zpS>>AkyaB|5#ho`LB;`)hx%r53l92Q1)7#4fCIg~>%K~%lJGb8{Ti!53uaPM&fHmY z8&c4kbzYhKBW702MMU>b0$_apZw*sGCyx|e1*R=o8{h`3A|>TIEX9t}3MFIz@S3pV zf1RZNG!wzmCLjS|Fcy)T6B$it5P zHN7#t#f2D_S9S?d_EYda=PqXR$*!(bF_-O6?5-&g`UDN456@>p2X;Pzq9l+~dHc5?EhlGwalLh% z)OTtbNHI?-riMR6P3jJ7_oz?)d6s_QqK06OJ_!7ta=M4WQvLY?=>R*Cw1Mzmf!`x* z5%U+%_r*~ccN0ny5abfkIsNKG?v)S&F4eqB*DUBL{09`^XbXyjsK?#7d3Zl8+FG%n4tf75M! z6;buc-Vs^uFT>((sr(w#=A0=(cJQ#OT37Dpl;ln+;4m@`b$?wgHWr2A;%JulN zgG;!3JwVBOx=j+w51mf(O$y8mX2^t$WDfId&OYnm54I0vm{D|QjaLRE$TNR~%Ty4y+f7fiZX56sjLMhd{ z!|&LZhLHyzP}V$mDor%Mly1E(ZE;uR?EU`Ig=Y?kn-dUB_ zMZCaqCLyakS0M1jlo4vF2C~&*UjSGZ$Gi?EH?r34m#*q$;=PwC_&&r-EV^fL;BeAd zjF$q)`IWu;;-(SZ$|8BnbncUn0<=Kkg$a_)|9dLt%D!eG}Mjnt6 zRR2CYR0{=o5E#VYrXv?mj#XR`k9@>7Q@iC1N;p6bIOpc9-Mn2h4-Js#LyE!xC6Y-4 zYI_50D?OO){-S+v;7rpGMl|ep`skjeIk}S@RwL`co2mDUfGh?8`$onfqQVtH6-&`VVoojJvVQ+(ZVGw%o5^}#35B|34HriO7l%OFPJA$hW z*;T*2H%l+J(?fZNT0qaz;DAhl{;mWPJ_cq(|Fvy`oT3fO*Yfv+avh+jCqgJ+t*&iG zNMz~t7sj-eoJ%%;|9{7XbKk7`kMO_zi+;$kePLCtYM6%7=I$wzf^qKm=6`vd41i$c z)C%s`;t8-8{qNPSoZ)^QQBf0hG(c%m6^W;1_V0A~3>Gb_fEUAs{$7D3VgS_Y%Mm{D zTNVDrF<1uZYnmA_Oj@sdYc2CccYd>g!31aj?dxQI_G;#aX}UWs>9091{0z)C zXzx=73Tw#CW(pKQ0sSW_v^m)V=>|3vP(dy3nLw##$G<11I0hRYr>dxaAJ(eBnEq>5 z)Nudmapk2}`}7h%f1A)2jh21OZ*O2&hnA8_J7^2oBH6C~3nQBW#BK_}Iy4^E~D^RyLt#b0{`^jMJvXYgyxru;P=bdT<3y)uo2j77f3;0`e?^>^o; z0!tBJrMbAtkDl#uPcj;qsU?2<*8*za#}srin=^iG^j4_Mb45Ud?cL-MWp%gO8&s6G z>Wn~h+h?q$zCRga|1q_E@u7|>`#E9n@JPUu4SIgn)oR zZzkpwdk2S3E1qJ}q1|135?svMo}glOc6KTk1PV&VPbwwgDgPP(#bp8Tdh7Z(OXTqKdkyT+QL1<#DBAK43^R70D>f31cAE;v zT>Xk9P`(TT2dp%v53_X!zL+ML45nM9@KUcuk#j5QP-&W$UHWHdFJc&!M0m;1<;Q3m zplNF+F=)UnRg#Thq9ufumouqglvh`_t4b(=gCNnq%ro!NMz_^iwah(_h1#ur8#mQt z2c1ZMyqvi+PKNfWNzFenZ%P+j6su>-0;sWrrHr6rh#udl?=4*qbHb*0tVQTwKqVp)YHorm+x`OPf^1}#6N6nTgC!A78qeI)qsjGx z?WS3*b*I;sG>0%yW(J6qPZ24tBsOV1Gl#Q&2H6B}Z%}N( zgc;gX8zRWekJ|V_Jt%?hqmF1_R6*oy99Q*IlO_7~R==7zuMGGq+{TicWHbp%Y?~;# zcfVyzz#5s_`8CUd2YrthLhg$AUyf+N+jAy7Midm??`lFQ>-flz|JM=V&zb&A6qGF+ z5vs6(fq}XAk4;3V_z4l0mrYgLDqS}>e&QbZD3!9vMec{g;akg&B%z%qyBgu+TPKE- sl<@28mfgpX2ku&t_x^vqY@_c`F4I&X6&N3nkjG`;C`pySHvaJc0cfDX{{R30 literal 0 HcmV?d00001 diff --git a/doc/html/_me_d_c_motor_8h__incl.map b/doc/html/_me_d_c_motor_8h__incl.map new file mode 100644 index 00000000..6c111260 --- /dev/null +++ b/doc/html/_me_d_c_motor_8h__incl.map @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_d_c_motor_8h__incl.md5 b/doc/html/_me_d_c_motor_8h__incl.md5 new file mode 100644 index 00000000..74e7f7c4 --- /dev/null +++ b/doc/html/_me_d_c_motor_8h__incl.md5 @@ -0,0 +1 @@ +e8e8ddf90a44f5ee66a10a2f8634278a \ No newline at end of file diff --git a/doc/html/_me_d_c_motor_8h__incl.png b/doc/html/_me_d_c_motor_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..bc95b2cb096713301ab55528336985509428fdc0 GIT binary patch literal 46538 zcmagFWmr`I7d=XMNH++AASEH43W!LFbV!#p3`m!VNQ+1_ba%s$14zSwbT^E2cijVg zfA@dyeRGd5e4crR^U1yU+H0)|{-7j_i$#frfPjE2_fGmF0s@LB0s`U(3^d@Amq<>H zz<+4Q^0LwhclZC&nsTEN5S}8)NxxQeOWvMycT-=3+#c*zenF%D0a7O}93@CDSJ#~} z5JI9rupLXYjd}CsM@E;hT4-)D->LJkPLLIe6d}vFPC&If*A&&~d|MhNY#53z33`!K zq54;3ic=3C-|atdaef)?72%x0>zxpLdUaeGkRV6RgV+rJ|IaWDsS5%D@bpAXRa%fC z&B%bIE(b0zj^NChc=QYmfBS-k{eA$CsVqBbgE&t6O$Lnq<{8GqO)*!>q&r=9`B z@HlsTS@3p!8%{~$g4a_KXW)}Cq3_8->Vii=KtcXB5BdHb_s_fayzTq(?jMRbYNwB% z{`i4I&*~}t-}C)RjM)FCF7>0A_VL>UQS{Pgk@w#>9Z0Z9x$vi}b^heKTe~6eTC%fo zRG-8go#B=Pyh-u#O<4vuCH?33Vfy|U#OE#=&NnQc7eUkq$iKwD~EP55T zBRsi56}DnppiJ%~k=}ji%fR+517n z4WHVi_jdB4x4mZ|Ac(q6v(>xbtHb8zqP&gWFL@>AbH_|0IcJ+ai)-_%_e=U$_4t?b z6VbMMQ`3jl*;jTtt2UqcKNwWHFe`U$c^vAI07Lu&j_bd>Pze*>n)>8A=hC02l9>^~ zpnZDS_ws1ky0jQ9U_Z~C0Ru+-JHpTT|2-MtaJrvlJPrrU)f7YJ;db0lkmuX~^WdG2 z>+esp`^it? z4l@X5;1}f}@z0SHVy#qz{4Q7Xx;yc7yAq%G7WdA?_x5fYgiO-W^Y)|Hf~J(Nw)?jR zuSafgwxgfniQKSF#7)Zj%o^mMeJwWLhSQtibh<;ek{zLlk~o&_?tjDI28@{(;Yv~J zBGW>$hvqlp@D+f~`Y$$)Ln}4UYd8k3@jFp>i?G8=2VYiYC+TZO?a!%};Y^aotErj} zI-gNg5{YwuV@4Kq^NA{kncn)d%rABkeR$u^7{(2q!SlsP_Uu`j-;}G#X*gpoK5E>- zo_wiLdP{*EhTK_mH(4&aO%gDc{+ArOIi$TsAIZT|?rV0NNkkAe|MBs}r`GHaP;w3R zP>B&FriE9hOEl7cbDVLH_coDJ>FOplS|;9PGDlL{nJHVC^?57&G|p(3PG0e+@t@$j zwJdAQ4)pZ6yg@ZKH2b#CQn~KiHtfgy^qFU20OTaU3nCy8e8z%KG&I7?7 z$=d&|A>Z4~F0D_VqJu^`{))h@`|r~8*l7&QqQlPoNBkF(Kt?X*E@G)cryslX(P@v& zm5Rjv@*l55SUu~%oMJ81R0j@vcAE->_}#oC zf9z*zcy=m39!-naG~RanJ`HN=RT!L0s$8p<;{+r-&BtWNXaak8$$vpl*1%2XMgX7T z>!>-;oX>4+m7mqZVOL%QZMI?7l-CYwPK}7s=r+HxNNi<%O6G>5wF?_=x{XAyaAfzi zSH`gJGjTESF#z5x@Lv)gWMva`J0MpQs6*;TFPWUxOMxxp`cQT*`rcE*INvN#_-8}k;~!9-|i_o zwbhKC6GCJ`tU;%BTq%inoVe~ewIqhHYIxXfNld*Yl^;amArIn>IA+h#OT%>|bvwK% zHne@!e1zw#D>|o>(ap{9}vQvBywv7XQ8r(??`8CvRH@ntmJh4Ia-R5v=w|= z|98@zY3TCg6=#awo=n0gX~yXP#;SEr>;o}vj1g(_^EoQIYQC?ELlsCQ5QzWu$rPIh ztYW5omjK>(-2Gk8O+t=;O|{~>%buOEaC|CVZIh?90kO5`t`8;rXE@B8Q_t@Iid;t; zjqR}}SIC%QrW!ina*cyg=fHg<=~b|!8n#8!AfkZ_CztZMgz#im&kSx*!X8=HIZ`JX zP6Q(VFY)mk0U_?)f<)7;OxR@1z;DSFe`G)Mq!<1*?+>!jq(ZwTa~_KZKU>PaH@AF@oo7a^VZyW+#MAX7T zMKNk_r0ny%hBgMDYHQ+4=B){?iC2>gB2GA22Ct-DEhQU>Fz%-;YoA( zr*4!c)q$^si}1oaYZKk94xHs>lJup&6FqLzVRHmT6dH-^n?WT;5k+FKBm85H2JD(CT4f#v@y?;uuVeuGuD1L4MbdipH4nIY(ou zOGQ(1YaN}O+2A5?;k;|PUo>tGaw_sXNXyt^>z~)JCT(^8p_3Yv=@t5MH4PndTMq&X zoX3lYqY8?>#N!a^M}?t}*B_irzp?(;C)O7&J`YA)gp58Ek{QqXnxWDi~A_%{!G(7L}s1dGl2rt}Jn^LR*GZ6qHE3n-4MsQLnMO}p!iobFpf z$410_5GHY(AT~v$BMVo>%`Z(Hji9$C2!-uGJCpfoOMrxXzd#SA#|1ta<&NtD??s8v zF+T&j3x_g$aqd4`3`t~YU{pQZ!HyAYS9NdN+dyQFPT2#Im!X}z7sVtlH4YRu^u}JW zw4Fw`PAg+n`aPSQ!g{yVxcD}+)heiyylD7fp8+}PKRlMhzC?suf_Um`qMx&V*f==1 zj9K#MT-f2YV$`R&a?i7XC^;Xc47IF5kf6!1%;t?FE?W>0_4`P2Hm+k^ka>w zVOqnwt)0l|KWVq;u|%6TKK#1~e6@MRPAK-@wn=LT&>40r`@O)E?^$Y`4zA&k9%Ly# z(t3?}!|Q(63}7Id-rd8f)uRpsm_s~_IuJh z!AI#c7#>dDQ*8db&hfo%I-lt!g?Dy^Z2d={Qo7X_%~*f@X>c^^RQWtmT7sR@&ObaP zGMiPy07pA&<2wqhCe+zQmoQRnA_B z4_UokyF3{+HHqk?kXv{@aZ%mMy{k~nQ6ph-Ns*9NAuHYs#Oqy&<5vn2ye{NYgxYvV zkW0E4nM-rJC9hOEK5~t1%j!+~kYFK_$%)2`l*Z;iiJAQzJd^*8^=%q{sE54`?`&Kr zjx*nyTosb{4qB&H!IGmYOsa!KNf|Ez=Y4nd@j7g95M8(VB)c0XJ`fDOah4S`h&8lc>oDXI5fOnoK1 z(j2|`9vu>svQ=8?OLpYfS!HlY3bP6tGk;ZIY4rz#c1(jS3je=Mi{YHohb(ID@Y*Hn z=0(zA^3z3xVhO-_vVYJ+of+#$J(IXCkqn*L2j)NR{Ms)Szd=_>*1wkuUR# z4e<({Up037{x@sr{h4gKz|dIzT?gt!b%9W_rn7A5Urf#anbBI&_S!7cw5^{+oWat( zzIDQ1%3mE%Vqhv^rXZqXJnu+OXNrf;40b+1jk|y(id^(2_iGPV)W);LG72q$@Ib^YCcL2iHFTxH9r&CR@YC(129 z(kL7EleK$M<(kpY@$2(r%|nYnRp*mH455id>zugU%1S##yKAI!MfA0@%5Xk#_AHf1 znbBRtypzX}O^Bk++lmjM5d4l@7fl51-DJ2@%Q7MLPd6cOHndJJK_HbL!BcZQ`Zj{ z0ILb@M^MD=T|6DTxu97)M3a~cM@1X+6#pX>u+}iOlN)%0jKS|3P8CsZv197#4x0FJ z{1(`6GIF@E7r}XL>!6NPor)QB@ypxc+8$7+5H%XL`36KW2x$f};wTwa^lkSFbj64> za-4P$6z`tZDkJ=uUI^1q$6ihROksBP_8nN;C=y+Q3tkhSI|4~_ICT*A&8ULmWrQG^&jw6+C8zxI~r3jSx z)bHwT<`J%GETs$mOc5R{E1|zz6P*!vi6b0D?wa+cxx8#LW$%m{GZp)K2n?z2I9<8* z@p=9yTK~Ihhj}k;z|@#bOadWA4`&H<7M7=&r zI(6+c_>=y=*Cs$LMTXFMWd2R;T`|FCp47cbRrp>A1bWgXnE^B&JFE+m>c?h{(y{rr4@)-sbexq}>#IOBJj$RNU9pvPc_>qFhC7myEqhBsknxjf!6 z!a?G~zhPiex^JtiBly(0(?ti>8Kvw#g9{b`MGBXli?SN)ornCxwS5=c5iK76)0+DW za>?Kz+*8FH{cP4_&{tqlBaK`TlG9D7vf5o$@l9FaoCJL9y|uWWEKJCDB=ZuJ|&!)s5cpSX4=ds_eI{Xj{`jU+G9mG|}@#Gh$A1x{^X0ohUoNOWUw6%(P ztiR0TBEPFMdY$p-4u=Vrv2t<78(88?Cwzu|Tu5h%^GNol#}d8sWX@4*swN)zL(uTAySZ+M3dc?{JxJj!;-I|ZrDJC}B; z?KX^tJZlUNvG(IdB8^1}n+WoQwdFO->fWlA)zB*Kxd!}|Eh4=bHjrQbEX>pGR58kWftJm7?GFdQon;}_PIeN zIxYTeXl9?UVA*u5b;{KtBq;toutYSSV^3({V1( zU*q3Fq>smSNpDr%mgoCexHke0vm#yLl#7C4BF2bh>WUR)nJ`o?k)@S4T4;@g--%xW ztdI=&#mutY9R+L(Poj{c;x0ls@|`k(W#_-laF2lH{UafjTn@LcEM(QgzQW&M>vo?H zk=t*?NH)~ATs%-rKPp+#3NJk9RR%d zEajO!yHcwEHclYA_ zS#jD62Zgta@UL$k$um=I0Pd^AF6)Gu`0J{^Xy$&R-1|cQ94CM>tl%%clU+@a5iCW_ zvp!+YXEjRJ{D@nstsP$?tRYp{_x8Fzud@5U^4Ck#{JD(8VWsmY9ZpdvnKr|C8rfN@T%f{+ za$Q^ZcTNYC?<(j4+Ox=#e~KS(XPZo}d|oRHKdOY~ve15+G@1$%XKcK*npp6}x)ch! zr_lX0%m36yFnihAaVjUMta26RbU()#&0tR1hpg*aI5;Y*+>weg5Qg7(u{qtGq18NS zbsfoU*jScf0_UIWtkHv{H*@k&b3{_pL>hvV^@411OY|rDR{*4Cb4rBg{dl2;>vRD! zQ5EtEDK7CST1^}ssGS*knJztZy+l5^``%%P00xsAjgrptRRmYS`l}ZN z(sVozIla3~Lx0cH1B(AfaBdMFPj;Mi%0vZz$pRnuyp`ve{mwmwoHM3SW2Rz380ByD zI+zb>q>t+Q$WD&{YOo@AXNIw0lUmI1%NwSGcgODrOU|8j8(-4KcHUCb*e zxP32d`j9=NjPi|x?P=Ecagmz+kMNUKtwU@bM()0th)Z{CK>EL6X0NVw^H}7S{tGYL@(@~r3k-ApPnNEKzAQ;DCPCfZVGDiH`YJl` zPqaZCzc9hdqrWU4nvN)=XDR#29nrIq2W*SteMSqL#)S{<8?1&2sH4OVbY*P&Q=7(~ zqRa1^j8FffSK4gsfJ?VFnRF}M?W1f8g?n|ZL$>S3sl}H%X?Cw|8jx-Yl`r8Lu;)Ba zwwuo8Ki!H_o$d9^T)ugz>^SagC(Rb3OQC*2v+je* hIwfhLv)WTmbS5uuQBaDD zsWkxsLmHg_l3z3Vxax!B8Gh4o&2N>2XYH*S!KZI+)4_4?9U1rSldpOyy&SJ;@7zYG zq$^(N2KGwkB;3o2Jf`5NW7|V1&MzjMWq9z>>DOhS3M<`)@pHnns2=nI^TZ}vm*)f& zvq0a->?e1SrOaCwLLLqTgo>`XguY-a|68!K^raHpy<%zFonLgE#=gXRm~1gCh@Uqr zy!x}1D=xQETTX%!F1~303gk8R3=9w~iy$wa%rxqM0K0TXv@ke;=|t z#mC;Qn|K%Q5^gw)tJM(_Cs@<+E=*WcIYz)OSR~YcE#FJ&lh&*2=9%Wth*gj`d9`~B z7ZY<3SLISN3LKy>)L5*qFl(NCG380M7I>W*%=3%6 zkOSStiOeG*cNV+Ce~tCIwHRL$ zKV%#p76AM0FLNi`!AR^@kz*7U^(x)!tEIukwafRt$&o@Z;$?_Y#U5&2bm;%4JS3HjB=Mo$u6ldWf=Q#%ROUZ9kL^jcW2f~PkMOf)&`Fq zcW2+UVMrRbO2PkcfLF_y3uG(kg4t+&bAlN)-6_D?8vxx$(bFD9$%NO9Io+hv;LmB3 z$D<|l{gWF#R~DWKAh)3^N3-C9cAW7s;;9y14^R|)0Y?Q%wu{f7FV7OTI@eH9lZ6{v z2a^qKe8Yj02#T=P1N+Wt!(+sg^c(UA=HQtr<=Jr8m}dZs`%r*f@4GXzXJkTpUyr;D z6_N}rc zBt@5~9QFB4ird+K-n#!Q3U6f_?**xkY|qh3NHfX2(U}I&pknFNaH;2GFNC8-19DGHf)G9YQ=nnZrC@xi1~D`d;RnS=O{!;oMLb-Y@uIZh!7hqec-rfyw76-GOdx3n=5m z`WOjEJTM(>Eh@^=QKe;){#T>#F4Yy&#e%Oa`r^2$;2~<92Jz~92dGS641j#ID)Hae zsHGg=>A>}D@8uF9TdzVudZcwJQMhMTm2FL5IQ$G$D0opGlmTPBNjm|L1B@c6*38<> zTroqBol$q!9Qh7cqF-dv(ZSPCSP`9*9W?#)DXX@Gw@CX8ouO!3v+e{dfm+a`%w2dk zAb?+;nEYO9?JrEXS{L(iRl*ZMLu3Q8pg4z~nrDXX58;#_k69hje4S_E<+|6x4E&Is zn!9CELl(@Y+8cLOGOvJS0>~4C_~Xx(nXvmCS(~!ANYeU{_V1fW=14J1v)`?|1`FE6`F^ zb!}W_!HTAJkL(ySz*RMS7bVDJ2rVo@pb0>cJ5ho6W}S=OI@+61{G`IZuo)os~%}v#rU?e|NrX3!6s?F`2(4aGWCSogU);|=t8C648xAEvs@snckJsbv9cMa0-^e7nmUpl_NvCC&US zKZwO(s`hW2mOKb@BopA>M&7ygMERWUUV=n*>Bq*>(aQ91tjKo{JXJP)>mG17zGMNh z71fVDJ_IC^AHqr94v$nE1Cjmy$^?Zb74>STV!kM+u3+nYh_Gf(470aa?`MP*>w$Dr z7Oz@QKxGbkDSCWoTuAzsM#dw}yBcP$iRKM-(T7Nh;{SHo&bykRXYB?Z}Wi*{GX0Byl1|! zaup=x6?qB~&Hwol(D^&_KxR^a&H}Os7GaYOTl|xVdHQ8E!NX)7i!N%U&0_8a5|(2p z_oeDUkv5^rtDZDn`65iWx|=m*;dNB)5Jy3i8D+wm32+a&rwB^)tyReO0#vg%`j*OdeN8A3sJT}6UAVIvi02g27q}VzmHz4dYrN(a^6iscM|@?lgs;yhb34&8HTHwzcIs2y z@Ebp5BthsB!tl$PT7%P?)&;5aq*hh)>jBm4CZ^7X>P?e>_Zr`KTQw?TWKBN41MmaL z*W)QuS65ebJ)6mdacjj-<&%(*(4AjBk{PC-?)8WKKpxj-bQI_vpx3r9Z;UG&w4Sy6 zKSZDaBecH{?7I-DNum%lf+w=Q$TdAzEDB<9f!wKa*U8%2nrGrvZbPFs`^)`yWwB{j ziEETY*$7P9+l~&=vo5lR#xK00z73+O=f!vF7vPDnYjJ~Hu&Zw)C6Hg5n#^BYH13+2 z2R-f*x_q|^n+Lk^;7c-^XfKOBvIWl0p*Ni=Ze?_@);_k43lyC+br|`yHcm5m7L}gS zD8Sxdb|tD(n<8F~=p$%fc6qMI#qYqB``sdb zjueLO9ORkwK>2{yO>C}dtHoeds(;%b@SwFE`%lP_yakZe_aK0$!U-#!6B-InazbiW zEi9w0IYoYPK%@3lH36UBzNLc?y$`tW7N-7%%nNO~=_Ys8i6IkO;^?S;kJ*#of=C+j<46TF#gEq#nbPMDVyz6RYI_jfQPd_Ew)Y1es@Df;1 zc9v(=4v1R8J|e}cDX%Zh`?xj%kxk#>zWy6|4~dVvu0$YEMRq<4b=KG+r$i z!FTBH7BfXzk^C!9KT-oH=rY`%;s5niULP^#k9+?j_u_#e*|_Op3)r-?C<{=OYY`#j z2Kg_lB;JDMOj#b;bPAR7VNkn3{Fr!Lm){=l319#O?uNz(sHow03f=;2j^XrQyn6?8 zU&*5f;zM`|CK26WU{BoGE+?(=iDKtULLbwgv{g4|i!zJ#T5Ly!Iof;7RJqu(th~*H z!m3uGHZscdO^vPiE-T!wc-sRZ86|&+#8J!VGX+N+-N=AjNKy;t z=XCFGY;XX0xpncZT;og6D%s%<)9{>RQb)XoSkJiW=6q5JvzIKd(!oy(@>H~WXE@$s z>@>sfgje)#Az%`_vt0KZqOj)TeAP)6hW^FAg|Uf*-H-%U0M%+z4`D{1$#<7}t=(op zKKt#Ut~IU@dk2!o8;tYif!xTNU9Uqrx12WaAW9DV%`vkW$17rV(H0lagz zP7An{rVJ1Mc^&e2UupwJDWRCYQvYX2D}CMxn4>!u^IM+TAH6W+WiF2k$ovc-l}}aK z;=X4loSoaf<_yy5Udqx$puwVk=OK9UHknzDOp-0YFQ(>MVf8fQ)wKNBjNcs6O5x4H zU3~Y4M-Pn$I}l}ab^XbexU{Y-Uzhmpjqa&&p`dJNGwH|CxseQy!rZP5i#E;8CPQf` z`y#`l33LZhkGrK?!{Sf~sJPATdLURHXU&X*RJ77+)B*t z0ZFx4H=|X&?*`AOXe?1kI}BCq;m>+}lXdql?9szQTaEC7mZ$>(yB=;Cfm^>36YM>< z)>KsrU%OGLm2aWevTm*uB*nS)A|U5E=LlRo%k=>;zpDkrup{rZv9R8gt$Yf*JMvWb z$UV}~D1Bs*DzZ~mz>f7 zn?k{rQ>k0P9sXOO3pyS6&{&chy?^9a=s%tF9HtF;vnnncVGrImOL5#}qt4IJ8bN#= zXvW#cYpXh&)NTB17g|81M^@#cHE9eC>k>qoOgyGeW1g*}vrxy;*g1G&&C13RCV2XD zsJyr@tfi*fak}lrsnuwLG#b@|TVR-@-JMg}f|tr`FTT8=eywvAHL!+L^=x-j%Q?t5 z(b2#lLT0bz)RveGF&EK39t4`fDES1yz245FY58dDe!<-OA-m0^8_Mf0^3=i?6`8zG z_MXKsHBBZPAV$I|nPnYqF7M-Qyp3@YCz;59$Os}7n#k{<=^Oi@U8dvx;E69UCyo%- z3d=C+Pg^Bpv%A3m*`f# zMq&A)MM-WzRnpEoBSF@ObDMzmVsooUAxVf-428DuPx-$&_3_0nqkg`4v_Y~e_7kEA0Ebret{CucVG@YId0DB9l% zFjqo&j~n8T3ndJasSdnW3IJE;0H-^L3npKrT_ToW!`+2RXV=||?c_5i=oBtzbH;L7I zMVtI(Mx1Gp&=QjB%5ar6%SPXdFvEh?`YSKZDnm*5qO}uujGv|)moASA>*?s4N_0

!&T~ZKkX@_D4|K71 zz>3R(=fctJf}kVzkpHhR-ms^u1J?~_U*rWx%An8lx;@PV z)-^K4<~6f!z6?c$S_XLtG}opL-2xiALCUe}ECl!b-We0yb*CFh9GMys1{}43JmNx^|}uVo`;|~Y<3&YT>^L$7FVCm0k4)* z>6s@kB`npxO8@EVJ228P#R!>~&&8x&i_zITv?~<5Q!5}c1#I^kzAe2)gCpn9Jy>!1 z&s0sG^#%M(%I+3$>Hd3rLkWWd6;5DX2J~Al+C~J z*MxKs&9A~xt2;EJH$2atN)ha{-J>gJ^?P*HTOkCbB`R&`x6_z+4>mBQP~C6?>rjPP zteS4H`ZK|AeuIWyc<>`ACo~C4=TEX;l*hRoyd)a1aeocr*VKZ4lS?(pW|T8wjQ{-# zf}&HLE3V7^&(hcXA~y;_`+E2-b!A_5u?s+hJvsJ!%UZ|e`z+exq)iRLKF))W{9Ymt zB2NhLsf-VtmLV+Qp>Ri0h2b4zS+3<2VXIfmqB+0QE);{&T5G4}*3yQw0TleCi zIs0BD{Vs9@V3YMiKKBA1(u zM)2qi^RX*V{{#1+U~>i3w=UG7yReS|*?cmmdn_PVoKIiigaOLPh15Rv>A||0(`X-o zWR_Uo5B~EVH#xSL`XO;2P&+s)M%^$`4gL$J==08<eI?jb-@O|mJQ7=lpCmpd zWp3z2>DCc0f}veRDCiLrLwmhKj_0((yR$aPXm}MN5hQGWdkn`Z%NtO-936s?xXn5V znmsMaA_@+<&stGN&r^;+f71&sr*dclbi!Y^b_eQEcR{!ov=^TyboZLB^OyfI&B?t~ z3HDRP%#pO*8%am}cnp1q3)}6KQAgR6ZIopxmHdwPO5^5NSOlIM zDj+u$}D4lTa*E(%-#L><>>5sB&mn(1Gx6*OWue6OA^Msgn%lJ`N;&Be{OB-;se zYZug=G*ylVk{20nPw!0+t?%qA{a)4|X)ZqH7b5k}jBb1oW2e)X^%po}jGyo04tEJJ z*m3)40YFbW2?q$L4+1`sl~&g9Z#MW@c63?ZuBt@3vgPVKnZKEv+Q6wo?DIp?UTJGH zzfL(qEf5S)zaUfk%j6SF7yz78I6v4K7`8F$*#&W@X#n9c^BteaY>=a}QpjZiAwVZ3 zPjLaRR!pQ_Bs>f$C7ln(XEIF$~c$4Gqu|63E^+dxLWXBB` z$rR@1%A740Z8fv=vM93!6ZgD&2x6(B9FY6r(S^RR_g}H02cNv1(bpgazD$fsY&YbU zvvpB~rZ7;o={lL<^#r6WnmKKo&cD0KD!Mi;!NRHr1CQ2ej(2x0&Z7IIWurza zw)8DjyQoK!#6XPL3H`3)MU9vA7$3}BpGBS3{$vv=n^a~$t$8_za?Mb~OTtQLCiq}9 z;`vrZSL==I09^iZztDo`Q=uyGO=Tb#G&-}(*726#XdU07qc{tbdY5|L?mO`|e0w_# z{;CGe^5=K1G0uk9G{NF(Mk0TUKN+20I2-x%eBwLb2agXA%KvN?f@Qtn zBfv4yng=?G1B!Dh+BRO}_XAni*!9}-tRvRw|F;K)0lOu*qQNU`O%=_HW)gR$_H}n8 zoNUG*6ILU%)2?!d@aN+Tak`G7dABxS`~BKYhNO{&!QJB1)&T(oSAITj>oQ!s`CkC1 z16RtY;`Q_P1L&5cyQzkw^SsT%gOyYebCL#9$T%)>F-f3?nvHyMaYnZSG@CPxR3@Gx zBO}jy+REB{x~gWpI8>s8$rK4y^8*`F4^G;~k+TY2ut=5q7Lra?NAL2RUkRQ*zWskX zYxm(jYEKh$y+~(6p?&;`Y~x$Ti?{_LiV=gNNs}<{&eigM=88BZ36vU~-#}gJ zPknb{s(aiId&A}*?oaw=jJYqz=MGW$$){q^;WimoJuKqF54x-SeR>87e3`FPk>)e*~^}`TW@{w0xtiw&wG#CHq&h#*YSFGb{|*6)u_I_J|GX zq7h|`Lv3@ALlH}HTVQfHPzo#yz*kg?aE9{D^T;gph~h+;;c1aHrX@G?xYAF}8(2^L ztzic(Fy-gUW;Kb;6z4@O0!)2%cCBtxyRQ2B!OxEo7Nr9*S%~~wo90NpHJW^SNH%5M z4l;>zSKBIXDcDYqBAkL*VxXidyC0VBPF$(f3=|4S4nGEsA$ey1wr9`#IdRj=L^$D_ zel4g$UwaWFWnlJQM}pxEgw3n+OGeRw2yU&svVwF1QZgb6u?C`ih>ly@rRl{G zoLG^$jqQX*?ttT4rJpxS3fitC&F)EI_lzp9#y@?3gcE2=K5;8*^crdlh^Nz9W1G8^ z+~iQfEt{4J_~}S9+AN75TcK3N-@V3)ofX@^BO>OC2%SiD=3gSUIS^^{g;Z{bM^8%yI^X)_R}|fD=gQM zyi0JO3VhztumU6Fkht{+%FNVM{Mmz#!}=|U=>4C^B4(-yeSTUkoaEmVA_lBPA;pq6 zju}goi8F3O;TQ8Yj4ercnv`Zu-9;;+Vw;!K_g`PlzrS@U1rDh!_`;rCBc)*Nf`ZYh zef8(an(1Lu7eo$68SS~Gpt_XZ>7QevDo;_6$emRW46 z*HW_obU&6YnMZH1Iqc4|lkHBA>3e6(m6v_s8c@M1HVkqF=T-xj|r)NfgBDgngzdilxf}_1{uAP zm|1q(&aIINiec${|FOuffy1Lldf9_%AKQO#?AvPGl(>&(Tj7c1N4@9oiO-+>KwVt- zN-2J2R*r@iQ~7RD&HsbqyW2%qrD6uhCX{m(cE;2bkvN-zqLIODYFfnag1rKu?7H=! z{u2RxLtzKXvS`Tw?9kr#?*D2I4x1N*5|u+s#>J`wwU-^zSv`^aNbK@)d#qYOQtBC) zKG|HdzbW`goZ=Q&sAS+Ojrw2X=~h0=l(x0z~AZwx1Ib74&4KWlgohOne(+@ z`NOlPTk5zvRYoFw7;qM^LViYkb2jr_HKyc6ltmu@Xg>>LpGt!lXR9N2Z6)VGwVb3Z528=KnB|LmgU zbH+F|-9mB6OgJ$oEvWh_=NUC_V{R`pG-LXSFYC7{^FZ_Q_hPdy7cZUiSZIT{2L1M) zNgKbuC^m2>|KA~9AE!b@1(2jgQ_y(P4;|l!<1upIGrr36`v& z(n`5GYyrQNxKVRc0>}CgFY2p5KkedVQzfrOGj7WEA# zlMr43Q;$fJkh?{FqWBNDK(C}Xp_=6I$AbG8M#71%C;B0%Yj0XW2Ok+rR18a4BZ--W zT5gh7wAoG^1Udrpc{(}CUnY6K9}xhuaEn?9$S(oz&pD@4pC#uh?p#r~lc^A1!SWiW0>{ba!2elT_@6HlC z;1AU2ZS^#@Sgb5n=6tAQ(-it!t1%g+p}u-10Xcc!%J;0x@d@L5svhH*&#`F+KXbPJG2meSOsCNDHXq*t2`klcP5kAT8}NcaM6LM2%1SI1=jvU#kUdkK##@dyKG=u# ztG^Ls;ah_w&Gx8tsu+*g*Hpz^cT-m7%UpdpH_ZUUkMRvImpW2G%^0+AcLlgTAn~l3 z?00&uQbP2+S`Z|1JexO`PqgM{`$Gbm`*d#-R9}_k792VxX>ygkQCQ?M^i}!FM{?+; z97z_j^^GBJqJX()p`l?XjHF&Osy&cZ4-G{velM%eQMUH`AZk?I?YHBaeVK%p)d+M5 zYgoLXrfe?4i8BJuoxuwQpWdojF{JHvtlXxSKnt|Ek+glLG;#-;pz;g;y*_Mp_06I? zELmiDumgV?cJIn^*?uPR8E#f=t)3>uL{s#>l)p9=J!El|*VlbvquJkm&cclEuijDbzF90DbBzc*U;OWWl>$Mtn zeh2E-mRHrX5m_)DXL-}*0+|2L8+FM0Gx_Hi=@>@-aG7}Cmn^=!gVYQs9?#m$A{;Io z)7bY0Cp%3;AL})HFyk?$UdbB=wGWO{)GW(>o0v8O{c8|R7W9&tsWpLGgWfgw^sghb~f51aK+<0@)_if z!_a7!Upa;#!(UM2+c3@jsxRa3&YUCZ z$r<~6p@cZ^81p>?0j`$HqI=1F8>G%mQX-)=oAnM0qO4UE-67689GNm8l<~R z-!t6r|M~DdA6%^ES_5bAv-frVYVT2y?q#iQG99dlYLQ<)?bZwY78!cDNSF|C@oEHU z?i6Avhphx{ZtpbBe+?6U^!Bs+}XmLP$};s$Ag`IxyT8tIgC z>dbF)dD&n1e`@j*bu|n5Ci-fvm{$hvgk{Ep(>d{Us z(N&<&080q<(db7ljbrrr?H|{UaPZImO(u?=;M4lDjl9RXLnEOzvqIwfDHD^El4|G_ z)Fs0J+XL;h|0;A$m$Zt^3jatX6h!JTD9NgBy&v{d>Z^C=M<+>fAJwbN2`&6ChxYbE zs7VK572-3t5KOu*a;f#KI28(lJ6}nfv4GeD(O$Ov78whBb=hCh60K_$fwPI0jXo1z z_v59t`96kM4g^Z!} z6AEccrP`06o~g7Pv9Z5R`%SWvloYb*4&#c)PWE-}wG7v1#cYw#;uDue4f9L)M``Lr zhBAbt035J!zg73of86miw3UXI!8pNAGfWhcZ0ghK;9C_wW0#L(d3E-rK=&mMTTr@k z9Aqhe)gmDB$GLoWgT8{?O{Q`{D^G5=YR_cZp6X_3mabq$YfRo_n%y2Z%@Nd3c>pEE zSkX+_v~@io6*&Fj(tE_x0{?U6Y1xl+Z}FnrG3aZzdYI(*FDBW$lz4_@wt4sz8wFSW z?E@!q$;VOu8@L~dN$Kt9!DnVqx6HumR8@n{rz`{i&IIMGtA1qWseq;C8|E5H>S~&# z^Nx-W#8_}M3bwClI_)D5LKPs@C{=~QA45JyEThe99FQa%iO$h*xJK=Y;?c9h`zwuR ztMh55a5NvF!tPPJbYzj9;=+^P1h@lTw?f~ta1pzi-BOLDE+2uHo@^@}qnEr(7%gop z#dfgzM{#*uf9%t%%jtwZLq1yqI{B1OPIX12&12tP;{tc3dw`MJAVCMkGK^IZrQ9$= z7_e}?5Q8bHL0jdT7qJ%62hFom{d*|?ys4 zl|<0EvjN6l5e;d4$S~_ubSX2(Wg4?WoX4uQE&%!0>g`w1FWJ zFT56!v7Yu3OkH^ZZNs7Bp40gg1Mf?vNlFnR!cmB((2s5_-QX29mhQ&uqfg9nW2CHy z{nC63hmf233R3SHkgswmHqR5=+_g;xy+j3vP|hs`2JTn`=q0zSKJK0}%V8m7N1p4O z?phHElZcsZVQ9;91rhvWpAK(_oA)$^8SCoZw}pk&$#yR*`x|T?HgQq%1AFC%vcksw zaLDa75;tb2;jb`ia@vAD3j63HlQc1EkV;dLRXnW3t3dAco3Tru$6)b- zx5Fg-$GHJ`$Btti3&1YPK*^g42+b!f%Fp1C4o914J7HWXYH4Nc+jOZV<<8b&K8sB_ zNv8eX0F53MK>|O77oN_f-tJf&<0Tt)K3vv>T!6nEh&+!8w})t#_bX2fdiL*qKJfPa z0yOZ+kx$GYU>lx>xZKR}CJ`DxCvi2TdSh?)V?tWOoE zlr~G8OXL}MR_yNh|1d*P@iE`X&iMN;CJ&#WgYP8rj zK9J`M8dif%`pYw4RG0NCvciDVf$rRvl=b<0ib#CA9jegr7iGn8qF4A;{f0A+C)oT; zcm2*$#eC0chu0)zI!Bf&?JBx^ly5qc%LWCtBoAL;ie#%I&K43-=_FF4nP~dWYG`+W zYyv>!W*Q==7}nBl*vXW9ocr@D7!qzP+1Q5|W_~z=XvcFoQ$DBK*N!)Q3(YMd2n`ae zDiT*ei3U3;WBr@aTeRZokhi5v*XwCV@5RU7nR}-Ta+4?L+so%lXaOwNM1HpV^3qE2 z#X!`^oa%6Nxqs6jIi*{#Q>$(i{ zrFVU*=#?q==bkFmWG=~8YB5h92Dzx8);nI7r+)Bd)6z&bho&~$#`)eewhxt()J&@KJr z1p-{Ss>uc!?n$u1$6yWG&lO|beaw-U|CT8x-#n-YlMHV@Jy|KqznQRl+jg>*ALH(m zK9rI6!Diacx;WF_qPpW^XLsS$B!I*Rd4Zk#Y+M}1}U=vpm~0g>VsPlBo3?)g4I%Le0r$hhrVh*!5~ND`QB13Y0aFUNOT zk<-$9z0b5nFHs{W8*_!lyp7VX1o-=a&DL7-+sE5~$xts8} z_B^P5fEdeN`Ue50wN&}{>;hwnFn1&r%bMA(MbFtHeghAzhNTu!wa#9>N-;_GpI{Qj zd;LDd0x0h)u(GlrFWJo7y1S^YwiEi=;`M6ZbF9a7d+4+>r`4b?^auR!6JDEn8*Lms zjAk5wIA`1fK&)&RVLaiS_6*UEC{o;k%GWB1b4ZLesNe4f``?2d+Hpg@rAvaQK1 zuRV%~CWQ=uWy!ToA2uwOWnt#dfC4y+{7m2f`HX`1Jk((}_1u5cB5J^|Hir}a1IfxC zr;g||_7Onx*uw!-ufmAd*>d6k{UtHFiF0d`1;4KR`R2a^MKt0cnob8ifCaR5^sgQ| z6jW7zI*&Nb8r{?lL6^CLeLSuMdZvrPu4Tq(4Adv|to}^aqw6p;Gdn9whRDc;7nZbNc1pH|`&UYgnmaysg!ldxUlIeBxw*r44gDQ9!( zc<*z2*m&e^rGeB z%zfd$qZz=l`Wo+pHt44S!pT>?s`H%bC2I1!vOUR?3@T)WlmAaa@DQCVnqIh{_wPFQ zsqD)e!BOuRC~R&Xg);DEKWYB^&d+@D=AHAr`j`2|CKg8uZ zvlOQ$fUemY>YjPFF3}_mcF~grBNnBM^GX%LEQ zpdZ@s-PoY;bo}}uD>?QMe)UwiNk3oF%ZHgi)|p3BuqpSxVZh=(G}=1#_r77y|2Ds` zU?)Y_%=C8m?gHlE+7|`7z;NeUw@|le7v_4%yl`qX4&w0}xWu;P1-$l#=l!0#d zMmW>HBy_lueCv8-;1>(;M0? zHC7|cJH@RBEUMVmT&!J*B~cu)1eFQN?cy2}PH>lrxGhtIh94@G*tn)tkx;sXrn4^_b{z7bUgK_P)NJ^V1pc1J5=V-$>Kp2t=@q6fS6=HERJ;~4 zi;Z?rs{x&Na#xf}jDY?jj>nwG1>xcWPPIoA*A4|*J+K3sG@w4xL%n5$t0vFK1{jdC zQz=jmqj+22Bz{Ht0FMyAuF$~2K%d>M?lN(TS(|xzN9IYn0yBZ7J&!BaBzyc@2T-&w zKv|TY_SQ%>Ee{GB!aI`H#Mh=^IFel^$Wh1%@8~?@GFrM2Rke(gqQ;kdcVk8cm>_)= z+WJ68)Dg&)lx_{M&irftm(gI;N{sD~lIlsE(U3==9k66DX_4D`2!+q8Ht7l5<|!Km z2al3@Lw7RCMZy_c(ii*+XednMgIh?WXrZUGPw%-0ulruAM6qKOZ;mgmr&o^sw+~U< zrmu*-c;c41QNuWbPQ|~xl3EO(+J&;;@w97MHWF_2=P07GZMz-sy0aw6z_{p|rrbqdOXGT+wjXHYpAT`}y z$CgCD$jJ}onULc~b;rGqFMydU4C?!Xv(1*h&!_cnnMMHE^<&=g>5yRiaJtZ?a)xTU z;PKzv!%O7~$ZFe%oTXrPta7cTL+5(4921t-BFU=xpu6^Thx>D}MO`!2%K|}7Qi4wO zp<})opnHl_BhoSa{mrEV#%Hk{`_Gb)D~dTL1Q>c=lq_W*fEuXtA{c7$Hkd-8-7cYx z1N2!2!cvP1UsDq88h#mTp3Zh1x}XFEn30|=?iySvf{K0oQLmS?k2>Y6p)zB++46#3 zH9R?QZO&rjV-f#QjD)QJUHLUw4U%Q~9EfyHvf2jR&M)1medoTvHPiwt9ClYk58uNut^&^0UI@c2hAbIkH^rM~u94RxN zqdZo<865>rAA?oI-t=JbN2vqA>$nWjcaXFJ?`JYpW6J#H04~8g!m*Y z0fF<)_A4IBMM|!MYZUw%vbtM;F+6F)EG>vP)crRtqu3ycgKnETyi_tRwalytFBMEhis8UqcQ(EY3fA@#9Hek0Ieq>BO(q zqagrX#_mIqW}Tu-UAH0*3=JPnj6JC1)zTy_cB=qt*TGU`I}OqfDz~I-T`bo}`P#zu z2wyRg&l+&_vxY78z@_#6)UZg6aF=ICTs5ylMD0GF7z$ca@{ffO8`3G!@JuZ}p|or# zi{4d@c532JKnG@>jN5YfL3;L7O=x{Zs_*|dps=ZX6FwfQM{qt^=U_ksR)**-n86Rl4xA>ZHeZ}MR0i&7=P$Pp^vu$ z47M{}Vul43DHv&g1Ru^y_mJx18-rqeWbrVbahR9047ke&e6J6zEH5&iWITByq8mN;O>s(*5=AY@=9Gm_WZ ztmMJ(Ho+q6mv(7H9Me1Fp`H_&=?sUTkXNsz_B`~icg69uAj=@WoJXFN=9Mkmx)nNc z#bhc;&G$nhh`D+YaV4Tx$5SDMPb;q>}9=>!d)a z61=O|LWyrIHMwSIt$w|XFBsVMEaE|eLjD)XAjyb(=a_qAv@mrkTjHfR-K)%}uLW`~jgysND`H?n zoz_ukEA;zYukVMyqmJJImJABGHg@meVdVnmu_Vgw?OJf|P*rXa0*aShmOgdFNk;u?5QEA|lg_ zpwf(0>I`DExbQv`7++}V&qLsta8WhLu=3QJUtY<&F&c+Eyhb-cmc6yru$UqH{b*dw ze0|km-$lj9kYQ=qH$_@4R+j|Fq4L<`yOC0kQpRLVv*$ zy%-on`w$y0c|TIhg7i?9$snE7>5QXSnd&xt!S9RF>x0bEVoJ5d+oP5?PL#MU-DMc7 z(iNJW7j_v}siCJU| zv0?wMYY3-p{*rttj#tF~6=U~NnVq!Dm*QF#sR!kc99cleKI|>^z0VwGwL672s>z=? zTvjZmJs9Md=%&(-VeD_imqgBGTTJ95j;N0od<~^yXW1BWWCC463d?j5m|jy!0qMTv zl?X-l3Y1U%(kG5xr@Y90gaA3>W|$Di6`H`1?gBkEE$)C`J8%#r1_^tzc7e@PXA%mH zo=6!jht6^Q09MJ{q-T;C0>xSxS%;!>va0}y*K(!=^D8c%iDoaRXcreg$0`1-QObkr z`MAV^EzcV1G92DTZAaQlcU8mp^c5~nMaeCPy2-+Kj2Sv(S-F3xwnwP zKAI173m`Y7@l;l(1nD}3C#6EYE7ryWoxC|&pWbGUMq_hNOQ}(Amhe$gys^H$U~ZY0 zU=z50L4+VDNb39OlDO0gESshyC2=K47Lk>TYN)44Nc0bAez)o?y6Zwjt%^BP8!56Y zBl1r`w>6JKx748kzRY43HPz^j$`jv{cEu}bGmfdkn8&2)HmM$lspX?6EDYo+#-zPe0DQOGrUSy?ES<=M`{57m$B8rnyAU0C>$C1F1Z z&Z_DpTqBBxLq+@e1$3xBJ9oK4C zL|lbyJOmxG;~_DtL7X7B{E-sR+bSpgR5m4FgEHJMAA8!UsfINhD>uD|za-;L5D}pr zAU&?55HeLg4p9u;?4u23k!>B@6)rmZ1*nRcCCEUFDym#04;ck+6j~>C0?KeV$7_bM z5+zFm%2DsmzPHhoB|sqxXKv6+G$JLEMICvWFwJHB7zS`@Gs(>OKB2Q$3n#>j5S7qX>LhgqtR-Bqn5g-F^pJxlq2; zUyeo=()((9#&KIH!0hOdNpb*J zI7f>2W?S@rau!%|dI2O7CoO>%k|H+U)+YjIH51sL28G4_?LZO)kN~J=25QjkK=nm1 zjG?mpq9U-S0mK?`E((M2)~m&khV`L2VnNiZvls&|MOnIJh;QC3hp9zy;}@I~07<9< z4@e}+2DUP|vvamk>JG>`bp>YkNxRe|x1UP66C{A$$(@rC3uq=ph-3^hAUXJ~ z+A_7r91xHPoRMj+SQm+Z;kg4&7+i1oh2GJmwZF~5Q#~kEZ?s{W+&4)3FdBiseo;~N z_Rr~%tXIw~U7PJh_hO!p{$qrrt%cHrITyi+X!c(s+yRd6%gw3n7)cT}!V(N!S)z6s zh@DYH$+5Rd5M>KJhg*P|2l&}NAQ)KA5nb^gEsamN6(cw{NKK~y?S!~onRg?i%q z*m`ZZ0y!GmFl)7~x9!PE5J;f4xI(=A&>GO9hE;#)h@fAYbN;~76$=5x+lWoiKAa_YG*`OBZIwRQ` zD3Xcd{hk%b0?vGGF`ql&DCk}<^VJVKde#A3)=zFK*Q)Z7|7PMn44Qt~{q`xbYY2}4fUyATF z7fIXKRLv5~#32GoA%=_IhfrSG|_fV}V>Uc{8~Kt9-gNa=B4|B;Ujf zN*Li+}Tz}tGN!xXoSvuvn&0FBcDrsMfdrY=|H)GkTLt!xTV z4`FvBEXn@`s7J8=pky=D&)E!;kP8xk}`9RWA%FNhx_TSvZjh$*9{GPRPDq5IL z7e4nE>@lu=(Klo0=nV*4{by3eZ{n|~#@6Mawo@o}cIwNod|VEw>_$)2JWKK8w8&73 zQS@NaE*+z68($P4$!K8(N|cte^XlaQJ-HW-CeJ0>5Lh-g3&Qr8!Pt1!b;{rRpH-S7 zL>gTUMmh&t;2u{zc z>@5ysc6{TdXik%wJMa>J^jAd$jpe?Q!zLjuj9CGVp#<*d8Pf%+x8N#UIa2l z|LwC-7VuR>GHM3BpdF6D073WP4gut2^1rZhj}`d^mSfna6g~Jx%~nG^hSshEY%x@4l-T&QC9fE0(Tw zy!SctIV}Zyaevy)9yy44uJ!uV@x%XXx2M@Y~S_p@0a}A(pd<1 z1pGibWDiUkc`NA9;<2lX>D5RmwZXo?ow$mpMWPX~pM%Sz>`i|9YWQ{hx~c!BxCT(#{tZ4M>UzAwZ`DJu z(=}`OGiqvgmVF9klrdh#0GU-0S@`H|A}y(%cPDi85>@Y?_7*CuwD3sr)QOh$!MN2* zp?9Npzew2-nLgSG zxGmU{b9JG+@WE>lr%?9Oh>PX8o&18nLkO-cV=j;eeod*g`8>-O09N{m9%~_zPVkwS;=atku46c;%96ii5Vbc&1oW#miu+EM7wTQ`(O|vYVdmEX(5O;gkk8I;Um<%i&md zars z=rf|cWfS=RMd;t+Pz4eaeC>?}{ZO%0(@&vnWC{Q95WCLZz1SP9eKd<2wz`N2@!1-) zc6-bZRb>-KGcjwPgzVr{Ba;zzpoaYihAZ#yXPysZIL|&$Hdj@>V{0>HnNf-L@Vz2b zc?zx?x41OM*K3(X3YSG;CL}9b)%aDZ2+tjh=Pv2UHGTa1KM+c6UcsJ^Ay+KOOU6oU zE9GS{DSkZ&erNCO*>BC~`5H{m(MsJSaoT_OwvFw=w@jQP^~30dn~&}ku$1)nTq<#V zP6iBkQRtO$R*H_a97@E&P1j#d>B=i(CDlxeEF+YGVERXONz9yt&z7z}b!_!%uCHp^ zkmrNUKs-i?hq7xoDeTj|gIC78aA`&7$I?W(*un`UUlJc@YS1*Sx>YGTtYVw7fbC=3 zf$&1f5gNSnYs&!{5aFw*?Y1JoFA46*;up8(_fgSpY%NCR!6mOc9MDK(aF~wcW zIl|mW`h@8}x0_Bgg#Jvu+r~ou6QNuX9{^70pRb*B&6NMYbcv}IRK;Tq0$V?Oj5wU< zI2k&`agtZbjoT{1xvnzT?>K*cxM;VE8o=Tw2L0BY!S(Hp3^1~u*{+T5J&X($M`|(k ze!ki%fC_q3P$m_*_}-!*-Jo=>D2ye*V7dOmw{c653vG<90Zu$#$_wPe@_(1taQN0u z%b-P-0jJGQN-sDiK8zZY5hTsAEVmW|zeLb}(|}O!y}Ir@oTbP|8%6#K4&4#V4MZvB z5n~?`V>qJHpOd6ZPCWfjASXxR5B#3W-E0copfAu7X%=LRynQ7#S!vs`SlBbBufUG9 z(JZ}X03ldHriF(rVafXTXvJGxHl(mr%iRzlz&5v6fLKVShnfONv!ah$<`za?nKZnA z$d;#5ZnNhb0jEmGeh_w#JRrk1yj?x)U9@2_6TdopxI1l;2SC%dhW8=+Juxzx>)Pd# zh6>I$j8#7I>o1l~Uw2?H-LUq-zp)JHKA#X2Z}1mgB3mKYFM*aMj(t?-#ZT|E>H_d^ z9oS&8^s&-;MM!4}Tr1@JU2)4CJ(p?kr{Rl8ulNn7Wl>D=@naDL`Q$q< ze_8($)h7K_vb|7~#J24)Qi;bQDYFBOz;48`a`3R(3B=wbQ8*dg!7&O?R2S&p zKN;9OOehdqR(j{{wC^|E6D+v(`#I9-1VW#@KfD=~15ed$QFI;cNX8AHqM)KH#; zaAoz})Evmx-zWJ6u2cseK_5YtJ%2xxD<|i5k zllI}t=jek;|8!Sp%19?+u58q}|3jerEj%YM12(dcv}hQa?r`WRE{Y=`mL2dTMlQ{Nd*l%T7QQDkk_qY-Q`&NUJX@WpXas90dGd zaNye3!0C&e<7pn6}a%SfD*H~kr$8~fP#U2SBuduwyo zpNp9$Lr0%!JMd48gf@Y3U5q%&A9)>IB{_ZUl^pC`B|3DPyl?-AbxB%(q*IGizP+o(Y)=@fplr$X!J(87yN0S>2juMHAi93njQEL+=PAEUpJQ?3$kXvCU?F~E* ziuIRUF(jP|k|+GTyq7c3{}XN^)ipJWx4T5MqE58J*c~TMnIm1;(jLU4W&Zh0peYdz zpJpcyO%}&AyiH8ZCsp@1$awLm{S@Zwl|lAjobUQmAPt1SSYBE(vRe|EsBa6ZF5XTN zSEr?=`N^!yaDU{@DT|pxAP!Gt@k5{>E}<7uxy|48!zFiPW}n=tCU((@ZA6|3E!AE7 z$mH*5D{F7{GaLjJ)4mA18J%3MTOc$|{j9wT8X+JorYLAWLCa|wcQ^Rk@qYWtQ)BI% z6Vk%tz&|&XE>!(d-Fli$-@At?zObZ4=3ncH=In_&clLq3QHztgFb&lR!ZkJ;S$+FOs>9sTY50;;Yrc*w;6O_Lp>Ovo(Cpo(jMjrGlZCTvVT` z8=jadrfNeB%hU!moIQMh{4+)K^jv^vpO9uP zE=5E8g&m8tDnU=Hb^o=(bDb-nVAIY__ZZ>@?LX(=0E} zD?OoXQ5%!guw$^UE^sf}S;GPB%we|9Dx`O%(=ZAzEi)KLo_R#k{XjWeCkq{;v*PGC zT335w9Nsfa70j1eJ@cLH-1yM33nUaMzryxIH4Jwm=8{H#*5=ZD4zzKM@4DhvMo{blYA!+yMj+!Z9MtW;VJt znM+aEuVWdVQvceZVr&P@2Sq#=y{~L2R(o_WFqB@XmtIJ|cB|@_^F>dQ#Cd_x@BM%| zgnX{7)Oy1~0yVAV+m2`eS72@%Yl&Mwr4B(3(zHKboPJ`n3#)A*t7#mu8@%9Qddo(# zE!JfGZ{fbUYaae-P2kt)xSvt5F&EWeW)pa5UAj`JZ~LTQ1u@O$0nCSI&~3@4ZlkQ) z>gMK7H{gtuYA5FHpfca>iS#&rX9b)9%88r~2l{s0z3}&Nc3nbz8BaFwJbx&|{y^3N zIYC*PQ)^Xq@k!nr8I5U^=2>l(B9Bywrc7Aft$IKl&Al-T4d$&#Tm8v=K&!6%aJQE; zzLHzTw?mJdLB<;~znAePcjqiCmK$z*vxWidE;RXY#^vXc>_0G{zv^EXkoUr3ZOsW? zDV-}~$117gefY!NZO(Y>%$=?@@e6yxsSqoxW~aBOwFhiX5G4$fJbNzf?H4?X31AbL zc@%FjX?Wva?vVMYj=kdu&H@$1Cw(EV$pALRi?b;mVNIdZ&Ma!?dbKic4dVUs;y;rE zAGl4q@?2Mbxp%!dC{>n0TzW?oS1;YZrNbF-&*j*?tw0?W@Ye2LL-W65Do7wj~JP6d%nfT`809`Ot3MbBp)`%%3g zbSTk-xTU|c*f`&1eknigsg)#WL^oiWZae7m;q>d9nQy!P5otMpFUL6U?hP_oxD<~S zzG255NJ{_i8=d8UcXR_ zt9oq5xjefk^hqRr27ZgItXRrd8ekhgOO(0JLD%^8l60P!qPnKCGfqgWR$N=(#bW2Y zid@NWVeG8I-f>=`q3ipP_i>19%lTGc#O1fHq%sO`_BVbG#geys0NADwx|1o%?Gi~$BeHhTC$xAHT2rS_ z_NR;}mQjkiPgi=0UPC?=TKH7)(Rz{*ijJrG4@UC(OjLFmGpJa*In>6p-Lv5iaLrF{ zQrNcEpQPPu`3f~-K-4txyR zG4Ea!WMkpKwueK3D^{alm>0Fp-vg?>2~rl=nd+yv#Fp-ILX!b z@9F~~uTTjES)r;qE6}rFZ-DB9$;xDTads}iOB%f5U3hE5(GXc@4{8$cn}8a1&{Ti# zABWES-5YyHGE8S%zTh>S9p0}?ACkZ+t%4U>F0_82A80tD+H+P)c)e9RIQn|S$Lr%B zyY|4;^ZP_um{S?{iBDgs7;rmDX zQ{t9bo$r?Rr_C-$CnQc4COCVb?bnetP zJ@&L2tfd`tR-5KS54X!XSK{m1EVF0R9;jGaI*G%B)s$(5Vf#))TRHbd`TJ9bZcr4z z+e3Ohm+v3>d)Xb)rAjC8F90SCGJWaK`usbi8McIBJF@a=DP6w~T?t-_`hu{;WML^X zQJ*H6XTJSa`>GWV|FBYH>7X?XCqdCBoe@+?66$yupVAgVq3|Q4XEFM9uqP0;hCR*3 z)ORO|G)D2|6?vBduyL((%)#A|&$ z6!o&fcv;yBBd1U8Gn1>UJgO^|Hv?j+-&w!#GBe10Ud6AoQcpNW(L}_FTQ4JP?n8@H zp?SV~(#es*(4(HGnekeonYDs=MG-tB(i4A9T1WWWJdJ&jfNi3nVe_wSrMlK$#Qg z(a-kS=zqVT{ngZCscO#d2Bus-q@*qQ+i21+7074-E2DOfH)n{@lCLZC+D{`KY@&b3 zmx3RD+rnlFre-RQ`0KKvyEDgs(goi|A{M=OE2H*UjL#G36_Tc4CXt!hIKi2>6UDb8 z%a_FiSlw@qpQ8X6{Owy2EP3;f==DyTA?r%%?L3Xg?|92O-HN zPwK3m!i8&(y@y`-vCpmvk1!*khlb4`GRcoUm14TK6q-73I>pGnUs=un-b@h}+4*RB zo*B?im!9QmELgqtasKo?a!oj0tML$H-v12v@{={-pE820E{zuCRgsXCd~#;YUEuc3 zhqg%+E7Ltt%zI5+Y!B5ciPMKo0ne3dAM}c29 zSqa1L!dLsVq&=Q2RwI3x|M^+MY2YY2H|y_GE)T9Wdcj1KPdd$81N0R{D{VJ8t@L_L z4s~x-BmFf)eNe*XuIE-uPdutE`NYf1wKp5rL^OeGfU41N(W`UrD6JHoBE&WvLb3(9 z3)YN1`-6JPZ-K- zsG45QeEcGuDe%XNE%*~~)4(VyRUovi!p?5(*pq&M!m>_IHS(`isJT>EhDgr&;bgA> z91|+sWL{UH3iT~=(yuE{e;t_>R)cMO0p+p#?sm-zp3fqmI4;v+8(hW`*YeW@CTjWy+1m25`2o8zWr9cc&88qQ7Xmc!n%-a zkq<53U!5p;qpHwV=roOQUd=>$V$QcaRXLLa}{q z7Wa3?8L;Pq(_;T>ekVU06hSwTB$zOGeXo)1Qa(Cl27tyOFLQC;vO9z2mwG9kCG?HP zWT0#i%u&f2&4{mu<51PN;EbIwi%?|{8?Wb`qkbiydN zz2U8=?*xX3%$a$pH#9?vELNh^+1E4O_L>Q%fF-g;W*FG}W8M!DXRcEfH3zzRztM&WHcoDoT1R$MR8;o)Xr8@XaZ6w~!{mA5sg$s>>T=stdeRP~ z!~cvJ$f_zcI(r-P97hHHZ_&}W+QQ!^9%(Y|QG@GEbGL5x0&tEzmGbI@KRS+Gz^i8% zyp|?m#*P9AO&<$dHY$Dhshc87V`FXAHe@zyM;PecV|kaWH4Zu900Tv!sAJx{yo-3l z|ENDsyyLTwV;8zG=}M1T=S75PxH@|UIgBlJ!W5=xL?V8ou$t!cWR-Ikte4&N~MEi{$U9*W<)%=R+!7|6=-Ro zkZ=1I-#m^Z;T(@TO%9U_Q-5FXfk9=$JKPk1AECIJ;Y-5*0%dLcnW_=OLv<)i-KXSw6!@*Dp3=ZkXIb;g@Rd}zf}w;TW3qglQl zJbtmq{vtdy zwW&Q816lqlh&%_WFVfjK?Q2nmyd5sclG3n9%dNe$d!d+m}CXLjsA) z?|VQ}iC96RAN^A|tvFrN&pD!dl{EbmOUcZO{_W`6jTgE5OYLD^?D!#$;@d#Z9ns|) zKVb6d(ORU{lTB!Yno0Xkwp-6v4@K5cP8%Slj7bz ztDDw1B3jo(oBkxemsFUW0#D08uCqTrL9T#1IHQG(?7(=14JgW z*q9va#Xy){|1r^P;=s}Vr9~#xbvc8zzF;ZKsOGXaH!ZABF*!D{?hUyGP4>u0%c$7b zo80{l2yStffm_ zu-0>)IcM)*?7dGQt{9%LZe%fhuJ*HlhCicu>nEPRsL%ojE>1pawMKtNol=>&OM)dK z{E%>Sy#U6s5cLHf^_|9$B^@#hnDmp$D(zw{X=t`9(FrYggqr_yyNq|^)l&c57}tOLYTFc^ zO$AF&PwZo!!jqMtZD#ZZW<+p)Cpa4-(0#Q*FP$AD295Cm-y=ZV!VJvbSCR)LVSwxe zXsu?Ezrcf@DGwA|v?4K1fk{YOqIE|L<52;7e?}D!Q$X`^JrOjsTDkJNWO%aqEg%g~ zQv^v3fMYui+y}iys?0_7VOcMNTj04EK6x=o0~YFWnoO>HshhV*|H+irs8hWMQtzt% z0zZPmb@!7D9vzT%S8i0_HMi5g9&zYT36lTictK;h0+Wn^-rsn=?{Np`NwR#p?}~`u zcT765cGHfNG5rBa4N9|h(6G{0{UIlts-n1nbn`m!a@-8;Dog!S1%M^ph=Pqoql&o) z36-HO^GEKl*xN`{0&8E8C1|%)Ya`A2RvN_1VMPamQJhIQ`&`d&oTB-#DTYy zCLCe;miA8Vsso9VK+QJQs3$67jK#$1*GO@J+R&EfxlT8@EAGsX2jbYR(LstmlIhId&4?gMyU!!yzm8VZ%;qR(^HcXl8r z(YsYo(sP_mV_Gx6R}?e-N@wU2e@JqZwfb8mdy7biJIsJbp+!F;7l1^Fjs(tId-SbQ zVUGwegr+dQ#0qM4+lAm0oU=GLm!Qb=PndL%8Fm!xZveK&;>o7r%lo8YD-#H*AC+wmCY1Dd=e=;n|5v=H?B4-(E_U){S(%# zwsmio4;YfA?7yB8JSqkl^na(?I@q@r6ZOnhtGC=~_<9>k&2wb!j7-sfg;Rp)0zg=h z&>p18Q??LVB$h0yHi>N>@0Gfp9jI~ar8{51$#$-3!M*DfdBuNwh>;}W4H#i9T&6Q$ zaE;OhLf8Al5wql^-2si#L8i5`hl23~yB{Rm^Io%wKUwB8nuVs1X|nM3SKT05H`g)) z>kVX!ytF5dXAjWky~OV#drwhZ(y4v92vhCf2sF~zv>W~>y+VxnKd#K@PvRg}9ev)L zYy_vG9Fa!l14qO>v!?u?Q}mwCumXhTLth4HoJO5C|AX!}VWvkJtpz`%2zc$jNk^!# zgV2x|56`0btNxN1nxSrdqr>YAm$xcj8=CdKMPPTH^kq7mLVDhSSlAv>ABbIsXW)Aq zN2qku%MgROYu01sb}8G%ln+RA&WewgsVN_rC&Ya>33|vx`JB{z+0oPv-qq3Ax);(|Qq6MajIz`EOHZ~rk zV3Fwne$(JK1DTLU6UV)Sbd>=NDu6NTR=V%h@qMvuhHPH)07ea#GRLoP-=G;7BCkJn zlJJeN4%N;hLqAi&xs@c{FyycKbxGj{2k$;AslS4nXq`8&^Dc7XK}?(yJFp}z=A!%E zJNTFFl_}zCYXja0>)X+P0bs+utga+^-w%;(!csvVoobdjTROdK@R@Qis21TXRtCiG z5JA`67EE=<#q4QcxpuKE?LF``sQzP8n`KrF?*%b{b=F_l0poGfd64AL8QjxCTz%S& z?`&zhO%6%jmp#hjlNbY10NGp3BU$FL8B_>h4~>oc8i+d^w~{b${SCq8{RldD%@23| z#4}(ZOVj+=*~PT=^@I@`I^fw2^At1`9b|pg1G6(QD@KFPlkU<>CbXT`7(nfCq_(b$ z(t`jg&HI)eMkzboP?1wxn8Zm6*MthJIeDK#bM?U8>cQ}8s>+XwQMN$oRM4lrJwGS- z4&HLic%fTH74lbiPxo`~x$s&iCob}@?>HzCE4+78H-E|N7N(L4tVxD3fugR@A&{^h zV#6OWrxMq_$*_^aKsEy|HM2fzDuAC;MHTAa0tMno5<1~bmep2OzUt%Kb5;Egtjxy! zx}wUAREA6c9=}PJ!u8d$T_z4ufaT!=5l*t2VVW!rfnWMr$E+`z_@OawH*W-P7+Hac zLf~BLhMs6xwO-*@-0!5nZI!s2wi;$oho0>0l0Udd;`wYd=WWP=jP@@E>mgN>>G;3% zXU@8w|BrDXD}=)F^n}!sQ8XOaCD)M+)+#OY8~vNQ)MNCt+(yRY(?(INslb*!eDW~L z`}s95ntL=qam;WgDK&7mN+jRJt#I5f1r zbxri+#p674M<7C%zE@@*r0o{aEpvTt-6<6mkF`SrABxGDmat@VRdenY@q$qmXr1F~ z8;zZ1*s4$HftHy<^YBy;5^L51p)9vqtRmpaA}#D!lST3Q0>*c6@#r;<1l9B_yz9(O z@eOerNr_Tq-)@ov(L+1p3V6ARHmQi~>p{e`FM`E6=K*kS-Je4W2M*i5hYNw-wW~Xa zD8OAvc6?||-pxyC2l}9ON5O%cZu{rXVflZugM$|IW7yLXItLnbz)_0FyQ#g^7lxMe zmGUk4=_~{2W1ny!G>aG^*CD#yq!u@KlOd>2=;KHov|pl}$aP>-h))J5&e_d>aQCG~2V#yL$9mpM-HFy{yD(<{Nk7z7YpZ+! z&H7i~T$lViZ}zLsN@96LLiLlSivqAZUj%1!7~O>+QUEGmp0B+P^fEc={WnMDKwv#L zR{^V5qH)a<99zh9ip;P1&#Egis=p0uOGB^{k@S)=cVL!*Y@JpL4?Q|X@gK2Z(G4({}pS!1?bJcWf8yLmDj>>?@Btwrcn?B2Y=s`#+xbN!Lz{1wU7Q-c01(s?IrAf`r=(&?nCY34Us-+tk{;kzAmK0j3gOkA_R6qmhc@uh{( zPhD)rVQ2`-TTH}w<}-QfrqVmW{J*sn1=0z-5k_B7Jm(bNTcW{SR2NFXw>RV+>ILGM5Gu{Ei`4e`5$5R?J{=SqR(&5C5E!$y-pr`#Pd>{s@X zqx~45gcvd}*p@wBbc*-}$UMt1RkQaU8huYpgA?}Ea3~ktmbPWz(Y10^5We5Px$6rE zkHmh&v;XAM(tD+UQBjE@l67BQIP^WJ_nL7iT|~*GbA)qa%{dTwzGeX=&yAsz59wr) z1reoHY&q_Iw%<8bgHG}-&#@0v3=hu0z$7_B?mop)!;z*B0cg%^dfTA_uKlXCz1z4H zMC;Fqrto=IGwE=2rkY>*>q2mCg0X}Fk$Hx)qX$JAstDxi^TG{f*KMEP8 zUW}Wm$beO@TNUxzwI~n*UJXq#ru&6fLRb$a4|iR6a~>6VbSQC0V9+pM@idSZKUQ9h zhpChV0T8957=}oc7ws@1n7~YD=}xk(wTfTfwn&UGW2q7okibW>XqwCwh5ewKyTjgE zjvG8^aw$GN#<6j{OV)uj;M;Z8mkwB^pjI_cVMNXVPvlG@T^Axu`;X{*qR0EtSo}W{ zY9r7lw`e(iON)9k13s7U_AK1oWnUskl{mtS+wI}5SB;yuv}wKWeYoqX8^^LH`+#`& z&E&KROTYX^J02TgUv>SL_)E`$GD29RbRQZYL7u-z5$ePEs#><%v}`YITepAgy;?sP zkDm@21|qXV1Sg$F%1{o0)BYruU@$7Qb0Sv(@f}f$2H?&M54TYPP8%WVKb~dekI18s z@AvJ)noKPHJ0AtL=NSTXi|^KKz0z!q^!yM`r(LUjrBlH5!92~5&@8`e1@%qwa zQIS=3Yisq5sFlW(DxBaleFj(&165avwsa4eG4*)$)xMhjQj+T7f4p(P<2VKGg6db^7IwD&YWB8 z9cI3;FJh78xv}vz=HeSXI5!#ymk%3z-S8Kd8z-nKWpXCW_Y&p?htCLT^PO9iflV4`g%$92uic_v0S z`M|WksMOa-lZ+4XdB596&{cuBj$!W(QB=NJcPcWoakO^t7l4-xc^6jC!Hduc5>G#) zPMNqWy;C{4Vmu!|sS442lSQ#Wza^VrvoeiRSfOoSP&`;Ti0+=eMFWY-{xgYOZAKwzkLZU-iA)(v~;EKunMKq*qKHP!E$+=Vd z%BCl_{DxI+JG*;llMna@drP|}`261!UE#>5e2))`XPTIZp?CPg#C9&bh&c*2%#01v z#i}rrsvx`kK^&7vT^XGyH=io=<`J{v!dSKnE#I#9;W{@|(-Iw#{x6ZanlJOuMGUxr z=F#DtuMvj>Ec}l&L_XR4PjOm`$i4gDxu2Ms`>)(T{99?iaY`_AlagrN2d_#CvSC~E zRJz^;#eUyXsylKgmI|kUoA*gGe3ZKWKA(Svgh{wIsr)sjUCII69_5S;pnALrdZf*$ ze%*W{6-Of3pym6^{do3JQW@q7(Y&uX>`GNs_<^7u$a&*kBq)nztSE^+z(Zcm;JI$g zV@oAto*O<1=Gtv~acss0>~670_8GBIS2Y8K9=fgifYlv;SJ5H{@?B->m8w04*h=(! z@S@zJSp>&-h%7+#6TCJ>=N&)%j(opQgyhyYT!)BKV!+Edh@G~V7q#vjO{a@1KGAN^ zgFaQMU9O)@E{}yC2J-L3 zaBC?#5Ymb9U$t4pwkN-&Pz$TG(Ew-smlO`5E0AX>Yw~1*6}TPt_8hgM=>s>eRLJ_~ zM{;xiSEh`7&tt>4Wit=$5Mx^GT4U_D7;$iD<&@+fLx=U!W{5aJJGeX)nMO@tvS0BP z_zQDZ*q@rn#;EfXn>+8K90is)lmaQXZ_qv=33cUdI%BcDqMustwFcggPf&uq7H7dz4 zM9;v7n#p#?%j`}xa8@hatjJvzaTHqUmh>NYwWsw@$L}cv3^ks2Z4sg>V>RBx#(CPJyoat&D}RcgtH95Y$Ul((AR$v2L9hZ62gMvFGh`kES%iW4r&7 z5F(cX)42w1%$O@CAS6FoX4vi_76jsi7}I{$|0Bu2H5jvghlDv-&P~pKcmbp((kP?A z>>QM-I4(;N`LtAwLdeZS)Wmv1U%Hbna57*dQ9!I#!x?z``j2z&xfNEpF01Q^tao(U zf29%kYDFh|SIWC_``Mg5*$pGs(V}qRh-nUS&#M$xJQ1%r3)r)}>a#^{noh7d(}{(D zT+x=-onZkBhtt;bj@LYPvatSxk|;5W7jR-=l3Vd3rT18&o(1sfyGjp=OzFo)T1QD4 z7ElIEjO>)h1F6#8o_aqirK7sG#)y^Nt=Ycpmq2uYJhtw&8Q@YEtPnBc!*sJ<0Lz-C z-~4Y;V%kZ{u6mhop;6`q$>V%BBV^749mV6a|5Enz0FQD3)`BJRzrkkimhs(BV)j!^ z7-Swv>&>O!xuGeese4(OuN|D#@;SbrEQU&E*{z;iE|ffUEtITVLU*#EVXs+Aet_}5 zWsppY&go$gjK-IIx-d$Y4Z?H6XZ_MtC({c64B$+_M&Xw%xd)XFB4z7N>LFI&^{;L| zg;pZooR;0kA?D8G4s6Pots1fL&8@9FBKRNHJc>lBQXk7VsC}uYNet$-B^k7rMYtVmJXF3TfpmO@<&bU$hfcf00$fp;5nTxX46O zY^40&_b|Vzu^$joxSOfHXh|mB#Y^HQ$}C&H0_4L^Na^agX40_goEQ5R{P+!KoD`Q_jG8YlTo}T7c;bY2&zu-1v!YKW8{;JZvvOQ94hPo5`DuTF49*; z*MuW|*RuRGc(KNT%bpi-%ZH!ll`tFDa`t^BJPOpdNHjC@eotI?8}N(b38vKY6he5B zA&v#5lkXyk_>Cz$nJN~^XWWEMf!FZ7&(rF>B!mM1!~~0aFoUt6>aUrvgAJDuI1oyA zU*kema`iW*+PCzvr5udG2)BY}hs5xn>#_SzqXLRW9#^=O4qxIZf;C3MN4+7E)044} zbomOfDb9hiiA6PbM?c0x#tq*7Eoer(ykW2@T==W)ZDaIMQwKFA2hwiQ~S8v~PZ-GYsl8NDNYLl+wiuGthirK8;CW4cl6Wlgr zyCgBTgBMziV{welmpW4n%1}!}>0zgIULGmpk@WU2|5;UFRL~tDMQTV%dkWrtlnZ|t z3D(LB|mLi=clFkWHw zx-(g3MrunQUT|vl3&AGC6E_Akd9Izpk{Hkw-o<`l&$g#o+?{f8h@P#6w35&hn&8pJ zw5x0HO-tko*|QV0@dueFM}Bi@rN*JQNJ<9|!e4zzw;2Mgpib{bineq@naC~Y*_#s` z#;^Nb{^*oi;rph^BQT}?O`6=iJl*8+v5BDj6YvlIm5>|bFvq27@%ACw;m?Q70lhSD z;ZKfU@vf0*r8D1Cw+sxNs~(|fTL}DH0h(!Ht8MBRP<`JS<;0JUXeTFDPs&?8eIIUh> zqAPk#q|sCFx#5>SRjsH4yppnI+-(2`w9dW1_KsEx&g*m*>RQ^m1Jf-8a|x^oMM}i5 z2YM@Aa(NNW0Y3IQbi3&hh_BUvVR*`nD#=~TDmP!~XWD3}cL{gcy|fs&SG@$hCtLef zwcsUx%94E5YXh2-%pzrSNovl{?NI7T_S?@D4B|(ZAU^zuC?~{<5Uvgo;|q;_l~V+s zzK9^Ni5T$?Q+nJbnX`v;RwhvtLW!<_rypM9d#RQ|f&Dq4c<(xz z@MDSkwi1m2CcKXB6kQ4J!&Z?qpBqJzoC1>$Lc0lPjb_H8G%)q1fi!m?`?O}H9? zw?~Hl@bZe%wCB99=1BuLiIQ&UeP+8wiuev<35q(!DWu9W{J}o8s+BjyscNFha&^eB z{YOXm@CQZ;5!&WRZ1VGKwUX|0QMfN%-9F!+i0_2~*4`68dPwBys}3q!G@NAsvHvWz zW#jb%D^k=Sqer+YGgES}FkkzQnj!;$lHtT%isD{t2GX%SZk9pCb8ixYj*DCx=$wD2 zAF(owRpxrErAzV;1a(_|zcW|2cys;c&(0q&4;=`%DJ^%TjVKhtP~pKX-g#$29HxIN z85rB+gs7%lUAY3L2N_y;D8^<(x&7%8{2a;^N>}w3#dEorpMMKTThHlPO~p}$DK@pK zq9&`Rdeco|8aUVbKJ{_N7Xa1*fuiA!T=3ch?ioFCzL0K?DN$-|E@U- zqB152mdSFiH@;QO(}9pQVPA6gMBwSr%KrDBMhi5U}wtSyTp#u?2+hR85`3AF?=DQ(}r zHFuXpJm6?zcev)oo9p%1{~vvfE6egYX-^U{)0CXGzn=f(JRjqj>|;DTjR25`*?7SX zcs1ViQmd+&h=PCS#Atdw02Xq}42uIOmjL)h36AM%=Q0{#$+%qul)ROOvMKm!N2+*O zs=f$&|LhB*4eS%caV4ewm@#d(sX7?4%*;@W=GRS1f zkMiY5bAQU>9@y!J0^*tE*dVCD#F9GK5j=YqahvzS#97W{5Xz>|cdGA72aUqr8gppZ zryg_VI**^8zGd2$(h7Me`aogcP6rwh-I_hF$#r7KJALbtkxpBqgr=;0MK1>`g<>B-d*BR`22^>R z-~imAYE6r!l$i-!K}=&Y)4%InzxBj$yucjF60y6oXyY>U zvh3?PJH_OaMTWdb8XU3F4f1}nk##yLI7&7P%2H#n7WJhtY&C}0R%yA+(;ZMJXpRH< z77$m`2DbVh=}_DH%EU<^=ercC0o_rB6+9RdxS4&volAI z?DF4ZRlB4awz1)yPhe{kOO1#Qw_D*K?tso5oqDUj>}?0&FtQH95w9Ql-wwP1SZlY_ z5;u5?hq2}B858%f6@gbYdvRBmU3cE%aKG$xfxq_gpEU!NI9!)F^W0Cp88n$OZqKAi z4Hz80xYftsdPhE0F8AA$@WJGn?VBk;=CGfBU3|=bysfuVI0v;%9iMF;aT&Ux04q*53}c$o5*I?gbN=9T6#(hWN_~zb5cf} z7+XiOAfIk$2{A@kLO!vIRiTJ*C|@!sf6}w5ha?cQ!zHIRxgM!wi<;&F4~DvE-vo6e zSm#OeehX@vXWd!b49$SIt{24d|L&Y}U(L*-oBTe%O)B6l@U60<(4lGU3sdKzck9SR zza!5~Vc=RdPK3s#GzJawDq$=}N;-oo};7kitmBJ%C`d zJ#Q^FBNCnW8b4v|%Sd0)5EYvZVtYv%<1#zrc(t zlH?Be9|ne;-xMk`7mtwM`fzs7DKXha_)SMNh;8}NdL0a-_ieU=aZUUuaBr`vea{R0 zHTVYk$wI)+Gznl{b;=TNemaidB(yMZEUCQCaD%iUO++dotMfj^@je zGdyrgpUNkdwd*V|JMJN5+Wn%))Ikc=>E?cX6&!?E8hFj3m3N^{ zb7E=>gm+@EaPIwqRvZupzI%@&T?@_!*TQ9 zyw{$K!9J&I;CYVbIbrnBAbpIRygdnX+rBvFIsd4KrXmOUjKA-an&r6&OAw@lljY}|0J#FNkJj@MR!s^>geS$ zxCXg}&DM%UAmotU~8)WsQq{3 zxjlCg2fpNo&BlJf0K{0YDbMxy|lTg5x7zM9N#iU!6g8lqW{*Y z>dd`y#RZtr02E3A55#c;w!l+-&^o=Ll~nmxy9BB1T4a%63v!?Wc%Y;!z}zU65Ll+V zKfb-*kkcA^bZ9oUb@!W|kVo-sMw-8bcL(G6LP9`D2 z-t+~STCh*Ze3iahKH#n=sOUycj6a~dFDeqrIYUS24Z7dL!3Z;f8~wbQ6#Xs@Xk-zO z8E(+BIvZ;VH1E&4tlzKMNm@sE zB^v@AhOmwa*t~HuebPvUtwsW-47p*}b5uHpSs3X$=;(nac!y=&x?nu5EZ^>v_=36c z8%b#C$1j7gP&p$GPHYxbXizf8Uzm;=ht$gW>!h694o=kd%z#Tds+uJ3&rcEQ^<{bi zYq;~X-0G>9+?QNuuP#F+?>1c1$xZH=E^F?~k`8t}!nOop7gTENB94yyf!B8!9J1k5 zo<<_ajdH5(o5y}S`ga4W7zd?*TMx+VtALNcC>&__`E#nVfAzCX0@L9@Z&Xhx{&m<} zM&3&G(nR-o@d2kUEr{?>>#8cZp(xPC{P)30m$dqKaOnO2e1|JypMQh_F2lI+M|}9~ z&$ + + + + + + +MakeBlock Drive Updated: src/MeDCMotor.h Source File + + + + + + + + + + + + + +

+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeDCMotor.h
+
+
+Go to the documentation of this file.
1
+
42#ifndef MeDCMotor_H
+
43#define MeDCMotor_H
+
44
+
45#include <stdint.h>
+
46#include <stdbool.h>
+
47#include <Arduino.h>
+
48#include "MeConfig.h"
+
49
+
50#ifdef ME_PORT_DEFINED
+
51#include "MePort.h"
+
52#endif
+
53
+
59#ifndef ME_PORT_DEFINED
+
60class MeDCMotor
+
61#else // !ME_PORT_DEFINED
+
+
62class MeDCMotor : public MePort
+
63#endif // !ME_PORT_DEFINED
+
64{
+
65public:
+
66#ifdef ME_PORT_DEFINED
+
73 MeDCMotor(void);
+
74
+
80 MeDCMotor(uint8_t port);
+
81#else // ME_PORT_DEFINED
+
90 MeDCMotor(uint8_t dir_pin,uint8_t pwm_pin);
+
91#endif // ME_PORT_DEFINED
+
108 void setpin(uint8_t dir_pin,uint8_t pwm_pin);
+
109
+
124 void reset(uint8_t port);
+
125
+
142 void reset(uint8_t port, uint8_t slot);
+
143
+
158 void run(int16_t speed);
+
159
+
172 void stop(void);
+
173private:
+
174 volatile uint8_t dc_dir_pin;
+
175 volatile uint8_t dc_pwm_pin;
+
176 int16_t last_speed;
+
177};
+
+
178#endif
+
179
+
Configuration file of library.
+
Header for MePort.cpp module.
+
Driver for Me DC motor device.
Definition MeDCMotor.h:64
+
void reset(uint8_t port)
Definition MeDCMotor.cpp:201
+
void run(int16_t speed)
Definition MeDCMotor.cpp:243
+
MeDCMotor(void)
Definition MeDCMotor.cpp:53
+
void stop(void)
Definition MeDCMotor.cpp:293
+
Port Mapping for RJ25.
Definition MePort.h:128
+
+
+ + + + diff --git a/doc/html/_me_e_e_p_r_o_m_8h.html b/doc/html/_me_e_e_p_r_o_m_8h.html new file mode 100644 index 00000000..c1d3bd7d --- /dev/null +++ b/doc/html/_me_e_e_p_r_o_m_8h.html @@ -0,0 +1,291 @@ + + + + + + + +MakeBlock Drive Updated: src/MeEEPROM.h File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeEEPROM.h File Reference
+
+
+ +

Location map for EEPROM. +More...

+
#include <Arduino.h>
+#include <stdbool.h>
+#include "MeConfig.h"
+#include "MePort.h"
+
+Include dependency graph for MeEEPROM.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Macros

+#define EEPROM_START_POS   0
 
+#define EEPROM_IF_HAVEPID_CHECK1   0xAB
 
+#define EEPROM_IF_HAVEPID_CHECK2   0xCD
 
+#define EEPROM_CHECK_START   0xAB
 
+#define EEPROM_CHECK_MID   0xCD
 
+#define EEPROM_CHECK_END   0xEF
 
+#define ON_BOARD_ENCODER_SLOT0_PARTITION_CHECK   EEPROM_START_POS
 
+#define ON_BOARD_ENCODER_SLOT0_START_ADDR   ON_BOARD_ENCODER_SLOT0_PARTITION_CHECK + 2
 
+#define ON_BOARD_ENCODER_SLOT0_PID_ADDR   ON_BOARD_ENCODER_SLOT0_START_ADDR + 1
 
+#define ON_BOARD_ENCODER_SLOT0_RATIO_ADDR   ON_BOARD_ENCODER_SLOT0_PID_ADDR + 16
 
+#define ON_BOARD_ENCODER_SLOT0_PLUS_ADDR   ON_BOARD_ENCODER_SLOT0_RATIO_ADDR + 4
 
+#define ON_BOARD_ENCODER_SLOT0_END_ADDR   ON_BOARD_ENCODER_SLOT0_PLUS_ADDR + 2
 
+#define ON_BOARD_ENCODER_SLOT1_PARTITION_CHECK   ON_BOARD_ENCODER_SLOT0_END_ADDR + 1
 
+#define ON_BOARD_ENCODER_SLOT1_START_ADDR   ON_BOARD_ENCODER_SLOT1_PARTITION_CHECK + 2
 
+#define ON_BOARD_ENCODER_SLOT1_PID_ADDR   ON_BOARD_ENCODER_SLOT1_START_ADDR + 1
 
+#define ON_BOARD_ENCODER_SLOT1_RATIO_ADDR   ON_BOARD_ENCODER_SLOT1_PID_ADDR + 16
 
+#define ON_BOARD_ENCODER_SLOT1_PLUS_ADDR   ON_BOARD_ENCODER_SLOT1_RATIO_ADDR + 4
 
+#define ON_BOARD_ENCODER_SLOT0_END_ADDR   ON_BOARD_ENCODER_SLOT0_PLUS_ADDR + 2
 
+#define BALANCED_CAR_PARTITION_CHECK   0x50
 
+#define BALANCED_CAR_START_ADDR   BALANCED_CAR_PARTITION_CHECK + 2
 
+#define BALANCED_CAR_NATURAL_BALANCE   BALANCED_CAR_START_ADDR + 1
 
+#define BALANCED_CAR_ANGLE_PID_ADDR   BALANCED_CAR_NATURAL_BALANCE + 4
 
+#define BALANCED_CAR_SPEED_PID_ADDR   BALANCED_CAR_ANGLE_PID_ADDR + 12
 
+#define BALANCED_CAR_DIR_PID_ADDR   BALANCED_CAR_SPEED_PID_ADDR + 12
 
+#define BALANCED_CAR_END_ADDR   BALANCED_CAR_DIR_PID_ADDR + 4
 
+#define AURIGA_MODE_PARTITION_CHECK   0x80
 
+#define AURIGA_MODE_START_ADDR   AURIGA_MODE_PARTITION_CHECK + 2
 
+#define AURIGA_MODE_CONFIGURE   AURIGA_MODE_START_ADDR + 1
 
+#define AURIGA_MODE_END_ADDR   AURIGA_MODE_CONFIGURE + 1
 
+#define MEGAPI_MODE_PARTITION_CHECK   0x90
 
+#define MEGAPI_MODE_START_ADDR   MEGAPI_MODE_PARTITION_CHECK + 2
 
+#define MEGAPI_MODE_CONFIGURE   MEGAPI_MODE_START_ADDR + 1
 
+#define MEGAPI_MODE_END_ADDR   MEGAPI_MODE_CONFIGURE + 1
 
+

Detailed Description

+

Location map for EEPROM.

+
Copyright (C), 2012-2016, MakeBlock
+
Author
MakeBlock
+
Version
V1.0.
+
Date
2016/01/21
+

EEPROM location map.

+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a location map for EEPROM that used by makeblock libraries.
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+ Mark Yan         2015/09/02          1.0.0         build the new
+
+
+
+ + + + diff --git a/doc/html/_me_e_e_p_r_o_m_8h__incl.map b/doc/html/_me_e_e_p_r_o_m_8h__incl.map new file mode 100644 index 00000000..66cbdc18 --- /dev/null +++ b/doc/html/_me_e_e_p_r_o_m_8h__incl.map @@ -0,0 +1,45 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_e_e_p_r_o_m_8h__incl.md5 b/doc/html/_me_e_e_p_r_o_m_8h__incl.md5 new file mode 100644 index 00000000..1c60f2e4 --- /dev/null +++ b/doc/html/_me_e_e_p_r_o_m_8h__incl.md5 @@ -0,0 +1 @@ +b823c8194a66c69671392008f8163769 \ No newline at end of file diff --git a/doc/html/_me_e_e_p_r_o_m_8h__incl.png b/doc/html/_me_e_e_p_r_o_m_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..7ceff3ce0138ae628e585cce98fadeb3589a471e GIT binary patch literal 46968 zcma&NWmJ^k`#ns9bW5YCbm!10sUn@y(me=Bmk3A+2uKZ`(o)h4A`L@#4IqqkNl867 z0-xXa#q;8i%jH^%bKmEj>+EaqeQiQjl;rWSsj!idkno->$fzM9p^YFRA**0v0Dlu7 z2}%O~zBw1El9NPc_^jn{yuSaVt}odpn1U&!iq&wHwUZ*pJn4 z4zjKnrEFIh)q?!G*q z-+k)Gj|yC06-n;?%UUj^0QKg1AI&N~4pyDEswW&So#e|l`VVW&M-V$bwl#f&DHC=Z z)p{)!+Vg&nErJZv0e26LF`U+7scPCUVrpXf^6p4L&vLWh*3;9d>0&Z3Dm;R8dX?pN zFYq3j$d1*_FXxT9Gwf^Ky_?x&l91#4YUeop!hYvgQw@_inc|FI$=J*WKADfll{lq? z5dmdVRloYpN`m8Q?M-I)Cz__VK`NA<6_tooJoK5f`f%JQ|9zs)OnudqVdzN88~a`p zG*Lb5!-*toaWV(-ROcGLiFw1)RF5mx0kc|_yS-}b8P_AqW_7|a6*V<_DO`d@GUfW; zr%iSTqp(oFEHco2#l&F1?=N-tA_lrdH7ow_Y3(t$Hd@c7Z1mJczaL*}^mHra#arL3 znYZ|lc?v?x{@&b>Yc`G4pgPgGdS(sVvFZ?GTaqm8?MIpEt-?~hB9bl+fit$~OXN}Q zjQJ?`_jk5EP#X!_+S*K6ForDqw7Y|4Xv*Pzb$75i2^x8!x99iq&*!^iAtL&Jt%Vht z|K3A>yhKl)@K2{FA*$Gq0s6u$p9NZ4+PauIeKWSZ{djC!cjgHf+L$O?sKe3e^WJ%M zYDb@LvAgXlGK zmESN*DG8WOL>y&H8A}yeQs|={AI*YH8H$nQxUl-YSvUKJDu)lEgFJ7V=UDuMO9DF?3m!^g-k`#-JVen7gBkDhv_Q`GG}b?+?%ul zM@dgdxV*|NS>HM&zDF>wWD+c#AOb-?M?LXqP<8gnG#?17a;T&_htBG!@t;_{in*|Q zup`hgb=+lbnJ0Q5xf3}Gbt34YE6&T!+*4lo7ZLs{cJlx2&+0$?R?7x{9&fJuu-eamN_Kw0fVVVbUj&5Q&l$(nH&+=59=vAW^Tx4mUySSkvHH-be9>%1G1i^fmm z!bQMDOupTBNCNC3_)i=9 z6PLL=jo-K0Z)<$FgMWF#S0Wy!$Z+xM4#muZ!m8-$%$UK<&?NkbPTj3&L50q@I)>u? z@7@+$9*aBdIkj3zY{Sf^{bdqPzQ~@VJHt1jh^Xq8&C-koGGnFSPmNW`VMbq6wuizSnVVi?daB z;dEg~Vd@i$0C%KuTVa6siP==dP5aKvc~owE?BKH zUL+E}z{3_K!1wR;#|ZfoOny0;K7-7be6E30ONyX@qdSvVA>NKHp?KxCY{%HMeoo_` zbX)RKoSw2TM|~KxYuq0S!PPhJVCv@%$=%kNAk!6D_hx9yy@LjfK8W0cD7VBf6+*N= zFhZ(^f`*Xl0L+v9ldX?)e*#Xi{_<55_K+g zPwHbOadvBjOTP=4^t3#FGLx|l=e$XrTdbVuOxAgGNtF;nRIbZ4Z;1jm|Uept8qs!*wiJy zdSyU60}}e{1eedfO+uUaRgU}K-Ouw*$4Bf~c(>#YHj}uf%_q)nW}BA8C8@4}gDJ1x zA`&e0_0+ADWmA>SNbU}0nCX6w_p!d^i(|MyUqJTB0Ng*967fa0{pgRBMdHG559&xh z9ti@7!m$<%a__v*v%(ekS5rusd#oSraxV|4qP{CFTtwNZ&tO$Pn1|JW3ObMRJqUae zO#X#E$=XqlMp+JY_pAzo&<~g!dEiD-^tnJ(CDgb6Apw7+aPcRTs$YAGn9 zoL(YH8mL$uQuF$;#_*JjB09&lfH5P^Tf;_65uz+*u{sVM@ZIJjv8Cr z$6SamC2ExH?j_+?1`ME(;5j%i_e`&`)0VR3XK4-ndfDf`@KbDFR87mKAE;DMDAQ~K z68_J+2^4b7t#dW=l1=uzMMzIx!+w=hp=-%HE0Pj-HW|Vp#Dz2vwI)BSd*KzdeN_V` zb^Ba|3C=VYbR;u672HtQd)~#}VT89jMmqJQ-~cyo-!m%m252o&9c$I;!}r3`N48=L z4!Q@kZlTKTw3?^COTKxtLu*YuUiz`R?kWXBrDQQa3|d-1aY}Y*zP(6>Q%?{y`GaDUf?0F4mxTpIFKpf zU5Wh>&B_PEd~;i$MZQrzHFv<*&AW0)M=hGx9iaYO#R|;e-}WLo$1-9`dpJ+w`KPtL#yK!GT#y-E&FC4>-SBKOA#gz03E!Mprcq zp{}Dlya<)bnsOemdi$9&*M$HdX&QICr=t~l=B-m@l)WQ@WLqDDCem35EZd9Wn^3}r zKwElssTonWLbY?#5R?UzZ&0$o;4KK%9lutBydtCi=Ov}9MChlxx_w&lKliy}n|+4R z6*ga>aJD%9oQ(VaByGWf*-2{_Q%LjZ3YgC7ycHO1U*}2|y1lQK{$Z zx*@hUFEdU`5m5?#nr5uOF(8|^b(J!^jhc{wp<19W2K3Dk)V2z2p| z=5%ou*zDd*qRA5>MMLJB6()4QxBM>9#frTo#o;PU1OY2}@%J*5Zy@rezjuTlds~$4 zi_PYO%I8-fnVN`eMabXA!H{P>;#ty3gEf+zBnaEA!1?v1(R!5^v(js#ch}rU<^Pwr z;RXR`ub#C3d=3>|0>2T3ef>AQu-*K~?&nZWdi;bJyJWgNp4K?&RQ~lsQWt)on!bS` z9#(QIA*b;pw3Ga&gMw-V*S&`&@4ELUbkn@qh|sj2G8Z)BFJ41KL)dHL@$Uw}3{(ww zviCck$dS|AgzsIq8w4{sSF%kBa0dcNl>ajMx0`gG-3P9ZDuR-8mH+S1Qz-ib{7vh@ zO{K%1L+6Gw*&%{=E7D^rJLXy57tZwpOCfXrFOv@gS+o==o;A;R+wrY7R1$Rb-%=+# zUeGn*r2UkJO4@{PUO&ZQRmgK*ZdsA9kOqd7hDnYpP%V2D^>Mjd>8=P+G;%I>A4os_ z9p{>0mF=YE1yzFt&q;4L7XF;hf=wCKfR?Sv%aIFkBGYZzrn@wTepx0vIb+4%C!dlA z9#FcP>>n6okx=&%3D_(#L-{Sq}LsbA^TY~+Z*+`HHv_88W@ z{Nr(x^##sH`GuI`LI=c_Ze`IdNOU~Q_ctb-FFq$7S&W`Oe!Z7dhL%>wQBj!%f z+RHIoE!PIFyR&>*YQt<)uURcKRxLF3olq%`v~NYhWE$Ov0$#NC*k)ox(DWNozIFCT zL*z4MlE}Y|`D@h;w7W{0QVG2Q$l9_(NaJAJuOW5Pe!H!}uJV{$z9PqBFhiky-O;xD z15xu1R2*Aa`dPQN>L5FH2eR;LMY^+Nesey6W^a*NBsyCIoR2A>XeKgw17|Dp=>UiH z3$Zmm|J>K9(flBsz_hq_@vC3Nusz~7OlVPaXg zT_fh9JwQD|P$179&|6kZPd`W%O3u5{2(x6@{Ul)k#aSYVh~k5k`KuU?*+0pJWD*jw zCW5=V##ycQ4*I&Hskzb>VsTwRV|~-xUb@O^k-L%y^pN?+S)Py*V$Pd@Q$)wUHPzJt z6t!{d@Og_QKO?G+0&q>dJ(=x{=wIAzNA%mLJ#GW8dB$-`&WvE@-TJnzfFXElj?E2L z3IR)VG=)ZjEKSjnRzEn18S0tsq&D#>kE&hdy3r3`3MsR2$%0(IaWH_$hZx?GN~NEJg|QNT`YTkITn+ zf$n@OT}OxEsC$`JUSO!T6#gzZz>eQCg5{Oj_=D@iQ+(`f*}kKJlc|Np8_meTD7$WO zR>$S~`bxVtcwXEhbK0LX{{-9cV*YjZ{de(^zR{Qv0)2%EN#kMeyH{VCLJd0Z7*|I0>(?qAN2Nibbt+#(zwCoxzK99fHb|_Q%bbo#~g3C+9FP zei<4J5~%fA@i9BipJ-mY_E(9J-IB(6)6-K@S7j8A+zooF`T0W^G8>Kn_2SCi zcXt;cRR5Z{MlNQp!c3BtrQd z1u^sRF(T*uCji{M>tYo?4iMYH(Bs*|L?Tp_2x_*Jb8&(8FBG#M+CsE$OsB34<{PAK z&+sqpd~BTEDvrO#onvAWDo*ayr_lfWG?a&FrJQ;*L*Xpyiw@?QHX!r@`WPRn%MR}d zE(??>^*YR17Ko!7NWbuG4cK@?Qb6?y@d}^6i_fE368e1XZSjAKg9Emyd1BYvtXpNeBvGSU@PW zm!kha&m=Fey7XSB5r-Neg2NEie6XHa_2sB1cOkR zf47T0ef>lPz$fvWLqclO_=O$k8(B;!d^tZ4>UIRqLh*&2j2ykP+ooSnTh9z`QybZT zFE>4yV8?n-Z{)RAeJq!xE?3&aDA^ggVBFYJGk8hmO1G8*T%+Qarw)u!PN{ORr&qow zao-#-H`J3JaD_aup#Al0HQ0X3tLb#~rK)AWoC(F{$qyVZ@7{%$J15siE&k7iXzH^K z)`2|XMpXBXR1KsBg15ER0O&2u3;f`QSXt1EE`A`vU~(DviY=vm?d2lL=-|7W8A8W^ z+xEo2hd)&26;Vr6zI$Bh)BE>jQsw`yu75r9JXSVBFDNZd+uXL?{J!Ap=wou(90*}Q z6Tdn?Kzq7d)8eOjTXpXM`eAqO{^?OpU*s?@#8@t+)c}7%=#c?mY6$m1v!T~~qX#OH zhtAN10)yph+J0|;9l#u~#-unr45BK1}nwJf)K?z11P}7Dv1bTpxMn zBGe#j+Yy*r4Y7hJY2Rau#d`&1Qq^TJI)e|-MI_U&LW8`C3c^I96yk1y6l>*B!a`pn z-$i+r9f=W{y1%Y-v4MPj0stj(XRQ`JmVE=-uB{8Ml zt&bdBF7qSMRUI^+iW2y~Mo73-{1_g4?*LC5OXy{B&?S8pLgV3H>%FM}b= zsXu1zE#XJw><`HGN4$x*2W6Id?dv?~aN&F5lvh`Y39|{Q64tH~`AYqw_{lmXuzzl$ zhS+YT?7LxV%}SZuyLMgW^o5ZN&q@*dk&WuGSHXd{*jw#AIYuFSK{A!vOn_H6nq+27 z>-jq~#jkm#rvH_sLmlwFo!`G-ROBPP>g65NW@2bp{<9o)9{?=Q_O)<#gjxm?ATdWE zUNoEp(p3NSXeSMCjb`oP1j6xjW1igF$D^rBg>ZEjb;E4C{+$H&EU7CUB}hEp9N1@m z;P)TF^qD^gTL!jXh_8o7b;5lA zBkxuqm1(6j3AjGridK@MB;9AvfcO__k*Uui9>1~#Lj?i0G1P*O*0R+!jIrWyHoUS?MK1HxL@N$>R)3~-E7s7BQ9lRGH zm`l$k^l`q+rOIP;jOR`&P=m?^Zf`59)yR6~AWJWlKTr(L11G>waIjj80@S|OsBlR3 zL(N3{sE}Qqw(sW!6`E)fZIqTBCxcU{6!)Q^2&e7Fg~+D9BzT7*`DbaQ0BOeitm>C} zqFkn8;Rh(?FhMy5 zaC8S-=Y>-@&3PC+`|HAi@qc< z>=qCG5TuHrd0vxNQ^#isIb1oYbb>;&z8+ESQtckoHr3b!MeY2CL!p!O%Se#GSr8h6 zJ0dnfy05FZKgc~y@bhI=+X%AQN{6HqT~v_R-ui}ElUbfQ#(Dp9t*;yvW@2ju)ZWM^ zGNT?jS6fyoh%e@P%7`5Mi|Mq|$|kQr?^4!`<9%-{^l!ocO+>7*FhPwUokB$8JyQA4 zvqlXgMG)Xh*Qa9>MmxWkn|$U}|(J?8M8{N;$e5V*wX$JCH^SYVwdK*eOvs z-r{^UWQfwVAl4&nIEpO@QRKT@sMnB-RO$v`Q2PP?2uov(be8bfv z9twI3X0_{vx^<;zPKfb=bU<}yqs|99#f3C>qRdA+b9OA6C^+~^n24{1&0j(W&o+zt$5=rr}Mfh zIXw+V33*>_PnsMPRXP389{FlUIE*Yj@3k#(lPiQ-(kY;iA>Gi&#=P7Q#n$_nP~)v1 zY0c@@AlDY1Axn8QMNy>;c=Zd@f#%_X4t+R~S@+=yWVaM&0%SLO{xHcWz#eFv=32U1 zP6dbMOi+2(uRpy~bxUI9-MkTkF+|yo^PLgB2+}~541Xm?;YJg1S({KdxDp1Q_P93R zof&nzat0I4xG61Lw)4}Sb;v-H1d$EzS9i7v*gx@>nI!;*6Rmpz@H(1-JL5#lsNX2^ zMIf8e&?#qoYDYjGwzL^g9Iv9yX4_9pwesq(@NnW7Etx{gvVi79cyk_I8mb%3kbA@?IAv9YRA75|o&LbXtf)(ofIO?r;kK8*Z`wzh!S?ydl} z@iTVbu6&laSckhUEkf|Hix}tR`R`eAp%o@B<|;2>KZX}>_ajuij4{!W-Wz_ zAcAY-uLT~|8X(vXVW*L4>6VRty-Vz|i_ClxS9W9iOUOk(aF00vy#D+40uUP5nXDsI zJbX-tuB-hiLJxM9Io?wk6CNEn20+Aq+s)*@JV^_AQzkJd=^c-vB$s2&HBV`c7qZz4=uH(k9)S@ zZTRRSF1$w{jcu}olTBweVQo*c@YrqrZ3sWV;1+g>_Y*+_`Gz!67cH9 ze)UpVHpG~Ia!p8UVKjSgK;%a7=gK1f)#Y;`@|3;3zbrG(5PcE3+2;H0u~b{ zJ8f}=TWyizsrKxtjcwP@f2>oC;X?LC2ABby5>af6(0SG~%Zz?I=c%GxOMa$D<_fb@ zKg>YQ`dyzM6Bh3Ct`4X&EmB74~z$42RDYZge=s3Gc(C7i4a*k4QKLLcx%TJVFom478?^&O4xJ=Lt~(^P`tD@t~2K+2n9mr zzhhFWFL8FL3e@z>%5N|5Qy?#4+Ogss_7vG5>N!*{(2M4a1w`*USTU5>hY!@3M@^)g zV>W2U{{Yd-4igOJI*|V8M8{14!iB^cP#v-n# z`^Ax>{(Ijjn2r!f%Yf9XR!|yC_Dw0x8^`;2z4DFm=Bjh(|M=aMx%Q-% zvHnBQ4Upe-1xR#Pf{wmV(@2x;9IhA~Rm;~4N5k#>?SiO*P#6`bS@=;Fvx^d6JNwkL zN$T2m;TRjun$H&``RTw2E)I@3e3>E5pz38Io2k<)fF z@AYE-nBr|CmjbkNfZ*>%igy@gKa>DSlx(27rn?VEflZr*HSswD4se7@i#aO%2u8(M zN(!}3PGGq7LIpXtL0b#6UtKMSfTRsDtDnlN=zck?Lk{)AT%VPTX}t}0z0>_K9dwfo zsFD`3L~%1~J8EeiS9c0_5-X=3L_Vk0K`-WAEf-kUV{(J`X;6e7cWFVYgPVLRhi$E%So^}PRUundZ`P+rcZnH= z^!^uThIO>wlbO&6V)z62lZY9-;eZhp1G53yROfO{_G8q(h8L9pp8;c+GwG38ZWm9N z2b?AJRUIjyjtGcX@Ffsu%w|wnwYgJF-bY{sy8QO8ES=nr1g#5R&o9J7fi#av*RKL? z49%SLFr?Ms4r|wut=53%g@03$NYJh@{6UCZ;Fb1uw(C#Rie%4*kD{*x0ySY!K=s%c zZrKnt8uh1Sv)p5UOQYc%?t+7V)@Ho`?AtNhK1_6 zCB~r&Bo((2^>>c#{=({#of{&+?yrUCbq8KE!!SU99YaY=H@u0w0hX`>*GiijKgL)_ zx-!sA+TUs5lLRa2{Tq?w|1*f$(LcciB*3pSn?MxDC7y%Md|Xa7)JFU#NU%9H@3MCy zFXe~R`|VVK;!obQhSP*-_t#-Bug5f!9bY$bFZ_+Z6T4TLnt;h}rhQ8#>3}m_D35)X z(Pd1MG_2j?4siPy5GMmjRSiw-d; z;a?C8CYT7Qxd-K+{ncIbAh_l?@F!P}qu#76-?c_z?o#r4n#8>)l?-D|i%9^YoemU; z57J};U05YViLMZsdRIrvhK0p;JPyVF-~)uGTGF3N8eatXxj~EpiRP!NSH4z#wS={V+(P88H3t{h zgIJ9uxvcBXZH>@(ZpLb)KWS?Fz8W?RD<$rsl!K@l z%JRaQE>fTqwAdSA#lk)8K-awd?JsQMJ(SuMkn$tC_uoKwl`53=v!OA}jfYW~{Sn*` z)6`gYlr>hObCIfd5uSN+9EEjL=9EVkTn88LDMtF4+mkRh1FltD^wGP|ZT1z@n-&X? ztX7&V6j2x#A@7~sk4FH#K%f)ke5@iy+6V}(Us3r;`7|I*ib!Yrj?X%nLV#lFO)&%j z9VL(+X{Ym~q%{HH<6pae>}2)i_;ohaaHa`9X4INog)9ntmjmiTp7v|wynJLY zLM*ThX~#(i<6j7=pfZwqTPr4~FT!#7Fp64;WOw1(`z^@Ei`)L1Z%gZ|uWfd9-<2*V z^``XA5})&X!IHIN?75(x`+1^%4Se3mCy22Bp)lTk^X)0y7#FO+7OKAYN6n zjk2ipAb$?@L{CfNUDM9fKeU+#XEspu;=DtBRoJndNAPs6iZ2JCSfiMHFx+ z>}$!MUuCxTeIdsm+2NxMyXm30sPQb4xQVMO{_0r291VTQ%U!#afE-cIcWjHp@5ze}-vKw*Sz$iMtj zVC2-kro?;NdYfE%j~f2#6FwusVTt2jjvrO+a6}TI+EM^K?G0jC$mjd@Mo0oL0)0IY zcfs&lPm9bbr~(NlH;a?t)?BEmNtZcr`kxA%4@2C0dch9eXpLS&E@xiXD(TrjC{p-R zXtO&f;w)U}bvTveQqto&w|E4#>XI6{_HCT{BpR+MTQE&aOYM=Kp^R2eAyDhnhl{KH>XLr3@FGQ4h2E`}CcfAgnlz_{Uyjikul2+UeVqZNTIozJJpkD!THOJo2KBJcBuwPv*5DwAE|++wBBH5 z+>S~9VkAUM0EyE!BisuJj*Hl7J+-LY?rzjhbfS2;Kyb7wD!q0^Qlk~~$C0ux@)aDO zc`jl0>qbHmXX2yZCbBWOoTP!=%eByz7hXV;2sy|{;xq)<53bG$)^*@8m}gt4 zHaD+Jf(&?nt)wHLrdUke%Xcbt?V(@CDP8mC3$6Cmd7ACGQBN>;4}j1g{&&roDJ$P> zggx#F@2)_gJRi54NsKtDYiTM^LpMPr<<;l|6iS<0oT>nF;SQ;BlyM>uj9*9usMaBW zT0LgdwiYy)lEo2Ig7Zz9PJ&6L@h;ThOEIB+ZxBLC2RrW z0aw=6i@0dgd;6Js_J^oh+0(qW~kN)POP0>+1*8CX+T` zHoK_K&ZolQFTz4D!QKy3{0268-HH^{96S7UyM84T>)m(F3DAi76Gg@DWa(h=ZA>oJ z((*clwt}YryTe?nFER*Uk|qoxg3kiGE*I|A9T^E5WB@_S0k zAJbVDw_2oSa6JzH+uE-d$>Pl;_b&&8dL%P!Um$`6g5K%1pbx0+F}90L1NzolmTRXtWW4KAzGy=p*@Gt}am(n+9&M(n-6`-oKIaaHdB5Py=E@L$HbA zg5-y(g6JVb zQOZ>%^iJI49pJU_yCu(_*coIR0EOQA8JHWaK6coQKDFJJmJlUf` zC_M!u;wWt@L-@|sxOE5wI?DoZHAA|IrP{LZpyY4fVm4Y8>D#qzAPWrFWH zmI}%?+efQ0M$YQrMa*MrfTJ;5gKckA)WS`YHCeAwG{#9aQ|Mac`gJ-w;$yXDR<&Ss zpOlRunT+0GJz9*G%uxN)Ao#P-Nr=A}JS0?ap4B9IFm@jbx&5|s03+bYO(>?rgR1A?9c5=rJpNP~Gfaq!q3qMlxtu181 z&>ne$dR{U>cu6f5k^=^M_)Q~tIuhxU4T`)#KeP!g2qjw`wBZKEEH5It!k>`k_mDfP zcT{u1^i8s$_kJG81yonD!Q@!|=$U&18V5_I&hWulyLs4t9l0XEEIoLQaxm_1Ab)Q6 zDO6NjtS`~4^(}}?4n@V(LQ*wiW76u2R&Ip-3i^33ZvaI=(^t52L#&&$cr4rL1bLU% z7!|A+t|Clop`WLh71x5c@*3`B#Ad187aeJcm`*a*Nk=v;+V9mhwB*SX)ykv1esh;h z`y)zDKK^ExgO^gcE4m-3h}PM{&EhA7MOk2@Qdb3xD`v2~DmZbZb)$g|1hq&;-|UE+~!TPHSL&aQy_`g8FLuo<>c0 zL`+e#jQ}r6VLHuHGSM{4EXx21e#^>@VV?S|Nvf%a5I>buuc>F^xzjtEa!f*0L-Wqu z?sexM0-h=abRWM|_Ymho|KW+DD@M;6=eo5(S3IIl$bglgN!DFrxY8>VP#%odOy>-8xYRhc zJezs3?&3`zQO5q|>VVmBSYM^6P2%0j7id(#0Nd!_4;u)w?h!*vYJQC;gsYeg=h!-8 zb`+Ki0{~S$O;)lNxW`A|8 z)}>?tp+((Htv#g;()?7>L-wT_o6RmNvl)kT9Cdf^@Eu?&XOL%l+TpvdO_DY>>Zg8Z zbjoF&__%vt^9ANvMV_&Y(KE_?e7+fr^e1%T@z^h=eNTt#y7n3)dga#TcaT_pH1_v2^44LU9Qy$^Qak!3#}9?hmB}#c{p5UPKK%?O zrqDtEePXcUOc6*ms}!u;#nrOMZ;XxJ=2?z?|D#&o;4fykB5=dS=S;sI8y6Y&kW*%( z`-@pU40SUbiuUhKnrLd@eCU;UH(b@NaRW{kDv5O}AyGZcKYwmkQvSp#iXx+;$?R~# z(uS})=JB@aRwoN7f-0n)j?kARowrmVbv$WxZpq%!Jz~;B!UFY1?*uJt*amBm1hB?l z>3!4~_)K0_5g&Z07DO#`@{&IU3ZU9l5&If>#BY%}RMEyMGIs*{e2p~LGIwG-f99g0 zIa6JBOnfrE-_!zJs@Hbn5`@!hTsYLnu#%F0LlS&Enz*rcfa*iqpX#vk_YmstwN z@mrOa1$i(psIK%xr>F2OqTAN@eH}41SaeLCVWQ!5`kp>Cd$C-H2ZYq!fky>Rfw;D5;1~rakj7D*`7$zcKeZ)n?kT zhEGd|0A+ZrBk1_>7uHYxm6?YvVoT;nig6&#V`UUS=af?mzsnM(7ik|cRJJjWzCCGT zB+D$Q+ z^iL%17oI5PdZC>t_bqN5*Da$^TAngD2TPJ`l zYja}GN7KV?wsKS3kkdh=!aNy2gsib(ccXaj)U=&v`1R}j71ndKu4l-tvRE2q-9B`k zFp%^5pUK2>1>>f&_%$*C;q8wfld^7+|QK4 z!gIBn%41>CtVho9qV>1QSnW_9<44Z|rJC5-v0ugeF+DPxdeJ`~Nkbe6;Ha!H(Fp?_ zwI-tx0#bF3C(!CYcxlR8DyosXkdbcd@bCjK-zr!^xhJYV6b20RRQk8J$-C%On2%`;#yMkz9Z3g907FB;{D## z`N#eGt>tvM>_m&%?96}OhQBw~p?@sFw`EqwOEE%r!$x9>Tg(3v`Eo_)Cr={e-OCCU zj<($wgiScWi~Ir4f?_`==w2bMYwGfE>!xk*M1&8JT5^&QeR|UTr}*AVE^SyPgVxO3 z%3t?J*D@JKA4Fiv#1~2X)|FPCec}I2k)KpX#5I_QQdmw};PCF$Iq$xDYq=rX`RgFj z&JsALv}+BaREClt)3bZD3GN-r2QC^|mZu=0v5-Jqmt0rR9P9&sQw_qQfyPg^vb8OR z3hxbn_3{I~d*10JpcWDm{R&a$rMdXI)tlJH=(=X)J@g-jwXt;nMb~mfekuo5Gkv3zBP)q13X9MeqQ3#<2JYo2GBKV}r78dcq8Am zd6y(Ep33twe`VU{b=gcU;QgqRJzg#zmHM8(iMU(kFk0JRNoXL7spuTLo|CNmOA|>b z*`oCW_Gj+%UmFJ#o)v{J*)i`)p~_V5J_TdzJljHGKH(5Pj-Os;Ml zNaHm6(Rs%rM#i*0ofZEjAX4&5J-*ojq{Kl~H9 zd0VRYpR9|VsIaCO_<{(rhZRY2H%g%btlk9owbAJP--qpUurV*ccNI~mrCT>6U%)3m zJDk&5Nnjg}x6e?Z$=C<^YX`mNE_Or8uew?Z=ShOz@U}mCOW!*avh-6<)_zQk`Jm4~ zJ-y6-;p1qeIG|t9%;P~b-V7oM;rhx;bAq*k&IaR^UP5aMI(M6Lkmn)N*OXZ-V_=s# zJ&+Qs=GaaA^x1?R1z&sRkIFap0}*vbX1oo04N&Zf-A{@iuS1CnAdCa5U;P& ziqZ}t<5X;%;2Ow1nC{q&xZ!GR37)Sd;$yO`;Z+# zB*nI?Y#fi(E2G<77b;NW;bDQrK4dE6foo16(Lh?#MBrWW%gf`9zF$0Wzl`{*p=hdk zTI9XqhL$~O<^m!N$?bAP!KnREP1BIQjeQp4Ly;L{wHmcbQ|eP>Fy3BLDvwcI6XyPe z1}`A~h16wi>bJDgkPYBNb2O|Prx^avUcQlJ zr>DiI`TYS$%wL6rlf>X!-9k&HNOfK|EZODkAG=%*I{eMcdFt#lQ%lXfwx^uCE^P)Le^zK%bbOK8u9i;JHJQ&hGNoVigD~9^M@_$yCS_RpC|LTiwobJewxtb z9qJ1b@&3hp^wyYOesUzphwzAak|g1R?1*eqnr8iYU{Q?C;T_PmkM70oPFf1H8O$)p zjjccB3GowovDf$}G-o-v!=>}zZ3rBO2>*X%ePviwUE4M(NFyL2p#np9Hf)JbX=zoK*%rOs%W`4F{kfInpX+_lvRSkzd%bWNB($F58TGx_ z+S;10t{dB{-=T;V^JSbW=b6t?EX363$okJWh*y4AtPhgGp50~ z-bU>deKt^NnKlP=#nTnG?IRU?m~ocYgx)Kcs%ccLNKnu*u=u6VTTTSNnP4v9v?*`o zFMH;jU^iW1NaEzIzHc@2GhdM}==Kt7W?Ay9-Iwou`>_JN+PxbUiyOFF25QbkQfc0m zRaBIfiA9Q3k*!g;rN4clSzIpLubs5&<8&9|W~%gIV>J8a+_;CDW$Rz|ocd}%)iUl_ zv?qt}{h~Muyr(t3d_M2UX%)!085c0_{ccF|FMsqi%eL*XQ!M*tezQI9vzNn6RV*U# z`n-s>i_|ZZ(G;L~`spotVg7z?4elk98oVRF8y$2y$)}H2dT0F)J9GlmUeME6|4!wx z{J3X%zUY5=)~t$N!kUcrftZ7+S&V4f^FT8W zE_0#bs?htrDXSI=Zf(aE$N%zq$ANN!`KL$=^y<$`#C38I-|BigYoPiFj*AG;)qq729?$I@?W`xtv&d%>Rtmx)|l4f}S zt0#fBH#9zv^x2kH?)Vr3PgNP$zd$O9Cs1E6zikkDh~95uwakGd^~HOvp6i(AFA$*iTYep$0Ju7joj`DuV_Q?nCew4O#K-g0oLK4M z_-mX1{jgL8J-)Jj;nIZTUF>(yPfV*I9JnE~zZd$>a{NES1%;*8Td&H4T(}9is>>lN zVBM3}G6u$9Yhi-ssL7~nR>iVQ$)F&>?RU!jahPQs#P=`AXNY*+<$Snz=M&pX$w7il@@$yY^M--}Ek# zve`d7yYbW*JcU2VXRgA}ge`iHO+JZ&I;g><#_q?NXQ&xqyNAZIf z?wAZQ^#)x>md9tv<$zm{H0%jZ%&jdJuvSc#^~w0wNvcmy!5Z20X-9eDB)nD$aoL17 zeq)XuzIOx#)k9gSLg2gH9?$M-n;H8cI46TR`w_nJj$Qk|s#KztQ<%O#jD0eOXM2rR zAI&&Dz2rz#<$Wxj)M8Z1ive2qwZ@8tW`cL5;l8Ct2bAu<6ciFRq&nI>o&P&h+d_R? zgu&dLfBk&j8ii>`@Z6Hv;`H7A{{5V5`>6A-Dr<61dKRTr(CxX@{?hba7tP_^f{&?b zzL4*59B`Hi2@26>^u`i2CIbItN@$4Qb+jSAm`cp}olx&>H+l=IoAY_ta7(=RKWRSS zuw0zoEGZvsEWX%1IP4hV`@yhwbNS{ry+l~SNd7VQ?U->Qvs%Bv2KkU56#R8^!Uy)Z z))x_8x5d=AUAzzWpL24uHqq}ldtY~Yeh2a$V6us8_+#h4G9j2z@TVf-{9=C}cPp#Y z+`O8Hv@bNftj@Jr#k#e6Vd|uS>2PB1*#DY(k6m%lq3ETo#*#Pp&h}r{p|n_;~F zpzHYAeEsIW?fxFm;qGR6+oq=eSihAG1$M$&U;uZZnpLA4*^kK`H%rz5a*G!=a~UH6 zjAU!iCTJX7V*y=AvX0WUh)Z;o>U#sZG>DT5!Su4dtugYGK4p8B={QKoEp>fod(A%n z-gfrl_y7zj&1jx}k=XGVI}N_Z76LDrw!Y4LVX2)>|BGPyfi`t|&~(D8m^ZA0aT z&Y+W1Ps1-t@yl-|P;%u~Zl>xB`lInOIkHcqB&4v4v&5^?PQ{1$&jZ{2bKm;%8x*U^ zH)Bq%5i9KwzG4;ssQq#03PwAZdhm-^132_WBu*+4{zgHK*@e>?vUu9xY=*4`{dv-_ zCRYZ#+l(`s$9CC|W;a#mDpIS=+KZ84fxOvW=Z&Al{{#;Ew=$V4E=Z7LvH2gIe*w~- zedF9q>fe^5A%UChh?0VMCsiRwn+K700*eN>K2F{+`2C?qR-ENrO!M&g0y5{EOZBGp zvxoi~VLy3Chk#g~r92Dq3R<;I;kUT>z*ZsBrCIlyCjY#Bc5mB^3h!hKX7TrJHzsEY z_nLYh|Lf-SGhg9fboCwqbcgS9g4A>YunDQ*ly0snctw{fCI6MtVedz21&+dH6YB&d zn8Cs1zl#aVt?wxp3O;mh&syxP-}N}V52UGP5>Z2**(4ri%{P_bA39eY+)0vNLFw4q z+pKX^Jpjp#8AsIX1_1D-aHgWckF=b-Dv zC=S2nwX>JpU>*i3=T}3!Qd`X7Zrk|W?bru_lj5hC7AK*2k$1RyN+pcqqKXBnWoMAB zof?;92a5gs1&LamB~uo2)C68h0iln}REe0Sg`Y5X@=O1!IHKwib#2ke)uNsj;b_<9 zk(ESE<+B}Sm+L&(#sbu2Zt7+! zY;m8bf$0p7{)?zdAdIbCoLB03+&auejQ1oK;>U(IT2LVxi%hl(w>OaT3i@czTp7bn z&mha;Wv!>vfhMW3F55tHnB5g0px~q6V1}xFt68js%ac#;RKl)L)_#k3+9fz>*l#ku~bj8}M5F@K;9*&olO`2Cf+n zyB{Wj2V7UkF&CsHfNyfhKG5Ym#^Ki+0=jvkazcM46(UcAdh`)%B99FK-8m?x8zt!` zYI#QrBLC90>%#U|^@}k)am*yt7XRR4#wAq4Lk(ikQD422pM4HYafqhGCCSq{CS_A2 z#rr11Vnb$xGIP)sM<=BE$1nrOr4i?$P@NkBei!^{z{7HFAU5Fir=r>5Yq1&6Kr`E| z>bjbPHJn$_ApmGNm9|f724-2Mdx*aWUJ}$<3~XAuZ>M~7vN7^uM>K6~LgVJNZAh|| z9eROg@h88VaA-(C7m&rYAL%`1I#+8GXIZ11!2c`ioPM8|Z&h&+B$wt$Vk9N6%9H7emPaokX*rzz)wHZ!&NNRF5xy@W(X5srU|u1BNt&i zfUoqPc@Jj@RWHp<{IvYJKsexAnR~w?wq}*vJNP`?`H@ii>5AuV` z$sOsQeBXl=GRTF0t_=|WVd@ux1zU4w>!mt2q`y|>rP`lb< z7$qq+={%h^MgIz+UVQ>=Crx5(2LsYl*5o{^zvBWZHp*pbpp?)y_i}K?JD}`e{I*GJ zQHBsn36NOJIMQRHwM4cBGS~bDQ^}Vo8dOSBHQj{^C5Q}F@MS`6i_3T)`4IX%X*LSA zPLi)s3R^4iGs-uyWWiM$J4-3~mJJif~CBFqm7l-2Wqwbfv1l9$0rx z#bIJ4%_A+Vi|)C3vh@0^2{2?GU(Td3J?@G&w3KL03u z?+4mHdbp^|RKzxqdi`V_DVhrXvY9P;wP0@-<{%=##d)2yUT=YAdp{sCl!rff@^N>~ zWO>{whNZ?}r78{AvpLXQsMKaiJeJ2Mgw5^;&v;L+B%}G7^{hpo#<2LOOD;8&W&E&4 zGzU2!u<3LZ(jLL@I}|;PKoMG*;gF#a+gHxvzzK=UoIQjq?Gdd72(kcr*+XcUsz8}Q_3F-;6!G>%HO8i zQtxmkIH=gdieG3^89&f$b?4y=+YJ~fh#FgQ%ds2MyAGZQC}-;5YW9ysrTk^Ev^Ja{ zOiR8}4x<=K%>+s?g{8RWc#dVAk?`w@fY^r(u)nJ~ z8WPL;c-V7}R83>=(HDRR;m|!6&v&U$LCg|}^cppzI-|wO`N##5hT&Lerlhrd9r7FE z595S35;em%*IJ}AKYo1s?cJlUKGg_!vY@v^VgSB0&STfi^#j`PqA|m>YYAF@6iB_j z02jD;_!;^Gxm8uhOy25jUKi^LrAf9CbkF(cc?0t;?mG;7QfHUY0ULwFQFN5+yg=Va z0b$IRO)0i;nlkpW-ydv&wy9TLkA|`1k+9~{!ODa?nNMxHokHF*nxrHXRLaFQ6ZtG| z4UgFQ^h%hGVp^;*%|W(!NU!>YG7*m|c1(H5zOd)-!Jc%Qh3B=4->o$VkT-XBtyznS zFP2??#7%_!zGLDqa{p=zK%CPF^<*1b%m7Z;CPLudEc+ZDofMk`)f_V>B5PiF(G zkN6Fb-==`dw_`*TvilA*wl5N^iDYZMcV84qR{jYkW=PU@#- z72G2(2Fc!v{Ylm0F#QDAiY9$gsI3me{@nbWb|fwFM@WHS!k_>mEvbOW{|ESL$!bASn5Hu zh)G->htSNqG9S=*U*=72(|5DyELo@H+++Pn7=d+X--u=LWY(tH0X}_Yd0|?2ZeNOx zg4QDG1L*V0`3asDF>Kd0WIptzmMT?#y1OVD&c$Str3NyiRe+F(_=Wj-Q~X6fi=h3? z2bXnd0}U|bAI(or_U)r@Lpvede3kicH$TzoZ4YT+93ywxu)Ow!PI$sg}!_%cC6*WzNjLA_$h=VrL z?cgCS;GV-ZGM@&R;3~!_`^I>bdyWk#V7yx2 z$N0Ws-+L`P^abnflZOq;vnb2(TZ&o(Dv3=u5D0J|SU>jFC*d2uYvVuRHc^lXFHFPh zEKCz~HduwIU9awc)Wy=3Y2HQ3avKy&!A=8rhJU!KcN{1{Tgq-%0lx4V$d3Sl zDH(t*{lb(wiVh;g!tZ7*JZqhKW9;;n_XB_oQe*xXYeUdHziY6Mh!108&05%PxM8tA z+8rOx1X30L!jf@JlDic(;HxM9u)(EXLv1C)nXo2QE2Rx^g}T+cKV!$2#OG<|R-A~= zXr?eT!&Mv_$H{^~Js-YdvoTgkRh$m#m~HaO8hb&9LN?}24$eiRf!0tJsTq#Ee-H+r zlERDbVhTsZS$ZQ{wbUOy1+nDu%snVu$HTtF3w%2XhdAL%0m-xEAzXcL_i%xYUsm@B zK}LMH%<3?SNQ#$SHGe1|bEn(nKB|g5F>4q&k@r_mqHu3z!w{=(vg|2^C&k}w;`2d( zx5p$xFjMYUCoKX0nRHh`o#~uV;+Ecy`Nf#(Cl1(I+lQBES{_ZR1Ub~zK5F|htFNNr z1Y-WX0!Yrm9J2=u5_Xq2`j|0jcg75IC#)T~^UA5MarBDPNNa$OmgweAzRfuzi9;QJ z>vfYx16UccA>B`x&9Qg;tg~eD=_?l7!yYjChG$Tkx+X_ed?N)cD&h zl4&&kW-9BVR(A3ghKz0K6>GE=+0hiR(wNSudRRNBi`3!S3pxykzyZdindRZcG-{Z& zDFhl;k^h@?e&ATdum)Wl7BTWO2k-%f?}YN9nro2 z%-p1fsjqm>89yF<|6|O_VdIhjLD`+2s||pY|Gyer`!TJjTqE5iu1D6cs<6B4!FNp! z>hEXklAb-<`9^ND{CZgVM$*M;%VT!uLAvBw(80zv2`M|hIfDSXr@RUU@9NYS&k_@V zqzXSUnT`kN3V{1;JUE)j?R6rQWm(7+PAnSmXZXWlCB?g4CCk@~c?=308M%#@7KDq2 z`9Yo$-5DWL?tL-^O#clr6?XUIRObgUSv{L2d>8pa>M78lBDe4^_%Bm-d zrK*j6u$xVrEXr^7AH!+@G=V7S8|+Kx@7AS1HLIaS$rJ+u1@%cvalDi(a$$+Hwc_RP zM>dY{oSQ|7F#k_gHs8yZEeVK{>ljTYaPKi%?inJWmK@^(vW`lHbyN!y>AhoeB6L1r z=nz|U;qbyKs=Tz zD9AUG`l1Sp$@Xhm-K(T2v@@J00DbaRv~<0eJQocH0frdyPe=7%W?3vus3JJKx}}QE zQorHm0EnQ~CLEDCZ? zeN^sJZiUR%F#pIuOrU$mwWVE9*9PlM|G{6kIc6kQCuNTLmV)`Qk!y@PWsro4mcZ`+ ztU1Hkg#hChzbtg0QL zc=%xKK0 zB4qN>9axL&7S9WJG68OKS)!%7XONX!p<@9w+JT${vo6OYQHLUCE`8fx*Du6#-#xp9 z!5eLy`u~RFMttaj9GYe(HJ&@@h|TrN7O=Y=-CGVIcH`@wl6*(PBPM9gBb?qq8V+y< z4*Q|Sfik08;&G_go>6UtSzZ?F&qk;pi>G`E9RMVl;gE+Z0a*Dv7zYDMhQko_yc+|P zD4q09>2`g%(22=5&UoOu@8fb&3j7)WZspTB?Ly5QO$*-RKWmFx7HQpKRE*jJri;Lc zK>##%L7&HLx{9NkWUd_-tMFkh3K)&gXw3?H%;)MI!k>bT^neQp5g z0wh1HGI4a(okL*+V)aq)wKv2vk!UD&9}vtyvcrHA&40t}LX8Bc{m@Hq#3s>X8yU|H z^ey7{mE~h1UK%T}6mK&KE&Q7XHpKepK`jU?*Rm-aawAqRJ5}ilYJ2zbBWu?!R&${?wz#-sdhOHnvM5fAJwFdUZg595yY-40Ys z6BUcf^^*?zS!xQx#0XvR0Lo$HQ9(CCFY9ap=*9Km7K~sEt~jy3P9s6YH{nf!ucXJVm*r>#q%*#E_sQ zyC;^6lGHH7yJgrq1HWu0P%ln(9>ju8%^daHQ`OaQl=Y@==g4u#L}~it@jV`>{#(vi zFF%VNK+<@~gB0~d;)F4WmF?vnb#{|Tw_p#k79+oqNd}TX1X2)M%|yQ#dcrK-v1f~p zL9-78?ER1YCHogBwwH7na#0?-2$`|4Uyn$aRk-C~od7TCD-H#;mT7Vey? z5;k#!l@}ja)Xm(v5$vfLall{Y|-T* zZGzN;UuGMxdx4!n0_=?KM09t^=h>rY54LEGQdt)&c@qCS=ip$&@*3@BVNRh^pVZQM95?Vx)bhQ#`*?{6i($80%!TX4gGV zR?{pCOy8_(^y8W^`pSRh3n!S{ArMHf@9qzI&*UA=atm5dp(|pWkrr&zJLz9}1ew6t z$>-rrlQK0!il!)4{u}2`$0pQ$s^q2~2qeoAi2;wYbL~gTQU51%v#l|MZxKN>2#qJjEctMENJW~ii~%0 z4(P;*@|R@_Kpc%8VoT~=hh&!k&e1%I5US!!@jS^W$H(qVB0Y5AmWGVBE7H49$i&x zJH@t}^iA-can@9Mowx&GRwZCzO2mogBu#G%!EAi3bK9HhZ!rIl&|zX^$j(*7w)qB# zyoxS&XU-#HS-WC1G}6BnF0jL&K_o){BX>+!Ef(|V*|u`lYSxOUcNP>$0pSOs^044i zq-K(ND_b$3(BMgbtLa3U1T?IuAp8P=LT8W#ks^mAU`n%unr~ptC$c1Xf`D#^3 zR^FK?FdQJ`r1RO>6nIfvwhOUJo13PpBuKyWm&AUrE?H}`0qiz2a!H=k2W zjZF3Oqe;T8Ojvq_+xYWl9A{;~XY7%UUH1Ti&xcpb|6dP7{Kuy%**f*0L7z zZ0>*1bS$-Hp((n;?f2-B_6FupS0Whtcmdx(adv}q+%!FqRG8q3lQd#TE|lJtGO2k; zEbhk^PC2!~a%+XNr;lVUPa{kkaAB(ZR*RjYH07Y^AsTW%R0uPDgRhN|Oy$7aL_nv= z2m0reltI#f)wTBVh`ZLh*JkhAIttVW#as$;UxBkoRvf@VrN_J{Zwh-3A?0n&B3LO{ z6KS^GWvMT+QG~weR42`9aq1w>+r>EvrnjfS{n`s&UF|;uxLluyM%4It0U=}dX9AS= zfDuBB&?aM*(LpTzt8-A{#CEp;;vR$?T&c|;e}YY+|1EJcGNO{sANi?Mx% z-?s?bxH@WUh9^s0nkKYm?8)_G(OX%SaK;DdAMFNC$`0SJiJb(fI%XJs!Jn?de^!y& z;96>gMZ+sQKpyWKSxsTKMT=i^GjtTLwiT#1v+!7T)`Hvv?6wlO1Pf=SLgLl zUrG3ZSQ+ybkHtSII2l@I=z8dcZ2YY}W?x70C-NWCR!qkdk#6*ov?zY2MM+_v*{QrD zT3MMr#9R4lWqgwn#CEDFg`Vv3E9z&M)Pc zN0DQp&7h#0h)fdMgD=qBZ(@dgoUkAx`A1w>dPN@c)A}r?66Gc=ZJV5JLRA_1paJ`U zBHRja!pq%4u@wgd-H4V+!ZpB#97hS*-Y?p>0PuT>psB7W1T(6fp1g0JXW|@uAza1V zsCd`}sMI0>z!cTuUP;R6t}-34>z2eLY8>xKXOmY6zj>?xxr14%e6u$x1cmr$Rjjt9 zF8$akZ58XPTr(^2t8SJzO)OR-aG7dee9YXph97qdq(e_IofTcZnm;7qQ~yfu&r5hD z(cc+toxG)>jBy^_GQSSI0~EtkDzG&6>>IY4^1a5&FnqPp057&*7!8<_6rd?wSJnrP z2x2RuW=~x96nYcsp~kaToPR4DF*cZRMSr&z`_Q`6Q>Ec|`-@?AcQ4a4hIwE)Aisr8o3`aVvc3MEPdBO86p=yP&VZYlC` zJfcc7MF~4D1h=AQR?zNw-jiuA`aVgWqJC?(TMa$jDL(R@nf;}TVaLGD$M z;o;v_&H~B{JtKp1oqCr<=~%1S$=z2TVZL#FGM@Hg7~b$I2Y8rmblfS9z-fS9XnO)2 zMZi{-Haq^C93&tNO$%xKJNX?eT~wV>u2zmw61b)1cJ0AOF5^wRV*%a*Swy;;&*A!d z&5JyL8tsboC5~-q{W7nYWe4SY(I@ANTB6u&V;sZec;7m#qnA%_lEUr6oS98A3)*27 zLT4&qO0&~2Jx~;;m41c!)F;!98GCx?C+qN&h3&gq!yR6Z_xxR$qbmA>69V4!OY#(K zE+1wL0YR!D64{D_1+rwGL4b(~)CLS}-qrIuh2Sc9C^(XIy-HnfK(Z1k4KzO#I%X0r zWF#HN-xiuJ{XikW*kst{Q;L=)n$wJHzd>gJ)p3yJTZ;aM&rE=vHKcr5(z9O)rwC<+ zFJZjI))(bq*Z7iP%d7kLd?3HOuP>o76NUyFDV@mk?N5Lnz9`x>s`nLU8pterp2HzY zdn`KfY1yTXnWy!}@U;smT$#SLv+i|JQkF{*A0K&{#tIJc(*~)qUw|{XTvTJ0BTQ)- z*-N!2r;&)ESA?(mH_zUb8-N*sTFE1vV3us>q{1(sS`sOXO4J!K^u5n?QOkhw7~wB; z`DSVZWSl4RY2>lPw~tQq@h%Juf_aCbtcHE zR^4dqSx%GqohM=o%pDJsnY2L)4rzIv)vH`br0B#OeWPM?En#A!Pzp|-&@WX7Tv5y> zDd{6QhH-?qp01(jnTfsX6Dy z+i$`LzVUorlO2COed9|j^~R3>gq1JZX3;nJkWiQz1iZ8Ga4xs$Yfuw_n}RvV$~CiM zJk#cFU=8d#Q#mA-zPA}T=JcQC(6N1bPb8<7cCV@P9%t`{26h~C9AY<=^;#0lueLUL ziHO(c=`N}q8}r(&g7ZxeaPHOL?o0-e*h$1hvyBal9{qx=YVjUqm5ahbz#DZoX^CPO*C~tgeKD!@}_idp*^2*`k58i zTo~XCM|U=%oPbNZ`X^MDIFOzi8nJZvVg@>6C%uft++`{$Yj!I3pm1%kbw47Hk|F*h zC(Qgl-pUkhjBPLNzq8XaE5?+UXOHR~qj_OYGLj%gmCl5LA!%+_3~|kV6C9~C?hvuD z!YM3<_cPR-zTpv6(dp^P&&rp1*?x>#v0kLIB{@O+YxXUEO@;LB_kWVxynJd*)8H}@b+u(oztrX^JXUX#VUzx5*M-=H4poQ zPQT)o@y@GPh9_&g-d{5dRZ^xI1&(N+a+(<6#Ar-iE5@R0q^%wV&quc3Om9fvlvnR$ zRA$W9v5!+(SM93PZu@!McDB_W z7N1WXCo-vgbC$n8Qo9hTy|9EuxbnY7cuRXWie|*Ev4k@97V=7g=N_z^w5LM$D>np( z(b{G@psr`I*7ifFQ&~XeSJh-D7P-U^l6t_^dQ1`DGlMWJQBtucQFSY($D)TC8ElL^ zR@T&3{S)L4Q_4*WwQ%iBB~2ywu5Nq6aCha`sXs$NoP7DQ;=s*yj0djR)o#4g zvh2Ml{&f^Q7fcpHdfS181|f&YCU(AcyAgYxRiy&EgFl(;x=9%ETsVyQE<$e_-_S*{ zUwskq&Wzx&y0c(U?9H0%7kW*+07mc}H!$UvstgvI+=x!~CpM=QRZoRTe|AMDrn?&^ zie1xe_)e$^74i|Fo46^xwbGlS%6t;G!_6I^BW{hsDv8=CeWy_<_PC<&8!aVg7c%+uMn#72qZY|f8 z>T4Q+Em7QKJ8D|rGgMaLuM{v;4y~7D>WQVDj;Gu;zc2wYg{jOkR#9U^OOb(qYg&Q+ z)r*TwCPps4L5`3=w;L?EtFjDyW(*IkfE7)@%jEQ+X2pe=z}qw~8AUN?kIlvE`h&p3rzuszna#B? z*=4>T8UQWxQe|1~P4(YTI{rt2qt&yhfypitG-$xffya*uMi^~cfMu>N3r7G_a` z^HR{V_+g@T$+%La%}s*L8drZO3XrR!HHKndHM9mhYA={2>yZ`jw4GZ#{t30bb1LWI zG!$-`{QB=3RD!tj9?9K2J1$9o>%nn0`uj58ud8M>LgSwONCU!Vs;1m5n@je;FBk$Y zShO3Xvg|&d@8qE-FkUN^a3K^VQc-f!{mSD?Gjt?kWXtX&*M6_KJO-HN=svv7EN9H~ zwCUhrP_cDC(}_vHz-{T=ME||4;f3^|l4$H{;HlZn8#A#VZeDvfceNR+E$v-89o09# z#}*!mK7G`tI!1w2uNpjbZf0Y9xFjico$@%F?t_F`oi!b&Aiodo%DP0ZX-?pZFxXT)3WY!1G=j&ThO#!T;d zbrt=0wP1K{{k|uGSe^`aiA0Wi7TFKGDo2ZFxc+q9wD|3|7#>&Nb&wD(tzw|f`=P->$1SpYw-u9zX>EF^+;2VrH#7X2i30`g z%`KAq$x<#(`p@-7TG|fwyot~F+#Y`yM7QH6<{#{}7k4WV*wMLp*n#hrP3W=WoDCL3 z?uwOk1@g}a+0H&Ek7N2iKNfHGJv7i@wqSx(omiN0|Cta_obZ2xDUThqP|yxp_LBb& z;ruc7$NbI6tx-;j8)L5=&(p?^&wcif-ZS5P^}os*y9i=8@m+jo?ZowaFNX^;PQ zx<$z<<`oWF7(8&19C}nQS?^9iJA+>7ZhNiVdI(8 z=vt5Hp;Dnk>-V>D4|2W2?~e>jX+=G4Z(;m=XojCvPcoKdX;qhQn?FcGEiGz>2y{mT zslD25fXn~g`9$#rScKBqdWIFRZ*ISz2b%vZ7>quW*DCtYV=g$VVkqZTBZBPRA^AJ& ztbRYYx_P|wZsj6uRg;A7PrvA|3!X0*_OP^JC_K6{U{9?k-y#+3Gfx8hXg$_&Nxl?fM=@ege^`-)q;+W^*-ja2WaKazSk0kjt zZL@)U1UAoFP7RZkZdz{|11VLfwq9T8m_JVMybIhb8t>-aPNf>&9MrV_EvXwGENh@| z%ByzlNVIdObB4gcSse zCFHuvE{w^F=zVmX-`i`+sQ4G-QgQ;pQXKzCBkOd^&Wf$H=_URn(9LY8z$`p&Vcz2AH$w)E z&SPBt-D1;}*=}k%w;Q@%fKRBGA~}1il#CW$bjvCkrNCYRTWaVmapdRlc_mEGYj1;K zZU!`~FvnA9>BU4k75vIqa2YvY&{fmfYBZnOseUE240BkelV8yJ+o_oAl=i&%?Ta<+?@clke2&QJ=+F;HSebz6 zqNj*~X%P;zM7EZB6D=GSazTSF?@=$ULQO#A!vShHZ_&G`5&N~*I;)42JMfLQjJDtPmU#|~J8zE56a}QdhQXc`V-)@ZOEUFr49Dyw$gAdElKK|hwyYeAOOG^R$AoM67*4~1I!EgIUYrDCe84uN|ZQzCgPOrB1qNF=Tv=DE=J zFbt{H<0M*tSn(`aH+u8GSpXzb3>mPFD5!Mr8awQ_IsZW7;(`f}Qqe!2UAx}-YK%O1`G(3g130|FUIwb{%bgc55g!0lJhPCqm$x)po6c+EM)i0wyliB?NALX!RO)fN41 z;Y}haHwQyBkUqRDF5sz}qH|ni%pwWs@F^Fn+SPHrxK@euSrndh%!W)r-VzUJZ{bsd ztE1GO+%v|1{XJ30Vf}s>I6iO@A|2_aXF*F1JNBM}j}=9FDwXg?)^ki+SUTLxw24^~>vz4b+KN*q4X8QM(^O{WbMMZQ&$$3YV_9 z^hT>ad<4`j{LCDsi;MlSt;O^v5KYXGIytEM%rI16yTd85t&Hj{r@7a?TYe>HK6%(v zU&vu`Kv*ZjH<6CHAB_hRV5z*%T1HdcZ#`2ogV z9K#bwoXWT#s~$*4-Z6B*Pl!=vE-TKt<)O7*Le#IHSya;Joj}q}O`-t4Q%Z;bMu7vE zt%ZfIMg-dhwxd^=$dGcPSV3u9s zVa6oBuc0rmNtTs~ZKj~`bX}*xg2=MaJQLJglcaQ~IRlg6s!LJQ(Y<%C>f>BRg&$iG zzx#@F=CB55gr^aARm2HKCoXj)l88V*+_r`_G4T_~U$M{bAaaOTq{7f0hns1a3Z-9kSXKfE^KYZ(4k5#13KiaB!T*f>u!Zqbh24kI$ zPS}-HIfdu^)5d7O0Y@eOWnM9E1xv*7w+OE{ zR6Y8=g>}41bH?)}VTV|$E2a!tm@#DUye#Cyhv3Gx%KofPQolp<{OIABalJ4V+t)@m z4#%w4L0sG{=EBnnxwFM}S{FLuN!_R~zZmPV1|NwPnKV6=SCaLe!PeE4_nBeXZ5L<=S)+ni%zCh*f2Q^l|)d5}V&8={i*2-?)Z9|c2*+j!at^Aq@O=>(ZxeM7e+L>w3 zf)@{84ZI}CJgFR`(}V=-Khd&}3tR$q#WT&)o;cIbzuS}`Aya-PXL9gpk!WQ&UEA=` zTeYRE>=n}hGVL)GcNoP4f<>mMMC%>%baF7xj!_>l>?}@fj?R zRKD>S3y+&#K}PFshgJm?wJJwS*UCgP*icKLxP)**)mR&%^hY*Y8{#N?6NOY$yaNfA z0KO_?oj9tya;I+5v|>USo_@+7+E~TSI9vHe^`I7j#9)O+<)mFQJx7PlagQuKFMaDz z%_Vqfho~1XCb7<+*R7w7Csi5Ly|PXWG7R%u7F)@={T)wHmgnbVa>dv4`v`Ai_EY@u z=AT&e;+oc81X?+UTGx+1tx~9?q^XtMYN4F^R}z|1zsueEMAD`!?PKHO2Mtk7Q1?(L zl|t@IL}athgm@ESoN+r=ioRMFu1=cC*EAZf9L|$Hgfs+R9kcQsosK$6cr-L?9A6FF zgB)K*+J6;)XZQph|>^N=yEv(_i z5nTCD&UXMjN_F7TPVc&6w2=RNbauz>MbBe~BHu2$+|EF@*cQpq9Nw~Q9YlQh{z?w} zDPMB*voqa6i$>=A&s9+hd>&IH=}n~{vOm8jx^+W}25FjdR4ut8aH^#c)KIrWJ}2B7 z9N<@Jb9wa3TO*^^fKkeM)CT!MT)(lf{y_EO)D8BCP2s+V~I}OI{oLn6Jmfy(g zBF4APM-Hrwg=nN7_rMW2e&qlLoH!oVM%a03?;^GT5 zrh!ABy8b+{XfC~UT76wZkhrop+w0$(6=-l~VeWM|@s@Hd7cC zk;UPn?=R*nD=~9)o!eC?Bkxo?pI-LwLF5KXU!RX;7kZo=3tQpBCPL>2hT^-IU8p_muD zS`d^Av@5gVhQZr7yN0qVz0IVxD?CnjU12(5j9(=^%FvH2Vd9@2!`@3-Tk=*GM}Z`i zs5>D@Yv6iCQ-3j)y&lOXFi`aKpo6$+qF+{oZ4^6h>RzbIv!D{7qe>_B)>8(5X4+P(cSDy9WUF$yor*i`Fqj=T%|Wgz%Z9+ zw;)3-VG!0&!0wUc6o-69R)vp+aO$$;+iqMAT43Ue7X(*fVP2jk>qWaZZrFH8{PH5-a}OUc<5@@aZ$lI(hj-PNJ1-7fmmk9S2!r(FhdV;cIMvi*Nxq_$mJ` zMe&D3qK%v{Of}?YymaA@%I|iU-YFG%w(*zw_nUC)Snz1(z@3~!%x6bJ=K&59jJny> z#5cuC`bTS_!uQ#l>I-0MMas4Gs-7$F4o@hb1hSgTydx3%Y~>z0&9N_T+uIn+lLneB zNO^I~Kn;}$Ka~NOnv8(J$pBTGAPuv1i(#Bdcs^NxSaqpq4aUO|eh;Ipn>tMOn=@lX zJCRStijnnAl`GxdpEcT{irNx_ILNi+6sbC2h-E=^#L6-266fq#$mFz_Oz!-u?qp3OMqTRkr4W;38J&>%6-EDeSAm zqU!p!hfun~Aq7ETXhEgBTVjST>6A_ZK}AABa_9zOhL8|JQc{LSy1Pq|l=wD2&vVZE ze&;>c;Sa6>_BG7jEAINOwRR;*$FYndX;51V+s(b6F|>hIRQn^qCDW!F>Y->NAw*rv z_!`T}N-!Vf3)5yYf|5a5I zPG>R{8MzTd&JFbPgPaELk$hc7|CfitCl!+))GC2H4Ci(ne0FceJ*$-*){o$d#{xFT zu|aKnI1c%!W3A=&-Z2XKEExcI@h+ST=v~W)^0S~->DzwJ4C|R~p_!A#0LC#J4GfsN z^u!+ry9HAPaU5i~vUe{N)`wB23}vcr7w0NHlRnFA;aqUWy-5^^oeq86(bz2tE*lj) zv?x(Hv#W&$u6m2I2qEr|UQXO&QAsCln3TJtOe`*!%Sg2V;DxM8?7g=-1cQ95Qv4Gg zNM05yY0WDknyiP|GX_(- z(ir_e7ee<`t^VqOcL1%U0d0r1P_*#06&R&BwdrviAzzZW3mF=7%L)d!&vyPM*_!?` zyrHXYP#*j0@gv^B4p)`6?}mZxvG|jZT%~IeFUA_w=q~a1om~J_H}mem`ecDMDE_QAflkZp2$n{rw-{|wDZCTo zZyAN@i`c>{V${%W;=1GP*vKPnnO)wrh#5}ne<-cehm{Vo{S>tE1&^~v93b$#m$gi3 zR&qR;agoST-&LPIt<{9uwx5&Y97etwcOyDoiCTHvg}CE??^wm((otXIk#LuiR=Lko zb<_LFe6y`#Nkv*^(n1>e4R@aSb{`e>`K0>QrK@gxN#)&(a;?>SyN{@3b@_;)yS~+| zz>f&qcy@>T2O(j#W!UC3-;8@ZChZSiFjnv<%2F6sV0R!QkMF(2Iz~)9{AqeDtAC#e`QL<^AewVk| z0wrr=e(|`rS98&Sf!Hh$mqU}fko-{c*dzR$&W0PHy$XPdXJ$mQj^j@xD7|pXZbZYK zco#svE2Kf*^0F&`*a0$Cs}8mAqk2*d^pGgmLgFJ935^JVjQ;=1|NN zdf62MUZpi7RZbHwQT9$OJ{JUZrxZ*YnZkto!%=-p?OsSnU4m$ z1syj&?ykAjSlAj%g5=KoJ%y@rf*;zCRappI z4|k=wvMAZSj2T+Qb*jzc`r_>DNFz2_gX)7Ui2Lc)yeEK8IO)U5>I2?93TjlE;cbwk z(;4aiFfLzt{TGpb8h)QsLS4Q$rSNZ>?X;K;J*Ru7qnW6Yz!8*%)T(l#dGDlW-ul{_ zj%;HE-!mo31vuNqN6DF%y2Opg9bgY;b2cji!AF`V^0oYf9a{B@{rGdlv&ZbfZusmH zfQXM50a(DEZw76C86bo-BDK(I?_vf~qU1@YjB-YU@9Elc5N9@3K<9o5`CIf7hcI45 zLcB*4l#b1k$|E7zT>8m5t^W=+^fL9P%Y zrjd2LFGR=f1?-5>u0#o@5`qD1$KG83`a;#RW06e9M-qtodk_H(ce%Qm z>)C9Cly^ATg<4tY5qN^YM>+wv@#b1v*-ThJwc?F8ioG0hh)=9kX= z&*UFdL*8NxiLbbY93iS;B`X zhg|B`Ldzy6E5QO=nbBd~v!zs^|$lASKimnuA@;7)=cieK!w93ZZ)c$oP@0 zf0OaQCCi&#O7~*vEizg~e2rCmLU7+|#G8a4JpKcUzb~U%<6-<;fm@$Q1ts6QJ1DOb z1$M2#{|APf&}}Ig(AjGZ#M#NXyXNgt5jPdKjw?Nk+=kX6YE&~%MQV(eXGiqPT`Zh5 zuKV_VA}3QKMul+%hGNtb%@vXnF67~{6d*$-d@3h^l{r>5Id)pU0}N{lJwSI`i5S-? z@yMK6ef;#LPu^MUTb!MEvEy(G`^mb9y5{q=gzg!7^xbjaK%|?<{^pJRfEG5kUw9Fl}7bAh!2MaWW-yH+A(bxY3=-X6q zV}Qqt-tu^{P+xQjOhO%752G?f3fuN&G?y;$xWyJsF^p+#DPFUraTyeleLYOsVrNG0 zz-5k0cKrovLHnw~4;arTPXXUq*c$)Y+#}<;W1yePH*Q(?O^--@WVabl>J}3*6ek~& zU~e#>NjUmJlGQDiq=-?OxiI+R8}wyruT^(->}?JJXh8J9AU9f+jGz%+<~MelvP9vdysr*T!)uai zY8rtX01)Q40#o|s;G)@hn(@eX4}W6&;1KVed0NMI7fW1`b?i;d1m_PL^h zFS3G8HcVO#B%C}<>2%zQiJK8aw`SUTFUM0;HkS_&oAHEhjKHo0^;>>~yOdta4Q5Q2 zG)EojYADktf38-|4eZ*$a&C=~z-t(PkZxYkJ-sh~gwv~+9MLG8TRL5%k zcwa)aM~AK3d*&Z}K?3;|Itz|(5iZ3ufRYO=GRV_j;+BxB!oD#-%R?rv}2syN*re)zSBY!MF^&;E_umwDcT;eP-<{9U&*ni}@;u3`9;V?kaF zAW577cuZJ6@Fd~Jtch^52uwFMd~>;?2XuRMx(3Wke%gfnbGjJb6w6zdMUvg_3h~Nm z{~70mt=%a1zbJM-n3e1^oilCG{-z$A?(Hk?BK8~z59ky?dfyAiC%3UsiZqO!=~6F* z9_g~15PI%aHd}%C$GiV2*n`np$DXcW?so)-)#@gu!SAfPHe0B{_g;}LjMw>9R4xRH zu@f(tFg$x(Wv{#nfVy%G5FD5YWezOxDTEva%LGNSm&n>BYkkKU{lUEEozCJ3G@&rw z-gv+vEjMhDMlut(hdl6e36%ew&X6A&w($kC3UlwR8~yizWXl- zF<$Ul#&^mg^J`co1zQQ3DpwisGe z5Hoh(S5Z`Thr(PFjbSoI$E1$ofsP$5BrV)?=KI;eYrs$Xo>vN(yVK{dyYEntG(r~; zE*dA4wsjg%-E3M?LX_)fMBfUFN}*MDh^E+svKgjNlN4)_C-v*#C-y^>p%Qo=_#^Zs ze`|HPf3ku(?vc*IJx@JN5g8K|hXp$*$xs%qzv)~3rv;UO`J=_HnHg~Bz#V2^<7DyE zmU5~#TfYlaSV+d$nkk(P(C2QHq3?$DJZRV#@^}m6jR?nG2 zIWw4fe)$WM50zuw6cb`at?ipwTp-ziV+6etOp$_lilJ4CA^ea7^5iucZ@k6pD z1CON5K-wXpXlT+IxU~BY(2^P^KYrdd^Y%AMa^hYZP>@>t-E=}uW=L~!oB#~>|Wh;PFe>-y}2}A++B-s^HobR+V)mu(j3jM zZ^siPD4E6}-*}GxJd~a%VW7#Do^vzm{eg)H5hY z-H)f}y_*TGwN`%cW%AS3twkjs3@XnasYf;Qq_LF(F$N%X@LEtV8cnO-k)11u%z#N~ z3POW1994s%WVGy=JH_bl7@0R3P!u3;4mBhGH)lE4pPC92! zPAPA_eMAugxkd|u=?xz5M1|5lc>tRhI9>A~j=~1b;!diu-q2#DTlKHx0~W+tV@tmO z;zTA+8vuzDuC=;Gg+%-hQo-=jTH-Uq6eLHqwt6! zb7*nohN;n619o_R6eBKUHa2dyawbO180IQo)7>-->8J}T+9m@3J3e>Lvea`}#(4yJ z{x}hYVa3G6tKQfHx&B{}@8A687v%9;D*(;ju6}!E{riV*c4T6ZGJ2*7k{6nwJNCSFiZPBum|4g(!11O%5Sr9 z{OedCrz{qRtDeF&wxS;~jx^WM%UTVxn^bB=rgm52IQeMKs2?M@H->YVi?v#D$?1dk=Scg(@Ctux^i}i% zNuvd+5LjFno!4u7KU}$AX~5!!OxAbwU>btal*xQP1lHFBE=_4kqmWf>-F18P2FBcV z+?j6*>+g95JGB6wzw!Q+l>zP0HNrM7>I;kkqK9PN#qhw;N zzhL$%?~kEjSVAEv_gs^Ozo`6=#Jl(5*^Yu*4WdnA-?Ga7EoMBs3XmISqpLnhzJY#nYCSz(Zmeu%vdWVFgGZ@|HPIPEk zUbcD2t@ldEmrmk)yR6wW6Nxq<$m(20^&P#C;la(p2JESK8{WL0+q8fqtGG;y5eS)0OlvR{XYi+Tc+vnPU4?*U)gfio!ZmzkX#X%CMhzz<=Huf+z#e42zs|`+<@PU$33Y#mB;ar4JJcwZOWim z2xUi4Pl}Rh);ne!Fq2`s>x$&r#K8edo$}<{ykWeWtWE|Z!uWC1rRD>Imk=HiZ4EBPPx3|h6`$-80ZEI?{qW8b9;8b-y8zK@ zD`0cqgcCbEuZI?wxFLb)hx-Y-0^y)TF_NKkE@ha>?ADTLS?s1mY>*2K*=3B&rogmW zo_#c*2IOclBkjz~rS}?X8A=3G%fN(bdpf>R1)$}&X zq@MQMY}>wJh&FtOd^MNWU*G*!WqHoS&iYB=S~JuM%RJaWjgJS~00#mkQt|J#@Q zU8Ub4<=T``y%Gfgia8-9T&{~GA;uS!O!qPF6T#im=i9j0b+#Y6PAbmBz#vFb5U|VH zlvW*g)M7yI$rck}^H@3jSANrRZK7*j+F!WrLoh*OyNAjXrI7KvS2p$xsY1R;hQQ$G ziox@*Vu6gaioDDDE0Y4SfXa{cCPA>3=*2&inG*227ICJwy&qt{6skOxK5 zbo~@ec<)B|2&X`ePA4kgekeKkZR#)aV7^4UYjJZ)3qgqcRYcE@5hNE2`Dr3Jq^z<} zGcd39^I~=bfyQLMspg^%X;pP6)aNnrdV=HDG~n&jx0E%~pH4k(;6N1@f2A^yq%ywu zKZ-(XGdKUOC}by2=&)&EktPc&d#tZXIKTK!_I)r`&;VN2#x^Z8jONNKH(NNo{`xJ`C_SUke{j&9}m0HAf9csELKx2R?s|Z3A znB9N3k=PHb5WmR25m7eAeKj+t{z%`O37~uCqA`Xf>ZdixcA-b2Dkgi4JAXS+&Xhk= zfQk}k&1L1;%9P>M$mGb)XY^IfEHC&VN3B*``xds=AArT)CcN+-s2)Cfky{$gg08RY zo(@F5W?o}UdU6ZgajD}*wn)$i@qZ-0}G)(*|kZIPu*h_;Q`j7cfx z-?0>Bj<{*<6;R;vn0$yPh?xGVZ8Tbh3lKlp$J1#;5bl_Pc_?vwjpNWBoA``Dnuzx_ zz@FBN`w%&i^Zam(W?Zb*-%PV>tt?{lbbFdsJmMF_QEdJ|mHZ8c#(#5S6?5S;R#|;! z?k`*bxsQB8XmQs8sNTWxIJhT&)e?>81fXc!Ba_< zUAvNjw=}=3SEMx?vEfsDjOf9XtuoPVGd}5a-Id%4y3AS2l@-s5yTxyD7m#IOy)CPS zkZWWB$ehtgTbo@spRIw;Xr}0+Fd@;ep9w0Ad)7DypHm;NO#YJR_s2{1RGka$g@zts zS|dq8V-VH&xi+(ga%Wi5i^pZA@ZkohkeG|w7+vtm|#S^Eoo5c!*`K2;c1FB`ldBI z)dzuMBLoNj16@XNJFOO$@QOyK*WOiIS?xkK1dYTbKOr0#S|xMf1)f48?RN zuRlVo!JdD-z_XV!v*G#IhHdw=LLLOEL7xa@S#t?D2C(VCz``~3gRn19+KGF_(WYAL z1Lu^bx201(<}gh$(K1d+{USoLc4qY$mN9f*@O3#q#8lP6=#M(3k$m72PR7iQ8nsBg zsRas$^B-qIf&8V9(cdcj`4>r6luk(9XRAXO_N5}nVLSGjAh(GV6Z;5`gHa$Q7NeNn zdFENQ=5+DlqpV=HF8!N5kzj5VwVAKkGac^p1`h&nL$JcHD#8--=UExhmX6?_HmUPt zmoHYT2q;kGSg3v-Tq*L&%I(3+sb1|#4)P(xV7I$l;8bE(*XIHvMl8+G0xV^2qgKc~ zn&g>6%j$|_s^~XLi~qA`N2#OFSOT10Z{z(m) zWt77?{ybZVCW&Z=g|irQ?*i(B6g2&i@d+BZrvw)*bc=G z>oM(ka4D585;w$D&WC{E-f%?VKcZ5QW~?}q1lS(`@Gf;cZcdR&j9W@8P)u|F6{sFr ztP@1U)4`7ej#akb2O$SnA@1-br6;353FPEt_sIpp6OQ3eEP8E6>Uq-a%}FtVvuRub z8wOBIEKCkSzRnNiv{2pm+lB{1fC`gIhvYW$FnBUeU?cSt(@h_2`g#yrn& zJt`k}?2RDShP&JMtTa{MsVB<`6Gz`sNslkR0V-j~|EOa01VO?M?gT-TN`mKzFN&<; zO^#d;r`syhN>7f`z-m1>jE2)Ksxn#DK+rK{CFP^jh<9uT-q7Lw1P({&i%t~vPV)UcEk!2n= zg$au2;}kY=8kJ^w8JEF)vH?U&LhSw`kJvD7DQ+ocEGc43?24-k+!q_gz*5OAsmDWu z?YH&TOTyrij^$Nwsie7EbV-T^YxP zGJLLsHzA6#x=tF2!BwW>5PImrCvW|W6{z9CmAKQSOOx=qcq*EHO~G^Azo4!r!J>X3 zmYwlJ8*6MF(<)^i$Z`NX9>2=6JMO}=yy|^Ji-fnBPgdjn%f+YP)HdY|ekUu{?+>4! z)cfv*vhANPf8A??oA_pB20A<+0W=w?DD`=J-Yt z<_`)xI7z-@4P1Id;9TG#BKfh(VR5YDcYyiQOP;38h-Fm@U)SJH~x}GG$XO{mT#u(vjzqG zMIx66MB=zqiiXz)6+<67I#D~aE~xO}Z000rvDzuwk)4i6GfgB(au+MTc<_~--w(kf#H@zQkbmjG2^E1AL&T5Wrr%a|~q-12I>|@=n zIO@;R{oQo*(q=Be#@cW3d++tGszUYpY&3?Xfk~|`(fGYz0plma6JG}`MA$ap=GV=c zf3d6|usF)>DYSEHys@}q-6XQ(pgAeY|6*koIodV0wKMg2jb3w1?A7%pNA$92tmTdV zbc()7a`UwCM&#v%hSSM+lb1V8px;laqritV5{KaH^aqg{pHI#^I^_ELJGb(vwjRvJ ztu?1@@n3NkGuc%LSbdy*vAs9zKX38LYsx6BzJF_Li^^fwp{J*3mI_a0kt5$ssor8T z=Al@Lm-TVUsQu>9jd9b2?GtY6N(}PMWx;{IzCOB)tgHbM4xGq!J+=I z{_5n&>GRcL?-FYpk+>Hz1*Os4v+l8h@q@RIfIEYCUh(T#8ezlF@QiC`g&5oB-=h2+ z86J_*Ux#@je`TK(Boci7{GzclC)bu)7FY~M9#6vs1bNYsh$N<-(B zss0ywML(zA>PdVqZhv>iuyHeUn&)>`k9BGE)ZT7xbL`NmQ8y>2t@CQ-)i8B{b-u%#`{bT7 zU_};F(RK$a&wXw@efKgit7p`mr)>IkHrj;fC6!UB&ho{>TpeVAbybQt|0A>wRSXdD zWfpn;>#@7au<6Sm!JP_Tt^=b#*^u#L8?~{~Di?{d{RYV5HZ2>g*||@{>(N8&Wyn{^ zmm-^uC4}9I@)xrs34!&MF9rg3xB57t7nw9LNlyy>w5yf#b7-&e8 z7JWZ{RLN7JN{lTJ{%hBL@={eLm4BE%Ms@R)WBa63NOyfMpwp#X>;veZ_xLnQpDY&e zvS%Z7?y~dim8Qal&%}jJY7#OvUtnMGq77yBduz(>N^ZXqZd@2l>VDY&=YNC32A&FY z+r8R&trHg;8T)Y5%HwATLBLdIz(%m6J9YvY(~m#bK^S#eEmtlIsdl^Vm1m`%&?y;~ zd2}eMDfL~68JF$`daC1f_@@beU={xRdWP{0S0*|gZ;z?!hx*04luwP39Gx2o;fwKI zI^%kePXEWX*V;(razCF2u18^_WTQ#5^IR0LbTKnVaO?P@ece?nVYQyU=LYSJP3DTb z?IviW;qdsh9u0oEh{+nCj3>v6yP#q*$Q7Yz?+2=5?^eQ?0wHI!D1eh2E`T(LEhfr^EfGKlKkHqX#=PR##52l?*L>ZFjPxWLJai6EyxWUfpG(>n5D$ZVK+AzrR%wMk-kwN0W zT>y(deR_ztY2QCqj#|cXwbHaf17VYmCE?F~Mo*w(`hm+0F(bHJD=6iBAjDx}5V!Ch z=hCM=;J~{1Tjfa_J!=%70!co_@@36>Ky=(19N1fp1gp!Ix4_uuP0en=iH0c%r1Taz z3_R=2(7OkCK+Cp#YFY69cF%_94fu`b7m=;XTHTR--l+X2C2dbPg@G1@8Mr!4Tt2sx z+H^JNcderyE~(P&$p9MjLvB{j!@4#6R0(@SS(rXN8OVQ#-E|NM-t zU_-4zqVz%x;{#W;6!5ET!P-8uzb*|6>wogsD+b2DM+qn>?C+Tc1Y%segGp92>4=zg z1ZKW)o5*evJf`W1iSHtKlAC%CB57%9Q!_KYA{>d9k(($2TVq2t4Jh+8T?hW`Vtm@ua6}B}U2~3uER!5JNiclx=}hiuc&zz++SevK3^B6@ xuAsvTs&q9zrR#F#Ud*M_|-#=vDU>q_teI_8d@VmW4Nlsn1Oxo=A{{x^x5(NMN literal 0 HcmV?d00001 diff --git a/doc/html/_me_e_e_p_r_o_m_8h_source.html b/doc/html/_me_e_e_p_r_o_m_8h_source.html new file mode 100644 index 00000000..184d9d92 --- /dev/null +++ b/doc/html/_me_e_e_p_r_o_m_8h_source.html @@ -0,0 +1,166 @@ + + + + + + + +MakeBlock Drive Updated: src/MeEEPROM.h Source File + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeEEPROM.h
+
+
+Go to the documentation of this file.
1
+
32#ifndef ME_EEPROM_H
+
33#define ME_EEPROM_H
+
34#include <Arduino.h>
+
35#include <stdbool.h>
+
36#include "MeConfig.h"
+
37#include "MePort.h"
+
38
+
39#define EEPROM_START_POS 0
+
40
+
41//0x00 - 0x34 (26*2 = 52)
+
42#define EEPROM_IF_HAVEPID_CHECK1 0xAB
+
43#define EEPROM_IF_HAVEPID_CHECK2 0xCD
+
44#define EEPROM_CHECK_START 0xAB
+
45#define EEPROM_CHECK_MID 0xCD
+
46#define EEPROM_CHECK_END 0xEF
+
47
+
48#define ON_BOARD_ENCODER_SLOT0_PARTITION_CHECK EEPROM_START_POS //
+
49#define ON_BOARD_ENCODER_SLOT0_START_ADDR ON_BOARD_ENCODER_SLOT0_PARTITION_CHECK + 2 //Partition checksum
+
50#define ON_BOARD_ENCODER_SLOT0_PID_ADDR ON_BOARD_ENCODER_SLOT0_START_ADDR + 1 //start data
+
51#define ON_BOARD_ENCODER_SLOT0_RATIO_ADDR ON_BOARD_ENCODER_SLOT0_PID_ADDR + 16 //pids data, 4 float
+
52#define ON_BOARD_ENCODER_SLOT0_PLUS_ADDR ON_BOARD_ENCODER_SLOT0_RATIO_ADDR + 4 //ratio0 data
+
53#define ON_BOARD_ENCODER_SLOT0_END_ADDR ON_BOARD_ENCODER_SLOT0_PLUS_ADDR + 2 //plus data
+
54
+
55#define ON_BOARD_ENCODER_SLOT1_PARTITION_CHECK ON_BOARD_ENCODER_SLOT0_END_ADDR + 1 //end data
+
56#define ON_BOARD_ENCODER_SLOT1_START_ADDR ON_BOARD_ENCODER_SLOT1_PARTITION_CHECK + 2 //Partition checksum
+
57#define ON_BOARD_ENCODER_SLOT1_PID_ADDR ON_BOARD_ENCODER_SLOT1_START_ADDR + 1 //start data
+
58#define ON_BOARD_ENCODER_SLOT1_RATIO_ADDR ON_BOARD_ENCODER_SLOT1_PID_ADDR + 16 //pids data, 4 float
+
59#define ON_BOARD_ENCODER_SLOT1_PLUS_ADDR ON_BOARD_ENCODER_SLOT1_RATIO_ADDR + 4 //ratio0 data
+
60#define ON_BOARD_ENCODER_SLOT0_END_ADDR ON_BOARD_ENCODER_SLOT0_PLUS_ADDR + 2 //plus data
+
61
+
62//0x50 - 0x70
+
63#define BALANCED_CAR_PARTITION_CHECK 0x50
+
64#define BALANCED_CAR_START_ADDR BALANCED_CAR_PARTITION_CHECK + 2 //Partition checksum
+
65#define BALANCED_CAR_NATURAL_BALANCE BALANCED_CAR_START_ADDR + 1 //start data
+
66#define BALANCED_CAR_ANGLE_PID_ADDR BALANCED_CAR_NATURAL_BALANCE + 4 //Natural balance angle 4
+
67#define BALANCED_CAR_SPEED_PID_ADDR BALANCED_CAR_ANGLE_PID_ADDR + 12 //PID 4*3
+
68#define BALANCED_CAR_DIR_PID_ADDR BALANCED_CAR_SPEED_PID_ADDR + 12 //PID 4*3
+
69#define BALANCED_CAR_END_ADDR BALANCED_CAR_DIR_PID_ADDR + 4 //only P
+
70
+
71//0x80 - 0x90
+
72#define AURIGA_MODE_PARTITION_CHECK 0x80
+
73#define AURIGA_MODE_START_ADDR AURIGA_MODE_PARTITION_CHECK + 2 //Partition checksum
+
74#define AURIGA_MODE_CONFIGURE AURIGA_MODE_START_ADDR + 1 //start data
+
75#define AURIGA_MODE_END_ADDR AURIGA_MODE_CONFIGURE + 1 //auriga mode
+
76
+
77//0x90 - 0xa0
+
78#define MEGAPI_MODE_PARTITION_CHECK 0x90
+
79#define MEGAPI_MODE_START_ADDR MEGAPI_MODE_PARTITION_CHECK + 2 //Partition checksum
+
80#define MEGAPI_MODE_CONFIGURE MEGAPI_MODE_START_ADDR + 1 //start data
+
81#define MEGAPI_MODE_END_ADDR MEGAPI_MODE_CONFIGURE + 1
+
82
+
83#endif
+
Configuration file of library.
+
Header for MePort.cpp module.
+
+
+ + + + diff --git a/doc/html/_me_encoder_motor_8cpp.html b/doc/html/_me_encoder_motor_8cpp.html new file mode 100644 index 00000000..8d08a66b --- /dev/null +++ b/doc/html/_me_encoder_motor_8cpp.html @@ -0,0 +1,319 @@ + + + + + + + +MakeBlock Drive Updated: src/MeEncoderMotor.cpp File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeEncoderMotor.cpp File Reference
+
+
+ +

Driver for Encoder Motor module. +More...

+
#include "MeEncoderMotor.h"
+#include "MeHostParser.h"
+
+Include dependency graph for MeEncoderMotor.cpp:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Macros

+#define ENCODER_MOTOR_GET_PARAM   0x01
 
+#define ENCODER_MOTOR_SAVE_PARAM   0x02
 
+#define ENCODER_MOTOR_TEST_PARAM   0x03
 
+#define ENCODER_MOTOR_SHOW_PARAM   0x04
 
+#define ENCODER_MOTOR_RUN_STOP   0x05
 
+#define ENCODER_MOTOR_GET_DIFF_POS   0x06
 
+#define ENCODER_MOTOR_RESET   0x07
 
+#define ENCODER_MOTOR_SPEED_TIME   0x08
 
+#define ENCODER_MOTOR_GET_SPEED   0x09
 
+#define ENCODER_MOTOR_GET_POS   0x10
 
+#define ENCODER_MOTOR_MOVE   0x11
 
+#define ENCODER_MOTOR_MOVE_TO   0x12
 
+#define ENCODER_MOTOR_DEBUG_STR   0xCC
 
+#define ENCODER_MOTOR_ACKNOWLEDGE   0xFF
 
+ + + +

+Functions

uint32_t MeHost_Pack (uint8_t *buf, uint32_t bufSize, uint8_t module, uint8_t *data, uint32_t length)
 
+ + + +

+Variables

+MeHostParser encoderParser = MeHostParser()
 
+

Detailed Description

+

Driver for Encoder Motor module.

+
Author
MakeBlock
+
Version
V1.0.1
+
Date
2015/11/09
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for Me EncoderMotor device, The Me EncoderMotor inherited the MeSerial class from SoftwareSerial.
+
Method List:
+
    +
  1. void MeEncoderMotor::begin();
  2. +
  3. boolean MeEncoderMotor::reset();
  4. +
  5. boolean MeEncoderMotor::move(float angle, float speed);
  6. +
  7. boolean MeEncoderMotor::moveTo(float angle, float speed);
  8. +
  9. boolean MeEncoderMotor::runTurns(float turns, float speed);
  10. +
  11. boolean MeEncoderMotor::runSpeed(float speed);
  12. +
  13. boolean MeEncoderMotor::runSpeedAndTime(float speed, float time);
  14. +
  15. float MeEncoderMotor::getCurrentSpeed();
  16. +
  17. float MeEncoderMotor::getCurrentPosition();
  18. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan        2015/11/03     1.0.0            Fix minor errors on format
+forfish         2015/11/09     1.0.1            Add description
+
+

Function Documentation

+ +

◆ MeHost_Pack()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
uint32_t MeHost_Pack (uint8_t * buf,
uint32_t bufSize,
uint8_t module,
uint8_t * data,
uint32_t length 
)
+
+
Function
MeHost_Pack
+
Description
Pack data into a package to send.
+
Parameters
+ + + + + + +
[in]buf- Buffer to save package.
[in]bufSize- Size of buf.
[in]module- The associated module of package.
[in]data- The data to pack.
[in]length- The length(size) of data.
+
+
+
Output
None \Return 0.
+
Others
package size.
+ +
+
+
+
+ + + + diff --git a/doc/html/_me_encoder_motor_8cpp.js b/doc/html/_me_encoder_motor_8cpp.js new file mode 100644 index 00000000..c9c80476 --- /dev/null +++ b/doc/html/_me_encoder_motor_8cpp.js @@ -0,0 +1,4 @@ +var _me_encoder_motor_8cpp = +[ + [ "MeHost_Pack", "_me_encoder_motor_8cpp.html#af46216bf6587148906d641d9fa0a89cb", null ] +]; \ No newline at end of file diff --git a/doc/html/_me_encoder_motor_8cpp__incl.map b/doc/html/_me_encoder_motor_8cpp__incl.map new file mode 100644 index 00000000..decfec22 --- /dev/null +++ b/doc/html/_me_encoder_motor_8cpp__incl.map @@ -0,0 +1,49 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_encoder_motor_8cpp__incl.md5 b/doc/html/_me_encoder_motor_8cpp__incl.md5 new file mode 100644 index 00000000..956335bf --- /dev/null +++ b/doc/html/_me_encoder_motor_8cpp__incl.md5 @@ -0,0 +1 @@ +a19cadbedec53c408728651bcb5d263a \ No newline at end of file diff --git a/doc/html/_me_encoder_motor_8cpp__incl.png b/doc/html/_me_encoder_motor_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..9dc64d2152cf688b0ccc9f9f663daf124fe037a1 GIT binary patch literal 48564 zcmbTd1yodR7%obKq^NXBiG)Zf46T$%N=i43beH6a^Z?Q#CEYDugUHYWNW;+GAkuX= z!hg=X=bm%#T6bIvT*IDkfBXI3c%J8dC*+;t8vp#&T~YQLbcS-ntSrrw1<1LOVic<@oM4^RzosUDGe>P z`|n91ztJ>s6SE#yWL1o(MknTMvC*O`(_6Elok`sPkaVxgPnHn}txH~~NL&u@6V97G zcf@NA%vdRv_?#}`v{|~hT%WW0n0OC*nT|K>KfdNU@Jef7r4V#$#tZ)ce#Nqc3Hse! z)+xhlH`CZmjG+I+S=xNYrX+HxHq0%_MD!^S{of_P4;kCL%YpyLQjiGVEP3-X zlMaZuyGABaIi2zLT?Q5N|IOu$1C1UBGl%`*B6eJh1b+*^27YYu@}`lLl$DYiMwPsI zWtFY;C3Re!9-Lo#ah_3SCNC{+at)9(Ftq1T+}@KBDvM1V6{U20TbU5@4-~4tJ-Lor ze_r@rUHEiRf2i($m!NWpn3z4JqV(j7ByjF;_2~;dcLA={;iL$R7E9=mH2pge%}xxw zq8<#?XpRqbPU*%!UerFJ*yTo(#?z&gX)LG@$CMsxW@g&Mk zM$c=Qg_q;sOEMYU87MYboFkJ`G0^dyt%sE4AE_jUup4{E`px&gSZ{i}1CL){Qh7w; zcqB&;r``J6u5BAv2;mc>?RAne{X2+HbNdiqdZG)(pY>0U*ZNO9@_1^p`bU$~Bgm4= zASkteIXc}g{p@iG))s9^gSXIEEgn%9zlB=78}ajhCbyWVg~#&bmY$i3mh<*Ry()ekN0CD4hRP4GW@<8|W1nI+XHfZeXG59S zObMqQ!aX7&U%k~~q^^mLGMFt;a>kyJ+aYZU<;#xXINwPca?(n;k zOyS3_U{-{Ljn%2~fxM^ChJ5zZ#Qi3TuQrGTzhVfBU;6}ynBI#veJCh3I2QH48_^f<5 z_x|rsNJP}t z!zVKlYC9`Mdv9M08GPR){|nlCvS$S~r}5`x`2OD==%e=i?RQ*R^!9xe-wl58txPzN zH>so^0xo|)T}M(|&Wd0IKENaR-wD&_>udyJBDO(pwgz1x1Vcr<8}f{L3%1wyxg(su znv@Cc6;ajb#7pHb#y(+%3x02zvR_nPiSPsaF!_c8N zB8{KM!s^DMPSfw~fyJD-Z!&#KQT8F|WpWWu?vD}9eT66Trh;5}t1^$BHEj_K)m6wr z;i1ttDaw+8ig(q(T1{^fOo_A}7}spi7u3pcOmn`qrW(eLdD1}D!jz@e@jWb-=+1?B zzDrIjp^z?KJXN=u4Hk@C8cWugWi|J@2f8;-;Er`7)vNjAd-s*lq%%VW{hiUX3_^ae zKu%#K`L!tzU1(X00HgC?p^t~`m<-%Iu`r1fA#o5UUYEFgjK(*5ldF`vM7pV=Q+3L# zQ48zd`1JxE=sF8U@DH>m7Z+!2=WhU8-=(SGzsd+3pOSsmrjviZbi8$gZI7>N4z+<&`qL;Q0%hXq$}Ug>h0TAjh!;#siOEOQtB9 zGTjw_o>1oBKJU-;VY=aje|8T>D$?=2L$KDPmH5aJuyJ?Pt+k?*pGNKPE+mIX$*4~# zWg-|eCDKd=BC*)0<5Bx);KlqJ6G_Bx9T%aZbFUHh=trP ztIZGf!2pTRpd!r#A`AS{{KGt>n+7>Yw~qlU330q^Y4SxKrEuv=`?BohuqDv1r<}7y{tT% zPD57?ZkE$0JZ0>Ap9T7Ck+Gpu*HS4;OtSwyYjC~Bbx5l)6qZ8wQhjR7D#6|Qr@IPy zM}z8=noUcDU~cC-Cf;T@oXWn_2W2mTgki$h^DNAKJdC*GA* z6p-$uZfK3!iw`v+)0og3WPa2YImt{*C6?L+~!LMkvYF^1CfB`cl(nD=jliCEgM)0tQi7$zyXnA#j68A$VH-}1uf$*lK(vu@*cu` zGp^%7#2yX4dzfxya>J#6Ik^&goHw0QTc3qY`*y|x%R|;w0d_By0R-8aAeIPW~_SH2LTg3-aX}7 z5$i7aXN5aRT;%v8@W`ui3u0DKSatBJ~RS7NPJad^_Guxd2YPeu*@N6S;sbj)Q1m zEgVaD;V-Lm)>@_b#P4tog)_M({3mW?TBt?<3)O-v}#%7($<_{ILYQ>H;GN6Hzk_az|I%c6QG~i_pDa zLl#Q<&J^W8!w)2rh~{UctWwX6Z4S}+8C@`}EiDA_Zuw?(v#8iUDE4886I*{c%@~9n zJa>z*E~p-9mt*;(|N0J{GP%7L0tb|79S3P8*Kn1T;Z`fDPjJKuF!;L}hbh58$pmo% zCLMdL|&I+Yfm|&8OK!Mev z03_-U^%IfW`PZHO`UXA7mBb@g`h$?aZ+LI9ZMS?;3NN?5BZyfjep}U{LEbE)vy3`T zE)m@@qRwIA^F5?$&2Y^#HLfVghua%U8t)+M`jo*>b%YdWzOB+;V5c7DWiH9x$0%Iw zPrGi*bL#BmyQOETBgY5x2y8p>YwNY$$XOqol*`Mggdh^dKqj0|bci%DU$q^u8nFw? z4SJ+V>D?OFbDaoy8}mepCL6yv=-Btk#(j^2VO6F5jlxoC8VP9#7rq-;rOEN6RjFuX zBX=W&1+%Pgrj1I%@hC{_0{Cmve~_!)xsyJqtY7q8l174o&-coUL{LTTV5Kii@Y7Q3 zhij){+W%jy?*D-C&02c{58ZcH|0mD;!y4)t`bbXHz%$Uvn^SiFr7f2%x2iyX@EwCS zOr+SE*qrT=e}3hqQf10M{s)+I-=26i+>vh`j%6vddkvE z{X0K!509m`>ZbJ^J2h7j9=nvbMDoW8X>_|EKXZBr=);@Fw9#jVNpQN(SHqloIZIrFJoCW*Qt z+3>8hBTkOYFfG&KceQKsk-7sXP?_Z;)mg_Lc7{v#rDI3Ycw<86OSo(z!L&}P!Qenn z=M7X)adp)D^R6?Emdtod*VnRyUzMSqc-cxRw$!8!sZ;3^dgt_}zbH2T__gj7^A3#H z3CGLLq*L~erLQ{GnZ65Q`rR_`^PK4L5YzFxc}rvlesoBwSTb)KOK?{!&C++1{B*@; z##axxUFm75c6NmlN+r^Hf@3SiTaK0%56$vs{n4K#buS+pf$IKFatmuaGXDcIzy|+! zLc#yRrEZ?*|8#i{!v@ODk~|-u>DGP;z$25UG1==i94emc^CeyPL3P(m_6&hC{Bw74 zkBJr4y@j;DAJvR+F|rI3@={J2+$rUnq+~<0<*}e!N`0OF__BD&1cEpC1yY6Hem2OH(VRs*%w{9gEspVfxO~Q*QwhpW0 zg!zonuFVj1l!eTkCsVBa(yS>f+&Ik$VV^_1C{8}$kgYoE0pt%OJ|K0PeYj3qsP7h)uV-G-)5UlvR{Dkc1+{%yB6xZ9>wd>6?_Pr% z@0%7*_rR%( zUSWS)+mdCLN>OdaUpgR^ zUOWUve%sH6vz;%$>mVlXs*x-lGu9<)G`#_4N1DTl(hsXH{&~&@^KVfTU07Ogq8Xeu zzjg#aw-=RMEXo6h{cNeBje?fot?LeZ%tN-*^Dvs5&)U*n69Vi-;ljE4UHZt{x>Ri$Oy1!7`%R z=Ht9V8jfWG2~@fXGUvs)$mOIrDONA;L@J87`UG5Eydr*36}PS1lGTS93cMh=PNVfO4R)tq@43o>sx_2T4hh**qG@b$g06Jxi z@RHZmIwjRqdW!ZW$M9aEx*_1FubaE6Q7UvXta*)uS(a_&iKB!qL#INymUzh{gAlvX z#WUXtrt$tu8EPLs?9H8aF-_M!aEFUW1JLHl?D5;2OTnP$Mf{>4P2!po`^z_f`-HbD z+t_&3dgL^v^p^t?7kv5w1p>nd1xeuHsK|D@rbtIYWdWA`93dI*68zyiFCtDx(OVLtnoETrcG1 zMZZJO5dEBAZ34ZV+!O7%p}eSMqy^HTfx8^i{N>;77?|VF9*L8p(V=l#S}leG{OZ~8 zB@l=H{(iF`U#SlnRsVQ*oY;h{p&sfopy9L%ohplvBqL^xH-&Fb*I}`w&~$7`4Q&|! zqJ`TnN-~ucC~s#`gV&BH4?*y?6yNrhfpI^oy2)jE++SQ)Ll)qDeEvA<2oJ&w(NlHs ztQt6eNZb`vuaRa6e=tYj6k$_T-I0M%L;P5hz0pUcp^}qeDBekoKxHq8nWX01rv!ml zJbfYLp2Uv&>ARTs!}cW}|2om;-eF;gCQ=xw=D|OG0mu_XOg#EzE;){OE~0W2-Q#Vw zyX0s{D(&=j`3IHdR$6X$=l@k@=3Z9>=O1{+v3Xyj>DYgm-zK<-vXoRgGHgz-JF!dD_dFp-v7%A;uit+Tr z?=&S?Gi&w;))j9l$-qLRZ!SO-mk1fWFj)amS6c50LV1;q|JyA?Ghil?Bxh|ul(~E!jtl5fhP6=z)7CIHz-pK!|Vx-@Bkq7To1_(TZt@E&8{4r$1Wu_5S z2SOxBJ^QF;88{BI|JKX~6qTJJ7239OggD`cf@+U;PA8NK)c2@LSUUTQ#c4(Y znZ2k3!b24+x}Wx!mw2uVG9+_HwI$iWg^ts?&^D&4CiriQ%ny;i@eV$ ze#kbj+*dlK@J+^u6}N5ciEcsnPPkxyL#+-&8)cC1i}vl{yv5+)B{_!ew{tA83Kx2o zI}H}|Hg2<+oD-PG&^Eah<A zR#>J{r+1e|X^5a|?46&4+9IZ}x-_BEhDvimNrAfdF5y*gQVPYuKirpfP$Lb6;|eM$ zlvgQ$#FK#bP*r^^GVx8y8%d@#N)7jRr)^!lWK+0B_74Xi?z^h}Na6pPm$S83P#Q_> ziOckGSl*LSEMypO2U5Jvk>yTPo7O5D2A;%Gtui^6OhKoxzVhNcgR)2$z{NH1{O5Jb_`*Xr6J2Y> z`l~>W+$^A8E3Zy|1%wFQqLiR%4?q?E>!?#7+j+ubPy6yj^xYx?+>1klR%$qwvwk!N zXhgwF5av6poWIeW~rX7Ay| z{{)z&tt?WpT69_q;LXkmbl3@CqsKT({_SDc)*kB;9Qx?knU`u!u*?`Au_ zNgW9=34#=bkYrc5b*-!j;35=S008BlgAGtfKwoxgT&oQy;ws!~7fV^T`F2zo$k57S z3bBoIcOaIUV#H8`45`9m{Ggz&r8?|^RS2lg8^5o34Z~ZV zQJ~|VspJdhURj;{l9IS3<=v?pMTP}I!rSoB7@lSW;8u6-HhgWsY2e~MZ^s;Ik%@XW z!$jyZ=3c9kg;TNIFo@P2~ns;?uiQJWz2x7X)jDeFa1>$j}S7#I*VUC6J7U>47Mg z35uan)C1Ix3`9&Ja9=Cmg(Ta@A-a?{ds-)#;SJ0Z{AGF%rJH zBADc;^m08_y%rz#zGr-Dhqe54@p`r)+&1E#cPX&BMRY+kBc$4qZoDAr%HhL99JOGP zYB8Zk@^((pU*`eEb>z*mw{&#k`wc+in0t>!!Ux0Og>_+}DjX7>dYb#k`mY`>3iIaN z=c%Ml2t5QVSBa$bRkTnjXl#?O{~P~uo5^3qPs(U74l+r!3*MZWaL4F?$)fDwqG$}Uvs56+YQz6lUF5q zFO`yeU&X=G#hMvg2&v?jzj!|bXe{$|XDzr=*ym8ZXZn40nRkGnaQoov?=wb-T5B<= z_I72r@HzgQ1%Qh5xQovzt?1ey?rE*kNri$qfYj?8G5-W+Letw?)N%=t{%n;yK~+vz z03msmD_}DH&laNjwR-+exO?G_&t06m<8E+5V+Wx7(ys__aNXm==I{JnwN-$=N{_a4 zPh7)%%*j_^M@Ti{C=4HQK_b_YTT4PBM@nOHa22BIi)6I9|S1(leP&!SekIWF7*kDzg(CXUJ*&i2k}?YH-dEvU8w)*`!I z3(Ml_;*%={?i?Ch)~6EQed1hwNE)v}N-qIoi_X=W##2nG~3I{r#ADbmM$ zSQVEkAM`6Yb;}H2OAOOXnwsVVs-Ah4A0D9A0c{ummve(LH>vfHeq3B!O2ck*!xdo_ z>gH(i;&b0qxnb^^o@uzb460Clg3@mrE{~?(^j3%wvx?-iS;=O3tNPQi{GN#qoqDMZo+PKy z;k;RtQNLm&(sj`*h&O4WnqdRLG%6nfFa?Jm_|dTp`KSzg@ZF7DKtBNe+M)1v^0Alg z+h=(P0AyOXEUMT=PY~jeuRa@8UY)pqiyL{2N1h+h+^faYd^iH5|3_P84tuD0N0Xm>N*xwX2=BBuA9M9r$`*23a)k_Al z+nWn|m9yGLN~f^Q_F8L39{cF~w%}%eF$oKPBnz~=N72nul8Q^`j)2A+&xX9nZTXhW zN|uXJQBT;%^DF(v3udBI5`8BSZDp|lNQWWD~K|!+dqaBcP}t?RE z&XM8aFTZ-?uavi%KX(cFk!HKc2(7%uApxVa@|3)7)3XQ2dCpwQwX@VnPcgo)o{v6S zBm~Q(XBBMILO&)uZT=P&+PLc$<9+}vv9O+-=Ck@i|ErP zCXvh0O|fz*05wF{4RF#g=q?EsRAOCc^$4s_wlo<#_Mu*@c}KZ+%H|@OMV(!+l?x-n zUt!Vlx_(-DE2Oe!%wQ^(^iyqBovLh|6G#Dq3pXRCZgfHQE|4?7eoSCM??X&{z2cKX zm?i7(3dBMg7_!ZQrtoSR65S`xdVf2!`?hJE<@eFNCbs8ywqvyXxrO-)3NJB|8oUgI zY60JmrGgfPC@D$PHcCp4tdxg-?{R7~f$aPul=?Ou;9BR&rJ5Q7_S&`&ry}EnZ|eXl z&y3AlQu5CYm`x%8bsMdgeZo{Wz3o(}ykfKe^Bmy$e!D_m#rfTwP(h{GkMVj0)p>)> zF9Ct8@`hv(fe_(~K;<Gj1rBKXaa8COf$|$R7jJ$#+U`{TI^Ed@UCNDSQ3i(PtaUD(Zyye^_)BCs4ue#K zCJKzFb#DCtLZBAARI$Gg?~W%B5&g=2E($iGBh$H|&&GjLga*zadXgIED6G(Tv(Zdr zk^D!et)h0d0%}LV5LbB{y4P{trGVd;w6WQB&u0K$=Y)G#-O_v6$*tw)<652WVE))awU{e%Qr_#nAP#D-CDBX6B4~55_vx>t73xlC5=Aus) zU1$&{i)cO=Ot>!WckKB=bkBuJ>as>qG4(>er4Fr2&ipq(Ph^`%3G%lm^eIX4hRDuQ z_cWu3h>-_T8MV#bS5flk!a-9Hi&GWVb)4vTGXJ#=nXrw>;rd?t?Rh4#KU_9Pm%S7i z7F|B;n!x=bPMx1>o8I|-z~pCNObT~+f{jqC4-G_bDuj8Unq;>ot`upL*L0w+AX3g9 zdO1HXgs_~P&tB6yoc$i1nW5dhbZC3Ai9x%2RfY0hbbHD)+?&JH4$2C<#xshM4CIqL z_XiaU&&_XX?&!SeyHdZH4G4ykhC4JcCho_!RUKLwXa!%F-qQH4*Pfo9?U|9HlrB)> z#U-fk_lG5Jt6_u*yYISc>Syy30ss&w9JdALq5-oZz>so6Urdce2Xk=eZ>f=^zkzTI zTiOdEyC!35FKeueZQ`wwmQNJT)1u?Ev{?Q98!u+9*^9iNIajZO8x8TjP7d~bTUvic zq!X$V)7nd`FXWwG>j^|Ol%$y3{q+_wKFmV@Vjyt*x0Q) zrRZfJ5TDW-B$fTs3Yemc^%tcX2Oz2m1=XGzh#%Z6RVU~Es5$7KXs8GSns}2U zN0W8}^&{Qp-RXh3*2;74Dd;Y$NnhfWK*a2?$vRXJ_2L%*%_l{AGXLHoGyrtZXfNn{ z0E+g>pkL!B50Pr&${mdJk4%v7vqM$b1Pg+ zn;2X7VGn}#VId0p7uy1{yW-gO2@IxkS$--lF^-AD6vHi-);`c=z9Qu976 zE_cX+i_rq^oqiCPQ!ApKa5MpNXc8j&HTT(Tx9?rBctA{PYD&(07@sneeykUGLc4osWr^zgJB)l;ZKMAp6~?tf5%#L#q97~6f< zx&9IfNMZRfDf1$Nl!I>twfn=f65hN%;DcRVoLtk9#AS&(nu3V%5u7fKyyV-`Tm5g>z0E^4RJ?(OekS%lQ3R)x85A1BytA9} z=bW$O*Qd`jsqwdP8Uqe+;Icu>M$GJF3YExy?S5cX=#ueuClLXmTP-^mVk>bwN^?UM zr;fy(b(6ZTT(vT=P&0rKWk(~yD84lg_A$tguieI>IdE5J$9Z;idgMIzc*R(Z`p6q!-<47w$%Eymn*Mnn&AC2CSDf=s`S}u|rI()Y~2p9bxU}wT& ziCIDki;YkRZ8qC=W8`@XTJ9$Ken09i_RI^-@JhB98n&d42BJPZ-=5!y7G|CNNYL1P z{?~(%ncP=EJEf%cC86AugdzugD?Ni$@Va@GbjPb7T1V)n6F;QNyOroQa|2}xobX>d z#|e$R@>Hr*9c+Dm;9W2x#QPK4qS%I8>Ryr}=T`}#+bRn@0N@sfboEo*6t|semtVUs zFvS(!t26CponWz+9SYNqg<)fPtWmTU_|4>)JpGQxjiQS`&c8MjmJ7@cEBK8O_{^#b z#&;KS6L+=jh%8^>b11YI1MYvP0UH$pX{=I<6IBs)CyXMOBd_8bu_|(-0v>FhI`_kW zfQBG_5I%own)sx0uk#UMm7)ccJU|Mvn46sG_%i#>2mCx0`QGX_^rcxlrGsdea-1Xb>~tJ3-Z}ly9DJC&xP| z_sSYeng(D80U^c{wC4gBGlph$k3b@~FojGYd1udXF8Q~nP2{1E;&E@(4~nEDhm)Ue zTaoPu3YYYu%;t8tKFYD*Rggmk8WJxXV7@r}%Q3V7xxSC+vO-mDNU+$xhXKPQXWuW$ z)?WTQ+Z6nF-Zmr~8Cl6mQez=Ob4Tv*yO0{CxZ&)ONOIjxdj~e#QbL!;n+Yid?h%hk zXzO479%cPswWX`!){90L>D0$mKwAMP*~)Jp763@!8_jl|F*j(3nV^v(jM%_FPlW32 z=mS>gk4)N4q>Gj)L6rw}7JmYr?F>IUmpZN*!1UVL+`fBOF1vWa>*GlkUw*}v&+xRM zN3apOgGlXn0jhQ=zDgW*k!N+-WsclMRR_4z?{w(hjHsi^*hYgEtQ}N^)kDx+&t)6A zDu}ot@bE-rWm>RXA1pu1^U0@HM<)#evn>^s*@Xsk^pc#-&)G?5oTVEMD)3{xJG|DYR2fRWJ1Mj= zD_3=dQUNnSYK4@uaqVmhFe^yPsxoXpgJr293CX(;Z;6HJyW82QWIIGYR^+@_Q~9Ki z(D-IUq{~dpdx+D0uIl3uF<3>^pC>>1MY;OtlH&m^apq}zyp>{r(gSQQZFeZ%Q9TsM zvi}C2MfV(>IH!J{>X$1$+ss9J5Y#q|FC&CJem5(Oj$?yy^=1vyFyUy=LBiH$6|wv{ zWE92q2K_#}sQc-?zwdgKR4)L`r~Z>-CmFAC9Z}=z<=0L%)shLc5|o(FwZ`tLsd67- z!sjkVj0E5Xq2w*$mRid6%sQ7&w!PTZ?X_Ih%QJ`syLVzN&WQm`6xwCrbnugtbA zjy)rQy7gl2LA`94Dxf3?hjN58TuS^pG0u+_8W1^uX4J?kLjOgFhtuNW_Wo4;;i;i1p1|I&oSSRR=CG zPnW4YcmC*X_t=}n9{*pL@hZNOr03rRFZG1pjy$S9sy5d*H*z^E0O3N}bfz6=0~B)> zucI1>XzK?dshW0>+4>Li^W#?1Fkz9 zxDuS2z!3V@Wut)GIkpKZ_K{#X`1#{3PdXz1Wg3$cg>)rmHj)r1osk}|4I5UagB{P} z;f}5y+>Nqu>$mYTHPjJ^Abj(-bz}BrN9@OS$eJULbM4NVX}QO_Xp4SiG_)I9IV2H_ z=~6@1da+tk()Bw{&U|w1+jF`lcY`vo#)y~tw>!AW6VQa}oFu?3WY0u@USTyws0OY# z`TV52Lr&C5W~VMeQ&!4=EsFt>-HQG_`Wx=f%qqFMUdSJI=kHdDgPN;CFkiGnbWoid z->{;&7uc$%8HL!PBIgmebEE2 zQ;thIw-xT7<;syjXs#s-G*aHp1Q0sM#r7*bSw}2`o_oU971T#5T}ql)axNElhU=B_ zwv6Dj;G(+6B+bb_EX<4(4WwWRO42)~P zd`2#W@0wrnk3>f)=iCSxMUN>cSIMny_I?N@8F_ut&z%Et5V33JU-DiRpF3xl4!ulT z-{2qT@a*$2kDT&T~ zpFL*6r(~;;kdm=zpbl)fd>ega=ww*jiVi9iH_6t2Bgt2CvjL&NRmg7c!jXTg?w#!( z0mJ0w$2M@$a&oYM7i#8%4nKYZjpN3B?J0OuAFqw~u!o#-#faFlbPR=Ot&@=s)qDJ- z;C)kgq{}L4vK=sz?iqj()Md;bSdX$kq}*j2sz%}bV72&71w`xfSY%o8gIAZK+szkC z)Vr4notqHy-(Wko@(y4&`}=$J^$C_oTU9T=@yU^ONo9=q20Q#Ev>G?#szl!M3Fxa^ z**OiUiNry3)VR<#`{Z1ar6l&=>48-Sufy~8j+goYXtMCCD`)E!j6W=6H6 zxadu>`}b8Kj~*$#NiiFHbUnMQ=aWVR39A+SGRFpp-8QX}>iA4q4-FYR#`1x6?ql2Q z4}5ciyo8R6+N1m1IgByOh$35^>v31T2SkM#c7b-Kvi~{u z0XoVpXfex6LtA}ph_?3tt_spY7ee=SUM=WLPBQ>T3kGvI>2AIV6Y7$@3HN|~vwmef zXmr$42OVtk?XjF|*ThaU0LF^dzy3JokH(`xK^Akiarm=C4hd(iL#Gzx?>x#;j=HhnZUby52JK3g zCBx3KIG=vO_#vv~i&>>X2^RlV6{fdkY3-ewE2@`Tt)1}YUa$^ibQG-%!`LLQRyCXQ z7Xfim?RW7EnfSWZ;|_VQz^%kYAzp#qv9N?EPOCG#ZsvwNi3cLNO+-XL+ca!G@F=g# ziZDGe^2g=;LF?N*Ns;r?P4okqzbk@+k0B37^glO)M5JVmF6aywh&rPyLKlCc^Y z_RhDccbdH`ytWQa-o7cnr*V8=FXw3c9cns6<0XdGU!td#dZ30<#y-`)cXDg6)o%s~ zsHJ&4H5D?cd!VA%>tB$kl=c{Vfw*!*0(IzIHPXj60jkPRwCQMLLePvZb6`qTR1_ns zyD#O|$Zw40KKF->X88mZzE;zx>bHoRySPL~vav$enR9d=JGwR=tb!kl!g!xnB^w#9 zPN1umD43+Us69tImqr{^dR+5f@l9))J{Gdr-a(K>BG6boSI;7jc5r168)5-#D)woP zyT@3~`?3yQ?`S>|1ByY3nOZF>{A3z<67pCw>gCwfoP90vj+?DKxhHGsA{K5hn~OpC zD;^(b_-rzdz2#N4bEAPn%F3CmJp?D4vT4@pl~g>}H3H4!c^465=A-wUMm|B91;?|V(oR^N~@0!Dpq^E|}O zIo+?zWns)EJwH!}%!$j zq~F+$JO(A(NaS&b{KoJ>D`x7hoNE88s?;5vN)k>iSM)0eagX*F8%31hJv5_~XZBQO z#0fp(L(6roTcx#%Z_d7X&@L~-pXB8Bxc}MF6lW;_-V}U>Wa@qi%M_jO{)48q>Y}@^ zqLG7us|uh8C1!YGg6?awcR#q`DEP|u+=IrXacip$T~+cc29)v4?N86Px4Z80p!1f8 z8INk2^zLhc$7)Yi>!;uk1Oe}ZaytyPxBqniPM|rI3JY1PaBMZ5n4A`seZN6p(qmT8 z`$RDCL<)i#wN|rY@sgQUJ#KizXHr_gz8SZMAabwC9qL4+v5Afo)879%l=Y7-wYb8! z1wk5tt(blTvL7d>?;d{{fg1>2`LxWxh*OBKUXosGil!7%j%)DqQnsbYxlj_;=g-f| zU5Z%T>yVc~!jD1gWE5xM&M`z=^Og=``HXZv0xo@|%_Aqe zZAo?KsQ9nGYjh02nPNj2rr}6_V>06a@b+47INu)$N8XU zcF$g^{0gZ{55nLXZqt@dYhTo=R#`&*ARJ?yV@{Z-_MbX3$51TZwzu$bs3&a@)6mXU-WjBR#Sx8?bq^^2k#O|sfm1+V#uYF z-=MSX7XM3?+37#zCTE3AMeKUxYFbYrCAKxU)(&j!FY6r)`EM3LK{DitJp%IxOO(`I zC0!%#Eayq8K98LCS>-O^qJsewDGAShoYn&0crRCYp7Bt;gi$c!Vt-VFQ^y^0A(R?~ z6L{ze>%XsvOVSy(k94cRY&-k%bVz;At@3RTVS;kgGkR)E;}HWf)Mj+yc^J|o;P-$> z1AD@H>N6jG(s_Qs5yF<lzm@2R61iwR=OU66t3ACOv1 z&Zm(xs=3~GQOU@W?f8M4veElxNQ(9Hk)hIeGDJtK1 zWXR+MweQ$^;Pb)?+3%xc(t4+u743`f6uv#Zx4DetJ6;`5tamA7ep`P{8-Xxt8TpB! zp7T`x0qEhl#JtFy1w3-e1s^|%Iz z`I}m2eTXpavA<-YFYW6I8)wd3@Xz7g1;M_+`L_wb(oS4f;qF#9+Y91hmlgp zYdq@Qa2I_tRCx|KBg}? z#VD{foe(&SCEND#6;u82E{~yreb&=A&YFnPz_P(rd+}4Xi50!9kg!>(Gux?#qWs zFI>dzKRVe!9ilpzl_N#x5<^l@QpCvy~bxWJ`+2p4)lWyu&`)kOx4u_m4WMLc#>gOA3aj z-F`R*J_TnaV6rh3^vP2swsXuynFJxldZe5U zx{_aK1bpiU299AjQE$ZFQySMb~U=oH=dFJ;_U)yTb4=+h;-(4Biu z65y!pdpszWc*ZLEJa}Oy$j~-?XR6>43a_7qWD;}BrwZMGf*fhu?cFT)hd`3rEE74J z(@;laxY(Gp_W8P|&zH@9_(kUPd%xY!xXaa&v_0&tl$Yq;)RPH%_vl{OnzXp{$I;?` z8mXra%Kt#LIQLqa6PKhbItw%2xTN@Z^0sJ>i)OPR+VZ{6%o}A{j^7%mPeohHu1J=> zFgu9V;;1A7F5cHaYu!)?y0Y6QxX49gTpYRX%L+2o97B7#zsJZjcdk=9oF_cLe zme55Fl%GdRj8A*IqOk*EhZ#C!Z4IT6BZ}b5;?{8NvZ&!!BCi^84h5 z)c0{kx>qYOK)Rm|r63oq6deSgt5ggfO&H&REmfYsD~^$L=QuLKvwxHKu6f-|emyTs zyQOGvRll?vLw$T+Rk6C6wE=+r7_N3oJ12$?9_iN21&VHVwkzlvO<dL z{^=q02g>rAWumuzgDSB@GyEtb>60VvAajfYniA_UAyex^s|%m!KN}VvXmI9He0FC6SAySJF!UeNiR^38#)k2Y&G+?6KIf2msaunve>wDJ`NNF|fA z-ev_bu2O^&*?&8mlu&IJ=bcn?p{5F8YJU8@P6FYW03ZLTr)jpz2Rv^NU3#8)ye@h5 zRC<3d^zV21nD&(K)EKa7$A4LnsK+9Ni1vG2!{ydaIo zs(pK?p)dNWxDP%aetemb^A9VxIzU45LIc{PN~!9ebBwMTLkTq2$bIwe7L(?AB)8!x zZ?A+@*~n8neummLr+@$$`Y#}?q+I^vfPP7x@%ZEC|!fN&)#eHZb)cfc-}GPU(4tCZQgL<+nkPC z(ZiBS$4&_=tF0Buo%8dydmlqPJ3Eu+vvbF@1sYLu-!awMTQ5qd&e|&nP5ISG_g$eu zp4hlJ*TfIl-yn(NnJxy%jm(+g*j-GLU`#rFLqofC9DfQS*TC|oy+&ybb0wTrgNR7k z$xq4+x1ndP2sW+1-;XLW7fV=TgHr8T*x46zhx=7l8u#*m(}zUyhkejG8pWY}Kr8)y zsP1$kqaSD|W#y^42cn2B!}=+WMqB}Nq^Al4b+?Elnfy1rf)?^q~h z8^j>*k_hW9i^gisu8>>W*jDlTKs<~G-40c7^MFRqj15pPX)GatZlI@FTlZ!FO+V?` zskv8=V{2)Vk*tIEGq+8dsF?Q=&IHkadj|(8N{hl)YTA|u^+*?*b8ma(xi)XkCl%Y- zo~6nc^WY_rT{~Jlge}EffunRNU1@SzH*aE~broZa`d< zag38I522bIW-9CG%}P<=3E-B4@&=HAJ#@*%8Ba6CJy?hEhI9M{m{0g8;q3m(6hmbx z^oClY`e-+WN8(o72#T{sKRB3e$5GU#0KC7YUI+X+1TU9HcyG3sxA1g20kO4^1Hu9e`PnLQ*D8>-+FB~cV66w zj4M1h{=WpE&~{1Lc6;b?yuO?A`hl{T&96*X=C2@X-2)-3euJo2>|&%iKQMAm0)~Nv zZ>|^!QeEk?Y&Era8S9#0AV21)c%#>|F~^(XT0kx>LU1VuTHbIVhOCa#;tvOO%8VSA zB_nvRc)Q&hCx)$5aI*J-3KIebDlBpXQS`m>0@0QkaH& z-eAutR{kG!Ss$cs^-5m>KGa36TyGa#t$f%~Lr6M`YVF&%M+K9W0I3JN6v&q-jlq(9 z{=6$cwWkwnb_|Xx!Kvgd`uusw>gtTd4FENeES!QZ_^Ry%d@Z8OMSwc@5D>=J! zgy3O};e9*936+Ki4Ti7yQ(=zP7#A*_i07NW46D5J-s`Z*-<|K#K>n!c*E{aq0T^v ze>aPG4RCWW#ea7@r^R_RJd0FYNMtdW75t1n6$tiUFE%Fuoj7&M=J` zkqT~Gtz58~gxqnWScD-+bem}6{WhKR13_X;WnA;HeBm#Xo*V_7&VwcYhwyH**{*Ei zsMIONuu1X@s=#3X$-mmUkzd5PVH?*O7_To}FJ8vqv@3!bi`D&Jm(+ziMInxw@}w<* zGAB{Kx~)J#kCZeoCr6hA6k%+p{MW+c^AZ0QsgIJLc59Qfy9S>Z?-&fw1d!Z0iZ7YjR-Z2@`?_??KLCe8mZ#E19RitFBfIEhu^Hq=^E{afkXO96 zo1?D56t3Fob&9bXA#cDgq9m?{YDRvBZCfX;3Ph+PB#BOU>m_Diu)J1X-&y^8WC#^f zAW#?8@mS?`2rQ#*Qgx`m?K>{K)}KsM%mJ?oU05drU>SZ=9r__(;;pQQ^eP8^<7+|PRW z8O%>WC0Wq9^Qw(&40k|yLgGGQ9FD&4w;7y~RB)XF>!Km`9k@ca8|jg4h-O8t`(0}z zgZccX#dBgA<(@sOcc>AW%m!VtkypnlXKsZbl*@x#Q`#2NuJ1abOv74DX$$G|Ey0a5 zGFs;p+xyQ#hA(%U72SF^0S;0{1#+?pufP|Dn01l9U+hm$GI`(_Ud2c6xo{!c`PN}W@6O?(KJ&G=_k6Zf ze-Vz?*UrKpHxWMEiblgyT7v26dv=KJjXOKOAMPW!m)m=DCufw~@*}?&2t$S1<|(r4 zj-jB9T9?8-Li{1M`d|6GC68R&R*oq&QmZ%eH+ePtdCikZ*&KlOz?pC;$9$(&UsNU5 z`ctzvrJ&_SG?!0t6V|sgEV9jpHaU9|io?d&Tg~ZrJ8m4DImcbr)F&t2cqjU&XIEQ$ z5Yl1N5h)`oBkEyw`t()z)I~Gf9Zt^io8w4~?f2D#Sl>k(;erWhK*h(Aklg;{@ zC5#{|Xpq_lMB(SEcm0cjo2 zYqQJx{N4ZPacmX8Vtreym|mBz{?jQ87NSq5&j|am%;K#qw~U8P)+EKqgOy_(o6F*e z+`HKFxRj03Mm0Qf^0M4nWw;HhkFPzP;}9hJ37dj1&T30p8@PZx)A)C>P=lfvay6blga9JN>`g2Nj8PI*l&G({(V6gUzx^7@?EqGef9<4B>k(|c84vG3L zy6EFU**KF|-eSP@v&EILe`voY{&V(Fv6|eDutJ z$o`79zD;V>K=C_?qIU0*9odE`eEm5q?#jF*86ER?t9~ux_~@%7!u_XcLM~oQ*Zd`? zD~UuN1CFPVGOEXo$ZmD{@Rpd-*Tg&T_xl?a`R9MdaNy^X)I;`e*UDYaURKa`^16lf4C%@jYm*?<`<oS=GxwI4n8PF| z`_1R(vv(=inGTVJ9=_Md3m<}X5eWKBw5-S^S6TfPoh4=|OVqLeJw0j2Oy7 z0p9o@bvVQ%rCr+%(f!pua}M!0x-Xia{^bKFl$@-CqJY9y!WdmK$=RiMr<=r=iiS_u zgV5#*phFo+7V+z*UD(l`*PE?3j5S)+Vcb7G_5BaN5zD2Ivz*gJ=0rGR%Fu+XlQKK} z5~uWs$)F(o9@xRReAVRqQ$f`mBz^B%BAM{}`Z{sG)qpD=;6y@a zzul@u(7JNX{cGktP2ZX(>5@Q3&)KtHSaJ1-Vb!4Wyk2NUN) z$H;@y{&f~oZf>r5IN95-{+^Et^h|~SI%*=wUKn-uBx2?D78~}&8Vgm>X#u;QVCSeJ zErSES{-$+nWGeky_c2p2l8FqCR@?1m@UxmA%H2 z!9n=tEJJ_K{BB)|((Nlf0j2xX`0UG15CW>7oQcIb(#jg<4X|$8;A4r=D?{A0?xfO( z&sLy@0?gPb?jA}SHj$IP-@g6h%{^1UDzT{fZ2n8~k4$#xs{rpn_S$v~WQ|JFMbiL@$U>Ar#qCb+>mXu@g9 z9Rq0uMK9OYyFd?(Gwo0wg*VBvHoB5+IoCekqww?c7oaq4*)NAE_2(SX=<(~elg!#y z)9}>GeQl3U?a#^kbLC56)3CRH?9A0C87n(Dn8Na-6lM_!W_(9%0=2(9Zyih6y+1T? zn}6#sL))%m!!cLa(`?!k*%|y%ts4&Ztc7vKHqOT;)+xnVl$*+BNyq*~ZCITs)dK*p zVl%*Wo&a+_^l*M)K8=Q%nVG4l&xMth_1U|hz;_*q)7$BpnWWfN+o_5Gw?!X5rXD#u zy*j(y$unnI(mpJrU3r5@u0t%+>TwZ$h_y4(SGX4NyX$}KcNW=wvIs}PV8tv)#%Wgz z(j(8zd^s_%{yH6dGoeQC8!vsP!V41u4&1J%hML+>W1IT2vA&y0^jt&Z;v%Ojvv+@w z7hfCZ(%g~vh)>;dUQRKdqTx6I3cz2>`f>ck?51r991cf5k}<$#9A3#>%dxxeadOAMk>nTL-L zuQx1FgO)mU?i@J2fyy@_#SirD2eQG`8Dy~xA<7@Sm`*)%H={UqcRw~Y^}*D%P4~AM z_9P^Iv){D~l2ptpoYA+PC+#cpca?6>o*yW_R#rfIpsXZ8cdJyeMyc?!t&Z|PZP(4n zZ0pZyeBdzabQ3Zv;p&VJ%!IN^nv8akO8R_XkR}Bi4lkmg#7%%uEA(@C`b%kTp}Im#B6{(b>CrXTkH;AF`&jIyxHzEZ?v=_ zHr1yyG8TrB#(FP(nh|7;A7BkV)`O3YMT1=g*aX;2I06#G$UcaDzZ%WxacX$qDzLaA+inn2x*zJ2AxWWM?2pW zi`T#ri+{&HTt@3er+mX=0=X_5VvP~APu}{7wz9#679Vb5Z5^eH*ULiFWVFyZ&cB!-RiaYa>v6g12UIG)9K z;Lk|vWCN7q+zKdaAf0W$=lUYm;6Z!h*Qb5!jrT{UuxA4VO}6+cOXbvE^v^BoADoHhyEuS zBQF{Fy;}UV4zPMCeUynks%71AAKr^{h*kx8zvkmb^R5>AS}e>A6Awb`8O9<~ zr_H25l8@iE`|PXq+$0M|8^EnUg_SG2#1tD;R#8;=^U6#UHcFV+9aW<11kqyq;aHRDN7)OlvCC1u4JeN;ZCg@lDpyW>#SqZ$MP> z^2Kk&Kukpb^N`H;1j_`*JaO_LB%q+WlVI%GJ~#BZ{wSJGYYKgJwVlpfbHI2$`*XE zI}=RPzz;oWU48wkwi@prrpyCA7n6f|X2R<5*`hY$zdx35Jc9;>bKA3@`~2biJZLu# zPw_v!;YHJrrNhKosc2p*`^SqUvjoW{c z$al%c+|VPX^%0(!Zuc}#X(qUOMdQQME^TvVO;WKb~ z$H3)L6DY1+1fu>|{gFY2nKFg_^X;jbC=Ehs*N+qf?R(=O%8-8d0B>-&5R8IJpBTumR0Rh!Es9)0I%@#&v_;Rm1-(KmF%}U^B z0>W&jmP?mvbEvv08WXn!z8@2NR&n;siT zY^P+5Kv52J3T7@L+dI;3W-!8$-cp-qh?Y_bv;n`&J@~;qkZ8oH>_IWBGGG=n#vb$5f1r=UaWoR%# zYnr5P6#MNoj|39`f4l(xAr5L@_sQ!PO89TWhOZXq7-2=UDqP+C)x&Dj7DrU2f`y(6r+hCj&3sKd(XXt97xvTtV+ zw3p8#|1SMHP%ApM*_ykjM_E;+Ztvf{wZ9RiWJ(9UYKg322(V72#huLb*3n;(yf6t< zaa0cQUV+%=+3bRa;x)J2f-mc}p$#a^sBcSRD%cKc2ta^m%AI0EMOCfTNVDL@g^yI` z%>ZzjsoBlT-yeIut#o5;EO5iidVsOjq~GR$h%9W6`M30Tp-OS$886)p0?}0WRC9mh zPuP7nGXR}gKJ1b?yo)SQ%yasz6!}+Ps8pynA*XGJ0>Wg)IUlUJNo-sfFxVvP(>66q z$1wx)==bEij_n&=7hSA!B*r5fW2tZWqq`IV@h};@OS_O_&FTd9RPf*-(uIZ-2I6t7h8LY(XiKKRD}F?}G1xXoPb6j**lIoM*Yb&(PJ(N_3cntn7X zz52v&M)a!rlfs-v+YdILw@5rAcita zz@MIn-c91+z=Nu$tJ|-Ee)a#YuIT0>;w>1(l7;D7j5vlpg3ke3MA6Vc$2W9t|K+k2%CY04mtCshaI3~V3?w!zAeyyX{lvz z6dhF{s>xCluPD;t_}HUL*GNH6-uk8d8Z#IFLy3QNJs zgjO!5U7Zn2-vpZ6Q3Rxx;K@T=%|{EPC0ZYzh5$v@ts`#l@?BN$$U4NE{_AqABoJFMty`ci|7Z%XP@$`Sl%38V{N zhYE2h{|z;d;&w~qAXe>KktKkx5wpLaQpbW)&~IMV4{xlVDHwj|BL$vNJ?ON(v0K`L zC6O-OlR~`_^V_M^QaJ!ID>Qmp)@JKA2@Q($C7?>F%>my%i zc(iXEA^x*$aTgYwjw@y8MiDPNy(SGkNR6(TC{z;_jBnEhYiT@`i!6<>id@!Yc0Ddj z2Mv#2N7DVrJgTPrxhK5rgVIY{MPqz`;wpG{zEz%j>!{ya-X|I0 z*ZBNozXNrPM|3_X50DeND~nS9Q}+E~@RijjI+NRLm6Dlz#&fKtcLe4~XfV=85g<9r`GS29pmfIm$pm$VcHhw^rAVj8afV0ey@dsw}rtFFVD*~nN40OPQ>w6gR#c2$AU}Uws!#s z(72V4r5#MX#)tAO7M^{BWMa610pE^cPohfE%7hAX$`<3sP?#oHBEQNq9rAsT!;^pT z_J?b#n3g|%ZA^Dy;fj0jfiT;TzI~`b-b#F-$)>u-_h+3E?Fb>SIqZN=92WsmZvwVp zH%h9#M<6fZ^y@P~Q93}GHR_e1Ea1I!A$@Jb*NEoGL2R7LzB(X$AKU|S{vXGOi(I|4 zFKp;FL!f~TszK!_Bm=#K4+8XvG%JkJF;RolVBtuR9tcwU4hXc~ zaXE~&!oFl>okn${@$YLGR}k7w$#5)IYHN~S_H`}nVV}{!WKjg#EkYyl?se!R@u&*U z?)bCx^EsZn8wT3UROyf=e=t*!)8>+=7GqV>Q_Dp!?#OKikDTd@E144F<=Pk(M^~g3 z0xCT_YhsL8pRN|^#$(IYtlFsI7AAS|3ib&+gqthIg$`_dh3?I~6$^2!@NG87)!=VO z;?p~j9mCE49~eLM;k()@5}a?z4Jx*WQ6)gsEt%L(ks8o%rTVafa30{Hi}9 z-;qt6$-&Q%QW0o>R|tLIm8+07M^=~16`zD)+`QBly^{4^f(R!nWd6ptaHj|c(BfJ$ zV9t}O(nbq+HW*5LCjz+|)3K`Kw4w*{CNCI zMNtB6#I_|7Ut~H7DDO{G8d@64Bf++_RDX8Imz*R(IE9)ESVUF#9D=}rm$w@Kmq>E8 zcvP5Vy;|Tj8;@Y$XQfwlP@~s+K%6AF7o^bJk7ioS1ge4We#G~%0t>v;I9F@@t$7KO zLebS7!;V}MW-e~9lO57pjki7AJt1YI&PX6Aa4htK&thK~2d{kk;1CRkxLy_Tf_?|)2! ze*8=7X3PgF!2_hlLds2Axu9Jm_7LMC?Y8)32bYXE-yk&@a3!qsJaIaOHB?__m{pm> z#1~kmo=>7euy9u~FpyyCD1iIe8gw_+$~o6!$@|Nesc^K3X?jtpYnA+(O`zSPcjOM( zJR;fzhAbOPUKY_*c#SmN<8V-hAh8z%5B<^yc;yC|*OS~@w*mMFQOEiZz{@z?V?D|3 zD)0D1E#=G9)B)rGfNsWnWLqtBeAq5DsH!_G0ccSh#6JYegD}m0l5k>!11cuM4!jG* z%FZ5{q)_#TP%%5yS~AN3Jo(DN1-SuYPXd2ZgSL-{2l)b%6*sO)N+WjI=d(Nv_Dtab zl`U}z`M~(SWVVPjwDhb;x*D|=0Ahimj2k1}3++AaWX4P|9MNDIU~q*uszXuU*~Vp& zH@>(QOABiaIqW%L!RreH@^pASKoPw7znsiPiFN+Vy(YkWBr7fan@CXAVDAOok|-!{ z;IQ4fhinlPTFfnL}S@UhY_wR~0q&A9MT8~PzbRhh(od78XF35t~{hcc} z>%$!!qR{eS!EeC;qLYHoXqhzju)R_;{^Hkp{qz%_jOK#B{!t`)(D>-nh|i5!z%S9k zBq0g3eUeM=?eBG>RM=r4)$LKMScf7k4FqlAKGpz|A?n=&djL8?dx`mRlwg7AkNO)F ze`-u>m?cRln+^svQ~a4HQSsI^wBKcTg2kf9iPZtS@|n)`^qe1{kMSG!FqMt!8*vx= zmk=*wU!QlqdPLI0MO?L2j1cJwG5|j`_ZPdwuBzaWFSY-2X*he}8#uclf+N$vIU_sV zNscJYo26s;uDf_EDfzzg0P39dI;Un(XpsWS5DM5@`@-SJamY9I{6Dlw)->(sv;nY5&Om#Oq*b75{^S7|lzUL98v)H4wgAwI zEpSlDG|08Ky9arzcGHB1ey)o6G!E0vKsG5=_NZ-E;q@Yccs7sMy_29?qQU8Mvak3J}oNnAR5)&d~N9+B! zKH@fRAo@czjLT6)KcD87bwCYny%Z*S&#HqlfCc33+j%3|8eherpe%1-OHhWpHRt)s zS)UjcX#_oZ;{Xwgl-vCgDl-SfO=#w^HH+Qt0-~qMGm4nX2Nve12RXd^YPKF0TG=_c zENOH-*p6to{uuh|^q&eK5>+L!n1vM|P{bD%{-bSbYcpVya>4=IN>O!G!3amRXz>c+X!rl5pZ>{t#nhiX z1IIiY@MDv`n7A@NosgcGjt=_G{Quzn3cQ17ea9bo0%HEB5j02gsmG3OYJl&gT}CF) z0WWb|Y8~L-uLdw{Cgvg$|I1v;3j+Y=%-Fnx)bMHVZu15yLZ6abkAF$bmlz+)^|!Yi zS3<_y_ihE#X?J{Wm(_uVx)J~J`fYv72^&`NeF2KTKRkJlZSpwvqS?fD`8aIw&<2kB z1yl^-*HdV3&IUJZ2@6aT2-3r2p@qk1Oyrb@jwPT~DFI>=;eX$gZC{JK6pmq$?J6E* zH8v;Iu$Si@Cv%QJ0s6f)2kYw#hpdS3VB~#}@TjOLV0X=rABZL{UmcXJw8y;*T#<2* zbRV8h{yJ;40X&4L4}l+-gxY;E{Gb?Zg%5sTvihxRWY2Zv%gJkUDcaEAYu{%S+!KIg9tqT2$M3i~7WV;^spaxO(s66O@ z4OA64@a^y7iTjUe;OaeC4mMW+Q)UV+=4qR6$iNUjz` zG|)?8w4NLvkZGS6*ex0c@`5!ly>Db5MkP!(CDdM*oZ{XTXQ`B(JXU8P^#{|l1u@cn zrg%k_*xs>Vo;#3lWxoTX6R=+DMF{_dY9!>1Q6M{kK^5vjSvyvHSlLk)-W?R$FaOXi zh+qrBfi&pP3&*4OCIiLFqc^6rbq6b>;O38BIB0ovc2_YNy)JRaw~NXhbiET{T>^P4 z@GM_`!))sxv}kQn9?{|`kwGbU1!|xTa~SPn_K)!3hdIc)hz(U&!Z&#CPYa$5q2>MM zJY@KlRdRlrV9`6bhN+3Lm*j8CQc?QvHd>MmioGmrj-JB+`(Qt?4c`Hspy7=nx-o$Q zI9f;XU*&K_eackj`^qmgf3sjV1gR`FFzGMnKZ{~ZjFluWYcPOewkzlJhuM|nbV9*! zymuWzEhBFY z&9lex-o@cyO)j@RXIP7~<@(%)Kz?OzVjeXAPrmFGs{+-N4o`dskw$Zvh^TtLia{Ca z@ry~__d^3DNB!>rM?^IY8HKtMuGw}V$hL~}*|HGBqm>-@Q&d$o9xc|Ae%u73xU9yfBk_kOX2E?2|*V)a*W(7spf! z`^MZomHhFKX#_nzewOU-34~EM+6XD^*iumv;X<{SH|uC8L~pEZsM35<@D0NIPg@33 zcb*4_y3SPvx6h-G6SD0Vq-)-Q7o637a{paaUsz1Z2bL~1f>fXShvXtDFxqY|2u+4`R(pYwX!V@0wX z{^592)hA5>C;1khp_GC0A+_bZ^4AVB?#)#I$m-hv=!uW`bgaHae&uSQna)w0#n`mR zfvuVQR=B!Um@%q)c5gQe{?+x@VPbmmSoM+Eb1 z?0d=EAbwdr8K0!U@dV#-J|ToUGca5YK)OS`(~{R5hxo5#+OL9>VEF%wZ5=uop!^z@zZ-7k3t4M^Zv?2i4i! zpjgPc$!1FWY<@L}@V~ZB{s*Fq7IK{eTA%b5)#T?^rz)=z=J7$Tx`#<` zlS{i?)^2%EB6Xcl^h^+!9r$?QoaJ&a3Kv4erzuaFdB6W9~>70zUjy@n0o zCv+9`q!X$BR9W6YWTVJ;YZxv_s_k_(tHt8U7%>5Mgn|!l{(Zm??-fPLNxgiSEUB8oamT>zWN+Vc zN(`7`-HASEuK4{hig7&_^pD+cCPsm`XUJ{7z}+B^{rVJltKU`#|0NqWLllKj+?Ow3 z3~Tq0M88mA8lOuL5FWg)u$vdGtEqudoV1=e!kLb&II@OAxn4dh!0t-}X!ET#k)S2X zr4beUcha;pc0cIlqKt@1*z^sSEu_-OR!JSh4Z3K_^ zEH^#+LL@bW#ASVhG1-N0lH2~CZHGD4XfMb$mhtcIt{{FEi2O&NyW%}-I@3P#J~I2s zufc~*(MSa;0q-Buhfl$Qumxuw8Jn3ju|HFQNDo74A zyDV}xr;-pI+-4TGRS9l$mBFLkJ_5m)Vt4buTDM0$#tr;<-JpAEG5x-g{n`*x=885L ze=NmHvJ2a6FG<(LuzA3R?%((oKR`M(%Mb%-1%9+(dmWOZfpwc~&LpfX1r+P%NWj%r zWiSnzXG`iI#Kd~CN4Da$V7z~1^DGq`a&GH^>W+E=8><5HjB`_zV`N3SU^pZemB{so zUJkf}ZWmDD#2b`%nio>z*j7h^l-wLd)#ef$C4MxT!;hBD7|Guud;2hU)$R=Mx+-m7 zpn=>1%r`oDA8T!qD8uf7j=)qQiBvQ^?1gJzfP7127wtEUh$4kUL0r@DUfooKlGt2K zn@)2J_-n(DH4X1)q&goCZJ>w9*|@}FlAug#T)iPpHFGGum$HX#&7^`0Bp+ zXYdtLf@b%^T-KR;lr`~KidW*lvow0gddwO3?KYgkCMy#<9leFgBe-ZS31j?aS{_$J zDnrTgS5pa+t|NcdNF2zG84kQ%F=z5#sneJ5ewB#5M+v=GctK=0yDpt!I{|y$H2GP% zX}QsLa?j5YgsM?`Q_b$k@?xiauc%v-&_XiRd4O&8WrB}Lo9Ap^-QwaUab(_FbO&Lgq|cA~soZwKJc#gEB;y?*{ruahqPFX^DA_n&A15xFbi zZDjAk@2TSMKLLcN1q;8}IMUXAt!WSHspbLLZST=eqmm zdiqm%!)&9Xk#G87-PYdu7GhY?&kjx6sa_w-mz>-%i_jL#wH0LkzvluVAR>hCIzkUZ zKr+Z$K*a;LPt{Y1XT@xvNc$&MrQ(zRasWfmn@i!Oy7*=Dg^qhP0|LOUN2IKgYq&z5 z+=g>q{?wK8Ef1=?X10;4c^OEnR9I>TkQbmMmo+~>u<;-fZb-WPHz-06?4V{b?Q&Ox zG!)Tr5V{tz9#=j)FwnGRC1~p=uYc7@ZecS#9fy}WKOZ_bqp`4%cX{S^DcQ(!{~=I; ze?f0_Ufb2y)HCU>_0n|fMsRQM?VN#d%WVt$WXM7-#h?9u^V)iPX@8BTeHUEM@8>@^ zu@3jf`PB_V;@7r@Nsep<^9h(h`nWfi3drYqo;wQepJ{29W44_+WjvnzVRa~-g#vQ% z3(-%cE|f3x)Vqo<*l;<&Df3&@w;%l{bl+No$9J3f zW$yIQwp9<_b*L0rNujx#q@Y} ze3m!StRhAI_HDUR+qZtJtO53PdJ4myQ6__OMCejigZ6TK9g2z1bj0|-P+A``V5^`2 zTcv$ct^sj`x)h4LoIxaY=fK~=03bLoV(l~_V_#b`Ej4VZ90YPFHY#_(qGEaG{%GO zY5G!Jl2T*XJR2!3wgp%!1qHE&0qnBiQQ{3q8-Sb~35?8tFnOcZ*oWuunI4tpUME%^ zQN@-yI*Ioy@hadqZF=gfh2yI*D?dUuk*=fx#80}y!F7U4{Q=rY&?4dTXG_bybHO;5 zAG;eC$x+|taC63cG?wrlJA|z~o)UE;@pd-ql$S}rxg@L3Bi=}Hee5N2xqtswl?u1^ zOzMy5Yp?8gJx%$hu>-oK7PGX+kmgd(6W6qpb8^y6foj&_x?`Tpk>$C0;^axztzR`$ zyFT_yeVSXY?ZQiE-z9SAR~@23>PD|ZUC&)Ss4l_?i?bgRo1Lnp8$jzfz)af(slrQH zqA}&yX{E(2Hcw6hD%GjKN8|FurEQnl-c8kpb54nN=8PUH@d(xWu%j)IY#j+MOsu5q zh2^q4(jI$`O_HKtdteo|(VxDMH?q*cInjok!yB9Y(gWxlt8Y`t3O?Z;OOlSPn<5r_BDAP7JT zM(|IL{Ll^`_-IZC!Xcc`N!KcTeWVC?)Zgn73J|a!_~XWSv!M*3FAyz{{V?)fh3J0; z!y5GgBnvp9G=B@`QSU_bw;1+(Y*y#g6Gfh|E{Oyz|7H?2p#EcWwzlFA z3#Wo?)zH8p00gSPlv#gS`^x)-tpEX`MLk>a+K0~`E(}!6XTU#~XOljkgk%?Mm0O%{ zj~fPaIe5%wwtBCP;x$KhB8jH6Ck@=5dnytHn9%&KRsNw!Mb90JP0L}1UNI>rH)!)0 zMOQ#)DakAfG7i?F^9nin@eW&8PfgUC+I8h?us$QZ&xiBkU!DYjcv738iKia?N<%>0 z1QOZ*jEEbaZrEckS|=qg15QV3U475;vcu6S_x4YiJ<%@-L%nO}yBkD)7bIq4`;D(c zbj?1rJ*;=e540Kb)phx=2gx69xBJ+-G(XGs>)C5Pug#0m_&%BavSsDAW~~K}!&}MD z=~Mu5pZ3nU$;k9fw;!18z9ZuCb5Ha7qu=K3(YAWIc1x1-2VO^S*48y?u;hDjCAgR* z1Ph&7G#>r;uaZ;edhaZ0t>1Z01b6Z4{Mn*1rcC7c8=;-B7;c3Hk1Z{pyOaB9B6(1Q z)H^{L-qy=1VGqlBe^(yI->QO6H~NM~dQ8gYpA=NwW#b2IOh9YD9GhVr=)Q?1oS2xH z6ZSK|tW>;3of%Sm`Mt;~T?~B>&@tKd9B6E?urA9RFCI-wTuRdtg7jo? zG7=>j4>@QdxGS17of(brP|#lieD))9Yja5rUoOD%1+ms;?r%grTJ~d48&4cS$b1|9 zV~84X7LnA014Y0MZ{MZc>?P1s(S2OZbA!XTOVar{PA!gd$zp7Xp_ zvqQHJb7(BRR8)rJBprLcLNDZcYQhDm=}KZ@o!07O#Uo=QFm-0-pS*zn7HF((^uB>X zg9SBd*%9CZ{8k)@9Nxg}vpr(zRv@OeY=BwYpM5R1U zJw0GB;F=8FZPVNcb(o}&H+V=5p)=*vuI9s^%C1Gxi?|F-zPD?9tnOb>b=S>M4ZKpd zac^zb=kiOn0nTACV0UoNHS&!Px$QENaYOygpF*7UMlp1%e0t=DY`)9U9W{aENPfg( z6I-xIO}9r4?2E*LdkOC`3?8G(HAyXZuuMM4_4>YM`rzeCC}qMzgy5P~GMcx0VNSw# z6be>Utj+~_t09^%Jp9F_jriuc=fH8#5=s=CONu*AeTyrtwW#ny6 zXChc{KEauy$F5|){>11({&(Yjw*+C)k&79x~2cICYW zZz4w?bEk*``kQ=P=pOkX99@v->c? zYc`kNf>?w9JY| zLVQ;mQ*^*A%mj_5;AhhO=-QYi`0)ZzZulu6hyLk`*OQX)6<9!MSAk!bFg%;X8UsuQ zSAFVh>cEx_GuFPR?W1B2gOfifdo!&JCnL z5L%)$66ygD!~y=$v1GAQz!NC@rfp~SAreu6;TEN=lx&!Xn2EnLbn~w;+^e0A`WKQ`R9|+Hcan=cgGgAgD^hVeZ}7U+Ba#mYUx49P-!N@7ZIe+{qU+;ibUC72{@{R zwaWyiecG$RNUE)li(uFKVH(w)C_;4av5#DeJk-w^^HJIn`oKe`39*9e53lg!9+LFI zE#d?mM3iMkF`J52MZVg-#Zjr&QN|BkZ;7d%Y3gfyQocGjeNq_jFBvudjLqM_!d?8{ z3VGT`BVYiu;S&C@MFAdvB~}KfS45* zDE5mbqU7|GhfRYm7gk`etzhIGCXhaa+pDX|>pe6COrn$@wQd9OnuCNPWxZN<%ElsS z3XxohDM(Y@Q{=jihp<&0Q^f3jZySy&9cmt~(ijH4G6jYo3e@L{@-^!Yq$N}BnZTAV z4aNWAv`px$iFMIX`OqR&4VpUlz}Y)+)>H2gD+xx@M^sAY9w@7Dy+i|HzONe>m`KTA zIPK695u_i4*~GpE0}3H)-pHx-*KEAxtPif3_B>UdvBhp38ZtE^dFnua3HWj}h88I# z9`x`11+>7Q%-TO=GWGy(i^o|q@zv0jjaN0Ng8_M=JCNAvL#~~Zw~bgc`+U zvnjzR8fECN;oVkCIVz}Lz{*cAWNZyP)=4sU@;)8k#>DoNKX=eqOKBx*N`E8XD-38a z)kgy`Luv{IzBf=WldHrhHFe&#OY>uz_@t}%-EGN2<6X)(x2h>V&tkzmOZXh|ptW_Y z6@_^smwK5NJ~!b<^m45xI&14dOR#eTWAcz7cJ>TJb$Q~FEyh{-iOw0kts*74;xfse znj~!9C^u5%Y24T5(w5yU?hY5Hhn*x%-^Y0*YIrLD-cJp`aVxZTEy(quKY0@Cnf)oo zO|Y71guYrQ*C?eZl{Bk%WwDO{Yxf08kf!A#+{~A0Vzt+q|AvqZcL48d{fl<*2VmUV z{>G$s>QFS~6Fm8Svt}5FY;#Mk9 zUry-t4?PY0v|r~Z{aE%}dI|MQe#joZK5W!W^0(`^Hq!ceLGC4C6DlOFl2^`zy@u!H zkX3?fgjM=a$x{g_J!@Fu>l@Fyo=tPSs;IUso%}F#+(y*mGMCvAR;f0}qR)N=%0(d3 z53x984%c!pXen!4YGhjju|Qw*o@fKi{YDD-J=-%t9Mz6^%&(k zx4fr!Y~&7v6G{?G9Z@6#?^D=c&7816E7dgdk7&b5Zrll z(;A3G2l2{6yzRgpHxgtYwmp@e;Wn(dJ+4g4R<8;o!lm796tb`O?GD29B_STQ9#G&6>g&_BwW%K=~Qc=BmE^`i`@j)C^ zkaZXa=pFE5wjQ8#Y8MVo4V7;HcqdFYnSJl}gK>{9fSH(2(RVx;xuemL5rgpCr(N+f zppgKjwiIMHL3gVVr^SXy+NC2Ih){&fU{7r5m}!q<%PD*uV%$AT2riGqXp41I6!H*D zryU(#aZBrF-|UQWgNWT40b4nu5&&BP1EWNTW3yZ$CY`@l*j=X2X^>?vIei(F#`!zT zPsMbIh;Vi}O+3@91H_0qGIYz{{$4V2{g{LNrgP-246WwIZ}Js~WjZix{r*Th8W~rM zeF@ujb7=XT2zV|&_zwch;StWO_^D&CxTj?+i#Mt_d;C}9^0`U#a4)sd;K9@FFN9*Y zb_eY9&sf4aWU=lA$*{fZeEo|gn?&o`Z$m&xNL|1vW6n~U{(BZuNkt;%NwU_lK z|0-L=0e|@&lD-sd^qH${08v3(mnl_MmoG{<>TtBnR8Q<&-3js4kKN0d3(nl64J3Vw zGjZjCA@ZG@2Bbz1q=1%_7VusMt40~9!qcIDAf?FdCCw_>>tFu_l2!*MCx%!sWutqu zXy&0hNNEHv%Uk|l%8f19vw58540%Xm&yVyqj6-M$bR&&Ijhuz47c$Hlub7$fC!0~E z@UAQ)rfM9x@h5FjyiuEg4W_x~=gxn!Wu&)ua|c|{34qacg}!(@PLi}`&}Y=kO&&HX zpewK=_zC=)Wbb;Pg3e3Ny&yRegOqt)64$BP0Z^_bfLe>rL+EC^3 zWC7=_aznkDGF8U&{MZ_fK|P6VB%zV|5X(1sO5XTw`=m@}=vr2jGjJjE~lGWX?P1UF(|l6Fd$iUI6~4cc%21l(D^Z`HWmARX@Zoo%sG6SxD|Uqy!ww!%1?ocY_%=U{K<+puJiwO z+F7-flzfI_2^IJd?PW7zU{ zXO&_J-SeJ$8h{jslm2gGFRRuL%#jGzheaD_^flTj-0XK%?Ms^1>SYRGDFY?Ece8RV z&3iaiSo7&^NwJUJAI1eQ{{f7NpKF=b4y6;BO)T>%G-OqI!mESof275uF7Bi+PV(& zG`x)Ylo!;#eFVE4ccg3BR}r1CW|Y7s29uPod5D~ZLtU*ZzrM6JKGt1x7mF~0a}F0Y zjL*_1fvoXQ)%9*x4~q`|8*%anX;!+u?;BDo{uAIWyX-;uFh0~YHg(cT0u9S3F_i>8 zLTi*7#%T_?Aoh=IF`JT)T$F^QZR8#(rf-;zUVP_qZ;!Lg0sPDN>SbUQLA8`6v>fBW zb}~KVMX?;Ao^Ug|>ob73gIJ9zz4NJxdBJ=%(MMDFk2s?CMT$E-iYa;TIEJt9pMpvx zO7)SUs}z9`#dv(sXS;dpu~%tVo5bXS5$WSP8O*-kZRLHVV$j^M<70a)@;P*O&m+u5 z6V$2UU7tkYMo~p?7_OODE!Ml zgGK)FHTutLoP!En?wDO|2ck8DHfv5^Xrc&*X!4ey!Efr|dZd2T%6VvZXS4L$>}?#} z#a1#8CxMAJdaAH+UC4ywcN(UN9S*9Y3f70{LlwXJhZCP!NkmdUx>^slh_{SU%s6rL zoD520V`W10A)F8t$!`e)sjKYmRFuGL`mkL)w_%p^sL9JiQi=m`d^F*y>N6wT@G2z+ zzhw5td&auULzAp9Z?6Na$!!b6RD5Hva5qID4mc88S!3tXwFbu(e>oLNuU}j5hPS8gm5qChd|C4klb>PZnZ1&*fs?wN8kwISBsrsev{2dPtWO3$dpKXw2_6s$5=4C5B4 zu0;PSSK{)fC(`A_gd>JJ23+e*bNb-glgmRNlz(dM8C@nJRLu34X3E2osnhc*%(^xn zr?vw{e$vc;fCNoK8n_K`AB&~RMziP*V>sda3_zRH#Kd{YCVL4c!=fw_0H42x_1+U# zy%b41hqA%A+x|qonBm*Hr-F!+enPog4_VJg==PpEQ`a_p54VjKi7e4<_b<{bmPr!g z%oX^a@~psIOsq*eRC9?u>>DJ|_DHM}itGW&jX@&Dv{pTa?pohwoNiPA)Nblkd;8y?>_Yvak z3I|^YFC%U~7}NX`DF}>YDU#G~$^q~npkNqZ`A_a125oneFlhp11bynN;k@3kf!o-_Eh;Q zbHO5EKvWsyW9@oirm|DT92r2PLAP#f)H`9E?%i^y6v&mi@>9b#mx|R)=X$C!t zU?BRiNj8*pX-C6X+jCMj%3GwBWLhqnQXE?^k*hxvrT(|-QY%)rh)YBlan6(5qpt{d z0tyc6ql^GOp>0mG$w#cZp;7C&cR^}Wk@`gYpV`&>8|PItz(61kO5V5A3IDzS*iSXkT^8*Iqto#@FofFE*5Mp8M&BR#yCZAN6jtG zM@}V5>1gS2R`WN@mIRacD|SvI5xpH$PL(3^MyFyM79am(7^dr-Tk%xMToI56$~~%N zXe+43h1DQlYQ$A$umL4qzGAF^&Tia(^Nmr;gB=&Q37k^pwc8NWKd`RVxRYG5jCUuN z_aH?-2kw~@S{qdyq^pBKBF=8sS zApB)5!`tPamgRX%llnWvxrMpmON%bJ~K2hPlU0o}7J&^_-v2HmN98e_LdSy`gu zwKPtkI!`*?(}%70fuvW_H)NySdDX>}jnq_#7x(gcGDR5X=UA7CEo z4xG+9dFH1#nS_f%z?C}fcTo`uudao^>_|_{A>_oL+(r>b!F+Nfv~%*6q5=0FXrUQWU2Y5}{cbz(1MI)SzP^x)Lc!bkY-nJ z_*dD$iCqr!FV7UX_jYn8q@BOs9=44MVSD6Wh^-sp=4n}z>>bc_r?sGwW(7?i{J=|t zVzk}RG7?e4I!pJNpjE#CT>}@+nJUF{`7dxRQjCJc~>zi2wqN8uX2H+-2L ztz=28Aa?{z79Jg3VOJ@YZ^%?BdvAn$O0!43#Q6Fft455ydEP1KbEyj?#kf-0i!(su z_lE;r-!JzSij4N0&(D8kCCJ<^Xxz@lGY+ z9#)9>oMjb1;-Q1VNK)eyYv6 zxcKw-e?=+EV=sGA?A1RR=8g^)yBaL|tZLaeHpD1FMCqsreR@0~6r(cQzD2W`B)Ut# z!107ceO02gB$yY5-(X*2yO2tAbLS3A)^zXSWTp?KqZOLAKVSB13F3)_pL~UzHM8lj zrvD-ZJ)5@gldR;y)#%7hE0ZcfmCeq(uPWp0MowAms0kt?Nb1)1LopmxFrvKE#Xsqt zY_OWCs!5{I5YXX-w%-~$$4r6w5`$Cn?JCC7^Cd}7J;SFm3x-EI2diRj5#5K6a=*&8=D-Bo9qQLv;YhVZhn>HVvAslNj#;}Px97m8iUr{wE4 zCM-E}CKb}{?5bQ`5)+=}-=25>ZTEx!AwqY;xw3Sn@8M_8HQSF|e5a?7J}9VgdUayb z`BkLq#X~otV{?)Y7X1C9ELHKYPzw^T!;F-st6`EK&ryZc@807|*^shD! zChNRHeaajQZ2 zFb)@}bjQCqN|-ma8127sl%$joQIB_TZK5$ly)u4(y$40=6(I$%DcJf< z!9_){@@4rYB#wS^lz7Q^$yCADB1y(PZ%3FSDHg;Op`B3(>Dp(v)Gm_ero!p6(0Ko@ z0&q8js3PCqhjC=*Q=Rz^EzD~AH5hsyS)K4*i#mpeW7+R{8g-H&!s!^6KEAHX0p^8F z)<@XazkCYSg_cHw#~7u}*Kx9xCvZx9pnW{VVmfkim#lEACN643jN+ZR3?KG=LrPbq z3CY9bL!j02U~=aX*5NiBbmh68FqVI5e|#Q7>Qg#-V?D|Vb1OQ7A2s*m zGr?Bo$~Q|Fppj8~MadbpRk_a{BsU#7ICQ*W<+ev9FjMl`sB_PY7k$|vPlZXSbrG|z z;0O!(^-6=Lp4_hIS0?BMG|{?#GV&%INJel_V^JC|Q})?0QI|{{Mjx#X9Y6Kjybgy1 zHj9$4I;z^r0;e6WYKD1|X>GA?Q;20kMibXHPpQsg)0+>nUar^@IbQ{{4@J~pyqb!f zhLv8-{!DWL8gK>;^9zM)9dSv6vB&XBOS36~zKCd_nC-I5y`;Z(c!mQGwf2Yay}uoTA0Lr`#g&wix-wCMC1Jut=>r}VqV zsaSFISy%C`Eq?UxQVD~9O;#M`iSjUdQf%LoY)?Tz1RyQUluQ2UO$a_|+q|5-xNnXT zlGP$iRyX+0G!va_VHHCfw+lv9C`mTye6B6x^5pgFrgj&R%_x4QF9hG^$kodZ9r-{Y zj_P3+Q*W8t2}#GXvp6Wfy)coz=wjCtMs$QP|oDoK-I(W<5DbZb}Hyd z&9{?-VY!K3$CAMO;&QUD6!yLY9nrV%{?f6=-M!(0TG@lVcldxrhKx!3$Q9t_4^1@KO zMxwH2l=b-9nSuy&o-3YdU+nUUBAAo_|uMfTJ5RE?dQFfl^avaX_3=zh_lI5`(PhJH2O_p;Mv! z%;ZR#F+OSy=16|Uu*lIzD)+FpFRQR#Vb6t~^v3yT(d>oY#ws!!xLFdy`#shq3AWS= zojmUMvbgo(<8v62EsH{MdzQbdC+vM3`Q!Yp4TI~bUL*eGk)KWO0<}gFgtR~3V3t`g zf7P{#aynjbOaUsZK{5b-+6kO?G~Be4gjoek=cq! z`7*$~?sQzv*Ij(Q%)s7*7sULr=*kA*U zuOb6cvA`NzcU1Y)_feL1^cV9P<8=cE=28sAuc=2zZ ze|0b%(1(%pH3uz+4I5VPJ-yyO__4d-!HaHLizSDk=_V8iVs1by@7p};jWV||Z|syU zuQ<_F@8M9v{}}9ob&QgWQo+8K^CqtFod{<+XJS;~jr*gQKu(9zqc=~LR0;(0vL>JM z{mu1jB!JL&+X0jY5l0mw5uM~!V)^@ytfC@V)qFp{1aesQ%|?<{-8EN@Cww1P5zzjd zT5f{tr!$}ugpYkmTXA8px$vQV0yk8La0)x_Hv=&o9GNfDM#P?&!1iGJqZ7ysBZe@L zF6O4LHg~&+HXBK@T$8OQmS=2e;;VpM(T}2jtuFRua z=Vk;SJwj;YHrQd*5qi1yVi+GLDf%2^$CKiD$b6vrs(T% zMLtz{JyvRW^v_>;BUmJsHS|H6`jhYHC&J!LXP*8t^V;Pd+Pe`Ku(sN~P{e9=A8Omo z1bD){cb4d8TX+aFF5aBAwRvT2goV1ag4w9|boy6<1FWR-`v*7~PszY_%_hV0vn1O! zxW9Ksu1*e&-qIo6>Sk`?f9FseJ_1q80~6l+Eb>w-^O}il0YS&#`WQRiR>MO>t!56D zEqG%Sy06N<(s|#K%ApkF3lL4UK6}aJ=i*1zAk{gF!4a^xkNGDpzUNZ$sZsGuCW#Z4 z&icYMOz(@I0TFzjSDej&0n%|$KbZt;>DMDO<7dLz;p`CKy zBjb!Dp^G(_A>n7e{gm2LU(;?v9~ab@|G;j|(#jj$c|#qZHqjOHOhmcQot6d@Z)xPf z=vtomtYji^K%3*wrv+!tH>jwnJT2EUuE71Qp0KxY=kT!VyI~$_PwsZN^ru9k8Y+WT zCC~kz^}A@L0z~Ze)V>XAr!|h1E1-J4u0%ie^QTz5-|^M=1|I5_Q&#xr2d#+it}D!fSVwmx3@=Hcz#`zH3ifS4FE zO(3Nm&zB)ihC+9R0PThQ+qdG>)YPuJh1`ZsF3{!W<#&$*K5RM8Z*mE9TcwEG<4m^H z^~BV}OfB!Jk`d9k&BX}MU*@xjHauCIu1j}dJZOo2=|N$a$T$K1wc5Hmtr|$^@v$og zCZ=!k?w3Ky!B>1v{8;lJ={?yU==Oc*A1Pm=xQIlFmC~N3?+Zsx0j2x)-d;>A#iP=( z2buCz;ewUj)}wiH6w25h+ha`c!^2lA3YvXL@Y91|Ccl=-+i|>C7&+_N_sC-!p)l$N+?drb zkOlH-2iR(5XGFKm1L}lN%N_wYlOsuse~=j$D$`dj!kL+Q)J@+qxN|r{xkI=G=--^b zkp&O^l9Ra6`XpmH7GXKBbr>awt4>Tz4Gu?;G5d8!=+!1D&q#u!dn4*B+lt} zMZGe9yiWI9c>S>c{yp8#Qh7sq*n{PQjL{O|Nq1%UP#f(owRCpz+f*w{UmuVy@M6nl zpuc-a>i*;`hK*-?bZl0CM=+=Bqy12k-b|1Q)Uy9xJEH%-j!F+>4t%cGJ)eTublo>U zci65IvF2Og71`|3e<(_1wEkzaaT;9aMMGeV1HSCt^Rggo`mh2P>-_1sN&Esui;PRi z9aKL=p4|^qi5G8|JkaIeV(o{{t=tz*AHVN$Ul_GNZKLJ0meuXU4Add=8vzd^ei4Ot z?m~lUHLd`lVIwF-SK4~H*V5W58t~g=Zi02z-)_z_hk5-1^NujvgnvZl)e!}| zX~P>ON7{P()l!dgZTcd1lHysT)0D^$`$Qv{oUT}k6+<(L9oed|)RCF<79QIcB?H2r zs5TcLyp*|cN8?79N47_tMtsRr(F7h8@Sgn@>G=?5h`7XG#uigo3dd*jYMv8Pu)qA9Qljg3wlFrS?7!4*8 zYTw(fR9eR+>O>RvMaS>=(>_~*C8?#Oe{LSP8nIF{AS<}NNL%Fl87#CUV3<1tH7TMJ zV1^Qe<53M!X7F8#yDVtIJOVxhpK4XySReXPR(KeIkWV5M1Mg8z)6MNxb1{ne;5xi5 zoQ>w`)>j*MtVf){)=z7xjSR&qIOK~6?@EuHyZitdU(?digN$gW7_?H#N5(j@1nDbZ zuhBU5M_Wb+IH@ z8+^d6irrd=Y4w-p=@@DHhHXq0Y6ZqP@#Rd{mq%XAF#)FU5=#l}#Q= z_?hH5mMBV&yjX^hxCsPtTN&{6+MsPG_0KHUIcD3V7^oQ!Jk{6fRBSO@oVq%X;@-+n*ob%HH}pj!y=39KEM(?u{MX@Tc5De59|Z zPquvPw8SX0dV|0a*EqT_C%dKve)uP?odV$i`V>b^!fzI0#^kY*ro$PsR+6cQqU(FQ zYC*z&olid*{&_YzP{hKfi36N3O|y6mDPG9u~X&F70aB{Sm6WnS6Fh_|1A3qAank0cjNcV~tn(!9 zPtl6(AW3_w+m`GO4q}6MyQ*a4D6Zt9z0}Wn`~JiV2@>y2S=pV;p^=0Z&Aq|fvBFo? z{D;{ec5C6y4Ynsi6^2C9148Upgc)T#$TZHfMMk(DQfFcBFwCJ}2c{XP5pzZJSL4F5 zver5%`|08=Bu_xsP{&UKUN17=x*)$=84~fbT?=$Su&d?bWXD3PvXNTs05#&XGVd!R zcRELH8)IT3%EAMVQ(f)jq{CzXSvN=~iStc7QSL)SG*1wXi3B zMO)V5c9co?pA-o`JmsyozPD+7w|w|te{%{Y6ytYJcJBi}x!%^0kbr<7!EGy%1N?dS zB#7nzTafOOVW!4^C2v{Tf}t%MF~VkE93mMR8CTu>N)zSE@ z1J1Xdn*!IDa3-9urMbCuOde4JB;M%%l#KuHj{@vl%<8z_1{1N7kN3c%D5oY{DQ)uZ FzX43^R?q+d literal 0 HcmV?d00001 diff --git a/doc/html/_me_encoder_motor_8h.html b/doc/html/_me_encoder_motor_8h.html new file mode 100644 index 00000000..4a7480bc --- /dev/null +++ b/doc/html/_me_encoder_motor_8h.html @@ -0,0 +1,228 @@ + + + + + + + +MakeBlock Drive Updated: src/MeEncoderMotor.h File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeEncoderMotor.h File Reference
+
+
+ +

Header for MeEncoderMotor.cpp module. +More...

+
#include <stdbool.h>
+#include "MeConfig.h"
+#include "MePort.h"
+
+Include dependency graph for MeEncoderMotor.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

class  MeEncoderMotor
 Class for Encoder Motor Driver. More...
 
+

Detailed Description

+

Header for MeEncoderMotor.cpp module.

+
Author
MakeBlock
+
Version
V1.0.1
+
Date
2015/11/09
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for Me EncoderMotor device, The Me EncoderMotor inherited the MeSerial class from SoftwareSerial.
+
Method List:
+
    +
  1. void MeEncoderMotor::begin();
  2. +
  3. boolean MeEncoderMotor::reset();
  4. +
  5. boolean MeEncoderMotor::move(float angle, float speed);
  6. +
  7. boolean MeEncoderMotor::moveTo(float angle, float speed);
  8. +
  9. boolean MeEncoderMotor::runTurns(float turns, float speed);
  10. +
  11. boolean MeEncoderMotor::runSpeed(float speed);
  12. +
  13. boolean MeEncoderMotor::runSpeedAndTime(float speed, float time);
  14. +
  15. float MeEncoderMotor::getCurrentSpeed();
  16. +
  17. float MeEncoderMotor::getCurrentPosition();
  18. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan        2015/11/03     1.0.0            Fix minor errors on format
+forfish         2015/11/09     1.0.1            Add description
+
+
+
+ + + + diff --git a/doc/html/_me_encoder_motor_8h.js b/doc/html/_me_encoder_motor_8h.js new file mode 100644 index 00000000..ddc29e67 --- /dev/null +++ b/doc/html/_me_encoder_motor_8h.js @@ -0,0 +1,4 @@ +var _me_encoder_motor_8h = +[ + [ "MeEncoderMotor", "class_me_encoder_motor.html", "class_me_encoder_motor" ] +]; \ No newline at end of file diff --git a/doc/html/_me_encoder_motor_8h__dep__incl.map b/doc/html/_me_encoder_motor_8h__dep__incl.map new file mode 100644 index 00000000..642c468b --- /dev/null +++ b/doc/html/_me_encoder_motor_8h__dep__incl.map @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_encoder_motor_8h__dep__incl.md5 b/doc/html/_me_encoder_motor_8h__dep__incl.md5 new file mode 100644 index 00000000..cdcc51a5 --- /dev/null +++ b/doc/html/_me_encoder_motor_8h__dep__incl.md5 @@ -0,0 +1 @@ +5a3738561e91981bb30edfd6fe448140 \ No newline at end of file diff --git a/doc/html/_me_encoder_motor_8h__dep__incl.png b/doc/html/_me_encoder_motor_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..37fdef4958f298fec9784b1c9bc7709f072e74eb GIT binary patch literal 14224 zcmbWeWl$Vl7d46nf+rB%0zra144&Xla0o8JT?dDdKyY{W;4-)qU~mcU8Wz1G^hLp~`=VWJVE!NI{{%1Dc=z`-F!0_P4dk%3QetH37k zg={P*B@XxW{FmKU6bA?Q7EVU|qZ&BD<+R&ur6Cu zv_O|u4LddEYg??MkQf`jft6j?tmPp^uO1nDnJbyaj7*;PUy5n<)f3b`&_sVVRCt64 z37oIrB0jbo7g2W213bbS8W2E1ONH^wGr{v>;I0JiTs|J zAOAZ{3;utdtEIc{&tTrV*KRp!uR4g}T9z#`PThTycC=9i`g5v@=MMKg=-yhpW&W8; zgRG0=oBsMpCzT&pMvbn(qouc0qTT`BDSj_&_uP{=k^hYVCy3-R!FEntSgiN?HrI^q zi*};@SGB_+h>%~tE9`X6VR86Eh~)T=ZRw=L+n8{d`?)pCiBH@>Yaz?yNKok~3fp;O zXtV;0W8}pJ#)Hr*xbL(bqao8}gFeeP62DveI1soe9+@T*=xY8S428Gh@t^u>lw(rP z39Y|UCBgnQuTOdDkUc)||GgY)688Li=%h0(|HmR)AkRqHn3!X*^Q@n zqz3vC_=1#{@5BJ{Y>F>XK)ut|Oc(v$F3UvW&^J07EBF{iU9jGgsD*wb+?49Z!n>0d zQ*;HbmH8XVSGSct=!@c|9m)?OfVsrHe*a%{-#Rv`ro(HZIcYYpnh3MluD{XoO`OB| zsV%*fsIhJxD^eaw8`iRdUVwPP{dmRH${j?gR{;Y?7@1Lw8bCWv{|44?x@9+V*eZA(vF!u?>TmFYG;*ft;Bbh-G}#-6y*j#AP%*WDL1X+Iv`S8D!;OS~_rZ9I$>`E}iY+|EaT^|D z39F%2Lj+HuY?_0Dmq8fmaAue-PGKxvWRZm4zKWOzc1^!;!ya?R;h5fftT2`BxlWQM zHan7x%D=NpGE?Im)b&S}alcd$Zv^IbYgp3Yc|~Ovx-~@X7noRbvR-r+ASX3K;KF=S z@DV0CGo6TGKZt~KCUHBJ5hA}SDj`HF7O!`%u3A*)6WH0D1!LF|+uf0GrHUeZx}^8a zZBi;33&w%}*gxLhpHNRfRAMxQ-fO{;wI)p7#lPOhT9ZdH>A(5?k^Yb>%w3-v~jQa2OfRV z#jZ}|DUK9Zi-o(F?-VbHBeVEikxBOjrcsVsPd7^Ii)=+QNed`s1LRXa_fDlulZu>{ z=Gt!l;)C7&&B~~$s{BdBUCP%nSoxVA8lUuHTx`=^Rouf8v?z~DecMD+pooD0q|OcK}T32;?Y9V zo{qvIFvla|b2nkpP6Pg73g&=6qq8HRRipMU?`-7GaMh!8(80S5H4aaNBG?x0dF_f( z(WwWv1mJc4bNRSGjY>6@(gq{~oI`?@u_;vsa@16IRMsvqNb|fL_1{j5y(~fjg*x{j zc#3ZBByPFok2~_z-7I%f5UoW!SSS%bF}k>g8@U!aJ~I6tBj8=KGLg+Mv%HFGo=n|8 zH9PlEn}m{*qlyaGTNaR!57nRjO(D}iEA>}G=rB=l^_k?j8#A^oZCb8WP%X3NuDe-eYmekak;cJG6;A6x%_w>8b^T4Z!K2{8BHxzF=A!4^vdnpt)yBcT zNx5nLo43Uf+8xgaxiFOAl~E}+;V90rJbqnR4?$4tWoE*q@$FOA!V$rxg3-slmZr{( z7a#Ww!iUxmtc8)4IZ%t}mgAxrJhz2^JtpF-UV(tXLio?j-i*(qk9BqT;lIjMcr{{T z2-c)HL0@~hOD;-I6HFS(@%^2n-Z!55o6mu)CiiIqe)R>BMKgk(TRCT&q^x^)%hE_E z)15cRn`F0VyI39B4M|CFO?Vn&K$JmEe+x=xPgZ$!?R_@qA1zYdZ{kmqmbNI}OvPIrzu8&)=F zWXMBAf~p!k51ovieLS-|Iyv=O3jda?E29(U&!?rvBj|6DQ=$o-b6Vxp+!ekpab>3qqrmdQu`dO}NE68VIL{)e zBWq32&>^E+C70Mx#;`%c_DaT`-a=Ggewcd#DFq=?N)#IXC84FbJYi-gQupPFR@FXZ~v zGrOQ;k3XF<&h_6}ddN|MG9Z+B(bYb*jF-OQv6& zKoHbq^HCc^9yWqxMEN1`pv>A^hnFA>QYYA3=sLqDn>h$HgD_gKHcBS^(29gEW{wJ- z=+r(qp;*wXhwv4K{Y`pSK?1`bT?oJggVNAbbS-vIO1g_~YzR;2w(}*2 zGnOw?I_F6FqYyEXFU-!rkGlJ7c;1+`U-$whCL8?prHX30g~_2C({5GQe3f{&Njp|% z78frU1++I#1j-;EC!+Nbgjl$x6W4oQ)M^it7dA{#Az#{eUuqB!4Tl0)!t&oF%8>AX zW0I@h9U^Mfiui(D1FCfaPj^u}GY{aPYp1dgA6VsHZ6Z}Ag&UcXpT_;w$EZ9yS;$V( z#6SqQ2Y-EP|B`YMZk}Pi;L|S9Kvd=g_Tz7QMYwo-cXQd+FgG?a#8Y?Y*L{PIY$fx( zvwMJ=Vo0|ldgkE79o(6P$Xghc`-OSN=2ej5WFnrMJ^KdXK&l(y8jgwDVM@|d?@Cdw z57O!8KKJMD7q6Qd(Cl@&)$@KbY_&GY5JEN&vtAXA7cW7K#lnU!S4TY>qN|QsSXt#8 zX0HOo>xA9w@xQREoV4zGTDaguF1@dmsx}{a8uXdSz1pI_+;+ETsx>`theE$tXFF^JD2bu^sm&b zPB7x^!SJlHNBAUD>tF?2;UObDWgJVsHRM(IIpN;xBwZY?toe2BO62=YqJ5s(`Bu@k z$l+s>^aq*Q2jY178l}*FzEDP?;a6_NV z1Y_DZDZX2+oxC!XcZR*w(U`*yCE??$zv;uQf0e);FV{)DcFZ%oXzm0a9nMZ#RO!aGhqnSgb>d{&c|I%E zK<~UiR~I!JEU$A0PPS4enX3Gnugh79#OKTuB`Ro8*?#nxTaneVGhP+P8hHb7prYs4 z5-xMbk~Q&!Lx8=<9DhXrhUP~Qe!8$Ze$BwR&ik~W^2}tOFpqZ_oB}djbzt7{@4xl- zgh*;ESGHB-rkB1=!Y!cipb)^s&p6_gXdKHheN7an@y=#shO%&Wy zIA{0jF24*53AOyGWP63~RSGix?NI$ukb&HHAtQ~BVLk}LyK0MR$w`4cDn}QCQ&ks_ z!!d$=8~*59K}MfqI=(fY;XfL2F@tB_>G2tGhw2Z*4bhCTqY3!aqn*Q{eE~3x zO!rL>Y>$-;7|zLkAzo{Ce(VqF8`TYIaq*hL^pJz}-QBS^5+7t3TlYCWn$np~wHH!+ ziB0z~+lnZcICY4#Ayse+o=$Tk_wQHvX#piJj{9#1czIWh$Dm}JTIKDl`?#p}>qv8J z+FODH+surIs_a21A5_zxFrh_%KSCnE!@*D4mNf($qcPiK>O8dWa%v^YQu(|DQNU0L z%YA&j9~c`J&>j0gQyBu@o)LeclmO%rz5bHUg1ytTEC0c~J_UV9!gCcLiHTgLO5m)p ztLjBd6h%=Bsi$1%j~~x`JWd6GCMc@|`RyOR$w{5N6W0+Vej%?hB z^YHFi#H6ycd|G9>JzMzzk{(MR{YA|*LTHxAXFbW+JzR3@QIl@&AZP8}PoO2zu)$@x zWGHD5j2rccu_04sp6mFO{-I-yq|?i>5D6L|PBov&hHw89vg`7dy%hAMh#WFFTH zK&GQsD`?pCgZCPR#(Xu%gfwiLOg|0OJyJ|PVcUt3y_i1ph-A>_-gFqj*JH#Dgx;Uq z3UQPv@jQdC8eb5FNkRm%WEd2-(=e&13Z#Ku7=t#|I#l$n!<2{eOw@!0>YeTZI%C?S z=L!xmLiPa#vthlW3A_w;c>fYa*qLL}$CusmE3m-a_?I>Y6J_(O*3h3QGem2Ax%B%j zY|U{G_f-?I*4m*uPdIY{kn+OBj0Cl)l7imAz~i+n4B;Kc43ZAC@Z)5u0d;rsxz=BH zAp)bdg*;E1Yi@AiNrHcT)D`_W){NFZC}0i^-JHqb_4;B%%RwD>C!bYh@?SlE8A4mc zbq~+GaS1kXxaG1Rm8NAzuAo_9rRekE=S)!>ZF?0=e9YvaKCUh+hA$ybi})Ouc?p)E+cYbl`a0`zF+?oI&%md{AWeE4UXYLb&kSpM?MkvJQzNBJ zKJpq4$KpPk7xnh5vl+m`u35FXs8ed=f5P3$q!)3-$t0vUB0po3K$&eb83yLJdw)~N z^?feQ2IeUpBpc{{nUhCpw8xsi0A{uy*qdBk>D&hHc|rRyy{nzPF}0 z;SHvI!t!QyeC@7gtW=$dkB!xy;f}RS*)SGi`>i(7d4f}iW8hzaUc*bzGNo-&%KRe& za2-y^K0O<;;Lg{Fs|2_s2)vwiS`?!>HoeVWM(zcx7_VLvF+Lkys9`^0|=gqH1l`U32s!01j^eQ?$^U>T=s+vc z(&}XqlhM`GzXJ-c^^`|ov~tIyRYOUElg@Nv-?j-aBh#rr&2bhK-klM5gF+$kGZX9T ztmjVC(U~&4^CWlvZQ`hZ0opU>?yDu!HX_L>t5CNYtr7erKJX5$eZuq#+lCdw~);1#>dMPUaO+mgrh`Z z!;;73<4RFn38VD65|USNr686I#^4MyV;*coG|(A}8fpTafa_|(4%f&lqW$G|T(6cB zD(5z4Zmg`Xl-8CuN005bjr{Q31$!r+*_|ZG=qya|^f!2Stz!ZGm-dMw~pF^}OqGgd6`%w#mt}dSJz!R1n*Y5Y2ckoaMj@T~IfM)=rxu2lyOQHj898!>5 zI03B*cA~K*pc&GH^Dr!+xL=$$-3sE)zaoHitwHhYG79Z5djvcvE1_N=4dIgcQ> z3ZA=6FQ;8pN+FH$Wi%T>79-)CQBVpqWvT}M9UJF#ME^ka#>_F-rb~09E1viMGht{n zVfvzA`^d9Kxz>eC*Jx6sU&j3mRFBvs_m0%s9q43)NpNnyW7E-qDuDU;RKM)>RaCqo|v^3P)i|ygTm!{q{89K4+!dYAn@exjhpn`?sa$RolQbQh?EWs z>#G4X3&id0L}7#GyD8@yYp%t?QT#5*ibW_cmo#8`AxWu104c^(0UMMWUmI7u`qZ96N`33jb_$eSGG!Yet6dH9-lo`jRsT=c_K8_70ExKnS=3LO@9n z26{Pf9;-_`V(r8bZ-e)^B9zQTw}v{d0!2T|6a0yTUjDQ(61|CtviKYsdBuPxK|Fsg z9)uHDVMn)b;6p$)g?ZLRwUPvA^Q!pJ z*U0`WjTzI0nh+Iw<7md2zi)b=oeK&%&5!?t6Jj$S;b-wIQ>F@IQ)4Yqysk-YsTmHS zvh(C8K5MX*p_&2jn5>aho+qK;4kxXKf)ySpU>A4)34nH#vQ*RXGEqSy^%^vd_T3|H zg4?f5l2YUc8-G`U{>M&5#ca;vn2SxTkW5e!yRQ<|aAMe>11r?VHF&I6AD?iT&UKdY z+YK_hzXyiA_7h_^-30`D4mR2jcbVmM>E~LI@ne^!|JDCkSxWb?DA=SV=tU>HV2Q!& z51ND%Li0t|EVWAYch+N|3sZVKTgsXfucf9ha(-gM?WZ8T6(Jo5DB8gXqC z$n0coMi%LE)!i@!t7CWvFR$HUEfx_z<$mk;A5Oz@xTIUQb_Ld9ehmA#t=AXdy7S9k z1(|O(k)|;dmkFiOxqx!c5m9lkX8iS=zoT3R5LTQGKEt-|5?O3M23vA{s+QWEZ4wmd5kkza=G9$EyFXR|zgA9?w zh-mIY=^%}+7Wb(Vs4YJm>wfcd4EJR!x@{jTm3DLE^r+DIcNeBSo6-bJsqDwM!~$I!v85&utfcTBG7F z<6s&wwAf6};j)q}x`gvILa|UCUbv*Sb8x2{UIR;eP`SR4E&nP{Ba2b1yI96yq(EWK zx}Cyd8Smy3MutxPl#bLAWkO3(x$nw35tAHEj4)Dq)EQ#BYGPR43*%uO~+O z1z~~JIpzTz90A{REx_!!;M8`5;Tue}{4zs=M#5rhY1z0tzjici ze}Dl`WNERorF!ev#fz~b)*q3kxe&DxS-kWwYq9J7;`$Xdbj0=2VToNm^#8--#Ccts zM=TGOPNuz*7FU3nOakmYt`d()wt@UjkP>5xn(l7SNeV9$Sz17?MFm<|ud()NQ=plQrjarF7 zA^or8sXglJ?nI;;(J2^Td&F{RfW&{Wz|(1zZ6=y88qgeU+X@CV^5H50VbXn&OwNnxkA*-X?XDu2cw zLD71$N-!zDCOeCy|iAN zT=xQx0nRUmbe&-Qh8eXbcBcj?PrD6tud~T^6U{nGAm8bqfhxgBI$J~=cQZY`IF6DT z)Vnp5|L6@LDLH-b!aGv_+8@sN zBUZv3I~42gpNeueHO?`Y1QLtd`yJl_00%t@uKbg9BePWQ!gEvn2Di=G5MdEuBd}X9 zJfI)lyBRLESC7{Bktr1b5ecS{26f}Cz!Y2Y8#xPxhX1kFuMwkBK*7W-4IE& z?8ON4kvUH80e!M438)faQV4_mJ`bJIHKjy^`cq+NqV;x-bOsy#isB4np0ewd-NP$L zy3wEi03GLl&8!FPVJY{g$=-6Y&oJRGlje7N{6H+m=Y1rEjRF#!0T2Nu^38rOqUvsq z-f?}i+IXI&lf%|H|DgYxpJS>QZkgVymHvV_IvT3OBBV^ZJ1U&Ny<(6ddpa zQkmu(5uT^df!Pw0Z2rLHWI{QrzRlF5g)~f4QWW3A=l{2?>*&=b5)@)SS|ugcC*cHW zanhNR$ptp3%56F4=NH}hxhnu~a8c3Zo1jZHDsdCFU{b&fkdK;;GIJ03N0iITxBC42 z^4f5$*EmWFd9uDctClog1pn9zaZQ^{b*V2YlCZS0xf)A8YcTV6Qq8daA&@ES3d73M z$32Pe+K(IcI@U9~+l;j2_`J9+w`A$C`2>fLfU?x6B$L1KOoRzMo2;bA@*Ch(1B4A( zl`Gf(V{kvoS#j;>JY^l25oz9zlHKA@j1c+OYz4Y;Ku;uOpUYjeO-al%VyK(b1BfU` z6|la$1lI|ci%umJ|4Z4Z>v9qs*As#fmG!>ueEYpq!&V~o2erAL36cpiNxa9Px6?x* z9K~g@(<29nJuc{~@$3%Rvjzb8EC3QAoTZ*Ok=-uX;8h^$OMR3~3kj!I@qBqm$=hD6 zAJfY%&p|H~)5|xIUzMnLwPI0Zg6WAPHzrBSFBd))(Qe_=iIbZX5?#Sew0u5UX3wz; zfYG>__o{QO{aWYgyQ0k5bb=$0W)kHl!0iw{Jm?CTCeM=)C3mq{5lHeXnj5-gB>k~m zR%cQII!FW<&*Jjj9u!tTHNWiG$Em$k*UgHB(2lM~6W6LFVI?OfiL;BfM$EBSHBxM5 zJ`^!S;rs)y+^Ce!OcA!{!a?tV@8#0HE1FFKP7F7l0F>lXx^tB2zHFTg;Pr>y+^zI79GOMO>CtMuKEL@|P%bsB%^pU%D;Y-DcnJ%*WOm zfSA|_{}$#*E#WmuPHARK>Tt=?=G1tN`LP8J{Mtg*asPDc+Ml%{+CB|pG>LXM(zuyo zGb8w?^31m#<@{3pZ$Kpz!~jYbhd~%i>PK)QXNV$cy}?~;+qiPO5$RYXtrTtaKVsEs z-5)DovImn<2vs5Gum_Pa{q^rHwhp!a5kxQQNiC{&Rl>L|w_8Je`CgfEOEKgfy)`qL zzU$AVp=B*;D>Sb&$mIN(xnbdVTyc}+tg~p?2zVt=dnmKToG+OB(a(v{ELpo*$LZ3@ ztVBwkow)wiW7528SWF|ukpx%(cH+f*$v`rY!J_V%-t8!Kv%)P47qp5Psd;r4;HUMa zZzED>w61U&*5XW}C{_}@#lGenK7-q5sp$v{Nuo(P$6BL$E2HLrXTwp4Ir$%${^;N))e2`G zKoq9RspB82EH?;5J?ccf#m-4QoJ?Q{Tgq;KR5u9o11Bt8m^#x*EdV*EA|)am`KD$hx!cExf~=3 z?;zSZ{|2JgM8JMFB?(6J01Q=-ES5<5Y_Th2RKcZ!YYb})=@Mp4gN?p71>NL<%SQ+G z{>z}TbWoQt*;sx&P;EqGVlhIQoB1{@Bq%z+h*d-(o|KsD?xQ-Mh&pEMK+&_bK$~Jc z@Do|NWbp(i*RES~YSM;vx7aDCv?PkczH!?3wfT~YuEN!wU}-K(9svDLe1Z?j$4fTa z5=<^0d~K<^+#TH%TOQ6ha*@>nO9H@sI?FF=62DBuSeC9HPayd>sE$tR@M5P znHOrJ^bVPh=I&Gj z{P$JdZEhX0ntzjl0l@*w z1H>97eTJ4YG#C61{0UQxBJPJLVa$dv#tlE&OB(EWqa3QrDJGgusI0|KbqB`E7{&G- zYg@8Hi7LYnI0ag_T{;tX7t)C8;yKK{hteC17IVTFJh{Ru-^AfasW?2N&IKkjY|eKd zJT>n&T#|y z%LgOF*F?SL>P2}q<@4(hp|!itv9_cy3>pTh&lLz*Vvl6k`WsY7pWwGo&;JJBbE`ir z{g+TA$Hbm4i=$!SOo{(Z;^nxv4wPWfpL{bzWc1n9zf76cM3!T#_+t1gtE{)lK)A~e z(<|;TfF7XK&aebUG(IMo5lL=r>3n>lAgPp-;rT%|B}qv_GdJ#6aC9MN1bhO+@~Rn% zc0knidj-}5^lIh{!4h(_1lDQXjrGnQXV^o@zVZUG`z@wfZOf!^Lt>PrSvnqcoW0a>1$X0!fJiHq0?k=>jJV1fsHeZj}fmk=$)#B|K^7io?PiS0&y z$gnDsWn?|9<$&MQ=q=pwT24R_Xt+gV?i9umi%0$Yy6-^6+y^CBZZ9r!eZ!LhStwa- z!z%@YRM+JBFHvXVo|!VYiVZ}i4jQlOQYca&84T_9yJlXrM}%KCxI}h10fgvpi3+YX z%cIAR5O`QNt6lf@8O7zYTGc0d)=r<(a(A$V56q*RgyjR&2C5r5=jBHyDP5K;(Q+L0 z>jx9U4Xw`&{fcH3lD|+Hbez*k{$uIm_vJlJr0FN+JxYOu;oK=!Tm|#hyxb{{^k%qUyo1kGko90w8C5vn8MPv_MtO5+JwCBA0P&=6z@rnC^66zA0j6JXlHY zjuU+D;_Y3Nn=}XgGKu$iSuN_$l9s(*H8PWj^)r1iFpGS~$Qg(#ysoP+<>iECCQdN<t5>$Sw~^gD z@(A}?czxGf(eDpOj;rW+1nv5;;w9`g+@CTO(s;;N&OK+#v^f`tADhSbnVT6`+>2Sk zPoj561mro#@q4xyMrJy^Hgn^j!(Ekj+D!+i7_#mnXPxJD%yi~f$KLt1Sc}#(Zt^S% z?*oMwZBXzgK#h_dn+3DaY&htL{!m-bRxryhCjNT)bq!^Iw(`jspz#f>O$(wG?2Y`~ zlZ)IKOGv)chEd&i=|!kuWY{h)-CR<6q{=*bC2f;UUtUQL`gbEx->|Ufvg@pZt|^C| zlJE_+5n(-#$j-74r6yf^Z!xRq?T|1<(I90=^{OE+v>TMhWN43bxdKV=o(IHUy%x8S z6d#wr8@*FAGno+En2L&ulc{#8_Fitrr*T|C^_}_SUu>;LK%F&3hKQeUjs|_f5m@K^ z7-O4ba}R7n)HTG~A+MyQOvkRRqNC$=7fU1e)z~gy_d0B~6JJ*io1m9$@P}fSu!6fg z?+5fxCp|GKBk#vHPZ_V}7OQz#9vzlq;!}Z#Ry8yQc|Zb@Qo_^0ZBE})%!nE1jAWl!zr9} zJL)nOmxqgea;y?pZoEr2C;@?;h$%z)gNnMg@Uw85EzS`{){ZPFHn%Q{ymdF6uV`W? zx>vp)c6gDS>oa$6PXFOv`n!|fqrA}Ux*tj&|7H~UK1s-W>Si05MS$CUGfJMmO!)Mt zO2EM_3wA)XAK!?HiK*+kTksuIm*JPW$lZMV%F&%~^Lm5*jYf4nyWgYtVN(8|gN3@% zxsZ2-N?9uncFWDFxpv}cd;Kx*mVB<3B~~LNhY~g+Sr0a=VXXM>i7tn7rXZ7f^8zyn zX}tXHb1tzksR5*$Bul#t)WE+P_G9H;uKlrJ+0kCrHPrZAJa4mM0eY$$jD#1Fen`I{ zIrM#evq^krF-P({x}i=n{u7#}Pc<)i$BwLWu-~CC&j?pa#rOUM+x<3o%kNF+(Y(l- zKQs$SDFa1j;?fGCXAe`@ucnL6tX6EK{7&C9g|dR^L#N7YT2w^LeVV&jLCby9mtj7x zkAq=;#7ZtI(z2xL(QCz(PvA}SJvS&>@N-K)q^%I*`+yqmO)Lr8PYfZA)`(_t3nARU46XJ{oKOp|&pO_8^cI;4lF~ps%#C)Mr`QMa3&*vMytzxRltj{dF=5!ZQudZ|6{XPYgW1J^3y4#B!%cG^WxY-~c5-1GZRcVji^1=5`Car1=y z%A)YBTi&%*-qncbWF-(YAsgb0629y5 z8@qSU{{o@kHW!)TuW1YNZiqXE>Fiv7iq5eTTRn(*6j`Xjeci1UR2ngr&0(M;%pOr+ z;WQeVD3?Z9@`}B$ZaF4#gO3SA7q{uovjaov@l!(m~K?Jt{bIAo{vdNScnDGILR!`0Yy_G^%4~LJ-qTEkH+`(CfZ5co@Kf9 zlzpO^b}^tZez6B^Ogz*adNHq5&y!FoYaQrVCXgk->_|2x6+3oSAKR|9HFYTkEbgWY z<>F@=pQF6uXM^*k9dd8inlf|plSiwZT3mIQjVS;NtJ%puKv)Y^R>tJ7Kh+t#0x!aN z_N9ssdh6E{26>fDxHD{x)7JQ`hDan^irE;v z1Xom2CLKoBKmIL)=*C;65$+zpW9FS1^J!fi;V$%Ecrvx{`}AmA_318CRFG$7RtO+w zv##5av9YVBt^D)_Uv?4ALjsi2d^hDEKDsP0|0Y4+)$75K1^K@V@)eF2SqY1)bj=SD z7k@=-?R_r4-{@3d66KYbe!6SaO=48@df)%4ZlEl_B@TFX=Z8EkKWm(K@d!}PRRNd+ zE#uY1&s!G2#d6H=w#uIt@Vukq;HQa1`+!3DI%a}LJLqS~kM_w}kvgK+F)@}upWoN{ zcl=+yGsSJ=cmTX3rC>^`f_&6|cho2rJ)y38fGK$MCvJfi5a~CpDG+_jch;r53WQs}mX?I$WaDu6nEYVA)uHc{anf=YZs{^V-iF~Pad3YUI+ s@iBWd!IWX)FHr0Ce>|uspRlc)q9d@cUPl41*ulw2D2i8z8h-tM015a(L;wH) literal 0 HcmV?d00001 diff --git a/doc/html/_me_encoder_motor_8h__incl.map b/doc/html/_me_encoder_motor_8h__incl.map new file mode 100644 index 00000000..3782708d --- /dev/null +++ b/doc/html/_me_encoder_motor_8h__incl.map @@ -0,0 +1,44 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_encoder_motor_8h__incl.md5 b/doc/html/_me_encoder_motor_8h__incl.md5 new file mode 100644 index 00000000..fa1e448e --- /dev/null +++ b/doc/html/_me_encoder_motor_8h__incl.md5 @@ -0,0 +1 @@ +a1df10e2d47a8fe0bb3cc531c8ae44cb \ No newline at end of file diff --git a/doc/html/_me_encoder_motor_8h__incl.png b/doc/html/_me_encoder_motor_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..41612f58ddf815e893a5ea17ff89e0ec3c9ed8b9 GIT binary patch literal 40193 zcmbTd1yEd3(=Cca&=A~12oMOagD1h=-GjSBa0tP|V8JaUxVt+cxVsH*!QJhiA^HCQ zzxTdZuj&m|%+%DGv-j@Zd-dwoeL@xF#4%8bQDIG;$dK56;P0XZ}!R0 zyn#2QkJ92IFpto`AI-TjFfcD+Bt_ngS(VPw(~8nsPjy3C1>Ao)+{p(LlpXEr@eTaA7p|KG2kKSqkk&#{RxPq&8C zNnDVK?mxf$^e|^t+DyAc`U?8$$bPc}1H82l*hcUMfPD-J7vWUI(u75TmvLR5#*1iH zqtfP!k0~}ap}aw0C3&HHj?$JJ%L!KK6(T{Z&s|`!|GnsB=;NQh1^#8}t1yKAo1jE1 zaG!tIMEfX~zkV7S_;;W2QSv`OxDoCA7Sh9_QD)HI=(7NEZ?0eL5)4xIJ>=HV4{pcp z6cB}8iK?qO0V^WXm5hjnZ@*tXeR1_k|I9i30~?`!aJcT%tVM!?#ekvFS>q_4#$nUS z2S%R_372Kwwb0Vm&&kmB+^-hUb27?wyW#6B_8j{Dy*1zJa&xBZV0ONA_FXF`Ns8V~ z0(!~~>C@zlPdV`9M6!@c@JUl{?l*_X`p^ZoWrrSo1W6t|^-nLhb}Pzvo$-{t>$f)9 ztao-_J`H=A4XiDTfQx~UOBHmM)AL8~>sf8vpFt-N&xMD@R%R;Cpq*1oZ8O! zd~fc_k$m%@=cFHZ`*}J8#&e1n$qqn{IXrYZ=x%yJ^coq4^R3P8%^CUqt#SVC~wzDO4aVCbpAsW&ns@M<5IJ^TkkZRi{#}-is~={ zuhW=-!~=m}&4M*=Z`Dc7y=jkq1$5+|Wr>`7k!9lL zq?i3$_+)1C=a*WcRl}ThJb1N~_m3hOy_cPJBg;;h@`gGMn=ZBm=~lBpn@ayq3$qy5 zL#1WANF4hBzMt)q)eenTZw}a%zGgG!ntHhflp?b%rMWJf z?eFVo3QaFY@TNSOStBRk{?#kQAEwy^s+{iOB!dSKEK**T>@kU|I>`6Zx3x}R4de|% zi3sEpdn$XY(zO?s*D{BmoS986Jj5+SRK$2qZt&{B--*ipwY?s_tvdR-fcP9>rnI>~ z^T@FJ@I!Em99uiJY5jJoCi{wJIMBrsNpk=P(ilOSmCt0A_&<68f_T%OiHq}{^_GL_RALp0DkuqEUDMnl4mF3++IJUrC2 zg}eBz8C6i062vF`6Hi)K&f>yGnitd`?$i_B*PN3T(_fNgQ!17w3$?Q`$CwHTI~x0S z^o25izokJjfrAEawi0EdZNq(G%`ZzYGEbN#PF2$|C>$O4MNi)Ze z9xd<)l<#vrc?%w{cTgRz@$z25p2AlB{(%hG;NQi9?NU7OS2PN%V!F@QZmY-lv-2vS za2t$-c>no5Fg|b`-lQ%WSQCLB>+^oGDVh;8b}A*XtKF#WPDLXO!PC@5(>waqvDh;I zn{rl^1$}CWgbIW)>B7kmADmmMiAnY>d(7PVoWqj}ulDT}$t}!QigHq*5H*{R=*RlQ z7k~XR`U4a*U&E;mwivO=5?__`EG^yZtx88!`ii7kRW-Ii76%AqC|;|xq!~~SzfQiJ zQzrJB&O3dYFK)6TYv+5Btf<%Vw=!t;n4i+3hI3740~F2XM$A)CYgx@WJ+|jrA8_j0 z()JfLUw{%OhAIgD?T`}6lXE1dPX5UT4z3}kg@L;TU5xn0e2#b>&i<*%`1xPc`et_Q zLu^Lz$oy$Cw=R?65B~p#20LfoKusO}YIOZJ`Iy9j!f7b4xQrxYsEW?WBS@EoM^YCkuzoR}7kRB%i>yS&J!q_{L}-lcqh zX6YwtA{_sBV8m0qQ!LRm`6sW)f(8pVkr%Z$UkYei+YLfVT=uOJ3!<3=4T0^AW=_Ne zEF~Vy`j9wqH6{{sNb=9Z(I22u_PGSZB~?)@G9=MrXs^MMFBcdtk~iT@R=vIIws|k| z)ZGn}ZSB~&D?!c7tM%V1MP#8rHE^soo*OQYQgi!$>L+aVwup5{gN=og6F-N($S2a1 z=lRwth+>F0l6q`0%KEG${AC$I17+3!z12HyabiOZ7K zg(NFG@XZ+pk!T|hHTTlkNoIL#P0T()DN+g$|Dpx+bau2~v-t$_oxc7+aJwy z>g`b`sNGblCtDj5C!HdKL|dQ48^`#v?N~oyQ@~RU_OS4o!$M!7NljxBjH9m&%46^C zQCBx)Y@@}I)x#$w;N_rAX^QjfKQohn4v3oOdW(%cOX?dPuglF0VAkXAe!zDr zYFAoVo)4t?NemqWnSb$eOdH^l#skT2DTh_-pxf@Q2zAcu?q_xFX(P*7b9D=xsn5 zn@Nfly*O#x`KXQFpOnHeRKo?S(Lqbgpk>3*O{;Jows^dg+Bx^i!^p>EItguW(E z$W6=6A8UOg1vy8Gf^IX|{Kj8Zq$_ottwlKaRNR0BoT9vOab03G`PM7aI-bOz%I{Rk zq48D4kB+>Yu7It`l|vAp?RxAvlKOPl{@V^>Yjj}v0D)yb5N+bI`JX#uSw8NF8oI=% zfWZq5>0lnRq3SjSnBaO<3n9FhqwDFtrtZ&YrVRTu=;B~3Eg77*kb=)ic(Q-5aCZ<} zf(wev#FaL<2-XbT$l3BzK+(ZC7DCyM`Q85x;aD2LFnSV|;x3ehsZ1V94t;l7b{twz zbXpfd_cxB7>;+)O{Jtw=H?>RWftBk9$Hh_?-=L+tDhk41^=+YTF_;M!2r*BK$9>wM zJj=5Ml&efWZJVP7<}f2d+T7KP-H_FAlwPnm&v-jn z{WkX@IHvjHFAd2SQ$#LYP!J?)gc9toFUiDMC|A`a*#as%tmw!QL=VPPVSzeW&eliv z4$BZ+QS$3YOS2gY;2d>=v3NKdPy4r~k5yE=3a!*U6eq5qfYEvkIDJGo1!E7@&wZ>@ z9$L1L((}XTi#zbGzewhIQ!L9bP&jQJH=y#dWJpwCpC)?^!?c)m<+m;QrAK02PpVd0 z>;65K#(N5YcV{lF5MM;_oGrD|3G;PvFFc~HrO8{o@VbLaa-?SehgklS}G-bqQoBv~y-UdfEbj! zMJqBU9ZTD{AU2t$xCUTe-rY!b-GjITyB-;sYPYCDct5Ie-q;#~w@&!B781VBj{^9$ zSZH}c)*Mrs=-~RNh_$Y%IqmK4*4+GGniM?>rFCE}RigAg%EB_YI4QFAoZr>(Z%KV> znbvE$hbk`2l_F$RiR>KA=!cSkgU7qWKjxNe;uVa!RoJG9X-B9-zPnry=(Jb-pJo39 zg1T7t4iZH=(`kv-JD$ueAF@Z{am30yrhd1yHo zWsvLKA6GPsZdZh&nW$H9I5Rxi<{jIcRWmfRncaU&{ROZMW3X10`Kax|LuH;5df<6G zKK0|`2|S={W@#7nkhDVY07QSRx>YX~uwy)@CA? z2#oq$bxSL&?!6Lkco(TkJMFP{P1{s>MUq`3o7X{MsX!E+;*KR_F z^ES2Fb#*`50#csmUgQnA=h}tFcIgDx=xzw3*gZ9s3l+BXv;Bod?VDHU)?{Fm$y5j{x|Jz~257~F;H1>2f6yD1*Q7HUp`*b?L4QC~1Z$;qn< z&2uLk?-qj_zYec}ZSo^$w*6^U?i=KP=s5~SgN~2G0+)NoOTnu*-aKk~1J>`l8`G!9 zyA_D~too1g(yexPS6y{)i7(s|u}EVuu8e?t3~C=xfd9@Nof(?8z7aEWXCJdE%G$Pa zUpqLw{$mH5wQ9cihd%M+yn~-G9t$=8i3aqCt%E|i|CU1jwCJoQd~!oF7l%gMOV3%X zt=G$WEL{{aMEc3*C*J>3Bw=a5)MvflJrAyj#4o!W9vfEbQySIm4n|Xqng<27&NwQ1 z2J9~{Q~5?LY)L$QrVkq_b_WH5Jo?hmTa$^=l=0MBZ<|T|{s#ptKDz(U&4r;ip95~* zTRALvJ0z|ydAe6Q+_F23F}$Gheq#JMe8I@6`{tWBN1Sx?s4CaFTk`zo_oaK#h*5cU z`Kc;XxS%fLIQgaH%dT7p!9SYhvRTcPvwwpB(ORSgfCz2Z9*8RG5AW_fA@|!a+0{8S zn{jbzSvYxUH8nC%Z|@4+#weo7%Z3L6`SHxX9*vO~ub(c8xpY?ZPx`f(e=`lpgvwe< zATH8Ig@XL@=jLtRngC;DT!#z3#j$8*+|+5x`*je>n+bKVvveRx zN~E8;(I<;ob?7dM1f?bA_7zjA8jAA{Ah@E3-xmCDRPjC&KsOIr(XpNhPO_5P!00K? zZ+VlQ#q~_K;yeTPi7-V4Qnz0V#L{21XFkyQ><)14Q=}9hj1}i-Q3&`3M|f_A|(rF$G}XeYM>p3io_(q z60AVJTc4;c|56EDAa~%02H{x*U}Dg-`m^Mh)(-t%%z@YMaCO$?7}>>d16Qek!CYea z?~w{o0@$UCLyGXbB$CqAJErIhH9Q$8I8#MFNjXH(O6`wAK>x8ZEz4sgO1^bihI$qXi}P#5TPVPqUuTCLMTx8bhwhI3GOPN z6*9qG$!^SuPpJNiO+07Oy8leB`x zah;tHsx`=&T!uncP!g1A8?xAC+v!%t8!dpQz!iIMNhRAp1tiQ`=F+;;?R*Jr50fe% zsvh<{#;^3ZGp_v7TlLr;&gXEzzJlgd`LvwFe8;qcfqvrA0-Z|s&g7%)x2<=K9%dg!c04|_}+Nv)PA2Yf5x3? zS50*x<{QjUG!i*0{2u#L;w_=+!NZDZ7`{Nw%9>fxS@Befk<@amp^VEFiUMj=$mr*- zz8qk6Kj@S*$Di1fJ-Pj>qpS`S&)AdQ|Dt`-qf(vUdI()M;?(6xxovg$cSsS}%XfBm zx?#RqEOn>S{bcPlK($Ay$Ns^b>|jUeh-EJiikO5FssjR^>~=Rs`jyH}uXvr~@`&1b zb%b#JM;Cqgz((1{Sxnv)+%7vO`;n7M=4)yBrnxOEuM<8=zvT;QWfB34^lgfs1EJf2 z<%_UZ8@qc?8x4+@o`~Cale^PiJlEmL?UqHSA6?-j2`xJXg>&3)dM*KxhYYLs{c$oT zNEC=PaLhaqyOED#r?!_z2D0H8zQQ!ZG^2Z-ttFa(H@L5oP7QG=TYK-8c_$&;Wxy7P_2!t-^`w#H3D{u7Xmv`8Sz-m zw>Wi1tqcs06?Tc?a^swAtUO zcKNQ$sS;M$T`Fo&X#$CkhoM05Cm#`ywkq6{~<4$ z-o2cO??j6%i}-uu!T8X~)8IZmCqWs*8i63?M?f|Qm&?eZHB~jP1;~1fGcE;eEeU+- zeF>7?aHX*Q_QX@j9D0B@c0sETJ@Y>AZP#T753=tnS~FR`Sv=C&fAr+@wA*olmEgJ_ zN1C2i)4+JQs+Mk$&F?=NMPEC9cR4q}<$VOoK zSH<4SX&XQ$QxJb_<=(eFH(eWOPei>#Gyk1u=bJY0POSYk$vq2P2|@&-Edy7JVAR4e zRGJIpbDv5>+oj(-8BEiUyLg0i1@Z~78(a3hv4P~WjHZg=m?p?34o+3=4ZbDuKj! zP<2toHP$sCf9rps(!feEL-C17!f2wqhFV~Rj=Q(YZmlbDGj;pOkHn0Tsa6%f-t?g% z0WLQ#zG7=~d@me2)niLHrlscC;w2)=4clJyR^+eB8!}|!XdheIKV#&iD2g4lI-u~c zixmb|IpaEYyNvJaV~fWL=IO0?ItO_%>a#SX-&HlI1*VYHKdB;56%DcM7-H{_`40BA zqY~ZUwB@&CQ-k?`VB`)~-0AOtZmsl77K&wV;EpJldANO~CGN=!>pWTTKbPbmFW1v~ zjV|ZD3+`}t+0YRp+!&M$7j)2R(;vK&w5j(li%5!S@ zb}z`^lw=#~?wwyj-*i}c(n=i1+`CSxlD~eu^I1XnWLnJ|LjyF!Ot%v}_94tPPNalx z-a5+_QqQ-4Rgyrc=!M%alarj^jiWo6l>`KP z1#?tH(n^)p!X&qA5HZD5Jt~C1p3}U4*u}Y9;dR-iSu?9U;_){6!j2?0g>mD)`TJNL zN!r25qt`s#EL98AZ$pq=j*M+@K%x%flPj~&Kl4k2`*!#1`GTc z{Gjz=>+*h~ya-6^X=IiO;phkR5nQ|6yWr!omGpt29B?BEo6B)k(%E?jbCuD)KO5zQ zKU~p`d`dovA=pxx*ovT_O;US$djc_@vqR)na^N!z=&ptR4yTk~m&O<3fHu@iv{W&} zL(_A}zomc#&eU$V5R=}QAtwx1Mn+r64{z}v0F8&2!t4%Sn<)Gq?$R=ZW@Tdp08AK* z6l!jZ`f7K#kbuSJD9TC{Dc_~=*@(_pTE4U*wo#z*#+9_2W$xd*Pa=xzC$w;C)SUmPjBVU`q@ z(IPY2`xol%cdoR8X41B=>5?d5Y20mB{@kK#4VW+PlarHz>0;SH1teaLWg*P<$0k3< zQ}vxA*0!{&bb&*+-V9i|CuFQTC_GSRDDnz~Pl#32?v9X&n8{i5-4lPPTph`)HBOMJ z<~z~47_~QQqDYHOMU*}>@6dPRKLT9TNyj{2?nsSjoqQlX5fqq{n5uu}rh*l zNitmO4mc^#+4nIl+q>1k%wZgKSPULcO#!lMEAr{$soKp{dG$bBBD@zqVXzakSTpj( zG@uV-ZQgTju7m9~iBB-Nhv3QGw)TE%lv)U1V~ffgK)yrcg=bm;_>ug|$);ZQ+?hY= zBE>#pAY!fUC$T%{9Cfm{9WPx+k|hh7k=+lRPcz|aXclz6V?|0vSJbxW&(!*e+PM8+ zEGM)@BHiA`LFY>e)z*bq!Er5yQz;Si38o3^9i;Nt8O?|brw;>vW zv8H8f&5#_0+)E2gmqsf|MN5p6F-egSK*JyoqbjZVM`VInQ!>bL%Y*lSrU!om;psaY=c3sqN9UPf5ip^UK zf4=*{$8(Lried*{fG2ylma)&#pT{hD^h3{VHQq&!{T5V(KY)<7wTG=<%)Bd!)3@4O z+8ih@E_>YGPQ7Dt!-Dmd?JWNI@-k*n`U$E3ylj10*CE~;{?!w^Kir%x*X76KzR8;0 z&{aIO99})0qjsZWn8U2SY&jl4@%*N-d6z<+;G za&hyJ7D#phT8F6Dt+6sx;gEed3=PpMJ)y}n4wjl+V1XO$wFb@e z(|X|*?~_Q2PxzQ0Xzl&^=Ic-O)6#Sx>76G~s(~5^%+_7}+>-f1{b~fMv1(ubz_T+9 zNCC$2i5W%7AkFp>&49T6Vz8ywg)LV*>5SfHH`KK2!SI_~p>FV1#=M%}p?j>GVYBq`~kY!MVc2-;V4 zuzdxYy)I$~)O&pJw30)LK*;nRf7f|-c9WelRmT&t_{i_?pjrTF;nTQG@CQWJ@?zSG z^er(;x$Yz+Yvd+FduBN+^D1j1$7zW-R%n_VO3XnxAvo#kCE6StD1e8~Cuki)l1y8a1BJ zWI4x+*bA&l3IKIiCb_NNHWiKEY)IV_T3pjP8v2vZhw?^xuxhHk;eZaK#ma$|Iq|p` z5CM$XiCV1fllYLQRcB%X;@%^vXUtw=R>%xTs@xHlAs^un1?VE4&M`a^OnR6EmH^o9 z*7A!0y#=j_qK=NlzV})bN80o6{X#R>N~X#p;WSB3rw$_^(xqCpg&1!Rzwd(zr(ifjT=K8u`_op7aM)>#+ ztWEhjggtd0VkadVjyy~@SdO5AbVPBm_w^Kv%s|p>^5UIK*X6FWk1Y#M9c9W!%3rW7 zY*c3VabAXmu?wgg)?!_p#}KuWn{_Y7iuP^@#zi#_Bx-Bh)}p)O6L~$4jhr28Q(l*nfeoMXCI?lEI69Z-P@D|Jd{~ zF1$|^M>Ipi;lSy8dVRMZ?3}F87rX&P+1Yy(8xh`YAZS8QX3sIC zlFA0o^!u13q%*cS#Jsbm#kFHCAenXlJOCMfO*yR3W>x`W^i;SUT|D4&g9_)6 zUK~?~62@9POi`N9r|4F_oA_c~DkmS40#>S5zM0dUE7v6}Zh=Y^y2TV74j=;9U=Rnd zP94Y=OXR6#!q^Fl7tcB0Hvh5Pow-b-v#H;v0n)0Y3}Nl%D))EVlE{qH12yVY5lxE! z_)>)OGg2&TM1J$3iXlR7{ISo~rzv+mEXz`c(xK)P? zg)d$$E_@@>Lt>Kb-2b}BPaSbaw-{=$mx%UD&`@bOrgQ@MTD ziDD&SGN|bS&q-IWv1LKyy|OF1MrD0JXVa#lc~2Z?o~rH7>S5MG?m|lKmWE$!tU==S6ZgAiQ47>O@O|{=SA280oZd39R9h0lV>-~q zgZZYjo*+{&Wn(kC=7)=&3Q!r_dz%WYgI>j#s!ve6n=v%0-CM zM?klZ>%qQL0h{1#n(F32A<$?M#PS_%pqqmE$#xFnoNCeL+LnTJxm*<_CaobQJ<+Hp z#u$CEjkE+PYUV@4OPV^ig&9NC(5waMIqZ2^2+g(lc=Cc>qF=TyqR3hK=w{X2)L*zd zTiiY|@VuBczrMQ?b6fj_j*5?K+^zJrzG7+RttZUOB`ikFAABZ&8~}eTZ0@gylMc~T zP&bqgy79SQSk(GRdCQP$B7b?~ZqZ77WnB|{9}jc}1+iq{Mu}7&%F>#Elm`=^?e#t~ zFQu?*8Ns?moaN^UQ$OBsD>;Vc)DnB;*8K9JaAAUKw19=-?YpFwEcdlA_tjp>B3;m4 zy6x)jzFMiuS-m)vfWHLvww7i@m8iEdtESFhhW6jxH$*Khg8Jt&hd|GJs}2K>y;G%v zO@2D5Q68AaF$Hp(sre(yrlkjs4UEa_(qYx@A37@n72f<4u&EW@-w|Qy&=3W3zugoT% zZiwQ=hw`fX4m1wB(bKOIEn5L&4B9VnCtdLQ(*h8IpScimpCof1}n+$U7f`Q2b90(^M25?+YP_DXK_Pr;iR}GWx?d5i8z3zq@%zSsv zT1cR{M)%0;*wLLVv2+cfzhYy`oW28u`lieMf2zGj!gNsme~WlPtsUArs|Zx0KKS$n zZlPw4BwDk?K_W!S+R`Bw?dIX{=Swb6x<6>@G;(hO5*N$mXJgDRm1X^RRASz@yT)Sk zn6jq{w?7Sg;?^HXmNcxrnxm!yd7&Z)!W|=Ct&p35>t7hIMB=P=xZSqj1p50lZ5iHj zx$f*vJ1jar8ZfM5yA72Vmh}hIXM!>QBmYJ%xeqz*&WC5t&$*gbO$@F3kJeEcI@Zgd zN1dXZ@KY_sClPGLcn{+dE~Wvt&}Hh^-* zUCiw~%|H>d^t-7Yy4iPV4`0fLJ|QgtfwkV=KCjjYl22vX1^MU1<9m(@{!2c<1XNvE z8rc7#>MommR00hb-3DIs|J6*wM%)i=*@9LTd-Gg@CK3itOdm4`8#DT@#p{m4xu3;( zG01>&P@6Hp7uyggsShKFz`xaH_bh+O2+u7thd^y%@^4TyKf?JjzS7j-Si(F(pxIl+ z4eQYF&BV%{{NYVy6h$um-dG5mz+PDfldb;YuG3qfdF*#6Kgt~^Uah9^b9scG;+V@{ z9+<~Z!U5boj1{`t3V?O}$*u>a7*w2F%$LH#Tk{}Vn8;->`6tZ)9T88O%`!Fhm@!Nk zb9WHahK%)qe4p>x(|krrrQc=qq$9e*e|K4P`!X@zX+gHn%yKf`Rf2HgwwCOo*`oc2 zZ$>ryUUC>O0A?L6=T+(?f(~itM1pabZzwy^7fW~V?xQ*K;wNTyU7eYjDf@ECV5NP;Q8{3DSUHT&G9WZ>H%&p=9 zDbQ-0AD-p}6oR#M2C)2?i6P%Hc+3Ef=0#|PnPfaS@Bd7IbO+(9pDN*!^q}#qJzg-- zW{ScP>Qd(7D}GNs{vFQLM0(b@m&4P>9_Qc)~YqB3)Pb z{1H6VIEeMN^9l*5Z-@s|lv-?c0U3VyQ>QB~7hv?&^D5yKMACyH{Ie=yZJx-;i)hfo z|D}Yn?tlZbJpvD-2Tx!WAd0^iNg{arJUCX+nUcuEsT7<_Z-BtrX3GT(Gl)# z$3OwgGt$?ZbVL_I1Fqi|nV=#;ZQOmm7~B3l=x!9Ot+e5~X<&xC9r?HZ3dtP`IR;`(&x>^MK6+z1W+iiyL{7%7J;v9ILSNFe&E_8k?a_>%v3B5!CVS%u>O7ZPy zZK)?FWh#d-hGl{7R>xfhfknjuakP91Xa)2qP(FASm+opWVnB)=Br{YR$?@zD%a!n- zqAm?Gv^wAEkL3H?$crD8>nCaxLDBkzMWx~M+uk0FuXDEgv*h8mS0MqT&(Z2lfTk3W zKT6_-(6k`;h!30u>V&Zcbt#r(&UL)<31aUz)KmnsqpgVQ`l^_C1@ZNBJA5TcRVAs_ z$JEYi0{S{BIcf^Sw7p(V1L#*z#D_S~=FV{-_a;*sO3UfQNn~hi-+Z!_syRg$D_ zEYoIvzBM2;FPj^9zC`1HRt0NwP*toctWC)r-@ppc2KYPXBg5sT{r$bN{B7j_SE)|< zOoBT3PKtd9=HmkS0m6gi!SG1tL8<`pRMcFoaTg8<&HZxvr?heQ3!p|N@3s}Zzi-VR z#i6TM`;pi)dlYtSLVp9q8PlW<)Uf}-@~;4Gk!e%N)}l`6sMliP0ef|Q z6{X*di2Qs+?7>WoofqO>krfkJpaXr50f;feS-~&1B^<3DN6zJ#u3zK>*nHEtY)6?d zb$i@~VH@ij-q3!fQ2;sE^U?DuPMUp}-7fQTN|i#!%u&43$xL#moUiYC|&>DlS zU9JZM!@HE8t3afsUvvx03R&4Nnkre2sJ@VXPd35ATnGB4geX8lJ&q&hgo6XsSsVrJ*^WL7H@3q@JwD=JJ3b@V zOWBACY#Gl1b_hN7D>YFWaHMt(7%7J2jZ(nuct(eJD^E4JLHIc-UUMR=L;I(ANd+mRi6(^hp9naWT_*_<>b(+L9gEh9#1G~y_Dp--Wt3@7foGQ;-=cRg{d-C`lNHbliE`Nk^^~H>SEayiJ98y zASVShx&}nc8^4y~xLtf7zkLu3O96iYv-ql3Q#4HYG}%?_mQ4Uqm<#>K9j5Azvm5Gk zr_-&04gvf`(b`d|g^k=!0R^qTvvP%lFhEHLx+TKdp1NZbDe9tsyJwc9O5W>sQ#usN z|M(*8q5KNSize}ZAF9P2%YTw+Cc&|$5{iXSbP_keo32xO5En|^N{v4z<4xr{%aN|ZQs}KKOyM*Md)EyK5R+dS#eL0I%z&yCvg;hd6j9o5st8}=SIFBiWa3-YqzL zn*NxE=4=(3p9&u~CP8p#9*4y59=i7A>VaWO+7L3#aF#F|w4;O#;l9xy~VzkAiH!@gej~Ottb* zB0lo@i6XZkDyhi9?b=#f8p!I|6`KH;?5HtUiq6jGI`urnPR~wV>z6qA`!?bG%}fMrlxoGb50;Z^R-uy(s&;l(3m<6gs~0^< z3MP@hJSS^!lC^C*1Ix%(o;SGgHCgZYr$!RGuZbO;6L? zbx*$E~QYm3U6|I6L9ES{yUV|>X&a(Cl$%YIfoK`W~Rg*q1k1c$a|A|3>yfU?E z>J$Hm74PexgA6ZSGE5c1FvlNl@7vnpZY{fSF*-%f@!qQv5x2SvJFzcSbr-O95yl7= zmBj|qt63R3qY=Pzzr?+$lF>CPBte)#ErL}GD{ELVIsf%yHt}aqJ!4JZChD@sw{7HD zzc!5P5w8YX6AX_al!UMoFq##aM&sjiE)}_G*V4-Cb_f!q+KPe@VCjr5P?n0@-+7JN;zdF@i$1mTcZ z9AEbNgGf1|6bc3AZdB1J7nog8P*ACQeyR6`H8ivb$h_$- zS5AXQ+$c%m`1DN}{K*u9OPN#qmT=N6U4XX8CKS@>)gE_I*lD7>>!o?Lpyq}Hzp;E6 zx!48X8mIHHR_U!)zCD_wi@T4Ska-PNRn;}s^K0C$VYO*J`*y^*?HLDE)yY??0&mG~ z$x+ndKyy~wv9Wc_pV4marGx9kdB;^B)*JTH`hp%zu$xtu6YB1qJ~i;i6x6Lij2ovH%mS=Ysd#=8 z4~Isk#~5=w++}wPmZkB1H_{jVLdPIbRUwV43LN1J`_Y4&OHhPz-L#%(`Q@T#F1@3k z=jDQ%`(g8?gy`DpcT$Jn*yu!TuhWFDroxz8W){c3En>Z;5|1$6n<=*->xiteUFh2_ zrS%@o`+_>BF{|Z=L@EbEE+@-ISow9yI(eYh0Y$xNYR#JZ3o9Q9>GJO@3)^0MPFH$u ze~=Eo3rIQQaS@|phg?cpnuyan!Ru*LUp%`=ljbJ8+J>$mgr7;Y15AuJrA?JQ%5t! zD|bs8bG%7~Jgzqq##^k-{*3%|zfB}GH{32sI#C3o7P8#yz`*Q2DTjXIDxEK8^GjPw z%L(~&wX8fH8@LFf7Q!&uKl%e-YxxbL94=QVei@{1qGn2Q_@tf8jV1iWVXdqDu;td{ zOn5yfnB3zHyR=+5;A2>4g%sf4qH>B74VMnhHJ?vDX$J%-_IWtV&w)00VLvKd%(xlq z9&CF&Eo#?i7oV^23}|3oJu+Eos8lpzQ)74Tr(%1g0lycp*S%)b)e%tDlQ<{rGG@m{ zf_+45D(p)EHSN|lZGfz8m)f;C&H66B+X}fIK#oJImpA~!$t-CY(uG0zq!-~9;mCJy znt9F}%wRCzgH)CkmKE?Ka95sBn<#a45F4GuqrMfTE6p1>RIOYeS2^%}d=F{L5A+>< zv(hIekYAw$Q8`#jw8qEmGto1H?upDp`7fo25bj=Y3XREgPdpc1hSN|m>$TLJ=6k=Rjuz z-1F0KRB7OolH5m(CiyqTlka#hd~cmCuoIr!Ynjt+>7dR=Uur_vpfX%-(%`#4Y#IR#D~RrrnQQj)kS}`{u)Y$4As67%?z$r{Xqorbk1O z(h6p*e!70{ZMGGuk<4XQLSfJO#l6V9n^*SOyUUaveyDkvj#UlwJAe+mn7JV=iXV4T z?eYza6um>)$71>sOV%DbHcfQB$3oo&cjXPrmFTetPFMIw{wItr?jAI zVi-$hlj5+{mPS|N+4h?U=lH(WZ%~_$(V7Himm78aJWO6cHrU4e85X&fa!xsTXssm` z2wxcYxk;gn7D=j5)!(cx%{@AEmU-<&al!TI-5Y1+G&S9=km3Ehp;&<`U+c2*e&SIbG(+S^&IIB%ZnoZS{a+j)12 z=8ZqRro3#gJ?C{|_wJ)5Zuu*n0_pM2Zqg_hGxzLsgl#GR6!$pi-Pg+;)NdI{+0 z7+fwXD^7!xOGHy!a6c)zG^kA9pP976_eK@m)o11M93I|J&a+M|lqdF~&%T^ZXH2_P zWLj#CYPbdA%;$`ky^)7!gq3_O$S%mQz_=o}*V7F69(`~OX4RjnpBY=Q%$6~h*s>`W zih*vX#`^--^#oO9pI$?yx3lim*Grnys&9Shc-LPvM&dMjH&n%nI)|gs!d+&2HrXr0 ze<4156sfbiaP;F#$GKok@n-)i(+B zItuus88ToCaOgIOjA{0R!q%j;w*}01%$jd~fN{55V~aF)=8CvtC@OdfP>~#YrR?f) zIM-!kDJf71nitgX>#;oM%qmXjmeyFNw~A_SOLMywd^c{5UXcM?dV6_$&zBdDSBz+G z7>ncAAOqIaef3CUIpT}AQu38IO#$%z!QXXViQioq$z2$UG0tw`d&gatYLuXZOX~G` zFt|JzjGqh3$v?`S`M;U!mq$e>oy9gIllOY#u;y9E11A@k%_3Lv*u*)Z!ZmzB? z{qAi$GW{CVUZ{a7-ZD_Pf5n~!8YjcKBD+4lF5rhn|BAUfBNMsb;3aREh`zZg6KMlJ z7E-;xd%FNB9Rji8j{2rFi$oS^6bD*Rj6mlZ6??A12EfG&O^sJ1!q^L0<$}_YW{!J^ z;~V!10S_=Mz8|pfl|gT!Wg_grtm*T&R^o7vFHjT+7d~je$zTpSNk#RAf1qI+R+mrU zZjP`3obxOWFCKWyO0Q5Nl{@?R$3FBqUzPE{dc|Yx0 z;!D*>7|N!nLsS3jwIb6ykObLl+);@L8;^Zb03Wq~!k+V56D^%|8+ zJd+oFAphew27ikB=Y*`ErxZjUF^gcQsH{V3PNxIeUq9-#L1SM5K#&?-cG;3TKK*uC zs2NP*-r5NM!(l0X3B%lcrqmF8R9RJ81*x$~5kStF@sU5Nm5rGVvS%a5jfb(6T9@Cz zxDldP34V1`ZLc7B_9~dwr`CKlBX&>RjR@nGETE~0gZfsw%GY8RbDwd0_VJfU_Ln`B#g9Uo&GbalShc{iL9wwNY2VKm9+PReFi^O{efV21sA?eBoP zhR7s3OZ(hUK}6`o><>&UQjNm~>zS4`PGHZ5m5u`d|6|n+orVS0v>vP=LV_z;@T{-Z zJ6Vg9}daHJIa(J?y?Dl2@P@AGBPTVVUB zZkABD;QKo_3U;ArcNH zNJw`N14#EEAYBU5Aky6(gCJcaD9Df!4oD7&2!nJA!gmm#=lebH`&`%ihyUT6bME`z zYp=cb+UJz+U2aTBjeGE?;bhfK`_N0*DULg_ct0e+6+Ag0N`&4 zW&>b1+m9)9WkO%E!kxQ$_h12;9MoUV;NrzP2@S#Q{kPs!g|p`1&WG2NLC;Ck@9OH@ z-caErQe#B0nzBQQg)mWJk5lsXHPS;$o-LI&(cgabHoA(sa9Cb~396H)R6$i(=}+&h z*Vgbe$DdL7A>69&0h86+;yAqwg17|t{RFtb(M)JVKgCzF`29fl@@*iS3~B)&2HYM6 zu>W2k37V_44fXg=0y5V+l@@H@?8o(1i+)O(sbuLt)G~R+lnAYc+l1pgtnaJSB#4+8 zV|8;C5cXj7S2e)BGt)O$4s-k$CMh)axG1eS>tVeCtWsr&XJMZu>g57YQypzg%0l;=E;^ zL|(8lRmvG;U6?aFMf4}d3Y1aRkw=RH9UDiNwgQy4h3A-_`kDA~IKg)rhc$@HpPCBP zJ`yilHP7JIE`bt}W8~pxQD+e;9T-o)d)rJLsbBL|exVoT*6E(it4?Xl(EDLef?(C%!ncj4GwI~v^R57B`WJZt%sL$E*3!1jrILe9=XKFdfe6GNL8HPW zDhcvaa?}`>hK_@=HedFHXs~^BRs9ZB0!!*L4Q)qR&lA9{2c05b(cbj;X%cZ!-xy%8t3FvU?!4$OgPFaJWT9AED@^O%u{DZtvA;>bM(rg1&8- z-siEZ*ze{rPw!nbtI8)1(M%PjM$zP0kjH0!tqQcZpn)xp_CzYnECLaoGOS{4h=Bv8 z0}*xoHR=y})s40TmuI>y|I!XcZyBVK)VXPE2SB3aza`;u9uH8sO-G6tgxGIrn^caL z4PM-t;RR)=5SM=@z22hKHVVcaqLu=6BjYX5#dxCh=L=KgP4XV*^}>{*nvbX|=sT%x z#WY|O;ur=M3}UqH?lF+H!a+K;tJ+4=@lC<4@^+LXy)8vGM#h4@cm`kJKa%paco(?h z2nEio^-WCc*iuMa6!3sDbb@)7huy~CVOlY&8nh}1oPZLAGYuiI^NwE8y;L!0a)Fa7 z^0&8ouFnY)ZR6caAu&?T`_tP%r@XirS6zqeIfGqAL;iIN)wcK z-l%-M>FWne-j9Mlc=-*ZrTT4p6^Fc$Ul}h5B6;=wv{3ev9?L>A&)Z95()EHwJ8blhn#eOxL#*POPcJj7r-WEEXh57kP z;?aUx5iM9D_+K&56k<<9drmh}G=UYuy;&iT!YDUN6sfG(5UJwfz2%=jEjjseSk1ad zt<~GF0pbMvM=Qdcl9zq{!SGs7L#fsCW|}k%?NsgXM)F|HI0M@-^aFR)t=TQ__oV+3 z+1R&<18a6G*rpzlCRJ7Lza9_{&^N7qr4+wh&!tXzyIcseoFCe?njIM4|69!aA+bC2 zM}OJcBGLW~muEN2WyJJliFb>V6rm1l^rGo`zOWQ}zfbPb5U@}sPbzfm3oq^qDMfTF z$PEuQ%R3p;rmcWt{Hunsm9To^Nq=z4j>?%NGi@nw>vG8xV)eFl> z-)(=TwCp5Eez@4D!jPb2%Qa5g*{RpK>%N<{WV8d|9kQnWI#sPA=#MCMf`j2a$Gg^7 zvHME7RjS3kTL8C31E{BKt69vn&eemXDS!G3o;v+$KMUFRn=PAIjge>5%lQ2pwNPG6 zTsKFzAL7@fK`J3_d}|H#(GkTS#`?@+AgUhQwp2cuKx6t-Lq9qPkmtd~i%}1hir#f= zK4P0sz}@vi-H_nsg+(DK$88624g1?1Bi1CAa{lp;nQ$2in_TF za?w=1k_EJjbY_>ri3gTCl@+HdMg85~ES@2pEG%5U+AN;A&e2(BnjtS6;8iHze{n~& zdr%XIKCy$9qDGEQTQ?w8yu5*DuwyNrQrt2&MX;_ppO0Ve{Uo(b@7;1zE#CLEaX%D# z#Og%L?yrk)Fh%?VlY)slV;%^CSz|j#Q;FL2jW>nLAtzo80&HRycWK4t;m~0rvGSv!znWdcJsm|A1!&Vi;b}j^ zHle8m_m*)}^6ky!>VXWWOq@}q{as>M+g5ftC|nsgi=niRhik_-SA+&Y!(hI8t-$25 z>< zd4=vXq+IQRw6s=&v@SX8--EcWwt+AM@miEAR}D3Bm11f9(h2^FEIX}C(Yijy6#UPZ z?INNH$Z(1-N}Sp+`hWv|jk1zDG1M{IFX7M>Bbuy_RvupDL$sPnjF5Hpa^M7f90y+F zg76JjNqC@X#VP~>02>Q!ZiS7YS2mV?h&X7`N~aa{ylZ{yFAiGvkAaaJf04=}@Li3}^<^7bF_ctm1rqJNbw}}xP1=cicCItUY3wf(2 z0gC+Lu4D#ZuX+K2gi<&o7cWhgfh^yMO)F<`7cwwBqJjrjha7R>u`YuTAfjmVQql9=BLsz|mn1AlT_woaJ?{qoD zNwj%Za5VvP=ZboI7P?likC^M#1%Gnl_mZ_t;5i6Qg1Z;LYI6jHnN9CzeIECTuBLcB zayv|su!T^hz6s|zHDhlB_&hT}@0}^JH*sXgUbjY_kV=XN0sesaY^8~>oTPKL-C%hh zo_POvzP}7{PaPlMW_fXj&bX#Fkm1s?$k$ z>iAJ+Oo|urjA8RQB*uQf_Vc%UI*riq;xMbn)N4m|BfTePpNP-=L+)7X4*Z2kDZT6D z9npCoF}z7xc>>aUU?(`;hb7>w-&S0v5DXC4WagFlwh&x~LIjpUaJyxD=Z?34po!JS z5Q6C|>On?qRISY%XRr4;Sy9>ZnD+s>{N~p>649K5dEwLW4frMeoFI|tVO#G?mg9ai z@=+I%;=)iJo|XV9vcP4ql-zv)0D1LLdtgW~aNOf>AgPM4NKj(e(p$Uk7^K#Kpnu3N zp9)HuQco@gaG=fE?bT&6=t4JDkNolt??{&32O_oTPl965J5cU=9n@>#>Qi%>8dYxR ziC3k$CRidgns`KE_Mw~+WxqzG+;}ytuWx;noOEY`FA%HVK9K5~gQ#TPT$<;))S^HY zuOXP@J$MT;X-1svr5J97VkbZ+3*&S1%&f4d9}mG-mR+P z60$_Bh#{@#TzAL0;Y5Mergq`8@?F?Q$l{O}ZTNT$&0oag4P z#y-yc%c{%xa5NY4yPj}?Ake(a`O6m%v{iKsSD*&1#!M$5qq0=djSreBtP!j!&n$5e z)kGRt8m}V9q3hIVGw7V)6otm!S}rur*VuZwR8d#bv3VoDd|&$c+sVTJZYIWGntgNE zhd~q3OmoLp?a0`}guAzM^I6*46;^F=gB$&q5Bfas18aH><2Bhz`%31>MDg>yJzr#m}s3@4~yUn#1O9Gtlma`0F*uu$((P;FMZ~=i1vTo zPVv{32kc;0d*9sBv1busk*htWxwlCXkr3qvvxPNsiOQ`8mJfQd-+Q(l1**6J0*L5g zvS5$9EC2G7u!i0jOq&;10Xx0N;BHD&RWIs?5f&KM1}4kx!)6js!~z&coc}w!69Qyb zwT5M%Z@dJtBCK^#Qro_feVwA6a3U40-ohm!_OPySwiuVbvpxLUQdw-`d(QIJev*5? z|GUTy3W2$bWHEj)*2jFAJ++e#rYW-zEAPEwjY|mnLjsRh($a@ZS}LlBehTT1TPdZB z?>hv}zm-lTUqjsjSw=BJ%94F|?x&?&!}KEyi5`^`E|*oW2v!Q!Q0!2Cf+5^2u$9Ni zL%%t6&g^FIr*<>7&^=c53171N9ui8ag^wk7_W@qi^T9c)0y!HmY*BwL#M~ZB72jkx zFqGVFI+HWm@y@#hgqcYLlh@C6S{1hUK#6<#F(AeTnJ8z4HUi%}t*i_w9FTPcUZE0y zAIJQVq!C>qH<<6!otRXS|D9R>khInCuYWJ1W?9xd2)DGv)-E4^-<3H~EB+0xFMxb0 zUKE$)P~)ywZim9BIKOBoSvwmY>5aUFGI8#9i}Sgm1)kUYApA0sx~_r{u>e`$fN2*) zBKO$_P^V{;-%S9%6!P=1@DERcNjSRMmCeP7Qho8!5$IV|A8kSXTs$?M)e8x(6I%fj zH|_xA$RSGstUA2rXz0S_tBQAe#8lOQ7Vs+~hvnV0S7WFL{63ZzHy?kT}6`)^=*t0`y(Zx_8=TRgM1o$lybs zI1(I*W}qHD041v=YIiYdgt~{vu6^BZt_1!delUj@N+kqNnQL}kw==_?kOgc8dqwCIut;4qY}G`GtUSmkf>4d@0tm_Cl&Da7MfJe4L~>>+y3CZ%uA zSIVR?WKziCUjPDg$P@TtuC1deO;Vt9cwHDMH=4`hGGn(fsQyyrb#nc00K#*iFfJTt zm)8SG@;7G%f3Hct3uDXtQ_g&GVjs&cbc5CTi?7D0r3|1wdVNGKqE5JeH}b}r076XX zs0jHQiGLQ6M$tumyF&0PfIA?daS8%O^Sh9#5~fu5xPb~BPM~Mk2p%Gw+a@% zTZ7@CK6Z0{=~jXqWaQ6I0L?xh>4(QNRUoT)n#qzvtotOSK zt3Sss@w0L!%+{h5!}QOu7E6y{2vzSzsk~wXZc2cP(?CP*!#E9S6aBL8pL?cGwZ;3t ztPa#NYn{>TP}BTRN<0Km;*VMHVLHYZH!5jtdRzP+)eVfrYb)gAT>`}~2gLqP1#ks1 z4Ld@i?%L4e9sajuouf9tVLvzLahiICIIuJu?|Vt;=Jk#r&OvG77w*w&!nz>BQG-zYx23t!9*1W~n)TeZtQG{#U&j?b*J1cr}^dTP(bBQ`~n`#Qb!Hi}%W9{`5}M zCs6eAvE<(kY|St+bos1X1!M_PM9;yem^eYI?OR(PN(}~7&FuQt(h+N>^_3Am(YZ>8 zxTRcR){tXPgWwptu^!?J+S@8FpET?R>iZ&+>2Pda`?2lbC2%g+Jy5gc5z3fx$^`u- zNQ>rsKpEytogfz#!wT0Jb>R8c#_f$r+w5+AH~BM4l!zHWFn&g=3G;s{vz504wkf6O zNp>j_OVHMjL@oUQBLM`0esQ29X2!!8lRwcgjh3nuD%VN$Oc@Bvk9hUG5$UJC6hVIk zN~zws4AP_a-3T>cu4118CFo_B$%W8SoVy-K7z{C1GwPKeC@h1E(!LK40 zpKz+Gn6*#028IZMsH^FEL&g3Tqch6*-YQjCIW?_vY9w9SXQk7N^gBC~m7mL1rzjwD zXPVy87bCIx_n7}5x~@e(xBFD1ekF%tD+w^e2o|W$61aMLG-ji2aZ~ZQe-!liQ%5A? z6jS;Ecqm<_FGJLBloDMaE-l~O0d`oY4)4@j9{Zwj8+;3@y{#5fbz%6m;C}S@o`e(b zHW5BBkSnrQt*x+wgP3hwpQZ~J1IrLlL&4Mfer(pL=lY6WOq4V+VJyAW&&pZ4aTKUu zU>JQK&EEqV@|t_Xd4e5rcZXG`_!v+Qmbb|j{kohRcmEjf$@_Tf(|*a9ghuomD&LdO zZkHfJy?jyE+^yBmdqY%s3!{J$$9oJZ`Tn^a08N_u%p6Kpq>}*oOEU%!1*R&N`bO$A z|H})Y;1`;!wWp#G2H1BPo~2i7HqNYW@IMQxB~M?iE+67a)LYA)B>^?VQ8Wfb{tLzq zPy8CSGXj0yb*6{;`V~HJqwSnU;DGHag{U&v$LqXA?#IOL8k^l+=a_38EP((r$m^Za zFv6^ekklFU$ctrLkSMWHx;Ieqp97ib*09YwvQ%tYWcf8hWQxzwLIo0n59=j(}g^Go(8NX zNs1dxxrVKZSLc`FE~&i=Y1zck^WRSAT3=h;Z+fJ9`I2!870&b0nm2Z|$7c zGg#na>|wp_HB4Do^cA~Yf8F~cujd-wO?IVpX}=Isc04>6eD36JP0J17F1;lK0)=H^ za9dEwu*WyC8!i^CS3w04 zK3gr(m!5zF%1HaO9%aY8IM)cP6s(?f%`c2ZQ*z9VnRo|itaoBBWiqE6LF|Qv0pc{{ zYSiD1|LhZ|4k>bmrZEBMcX%b7_z6gLfFFUH18ZwX8trr<^F)2lUo$jc_>*jQ&E{Pj2>i5Spp}coyB(t2`Y{z{mM@IwexuBSUSv4Y=Bb{ zc)*6gqzdTL--BuZKF>B^lkb3|)Ag8AT9VvS;~}D}B6za;M_yhEYQkQYn`!J3+c)N z_WY#XeEQu4Udo~UtpJi;r4Yzn9L|pc8Ex=6qOs`x9C$1d+NZVC7bq0*G9-PreJLId zK<=tnd7seR{FT}-SL?CT7c8#qyH&TIcRaEO)O@KH9W`@XKd#=yK4>vA6UcP8SG8E@ zS$jj?)9kPGayRq=GQ3yw!C5olYKR-?r{3qQmnL6k2afCH#WO$3RxH%-2Blv}_w2t; zuydd0A9rSYe=q>==~1BNjC%h@^y2)|1jbPT#_4f zMO%#cyd4%tBe3q4=Hl~idSw8;Ea091w@lj2AHC(Rc`VV|2{}0dskQTi%w#;lqj>!a z#I2M6^>gh1=y|1vFOkFjH|OPjnAdIOsOJK`euYYZLICmQ?{zuv++-8A6Pls>Tw^Og zl&uI0+7&j#sLlTC7<{D+5B@Ah1SC(`eC75Xl%fkvzO`W5rfY(9g94PKpu#b)8m{GNm$ zj^C=E#Qr=YrDW6#;ue_oII;~6(iGZ2ee!&Y+zZIw*?y3@Z9BKxdH}e+`O5dtK93F5 z-7Fj6r3`}^0o518ez4@Hr2rlT%D|M<1y=UU9dHLNR%C8{Uq3?&WFwh1)yFOZ)ibBi zT3_G^6jzOp5N4n<~y(Ay6i6w2?g z2dK(xwQP*x|Mu#9bTriPI}GvqYzR-f_Jyia9fQ^z#sPh#-^NDD;ONqh+kAK4*JlU0 zzRVD*NOt<6A7YX}L^B6GiUy!XQeA%}GuNXQn;Ack0VS=%($3Ca`sV7_o7$_o{plhu zBwFvKO|*v}qIY)ice@jP66R8;Od zc@{W@v~KE{E8A>sx~ZY`fN*a>KI*Jz;d0ioBfb!#{_-4lV57P&4l-ZT=J0^CpmlyD(>hA~i}{X)7AilOV}06uMm z+gdDDUv?lTN#hkt@ z^Vx>+zsDhNl`2GxCv`lJLz;9xhx63QJL*^DPFCOpJW%Um*A8J*4wmue$mftOH*^qN zcxT-g0Ff2bjxYn_lK?vr* z(VRI^yZR)=9WW5f+M+MKja)Xl1B&veOCX@c$~>8i*$e+-!GnbbhSF!-odVGB^s=2| zUL)gk9uxTn3fNx&XBSH1?=5Gz?6PNtkaS9RgtR}zw#TwAj+i$xsm$wo?Xyiaz7Vj3F7r(hAZP$t_h={k{6-n};|oI30&k97SF>XBYp{2>`2 zd;3Z7SZ)3f(doq1%R^Ds6(2Rm+w-y=r%do zbAa;2x?<3aZa5Sh==$Z!($aFKc@=na*tPg$^2hPe#Y0%7Kf{T=K*wTT&wx5lNW%8z zf?2;hW6Mo62CxDKU?aXY0$8JOEkM|#c6au8KLsuQLqX1-8#!f%Q7EGcKA-PdtI9?o$FuIfM>p62ebZ&2vvUpM|9VoK zydTf`7NoLZ6Y>HNP#;ES!v?wEJ0R!XfC|g9&6Aq?scB%uqk>cTK+GE zs9)AEIne{Z&B=?Sc?=3?o>otu2E>nUqFDL(-_Ki(-87Dyfe#y@0Q;M!eP`#hPXIu7-nYrB#dMw zv^|q?(nj3}CU^4?(kZDtfjz*})m-;i6IR8iIrc3pbV9;Do#Nt9az#RNAWt-^ofTa5qkkx^SW9;8fq zuhF_Hp%rwBiVOt)ZP2rN5=GMdY|X?U>Q8lV_*JXbm9VPp7({YPNzp$d^;DU;J6$Sx zuIeG#*RDUD+aKi0nb@nh!PUQ9^9*I5uQ$mloc!M8>fS%;wk?o$@*ua**ZEjinvZ;~g+MRt3QvF-pTl-KMq9z) z#%4Dy(*Y=k_LDY%B8hXXK!DHSR+q)&UgE5t47xV`eI$_4k+`2b5WO+G#o?bq#lpAi z4K&8DxZP@MsI_81YZTHZR?)rI9j!Uu=U#(z7XG(B0_GU4g3xE+mjsG%2TQ7PE_rM3 zcNh0oGt)M$Fw>PoPv(d+{N0lR-)!7E8~&S|8dSN8Lh!fA@NM&uCV^@Oi1Y`{r{YLk zQ;q1F&r_|o@j3T*^I5mxYqC{p-#^5~xds-$H;hbR7)|8?6Luy%_h?nP%-QsKpkutL z4Ol6Ftk!{r#K6b8qVsNbLp}84Sg_6xBUC)x;Uezic;1CH+1CI%esON7NO%+66j>Vh z!E1KeyKY=pnj+mloaT#MU;xknM0s=e@YYVlKPRbwv`r%t39}C6LQE2PvpzJ?vgT*q zRP1iRlkW966+v_m>FJ%R-AZPVyfz1`H~Yz_CU=seoLSpz4Fv(+ScjEQAogdasGLdq z=)HA;FMSJ2+jyFWsL>CvT0x7@h3`p!$A*H7>(jZ!-RDM008@k^%#%d_!oIcTS<|Ka zIqjvv@@D8zY@t%nWAnO7?xgh2QHS=U27*XGM%Jb9&7+?`X?s}%4O0C^M&{dpxk2!3`$j&?OZu@J=Zy)h$%Px)^jH^H>`?d>X%RpJL?0HMx^7 z0CbBGMmNx6u+o$1k0~L*kkSKW>K)*&b;4+wa9`*|>N%IGAVBYd2`#-(D7P?S_}HJr zyN=0s_Vmnw-~a^I^zc`dgCA!gfCU2ZtTk@<+7*C_)wL^(GFkvm(}l3QGeh5rQ*9|>b#&xxN&1|T(cGJQc6nG~ilda=c$DMR_2+|bG(1Qhl zNE5Mezi^cc1zm`^rh|j#hScwE2 zQ<}JCesEzTHE3(IT~^I8$gG>!eX6pGkL3M3`|Cjf?>w-VW>>;(hGmdWH`&9ep_8ie zp=`*ys-X-Gmw;(qNAvp!isp7P+E@%2E^@{K<5S-dZv*TH%^>Sr8r^g_e?H&DHBjA$ zP|H=vu9*P~Lc6BX-qL)KK~P(ZS$2qa;%UNF=2-A)`RCq8rilOa zqS-dQeG3esN(ty1onmhDS2egEBV-!;Qbm2;J|mKVH$G10i5-v{Nrsr0!eqCol|ufO zTp2Zb*GgV6gMgi2k6`0T@}qeF&|)c47sjd44WE&e#J63pTt$&Y^QF*so@su>THAjA z9D6w+bGbO7o-MCGZX~!Gi&azg*|oK*Om2vxRoSBcu&QlX1=Rq?XaaJ1mp;lGhitWj z0rMd-P$lsSfNMIMa9UNuiNY1b3Tj`PlMCE%PH~OyTJ;OjvTgwBw3mfb zka%SGX6E+yG}B}2a3C)tVsJn0dvP|t$aqp_W9%Ls`-CA5~H zytoGEM}*q)g%2HG|nDKPsHz6z|~&ii*$8h$#qho7vRP^!I`}23F3pqfErHo<5NJn z6ep&@@sL4SLn&assgcu?Z`HNrM5r>jkrWl;8_o+_>j$&eZm`$*xWQNz~ zf?c`tZu%&kynwhB)!Uy{km8riaraaDg>2ETX{?&cIvGA->fkC*byhr+k!Rn0z6a2$ zpH|>xM~m(9>8f3-o+Hh{W+3o@6r*Dv%qOIWQlW4o(z5nwhH>sT0fLLf?1 zEu@$)h-|ARh5?7Ha%V!SX5(Eim&d+1GqeuYRmk!)gQ<=BV|mRei#AtUA<|QYW$uVi zI%_C!P%f$HCO4Owel+#gV2=U76Cw5w{+Ui|uJvK!KyikYJ^)o~uiL#8Ogb|&I$$DE zhf1Oz8YoTOp_%Z95{n8*A}2hTYoH2hua@F`(aLkr3^45h|G_uB8pjR;t?fpDfA)$d zLl-7hS@Zu=ZjFexbhiA=26N6czMoKN{Kgpb%hi(Mob_U!8fJ^{C`)@=goj<;5wr`J!(50hWV>!DC>x z8=^GHQBEn1q3hIccLBqk2`0NY@F?sQc?38T^-fitfY;Q8+}$5ihj4`}v7{s#iN{$S zu24k0VCdEn(OA?(8vk|Ux#lprx10Z;ShoR4Z}Jo*SRo32KSS^3*eh~`@a}>_0Xja( zoX?|0LQzx)WnG?4t!!AxxOcG{PfJU5frHXkmaqJ;tCNv!m=sKAn@)NT4(Kog{EyJ-flj#c4G(sE+TZSy*crN^+gs7bZHY1*`Dn@Klb3Q5=Ap8Of96#wASCCecaH6kRaSaP6p@NlLIFo}*GG5kHp=Xtkh z+SplePvjg9kwOM@9)bw{D4Fp~XeZ8aPM6`;r}b5*u%ACB+uAwHT3p>xNz)=6DDVD2 zqwl+>+42D|tucA|j;!3&wPtQnq$Gz)s)A_~ryjW){MI@4HS)Cfe@Pr0dW8isXg%6})@|>Dj^w;Od7|A-Uzu_aocZcaF^3O74C}DcFa%dA zjDN3q9f@iPovH5H-0> z>i_9y?*=aKK#(c=p4Q*5WQ>kz3cS$?{i-?Ze4>XklT;r~qxsHCUUa23bS4<7Q?Vl_t-VFKZzJz;onUjYf|1^z^<34-RN(#v3d9vrhM%(+OGPu^ zIANb)S%-4)^Ur4|(!J^Hs-L6zw`(qkPuo)cLbn~ zWBRDw!jU^ROb}a3f>55fY|t6l1Ord{BbI?e;Bsv_EuE^1KY!CNb zEb2SZI((J>xRqmT!MN^)g{sd#GjtjHSMRpi!KMjim_rORC`q0Ijm77)HF(nR>)&*Q zX04;}xKlubWuFq>;i{7D#+xP;P4rTUj)jr+V?YWpg99B9`VLcc=oG~WNP7PZCL6RZpKU7+N`}A=FFg#F4P&e5)#lZ(9sP|pb zo41x$`2Av*UfMD-(VJj3>>$wfqO$9a2*)g&Bi^pga!}ZPny+t`%aZ^nTuY^=S-pyE zoMh|ETb? zvhBi4XtHC|e*xxlD^|ai_LPy7m{rd<8QJ#Qse~pCG*yS}n=`L_Zdu2}56=a5r^~-= zYae7Lpl04GGe03e2n|sPuyDHjo?Yj2Jbao!m=1U`>X04Gb1iumeaN0aG!{xoL_m!x zh)qH?GG}(W_SD_}4^7-g2qsz4{GG}apjBdxH;_kU4_Lrq(SYmD1?Ks^$g(*2BG)jD zFy|vi{uUMC=Kwl!r%zmwc=?F~&RK^S4y7)`P@81CN-K9CZiZWYdB(%P#FVvy&14i8 zF}rU&eRUrnrD5e`(nF+v$XG-9Zj9k&O7v@YVP(g8t%S9Y*|LV!g7^N{Lnx`fF+yp$$lbdl#KmPZS zL?n)&B%%jakz(I9y4qAnB~orZ8n@|xl$z$jtok(k>_w!c&$LW=M6^$)*7KjM`O~QV zpZX^2-gWBry%UR0cfE4V;A=dAgbs9Ti^n>F_9e3IosE|2S6onK36_?CT#jtrfr!%3 zsONsIy1`rCWngNjuY2G6?~~hMOojo@FSvio>yKPteNOz^+3U{fxJlpx3Y7##2=@jC z>7A*MUU~38kImUx!~x;_R_4T&aA3RSSi06CzRF|D)$B%*6e#&+HrOyk`c7jP2&CZ|( zf({)q?uW7C497#T^TwKQc>Ion1#;nuk}*qeUPm=$Dllr)9GAEf&l(z7^o^Tw6+gk- zllfS`l0w1Xz0+K(tM%5&?8$)-TBi6gX7m*4u4I~8)T^ws%@^;&QCfRfTZHn9)h6Z4 zl<8)nYSdp_5xoYf`)L3@8X;2asy@q1NP6}I8;KFY9)KU{%uYw^l;xF4Fra|-9MD1@ z@XwS?6Odu>6Ez)wpDOvka4}Len)NH$u}W+ciRlXMzDR@~MhH90Sc!PhC2{}J5LXK~ zn3?3WI51~5abx`5hiD{2_8b}XGnY+^IYgVmMR~yGyEz2uN*DWcE_MW>8}|)P zxpyzz(utWX-=?|Lg_IC~I%Ehx*MCIX%BG{f@RWDg#LCf9_W&Lqs`$8)h$7sqSZ_@W zVn37yT)`qd--*}u3$aZH(r-f5Kpve@jrawht0M<*q?dOktVIBuqx&uMo{%|;;jQ#B z1S5+ktEFXkXj;TptL&?VIZUy%v<7d~p!9($x0aog`5CKd%4IfBpzvmT!1ex&{Vj<0 zAx^z3Ap~G1($ByYhK+88O0|A#;`frG*h%3>CziOYzlFnY@80swdLkt3jB+e{l%JMjl)^nNN%TY*oNarr}|TbgW_^x*$ObhuIk!C;wX2 zt7<*Owv6eG0|3^>^G_T5?MV(e30Jx@&ss3-AY=Hip)0VY^(RmaIp_Z8mrTaUzjmk$Q%Mbj*Bts1&&_$Sj^}6 z+-Wpu!<4vv8a8G-xDV)1XqU{l?K2@3;bW11_OW3Hw+x&lwhZ8u%QSQ^d9n99frzSY zhXmQ$=9H-7B5s9?VBkWiZAnN;P?b`NQT~}C-jiq@meA+HCAz`ewoHOJtG`84U z&*OWNM*pt<>j+Er9#VZ}tbGcgU7K1p^|4K1nUvy1hX8SL>OK|B+FMMp4!@?8d*wD?4L?{)ZS3 zIVc$#oU&XtPJdtXA$TbVv*5?|x@l{3X0E*a zW5djxK0^b1e<-qdc#8y7WhsuVf-)i+WdOrD1F2-dtAyvKk0eDmUf@Fi2jq4Eqf^&q z0>3SX5LF@QI#r6;rc~jq&J%)3hof=6--EGb4&Tg8TA@~y_!-xB^SF#w>djCL-kE&8 zg{E+wFGPNm=(s-y=CJeBc&j8LB<58yY15a={TyK8OxGONEo?h~4w zY9r4)JCv^%utIqF#sG7@&4pD#n#5FQCSlJ(z^CRD6eS?ZS63<@1&KRHXR_Noq(ur9 zaAa`if37hEWNJ^=D1!)jsCl%p;I~u6X|g_9X%s~ro&A3E@;XZ=+szw!HU%;)lE*mL@|<9j{q7fbKjWVG;awJ}Lp4dI*d{1y|C!Ad7rbW~ z;c^5@2hwGH!PN4uoSE(?3T+%*@=xXC6BE6s>N0zdB^A|r_6K*=pO|3fRE$^DOXUC9 zRgq?N!9;jSFbE<(P6=bBND~MM@tkQn6=Ry9Y!~yU#2i$L-rNnV4r?77=v>qL&IpLu z)7Q0*_9JYo*Iet^$)SuyiI3!8t&-m*m9>wY0{dBo#Zp|dt)%C_2paoa$xwN=i5m)) zg+=9`%7{zqbF?M|==_M;Z-bUz%oIoUW8dhw=`V#z2c$yZEgSh1RONVdKEJ~fh?^}_X&zTcNuQI9x|xK8he zR)?mCo+X7!t$Nht0INh4b`;cEtC5=eMYZiAZ=q5YAeMfD4-z?h7{4X!;<9%i*XcG~ ze0-*DVI;i?b^02@X|Pd!|Cy6T`z1^Rh;duwC)Z?#V^x9Apd!|-RqH`p+6p)h4gO?=Co>3uX(4Geo;MpHh?_WdnnSE zeY5$cXLr54&~6ayezpbb6kP>hj;-`WJK=8-U=<|fKM?iQY#ftZ<>Z{duuLSdU=TQ< z8i7<_tsK0=bI_1bM@!v-3Y95i_bBP`d3ih(0wDr!PQxWXc2n=o4U~&UYH(-2|=q2lDObQ#%t}gqZc`k zRoIn;LD|w~dim#x%2?0!d|+dX1#6>jZogV*L;FgBFf4ajQ%nDb$C%D#*&rXWDx{J6 zgyxc`cNJ?SVWM7&CFB@nZ|E%o=DR(K9X1fQ8j2O}$rgN8I-qi*Gg)#%2##5b$( zuPWRuwHnCww1N$Gsw1F3Z(1+Jg;bU&QK1(+qF+uLv6L%UqWWylg6X;?KX7(YTUGYb z0ePq%jc!D42zTS0u&QG+y)dscHQ@+3U~z%~MW7^6IwAGZZd#8qO~wheMOI zqZ#~_R*)s^3mzPgvl@cQFnMb7W;!Be!J{Dy>4YpXplk;#pFVm?wzdL*Exb`rq67%p{e$bmW}6jy*Bu&FJdQlJKz_adX9YbTvjMGdp2K?r*>I7bM+UinR+sExpdts_Vh%^$Lm`aK^Zlf(Jv@<Kv9k2{ECRW5_2#RF z<3ghR7(AONY1XCF7bGD6F{V77H3!g9k)E7R9<_v?Rs8C6lWRU}HPuNSw}A|Eo@t3( znFC51gg;ATIsn%jL|Rc$wU2@%O=FH$&v@Mn8L*yKMfN!pkNZJ`>{v3~LxK--6^LQMOK=$1gK;@!9 zf!5Y6ZW(1FwO1}flx=aKAwp#>YV!VDk*TNm*s~c4mGxk0+V6~&{|;n$vr%YT8MG|IrMR$# zX&$!p`cFK`lF9C?jdmD6mZgr0fxeRm>Rr) z8vH6ul#9q>RCjlzX`FPw8JsFk30}I`{(qHScTf}C9;Vm;L6P26Knb9RYNX?(sG)Od z0tQ78K?o#}P$NZ(A{bC=s7ebcMOvZ+f{K?aAVmTMf?RsXNa*D)aNoTD-kY~GyR);q zGv~Kw_LT42@B5v(j{VWRpjMZ@KCE;!(mf~1+urvT?oRjb9&Ui>O~r`kusyZ2T2&SI z%be$o*4GwO-x(tK6qBi*mT(pUw6Cti5pxD|L%}YbBj9EGYj!s8z+s#ycc{>2GZfH zet>^(3Cv@oby-_?2dPdapUqS92bvQ(W@mfd=ypQT-4MntyuY zt2x)4dvJl1VkXE=M#Q|2xy9k-^GmHtLa?H@Rs756<-=%GMD*#!R31unILy@ej({4M zTp=RkLP+CvuMtJO`6+gY8`?Ml3^0>%;BD(s1HRo-c>xvaGw~J@%pW1b@sqU+#%WI0 zmIjz04jx!)IK4nB#!$1pnzAUJ#c0d`*c+?cxBO1sf*KImo=))=M6i1I(S_)qeJp7i zhb&7&qoY1XWOSkzbAzd5K={5nB+6OS69s~G=<1fa@69pKrNB0YC1AoL4l&-Mm7lSb9?TmPK*X0H){T^Ym zUO3viGf}fER72&L43_W1^~98);TwYLm(228-#HlSFWiwC=F^LW@bNmlKG>2dVq`9clr}+ z$R!kbo$yk$Z?CYYgHlW^oH^`J8%(4N`~cR{(c-Jz!-w9m&r&qa|{- z%^g|4_(*tY%tIXt-|-Mh6EAqt=-FBy;fE66&U_H;j~hQi(K^bvZirN9a^7U|kp_x0 zCu?rAtCXj+-KL&qH`8-`cfvHLt#WqRJ<+(2=bo#M0_-)y3!*jVf&eCJ*9sDCj$kDM z+PnOaG6Sq|CqoXacMn@jjUJ@enZ*6NxGwfY@~F`Xo94USby&09vr!FRmNIiFjG5J- zo-~Uc@H?!DH*NSnq%`d^X^XTSBT|h@M5ybWFss?ysksnir)~yeQpi4Y*Wseq$pyR; z4jAg{W0v^@I&QipjB~Q_P2>THNXlLn7%_O3t)PUGBL&Z-Q+kB`Y0<(^p(eMtJz$oIUw6T_L@$awX1=%WSh5XhZaoXsONYc5U zV}H5|6{dZN(#M@;YmPw4k!l=bS`7vY5wb;pV?UYjLD)S`ujj{341Dgewd~1z_^csU z`dkh%Af4AH0#B%x4`3J#D1FFo^uM^zg!}SGBg&Pu*UE^c)%qg^~g6#FU_9m0DOz*)cF2ID$FRU-;fU62#F&uQf)f`By7w=D{{h zkwEXo9g*OJY`%TKowl>fv5M&XTZ?9?dhnECS7@#SXJThM2iXhDzrcfS`wRb~a;OX; zRdpg7{+d8UoO*{y{9vRbSk`hMY7yOrUn+XlXEdJr)5Zw&*zWN%>`NZTgfLYs)HxWRFRp}7NwRa z)DVr&L$^%}C_=F_FJv*yz*1?cR=CUbw9!L}MYqd9#e*Lbiam3pV!r%XF<3X@s-$j_ z??&sY1-FdbUQ@>#u%TY*zWw2SrsV#^e$Sdivr$#K{yH;TAob^q}nhi8qNs*%)GTUvb(lc*P*~$U0v-a z_h>vPOjN}35yiaSvqaV7Q?1)vjmf~J5 zUE}`vcTt1xM2^PWmT1E9ujq~OR@ndzFQ_+=L~i{TNK8c z7BORGPtubiLz$z&i%Q)qjQ+cTV$$Wj2|{#A>9`omj7t-Z!gPS^OG;jp*b`ZLnHyHe zTag(YfXf6csu_6i6h=6XWiM0#M~h;;7N%*YMxd+#R-y1rbw4uOxU*vmGDGQkOpKhY zoZOmP>*;X^>U128Ldu++d(LAyNl=q338by%EH}GkDl&F`;qz3zG@?#wDrZji zO?*5yAUW|#htDqC2ka?rKq&mJ?ThO7v(oL`!Co3y&?}&0;m$7*> z6y_aS&ORopay?Qpv9fm8_6EEA)MF9ol$K=l0SB=!Kb2~_k}W|Eg@2*~)~?3X4sX}O zCkN`|LkTkIAn*h2GH?h#wCn-+Xlf{CMZc6rzLhRiOkb0>x>e##HgSic-zTu zi1j+Ir`h5uoGBwqhz(VvNuxAnw`}c?;B$&;^M?Yi40*Ti3$(zwlGv=`T1KC}kUgOV zPFQ%+BDb^i%~#W<|7ckYNNh?Awuka;>MJnTI!r#`6qS$V@lCMzAnixl5Oc`3)GkIT zF?wOOL=t6qr;a#rGS4uOjJn$i8it2w5xnl|(rUJ}sO0d3j)m?X`etAWvD3?ID`pqm zG#ItESy{hWl*z!uR|!KMWmJVP{%>;EY4+)hom!9fBr1Z*K&5loU0bp{by+4I(Q5@N(9}m zn2J6bQT<}*2dpeM?AsqbFm+)MYL)N(V>$R8R|-TqUIeLG{o~DiWeF^ud}xk*xTyx6 z@vkGTak{J?)gUCfG`4pMysr?+Q25m4aTKfikc zPk>GFt$Um9(z;gw_t;9@K^+~mFW~ThH8@BBkY*~iYOvbf2B`rgjEQOyf1BpN!=MBJ zdmZ)_TH@8RnyweYW8h2j75iGO;|(TtNb1W^gCB*84oNt;p7YgZz|li*UmPY~3(6F4 z;D3G#M-kVkXrE)!M8ej%nvm8(nGGjHd_4ryxDl~}{Kc84VyoT%9q)f$`M;bc% + + + + + + +MakeBlock Drive Updated: src/MeEncoderMotor.h Source File + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeEncoderMotor.h
+
+
+Go to the documentation of this file.
1
+
49#ifndef MeEncoderMotor_h
+
50#define MeEncoderMotor_h
+
51
+
52#include <stdbool.h>
+
53#include "MeConfig.h"
+
54#include "MePort.h"
+
55
+
+
57class MeEncoderMotor: public MePort{
+
58public:
+
67 MeEncoderMotor(uint8_t addr,uint8_t slot);
+
68
+
75 MeEncoderMotor(uint8_t slot);
+
76
+ +
84
+
99 void begin();
+
100
+
115 boolean reset();
+
116
+
133 boolean move(float angle, float speed);
+
134
+
151 boolean moveTo(float angle, float speed);
+
152
+
169 boolean runTurns(float turns, float speed);
+
170
+
185 boolean runSpeed(float speed);
+
186
+
203 boolean runSpeedAndTime(float speed, float time);
+
204
+
219 float getCurrentSpeed();
+
220
+
235 float getCurrentPosition();
+
236
+
237private:
+
258 void request(byte *writeData, byte *readData, int wlen, int rlen);
+
259
+
260 uint8_t _slot;
+
261 uint8_t _slaveAddress;
+
262 unsigned long _lastTime;
+
263};
+
+
264#endif
+
Configuration file of library.
+
Header for MePort.cpp module.
+
Class for Encoder Motor Driver.
Definition MeEncoderMotor.h:57
+
boolean moveTo(float angle, float speed)
Definition MeEncoderMotor.cpp:242
+
boolean move(float angle, float speed)
Definition MeEncoderMotor.cpp:287
+
float getCurrentPosition()
Definition MeEncoderMotor.cpp:474
+
float getCurrentSpeed()
Definition MeEncoderMotor.cpp:440
+
boolean reset()
Definition MeEncoderMotor.cpp:208
+
boolean runTurns(float turns, float speed)
Definition MeEncoderMotor.cpp:335
+
MeEncoderMotor()
Definition MeEncoderMotor.cpp:168
+
boolean runSpeedAndTime(float speed, float time)
Definition MeEncoderMotor.cpp:399
+
void begin()
Definition MeEncoderMotor.cpp:188
+
boolean runSpeed(float speed)
Definition MeEncoderMotor.cpp:354
+
Port Mapping for RJ25.
Definition MePort.h:128
+
+
+ + + + diff --git a/doc/html/_me_encoder_new_8cpp.html b/doc/html/_me_encoder_new_8cpp.html new file mode 100644 index 00000000..90589c7a --- /dev/null +++ b/doc/html/_me_encoder_new_8cpp.html @@ -0,0 +1,284 @@ + + + + + + + +MakeBlock Drive Updated: src/MeEncoderNew.cpp File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeEncoderNew.cpp File Reference
+
+
+ +

Driver for Me Encoder New module. +More...

+
#include "MeEncoderNew.h"
+
+Include dependency graph for MeEncoderNew.cpp:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Macros

+#define HOLD   0x40
 
+#define SYNC   0x80
 
+#define CMD_RESET   0x00
 
+#define CMD_MOVE_TO   0x01
 
+#define CMD_MOVE   0x02
 
+#define CMD_MOVE_SPD   0x03
 
+#define CMD_STOP   0x05
 
+#define CMD_SET_SPEED_PID   0x10
 
+#define CMD_SET_POS_PID   0x11
 
+#define CMD_SET_CUR_POS   0x12
 
+#define CMD_SET_MODE   0x13
 
+#define CMD_SET_PWM   0x14
 
+#define CMD_SET_RATIO   0x15
 
+#define CMD_SET_PULSE   0x16
 
+#define CMD_SET_DEVID   0x17
 
+#define CMD_GET_SPEED_PID   0x20
 
+#define CMD_GET_POS_PID   0x21
 
+#define CMD_GET_POS   0x23
 
+#define CMD_GET_SPEED   0x24
 
+#define CMD_GET_RATIO   0x25
 
+#define CMD_GET_PULSE   0x26
 
+#define CMD_GET_LOCK_STATE   0x27
 
+#define CMD_GET_FIRWARE_VERSION   0x30
 
+

Detailed Description

+

Driver for Me Encoder New module.

+
Author
MakeBlock
+
Version
V1.0.0
+
Date
2016/03/18
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for Me EncoderNew device, The Me EncoderNew inherited the MeSerial class from SoftwareSerial.
+
Method List:
+
    +
  1. void MeEncoderNew::begin(void);
  2. +
  3. void MeEncoderNew::setAddr(uint8_t i2cAddr,uint8_t slot);
  4. +
  5. void MeEncoderNew::move(long angle, float speed, float lock_state);
  6. +
  7. void MeEncoderNew::moveTo(long angle, float speed,float lock_state);
  8. +
  9. void MeEncoderNew::runSpeed(int speed);
  10. +
  11. void MeEncoderNew::runTurns(long turns, float speed,float lock_state);
  12. +
  13. void MeEncoderNew::reset(void);
  14. +
  15. void MeEncoderNew::setSpeedPID(float p,float i,float d);
  16. +
  17. void MeEncoderNew::setPosPID(float p,float i,float d);
  18. +
  19. void MeEncoderNew::setMode(uint8_t mode);
  20. +
  21. void MeEncoderNew::setPWM(int pwm);
  22. +
  23. void MeEncoderNew::setCurrentPosition(long pulse_counter)
  24. +
  25. long MeEncoderNew::getCurrentPosition();
  26. +
  27. void MeEncoderNew::getSpeedPID(float * p,float * i,float * d);
  28. +
  29. void MeEncoderNew::getPosPID(float * p,float * i,float * d);
  30. +
  31. float MeEncoderNew::getCurrentSpeed(void);
  32. +
  33. void MeEncoderNew::sendCmd(void);
  34. +
  35. float MeEncoderNew::getRatio(void);
  36. +
  37. void MeEncoderNew::setRatio(float r);
  38. +
  39. int MeEncoderNew::getPulse(void);
  40. +
  41. void MeEncoderNew::setPulse(int p);
  42. +
  43. void MeEncoderNew::setDevid(int devid);
  44. +
  45. void MeEncoderNew::runSpeedAndTime(float speed, float time, float lock_state);
  46. +
  47. boolean MeEncoderNew::isTarPosReached(void);
  48. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan        2016/03/18     1.0.0            build the new
+Mark Yan        2017/06/09     1.0.1            add function setAddr
+
+
+
+ + + + diff --git a/doc/html/_me_encoder_new_8cpp__incl.map b/doc/html/_me_encoder_new_8cpp__incl.map new file mode 100644 index 00000000..05a654f6 --- /dev/null +++ b/doc/html/_me_encoder_new_8cpp__incl.map @@ -0,0 +1,47 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_encoder_new_8cpp__incl.md5 b/doc/html/_me_encoder_new_8cpp__incl.md5 new file mode 100644 index 00000000..3da40f07 --- /dev/null +++ b/doc/html/_me_encoder_new_8cpp__incl.md5 @@ -0,0 +1 @@ +eeb118496a2a2368d306e0d6b2406d55 \ No newline at end of file diff --git a/doc/html/_me_encoder_new_8cpp__incl.png b/doc/html/_me_encoder_new_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..ca786195ced976c214a4153b87eb4e32ff7f6437 GIT binary patch literal 48549 zcmd?RWmuGL6g5hh(j~2QqjZDPE!`!;NOyPX3kXQp(B0ig3P=sz2tzjvAYEsO_x-*T z--+Mn5-+ZcVV>uH?tAUE_u6X@As-c`(9wv|U|?X-Wu(PbU|`TMImnti zfPO>zBqt>fbN}!!<7a*h49sg78S(dOZos`i?p~?Rspt38o7DOlH4^W|KjZc)+e`Xq zsi@TuCp*DA=XEORV&QAT(SI|#@Di2w&g04FS-FYDRdk zc*F?^xpNV%#(^i7x1+HPwQ|w4ja4mak-hFCj%B-g)7QYUFH2s8Kd5D*|5sl*qfDU~ zuOD6~USe&%SRvA_w<%@f|3+IQpjo124;X#JDXd0FCi-vz&Q|L`O{a2ne%^!{{mjSHb4hwLp(kr6 z3tswhebFG1doR|un`5C?VJy$49<8eS!}nvYd{0;7EYl|5pIuKdJdoxz$9leP_Sj;c z;(>YphG?GlL818E^q1NW#ia$V&9ud~a?A70nZ<+IrNff8bmQ~g{rx#lPvH?Scs^SE z4)e5!TjnSO&K)cbhtFLP?966j?$${6HfL|A;fI>9&#S7n7IdR{W0!V6-lp-7eUzwv z-YXAJM*l0vgT>GUeYu>Dc#d0lCEs#^nQP3?Ia43;KYCsrAf4!AoSmyNCYvTdY>xTF z>`!{eB6%XqaWv!@SKsV$YN43tm(++O3R94yjhSEVw3zIl$We8mqdabCHpu_`KXc9< zSGNjeq|!1x!0ei@t8?(Fa7}F|t`rOnyRJNm+g0#?8bpa%NRwzEA>fR}KIGVt7j$sg zbUW*3^mdy3ccuRtnS366A zMe{Ef-8WO`>umm9-RtP+BqMucn-eOY#6BJN|M`TY)e3G)L+HY35w(er%cO38hI1QhiQK@9^)3V+%`IsAH+ypC~6snIWc_ zqhN78*C4vw%R*65S&Lrg-}gz5M?2@P^`#DT6fnj$H2s#3eg-XZ9BT^2JR|-T^VCew_nI#HWvJu{1WEdQCVp3*VO$2i_@Rbupi zua}#glKsJs3o@|UIy4;yq6z`*p;11bhh&m0H#$E`H%EecqWUl;~w> zkCH%srR=)s4ltdsvv!4xHz!tqUW`fqN_QCFPC<5PM5giCwD0ZoJcZB2a+Zm7Th}vl zMd$qArGo#5xZ<>t_ytS0blUP$NOH{Ru)h8r9dH+QXOk19@-GO#s*3+e^7Qh4edZKi z`Pp_UFvs8i^CQv9;EI~@>&O#B7yJlBdut_{u~x}qbeF3Q(D~l}?RArjZ^Zt7nkRp& zWxT)7*FWX;^_GYGmy2Z#;s3H*$P&xU*~! z>CM<4#wRe2HPl;%aL%aYiyUqrIwO1D`+tWJ7p+(*E$REV$qjIXOFe_-6iWTr&(y!4 z@{CCDo;m5FOpw5oaGM$e&+8{LM1fCT;roy4=hDOBT||60U0q*~o90%6q8^`%`luOk z{6Iq4m;3dr!CGVotJm(xG25bLfX2L#=N!#xvv1Bb;4iqev@2%6zs$=$GtBkF6MfQ^ zDV*#7j>Z4KkX}*PQ{^!x>a`_CK|FDN4DQPCK&!mm3~Y53zD8J?76~4FZ)n2YFBb8- ze}1{Xjl6GOk*F_4=GOE%Vd3T}rh42@mFf;}pOfT~3DX!tzT%!VviTs6N4O!zVDN|1 zQ8d<09Qlf{SC9-R#zJ82f~@Ke5PM*Pt1;S@~G)4%f!(r$}ieG`tQB^GiZ7q-m&ewprk8N&jTDGrf6D zdGXfNV65r24>#$#RtrDfaH0%LMeG_&d%XNqEI5W~v)dQ5S15P1|G9`U?G7Keu)8o%&mlHs@PYs7`_(T8Rh1nogode*YLd!)RhGGVf zx`5$iT6H#~+tAp^#|YnYutqe_ClGj!1jJY%=m3!W0*j}ZLzXal0YtLlsh7P;C9E{% z2JhHfIdIOcY(Qh)Vg4*G?YmP)a&|3o`xV z{>2$nj=d3!mtol#PD7osM*p1%Ie8!RnBBis7o)lTUfWK0JjJ0TKdI@yFOGn2{?(TgcY#3F^zkd;x&1OO^(Z;Wce z<)t)p>`Z_@b<|9aD6z&fV|4D<*|+cdF|_N8dVZJ|<;Ivv+1OzIBa(s`)k5bQ z>m&jrtY4do&l0v$_~znOaPi@9OG@|Cj=m7&D{ry_(?5K*7EEE3Uu4}>5k!X99I^FU ztGIo1K67u2YCTm$k_+y;$9%b9bX2ZfoEPlw!jQKe=&<^6M%MES7ndIwip@V|f*ovL4X$ zr%zD)d#}p*9#}{Jq-Gn^3a;%I4<9S?eot;5z;^4n8i! zxOAs2dE5j|1g^}cH0+!(6=1u=v!<+U%uqq<_NIa%AiiHic*(`Zih(z+=HKUeQ(422 zuOMr7ZcS=O08s(=`PtHzgoE3@T9%f$mJARfs~^?L9s^+6FdA%H6xa76zn;2dcl7qt z+!;+STquvapXE04$({d99{111Zo#F;t^tgVX$&~y9-S*?KXbDANWAOX0At154BF+F z8N?0fTe4fwjV&+L#u4grzW*9=Bb0&7OHlw?OO|I98u=sK+tgiLZPD}c;P=`=oqJ`& zmf&q|i2!Elfw2rNAq*YejZ%A&Ob32?VfeRD5S{;Xyuh$-4N}!oKj1;<~(#>vMuK;Bp0=dh7C)mh%?FD#G?t*JIU4 zjc`qnAny%H{Bf67!n7S;!vTv&r})Y7*e=Ui#*4c*9EuQdIjtcXnOU;rhfi)t4>UPi zOllBFjKo6nP<+z*Hmj23>yjJtx4e?wp38#a3Mc?-+rR7cVEiWMmvr#IxGEET<6-`( z_rvM9-{d+wg?8=hRvs0io}zV<;~d#w1?(1YQ){ovEkR_9%i7Cp?Uj9^3HV{mhE_OD z>)F9%F1eL@iOum}Mo*ancL5X*k3t~fKwu{b5${CL%@Fe3w$jHEA=%c0212d!iV(Fe zB6(;|?!*9{4na2+RjMho<<@T||7n}WLAkGvw@pzsZq6DC=^a3nWa&jX!Kl8SB1Yk# zpKKNkoP@(|pMcES!3hPe|11zFGsH@QtOi>@UT-gYy1X#sU|~hEZADlo-m0Yv0Yg3Jt;hI|tWwoEEP*V6rbG%^u2Tui+QfUp`Nb!cV}N@;>3 zZSmvG1!d&YXZWk-! zkMKa84vpv(oF++!RX=ZY=v%!>&~8v6^c5D@F09QC%7R*-%Z~C2g)rHaR_I{w>#A7q zGPeY~N}*&_qQ?7e?Pj6Uya&^dDJxl>$#O*#dN4C)PY1L5%Z3Db0(RW>53fNV7;drPE59<8kcfDW)z&P>gNd2A z;UR-~2|IgQDJ(CVnE1M;Ek^!%@rnn&Q1l^%1jjia0VFnw%>O4K(}D@x)z$GeY6c_I z@lusczCE2xIQApiZMPI5)M{tNuf>VddNm`Ets8aWMmp{$(ScV!{#1h4dg-BNo9Tb3i`R7E@iy@7^?& zZg~->K1HcHp7{Z2=eo{82jRu+L%dcNZUH?V7n{5k3&n*Xtl-Os^qkty=fPPrT#v1% z012I%yYLxxmkcwV-iT6HzhMxV(zq5f!nMP^rXd;aCpD%<|3= zZWy+{QDRJJtWf)8PAf#@Rj0CSQoPaqQvxt)!AbwfcMI$YL+NpWbKpMxDy4Z0$Hd*}ay zuoSn zUjkJiUxSicPlqF9-RJ{I;G1M+JmvInvbKQml{a%Yw+>u~p*gSxpN}t9xb7>D2OFBV ztcV-Ff&>HCdV+ZBCM8@)-FrgArq^Th1FEmMr`>QNa^U_VG$x&mUZqe_{xaa{W@1K1 zJ0;0{F);-d^scc0I(YnOU6eVhEgimu!-(1_T>)1C1Xffnm<9L}dZp##(T1=Bq`XY3 zX6d{-P}np9lsNgzIU*ToY>`jH8l6U@Z-4V#z=fI z=;g5rvo)9OWFREMO_=KV_93~;sb0p&FTQArU84n$4e4HtJ;qM@*Pi3k%YIoqIiweJ z7AD@%2P#Uk#l`3^%c{YWQ_u84m3=z{ zwiQhyLnc!|S==LU-B!9elXKqA3YM4B9&8U^KBs0n@NN5mzXB>nxiD~808O%aXWnbY z*Y9eosi9~~5LafkNswQz1-=1>mwX2A{Q!5v)dO|RIL)O#ZJWJ0blXt5sGZxLqCIh% zvVP4Sf98HlU3^#%RA8Irj4e2$Ln3$PZUas6(ZKYMW6JF=ufND=U9(hZq-H3_m#-`9g%uk-Q@2s`9B`lKTa`9#PsQcw6DHE0uH zY~jh_H6((S_O|uRT?M4_X*g>pyW=D_lYX=6r3}vrhjh0$b6kqK>`{7|PP*uvb8$68 zOML8$*AR5DmFpUr$5W{FaS7rY_SK`rS>Hhyx&e8 zaNnPkTN=On&+pVtmPdsOISHbY_TX@P4VIraB6$w_p6@49>yEM=Bsdn7S}3G(kdFvF zW>wrq`)(w`qxC0Cr|s4LGR>qOK=$&C(0bTIq_l(z@`jpH)~3+kMMuW7SAwmK7qIVD zEv>!kwgj&X5493F@?zZ_QR6ovPALwN%Q6S^bqRkB6Z1R3_RZ$PXPA`DBnX+)wrc z;)Q~!+^~zV^LmzBMPd%IEir!;zT402amn(Y@XImglYCJjJ1wZDBb9Z)5s=(I_@S01 zo*S+Bhm7&*03_r7{9n;&16Ro~k7(ce|o?TzRR}4?LLYtgOLq1nr z`8)H@v=Au~QIH5S6jWBQ(x#C{R12NR-!ZJX4xH!H;0LhTE)I@y$uTb@7kk|2KlnLgBSp}zKvseT?27?N zlOMz0OktVOGF!dXh9y*GD2?)kjZ_G;6~$hNFEvEnqWf(Pk)>cPyj^JIeB=F!_uSu_ z8L^C>|NEKcrEnOhUk0At*&xw^+j{`(jl8uW=ZD!Ie5prCP3*GivThtxchb`u4!;2} z1s{p!gzR+s*RFKe`~B*b6$orgG_y3xxV{$rP=$2i$>C~=NtMAYR=9JpX;)MCOKgs& zL5tE|oYtwO6RMfCKDO-8xe)GSS9;#ZT4e0Ue51W6Ef*};>;MT0CD;YLBR@s%`GSXs zM=E!#B>TOiWBh?9SAwbCC}Np_8c=k<&`1|+2jYy}>}eo=x-ReZU*Wjgzv z2nesI>O{V;O^Y5Y9Zmk4@}H8A5_|5+ZU-0c4)XDr8mm`=^Mxz$tG^#DHnFTqrgYuy zT<(BiYOeNbzjU)Is8SS+3xBE+`R1UVo*009K26}99~};P_*&*ma#(VB@~|~!a3%fG z7lcR&h?X-~r1wK%Zs!G69=j)wL_mkZ`V06MkkP_Ss-;vr@%GO~IYaaEor&lG4*nzxf771`^1b#{s%o*Pn?9|xD48841g`@fl}!DoQ<)Z) z$ild10-IqgHDxPrmVa->pdg?-6u&qOlo?WJZ_>&+;3X0xV)M|8;g7_Smy;Wa9{js$ zD~TP?Ns&O8=~nlpz0{ith|;FOS!|5?#Es zDnCh#Vsmzs3UVCSZ2c}5hwyy%3Er9~7c-e-GB^s&qWbRPx?tZ+Zdm_VrPgTv*Fu6N zP+k@X_XQoOKmfToWY9j9ci_*v!u<C*xj*0nTuwT%7xlg^)j2=o7UaS6L@p?PTt2 zQ4&(GPM?VSR1VrR{K%-PDnk&rJowZv>ZH--KB?uB%gWyZMoWT18|^*C0A-jLy3FI8 z9Z#+Y?gCVF|E?q7_#7OJJux~^i5e+BLIz1oBQN{;pu(IKWx7Mz?|;y=&Nc`yfe#{+ ze?Q(Y2lb1)RBH*`3wVn<>(x_HhJbnhVZdWUZ&v@Bdf#IG=0ZbE$_3X8s{tz9RFt3J zmGL0yG&$%pX#;}sc^Q}A1dwo;1IOg9^9g&(!$1t?v2wz|_tVE9L2sy#(Q_g#M0q5L zG2REUJOu2MNt*b<%!pj=FH2nyLlK!#?9964tSKx5Kg!QmW~r6VqaNLc0Al2iR6}@7 z*yg}5d;OamE}++12+V_P+U-iX+>#FF>Rco`pzpm8cl`e1j_6DI;crc7l1i%=i0ygz z^v3TN|7jEdd|C6WG^W&+&qs`p7v!0NA8@QGh zR7QW4x!7l=$3<61km}g5SDHAd`@W9Hv$@AemTiDtK|IQfGf-V&_xSLk#8&3d7T1Hg$;*E~XB9+RP44L;I3x0VV{L9KHbR8PH~P zq~iSPrI8eHfBV+6$a#!)yq8 z>PLry_~Q3U?MRBw53gFPgRCtoi13YnYF7d;!H|Ia7EXN4R<_JZB zAI_jNr$7FmU;P8mI86Cl)9`Kma->ckf)(uyoM2kts`5~LFNMiTGR@I^$C4;9u-Ia? z?<(TPsogW)WuwhdokWQsRfa0NEqDS{W&QS$jL}B)VJ;$E`QPjil&lhh7`Jwbiiy3D z*mvw#Tk3qIHOki;<83YbHeT|psankNbys)008U<&+~2)mB94qqDo+VSE?gcxab8e@}c$Y4bHIk-!~ zYA!`##swIf9*cIe`6J6hn85x)hVp0!x6p*C_IGo7>nv%`4cgw-ggvx901c2S3;3YB zB(J+Y+4Ja8FZfUX*~d3fszA~D(O2#7$<+7NFTTivy9P)U3DtFiueR`pkE#^42MQ}w zTcZH*-iHsUf5X8i$Vf^?llFpC%z?V^1U^j(QWUfaJB&1wHZl^W1b0q*6AMoB^Yl+Q zJ07>j_whKrnGp=4P%=?Npy>O2d8>PA0)7Ea!XqhL>$3+>%=P|(4Uj$D5b+62E9^WS zWMgM!9aKBpBu8qixViCD9VzF$>xVi@?74rOM+T!KT}`Psw;fh$LOVP=YfHyBviQB~ zj4iJN2xFsHnd}%VUbz{-sLDZ?6G^+E8qkb-P^NYPYo~eY*pOd-F^*6H?b6T9L>cyj z+4^p>sBC)EZxv1!YOUtS`OTZtoAY<~cFAv3&G=PvpRyn)4Adoo0}lozU)R4QOhjFX zkz;teQa89G}L&$=Nj3(_WaqlN%kdTRI6s+ViGumc9U~>B=8{bb_@(e+1OsY z!S=mi>IjJfVt3e!#!?u2LSva4%o;%PViBpYn87HTGh&1oEc`eWD~N{9&Kw zb!BSvr;#0Od?U{{lbh44+cpEA9JT$f|9I#tnSd<_E)A`LZ~3slPg8R!%=1MALwI6q z)&4e`d9lQR8)Ehi*}u^o*J;w`quia(6w{L@$@TF!}ON zX(CDebosCi_}(Zf&;H5Fo>O>Af-xV(*fDv7*3y_Ozn=Spx0@FFf9S`=`YcRiXnRbO|9vg zcK{8>!6LOp^}FtUw$i(){IG}|>?$*vSbvIhq1Kv{(+8u;oXHofgV{)fS`OuoJ6c6d z>W*<)AosH>&4r{X+R_#Ye!g;1Z9M3!;z2(cCj**I$Lt;z!B~*mQXHK)TNoUHnFG>C z1qTvHa8TJ!SK}z+1akRZF`p2fy(~gCiXu91t=`7@Or`Ms@Cg{;TfX(3aj}T+hy+aH zjR~_@$qJA!U7-f6N44bP=)Hots?X2NjYQSM@cTi4{=(2cw~Ej1P>qcM&aM+1WFg+ZKiy;-xw=>&zvM)2j2jZ*FC^ z_R7J@w%bY{4C3s{a4Qe-%vr3Ytq&xyy~(PZStAZFOQT5fFFzH!LpPfJ>ZPpiz~5)- zhlqWXj*^v0*{zckXKcp6)<_? zP~Stl;WJw~9X;X#xeOD{T;v^XJ=bHAY$7vW%Ev&ld_M3t%t%8mQQ}xOps#(EdTAI( zpZZ<}G3B9mbN#cRhN5_*C(@4sHXX6S&RV!QAL`c3Vz&_R=Id=_Kqbd}YLcp7Jq$71 zcTmeS>-Pfg=tDy2iLmNh%QF3Q$)-3o`9x$bXe5duHMy}?;^|4%$&rC;Y{USeHy7=nQ zL(SxGc}>pwWT~(O1QSjCXtA8 zKn9SDdYiBz=?DrZq>5*Ft&*bpQ+Md{rD!w%#oH&f%%;t?XF{3NT<b1(EXr|ok1QD`4>)^xx2k=kX@`}6{GVSSZ-f_jPhPnzVpHM(^2oiWqv8jntT zP8+|1Z$JA?rFUeHlesP^I|aRao-IWG1x4X+6?{i3Eolc@JNiB$RDD?eSuv^k*~;84 zVD@ZUXf?gPEG;su(vO8vO`vsAfWq)Sfh(p9|6cd5L%(W=cC4ESz5#kHYLQ>Mgu`gR zd!>!E$bt>j+72`Wfk}w|)=c&6Wj5KE0PZYl2jol*etvp?WA}FY%g$gzER&v`ogS@W z1egk%vG+6k3+~mSff(CAK|S$f0`413y+jo^qaMf1lGy$qcQSWbRBoD_I*$eth^fqwa{Xhj6X18FPGOddhINe5#%!2@Xk<{?Qj^Z z`Kx$e$$Zx9|3a^`WYSS$WHa-WpP9h zLK_NP(MvU;ulzoj2~j=9XT%c@otR=v%wL-h`*8Rv0!Il=ofu3~s9!p!*)qV+Z zO4JJ<(dGs!?n37p+Q5m~inm_{86Bj|HBikETaercJn2DsG)qKfa8*9upa`%StRqel zl^bJB1p7^Ikxr|!IMHau8$+?+U72Lv&2ACQX>ZW(Z`GmzTQx?#Ic~N)3;MFgNBP(y z5KRj{k`|8X=!F_2m6;8#XC)6OlMdP|fyDdO!?D2}$Z4snuQ)Po^z2IjNG+jgEF$8# zfURhSI_yx1%Bl8Pi>UqcXk}{SRlHqxZl?xwFSy%Ao_z!kAz{FK_)}EL*=r>AmqO+E z)be1pl{dK|+M<3yE~*rQ8qNX6#d&tVo%&J$B>2nD@69+@FN!6b(shV2b8A7^lQKg+zpnfAdSlx0O9k zupJr{+!hVokpnoscq8JFmDU7`Fr4)AoA@?jbP|!jrKT=aZyhazHT9v*{K#M4BvYGG zsI1I1fRaSQC8B=IXrS?79V?{72_#?PSdX9Xl z^L~?a!P~R93HYw|*Db>Rhz`lUh7-9t{iA_kuJxbKssOcJcKvbe1V-Ze=1gptH!`*M ze3<9O?9VK~e4<1bu)}(*R^!t5-M1|u!MxZOd^Z7z>}y=gfE2k7WX-{F5-IlKJ5HC4 ze))KD{BrWXaE7bA>RR~n-#F!@5uX~ir+{ici9GPWigt{B3b7Xn5B80Ic@(sJteD0Z z=#Jo<-1h;D3f>8dvv#(Z8oiV(z5=yyGBOKp5EyWd`fgZyJ?h7?AAGj@!ufbDZ=hOQ zqW#3r5SB!GjxJ&Q>TlO#v)A}D;Hpc|ttzo*^*FO3La8lp$3FtE z20u?f+T(Ip3Z0HD`N!&dY$obZ_QH*U*Hgl}glzlTuz@>$Qgw(06%!ieJyGXI0Es0adYq-?3Lr|U$% zE&3=+%|{*}oy5V%5JMa-fl%#_*2jXdkL^?n9B`#uDM-qT@G{`zbxv5>Qv?5Q?fS3o zi>W^e&ywrOI}>bSPpUVAT4#!M?g2QMF{BB7x3CnmEx}BZyRmhx3RpHU!V5ZtzJ_WM zc_1$tzDt5WO`Xl|s^!+DV{~_w+|Fx15m<5rVSV*(z=Qt(cD=Y0LxfJ^Mpgm*{0>4b zqpP?w{%DvUNrv@AEF`{Hvb1KV=MQtrcnm$x*9s&jGmGrCu+Dok-i}BRlMMK+EmWI^ zBJMP1&NUR>snl=rb;roqg8}&zbZ2BflJ=4g<6pFct{2J#OPUf8+gDnbhRMNGtzG4? zKExeT5oz-CU&xPY_T~huib56IOMAV->hXlaOERf;{c2$oN=m|%B7O-aln$@T(cCdd zBV_u!C8g10D4L!y)!i`JW=LjT zssY2zMjgMLn1!ke>NyzV-spEOK;3Wh!fS4*@43!C;3op;&BHe=QM>Scn3R%a40I_W za=*7C5I;@};*o%OgK?4LF8Ayd@5zR)rtqON0o_wg7hzETMt+(kY|F0XFoXdneH2r9 zG5GpnvP-svMagVcdjGX{&coP^YCyuF2JmMr*}cdWQMY#PU_G>tj!8)D#`fqwXbe%h z;C-nT<;!FWya(b5sw*x^In0f}n46aL98J20rWynCj(It|xzMJD>McQ~f$v{2%HAaE zsxPavoUGDOxnH;9+yMRB5Db777>_-EN%n6U_TH_6ftU}@NBG+DVj(m&@ExUORfpH~ zMBJnV$@Q!9dQjfj{?o(unEoG~B5$Pf5VCP@%Nb>2A$&W>PMv-)Q%+W1k=O^fGHHYciqB8R-$QyN=QQCrq~dk644%~-jvS&&HQq#FV7x)>u=Im^QWP(;F?v(JTAnl% zto%d`7q#s)g}r~Lljj{7)XFd`LiNR>G<+D^#3FvI7;{jITA7sS;|jM)yfu*J=^E+e zN@&c}HI{c*o%zQe8i`Y-z#3iqGn|ZHHr?8d35O**SZ&Olb|Md^_fJ!hnUp^_;qRdE z_GD}PRtKo+UU*EMzDNehUQmf*tHJWmAwIDe7V-4Dx%SG}AYbd^Fz9T-@Z#UncNeLC zDY};KmQlNA4`W91tgwq13orEQpw&ROvueoEPG{|9NgCs#1jN7y$8Pq_LfGZOP<5({ zf_C*qlbEp)F^?HNGLZt-bL;hx#M^~HKvG{Q%1(^o3tQI}lf~*?fC)xpZYrO( zN^s1%3h?&p8mKiKmRr3ePnk=-f+BhD1bqB?aiTs9OaZG3*TiI}?u>8vr}68|qdSQ| zL>-1}69F#Qv0Sz6&Z7YKlzG{lIWYCe@; z)`7V9sa*#LLdb)0h22NhpZw-%0_}+W1Sg8+L9Q2Rhd?aiaeF&Wc_Iy%ell}C<%0+5c@UD+_gFzlrS*g!0yc3 zWxU`u^W-WgW$K1{XaG^Mz0a2R{TtHkKONp<`?@9uyL{cRlj8=R@zF%Mvq9b zU$~N3sq&9p^J5p2cy*`wIB3gMxxF)p!_NZDoxzm3JHxQ>cIuve>R|@*KS|Y25PeUs z)IF=%jQ_}eV%@X=eNN(p_O-sFrs2otcb!Xkh;1i zEq$jn{~Z$bdRX38m1Xs8>+|V+9wzBKVzv^df%7@d;yQ_i ztd0`&a6Pd1l5ScVqslvsx5stUeAmU*EApfmnx=GMvDnRdLcq0fhg_g{ox11dwB19{6vB61U+1tL#-d?a?^(OjZ1+QD@DO{*RNj2>Gk*>%FDuO z_p9AO$v;BParsyV6bWG>s&b$)q*Q;1i9a7@3(5^`au?ZvSwBX3H9BE#IDZuVG>R9A zn|SPtqR=(Oaz`4u*E#iY602$80kLgB0}*+NJV(zflkY?b1i?eZBmno$!K`u`ft$51$DO>0T?Sq58zD8L zIJAzP4~^}+f`1q+NA6XYDOZ9)o>|Nh8}=tvNmY}(R$UU?XsMwCEO1h=u8piB{WaR* zx0MwJbOIQ=;)(j|^h`e=4n*teKw|uHsx>1t>9LGiD)*F>~e0Vg4A^ZSC z8Z({2tsGuU#5;@<#Hpexmur`_qEt4PG$h4Lr5BvvaFko&zavhCsqC6LN;&&m?U{eC zsyHa`5C5ffWCcMb)F9~pss>QX52YQNBQ>U}Xe*B^6w9S%wj7C3Z_r#Wv1nsH;#X24 z5G?RCBKj!>=PG_DDGps%fF21lKK@RNJKmD&h3#v(Af_|jp_Pui-eA!{;ja+0 z5w@i>{;+r6#-_5j95N@(lYRf`Y}WplucoJB>^kp+`p`yFM~$uWHrgL4 zPJ`sePHebwfBo$o-g#~JtEo>RZp6IkbA(^$mk4G8#r-$vT{Q>>EPoQwRh~~ZwsW254U#%0BpHQo6OZ#Tpz5DRK;v@MfzmhG`p#0Ju<3)&V zbQ`iAW+!^!{@Z^#cK&({4da%HHozELGt0Wul9`Qan!eF5uxs9}TKbr14fu-5H2x49 zCW2KJ2EF{9_93$XIyg_*Ll`FI9WU*Y0wB%2V8kp_Djs0m?~gw{1Z_W*gC~-!%X}#} z6wR5NtZy`g=*vmS((tZCVfa;p<*e1Er(ut-R(UT!Mtw+y2rJKC&dvEp7E1UxLg)=I zjG@c*Ido3@TwL%Ga1wQcxNNz??)-M>n6Ypa7MnUWLZ>ns4ed?{EHD46D3Q)|Uc;cr^EK4!$hc#hWv;ofQKQ?s2r4^~P3QO#aJ z@zPv=ugT}D9n})Gx0gg&Sw6Fh)>eErAYrg66E}A4oU?Y!JF;VGD!DFrIkPM8oyC}I ztO&!3mH0xi*zV*)@9sz8H>Q{PQ1DnK_qb=>z`5zhRzm~YxZLqn-8_($V0kOU5aS36 zp8r;j7RR-dHrM|S<>Vic(FJ_d><`(Zs~9w1nw6ZMsnrjAFNL!-&xF+S9UqXcOfW^I z$EzBv>gWAMw{zRhwe6f;HLe|vAnOL_i^e+gq{Oi(yCWc3RN7U{U1vG`$Q=*kRE4(k z{Euo@P;uy5v%%(edGH&d1%C>-C0K6w`U@Rx_ARu|_j!Ujp1oiV@Mrb-8h$Bs*FCH0F9b#TK&%;RYj+GVDc|DTRpF1hxkUi~=lvSflhqDT&-0v6ZpMhyp z_;+C506@|YhprP~Cjf!PSb719S2qCcl!{8H!>3_fnMO@(f8R!b1~}4}_koJP9TH1F z`mvL|n)Er-wjoEaABx5N37R!P_BSPvrb)>Y5F)ST*+^ycGktWNg z6MX61Zcp&zQFDVynA@Rrw`wQ+7*~bQJa%DKqfmyWr9-cT;kNJ|x?CPgFGI3c10mfh zw^X`RS(3jWux$_&UtX=hFF$!X(dj|9iwja+7Br&%xQbgwWZ^bMqV z!>o+-Wj-bH2M<`gaLJkcE9%(;XL1vdPtO3SVEHm8NZ0w&A8v(B3I;0rTrK{ho&&~W zx)Bxl=Vm)PC`n<{Tjdp7t~t7i`in9Q7tdL(H!L(WQjthuZp4DGV>B{o5I$Vd#G0ZQ zsy5gF5)5BX!XxoBK9S<)xj!Ym|%}s z%i^%lwb1CKR%g)fI45f`h$H;eU(ey~+YQAW{G!VG^`r#OUuakgRX*V*k5HDxISV)Y z^}Fjq%E|P(}EAPm))VD?+>6I zI+1XD^@?m@y}*>iw0JrxIydV>>d<&1yk4jSUOyu^eq;Zp(53ZP3y5bT_M5Ycd?WHJ zx{8W^wsX(aLIHoITdGdN03W`&UFM#@zxp|$i0?^MjGfq0q&i7TOZ4WBypS)8#7id4 z1lgmggQ67-%mjZLoHz#G?s)lD^6B)3R3@WO$&*BI3< z3$6ZubTwL@9x%QRTyL_JBT!jvOBA=<~`u`jg}Dx zgcy>tVaE9F`VDPgU53mFkf4lk-3#C5PiuG>$LTdwr7c(%8N*;D!P#K*U7mnO9?`>+ zscVLW9pl_Xa9A+4Feex|ZEQD`%hQ5l7t5*omPZ!x04uA7MR2n#5}*!7`{b1nIDo~? z$UpUZ4Qz3UIw=z9I$LOyqQ$$%KXbc}rHjhe8PvD;b`ujz)xJ3-w!UB3{dX3CU%oVr z<^C_FL7w)ju`cgUld=I8C<&>SpXBrh;CuLGdl|+$7^TqH7eg#{ZPN5|jfM1M=dlg` z@&R{FDFXR(8U5e-O1Zz*q9*hp>rFg(Dh?8ji(3?>#H;y;jnnAq;BfuUvB`11P)mBN zSGFV_=xuUuvkJIC;xM{rsoOKf>iXpAcn-SD}7*ipNP?dJV7orFHY@-?EISRUD&9fC_=}!|L(G1OB`0RU`qXwOl(EGym2l^Bq^8;wn zIJck{8gKtQxzM%khtjAf&@co7A3Gf&aZFRrL94ob%dg_Vfars;7YrfnUGJfhIIe+4 zdw^q#Q-XBR61<~2AI~`VwMez%`4DJ>0xe(tI=5$6u*a$UDO6sX1A?44NqG(QH$p!m ze1~6@_=5ArDR_NbM?<4kvielNl{AnFD*`Kl3ab@u4QBqMLCp&DCBau`U^Z}}OmrTN zS*qZ4Uy(j_ok3JvT1iC&!0$Y}>^B(ENx**$$X_Yv( zHZtjs*}H*|V-oPIcI4Nc6Gb1icg=s}(HmyZR{EZxuW<0>XO(m=UxBUS^BrbSE3ga| z-BImI8P&B-E`6GOF|3EWnEVES>Wo` zFW2wgU$L$8lWIT$Iu%wOFU86M(JqySOLm&XW0!Dph~%zbKovf@I`>r64Ca#jqT{y8 zSF2Ve@G*r?I$T{xtIaR3pz0UW!~llNfi^d}3gruv7% zsDf-AkqM+y-lEvszy~a0g~Fu9T2%iNW=%yxu!45>L80;iB8CJ5CPCjH15=rLM1|zd zFbHdf<2Tnv`qz5Ie+N#<#Ys5(iEFfibyiG2PXQJSz234$3XRo@&&q{qY-#ExyzoDS zv4w3rxor5Ek3)~8B4W4FKzHF&bpL~WhWX|8G6pkp-9<*j7@MtUD#H=SDp_!-Mccw2 zH2d+JJY_$mRA|Y$2<$N~!lO1zCzJDvtlSjWju6wIv`UkaFrL)5r^WbIT!jmH(|@ub zR_&b*rtv(E=YP;L+R7U+G;lr{63gXT3-3O-zsBXRP{f1rh0Q`)LLul6GXTiuS0M?_ zIyY$6oNSUa7SQ`z+2obDw0cD!coDHwk}3t?6A((+3Hy?K{I;_5!5s2Bla7FM3!!)U zJ_HBm6C-n2on05%$yzDM#*kp@n>wF{ao+_U@4OGK@6>K-ZSwEdL#)38FsjQf_`n@P3s8-n2fOhbEAHrkcu4CZ0&Z=XhzQ$5t zUo?vHqD#GG@7O*~PT#D+YCw1ezp&b*S6`zwRsV}vAtyT${y3NguGffU%I;>t5QbGdfQEg`OU&Z zf~j4t-sO!};UpnI;{kEsC-Nh>QmlU%IN@sD8*jGjl8%l0Kb(t61oNjvuIQ{N9pC3S zCdqwWjXD3-_x*6JPE!XEOaI|zgM%I`5Bj(D(4W}QEre@R(}MZ6)%yMWm!Qf?y1ui& zIRnfOO#ms3e6$+`-jA8&4Y_k{;ZW%uiMB-Tp&d%EE6| z{K8B6Ny^q;2mALrXDbt>nVR-PDKSonl%p(t8 zE^e4jN$owX_+<*N$!Ij+vFsJDS!-1Vd8RBDZ;)bZ1Ppx{+Kb{_2PvH{)5M3+6O6Vk zu)}_~zr-g5@0itu1Q zGx0OXo${wGebOLIL84y1M@qh%Gw(W0opj$#a$mnpaAzDu#6YHmi)7#o9nn&!w?t0P zk6E!It`NXNG|1Gq-`J=$YXDXxDw?8S!3U?n*x5;-YFw@ZBkGw93$wG{DN-6_3?Zo* z(|jbczm%)$pHSn2Vqz}3+tBYGXFWw-;<#cusRa*Z8x8EXLbp>ljb^2J;oJ2SW+(iy zMX)Rg*7@Jqdh4*NzNl-I5b18Dq`SMN<50q(yOEGObV>;dNOyOqbO{P_Na;=wNQZRZ zjlcJOzWdzo{)harU3;xH=Nxm4F*o6k8&gwaTVZKTL6v92p!aw-IRInx8mmX)1|c`- z{xuF{BdXIVn#akea*l;%dclJLj8Izn_N_4;ws$#@ghA~a*n1Nzt`gS&fEYu$ z@+*%Fq2-tc>})m_y!`KA`Hx)0)D| zpkDMcg>Sy=5j%!3aMGuocgJixc&!b>DI`e>X$I;EtFK;gY^-awOJCupz6zPby9){s z*-}P=SbVN!Nf8wPoW_mk$J$MQs+BBCe=754)*r8sYwFW&({qOz82UEC}u`iHvS)kqonz(NdNuOx*K5)T#}j%0+XFZ%Ax|AY5|{}K>i-W!hEiS zC)-$XE$YFWd(^vOJ=g7WB-Zm_wp8R`PJ7!saa7$re^MdRpE5oO`LmFlezT=ANsZdb z4GnBZO(5wmoT=CH`mj&r?a==^E!aCF!a*S#l36WzwG8d^?PLM>dM|c&PgL|3 zf0Mo`ZrSCL$$P`8a7`*s<^LMT6Aq;?NmCZ~x{ za@V^ksa;MTNQp}SQ$d51tEWRhy0)NcO^m179Y&qZs&RME&zVMxrn_E(&D7zNVo)j- z32gN>bIP+Asjlwuc@T+E_QfDpT z;&WqjxXvE7;(GyqDt$;eXT5F4dZwiYMldJ(bh4uNx!@V8i*V+q#k4WkFQ1R^b~bab z{Lk4ul(JZ}>J>rRQ6xl|RYeFbrCnn03oE@C)ttrpG;Qdj8_Ro5qP%*l>t;1)EBY6+ zbSUpujBcn=b7Pb~0H894Y>2R?Ke>R(*eMMw&+#h8`U+Y;nb93K1SXoSWo1+FW=rXB zaqQ`84L7G?Ji*qKU3b-GuI5Nc?Hc1JNREUgRB8jbS1L&c;2;2U)2E!T=+g_9sP~Ht zeL*%VUVwggF3gcLyzC&Y6l8W^@3r`X7Owh-=ktgh4eOu`Ibx=7@Z%}H>+j_x0*2+-IM2b)9i@& zX~<<50V_UZ;P=8HrT8$dT#g$k*|`wmo<@c|6TQIJo+Qw;TPR$YqY)$7HcqQ;s&Ipu z(Ouj7R5$CYDl|AwMG{iSs-^-O8|K$s=ZC|)kS=lN4YxS&3Jwl?owL~`iM>ZpUHxHf z3%}(qL0|y#S{|RlxrDKps@n>iEasuh>Mdvdkhl~L9wPXcAxIOTQ0OIod|}rZx3*kd z+x*UF@%6dyf|pNK&7~v8Pbv8boV1-qP;E1#%`JiGI(hSI6bJIiuj$>V_q9O}`}dul zVm))hV$C(3o&Lu9dU0?^y4KhtIehbk`QYTI>Pr=SW&9E;{ZOJxmt3Z+!_>hK(dl@H zd(Hi)u4hn6Irl4v!0q?6o{mG)#~TnB47UH4`{b}?O=8qF%e9=OgE9B_LHplVg{7ks zCu^8NuG*2>A^IjJCW!~!tK;X(4Ea2I2+S(sG@|0%mHxP7%)n5p5V;9^pib0oV*a#q)gga}`2>AA-62GYg}e!YBe~=pF1% zoY4Ldb8b+n#OM5%0&T8;!eVH^)uIC@miYNZl8I%j_fEE#H}E|=t-x#dt(*$vs=uS04h~R`tsfskLQ zXz2DmS?X`{k@8CuN$FkZgSkUvX^qf3xh3M({IY+LSa!aJrS|0COC{wdNAST)9ajz5 zaKn-1>gcB#X#a;%kZ{j2S|&Lk=6=)j`QmGXJKI3e#)&F22O&L*SXhI8{=@cYwbY9@ zGu9OfzhZVPMkD34v%`_0nr8PgIt52S-n(Ur%6xR-o7xjtHQqvpiE0|4FHxX z#fJ!jA zWa_=Oxwv$4TfvCxpv@8>Zjme-u*FL$sw2(*-f>5C39P6Ai<(L>quY1wyP*MjCT@X8 z{h1abvGmP@&M-Mt-t&1sZyb-(1ZOQv65>v>z@Mn{&J>obXqN*3h|(s{ahEXu2VqcY zc=E2iJnx!Qt;qhg4vkq(+V+K^2HZY%f3|IJE_>61c1_XhUpK1k0L0^DfOwKb>f@i? zyROPw_4hr_<=3}ZS9euikB^;4hiN9|mnxViez+BH^*wG1#83`C_6fd)U|Rb2|Dz8| zvTLGC9trF#Zg*80(5hm$GV+Ui)IY9zZ^aaCbLGO&dNlO9iWFZSzJ;wy$n$I{`7l`h zq@(DeynM)6xIMe30Ij8VZTvlzSx?llcCDz1pD*PvdROX8_WnN=kWSxlW5$FBo!=64 z%Z9f9tCvl)=3GR@R5gw3TXd@Vz>)h_F;u?+vzS1r9O$Y`4y2)7y(8flA_CTPTqVf= z?Z=^qjxR(f_G?!c=PgfycULW4wbh^ZE9UoAQo2`H>BhspkHj~pHZw{%H7YHRv)BhMbxVXC z9S&Yxk@df^4;{nV@D3TC3OKBxWbC?0>yBMp8Z@&N7BS%^B=xL%yv z$(>sXSY4~tRgcTBq5L#7!bL*2|L=co1^S~I7!CCoJ(gS#mSyy;FBJ>#2hQn+_u+us zK4NCg+YSoy$m0K^q#isHloZh2y* z)a7ijd>WqnvyrS-%wJAC{|)gso)%2jO#khmKnd}G;PAG*wy~o#17^dc9+dhc{T#O# z!QA>;i`%@-X3ss37MF-DSzWG8KNlL|yL9g)PC^eRUh!f^4$K_MuT)Ps40&nH?7{=w zC+zuufmwp@q$2KT82B}}cs5lA(pq`?t7L4 zWxO2nzhAtPKEpVdI6lnrr?@!RBd<89UlM)O(;4knDJ^%SOp$zW`op|Uh#+Zh_oG#u z6G+|B=2@Y83$3VU;yn|A3%yIV6r6|3%hC$o-bW}R&M zxDAeoef6dE?~tEY+_&zds9EEqF#-K!wtg4y<;(N0d*gF?9o&9?J(pLmLes~M9{1$O zc6EX3-_NeYIr~27ea=OYRN9`esWUQij@x!&oA@$PAF~_v-<6QI4c9d_IkxXy?e6K= z_qcd^pr{oTRz170PCQv%ZmxVfwy(-Dp^8Po^hI#_+{J~5a_8+q6!<~Tq5kaz8*N18 zTkC+w@V_J_qXrNP2hBl~SKB|WoK!@YOdOljxdU{GX178twRtRS`7C)B!cg&F&bY~J zWdlf~;8dJx9Oy9+6NQ^uuo1S1!#$LF2Kh@En@6UAE1Cxh?AktZxlX7A$)}-!;2GXW zAV!(A_Fwg4cgCja=;V>|n&~27`#?VIxL6>KtlM7Y?|wQQUFPS>&5d>;b+Ks}pm?HF zcNU2bYU4uIORaMK-!0}b_@}8Ym?m*{aG?rmgmEG!Ns#0~$y(a)=2(Bs3V8h57`(4p$F5OhZ7V?>4~Qr_G{7 zb}6pK?pMK0b6gsCNsIP1>4a6|Bp@pCH^1LHy7%XBPtHYHQ<-h05i5flKXZ3p1V88DMaN&e?f-ux@>1K;yM;pap4LTYTceMG7MVuWDO&Nfn|b*9_lQu|3whr8xe* zb>|wu5Dy^~p-9~_O5N%lvj7ejeCQvQ9DXhz{sYE(5e;N}X3{MYtb9ET!H#78-jyMe zskEGbn1Nw;(I&kOO7OZqH=T$3l0)mo8J^&slv!706@GrbQ_8}ujllF+s$NiS*MI8y zQL`%in&nes(fCgi-l8@mOtH=;J<3y&Xzl?F>oJl?!AlOwI5}aeRv}VLov{QbYx4l3 z@PD`PKb`4eQeYTl0eX{O1(j7uD|1mqKZyDu^};*mI-)LjjHfVs=Q(vK4QZBIF0;kL z$7-1~oXVhB{Ei6>?bKv5=@cSORRU%3mbkwXaHJL$UD_wHpPQWI`6Idey{aj_U<7pW zHDZ5@ZmMX@wF9!RlN0oKqit%Vcl|q2ebOykaMe4M-LSa`W{_^PKU;0zp#x|W?CAUN z2|3tJ%jf7EW$+) zu0xc4BkMwx7?k~)!S>U*Q+c`Y)}awC-=0{yR9Ymo;149^@}2v>`pJVY0(0;Se>t^U zCG58o*BIZ8!yBu+d5yU-jy}*>V$W+m`W_axDm{2?&duAm7+noFG6>aH`O8T9NG2Sd zLbl`LX5%EU=Y2MEApQ;2{G^s5v5mr{TNs`+4VbN04_9kfBGIWYFLv$8wssII0X2R@ z+qj>Sk(Ajw&TtN*t3VTPZa7jTU2!Ev81I*vnQ8CrthNi`N#Ad;oPt!_VYS@R7?H)` z!8t1fN+8iN{{Uv8f-BvL_j3St1W-@Y9G9oU6ReElzos7!}R}a03&( zr!KbK+RC@yAP?0s6=@lH{|X6By{2zdKhdVg*+%Y#!4(*FIf=H+jisg(nGB}AvD4Ix z^GpV#4eH(%4*_Zn39r!$X|?FB2q_*!hFAoDKOuZHAgb>7JTE4|8?l+i#Y37^d62g+5o%w374%HoO~Y7{v~Y4pFW+FNb*q?ku<^{@Om1jGjD;_US~#0YGO|F>d-6J$0B&x=5djX7`PDmwBs2VGt3T zl+l~sVj4%}z;35k-+&7ImnD&VNJpnup}hYcu8l4sRJryqfErwyxr!o1>t=CFIGK|M zkwr`Z>PHv$+5+@5Y)yQ0!kYJap-77 z&r(aDOB?hleB@W1)u(3%AIgTKt>w-l=Jb~U)R?9xK>WkPh`NsmckFAzpT9sf4fbBZ zAY`AnUBa1qM#pzPNWGcl zXa#-RK56Cb!-Axtvb}PVvTQed7WdAz1XXyk`>bU*ZKzPHye=A5cq`S{FRVb;>XE>$ z>-#*48w-DSqwaGlGg?sJE+ycb{k8BvMf$IW3-c*Lqea;8XbX|b_kG87HdnVjq+(3p zOd+F~hEBGkm`#_{goU%Lxtq_swa@wn)Dd#>k2L^&a4GFArswy4lu}PN70~j0A>F=+ z%Q^*m_pe(N|I^B+Wgh(s-V9UsZ`$a*-kSN9ei~8`u(Z8V|ET&9hI(Ik_tq%wOOD=s68jenmUaq6w4aU_7L&0J58*kSFbj3!Z-1YteQ)Qica7enpL z&`+37cyTE!Ge&vSB{FLYlo|!(gjCmAz?V3!{3*i_04M7Ju16byfg+o!MV8L`;6@=a z3mB0q#|MLS0jy%O!&@SV*Eo3}tMY8D;vTpkoRnT5N7+woP5KhXGYZa-z4oClG6j4% zGjy_i+wRZ65QFtuH^YkLgcxPq*q|rUcOMgDgcPT*JY$GI{tV?@#`$o?Qpv`IkMt)f z8r*u&M)h)K>hH{%v_`abJuE7XVbRJxorjR7*D|u98isERuj0slAb@M4elVejoeyl= zJlf_B^L$p~56?wZXJ<~R`?oazl=kUpmmfD58KM)1LJb3FRtLrs1RLJHP`*UG=QJ2m z$5f3(2O^0Tf0Ot~uhZQlLxA0AlsoP84FHxxI+b0#pPeG)$&adP_Ei zn@U!r7N(Kk^k3>DZPLFzcVwUey@{g2MuTgMK`mZdTm}>&DOQfm72rJYW2-qTmm5 z6Beh5;tHegCcVc)hy<^{urg8~FF26wUmH>4P!T5ETGjLh8rc>w|f`}b6v8VAFSU6lP6fyVrQ*0baAN%?HWBvPg+IVKutE3jej zwe^$vQy5uGl`H4;6RZEJ|7}b}TL`$#A6<@`onA!lTfUwG+&1+EO4vb-;cwSjaFr2W zcS)oSv&;C{e;opa_=;ngb8wB@6a$6c2JpJh+}w0>exM@JNY@cHwFvnlq1*|&Q+BYl3{k@X~_*EdW#DJHfqaE;O1o@umfFAfWqp3Afq z5+|z{^Y#!e&N^lzK3^~AD}eF5qGW|QU#249<~^riMDdNGB9kAWD1>C&u!|aU*j=x6 zH_A?O_(jHpju!uNPmd~@ur`XAAy~0%P7}x?9<{)BAeaXzCey5^z+*FseReB9%(Qv? z4LH}4U=L4};9i0-8P^3Qsbp+f{o_6nTr%9*$~edj<4OBNKanmVWyS-B9W+@cIw)~) zoSZkgbvdh8b62_oJ|i=h{WFeuM}Y1r+iI}+q-MPD0GoySoYl`QfYz4vnW*6B09TP{ z)G6+!s2EC#&@$lG=DYw}*nIjz>(5h=$9J}QOV}C4g#4|5s zt@>Bva#IK0|8vLYmP2LQy+G;t8q^xW!?IyIA;iHM8+thb%3y@oY768WWFZe={S10- z?OT{rZDIQFiVS*A_`islz8}y8X~bTk>>5j4*RQNGq!U$7)V6XkR-9pGJ`*gVgU^mV z>Y{N`4mpfE&~pk5c^U9B(!TdNF>xYI2v{m<$urK9ZxsF+GtMK5BJptSP5k0@!3hsk zg=PBVurImEyVU{Ke)IATDRys-t21GLaqhp4@)!)XvPe0M5)QS$Mq%|E-LL%sR7y7j zL5Y059LZDKu4r;0lB!f~7B3dIhx@NHpbG6lmcD%zbMk4!lc!b*6I}Bmr}9#32SNn2 zb^&yJOj!v@`Q((y_d_JZX_r8B+k76_R)k#L_^2g)jJLGxNZp@fr=fqoXH%^;4h?ci(IJ2Q(VWoAe|8_7A4g1sC)U$th zc>AX)BIz(hpS>>*s=HSPuo~?8q%nZ{oA#Op;D{Hg;PU#c%y@7wb)@o0y@zm3UQiOj z38VVf98|<<}*+sc`Ob-%qI_bqk@8)vh5$#$xwpo?7i7@BZM-esJC(q zva_csbdFhfCZ_HB0&^-}2&r&$@1tEj^WM~A5Ghp;o{pFmX~S`96P^YC3-fbhIw-ym z7Pl#p0(=nZPdzn(I0pj83UbscMKx*5=MA0MeOE%tr3oKq6W)WkACm0EXd4^!S&#*& zAAI-J&CdjjL@bTOepMb=nEV?dOc)QAKE9!O_epmLc;Rciq+vdJxcOkW3PSplF2MMV z9N1tM{xSf{8SDoLx{ib#CVQ#2ony8yBjsLaZ}tg-g?~Kf$&qyrz-ONt4(Vc@<|hko4jl7OC_Bze@)IdInKf*g>_N!e zz@6jA4P>rk0Nhwefkt4aTEFaZD}iv462M;~v3%Jz z)0_UBMko5mwe?y1;u4aENdO>aIav~5zuiZmu+=zfVD=tfyP8j>^cj*<;KuH0--A%{M5}T zPA3lnlTs}>_FwvTHtuFOpN(kRP=j<~B-A@oXP~wp#Kq-qIi35E**B{H|4BA~2e7ui z*3i_c1+xI`1%!IUC+uR=EMII7BC$mg!b)JW)|^fDZ~K%GaA&?q?Dq1lZ--z&fV&P{ zx(alK;KOqJglEmox9(X2H%OQM9EyvjW8DC7SC;$|#GB$F#8JeySJa(haggV-HN4!f z`fNV3arYSff6*2{OFS9X|L^pwTfzz;{Ga~H6mJ$+OX{%ESdx;$A-+pX#&Ru!T29CU z{yKn@8#U`IQ&ErShHsJrRCrgl3BDwq%p@y6SDdy?wsprO3WUBUhC|^zc`je*il5#V444tve=z_3Hp= zcsY$MyoT(X7X)wMwTIlyRFh4+x9#WOn|v2yIRN7+ z2MBIp#trDag^Bp>@>#Ca*?B7%Z-3?}h__$uhHP}!>&DH{z62{# zvji^D$OXrMz=Y5|o5`!9VGMWn`0fSgf&|-Yx!q)yprMd<@&{QT0mPp&3uS#QxPj|J zVJx;o47H6|U;r0TL)y?_1YwK-$(=$pOlz`3_L<yX)-bvaX_LK z4DYn_Md+71NWbeSHEqLrBpBewBdY$ff0mu!(-HvKh{gr5I>?A^DAg5?I@Vo<(=4Zx zjt;!99MeBuiKN(O(ng(Otmw$zsxwI;%niK|%3g`g!O6yi}XXV`W07CQNM5tZqk6sS_rT7x6cc!<` zED1!vzDjZRL}Wj&6qsHBS7?KYhxTfmbxcYvEf$Pk7{NK>ZY-`Q;gxtHymq4L7F(Db z>agrBeA7doyQ(dt0EAK0Gl8;$P%G3Imr4LVt8u16+5gI985*dcG>~Qk_sr7Lz2Fez*z_1_YlxG_Br#srx zPJ!fiv-qa2`BcNkw|IEEhjc>Zb?2$;w38Wv!iZBizQl=PF8eFHe!U&|yz#f9o;lOd zK$!IBjw$Uphpyy)6@&3+a>R|WbU7^uN$u$No_-&q?ZCSBvCk_+=ed~}f1k}-&5Z5I zgnuM=^LAX_{XI)R>AOwV3lklK+LllKPp!&M`g(Iw{a^t7e9CTNubc|iZo~V@UOCsJ zL!=bW_$D*ZHOV2k=WA14-@YEuY|xDk_nwC}(RI=}e^}(vA5XAnU}x7a-ZBUv5W<== zVsc5cM^o6C)Z}u@lu8s4JMKlBE4H8KGU*H`@&9ALUZRklV9WU0AJ;mT#WJ`j>f}{O zrR;(k>nXjizTT6{##^{>PWGC)K5My2xOzFEfzSC?x~xyM^?&;>*x8pY_)8Nkb(10^ zgqM}PXs2EXCJaNT75LA!35Rln-JyHuF9@BrQ+Gl!Z@F-5_R<(Qu;v{6o4U~?Q6erL zG^7GIfCcEn%vU7QJ`vQE2`emi{yU!pCQjO{xm-N@uBHnG!e~5#^dUEa(JAi=tFBmx zr|Sz~q7gO;+!r9+-xN+2$ijcx@U z9<$wixVTM|iia{fJIe*PYe=d6WvO|s0{&n=CV$OcC+Wh9^|j(&{v3ZT%1ASs_0wljsc*WZwr^br%<FUz}NFkzm+4FIJTYaPt-Z?DQU&2j3_P54Ic15!h zDSe(%IwP-7@Nh_I{jyPTweT?o%PaLCwi~1~*uHH(4?HxFtn(yMu?oQB^YN@e-_itx5S{gxxU=EFyR zhF+!+RdmJzN-)T6h1;|_ng5UJ3=AbNkjn{nG+g=X%Kon?c?kW~2(>oTf$lJ^ zhsO@K(~WmahjkHnqKQ?W;N#9N{A@gbt5eEYc1BX)ZnUC$NF28DE65G4UbaOkAI58~ zs~=jU4Kt!f&R;1Nvx4j;)B;0(>{x3GQIikR6%uAe@;?5Wp_E=;`Ho7iA4^_Y?|YcW zXkhuzJ*ol4S+wk|0wwpAqo_(;^5tZm04;gS$5xPMqtzl#U8_mYx`0dKHB)UEK%{d9 zskxsANbC&gj(db#%BB;=@Sx&^P%zc9^1%Z`uMdZvB&JHEMdi=__?$QT+HIsi=7i&k z=8jNoQ~CeYpZ;C|(HyKW`&??_&QdhRujy)k+#ky1>SEEao|-X_k&Zprq2<*XyJ$Z% z=vve1Ruw0v#DVRjtS4-tVS7_(3C#0^;w9Oil#h3>@Lh`Ab1LX}SS63OT6R0C7>AXJ zE{+9JADn+}9Ql{uiXu?nSDY<`H6aBdV5!O)GIZ$ku!knk?7l&H+DF@g|1cbn!IM6_ zLNNO0jvW5?>n7HF{V;jWBk+dL#V~qDwlp9LhPu#k z6mDhuzl+{JVd7kpleMYTt9@jzHi|ltEXWgQoP;AMlvr&G4RHFJIpStsO^H&aYmTw_ zu+tg*X`)6MYd!BHiuI2f-$sh#>54Swc(YImIHLlWAb`X2rkK(o9^F6*UlZjrwyg9; z!vWK?e7P%k&H7+!KA<3RR9!X^?kV%_)#H3wlX08RG7JK!N0x6DeGttp0EV{#I-LRFQN{KZd7&SszbnnDHDPWgxQ8tV`DQN#TA*aM{5=!?%)4GEx1}z4GA1ww~ zvd5HLMM81ck5`GTQSepmqpm1ss`@EX0aSR(bex>yAtav>C?5R`+Q znwQd|9GT#2+GkBv7+Se^V!%ZGbi#FBRl?Cjuz{Ck>O-L-fP(b9MG7wOT$6&`hdkEh zMLm*xES;zOJ4rZP8nVjDl*qT8Frig=jw`0~Dng8X@AX%`an8BSRK65(01%&c-B1l# zZi(B1d)Zb{iW20Oym9Ow9~wLw6*XZ+3%ub+IZWTq+7LtINXspJ7D>pO5qT_o^&Btx z1`1(GC6D;6gch8nH0#8l-eHdAsD7&8)JlN3U=Czu_yNtG%KCF>L<pQSY_B*jq+ zl5y}N@YT~oHIRj(WYbDq!thlZ0!)%=T>z@qNm1X;AAELMLajljNkD*(04>sx@`pu5|t_`cwK0Y_96(Xpv}+Qk?*TOG6X-Kk~wwX2dia@7p?FQ)e__f0I+bBqp>z-67(0xqhd+B&V7 zD--n8AKrB_PrZvklar|Tzhx5J3w@FbW|xuf{}5j3HX$`-`V5c zaqjd31}Q$4y1^9im$_kpqvQR{goKj@_lZCg)Wn=Z@sL5jL!}Rd`lSnHq@Gof9FDgBr|MPPMOFH9Iz(K7T5R3@tL7hpuQy- zI~j5I>E)G@%X`t(3~T2tS&{V?DJ34vXTUQZpQi8R_;KtKzl9qlcgH{{VpF^g1RcL~ zaIm+t1AaVkXYniA)LUxf^hpT766#U=3%({gc}f{iI#gPU2ja)$is58ImXA)kkrh>C zB%N($NjY!;QDmbPF@!tzERCfHS%mXp73*N{5LRQ+0*wLG8D2UJuT~5fH`?XBf61kj zw$Fz8wY8~HzCNBHbkvI3FqnE&=)Kc?=Yb#nOg5F_bRNFH3kgRgEqTp>iL0a7cb)yI z`RIUtoY)I$$7cs{T39q^#Tonhw&?b-K<(DECjS~{tT^(u2Jt;LNFI!{dnd+aDN=7` z@Upc-qZ!UH_-i&5b_7HW7_J=NK#PpxS#cHWl^_5fMUuE{;N{9J&Ee8GR}WA%rzw4F zAp!Wmbf$|JTuDq;djnO>9cUK$76udSN!bX#1i`)9e7E{LUfE6uqC(>tJ(hhzKrFh{E#mNLmy!;=TQ#pvCne~BRT$2>N9z? z#T)9xD$(H7*!wNiY1pbZiE&ESD(;EWu0#B5ed!=_$FcY!qaoejdCy0$x!lL*WUN8^ zy5m9z!_XBDibwU%B-8-G_=X#A#ydSPudEKr<8O{rklcVnUB5*e_2V@ON#7K#T&jRW z&VU775f@KaR4xXE)}jAuG_oMH18$S9#5n`ynCT$*V>8H8*_Wq!pO|mvXn)fyP%Peb zPxb})@at%f1y7gCMg5^rigD0wB53c}A;BD21?zs#L#lni97Y!LPTo;0WbOgWBlBo= zJg0fL=IMel-{#>waq{A?WtsoLcZFi(a+g713e@Z0NheZD+!;#1(Zpf|T9E~}I})1r z$TnFwOnph)76$$T@1O(7w{gpgC;4LKAbxDHy>y<3|5pP0WScsDW)Lx~*PHy`#&4T$ zYVk_CD1mq|H;f_p(JN<9+{d_Y&j@aW_|- zlx0v9KNiC9$4T4J6eIcZMf$JOgm}Q*M`B`7>ce70?_xVc?lagZ1>DG@$}5W0F1*Qv zI(%~vX`sg&${iUH?M}PeL0^+HNwmwpTH{X<|1rDd5Q)bb>okYnb+ov<>kV1ClG>ct zGX3MwLppNzXZPySxux{VHo)tocK7HaJLtHgcCfPr-RrLEmacZ}jW|VNH|TD7dg}}3 z1M1|}Us~MB4U#~*7a;+Qi*4L6Q9H+~?Dgm(yxNmkZ|9$Az5yzPH1-&QC?{$5_7` zt2htS#b1roA61Wv?{aL+uGkHPG_4pKA?}*a=H4=r=2C?oqMK0lpY8B5-b(1g59_df z>G36dj`t?IIxYS;g+oRX(j+-wnn60yk5(CT5zwaO{DDuRe;#(x16G<_emNqVKkz@$ z-=<~em-i^O<%`jb+^eYPQl$qTtYGWCAXl802l(>OyCHS>c!?nQZ=5*K2vby_ry85* z0ew$n<09N52%k#)$Ku=-_m``8L+R&9BbLsfNLi33|1RUJSbKl%#UQjWz(itbGWbl9 ziI<TBE|t6h_Z8*3g>-073M^OpoFUi^RC{haGuJ)Hg2pE$dI z#QyuyT-cIy4*`7#jH>OK1oowHuNrN@_7^+%Lc(SxGKu@`2s z?gh=HibjYJM!Unu=`6;;3QX449)V|Y1!0&fq?1F^QX8^?xs)LgG%_PE-o95t4#A%z*048H1+EJWA7LCy`RIU?FEMv964NPW?nOh2>KBT#n<5Fs+ELjGlQ1? z+9;)Gm1=>0ZZxTQL^zX{zh?J;HEA-pPXVDHe|k2*m-ZR!mVQ<&vA#!Rq{Q61{)Mn5(iCLTgt8fbJs`EzSHfBA8?da>{7p+*|Sn z;NF6YnrMGxG^ZzAi0ByHd`1gWmeperwU+(wt1<&c<%+CWjvCfvF3~9X##9Z($<1bZ zrpPAnCP;u4MT@nw{f9NYORGB5CEv3_Grd2bg2JCiby0`_E*I!odx6&bxe^Uvr1@WS z3?sP74IclP$q*IDEwAChH0RNPdm($>%+l`;k4wYRN$lE2Lo&+{E`QIbJDOlKzWNbZ z;CTt~ML6<^LVql~r5o&3GJg#Q!~cCM9cWZ|@+IFukmqwdGOEddmoFQBym8j_9nT3J z=`2c$t7<9OCJ)t4*4{I$&f}~5YQE(%BTtVXV$bxLnK59t{by;N6dh; z`?p*=W1ut1yOpmCX)Bo4CK_s^82|rJSQY-b<_YKtxm3A4EcGukr4woSM4UPsJVN|` z!|s5gszfrf%x$GDzu$0(>LsYT_;tS7HX6R5l4syp{+U+%cTB`AcE}5&mzUTwgXACY z3rQ#Q)=$tmJHKQP67@!Td3kXOa{I1Ry^J@GdOruZ-tO!%Qvt3r_zGQ;iiim@7VV6A zjd|_gU9|Q?Wnd?1n+oNZ&hOk~#?C`f(H53`bJs3}ggJg@r<)JosNcT#7gKRIRS(e6 zBId+C9q2Te4BjpY$r>}D6O?gb>QSFiRa_Sc%K}V=ewdA}om<{7aE5z$>JeK~Pw7!M zkdTzx=lRs-cQBnbzVw>c4DWq^VcjrODw1Czfta;4+ANbH68q;Mdf$HS0^4VAzz|j# zM909(^Du(HtW;|BrsyKTc1Lu)^}Sf*H=nH`LBG$mmruC_v0KZ(+nrS#7S(|%w}R5Z z<5xn$v{@%!K?xJhamF4Elpg28XPJiGj8ykNel$x0-0_OP-a5?OWqeUNIsZ`7^n4A_W%p+5rg6jihcQbiO<~r z6n_V;r%&B?9}YTNx}EG$TH7c}WNcRmdMIr=a!je_lwjbLxMuq$Ah>&X7?OS05XrJe zsHd+_$9Z9W2e2ZdC;s=gSFUU|v&+A>gcS=2;HC)BWN!+jHO#C!21-A(sGqD%TZkIC4S8WwCb8Lm%)v8*$A74IByCm5$4J%{OOG++3OB@ zJ)8_iRA$9ip(>;bf=U-kE<$g7?+HdWQv;@21`DbZuVP>_U-NMoSItz136)}%0B9i1 zXzLnPg1^4d;)rjV@XsP@t5_e7heV$=Q7Iz!b7G5h@5bTYS znh`aA29gW+PT|`d+N>jLJ!wExU_)2j$}#2k{wDGuNL~Zi{jwADzEicVX`CyO?b9od z?#k(ke&UMlpYB78>bqp(aH;kPNEIOWupzXmkbtes12_`}J0igp$HsO?AP62mVEXbv z6Mr$?app1xy;6Mj>D9Tc?m}K5R=wQ&=Wwh3)F2|RNI{8siKvDRw9QeDl7Zhm;Olb{ zgBdj6X}59`e3`><caZl z;+EQX)B80)czGQH+MbH8oDuZp<8@&oDkhoF)jK^i0PBE}=D!>jYIG`=K$sjRlsJqy zlu0LQ`ovKLwMXN<-jYU=-hMC-Ai6eWqAvBRf1-!dr*i`7K znXj~2xL}l8V&3n4dYOKfPt5(w^7Boq9K<(z>qIuT?pUhyZ18QA5`*aO(Hb^hNd+E0GB@C8G1Q3E ztG6l0c=Fc_U>SdG;oSWgwlau3GguMLkiluiAi>tY3)^>k@l`2o@+CW7@t9_;p$=Wo zUy+bB==;? zIy|AN-Nxn*5DkJT?D^8^I}o-2@MG4tY%}kh0s@AxwZkSghiqGE783M zRsRe@r=)g3#?a9Z9n-N^<%@GY&B%Bl!r0$O!`4RneHRrwZbht8a`?txj~IRVrP$6!G-h=aRQBASMhZK^E&e?d5>B4t{b2rpdqR;^pb>vB z0>0yq!o}G4q0z253mYGtOBo|F?4FVV_$J*nYy$L=m-kGWIPW4RnN~fNOCZ3vFKvf0 zw)2e;N8oaFTdi%;uMCZur>H21C55sGGH73Q#xmlH>@^7YSrMaUc{gC1yZI*ySU?uY zG&2Z+W$Vr5hvl>n6(#8m~KXJR-+^%LUiqjwe8CrUF?ug_>x$Cf^eTx_0AUr$(M zf-7mOJ(lphwn^TfAR-sQ|4bSvvV^nn{EwcL2JKQ3%5voCCHKOkQQhP3)=_kY9*?9K z5+>oa>F0X`di{~rK&j}KQyprBnzcF`DN(Q5`s4|{Ej6=`XtCtJf2)%yKXC<1A(#v%I2!LayavfL!(k!$ zOTDmeL>aA__$^hqKRI2|>G5P_e=6h;Tup~>bz_J+H;bggUmP}oPYvlN-!&zl3Ml@- zNTHv)EwhSIyJ(w6Xv1Pty!bJe02Zm48Aq@nPK95W$s@`iXd&Jx9#r;Y*;2CoR=3I_ z9mQg*c8-7-0B$geyfN@0pXXE%GS5TeQGJ(XS_*sz^a_3CZEG0|HEU-q^HLIUk0mzv zk}SgTL*fW28CB$AC4M~BGF(+!+O672Zs9}OYXGns`A=D$qF!Zv zD_7F+#_kKP^D%mhY3bRtyM$D(p{1C8N&@qF} zT#Ixb?3hpmTq<`x3fGYFbr;Dd{9cN|b<~1e5IQ(8<>gdVID|Iy(Sn^OeJ0N?`&f=o zPOSm2Up-HjY6&lc&e5AZQ-%e&cbE-%LBr?Z6gRaRgNMv~d1{=pzM>}I{oVMpo)VaP z_&^aTP?)*?A!atJmCUR25!7K(v~Q?1|6Zu*hxfYwKpVQx}j1|B_+`EP!!YjdRG9Y`WBzMgiGS= z8B9{ebQjkkhp^a}xGHnk&m81E2h8_4UNj_I!_X3xK_BN76Q*r2eNUxRWruNxukf2i zsd)<>_KL2*6;qMb#SRfPcetmG=`Ti!1_V625tWed?ziVaDNLqnV}MgmW3NGj5-|oB zI7_7$HSzX|;r?NcV&1x;w86bGO?DNh`>mnCbd?RB-ZXIr+aI;+CF#|uhJiyhNnE?s z(G~rEHs*Q!IpstOzpBj^U=X`}h@BGYlOO$WEWmm&9(o0(|HB0+_sg)EfyQb~ewxlI zdi28K11~Uxe!gqBIadw(FjPm5hl}{1cH5}<@?<|fVTi%H;1B^ZX8|(!zS@L9OcVXAh8D%F!jE714 z<5tWVDrR$0hQu4IA=1F?=^Q(NzlPoFHp;E}O&GcDDX9T<$MO91V6mER4cecSR&X}z z+Uod5?`gCIUr#1lXD81b$e?JV55qrxIpuizdCyMn08XF!!?}#}qhX}8q4_){8x^N8 z=w|;j93qMoY(B91;4>opX?duiJT5}^OGf7q)l~dJ4uihL==F%%+2vz8*E~F_ide_4c$?-?T zenMuj9AcmdOPl$i0>qd5doP+(u2lhLV0*!{3%AEC?g-pxwgRlQcyYL`F+JU*fepi#Q(G(n(F6BvcUYh*DbHkD=lT{O8H7yG34LSybe#6$75o#%*c{YFWWa_07m(&ap zIrrwFaaUH;&y|lN~ZV=8qUiVLo#v01|Sz_V>nLsvvezGD6?01CSfu;KdC* z`02xZxxT$QoS293@{Xt50dW(dF;_%toBkSB0&PnjR(s7|zIBiNl5%nEfR zDAY@?0?Y)GRU3Pe=Q`xr18b;8ZU!N^CuuB;01l8Mbou0PHUiv86U5d`Jd(3XJubNnfoID^ z93jcmwxMX2VQ?)X?}PFO1=@b=NufAC!NlSfxHA@qCv-1YNu9dRVcU% zPXnGu6VWUiK*8_mGkfi8r!AlhhRA}^121_K^>WRpZ4homH=&SHQO^NH0r`9*(;vc| zIdO=hu&C=*w@nt|L(sxTy8*;U_(4rkiSy8aw&SrOKS?Yhz6T#eAzrcx3>A-fU z(@kFT%4~q1e0JXwwkC2L=Jcgfq|(M>q!Sn~&Oom!w6a<@^lym z8NV0(*hGnbOIl?%;c0Ffia~u(WJ9`SI!xv84~24Sc0WtsG~; zVQ_oY)V$eW4ut^A>-RyYjsPoNSS_Evyd%5@L-`l_%~=CK83VQANwP3YrF}8j(VX(F={j`m3BPp(J zIuuT)$W1#5j+~uqdiDluiz!6c?})J${csouD48lf208hBQL+I%Oa);;0y4AG`|>Y1 zi2XNF>n@JjMq^pl1_fRNJWZYi7;G=A$qP`YVBjP<%UAFl{6r~`p_tFU!7<;HU@fC& zP#h*sZWGK#fntAX~LTjJA#_8Hn0~6Ya8n?tRWvWh!eK*`<>!Tf>mW;6!vv z@%(M^_?P(?i%=LmxQq*rb>ywqO2(3CY-I}5)f`R$#siETYO|JO!G?vP@q!Z_J<_K@ z|K|R=@~;e1qvsl}%=~KYt^C}T^N90g{5dtU2T5o8q6P%NBUK=w;1BZp`zvU_Zz~v_ z%nQ;>Xz7>dhM4IjKsBX>`zaVYlq^HyIH}ec>uNA_oBA89G_)2}{$1P@I@{3hbsO>= zp$~n|w^3zTtVuSUh@_X?!4k@8-ky2<2k!joj6^d-L7yVd%gFh(^;~284&CMVilD=o z`&>VxTm;twJ4a{I^M8;V>9+Ll-5)H>p_vriTSt13@7}_}Z$piOE6oN8>2NC=T!6VJ zTW|W$gce3#CZZJDUcxMC32>_y0Vzf3UPs%Rg2(er_60@<#(4{OV3YCR@2(btPBlO; zw*2SYT12oS>8s}O6ceAN$jb$PyxLz`8XQAp#@-4`mQVqrX#`F?OiR$*7_4w2h>L!S z5Uu|Jbv~jriQB1NI1ksnSE)ITzET5dS9?@kCHfSLYuC8_*!=bFg`kI4sgt0SJ?I4w z;M4%WhQ4QfxFb)?gyH5`v7FVdg1!u>OIP#V{{*h+HM7-^cyFgRdQCW0ynV9N1Nxmo zXh8i0s3cWEuW0SorRDlF&9ou1eRVsm^Xg~_MX&Ls?Rv)F!y;Qr&3_h6?3Su+WLD_< zaJGKLu_YGU#nbytg|&R_o?kHwFplMk(b3xY9nAtD(y}v!0^?Zqk{5&UnV1-f zWy{`pM0tGABQnqHungJ>{wJkJUhuGPebfqJkU&u*7~F`61p6lmmgZ+0+bQ*&-QKJN zDAaY3#xCLKKJ^Fofjt#;fTt80Af9Pe(evF2mgqq>-HFRL-qkMkE$e{M23M}=s?xLu zF3C1{Lz#QkNz4kfj1l{=6;kKZAn8qPZu~{s1~9IfeUdxibWH8S<7sQMYGGb9Gf|Za z>)~0XKl8Dpsu{Nnup%4wR0E3hfcuaRTjSClyU9o^6M=*t-bDgp`iIoKCaBuEd~up^ z;IgfhQ8{OP4I*j~4hii50aN+7Du>`7yvGW!bf`L)sr1yeL2`+Nb=T`om; z6~fy&fG-Ah{}iQqk}fNy+`2dYbBl(QxGOJLjxZlN5%JSv86w5oIVT5mfc?CfBW}FPptnd*jnd8&j=pO`Dx0RLmQHB)|J*sE9-t0d`H= z$PHL~!W=c&i_zrn^R$8^nKQsdJ(faa|Jh(l4W!L_K|9~1j>vWPF3GQ%X4PgH$g&y- zZl7XxUaaG8V{IV_r;f8(!UcrZ31d{0mxC2NeqAm=O>z*V1~$C7lR|n6mgLHD)1ECE zBW=K<=}WE%21EsZYed1NPkcdoR_c^tq+d4n>1;73*Kh$2d+% zmNV>29a1Qx*2HS~=NJ(J#fdc5l>3 z`+ZKu;QJ2qyrBEe1Fs2%{~){0U#4KUPYDyb??&kiqDm27eE7DBQa27_2wM-I%^OXy zhS!8fU_QO_PIF*)k7j&_7NDZ-MXt*YLO&2d8Uk!Wr8d7q#(BRa)99UZF5Xdd%a`Qh_xqi zdc#W9HqXte5nGYZOd60;_I3+{6xs&^jKY5cwd4<`Lb2;-z5Y@zUDF_vUJT|)@=7ti zWTHNBBe~R3xlhSg`{zP<+r7b z38}zJx23UlE8RFxdlf~H%8`OUZ~{=#`E}G3AZ1@i{c7J~6Ow_gJhKGW)M-f>Nxblh5g#cfL1^)p$MT~5o)V!b(r4l0?ZHb|-n#Ge=na86p;E}xiJ zjG9{!`poFHE@@tjH8;;|K2MBvA78dsbiQhsI^4tTR#JuPaz9@kz9Czf={@^P_6Hcw zLiqyz3%OHzjG2@Q=kQ1I-#qieLU}cH^NXtGQp@@pEScy901uq{Yx`BTRrZK!d_U#2 zCxzh+Sh@RW27r}_DEiz|ow<}gVGAgW%7b;F2=E)^lm(n#C|pFeU8eXUxEy249zO#C znjO`3mR%DJ3bn?pq`9e(%xJ^ey1t4!sSw-;92M-E^QE12>Y*;S^roCpwqi})#=iCh zdxEo7mgjw*GRsz|V*UP6IO)kHWD>~fN@EJ%0lq-hV4h%P|IYKg7ArA8V2VNJhT~fd zQH7jEs&!E%KCcdws~n-R+u6{i13s&`GAgc#G4 z3RfFMVpE9UT6orNtP^GsKELCIvBD{o480SD^%mHIEmqnCXES1R!zwDwb@R?AXf;BY zF3z#&4fsEJ{uyxFI$l~?tST|qBs*LKd$fkBH%zGkB7MbVW^FRfq)L9d2wkI7BgkC1 z8SVPT5|H)%JOkIuL%xX6y%{{{;1Pu_xdaNpA3pxybNE->@AHB3pOp$_H14PE5xd(M zD~Ren(%p1k5ZR9dkE`FDor`%vjPlA>v~mEPW9UN+r0R~>VMFGHS@GhKfn}6VFnd6# zw}!epsw7-_XulYv%>Or~|NL)C&xOxctfQ^fUQkW2R-}~YH+$ffP~jF$@q(ElxP&T8 zR~uvtrFOD22dsvqwGlL91Tdx%bfIVek?5ntfQ6!ShF=Fn;0~|c1v~PT1FH+?%n7y0Fw`{JK|!!P zk2gVX<2)TQ)b#_Hvj{*#CYcM^a1lWIS4JX0PWb&;0;x#iqM<53mc^jrldFGADQ0jf zFQhmBR3W9>OeX_iV}=2Ov#={r3J3ehmnc=51n4Myo{$>b_~`^6fjR6P{I$jua=$tu z2`$gq<6vOuDoT{-e7Mp^6Tj27o;S<*Nf+=WJ$NQ>B_tmMI>DV}71c(8ZoaK>-4)7G#*2c<; zSD%?3evARl&w+~0Uj8_W&m1&vURB_EW;KjeP2L-0k_P>1;eXo(bUeKI;qOL#V#+s#V3)m?{0AN`mk_ z%+eAhQ3`T911T4_5@D7ab3)B+k(7a#!iIeVol1}J`{YS>>7KdfXz2|_tKvtLwi1nPL_YQ46Q zM4Cx#UEE#$;V= zW*iCp;}SIKl38Pq9cbmPBHEIwQ+sHq{}Z3ktTpxaH2o60^D9j=mE~9o_omo4c-V5e zN5`%)N~F;ccJe3Y=x;z#;u#qQ!Llj)(Xdk9z2P7n2XqCXXv*1{@3q6UTUi_LDe2x9 zu*e?NiHFGUx{ZHsKvBj&c6xR11*)pF8&>*P`8K>4PA8}u;wJBpb^J8|y>x#7blR@% zyO9dRT&`oD{NZe52+BvwoA;dx_3ysP&_a#A30&am9SB;#vyq6D0#J9$E*Ny}wrNuf zg~Pez{NaFbaAh2VD2yq}H;B0^gS}mPz6G?fWS0B0K-+B|7+<7pqQFqX)uC{;wW6>H zXe=bwotVAWuIlou;E!>E={x{&z#_w{3l>HDPdZZ@SZg`rHQ;#prw*}Qk0ld?M=K5g zFOKB=#a~6G3i&Q%Qt2c1TLi(GIh2@}TqG0JeTD8B*EL;tzpLI&EZ>4M`V2GK{>WMLKs#g0Ub1}B> z+d2Bdt7OJSzb_wRWT+Q(FM2BM#CZ|*|)m-it ze|`pM6P%sR0CkQr>X5quf3Dp#LG$EJq8sr996Zgn+fpiC=6UDK^wOk?HJ*JJen>N= zI5veyItEmov49kz;cFh8ewQE9A)A3y|ET^3`3)Js@+{AHB@-!RyTEcLb>u=!DG6!Q zjohElX8x-%Be)gTx{LsHae2Hz$s$JU-&gC&00C{6A@s$U5E=2+Z;iknZAHf=Y_uFe z4e5CIjEq_tO{oaGY6yu8DJsgb9wWMnnf_nbMimO(hhxVOcmDk3qjHmLj(n$MpKLz;aB3^zzrgiIiQRftM8z9{Y@ShQ5xZtfj&F@ zxUkl!*7kSC%g^L@j~j0|#}vH1@t}QHlj=~{2aiUqLb7!XtF|$?+R-nOyt^ohJCanc zUR$4gQX5DfC1Wj$`;QShz>74U$faa+a=590B<%`W=K!q6#2}&>_9XLV3IP%2`ddGF z1F)_~0e{0=0^o6pft0W;eyoPLU|M?nhtUg0pTL<2A;Tzqp8DbhSPZH>uQP6}La*^% z5C!qfjm_hyXu$OoNCJjQzVjC=_I!gQC0U}2iGbja-cre$a=hVy{8sjIYID`*q5Q^+ zT5$ig6*Y6N>KlUAy_o=fm`OwhO0$q`Ex5e1u!z0`sp_tXI0NV+wn&O>21fV59|N5n zE>-L7{*&f4?^5v`&QC^IQYjdY%&&CvI_tVME)iv_GWC7&bWbe^mlefgK>Urhp@{Ph ztnb+@R-qB?h*#bt87|lw4G~Az`O+vn6<)di%Ma?aal1;n$!g;ktBAWpRf3sfwKox? zJX@h2>JHc-WJynd1wZkHx;&~|XL?hvKfdlFx9HJ$(AC+3sz3zHHy|H2FJ0e%Yn{!E zABNNPRw4>Fyy2ZCl%wL^JUiugs=_KwMKZJPt2e*;?H=m8-dB+S zd|MHa!kQz}01$VN0{4x-5}@(g$^##>V=&F%5C66(FFW6RV!w}Y(-F$DCzze-g?xL4Gkf_8RJ zE+%QS;4vEAl0In62Rm`EeWIEI-_U5ww!<)@BFLL&aBi8j2ge4@j{z^v&pzyi{R%(PgY9em#l*CjC`AA<%P8(-ucI~AA6AKGO zZ(TER=SM>ThFe-A@%(wrreS_UJ?w}u?vFX;RQvVG7VAP@_QiFi?31RcW5G?eXTqVqYp>ECyhdaECUd~vBn*5zcJTOJ6R{* z0gRif)bDM0NYdy&C1nLtM7_?MWp&s;fjlvK8u(oQrZ2kH4YO6*T00tBkZCwu68`3% z%C{_PH+NJcflmDW2BuLXSS~=aqNAa!0)Dx^D(RB@_)JcB(F<;8w!fux459bp%`9AS zS36>_P+f#U3#^W|}X;gp0e9%t_97R(pSgX!(!He-SR-qU^!MvPnp-&6tR2*2*I2io^1-Y#63>A?l8oL~>P`FPoa zOu4bRK;9rnOOzr}2%QdNkm@o2R_`l#{d?OI#WNa3f4_~`8(c^T1a*oJa%s{pu_JJxkK2*tgl;_GuT&IQ)%k|*>d+ELP zu1BiTu>K`EkNO{CZ5-7pe75$|vVQ%P2yMbH3qf=&?LlLE*6ra_wHVE<_5)Nu34Q20 zQnF(0xvD>YD=zYeR~+q2$w`eS=tZjB+R`a2&XhQb6Iypde`^JMviQ@S<@(w05sP~c zR(q#hdy4i#MEZgS2v&PSQ+4amFZes2!(T!M4QYzVPP!K#K7E#S-J;BVRVFN7T^2n2^!oZorY+8M&mI}z`Li+YWlJ$puyY3#Rs=mW49nMnSMWV;oi9Lzef`=@teqX!4 zwVRKo9N8Y#KrC!Ns2SBFTTcISxRWiMkhz=S5Im^}3hcWg> zvb({9*_MZI7+-httP5-Xh*xU)lIo1?nMw(6b zFi%oFJJ>P(ncky1)+~0xO)Q1C=QM~D;^L#H(QCKdR7WMoU-X{aWDQT_v_EkoM1(;^E4wjbE*!j9a6BK|eG z&O^ImWu$@vX15<&3m83J;~^NlBnZS@7~N9P}= zQ3j8unAca@GK6qvFP~Ib9TF}q!;n@mP57&ieE8x|S{Li>eV3MJQxhEOsLMms+8?q8 zYCf*aZr7R*5%j2JWNpiriD>FMBg&;PMu17Vj!xIQ^Clz03B9)ifhM4=qCb$3eJ8r&B{zHxK5F|Rq9oRv|t zTowA~98?%6VhaO)4KK}Hl(%P|F8SGI2iGpFfwSc7NMihwILoiGyf_M z7;QA4W645h5Yr;=ut`wWUOF6AxA@AA6^nJtaNL5Rm%cZL8QjJ0+175wW*CX}dpYA= zynr819vA!1QS!26T6hc{VjnQBTWn~FSiN9Wi0Fqf*4EitxFh4K0n_aJ;a6znPs=tTIq{dpe zMVk>T1~tr*)2ezHCCoMUIkDr~;3KJ4L+g-W&E{p9qj;QUd{c3b^*c4rBgeL5-dWu}G=tT_UAe3%|MbnERoViWhYLO~WQ7Rg6TTj1ixQD3&c?8eq4`}Ex` zIiTz7gX^?sdi@TcL7RPJ+xwoW`O?%(G2S7&qU(~D@NgiVX$lyqcPwfjavw`zinZw~ zP$Sva-kDgov3$(7zB`X;A`9Q&vxd(F}U@OM9HV9qv-E3+HNi{XG#DhvKb>O9uRVR|QUM8#N zB}=qDSU9p2;i!bFXQ&8$bGr>1#*pM4m8#j2pthMGG^;$3s|k*3+@@Kn_q!`KaA3Sr zv5*iKcd66f60}h3i{CEHvBoHx+V!b~S<=fPlQ!+wK(hGRQustr!n0Mmq4r6(u!Jlk zTsp}@uqFMW=@_{{8(_FQgX+fSe3C`SkO@DuBer}bwS5Je{RWpSR@?#cBS?7o)I0fE zPMgGnbgQ)DEIM79FM~CY=9yzKXhQ8A*Q)7plI+d=JHOisuEz+;7>ZIe+7wmFWs|hA zvE%hz>S$`ED#AJ0ujI>I=jqGm@%7k}e;#^kOe}7z@b1I4fj?$@xfadufF}=n>?V0r zeUvJ}%#&vmfrJnyRRdX>e4^hmGsP~c^LBl2pR$Y2fhW{8zHFrQk}GY2wFCkBD7Jlk zIfY+JuWDy8#om|Ay?%ddTWOSC zch_4JxFOh}dmRhr>#TVLmO3UCQrhHPixR_t)6iujAhRXAwa^&Z_XwDi<#h&fus(QjnJy&koJ-{C&Ci zrIwXWDwZM|j828Iw>gmbJ3wL;cu}^@tK>3mHat0M2$z1v>;L;}nh2YirqJ11*HXDxp{R__PA;*gU h`4<1buLZaFLIdLZR+JPfNie`6Bk@+eQq<_({{i$-Nm~E_ literal 0 HcmV?d00001 diff --git a/doc/html/_me_encoder_new_8h.html b/doc/html/_me_encoder_new_8h.html new file mode 100644 index 00000000..0fed7bde --- /dev/null +++ b/doc/html/_me_encoder_new_8h.html @@ -0,0 +1,270 @@ + + + + + + + +MakeBlock Drive Updated: src/MeEncoderNew.h File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeEncoderNew.h File Reference
+
+
+ +

Header for MeEncoderNew.cpp module. +More...

+
#include <Arduino.h>
+#include <stdbool.h>
+#include "MeConfig.h"
+#include "MePort.h"
+
+Include dependency graph for MeEncoderNew.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

class  MeEncoderNew
 Driver for Me Encoder New module. More...
 
+ + + + + + + + + + + + + + + +

+Macros

+#define LEONARDO_PORT1
 
+#define SDA_PORT   PORTB
 
+#define SDA_PIN   7
 
+#define SCL_PORT   PORTB
 
+#define SCL_PIN   4
 
+#define I2C_SLOWMODE   1
 
+#define PULSE_PER_C   8
 
+

Detailed Description

+

Header for MeEncoderNew.cpp module.

+
Author
MakeBlock
+
Version
V1.0.0
+
Date
2016/03/18
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for Me EncoderNew device, The Me EncoderNew inherited the MeSerial class from SoftwareSerial.
+
Method List:
+
    +
  1. void MeEncoderNew::begin(void);
  2. +
  3. void MeEncoderNew::setAddr(uint8_t i2cAddr,uint8_t slot);
  4. +
  5. void MeEncoderNew::move(long angle, float speed, float lock_state);
  6. +
  7. void MeEncoderNew::moveTo(long angle, float speed,float lock_state);
  8. +
  9. void MeEncoderNew::runSpeed(int speed);
  10. +
  11. void MeEncoderNew::runTurns(long turns, float speed,float lock_state);
  12. +
  13. void MeEncoderNew::reset(void);
  14. +
  15. void MeEncoderNew::setSpeedPID(float p,float i,float d);
  16. +
  17. void MeEncoderNew::setPosPID(float p,float i,float d);
  18. +
  19. void MeEncoderNew::setMode(uint8_t mode);
  20. +
  21. void MeEncoderNew::setPWM(int pwm);
  22. +
  23. void MeEncoderNew::setCurrentPosition(long pulse_counter)
  24. +
  25. long MeEncoderNew::getCurrentPosition();
  26. +
  27. void MeEncoderNew::getSpeedPID(float * p,float * i,float * d);
  28. +
  29. void MeEncoderNew::getPosPID(float * p,float * i,float * d);
  30. +
  31. float MeEncoderNew::getCurrentSpeed(void);
  32. +
  33. void MeEncoderNew::sendCmd(void);
  34. +
  35. float MeEncoderNew::getRatio(void);
  36. +
  37. void MeEncoderNew::setRatio(float r);
  38. +
  39. int MeEncoderNew::getPulse(void);
  40. +
  41. void MeEncoderNew::setPulse(int p);
  42. +
  43. void MeEncoderNew::setDevid(int devid);
  44. +
  45. void MeEncoderNew::runSpeedAndTime(float speed, float time, float lock_state);
  46. +
  47. boolean MeEncoderNew::isTarPosReached(void);
  48. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan        2016/03/18     1.0.0            build the new
+Mark Yan        2017/06/09     1.0.1            add function setAddr
+
+
+
+ + + + diff --git a/doc/html/_me_encoder_new_8h.js b/doc/html/_me_encoder_new_8h.js new file mode 100644 index 00000000..c5a0b7ca --- /dev/null +++ b/doc/html/_me_encoder_new_8h.js @@ -0,0 +1,4 @@ +var _me_encoder_new_8h = +[ + [ "MeEncoderNew", "class_me_encoder_new.html", "class_me_encoder_new" ] +]; \ No newline at end of file diff --git a/doc/html/_me_encoder_new_8h__dep__incl.map b/doc/html/_me_encoder_new_8h__dep__incl.map new file mode 100644 index 00000000..b14ab7d3 --- /dev/null +++ b/doc/html/_me_encoder_new_8h__dep__incl.map @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_encoder_new_8h__dep__incl.md5 b/doc/html/_me_encoder_new_8h__dep__incl.md5 new file mode 100644 index 00000000..5838cebb --- /dev/null +++ b/doc/html/_me_encoder_new_8h__dep__incl.md5 @@ -0,0 +1 @@ +8172684f3e2b362d9456d519b13994a9 \ No newline at end of file diff --git a/doc/html/_me_encoder_new_8h__dep__incl.png b/doc/html/_me_encoder_new_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..1ed93dbf4d8ee2fa3dd960c8c6d202c6aac16012 GIT binary patch literal 14195 zcma*O1yq#L_clt0q##{_Aktk@Dh&ckN`pgp$Izl6(%m4Pf^;_wQbWfOf(+d-blw+! zzk9#`U3abfeJ^Xx%wo>WoU_k9dq2;!_Z#{_MGo%?LqX*DDyv|!-1BNhhm zXk+6|20USWR+5uOx_|il*;*Kfg!CLqLHezRXZqfvw~zj*+rjO~Ty7d(oAGmO3@Y0o zWHz)f{ofW?$oe5~-n~doEEJKgTVv#~Q@sWo?zyPUrN(8t#Gderi*LpCXnT&2GiurQ zKoUDbvFY`{$k@xzE;o0opdcGP|CDH6u@NN>is+S3jWMs;IQDHfT*-mWc}J`lihEBR zwx6Ot{oh~3(xe_p3=9lvcZnQ&?s^M6@|QSYmOBO#*yzGU@t;18u~sAg?|`9QDyP2Z zYh1Y94k#Q>ee}SGl;g>XfH7Z^1#Czs3Y5b{aaq)x-S<`!v<*W=ae;SAh|GDxMS$G(M={#I&`H$cJ_=#dQMcmNu-{oO?Z9bPQ z_q0~c`e#CuGoF-tN5NN(pCOWe+o^zoEa9mQsDuwM^412Es-4#c%9cjt>U`tlvi%4i zzB5JR@$1c$v7>jj%Jqv`X@S8MF+@_pdqiQ`1r}y$q=_RM<+j){|4P2gipsF_L2V@^ z7usCBY>PnaSE7TbBDjB-K3vmo--pZ<0xO8eRAwRuR_Y`q{E=_rKB~r!2lVGiep)~V#>-#Y z*w`R+s?B-q=4u+GVt8w9W;hMK))E}b4O^R-_CEnrC<$eKn0Sf4O^6Zb_cPD%XgWII z1f!ZI^Zo`n;5koYR@5K%K5u}c1>+{Bvrp`KGViyUB>S_hhNJEduM-a_=$x}A*Qt+% zH+K5kXS~u7Jnv9V?9}(*ADoZ=QS6K@9E~Pc`|6u0F}DPkKFvD=sW%NZ-RHt$){qzL zH=b_9;>lhuF-ih9^Xs*@TrQ1FUd#|t+`k9hHeFUN*cWySM-Mi}d9-oK!b#udX`n|; zk3258h;u4}+c6n+sHaipkQjAWuFnoJoVH%$sfW#;aXG~S{{{{Df%0AA z;81bzW}l;nb>Nck>1%a0U}cO1kK3csNW#XhKliWQN!a46vJIc&*8*g^vuHjdWYwS_ zA$g8-uW!=xoD#kb5kz?CFl&R}J2~>H2v1tzHl~K(|0R=a0oJ?r{^9tSTe6+%-e zm>97&Zt4`-AA+de<2eji$;r}vOn|^K?%nLFZ;^if`t>XMpHi)5vhGY1Y(DPrBlUv3 zE`RUX_d65(Q<&dmC#t8rKAZ$_Af(3`#y8g48K&I`Oo$uHB9Rd~W_IIxm{Sg+nU4-q zP)HuL{$2{d?Lc1c*XY{F$h*Qd8#|Ciu~6!|yq+39GmXhg)X0U0sFvv&b11#OkzKA9 zc0hl}E>P@5j^RsgqE~37mSs9ZMyBgye2m|V z8k0v7c<-ftjq|Od_C%h=+ZCLRsP02?KR>O$&ZOGY?)CosU~!p8i<3w2_u?euydSuT z(GHNpz?8D6&ySVtcxyfDyK8n<3ple6+;Z zzfBz^O~yHPRgYKB$V3iT!!E@UA4@Vmb@vpzQHxwO=g`2zDGD!Rj9TqYj6T(XkhJ`D zBaB*%wUUb}YNZY0KVhSYjd63661mkT%996R)(RvRDI+zYBZoFo&R@eb>Td7EyJ`AH zT90id4@z7__R1zwgzaKyG9<>>zZZP}X0o~O$$(Wwg4sA`0acRrCr-isss7EUXXgU_ zc1R*cTELu`Nu3M*WkKC;uUBXI;#PaE>v2taB#luM#Bg}S;}vi`p^wLtB}di%gzw5a zWzQsj7a7`r@$)r}Cl2aCU!N1c`AhF{I(=ftqPk4q-m8wLya~zoe>{dZ&n-!KtHmma z7cK+QZ!YIvdV@81TrXzubbU6rY@c@HU5S^_7SosDUvBj1+zgkLmO1eEL8mg(TJAiM zvykqprw+>nW?&UzZe?{U?TlNtf^dIYkuLGQdL6_5Iv@6}Lyyls#13 zQce1#{v_Ct&8dcn$_|26-)HtX3*8lVuKKLFbYov~Lk@5yq7d%85!eh$+z!L1XG0&Z zDNfFX=WpZD#@R74;cOlDCaM`f$<(F)TH0sq4NTx(J1Q#nb~ole5X=w zyl&X0d&xN@WZ~Npsqx~Rxt`h(2!(y`1aF@m1s}yfOE~Pl;!}S`l*199%~j*fGFVm- znz4OZJ1qEOCPMPzgef~FQTTsW*-X?MQ6dobSj2PZu64ate%m4G`Nxa`n?VvBKQZS} zJ%jjuno$G#GjE7As>Tm8qa?a$FD@FY>+ zMg`|mAiAUL(XrPl^!K4(sr_0AJZUcIhF-f7yg zJ^vIX9#6t1CVXgbk12sVB=6QlA26sTq~}o?nKs=7Te5&eQDZ%K6}CL|*qA~%u$5Qd zeW4p&OmscA=#b2Bi}M|r4v<*Ju}Rx=I2NC*!n}Fn(MH|XtVUB2+|0Shtm{;Uv*}#8 z^9fZlZG5m6|DMJY%}{sV)?$N7u3WZAuqhzWbS`>IHs6yLzzZKAl2D0S$+f>>A`3@(Y-9a1OOl7!%Fi z*KVJnuT=K*_Q)Xt_wI%?J3nHcH-X~(xw+dydA`LExzQi!HIMp<&4DeU`mDTC*j*KWIAry6LF+IsN4YhSN=*njm8k@bt9o#!I z=$gYO2yTolRAyC$8Rm8))Kd+U{Cv1KwDhMR?I|_GE0r&s#2I%5#J~ThpYyn`MWgl& z!3ewRBWZF${OXN&4HK%R1efjN%k6}k1ZFRD!88)><*+->+lXmQpC%Cmhp8Xy*d_k* zaB&EMh%35E5~k}Zljlk449o!$Q5>yd2Y|=?$2`fx=3#$)1riu~&zPdnaY@QM5rGJ# zD6UA6R*0@K5~0Ql-&lklK>dPH*Qv2=W+f3H{WK#ZOeZwo^cTgNW=g@A3HmS=v&Vua zNXQq7W5sTJzfGqN-sy?93@$4MXyg?1{e!v<*SVEda%~-2;fD=<`dW>Y{2f6K2{y%( zls`d`JG_@ZfuAs@>uGb;7=R+^)24^-+Bz=MyS@Lk9cyBV)z^h8RZgxJIz^{K>rj)s zf7%E|5%DD>zM%W8|9Lu1%Io#}bLotjf4XW2vcH9jwd{O9C<`mRHX9*4`gzn=)@aj* z&ayD+V0GTXLLtOx^UxocboncJpxiLT!C>BWiDuuTnlY@Lq2wm$ZGR4TKiq?>=18a0 z9_`Uv`Jq%fbFW+mtm&YEwo|fiJD{2~^D*RE!2lHEdGwS#_P^WeHj#W2s8ElFj(6s% zJQEQq!W(?tx7f=9#zxyaUO}iPCrg;P`0sH=qHP%R;%ggu1aO*{@dKtPx~!yxYWUPSwQ8rE%KZV(L$2y z3WHmVzgx12aVXkGMbqE24XSghSQ)5TIIK8CRe_Xb<)DBZ2o$fg0(p2&6s@t($nu#J zzJJ$1doYfve#Gd!1wOX`2qDDp3Q_m2j%$2{jo?|wgo=d> z2D(Zus+R;1jk;aDnh)b?HB~6AUl}T|*r?9kg8@shXmsII!GU-O%+UCCV1<5}R%z#R zY>U2Hf@dR++;Db9bA4F5`x;=9tB`Z?Z94vOw=oCi;B+dvDyJhY2l-X#oV}xWkkO`I3rvN!9cccW2#R)*10HC9Vt}Idx2H^@_RmXRU&nMqbm2CQjK=#5 ztEUy{HwhGjGlHalhdnz3ScMDq z9BwQ8^!L_M>TYe!nUh@M2v)jp$H;Jln{wP9i}}zmnmeZ;H|ZG}DUON1Q7$uc=w}4I z;by{0qPOi$)nDjYQ@p0Y|6>R(#oQw-uTtX7)AuG8+uZ&R_7YlF0u;}M6TvAO{A*E zTTkZc%W#>PPdWM`+Dz?^4&fw#k#v-&GK#jh{4oqghybbb=#kKh*ytP(zf^{&tAkC_ z=O#s5bfvhUI54f_l7eEqU+0&3KLZ=HCz3y+pSUj%O}-4FZo+M%0Rs-R4;NGC^o>%B zC|Lr1WZ2YNW>^joP2(^It-OD&Wnkuex$j{Wa^D}5TgEw80t(72;Pef%yfIh8KYe*6 z%mrOtU>3TfXceHYQTMh)UXJD$-iMy;pH=28*_fl^E%TPr+3ARMXv#>XWo44vp!hz&WsdAP;{O zUc5)7D%VK6>S`(@26_oK-y{(-QAQH|!kR{PZJd}I?HEz?O1aL?E4XN(gTHjKNB#Sy zdLC7fXuPdFg)Rwh(|+OSpu#vCKx|CWPoFyyS7uN@DnSAAL;}FteZ&#VO}u9Fy8xtA zEus0u+YX!#KVz=nOD0BLumgcz$>S&9rH#xoSKTIr z++1H}aZ;k3L{RAxF$yx@co?6=tCM^X3}O|x$0$G&U$0@#IQ^#ECc$Yp-%@wa)Q0DS zR4B-8&6oPYyDPcAq`$6@;zeEo?Avaqiq`rmYDE(wm4a*f6yd!ld}{G<*wdG34q>o7|sJ;%}=s#J^AD zk3euxF!_ra)2h5coluBe7TX)OlZ_HJ@I{s!&W}6gyN8!MB-hAq1h5pMdi zkvWnt;`fg^blmq-KJaI?(V4#k3lAD0_L>ZQtaDaEY z--@$mxxhm@IIeQvBI^H?yuRGNDk3F{LR->*D;G^M=aobgG|HXQm$^UOSrUSr#fr;_l&D;WOL5 zP6L86!#|(qK21)YD!_a7b~iIB|cRfW!c-!sm4Z|xh|%I*S}cv z^olaS^sUM0Gl7uIj?MiFP!cdfd4UHDGs-=<6dZbqHuU7*m&x9Bbn*>i0WUu#$a+Yi zuQVHY&u!KQVi>#o!gy)U+}rCW>#fzak=z`Ui!0>x1T=YpD zPJ@3Yo#!VeNW!wdolK@Zx#$q1RC;|Y`EOwlYE+?Td{6En);s>d=wvaWLKb3gZED|h z4a*bxhFd-vM;2<6lD{5e_N-C!Bai~nDw4_zrK(r9#`EGcvqztTBHz}v$>K*8r(ve3 z*M#iavH;xyj~8w8Gt)AvtIxh9FFy&W7_LV5pks!Ry$0?fkR zNL!encB>^c-F%edrtGf0aP(|`T&4YQ#sTtuWnF0g)Y(757YeRaW7c1|P-w{a__k;D ztr9dicEowyc$4ztWCHm{a?!3R@(M@H8N*6`IXnLbHpJjvylIfonZUNwW)gliPw{AL<^i*JsR1sS8G|(0)aIr1T^a-_t<5~$l!t;NgBDZ(G zYukVfxGA4)IQ8)vCc0m6;O})LO$*K&_0Xv517Hh;73OH)<;g|iTT5gy{xP&Qd0dz7 zaBKae=10pRp$1CfIQIS=MTfeq(g(tRVF=w(~K=f7n_`d|ce&=%sPHvW3D>^8$TB(+s3p)&L~XId@dOSREBIj!E0LA)HSQMz7-^1em31ki zfNcwEyZx7zcgV8<%HvPvA?Bnvw^hB+C<0Cu}~mwr4kMU7Sa}w zb*C5CN@~-=v>vJK=Z>;&tdFI?36YV${l$q^kS{2TyzAr%P2Z4bia^SUEAvc9-`)m==T=dhvL4;oUGJfYw^oYG%MqZ>nMl_Sn zg&oQ0Utws9wO|T|SN3K^oE&Gk)z4NofY@aKl{BM+bh$HEuJM=d{h6NV4IING?a0F> zb+^5bMzvU;S%)uHS}p)jm`VlBwxr=+ZDG0C4Me>@TB@6g~6vsrkDR_XT4;SOp}j z8pig0UksJnd6Re3eN*AhOk)%xoVCh1Za;>I(%<;wNLW(9@RSCOn>6g;e2@s6whJaW z*4Q}b{Q(dow9*ASmdfnvfLyOy+?YFIfd>6m%s4jH;S@rLw1;=<(@dEpI-;g?f}bOM z7X7*%^M6uxczFF}#A_?l6VEU9i?c*ApFaSB39^VaI1t&8*NndFC*JS!DEmu9S@TPi zj557JqJEL;H!4-~q^LbOYg_7_A8%3u!SeZ{2-)lofVwwjn4QF=6W_?)!ScwE zOE88bVr3bK$N-L)w>(FC!qP8cuJ=VGr~o{SVUALZWZsgg+iz1L>Wwl>EUVOfV6|xx zMJd*|ai%Qc_3lg9xaON;vuG|%6;(T4$A1Kifn&L>KgS-izv{o&1Ug@j{!LCs1e&dp z&AxEz`(&SJe~b`Ymg{h6N!ls7l=2Z&61}OQz8f>SY%UShj@aCB;jt6D^EbXGO};KSd8j z%nSJW(218kxi5ul`=YvS!(t^Z3Iy>2Hv$(44SqIM_hpEi{K@pTuQBR9V_eOn=UnGv z0!ImdLDWdqQ;1u?(-qEI*tAHOccg(RcZ7r{%G?!;P)S|PHKEtNSSK9RDjA3W>)3SJ zklGH4T?F)b%w>mws0zEf`|qNe&XsxHg(B<>ibRV@4V_Wcg42{n>Rq6YM^b`K$+4{+ zf2Y{qo*v7tc!tO;$B`|x3(6vS*)WRA>74U&c3nT-Iy_^)bymq$oK&DwMW6>CHM8{^ zBeS9|_=drm71$-l(q6q*dU;;o?=MG^P>2E5tFf&4>Lxz%zXS#y8S&2Yy(Y53+xTet zm0g!y=ISSwKt-tO6MOnwb#;3rqAjyE@t?jAlITA9puv2Q1XGGB8#fCw-KQzrkd?^d zc#f^Z5oG^wh!7jHPu>eh@oBw!zSg6I!{+Q=I#~R9_XTkZZQ0U&R2+a@5(IA%NHYD{ z1uJO(S84Sam>pv%$X@H4X6lM_=*rkVNiSRWo6gu^|4t-pzPqVuPUV!%8FPwN|Eo)4O2lwV(orfcWD8n`QnIzd!gTZlbY$NC z++-ov-rPpkp-ENY)5!V$1Nx-_;HjiYzAN^9wE}Fz8zi^4RjV#zNl%XPG-5E0grWydx;Pa zVk3rNY6-y38bGX6`*nG73FbFO*)H%V^La`S`8Cc(A@&5u9|b>NN14=|pB@cY{59q3 zp#c>)`^Kr33;h+8u6otf`E=BcS10eu%ojx?BQ#_LhJmCY3SRNB%3tA{Xxb2a1JNJx z%z*g^^yy3d%q6-E1@JiS{)?`t3t}ZHG~ZOKr?q^M>(4@J>W5Jd@tnEgJd8gjF z=~?@D>VmRyX{#ye=C=Fc+q=s@TIkZQPZy9*kVgP9xENDP3<#<9o2W}79kfD%gpb60 z2UX$d*Z<&gc_a(66=to>1@G4-sZ&umnx=4e`x`(d{EsXJvPhs=g(6-#>;Bkz$gzzp<5D^kSM-JG=Pm{aKWtBqG$cLV(v@DGe!i`2>04 zM__349HwTKp>%CM3E#ha-2||}$UX`W0V;m+)p*f+G}})TrUpDAp9~g$)dp20R|-4Y z8@6`5hT|76JjiwZahHOJe+kQ5n_-zhL<8dTnH8gm!jJ++#T-#x98&C#7sV!&P* zht=p8!G&wrWX4d@i7)M;R!-Pt(G#qu0Q+!SrNg*~3Ku-=)A+cOdZ8ALF4Ft=r%zzf zxEFN=fjt&hh5mmt+Ofj*w1r@h26*u^jve2wJOx{Rcop}m6d(j=0^8;)rSbd>iE05> zq}Wh7*g_E(!>*_er|rI!F|XP@{8(52Sf($>u%q!)G5WLce3^l79bDr)r*Diu=0?=v zz?1pH6!Uj?gvIbI4^O{~k-lYXB|4WHJpj*Hewt``G<*+irq?O-vHI&~_NPTDr5pw2 zZ%QgBQjnH5cKH4axeK#vJ9h?X!s2@!J61*-Zfd~jvK&4Y@oz&9PI$d*b%i5P z(XclH)H_-av4oekUGwJ4pFJdsSXAH^y-x_v+QZHXM~ONPnq4?k3v{2sVr3|Bgj=5M zK35!dYn*V~C6^q#KD~J03M}f$6qIB-fAn3}gCY81TFPk(lOwM}s|nybL3{MOSm73` z>Bb?cEn%xFq4Y6g`D~I^C)fS@b1udST)E8h0!z7%s6A`{jb<>rCV=-KZ&8GicNt4i zww*W6qO+D-M-9WdK2xadkY?H4F2w6<-HCVX;7cMs$j$ZJU{NBEa3ZV6GBFvSL}fw0 zRxgcee$zv!BAESrn3#tM^d_DC3+#(5MJe^&)3JyGU;BkZ#*a>UWZvW&Iw$VN424=3 z?!c;25qYdykfrF`@MT`06fz7BG$3DOCNsp|`iCZI$rh_P>Li`ZR`lp*nOgnw~m!L>v%~OCYdm zHM7!J$Qg88(Z^7pJIIrM!?RVF?6}BdyO1gzlmE3$x!7aJnED!POCqw^P2YuU_PlKxc{lPwB^Lo#z8~yy25`@)0sV{Q<)Na7(jwekS>2@eTB z#JxZ6d;~l+ap|#)O?VB@Jh5lP$0Twihf`Ax_5VxcaGR|7vx*!{CC5&?`c20wL9WHx zrY*bb^KxC*_BTnLGt*c38C-_ek_{d5oH8z05p zdRu<&VV^UjmvcsQ^Ow~&UabyDLhT7=i;BtDa{oiwETAO< zIJ+YNZk=OaTyZ$_^TRqhn>zGX{GOC(M)Q}viy=LY`!CK7>Fn3B@~`I?ic7{-(U;jg zOUu^F@2eQYtgpPRr(mO(`;L}jtH*e8X|s#xes7NaB} z$IK?T`JMQ_s{sFDHJ1UX0zzFE{&pTCE4d6l2Ux$JP{99yr%-&WY=%{74bYk^cxJyM zB5H>hvZW2h_BT%`0ufTn@&=Oa=W8-&iVHmbR2+LJI{ORhV_bVA%YNZ!xpJEth}9zi zpP$(0Y;7v!V9YSb$pEV36#x2oEX;`iE9ALbHwB1vY-39z9Tf%+vkne?=;Fy+jreeO z2_bfdC>oLe78UN~Yob!8c>wdbxB8@LLpa$^9|!^%p%Ox1l&FG0blDL=8a|<~=JoLj z%hH(`iFgy%dHMzq3MbzqJ^lsMQ!X1o@izbp^gz)Iz>K0@6Fl|%u08)UD-PF_d{*0N z1Wz$1sgCLV`jYX&Q8soH>-SsV$rT}Cot};-1s|*aY}Q575^Q!|9szQS$a=I{G|&Zm7mI{y|%6ir;K;CodGOej>j%mr%U-Hj5&d--4Yji{G=yBzNl2 z?G*Ku!~f)OI&Amx!Di>z3*4Oqff>x<=1gP*QY9-p(*WYIUiJj9^#+66elZ%|RB4d5 z1_hGT;s38XtA_e(rTFGrI}=%QXC7Ln2wcviO}^pqNiF68i$$0{@;pZ#v(;|V9;mro zn+abLx4&V)=5GII<^$#!l~Fp?X_+d-=<_NCCO4iLrN8<~PN=q(qHzdp4D%SogIJ;2_tbvp+BSZ7Z0| z<=Pen&1GU%sq41 zNf!xcYWP_M0dHA;kg(Nn2n(TNs|?nV0lM zx&31>iV6E=WxN5CqV@gsun*2y?0i75o!?;B*cToK6+TDL#`P%nVf$_ff1WBF(%| zjJtga^)xfxvc4FarYIg!O?rB&fF_K)%aD8NW_&^|G2pITomdIPO3c@s5rFkSBeyU8snuc@Z&yeCgVU-?a#NIl91 z^7TRkfkpQan09>OW+1-A)Ki%IYT+{a$~wModf2a)B4ghbYP(Eu>Y?*D(e;8qL`GU6 zhYCsP;y*=1Meg|WAsaT~%Y@9&{)$zvU?Xwo3zqFa1dRK2u4?hV6m8W?fwtGJuJ~rK z(>ErB7AC4Wz$VQFSBm9;dz%y=M1{-D3s#&aC3`E9j21JEGM5H8HlgI|!3)3urNRp( z)<2*R8*2DgRPm1BcV|X~u2$P|t@x&TtU?`19MK`NW^`f*P+FJZd+pdJ0>{>MgBS8X zl&*o=o*?Kc^xaST#ZgJ1w5P}(-!`;$5gyI1C_L{9<>0a-xQgdq?PBM6O&Mxm_b$=O zDm9xP25{!>>lf&iK&>xDVx9O7TWrmh0xe} z;kj?BMcq22_HVA6(A`ys{wdIovo!$Hxd94VUL2Mzfr>Ut(?f4e8M4yfaXwLYg%`A% z6!|5HC5-oqcBH;_RQw!!3w>U){kPjE!9AnLYl9W|-G^LoELq4)tS?+;`i;kxwo#8j zS3TLrF*HPf1tJ!fsMhj5(5tipd4xi2=P~+sl)C?l}cy;E+t*dbO z5-W(46(!gEU2I|BII8*O@tQwH@V_Z^Tx~^p&t5vit{Rxde1*T)=$W`*w6?#xvv00e zh2f%F_-$QnZEeG~UGJ<%;}IWJa&c+u%-;L+6#Q(Ut*YVQ^8UToaH_xv8Ms|3iBo)J z=&o_}nxjdCE`7gR(lti>D7o@H4R9{WB5@OMI&5?e6hG5@4 z*og6m33B!&@K9~1yIsG`(syXF1Nc$RxJ^luD6&Cm+9pN%jX|BQ&PPbyGg(5ks9%6F zaDc5J^4o}g-p@pyRG_7p*4MG^Q9-fmI2(!JM;=)g^F4XxU3JRCI)7funzVOYWPT`X zLJsAwj(TWtg_EU(!_-y9Wypi~>K%^vLm|B;8mBHSV+y{s+&G00`q0W5HK#-q*VQzMo{2Ai;T9?s{ zpx||xxiH)QhhVpx3nwrbjHHExu8Nxii$C^R@+I;2dU00gMHea>t2VK?NON{}=8oEX zbtneih<$N5CpG2|&GPTOpjMZ)$#c=NCTWsWGeUY03ya{+eCxy#?zNz4sIBqov;sAd`d`JMmH=V~Hr-}|U{>86}q zA-e|XNZx8;gxk;8+4ZX6@^~GuwgJ81Gi0aF)jnVn(5{v@@3USxowVtR*OpO9Gq%Q3d%=l@;{XrLl7z$H>4z93ES@CE>WIe*C7N|j-96=^9%QY3H0@g9E-cqoZ~>_-GzTNxNM6(5>gAFuy+H$H2BPjpJg@j*--)o@#1 z4&gO}Mduba@U_KBSjYu1eV}hKb+};Qk+Pgaq-DiCEBa? zv$~gW@jTjSw#XZMl14ylC6j&b64w;0k@}GW(;I1xzDz}VPBA+o?DKaJFqFnBO_74@ zCr{h~VxVqm%(lWsD{r#Th!dkPb?1U|xHi=A+SBM^S$iU@-swI@OYfpWzPx9mx*4S1 zzn7bH7yC>;>{|5?Lu1`#khvh{OcM$lai$;+B4Jo>0A^U%Xt=92a1nG&6U2Su`KpJU zdQgOI{=lpOVU_J)@eQmz=I>MEr_i;q2d_0X;F6={bBI4k?l<$! zsIFq0I!X$w4Bz`qmrEVLVk3DWdcVw)`a?oQqV8^TwhsJ#vP zTqY?wj$m8gG5iH$HA>*c=$p4(q1lh9U&!CJ1uMHfR0wE02}@6cG#= z`XgDG*3zqP1y^;}wy*Gg-Bzg)pAhs#6L&4Pm95U_fRyZ7WVDCBrxC~Ha!RTE|bC(>E=PdIE%Cr_&H_0kA9v1xv?Cw9O@~Kg=DQ3#v5I~ z>r>|hl|3IW>~kg>E?cKysf-&5iy!oJVVM}{bG$C86G~O1B?g6B@n5q}+ZfqBEI<$g zKI_poF(f!m27etepCY&@y<;6l|%CCzP+b=(l zCHLR*u(YVr`AZqh^d$5YG3MXRk*Tv}SwMV&8$lHNAWchSFGG3#IrVU*#I?4V6P(G3 zVTK2tnv#tzb=|iMpQ6%K-^0#C7QTICijsV_#FM;pBqxdyLPhpXA}Z3&AI5qVJioNu z9;HvmCbY&~htpW`PJBsG@<4OEfqd`USmGe&Me)fI3MJnQaY0&FDC^!)lHL1Nm)$YQ zuNgnrc~aKkY$$rJh zU;lg6aA*W=TgU^~YsK68Saz@w{Io2w zX|F^F07~)^u^M?~Mn08>Aib)wYkL`%tLr={6H)zCsdhE^bi1KDntb!Nq|DS;5-j!k z&mtZA-OtT`@}2pH&0lORErlHc@DPDbq2N*JPL0+{*2QhhHGLmI&n7=V zKlQ6=ztc9om>*{n#V(<%IiEJzkvwKZO24AN{dvyTuTgXU;=hUI|L=)~<6d$m!c#|( UXAu{;iw;RaMn$^(o$;6d3t2)IQvd(} literal 0 HcmV?d00001 diff --git a/doc/html/_me_encoder_new_8h__incl.map b/doc/html/_me_encoder_new_8h__incl.map new file mode 100644 index 00000000..b55ea181 --- /dev/null +++ b/doc/html/_me_encoder_new_8h__incl.map @@ -0,0 +1,45 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_encoder_new_8h__incl.md5 b/doc/html/_me_encoder_new_8h__incl.md5 new file mode 100644 index 00000000..212a8143 --- /dev/null +++ b/doc/html/_me_encoder_new_8h__incl.md5 @@ -0,0 +1 @@ +b450cdaa1cf5aff6f389b133f53050dc \ No newline at end of file diff --git a/doc/html/_me_encoder_new_8h__incl.png b/doc/html/_me_encoder_new_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..da654f1ac0faf651b4b7e8248d880037b220c79f GIT binary patch literal 47003 zcma%iWmJ@HxHTmpDbms*-JlGOQX)u5OCurOB`wk=T|*-&-93Ob3`#dcOP6$g4+8Hw z=ifIjmutZ|&mC9nYwtZl3UX4IXwT5#;NUQ&--y45gF_mIgM(K}VA}iyfs-=^c6Qzq!HeawO^)I^?2eC#Ko}64f!ukJsMQ#}>qCENc&d5mf)-R9z zEG;dcE3SRhUnuiKCln@dL?ymH$i$+g{`aC$)6|?6=Wbx!Amw7Y#7^gWhn&*ObN8U2 zncq?r0|}fTGsCI)Hp;rl&8^MNL-_qepS&7@7k_x!`8~WJ2PabaeIni62UAlINihvS zyh;50jZsqI{p$@yzAWy;Ue;-1P4E5(SLQ&P$PMew%WgTCbRY|H|`E;Qwgv{ZOl5ub^s z485CX`DB_=TvP0u>15UE$(3Zy)vfK#8t3h1!I~ns<0H4R@srY{qiV-(OOM7P^I$`6 z)Sn{IRBk$?f;eBygV~`QgKvrk?g#=+m~Ztt0}Q4>ZMzAA}moJ^l&0Q zrcJS;9n~$4#4?C+}Ahm(daonu#A4Lxr5~+cD%5IYlUhx zhzuUl??MfyVmI@(qP2|wR~*eXx^^W@rbP&!f9eb+#&sm^QH&5eR(At}XXV9<7eRRy z-Fvx4sSj6A?eX7|#l^EDlyia}?*4D&!`b}*N6U%?+5ILBXX_o2S{3@;h+sIL9>u*o zC$p22i4=~=#C#9Wcw;!@A+)!7v^kCq#bhyVK8bWIy}3BiFQGX;;?;E%sy#8mKDprk z*tr(4E4ZW}uoXkIRh)L2sy5!tiE8Q$rBXU>w;h|g7;LTglTW=6rXwwjD5~2vy|}P6 zZ@daCZml1Oa#eI?LMdr{|7Ts4D&H?TuoJD|J9fbEc#A(e-z4r&PZ?-Vj+?8{T}?pL zVbC*C5;;q{<$w^ADRkcxtaJL*zt1804SuAKD*08|okFWG&(>ds%Gf{=re@A!i5(rE zA4BwJP9#8x!>w9;^CodFN~z>`Eh$|<2aaLo~FcCV@C^#6h#nTi_m|BovA7w z`EZVU^7TWKE`xh3DXg?(NMiUdQ53u@rV!&6cy`F`OuTX{q1Fd&zv1nD2H{XhW>!06 z9fvjiHIA)_kbg#Bv%;d(>30hlYvKbIQ&kw#@cfmN_igp?I(NM{HOGf59pa4qseRwz z{dZeqg;swbCkp29<0UGhks>vIwQYD+pXIwE)4N@lQg;l-zb=NHRr1+VI;_R-XqDxS zkW>8P^~FD-;rxBIuXBPc^nNE+sg8Epl`Ca&8tdYKC$i+T+&nA)*=LUA-o5yq-hNu% zN@2F3(%#S{#jM)>jr`-!BWL30G7q+Gv?rC`E>9ltTT})4Mi^7gwbRU$y0-Sk{{)8u8w+cOSk>> zJx2Hs#A=4aolA8PQo{Wk!4xhIqHbp z!gIvcNm9bMs}rAVG}H_n0awy6>}~7l5p+eh;m*bNUq!2_<5;Is9)gi6R6yYsGpC`g zJrEjWtqM<}ar1oLdD^GsKZJq;Y{o_hO1ZP3+)ti9#vTKA_dp&QyFW$ccs84#&%QdA zaVf+^6MdhCkvL|BzKFp-ZLHW>dstD5vX_4?Qbh<)d2GDJaBU-KDXS}V5|Sc#z%n6O3Ot1lA%|&T|#i(RL?@2Q^|jGd8{#; z0=L|i_>X!3{whl%C~2N9=Y!hFnc?XJ8sd_*T!MKM?J)?Upe(&fsi)m%Q)LXyKLQ)*9q*!Qi{N1?G+5mo+j4}GdZK#s(J?3TdLA2ee@_zmbrA0x5 zS>T~iy}?QzUd-}!lB?RuFQ$eeaZlOoIK7dwwSgQfzr1L8Tsr|~O7Bb2U3qj_n=_Fb z%0F$xYh6b{+<98jdO7t}6VEXtPh>T zu3r@eB?fM(S`d`3$1|WNUp1Zut&;{)Bq{oo!zR&DzVC`GZvf9`dolm`!_R%m7?<7> zP6l*-kX^Q%u?oG%4Msn5fj5n}3gifKG|5rLI4OUhX>Z~hYCF2BojFFudixoWvEX%D zYX>OFkZ8?wCX@2)t+p@e*hz7h8h@SrXl=l>8hsD_bc84E)$wKoe;PXzid$6>BabFl zFaV+m)aR*JQqt`&Iu~M^&b+?`+P>SKx8*{IB3C9>)*1wdbwZN;n&#;IGx-PpJ}yO* z?RSFfQon?bxGB2r*Cd^b)s@X6q)6X+yY$`=ns~BwF1#4F0LpCntGkE|;htYWf-$Dg z9jI$*8s3ERrx_AHAXg1oTg>h-v0c4bq$34+sfZ>islqRbrNO?fQD7s{4JtVx-*+;6 zDY=|x-hLnWs5hKeS|(WVbPA zLMN18{^f^X%a2IHxF6zHn4r8gXXKjPQ8+04A)%?tM_b`LL>J;vP+U-YZVSo?-$f?S z%{2)}A%c3&=~U4R7XXM$qYkI@umMUk#meRE0^!l~W52vZ!v;R)OKn$TsPjiQnPQ)FhZIm%794O`y213%(wbGTYtbeSx-L*MG8llL!qX4Vou+ex1QRA134dI#iRTJ;F?8yE(6-2NFo% zgjUN>U>9=?Kka%C6m5l{w10BQ&1p{1tnio@TNinVtSbc|N%xodpefW~yHG|^)XP?| z5faa88*ukZ|Ml2M>NAr)D!0HfFslcy@Y9~UK2-$qjIO3ZS}?zSu|P`?de=|TpqTMT zFoK{Fl${&iF(la15~zxLdH3_^q|a@8qwI9x?zPE*ce8M{5oL+M|Ca)M&JsX}VPr`y#Xq;+f!^ruR`Xs2npaR8vi?-;nfjF#$qStsl(|7UftghszTy%yDx@B zhSHo;W>}}jHhiDWGiU6&!-Dtb5&UbSlLisFlMv)|VII$%@1JOtj4IMhI|ry_b(9UT zZ?}<@d=TVw_!veFd-9o1)ECQBQOSygCY=7i`A#xBMAO~E4Mj;PyFc_POb>=1I*l=8 z_^E)k%29ER^vx)?tLN%-=uYA{Mg;N~OKY3s_E$q1$HpUPv>*1f=dl|V)C^1{QjBV4 zfW6s2rFeN;hxM`qc?MD&cW21QAi3$BLU2fqRYUW$4VEQXhu-Di>Ai?$2vh4C4SCm{b zOW?&($IR3??iY4of=MBB|D<2WO0rx_6L(*Jh+jTsO|8iZi|%L0awA@PY+Si8({u*& zUKgAhr+8Zt+@MkfYuIteabZ=0TsNhZCqB%5l_rd9N{~@9$?c<#TPGot$h=r@1z* zllB+o^+zsmzuStRYp;Lyne73;@vVG`*-hP*ZDrtHlZ7e390R5ivwk+)QUgKt%Xz&qgB-b! zL1o21$piT#95nB;XEwo-1JUJiEmmF;b6E?#a_*%Nu}PoE1#!UqTF2>|0Uk{XiJgT9 z{>rfF-)vN#>We6cc;GGdhYv()jo|$EWk%%Y?Nn-MIr9`^YPEcH5Tycn4AJ!|Y)skQ z7%ayWOMdU4ZYdrM7>$Z}$R+nV=|uR_*V>BUCOIU*(H z7)TL%NkIzJ`n{TM#ZWZ{?53(9)-%T0mIU5yJN*qJ&2UBbri@s$oMaT_Ock}Kj#0!` zv22#Yk$h5^7y9B)o7?W^{y=#6&M=jM>(nXYIHIYq?E&{Zm*E>_p3?+dKd^y<_{qno zrN3e1w*zx6z$8R~jI&pBE`KIO+f86PDP&)1n*WHtGVirq(ld^Z%;#EnPTo(-87|ix zBsUv;eM0rz0|s#{d#sGzbw!7g{P6j|lyk23D8&^2#GJ%@%Cc2;gK&Y_cggM6RKAaq zJ3=iK>e_On7gm1}Sx%F?|3P|9n&s9@i;U-=bxNziZK!Yb6BTSNz*6$|EF0j9@Eyt5 zQ&5zLPN*><9K!g`{TcQjE@?t?r_6n0EkQ$ucN{84!ldaub4xU~0A3;|VghPo=x>8> zJAd@fqU_w*Ho%iPTV${BGJM|T2J=&#^~Qc(?q=968Wcv&^pBJQ;L*|$<2&U&;O}B9>bdA zbvW%*6JXhzxfDYG0+SloaocWET#bn=ESMa$T^c9aEn%(}kxG#|Ut1)g*tGtZ#;B(i zAL;z7g`Cf5EBWSBnU0~GCQyUk_3TXFtxLyR`0D+LMuj4gzexRF8~XgguI@cm8|j%3 zpbl-hGRJt6VbVEx!A&_P@7+hPGatAI#;kXr=@ZHER79lMv^^HX<=_? zD{{Ekj*aWT@Ltp?Nj$Uq>wKq@pybIbLPGJ|McuL_gY3GG^78W&w{}dnYUVwyJ@glv z#lS2VO~3+>UhP$T-4xs*iOB7OPkR%m`=nBD>PU=;L9L-qz73?!CX)3|{Ma8?ubPf8 z&kj*&4oWk3BgLWpLM!pf_Ok%lHPA7W)>*vLQ&VcwfP} zUMusSTWOzxEfkh*;vDzM1IEd$utV7m(_IyVio$?38|EhUj1kM9WA~qVIu5ay{9`F- zpFX;8MeXWFQ`j|Zy_mgRdlblL5E|qf5KDJ5gzQCh5%&g|I*Nqr(Madi*;`~`v6J;w zYMOf>AF00#gwga|t1>nt_eW%HStK2&tPa@FFLhOs*=rm}Ih>w%A-Nwk1y@8m&m;xc z=YityC6OX+n0J3-J^DdkQ8sgI8U-YfCAPQ0SV+c#XfuDH<-WUXsp4&Ic@;ZM-0ic@ z=Vz?C`@u9Kq&O(`Ui0&mlJ<{1JvVV%S14CaJEgmM!F=n2_sxa!M~j=3q7_=?+<$7{|E=CnlI%rn{D{}5)&)ZopON7ZKRvTi ziQhkKv+aLW9L^unt#Gf{MER|lNNNldSE*g>Q=hcr$6-w_d3|x%Q)G z^O#=DYs<`abqSliCcOv!@5QTfX^+UF@Z8IrnKQH<%nxS5c7LnBO(|Dz_m5-Yk%|73 z)S}u8NIYta-Q}uxdMdcr7a0P0Nk1Sgp}!I>H%=-F;$O2VYZ7~GXU4_S-5%1c+JIxW zByElI5>}bC|E$yh*QDMrw97uQTAR1pmv8ayL?!Bk?0%d&&|O&UEf;g78M)9EwwrjU zC)g9P2^-5h?1oL$qOI?+SkZhz04FJBHnUq4nbs+c$4OUsib8FO+jEwu!LxQl_lYbl7m`b7a#m7wBE3WlBUTH5T4qwE$zS$FB`iL&#yt;dS zXk`Dv9h-krpd_S;rSt2PW3B`k6-s?sT5FlZ&7r7Xjrxy^&CfaWsk}=X&Z+)80Rr;Q zj{AS3xUMr++{>SHH)Hb*zB_*$@^)(hI35Ve`pV?keI47%d?2=uo#apuxXB+`Ihahg zp4iJ%>+6s3NktXOPtPO@LC+75CS4#9fX#Wf_iS&Rtf~6*_lVuCWe8+~VhIlHI|D*m z;|PuR5$k8@9t>~^c8ax*p5tEsu-iYB+ej*06Ev7Yx4dY)hZo8IssVFMsVHBeDNje)iS z0xFNRd9EA#b;5uN?7R= ztaea8Sd25Ai@_Phfh(#{wY{Hx(*ctXptns$H4r?TGQR|b3pe{u^RXDuc|AWt9RUg9 zDCzwLKv5dPEDN(YwhymdEp^j&`(D&|4ulKOY1}W-DgAZ`=&}b3NPt#|0V(CS%6unY zuU{AZ@!gtB>qu6$c++*J?&xrh*LC5K_lX|q3e|3zxAPJ>#MXr}|2k^FfD$g9%@ zX$hy^CEF@TNMPAo61k%_tJc&~U>=I(j;#I!=wGe(p_EOiVmd!Az=xSd%3yCI4>Jvj zUDd+r`zSHU6VV;$ES6t|fc;nSWua&HVY?b%=GyX<^G8y2aKPaU1El@z7Bs<7XF>~t zrO2a_gP6GB)zqKLo4|zD1*ut*zS*sRdZ9LwD2^O*KZH>N1Eu*Cs3(*wy}JR_if~IS zo)!Z|^cJ8&7xd&RMzDV7K6n8r%)DwB6jX17HyF6O&FD1g_rwQ3R`hDRlV*Y9yq5;} zu$C}jT!Y_q)w??ZS}pMK8{df`!p;X}3v(J*#3A-MxhDK?99hq51%bZlD{2isP7k>h}8{O3ZnW8aNpcg8vvqwUZ#9@VonB@S0=irl{4mVRM*7`N^V%Nh3$w z9&fsyy9TKE99I0QW&U&qy@o_F9KLk|UN8BJ{y2g^ZE1F~ zZk~bho(aQ?Zb+7mp}Qyc-+FlhgGuv9I1b$d@990cok0j-_64feR29;pNeEr+L}{cpIDU* zY$`92{Mj(*(Iv=XCpG>cnvh^xNO28^_|skX(XI{1oO4pe5aZR^KYP;dig)^5>>N;oYF{EYVWqFb);?yY2refvE#{9DD{xxIlVrW`jN2%MFQDL&!gcEECQ z!CAs`UR@7ZX`Xb*T-2n4!WdlKY~!#`PGShIoPKl7R|uuaBcRW?#=k--yHreEf)-)# zG#UT$Nv8PX!rc1eHXv95{e_)cW|5MS8pX6cJ&OJaJF@+%Q{A#m2!PIKyxa{aAl?nqy3DnUqp?8=oPUFBw#eK8A}1c7d*IGZoX5y54>=~c zrr$5Pn5VIMi#W$RZ8h;tcHt4OwZTOP-YSV~q4gKnu&=|Jan|D`-ntj4dQuv zP{Hsv=-&(-g5on;RD{Q#VwBigD{oZc^*gk0fUzV+|6Rl9rVYuoZ$0!_TF8xvp8|<* zG?gsmckI+Ba{v}4jI1x8V2RWoij0Mv>U1i?8^^{}eUSxC2x0rM>gKduHU=&kgO)O9 zL20-Y?i0eW;Jqgi$3OvAp&b==xaKCS!6VCRj^3YcM$XH zek)6v@aXbxKl&-to}!-MH+XV{>-nD-pX6wNj9;}NYYrZi<3kq8fsd^|birtwlprlPP_WwLX<9MXLVzc6}YNf!*$-|^}YKVSDYeQZd(ca{< zA5yG%2{b=9)(!VbD=3*y3kOUsk73Bpt7C(u9b%628`--Q&#>zcbH`MBk+c33SR5;{!rp`Jy>ori zs;l1vps$JV*GW{3Or^_Q5>`&)p)|~b8^eTAK~u9|drH@GdXZ5#TnQk(B>+N{81*i` z4MqRuT?!-7$}0E~DZ(ZClBzEcagv#grS=G4)@`~7p}7vmbtFCl!=Oav>7Z#tt6q9! zC?5!)i2kF)!t%$<_LSXWIqhoJ)*{*SGUOAu@sZexwSdd(0pX5N0vHP5CaP+!2V@GV z+A;{(EMN?BR!5=+$OSFPo2dt?qs$)eYW@)<%D;v5F9@ACW;7b}Ms$Mtb*uBuj^Fdf zq3q4IPSq$H-qQ(@+N!`5RTN_9%M~!}E%;Aef&w%7Wa*`K-jOO;pA>rw*#W@|5R3}@ zYt64dlZV-@&uvMHaEPQuShD@nquHb5XiX95KlO}p%diBNwF_~5vNRd=NLC*3c`(>1 z(|J_48i3_T21<1?SDOlkn%PsdmOByjVn~k0IwCfVrz(71bzKYV-g!Da;Yi*wuq5qd zB~lxCSJRLMje9Y}n!3nt#WPMgZKT+RGpTZS%-QqCxgI5#a>82xvSze-viG!e8+jdK zdS{H_8v)`Ces%V{#wS@W(4&dyqF`=kRm%woqKt`#RJPB$uuwU3+WYi2J>*~E`>3Vt zP#om-UuTk67!ACOdDAff5r0e@hbR?56`hreQ6PJU58sa-HoTELE#~Xd@=qlZu!Y$} zUSYjMz9|7HXre8*z7`dLoNRjyMPbXh5T8ZyPTL_E;uwlAZ(ohJZrRx;O|VodqQ1H} z%{VatwwhVIaOd1^K-F`ggd=}(>t6y~EH1R$#3M4cPF#Cf=^;DOHvkf85WqGb#vZO1 zZdTJFH&xPzU^d52sE5{B&WLt1uYr`m{*^+sHoo(Za| zcXPr1xGy1&<4uQ%+0FyiRpjugNyEN`FE(uE9mE+R_bq6zCi{_Z-9W@?$WU9CQE(wg zF?o-SE&E;dgN6={5oo>}aTRyEw}-B)s7#$;HZUN+#mIrj^?tEK>tonpzlr&M?3rb6 z#&2NpPiN;NYVb`KK9PSA9G#-ZoCyIq?F9u%XCGAyNwq&SXqQ+YvF+I&9m8AMtxX?s zZ?XTT+ez*&bc_Z0sXE13=IU-hU4Gxzb2I6L@`e z!+)-fDHdogpdeAjgS5m?-p|x?EO*fyjV!uUuy=x*i+_fP@rQI5-}@v)Pk06Z7H>@s zM~<%(kMd_7Mb_`ozi$$RH@|}fa3)B);k*`#WL~Hl9ZClivK|UeA2Q_TiXw7hnd+_A z3cYD6OJ#BvM#qDDLB7`x%*hdN#7@LU--`5d&zL|RtGKs@fF)Zh2?xvr{wO0n;?Gz{ zr-FO7u;=z>^^%9t9ZK6(3Cp+3C0(4g#<1T zTA_`<<57rP*<{azQ>b!3#taKpRo-`ZOF1);eA>}_um{{kyiRaMBO7@!V@+5j@{TVb zYqQiZXrcq*r(t+!^~WsVQ|7Hc<$BDxtR^4oLWp4WDXv;|+1)xpJT4+fEW~b*g$~Rj z*#ZBnwa-eie=A6@2N$BwpEl4HklH6*{YtQZ25 z64}!XupWz_pvZ*2R0hO(%1$M~#^pJpA?|c1fJNdM4*w;lTCs|Or%(9pZ(k!e73#pY z6znPYVvJs*2&6nB{1 zXyX9U;%@!}orAp7?_L3b^FD)pn0Tx-JJ*^3Q8Z~B?w*L4t)9e4L6q?L!n3|5nAYV< z1nQlJOnm&mXf)(4pNc6e%Wub6QSIA?RsW8<(`_IDNw$se(b8UOE-#@8c`4f3j@Arb zV`gg?UO3=PL;#@>h1pYd4yn`gj>Js&CF^J={-yTaMcnN=4Qq`D9AoR^Y?TUQUKaFaN8Ghl$I?>#ryqwg?5HMY&xBh4 zx{4>^#og1b8r}-Z%fgIHRgxd)zszg?dCd#JM1ea4K{rSAz1Lzk+T_eg3){(i1uO^O5J~yPtIF*B0?~Mn6({oJ!ihv!a98+ zDUKcPEYnzrd2i2Xo!JnDeGXYVW6R_SR@-!Z+B;TPCT#dRUs-7>{gPf>GdeaKnM8i? z7~R5+yBE{SSM}UU2B?zv-pe;wfNby&aRJ_t;6H4!|JNI0AFn*OxJ1-Z=D`R(Shz0A zEw`Hlj2sh0A3w|cI1z9-Dfz_p*bFZw9>2EM+H8M{|hPc)M`rp_tzo(VJeq-rK8m$qPS5f@|pEorSqrG#mWXo9fx68{rVt$BUz%(?ct%@B%L@$5E;4#zf&sV3vX<^Sf&6){5A#5Ril#+NIR9X^79ii(zh-k< z8iuH+Q+4kZ`EhUO=T(H^-C>*(5-l`Aa(}Jrypf$i{&CU3+(y#1I9W&op?pn?WQtU_ z$Q}4K%-@g%G=a2ex12#}wj0ytKk1nhap2Z7@{{vo`&O8yu)72h<+u&`p|=Wwomziw zVb0Ig2%bI4TlJ^bR+cKg4IF{!h8Te;!!K|qq5C!~mEuha+%e}Gigs3=JHX_SY;B3< z7fj+>xsSp^r=B)&ZwMl0luwqtSXv^YAIG0g%Ys%25oWueAb{pm1`(w|Jddd6i&?8K zfC~D)Ut?i6*zb}kVZD^afq*4de^5NdT%E#3D%;J;lz~ zR1|)8(!Gtv;wFP1U>ygm4tI)zD|#H{hb$pyOK(`AFDDB`lOJtK$@>^n z@$U3DD+wumP(yG-xS5^ml@A#9U)HR@H4xU=r@gv3SC!NLrwI+~CDgPT{i zdjM{+s~0A9E$pbLmBeWXIxp6yE-}0=W}iCOS=PfFd+-3*WhZ<1&)rq)eZess~;qt1bB`XIs;Yr-D4+;W`@1S65x4*El)Y zUOR_~)e|difpa$v`lg$R6ms1hWg zDEKDUynq9-R%yWozH{L(-lt_-rEMNJgIxB@U5c0%`4h$z!ZCtrOGE-enU3TubD|qE ze>}|iXmn>kCtHG$96i01o_#R%+XZ*^Oi&MMJFViD5l zh0TAuY27*CrIErXD2Fc41NOldfbm#IzgswB`u}JE#5Uf}@f6Or6+hBLIxRGhM>K8y zZ3Rn7em%a#SAX<_YpM8X)77Dtjd6xJ8J%Y-8Y19hGIL5sC9`QVq22HqU}Px#m6rDO zoy`Ogg`GXhn#wkNDl}DkbL)n;I!!i1whMqjkNx-E2iuTVVB!`nmR|zql03jPVX~J7 z;Y`M6W~lDWtH3nbH!gwH5}Zn*R@fV{R~2O6Of38eI91Ib(?IU!RGrS)rLEM5c6GCo>;!x zd@B9{2lyHV{ugv<x=J^w@>)fCZ*lve# zt0gelAnZ3P>alJIS48&Cqx9NQvR5+yYDOeQXv}X*v(3jk(@5}_b9#uTkw zYqd#GOu_WscoE`*FFG>b8-&ljj9bF(N@e?Hy+ZU|tS)q)U!Loc`Ozm*PdIm!3AmXt zYGo`x;`sGAh86Z#bp$Rmbxw3dV72;*e(#?w4wMU0V$j7UIji zy-!SNl`n%-J`S$_1GjmA~_}`J&|p+E^GxHtsmmvRmqI6ljq%#p$}G&`-Xl z`J9eU81f#ivcQI-4YT^p{UBD-A+w$ZFF?PzuO|A1?@N3H{S+D-fl}RA-RmVs@{dlP zy*$7oI}@DVZaT8_zKul9%>bi?zS785U{@$%{VJB*r&@C0_#RA#vIYOsTW!)df3@IM znJmk@+lMh#c-wosXjfjK^O=5wlcP<@h0jP^=PQnvq}r zb5k&pQXw}!$fk)ww~!_7L&;(GYmKlS@;*9LEphkNt=DNb+Pd;hFH!^wRS)evlr!DM zV$4sx;?hhOn+<~|^KVoa=*3K1#JM>%5{+-yOjXqQs$y=Yb3aH75zU7^s1(zv?sZdq z#UMX{3FHQKOPanzLp5g2{{wt9Mo^QVoK#|v4Rt9_o{~Dp4l%j>5js>)T>iDIC=$G} z8bQyHvd*B4Pig8ag24bZBkhYCl+C|*Us2nPR3z*Q)y}vSDSuG;lys4XCyS_DPhM9? z@sp)JT4D}axe*MG=OG-~D2*U%e!lk+c8FFbym0O+aZouviHxc8`0JSuY6}7ZHc98C z^Sj81#_&-^jvp$(hNM2HbR?vd-9@;VoODX~pj|?NLLe7DQIp4UVtb}KmdtPyUU@XJ zNf(?Oy_Khwer(ncJ3phMHni!FdAnaij^Nzgo3wqZALmKrktd63^S_i}XIEP*lGe)a zeL;OG5j)h{{DYC`cf3MpetUoQq)AYh!S}YIZ@Smxo1uw0*{|$91_U#{#jh-#Rs#;c z@r@qg04Z&C{DZ!Hoi*9GpTfGsip5BD87wGP=2N|CTeJ(ysBFJ+ZC%B`p7;!NTS^~+ z15;s4eWME#zmzrBfq<$vFiPSC0w1|43VFaWDUoGA(ZmlT4#V}y#V6>9=~^Z1JLg#? zUb0xS2^xHv9B4<~_Vwq$bO^Vjx?j0_X*|oiLbY;Nhk-kdVtNXkJ1UE0-to3%?IMxs zJGHpUs``MXQtwmy{anO_?51m`kU#pIEBHwG68N5%p3Kf$i38E1P9Zj5@PDQ-qi+fq z?>VdJn3*kBHY$SAXV|_ld}8UmKFsZF05(@Gnj$B88u=63%@wn@B0mUCvwqHNZRC&V zq{b!jf+&u$(bRfkYw1fgL5=nJIvo?v9A?!VVjx$H70^aDk?1A$4UQ8ji2Tas$Otk< zLLFS0$mrGMSVw>VW{|RAhc0>@;PUP&fUC}3KEKMacC<7P1aNoSYXH$op*@AN`P}@@z@l@N;{U z^ZRX7i&iml!?zT`9zLgoS^{_`R-q<4DRdOsT!RV@a$!61DFcbyXqBv@n6Dj&38+Ua zvO5YbzUwzBFCgPwKOLar0IJ$ClT7_1ntH4i2$r?eqq+7j#@O6m=2RpS%3d>v6Lo?< zA732sHZLmE-hsk|Zb7BaNoH&vlNPFB;gepw+VAx9<9%jF>3QuwR4pU9R2z^CrdCuD z#9kkg!r)piT;m?(xIfK{2RTgKVjTy0kSnTibMZ_Y=*Z{^K##? zpf?)wkw2I;d_&qc4s&o$iFP-aI>5(%!?ETE!>~^xLWgKY+fpVAQO0G*W+LWu%%n|o zeezys0Dsh*eLhqQx3*N%ge;yHSvu?BC-y#b~c7CE&spUg_RmcrMl z3smz~NR0_q(~9YGH%x5-DxQ49n=G9U_XRq;W9!2}yz0xZa`8nTWLZBXrNk@v;Pw3( zauHGBZeE=hiVAU>G3WMZ_Q;Sqd-{4>O}}iO$N&jo*!)odcVu3AaO~*Dn10cpRaxL! ze3Yd7RaNbbSz(q*FpBZQ`nj>XAR4Lv-fRJN{yx7_{iF8J=zAWNxfRoowA7y1))n*) zR*B_*+L9}kYYF4fh2(x4T~GO{3R^9pKC}Hi>*x1!tyDHWkwGgPvG2|FR3%&uz%*mgbvGfpF1!n|ER=On7v>hUm)`f5%Wx3Q^ESLZobbkEZf;WEQ13*-_I#vYKht2 z@_>f_=_Wlbs0Y)%=Hwul2>eBHKU$-vof&L z%Z+HQ_^KRU4kd(cVyUe0{#i@XM9t_A5mxf1QC_dyPwRdMR`GM>&p7o!*aZ3ByT zq@J1kb*d?Ya)?^-B{Kr=Qr~FSV&DO}fDn%`4?icFhr}j9TyZ70|N5N|df}yAF0VAV z8pjV5L>ci@26VKhnM_KeF_fS|S%Jwyj82D+J2a9l&hf+Z>pc2$KHc#d&Kv+Fn*`>Z z<iz|ZT z=RDLGs7vsQD;wW*i#NBLpJVcOny#AvM6b;EW@33%kgRcLNc%da2E@#mBDq@NqRrcKPoGiE)7efaOU1mVB1KzJVOn6 zlIqOF{`dQ@jZ9GTn@hvNA_n$qcIdI2zncGnY=%Qpoq|V})IK+Uad3r7aQo~m~Eks3EycT>SZ;39L zlVwO0;@z&oC#1~M*9eVy{I>lZ1s_T)Ov343s%n75l-t9tV?u&~;K)CTv&!h6dOEHy z`}K`cr0fa5CLOAz!}EF%?EanF4LkF^gg%S7gYc)^BjohL!cuf+)Am=!E`dy?d~D6ZB<5Owq{Jgrp~&mYBP-Nk5^{uFvI*Sd7-d)UO9f z(>E*YIBI@wua(Z4@y!I@_A6*&HHugeuYqgqc=jiVrY-^1qut)o0lBpWO?i}{vTUk z8C6x=c1yQ(=ObOx(gKnKo9+f_>FyE`K?DUh-OUE+ZZ{>HZjcr?-AIF+1<(6_-x+6| zAB^D-S=?){`QZW88l3) z;2@e6}dr8z+?>jr=I;q{z2P4Oyy`km%t-sLA1Gn^}6JDO=gfBI!k1nnCp%l(g6 zHx)vm6Oes+7&%FtoG>QSr|kRK3HIZJ{*-r>D7qqTCvW?BC)0l(4{B*>Xyih;1G0K7 z=k5+dYgds&5Ie^geRQo&O7(G-f-9!k0A(|>;U{li&q2Im#7O1s{g8Jh9<4|!F|tkj zE8S!4Rg*XgvYxiKcKL2v8F?Fv@u0MT=(g#0R={Bk+wGU&%eK{L*Vb9|r>+JD3&V$p zWEgwIVTNm!>|Ms`AM6lNdTs=u4nWKHZmqN*9u2%mdhtm2@zeNiaiOq2+e^{8qJiakN^(34yVPlUM;5iZYRpJiBJN5_?Z2J(dvnvDhT&kg!hq;r z%6s)$GrHYtUlU_@(G|6gTbrQGgKi!I=A_x3ugLaQH9{;WG#YWIEx+|t7X7}?uBZoP zTcy8rn3c`Q&=Onl`m;R|OD8E&G)K-Z=&~|Q<=F zyM-8eH;G>{wSWjNYpge!+j3U&qfx+QDwXR=J=>^@ZKhhb$MI|r zX9(ei)>a>Gus5*=W?U%-EtA?~wh21HS0JzJw-yfDjz+g6E=8&=3zvU3I9U4Sbas@% zxFbz%6;l9-2ezryS*`ZC zbn+u@>h9i14%ZQq8nSKSjbZLCNO*e+ZB&CY*hX3)C z6kD>oTn1-j$24=mJl55=y(HW(`^e&uky^!f(5|pB$Sra!U|%>FH1xVE2R{tJ`N) zmU1Rb7VjEj+x%DztCnEkvNg9(KS_OYCID!4kl{!U{o>(^-D}K`{Z>dqQA1&y7Cp^F zfczj&RFn=jz*zbQT`pUZREdZpP|ayk7ZZE_GqwId#zlW>R;o#PKq;Rdc<(5kp3X08 zfZUQ##gRM(fl3<_oZUlH{Kv1 z=stLPinoIg5Skv;qiCx0uHs~cyQ1K!-!Il&DqU?Ll@=g1{U^JqeoALzI)z?Er|Cga zH*Chun7{eYIqJmC`Cejr&z+tD5CIn^yVB{yxdxo7pqZ(yH_YvSfynH| z#R_NBzOcOB(dxxzTvJ0x!0m%KbyeM>XkrXgX|Zj8JYCnl+HF(AgUi6Jw~(pc+_nmB zT>((b;WB024KsDWr##IaW*{137|PtDS`b%J)F%lDrvcWzV54~wFbX97ci}TVm>?J zf4MgH5APROSGc+ z5l2>mbjIT)S4G3#`f02S>QqW{=LZ!3rib=)3&E%aIG8r5rk*`f=~UdGWFV6fC1r&V z+MQJgP01quH}ow++{Id6t9gZvWpOf??8ZI=0`{tx=WYJRKfBZq^^MPqrh~NlGzQ?IINnh{W#>~|9U9*O>X+zG^4HNAN6t?4zje^6Y*Xq7lc7?`16U4$QCc_&*2H9hsKu(>|Ns(Ijww zeeNrpa3k{tD?TqN&p)_!K(JV>ad--Frgvl)HOI1(%?@nK&NuPHwW}#S(nd^UZ6v&| zc#jWfnGerIu>&terUW^P%gK()0xfcex2l3(Fsg;non;>m&T06J^?iqBx4mLCs|8r>k} z+WpRc9zS7-G?@+^0qEKISKdx){*l9 zG_a~}f8T9+VYMxQ_IxWSAU&_`@?hi^2fXEECNXw^ov{+Tu)61E%PMYDb|#977Mydg&R86v;@KuN*|Jhk}-NUeEYmjEuupSD3cMf3ED+H_~Ms7J-aHt;oY5phX` zL6X4_QU<5|RRu*VwJDz|`H4jU)VWnLYMBG@+p4uPd7E-7ZI;t{IF3*6120)KuffLV z@7ltav{~IEjAluL$16Y84i0&AM=UN096zjw7>IySoL zJ2Pk|YFH5?KRM|d?iwKSA1_$i`C9@8Czkvl)ubWh_?_jvDQgG5{tkzjKyAv|65?V& zWGFH`{Q;{a>~~)Cf>GfnOmr6S*@;lF@Z)5oxu4++aUkYb~A%pK|vJ)CPZt+Rjy*mg!z*5G)C>eJh8)@A4s9AgLq#MvhwNBa{N;g?Z6e5W$0It~l#n80nk5QkFOv@=~T0 z(95}1?!4pAY{%;-=eO%y8(___>~YiueDlHtE4Om_mTjV_x-ghktN}pXu|Ify8yoPf z0P)*DS?j66Y%b#!LYA=%FcgK6I?@XoKzdWh82cRfY?7eN9enJ&uo14{F zBZNZ&h=%GbnidUG1sHqADKjImPk^6Rto{36BjZd?hnXSsamw?o{nK%hR0r$O)^!nY z+T06+{G7|aD-mcDe)jo6zhc?^y!WH&<+~8plX%aY3pn2dfc^Da@A~BKtwGMT13AAG zlTA@aF$}H~+%mN%4s0iF6euOB93-ZQmEvh#^YRi1!S7bbR77#ER+$0d+39FBu&LDi zr&n!6HVuFAO_-GPFK0Te3U9DH!7hPrd3^u3hxN}^qkMZH7WhILBo=W6IUA*t)WX2} zYlTwZIWQ!mjq53DHm-o~UCY(WU3!f)SEkr;nE=WHNi<)BISrmvdRR}WOqh(JISv*Q9by%vR(Fk?eyNamw(&|oAmnRcW`9K|uOD?W zG#V?CH4?I)f85zCl<d3=TsmId}@}l6l+S9p0V|=rD}t7z6RdpCq(>sjDMAh$b4lizI9U) znChf7VAhaRTv5Iq4gCcIUQ*5088$gyb13Q!>l-yNI zi>Rq&54|Rd>ukSwfq*8hAdv2g?KlskYbgX3thk6WpNg0(P|?I5SY8$#zAu*oK!_PI zLn3V+o`VHHQjEWGLSp%rG;oz9DCF(610Nsdzow&2XlmOVANvc9HR0b)lDtHUnW+mF z-29O@*#8c?^2Kl2tEs9r*3*Qfigu`PN5l0+ogy{4KIzsI2p zez5~X*x{b~nW2olX7x~4E9_XpNuRei zAzrLw#rW1fk>8NU*q0ck@Bec6u6$Zhhr@Rrh2!|&Qnlccm%sw&;Jc3i=xKX0`P5Vo z_YFHnPBbc&WbF0#3V6BFBuz|DMRRz|et9%g+x@Hs|E0SGBxmsxnwjf65d5Y4lEkM1 z9+10w$JftiV+%lVKRI5Kz;uuE?;#$m~j&(lQ=0FvY##op3t^FEhMypAkLo-4d2xv9v+b zk?W8wUZ6OiUi)&Xm*nN?^Q3?0<|X=N9GNqJs%jZ~lFW*&U78KF-%HZL55e*1&!pBW z3`dk_*v|SxAH{8=W*Ac|H`jF>k402b+6Z;&KNv5t9*`)*C?lz;^J*w&3(pWjJMGM} z5zU^%<`3X$?osSRbr)+3K>f|^RUm|kX8jg6u7V9BowF+F-N5ClJggJGnC%V?dHwpZ zAuJO?6(li=_2FFAY4hj!PVLNIU_WEH{6^hmtzp^mQ(=1#2n?N0~vFgYD&A|>7q0-qS84`*|b>qe2ido z>f@SjtjHS>$JozdOouQIJ_)h_BV+&DKf{`}xvFI^!TNXgDg-ef-4TwXG1Ll{_OON;fmz}s z`xbSuRoeAzN7ie_*M^G_bn3!WD62f45l6#agfg|NzzZ5&TJVc@aW351of(}z%>yq9 z%NzRi5fUW2Tf?h=U5j23D4hxXw#duh%Gym+_nE*yAVsKfzvrM0Fm48+n{bT~Gcz7e z0w-Le$9NpXUQXGsgRQ9d4#2qZ1#NTjV@%i?#t`wYLaVsfBXtqpRUN6Ec|{$i9QKLC zlnf4Gm&7YMOB!E+^`_a=j2KizH5=R!!a-|p#$4s;%wqvrL#f&CGQh>KnY_2x4ZsAI zx1X_8i3jQ*fvO{STK5-M&#+`wJ5Q7acIcDCOvlWS&r7o~EMPhO1uzabV}FA07n5y} zP^BbXS)BvzH*Hl%h#$L%+mQazIrGh+I_YfCTbNa(beOa;^T(c&W^r_J0d-iN;P>i7 zEMqQcB*c+$9aUD#`gT3vORt$YWthe&uJKp*mXA81*v`Gi%^n35@nO#{=iqbTa zgybGcAB~+S*h`g^TZa@DKs%rYN$6{B8e1QVPP0vnPKnZ3L(MhKTcPQHWIh>9iUB3S zl(o0E1)&+~BcjmDmu|OGqD3zM41@Mq$tNgSyU_Z}T-B0$bbw(wX_W`XR9d5fJrW!o z+|u_5aF*W0k0X2WZ^wOK%uKhBe7{#qlt8ue=v!DRu48w8JU(5tNYxY@>DSo%;qRsR zk11(XN2s@z`F)CkA^4=Os%F$+ekMjB=10YL@p6r3I|rg6bj_V<(*>mwZy{c>;v{6h z?kowqIitKpS{*q}twznBLuQ-u(@*-bb-<>#j~H@6gE`9cdjj`>GoQ>qe4)hOp9&&A zJp=JTyJ)T`PjYl_<<{LaViNF2QdJ-A3kn_}5Rl317q~Lhi&OW&H6o6a@^#$8o;lpb zeseUFY~q!XiK;Wlm;fvV|7|`H?ZB9G{B+WbJXJWjS8=alS~&_J1w-T4y-+vEu#ZV4 z?Z+r_9M9-PBaTs*amjkejVSh{kYD&XvpZ^hK{=xQov~KJphnh~ zNm|}720?>49fVUG0$>Kb+p`7IK#@gWtj{p2Df zn_-k*e(-|$E4@bm5e&LPrJd5i*$@ts{uR<0@eAoe-J+#=34h3X=Z>v*VWU*>G5HbK za}LSmRF8M}ERtkXD9K=iWHP%TZY9gtOM^3rvvDH4zINk5?oPR@&eHN&csULN*HQ#I zfaDzCVhL~ZZ_#EEUaYXF8-Cqw&jrfZZFYsU_h5Tw)W?oixU?kKs$3V3H1ND@IoKwu zi9LYfpK8=AGN`CqTFLk}M!ArS#Um#NWD-YKlC1(VRyzd77e?j&b{cP!p=&Fmp_`;q zKCO&vNKSarM%20!NVlN|zQmuE4l@d!2@~xQ8d$fzBp$p43Rp(LJ61W2)Cs5*pkeLM zrZTI17xum8|8EwcTB0B(Cpg(2^BLAE2mryr4?t&2EwmRyk;;{N`PVFh!N@#m{5;qu zPs?}tLiha{)gO<=bdgROKeTF_(j;4_{|_3ctzcdkb+#MF2cP+NazLvL!4EIKO&K*h z!as!hA4gIM6V^?3;u%wknl$=9T9=?pVki<>F8h6OP%bBWC2RS_GKbBN{@;uO%%gyk z0aZOtt^m5P6pNG;C@O-2aHVeEAYCBUAZX^}`3q#jUu*HG)-P{d0otd1d(gJG2sg?h+$*pKEBk0nUqmC@c@Sx2-Pc?rfu0gM)R(54 zJTdKOPUgZPerO|+fCrIJfI{vBiLTiAc56j(B$*?c)YfC5z|lIP03?qT|KK@%xc$Sas*G?i}{}(?qLY{^HLg zAby*Vd*27szCj$-tsA5|pa*f|^EeKN+zIg=qd9|*Ojsa;s4>MBrYIE$71h}#IE-&R zokQjS?Nn9gU-ZB5T;>k=%}tLkcKfJ}CPU5eul(AND>UIb9GqOw96GQiajxO0KyAF< zAk3Xv?sw_HeJp1(S?wN5f@9=+uBlKGEEYx!YD@1&kdXo62W^mq)ph*PyT(L*0tpRY zIpbN@J5!5i)&9m@RnNc+ukUq$`Fg%Vpkf3ODwgH3b(qD$5dQ%Dq>B#_<0|XuV8! zBk?$!$-?|Mvj}y-^j0x412r4_!#Sc?GrfS$Uw{_yyMhI_$(_JqEu>(>9|k8gLU z!^$d}g3A1D0c|4jj+jU+*_L%rTOVk&yrpe(+*IwO>1?o}nFUvB+g?F;8Xi^fb>+~^ zQz*`se+7eN2uqs%5wLCvSbeUN4cmXKnHwSL%kt@4{k-`Eak)r7^cwQq$Fh_cFAk<{B-cpPJa679Iz=1tFOMwHW+P_RP6Y)%H2Y}lGrQ)=M{BF32mvdO2B`58 zf)Jtty?DMvjC5q}=$>9AxepF)3`Tx8YysFEa3G z7a*EPx>GiPDJ^GYPbwNY=TvO);K@0*@@`#L=fm0R>3)9cPy*nHuk2N%ajKUjQb+CS zh#2J3!nc*W+PA&968#{yirB73JQbJ7Dab;Ob~et{sv){Swt{wmA31aiDu+;GobhP+ zA*ZpAAtc_2srt1v1NjJ(wRy%~J{vK>FdM{woJ5aEU{OZ}>M+-XZC*f8rj_bE0SeCs zS{WZ!?7cjD$1%o5YGMDB2A&Nwe{>7h-zBB()*447vfocut#YO3<-xcg5Gz@YAU=I> z?+DlP%=JS;d#rV|tXt-;K{ld5*jBbhJ<yAdoXxcbY#ZbQ^kPRHE<`R}UmCdBb4k3#vxPr%?QgHej=@s; z*m5m8`R#i?fSNSSNC^mC;=_BPgb?qd{nE@&;ROx!k7ZS^UT;z!JdA{gzuK2I&(Xy2~b_$a`r z{%kiHVjxJ8S=jJY2=#t&TLh@V2%x{jde)F4*A1RJJzAt#v7!f0#aMX{D*r8`>ey1Oa)D@j z>}e`Sxh1b@ZIS#6#*;;nC%ujaFYk6{r6S2DXx51E&+tn&w&r-bxZJy+s;PPx`avv6 zqOwX@r_q<%soQRF(>f_gtn(GSct=myFtjVIW=C1jb;*p84jGVb1zlsXU+im@&jxsH zy}$iE26jdSP$@URyN%7Q1n>GE$D)=AyDr^wKt6PF)ohl%g7``|!JQ)fvH4a3Wg%jD zdevTj0#Doh60eCsjV3IGeasyp?`H4~x7<;U|EPg`%#LHsyu7;(>zsc2sO$Zflef|- zIHkO9U3gTg`9Jo>JEPjAfUxQnPFLQw#lhvbSY4Rc@TeWw%P)Yy3v_FKy(SQLV;8Hu zsg{z`K5DI5{uJkKXNDq!jBkAwx-19^X^kOBOUC*MrrdP*>b_tB8F zvKEj@0h(~Q>7&_7VVT+6cx0=K07Aj_`W`h7IabTnNO~73ub|(t%HRGrGWPPZ6I&5< zLNqS4uHLLsL}pZoE5`$MB-E|a{S_m=G@jlFy5tjgtf0enu<0xjDOt!g{*UXCfWfn2 zjEDyO=E1Fv7OAWc6~{D7nKq-y-d;(7Mh7}EGvL^a{(LqfAO<6l>VgS`kr7)(#P@`i zBqomISPSxx;IISUMind3BG|_1VFWdw)df;*n5$vYz#xDde{xDQRk$#FNh*-REjV#x&feg75s6ze>Y1zk#mPXe~MbaTJWGyY_Lpydx1@swhAi60t+rN6B zQ|Q5XM!7z3zcgx8*LkJ<_TWeo5b&j^4g?oi(>rW=Zw)q8+^48iu|2dGRA`(}9zC7Z zX?!>n3GUH@R6gZwikvV#W=$+G_qS?n`Q({mLx&nC(}|7xi;rOajj=q_;b|O$Kr56T zowS*&+=wPy%@O3prw&YEIBKr!Gw6v4;0S9(1ljT}b0o=5PQL~pPZN2~erE;xXD^%= zHRnpWN+7?hk~3j$(V4q!>IBz#M_L`cC3|HEHhb4TEUsU69I&>_IpTfQTy>x1{o0hp<1Xh))F`m!v4qTKGYl!PS|s-+fI^hhqxlKF_C?Nbnd-w-Zzl{!#@chz>`<3N<10@zYzg z{>(k*DC^f^U|&DNpv9nGMU+W;QIW|!_9vi%W~i>L+jos9X^SA4Z93l550?D1*pw$f zs(@30BD(hyn>Zzk{S$oujK0;j+#U0g`sW+#z_%>K92pwkTLisc$FP4ms>y9`*Vf@w z@FRCpPY3LAx4J7PSX%c+voR^v=$^qyg&uiUvyt|iWL&%@;JFHQ3_G;yQcko$me{$_ z^;8p^o>D5zFW(bng`Mg*6d^V0#x0ZXH3pn$pqy)aVYWkukiHEE1t6}bG@XC^-JJ`bJ2FMO45gUgn$OfISH0_6I=a~Hj8GE{Zc*3}5DXvK+n3Q9B)q@N;JS<+a>Ix#2OUh@ zz5rZmTr=Pn6D_~Q!L;ObvNm6*Mo+|8>GLh^rkh2g$rH)lbe7Wy4<&3|rL5q&dvBLPl@2sVOadtyXhn zmd4cjl`!o7EtimARv(}_-;G?J$@54jPCjS}*VX#6k;+)|#&yF4rqpzc(}MRL&FY>( zHM+M1I$d{YB6PY7u*!p~-<^@pdM+XS^euR7-OL>|lfMP7wqo%c11m=D4BE$0J=% za7M3GPFQre?7V6A46E^P+`3avtw$5(8&`>zh-0{I-% z)`agF){r^jY61D>RF zOf;)S5Gow|o(A$udqI}6F{SkP$Uj) zS@LN7W0ohCbeG)7ln#r^uh6w4F4eWxaprn>^o5cjpyCi1a0;X;aB1#BI-AA^_apHA z3W27w4Bxm|n!vV{aAgc$4O4_&zzQbaz+CL&I!l__#+YNmp;p>rk#CG{g^hG$?kL*) z)JnM}h(lLb4?{JzrNnyQ;9rkbC+pK1;+WhD8loC;2|Jqvk9dwO|L`H`#{%NfqyVhj z=eJiv!v@J=UVb_eGKsv&6hA9KRBJ$)5iIt);4=$nC|DJH zh^XXu8V)$M?FvZ$%kx+$z`Q0ydgb40me0**xKE%3;f!8a~B=j3v29xb@ ztvsNH)fQBj4Ahv>pSQ*GlyrYx{IclLx8cV@k2`hu5_J59NYI(?OWj7AgEd1h-H1I` z(Aujiq*Mi1W^DMgMM!-RP6Kt;3}EH+;MpBLVpSBB=O2`Do|ly0exk>kLuI&8)%iNV zj!%32u)iGOOMKqaeR3q0fnADH_E8Cyr$xlBX(H0CDgIY63{}45=d0fMZosIPTR5IgZe3hPRXDl zKAmTxyvYMyWyd;%iUOgbLgGh6_Z^jE&(n|7ROiR2R!51+pEtl{V3;lmB#SfA>ZIMO6DvgwA*%QPk`splKLMvCI4p= z;!srE65xJ0B4$HROGolWT6JXq5LGckCgN=DUMjeut0E_t&~qgQf(bed!OA}3|2WF{ znXXe1n5x53S-L$IS2l}o&I+dn)K&1pxODqZ{VYMxFK=m-E03KC@A_^R)}it*D6#u? zU6Y!L%a0Yq3h*z`kg$C8Dki4h+5RZ#M9D6QiAhDL&gYo}-pLJ&J=2EJkk+7K-5&|f zO^yQ*)Zwmc>sArA?o$fshq}7DhurkD5kFZVHzn!m=~*^z*m7RDuxH&?Xq3q*cE-zy zv53F0xMPm>H2&_gkNuW(_XvHVhGIO|@Z4BL_EVQ{l91_E_bPT^8fbZIdDi#w?{d|M&zrKielcXM;7oUF{<@dstjt0dO*m1uC+ z^1>0(?cNoeR-t)3ebCkBZPt81ja9EOW#OqRH^9Nr)ev{}|BDvpOlJ9vDhLLv>*k`wG`{1I4 z{4ZLMCzwxODdt}e%~Vd7M%HuXaMAq<3|@yup3}Qm{*WR{Nt=+*cIx(Pe17tYC=}|Z zE{sdVPm47mLLBQs&QIGP8_pX5oqv^Qj#qCkBt<}@ z5L1&2z0#O zCvmd}Qa=Cf^C*w+n2ynS*c8hb5kT$L8lRjq*bWp8O9puX^pqa5fk}o+`bvr!uT%th zdbPV8!HF_z`7{+xJT2BMeaW&% zT;VHK$&lE~qSI6+U=#=d^@ub<7L#j*sPVzS3)t$Wg2aAnRvY;2X;LFDh)~(@R9ZqI zq5O1)w?B0_-#BtoT}+1dT#Oi4KSlTY5rW?}1Kn;*U~Aw%P|{wTKLR}|7Z%y{?;*HX z4?QN_<6ELPMn0Dt49gdljfotZEiM6-klvEc^AUDg5Ib>){XIdu0!5o7V+X}K3_@yG=2%Q!MosJEUL z&L=~?;u@ODgXwEuxTggtNs5mb=SwWt%m(cRy`Nnj{AsRs^`Y%PY&K1i<;w!&@~yX? z;zVBi${2Rk*UtEr{VSSQM=|e_ie1(J?*IEoduZKOe8*nXDE?$bG18tFQrzPcvD3ym+m|p{($SGJtKv-?xkwz; z_1@o%1Fg*6_X#E)DJKS}1%iqUF%iFe?>*Dh@G%op z+U#va`|ah*!-2!XdOPz18A6a#`K9HuWVp$yUCW!n4?&B1UUEl4;~tC1eRbulw_>CT zZc8|uL4O*)b!O8Y^4bkJukIb6%^!5!uT$sTQ@pqpqq^`C+~)W$m{d4wCzAb-SX`Ml z<07909o8MbzL60#-VNnPU_*iapjG?u>HcOnLhWal`ArVm0WRUo zTgWEOi?%bPcQ?4ZE_BbDRt*GyL~da6U7j&e04vZH+_A?h!N^Rw_)Glvs zAd$wSIm^(toE{nBI`qX64eNa#iq=CP_Wf)XO-O~k?hrb)~WkP2m;w?`YI&o zq%nV#@(%H%G&2C$eeFGpSN-v=v|DL({NJ}U`?uty0S&)FHcD^_p<*Mx52fkDi5$1u z5p*1PY{txZS2U0QLTm#~f_BDs~<wp*`bpe*ckZAF%)ZIivgYv3OzT#5&HWKsveQ2bGn;udeD6 zrVY9SZCp{MLjqxhUaX{W@io_fjTJ~|WFMfZduRrN(&vd`^EytMtXdLK*&tb{Lf zGBQ>?Z4*TpN3JcRi;00VG2_2im3JIWt9|A>d|P%D+`g+Z67OUk)64dn%^N)S(e(oq z9nt!8|3AbNO<{t$BzCXuW)NOz(OGSne~1O{p5k76o6r?fK0`6#6Yeft?I%~(p3%My zsst((*vUZTIgKd?%taVoE13Iyy3hys-8qlpVxk4Il(!10o6^w*#2lGnwK=`!XD6P( zr$Z?HskxrL{-cahMQAd73XUAIng-Nby^?nE$=KLeJkMBjl_<~_fex%QkaPQxOi*3-02b|ygYB_W&<;A;0_dXAI4 zn;c=U$EyE0zS&woIjGg(VIAPUlJ$rK38|r>SE-KXj{nU9%o8wACH0uB5B^5Aai35~ zu#ekt^ftLX1eP=$?;BV&U~;3_*m>6|PUk0Lzqj;Imv}WDIj~DL*2$jna2nJ8cRHi_ zUawFzu1>^Y@z8P^uj_o)s2%tz`zb3w)nf|+L-VDxJ8%06D}5%v5()d>ygogy$_dpF zlr#FUy}R3b)G%k7@ymhFsROX}3NN*$$fB#|{3e0z`+(fLlI>EwULBE{b6O(x+N_ajooQ zA!xiI`2-O!md-slFm#i`T$KfG8Zm7 z{KBfTt<~U6urEz%IO9%=jg0%3a#^ff(H={+r%D>{#Ec}nzph3Nb!jiJ_ z{Z^2npw?gB3a^S8hL@`4qSQtJlT-1IW%kkM`<9}fm>pk@V~69(8!|}k$8E4@3am;8 z_L3K5K{?K@6vWx>G-Ufmv%F|HioL-9OL+y^m2!ZXhn5@Em}15cvh*CP=b!`}t2FI8 zQDe=o3tbE=VT$)~>Tem=HZ2Kr+Ym;Ka@QC|WiF^M>tQ$EbqE(vilt&KOE|PLY>K({ z%p}%CG)CP2RIM3lHa}RT7^$Afr66pt^jtw#Ek(bzvCR&wx{aa!OPKg*d#D&BBmA+q z#g*k)i1DkrmYr7wX-T4Oq93gtaP-tlTH_Te9PdQ<_C*d;6`lhPK^ETh{-&nqJxKB1 z4uSuj0pB+~>;nI{#w~j0pE!mMbkmoft1Rmft;ns4o6`~cD7xrGku>o4Qpzw5Mt(LF z=wDYuqM?DZm1Wj25l_$|>qYaF7i-TJzY}9t(PkosE3Mf=rX5#Df8Ct*&gHq<*kY%9 z#ZG-6#PCobB}qKT39m>q-oh5jG~u{tf}DN~iB@ z)Tovy#%_^FH@t3{Ir2py71+!6%c8ER)En7U2jvSbu1g_&%yT5n8zC{Iv2z1ABCYRa zD8ZlQ^a%B*W@-^k>>zdFdDdJeh@5U#&l1d-h6Ytd{L z?{eM8y~9f7hKie0!+J2zuc0*FwSs{<@$Z7~RMJBk`ryq;cxIa5aY|>oYkH{Sx~3m< z(IP(^za*rMjI{~DL#`#i7*u&C#+;}=liSvZElg8Hor=AWDE=JA?$#2t!#M~`OS@Ao zKG&WoWMK%@GZ#EAgf?hlx4g;%%i8=Yi+%T*y+noW_eYRqGK6;KZeF+eO(tQ|Tf(4) zm@tOW<&Hl83u_0NN4Re&srybi4k#5$5`tGU=1#9;pWX#T?)zZ=T+3?CVlww8h*Fv{`m<^e(XLCinQ*nKX`)z>=D?}*I zcw0Cycn3#u$nk|~(eM!p^A`4i0iVFFw&3pH-D*N%^@y`~O7P3zfuudsZl5(b#6ur_L#TxCzZ4u5i zHjyf!qPd;Q%>!IEXu1?LM`i8}-6`+hyPJtN1x<)9b4d34M>d_c3Xj};vx*<5e1(}3 z5Zd+0Rad3V@mQ?bSZ5}e$nts^1%_&aP}v=hRn8bMreJi`3IY{-mB;SB<_gqG!pGNI zCyj8ZU<#w)JlfQ)?#Swq-*df|EBBPvlbA9tlFil6lO^Pjqs0)GB7@nG81|Lhc$gRt z#I6rMN>7O>msnndyjn$DNOh~$yruA5Pag9t8jCCrkcu}4OJV?Ln&2C-#y3qkS|rKh zVhd*$OZc)51tS-Gcz0X(J;r%h$4AcV3eO^rWJmRdLNm=g+AD8i)~-{A50Fw?0=>Tx z)m-A?euBRl&iq0)<~S;LTwBK3Ur%w@8{+-bZGcoqqDquEq!Wxj9e=UA1X2ZV%&>f8 z!;KUHc-1AM7vY-ZyU`@u`_IExwaWRTeHy0P`o>gAMZp7!&W{EWa+Hj*i?>D<_o4uy zjKYBLCntg`x{NpZ=`ZjMlToZc#ph93g8DHZU9$TV>HbG22H8A8o&)$1vUGQouVGg|97t&JVdm zY-XTNiVW^|S1ich6|NwFOHS%c*nOycYydvTT7;PI%|HfYm*wSs=VFz{>*pnz;hKj* z#ZIWYc>T1{;ldJTU->e zs@E-grf}5h2#Hq2$B#qo_xsfGtp00iA*85{dvO|l!ERNnKh>BxX4ioA5{+4tC-Z%R zx@-t{bqg~qSqc3U&IropmC{B|BJ?tKQ%fHG2zd2o^ny!Tjc{Fu?C^V0r{E8n7TsrF z8sWk1xuFWi@U*hXVZhrN$Sc*&okk#w3a^D8`3{eA8I}aVy);;$Zdhb3l^L)-M7#}}+lSl{BtYn`aRoo@}^ z2KPJ1@|I~6On9IiI=isAlx|U)O8ybjDJ^{gUeqLcDnzOe5VS1vv8|?V4OaL%-*wh1 zFJSfbA+C#)bmCB>wO2rcAWOBJtns%rW)MHRI6Nf36KPdL36sVf8m%Vv#J?=iIgLq(M4D@As_W(2_b`&v4q;OAYyV>3LlI}`J=?}j1r9LDUS=O{c`x9_@e#_HI1R3aZ6xZQ)j2AJwh7-8?0f2) zHLzDb^sxdB)-qncZux$c+ImoW6MDU3GOVkyYl-M=Bq3w^N37F|qiRZOLikWlI9Yfg z%64!lcwjm)T5sWy6?nT)tE>9TshD7*DYoujr=MSanY*%*Rp zc!2>RdiD)^^D6x@8)YRM->$te7jmg-ngITN*y;FtLN`E^YQJutJn;p4x@Q=MP(*m` zt-2ZDa%x5tK#Sa^+28WF3?$eyLE#L71`{Pccv@OkUZ`t(Kw=xPYZsG#ZE4$ z&Hx)Iux4&lm#rduE}O|cJ)CqNJTR4VDoSId-HQx-vpG4-oquEdfe%QeY;JY`;(&9s z?|EcdZLYz9FimDG4>~+BOwo5RkeagMrYfWWFm?`VOI2f9j4PpUbEUwG%LrZd8JH~$ z#1julTy`$D={l@81^;1poD=aX;77Rvq@*0KA<@h-S-&5eO$HI-G?KYwS0eDqRf<~W{XcDe zby!s0`Zgi0Al;(m&?Sg;cQZqWfPhGMmw+@#cS{U0bV`W`GIWc=(1IY{CEp(3bKdVg z=ltdmuDPzcX0zAcdp-Aa$6B+Ibg8x2DcOdR!44-CuyO^S`8Z6-gLb2i;3+M5NL$aN z9^#@ZqV(_Sqe^a!0Q%db z_UOn!>18Dkp=QswqFEIes*ZIp4U>$CX4Yt|O0e(7DctxR%FQ*9Rl5^~zawU;A*2p% zgsW=H*&vfMK!B~tkQshUe^Xlu4&3t+4P7zek+`=&jSpu6YCSs}wMUSLJ`N42*9Qb>wsYd!@Hs$n}UBi>?m%s>#Or{IyxW8-$hC?fIOpuBl z?G!9!?&sH{!yMFMg-pCw+@0Vnu9ZC1&g+a3C8)hBnsvj!q27=90TSr#!T$%)@6x}1 zDeuQuT^7wOM!E6v>VaG4BV*`@t}F+w0(_SX+Nl>FdfD$<_3_d6(assBvCim|SjmME&V#2t{r0q6 znQEVO8Vsz!fC6u7t`;#AKCkVO$tqoWih`EI#ACGbl(5}+!%H$i5K?CyYOGx9as1ZU z7&V9BMkgiP(()o-H7joZzKNA=jc#jW?K^a*9IpKf+61M}XaQkLF9nHaA_dmjK1S?o zpBVRdTSK$J)2BxB%>twGD+e%+!t&UyrV1KrKo!Hf&O)|4HjkVl4^p$V+t^bNGZ!od z8%aPwG1MZ|L)Sy=#!h#IG(WIxdzHHfdALdA(T2SuOXNlU7rIZ>0P9s4?yO%}6vV8h z4<|mmjbxy#H(w32hb&h4WQ$y|B9@j@PW_kmq6ySL3+FQP{wPTC3%WK6fq)+5;>Tqg zR%h+H@@CGCsC?r><3g7W-%!uFtIA}pxuDIa%)%IHwEnGFv^9$4ftMi(9p>wyR<3@=?dbg3@$ zH$Wo}4~3}ZF09m`fK4OHd<}kPhbR@&iSkLN1AR6%Yc39Y~ zzQ@rVtxX5Suj?!OrM0Rhp{Rh;U?s;lx7!j!b+U$mA-c*orpo!UnThu;P}mH5c6+9h z2HNKHTGgBX7tu>Tz^DCFn5M1@*a`)P$u@RyZLmf6dTUC_Tt5V;TjxcW|5i+K`i%E{ z{0foz(&+ET%nK-nrB7&NSA9!~FQ}6gYgrqGrDLWB8w881c#9RvmFP%TxCNvxXA9Ca zVo5%TKYU@vZpbreJ=pjZNAAS3XR)Uan>@Bu$Vdmd~6uD{kUhD$A8Yz-AC*VCZ~T?q@*`UUR92cpP`v z()M9_A(a+#5$Xv%_BxdUl z0#@2$85`^j?YibhLZHo3p{L2AK*T^EctSM6eIq^o%UH#A&-dfE$^V1H%ZRx^qqhlN zHZ-tzdigV+WwG0^(fh_r=7N?gSd({vkx>sPZ0}*fIeUz?V6{Qd%3qH!u43fGYvT`N zoT21Bv`TGV=yFf%SaypnB>)DO6YU`!C$#jigveVjg*unwE_)<-A{H}M>o$ZboawcwEvg#XR6%T?5%-PX9C*D6*Z2473^zqOUk9vT{5^qLb#miUw+}fsPmNETqm^^e= zT+3`#=-VH{{CtCYIA6{3s$+E%XXJ3xq^p!%6qX~xTnl>#o1}c;``&z7uj2B;hQxZ7 zI-@WJFKBhzAp%={`r`Z{t|64c><0zCY=dj+JCx}r0Gk#?c0eW(K4=ms_*$>rjbX4% z)}7mUPCY>JHd!`9H=%h+`i421^B>YPE>lv5%ZX$U>R&w=(5mcA3R~aTKnR&24xjs5 z%6D#Ck9=Q{Dr4K6P8;m}U?@&9Apz?ivCMgW21(p z3Lh7@`*ltJkW^FC3|t28-}~NGdCr@jm4|cLCeu4Zf^mK06TAouqrRO1=A?4#q0lrY zsrgmQt^QaxM0v?GIiUbO2JH?)4sM1VVy@KGpV1TRWGbbX!|VcPtj@Kd&FPdubU-6g zM*UK?}@zQ2>wmdc82LQG?JOBgtKlkA5D7 zEY-yc7MB0UQ*PRE9k0(kBIsV@WzO|Ix6)BleG}|_pJ&wQmqS5ZU!O7OV!(W<_?LcT zp$J~)%ns9UWBqG14gP629tBo1YF9PbOA8|#Ysegk`{!4#F-%i@!Oz~;=`PcRRX9Tz zR=rdM%aIt*B_Y*DAsMD;(u$RS_3bgihM|X)6_`MKgK&9lcXxPXL!9<+KzGB%d;JH{ zOD20G)5^7B($Ayb4mzQ!VV~}PkNjp|Qk=jvmE;7#<2RR!ENpVr@3L*I5~DR$Qh}}< zz+)eRZ;BR3j1Tt$s%M63{oktZ2hCOQLBTLv1br^!Ree)IBN7*enjIQv^I7(s?rijs^mn`_3&_IY8{VQO+YmUFELmpSJZU*=9;Z*cfgU!|9;Ti_;O8y0FDM zB#oBSXX*7g6dFSB^8l_=uxO7{prSAn1FYC4W*46);q_gzSBO??` zyi7(OO~N%fJ!Q_B#l09kg+0uqx9HglF$BI4eplAZ z7jDMI4*ZUxyqgj)(%E=6 z+Km0h2|LmfakAy+4gPgGx=-pc@bXce4gBySpaV-@I()D5FWLS$+)aK8!^kHWvp;U_ z9t~XXIeA9xWGQ~7YZDcJx&a^ODcjzZi?$+$Ge#|UuQF+%)}KU3vwZ_nG9WleV)L3e z39^)jb*ST=aja_Ub>1^7qBG)kW~|L_`TG48@ZQTz5b4C^KJe^%;VLC3%T3%WOq0@y zX~;z~Lkfy`8|v!c4)F8ABwNZ?=3tFj_H$f&m+Y zMsEjcD}+{edi34gB$YQ6aJg8}mWa&(b+hVJBrioJ#l{ThMm05S_q%~8)muR>Y*IaAtOj;0g}=_3@I1_3%7`2>L65 zWr>-U<%yd`yV#|QYyl^o9B3cW?N>0XXP7M)&04OEWKsII3bw;4bCUgEEtzYZTqI=x z8^e`MINm3z=V(O9_t!DDe)%+XzOIf>81PXGbDBwk6WtXFwDkaEhT91vP<}!2-5PF3 zeITKGvwEqE&Ni?Gtr_%VxeTmW86S#5akEy-rw|_0sP#!MYoXo!C86*CfOkML1`ywt zv4YCI#T&J(I0fA;L@by^)_{qt<-AK#px6v~dr7rczNjyKOom)0VoP9pGO`%UwY2Ei zk;_6SEbHIQ_ax)asdKJ-QtRdd3e_Gp_5rSPXXVXxedeU0X&Hu`Tn9?keXNb_z=2n) zuOF(1+&KeEbotSsaKP;e=|2X^Q&0Os9Mh_>l~iBHx_iDl7}Od$O0Dy$ztHpWCa; zMw?$Mfr}M8Z!lv>yWdVz^vBy-sN|;ZAqz>P4VX_6WJ&0r&3O`Z&g*XJxs}&OtXY8P z9Na;RhrM6WL7)nDW^%EY0M*uj2)H?uWBhRz)=5-Kt&jxkKTLsrDY3AOE-@`6 z?~=>^DeIP1dfp;6F;i*7iRXazSK8~ObtZXf-l`h7?Ui#2joq5DGzpxXBbg}_@Fn6p zM+qWdsmjuxUzUmdr2Dthpd8ZrFH2$f-pmO}^wzU`flx7x`x0z|R2BRUN&ud?u4EU5 z1-If35dsYFo;Q$?B5qA47$di2jGtGFcio%hyNn5%ptO8j^mkI=W3~yn;NA)`W5o|t z1m-uzMlIWarvxlvYO&V-X|FEpNkLS-m8+7H%MZfuxFYNNtPcdCF9#brv?yoTAdZ^) zb)C6G?biwrv5L#OX9g_J(Y-~g_L^ptGiK#SYLD~#A{JgRa{-&!FDcK2TX=aqj9Qm} z=uO^AS14Xfo)}^sGWZgan1+ouw}s>9 z`xjmR7A@2$46CsoE^~y;@i)Vbk^y z4QvFZ52vJS)4&F$fCwTzUUuU&>7KMtKV;MtFp>!YDfI>FyNF3d>R6-E*t?)Bnr-}< zk*t=sP|lvdy@7icxcKmB=S&Vo1)Be8k5)&&zYe=Pb9icPA-5z+CVM&@ta9&iE4;Or z{B`K$F9qY|R;ahcN7PcoX9AP=|=Tsym}TZ{Nm(zLupXe}yK+bzlD*Zk4p{ zmiw#Wvu%ZB@xn+!^!&|F=Fh}Fhe*5)JqkaOxAHYyC=cHk9!7@|38@xp(Ew)t6M_dn zPJy=Y!#!Y|)}K*8r2dSVX^-6t*Vz}ejNsvdA)&m*f9L{xzAa3fo{`8N;MwR( z3-`Z4xwEkyU@Gjnq7V_i=4+a+LDxd&TfK0)GZ&dn8Tbo6s_yzn`OKt1^JWDY(YPh3 zkugU`b1P=Dowp!&C=u)doIa@dMiW$Fv*PNs&!F~XuSa4{vl(y-%J@qwnuG-&ZQ65F zx+Y=Qv^x`Uoi<55q8j}y35ebA?V6Qpr0#YZsjSZd<0{J4OD)s*UA#VKWsy=1u{j|f zzO9>FYmWz%Xyso`SUxZQOLJKjFsoi+P9OLbXu?eS1cj-rsRVwKN595^6J05l;&4;} zOvQb`O1uIYi)P_bN!`cE!4@rbUOe-3q~5YtwMq`8jbKB|$%~WeWH0`0OX?CI>0gtfYEB$yfF5m4vVr88aR11H1kXtrLInRr=q) zQC_?0)v%yIdp!W1ua7~f?Ne;O95Xgmh|8n_G*j$pX1!YdbH zA5S35GPZdTr@>ZqRRvP`b@HOn~LVLjJ!qW2RULk)>!W#j@C)2ZzNjI&1t zd`gfEGb6T^5`k7z;G|QrC1$%SxY}`ejhpHHMU3H2d`}FtOsYpq*MufiDux*n8SVa< zM4j0odh#d7xIy!At~CX~R9{ z6(+4U|&cf_~4sXh?OS(?_SWIsi=hNnaT6B1kZ!#O{X?Z1u>ve2 zoJ-3zlGL>xa-Iza+BPzvIMl60duxUjPy8kZn>Nj5fBX2cOW+Qisu}hG8|&n~>j z82_1j-=%r!sBderA z{*Ta#iiPmSUrjN0E)#d`Q+!KIyFY5*0kc>|5ZF8DTJUUJ%zpf3GcuwSTS&B#4Wipm zl>Pp(a_cp@m2at@JEwlN0v6gY8p~Bo{SOQ|Ne^(OELG1c{&q(+qYtm@Q56nWysQC> z%K^KZs-Wb|UGQb^17CjE!gAAC6$dZE5Xt*1PX^2#Mb-CT8j!;)lg19`zm`qEqywsA zqNeO79>*!)f%M&sI0`QztQv@!O_3nfft;8QZ3NbpH=K#ktKr_o>ygYOdtV0XF67g) zk8WM@=@P90f`ej5s-BGa^rEB236ka*6j8(UK`Ou}H=dJibq9AQNwIv_zXh}Xo+BXk zy70A#kQ6eTaN(10p+uQ!WHHE^gm>@&dLXI zN@ehJ*tjgIy|{FG@j}~E5cwr-I%Qskf`G(tW{q;!u#-g1Pdft4&hkQ_Aa%ds&_f-1O)Nrgzt-C2Yu6yT>}JuGry? zSHpIG-*Z^a1gQT#5TLIg26!TP%Q>wWT<(k;#a1q!OiJHpoL>BTX#KJ)PopH43txf+ z-4wNp3?IJjK9Hii;USF7(G>V&UEH9=^oJ;*JD(*L*eiL`q{g*N^o~JV-w`BhqhNP5 zROc!Mf?L2(e-6^$BnFCG%5G_=`-gc#_U`EddRXYE`B~)u262#^bD=Y4U_wdp0*N|%|4oRy*k_bY{j4pA%MgZPeM7b&WlQf+zyz$RaOTWX zJVJB&96m-cEi(-)4{1cIA#j_l$`ou8_7p{n{t0xY90t!qd)-1v$7{j45|3euybhQ4 zjy1Q7Qtk>O!%yEqYg((g34kWLDNT4wa}e1Aruq8lp}M{{+t?*V^`E6B77#5ldKibK zK{-BgACr0l^DG)K`R^J*keQ;Lv7Lv%=;%_2^Z^lzvT=%CKii$lt?Exj8&PCD!btYw zNb-|ohJ$isX5f8R+kU;i@m*{y!E48Kp_uKdH zwS(+JHbOcL+SVH;1r{7kh$b{dYPG`xytGisv0#8ZqxWesjTfr@#|*o~g6H+jvWEY1 z;McIK(Uf&Uhf|iDy^_x93t#-@oO#1_n)pBsR5VxMPmQudhnhZSGqsKbWZ4~Dipc_( zog;TfxVBHNvgIwdwkVwHI9E?CiIu<&8&WE4j&HLIapW3tKp3)NlmaF7f+Q1<$7L<1 zr>?nj{)9KE$_JkVQaHw+n3@ELI6~Rjn!eSY00Z(6AUOpK=`e3VWY6rW(OTVJ#$KRG zIPBbLSU+|D{0=|hRG3QAi~c7T5K~Kz_WmOju*7J>$UxvPUSSfmDR5ipSJNPAty^+q z*iT+5Y1Q!H)*CsR-u;0#eoC<;wqnDQgYKd)D9J92j6^X6fYkVtVG+g)eHgv{0F=(Y z0HphBE@=}e^N>*`m-%tM?#3?cR$P;KJ}=u$SsmIXO|a|V9>`0CSutOO9Lw)ALf?ZU{HVJp5uhXk_0*MOyxl)-T3+h|<&VD&kx zen4i#%K!BA`IjWyV$}`d#Rv*BtrFZ7p8b`PLuq`Kx#=FjyFm5VP8opcrwodj%NNxv zb*~FAa0*{^GmuULsle}^WTme!tRSK4u^TQ;*r~Xy*jRHZ@V8+5$`-i%;u5LpL-VTh z@g>dICJ{>RsM5;@F?qh`PAdLCpe{jgv|2?>d8?Zg%fvW@XZL3_4$h$z9KWo z1z|0@2!V)~R(s`xW8abfDr{bl=Pk{udm2WyA09?;G4urXU3Q%2^Y*X*acvcXi3SS4 zh7%2_G(S;2Ci}@akzS2aqE^Qq%k`HuJs8e$o;g`Pi5=?_+iGA$q3~ zsKTSCtw-~%Pn-O-A;Q)9K-MC&{oO4_tz2%#9`OrrbPf!cJ--(pI%FQb1hP z=bPK_Ec0D{sFdR2^`u}sAj5~ee4A*?qb}<)2f&Fq2V(~_-YcpW9ZI&QOvxW_TEohb zoon*E$n3}W{t<&P9vpKzW9GHmmL3wd;fv=J)CjzBrrsOCs~(zL7AuVW%?dNF?NAlG zLM|wI8I1^-e^^=w*i*?{CNwhhjMCZcjl$!r?Twxw4HnCn@z{w^=k-atCFIYL&L(aLVh;sb`6tI{j{l9W~@6=l-}9lW>~M!20%ncKp1 zq`y3&@Qu{c1YKBT`EGqA3O~`tMNPN1%z6K~vh=698i6ULxm==W9*w7hL5+>Iji*3+us_)yNvr_W-5t@Y&cUeEgt`N%mjn6}8uNFMbo z_{q|G^%OrQc@EUmDfxnThqnzXXC}Swf=*qFCt7m`f&D4s*F;60J@fJp3>4q5V&uuQ z6mSp`5o!0@N2D5q(hGA`1p7}1)vZ_?i~7t&${HyS^;=}K`gen#ti z>*RUWO&g$swYXVl@Uzj$j7F*w&Lp^c_(o0AYZ3V#J1Y`V&MFpv7nvDf~OPtZAom`uClec)HS=_ z?&j*bY0t{Rijr63LY|W`-^MZM2326Zv^t75_z1{_1o(C9tX9k=uV|JB}lN5fhA)Yl}Q6ifZr-UABV~ z-C3zjoZZpsqJ`cKWX{yskt$$V}4HCZ;IS>*^^GXv%A@DFs_?J+fSWm zl4$OwsK{gReAK1mzrMOko9OmFrrtS=p#2$YzGGx-2z#A`Xx-du0fx_RXLH(x2zd5E z6`kqFdhVa^p*+mDbJw2yIF3=x$Uw=UR57%5q(XgFD|Y?mS;NQ^P4!q+bmZ|1B8_vC z5_ht#8@Vf4J+LO+86Dat1sDXF1PIPNI-9S%@eDyfzW0TQPW*MHBvISsm!3^(c_@^r zsU)R-i`SZJYPXJsRTd}g?``#`y8RgXcp6mOF1*KqULt8@h%>!&iuGf$-NWwJWn{5w zjfVdt7CD2i%K96+;C#O6eZCul$Wiuvt)bj2G?e6z`n&M0q^9;gp{uQB$+^3eSlc+e zJA)PmgT`l#=8EXKwix6j*jJmx9MPPw=O3i;Z{VX)y!AvwiFVj!`H|UimU|MB33^q= z1NBA)E(6ZEOI%UmC>jb1ql}HA(rJS7&KgY<>bZ8O0D;1y12dHr^(**XAQbf%ehg4-}jE1y-7R0&Y2ZZ z(R^h4iHFVcm_x`(-{H=t`{d*0?J?$5ap@)J_k67GTlo?6Hw^MRO_o7&Mjq2g(wyoY*Z9%LxNJmwCA%O>oSnY?_} z%Wu$TUj)YxpJ3)Utd=n0#OL%RC@f$(ol$exbzizng4{@?40%VL{1BTU+dv;mD>@hF zSTdb&9)hpFBWwsxF;L#g>Sw2(KBsV?s7F3z_wnurlH0p9^Lq1Aczh`4in*4%eKd8U z{z=$483x=@?Gn-tku-6AmLFw)mEs=od35M^(Z6O|aOBosa|s27zKH+9 zpKqf?MvgxH>)m5|Q%RnXtdY{J5o^SJhIfBPM*~lNTwGj714>GKQ*%RG8+2r3q@zJw zsXs#<;RC9uXug(n96&8lHLOlEtky-$qu_>*HsV;uUdjO<4y?W literal 0 HcmV?d00001 diff --git a/doc/html/_me_encoder_new_8h_source.html b/doc/html/_me_encoder_new_8h_source.html new file mode 100644 index 00000000..8ba4241a --- /dev/null +++ b/doc/html/_me_encoder_new_8h_source.html @@ -0,0 +1,250 @@ + + + + + + + +MakeBlock Drive Updated: src/MeEncoderNew.h Source File + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeEncoderNew.h
+
+
+Go to the documentation of this file.
1
+
63#ifndef ME_LEGOENCODER_H
+
64#define ME_LEGOENCODER_H
+
65#include <Arduino.h>
+
66#include <stdbool.h>
+
67#include "MeConfig.h"
+
68#include "MePort.h"
+
69
+
70#define LEONARDO_PORT1
+
71
+
72#if defined(UNO_PORT1) //10:PB3 11:PB2
+
73#define SDA_PORT PORTB
+
74#define SDA_PIN 3
+
75#define SCL_PORT PORTB
+
76#define SCL_PIN 2
+
77#define I2C_SLOWMODE 1
+
78#elif defined(UNO_PORT2) //3:PD3 9:PB1
+
79#define SDA_PORT PORTD
+
80#define SDA_PIN 3
+
81#define SCL_PORT PORTB
+
82#define SCL_PIN 1
+
83#define I2C_SLOWMODE 1
+
84#elif defined(LEONARDO_PORT1) //11:PB7 8:PB4
+
85#define SDA_PORT PORTB
+
86#define SDA_PIN 7
+
87#define SCL_PORT PORTB
+
88#define SCL_PIN 4
+
89#define I2C_SLOWMODE 1
+
90#elif defined(LEONARDO_PORT2) //13:PC7 12:PD6
+
91#define SDA_PORT PORTC
+
92#define SDA_PIN 7
+
93#define SCL_PORT PORTD
+
94#define SCL_PIN 6
+
95#define I2C_SLOWMODE 1
+
96#else
+
97// change sda scl if you use a different pin mapping
+
98#endif
+
99
+
100#define PULSE_PER_C 8
+
101
+
+ +
108public:
+
117 MeEncoderNew(uint8_t addr,uint8_t slot);
+
118
+
125 MeEncoderNew(uint8_t slot);
+
126
+
133 MeEncoderNew(void);
+
134
+
149 void begin(void);
+
150
+
167 void setAddr(uint8_t i2cAddr,uint8_t slot);
+
168
+
181 void reset(void);
+
182
+
201 void move(long angle, float speed = 220, float lock_state = 1);
+
202
+
221 void moveTo(long angle, float speed = 220, float lock_state = 1);
+
222
+
241 void runTurns(long turns, float speed = 220,float lock_state = 1);
+
242
+
257 void runSpeed(float speed,float lock_state = 1);
+
258
+
273 float getCurrentSpeed(void);
+
274
+
289 void setCurrentPosition(long pulse_counter);
+
290
+
305 long getCurrentPosition(void);
+
306
+
325 void setSpeedPID(float p,float i,float d);
+
326
+
345 void setPosPID(float p,float i,float d);
+
346
+
365 void getSpeedPID(float * p,float * i,float * d);
+
366
+
385 void getPosPID(float * p,float * i,float * d);
+
386
+
401 float getRatio(void);
+
402
+
417 void setRatio(float r);
+
418
+
433 int getPulse(void);
+
434
+
449 void setPulse(int p);
+
450
+
465 void setDevid(uint8_t devid);
+
466
+
481 void setMode(uint8_t mode);
+
482
+
497 void setPWM(int pwm);
+
498
+
517 void runSpeedAndTime(float speed, float time, float lock_state = 1);
+
518
+
534 boolean isTarPosReached(void);
+
535
+
549void getFirmwareVersion(char *buffer);
+
550
+
551private:
+
566 void sendCmd(void);
+
567
+
568 uint8_t _slot;
+
569 uint8_t address;
+
570 unsigned long _lastTime;
+
571 char cmdBuf[18];
+
572};
+
+
573
+
574#endif
+
575
+
576
+
577
+
Configuration file of library.
+
Header for MePort.cpp module.
+
Driver for Me Encoder New module.
Definition MeEncoderNew.h:107
+
void getFirmwareVersion(char *buffer)
Definition MeEncoderNew.cpp:812
+
void setRatio(float r)
Definition MeEncoderNew.cpp:651
+
boolean isTarPosReached(void)
Definition MeEncoderNew.cpp:782
+
float getCurrentSpeed(void)
Definition MeEncoderNew.cpp:567
+
void reset(void)
Definition MeEncoderNew.cpp:295
+
void moveTo(long angle, float speed=220, float lock_state=1)
Definition MeEncoderNew.cpp:223
+
void setCurrentPosition(long pulse_counter)
Definition MeEncoderNew.cpp:419
+
void runSpeed(float speed, float lock_state=1)
Definition MeEncoderNew.cpp:250
+
float getRatio(void)
Definition MeEncoderNew.cpp:620
+
int getPulse(void)
Definition MeEncoderNew.cpp:673
+
void setPulse(int p)
Definition MeEncoderNew.cpp:704
+
void setAddr(uint8_t i2cAddr, uint8_t slot)
Definition MeEncoderNew.cpp:170
+
void setPosPID(float p, float i, float d)
Definition MeEncoderNew.cpp:349
+
void begin(void)
Definition MeEncoderNew.cpp:149
+
void setDevid(uint8_t devid)
Definition MeEncoderNew.cpp:726
+
MeEncoderNew(void)
Definition MeEncoderNew.cpp:130
+
void getPosPID(float *p, float *i, float *d)
Definition MeEncoderNew.cpp:524
+
void setMode(uint8_t mode)
Definition MeEncoderNew.cpp:373
+
void runSpeedAndTime(float speed, float time, float lock_state=1)
Definition MeEncoderNew.cpp:752
+
long getCurrentPosition(void)
Definition MeEncoderNew.cpp:442
+
void setSpeedPID(float p, float i, float d)
Definition MeEncoderNew.cpp:321
+
void runTurns(long turns, float speed=220, float lock_state=1)
Definition MeEncoderNew.cpp:278
+
void move(long angle, float speed=220, float lock_state=1)
Definition MeEncoderNew.cpp:194
+
void setPWM(int pwm)
Definition MeEncoderNew.cpp:396
+
void getSpeedPID(float *p, float *i, float *d)
Definition MeEncoderNew.cpp:477
+
+
+ + + + diff --git a/doc/html/_me_encoder_on_board_8cpp.html b/doc/html/_me_encoder_on_board_8cpp.html new file mode 100644 index 00000000..154aa4b5 --- /dev/null +++ b/doc/html/_me_encoder_on_board_8cpp.html @@ -0,0 +1,186 @@ + + + + + + + +MakeBlock Drive Updated: src/MeEncoderOnBoard.cpp File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeEncoderOnBoard.cpp File Reference
+
+
+ +

Driver for Encoder module on MeAuriga and MeMegaPi. +More...

+
#include "MeEncoderOnBoard.h"
+
+Include dependency graph for MeEncoderOnBoard.cpp:
+
+
+ + + + + + + + + + + +
+

Detailed Description

+

Driver for Encoder module on MeAuriga and MeMegaPi.

+
Author
MakeBlock
+
Version
V1.0.5
+
Date
2018/01/03
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for Encoder On MeAuriga and MeMegaPi.
+
Method List:
+
    +
  1. void MeEncoderOnBoard::reset(uint8_t slot);
  2. +
  3. uint8_t MeEncoderOnBoard::getSlotNum(void);
  4. +
  5. uint8_t MeEncoderOnBoard::getIntNum(void);
  6. +
  7. uint8_t MeEncoderOnBoard::getPortA(void);
  8. +
  9. uint8_t MeEncoderOnBoard::getPortB(void);
  10. +
  11. long MeEncoderOnBoard::getPulsePos(void);
  12. +
  13. void MeEncoderOnBoard::setPulsePos(long pulse_pos);
  14. +
  15. void MeEncoderOnBoard::pulsePosPlus(void);
  16. +
  17. void MeEncoderOnBoard::pulsePosMinus(void);
  18. +
  19. void MeEncoderOnBoard::setCurrentSpeed(float speed);
  20. +
  21. float MeEncoderOnBoard::getCurrentSpeed(void);
  22. +
  23. int16_t MeEncoderOnBoard::getCurPwm(void);
  24. +
  25. void MeEncoderOnBoard::setTarPWM(int16_t pwm_value);
  26. +
  27. void MeEncoderOnBoard::setMotorPwm(int16_t pwm);
  28. +
  29. void MeEncoderOnBoard::updateSpeed(void);
  30. +
  31. void MeEncoderOnBoard::updateCurPos(void);
  32. +
  33. long MeEncoderOnBoard::getCurPos(void)
  34. +
  35. void MeEncoderOnBoard::runSpeed(float speed);
  36. +
  37. void MeEncoderOnBoard::setSpeed(float speed);
  38. +
  39. void MeEncoderOnBoard::move(long position,float speed,int16_t extId,cb callback);
  40. +
  41. void MeEncoderOnBoard::moveTo(long position,float speed,int16_t extId,cb callback);
  42. +
  43. long MeEncoderOnBoard::distanceToGo(void);
  44. +
  45. void MeEncoderOnBoard::setSpeedPid(float p,float i,float d);
  46. +
  47. void MeEncoderOnBoard::setPosPid(float p,float i,float d);
  48. +
  49. void MeEncoderOnBoard::setPulse(int16_t pulseValue);
  50. +
  51. void MeEncoderOnBoard::setRatio(float RatioValue);
  52. +
  53. void MeEncoderOnBoard::setMotionMode(int16_t motionMode);
  54. +
  55. int16_t MeEncoderOnBoard::pidPositionToPwm(void);
  56. +
  57. int16_t MeEncoderOnBoard::speedWithoutPos(void);
  58. +
  59. void MeEncoderOnBoard::encoderMove(void);
  60. +
  61. void MeEncoderOnBoard::pwmMove(void);
  62. +
  63. boolean MeEncoderOnBoard::isTarPosReached(void);
  64. +
  65. void MeEncoderOnBoard::loop(void);
  66. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+forfish         2015/11/10     1.0.0            Add description
+Mark Yan        2016/04/07     1.0.1            fix motor reset issue.
+Mark Yan        2016/05/17     1.0.2            add some comments.
+Mark Yan        2016/06/25     1.0.3            add PID calibration for encoder driver.
+Zzipeng         2017/05/22     1.0.4            when motor turn its direction.
+Mark Yan        2018/01/03     1.0.4            add callback flag.
+
+
+
+ + + + diff --git a/doc/html/_me_encoder_on_board_8cpp__incl.map b/doc/html/_me_encoder_on_board_8cpp__incl.map new file mode 100644 index 00000000..68bce45d --- /dev/null +++ b/doc/html/_me_encoder_on_board_8cpp__incl.map @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/doc/html/_me_encoder_on_board_8cpp__incl.md5 b/doc/html/_me_encoder_on_board_8cpp__incl.md5 new file mode 100644 index 00000000..8aa6c5ee --- /dev/null +++ b/doc/html/_me_encoder_on_board_8cpp__incl.md5 @@ -0,0 +1 @@ +72a9a2ccbf1573eb96d78deff802e6f2 \ No newline at end of file diff --git a/doc/html/_me_encoder_on_board_8cpp__incl.png b/doc/html/_me_encoder_on_board_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..3b99cb09efdf43ecaf3e05569df0a448cef7efc7 GIT binary patch literal 5273 zcmc&&XH=70mku=;1VoxhQ4kR!1OaJ5P`XMFJxcFQx->z`<mPz=Kh%ZJLg^NE$8g>?6c2));{Zf;tlk)m_XM-004mL$zydG z06--}d2eQ*r`&13U%Ezl(A#NisRJ(lz6x8*(*Xc>y(j7_#zF5lr^4Rw9E8ztuQWH+ z4&>!TASLlOHlWM0r9@d-+CTZPkO%*oyIr&9FHBp~EFELu0!835?yl$oRi8X&V6*zE z7aJ@o;Y?5OG4te$(Ve@cE!m{(?NI|GIr_l&0NF8Ry$P?2ZNx1Hblu0SGjw=}vNZqi zx`~lmuc1v$iOeJQ|7t36YXI!`kr57{cf}g7dcdKpwYBvZ|2PqMNxni;yP7cshI}4R z897*#9}ETP-ACN&tGp`%sBtBf%~ceqNFkytAoVY%5$`zuZN<^r#)tYFQjZ*rgN z$o1SqC6_6mfx*|S3i_3*@~fo;z0#{x#yY1eRX)iB0fa;3NO}Qxt!QCiY^a+ zzFzD{2$CZSpJxYN2G7Woe>!^?6(gEwlh2ZqZQfOkDi;Nc1UM~LCMSkc{ zg%7!}>fP4~`huTWw3Fj1Kf`XJB*Qfa!2itKzf$>8`PJ{8?i=>MeomFyUm3yYD~0N4 zxiE}oX=eq1xiSz8$t~Q*7dG!pOJOk4ys19*h{7cnVG?z zn>vJn*&`%~SMH$N{S*>0u16FsBlrpQp9>KDSpEOgWd{Xl%*?AK^GR`E(rT+~ZTf&eHNpNQnMP2WF< ztBJ&*lP7H=)!(Un4eC^fL4_I-*CH}^x*fK*V|AQMm%qSnS^FwHD08gm;`nRw8b6B| zo1r9FX4erPv&$M`O}*V@n#qPA0&@14rp~ENBU(cqcNm zI|yu`Trm_@!9*>6Rht8gaFad_^=r`f0no4c{cf%su68``N(5^OfKm;YR}XUNh&) zfJ``pxtqq$68Er493{`x#OX|dFNC3 zPF@4?=r~HJ-<|sp$&1qE<_SmDIa}mN97)p}RgvJj&sRR?%K&Gv>aQ8jVv30_FEEz2 z!WW|=`wmVW${-+Afx(DW1=^ z7#y=et8f+R-wlzmk|7cMl)Bw<1;>?8m3&)>ky zf!x5WNN1(MrVyRxN$0f|$Yh>~CMVo)J`LUj3OuzdSlhi`mFo)R<`nX3T=_kaUp2`? z7rs(D8Sn|#b*%Yl!45g{Xzt66{T1I-lHJ6?HPf|M8GX+ac(cIL{s>u4bhXjo`oo=y8FP*d~z%WogQB&e(lawab6IJ#aLqeZ(a<)o7rpvr_z}Qw{`viKj4ZPjm^5A|d8(OqkH(`j^b^sQ_-12XX?51R!+L zg3!2rn* zpoy2*#A13Rv&Fgylvdv4xyL#s)V1gAOkgZM1z|}6uPNfI0IdDJ@ZBA1Gr69Q7u~Y4^hMv#L;>J-ERKc^Rj)&TTA3ii)DsE z!&%&O=Juy$2Tl3>OZ8JFxOtw(cIHE0m$pS|JyVM8Z$e0DxS)0RAO~HTPw*fjj-at) z4`}eriM1B~^FW9a`74T_Z?!7Vps`pj+6(5{gJI6E8{{`hYtId9i*yh710SbS`w3(( z$_L5hjBZKr6SLPm*!eTzf88dn*F4j#rUVb%4n)dB!e*(D5tLc7-yl``1#!nHb7q_4 z#onP1ht_K(k^+*;#H`iZ?%Bcz=)0m+dW^STY6Fs&6A{9u(-1 zSulLxfpL1IPM5FQ{(v^^-9l2GyZ3V_w z7`$_USNYKmfvPR|PA#mTgWJl3j!gY~mW`Xi5%Ut=Z8tA81<_pDgBn;oEHOfCbUiKp z@}E?b!U@k(!ufY7d>!$JJS&Adm_TAJ09LFvmQrXIAwo#@+H+$buuRum?pAruE@3Js zT*v7-^BQtl_Q&E-0^?G#aq}z2s6@bf78@fwa|uaABB~oET{33ry5*i_rnBNEi^Nst zzrlk|DmgpZdXt!~6iT!xt9WORIZW*+FmHqcm!FkY2ereXM{kkWkkH@N!PX(jB7`N?3lv#n6XFkVr zgqmD#Z8WGC8v^F7{KG~z!VxJS?nc(-O?M6B?I;y#9T1__FPYy(zp>NM41||AMin6E z?M(KQMb5*QRL5M3!Z{EL~Y( zmlYCxNr^94gge&Vf-i{2yH6HC0*$QePSUcFNyQ2 zBFoOtcANy!St}1$CIk?xqCbJ&*^Ar6c@?D&gXiRGBB-tjXUR?wh@*;A@iCg`Rti1E z)B%)TCYrxPgUlo53;JPopYdG+cM|H(nYk12-lDXrAa83y^hd?meHXyk=4=6g7YHbl z58idy=V5YZZ8LmR?ry$-vAG5sZ*X8&04R+A-eWrRnS8N_t%Zez5XYrhe%u_p@PE49 z%vWG1+D?E!cZLrc7T)MErV2+T@O%mPp#~TidJoHd6Sx~KiSB^$5L)5oi|`%Uh$@?l zTVwARCWbA#4ISt8YdOP)eB*${}A*+ z1zzwV58-nWuYuOR}T$^{)aFLa%m(z=C><%3ptYz=8)Jr{1kzYNHDp zHZIc~#+vH?VWaTiP>~J};2nO8k2WZ{QTXBPei$-)In4Uos)+xRg5wM@wT_Cw<=yn6$cR=@-?d+l`*FH(-yhHmP@=0=cUrcD=}#U zvbte$dAy@MRN&Z+*PWb?#Ml)D%v(qwk$aw%gs%=x0rJf|>&N^ng z5V*zN`AW;D9_qq|w*b{K+$)N@^ermP@J)0gU$MpelMcaS^oKDfq^q`gjo!**<{`B! zMvok~(#$V+gaYyn@VN-Zor2RiRUZVmWm&>A09YH_kEZ<7<$jb~?JN%6HZk*Nj@YBk z{`iQI-TKkDgx23>jQB5Otn$r)DM^_*LdmXuFtQaIxD4MBjbNinQmvutFjBB_(TMes z&BI6vQBJ(Lxv)j=SL>?Bg{Rky`zXAgebbx0B{CQ@`+#oQcEi$%D*XElLEwE3@Ayw;~r&EXq(XPzU}<(f%xm*sh#=V;o%Q2XDv<5!_diEV##uLq3ZO`^~TguMgUuPYU{cla=pE3zD7&(wF zS&UgQfu2>DkN50mX^r*gk&AFUOLl}^B&mg1M|Ap{9XXIEM+)flnr>-)L3qI_yLoNk z%hutIm;et^8vTdyf-g>OB2O=&i3xnlLliidJTB$s0BFWT-Kw=9roFyvF*Dv+n8$gm zo_*gy=!>yZ%{-Og0I%pDhg;WyNci|}&4uT*3 zxP4Lc`88=ipp_!GIJXmAjji^qJ*G0AalHdC6!y;yk!6aWW~yQPQIk;2;tJehTk!=} zRq1RW^n4(R=oam@$k)x%zGt=(Y%9T&H>!d3RK9Q#z6e(7E4BLZ`pufA?Ztpu`YkLh z7Afmlm|U{W#Df9)xdpqKBv&j}G~^<}Ie)n3Itpl-l$Ns@E8_LYI-;sdC0jSYUz*_>xp*Ka#MLH+5*q8MG~r<o74csn;Lqxk*ELpe4wQlQ8?D+{6;Y z<-qf3WzyDm2&PLDwsxBNOn)SaET`7!6P?61+O!<&75{HpLzENWPxDWWBPhINp*U3; zBn>?72)N4hqrt1&xgg95s!8y(lr!D%8G|5%5GqPaUIb6ZIeI8bC$> literal 0 HcmV?d00001 diff --git a/doc/html/_me_encoder_on_board_8h.html b/doc/html/_me_encoder_on_board_8h.html new file mode 100644 index 00000000..a16d93f1 --- /dev/null +++ b/doc/html/_me_encoder_on_board_8h.html @@ -0,0 +1,260 @@ + + + + + + + +MakeBlock Drive Updated: src/MeEncoderOnBoard.h File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeEncoderOnBoard.h File Reference
+
+
+ +

Header for MeEncoderOnBoard.cpp module. +More...

+
#include <Arduino.h>
+#include <stdbool.h>
+#include <avr/interrupt.h>
+
+Include dependency graph for MeEncoderOnBoard.h:
+
+
+ + + + + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + + + + + + + +

+Classes

struct  PID_internal
 
struct  Me_Encoder_type
 
struct  Encoder_port_type
 
class  MeEncoderOnBoard
 Driver for Encoder module on MeAuriga and MeMegaPi. More...
 
+ + + + + + + + + + + + + + + + + +

+Macros

+#define DIRECT_MODE   0x00
 
+#define PID_MODE   0x01
 
+#define PWM_MODE   0x02
 
+#define MOTION_WITH_POS   0x00
 
+#define MOTION_WITHOUT_POS   0x01
 
+#define PWM_MIN_OFFSET   25
 
+#define ENCODER_POS_DEADBAND   10
 
+#define DECELERATION_DISTANCE_PITCH   6
 
+ + + +

+Typedefs

+typedef void(* cb) (int16_t, int16_t)
 
+ + + +

+Variables

+Encoder_port_type encoder_Port [6]
 
+

Detailed Description

+

Header for MeEncoderOnBoard.cpp module.

+
Author
MakeBlock
+
Version
V1.0.4
+
Date
2018/01/03
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for Encoder On MeAuriga and MeMegaPi.
+
Method List:
+
    +
  1. void MeEncoderOnBoard::reset(uint8_t slot);
  2. +
  3. uint8_t MeEncoderOnBoard::getSlotNum(void);
  4. +
  5. uint8_t MeEncoderOnBoard::getIntNum(void);
  6. +
  7. uint8_t MeEncoderOnBoard::getPortA(void);
  8. +
  9. uint8_t MeEncoderOnBoard::getPortB(void);
  10. +
  11. long MeEncoderOnBoard::getPulsePos(void);
  12. +
  13. void MeEncoderOnBoard::setPulsePos(long pulse_pos);
  14. +
  15. void MeEncoderOnBoard::pulsePosPlus(void);
  16. +
  17. void MeEncoderOnBoard::pulsePosMinus(void);
  18. +
  19. void MeEncoderOnBoard::setCurrentSpeed(float speed);
  20. +
  21. float MeEncoderOnBoard::getCurrentSpeed(void);
  22. +
  23. int16_t MeEncoderOnBoard::getCurPwm(void);
  24. +
  25. void MeEncoderOnBoard::setTarPWM(int16_t pwm_value);
  26. +
  27. void MeEncoderOnBoard::setMotorPwm(int16_t pwm);
  28. +
  29. void MeEncoderOnBoard::updateSpeed(void);
  30. +
  31. void MeEncoderOnBoard::updateCurPos(void);
  32. +
  33. long MeEncoderOnBoard::getCurPos(void)
  34. +
  35. void MeEncoderOnBoard::runSpeed(float speed);
  36. +
  37. void MeEncoderOnBoard::setSpeed(float speed);
  38. +
  39. void MeEncoderOnBoard::move(long position,float speed,int16_t extId,cb callback);
  40. +
  41. void MeEncoderOnBoard::moveTo(long position,float speed,int16_t extId,cb callback);
  42. +
  43. long MeEncoderOnBoard::distanceToGo(void);
  44. +
  45. void MeEncoderOnBoard::setSpeedPid(float p,float i,float d);
  46. +
  47. void MeEncoderOnBoard::setPosPid(float p,float i,float d);
  48. +
  49. void MeEncoderOnBoard::setPulse(int16_t pulseValue);
  50. +
  51. void MeEncoderOnBoard::setRatio(float RatioValue);
  52. +
  53. void MeEncoderOnBoard::setMotionMode(int16_t motionMode);
  54. +
  55. int16_t MeEncoderOnBoard::pidPositionToPwm(void);
  56. +
  57. int16_t MeEncoderOnBoard::speedWithoutPos(void);
  58. +
  59. void MeEncoderOnBoard::encoderMove(void);
  60. +
  61. void MeEncoderOnBoard::pwmMove(void);
  62. +
  63. boolean MeEncoderOnBoard::isTarPosReached(void);
  64. +
  65. void MeEncoderOnBoard::loop(void);
  66. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan         2015/12/15     1.0.0            Build New
+Mark Yan         2016/04/07     1.0.1            fix motor reset issue.
+Mark Yan         2016/05/17     1.0.2            add some comments.
+Mark Yan         2016/06/25     1.0.3            add PID calibration for encoder driver.
+Mark Yan         2018/01/03     1.0.4            add callback flag.
+
+
+
+ + + + diff --git a/doc/html/_me_encoder_on_board_8h.js b/doc/html/_me_encoder_on_board_8h.js new file mode 100644 index 00000000..5c49fce9 --- /dev/null +++ b/doc/html/_me_encoder_on_board_8h.js @@ -0,0 +1,7 @@ +var _me_encoder_on_board_8h = +[ + [ "PID_internal", "struct_p_i_d__internal.html", null ], + [ "Me_Encoder_type", "struct_me___encoder__type.html", null ], + [ "Encoder_port_type", "struct_encoder__port__type.html", null ], + [ "MeEncoderOnBoard", "class_me_encoder_on_board.html", "class_me_encoder_on_board" ] +]; \ No newline at end of file diff --git a/doc/html/_me_encoder_on_board_8h__dep__incl.map b/doc/html/_me_encoder_on_board_8h__dep__incl.map new file mode 100644 index 00000000..eb05b2b8 --- /dev/null +++ b/doc/html/_me_encoder_on_board_8h__dep__incl.map @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/doc/html/_me_encoder_on_board_8h__dep__incl.md5 b/doc/html/_me_encoder_on_board_8h__dep__incl.md5 new file mode 100644 index 00000000..33912f4a --- /dev/null +++ b/doc/html/_me_encoder_on_board_8h__dep__incl.md5 @@ -0,0 +1 @@ +6e85eef8ca35e17fa639d1bf200796b4 \ No newline at end of file diff --git a/doc/html/_me_encoder_on_board_8h__dep__incl.png b/doc/html/_me_encoder_on_board_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..0d8476aace6031e9fd258e110133dbca9f28495e GIT binary patch literal 6624 zcmaKR2T)U8*Dghx0wM^8F1{2IkrG5Y3P>}61f?szO9=>}2b5l=NJn0JlimV>1Vn;> zfPmB_v`{2;QF^(D@BTCQ{&VmA`^@B=nao~$pY=TJS!=Ho{ajar;VQ>fGBPp-Elo8j z85so}c=n*B27Uvd8}0!&YU^hjYGfCe*S{U5DP&~qAGOq;yztH0Bm})R{~NTrdvK6o zD;&am`?0U2)~;LjV<-=V8Nw3v-n9=~ul0`Z{e(8nRt0-YwBSyHgusbqo=GAzxmdtpu@?Q@gZ?C6axNDz75y_2D6$$ew3zuM@I+Vb3jxh zIL-f+>?SL8=%lh3?;G2pY$4#vIzzKpch=J!P<^7N=KLNoBW#v`{lc0K2O%kjW;iLo z$O5s>B>qLatMLbOq_HNwOMSyt^+T!e72)QM=E9w}QoAuXx*iJZ&+Fsu%*8_}cWvulX)*;gUT~j5# z7v;z}pcKb05XHMg_L$Td*EZ)fLO)?k+lDRa_|h>8B?y^YC$$fR^83W9Gd3d;vfIKf zgz0KbvWP*0jz>RXQg(T37+NFT*q*a#C@BQJ0Gz}B{m=Csq|)bgS7W{17)|KiRu-*) z??#xeGOH?& zxslP5qODZHMjIjyJewojj2{5@WTW0RT1M0UHAl)M65V zU*bzw@IT|5_0_lt%dO!1A@BT8X;LFMdh-fnon!EBk2obyq+CffUO_`p9= zW;sY`=Xb+Jgo8r=_>}OrqLKpf%NQXGD%Dh^DeBl+Qa`(mHtGqIXsj%r>SzLH7 zk@fGJVW9VCo6Qo*Q))%_YyG)V`1iZyIV2XUpDimf( zu1l-X^au6;-!}fGY{DXeGvf3tGo*J=g67dTvQYW!S89Xq&kwmbPiK#tTC6^>05$%8 z2tR+%nQ==Qfm(PHV{l?PJun{gM2!Rla1!;nB58Yv?g8IZ8oo(ryT6jnPO2SpWny5n zSO4qY8e!H`yoV!aP=-^2OEU@n$+LT~wG2Zz=ZgW|8*jy7?8#rX|8+LCzjt8GtZ5Ty zvqlloT-{jlg6l2g$zK_ZM}^T8M!R^AoOH_7EU>8`(sccQ$7j)#H?zd5t}E%rnw&qV zb11p4@KESd3@!gMdngE_h{Hf~zwx@Feh5}@8y!T6U0?8jzs}8u`#IkFlU^*>;}@@E z%Uq2QeZ#m{p4gD>;jOq9@ZQHptsKGmm)8%?;OM#zg7#|xQM(kYz;}m8P2$Py~0HOlm_C6ZbFviK*eq-`}vC#4cp@BcdMTi)ZlB# z?dFd@NUyIo3^};7Dx+;dSg=-%%kkvYKjR6T*c-}zqkcaY2p|@!?W62PPz~|^x_isn zc!J%7wum#iM`(TLjGGx`S%hin+6n*Fw%JeH0ba;Nu`qJPn*{J?zYE#6H}Q6@+*>*N z2{PfFUhz?3o5^PBlM!6&b^K4NId^Tcb6G*$D{rpM(w)vMgm!Aukayz@aeHHP zlPUWwLbrCbrJvAcau{x8iz^uno?uJXd3G<@zNGhS#;N?&$=ozMPDnbRa8U2<;QLT2!oRnU7TE8+DSe^c1bULSIN?1-W5i+k=Xm`+OX?8epn(02jJd}QDP8v?!(U^ZB1_pG*oL#OhceE;nKuF*pukh9)|1WS`~FSDn@LCcfHV!^ zWfq0>!pupv{c()*FXrvyBJu1}pq#-Ub_cZ=ncdqEsS)|SvA9dlmBY|3Lw-u#e;`eU zYWkX!wHK{jh)gF=GV!)!+?(4Ke;ruPhEaQ^j4m`Yu8sHupM+x*X|2dE|2%CbhE-VH z+YbvvWigIw{2c#Dy%UPFe@?9)^uM+;P+iF}1lF6Fz&+?{tZJh&f-F&Z|ruSv!sI*t~w^ z6G{9yqE+#hSH{b6fP~<|Q$-IYY}1)*+7{Qo9%#dsgumG~2Ckhrwqb0#liQ8PS$+&{ z-3_!SA8*%-igr7w*T47Cj8H>0iNkr`ZI1@lOO7;^qJ`<&R}Vd_-@-vIB5 z&Xk9%TiQDbZClGeIbxIkH=gnV7+Qpu+PC#qyG&hh*IqMb=HN{%@b^KxUTPnR zw_mqwPr|aiTZH-_nYA>-h{d)%gQ6S4tt`>sE@|~eW|et#!JrR+^f;qZ<+CB5n&KMA zzVemx{#;8X75aziA?Lq?xtuf;Gp?}S7dow#qcYqek?){xzpqvv z*6%Q=j_&h^TcD@OkiJ|^RvnQrW7XpE_amt(9!;-*x$9x?r!>NqW{De zUlov{3?u5{r+w^25Ffrebh=G%3Ym18f+u+Ww67|-4Czvg#_v;U*eU_lNap)bjlAIL z?>*BhQFz;0jjMd$k*J!%eJq##=X#b6K)9N_Uw-_KnV@ZpICYK-j@*tAHP2mgz_`sU zxSJuP=DL5;&a-UgFe|=RNt6x53 zr93(BW{HQs`DNy+94B95`tv`z^8v>jWgSj*2S{eg17TUjxycV^p<3WdT!KVjN7HdO~LNwSQzx!&cS`e{-tqJf(sePO~F()OPLvSl& zWi0-m;NOQoYc~bok3$qo4`^2CnLli~G$3MR)sor(0kX}~kymK)l~`?UxCd92G0D6sPu^^UShnE zAL45+I_+BKX!$ zqrHn8hXT%|RJJ6I?Xe|jX_WF-2FWB@P@%eHQ1!gJB;;ZKSQ0ndmEx0>gE(>H2TTO0 zFgY~cvXa}cho}8>T@60k8xd&q(Z9i~yCe8D$n%lMRBl3O)BZ55H}#5E&JHrGgkjE& zOt(+DBwKgs34!@`yk=i6|HR+I^ZgY%rL3SkUrjBAckW?%-jD3Uwnl6#ye1zmWsAGH zgq15Se)vO|SSbLnc{97S>1nBqh2z=j&5&k61{~qZ@>+4HDp4DIrpjMl@FJK&-VQt8 zdyigsC{{MwpOttlBHFxMph62(bPSRUu!qZAg@dolEhvjTc)B%9<6hxrHZ)+pcbQoQ z;Lu6wIb!J*;R#y@j0F{!UUdbdI=Bj7>b^eS;+NP`g8fBPEqOQ`w7LHgY2$n)UJ5XG zcK$D~@+WInbsB?|c(FcSv|>XzP3rw;$#+{*+LE&ulxmn3DdwM7GkuBEAB<$JS|1Dc z_hNxtou+k{g!s&PfT9x#^m zsEWy&^@qQ07PDf#<7@Bj{aA&0-T9YbX{qDF@x^52g*y2Qm}M1#8xHyFJj3GffQlZ- zO}XVa;T75@q@-l|a@ot|gT;sOfd)9kA?hM$&=fQko?2#}YStxD(YSTpO79lu7kAS=w5?|`yT;J$I+9ZFG zTG%~Z(>jSx8T>q8xYj}*`;8OL?YMd)cYt44dy8MP^*TLVF`o?qgtHl5H&BYJg@QPC>;An)Qcxh9Wy-v`Jku@Dyrj_O7H6`#gWzt`hYuES?v% z)~B_F-t-I*-U1Z|3%8~eLPWwcDy|H$s&tmEz_k;q1I`W{e$F31`vJc|7DQ>^tlTkMf zXNoU%Xb~H@f@k2mZay;ScEJRPF!Sp8n$P`LsSZ#8Al>}wcS>s5XjVi;op9^34}j#m zg!BOHj?BHGqlwFqi#%1e59Bf zU*Q+J@-RUK-I8i6W%5og6J0+=Y5puOcE5MUH$bvP~aE-CXU+-!C|cGwryaZF6#NY_JuuT=Jn-}!Y- z{0YZ6csP0I%uERsc+uSJcVxm)_wsfHu?&Sep$DJLjk~pwvdp08 zU7TXK!AW%*m}52k!cRFcuFe(LoU7kR7#nNoBh;pu`VmCEEuFPp`FzWY4!*EGcQ`5|#(PVxk zjNS}=`WdNOZa1v32a%DM-lqp<)8vfJ%pC7}4ao{cl?BZU)m{jB(7QVv{k~RcmiPj< z&>iWwKkY!?Owp5q%9)*=bu3J-$g07lABXc#2maaC$(DxAIF&v{^F+_y!W{NQ2b~mj zh}e%5JY@meh@wf=YNXLvG4!{=M{^3qdRhzv(7cNJ76{17f9pH;<^KPgTF{if+{}(; zhw{n6lFimKb??E5&F)kG?Hc9i z7*-2Ph;t6OHsoa_@|_-@w|mgwTKPPCIcp%GSgvARjCAHMI~H8lh`9BiW@Qo5nOk*S zL1S3G{Jb*QTrqyefwaqI;$^hu92BXg@KY?o&@pcb-5IqsCc*y^npbY|^4XU5tJ(W+ zGaFJfmC9o5&Kf#wO-c0|5arUEmZ^H}$g3%LgwG0ooWwT08md=WzYouQX~Ws?S~$9S zfB(^^0l8RLy@$-Eu*U4Y@0(z}2Lc-3wpbC5W zBiH2%R0h;Sx8KAfxqO(bYE;Q!XnmCf(ezTFHQNPhAR4Z8Kju|)ZsHrX{}8CR zXR;6dU~{hZ_A`G^L*c)fquVZF*Ti0;JRi-aKYrHpe5k%mIklgg0#a|feXFVL)8b3s z#Mj9Q`OXZ3S}+or1b!)8mNAepfT=LNCtF#Rk~Zd6tg5X0s&Q<-!S0vmj zWPm7_IlPK?O|_}|1k7$4yNke;l?|t2?)R+(8B13@!;T~8T%~hwUj%`Bo;#W_yWvHP zd5)jfr3{(RRNI;e?56n#wbreQcq?nQ;-DnZz2?B<-RI8A5DWL#0g{d)m+H8qL-Xp0 z_FB9A$)q}K_ZwVhjS`r%XYo^w5~#2CP5IpLKK$c3%Gew%DhB85H*qiDUmdkqEFTZn z-#8d|l#j7%AS75zq~nGwMtWnLz>_vDqX!cy{&Ep3MBnnp3sSq;=>ZA6jA==hDflLI zPv0vAG?}g5u_ST_Dk_(#UHsD_rt+vaalEbUflF+Z)YV*#VkimR186RV_r0W}vAf-M z@#+Zq^3-F970^llA6mznUGHLmI6sP0C50V_f5YPg_Xc5+x5vkr|6bkS#7!3LRlgvW zEe#PcG=Y*4#fbahZ|e+p$>)47RmWdO@D!^ m^FQArF8kI0XFzMtl?k;R@^K08hk;KvWLi&k)v8r2-~BI^4o+JD literal 0 HcmV?d00001 diff --git a/doc/html/_me_encoder_on_board_8h__incl.map b/doc/html/_me_encoder_on_board_8h__incl.map new file mode 100644 index 00000000..1ebb1abc --- /dev/null +++ b/doc/html/_me_encoder_on_board_8h__incl.map @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/doc/html/_me_encoder_on_board_8h__incl.md5 b/doc/html/_me_encoder_on_board_8h__incl.md5 new file mode 100644 index 00000000..3bf9ae60 --- /dev/null +++ b/doc/html/_me_encoder_on_board_8h__incl.md5 @@ -0,0 +1 @@ +6baf618c3bd25528e6ea36ad04a48d23 \ No newline at end of file diff --git a/doc/html/_me_encoder_on_board_8h__incl.png b/doc/html/_me_encoder_on_board_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..ba679146427b4e87fd9af7933424d149edf0ce66 GIT binary patch literal 4224 zcmZu#2{0Snx2Ker+G=Uh>dt4aCA74mwboX(B#4CC*HnwxVrxaUf+|hbM{Fe_NGugX zEg!Wd_69|5RiYx+s-?xt|IM3uZ@zhRXU;t{XXc)B?)jZ_?zt}?+&2;6lj7sx;1Dpq zXK2I0!KumSAD`f1)7S$>AbaC+GdD5hIQq}ZZ^CDAa0qLf8s4=F&tXkPgg_S}x;EB= zP0*ZIj%j^48}MeZNafuGr<_vCNgnBxi&uUBDUzpm<-Ybj!{=*oI_Gexh!_{!JPc9*1QU1gie8T669rQ6 zH2)@ZxTvj^q95ojJbnOFqJFY1Q`Xi=%t^Sq)>C+*%OX`kPqDZ8VV0+V<^~YrE=x;- z2$tECV%A!Ib`2lpu@K`P`@@S9NW~CJ)^v7rvRfvWx!3dYx@{xI9moeWu41K?<)IIt zwlJ+fy>4y=rbpV7EgA>Vmjf4$v@?P{RJ^9peYdm7J(}+VB;}$93;XA69l>NdO&skxNp(Cl#rL<}KnOoLrM)JJHT}OF=U+gRj%D z+R*yLfG{%G4%t4y%oXY9D5mqLoUW=l6J$}rbB$LYTEnY%H_h_2uiw;b)621xn1g){n0KkY)*rzC6Q6%a&8!_7 z^?NZpP#pmHuJc??TR=#tG4;WYRAI?pb4!Gej}KW~^Wj7me1C{JfRXzh+dWB=$yssx z{w@P@@Jb236Vn__53K7haRsO=6TzFowrR%WX{+c{NXRX)T<#?Oejv*!J0pxSQN9qV6f6T zuh@FV-Ibyv@z$lWA0#HiT1%T2?meC>x*KzqD1AA5JA7=&0$x)nq52x7V!t4F2c2Af zQQ|FvsDUZGp>%YfpSD&Qbssg80gjP)$;87L>a}c?-+|V_CJRqCSv`Eu$Hgo7*m?%D z89YXzUK^E$mn$cys-w`ki#nO50$}>G-OhdN=h04;eBRw4C5!NRO!dr@a>5UoLZDCx z)emLP9aBTeVl<{tq!3^@`fPd0NWndQ(*5FaiFd0J(6jtB9YZ=o<&4|;>ff!Li(Jxn z6vgzbGE+G3`hL%^RfS-axA0;2%cd~7_45z?eNYL}nY0>WFhwi8;#5alH5g-btmfp# zXCM7Q)(`8+X6ZCUBzDPcIRXy9tw_C4vYEwpbI18wM)M`$3m%k<%8zrn4leKb_R|XS^ z!C6%Q7kl*OAwqrV?)w1l=fJs)Xx9ij0vGwY#=-b0VrmlMPknC{C4-jz8Te{@Zvtz7 zuP3-QYr+HRr|H$9f<0}ztmE>6>z0#~HlEbZ2a%5?rJZp<50!08X%*lF=B_0%ul+|& zWg*xA{AjF3KQSEoMqJ^KtCA9J4We|!)Um&Kj&j!-xOfa{xBKcI^v2gpb9_Up7nO~y zlowY+D2$D(s^>Pf!}1MQgR$~2cvLc@t16>H|M2V?B!&|eOU>CZTyQt)tEzJJMbxx% zJofg{LI1}J7=y3D0e{L&bSo|qG%mu1;DXRHV2on%qr60$j-i_$NaP-uxCoWvr$Mqa zTO#)}yZx&wl}vU&v>NrjzkR`UX@qV0u!D8*#b_`DB*UuLb=<^_G`_?z|r`lQulSZf1wFgGm*m5Sw&N*mU4uWB-VQl9G;`)~ef;r{=n(3#&vLSM1fjKcR9=GV zK{@)?B^W#06n=Z5vEP$=on2x+>C^*QJbU;CGV?h5BGrDGC{XhiOBtm>dXLi;hVm`H z)dyrePYt~Ct>-s6(~%HmiE82am7=$#xZlso!>$Q-+Zo`Qq{7eFh%x5_!@JyKcRB5RH)l-_T=(ifR|*== zH=LTwi{s*(;&P1`MBt1)+Xs}uvOm8tZ05aeVYxd}ZEQ&RGm)4ecWkcl2> z;V>XTZw$)60_k}oD!$+}3@$le>$R*t?L(E{j9GWP}LxTWH=u=zB@l(Gn{1gj1BGBMiD-#*4O4XpZh4oFC-nvc&)qkP?CK; zFQ?dr@GAhSylj_o@!J@`rYl$W@diZd*F#r! zXRPm);s(=Gmws5UVfe%E%^g#Z^$kPeHcE~2KB-BK@p9{crgt*Cji0jE+208wMhaUl zcl>qGDw)h;;np@%kC9ONN=xkee(U5};ZO_Ki_Ct8#0A~ExMw{1&~GjG+mC7k#aBTQ zN9(qi=q27jvhP}{oXY2bs6hRja6m^>sPP8?m>vf@33Nh{%u|8(oK^|{cxL~6 z=jTff~-S<(UIECQhYkJu#VV}+MdMUub^@Kx_!D|*KXSM zIc3qeI_ABC0=?b2K?{vAq2*+%9DnX}6~Cb(=km5Zf=p9EX;Ape;srsq(CAU+ZyNX( z+kXF_zNp0ym7=ezYI53~YMiQ^o^1-xaX&>Goo!?qZirN4L-^)4IE^KtWYb{QNY*K- zUvb})VEa!8Rj+g4Ib@#k6^Z?A7$Lr!d%=zQ7Fh>Q=qngQ16&h5z)EkbeM%GPgETacCk zEEk3AH&gAmEBFJ_wgbr+6` zj}828!(RS$oSaHd`+zn^1GEf!45|cGs!UaB{+2dY+T}|6^$u^Ywf3eBbV+X)uDP8D z(ML%xu?36>mk<#gWZGAo0$-lHF)i|^I$AP%=BQEAf7I@~?jVGf5te=b_Gi zz0hpi$i-#m2LZDE8z6-2`jCvmk!5ad?%x_YT!G*T*XV4AdyI;nH%E^_Q`a3dE(Hxga@(Y5Ko3+m7*XxL`sAaiXy}qR1JduI z;bF7d+^@&){d71sJ6Y(i++nC`Y{0h`+6HC(5c`9npJ_{~u874o_l%v%@SS&?Y)Km^ zGs*Bxw3$?JxnQ-(2=e&rXHzj@d0oS4)&^Vzm5u_&KH;-o+V_lv)lSOZi+=5&Z8ei^ z8VghFD7Kl5RijlTtOYhyuaquKSPBgDK&)hQE30B2<8utkZ0KgGW{Q*R8lN+9)>2hq z%g~#yRJqTU{TSmPN9l=qlx8K-9SMtVhsLqom(l5K^|seyMKHm?OKRa20Z6|NDrlW* zeJWU>Maq?QZDw7gNno=!jJ)uDKUqJqwC~>=!#kmlp;rTC!ZQwW~QSd z&1pYUAiYR_?b5WhS+4>)Su^c>5E>us$j!xRX$!N`9;rUQ-8W`c{IPEE)ZVmHFOo1a z7P?WPCi|egMAH3ON7CPFUc-JH>v8{{ZvPt%W}{4cdXI-@@VjFUdGzNdG7+B;+!{E| z&+#VWnj#TmyU>n#?%vm-W#6kStoZCoo6pL~#6(cv$d3xudcIIOpWdv67?TG`!5hLU%3DP literal 0 HcmV?d00001 diff --git a/doc/html/_me_encoder_on_board_8h_source.html b/doc/html/_me_encoder_on_board_8h_source.html new file mode 100644 index 00000000..1bd1fc68 --- /dev/null +++ b/doc/html/_me_encoder_on_board_8h_source.html @@ -0,0 +1,314 @@ + + + + + + + +MakeBlock Drive Updated: src/MeEncoderOnBoard.h Source File + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeEncoderOnBoard.h
+
+
+Go to the documentation of this file.
1
+
73#ifndef ME_Encoder_OnBoard_H
+
74#define ME_Encoder_OnBoard_H
+
75
+
76#include <Arduino.h>
+
77#include <stdbool.h>
+
78#include <avr/interrupt.h>
+
79
+
80#define DIRECT_MODE 0x00
+
81#define PID_MODE 0x01
+
82#define PWM_MODE 0x02
+
83
+
84#define MOTION_WITH_POS 0x00
+
85#define MOTION_WITHOUT_POS 0x01
+
86
+
87#define PWM_MIN_OFFSET 25
+
88#define ENCODER_POS_DEADBAND 10
+
89#define DECELERATION_DISTANCE_PITCH 6
+
90
+
+
91typedef struct
+
92{
+
93 float P, I, D;
+
94 float Setpoint, Output, Integral, differential, last_error;
+ +
+
96
+
+
97typedef struct
+
98{
+
99 uint8_t mode;
+
100 uint8_t motionState;
+
101
+
102 int16_t pulseEncoder;
+
103 int16_t currentPwm;
+
104 int16_t targetPwm;
+
105 int16_t previousPwm;
+
106
+
107 float currentSpeed;
+
108 float targetSpeed;
+
109 float previousSpeed;
+
110 float ratio;
+
111
+
112 long currentPos;
+
113 long targetPos;
+
114 long previousPos;
+
115 long pulsePos;
+
116
+
117 PID_internal PID_speed;
+
118 PID_internal PID_pos;
+ +
+
120
+
+
121typedef struct
+
122{
+
123 uint8_t port_A; //INT
+
124 uint8_t port_B; //DIR
+
125 uint8_t port_PWM; //PWM
+
126 uint8_t port_H1;
+
127 uint8_t port_H2;
+ +
+
129
+
130extern Encoder_port_type encoder_Port[6]; // encoder_Port[0] is nonsense
+
131typedef void (*cb)(int16_t,int16_t);
+
132
+
+ +
139{
+
140public:
+ +
148
+
154 MeEncoderOnBoard(int slot);
+
155
+
170 void reset(uint8_t slot);
+
171
+
186 uint8_t getSlotNum(void) const;
+
187
+
202 uint8_t getIntNum(void) const;
+
203
+
218 uint8_t getPortA(void) const;
+
219
+
234 uint8_t getPortB(void) const;
+
235
+
250 long getPulsePos(void) const;
+
251
+
267 void setPulsePos(long pulse_pos);
+
268
+
283 void pulsePosPlus(void);
+
284
+
299 void pulsePosMinus(void);
+
300
+
315 void setCurrentSpeed(float speed);
+
316
+
331 float getCurrentSpeed(void) const;
+
332
+
347 int16_t getCurPwm(void) const;
+
348
+
363 void setTarPWM(int16_t pwm_value);
+
364
+
379 void setMotorPwm(int16_t pwm);
+
380
+
395 void updateSpeed(void);
+
396
+
411 void updateCurPos(void);
+
412
+
427 long getCurPos(void) const;
+
428
+
443 void runSpeed(float speed);
+
444
+
460 void setSpeed(float speed);
+
461
+
482 void move(long position,float speed = 100,int16_t extId=0,cb callback=NULL);
+
483
+
504 void moveTo(long position,float speed = 100,int16_t extId=0,cb callback=NULL);
+
505
+
521 long distanceToGo() const;
+
522
+
541 void setSpeedPid(float p,float i,float d);
+
542
+
561 void setPosPid(float p,float i,float d);
+
562
+
577 void setPulse(int16_t pulseValue);
+
578
+
593 void setRatio(float RatioValue);
+
594
+
609 void setMotionMode(int16_t motionMode);
+
610
+
625 int16_t pidPositionToPwm(void);
+
626
+
641 int16_t speedWithoutPos(void);
+
642
+
657 void encoderMove(void);
+
658
+
673 void pwmMove(void);
+
674
+
690 boolean isTarPosReached(void) const;
+
691
+
706 void loop(void);
+
707
+
708private:
+
709 volatile Me_Encoder_type encode_structure;
+
710 boolean _Lock_flag;
+
711 boolean _Dir_lock_flag;
+
712 boolean _Callback_flag;
+
713 uint8_t _extId;
+
714 uint8_t _Port_A;
+
715 uint8_t _Port_B;
+
716 uint8_t _Port_PWM;
+
717 uint8_t _Port_H1;
+
718 uint8_t _Port_H2;
+
719 uint8_t _IntNum;
+
720 uint8_t _Slot;
+
721 int16_t _Encoder_output;
+
722 long _Measurement_speed_time;
+
723 long _Encoder_move_time;
+
724 bool _enabled;
+
725 cb _callback;
+
726};
+
+
727#endif
+
728
+
729
+
730
+
Driver for Encoder module on MeAuriga and MeMegaPi.
Definition MeEncoderOnBoard.h:139
+
void setMotionMode(int16_t motionMode)
Definition MeEncoderOnBoard.cpp:791
+
boolean isTarPosReached(void) const
Definition MeEncoderOnBoard.cpp:1039
+
long getCurPos(void) const
Definition MeEncoderOnBoard.cpp:554
+
uint8_t getIntNum(void) const
Definition MeEncoderOnBoard.cpp:252
+
void setCurrentSpeed(float speed)
Definition MeEncoderOnBoard.cpp:386
+
void moveTo(long position, float speed=100, int16_t extId=0, cb callback=NULL)
Definition MeEncoderOnBoard.cpp:649
+
int16_t speedWithoutPos(void)
Definition MeEncoderOnBoard.cpp:926
+
void setMotorPwm(int16_t pwm)
Definition MeEncoderOnBoard.cpp:463
+
void setPulsePos(long pulse_pos)
Definition MeEncoderOnBoard.cpp:329
+
void loop(void)
Definition MeEncoderOnBoard.cpp:1058
+
uint8_t getPortB(void) const
Definition MeEncoderOnBoard.cpp:290
+
void pulsePosPlus(void)
Definition MeEncoderOnBoard.cpp:348
+
void setTarPWM(int16_t pwm_value)
Definition MeEncoderOnBoard.cpp:443
+
void setSpeedPid(float p, float i, float d)
Definition MeEncoderOnBoard.cpp:707
+
uint8_t getPortA(void) const
Definition MeEncoderOnBoard.cpp:271
+
long distanceToGo() const
Definition MeEncoderOnBoard.cpp:684
+
void updateSpeed(void)
Definition MeEncoderOnBoard.cpp:508
+
void pulsePosMinus(void)
Definition MeEncoderOnBoard.cpp:367
+
float getCurrentSpeed(void) const
Definition MeEncoderOnBoard.cpp:405
+
void setSpeed(float speed)
Definition MeEncoderOnBoard.cpp:596
+
void runSpeed(float speed)
Definition MeEncoderOnBoard.cpp:573
+
uint8_t getSlotNum(void) const
Definition MeEncoderOnBoard.cpp:233
+
void setRatio(float RatioValue)
Definition MeEncoderOnBoard.cpp:772
+
void pwmMove(void)
Definition MeEncoderOnBoard.cpp:1011
+
int16_t getCurPwm(void) const
Definition MeEncoderOnBoard.cpp:424
+
int16_t pidPositionToPwm(void)
Definition MeEncoderOnBoard.cpp:810
+
void updateCurPos(void)
Definition MeEncoderOnBoard.cpp:534
+
long getPulsePos(void) const
Definition MeEncoderOnBoard.cpp:309
+
void setPosPid(float p, float i, float d)
Definition MeEncoderOnBoard.cpp:732
+
void reset(uint8_t slot)
Definition MeEncoderOnBoard.cpp:168
+
void setPulse(int16_t pulseValue)
Definition MeEncoderOnBoard.cpp:753
+
void move(long position, float speed=100, int16_t extId=0, cb callback=NULL)
Definition MeEncoderOnBoard.cpp:623
+
void encoderMove(void)
Definition MeEncoderOnBoard.cpp:979
+
MeEncoderOnBoard()
Definition MeEncoderOnBoard.cpp:92
+
Definition MeEncoderOnBoard.h:122
+
Definition MeEncoderOnBoard.h:98
+
Definition MeEncoderOnBoard.h:92
+
+
+ + + + diff --git a/doc/html/_me_flame_sensor_8cpp.html b/doc/html/_me_flame_sensor_8cpp.html new file mode 100644 index 00000000..ae334067 --- /dev/null +++ b/doc/html/_me_flame_sensor_8cpp.html @@ -0,0 +1,188 @@ + + + + + + + +MakeBlock Drive Updated: src/MeFlameSensor.cpp File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeFlameSensor.cpp File Reference
+
+
+ +

Driver for Me flame snesor device. +More...

+
#include "MeFlameSensor.h"
+
+Include dependency graph for MeFlameSensor.cpp:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+

Detailed Description

+

Driver for Me flame snesor device.

+
Author
MakeBlock
+
Version
V1.0.0
+
Date
2015/09/09
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for flame snesor device.
+
Method List:
+
    +
  1. void MeFlameSensor::setpin(uint8_t digital_pin,uint8_t analog_pin)
  2. +
  3. uint8_t MeFlameSensor::readDigital(void)
  4. +
  5. int16_t MeFlameSensor::readAnalog(void)
  6. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan         2015/09/09     1.0.0            Rebuild the old lib.
+
+
+
+ + + + diff --git a/doc/html/_me_flame_sensor_8cpp__incl.map b/doc/html/_me_flame_sensor_8cpp__incl.map new file mode 100644 index 00000000..5ea926bb --- /dev/null +++ b/doc/html/_me_flame_sensor_8cpp__incl.map @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_flame_sensor_8cpp__incl.md5 b/doc/html/_me_flame_sensor_8cpp__incl.md5 new file mode 100644 index 00000000..7442e35a --- /dev/null +++ b/doc/html/_me_flame_sensor_8cpp__incl.md5 @@ -0,0 +1 @@ +f18c91daf64bcc6ec90c9d8e139c36f2 \ No newline at end of file diff --git a/doc/html/_me_flame_sensor_8cpp__incl.png b/doc/html/_me_flame_sensor_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..81394ac68039f8e1e57e2503f330e46100dee24a GIT binary patch literal 48064 zcmeEtg;$hs6ecCz-3THf&Co54w6t_L3?R}aAkre;C|yHI*8q~jAl)Sb(%s>HfWJL^ z&YnHHf549Cz;WiA?|a|(-uv9=KKBx?rXq)hPL2)-2ZyB~FZ~)04#@`&4n7?f8F)vN zE#n993)xIjP8#m-{lA>n!gx5ir*I0=FEu?gb{4#R6V@949uA)>N#Z_VhJ4EzwIec! zET4VjV-rNrT5c#wk}Sy}Jw9q@KSAA`=Ti%r(BP$qKj)j4>EJ{>k=w1ZQ|%BPX?iNT ztz8~CkTmFad)F7zlOmDSFVg?}+P`)E3Fvsx&zPWYF!{R82^a7G`ig^87Gd097f0;2 zKFEw9D{UAiKihM8yup~uE-5YD#KEzJAPv0oWLSxt`7pbrav@SkPf_1n2X=jhNC6k9 zn#O+o_)-2Zp6~$_k&M?)bKJe}>G`inj-vsViti8Ccr$!#g8OeN{gk1ibpKw0(hpw- zzW-4kTYdW3zqdb25uV+@cmMj0`@dc;R}l%k*N1JL=}yeQ=(!q0XQ}=V8%OnNPSfp9o}bs=ge6EouamXaGCm{}!!y|0&!PYT$v5k`HU> zgY%fwv)*l}4QSbo6>hG3RzBA_8#^;IkOGNm1{r#BP_}z%*4d`j2LulAPEBTSN1usU7D$o zDe#Z3bybwMI8b}o@n@;ofRv?~uxm&NmSZ~aIS=cfE&F%wh8~OhI=!|ux0Vj)#fhi2)Mky-w66LNQCPfJJlwNeh)nnmDtWVv2z@s~nw zyoQ~UEQr4!cdea#5MV0lmsn{sz$M6)i%4{i6c>ATENUL_BbCZv{T5OyN<7i99udO{ zy=UtX0~R{E;9%_sQ(&4b%m|I^%tdkYI?cHV38AqPoWAATgF!Y`VzVHy<{GX!6#Hgx z$Lk7xoooWUxOq!;lBf6PWLt-2UeDiM?~A`1FH%=erbCqWP&wR+Au;xi(=qb09KzzC zKWJMVXQZPW`T1~=_l^=r`M8gJGtq}J?L0USS_~>bX`ZnV0jJ9T=po!DiHtXYB?T6vtl%i!I1zina2`hpx>|+~G%??F0jsc% zJh~iNC8ZO_)6n?Xc%0v4-ve7Fd&|}?^>ZOwz?$?Q!Kg1V@zo*4Qup~cr|+Gl9#*9c z!1s%oA6zpI-hPG0hwK9MQ;#DnK`@{s(~RTYQ46qM*gsT5On3PK%U--ZzDFF{N1w&C z(bt$q3!xIT4Hik-J7!VT zH{tp8n&XZ!8_>~llm5394%THSlVf3Oo;oM*_~#><^mKIiRR7LnnJvRcf9OK=CsN=D zq1&DT&sd$bek!oevwz>t!0p@>xZD)Jq@AaBQ2-tn_ZS^?f~JGGNd!Mfqh_W#n*xdO zlJ9Se_ITUR1TPrhfHo&Yuly~}PG>HvbDQkEY>njbls+#lh>@7mTS?L{D@&CcZe{g_gqZc>kPc#hE z?)kRpom=DbX1_iF0^}5Z)$8-|1)(NxXPut;R3%?O8EFgfV*9L*LF5K1K&EDQ|-$g8gIBd>pQ5mMz3!Cq4+2^uZ12AUzXeEoVNpRk7tSH$tf~neo zw!$DextE$AJp<#{o3L7RkNbrA7yEco#ND#wNU)XQKcM(G&a&K=yQ6k6Jxf=QMVYv*X3_vBb1@@05)P z)BDdEfZgEz@27Zgmj5RV7J4KE^kEKv59V)wSQ(s?1j_~&Qj))hX<$Tp!GoxFpVM)p z{>wxCv{gFP0m357eR3kd!BJ$;JFZ~Q&-Dry8WOo=(b%f_Q6K90E3HP96lDzSKYp}` z`Oj@90gt_X`yx?@XG`eaivZHBc8a>oQ&`1}BfZ1Sr`9y&ucBvRm1ul_eR`#;bazs> zE86cWC$DR?ulibcTR7hKP(*c+MuMmXGLq`Bl?ApJYlSR0RUF4{y*Y(eD=kHmD zE}`Ogb8^i>{#(%8^ZHfm%#BiFBPyTGDjjYeufK#@Z_jkd{Fi%eW{>EcTdz`D?{-#2 z0+wzaEA#|L_~1&%>Z#Tzd^#or&%!H1-)U@KCCWfj&$RX5+_3Xr+74G;29+z&k1 zR0Gf2(`=kAkNp7RbZ%pLPaQv6$mn%4KIuu^qulE`^@3k2O>>}_GbT~JDi&z((dF?* ztzlt&-S^6*34m7Xni*L!Uv>!-$-neho)j z&7MJG^r{Aq)A>1PUq|(lp+uqdq;kPB7ew(*^laXl7AqLT~M>Au)0wOmQ()^ z0>yYYsKr?aS9=BWu@#RbVWnwy!|rb#^*V=nid-6827`Uet4BMXhIsorv(8=+UyBus zFbFAe=b{Rrdd@AwhY?wo6|q-OG?N!TOJossHjLon0Zp2;{I!<($pxj}{ILkt@64XW z{U|ayu2RjL>K#i*S8e}~uc~IWem|ej>Xm_BLTjM>_7Q9&GpC0k0aOj>4P^z>?0fwg z!J<316%L`XSg(~_Q$j#wq-Y}hFxOzBCsKN8;cR-AKYR&I6)#p{4Ny{w&JpD6e2y77 z5fmN-EYfJ|T+>0nvR$VffNV7vJP<``?ia1KMT40%W20~va_M|73osSm2*w+_Woy!< zGUn=1Z=w3mESMJLq$R*%m7f0<_*I~J(2zjD+gvdYS-%Mj{p5bZVWVF@PLW(6)#U z-eyM=LBnE{fUJyi+{Brcf2gP-KmX>nqesM0N(|@;X;4iMV$w3}o>N8ko=t#cN|&cw zk13^+qC^9gCvh&kwemKa>5!C-uE0p$nT#@!W&hO{CvRq6{|zM5fg7Vt`qVq+F;STR z4Hia7>Ed zD~9@-cW5?y=v0*I?sUDroJY$r>#;70bns%>QlE||TT>86O3Bze)j+^Rq~^0m^SUYU zt`n4pN#xEYd%J&QtU|sn_U~Rv1|8+v4Q|8S&a9nR0j-6r zgU}1qN<8yMVa2-8n=hrbCUu%+M>p$OQF~93gz%Yi;&J7pzsOkR{7cTl6LlOo2Spv1 z6WwR+3uL);n_-0+mQV(ql-I)DMmv#jh|Z)7MK;4iV1-y>SiYDxuDYgb^}N3!cf>c} zCKOP4;4k2CbK`Ms>Iqd1fSbv@Y56FR@-KIWz0mgZ-{OVAzX%$#y2&Z^^O{Y|JitNz z1lFC)kn10c-#HayCJhz6mFYHHDin;}B+Uk;AcRQZ7acpYLTDR2SKBfMgCs#;K!J4r$q9Wq4uJ^#+hGs3`Q;t4UFarwa~HP~X#TTyK0>;Mw74R{BPO)b z*jPa$MY!_P)iRHE-%)Fuk3AsNLFg9U{4u62vNATP`x{oR32!_oJ4^uVU~Wdyci7Qu zFz5LNGs5fgj^UpO{^zCPXWHMNpAD!;=5z(YO=F9c0=K+Md*oLugG6l}MiKj|ZtSow z?2W0UX+Ke_3g6;@{^)efJx^!&!-4S0jDBz7+)C@^kBq(?VViluG@vx8jacYchSmCd z!Wn=qrZ9_Q1uY&wRn^vhL+W@+$Bp}l=w#n#Pu4Dj$eiKDefJSH&({&H^g1`lZ(=E? zCRA2L21VS6_A@%Of^3~e&+R`9H-h4m)?w)`{wVX@R~2Q06Hs%bRuTs+&j5Q=LUMvZ zvM?7;^dRXxlE-t#e0`WV3~fXgz-_22^z&Nevg+hO@W(cIqv1ee{S~&SHVrx$YU;&7 zJ!0bBc)Q$Xbu*SZ$LUneT+R3u!a<=@dfvHUMoBKTiq#_+r5Yv?_Vb9$iQ*swz?03W zhvSKR$zZhKs~1%|FZg5?rr8&Yq3GaPf$Uy?WNEMkdxE`G#8y`d(r`Ry+UaMrRJ=um z_wA1!3p$67UT3xY5ZZbtDh#K^dX8t>ckO|X;E0d~PacFEB^x`UcCC;#ypAr67oPR+ zL0`?P_Qym*_S4)TT~fqg{~^L_Mdx0&@?%|7+9|{ut^xaqodV2+xo7A;t~y?$j3M9x zL1W~zPA@2e6L!68uY|}5OT0HeLVnuiT&L}sYhGxieD-5_eO?6sP2QB&8d02Qb?E2i z{w$qS|M$Nq$&;6#I`QTsj+vu4CJAR~xYb-^nRojAj<;G(+@hGFWCGcI&(PqkF?*Wb2rG52J||;kfj3;jkU`WOOgSz&*%1tMkD12xjmRbl zwUK-kZh7`Sf`3Lajw?~5pYDt7B?QLRj5iu)0fXNgTEA3UgNt={uJevA>3VDh7!f#r z%{zIGYpd2V=0Ymkg?z&I8`*k1K@6Tvf;>I zxhE}V3N9ea_9*PnG;VfTeQ)N&v~`7?HjtQA&)!X{$h9cR;0YDTIE1deeJkP%wc`yX z{?AJ&)!uA06A>TrF1H6MV<%gbaH#4Z`rJG>WVCj3h6fu zeNVsq6S5*1{g7e2Q2%vrs#Ta5I&JE{QgN+mn}Xgz)%>1) zPvZt3t;Q{p$msW8SO=cbe4Y%WA;+$|e7ma=9~xgp3Myfk>uF0VtS3C{gXG0B|3!f5 zVbdVpVY8x2*^wyK2FMs1L$>mmPpY7MfN!|!I{sY#Ng6z{@AZk1g@rAu+9@vR)dPO^ z!D-YD%EkSuKPq%N)I%-_Zs()SHoi_k}Pa{qVU7 zDr}$XuCVU=USv~U$5)5cSZ-^Cwp_9kq}g-C_Y>dB5bTtAkLyFncGmv9ASNUIhfKJR zS4Rd24&VzF4%!zw?)nk`TJtrq}I>W7McW_F8jGmZyQ2#|QjN{ND_$%W223YrY;wF21Ao}}{7Jfg zKpWh?vNJu3NA4WMybMYtC>Q)}W(j=(AmR#YLE15In8G)nw{8B->VArGtyJ!QqgB<- zzMh;3U6R%!Jt0ssl1C2i)t^JlL#|){zV(u!wANA8HT2(3^USJn6xTpF7uW~RVf&NB zb3=Nm^9uu?Z#tJn!fNaz9sRY}cSAip_mRYYz}hR^qn0KJXEtgylYSR@w$g0$7=Tnz z(iSe=ji6duGH06OwF*;%Dpxka&xQnNGjitzB9gQuqyia0S*{x{AZo_nTp7J3g|p&x z?D~0gk8W~;@^|ycF@{OD!#xjwvr*M4SrRx#1p~55lf&SgK9EsBNH>$d$)>~B0Q}?V zu_(FDmL-aD*F{&rZ6M}i-DOj>m!)>%J06mI0xak5Oh-V3W4RAErY;HY50i<~)#rfb zV|f!1WRVYty2rTW)u-n*@~V&QHGKNs$rD^^JHnxkNxk(Yj591VY3+{;U04ml7g8{d zKaM@6SHtR6itB zdq4C^&&W$?!>6Py3DRDKW<=%;l6O2I*t)x1*$?(@(k=u6q6J(|GKn>y2PQz0&j%5mK_Mk$yt zEYZY!qAY62QX7vf^o~dDGje zNced67JA)gG{oyJwD2TN$Eq2BA?_vM`xMO%mDi@73=OjOG_6lS$L5X6C3Jm z_=Kl_QrfWoH&6lG$L!2ecAH2tqED(@w-am_l4&BHF42q_j8{pbwgFSMQ{34f(Po%= z4LHw=kBb^gZ)dw3ks8!46O|$LvCgE&uwuLoxu;1%s8>hdw6ad5=JnQp?(`%)k*O1l z5aKRo-JDt;bgWOb7Y6$&S7nlD8PWk1V0kx?gVX?_W$DY}vK(*sS%CT!!^qDUPy3M{ zH{)mXZd48hrW!c5phpJ1oOphwYjHY$-Jly~xz|GZA%Qi;?r%g%lG2Nca{|%jptIPp zo^XtaoeK4F`cZ9rkafmB98J$927K}s5(j({peJxRtW-h;W>-i-F^N zpI-y-r>Cc+MvBt@Li@`Fru~HD& z?^TrTdbfs9N(%B`a!L$JIYnotUN7oZ(+s)yfpQ|<&n7f>Y4DQS^!}MrYGC_TI@W~< zcDOf=jdrnzC39vs?w-hYs+xL8vFuUhmy%dYL;oZB8ZYZ>)u}(69E_vx1Cu@eW`t+w z5{@s00OAG8!PvCed_rk}cD{20+p&5`6o?c@Nq%W@0+Za@-Gs+szHjwj!)YrkHfxM6 z0tBIJSM1G{N6a*`n@jFpjvZods{*HqQo9?%9foAXkDF;m`v-a@CKAgUY8Xc_w!o93 zi0ElJtbT>a0HOxu3mN4qLrQni z8MUmF$c0NXunX{ia(7WWQT3|%-n`cam18I~S zsWX_aQWfB@l-l)K$i!~iT10b-qNyxd2R=cusd26w5ddkuxi6l27Ng!iG6;Eo_wi)w zF$T!i_S(S$p6Z1RbeNMJ5Nm$qLKyXbonO5Ct}7K$#XGhWTC|O~8GS_5*3R$NMrQ1` z;l6xiO3Tl564#~%kdRbR$3K>LV@)wlArM_Y2Q{m_62&?Ct)dgzr0?}v8QTZWga@y> zBO1dlvO#9(_&Vv)22S$)LT&g0qnU3!+QuqkIGiunuU>_D?PX}`oAIhACpZFG!@BnQ z*)E{m_a~f$9Vmhaf=;10e2%})WI$|0?v9`5-l!si=0*^0D8YoBNS+uM!awD`DRhlM zI9h;~33p$}ScyzH_5H*GHPEE!YgnjS>@Q%lKgK}Q)2xGY^Bcm#ag$Jrjq`fv*NWRB z+Pd<*2bLg}Qub=$Yu7eGprg%GvvjgXDT@F5<@8^b%6I1+gW2Nk>{~(>%O$#dfI`~% zJ&JpoEG#?L>yy4)D@pPR$9;7$h8u$}8N<7(%OBG%n3lAh9+YQ`AVd+ZOk zJ!q77*6GKYa|N>nb*kE0T0?Ko@6PuX#VxIji;9Xod)qm@)QRp@SZ>^mn$h#=wnPj{ z=;Yt$|IGrh_vm3LRj}9je1(*@dYu|o3NF9P=|i*{SE{m{N%Mha2+pM0LDR$o{Kucm zV*~!b9aytIzp4`gFV1P+aYZ2LtTNip-`_b7sOaagVp8x zYrBVwPG0?nN1^=bA+zxj)|nNPqycolK4RLfDg6C@Mc~z!Gn?6LrtF(jFb&y^eW@z4 z;^R06a}9e&#Q@_NaQgX-ZbXlBg4{mB!D=}pu;$6e;!y}kwtFlM;91-aiIZM~Ulf11 z4st;`Ro;3wux_@`r-{4j(j=!Gf2+Q4kkdO(a*Ok<-+UkQ^TLctH#WmkpPERG2%#Y* zSMd0NNK?vIXPpaCkgj(255L8_kOsgNzWrmjCwU%?(UA1FWlNg!E zYff4}a!rCy?W<@Tya-wOmd#V-Q5%x0jW@d@I=o#*_N}Z7IhRp8+L@2t%f6h6+2k?v3uXiQ%Yq48F>fwO@vID}%V@Wa6^0I^cz z?z^uijj?8FY93KFpq}J-H~q8(I><-HTTPEGt~*X|rffq%Lk5zFYKmS(ma~tcTz%VUvU#LMS10qCl5*V8 z+l!DcF#()pwo{4?2EX~>!iU)|IFT5AckMeXJhFA9`1i>Q( z%9L9A7K*u$^3nl(e+C#`*wzTnL1NINTW-yAUUN`HbNlw>n3}9<3?^}Hcb)4PLyU(& zZ^1*5)VEsfpAqU|k+=e?r!;czI8uKC55H+R1KlbGgx&$3hhYa%|!{rc9n zQXwBdx#QXjTkF-+JmR>!^}6CZvL#H50?;3@C@%j;9g>;%MfMSr)A|c1{~aKtQls*a2l%$*`_d#A+KuR zVq-u&@J|z)P|RD}W*P*Z&SpOa**$5T%-(k>gZVFJZZv85co@}#W_z9ku#ITc{bHCy z)%(c-AubC0{I_r%tnWF6KvhyE9yd315g`aFjdTP3v289XDC|&>!%Axgsd#K?Hau&D z6!a1IrjhQ0^C?IGjRXt;hpb_;yy{zC&donfO68EvlC~68mirkI3kep*i@b4r11!p| z9;~_7zWlAcrcgkJ`mak6wPmJH?XIjor?+Ym%0ZV3L^dDdQfbk7dKw~x@50=x(^(D0$r+IPo2 zkebc&Q9myT{G#|z03NmCPP#Ohli<@uOw6>ZT1nlN{mT6UM;ES}y<1ABPU~W_kX~lB zUyDHtIc0^Tz)*C6knjhd3UHXTz?Jb^xAy8zeT%NuuRA!Bz~Oz)KbUP6n=pAP_ko0a zcv-H>(YH=y<#5aFdI>;}AQ)oO9*^mw7H&<=Ml-k7H8B0vUibi6^6grWVmsV(Y()ff zZ{;{q8h67~PT>_AB|)^X+99umd69mj*d~Te{g+3=Izs@v!8VzEMMIuPDg!b{G-svF zl@#C%>{>|O>LHapIy$Bm50HEM4cQzEM!x(!gM`gQ`4~4#AL!yrU+-B|%A>^U469r@ zBW`$yiFXs+mA*%4yS-B7!M`a=zd0H=Q&LAP*l~0{orE#H;)oFM=&oD&gGJAl5)^TDGiPy zVYP@B9xi;h>J|F(vn@u1gD9tH+qfc^f2||M*pGN4b;CRjB$+G3$A>%LcW}n-Go(P` zaEpAa8RudW?(CU2_^KB?!7|uCI=}e3n1){&_BH40sFtZN-Hnd$T6$a_=)#*z3QU{6 zh07H+!Gv)M6gF|8Ka&r8`4>6MW5WwHDIh}Qmc{t{63e;f-H6g$*3da)V{XBB;>3yr z@i1ir6jnfm#DmSJnO%E~*M?(SJs^CZ@kd5K*)3iOw|Rna`-$UC9z!qrR1(K2hv0mO zTkju)U-xp+R+`1~EB<#*KyhPv-$!uAMmLY*UBz9-H7V<$U;gxSI-Zn}7{7<$PIcMK zB${kk@&_BLXC08~2S@ck!3t^o4+1G2Z}VdB z6L_6vLeu#fN^V=z@bc&;h!TJ-24R0)R-4k8Gs5(&V!iQgH)f0LusnqTo7}6i`o{v_ zmvLL3_Qb6Nu+dwVpLl>jxDQp^e_MPKt6JNETf;g z9V*eREYoMd#}tQO?&mcqNU~uXrePPk+Xmzc44`B}x}j|NR@cWK)0DLc(8JaDq%y_z zM#7?XE!^Iv`x6xj8bH7hU^m=4VO2}igtY!@|P-cyM9 z=)`JczY%Pf_10KuTCmiim=V({%5n9}QAmIc|q zXvJCAHqN4&FZU%&ZgPVM8v*qgfxE(eIVQ(bm|~$O{lgIxwjC4}P*2;XTWhB^{`}Pk zEh=YaC}?v|SQE(FB=z7=6#E|bXzx3dIR9X*Q{t0LeIWl%aEE_D*fU0b!~?Iop6_`T zU9Vf3``gXfG5prwY4q>tZ%x5@{iG9n4^aF?i)GVyOy-oOJy_Dk?2;G$zxbAsbiW6u53gJ^^5ri_ZZd^Ui z`BgMgHdoEk&fA=Y^X}fP_q_8@OwaWRFZ;NDwh;MjPe2UYr*u89c^&kJi4!lVug$y8 zLUgjXMz)voO$1i(#;Q*LhW+&!A}MulaoI4gpu8{t@VMDIdp>ZAfqNQ3Nl9%lk$G0i z`2Wpn2-$ZMs@BZLbZ@JlP|}!Peg1 z10M=BUy#Y?ZBTP)F>Nu!jzUxdww6Zcqyw-haY<`7NM=44+2i-~KEhY-FNN$NH>^r= z!Nugl@&}nD9_g$rR{X72N~e2OJk`ntvkKkWc+?~35GaB;39NL*O!Di7pd zMlcay<|j=)U2jdEy7m!W9)|YN4*7l+rd9M#?{l-FG&Zy-^?B13^CszP#AzOjM=wfM z3+O2N2wUm@>uw69jZpt6#!!gQfewBj8N$K5TZ zyq^!aW~6L@8sB{`4=+ioCKBV5=VE?ql_!<;MZjLf1P%6ULF%r)o~FoZVHM@~lR@{@ zZHd9?C)mjxOx35YWc9wG`!syVg;1MWYI8G>>u-Q&x61b0*(z#ie6lE_yG<47r;gy$ z`!*I#@AZFg*iS25`(C4pn2+2Ior5lrM#|!t+IrM?U}*zmDM~N8)dl3zT^vy53S*;U z;hjxI;6=7z&$w2r#(g01h6~BOIPtu4OWmR?=Vy2m%gTV4w@exM3=hEaBA*_C^Hkx1EHS3Al;V{S6jtr zu}XtlZR4@nD+Zu8gceg+^d&Q-|2uKv%xRl5ZY6%7YW{_%s)}V=&3L5bvnpN-Y1O)1 zcdPr%jaK9;fYp!(j9~$dTPkLtGs~JsSV*{a)LedIkcx^6mZNFy8@&G3)Y^flK#4?ijA_elVuu4mki$3c8k+*g@Fw>EdY^Cg z)7wO@Q{B9d)%>%HaqbYicf9|4;)3~m{Hk^n&MX5G-}QbShQmfO>bR&8Rzy$J%P2nI3uTg|5hb8FcQnL6EQ|4$ z#zF(4CoAUV&imrCing?ELpMf0NmT2!<0o&t&B~FT`uX?z&LXM}wB9A-Sflo)aKW#7 zW}tne#G(0lWbMQYdl99@WvvA;e?pgjLB?C_9byyF1Fz6DI?>z*Gc~a;5Ujme&V`n9 zHP~?aPlq%5edur&`3;$F%ShcMqAu_KO2FL}y$MAL(yWM)+5Zaq+~xzHu?~9zy{6m> z{*@x2O&?1`AXeFy)-CW||z~JrXW7pt)XE7=2ugTi8An^k8 zQqwuj;9S}^vlpl$MwXS9HBC}F25_Co-az+}rKCotN(x9^|BXL2zg;&AP&J}n0_9R(q=#lq zk)>4zDEf#VnTquqT(U;(dCV5Z0dgb zsL)b5SYT{HU@WIE$|~$Rl&z{&!NR?Eao(UlT8}1re^c=;uG+-t^}H!r6MaE zLO1w;V2`)7H#B9c)B9CFsu|=r?jiSL>(+0GtBn{+>9NSYp)+^fSl7&G>Mm!Si9=@8 z=ZvL-y%LWRvHL|SO22K~+1)%g%}f}Gtla_N`O}nOL@=`6ee@iL>|6G1i2hcJiiLA- zaAO23I&uY&l?6D}tlf_|y(H-MfgXNw``V!ZU4&|z5P{n}ZoPUCXWvb^uPNTX<#$5T z?p}@zcHu4l*C37aaI5!xKWuJ*yd$g&l%+%uYJXs)eZ+2cR#aTH`AGAN1%sF1gj>{|Gxz>d{zX(Cqht&i6IDw4qMItB1}45xA*~thQUbzGgcYaDSH3xq>zuFc-L?OBBir z=yi1VG7Z3N4@KE?us|))v`)>U%Q`sSGXNSQI#%90>_gcn&s_F;ToA+z@9BlQob^4d zc_7fx=8R{I1&X>*R|cln=UvoxhVB5p6@kBADW09vA@G@B3*t>;rCCz*NHY*P`u+H%&nYyAo&z zjj+z}`}s`f->dsV#8gQutkj>)WC~(s_DfEx)@z0?l7z1j+R>!^vv$XF!Sxs1kS=DN zs9}KOKKJ96`^>hUpp!gZPDaxn2{Tyn+29Ah3S zJuBU7=1hgz_kqmvwhGn-@CnL<=h?EFgwjaTNj#wP^1wV+$+8WgBG)L9z_P`XH#zKk^?D(1PG~3t zK~urU#SK)cX1Yind$_EooB;|ZFf0(ZXJNEJALvEQ4dOE)N+k+*VvfbEpW4$?JmH*L z!;vUOG^UIQ_wOOZXE`GUHq)g>U!1LekqG62I==qCc1rNu*ncAtgIgxJ8!8qfWpgI& zRgzofs%kz`8)|W*IkV%jm&z}m3~!9Q22)X+V=OB0uHN4h2qjnb8OI)9;}{0c{j zWjKPnu1yk{dxuF#YrM%Fa3&;nSd^xx(KfTFbMr^be=#<-=}xrgVq)Z{rhS!}-Osc1 zj*Me~gis}~m1O!Fnv0H8d;rb*arpzxG^)ihX@~&72QM4x`pz$u=PEOvtFbdew1?Du zkQ3i=d|_hc)iR}48ZLWem__1}*IL9NMOXsrTob!E;fjP9b>v+Z)HPJbcCD?E=%}Q9 z#-BCg=PF*?b51nRH!HJWsT#ZXjfhu5j2Jq3(KoR2s!mO$Uwb1A(2UuNB`RWdTR-Rd zgWiskl}M-Zqwwq2pez*?Zb1ncyON_)HsOgA*YPic-rb?3HG*Ts@>9%m=SAWba)`FKLN665alBykx~b zGK`XdtW~GYgva#7&u&CA)H0p_5X^qcRjl`=d$a!XD|#{pW#|zTwoW%gb>A?X1=Uxy zR^8BTHTEd2K4qicNcwN+E9bedn1|jW?zCxgjNBryV+5%-fVVO}-AwFfAiqc(bzvWr z5L7ggOISn2Fi4);&>Wca->?=-vL!TPmdvk<^&v44e3gqH9r|WDmi`of`3;fNyt$w; z1vX21)Mhl14-f$jtwT0&LHGd`$eXHnEb0Qrc-FWIc=j53s<~1?Ln}v zyjW_qCnAx;)>#QF?g|KX%>3nL@RA^wtX43xYy!y01Q|?TnJ5vDajYNOyn(VN+U~|f zlb$uIngAskx2#^}R7hMPT*R0E!pi!M*?1(uUm@|5jy{7JR-8_^e+~GKf7OEpG;*v8 zPHf~ZiNHKy{i=g#{r5*nOJ0}xg;jshIlk^NcOGxzkcyx4%q)9A7Q)%bGHuroh}e-M zv_6su-c;{d=xuvAWroHJNtwi;iWlJwsMe64qX&(d(F)S*bD@;fDMU{49r@4nj3rtTTV69;Nm#l0>tp3v^SB2StAe))xxh#gil3_ z7Y~K&A)N}MQp@L1tg27GqUlx7m|JBG&mwjD6lS7?NmF}<_`lA#+JaULTK19cdbk(9 z&<~MqaU-q>EK_OiA+PsJiKGq7luK&WsCg)naETpX36M==uUWe5hWvQ%>%T~+aLZFk z%7l%Y=>F0Rwx1Ez&-VyFPrl}I#G)@DOn&tZXgFOfb{zd$OXC{#Emk@kj*_-Bj4AdV zRV1~_A7;9Fw0VN*IJ@?AGLMP;%_Buxyq$$4fPsp5jaY%;A!Pe2w9+*X_Yq=aqy(u1 zs7OPPss-ki(|opAJVln!#WxC1;>!nap@mc{2{SJ*YnBAb;+3^`fcP~(GH@&xvX5P% z3@QzLy*a7=dG?`qI~@`9r(@_CR6(e(JT6HbtqYCg$R`PRr8_Biatz$8m8XgUNUJBeJ5hR7r4( zvWc!q*;roB6c)+`@(cKj&REHtGL#EbQ;Zt||(Jf|1qn`K&AM$#Q0zJ7~$~AL| znQWE!pH=b{jkBgGS14+NtNZp_KFmg0Hc7d#7^|f`m3&?)TuJ>!!6cQ1H9|EZ;N&`_ z1Yg;uyi=wmW5eU+)3ni6!v@U+rk^F9&Ug^=pY8qDHA#O=AwPnlT|rdEM>QMjR;4}H zF`Un{1E___`7!3Vzj3<>L`Aom#5qkFd?!RHV97vofFouej70Iu`4nk%Syu8A@mbv( zy@DHGCz(VQ)DPVa*w1H!8S=RaxhDY)LOR;-$XAK}Ej>rWIIA=Wf4M|C{X*-DFG7}{ zRe&ylr;MX_J_8z1ZY|>7LxBM5L5h!qCE?!74tNCOm8xpBHl-MIlsZFnL?Z4s^LixDUuDH<*Q{xAnzTH(<+kH~W7rr$aWO~Tz8of4J!N?@>iMri$$;{Y zT%CCNVD2iX<(G$lfzO2E+xD+KW12Gt-vhdv&WAUYKOaT*;t`-+ zH34QP+kl_{$|M!tIP%Gwv;PLK?k#yFbwZ*P5y!FZaVz>NrKxLOI+YHuP5(z%*yl4b zR&zD#?v)Z=F=)CLmWN?QUD##(Jx3iiKM59*}7O;5tP{D8is?J2WNQT2)SOt_-sk3FlmEm?Sa z&yRo)LQeF>bBNK}Vt^N+b(tBzo;DNz`$@aok1})v`kxIx%wtC`wfS74kCY<* zS<}fHGctr!Yry$vGkKWZd_)x<8(~qy#x*2#R<@+R>d$RVjbx;c9jZb6xN4*1t3*6# z{|q^nL94C@v#Wq{sA6Csx*H*+KRt`3X3E1Viy z`Ng8#q^yWBrgceP$+25%2Z;&&jV68^k#~ZW(2W`n#a245nQ7sY>VKftO4uI@PB2Pt z&;{fZ1!Ww4IgINV--3u+Nj>p(`91*~(VED4zP5J5{4`_EUD}Hw`MHE5PY^m z&1Xpyco$(96Rj958>&08skr&Em-}wU>Y-s3gf>%Iy84BRj31tZDBKx)zo0Rx6khtW zpM4LfKV?VaCr&8#-}sdXB$KkH`DX`KPod22j6Y`gVj>GpegkFE&^v#BbdC|j?tJuo z^pzUAmX*$h2G)-{ea`?Ed#4X%rpxi(PxkkHpp?Nn0%wwc}RWFLaW(v%q zixuGNR`mkK&!PG${sKqN%{PF9K=W&)s%Q6GyvMq9PwMfg$;Wk1;3F7L%!nXz7h!pV zO>M7@!p=TG*jZm*%H>3(S43K_giyyGumvg5-C#9Tm4|rws}_)#fnU+!3&7`3sH>zJ z(iU$qEb#pgw%#%<%I}LBra?eDrKCHhTLh8Lp;KBqhR&aagn)E+cXtT_GPHDqFm!kG z-r)avujj+_#SdK0%(>6mXYaMvUgz9nLtI9>V17zX=^km-7QMLs-4CZcoz5q!1xX%a z2g5_1vtTJn?qWkwlYz0GFiq+Gz#qf$d`~RfwBqi$F5j-&9PXmyR-5wEcMmf+U_5s? zs8=;L5U%@LX z!=f%(4QY~J3xqZPNUEb-I?`g29C#|Sx*e6mrevz(H~J&|xmX{RRwF25|6x-Pcj7!| z#1_pQ#Eqts(GPL(VPTlLP7j~q63O;OMhMWZjvhirp$GpbuKE)j%3h7tzi}oafS1Ea zw$+XPQY1Ct&ccI)>|Q~1MGGwiljFy7|8z&?KXmwt>vb3!GDevRMFD7-Fk2Kgwf%v~)vbw{dzJ(y+i^dKzQvtUzX}h5h=L{89Mho4K(37P!RiG%urPF9a1N)bOl1XNLn8>2VAGInXva3X?`u>KPjY11h|}bs09etV z%c9;SY(P0`!4q^b^>MfQw z`6|+(oC&$a!TCoI<~>7_OJR%5V48X4D7VI?H_Po?=S3hCb>>&bToaI%Z^ob#jUY(D zV;b`W`W-=lHr0K#Cu8-$)7$zsN(Tv_PmddJqH}mMRzy&9Y#nt*_%IlCWyiT_Hj~Web+fOdR-17p zNJ}N&2(h3fN-Vr=1!HUuu`2k1fb%b}=+89>eR&%t3@+H#*BI0OpsM&Hkp?<_ZE)!I z*RZk6{v@F!p@pzWj)p^aSh^waTl0@SBb21pv5XCUpd!t_9p6RaOW&;eZ0Q<){Yo~z zJBKP!ZjT9?|Ff?Ipc7zLQbIIHk8X@}V)Ztq(JyI}aWaB@Ijt1Hcnly^fnzY2y`>PY zr5ZFUl~-*}^WAm{((4G)pY|aB@XIMs6NjDRr^k6md4=4=1%lPj$mYeT6e@OK7&m8{ zd4s+%0D0~!>ekswNyZ4Cc#z!R_cvhIcYB%IuS6jD8DmtJ-(MgGeJTK4l|^I3)}2iG zdRsK~?7o8_QXMpj$W$^*27&CwgXn?l{%#;Z4yV98v9z~8E=}C_g-s;H;w^IW6sA#_ z8}xSH=FUESlcf+izm%w!Ssu^37MMZRy#&Wc;3>wTmh?}WvS9>;(lnE;$+@se*4cC3 z5+1ZuO*44g%B^4x>6G1B`wQvKQj*8CBc0CfFg{3DJF#@*sVKr;!ae35M^m%7kj988 zT%YJFsEWl0Yx@5&z>uS6A*xTa5@{zc`lmpMbQhbViqu^_Hq#Tt)B^jq5JKBE$52VR z2<$u8?8uf#8nD;u>#VY<51_Rg_fHjr5<2iWirZFHi|K4;dwNWY=0F+d3+uVrmcDY* ztXSu;12iV4(okr2N`8y9;BX>-2_goJUK~%{gJ0*^=#7Sgf@f z628-VL^WEG?YAX3ijEmwm6nD9*q?;<#oTh*W*2(6a7*Yc-Y{p1dvWgOR&PrQo%VYZ zagxaFDxj#;ElklrNv-jnMC;979F@MQ%kxHX8y9_FwwG!Ga#vkNF=}R**?;8sV>mZ> z{UgwqVlBj_R;MIZ13&B+wBip}ck}cLP0S=(07aifP3%gusTxhbvEFBK`_A#k;!{)M zU*iq0^PkLV!4XU#rZhP(74O#^>@a7$5~p`%63X%#ic|UaBA+(o5Yu70iB0 zjD7m!^4qt3X6qf1bl?IB`PI|g==(o=?*D%k(0!XWshu-0Q9CJvV-pZ{+{w&B4m;Ro zQ&C}UGmp<7Miv&GWcahiaI>ihVtVdJXmx>#!Cr-sUqsP4T*|cO9yD|zTHCD(6qos2 z0gMnPl>*p>Y!(0>yT%{6oJI3uXH4-H{GuDMo*QxFFM8h8!`@^~aPDwP$=^YufON;! z4MKTWe$qTZ_zy)QF{X^k1_gOaV}m}Sz5K5tgg=ln!<=m7XR1`wuO}xt-Q-?y1!p{JdnJkTiD1x(D_;R zn&AY57#t|cE{A}qN`gDtXcDX0zgmaI)viyD&7gA2atUJtcL_kb^vASL^K83xwoRs0 ziTQB8B?Z|pYVMdsGI!khaV>ceh&#tj!#w&lKrLj@MqPBq5ms~jtFVjILP-ANLMfI+ zI$C5JU)NRPnXxSKy?y*9&fFap{J}7IsOdBj?-K9Px?T%=EDvKPLMaYkv|!f$N1kXA zB>V(bVDw1uK6Pq1!mnS@T<>*uCWb+q2n%uVih&j?hv)hb;v&&kCk*QV^sWsw`Em_K&`Sh9`< zO(29ag0RMAs? z5YRxxr){vpH9WAE%_44-U#YN`(%SI--E0tPS^1nfFIbQ;=!UBs^hY;p9=&m_o>kNc z03Q;B(4s7W@jUC=o9)raGU=I)n1w4ibl2ckx5b&MZ<)>~d975qv+H+{88}KRC6vtf z`jCTkwv&_p9B`u5T8Wt;}zg zABCKL2zob8d?}_|-FE-PbXq{OX zUuzob2R+NIZ`roSmZ{5*Ocwn5N~Gh?J^{r6YHQx3$wI?NC9e$SXEd8b40jQ#{5(a* zSWeO6{py+!_Dy?)*-%0ap%ZUfP8G+<%}bmdB^MXb!X>{nZkJaS-6zTvN^cdic^ z;;CpyZ`&A;gS%4aA1@N%?OWKMY^>MgJ=F4y!jWG@0b{VoSisSgCd9;di(4ysO4pt- zjTCc$tMhC?sy0UOV~{hb7|9g}WhTTl5@;Ia4qeVSsz82Gma_%;p4-5Sud)U)R!0l3 zfirqQ-1%Omr!ZCH;AH+n)#Xbj4foJPCbq!<%|_Sc>u2?wDS`9rzn$qLc+_?l30%t< zx8iZF5G7zwwczcfv~)jRIubl%;5<{IwdGya(LY7|AXvEm&Fhvm6A$_&OMae&y%E)a z)pBK_sjfa=MFgMTt{IwOLe@Xfx@Gq;eRp^}!ka1TJt-6=(ga%Q^EEWl41*i>tNH6f z$jIoFy29!twy2)qd$d%)K|`G^Xh4I<;ijvTa2`1 zQIMILnIyl&&C}7Ya{tNo4l9|`Tl18@BU?B~Y^xcl>%I+?v0K#OTNBFIz1krNXEj;4@j_Z0xM z>DXhEg=8{9Y0l9DC24xksxKXn`!>*D(ELs!btM0PXCovDJ$AyipLB@gvV=v) z`h$-quyy(x=KC4~E@ccw=FJlIiG*DDS8<0;p6<8AwClgbZ#jzI&5hO!^DelP)6WRs zANLGXcvneKliRp%k<53Bv%IxzDs0Z;C;w4`J|S=@$MpkwG1|oLx2ud zcd4xgz$o9QOrGI=Udt0D#FWWIWHhPieZx%xY+nxs-x8Y)+&Hi^{lGik*T2wpyO*iZ zo1_ys3#x$KwYS3^--Uf7FmzJG=>ZS}ltm`2QiHM(cl`dOfPZM+Bw|2`&8t)gAl+x3 zKmb^%U)P9(XnLPKhzI9>ga_aUz+8>mOs2O*n92KTzfg0|z72X~`{!0!f!9eEjWQdo zFF$jBYbor>42o{FY@v+!fMoJnLvRGCoh*`@(oa$ z2kyoSQyK;-=VzMEW2Q*Xhkx6(k0{p7;0e7IF2CXXAkjo(0}dNP26$reUAf9&dl)X} z024M|pP&Fi3Ev+>ERXhdM~!o>&KYw7G} zzU9DVCiO~tAk}v(W>7F=-P^aKl_}3}(CGZ)YA(qdU28rFiDS?xlIZNqyy+L@XY3Kv~J*vHp z<-9rb#k%)GDBe3-Ni3>4`UBgJr${h#^bRXDh^E*9*Fg;|adpb1xb)-C z8x#kED(jX&>-I1cdHWaAL01UIGZiF({1?SZCl*?hsN=k8a8N&Epg}}rzAtdJu&JPj zQHF+cR{Dl}6_nNzYsMyG0$03V00`W1;t69C*qraU#Vi ziDDbu7j}hwMr!3w zGBZm0&Ig3&-WD@%C~dvu{0Q92O}*s5(?9k$$Al2;Jop%(UECOQfOO0YxPjXPf6xwn z`)S`E#^V*!hNZZDC3WqQr$X4v1eK}$Og!=Pg}*s_Xvbtf)*5V0ZJl(gL2{_UEKq`5EXo%#;fSPdI#= zDH|J|1mKB5FBg&xNg{x~Shi;&Q!9Vvw?LxsR;T+xYfXQP#(a}Ud0c%$el2%xKIaQx z`k2@HN6C>>#v<+7S2h0paaWZOEa>U1J|lMvxFw|>hrQm)fBG=}#fy6|+alC-nJbu7 zurVxkN1+CNzz>-Lo&F@!vHGlunWBpTUq89i9nZtHs+^)q+mGpf)f6QkQ`1M2kL*cr zW4`Y#Ox&Pt&NJP;4Qeexe!OcQb^WlgeE2iqa$|?}sN$(F!-*m3u7S`;zx1cx*X5D9 zl`U}9m9eOZ#k08GBl92@K+^pxovbo?t33=K__ycPLpF+7WZwCsmh$5!h{fdJPQzWo zH$^(#>KK_>Il3Y!EPN7~J-eVE_2!JG%X|=MXr!y~;c-9M8@>5GxVNxy!5C-F-2I4> z(M~yt|Mfv&XHRrKrvH*Jq=Q^2x*reXvyk{xZ)-%VIUvnhZvBFGC8KsYHA&xK-o@bf z80eV7cvxm_PO2O{Rs!UyQmN$1ZrRsWf}-yYE`{t(B6cuUE(yyFfsLW2i7HGkvn}&1 zW)F&2N7GQtJj9}`z%v24Hkj}k8_8#s0L-Z+<6(kB(WtJQD1chmC~*iS)D3aEs7E$V zP+DtAqkFe`9oqBrmlt$Ovl%)qh+wU?C=}ppko%g1*F9CXkiS%;93oq$cLtoiHKiSK z9u<*xbad4C42?-hNZ5bMjeo!=ANE|N?HBQ!UMqXL z^YjqCNuhuL@$m7Lh~=s8h~ciLRg0}9v!>9#S_LKU>Gc2c0`%+O3oPr^YZ%D4|LXH= z6U*D8K$rn1^6~MVRr=YU97H!twxwnCUOtSehTj1JD6Wbk8%X_^g`(R$AAhn~hIR-0>nVv3oB+THDDuzLbKhhpxj7;rsI z#kCvs?Iw<5d!R z8oEtT4URFTgBJ^pA4Q2)`mp>CgUTVn>69ncEsj7z7R4T#u(gv`sI`$GrmUYV2MEd zX#-*NknAoIAziNgdwz{T^EhdIg3!UGi}=$PLPsIV*js@hB%@pe{_;mtkLf{oz_15% zoj~CDjqo81Ahv)KSQw_9>wt5NqfB8*YmOTjLEL63JE{(K(`~gmd$C4Qn8+Ig-7C1& zL{`|3!>MndF1eFRB-P54-8lgbRrtGEFyhNd`wMu!+-SgFI>&ROtp742?auD{HbiO9 zREDQjUPTAP?B*3=VGRH^rozYrZ4@<0f!9R&#|h%7X2$<(jkblYXmjWDlq`OWLC524 z2O1pP;2~hi7}>XEjBHtGGI&3f$?ODJ<-aL{ZTQ$^7~kUlDZztyCP@NM!Ll6H5Rj2z zI-NQD@H$e0TEHzy;I1h^Wr2d*K1qy9T&FYdi_kM<*rxLR3x4x&>VPcr3q_RGfuUP# z6>C-5sB(ys#J>ol;fpNu%gVJ zOI4l)!<1%Xe!?bCpcgwc2&bu;JSFL;&d*F9gH*Y0hH9gR$cBi4oPlV^%1WD1-krjE z!xr-gDekYRX$+gYi2BJ*Dp!?D+hq* z<$^wtg^aUB43td^pkE_I183=icp@9@e>w&7)P5}+a9ttjY_zyAHJ6nZV7q#|zs_JW zS`i&b;UO8LgDlTzWpX|o3th75{a)abwx>$nEg-HFFN9?m7V_(3Bhf_oC)G^srcP0s zmH!P(aT}IOxRisFq|}M})dOO8aw>22mGY%2_rLsHKnR$=+8psRUCH{WBBTVkYZ0wS zhbWI=O8pD5GYGWmY1fAv)!A%EcV&Qr*wUR2Xa5De&};l%Vds~G-QO-LJSb=;?*&$( zt}6zUOZ4QuRtn;&CIS2EJs@)5)tY}FFs@h7sjEnS`i4_p8NG6o9>r;X{f*{gw2Qeq zTK-IMx~#XQlVnvuy7+jnheM6%Wuk~h&Zh^Orv&w(^Ot4h#ekuxw~L3tt)5@9wmztw zFZto5vD8VTO@jP{`K1jP60QPVXjLftm1$Q2C04P<=X}uzq+3hL0XEvY&8T4}n4FW(f$+*}AC!r}qEo7X*cf80-WplkolPCOXy;3qZAF|?7KCg4Rozi zU6T+40}c>V)SD=Ie@Hd^ViLVmr(#UUw4p$Q&^+&Ubg>_Citn4FxV`!TjXk4ZZkH-+ zssJ&|(8Ka1cT2-IdyjvucIl+-B$E?FC zO{Lm<7?~haVl+{9vNOx#GkFCtkIN}GW{|eFMxR=9OM0=;O`Aw5ee&l;dr-0j#^u(If_o@ABU@B4&Uek1;Jlzi^lV&C?Wt?;7u}u-2&2M8S=epLaqe*wbWyd&6AUy+3V^v{>SC#9@ z-6nwAF0WYhWh};aaE|@;I-r7MJhkgc8`XEGz?3Z>aAuU3SX|J&W8E?^ zl2$30*8KeeP#u-m;tbd!0=?bu8xf$az$oMjjQByTs`Gy4|I26gK@uj5RG@@KofT{N|iR9IHSK-A&0|Et}p21JBmD&MiPhd}DWA9c7!cQU0oDW>M9 z)^7s}0CXT)PbSycBSqRz638>s*mD7WTd4Jn+Zlz|E0%rO9M-EdDyh3ppHBGAonXN7 z&&e*78Bn5KLam?p4%D1<`QNTA_AalTsc*%VB3FUXTHxc5W0E>W+y?;46TNGbin&F` zqt~D;bSGm5y4rAZ@Kx6O3}RxE?;f9RHs+sRAXh{}l;&;(JO&J0m-#B9pyyuKZUa?D z8sGcJ1H--#mC-;V2Rd#C_;!T+*i9S+F`k{yZUE;8x%}_S{6j0_08FU%G^Fk1YUZE6gDPW!zGg zLOtJ3o%m`xGLg6QjJp6cB+MapMFt?>%q%$2guj?K!qKN(8cPE;oH3JIApSRi1V)Ud zI|txxm5a|y`Lo7l%n=}dc_Wr8v4fz$SN@&FH4sO4*`Pu(oAu-cCbQU1Z7*vrpw>vy zWLr>9!uu%{CJVa7+)o^(wP7jjYT{QolSZb9sAQZ9Wo9csH|k8T|Er6#7b9~=OCm&Z zP~%Nec=JwqN}_uYcV%NuVf!Aa$kug^+s(@*_BGF}ffgSXk?eIRT7M1dPP7Gd_Nd!0XbU$=VptvKIGYK?@zpgYBnV_5AuD$Y8 zg?70I2_Ko2eNq*J7p{=nCjt5(0FA{X*qbwvhuyRKC9qmlqY~Fy+#`#;+016mYi|y9 zNS~YldnGJXi^zS-)-zNU6n@T2e~Lm1$qr%Rc8{9@m*N^QI4-vsVO+&+_JGV$t)i=E z*VePIcu-zR7lx(iA4I&?Xi1`wQuXX)0-r>)obk!MvuP%cIOgk|;OI-jNad?-YfJMB z|3JHHRZTwz8Ql4t_1y=C`7-GxP2>5e;Oms_&2?5{Z$&mJb^n7{#D@#qHeMP}fNKH+ z16(3(z>?-6r@VYBRA^KBWvm=B=*8h|*t}Er z!)eahsf1N2Vk!aS8=xV4%d2}IU;dXe`L9P=o*mX&>c#uwGa$Z5fhD9H{XeX9Bll!8 zH{gRmP8Q;|P!*0=F$7Y>l~KcIPEmWH{V-E3Hp*wU!u;62)}|@^?D)h)N#kAY%lxP& zI07!lUL$>54k1I~dr8lW^2Vhv?K~S*es=O0kCz}P1MGMR*TyWrF%10piDY(TOK5wf?2wjb02vL5T021U%f_6QTy@C#sOkX>fD zZ!QQTm1j}271j`~fCHn27|gU?xc|=oq?bNgduceEdnME$H7x-FWDD5Ioa0;ludpJ^ zF~cq(za8eAxb=tL6vi?88#m@ZJE>46VZneSjva%r)XBs{Kr;w;J_~Z;%w+a`#UrKr zhvGZMz$-WAiw62&puEKG|57X4df-hQh07rDQZ~>qZY$)J|5**xcT;WY2~$VnLX2FM zJ{aWj$Fn9_GjM^`>6aO^@49_q0NekNIWgkVAYyI#ao=2)mu4_9GV zKFHJY#>OXKc+*YP7wAN^BEY4g>A^(cxGTrEsF*G43K`7bkBn|KI;h&?@dJ*8^?RV~ zn6!iyoKvnIUAzzVB&JUr8uV{R{jl)^$hOP2hJHafNBdm0p>6S zb3Vp>^9j&rD4!;{JsSJnr!_vIXV{LOYH$~4s#(JD%KA_20&TO05k^DFm|OT&U7cT) zC$COxR&F+Oo+&ED&tj@chBSmWgh^zbP>&nAYDV-QapV!F5$g`u&#J^Tmyp*aWchQT z6Q*^9QaFMEp{o2ViQ|dWT{BJP`cnEqq-t8v5J{v6fEx?*{COb-1LdgfvUlIk_OPb$ zde;8|u@Sch5oRy02M;?*8KkhJ466?7TdN5=Uju`Ye@A#Rr35Yfab#7_r5prVTI)ow1Q3yKC%^!;tg_ zQ4zfYjHc($5}8VT3c_8T04ZI!aZ`j8QL18X2ujgu1AHl7!n%{(ycuX1C5PllFM6rdc>%;2+j7E+>dn@$VfxlR7oziOidO0GfMOTJ%rXk*` zf=A0fky!5TV3)2OoRZ80$%m7pmhpK>oJsgj3Kkfo6_APKoNS=4R?@E$dCukEWCJtC zySHF+I~pcpu2uYua3KP-*ciBpJ?i`scqS7VP&g})0iJO@3SVm#sxinr=f3Bt4NZl8 zq4sgK!NSAhnI=;>VRnn|DifzN$N_09vzK|}$0yZ2#EMR%A8bn=h$J&)J(~WdcnuhJ zPVmP?D;}FM@+a2h9PGd;vJ0@T{EoMnM=C=beYZYGaJHi!^Xa)J z&lL#`7soZWqsL^92E`rZQL5X^)ljjA$p~>7>SbZ><9@x}N z|6##Mm(RW|JzeGVL(Ox0eQNQ^S2TY!t=WrxZ72l1d?Q~}uK@x?TZ^S8^Y>*_CMGvr7Q?OCiS`JflCQm53!a(JEbAN8?- zdauFPTXqA=D43}K@pSw(IP9Epz(FMY%+%|vYlB8rBHz!}Ett#(iUYf;6m1~&M_z>+ z8OG1j&rx3yp7AUZfGyH4;^~$O@`K>@%+R~}9f=z&l6w#vkml9hDc`-`(?qd`V`XVn z>6ioJ;Qs3A`9-Sg7wu0cGh0J6@87N(xb?n9EJv%DoX-)bV>!&83<^%hO4KcFn3|OJu6nc}?@qzi*zY=vQgOf12fJO_TW`I412)Z(qM5gbza*$pW?B z8Bx;Ym|V`AX`>E`BSRjUM^08>34B;s5cIkVAr*F%R|fZ02D9^!_AWby0Ec4X4aZ`E z^_-%^`9r6#sLm>%{VNlt`q?a3vx1I43+@dfhMPk={jEz&&J%$PwebRFSEERDJoxa& zdqpW4)sCibY-`*waU(&1x! z$4_vX6yb29x|BWDFZrWfzlyHDp|92WRo&{TThJEbuDX@0bXA{u6LCw}H(!;t8wc^n zcX2biS7k$|)lo-i`-Lq$4h+iB@B>@n(&IE#=@o+L*BJ!KCVI2jYed`cwqYp=oRcDg zL_Q=m%^JQcE3+Ac|BQj=Z^Y8)rzu${6GYN8p*_DKK!5E|055jl>|L1iUe4P58yF1& zhuTj)>7gG2-~h?b(VH^GI-PqT$`ne8SEQqRqtuJMV z;G9Mm9NLBjywWCtiU7Xwy?0v1sIne*2MmiW08vUkgYR*#73Xjs){;IeN*76byv2iN zO4jwwC^mVaDOn(FG2><9757m8{Ftt$%Y^B9PA~)$$G3A?=Trr++v|_nyERqb$)c^61@|I8@z9X@ z2{YUhi=Z5D-5_gHLePyoaLLB88T;;_St#t~o_`CZh#W@^5>WaX@tz-V3K>*f@%pzc zOpu(qBZA~l?6pVbT!S}k@w#o^m<4Vf8j3K#kd-`N9^;eu$BMto@OOdhGyF2N-C8i3 zb4mN))J0kYLL;XSP*k#o@tP|W6)!VUvQ$<}^X_gG8 zCq)wv4_cxr)lemCF}Mep=uHGfSMo27GVeG-{XHYQpj|3mf<^)ka~1>|${{3I+P(PG zPTXhe++X5Rw?g2ZvS#XmW8mV?%hI7Cs%-qxHk6yr>*41&MSLyTebW{CA#v^5SZYXu zrEyCE&e8m9IWoE|c?1kvUtu5r8eYy}k6O$WF`KoZ76BYNX-sg=!GVS6)8IDGm(X4^{wxWHkfMY1&G-#N^L%WTm)q8&m3JRZIi9!Fl)bB<8^jUCy8 zKu8xhn8!EIud}}7J0FmUGm-Yh!pS^6F&)U^j7Tl0l%<20`Cn%uuQy_e_daT@9rKzW z5LuTfAM5d;`{Ws6*(eereW|yP+4(`pWm6Kji(FE?xjF=4r?2Dou(22rNE+#v?hg=t zbm($0UrX_GPXENke=Rtr!{u4&B(QE$6+7B%uJEqUG*uJvQm!`)zt8{sj0sYIcLs}# zOl+jxLbqRO&y=^P$8rHgrR&e50fkN)E(!5TC+rd-{(Ne<&vzG^N&P(XD6YEB6GPl2GV_TU-0s#z`4@XI~b!OgWa*1_|fS5uw&TV{KJ|^{#7~=}d1f z2CIqO;Dxx3Pnza=`fUEfC#SGrot-!vRsJG(#U}@^UPe+K8gfgCo;L_ifDT-=$@Pk* zWrQxe5PYJj0}9(Jm?;o|6S!uiC&?6KJ5Om^Sr9f9zw&R}WhwsmJY?XMQPpcI$T~s9 z8+E84S@s8TfSuO(zDYYS7ZiPHsK+CEe7IpG$u1!v8%Qn1 zuO~E%VX0|c&M;bZj3(_-V1h6@8)R%(^hNb4nAbOtO%onNqE)=L<=T^|uuw=0lH3Kh zVwgf#b7&_2I_Ot?8ix|ztEBH<(zXuPFL0|@gT_NVMH+JbQ<9DmS@vbn92sFM)XcmB zKmS#mj+7!svx(wDH5M|GOiUE$A_8fsOJ3Zk;55&K&!1&DaaE1&aRDv(Dm`}vqeQtB z7Z+3=ts~gB_ziFh=~c3jKB0m8T4=?d??m`#bpA-^hw{edmXfn8kBb(I>`ZGAzvf>z zhC7Vyz~LsK`nI81gRGY8LN{9kP6vVr4Xzbtz)JErsT@1?gV)vjT)y%9A0A^OT7a&(J`hZ2Ou~Cz#%S=T-drx2=MzfnEp}v8B{rdUeCFsYFup|+uwmyU=P+z(zPiQ2i|fu6UVkHn4&6tZ z9M@y?TTb*69h*(O1;gaTKCAi*`a05)x}@a7d#mtK_+C?1w#CfL%%Y;ADz12JrC+W1 zTrH`!qz}y?2^}HrZ)zjjcRuhQbv`{Zi_5|#r#+$1Tc|z_ZX{P^`V?zDt%}_V`VUvF z8y7RsZ_%8+>r&}Jud`boij~m@_*LGIg}zc%1Uv8O&Aecd$f}Uiw)7!z%HoW*yTe)# zVL>fMPvO%RzKRHP;tIq5tFA8TF)PAE>HzW{a(~D5zPSz_nR@f#l(-NPm{>Z6&zJji zj4P2lx;{Q4(SAzQy%9FyPg+6!aG+N~=tOY28!y1%(D{AJGxmoCS~DxZ!CP$L7MZQplqr{Hb3c>{t0001xf*5=X*D7qDrknz44ud@eQPg%8cY zo-bT6k=MYv&grV1n)qd22BdgaM|Vx5&s;Ob5ZJEZRP#^PFCY01NaoM~S(vt)5jD#F z1*C>FwH2l;CWw^mW9Iqt;>9|%0D92#17#Fz0n!GP17G7GiV8m_r{UXo415U1+%X=? z$`jeg{^9#1GI?>?5cx<>aoBLTpxE&V+Hr7ubSU;!Uz2XXaIGWiaPQ5bQ}VIj-+UW> z*I35PE4Pv>u+m-g-6Q!3*HWXv*m_B)*{#=;>*KaQU78q@XB)byZic1Bn=#RxF(eD# zK2tu>GNLP!ZcayDIWC5>JCF9>yBlh#$>leclFSkO<%<=4uut2abxid`$8>U;Ei~2T zXkpnvXbkMC&z9UjYxMfc$Hk)mXw__?+B$e7d^9Vd&9!I{edEE!u%Phj-B`aM1z#p) z@=TgH(*&;oE@}m+s$MU+F{H~2b!2;dAEk|N@dCtC?Dv7$EBu*#xC@MbFFhNSwN{y%9Hz-DfWnu`O-foPY;jqUIes66~`uv9y!XBI)8&(dc=5 z*WS5#(j#DpbSmmOuVFZRgFG0ylrgggtzPiC`ye3d70Y}lL~;q{-DZS&BflNZ+>dM8 z&lw-a@f&!RN3{ed;-wRrMjp5ah<>=gCb%%7VX@Vs7mf^Bq7+Yw5f{n#F@Nmz9>AHh z)7CNNdzZ+6NPV*^hiMJ=7Y+%jzV394`7C@W&h0cY&gvg_SeCZ$#B^&a)V#m^3m6tZ~mfd;DdD05Y=*&`Is<3cjF-ZeltTX=4Yu7aP>R>wZqxR={&Qq zz&Ipy1EWx3C?aJ0ZuQKljz3;-&n3N#GmpCq?1C?C8 zp(zJ)Vj58`{S?vyPj{a541v%NR}%32gO``0!JdnACn+~E?V}2IyTXbskLUIBTSs(_ z7p{*)zfWSUN>U~%OBS2nQk|FWBZI(uOKM7yqM zjzo_;qV{227iLoPz|}inx`AA6fChNeZzX#gBm2uXrwK=)u)^uv_t@j_gUu~7iy|(` zil?{#Bj#opo3Q+}mj%!6pKYA#vpoX1I9yJuhg*;Yv*jR>EH2H<)QAivD+*$(OfVQ9mI`J`6)2wKl=TKs3mg z*boG-)D(V5V#u0@v;eQCKUMmJWO=xUVGIP@#>$7eO`~1n-wh$B%eSTMsiuEA$Skjl zfz0#Umwc$2D`~x;bL&>uoTGn9e6QYw&nt52r|9&=dUI3fJ2OK}3o&}@G zR4UZWaUzxsA!w+NCPcMAgVz|AO@I3)=5cpEHlQ{{n@P>)et9>s!L-mwr#n}jDrRGt zYC3pj@{9(M(@JLDpKSq?**&Ce`8J`ql0=n&_F?=xtm^rYKWCpQgCmM)RxiB1_YjdH z>_^wSiRkVU;P1?wWafhzDhsupObf-}b*`T1I@pxw;sJR{4GYZTKZo)KcYN$K{0+VArH}*24^i1b-(vUMWZGa6C3>-{clJ5A*n82 zD+IowJ)|lIYT4+3h7sU$1V^y9S}gSrYPj4E5BN*o1Yl@}5MF)~rir2{rim>S#l0-r zUGLHqF6vd=<0~&*&-wQsN__!h$*&*;I^1pk(GPlV=jvt*`Keoul-BXYn$DdF=AAQvspP~C$aAoe+Z$tb0j{CcO z%-Ci-+?nxlM@Ek6!8eONgOLgFN;ko6kJm>Yx0h1}(|_wDBO~Kz4F>MfRr|3q_@OYD zX)dHDSHg-9)UJtsPiL^?&6gFXWn#&nTm2rLo#bzzE#~9)-u7aNw*(jf(&`tvy*K>R zvV-q&my8Te_R4rWy;@phGGl{~Yms72CdtehL=a1VG(H%hI4Z2)}0jJi8k zVvA44>PZRH3Cra6@PFSFU4U2kkT!6+eAo^UoTLm>S7D)Z|!ei{~8Ul6qOX8v9yX#Vjw2IDN7z9d<=qj z>Qgr8d|MK$59PdY7C%t;pdElF3x76N;=_O4k|-#QvX7L8jqy8nK+o?l+5_S*ze||u zFxA3tvNivs+BgD`Xt7_Bxha9wKC%!)O#65yTi6o@JZde)5*r$=!QU18>A^cf< zOC-CipE%Y9X{2axF0?e=5w3ms->%3)8nHg-+Rxc=!gOK@2yzmPvJ0h%Y8e+1_aLD=>KYUU);#v)~h zFK3l5|J#XJy_A7>1efPIKpO6gShMJAl)8~o@TVx;MeCk!{R4PeoCC%gO0jnTzrMZ# zDypvUcj%IqZbaIlyAhJbVq+kVd+<%nUt9JQL?P=!JztHy&8(t(Y1S-f*OwDA~%-jBowG zeDb>&$<^tJL118ih%hkrO;FqmN$%nvn#I1$$2RJ|(Y=q>^!1W&o z3xG!iOh20EuUPv%14sjGgK0$SUG2mX@8V75wcDuH29Qv7^@|3sY5Rcok*|CyLA)Hq zAUd>%DCt^RwV+~T zP%qsx38)c)`fviC$ao{T;;K>y`Tf1Y+u-*-%NzkBEO|UO(kch4HV9}O6PMccI`#3hFpzi1Z39+&KR@Rq_j3W zcilfwb$G${N4M>Sk0P@{)l?-)B`13d1-~gBH0`8PxgU<1C;*$&&~+COR7+{y3%}F- zU7gMt2%HX{Po8ZhT@MDm@x_aJkEuf9wRt)(A7TNq)>h|vk*rMgr=S{)bY zTNi~&WdaXVD_Bhtrf2^)VF~7HEy{Rz1Q(8P=A?#%;HoK#<`gNIp8+SG=n28@h77)Y z;zPTU_WBKIv(V)5*s7Uw)f4tL7{Eiz8ue+c`8C+{Vo^sz(A>5xEoh=PT>@5Lqq&(L za|v91M`Xzd!a zqPUbeb!a?ek3nuq)wW~6K@JXM-zhbN^WeD2`beFt^&AVDv3m9aM4_7v=WBthZ@`rR ztTos=0`^Qa`$0;CSe-g>XbBbS$-@}TMJ=SX>Go^2H5c=#BwV?o{9HHb#Dvz!83sm?mC#iz@s%=W}i{Xj9qpAvuUD z{z9JE3{CPOL9c$Gw;53MVaE~Jz_}g0T^yVvzliaCL)h<|<&Hk==m0S-fJ7}kVO9-( z7Z3=YhWh#;@=UWe?EMvDJ(jhJ_v!mB?O_j1E62atP#xjr0BtokTa!N?rStk)J8-Pfiw1@FbFoMw!&FAzF)~&hbxaR*aVW(W3CL+yq4xbg zWqkTaVl%eGp0EA~ghJbov8Q9)e~M)ri=GR0>`8mLO|* zO?EKFk2qq}CxGTP>haFkRxst5kCJ^A$ER8y{q#N_^799}ym?C46KL6@e767aI9?t@Zc&!;b_Q=)C}`8ml7bQQhQSOq$0PKvtxZAtxX#jgFem7*6BMGhHWkp$ z%GW&5K?bhE??vcM*&T-lOQ`^!fUj~C7SZ=+u-(0yx&qOV`sve12PU!t^HST8$!G4k z88&FxWi(lP$?*Q%aFaiKa8*1lboN;L;C-h`CrBG>b(=VAvN#NA8{XH?Xu#d>bxFj=(Qyizo%J&ImPb|&QG2tw0t+Zq0 z+=0AOLWu=^Q>0VBUEsdz+(|o@W6#?F7Txqel4h^~K9;7flEWmJ8J>^e&QZ6dURE-S z)=I{!z-aqC08IH4YWG3x&?{zBSULHfF)a5XSqSw+jOpYo9qUrjq(Sb&ay`r%8dVqQVB(4SmT)y#Nns*XKpk zRy|MqGlBF=MKjRMg9*DIb-j4h_1$Di5nB4X%rYnNtXyoNO>I$0Ty7jJmR}I5=1lBpo?$is$6KJb9D^hW96Qe79V8wqJj_7)&z0>jLvnFr>fD_Fi> zGl9s2ykl91ytmy1yjo-mUpd9vg;1f+8t|c&0wDQRkU9%JNJCk&O#{U8AF^v$!Po5c zPxGTGRj0Qf2|Ql&i5po{oL(D96{ijBdk$QavVF6Ez@==p3moClnAnS1rF`fwW@tgt;kbz$8U-rWHcW@wh^u>xB z^!9=3W*SGiydT>Me-Tx?i}z-UT){n$)28x}49Lu0K$ThR*9Wk!fGS-IggnIk{JH`# z03~WIsR7m5SW^FX58`CIEKmH$BIrYq+Aq{9N4{)o^?T+zL;2?WgT;>}&pi@*x@`^u zLKeuh-#<_609c($DWFjU0N`QEJwRJ8CJ>cdZcT$qE<-fBCcWR5AeuYnIvqQuq^-0| zZAAf;Fc(cV(ABiN&B^vlhv8I9&xJgNA&>)jprpXP9Fiw)dvICL?&&h${Sh$9!hwgA zc5ikvjJzVYMX^J}Lal-wGJ+x3l3!PaE46HGJ=|Tr8bO;xohZ_>M(HUioF9_weR(n+||4Mf4on1*k|fu+6wf272BHiB_~KT^>KxhB< zEhFq{YPa3;9Ni1NiL#nH;ZEzH^N;x{0Qy)9e4SG4Vcj*8&H!Ben1PYkw!N=`YAuDQ zcxn~gFbhQoeBlQ}_lQ>c(vJsaG?abBg%p%nJth4#Dje^bdzLIjl<^T}jh|w^0Zi-X z55%Idd8Udmp6`zm=F-H{`3Kz24#*YLv|w0mJ&3@D{T+q}Mq0pJs07`+YV9gwqzN)KU;3G19|`Th2z>0(d+R6NZmAncX!_El_BsGfF-0OJmC((|J3i*Ho-f*~Nq}Z1 zOMx;n+xK-*pLndApc!x-jl*9vwA-<0V~;5brbCKrC&2syN`OiG2&|c_j-TBB6nHM5 z{}UOwr=(EAnSU5*0N@2vH1X5MNnzFavFABr zhChPL&PIU#-882y7lDfyP;Al&!gEwD5Qpgd^6*`cyxoG3Mu1$m~#~z_)5hs&Yd@EJK!1I;VYF8(`xGKRC_d}GMw#)8K!I!x^tExYu zs4vk*Z1=Gb1Xu*49shBk+%4=j8|wh!b)huR@A&W={i}5jO;2g%hV7T|;<1yaU|wn) zJet67)X!950Oa>7zf}5tQ9rYwDinq=H%GZB8h;Tr=|gyfpC0k#+tOBc#Ffxvx7g`3 zN*BG#G1T|jf!4e@RyxceaZGkp;ao{Ol(;^d+^|J-KWW-Hp0k!WdLLrk%$tJ#a5IX) zEUjXdfE&2+0_6gYR8f@8u!RkxZ&dZj+TXU6S2G7ajH4WV`(|%`4nkDhT^C%Y=WU;6Cf6q=~$%pDUqLhZQkn+GfMdVrV01#CURP+aNwI7B-B8rHr%2d z6FMX-C2v+9SL|0I8BsGf{WTer|MUAw9HH$C;!>jF2g%9+sd*Iv;1u;wU74u5WZ-iA z-j`L5s>uq#VhinlB386)cF94IabM~nFuV>i7)D=mFk|0{9EvSF2kjsp9}~u^4S1i> zxKs2Xg~-}t!9oi}cjcLA6@8Y^Yg; zP#bK>BWvzPp7!Q0MAk13fct&3PT@LqvRs+^n(;(bGZj!sP|)Xs-Zm!pDgo2H2Czhk z5Zax}Idop(V3atCk3zx*$$f(NZ3G$M8h(?Lz4jWq3RImF2hO2iOnAQh3cPvmXsteR z#=d!*>bvp4;Rs$-7l~zYLBimELbj~+f1BdEQ^1x!pl66LK3Wlta&cU}{0H40tG={6 z`CnWTR`XX&1uSr7ztXu2D7Jj23mfxfk8;bjP};BBYBmf#pqA?`^M}Veo<$+iSc7>A^ofVE?3FzyLk;OV>2FQ#?y8Uqd0RgMPKW1R+NE>g&hXo>VywJj<-`fo20UJ9GLh<%ay8+s%#`oH;x6z$%y~t zA#j6sx*ogLPoEVS-+MgZ3pA|o!^AWaBY;_V{g-@eyz)QtZFDG*ORDOQN?}^&U#UPz zx(v$RP%9hzT6!OO@`xeSOzwe8XQc=?>6lR2Rrsj0ZZm1Qy)Q0|nHK_v@7c&0_$%u?vaRvwQAc=o{gL5vDQw*lP5HIH$d5KY)jO*g5NyEQ zSu^h-jGqG{Sz2aA$+r#cGBBLO)i>?q3;>N6c6zCQ0TUdcfygL%$p;BNp%HW9)pc@q zqC=qwl?o&D=L_bGx|d=Nv2QG}f#_ zV5iZ%SlV`GS0UFp`9RGkTdQ!%eTY+P0e@*|cLId{Y-OVqkijd}%CfT8bOzMoui;p- zoo~a_LqRTFf)c9lUW#A#AW*Jilh4u~6msUS`9b-GZza-+Zt-`qZVZ+&qGQ`GAqmmg z9r~dr-D~{I^GW3AG=q>>zNc1Jnjrw73g{f_eE;Oh;6cU6k)rm(*~Q~y=d=NuI0e^w zbL2st&Xo7X!GFudq3~$u3f5uN8(gm5FAgv+X5h>*E^XDW!egzC)vsaZ;6pAYQL%U) z9e_S4SfH_mF#A+u3zbTeaIMTM>i+5ivYQX?Tl&#g%K`Kv6#s-tY)JDwu<+qId)@_! zjN#dtSUL7Zu-dN-!NkPI($a~auFL}3?RXhs$CR#52Uz!Oc~*(uObEQaj7Ou}UeRUR z#m+8q%c|ezYt9KJm+b+yJkDBV1s&Ia>HluT2m1Q#y>bwT`xUpL7S=3CDL3cjE%7Yr zKz*5;k|<;1R@KZe8a&?`Sw+2KSPlArH0A^M_tIkuhtkt)hw5*JNFwY(z)3*_Wah_W z=raM0*8kF%SsZ=;Uu4>7K}kZ|`X`;NY+~Pa)N=NYNiz;oURw`ISdW6^V`i%fcK9*o zWs9%Blq# z>P8)zEw=Es3bvt&pKb34)D98hU5Q@_E0Syx&4Eb`evt^8XYD`73@XiN?9WhAzM-j$muqh`_TISQUh zI^#cstp3FGAYrt#pOVp#zj*qXx1S!HCtn?f7G3WuNLV^K+|wwK_)lVIBQ&|ONge(! zq)xUq*zjKnBUX(r?!VM*w{oFWm1s4Zx=qs13$kYyUuJr~FniQE1hoMITL7mir)r^m zWd6dY!;Mq#x%9WNs890$^+(7Mr zwD4h>|IxzVP?N#{FuQef#IjtymwZ4eZ_}jkT8gtmX>H)tHM>gyo8U+SLAckJmRhB; z4(eHxQ(`Ai77%!U-rUUy2e6B$RLEaR+?hh$miHsRab%Y_aL}yeLX4|#6Uzzeji2rp z9T_DFin2remF)U@|4<7#}`YXpv0UXhUOURTkidK1GG5Ju!2XEtQm9%@F+QNS-t0_k-ZYo;Q zpg>Ft*a*0`xC&txh3XI{Se$+XH5<$ zP@p*yOY5fV|6c-opxM$5X67hz^~`;6g;%Du=Q^Pf*V-zb2>+pBZgYcPj2eUvt%#Fs z;HnHx8~a9z;3f7&t~%P(x0e}-r93h=YVIva_l_4tW8tLmqNX?cDr^oW4oE4oVi{@n? zBLy=xMQh|8Zn7tD!R(238x-&&Bd^Fl>e9qj5uQT+CFHZxm$X+R(3&RpPS9iR zR8wBpnB1FrF&lJ2nKCB@hX+Z~e#4kp!;(P8oAI39uEe#l^9y?{($&dJT&<;nNJIVL z7E?Y~c2IwP3iFqy`IPj-uZi#u_tEQ(w9%M>P*mN&>F*?4bpzNxrh2Oh$Q}F0V3r}L zTw@S4wHvrT%tWJZtES%Min-9zjEZ`&T`bUc_UqVH)>+x;E$aaQIfLbiD}Z$ptBa%$ z*U++K|FqHbzV+9O^-P#VGcpLeb}V|=Fl`1SS#bZC6R_!&w%fh1ctM7XAsorySfoe& z+02BubR*nN;?LbeL;if+FxagPN6}p=AepS8cmqBc5dV4Mj2AF@$QUjj8#}c%UcC0$ z;mQGcK>Nze=iRyLD+2JnnBxd>?r(*afU;rEkj^TCk?(`nuebnrt4Ha;!}{e`1sppz z?!>#X@v!pZV346K_S1R9vkD!gZ@1kqw7&9mKD2tq(puBx-{#WZvjNj)$b?tV>nzpV zMXTg`9^zylJO=$HTDx*W%^{hZz4$ap60!Xu|0cu9WX=;b)ZNlS?)gC@PjTb|pm7>$ z{es^8K=z*$aBUtxvwpc7zvvDU2|+uqaG#uvw+u9hd@8okLj4%qz3HQ7f=pQU!K)vP z9+?#quJ^{mkzPAhQ``0FPqJvAb_4^-HH-8NwJC7TmCtSQ;sCGH#eR)BI2-4U63<-~ zh@Iim1NqL}lMh$Xok`U@dEaD?Xj5yg>zp9Q^nT&TcVP+zh=F=@?atjN&iEG3C+sf3 zM%BVa#Dt!P$-R zc+l^pE@CyrYYgNdn;0!U&1Y9?7d_wB^ro$B2-|30md*om{gSe7IBP60oD|nZHqqaD zkx>3rYAg|byv~_@QOY&)SMqPgi`u<4eaYwm?6R7u#^3hgZpwh+f8_#bL%((E!QIP9 zT*;DpA}+V{IF7COcbfkixvM?QHxv^!m7;g~3?V%nX% zYC(j|lAPD`9Q-W4&n3`S5+z3x;ci~l8k4mf(Znqkw6y19KdUoXsW5BtpX%1iYbWRj zf?+-8leX&ZO$91SEJA-5DhYCa zLQ?lcTj!jPQqVk~a3dYhsa$@11qPfB@fc63>tnD0k?D#>tIvEWa~)djbV6_PxRG_S zWqy)`{EI7fyaIydr^M}z)10qs_5w@pgYiWvM%_=dsZjHd2xmw3LoWqST$l$5l6z%7 zo2h-nl}aG+FLPC0@wz;{GY*GU*9bEPymIkmyk~Rjd?USj&!yD4x((p&0c0cS}(_I7A@uF6P zjXLMOPu=3r`TdjhOqLHFqigoTwO*Ljapk-ZLy zwGW_hCY6P4vrMl!#_(#cQnY}>@ov4Qx+I(s0b3~~t>gb;Z!0~?kt>XX&0vd>1ggBx zh0J-erN_bk-?bt>FnL_r4A@pa{}%ch2$;G50Tvk^klcOXk+nB0EEQ&y(L6u@t<$dV z`OdGEyT4>uAnIdYQ%oSdA9vaLgTw_v@zsZW|LVy))mHx{Wz{@r2y7l)U)@HgDIq@R8~|%-z*dm5}qgSgvTna_RTN= z1wIznrh9~k4$5GK4{l_drz7b75YiHTg%6MHTwwNV&d#YQyLS!ko92XB$vE?V)9F{D zw38C_)&nY6NYQ|7=246>+G^?H_3W0P)HoOlfMU9;cQN5KW0jJBvpBt^1r@@@Q5u>=Y#=6W^MLu))f?#0w9K@F@cqae`Wk=gD?D1}6Dg5w3Wy)d-HKba-~vABi(LtC^2>Fqa!r zy67T{2GmsMzdsBRPoTpjJ_Rk45>$XcQGC{qC40Hcki}8uYZgnDW~rwZ z0L|Ym>d(S%L1`KLiNCG8C;Pxv3zsyTInvm;q_+S}28da#2u-uK!C7cIAg5WYZ=aHY z=u~cQgmytd5Mvd}22FuBAr2I;_jL`W zTXbHQQdydtpCG(;$Y~+f6W>PVh!6%P&=}s>=W1@+qmy`_msh=g&7&Ebi2<+UXC~(S~6lvEfo_yPqWen||*xlVV`7E6Zq0KyA>(i}dNT?B%l6nu`VLWE7@Rz}9*Z)8aqx@5dCk%CBCn@BXZ%rl%hkk7{pd zZ7m-fdc&{@*>ji+yH0&w58ulezdG3%$A*oPQ&0$<-b&2L{LX8Ohj4FdW^LfdL`B)V zy9@4UsoFU?Y3%ImAT_(5s@d#bT<0=iji%1psN5x;hOqRB`QA?dR#;m;Tpww#VjDWm zNDU#xte2@@c9tmaaX*E@)>-1m#RUHN9~ZS~Q;kMWMxKwXJ7tMORIRP89X`~{&& z_Tw4`1%AzH7nGDNA1~IlqkCpyVq!9ICdYh6v$V4Ea*Bx&>v@)B-)&;R-kwuMRk7RB zl@7agNA`t3tt^^==iXtKv?t4-gJ=7O&P}llDPYm!;=$93QE#w8i{z5~(Xy->FiHqR zGRz(PIA=yjwYH95iBRqaJUru&2i^Zs(EIc8&+2xQnJ3ww2}Owm+5~q*s`=tkouK!C zRJuo$>?gh%wEH(I2XDB4Re$R&DZ{u`USRQj(XHy>fwUig;V4vol^=Zn7Fo^=cc#s& z^5HGn&%1ZYZ}(K-8yUA?2bCXYDxO12cbLT$vVOZl_iu%|U;6YL?X`~Au@#f0I;;82 zW$gEERr)Qw-{pae2v{r8s~J@o6c>`V#ZdQ3VfxsW^#z66kUN(-o?ts}3OTn<};Q3DG zIVvO1kKuO?zn;2rf9|x@9FC5TcJTJT>h1WBE?3jrxVE;YJRmeJa7F;KXM4?n2J+UE zF;qQiN|B84|7J-D0-2RCD5HAIrDK3{E-808N`A|kjtcHoUm(CJcwCOAnxpW%-T@ms zBiynU1ITRY;%a&0m)7_i#tE_C8d@~Yi3cD1=PIhqjLP2gJ|AY~Nq+j-NqF;J9R7@3Zw7hx2I0yPhXtJIiTJ`KimB8FSk}&A4s*isl>96ehJMc)Kc~RYkn# zljbMkSz=J#l<4KcjdV{LJ07O58yFTu))14k6~dlfB0#Vy`$@#%S5txQCP;2G8HF(| zM>;tpoFB;#rX@~7SBbfz@Mx=f*yc}@oUf6ioHqBa>`!64U(45Y(OSQmY$8KyCvwnn zrGBMjRwBVeDgof*xvhlQnnYEquEg(rj70iAp$#sE`K~rT8-mcC`e*QO(|X70#o!rR z{DCCYW2p}}OzBbY|JN&n=?ne5x&DI$wDpn!9hgX;o1*aU zUjgOFQtqPs{fV9EKeGUY8{~U_nhOls@~4}=EiElZp`(eDlau97LAVZ%j*)-3(0~$R z6dLCU)U1=mShUTGg$1+U7h(M~#f+4JQt$0;Y!rdhT8u)+E(W=Gh{PM3no=OxvdGK! zjz&1V|Es0Pc?|($RsZb4Ml(?HOfC+VHZH0Deu@9zKeCQ@7zb*ewn%#g;Gk^~NJa6v KLZ!Ur$NvLsZ{f56 literal 0 HcmV?d00001 diff --git a/doc/html/_me_flame_sensor_8h.html b/doc/html/_me_flame_sensor_8h.html new file mode 100644 index 00000000..c135c053 --- /dev/null +++ b/doc/html/_me_flame_sensor_8h.html @@ -0,0 +1,235 @@ + + + + + + + +MakeBlock Drive Updated: src/MeFlameSensor.h File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeFlameSensor.h File Reference
+
+
+ +

Header for MeFlameSensor.cpp module. +More...

+
#include <stdint.h>
+#include <stdbool.h>
+#include <Arduino.h>
+#include "MeConfig.h"
+#include "MePort.h"
+
+Include dependency graph for MeFlameSensor.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

class  MeFlameSensor
 Driver for Me flame snesor device. More...
 
+ + + + + +

+Macros

+#define Fire   (0x00)
 
+#define NoFire   (0x01)
 
+

Detailed Description

+

Header for MeFlameSensor.cpp module.

+
Author
MakeBlock
+
Version
V1.0.0
+
Date
2015/09/09
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for flame snesor device.
+
Method List:
+
    +
  1. void MeFlameSensor::setpin(uint8_t digital_pin,uint8_t analog_pin)
  2. +
  3. uint8_t MeFlameSensor::readDigital(void)
  4. +
  5. int16_t MeFlameSensor::readAnalog(void)
  6. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan         2015/09/09     1.0.0            Rebuild the old lib.
+
+
+
+ + + + diff --git a/doc/html/_me_flame_sensor_8h.js b/doc/html/_me_flame_sensor_8h.js new file mode 100644 index 00000000..3b9168d1 --- /dev/null +++ b/doc/html/_me_flame_sensor_8h.js @@ -0,0 +1,4 @@ +var _me_flame_sensor_8h = +[ + [ "MeFlameSensor", "class_me_flame_sensor.html", "class_me_flame_sensor" ] +]; \ No newline at end of file diff --git a/doc/html/_me_flame_sensor_8h__dep__incl.map b/doc/html/_me_flame_sensor_8h__dep__incl.map new file mode 100644 index 00000000..381ae8b2 --- /dev/null +++ b/doc/html/_me_flame_sensor_8h__dep__incl.map @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_flame_sensor_8h__dep__incl.md5 b/doc/html/_me_flame_sensor_8h__dep__incl.md5 new file mode 100644 index 00000000..bdee3aaa --- /dev/null +++ b/doc/html/_me_flame_sensor_8h__dep__incl.md5 @@ -0,0 +1 @@ +7a74b643f4214c40cdfc71c0e494031f \ No newline at end of file diff --git a/doc/html/_me_flame_sensor_8h__dep__incl.png b/doc/html/_me_flame_sensor_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..a9eed6e76bd583bbaf986850caa709f7e486d0c6 GIT binary patch literal 14054 zcma*O1yCGa*DZ{bgrLDS5G1&}CAbrUy9Re>@bKX7J|t*x2*EYT009PfcXwxy+vIuQ z`_=uc{<^oPs=Hy%be}$FpS9Osdw2LJC290m#INAs;Lv4dBtFBzAw>Y^jxSJvy_05U zI&eTSk(ZW$dwTwSYb{EIgL?}nEAdgyGwX2C%SZ1reH%9HB1b~YBmb5xion)gkUHRH z;DIY#KLkZg+I84b(3DA63B;0pabaVS*r<5TJ)WL!uyu9eo@k^Sl6mARpdpqqGlLVC zM*Yu+UL^rCYWG<})1ofxOiA7B?MEji*-dBJl7tf161nB;{eo26-3fl>$=h9~;oAo= zMcDttMmn5;@j*gD!n(J~ZQou=0Hs*?BUX#!cDBbO-!32Uh56T}d_*j4?D#oj^JSUm z?~Mul-dHLMU;zJ1{}4`vjg3uTEE$RKv{zh2OBON_whi`sw z%$j|7XZ$}Kc`ylbAoBhwVJF`L|B;2 z<=6-((COlraw*SOSIGX`k%S+Y`_r*Ln~y>;nCHM&BGK2BW@t5N1Gj1E6!*;FtTm?? zk_ZDwMCZjF;@9My(f4dK0^Qjx`fdRn64DmBhdiHhEN7h|adu^P_%MT?)9O30K}A12 zj@RWQ!>$ZDzU6V&CH=B;Aeo`)S|5@*R>Gz&l@hrLSz? zSv)hHYSJi{qHY3=O+M(~kqf8K4;^%UKNA1eAcb*z^>CjRYxxwer{W z)WJpl5Fb3;b~dG+1H{dKqQH=9acVQR`P3K9i;sJ-BD(Zo^Pet!ex-d4bd^FGSXelkWD_V|rQWqFP;B>Tz3jq0;;TxWtCQ1-lWfc{1>OJ4$?*fxS zw_4t+>7>OEf%>>?Y4;)UZXuordUc3}q$39)LP}9k7iJwGtd1d0BDk2Gf-xU=LK??W z?@wD$9*w)yd4%+jmCb3rVUzHog3NpTuCyWPqX7gLXU0bU+K9NoI-}${1q_es^UFC8 z?}wApEOI^z&pwl=#ttIF$aP91mp~6rkRL^d7dD?n$Hy!Y&O1^JBGT6g;6=}9GU$@j zypmz;Y5j(GT2do@>=b#EQ=gb$%xS~#L=55I9wOH>2ZaKAdlyV{5oYkl_1FW>9N}21gF)>2UXu>!u==OXloJ76}hryNmGy*54>`sfX^pm>lD zjaaFMbN7d zk3nKtlwjkXqd2)u2X9CKiN8%({>vMm34Z&7f8u{r{G%iaF?m-~DybG(iro=aznF)F zBbC$RFWqHzcaL;;)b{5N?cp9+=q3Nc>i9Re(i}FJ8q_GQC$Ks#u8}eeTPul>s>v!l z`7&YptsLAc>EHzt0>)?Qb!7b`1<(#{oozQ;9G}Hazm;tL(F-AAg_bAy(oCFF4Acp!@-Afg|p*Wn~Y+{r}ja& zv2JqdkRU%h+x&jGE3~os+?<4Ix^AxN-Z{!)ZIG@+o7iy zZhK2kj4$9z&o|+40Bbh)<_y0co7yZwV1=I-T8aFafo$(n8aJ&oQDfP$8o4X=XkF6E z2K2p%kiY_ukv!)Of<9sU;;2cb(wF%+R?CN%tBebKlpaPcBr{{9CU%<(v>kKy%Ue*n zmA5DUMM~>W^PcI+1=DJJ7xy+O)1UNmPd-RT4zaqf4%=U=qI_O3hWK;QxiXf86ryG| zZt4i8-9E9ue1|BcL`Wol?ysO)-Jdn@?zx_co|P_p1o0nFHwJGb9)}T-b@RvFdevN=qh-o$!-_bE9*P|E(M7w6KiGm91K9rdIET_Pjl@jU6oTR^yH zXQSu}gKX*lD((UOsa=fX7JTS3zaI&FON{S1vJ$(+edh6np5e&eZtA)XmE-IoC>C8U8XU8_80;{yYY`I< z3~GO^<}=uE%OVdY=L9XznnIQl(ay_Q6fb5Enl5Np-7SFh^&q0 zBwxs^x9sh%YjC!e7aFio5jhFnXC_BYrc>dn(mD$nU6;@55Qcb_Vu>a@fZq z=;SS)G@5)1J5ahnmoS`Kj?I|0i@Zz@<8v@a1j}t5soC~vxe4TwYgoq*U#pi zpYO5XuWx?nhQvJ`z&~jU%^SEoTX(Du*ZrEI_~KW!<(FdvUe#GWfdj>ErMy`}p)TVptcf(_G(jx9o|-Lv zltJK;ou1h@gu-3u7q~j&mUgL6-@6V!AVS!n*rBYX!ksC_OF!&qHr-&b#;*au6G|p^ z%wJ72Eo)QpRg68i6*eC(6Ok`!A>k1=P-f*P2e zp41lw)bux|oWEBI;%C+Apr8;@kfu+3N#gFc80cq@iTK!;<%zV=SBHw2_s*3ZSqEKb zknmOZF+%q1lS7mJ%U^D{{22arRit#?FBTkwG6gaYb0FS!;EmBQ5?vDT82ktQ)Ulmh zu}ig`1`KEG?<1$mmjHaSeP2>^U}|!s&zOY582bkB1Ch< zUt{XlTB+(V63OHBNiQzHUTq0*>WF@j0^BJd*2VcfL|voJYM@AEYm0zlm+V*6sCGX} zphf?LT_6}`-LOc9^GEr-L-#EYo8?J+C;X!s12Sm7{gscp+Y7H{jgdOzIS6 zVOL+@d`<&7ntg+VKDLKwpYuehE3e&5PfmWtox5c9PPV1vW~9*E8%Zj{*ibr&%Nk`2 z0}~`tn4pc+W050rW0BOs4TK z_YdbgGNH^l6{JVe`#F`9{-+#L>rq94?_j$&VcgSSdPv98uTo zI`bQGUF1RJp-Z?2{O2m*_tKQxwTo@7a{ z0N@zj^44GQ-b(G*wQu0Rz6dR&*E~!C-0Ql%4==Gk@2cAvV~rT}J`<1UQ;Zg*2C(=7 z6i;kEx37|mQGR3hpyD?+HslvQA2a-&x5d6eqYQ^&>=qj~L3a9nC0%m45B|(6D59=2 z1`a;0asLe33AUUL1uXNL`byVqmZo#lpO)Fk4{4#iGbF${d;*3dWi5x-(C$g2#4dGi zPk%{`caTcCW+u8Pux7@XJjGtS7U_K#Q5%PuznBolq#JZ15g)BrMFYS`8jT?frKkqq@uyq+`TB@G^cOQ z-f#nYiNZ)G0wxNVAFg*fMG)_QeV*1_W7t`+V!>wy$;Lw(NqylG|EM~ z*BNHgxK1=MXa9ug!NcZ`Uc@yT<;p0SGVd{fEuK|%M`FZ$QcuS0t_xqu&ri4l;?!8v zL*;_Vc0pY;92R`DADmmJD;uXRQekOTpwt}Fi*vA8f;7FwH3VN!4eBZP< zd?}HP9|n#%0Hcx9g@oBlWcDdsXY1-U{Q=3B@1GSM{c5UC*x9;Mk2-FuX)TWTZgWj; zRk;xGxP!^E|Jv1orH)Bw846A8>Pm<=pV363d=?*^Z}?*Xu1ItCb#Kn$_|*F`a&DNN zbPVO;NKbWYcE!Y|>3*DV7`M4R%Q!3tNvV%I`g2un0uEccf!{h!>`(6-JL_t&1R~3r zXKnnTR)YGu-5{kM8o9Y4KZrXbtncFU^Mk~&JJ+z`Vj>Sz1Y*+!;v>+Rx0-DfQhGGq ztfGLMVGQ2F=^hDLK0O6B7RCq$U3q3BW)bq52~*|Z4B<@1b(4u4>Jp0D)a137JVOspmXR5R7tXYA+|^dwI7g992o7+Xtn7ZMqUIV^SZ@Qi6q&D# z#J=N|KeN(p>WY{|DP9D+wR^%m7t1gQKey!8G}ov```J|&;^^xw>R1l$uH2=7(`Bz$ zSGLxL^%*$rvm7<=mFha&YsuFEb%W{|;>^>yukUPaOpM_yf}z@cXfM}HMymqKs75<7 zJI*`KyODDjXC11B#}9HuBMIb%kv(dO@)|B~C4^OeM#^6sU1)%!6UEHzcZAJoAkn7> z)~y{p9(4{@tJ0Go&aBb4`TbDCE%KE-zRN(B9QBDgRY*eg(3M#NJHo=;;dxM8>x_)b zzVQmW#}e0iL5Q*6!vN!9Eww2yCe1DM+v=>YD#nEgLYbPN$NPM11V_$RHG zvWcH(t9}PPXr5f7@HUJeKy(97_0KI0n_c{Sots&9`8a`zq6o}{V>7sni=E`}+6|z9 z8|LM4w&Py@r&qE}^lSC2?Rt)ISr-BEo4b_FE449pr40}FTfsY6BOjyJFQkSSmT(yB zLf~v622JBTY6Yv5y11pP@Lmg(VKwY{>Sx&f{Dt-hrYn!5^VFIt2Aa3v5a(tFe@TYj zv)3JGs&Y+weHK8&Cr?x^iL*HI1uxa!dd;xpR?3G7h}OTd<~87RdNm3sIp)8cbHAZMy2s@+f=Ki7&Km@{ zUEg{cM;s##V-Pb>euDF*;uk0LPqgH-sN~O{IE@~fo_QnNtM%i6vV?G8ZR7mQhj)%h z+XS^4LVp_ULV4R}JJP-OsF-Pp$5M8CikbkbGA;uMaPhAa&o8(cUJGZu_#4VL?CP(NM}XAOzEsnf2>GdfU~b!!Koeq3P=)&H>lp-*%Yuw1^hYcWaW-_+RS$60&>8JjwMa(LnItXb0<_i#RWeJfdv+Z>Ps zeWiWL%V_)dJC-~Poz;XKSGSexiw$RQzE!NqDZq3ezCZ_L$-lf>qUgDuKG;xUzSJ3< z{A$9Ff0GKWRdPn8Tb;;I&j_BHT1~4{6P3M=C zr3*LAxjZ*GBf+Cy8*GaJQ8el_R*I|@^bI2M4|9Roj%#^8rEancO7sH1W8-g z%q${cbP}PNCwLK=4>oY^tI+fg1Kv99G3_C@nlk|GaONCV?uD8|*GKd2&lPSmhlEpc zCdG9+tA%Ys9S!<439R72Wx)pSfI|2U&~ap5)*fHot!nZMJ3{+ZCtO$@@m1^y!Yo4J zF|fPEJAXEh@5}Dw=RO5(wUN;#;ubonm7O@%nd zL!8TYujU7D897C28fSTE$&`!BXLmI-M$s2U+vAr@E=>oTSPb`+N=fSBw&8}Gog8ZE zqB(dD&YB2N`9zDhM`19ZyGPZ;j022d;nE zOAc|W>|AONW%;_hf4RZ@I~oVFpMHL6eDE4OO&Z9^el+H6a%|&&VxJmJGBeT`dp~Y^ zgv{HfZzDU(o*+$tNS8q8h09azO{=7tqf0>lPeEV}wGtKcKk-CJy=9SV`{Hqu63?{0 z|EF;fDk_Tw3w)%QmRY*l$j&t<5p%^YZPm1K&hIt_ju-1*rR%rWIS8$vaX;zZy%i0smB17#IH~!4l91{J78FY ze7$b6!xN|ik7ABk+aI>*O|USr$KUjv^=s-0*zomK_Y{1mV*~MWkC#5MSq}xZ&4g$N zk4Kz-CSvTO|xP#O-F=~>dEC9~m zz_owEI(b!vn8$gk)MQEK_)k zW)~h6;e401<99u^WLF5o8RxH0%8*B|yFzCxsT0D~5CQL*zxCJ4==CmeWyNoYuXuGF zc#cx8d|5GStJnlFXo<}BXxBu@v%X{4LFa5}xG*!jOt7S3*dks$5tv6obpK(re>&xQ ztB&t0wY+1wI+dPct2e&cZhR6;=sz}U>!0Q-B&$1r7`f0Wl4wLj?C!d(z_0_R^KwOY zB=$;>7KaxdciPmlp|~)t;j$>ocCqCObj298Ehy@aL>IWgriumgg?CNof_Kty`#wA%v(3}eS@mP zXLkIn#n1^Z-o9HMv*iY5?O`>b7jAY0bs$Q|IG!uC^6QRo=I}HOM2XHV*ggsGdNN4P z`?kg5@|x2`V<66(o2+s3dLilApRl||7YZIVHBOr7y;YHpY|U`&!?PM(n;Z3FKM&Zr zA)1RaP#(=g)uiHB1dKgCB2m}UnHn3HgMiPpj7Xj%{B5W>3Tn_t@F$PkT}}W#Bg4Tm z;=c?*VtE7>!wRe{`ej#kB8-b2bZaIPrC~U^f2qiHr-IVB@ujby3PX=LU$X`O^l*Oq zw==8#D{j8bKvvgZGdVP5$_0(J^V_IUMW?YHxo^v>-XAPf-(CCcGI+n+B`nefgQbsA z{g@vwDMN(=YkCo{UKe<7lxog1%0hH^A+l7hsGc4zX$dk^9Ocg)w@TG#!pXh+z^^(D zMn*batHh@BlVXX<5<%NRgL&y7M-~|ZYW|Q&a=)!K|_X801E9V3! z%{*n%o#Qf+EdhX(m%(KKk2C+3YkA2vTR7V_YBIlkU>M#HPAJ{ptVbd1ls*TDh&&c= z*Ya=O9i4B@zJCtR85y!A-}EQTmgHU@}cj5DNU;NlXg@BI=H3{vB@*DcXh3$$oBdvDhL{T-J-3otzhB_;l$lAjAv9Q4v ztBRUh?lnL$l-7lEboK5ArM+@B3Nw{D_p<#o{xtkHD(LDBG!6kb>#?_EsvRGCd3qteMxALkj*oHdpPO{fi~e@+qXb4 z=txc0ekMw5W8$WCw~NqvsbR+Y7R>r3o3%{R8sgA{;Y{fB#7|<=lf-4IvFV>do`b&B z!%KCMEmCO6q`sy9+h}@MF48B8DuTS>?AE|)U{_-CiHM`8pv$wcdPK_{iWAjyO4W;( zI;Fr@kjM!eLk*l}CwH}gDI6DndgY`HByb>cf)vwEbnSI4PgEz!E8{?Lg9)G`Gr;-O zLX&|$+rabQeDAsft?$bPMEwEJ;z+fzP&d)>(|RS5Z_&v`DMOz@mlIkYa30{|2>tS_ z;Y#+@1W_XRSI+OeuXFe(3dG>XeH{$T_ceWk&smKqt3j6G+tAQWX2NnhjpU+lYh&8T za>D=0RsCr;iiL!=M2vx%0WM^IUq*xz&9yTyo^vw0T+IQq^fy0V6~tDS4?N-C_-6S} zS1$-8#uUw!Ep5`FBI@N>G*}jakhbdoC#K6dFxrFchF_3NCCUWxp)Txj@AS7-j9&)y z4FcZ3?=_G4=+1gkylC6LvmV|17oHmW2aMwx-oEZ5-Cq1X1P1(-YKY$vgIR3Z7R5N&wn4x$eBBw7 z&-(B1svt^gVN|TWZ5>@=OtE!?t}d@f#;N~5P&Zv2Tg@>__2#K^K_yn_ zCCnBV_c<>uJ?P0dEpx3uIN^_mc=yVXx5kXG!+T35NDo~w+!_eXa-+GBGqE6Nto7vD z^zVT3EH=L9nt#VD767`f*7y>HoQ>J?&cJoh;G;v4my~i~iFje8pAvw7M80FZbBcyN z1#g@HX$jDIQ$& zmbxOAdNWx#(awko!`N!&U4MQJq3>IwOQeA&6!fSiAc)E*mx@p$2fSlR00?x?y4e?fYFEW6*3XTV#{+0Cr{eq_Ay4kB5w zTKc&_t|U-s4Gg|2-OwrpsSd*Sp5nkEooug~js5&;v;&F{k|`e4fv6>t&kDD5x}K@N zC?TeL?jFkGFYPZ%kXb#r?(!Z23q(1ij=f+j@X@IUbseatTUe#w(8b1h{U9Rh^rGDV zXkICf>2_gvi{zaQL@>|H9S_L+@Mif?S$K8u8+Xip>}w=0=JFevettVwnuqs zCJKi>E>zKZLbVCxrTe&^Go&bpPz(eBfocL>2Knb#ZH?gL5W*}(Kp37=(c6w!YZvjk z%HkR&x>vy^zj0z&B3NQ`-im|Q#sI;0!8iGmj;LPZnSwt&=wUB+`@Tv;J8&~4fz}~M z3;kMUAW;&4rrZ7>Az1!;F$Czhx9^-FRo+1);bvIZSfekz zS;#W(!b|7%D{6;wNF~dENQvAkY~n)OrF|HEEQ^46JHv$>(ulE5!bH1AgmUt;YaB&+ zUC8bviAb3{Sf~`0n@Y7vB3|ZYIRH49h*@M1@qb>CQEiQo5DI5}EOS@*qzA(C#Get@ z(`)*DGhN9wUzrf8b=IF=yOX9vg=9OwVC#*8p<)6sUliU)tnHMT&8t`d+ili}Hrx@m zo6p(N!!tyHoK4jeqEB4F6r5jIHfKL|F}JCS?4~@qc1OWc7F-LwkfgcE3yWbOnsV75 z;z_fe;FSK4gD<9pDxzkEy0r0cn`B8}jBvw^@eP{_eK}Ekp^OX}4+;`0$UUVB21-cs zW!_An>2&WbPdZ7$n7&nh4=j2Xz2Y~#4AMr!<@=AE0d(5^6zy&*!b=>X%E- zJnm2ilA&zjE#1Ci7oX+8wC?f)FF6O1DRTJ5%K;2ihI~CLQzZ0kV6L z34xj}2SEftbSx5rfW^@>djW(`iZa_@dp#vEY5tf-ZK#-| zjI9Iw=1ntqln{UV{@sYSb@!W~o4!k5)s`6>Pc<3cnxEl7Vu(|#FyI79^$+GsOPT{M z$`F-CvqI*(KjK4E`rXLa+#z z-cC{N(-SnKiH#xu5=+iNTk2asjoA+M3DLH#nh@S@d&?2#(h+SCnJDvpoM7SqkUtmo&J# z4bWr2WQ|0s{y$P*-cgB0KF{T|N|qgeB|K?LaCi!Bv67 zT0fN)-IxZ-5QPa}2`9)V;8vDtke(5Y|C5O;g-GvZOQKMJUX!t3lT&hQvSkMXsbEuw zQ86l0IK_KI8Lk5?4sPkZCUxQTc;qIHBprZ8sMS7aUUliAmvJuPA;H>}(b7^cgxV`*-1#gwWnxUmqXFY$YZ6Mj0U+R(D@ z2KEY7HUXEoJukHaAOn~D8zalX^_OGml`)6?;ni*6x$lZ&7hC(|X7ZKJ7<>OIhq#TC z4!ekqtBW^<)OLKAYboLR#XzD^69ON)%p1Hxa#?aKLhsFf@?@;ev9}fBN$N31zkpbU zq?=p5IL~2Vaw^sJo+=m+7E8pA*w{l0oP5)QyT|_|awnz*pAxPIhzwEl)ck1p1tg$~ zF&Kxm!fUd2`j>|XXURLKxph_DZ1&Fv0#O4|V@Oxc(czUeU>Kr;WG9F#w-Bj{$+)3E zQ|>ve)IHIFad&k9S+gK`!K64DCHu1%4MKhm*nngc(z1U4Bd^Cmk*f?eZ#W0tXrSK`MES=+7I zs)7BhB5kAH_e8iJFAd}-Xl4Ss_+l*x{>p_DO4h1C=r*!viIJ_2GW20?#W?hkex|9q z2ZM$zPhk-V6LQreLLJ?QohzmX#gdH|efcDR@s*Erl<<9?c>)!EYLKxSZ0rBz*H7hY)omUl&e*5Ds zWn^gO7v-`%W82S4a=5bni*;Qj%eE^D@-<1GgZ4(Fj_gv(W~Q-=ljx68+|MdsfJbj+ z6mBZUH@ermlVy~gy+B@>v>`$Mg?2JG-i7>!RBOA5x>`XWFzP+lO){qAWeUlG<+IsN zEglnuQZ6I5d18B`moAd7*UmKABF?D`~O|BzwOP z#CVq{GnyHPnn35@3|wRlgX5XO!PitqN-Z-^J--n1t}ovS6&u@fsLSE@=WjsY1CVsc zv_>^XnhAeA4zIuw!OW5k#4QT%ouQS_Le+AGP~eLqcC|M^OtaV|np-jqFEGhyU?JUx+Qyiv>w=M9g3G^sd} z&I*g)vV#5~cZ8psypzm#y5mUStsfW4bJ|Bh#!rm_y}ZOxzWwu7bQ%k%U#n((e(*+d zW&JdkoMU}HD9C5~Icz`@Pel6VaIU=zY6`3wgGwJ6*uxTHWM2X0dzDVxg62MU=e1?y zac6VR&xn9qH5R1|&wRuMhuL_3t(!8x_%f7EvTqPS69BpZOVnBy5-+dEEA5RE8mb|uO&mSrP zT0F=fe*T)}Bo1vs%LLj;xXmsAy<}doin18=fKIaylcOPNBa!H`R1;5~8eqgYonMhIcgskv^>5E;YHL@px(-%H*YZe+ind&=(vY zeDo-u)^)e=x2<4(ylK1|$q^nLnct(y=o+lEUudYVA>9X0naVzt2^c!|H1nS)c;RDU zo}U;Vf>RFvBt^RoHhl>lw&Ge6lsel1>Rte-N)WOJQYJ(#_KQtFf7#JTzkT87^ITjk z2}5i%nrVD1;{p!}CQlC3>fAX1IS>nNo=`*Ak%R)zZ{pt_3{At@t%o%^_1ex=^pC`h z38B0-%KD()f^mX$g;{0)JJn9M16%(N?{O=rhebFM0T$UrDqN)F9_bh%>^0bR9kyj# z7ho}VGN?avCD!IvsatPfobGGgpFqRK&Aq8BVcq}+gR7oSy&spBVaHEreIyr2KfhJQ z$a41SiiWif89-gNj{l?FkLMWmk`_pg- zgY6z3BG14j38|Qw)2VNJ-Jsu39?p2D`f%*ZFeoZ3EAz3jjUXoNn}af9X+l?rLUa9D zbls;eY*lG(a!oaabXHbx&;tI=&gBpdu%)ECaGy|!%hbBLq-8&Px}Wv6J)|o$8~h4O zR2K2dSW3pVK3-~VxwBR~V)ct_rf3lLPH(vHL&kTcbPN&zeam+Rjs&--v^=4w7oi%gYC|1?&G&kuPs}xS9_|xoc~$Uq`FIFVmYJVV7n2?fR>W-(~AH zVEAp-2P6pz{GKOoJr z9pm%5c)7NrQni!kv-W1&Y4%HMGLL8aPr>6B7itx*l;>LCF!BhpbEAXjG9S>o*tsPk z$tYHxn^Mw;SDKGKA5K=t1Ps;VfhRMijmUr1TGc!NZN9?n1cCKV*kD{>HJ~g}LgLS= zyyh%P2j)8K+Y;7obUoWpzsEewBa&j8(=w~(^-Apant|m}(Qf3cvn6x?^#WGfH`z%E zIFj7mU`dk}cJ*9H=kU8OA!1ZVL zF@a;ryCk3Q%UyCwD?tr-;mafjqcYB6E-9_RQSo9jRKbo@pk5=yxvo9@s_4q?r(E@M z5hz=)-0s^N2zPgdzHx$>D*5AJU}`j(X}~lFOTP)EQ2(R#3oxnS{J#h3fY41~RaxSf{%!p)Y;zJG^-0+0Ixvpj}RCThgkiaBQw{RUqGP{8kNcsr%r$5A_G@WHNd<~rG-HBsB3w@jv>zFlksqGJim7`zO> z^8E?(YjNA~#_X{#nt9OOyZV&y-J+4=>TiwzZkRDg*D%E9)9i71S{kj6CbxxnX@TMf zgXEyBokz2#FY5egkxlyn@-mpY_snq1il6-O2 zaed016mxB4KY0JoB8yFNYrvcWeZAo-J0qw9BfM$KCRJ|KEe{w ziZS3}z%sVS~kzNuM!Scz58fX_J1Q}U7K2qspMIN+t9*zKz)izBJ3 z7?<=%i^6DY`;9Pn8Z^yXzo0(6xXmy3S`+#pqB^g}Ze8#|Qwy#J%P7#s$juVemVFjk zmlNhux7OR#usJmOxleTLCO}RmZ)d(Xy-VqMJD~$h>{Op`qu3W{oS2u@=?CHBB@8jv zo8-Jr^`=W+qbsb4L&XQZYE{G}8nbVSu&{p1jo3S`=kt?Ch zE?69Qi9Z%yO1NHbQV@TnmdH0*C#+UkbAG_Q%J7pgGLm1Gigz#0P5=)OeM3-gWwKnwU zYvIhD?ZgM|>L&`;3ZHh?3t`-!i{VqE$!;2va&~XlAADLiX`7denij=O844dtACk8$ zHm&{F%PkmsbjijW&(yd&bM=Q^?q*=0Tz{wqgc3h?JLLp zjWu6QXGKLt){E=wQpG+A(4XqhWQqA>N&8wPmCbK<5UQC_ZoB>N`K_4$%T~<%B-$|(*w~L$?+m=S1}7`2BvBz| H^!0xM95&(U literal 0 HcmV?d00001 diff --git a/doc/html/_me_flame_sensor_8h__incl.map b/doc/html/_me_flame_sensor_8h__incl.map new file mode 100644 index 00000000..f1a9fc2a --- /dev/null +++ b/doc/html/_me_flame_sensor_8h__incl.map @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_flame_sensor_8h__incl.md5 b/doc/html/_me_flame_sensor_8h__incl.md5 new file mode 100644 index 00000000..61ed1d7f --- /dev/null +++ b/doc/html/_me_flame_sensor_8h__incl.md5 @@ -0,0 +1 @@ +c28abf312952f1b87f16e819df547fbf \ No newline at end of file diff --git a/doc/html/_me_flame_sensor_8h__incl.png b/doc/html/_me_flame_sensor_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..503881b2dff8bedc2c1e8c9540cd242d90f2d753 GIT binary patch literal 46617 zcmagFbyQSu*fmTeEg)TrBHhv{f`F8WlptM7Gjt;&Em9&iAR*n|1IS1WgVN0a!blI@ z@ScI+^Stjr-}(-J%v!S!=RS8_``Xvu*F?V5R3;&$C&a+OAW>COe1(C5!t15hGQkV@vPsV`VaH$G^Yn`GONwH*V%grGA9>=Dkt)$Oqx? zp~9qN(_Bx(zHA;|Tun-eLNQb)`}$pi%DHJ2#!WUfUkZ55ANxF2{Qtk2yK+eHvjUfq zsQq}Ug4uZ?s5iUDb9=U_ukcw!go@{iB9lD&G4(vu(Q}NS7DKd=Upm?DeCWW&SIT^* zs93FL9TyQ1(F?gd0~(T zp%MMe|9u_*RPp9Pz_TKH@8?u2|M%`zceSS;-rmhB6!Gt$2m1cC1Q1*ze8#!sGL)sk z{jL7?L~8wn=b`M>sNs)x_-`g{|IdnwdDl9(|2bD*lwhud3;%IYkYfR2(FyA3WM!>p zn})KXpKFxY1x&*V@$%+op@>Z2(JZYV7l%i3PTSM)T1Vu%_mD5_oyyS4;ybgO~nl6Gt|mjzkY(+kre=J7Z&U zHI^Y`$-HmhUS>EABHN{e6Kb*46cy!fm+#A;Dx67U&fm$^-!Cgy!C#5r1`K{J-+=!b zA3JyFiETbVb154|{eMdhWh*NCR3O-3h;VOmwXUVLHh=YuqqZp5QpSb%R_(wT6fg~Bd zN~Gvwye;GN{g%O_g7pH)HoHkupTG+rmWG0L@T%#Mh{x&t%w`e`^OJY4Q4RV0XJPv>cC8MeyNK-=0LD3GnqWj0nyLfVu!LJk^o5$eIdz`#Q@UVsFk0m;I z=+C9OmC9nRoxsc-N~K5?)?)6M-?4EqLyyH&Y`fQ$j3EdEfpC zkRu5Vf%wY!>fy-!FPvc+z6e$4)zN7k z$G2MGlIj8wlK*(?ji_5rxVmTV9q}*jy>teD^j>;t?xr=6{Q92=W|m7$j?&jh%uFh%c0K z)`zA0Y50VuG*;a;_}Y(*Ii+-Xrj=DuU0^?5?;i$#9jYqNhZ3)ZW%it3v5*}tN#XAOu8P!lUktPZR_7N;?_odiS;8lbJle^Tq8tJJj{R zATyEuTti%rxffzDDw0yr<{g?9S%tB@9q$91opw~>@@uZJh$nL%TuG$W89e2wbc0Lr zWv}KD?9Hy&F5jf;w*70kjXo@q1d>9_AY~6(R&pFlA8Ak39QIQLTAAHz(ZTYka6ynk z0yvTFr#(j&rq)fB^ZQ~rjCXB5DfmHXGpZn+^2ByMK2x#JLvFR7*qgS`QwYvm>JqfsUfo*w7gd8c0Uf`wUZee=~(GoaVPeJH~Sr0(l+6o z@&uLGs78k4o|yAh&3g8nUfnlHAE|pTX5UOMh10GXDdnhXzcy`l|N0sJgp>hF*`QhJ zmD|h1I-K&~32L~B*~X9oA&`#=Va&iP_4E>7+vMDmY9NO3w#z%m__=R`4qSe|TJJJ{ zJ&!?nW4#!ZAeqGX?#s-><@vm&p7Xx7PBFF0tqIwhVPUE!NPV4sL5IyqNIYbG6i-pe zhS)_TMem2`2&>fF47!%!3Gyjtllgr-{o}Edf%u@P=gMJfH9}8#39qI&+QFn=xOj6- zs)j;#JoA;<4~*sDAj=DAX3vxT5-_-MoBwjB(ft&%od`U$7^(ec$&><(cbP~>QwS4jLE3)Lxu%Z_1M;nb4y)lB@4%m4v zChOvqc3W@gX*6pN$$!z1Pd&PY_iEMMk1WBvG8wNzt?_8Q8Wf8R{&wp$T~LU3E`sWm z>Pu6WfC=LFr<`t^a~FKuHOxp9>d0`C>$cmL|it~shHPs zoAFs$1TC9(?%J;sA}qpbi1|u5tMPrkvy>pTL=sKSKbZ#ur>|d5jdZ{awxw_eGq95A z)$tUS&3cKkZ3s~kL9C-VB}z%;b%hyXLmml7z8#t0sXM1~bFYOP#WCtcS=>T%R(@om<{Na*Rl6*J@W+l0I zy(K~Iac*gOX|2HY0jtoL+kmB8vfUmQqNbab5X!RB(n~({Vp7ZgO=}CMjnOW|p@`@C zk8UYuHcWcWe(QEXSRj1F+TR%2kr;u7_VVID1(@F7*}@ZWDYr}w31$HN!K>f1ZkH;{ z*ml8N3z@(Ed4daNs!McK8a?%$Nm*|*OQ*&E1UCp3B()S~`+b$y;c1U`MfxN`;_S+_2hpMf%2_wgPO~0-~N}O7$&1u$?!y7@X>z*LKzk5{=s@yx6rSjEO?uD5U9s+VVhJR z`O0FEtOBG~rB{vyAM4bA>v-2*ECoq1ys+3&`=gg)syWDKcnE}~7IP}fg!O0-k!Vi| zyQ4$rXPQLjK~$C&wsYz}kyxOfj#W^UxJidQI$udZC-0l7-?0?t4*87ZIcU5ms+o&l zN^GV}J3L8&I$;VsGD&Ju$~(V>S7HT6kk9NX>Dov@wGcW{b=hLeVU!nfR&xXVwCsDe ztsPgzaey>pKM#4%NKlFwNN@k$hQoP(y||jKoyL6C`vgW{POFUFEu7N2T{&!){LIp< zboz0Ru(spGy?EZ+szInXiOoN!lLYeA3D!4m3?^$dlJ2adHO1uv21>8?+$qbeR_@=p z6t_rf0pWeIg!6~2ud_18_^wRJzj}kLBA2Sl%BM}A!V{&Y#b;Fat@I;89e@7SJ;a-* zon;&U@4wJ`)K7n5CLD;9v03?zk+1*gopinjGdG7BslZ&!+E|#Um*`GM-RmQj^y+he zoKt_k;2NgKSV3Y)WKnRMPgwoqb$@K#9>Sr+25}BpDF$JztC1x0yv0S4Z%!NeJD2ze z&u_~M3>vKyO($b(_$i)Nz5-vSz6F`hxkSDPSj+;)D@}U|x>gr9{$S zu(04n=q|qJ6N7Edv0n2FuKtjvP}TG0#hFZEPw};pk?cet`R-4 z3*tR7gyD(76CqNt#URxz1y9nzcrKHLv}vu_|0^uaMgsG(QB z;HEsZ!sv&sG?9z{j+GeXEN`v(ndZA}h~zzDN(UJbGnze65@9>?c9v#m0M<`GS>&V> zZ^cPnY?AKb+JmukQp1UKGuMyP_o1hEBk z-tW_;_1s9{mh+s?)tzd$mH0Cw;Uj0rV%J_rGwSZEDCov@AcfB-9mZ=u$|9Wa? zpO3|XU*Fxh@XV=@w_Z61E}EpvbGT(>Bq4o=ma@x$h%VgqQRUm!1Tsh5=+1tC1*$na zyrZJyxDBcUODb+@u|sMkb~5DL#(2&MI7nWy6(cmtE=t;PsS%WfK`uTB;37 z7jefdzdH`(xmaGjJ5J#ttIBP(ukeLGrKSAJgaBtJHm>w~6>t-9~pXF4!WxCuBFdU6Qk~wNuM|Sr$R2p^?OwVY6|* z)Fh(|M#+T<%*Pzazx~Asg9tK0GBYsrUeipmvyyOQznP*~;8xLIgyPC$LIY^U#? zftN6jQ0tfGb3fzjyNNkv;^yah`#ygl#;K)O*E>=2?nI@WF#&btr`dKH+HiH z`26&dUej@1XADfPAu?sYGo!mi(9w&K)XGBCaF(t5*ELTD&f0cb{eCaio*As>`Wag< zO}oyM*X!We?X_$vnkNqThnPoo^R~U+LBVD?hE2J}B&02&BOj%$p(9UY3eGm(E5{$* z?t^0KoH4j0$_zdmzB)e!_@y4$X3aEsmpev$ky_n7d_28K+yE!yRf7LzE%-fYH3tXf+{@ z_~SU&{Wa(R2IZ(pTg4mRf8?}X(j>i=%zl9t&Vnsh3ZVAc-qh4xtrIuINM3lgXA)MR zsgBk4SVNH&M{0ZTF??XfKO7X|pPhD3Y&64xUnx_gy1*fFN9o%X)>klgZBfW?ZYI6D zRa9e?Tx8U35r60B#-&}fYp7IKXCph+ULCq}$U>@|I3UiqVdcE_EJug?H4nfCLK$45 z+DEjoV!mphfK0Vd;Qf?y&%wc;A!;E3jOzrA&7Rd|5t8W#pO3J=&*))FFcNI0H7S+^ zKccwBg0q)BtPA-faomGVkVQeF#zzU572DKWZcHxm-9B|nq76gBR()u0VgNCc-&US~ zSDUvt>3D_XSFn@V_Yz%*>sp{)sV6(=Ki(a`wL8wHFOtHDSVbZ3pXU?aE#GZyl~ zOYeWH3^kt6*xM<}z66RAT-*$N|Ctz%@B4?-3fmCa!(Iw*j%-44B4lZrh0){$T{Z7K z;+WxHOMu-=5cf-9T??KktK|V91o`GDfa^WG2=&mIZE{J=2TpH*J!MJoXFN{;jGDV& zWZrp;ix^%QRBf5 zxt)?p!s*gB9%6*{_;>$`HmQS*)Y{CdLmodAV`=W$xA2;!kklj!m3S&5luROdg_Za_z5oaJ${aXEPpleaYoP+{x%x zy{1dS0*iPHePqW*MhZYFC0$=m-)8&-Ybt_;nz5oM4@pajW7L46ty|kh(z$AoetDYt|b;WEAo`3cAz=Ejg7Y2UJQfIY>23|!}etQ5{ zPZNXq=QtA`9IZm%Q6(}?dye6CX85hzd0R?<(fajpv5v%{_m+Am;O^#W z^)wMo4rXkOmoKMXRR$DFubsEl+?%v}kXWL&nOrD*__copTx0X_`sWm;x2=_Ii=JlX zcp)g#y(jDt+#w5132|S1=y3+*7#YE?T0DsAV$~zJ(IyNVHh+gZ zYQYoTUzU8>j)s8usrMcZ`T%P0)_Nbk*^vu>IQ$miFb$VSFc;(tGcm7KeE2o#YL4ES z=8S+H5giTvGK?-%P;!5Jf)7oat+kUOg z7A>Lw3ODzD=RDU@(Dk9Mfh5gj%d1;C^nT;j(TwwsSV@PK*}I0e5(*9sr#|}?dZsD9 zfP8con}&6AE^`n`^vC2f0#Jkp@nK#j$oNIVY%k&&A>rjYEGhn(@^^%*)1Z}K;W930 z6(%8j=R@G}v04z-r^Q1g*l#=hD)9D&t8uN>{9E%I$(Owm@Yhilhrbft0L5Z18!z|$ z--pJNGu;BVgJ~jzux;7ZZJJvD<5^{td_;VbIv>S}PQ2K>_D!bdT{DhszJ;6|HL^?zUOxNQC~v0Y1*_l7*NUm5l8>HtdetXesx-QI_Bn}h#C zyX3C^oF0Qe$ig20FEzZQ%d@u#NMrE96@Ht05-=b`6I|B)i)8n&mk^^fHqjYvP>PFC z%moyjGS2D}3*H#KZ2{!;2Q2z!lEBB?)143E(fGRs|MjomiIsiATq<;9;>rGNpDww% za{_$1+e7U*3uLDJB4hdx?!i-SuB=e|Xoshxe0N9k19%>UlzJWu}W2m)`DZ?c%Y!0_|)C9+< zjGoOjqP+kW7G3ZQw}((yNaok>l`SOxfmrf@jIG9p_hRj4&{Uwv(i%-wd?Y!>c0}j` zhxvAJMrhMXM)y;;^WfGXsirKok%`~gtYeUJ$OoU~qYmoJ>hTJuVnjZcdM-O-O54Ks zzwa75(3nUbR4HYFjz=Cw$lBf1@Y3ysqjE50~(d4X#*hjRHN_sN#*0ocM}XBK@-tuZ>(Qp4avJ{n6&|E&ypdGM36T?ZsQ5L~sIVPI66qpT>}4J#qq0#BAR zV)-*Qatxgs`3!Tv*k~PDu2cdHt;jbNBsbeGWc8EsD$+Y4Tp$or+D?M;WU2UGxbHpOe(^Ic#Eqi`X)+ofX2e`&1g z^I7-;4f^#kWuquLjHhZu?4$RlYP4;q>C?G1n~e$^&z0wW-}D#4;=h}9DxT{*et({zBorS-PTUETsYgXPVV#AGep^CMcsAPa-C7L zK5&2Xv4@CXz1>Y=Ld>;t7&x0oEA~xzK6AP?m>YR-I$ayNUcQIN?`r#?k|%kHZa@0d zyw{8rwR}3)N8huvBe|Xawids(Uip_I^KXLF0UD%0bc*TXCB29=h#@LrpIR^6k8~d^ z)Xw$Z?V*v|+ov)0cTL=}KSvJE+3Q@-W*&R6`+1o(NW8i6nL@i@d2uo9{vr6%4)B(u zd%s4hXC$zz{zZzNq&i*DpRDxy%gWI<=+>Ifjf^bi)nE?JHEDTe6}c(n)c}Rc8;y7k zvS*LKRizhrSM#iiCC?!r0@QYx@-45rWD6gIwVKxfbpJMDg3<8K>x}A$oHDrZ!0E=6 zL^*{MEg-;960}}e4RQWSbk8nNrUxCD*B#_*A{;US5`vKRVZ=6ef~SO`i12runexo>jk~1NJf~hW+SjTN8of6| z!+13i)6M(W8Gv`bvVDWmDMiWQ_h7P-8xlq*utXq-vFsXhZT!U};`C)*(|BY5zM;1RM83zKXqsA8$Z}Qs6YCvt{ z;@_6Cz)Wlj5uv!HUTBtZ!{imChiJU0<4oi9b!*!ZcYvhH%%30IHBGh-Yp0nj|1@qW zSl)tEP?K|mD|U*6amc=fnR=#?T{M82b%0gie2%s4B0iS!Zmh@Cc{J76=oeOgi`>F+ zh1X$o+2Ef<)?PBstK!ZEj3t7F;QchZA*oim+OK1VjC_ras9?%B zTL^sMcPEvSo-Bp!;ztH`dw!69e#hkN$l=TfFe5Gt(c`P~*_ve$qcb0^8zCk>u*8v1 z3nV;Y@fS;<0bs+peM4{L?!CkJ9=p4qya z#dy*p;emKFpD>z$GIs{DZ$%$m9(LM|0tmN$8T`w<;aTKw=j?f zSIQ8)^!TKe!cPFen?07>wK3(=ItwauEf=F*{$I&IN>X1GEwJW^R?>=(Dm)%bn#|R< zO_2S)XQH;H=*R5cK62b*q?91j_2qJwc1<85_!2h7uaffNp`fP+J}83SC*@-YPHW6= zbtk=-3DldD8nt9Xw)?_5KP=!(u>ZH&>ex$>Wy}sa_Hd)n;1z2U*_2pgJwUvPmIO!K z=D9!{D21HBs{e#A$cOkd*vO$I2cFEkGT`s!{5Yh_kEHTFJyH9*|c@qqD2l^oM)Lg$9Ij!hUb{cV$k?$Zx1Oy4!m!yM~}s$+#yO1 zaqh#d7CdXvTVStQj|8$U_P`+9xVo?P@5j+;fRR469>Z!@D{(Hh=?r};|GiUIK1MHs z-JcirfsX$pd>^y*F8$E2H$HGrWEh}!4J)&JC3X?%sYlJ`$xSX9+d>0&^Y|SiUFSbU z9#s_9L=x-XY}TV!fJ|+-8lHE(V0F}fdXeY$q3(GmZ#q{(ph~|X))ODdN1#IBT~`+p z*QGL?S-O0ZRL2U-qP`@zx~<#V}4IfAeeag z82I9hX3*~tPFlalXIv=)U{neTIDam^vxfInS`5fw|7yro&N2blPYjG&z!Xd0m-p#% zb{6Gp$^AVaEt%f?^42amn=Qq^$QB6S`I0)2NO;->ke(Pxedh=uhi~(^+4fYLXS@;a zoR5{%(E`qNx0~qRJFloVI$wdo1RG)&P~6*86}pYOB8bs0w>F zHAb-iL4=4`HEXZk0d2|A=4?zxzFk;gNZ2U~=&xDW00(p3bEK z!cw2Pp?Y_g1=o8=N6|7w@rh*S+#id;ZS5@@n!w9)oL%2E9x#&k}C_SsZ7s;DD)&bNsl=O*fO1%YjUj76Ncb09fk+dj0!io}sh4 z1nIsavN+06zQR&M(V0~eG?Qr?fPy8q?^-W-HspFcbk=opbDQq;$;i5Q2o^A}hJ*dt z%m+G3tuMO-I?Oa3<7Jxaj+s>88fQ*}oTPQZp}qIyzh1cp4NH+Q8jR@S;6jUEM?qgR z4-tRjjl*g*I;F5_+J7i)a{q7Xx`iLty1{VJV5XE8i`UM@4$bKuVL$KjQo{=We-k-` z=oYeP&kVcR@t}v>j7v~Q3CxA!G%NdD_*i;>Vjx(mq0v=s%Zd*Q%Z1l+0yeqmM@~FS zCfR3a(L29FtVsvlJQq8+Gy2`pz(wQosdFL(n`zy(UEj!og^s!vZKdeHgtS2l?wnSn zQTVlTR{*J4CT8EBaI0X>$0YrxU&qw8TC0S&+FGVb%Wp;P^5q+e?pXeKaM*|)T;awN z8*4D0!)b(yEtF@J(!OubjAx9Xb&P&pk&vVhrfssY&D}pBigT4?lLQ5Wj z2_Z!;V^ zWR#nP$!)oyyLk+~Xdl)g^%t$s5Am3^}O@)aXBPK@htcTUI$7+VGQ5JLJL>JjR7C3i{9sUQ24 zpzzu+JosCAK4{8&!mVR%TM9b$8-l8$_qr4{i!z15U@L+Msn7sEt#rUuqPi!5|IG<{ zu&xm8Uidc#-#_j?)JpgVLLJ8w$Hc|9sI%IDRIT2Vdk*%Ig)$G{F^Jrou90)RYqq#( ze7_I6_94GNhCdA62lPy|O7ZhMqaMzB4`)8}t z&%S#e$xxu|+B_MvBFkg9iW3@{xA0le5*z-EbO2_c_tuWP;q2))wQ1KqQ2WvvQhM8E z8A!1HCHOB3qQO}hu83NoDK5LEfdj3QEkNH)ilm$N+P=s;57CPjtn*DMgO9gKp%0I+ z=JA&`+AN%TPb4$q^E4~-uzzCt&4CjIx%`U}q-CIACWd1A+3=}4;}RJ})(8pcIVLWp zhIqc8H+%UNwT9PVE^UqKSy%9Tu&&OE{T~ylLOXL>coV_{{2{s6%h5){l!XIB#y6c#nBP>-4vJHP zO&f*zjkr@j<&*j@P6Yxd)&hHmBsqcUe3`!n`Qz;4S4-$k7lTYK6qL8Q?k*gScKB?U@{uf5`w zhCTsgp|dhL6=Dr>g3MtW3pe!YS?^1%5L}mcJAmNjeDy89{#kkYjUWw;_^oe){*HX5 z#}~)3GlFo|fzb4ZN1*r9Q+c)*n*>j=h%73z3-;sx%As%Z!iGW-Xz?6s$%yMfT7f*pc3Vv$zo1_$NEDktFYpwA36n1W)fxSW9oZ!IdU&J6)EYIyN|cFvF9 z;)Yd|UA$|S7@!Pd`jYRRDaXD@gE@g+r=ek731sEXL1dl2;acawuRT?SgD@PYzT4*~ z7ImrCZuIx+fNK7vaUX|pEK=1@@fcTXA<|_#Gx0SEd99Y+yEm%zxwf9Z-Wyui&8OcT zjZ)}>oE%qRr|dIw09zIMeao`>==uTWH~s(GzeuX-G>5sC8p}US^G}vL%Ot4VN`z)O z_^{zPSJv>YvhGG#wACaAPT|x5>d6o53N4N$I}-@GpC{_TB+|pY({%wi0R(6<$@c!T zQI;dNJjdo$vFccGs07s=rmv|r+3%Q+53LDAUIS2Md@W|#{biSSS(Qd!`3o~n8$1SR zOTk4I-2b~c&!G|?WvF&hDDanA_!FJ_%sS98Wz*yKEC`bIj4d!Q6D?m#*~i23qeZx4v}#UU+}U8sh5+$%x~ux4GvTxq%6dG@ZqX| zZ?%C_khUyAhfIgCyD+mN($e~Pwzn+qgAe$ZMo<40*2?O~v+n<_6V2Mh{@Mvc&HV{& zu_}pvEBL~vo>A}p`h7Y#{uLSuZb{}}+}JiInXUN~v7l|Yqr{|^*KuocvAjZCj?S*K zYZ6>Lsji2zaW7?(Y_*fns^cvF#rLAf;jj^h0DV&_IQ~lgCW-h1t6C&3_N^-Ae|rj| zCH0epvJxf3O;~45odEoW%v)>~y+LT5$9e!uf^G z*mOmRwvBoTU+u#4Ox3)O+qPfF8oP3QLcwj-Fn^5&k+3~Hxq(<8ys>lXe%$mkC%3P0#LnjVRNGHQ<>bvvIM2>C%es$w`1Njs2GN_I72DC zC^p7jZJbxW-QYG6q)J5Ts9@gvxtF@>suZ%m`tC_%ry+3KOh;4e9|=30?K2B8Ehj=Y zoMxZ(DkMYxlmPzm*s}O&td@0u7JxF2L8Ntq7i$A_X4>h=2b|wQ?5Ly_7vCUbRdx!h z8@zp{4)l@`G?819A#4U$-mzcKEo}rxyYN*8Q?W=;&z;J}C|#~et)pECKTKO%V@$@) zm(G}Sg{cl?N~zo?JIa(O21IB4Y0}XuS3J7^-i4X1r!XyXD}UZs)9W?gaYjmd(;tLC zsQoP<-)q~h7oT9avk1a*`h!DNDo9(Ts9p*KVvWqO3s&CsrLVQj^4zyzLClkT0*u~$ z*`2Xxlg|TnfL_%&@%I&6YA5k{9Z&*GOm=;$X;UEE4YS;2J33aI#~0texwfHOIKuV# zcKA*29pj^W<7hkIQlliiu80|50Ffak-iPk)T`zUy0{YL3?g^j6vDRpGbD*&-$=}D>qF7e`_U;xXsQSqR!Lggw`rP{ z=YW3>IRtXx@0p?XNLcWCOUT&QZY184XCgYBX*+izQ#SsXw4e72ae3~DxuodbIpTLT z(h~fErSs0z1fPc)Y@uqJML3y$%fL=)3sNa7`0BHiGFAU;UBxRx6DN`<68^dMU!=~u z>vK8kNTf+Ji|{Bz%vVdj9^N-QLg}p@Oz;QW@b2bzeNhYH$Ed&nSqQGa)~K!{S3Z}Q zUc|>B!{T2-3ZIS>966avH%PB7xY#}in8zf|&_*Pk+6Ba*m(|QjSXSzbZ3$ZLv0zBW z$jrlU6lvw8`BTRS9dzrs zprCs}kmDN07qb#{-{gJAhbUKP@n?OC z?U>@2%U}bDwQl0(N+IYlAN?Z@32^RQ>Ng4M%WF)`t$aZ-$@G{*ZQI^ zZ4B3r@P?A;#%8%I@R8yVlvM12e^zdYh|>j^4J=)13LGI0cF(y*SnB8M8Y#)VJP%AfRM7c(EgRFQV=;m9_av`9*#vQpdZQ=K5-8dj0 z$jv$-G9h9DfjjV}3q9&OQ|njYgUdNXLWkNfeSjtV!fH{91L!X^khO;BhsX#7GJU*o zajLqMSa(QIp!<9#b^q%NSBrbk{FVu>%Q{T~aj&&K&{NAAPiz5ec4qV^EJU=?M-AvC zDV551QpZ2Sryn#_foPQwUCa4-F|+6fhy-4Mwyj29$p2{$$*Ifv9TnwRRHu6{m7sAH zcQogY@Uz$V>a>g;%e2zR$D2KN3mQMFXCnyTE8S1Ud=dcWTYu;pUjP2Be005mp|Oe( zXlN%cb&|G5Sj@}DZN7qrpDncs`4>JY09y5f>znLL$?d<>)m<;WCNzC2{tV$h95=(j zLDociJVXY_P{>IJ;bq@E?17M=Mn0;2_P&k_c;B}xiymgn7{SMJ*0S+!_f8&ET4%#n z)~v1+i`i##Y(1&p5I7Lm-Yu3j6g@mA`yKM{{ahk7->bz}*#=?Ltl_4sXZ@vgB$9cB zk;+v4V~dm1k$Yrvdl5f9cv12^kK~RX2AV2S`sQ#QKfK^g{#&asJIAFXFHRrMnd471 zNwVVlku8LJ8=k!IbpIXja#k4dm*SM-wBERl?DuEW`HeD$3Ma@h&DmbaM@v+BerR3y z(u5x1b05(Huk6EBGj=ctu~ll~G=zE(K?giL_V->q`Hqjl&ZRD&dWU#>tNvfj`k`9+ zOa88CmV9wGny-gL21Qw3NotBkIQ0>3;e^)}9W&Wy7H=}Yrbw1jPjct`TRshI-PY%e zZ@eN}`Bg>OG+4oS#w9#@Mo!-Ub}_w<(mHlQ!pB-O^J^fj8EgMN1o8dsN;vJl1$L6;CPm7sQO*xCa5o>Kp18zqxKx-b&4bgb6pjgT3h|HB^Y8F|7UyX2yr4an0QHGLjUVhi0ZL^saxVqU z%%ApqS=Yy4F{s|rx_E(C*zpse7Ty)N6&5)tA|2FHMsYPEFh&cRs2N`T63Q z_n|1(L5>(rs`d@9HW|D|3_f%+V;1=wa zZa(}|g%DjMp*3TFR&aWQ)ADyV9kvx^&4BoKEXJ7rogNZSSC0&lwzA2tb5gk1^5UY@ zN!N$MDNKUaRe1darxGr>F3)&+$q3unYIMExw;%H9y!>(BU*ltgvG?5+wmPak<&J$} zrgWWxd=|oj`!JlxSUUu>$?Dqa(IvKADQoZ|im%y>C8Pxtnn}rlNUIqA(n;WeLH{EO#OAICw+TKJ#Su_z@I@TTqI;gRl&Pb1?qnD*O4w}4~VZWy|Ch-%JGnl!9bP>VT-FQawg5p3T+SMQ$;7+*NWFg z;zH=|*#7#kSGgcTw~Tum6iqL5SzY0ZjhK_UcUSig+>H(#>YNof4qs6PV$a?s>N~D+ zh0T96Ebznm7_Hk#ON+xpdS_yFz-;8`2hX_tsoAzt>OT(l)qYa*MPC_>kN7(In;AnL zERIUcXC7hrAq~chNvBVz5MG*r5s%$ViAIzph$boRaHy$>j_1jfg3dC)YZ1kYdV3y8 zL@H#S^Ms>6l4dS5HpcXHlO-9TuH1L27L87)uimNu&k|=F9-gt$1jYhw-`lUFxc59# zz(ka1Q`9Mza&^FJD;nx0Sa{4h{;6T3nBWdEz2jf;_)!P!Xt#yJqzpe{Nk}^f5-!h! zA%@&{$mfg}5h%=1!YUyA_+DWTzXSB1DsqDj5@+$?v~;1#O2;}gkZ%QbN8qP+dn$L2 zh@4e<$1c`L$VhM|4!yC#YrXzw4Y4W5m+(LSZ`|v)i+Eua;Y7Mq3?IpZKteC#`-=Gb& zc80o56%j{R(lSjg!wob)C>O@y=8q?eGkv3*c*xYqD2_jgG0SLYZqi=6_`3Yh5-F0d z=*6R_b$3RLt=$||=>1hHbQXOt!|r@HQ2C6KN^v0KAA6eQ76-x6wwYoWhQSJ-X5@9b zhh*PT4O@ZqG4_G~rxzdx@^UF~@UKwjz(os6LzfTlGo|-**hYin%F_;HvJ!TFH)6Q8YypEDm!} z{uK4()q2y4_rG&UW{RGQD=!+=J@64Q5|qm4TEt<;NFm6;kU%qH!&+?=stQf~; z>ucjxQhy`nQ(c38K0hl(YVl1}{kPz@VsG>LrV z&e!jd*C&so z?{sT{ap+A^cnc@9da|Hrr}xyRPFj1BasGM!s|;)y&T}khjN>Aqj(UZwRcFs1Z7RlO z3MYL1rx5C}joDY*sEvgV6@`kYO)rvF9K(1}5AiLl`=Vq33|9a8w$|9ok#iN2mi@%j zqeaEIqZDNy;tH92_4D}s<6f!DB%6x58R|>L?0W|IJURw#j@;KXf%&mCtONmsD|c{S z1~L#)WM2Boj*R~7hQt@EAGxKJyz_WtvMNA%!iO?M1mc%x(InKF^c+mXB34rfx(|iHFuJfA*23Luc}G z*H1zVah|Pq#zEz%0Pd4-3TC%QHd<)rm0VQy#<*k5njQ7iTFvmH?m9?Q@ss-(`i?5# z{ReY=N=wZQ{RF9D(_MTX&W)XkBh@Xe-zz@Fp`~8b> zPcS(2zol;QhQ&9w$GN-H?PJmU(tYE*M5-Da4MS@GY+t->5AUWbZjIdQHVEU{ z6<(=to}+$i*uIc>(bQq;-7x6ft?!L#{^+jV@m5f@%WI97CL3$Jtge~F(l|dY9;D7q zZRH&Lej{AKh2zart-!75IyjR=Q~Rx(LB$^%UVf^*Y?dDmJH~ClN7Tn1xH6F${dJ>! zQ0ZbuTVbE;(V~~^rL|}1_VDP>Ir+Pb*NUgbHc=i}s=DCMVYIfw_E(nAL%-stNsx<^ zt-K!YSsKgXnQe~EZ+n|6&i$Qz>s;I;P==klxL>!~RH%fNFV z268^o#}Op1wNDUK^s&)xzP3_*^nC*1M)e{0L)5^kJURYrEi-!?z99{H370uIUq_R5 z!jnT0J#^$Vbn_TBD6zM(omrWQAso%9`m0~lmAK^>l9x?@bPZIH6{dV~VSiV_jNFV9 z!iSAC0F|0{etEhq1wGC&*2B#p@x#5lj zxj3Kx%qT0tC00KXss96g(7_8E7Z5h;khFb^^`qmY!!MgB|Lzt<>M)9HEqa@AuYDa2 zt9#14Rjwjhra9n6i2D40$a)K)D8G1rn3NPjT1vWG>5}eVa#>JP>FyE`X{5WmyURsD zmK3DBL|95n+W)is?!7bbyfZKiGc5a@`kqgnvz4!i(1l8GWEZ9+)1Ogp_)tYSHTKD_ z*96$R>m@s7iBg82xj17;oBKfjTl6Hd&tJ$#G~XLpS$-2o$;IeFSvKMD`x~2g*I4Te zZ0>#QU;QS+H0?EG;fME?FPd!bJqDG0RL-&bzR=kzTU{O>w!h z-`er7J=>3Q>Xw&n6DCP8xf?H*9IKkvitYc0Ec!zUnaJkr&UmmyRlA_ofO`|0j;;{t z6=j`z5~BkzjxF=|%Ia1e=JUTOLwRV5q_UYH;no)EfL;Bguqv1Iqb#;xZ0pzr4+l>$ zTm8kvqB`ZH5;MIN*Wqo^acT+HU9s;~TMX)l0FJbP+_))Xw1EZkII6>^Z7Lf%UBnjl zSJ<>zO&Y?7X+{$NBq*6h+X=pGwQuFT8SZ0Qw2M-Y3^z~QiJ=-Ul~gmV5=~A$`-I)u z%0B6rFi96#hEMSz)VLIQN}={!j%)Prglw+>93`^6(Q&s}X}{&F)&!vdk@c5azij@X zrHHi*PT0Q5AtJpsW~h-wDH)LFn>q&HjD%s`+da?Gvvd^UK5uGxJLXTM_S=B8B+3Pk zhX_FlG2;rv6f#|F^U|49C_YJk1qlodQSj^iCPhUKz==i+5V^y0IKKf;*i1G^5xV!W zFb@d+QcFqginjjWhVK=gD6c4hXOVoRFe-f(olIggC6yjZTY33h8IOo8E3g+!W=iCe z!_xTYj7=*788NKRO-nUx+WT5!4(z|d0Zi5`7;Z;<}69R+YD@*9p)d7xk zB9g{Yb|w|nK+zcbC{Wd23#`b5HzAn9&{v^}ul;+%@NyE-z@*QCmWm=kM?aFJd^?K4 zjP|#79Omzxkik)0S<{$?a3WW?-Z4BrD~$gJcrWBcn~H%^EY^v~?OGluiRff*L&L?u zQ6d<(_Gd)w2%VYWVObi3oxC?0CWRI(C-w%KqB*Me?CFiTTDq6 zt;UCK`^JJvez^gs>8ddFeUBs6k zUX;{(zFt!8>Nj2v0Kcwr+q{e(qwo}lc8v`(5Z7r(Ub>;&t##<&24j}dYe)iQkl#wd zZEnjJv4MLCymA)h8k#oxJ)HCc4Xo7L=Xif=6}pCVC!chdfVXnA&07iS)s^^6Dwm!u zVUhYzueEHXyB_;`;4Xf98P7;`9~v4!veB6?t${rstGQJq#6Xg;W&Xx+c5kAJZ6kDC zu01j*u#J%=T;cgm497jDuu9S~azZ;KQ`5o2L;4bI-g6CF@;8$g-(A~?e zf}&*QHtX=g1I$pPwT?#+03u9c7mIyO?q#qs)J)qxJ7O?+p8OvYqmG<~3$rcL?R_1J z={sZfav)7@ZdFYv>7f>UJ{O|frk_-Jw9FQ9L`hHS?>{4xS;TzeMT}t0HObNk>NB zl6wnDE{jqNhZE1f_=r=y&6l#9Cj=ktsGIx<)vIv9fQ}ky2Eaj-<~OiMc+v41xWSE) z&ZT6{`>Mtb|CRm75pNXCNu%eQSqRtlt)P|%>HJg6&)6ZsCL$e~Y^=^sT9Kf%p9{)K z`}_Nh6&ap!+3d)aW2+?wq+q9D=34KH%1VXG{U`|K5<6>YXi(-%%tC<6S9DTc%d;Ty zGN5AUph4I$@!Co7;cL6Irw_$x+m^+as^`xkmv zcJ?zd^_pwA>AwuS5Bp~YEp|dkUV^DO;`UE}!WrhyhulTub3GfYTPL;GvlCO@~vqR)csN+2@p@r&1PS0jvUsUH>qK(x@L*gfwb$J_}3*s+m+S`sri^8vmxH zC5vA_-9#%(_(cz!2z?Km^-Yg+{@xVMH{Kp~HjZ#naY5N^xVz62)<$ITq`b#=DShnn zAk6J0k~K@g4_%q|-Tu^ZpzjHa(&71cd`7j7bGqM6au}Ejj7j0%J3Dv5NGbqNm?J^o zLDhIiKCRM1k&4jpqK8%JD1#Cu0b-^4F9LmM4n?q1lQ0H8*ByzNf3lJMLH^1~VJ&AF z!^Hooet;OO^tx9MkY#V?>X@%$G2OYuc=+@CyCVrRIULJeM4YtU81=o0htgK-9t9KN zJ@n~`5anG&55(x8gf)%+u*0HK$}yYW6$vt?4MgiHguVU|`t-NJ!+#nn@Cs2<&N-7{ zT4dt|^XNS&0I}|q`rr2<@9Zq^SymY+I-tL+_&E+>EXW{ViRk}5n6)nf2GY6_fQP1= z(Fu1fL-+cc09e))-R#azipnj57sU=JfQZ+y|KDpArj}}KN5-rEijtbE9z~&Bk~dHCL8D`k0p9<4r!A~6HG+k|k8Y_}dM-2s4u3m0W^43N023(u zUv9NIo?CYIT2IbjKZ#a4%9l_{lIYaKfZc=HoRxkp9$zC9;PpC?f)%3v`|qM7T#WNr!R5rqkfJDmSA77uR9!UzfX^`#7>06S5oSe8=H}_Z{AODLTkpmTp z08F$r)B{2w!w(rO&tV8uXqPhc@G4e6=S$(WH+)3zrHdp|BE~b*G{RoqYtp%Yr>6zU zS5_PpjBv2qIcbe|TO}Pb*{y!oGuOG&lKP7Hf){(V983-N)P67;$NAoFozFF=#?4jF zb@+_l`t)>keiG>NtN{?JvkvQ6G^TjNiABik z#;d+@t#{)C>{QJP*8?>Z(4UDzuTyJexOG7hqPE45gN`b!+HK=zr&j&?3XK%CAEA&6 zSocQqjpm`O;U0*?yl=4$z)Hr+Z`Z*4((?h!w&v-$~5PU#~c)zni#0 zcnY3e_xbm)r#nQd8U^7H68uK*`^97F%Y)zMtJCS4hwh%7ze2nTcML)A@W7ItZ#@6- z>8WWRVNgF$-3Ng7HqbqGmI%jYt(p6`TkDLEV{b40b(7?!l!4YylT588(#wSxO$(Q4 z*AIjFqW8`LqM`x$S;p?yV$hL*-HqawIRC(BO^5q04h~gwYEB*g@q47m;oPWG~S=!^k#+#H!*XQ>0X2Y2w;FR;sOtSZu!T zYhTYH_}<^n$mxZDe=oemhxtvRzd@R57_VSkmy6cKZA@^>(y;hCj(DDzjmEqPQyA3pN!Gy_NWXZVM zy~Edu+iJD%W>n)n>74Id`aY&RS7*~Cly*m2J`u3p;sZ90Me@(p#)I4GA#ymrKsS{H z+OI&tpw(FU^%P1B1VGdHE0dT=rwOgiV4r(_j)+}GJr zyr>I6H8`y?sbp6vQRatEXwm`t$KHD$0{0Db`w zCS08wAv>u7_YUOqPo%|(mFdgvubv+PcDV@RV%CmQA-pxy;1e%6X(MI=F!MIXMH26 zmP_uyMqH8pJ>&~oAeImqE9>}u71pVG5d<&=!Z(s%RA#gMJK@VAH+bw;bha+-zh5nr z`fSYXeoZKnqM(fRv7^NF)e_7S_a}Oy?c`EX0btJXKCPX1(Cv*7Su+Wjd9;FTQs`A}spijJNAvE=ot}SElkDb=3V}lzxJ0rX@X)=u31RjKE1725?OHrT<5Oghph>Tp@UJ0tp+wx*jG< zNHD2fdqauzegnaljxJ-y`iC$!;s7H+qw^wQ>e6P8R9SW>mkdm}(-4TG0z?*f!)T{G z%zvoMJ(f7V#(bcRM)IMwV73P7zs!AbAxgqbmcUa{8gtc+3UG;NY2?C7Xw2(3?c;E- zAE5!J$uvk9-=t3+Yq!#&)(F-8j}|C|q*|jsw`dBT%AG8X?}bp(x$8Me5-IU)WSx5Q zAW67204_u9b`fTsazY}yy0#FBlV*;TK?$tCnRs(SVQQmTL{T~YSr#^!3TOBNGJpbP z2UwjHE0TBtNB`1}y0bz#`(jH75~`du9po8|PPc4Gm^9Y_;FDmctVwLG{h<6ytM6o6 z%}!uPm(a%Sd`eBA*S*MX|C63=3r4HU?G-C_gN z%=%?S10>8ncB%|7=7pL4Ay(HXi_2kH1Hw(T!8aw|U|1)bLNDOVGDjV53(Of8kJ!OQEH!RjI%rIe< z`*oC-3jxJ$tz#Z8~-+o_L_{wtz~FiDjJK0mJk z+|aIAYwSz};IqOQHOTiB9-x$u02-Nicb8$K?*;n_-J-9x!eAAEdtIw@hOHmJfjL~PMi zm@KgtpudTI)AjLQ9ip+kgH5oexEdt9*syKl+AX=wn;^{2IkX+2TJv}wm(9@(rPI(gVW4d)W}k?7D|+=!nj>qbWK2?V zzTSyd|JlHIfQKfg>cBrhFi6$RLa;6+-;h zSxvL%gfHd4>4j_1on9R>^&8VRk+Ev*@<`1;Iq}fYsuP9anra%&z)| z?!=3OVft>Au}c?2*fOgSW@m;w$s+AexO_N(XE(T=sMwtoRA&@9KT->=;{zXHC*XxeSkU^*f|9s6mGK!w_a=8uD8pNaEab7S>Yf{%u1M(KHB4rYthd!t-(FiUFY>WP>#t8eB_{r~XuFL^w*zaIX>` z1lrco1gv@+|HylW0UKxXrNr#IWxm;M*oW-P(_-;T{>Pfj@Rya6o~M(E;p~3Aoc~KG zm;AL$BacX`-j7k6N!nnhag1L`x%7>T)*~b&3oTVvFCUHJxApOUE01$RqX=S6zdXrt zus~BwNayVTV&jj2CfB7%3ahGI0JB*%um8-C57~m5!rFY5?z&z|q0I#x+QVZrB2?G9 zzA1joIqoK0E!OTDQHe&)zqib=f^} zsHvDTo_*=DX!pNafVeF$0ya>(F=SkW-r3|OH2d`%@3CXCm_J#3%E|5lrEjCj)4-My z^vhsuX5_!VR2oSNM9?zGyH59vp1NdUw6f*~K4haRO2+wrXdZ8|fAwpmBHYh@VqaM( ze_FPjWTTue%|}7=Vb4=toB;4pP+Hedcjg(q2ao+k63KN%snVX}5_+j7?{8S%ai!|} zkT=o;s86;d2CnxwK&oGS)IRrPynZ9R0yp>(8Vjd^@_?K04e^fURjF+iYw`S_= zFoUTZrF?r)lqjYGlIZkTJF2I3Er@iO>tc7x@u6XMIU+ zetd|GpGR&>L}#OAO8c_SzN_o_Jr5{?!GK%SgfPJtz@gX)h^p6ay4AJcqVv2WNeH~njzg@Yu32y6_4AB)jtdb8;4TntoERwfY`Sykcp+fV zA8>1>d(s74m21+VAEbI3LJQ0irpBLFw0XkGo9BLOyll_sa*UsPmfAIKU%$5NEc1ZvXRA>cov&OtGJ$Jcp4Fm z3)s!(Txqg4$*2WN3l!~jK!8+Ae!bu1nP1>5&QJGmEp@OH~vx?n@RiR#+Hhh&OBqP!;*59s@1dJVv4QeFkPkCvtgc zHcuePFM{PkFGgTqvuB)4uA@?jLi8#>xnj8@o(0>iH?*pa8i zg5IN5Ovx?H2z%ex*@r@KRD}hzMa+AKnqA~GlurIKKpy%7^iy;M!qN3Lj+~!{k39p( z<;%JXgZVSSPM;nzD5(P|T^fo$;7h@E4*o`Pj!zF{ck>G_u++^G&*r~+lIMJ;_s{`Q z!@JR?XTVn8PX5&B*DL4DK3r@k2@THzXOpnHQvRg+usf^9{~u6Xkuq$za?yB|FIeXC zj)Otr3Sh*8NUA^ziZ5J^W!jwBB{#L6j@>N~rK<+^BkU?a@lR~CGr5iw!e%RXGFajq z7kuR$YSAL3zrjc_8>!MP@=7`AUuF8sQxn`upe#xdunDV_zvo(5X@ywg+$~EC%k?HO}RYDvjUZU$RJ{Jtvoom9^j2V+O zD3Wg4e$Fqm!+|6eUH6s|8jFHKg|fSSyaEQai)*VF2pgf_agZcr-UG|e+$e18Mklz@ zoK|=qZUC%IhPpB)hB+^)5h6T5Kvs>-1kzlelFqI*aMeE1JCSF!E5RqX8By(RTr~VE z#M#pwCZ^nc_1sVbFpPLWcKb!-XijGIPF+OjcoXV{~C#D@8|sGXHlzX8F3Y&xYcH~3#{&8&Dggthjh z;=!63Z0_?7z(U*cc%PW!(B(Vu@onV2<)&p4Q=k3J9~QSfH1rn)w5azEbR{tIzGvpN z4t1NffOxw-8VXrw35*3CCscc!-^NTzgmq{J&rOQMJGe+AUEG}$Diozt%e74?5@rH+ z-(yD!MT4B)1D9R`Fg~qCyI73C2Ff@r)HhAy8LTfywquD4>?biJWHh>f4P~qr?Ut;C zQphip7>9BRTi(`@N&E|NP~4*6HvhMWhN4`6pC#+1nCwq9-XeIMOA-S=#I}B7B-C_c zv9Rqa5rF-u6YQ4pQIMg&iqu>|^W?_HJ4iNT5~aiHmQUulm2oLU>@cdnz~CVL9FTS? zPIU&9l%9@JK$6_;iZ;iNsy^TyG)EM0zG2cOJhgzvbb4YBX&Wss!>LO5fRMTxvYaM+ zV&B2V#s+qP3?_Agyv2(toAab0e??2d=U+yWMbU+XL8IJ3h5@@BLNN^O1&e}5TGYtq^yd}>>s4_-NKQReb$P_*?F!n{M zT}X6YGw@CEgsQm5Cp91mp|^>UB*6XESsi6JJBWlBKrk})#Q-CKp1_BkyD*bkN|BFI zaAeyWnOJJCvvY_2AFa}Xu5u?oAa{BP;2-nFkpqM41~!E`z0cN51qz!lQ1)9paeI6d z>;NZ%m1B0$QdJPj?oP9OZbu~{{>qyIrh*Osj;rS2>@{cwIv}&1*r#dK`~B4+Xbsty zMYTy#r<)LyhdKFO_4H_RpT-?vzgk#DS3l9yA9Oz^QpK>UJngmt)94iYc#-!uCVQ3e z4=_?j6cj7vTmXJd^qwLILoFbyv?Mz0oL0>j!bk{Muz1J-V`+~7pjC-l?T9=K8G7`W z^SmFteH->ILV>7W>Kkv?+v!rRE7`qf^xziZhdDF7R*dHi`t3MgjQHzi`-GO=Yr;F3 zz)ydMe97lK9lzO3z^(;%#fN_jvBVp#=$)={Vv>fqIyG}Jf%-am&e73$4oBWJ_xB)=;Ec9+IQhF4E zKNtFmCQKGr=*~Uy{)uhzL@J417l7qr07Imh$j{obM8c3zM3#eEKQ6nm1739Q>9fE# z%wcii)4! zTa^b(3)m5lanU+_OxDrzr^8(V>h&+f9*H#6F4!bE7X@$qrS9NIZMbWsuss5Ev1HLn z7emq38S`3-KWBsyZkqs!{fCHe7o4B~9b;NSAUX?(l}wHA`@4->`My`iV6y4&1(Xvx zwn5u~4AxW>S;@&fj9P~Wk#x&jnK#wmI~+54Th*u42SKW^leIyk)-)gu8U(=00`vFP zhRdpl#sJFX*pZ#-{qvE-@V|2K3m#(X=lRh@Ljz31gaJE-HXme8!9|c`!Zu=BBs9J? z69i2` z{Wz?Qbt=N)C>p*5^fOrjVH+%$Jp<=y#J;MK54{vAfYv9J#gL1fz}Ce8HF9p(p?a}G zq%oSy@b6UgI2gLvcw=f6f2D?*%SuR+e={~KZB+!B(93_~#guLVLu6GZ_DG`7p5LTD z-{}o@#A>_Am3}5g0CkoqPD$l+jpG9J+RALcaV^W1zKTca=k()M9CIvezgOVqZ#z$@{VBYcxRB7k2!QpQC??^Mt;@iDtMj`9QJ9_zxZg zK(AK&!XK54NhRj9IXk^J(lpvT40#59a#uf6IKldm@rht|-E{pXj8t73M$Uj;BNiYI z$>f9q(-ir4A`1Yk{>3jhTp5$~H7dnhPC0Cx70bJQ%Nf|-J*7jKb8!8?>|3nHa%qxu z7dPw#vDH|^29FEs2w3{jn3W$sx`dGq`826H z$6{!-jk>)%{Wi<99p9@;@Ne^F)v_x@S`t+kmGxYbQ??+_DUGdkfNh)LA0LNmecqj8 z8zc^uTAoFL_2}f2bYll#hI~TbvgCJi1tqUG1W*n|X_mv5PhA3DM8N+C3?Cl1KG-mQ z9(icPwf(TE@nc4$-s)r5R)3tCPnk;$N$0Uk8#EgsT=I&a7htCPxI2w?4eF5I#xEh} zboB0jAT$lr97N8@BhnmEFO@EZ0~^UW8aAy_HjnD(7fAeyTJhX)7&vB{E?B}mtyaIQ zb7(m1=9^No)L4L+O7Bu_LGy_k2wxq+(gh%%w!N^qH(m;1lo==Yyt$7b^U?U(5~ZmQzCpkB#(6lp|H}6ENla@{4S$ zRDXx==Mk5>f<6!e+ClldknI>=?>AwjnwK%(+*^SNU-ktOSBR4o)xky99&hG?c|%3> zQyfboo{V$9Y#Aj}+f1$53K@E3gk94RMv6!Sm?lyqSmzwv0?zHN+JvBPlBcxv$Ri+XY7rP!o$sK$2Z33z-k7dI0b01A{_6D*eE3m+$iC@4f`^JPPD(NNLEp<9_Y;73`$6#jtij zrd+PY%5VVcEf?{pL22!cM^sD?2*D?`&@f=m3M_>`n}f5`ai}FXOala1d}&B9Y3whXg*Lv%FQWL!%cP+2~b#&hc?L8^#gVV<6k*i7l`2QyNSQ| zK~HIeasvKq`&uH{p;Pq6(JK20new-Y9_8!7ZPKtgt;@gL>wC|>*r}K75wl-zmpgR_ zxOemDuREb>CeTr;b4QBjF8-n%6zE?~ujrFkJO0$Hs^sYEU~h0ut6d97=^z%{PEj2U zS+i291XDfzdF3j<0%V6&4T-=~hHhki<>?UHV_OpHrZ>9}Wq{KOC~a}%uhNX2%F!tG zuRpDMKYhgori(AgoD(Vdj7eJi54#`8*0&y@;s&CJ*0PrwL$@BwRW~gZ&O+ZUEEJ+? zH`D$2sOgU>;eY~Z*(9QuEa^Va6x`f$FPE~SMhrsxov(4@b^nh*lk_JFT(SQPP2GRV zx}lFrAb3CCdz%i%b|9dw+c~|aGpgNX(aj5*?0636B|ZA!;yu53>>^`Dc7_fd{|R%- zWRdBwyy#oRI;~i1e~R{{jT((oK_dqP8C@Y%Co&^Kzh+9uKJ^U^mMKP#F%LxGHailC zG(?V2V7}qTtA$5eJOTJ||ivjE<)7c=tlI_*_%0U3$*Mcg1!)lTux=xO!z-V%NSOiv|2a zHj2w_G*S?uarH`dFxV$Oez36Kgl?@Y^0MC?Y?{&6Wu(;4R)>6aBJ@ANaNBGiu9O8Bo;qI^i0MvvcxC>l-nZ9 zXjw~KD4cbrWY{;?XA`8O(-`+T>$e=w6Wxn1H#avXJ>P@t)Q5JSgz}yXkg@-O@~8 zeF&nF&6p-JHCGD4vBBYdu_x8Bn1M!OAOX)n*VQg>{mAda< z7ve%DOB2MW^J?|~`Z*ZNS6Sb0oLxhZ@RWvH&Mqh!j=M2|FS@htSVomYvA@L`@Q$_A z%NEz7?x&^h)8ljgD-UbsBZ6>SNWg^4WL})9uP8IBTnxXd>a(S)q(lheFnc+Jxm2%HyCZ&Dlh{dWa(QVt5I4Q zC*iXj5Pkj48x`VuxY*1AZsQ57_siH4>Vd(OOEhwGX7AH_fEYlulhCq$RQ;PqSIv#@ z--L(9{r3`Ku0egN#5u<6sjb=#Z-59&-hhr*rxoLpiQ33HJXg+}|LM|e@2X?8kHb}{ z>g4QBx!7w@{9a_Xc!o=@-Ag31WO&6}Ax<8r*_E7FuGd0_0DT*ku3-N(rO#TYePQv| z4XrNIpke4dkH5!y83_#ma1EhvJW;u5sN(;J|K$3@xv9h-e%Pb-{PZb zLWDX;`^Fq+wbu>mzNW|U3Xg73nZ+eJOvf?NWR8rta zG^DPd34t2}G(%-H2T?Ilw&43e%PR>5`)MfX?qam`-N&b(xHr-u7Rwznb9skl{|#^HIi5%KEW&2fHrVP)f9v^-;QifTiC9tP@G|@TyCe|uqLFG+afZ&=2LQ^wPhzkbIw3h%-Xn)Bc0sX zTFdKKDY#2rGD~>o(-0>gf#>3P)w3msD($=U&ea2d`m$T4V(1_^L=(}-5iek#-`xF` zYF(NZxbg9?yFId%45P~)YJvB5{yXzP&h(XDC=_@Y_WGl{)?Trl9efhW$|k&h`b;c(H-q-p`O9wT55&^ zY|vm#?&1%=B~C@+3)A-~(jY>vxr+;3h}&n(ibc49Z{+Yf*EBHe4LttsX*3k}!i)ON zBo#dM0&cnIU^V1I+~aQ|V%`7VssoZ(JBeBGffSX9 zAnBwrOExMrrica@a3GP_s*bKcMLbFPAU*PM%rM^jR}8%44w5Y|3qSY2?c4D+HbIEvAz*VGhbN}xJ_W8O)7gmFV(VQ3`S)&)yuhIrn(q1 z8~La|q-mA_-NG4>C9T%;(p~KNN zoF06|l0effeQzjHIX(3tjiwcG?ZX<`J4J8}#}T&&hf`yX3kAL%Min)eq}wh$D4DtT z+hGd{6tKQ_;sF5}_lX@_izRj(qi;fdA*qJ<5S(JY#sr$+?~-eCZ6P@%1v3dWf0h1a z+}uI6RF%0`&1(CM_i5<)Ss(IewRVT-VZwS6AsVH~1aW-F1;B6GR&8KjC>a;$Tv~$P zf0-aPf$UAxkLlw2CnpCtwU9>#S25+9%xF&Fe%nTY`#g%ql zx$|ZNE&38KIvaDse>Is&63s~H`TS7u4rB>smO8+kDX5gY?-nJAke5T?+oU z4cama1ekE_btQN2hO*D@z`URHF#=PTuy%nY)0z3nig^buLNT?L-?SV=@KL|qH)PEQs3ls=*y`9PHauW z9A8fm=ZYrv3jCwHkX2C!Xh%TZLF^*rJlE?~BzmwgBm|hE2^{@Grz%Ar?h=WaTB-dU z^F8~C25~Gpbvo(PpIqa9$^HFr7ng)Um+ybZ2YEXEU3i`u0Z%6iv%uDk3p@Fh={Rmd z>8*nNX7k_a>R=4T;e1BYVu!n}{AHuVipZ+pG?V?GMPtYAp??jBxUBYCkrph|%XQ=&O`*I87Z%t*K*og#47R@_kRgGv02sAlu4&c2GM zAd#E9q{E*l1Ksn6oLK-8M_#1C=u0`Yu-$QF0-vouqodZ?`$I}KJgdK!x+`5%!Q{wX{F=j>H3Kytm5rE$?Y^RTc(yWIy?p{1o4gzR%u0_LXbx zoy)nT!dq$_6~BnA6>+Qy46{z{QS^n!HXS#TdK`^7s_nw?-U)I}JdyUHu7e6@G`i!2 z%f3ayBm8EGB3+GR8Sz}o*!bFdy8ZdZRUt4&xoC7OjHo8PHR{=FCyb$@+T^LMVqvG6 zwT>0qRGX=EclaA~Ux)8}*=`ar^nM2rX@$5@pLnmMhl$SYjLYeKE14RJ-zO0_3{39e#=y0JNl zo-`3TtKTztFTvABOF^$I9Iu?1HZ>Vx!hK{(sWWedxzwHpP>=umYQ~>^u&3Lt8?M3% z2OFQKro3D~_Kl zT(T`pmse=1d`flA>3bH`uSGq$QL%23V(pqRx}72wB@x;`Xcjj5V${P&5s3=xK>j0I zyz$`TKlG$o3YTWoJt&zhh9sZH1Xr0-&Dv@)30&>8=?+<8M=|>PXm%?+T=1O**Ukc4DhYKsOMPT-IHv5teRXFb;n$bCgvgPTkdVqnxSRc+a z(CRalnzW*74JLM-g`Y}bn_){_)lh9V-PJ$rHR4Rk;{a=PSNY^ z+X=zoy46sZ;H{ILu*4n5^m*&9;;;88=8<7roQA2s2(IDYhB0p%>I!Gy=7tRE{^l~Q z>1-wCH3@ysq7%fI^cqu*ifY*%?&jSOC&OUROc2jT8S^2+TSM(Z?!vp9z{{7&=44QN zsKA29>0ZCFWzQY6U?1L37Lk87dox7LgsF-q|K%mJF44xYuE(0-AW?~wqA}6xhZ7a| zz`1Hfj}CNk!?JFa>yb0Y@_@!Y1I6r9@Mf)*pV(^!0A24+zIYseN}!5jl|PCE4g*Q) zggdpG*!|@S(DE+sn}gpsyh^;y=~h-CRxl_$3DCkQT?{in!mRq4=+sW(WgN;6XSV>Z zIUufBv=kB19wo|CHsf2z7AvX)N4D{=4XVQiEi`~BMZFI7l*2+IAa;1u2J4{Ae83EK z6F+eh5Gz-YM-o9Mdnz086s4OV`RB$-l8Gz1`3*h(6sV%>rzR`uh3^W9IMv%^_Gq;W zO}dg3K#5U${k9sk^CXPXz8ai0T&kU|(HyaIeii&I*q0!~uMm?{NM3}GScMBHLba8X zXnvBvQ*FCH=L=MserAh%S%s}`RTAU<<$iPR51d%9r4ww%xyQ#{C;hj7C>>>*NS!#p zA9RF~aoX)}F2L+7GP7DrU!e61Ngv;q{0ECf04VU&UH{T|)fRY`q5OK1Pw!ps+#iN1 zabz?~QW^}7$kPgJ3Q9{8Kas2OkO1!qcv=ka0xSL$2Jyq{daC1J&y@_4YMr+pliV03 z^a45t91GLW&WxI%#1EfOqbswTZ6doe_sFbjr?eQg#`RJcFqu(~QQ7e`j9PzW#ip0I zD5)7Rmz}x#B?Xbc!|HeiL-^3BkVo|~?G;9UGU&i#3%57K@7B0yW8xn|Cp zIP&VsW?HLa(|u9TOc>Tcg*O&GwtL}t{J}Ihlm(LsFQ2*M^$coQ}?Gmss|j6$IDm75+qB!@aSLnER7vG6pcQND&*N4X-dqpb|OMnzNz( zw^a~V1UdJSdbr_7zZ3b#1t$l+qy*0@584l7b-8F$^I?iG(!B&?z7#p>%h5 zNv8r50@6s1Ff0tRwK`3BRW@jzojAS;-}>j{+4im5y(ZT$*!TeKDcmyW_t*d4aqI zhFbfp=+U5z2;nrHBII+gZ8*ySo?&l-6|fr|_lGiwBANPeW?c9v+rPCc#X++1Nq+6$ zT}giYtN^VZT}_E-ZDrQDeI~P5!~0XP08ucz#t>>xW=kpl0AAgZiMA?IT*ABP z?_NH-$|_v!kQQOD*?>lGaK{Gk9I0Gk+LwEy`RqvcDA`#LOi*zG4{7{=Z|j(% zK#TPHn4#ntR|mfyzO}#&Ve-_Z8_9w1czE?sm; z;(kT@O?Ei2Y}ji)S|M6G6*f@oeSdigb}#W!jMeTK(R*xpXC)MGR0qF$jC6R=9o8+c zO74tJEYkxhUGDwjgR-}Zda2u@6ZBUfIu^$f({KB#g(471XfOKGNt381muZl+L<M+Q8alsH>JA^=k69MBut0r+q1{}`n2;}Aj&GgEdJ?ubc8+^i2h8mQpC>20duy3S zs~$9JS%t4Ay~h!>#=b;DWfjq&t^vZ`{Ic=qg5hUpqWmmn)PD6zx`%LQhpDnLhJ?zd>u@dnz^Q5$O5zC2_><>lrVOl^~kPk~j z)51}{1@jLkjaMRa{oWuS5VPBtUS6z!_!4yFQpUV4-&>T+X*BKR8%4lvnBm3x59zw@ zbazd|Y$Z}viW4>+6i+qlF-Efd2&Ug2ykqivw{O@YXPtrzxyPQ%G;@STf5p*1(5aXd z)3c}S4@`Dgcl%O3Dp~gUxK985mPj_eG_|eJ`N6Y)+^g9@kXwt`_`Rh#*baW2()_TK zo{FwDw9(MSta$*lany=S9|I7UQxS-9a#s<9b3^~tV+eO0+8|~SFwvy;)jp3LX!m$D z>>^|LrDh(cWK%W(VCw%#Du9fCU`zL40<660-utg}u}QQjS$Js?x**9`?#y!vV`Ob| zkHDJGSlMHubhPzhm$^S=^XkC2uk>}F)4aDl(Qb%?iFeQ?-#lM(mq}mx!$K=9Blkx- zXgVl5SRAL0l;qSQ0`W5fgvG*{$gSTJ z@_@|A#CQV+t$!XaRQC(-$6}}V)E-H5hl=VEyM#J}vV2jP?@2w{fJXd|gXPfVq)%fx zVT?rD4~1?ezi?CylPVIVFkn#d3R3}elHKoZw}N8=Vvr^k%WRC$i0Ay(sR22>sG%xY zQ4Y7&aci^0ZE@&KM+-jc5rm1htak;<`MC2Z!O`f`Fvk;Qr)QZR`HEhGDd7gz-a2jV z$f&R5FW7+10D_0E@dp4u;_&(9`T^U%!NE1ZKn=8$AFT22KZOZ;#znGkW@-d3leNt( zB{a82vdwd)?p;_JLrEOX_# zQoTuTOFS*5%hu~b6YdX?eW|`ku0HUf>VQ3rOln_mOgxb=buu_olz0kDA7Q|^N@V0= zsZpgX<l@fA*u$Yw0V{qj4ZMiAG0Q~%iLoNFgKLWoszdIeG(8;>G{RXD%hzrX4Ul#X9MrpwL1ibroo9Mmn5y7zA-YMNMBqa+47&{ayu z=7&VhYR+#m6HZ#idMu?#w{t2WKeh^aCi#@-2KK^`NmY5uH7VQv|Hfd;S+pT#|LZ>m z<`sv%l9@b-)#Ex8^Fy7Ix)}Xg3>sW)*y{Bql3J}~JaS~@tU0jsx1#4X!IE9DTpO|D z@{2@!i$>Fd*CF}?Cv!fQ#mR9_)^wC@Bzukil3rKZk$(!hpH4S*;k9i`;0>g=YL+L! z9^7`IaNz7ZJ39=l24-$5a_#e}%E}+s8t@luMSktH@%;;V;#`WZCuHO?tlB_GCUJ_z zvFB(HmCB~}S4g2afsJUVdF)5FwuAKrQ2_H;C)s0J6b?KL6u>-YOpon0NviYer;Xp< zFldRq#CMSFFTtKV6V+|F3D&}GR!Jy=;ltQ1+1$U$OJf&3X`(1wXo(-oqcsD@vl3tB zvj6I!sz91*IqPw_Vc1@Vbo=)E!2?11Ry7m-5uUYNF(HT>=S++=xY>Yb|JuR1v>4#i zcyoblEw)e-nYxsXMf!8FRl2)quF`z!{*4`&OV*1Q;&05LMPz$bv}u1Eka+Eg5 zvDTvq$TrSh+o?Az2R~I3p~=GqIVI@n#Ab~Rb8QaA;=7I^%&36+7kI?cK8xKA(M0!R z?cYtq{+%)qaI_Y)8GQ{~8l~y-5lZyDF1FHI{NmI`7=(kiOxlB&itTkP1Z8-P33Yt3 zrwK+=Kbm-rTf6Q{H;8+V9BGSBn=SPe!MD#&wVyXs5e1Pq^!-=$zIYhkIcM4*m0zV> z{o^;&{^d85UZq$79??xS$=YHx-dPm1hao(YE%o#?h}}X^tH0H-H|FdAaMYE!Kln>d znZo2=KWXM|vpX^|q7UzUgr_M;DIFgU-$+C(UP?jsBubV-#ZG2V^2FERHbKQMN%#@u zzt|nTM|h-8L}_E(Cph5mEK84~IFtz!vEMOBqZP7t#RNGRSm3JB<^GOvcu^_CeB5YL zN;Wbf7TC%uZ8zHaL4vmE)i*ZwIkr9B+}PrmxAywYpb?_EUKlZcdaME{IwoWzZ05M?OuUp1n6#R@+;VfTOv#bt00j@;px_ac{El|?3>`}sSb6CmP*^rHUb}9_ ze%U|O=`%Un@2vPgRCRtY8AgGSZ#gTO{3;uFz|RGm zPti}(H>8dI*-rDSBe>*2$myefo?%J!d;;0t1gp zuAD4(YVGQGNx(a|qK{WY<8YSpN@e3!L1+<)!jL|hY)O+&%$|DH77m-6<1-K67j>wq zt3GzW8(i`xMlXGM-nT{$nseSi;Er#Jb8glKNY(b_Uu+e^{r_OA3fh@+yWJ-Gl``f> zA7L#)=Ox${SR55|Frdt7h*KX!t9gooZmjMgYJT^9@H+%uX%it|3yzSimxr zr`+ur4~io`7JbU|8SBtTcIlG~g4A=AjEd0-BG!&lj#9qhdPfQbai_K#M!6&-_MKyk zPhDSf+!PAq2b*(Hoq@Gb1ewofd2p$2%nq7cKBT1id#b77J)u0SocrQ9Hlpv$!*A^mde+ zfQW$ixtUWCJ2gU`sx(@^C9)5%?qp*c>@23yhC|my#XV8+kJ_-V{;!RVdyU7#@!sk{9`@UM}&D4GA*; z2kX>=h|0o==tnPN`-xwidzK?SuUjK~SE4X*GI2UAmhAz}amp#xdnmVX#BXSdf=2Is z2hn641RGnHsY-g8f%WswIr3mo&H^_AgxrIQ#{*B3aHSxKrmCoeRvF8>ksF1Kvx}Xm zJp8HNHpvhaA-<%(1SN|vb{b%47vF%FCXJp6qn3lC1RM4)2R-6A#LkGyd;A{T0=evr zxFJfC?{gfI%Dc`wIyS z3T1@cY4jyS>NoXPWGO9bu9BR$l2J5+9a)z{B}o14a57)Gl}7h?J=CL%|2)I3sN$V> znN`qT{KO-qT*t&dRUMk$ELsa)#wI zxmrAh_-(NVR$ZcyI5ARg+r0r$#v7yHAFYaMhn3DvJ~UJi{;~M!(VhE4ved=0kFf3r z98`;P@{CW~1Py+W*wFb;@fZH-rQR0YrqRlxgw{-@QghXfCW=itfpcnp*85$;^r=*u zR4`HV@C*|wX~f>=A4SzOV}2?NO@Lsu<%FEbCc=#9PmXF~bfrq_`1t3@K;<5bo0w(w zNK0kz9p)rw zX4DnPB=_Ece)=sNCsl(q(W>9Rqa-=2k`l@}HtRN3kg?JW(zEGrM`Fmv{_+&m)O9@AUCaoB!yU%b;$upSsTd%2^+W}q*?@mcwL`@BI z0FAr{C@jBC;QCq?#)3qo;3MW(JnCQ`o>Wd>sxKecfY2r{$=qw7KaBPkyVM0-Z54SM zsiHX^-h5q=HftGcyPC+?)bU{huNuXno?iF*J^ilaMC#jQu73cG?+6G^Yiq~`gYuIk zwAidtX-m!Ed@s8o^A8Y`(Ov_Qr-8bf(nOd<>KK^nd0+hNj(i>sjTz%T&eV(QLU?uv z`%U@(o}nL~wQ=S1|0Ad3ZgvQiA9x40$~JaCKT3qTNY}(C;2Leyqt=okXHH4?sxZ_s zsY)?3H-L6^gl&ZJc>S?P(2KJb+GccCV)cl)qF{_;a^$z5IR4p^1{I)?sl}H7L=%Fz zR1LBZKlpX7ShUqP$TR>yp^@}i{N58Zb9z|cBu7AoxbIhZkWv-3pVK7jh|YCx8VGvn zw=VD~L8>ZlR2a!O3LTuWlzt_ZxR#rQKZlO+PG(A+wHyNlad#=;4x4W_4m4DBht*F> z`gvnBZgC(f40~r{fL{6NGjc67Kk@c|iqly1_`3i2esxsYzkR=+l)?gVPcaez??!eA z;>xvhlJ^Bq+BW7gmtr;S8EBwA)(Yyz)**vPS+G+E=ogvT}ThSAwCc(ZEQBwO59-HBszE;bO>Gj&h9+`U-n)G`-)j zF_7L~oh9(Xo(msYp^~!%ME`x{RlYvRE+&N1O6wxoIcSi~FXpAGmyW!rDvgAOR><#r zUE&kjl~qjF_4&4V8C6tP&m-T!UPX}UW?dkbmHl7g7KDu;*iX<^&c=%ea~D#{n(Bvp zsXn*W;}m6LUyyoacjE2ykpa;gY?=IYf4}5hVCDY8)76ON=!HTVy7cW(4OmAf!tTgX z?h~W?OfzN6tdLVi_a@vf@RAiqQ7dO;BNuu<^x0aZn}vK406xeDxF zboww-LW5}&d#3}f7b%g&G>n2m_CY~bTFaM0`F+ADVK$osFlhAuC5uyGZ^#(qs|SvL z*BJD#SN-7YPQ9rLFR8PHh}om&h#8TDu!^uM@e6wPZbLbsD#`E+Fy2mAeSjV+ZF!7Cw<4^ zIj3&VZmfepW&Xl16bPbZxU^3Nh#13{Q>lDK!`+C9&KV=G^VG&@c?~&BhK{(HB zMBM^S{WLT0AYUn=AnS)vlRROM)nSaGVn3||e9r9HO$BZNaPb<=M1tCkl8_9kR{p6y zv?nTOBulZflPAHA3dsUKBT0~Q<#~mxfptw5)PEx-#PESQhG~w*P}pK=2ICFDkx1Mq zFS%F82&s|l#^P;DoA%3|kCC9so`V{(0SFua5?a3wXMlCF7-++YhFlG-i`vXmwN3yCn&|xg-Iy|PXH?lCqJgc(c}$7(SLD20!r`Go zp`uEnc7#gX{;MiSuP~Cf-l0i}h>KE$j1oq&GcZE<#d>+3uVN=ygWz;KCenM@cCsR5@9Zaf zz)9W>Yi4o!A5j7|rL6b1c1!mx`7;N4R%cnI=`r)oFOvVQ>^}rC%4TjIK;jJ-J2|-D z5lypdw0#IiU+?V=n;l(7!^JM{ZwLI%UVtKruaRB@?HP5Xwi)&w>K=6^s%}Al(?=oN z`rv1cIn1R5g-*B`Z55GdyQrRrl~x#L$TqXVN^8X!Zg77|gD}cMP%r7*{(>kI3^#t= zP8>r5a*B-NBSB)Rx?7K>F|~qrg|xmLQQqE#xO`mj`;XAPdse~G4c~A^vq$qpEfEVV zRFsdoa_2aD2FH2e^|WqE+8_sQvFK#rPEll5JNTyi6~-hhwcN={EU}!M#Pk05Z0%Xl zxJ_Ou@>8Bzi#Krxd2QN7z=P}|ls{)F#=iFBW92FNbkJFQ&Yv&rPu{ANscDw5E01A` ze{S|x$1$l5Q|8>AY*mbR82X(W`IM}DYr98lEPGKMA@riAR8GsSmjW3Jqe`GBoP?;; zZX;}UI^-HEfj>?B*72^-1Q?F>2p9aFNwjrVW7aClR6~?WA~lqqeDU{|PI$|$z@cog z|7IRFi(Z|c_(9$g%xFV4gDOtWg?x7tEvLj8CuIbgp^2xN>1w#!-;@UMp(ffl@uF`_ zO#sS9$(^dH9F8}|5O$hzbe#l{UD8w8<%7&s_Z>IYcZ-L^i~ta$%oXD+H4(%=CmH48 zxFkbiV!*ezj@{^FJJ4cZF1|_S__Rx=N=mWg$SWePkq(f1h}KVEIy5d1qORQycf#-Z zL0GfT_X~>Uv~FA+*AJmUh5ajb4Sa0XIGtu5F^jtRGZ%-qP0CMz77Nk@+6qS-EW-}x z2xb#Wfxyv-<~oY>D$N9qdbAZ|g0qqs4X7t29&jfV^WJCGK)Ouz3d(8x)V>?M?X~pH zzxpeYs=<1KMeDmpDFEQB(5HMilb?jLZ+G-2-H9>FlSfd-2>*Ll!E+^2w~AnTj%>6= z)ax|}ykLaB|JQp>)sK_S%=5s8Jt@8i|FY*q3ox1Cg>TRE0h@0wKs%(jO?tNgvOGmU&6PJ0hoe>0sx3>R5y)FEpky{}>?FR{IZJ5*ZrlyMg=WyK$GUSUURW53=;QGcc$|PFX z;Y1nDiNdz`NH2O^5{w?UcTrJP$CNLoQvOzeM8#ZRYTG`Oq6$)@#pu;Pdd3%Q9r$&g zeD|^Yldwnh3B8U2jh{g20wdw59va><<&UAFkDkOt2-hPrC%Ly>v)yy%S7FP0kKfe4 zfYfza?eCYtl6zc+thhMN6WKN$(mNhPy*j*c3ltNm1T$;0<>P{E@9*tsowSx)jngBM zuzYovs=#6HKB*vl|C9iqq>TQnWBE)uittZo-<4kQb1QBOXx+LZzBe+Y#YDKuPgMSG z+7E1;y8xY}hw*ehjAeUF*?%vP8E#o!R2Gq7)zu_xT814?Bub4O3i3(Xfy2y=Z_tl3 zo?6iXrb6@{ef-`GH!s_ILazX=u@p4;kS9C!hyWFJXtSid&C z5tkmVzA@+Gfs23(3l#~{%}d`ie;ydJ<>Ur5tb`fX=J^&c2DBD@FR}FmvZP41IIupS zonbR)UHVOr_eq4JS$jK7g3w*urpS$I7HCxBfSSRmfs5n&b z4H?Pe?#3=Fp2OjMRTvw5tGePQ$45(-v+K5pf*)>eNwp?IjbYAu3_Zn0gJx3E@zv9H z>TQ>$P_^a8zj*o4p;JU&Rf>NUjmbe5t~+A@;z%F3Ny7WaS}z0!T2@3;?G&6$tCfHP zkJDlKVk&s}8&D1rd*dH)&ql`lemzqOzg7sUAo3(^$*YT~LL#Yw?J{D-tvw42#baN| zSdg>2(Gi?<|G>!A%t1)-d^eL~g0v(i1NWs-fKglWw}zi%MBiBL(ent~t8}unVS=(} zP{}*IIy9sDvZqh&=QsUmSZ7JiA8PgIY=q?G%c(&TC#=CgsR!g8F}X`CV#P+QhSSH( zCbL!U*BAyqX*z=Zq>ky8Yb4O!o(=FMr+z?#K0h@VO}o<}!LU6qkC)Br;6B1Lh3{I25J>Qx)o2 zJ7hP33XT2HLq&G{WGZRYEAln7x!$9`6 zf)8K#Q)y&xE@98zi`dKQhU9s+Po&0MmPQylGmBnJtS6L=5~+b1c-UekWWw0gi`BQW zeL-jvGFH`|j?r~)-vFC1L)i$ym2`BMp?)))GnW)b6$F$%_R9*^(E(#5U)AR+bP&)z zH$Jge7RBiDK=04P6$YZytYNR|Ept2F6F5wW`CbJJ5voqsCk=DX(pZP4<*kZF6Nv?l zNt8k-9epZ_>DZB;m5&%83V@8^e)f+(#%Lxm=)<4BCU_C=1d)^&50P>?@2jgtpQ2e6wV5Y6$ChUp_xb`F(4FtGIM!sJWJ9`pe(GE7 z<(_G9FXF^X=A0`igNRBj2kZw(k@u@7zi`$jER0Yi;q^Us=k}ruZPW36{!(6AcCc zQ*^(NtOltdv~+}{yC_p4U3z#NFB^O5lhMrj(#3^@OMAnW>af>vU|{+DRy>geXDysP zkkE%Zb+BxPH_oF8qw70%D*EACpDa;TJgZuvgG(_nUFe{Gk$e;P6r1=6$i_%0zj7wS z-Z1FU@tc*^)ik2t(rmmswXi~yYUji6Df@kQ($98BX1-Gfg^b=#Fh_BOvq6^*xnNI@sj=;Wy zY5}|1Ahfo8py8c2?hew|nQNMu{l-nG``wITmpcZ;kGuD#Rmcuh?Po!p&b`BSf2(F% zBt}Mni2G|WYB)OAy~udJoL>kJ_%q+19X%fHoCl&pkOtt#&B!@*M`AZ^UDQ`DrtC5n zJu3(@d?5~F9wgtM3z@Hs(Cm7vulS@M=O>kKNqX#eQ~Va1zt~Wq%dKguHCE`~+p(wB zUAUg4l(V~t%>E+3lk?Gj`y}SQ4-ulZ`s%5#`2~mmXw!Y;;2QmnkMtK_=7+&NHmdTE zAaaJ&H3vy$PfpxP@^noh`2oDQ^K>zK;gqO!U4((v(_!z(yEU?8>A@X+Qn&aT4JKCb> zpAr^SPZ~w_Y?(Y`2^RP5zW1!{pNreQ+sOE@OqF@a&p(+e*;|D8ASEE8%Zwp*doHsY zU0Uu8p8L+|WE>BXpJI33wk$$2cCm5GqS^j)H2pVQG5sB1n7Gq3y!w}%|TBL&`W_uuZkAGKw!rqD2!y=3wJXg9Cu*<8OYj&)U? z+rGuATe$>-ULh7dcWFGcyebxSp82;ZBK-PGGgm}iU0uYh8UH@_ z$mPMiqR#97pWfd2B^oRJWzbb{Lh=;I9AIaH1Q5wOjA{5*u`39parzKf10`}a})f>szoIhf3adn&ORXI_NZ8_Y`zpR{ zLTD_%4FEm92x~ENS(%fIOTuF1%lrAoetxrgpOe+pHt!3UkG8X`eQhc(Kocha?)&>{ zCh0aWPMJ}Adi|o$>=y5>Z6%}g4^#9jsb5omS$WyVFnjK{3S-eYM^BlMrY0DAgeDmI z%xv*GY15~lyuJeC3=NH1BnkVCQkCTXfGBd^1~u0qz00K4nQb4(3*WL7e=9%|sgHMc zU^9jJG?Mz&)Ud+$7I%TIsfrWP+cB7&pvV88Tzo!eCh}DJ+4WJh!oPy_)4f*sXlN`= z{pXvN3nR41f}+IEiA0&B4OHbng<{~}5=ldFDr z6J>@o^|oIKfy5O!?XEwqD+fbfwi_ zY%5w06g3CnQbR6t;Cvi1&AbK!TFD;r%yTxR(3h~P29=JrgqgT z+5B_*-U;hhZ6BwmJX^i7E+7{At+2bAdgdf$7RYYU)Z0U>{kYa9dl3RxnTNd7?oIZu zMooSVJ24NP&lrcdEnXd!SHOLxW=@E?W(D8MUZ@D&8mp1@t^e8ESg^dXxa0EM)pucQ zSn}PzqVIr%(LipsWSz$hSvqj&#pi=wJ&BUeqk^5r(9nwtMPjLgXAfDq`dDyIG^EGk@E4e_r`9-v9amKR%=^) zoyVj06-97H5@93yX~~wTTHVeo`IEi7Msp4T|)iZNbM?){%m;`{)mHwIm4M}xYgT8G+~#+eJn#; z^4OdIDlU>A>=@KoUf)#iS>kMZkW>eLN&>1o&(UzLcDz!VqC)`K}g~PIU;MeJco}n)&zet{cYRhS4n=t!WVC#Cl(AN)~)8dhKLH@

h@Zk7eRi&y1IY$V7p}_Pi?#KEOU6?-s{mTOS=VN`yVaV$ zu&b74d*o#D%q&UexZ&pNtc1NBt_x^n+1xntpNs>S-?`Eb2A133w}|`a=f`&;bRRZo zL0QnBx0z4$szGBtzQl5-p2WlI-ON94D=>j7#J|4*ilF5GuW|VQ{bl2~%314kW`t=KwrCXcVQ1-xp5ttrW{h?5-WS&w)~_n-1o` zR=*ksn<%T^M9PTXCmHrebHJwNSKzm=m>8l^T;5@^UY`i$v;2~K88{_PT4`&D6&;Ry z){+sv=4h(C+E{*}-|Lv%5(yeV{4;#;YV~(L78WB4c)Yo8|0!R1^Xgv@am?4eZ3KfI R27f+RkW-Z{moa|xe*jFhcc}mX literal 0 HcmV?d00001 diff --git a/doc/html/_me_flame_sensor_8h_source.html b/doc/html/_me_flame_sensor_8h_source.html new file mode 100644 index 00000000..62472241 --- /dev/null +++ b/doc/html/_me_flame_sensor_8h_source.html @@ -0,0 +1,161 @@ + + + + + + + +MakeBlock Drive Updated: src/MeFlameSensor.h Source File + + + + + + + + + + + + + +

+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeFlameSensor.h
+
+
+Go to the documentation of this file.
1
+
40#ifndef MeFlameSensor_H
+
41#define MeFlameSensor_H
+
42
+
43#include <stdint.h>
+
44#include <stdbool.h>
+
45#include <Arduino.h>
+
46#include "MeConfig.h"
+
47
+
48
+
49#ifdef ME_PORT_DEFINED
+
50#include "MePort.h"
+
51#endif // ME_PORT_DEFINED
+
52
+
53#define Fire (0x00)
+
54#define NoFire (0x01)
+
55
+
61#ifndef ME_PORT_DEFINED
+
62class MeFlameSensor
+
63#else // !ME_PORT_DEFINED
+
+
64class MeFlameSensor : public MePort
+
65#endif // !ME_PORT_DEFINED
+
66{
+
67public:
+
68#ifdef ME_PORT_DEFINED
+
75 MeFlameSensor(void);
+
76
+
82 MeFlameSensor(uint8_t port);
+
83#else //ME_PORT_DEFINED
+
84 MeFlameSensor(uint8_t digital_pin,uint8_t analog_pin);
+
85#endif // ME_PORT_DEFINED
+
102 void setpin(uint8_t digital_pin,uint8_t analog_pin);
+
117 uint8_t readDigital(void);
+
118
+
131 int16_t readAnalog(void);
+
132private:
+
133 volatile uint8_t _digital_pin;
+
134 volatile uint8_t _analog_pin;
+
135};
+
+
136#endif
+
137
+
Configuration file of library.
+
Header for MePort.cpp module.
+
Driver for Me flame snesor device.
Definition MeFlameSensor.h:66
+
uint8_t readDigital(void)
Definition MeFlameSensor.cpp:120
+
int16_t readAnalog(void)
Definition MeFlameSensor.cpp:141
+
MeFlameSensor(void)
Definition MeFlameSensor.cpp:49
+
Port Mapping for RJ25.
Definition MePort.h:128
+
+
+ + + + diff --git a/doc/html/_me_flame_sensor_test_8ino-example.html b/doc/html/_me_flame_sensor_test_8ino-example.html new file mode 100644 index 00000000..29c63df7 --- /dev/null +++ b/doc/html/_me_flame_sensor_test_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: MeFlameSensorTest.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeFlameSensorTest.ino
+
+
+
+
+ + + + diff --git a/doc/html/_me_gas_sensor_8cpp.html b/doc/html/_me_gas_sensor_8cpp.html new file mode 100644 index 00000000..96dd98e2 --- /dev/null +++ b/doc/html/_me_gas_sensor_8cpp.html @@ -0,0 +1,188 @@ + + + + + + + +MakeBlock Drive Updated: src/MeGasSensor.cpp File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeGasSensor.cpp File Reference
+
+
+ +

Driver for Me gas snesor device. +More...

+
#include "MeGasSensor.h"
+
+Include dependency graph for MeGasSensor.cpp:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+

Detailed Description

+

Driver for Me gas snesor device.

+
Author
MakeBlock
+
Version
V1.0.0
+
Date
2015/09/09
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for gas snesor device.
+
Method List:
+
    +
  1. void MeGasSensor::setpin(uint8_t digital_pin,uint8_t analog_pin)
  2. +
  3. uint8_t MeGasSensor::readDigital(void)
  4. +
  5. int16_t MeGasSensor::readAnalog(void)
  6. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan         2015/09/09     1.0.0            Rebuild the old lib.
+
+
+
+ + + + diff --git a/doc/html/_me_gas_sensor_8cpp__incl.map b/doc/html/_me_gas_sensor_8cpp__incl.map new file mode 100644 index 00000000..c01cbb2e --- /dev/null +++ b/doc/html/_me_gas_sensor_8cpp__incl.map @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_gas_sensor_8cpp__incl.md5 b/doc/html/_me_gas_sensor_8cpp__incl.md5 new file mode 100644 index 00000000..5e0cb777 --- /dev/null +++ b/doc/html/_me_gas_sensor_8cpp__incl.md5 @@ -0,0 +1 @@ +93c9316f5c3f506e0da8e962ed143c04 \ No newline at end of file diff --git a/doc/html/_me_gas_sensor_8cpp__incl.png b/doc/html/_me_gas_sensor_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..69b8a2958355750d07acdc328b626e142e062a8e GIT binary patch literal 47884 zcmeEtbyQU0*DfU}El8IlCEXn=AR*G-Fu+KIbc2Y1bT>#ycQ+&8(4cgOBMjYL-ZS8D z-S4}9+xzIbknyoQb>Oh|Gu^r#33O)MUs$uy>=F_>q@QL|yl5 z|0FTK-UET!S^f?5#=Nhr^(nl{m6+6Mk=DoSCMx_Z5A#xLtF3g!F!W+m@^uB!5~>@X zz7EiQh5xDkWgNrNB0Nfg>l57&cVC)wYIzRpA!?#UI{n|p@uYL>8^5GX)a2`wh zJ3rwgM%GZ4+1gM50(*G_JNYhu|BYi=aDbxBio8XSVMy$QewckkEB`SUjTZ+WNx?k7UqG(PZi{q<56Cnf04CeJQq2M6rrq`iG{ zZov->JQ~vrVY&~>ZkqMjpB8N@Hf_>WW%f39!P{2S3Q9PM6=fkIvfz6I{wchjPMt_1 z_XKIJC>S+xpVYU1->)MA_83mi8wQy8&)0U|P20JBH?0zLPXgy!Bb+fECs?`Xtn*20 zMYG7_OTJgTeQ*ts#pB18Z(07WtkfWQ(o>&j5HY8+JT@Ul6)`n)o)IKxurL-!Ew+%+ zP{K8bp(l3XdGaR}VG&{%62obC zScE`(3CBrjNbhpa{lOr<_umfvpO0|&y1=zPfb-4xzi^cQ>Q{&VoX>S9LCetO>U2jX z>6uV|RTbAJfs|Ap4bwIvO340na<)1FzXTDTZl~_lYniy8A4`5@B+oq9`D^v1IWrqF z$S-3M7!qQZByHf2@Ko7)R)x!Md}hg> z;TwSKcrLR5j!ve1Z(*}uW~Ixl*U6@Du#h5!k^?}3{vsa8^I8U`dr`I8zzHG$b2)A^ zp?Tt$uMX&_=F@6VTPHe9c{eg4D+SXBQWFr_}%LU~#I zE4#wpOsn?(#kG+J+~=3-JswKV+Sb^xD2|Fc(N1;LEst}gSyjAIO$K~U>fZT#qv6mp zyY9t9@@{9$Bp~8s{$tNSaMl3^wY%~7H*9~@9QLn9Vt=oXT8~HHQXnJ1{E+{CQ=en{;uv|{cIOKR zqQ!NaKF}AbGjDPOt46B^0uXn1{XfO(`Z{o|0KCShtn9Y6FaEl*J^9lnMkO)_1M4Yu zxB?qp_;zop=5ZaSUn-5GV~*8C?#>#yCGp<8u(m}TT4=FR~4kBs-^Fpc3X9hh^jJDp%kLIA4ft!?81#*3|?jRaxZ1--n+05)Pc~>=F%;FwKk1p^I?5j8Jq!N`_P(WEj4#mpebq#uXI!-7^>`pvrfE zn4dKZJcqH38X6)y`7Z%75VPxRV~2mKM#nn@QFb^8V^H3Z`N39kUTtn^xi}jMZm8|8 zRBjkWiZ!jt`~3mqxwu^)2lQ;)tF2}2ow2nroL+Zvm{lBpXY`TkyZ!zvt9d?Sfsz_8 z9Ubre{u^Hdr)t}|i7S#R4-*iiMH2k+yA)osKhI-9ln`V#!8F&;FD-1aCHccizXwXB zT2-7}VLW*pW2knIhp0KM8)GOiX17RZ*ymP%d(C$ZY&&~l1=ml~vy543^dKMmizY`G zgoqh@Odm#}b6U!UmW}K(l6o^wc`oL^QRD>Sa^eW$IxN33j_69Y)w|d^^r+8m0cp;| zFW4%$Cr1^!Q;-zU7?QcZXDo0xh}l<)^YWuriaYZYlj1FD+i+N1@q7u99eHt=t73fX z_Sq#w2VpIO-*8I~Uk_KLnk%_D+v|*uaLWqL^X?k9YwK8=M6Hoqm?(K+ZF(<3&e5RG z#=@M$)27f0e{?r;0{T-kduX}-mPguXcy7=EI-yt%?L(Nhanzt~#d6t=|Df()Icf^) z{2A!B_iF%LaPOUPl!F-XB)30~Tn@SIpm|}I`RvbR{3jeppYlNtAmP<)XetaThs>%5u$*+ANG)LCpE2VEWa>D zt)vD8_GnA&o{5f)y;PEta{ZUy%rsVYN3P~@`{ys%%W(YvT5oBV?`?J$xQ}w6v;R1c zlBzOTm}??BbuRx<2De@Ojv;22Pgdg(@}CMY`aS;Ru&^T4F0EP!KBxH5iJ_5)8sxo3 zoPp0kJBs%&yG+K@`=r*D4-3slP>5^|)To(%!$^ySqx1YGB?>hy*%-LS^lGl~j@YBA zSGIvtrjtRK(j%xVF~R0aUN^_x*LC8;_85Dkk4ylZki5r7E^^Vl;f$8V;c7oz zDJn6cX9~}vLu7mYy=cXcxb`H9C2qKWVDQ*8BSYZ<-{W-=cAcn|Wyo;QPNt{BvuU=95JxMEW;@26Wj`tYE+i02OlH`z)8mKR=9|HQtY zXghJP%$WObLz7vUYC43fQvy^f{{Yyt^tbp3o{>d>$P#MmP~m)akd)hHsXFg@p>wJR zL<%cKLu_DoNYen*tGc3g(v5}u2QOX<2-*j^wYNLN)G<`+TuAnKQs?5TAjf{RjWVm@4-&g6 zshtEpmpMe{SwqS~!*z52^)#r;dy820W&&QoDEugZp(bp{7&AbMPU{|4V(f}!FJdek z3BZY6#gKDTmnyM^oil;+M(0%YrxL{6ZB~h52|MIOr`V-~Q(m~k`r&ve_JXAk65&4@ zYf9GURSFwNj&A62_i`AOgCnxt-X5*H)ReyXeJCx}{Lej|i)@Xkm!Ab<6~Enf6C=x| zU6sktn1E>FC9CjsWo||35}itcecNaVtQXc?xE*MJqU6mN+RE2dx0H0`e8rcQ`VeuS z#x|6H_+)1JhB^hvFXQmEFD$f++Oo-BdZEe+i;l(i45kBV)4VtS#6)l8l*dJGNL z`KzXHyd;-RRnz1An1H}7X#w_N!@`?|11ogH5RsGfH3N4;}q zmxub+(CppopK0fYLw)sS1+Z>4U)o`gd7U0y#f>3SvFu9leoDur492^3w0QDCq}RcG zkPoTnOSiXTzi65t21KHva2EvLWe>pIW?%n7lR$#Nxk~05^Vd89ACK8Dj6U^b0}DDC z?0;$l-g}o+f*tf~`_F9pLF{GUmAIl8$*#kh{=g;8e<*>UpoI1s|DzDP4GVb}`9km& z(Pf8MLkd?u_B|{WXCuuApg<8^W;#Qm3EgTPd!XRNrXphT$*S~MYU05=C;j=b^n*4) z#a-^18E$*<4PdXW4JQvE2e4 z4qBTjX|%@l`ke1RdiEh%a_dVL0Z%HGCUQeK+gIPOot*)bbNK5SXNTHG?K0AIXZPDC z%m4i%E6j<{;i-dx{ncTs`Cy(Awm!OkCR5ehY89{&(>B><|J3>IVyC4b*jNFXAGHBA zpUPA(lUr{86afKHe>WC1f|$j7{>?quy>%@Z=2$1fXj&>8tY2%BFE&>2YN5=VFR8^T zyDQ0BemiwreU1my>%&{={wQooMJE{cvH=9$DbcHUwA;pufAbQ3cEiO`9UsPomGa5) z31^=%3MaqQz?NW?iRhOq@rNFHML{z5nbv+$l{Sw<{qH<5#w5q|+uoQeL|{;8WW^V& z@hMl=?(SA2Q1!4d|3)`Pe&dld?VBF-!AsgiX_r~);t&2XH{1zgD0rp~88Uh9hW&%E zt-2`ZyG+m!)svzG>+}wdEqu&Nd=0tbLppaTke%3Aq?BhCks)a!qqM4Y0Ux@pJOjd(`Ul$>*#UoF;6_-9VSTZozN74kc@H%I_$nV-fN+;SFe?Oo2l zBg=Hb>U1{{;)2m|!Af>cc5PJ~zuq;nZiFU zfZj@RUf^4uA!l<)*C^+V@y9MHYg=3&rZNez9dc&giS=SL0aKJrals5$3^6;m!oQ&X zeHUG9m03a()723JSD-n0k3gDLOHI_jg97q)to0-{VlqZAwqu6l3%oy&s+vGIUSfm3 ziD>ZsxK?FRu4c?UZtINBMFr)M$#`w?SIR*$Q}i;sJf65uN61i8FFZH9L4bO5vGj+i z`#^YBEV>%E&_sUD3H_oC3DOv|Rg)M_K%)-(k*vqJP=DMb>I2kNuHO)@{;c44`p&-L zG6!UoGtXj!^$I+GvRZs7EYTYtY6AK7NueL@72)&@-osm~{fE#l!Klw3qB&*8v~2}< zXJ!`iLT?8od&I`mA0W}<1i)QOLC2b&GMokn#W&#KY8qF*WNnt>hEEHz!%S`My}h@R zO=JbgLAVl8WK-alkp$;bL{>cey=-ub`q2gA8ID5?Q<}wOs0M%xLE=A$@cVeQqqlDE zpWLnwj7@gNk2n^dM2mo~K4?xnvEHp{s(xh>bqq~;;U|Nf{>6#CtU$TU34ZB-CZWSW zK@Naa<3=S7eknrKH8uxl{rW2+tt_a7pk`;L(3)Zw!7PCq zg%?!qwe|Rbc;C>?H8(DIWyymh3MWXSMXLHf-}XM$te-8=PPOI~N19Jmboy02a~gG< z*&wvKEC4MrY-0K;sFt%+Vr=c`03%W0sXZ<=g;`wiCH_~ zVBgq=lOy)sy^+wfYcwxKjtu- zyS85r_db#axdoq*U6a9w7GGyq+3G*bDowXyi+RE#scBh8@+9Jq84ojM{;%1e7oVx# zoUr{k^&CHu>*?P;j`{u&7buWO<50n`?-{VP-gml!f5}9OS@Uvt!}-D6P0(NY-G_MS5GsKi68~*mwR=Q2S-v>J{JD{v6OXBH}?48Hax>f zy7L!uhL8!3AE)l)b#iB{vKQKca%+^J;a_$ND3K_b{uav|xKX5{Xrh0R@umhV;k0bJ zc_jCMjE(+xci_m!I4fWiAj6hrJzu^Qq6|9-*5r3vVVEwqGnbqx5$y9E8GIJYl7BMy z7f0J9c8qxZqCG$*vg)Bb*IOxPSeug4W8))?WZPj9Dsg1d-wvydukEH1zh_qf zVOm$~;Ed1tEU%6cALm&$J)#yj-?i$09xyW{ZcU8opu zG+%nkq1%&B*Oaguv_ZMS$`*_dw>C^AN8~7q4U@K{JA9z|Sf=`Oe-ef+d5<<47&Hh1 z4(LGDDydM~1vvk7Z<}Ca;OCz*zb=nXN(8qiuw--Y!P?9pLEO7U*=d()-EJd~Cb|{$ z#DBW5>aKe2_QKeWz44W~m2tk-lmWFTHo0)?baS?au4(?who{!DE7k}?iKcI?Ncr9o z*5fg3u0en54IK2}U(8R*Z2lc%yx-aC1#)GQkk;;+KDqQ#@P*q2auw+dWA$hYXza{s z_sgkhwuA&~8}UpM&Qp&$Y1nF+-n1V=1W-=J1|g`Gv$*53x3SV!e%Ygi?CUlLu`ypF z<@XBwU=(Qfd!p!Lp8MEGHGb6}g_m9u01N#Jq=VHL65|;Yi_M$HP=qWYO*NyQcxdf7 zY}t@tjo~1f(>)wj%pUW@#qit{QiN`Vy11hZ-Zu&*xKabQz`Is)^6S;}xLQov%eZ?u z_N{%o3POc@LCAJXah5-BrkpyMos3_6(hi^4y?&0J(&U_Y!&9tVUDP_PwD0dV+d)mv z$jVkP@kS+1R!<~NsO1PJ@N8xN9b`3>taS8|p(>E*ZWp^B?^42`RS+%hqZN;i%TTrE*7Or znQM7-7BiDfTYdHJZ4!Zw`@?YDH0v)y+7hw@#x<3TVPg(4WHbVeG_WshdfM4LpGOyU ztiAWHEfysqT!KBMlrYZFNsaJ#kX#GV^~FnL47`bSn>ku`J@h**k(O3RU1#HaKA~XO z@`tbZjoxR`);R!@YwC;^kk4=Ir`hVIB!!7R`z`mE-QjUG-ZrF>R>fv1q>(j7kxhSR z?~!D?!qy|hw4uiBuP9c|HZ9KPaOST+Q;a#eco|Ul1Q2BD2zRR%$Hx6W2xIA2U3@?G zG?IhAi10l?UTUnGHVkhrulAJa3(rE4h}!A8);BmcT3nX#NW~G!!njjBqN*8Uc0(9% z7I2OD1W~~?U4HPLfuW|$Hs+gLo4P12F!wN;F)e2bZseyP9g;wo3cJ;VTf=vnzm{{0 z^XC$8(o&-281S2cq(mG9Y;=x&cPvBh>)ynK%MzL}h9`>$jW{o&pl} z+xY2Egy;HZ1mvf9Tq*ur+Bo&mok9HvG zV|h!cm?lXXjJ#x0x}e|H$JCEysv5{Gm&p_O?RN3KyOER$)v&wCW{bZ#X{3fqWr{)4 z2&n1yI2_%{89)lS>5p)GkiEcm9s~T9&RBki{ByUz(wcx%!`Xk#GrFs4QxOJA%J^Ns8o-MhT!)3Nn)X5&~9zFlu0Wh$e^%cQLmO5zqL*CBHz$vVF?O9^uR;zS!oTPM0)S`HDz)i zjx6vIBGmP4-8h*z9kSw=nqINQKTu!armdmDH?n}S%W zh(r~9WD-1FZ?$S-T>1Xf!Ay1DUl|#_mPoPFY2RzQrj_hq>dk$Zdl#mfo=GYw3T5Fu zbj0{5@SjGB9US(`=aqDLSLa)UmxJ5Of479tgDAVM0L2~^uw zv#$cX=z@#he!<{he;l)}K2jS@Nbid2Ad2q^5nGkBPxecqp>nb1ZcUi<9L&}m_%O%? z;Z$^R|H`^5VKYe6<|UDod{kSF7zdyO-C9You6d8}_;_GP>T!=v${1*YnPYv8-{;Mf zJ@U@W@6HTwW&k=*K++-PtOHW4|6Y%&D5=t=EwzK(5VjZl=B3#=nL&5Vv+c)=9r`Wq3MRtlvTU89~&;ED^7odV&PZUbRn#;@M z3$B0Gj``Q*Hl^S#iB8>8yS$?%C`%>KQ`6m2dlUIbfu|kxOsPB0_Z_I0Xoq6?%W(m( z!f-nJ1ooc}kMAC#{*0CjyLFFYML*q{{VJV)El*JbVz&mE4MX>V2VmtkVR$u)6 z9BG{tVETDQKdS1NWabw#rMBjT2!wh95OVf^4}Vf|rewok&MnvUbi*K{p zl|J+MELa&s^tXs$(WcoPF|aT0bJjGg2*?@GZP=vp(BB@$lOc9|CAvYf`Gs_a(x3cnm!XBB@rMXFXup>hgS4nesK3>9C z#>_*t`J%4#j;iP9>T7>z@q{cU3$|?cw$^_cT{_vs1XS95zTs1`IT}3w)Fm#67e8_J z4xZ=TQD{vVI{Pe`a&)EQ3Ur;RzXjChK(i)x3=s7VJ^EQ({~VBfrEGNH(u^#BQGZ!z zy;WYFmlaeqpY6FV=IvW~_GC6;_+wlqI`i&ry^OsiS&$I7zBBZxJdeU5tX9 z2Yjat*6?^%pgvSxkW*e#@LR5fwDAc{g5Za%%lL`ez%Y^E?(LejNLGW93DE4DyJ{(^ zIdkJRx=L*(uMnsU!RF^H!&&4=?U+sKeqGK7b2FDST7@>f4YPF`KM6fnpCb|-5j`5z zGZgs~ExG7jwzFkxwDrF9bV?*OS7gf7TJC~aNz zt4wp+K-BJ=mr~8Sxt#D6aOMi|f8%&|*vO4f6Wp=eSC=`y7!883e7swb!XZJt0gMY6NAQN8ArvzFgrK?1@@xbqU|eRMDB%aL)NV9;AhHGg?Gwum%xfLkpcMeD zI+X@t0j2+2z{f{ZGFaSa#cBS9PPBT=;q$R!JpUQol3rL|s%1UbX0s=d=VZQ(m7)OZ zP3@+RtNl114mzf@R8Gvrk+YrXs#Cz$*oEk0rOSq%#Q_(qCmewq_6;hlw6-ur$M+c! z&u#sxzP7U--ODe-qbB30=d&q~5m|lIauQ`vzTjfr;gP4X)%ZLSRTMk-KEaRr55Zi> zg(&6o-Y6Y9$;Y88Q}m;Y4x)x_EV_4YC;1xSJ~ZuvC~oaw#TqiW?aXUaCaT=Um@nuw zQ|bB0y-`8lbX;ER8RU~jvssA~Y1ATO9)5lT#-~w#;VG+G<-(I0@6gkR-1!%}^9Ms^ zX#*z#z9#I@*Ew+;$N488pPK3I1Wjbn3aZp&ORy48=E zdu%@D_VFlxuqZZuby%x`FdZNr>4_OzX@rWAxV*b5^YI@YgSU9LwVa*QMJ}Sf%KRJY z;~&Qf6%PLZ!F-l^tmQu>IASV_Wy24y>6sp%@8+3nIEu=qwvxBg=I)|qEjz&@COUZF zbX$UCk;o`!XkgkA*3AESUDS9(j&RN30hfWn-f;5H-ps_&KZ!R`^G?AkN3#$v#S9k; zHT4qSY_2wWHM*4M8jCwp`-kgj&GPiaIG@~KOjV-}&%RjtI;5ki%aEr-q`IUuq_9V1 zgq;D%lpDjW0?@~?Nm+Oo7xw6{DY*E5+n{9v1tAK5{geIi>Y`Jt+APJ-VG8^1wjLRO z2T|>u&s{_}B$!$MNFbPIShM(J%lq*F^o+Z%f@S-LS zt3&?~{VbGc{tn`ygD_hFx9WSCplD^;Bi|v~;f}lESm8Rm;Xg=saI5lhH8IFWbbH^p zWh(AL$1nrw=8C~HOa4L!o*X~URn!Qb`qd0o3`*6|q|s6DV3qs5I?xQ=ND@pUZpUf0 zgEnC-NV>3RToWi=+61oRmUKN%ueZqu7=0YJc*+D}8c$S(Be}HN=Jtk>m%|Zpqxr1z;;dFC@TnRb^kA`D0e@X9%UNUS%jf zL@Don0oDFRz->FD;KcyA37`nT1+SwhrWh?8#4TpTHs$g%wk&iA_odbj_!0g02oFjt z2c|{xheF{!7Y`jcqmvXRMK?H1L_?3X&fW0QM2jXUMm1fk%91-Kr_dtw?V$bc{YeE_ zg+KXU#{}H#lC)Jd98vcz7}Iy5H{zSkm%uYfP?M08rk>2vt4xh)0j=fN__=~Nvv0xO zJitHP_g#GjU8=R3CNBrN#hhmIO4_hL%e~ex->8cLtN48Frw{YpR)xLm(W;q z4Yg9TbL+JO;sk54y`~+?ZD`AaZs6BSK5XHMbVrR(7JT@>l=~i?g5b$0@APdNVXgE{n92GSCv25ryl1BB0ghJYq@x zKn^Hjl2F?~M&8$<)0ZO8wmrgVX~b}K$*ZOew-;}`B7&!kI#WFx3cJsyY36*C+z$>6 z+y2^O$`DZVVa#1KUK>#;m9%fp1nLeHk?VrJJRY0Zu^Fm82VSMziAbaS0fkiVnUu=cEI^@G0lir=T;F-_u zkz(V6Mq9a{ca*yhW=JxEl&`j6oL})FE7E}{xD@^}L(@MgK{rEV+pA30N$o%-lD#{R z-HLZUIqh}ft60ANgzSFaOtzy)_A-D?@f(?A@D&Jp@%GCOp32lj7DAV0ySScTmJ}?Y zvzX<`EiZbGmcwwQ4NdyzVL;eDdelFN8hM**W&#PfE*M`?2tPpd_Xzi4o2I}t0u0X_v2+s&MjRlnMsmZL!sP^IkaM{k+LnhsdH9#h zo<(dP*7H2a)EjCivEC3nrhb=(NTs(tY7|wmVewJ}U$aXjlXiS} zU!+Kh5i<2oVkY-i7al61R@Ud~(mb=+&FGK4wG5=8n2%fPY*pZai6d0ou>>$_^I8N9D^Tck z2V>{|x=hAyHQC1q<}>N-Z?|D&ZW)u&eP#{`g7`v|xXRZDz#J7vfuhR|ki?I~;)`+7 z-)thH8i+HwLGl2GZrS44PpayPq0&ruhUcYa1^OvW-xb;^}Fjl!bk7Mu;=B{Jie*lb3eS zWgJt4!WML@Z7JX!z|d4~`P+Z94Kby?#|;0iMK$h%^J!2%9z8u7&eLX*Y8zghSj{Ic zF3ZE_yk_w_^RXa>m@(0CzuTwl@`{3$!HxmEUM#_$2o7W}fkfeJW6LVr-GRncYwy36 zK}HyFjv`6byk-l&+0-djMN6b{iRtw&~?v1#~PoV?`sGYM=5LW3tJ~7ifwxZZ@O;Yx_~OCW8lC ztEQXXY}6CeTPDxm&wf`2W=`Hb;>2|)gK42#%c^OK4csP1H1%)YB;ybBz>Xj+YxD70 zYqK^sj=IY5D|BS*fNST}sM9s|{Gbyhhbj0@N0bpiqv2(cK&4BGM4A%_Ai## z%+<=cC}3bkOI_6PQ-4CQxk|pw;}PTmf*(&#d-l2j`4Ub40iEfUgCRe;z#hVo(pUw} z2SU19g`yUUWfTnz^4op4nG#6}Wv5(g3d6@psj^%AJb%3>;74sgQfKq7*AdSud`O7{n+oz^aTm2woA_*g%&jOIG{%LA9&Ur(1w zNIRl-zSc_kFYLQWg+A2` z3MEWtYH#`L9Y%!uFMBJ8Vxp86nAGvHU3GD zyP$4);QrmzTX?RmTI%zCu|H~?lF6inN`qn-@%=~FL2w3;-^s7XC3nMj26Sc&SE`P* zonNmtb78o1MDLDOtuHuR^e?GAENF3hw$C2i{Pd64M9uc1&4@yDOJIBFe+MFfS5*o*$_BpN1cy(;%IqlLuV+ zOORea8)=l8+ik9BT^w>p{EWEBa-5o7~YzYijy&XTnAu%uU z3IBExjp03=4hZ2fGq*tpUg<3hI!O&2e&fXn!wFMYTy~{Mrw;J3u8nS)|4b>_S0UP8 zofE($vEAE(rb2-pV>q^3Siw2+K7Ft>ph)Gl*i-d_ezm}c@&}%g0JEOj@ck}Zy(U|r z!HCy=?I)6%ws1}d9h9oN;ZK7lG5Tak05TXDb+$xcB;5Z#DZYM(Sdq!hA>6H6UcT;K_JxTdgx0 zM^;Zav-)=#77mXb^12Klb-FEfPQJBkv=&uTA;t?oY4R1g)?&2modW90TtEt>Km?0%Snk4i=oyXAT-ACdIoSMFD&LGa!ijoPIXGb~yW3dT zyx2`PUzMUd7k-yCQ5T4EinrxWYn}{HzNk-AGZY)M8@fDSaGoSz66pvcf;Bq%QV`w1 zI=y;_5n$L^Y*RN^HSyR3{cXTiXY>ebhWTGWe~@~&V}NRo0x*{rd71 z@#CWS;XJH|u_(my!aO)R{{FP=*PJ;yOgXI8c`25*59rJv&stc_zQ%t=te0&(z@Uef zqnsVasE;xTPkr(X~EyI&v%W{F8?c zHCb~Kv@dQR_qzps#F|kh9#>hS^?e4XM zixPbko}1cmA=-5{Hk4G>JkQAL<6m+mariLYD_`oD-lNkN001h%6F<16yZ3L2@8*&~C^zAbsIhNb>!20eW#|EbI% zi6*3yh9*kdPia{tNZN9Bu}R~wxMRkbHT@?DpPeWfTeQsKUEk^at{X>~!)p%W6{{d8 z^wDWgPTCh@#H&#oyjjBqpMTd7kUIx0p^nHuVkA*jaj}St#CM%{qWxs`!k#B-odiWbmsyWF{!x5Pif*m4$xMEPXuOh-f>n~W<)v+V zUMD?DaIWabE{&>C)|d#@#>1PDU5%^~*B6nK zf*_3gf|iQ1x0`N?s6_8J1W7Eurn6Uy_2)js(odQzHIn!3!ceB_aa$ViDw{6 z{Za>^k=qpTw^na7nUZOGFIZ~BoiCud%>~%~%S;a-hoUnFWZ7;UZf!Bjg)J3bu*Hts zszhofKXst(jC{Dm^p2L*&epujNX*XjsLo=c_*>9J2d>Jn*J>}DOkESMf9%Z*OR18- zu|#So#OfPyBH$^4BPaE|KJ3%)rYMwEZO||ec$g(E$U+=1ah@?|tS(?>EJY7{V1dMl zs`rq$g|p*bqqVQ{;*p5VQB{rVWhnP~PP2j|B|}MdO{X5pi};`){HrXfqiO*j#d#>U z3Kdz*dsi88T)tJNQNSM5@+|U?AIe-1IiNXM7wwm&1s*0Yd0c!es9MM5$k}G-Jlen` zl{hog*>fvj2xT8r`UP!b)<=pj#^-Q6H@|sQ4F%pGi_zsXgz_=F{lk8x52R<90db&b zLY!J$7{%o}Zzt>bS(dkQ^nc<14!)?ww5}|sa0%;wte|4@`6d2)Np0*w8jUx!OPbm^ zZZ0mHr9!EaKgQ;2itvzA4e?h>K$H35v&+46TMjJemyH}IjCHH zzXvmmeCPPwYcxSZ_m}ZuN8e0r%U!~y8F>hNxGUNAm5g8Xch+_VBd=-(N!ZQy)_U7~ z)vJ*@bB#ZeD$m?y>}IDtu<&=vWi1FGhq zPW>M0Qdw1r+{&Mi-!yh6{U$VTS`xyk(~+Zsb?QK7AdzONnImrtE^N7o8ozugmQtm} z^%lCSBH3^5q{3_YOu4M z_6gQuxeT1DMkWsSXB0u+3r9#Z4$+v#t=45y(Sn|pILxK%y-Bu1vP<(;0~v)w`QTfxJmI4gBDS!LI)-|ChwMtp1347>+-Q* z<*-5CTy4V7LWg)J9`fQpb{$TKuMx(HTzN6kB0G=PIzCbG5Nmsv8*b`1K%(EJKDKgT`Z-hpX<=h3_mx(56O4NBVm6+k6Bx^ zulK10{aEb6W|BZ`+QkFOovBi6!uM3P-)_Qv>2W^s;fSOR%p$-mo!;NJyEG;i&h6m4TNvY=g50;Au*gx~Iu){jG6cb8mrU`kC|ITLD6KzqYcydmuXZKZTO@cOh(MdD3iv6@|&a@#Tv=T+sLKF=E%4mwh#MReBt0` zEda#X<#-H&$c^J6sKw)Oy||0_@=6-3Zjc=c0fM1|`EWAk`{OuNrz^^O)kyG7*Ej`W zARi9}I*!OoeIumt`oCm-<+F$ya`66RU=wc-oI*dD! z)~J56+qO6mzsU)oa(!7_tRNs2oky&odavW4%~Ez>NKDb zP*!8@5DDKfzKZ~c5$`gc2CJKB`=WiSAT6|ZBCI}B;LXF^p*cxf(T$F+*Wg0fo7iTy zpJ>|*@|D^0nbe!4Vvm+ep68`=?z1h&L8u-|aQt~q^|DsZO(i(kAIE&h`yl_tVfm7f z%R|Ovg2%&QL1qFSPGs`H+EJe2dpK}5M!10G#T7C`jyh@q5hpUj_+bYLO_65NQ-y{`TL^ZGgnyC5%PkEH+f zlO1pdC`u>;=-k9@9mN!NrPZ+#4?fkjL^6%6RinMPwT6B2P+N`2{xTQ${x#l*l`YzI zoK}{8wr`f@Lj?&OH(V^)-)kL`auqBKV=+X;C2Hi{94J!*Mx9eR{(zLyWmWg296+y9 z*4)?)Ls@@~6b&q(*rTJQYx{jH-Pmme9R2;n{!x86ykMVTK~BF|rTDQpVxH{Z36iHV}4OO^EB%uB?Al8qo1upek?t-f zB&54hy1PpdkOArLp*x1|`@-+<|2!}5&;5p1%r)ma=j^@LUTd8*BcCwou! z;IFGt%B+{>Alkg^!lif*&ieD?F^h^KI9@=Lv$PsX1$Ufv@|zRn<~5rbal|4;3j;r#fZ`6^+jIi9BD$BFhBke2D0t$7ph8#BFJTM zTge!WE2IgHK1w4loJ_f)g~1fETOA#S`mEL|)X|#)(MrhK`9C52e;W|f#Q&?C7HH;l zpB|8Da6XxiRFujCz;5G0v%3OD6$p3o)8}At0tiF^n646lk}#Mt6RPqak>+Cd+bGf7 z6>^n=;NZkbAS4)q-(X@bU#uPsbbd09;m>@FJFvbJYnb`1rEx=8l`I~=4#N{Qi1c`u zHY%vWmpVi!1c!`c-j0#|cbfqB84?P|5vp2nYYZIvZO3B*xdriMmy;3FDjcggA7R4E zZHmQm(Q`eO>%$y^Q$lIL`Q&EoC&lmXJx0C!LaD)jSUJE{g^*GIRb||^bDBiKYCOUb z`Nf;}J=mz>8Gnf`$+*t(bP~KO+qwjZh zU(`~+9dJvoEOsETA{gDtyKxjzh$UitkG>=f$M%j7+)2BNFcuOsbo#E|Z{X6}Q(|>C zB<6nL*vE+>Zk!#WNLg2+2A=>|l(SYN0{)fd+&}1*Ju$>I^}R)E6Rn_#UE(dhcxyMM zk)M%Z9OCZOE2SM4)_WJb#I`+fUynLpKIq3i{w&3&fbC{DeEIC6LTnIubQRh=^7KER zJ-&$<3=0370x`u}O(b0pl^_X_s4f|_V1iU1gT)SA^kcE6w#J&1@dLG|RaN!>uzmj* z*yz^AqB*k{+MClcZI@7~UCyK}^`}%BHGdSJ_yf%OVWfG`&3d1r!d@wn%Rj`j+Q^up zWZ_D{8kvq4*Xc&8zL4i#kJ{7~s8ez;oj{@|-z>6Hpz<>KlX#^%wA81qq>u|)1xj+7 zqo2JnbPE(VZ1-Tgx}f$oybbftvw{3))Ec!h(nLC~SY7clS2Z>6p$EX(J@&93!zxj-@)Q#^lEQ+0fk8zbK^>*G(+-)Ce%P2(`xMVP{z;%29Qif|FkHzc#qJ5xuM_z_wyyep% z04SM_8GadSF(6Iq1htND+N3J?4(I~~7{&3L@pi0zF>#+SGF@0T3u0x0T;x`Kl&0hy zBK{qaO^H|CKwB=2-{~{PDbRc&or=`9r^baQ!}a*89EWD=(sM>>Z1G4LV!Kgl~hHn*>2; z<(;zB0Kp;pE!YgT(|I6YMy{vncfj)F4|}c60grD~HY9RSfByq~eCZ0RKJVGt;Li3W zV6i@!NG3 zG7Sm;-(J8`+GAGT^S<%dc?Fn?&$9?fISA!#Q8i$9!`J!X-~bC+A@Hu6fx~Q-5!7QpXuddR>JD;sVeI(qy5b`kSpwLV4gI%lgdX z>H(N;#TgmaznI2cL8^eug0t8%NmS;`P5$PPD6S|(ebyFbIi&JmUFVV+3sO?ko}CEK zQX2oEzo*}F;ni%)?%lEvCG?%UTaUJ= za*`f!*9|M*o9|x9?)oIyn!HP0b7yUS1un=Q=QjLB6V9%isEG?{5!O~I(>b#cd~T?* z*>UrU`6L4DF#E+xPO>gePc^x7QH$BJXAz+X+A5E$u0uA)H|cxqG$N`=9%Lgaf6f2f z+c-7tU~)ow^;_mkI2)u(fH}x~%;*Ftm{itH##JHC-t;3{ntG--)JSSBMTUIV;&2S| zKaJ%)U*9ton~ryLWomN6H_^Yff!mvcwp>fzNV`W@T1}TDmNQEc$zQ$vCQ3OPa?%4G zO@1d>aZeMx6!fIaqKUv=+S9lWFcQ%WmwMF2*hMgtHo4(b!PlZ@ji0lEIpxV3aPu>t z+GiH<_gWX0KcN(~s3HQ_EhI56TsmnJOW}09#vB0g%iE>EyS&4jHma^4Dkv2jwO!q2>HU+7unvn3qE;=KAZax9cIQ>S+jd z44%W-Mvz9De>0|)TL_SeKhVq7L!|>$eF?m3^ms++r^QEx637ENk@Gc>K{U`7Qeax) zUw$Y)E+17-pHvo1-Jbi)`4k6m&6G=>>yh`jXB1>s*KjKF;=I63&%!%{S#-k$zJf0%lLs_fX5OVso|6{BYp zPjU7oPc4**FpdO=w#cb2q4r==s^z;@^&WP712$L*d6`lyKDjz_PXBUn8F2?rIwLS<%5}oq>H!NU?dW zh*3zybwT?;4c&YcssPHvUV*2Wab<-e-Y0h`Sr9MsGLDBj7ll3lNx?pBW1;&3=`60;a*^hAJFk6^<%4x)vvpFX ztBCf@`d*x0=7i&K;ms}OaF}zBIOq4|1tc+tx?@}Y`RTr*tZ+Qu6`wQJsCE2B=SI81 zb~i7}(h*Y5z07{{*&n_Vot4#0G=bZqI~(l^sGOoPcX=tFy?ioxCgB1B)z{aThV1AgKI7}wZanzpkxAva z^h&ljq~*fl0gyQKO**Q?d3zh_D!99WGB8P;F7!6L;cxPd)$w1S_cfa z{`P|XwktLJ+hk+Y;1$m{$9?P>56vKY3*Z~R`;w{0k1ioPh<2mya^r0&CHZ?LD*vN& zR+YQfv}3q1J#oG;D79Y@u>&yy=K#Jk!R4Ot4|_TXyd?s5A}G{bENJA|=un30k3WAPrDLB;~pU0Ws*C09_ToFCe?+JP*l zH(K7x1Ge?Uw-v)1hitw)qKjeah$ivN5|`C0+a7cn^Qa}&$?feea>;Ekd52FK`0m4g z?JQTLoIz%_N;C`0=A&4^#yPF<<+NtMdt?OH^-BM}6qb4fT{wOk^AIJyU zPxo|8S{3I)!`mWP{0;M;nMT$((nHC;iZ;Ju^H@7BSm4egdi+#LTfv&Sqh8rq>mVEM zbPt^u^N$`$XSA10cljb9qzgR>Jxi~Hl-g=mGd7E+O*-S7K=VXiW6NeEGnhK{5_6LP zbR;spUz|-EUP8Sy-5?jw%ik~by2&YDG)X6M6g0h8h?|+PqJ753)Hvh}XZ$5|mCEl^%@8r!~8a=_}S9v|N8Cc>bN05Y)O(i3fK{c7 z;d3`~Zg=EyGfJRDFl&byy5Al-g_9tNUxC{+Hkc^cci#K&TZGpUf_n|JGl2J%l zIgbcV-r%<^xv#V@JPB)TlOB1sbbM_;3ih#G8k)UG64p8?0B}-m)OJ%$_I^e9t~XI+ zhu^Yyi^xN}oq_&}kH_#9k~s^z1QbvTI@iq0;tp?EPwEP+%D_c>UcfA7Y5!9xEWH?m zUKEV}ETQmy0Se6D_f%X#fuY`&R(1$%Y%{xkZ6|zapO&JT$hfI*5paA^%E!SUA2Ai# zh*54ah&H}C6OlA|C(F2qwx|t6aC^AAe@Y!Ppr9Niu&xtVuDzKc`KKxjSd$^A4u{mN zJ}=sjgNo^lX06uaj#dJc5F+p4y9O(&WH@WY?t7qwdJq&oBI$fp`Km^uwCnQx2)uuf zI8|_$N<9kaCCjGx<5p6!y|a5t_H=YxKb(Dhzf!Tie`LLMY7&u}?Y8236)hs*UvcK& zO1`kf-{NiKKRly1stiHndwALQ?6hJ5W+W3vTK`78P*d{O=fyb0z3T8 zEr9&H;7sBG|3`@(^SGyL8b%-AUqn^9;zxKf3caLG4kXV$b{py7T09*)4fX7A?af>P z&b-?A8?c{mXFT}YbWuwqLc<{Tuqx@O9&SPo)fx}+@P04ws2DgEgC;MBY+?eP^^d0fmdArHj0j7W`bAVoe;LJ;f#u%5_-S& zCnngIC%5=?aplP}z3u;t+bT14ya+K`GKrlErSpPu8qhe!0R$g*QY#bB8V&%z_Hc6r z)c^JsCL)+@eTFd?YErepsqi#=u_Sbe1>J}^M+|ND z1Ajv!ZH4c9kHh_y;6H==3kw$vN!Co=B4}CdZwFt0ec<2S7n#rKzvK<=AQz13#~<`v zNdBe2JuKB6nBnZaevv<#RSUFLV4VT2UMR6qO<^^UqoO&D;YX{Y(utq@d%rI@vxquu zfJEE(W}??&vBg{=a1M17xf3`lg&&GMLCw zqSsK%iS)YhL2Zlc|7y#`OVGnk&zpEr1K}@V(406}Z%+MBc)l2WM*HnvsnnHF3)TuU zR(AdGg>rp3`X|%`4W#R+?dqW_vwxk}Q~om`mv?;vsOX5ibBKf5>z00fm!K6-BGVTE zct#Wfac+8ZrjbOtr(rduP5mH0HLb#|4$Y|G4YE~f`js+30`evre4#v@Gxx?cqnvXOO5{Q6WZfpEP1-=fE?HjDF?GDmeY?LsvOKkdLtp@wV?mUHLGc)s70t52$0l^ zVZuVJmy_RyAueE!U}v3p}5iYXC50kLi|qlW85trZU?r8 zC-4Sr|K0!r1Y|i^vb#LvjIK|?90;NH-BEM6uZ}UwG(!pKFQTeS+9N>##TfcE>2$_&fi_*$$x*XHKQ&(aX6q}q$RF8^?JV!8@$vDD-w?X;^77`V zf<#|@@&V7qckKGd@jmepcW!)7%VeLMZ-tk2n5mV6@NNUpR*;2QF5&nf%KGp40iZlm z5!VUy;V-cN8zK(S2|z70cj49p#&%sv;SwvW3hsTEdRR|y@j#{ zzUeH}efgC6BfNHEsn|bFtJ_Z3h{^jvWI#S^sqxa=eaG|0yNxcYXGBAX(>jb?$oq%T zrg_;MC@!4(LY23+Wn12$kF!Vm$p15tDbI^qR0kU>%#OJuCEje)|0L)`5H!Q~R5waw zD*LE|JAo1A{(oM80D^s9*y0zfIPwzG&+)gr+zKcKaCC5bIb~wnXn@gSU?r4M(~?VF zKrW#b>C!QX%M#T*_O;`GE~P?bR%^5Ywouq2l%^&Ar+yJc!HC)+yZi6y+bb#)`5%#U z3hyH>y2JtsC#5TsYs??ioKcP=>^$S>!*Bc~H-hXpM{G3Nh7Pk={#q=@-Rl(m8ZZnk zO=w$a|6@8lYyi+{hihc7Mf89r2jVGF?7qR?6)LsQ94US=81_y=w)HSzb7od z)iW%yl~2OecO{`+6{}HT4{)-r6RSr)GYrs3ZJEmp!Plk=r=30vaDqC?jq`PS79xbWKD|kPbffsSIl)@f5eUR8DYuKy6_5vkL2}v%1IF znzj>-QP?jrzT?_v6KI2z$xIhGH-T>S!bUQ=9rrjKt;@k8>g=< zu9_bkB4n1<78d-or+;O8>g}zm{Oqb)cjE2Nih?BqF#)5BmQmXeEH*!k?63-NOD}C2 zONep?f0p9IlPPr)?EZclGrL1*>V+%2$AxeO2zz(`4XYb{Nh`>bfOg9SWJjIbDaL2J z{_*k+BrDS5`kx2w{0AVU@nUUrRrF{FRnw!IHyRx#32%@Y(VTF1ParVyTDIM6K?)Cb zgu`gh`LvoORux&G_-tNV=URtqWT{HE#Ky+V^oAEy9s5pcjIU#M7wW`=ZeNn5bQ+~? z_)V8_c$WQVL!(gr@e%|ReBOpHC;&$ekp~T7+^#`?8lVU`A_{HOgZ$cwEW*D&PZVuw z=(2!kqi$iT&qCG|6(}sP39gBFb67LAR5;7Nn>uv8%T1^ zc_v5B((kN;Qt>^3fP$FYwXD|?dEwm+5DH5iIIA|R`u}+%qDxk@T29B0EbaQP88SxW zrJ8C%MMH%v{Xp^LZI@+YB7J<JcN1%?$NR7;e9`BE7Os13KnB&Q zQcj){FbyoP32iH`0<3!bE+DjpTCZ2KdzJy-0c5I5(V&3`zwJqoS@qG!fX-Zfg3>sO zyG(4e2Am51IJR(=2q%maLUuNs)xKLiv+pZ6MDf;u(@yy-|ifMy!; zCfhGd@cTi!tjWhln9wwHs^IuMHwB+u%BDXMDHc2p@QE0d*Wzxb`WTc?fPUGG>`8Iw z#%nYYc+iw*a00Z$gk|N`u%keKF>3(8nE`Qm=1hBQ0AtS3keU$$b!rq zDl9Q<0C6%vxb9a9(STKnD%*FA%e*2T)`4hEcG>f;ZSJO@otnl-6J^81d^LWPu`&Pw~7PVB!GJU<)2twt91A zSn7IxJSBioim!=k)H@t~Y6H$}^4k)A(_1B6N;hZ4e+9P?!C9UwM}96?7>H4LuB$rC zOmNxBPj7#dsccw-++&6CI_@UbldvhjEkiq(0OR|vEOkDrS>qZxDfWQezaUkH(g>*P zs|CWfZvOBG>djyvoyohKwC8vME(z>Q$=J85kHU=VqD^?st$weq@vYRgMV%X1h}fk; z5kq4TI;o){jr}d)nyveF1zG*gv-#O5WaZ|ZrnSzSoSiLg+_6Hw98IgC?&PO~xV?1K zm;q_}mqJpcI@|d_wSI*_PVL|+-~I)Wi=Bq$37?}ZpBe9U?ufU z1Wx2B0?JAI*{*w^<4iLJ_ipru;&t}scl4+?nGqZo9ud?R*z`(ea!Tg{nt-Z}l!Rhb zc&lRE5oU333e@wV7&NxAOa~$sipohM)B{YU0L3m$m-FdB&>@Wwzx|i{h0e%O0}lI< zJwS0=U|ghiAayWcrhe(S&8-1M8zx^Ji0^H7VZ#LtU;_UQMMz+SKQ10Gg48?H4t(x( z<|^o{QMcmxEzY_0FEsSH^Xp6W<5?}eD@o{PSf^rlxsTB@#&P1jf%ZE*+IF3@?}ZGo zLHTS+-?E}cIK^O?239vkBH?cmIBJItBCJ|T>*yHv4)$tp?68wISYA+POjgso3u0|r zT|f7%NA5}z3~<}|#;!y@6xUfRH!n2XfPLmG2rs3*%z+YuCGI-ndz4;T5)sWZ} z_x^Ms;WDndoJ1n`O(tNpmW;bi!0?Ym-6Y}v_Fg&>ybf||1NO1wa|H}(v0%}O2dp_< zANBj1yZHuedTw1VW876WOM5U92;jA={isG*QfRG2&xRABP0#Ul+AoU23d-*=Lme&^ zRhWM^cg}VH$wra`9EqyEqsk?<^R!D$hwPYWhzl6pr4C>l%7~CbVO!YB5beX4^^=^Y zNXD(HxW1HbT-n{krVPNE+TI4>#yu@$zYa&Lg%`=4?SDs~!A;N5Ic+)fYb+NR5$HVQ>e1uN-;PiNL>#y0 zvcM5@7)p09oA|H>g0&@A11>M-lcuC9t>-4noLODJ%rcros;m%qJK!e-MfI@&i-|O4 zyQOToE{veZRZV&3P{*$SlKEY*ldaCp$!ykCyi7cKoLdtKT2asTvv{|{zX<^rSAj3L z6UmRqG|^g&$B z5v&@oCi{u1L!Ada#hp~X$x@g{vBUh|51xa-Y?ZgDHWrm_5P`BH0cfytvmxF9C!n}0 zzKXM|vzi2RGU;hPv2tRI8}0md;vgZz3IkwjwPMw*=?ZnYJvLt-F!ri`ua( zv$_yKb|?h?Usw7^di}37A}WHp7}JTn5ptDyB5)spkU86s2ypS;ZKb+@mVNvj)8hlQ zO-m?a@)Y3;Gec;xFZ-jqz_4pE0aW2_Iph$Hw@;#G{CH8pu@qd9zw2tF!3U7To_^Z^ z#X|iYl{@QI16>G!LK6%G&vk1La3^a|~ z3ON+UsuO|9(w3eub0jLn`l;FncNc%-sUKa#xWMh1xL-40ZgjJF3d|S0n)^MD7QDkr{Sb@-sn-&MD?;GDP@clwstL=t4Pi4@DS9 z#UyNiH_H-3kFS^)jTAs)WB)=9ETw+?_T=ihkBr1q+Ucd#$HyF?XIoEMGhy{%tG_nKtMLwv^`O8!n_4t2803+1F@rPw%+m9N*6s4A^2R z4`V~TAIi|(-;_hY)cRKJ4*h=~SofjDfP8rRY=u8*_Oo#=X z*QYd}H&v#WF;7-$ZD*!J)=bnWBMp|GOlgxNOxy@0)LjEF=>T}Ktw9fzVbUfIc|LZL z4+fWl**+T29V!){Y>;m7dSG$@fD1X;p6Gdc-^Gn1s$@BmVxM-gob* zdE9U1v~9XC2M;$`ZYnj1j{Mgro2MVA`OP=QW`i`H((2Agav;Y(urUC}U@*fGP8PUy z)~O-tr?GB^#wIKm%J~XW58nSB-(Uh^5qtu7l3U-}Mh?h7v#?aMzRSTs;YY%SiH*KC zsUT3nGhL?qJ8)E@mTolS7W!3+?@e+wn(2g<8v#6M+07`w`)AW)hMSJgB|{d;k*`2V zoZ<+iJk6pUt+Tlb#Of&8QkKm!!T2q z?A-8Pd*n}4{)3WY?KD4&0^X*0U_Rhpz+6-_P#VH$F5p7NQr+CO85;$_?9@7as3(z_ z{xssJ){8@q2Y@5tDtqplH4{l!(NH4>e=(9OgjZXI$_3UjvV~Wv1*Pk2hgETks6Im7 zmwStzQNQIvZ5tO?{?82TW)fp%*A)D8dind|;+Wpj4XBJ72~vfydo1h2q!SNdhpdFx zVz43lv@WoU+j%xbH@7w;WMsgdzpkIGi(6r11(k*dEk`++3Q;ow$mUv^3lS^pTo4;r z>hFvr-*8}@AK!{u3%rC+251T(7JJFn>;7xyRkm%l&4}r>a)6@_l&QAb?m81@$8(p= z$A7g8782{6^@XV2U9T=aiAOsp3gRqJzQSr0;gX=jS&ef^8(^Us@_UeRljcWqz?tX% zJEmP-C=Il$@EPi@8l8tN87TU2lYqVa|JP6ZtU9Olp}PLnt!W6B0Ns?YGy|+>CBps7 zWHL*hT`T}PE*ON!p;jdx6|4ZICtMt$oPyG=(uVpcsxA>pLDLa6a%7r0lY-qPFG)Q5 zl7hW~(Ad@b+U=`xwmTq4)gfvLFvRyOWCa-k(g|-65UtwT{qAkBTvkO z-H=el-sW^ycd_{>aU7f9NlhVM08A_u*6SiC33D2)V7&Q%C^qcEmgu8_HS{g22rdqg z1)uArV%Q*;)!Vm`@Z{%|A6p3C!A0o;g&Lqn6h0JNPshEta!Yiv$X9YBo`yF0Fna$< z$6z8g5A0_AM~r-CqTh(J9f3)6=k^z~OAsW&VOqc5`*opizBH5OTAD=jJ1{=*xL?94 zaiy6M@O($Bhc+?({G-sse0ZJqh3dppqt_4h!tnna)|#4HMr8ja4Xbk8?yo`*>`Q6W zq=@6Ck_B%IkbcwZB}YXEgkUaqAkBF0Ka&8~Om{7iH$jeToOZUDp=dVfb)_fbz}PEs zG*NXuCqLe7WdXxoxlz=8>|iHx2n=A%b{T9sTSPt2NFqE!a+5>{&Pw`atFsUrD(=!P z=vRQCE(zQ?JJ8YC+O%13p0=35`|w}S@OQPOMc|<~jp~L{oWaqk7Uxbd8OAAF;bGk3mN}i|IQIC76jUJ3eehSbHo8H^qHgdg$vWNWwh=* z&9$Cg7wvgJtyhku%6<{+^8H1?i(kjuq-HIT%xUb1ozKcW6x6h+Ti^cKy0NaaL36>Y zR8voaR;`h-TK6S2SHMSGWQ{eD-me8+Uj4msM)*W#XOT`(i!bjiMuswUL`M3lqES=% zorf*?=q$I|M%>59bbS?G&CMfQJ6T(|ktB&>vigHOKIAARTDT)w+lHj)mVVoLjc#XlscT-!q2T*#q#$Bli@}MihL!Xl~HohD)M{2F6~!MRev7Xp*afgd*h_6OHbM&inq-DZX>dR zLvSMf%x#Y6$osNJLGJ<821#Gjh?@?^mDktA4%=de)=RaV>Q$_+WqDj-R%fhk|9T791YCB4+yl^2CZs}w#P4FjesQYI!9Oz7*1&E z_!S8&^5lA1&_fa#_1BwD#eLb16&x)GT%|;CqYe1&#m!r6jN{$JU#O1QydtGNv^%6p=gJfdpMjm%iOE5`u;K zf7pZ(7FaW$RxDLb8dE~3S5?;fCs674Url82-sRl%5E_)FGgZ4xS~P%`^Qba-D)2U6 zt$n?+!^8OI5Ke!5J}zus3@nX)BJNU8a3@nF`6y;kNV^tSKdX&89sU?1@*V+Jp7o#( za?l(!fcdPfNk|=cYM??se;sGiL+D{HX(*iOB=mbaTEYI=#0v%bAK!o6w-#s&pS2JI zLSd1L7fQmchRM>V`Z4P#Ha5*{S6+;KLCM^ybEJTL2#ff8R4zKN z3S13g{ELK-S)$ou{UdpCI#afXN)1s^iUXdUs{IJ2OVOJ2Y@S2(x|6%W{-888pv}cG zo_t}x&m@6Mc2Pz3ld}SC~Z%$?VCsdX40CN1`MPR%FoJa}ez@X3>HAU&^&SECCnM6n6Mc{%9$Kc0!qc)4@ zqY}Zef!1&Q12g`&IgG@XwEWag^sq}5Se_?t4yI|Y=^%DzWGVr}99{hEFP+IeKFB3L z2N?18Oi=%FZ_P`zkM;PQW#n1mxoF~{ed)K49r?kigUJCrx<@Bm_;>RiWlr| zDI>`j@|{qyQk=Tu7*KB(@9#4SdbeDXvvU6N&HmYG7_#u(&l&^izJ$;CyknfXwGnxY zWnxX1lDJn3t8?V9#@H8e^egsz^P{epng$ZB>vL}3RO@h$e*l^BzdoJQ+4Is)LI`?r z)Ycm-;`%JNdBd&o$qU*&&}A_fY}sDX3$V7kpx}75x}$0g76#qM0ae0Fv)B?wR|C<& zGu_4$Q8d#Qzp%vXj*Laun;M!ursY^)8bbTx_>`@CZGAU+W>|x`vq@x_weM(KQIM+} zG&_@#_(Hz=%@v#==gDc){QExAHN@03W}LHAE~Cod{+EhW|JIFcrz@g|~~$kTFJ?E4B(^3J-TVAgTNyrRk2P zB&{H`L9HvTQcAD{T{r&}THyF%dDzX)tMR_rUxGwbBe@hFH5Z%%2Kxv{PE2G{Y`$1+ z;ZFD*!qB82{cE#R!&5hCp;sB~k=C~E3NCPejw6VdaKq1lw3HK1X21~W$N*QNZtfjq zvZg*AB}Ig36U~WXENCQ|oXp?#2BfJWdC`{ks(B=0{w&Lhv+B=2Cy-dH^gTdE$r0%; zE*QGn(TK}(FagD=yP?bqOxC7V$r;zqT`3L}(*EYhX+3-J(#_qy*HZ21NIhc))u~{D zFRDwog?^U0$A=)-5^no>N#`Z~n~g7+tk(tmEp!FkTM_e z5EL#hD{C_VT`5i7*7kMK9Sw(8HddYfjc#X_kmS+O(kk3=rc4(7>XM9Zy4n6z`*KzC0->bH7C>bJ1Dna2QE0o%I06AC&N)LCxugC=h>$grDX!TdenA9}w5g)C@mq%P z`Ixk~s4Kgxv;bGg^@ZE8B zKRLsa(w6ntOm|ebtFkYRD}L#~Z+<_SzoiLO81_dw`w zR%s-}JICD+t^PIjL>r8GwRHfJ!r5!g>~UFLf?WpetfP>q10H`ptxm4jP(HjS~nHU{ETxh$0+ zji$GnhK9=A#ELg=2SSOWZDi6ngZ!-aGT3yRinv->%#S`3m}w zGDCi$p<*g%q=>b#sr55^{+|~hv?wQPyg-E>tKUJ!AP|9gn*_}lZ4NeYzh@nyA1$)Xwd+S30xty{~-dvz6}w z6FNtq8BHJ?nvj+-*rrdwRAKs6s5>$(jdNxRDV$A{RY4u?^GD`Vp6`_b{#l*UM+d4} zxepL9P@Lo|jrfHc>BNV?$&nBfr>Nln{Sy}flPfO>OWipC9~i7cJO1DVEctBqbqsmm z3%U6oa@^gk6$!At{r=AJDb%jD^Kc_V<7lDc>FAMb*44b*kND_rr=tSOnvDKLX8;K? zirOM1RY<-PMPJpO!!~{jHs}L<`5(nFI5h9kN#) zhllluV9S}!IM2wJ(+(@r?r!&31`TAb7CUX%FNptGhqerfEh}G{dwGc>`j(wJo)s$y z`5hp+Dj^~nfr$u`H+^?9X>`|NUyd-D=JH5A4qiP^d?&zQ-2MH+39B*S_nvF z{%Y$p<5^Iq)tjqM7v=OcywY4S5@A!kHHUE|zUpS6$Myz4Q-aBVrUU30z|G6Ru7Vde z0d_=NUXXD6dxE3lbPeE&D%9IFGye~VR(kF4v&naEoi^oNcn%h_j+Cw@X@2ZGw@*#1 z96!8|rWkhQin$t_Xt@16EUN8xaM^~%7QJ+|Kmj?OOV^)UnX9U-{h$m#Y9t=2&!6>H zFsfK1=!3yQPdI@WeO2;)6=gXIPhSc?4n;cLiE2jVMRBwQ{Kd_6r&-y^MskAN`d;Oo zMvXzd4Y*M>X6ppe*Ov9vWW}u$he+Wn_-KJ#j_iR96H(YMFI<+v6%~^qus5I&W0q83fsPQfTS$O!eP?O8y>s({z zpu2C!o#{YHZlh^Y=fw+)^vn>L2ny%N-$rxQf_%FoZlO-BB!6xdoS}s6?>|W}(m#Y)3=MF@fQz7KDvz@M@W4;R8lbS?-4Ke<=i4TOyUl8R_8J zsI9=XBOAX{go}A*D{yIrTN-9%lYfx{uFZzVD~`$a;i#FR#{a>31AZZc?j`ob^P z%g>4(FJ9H%i>>slM792!{xnXNc(<6Mw2RfL=(Pb8SsEQa?b7b=23+5EH}pit%AiC6 z;5gg!gUl6Yxkd|y+gTQ7*1yIM8n(1?rue2;5Z?-FhK$c!@P)v<1U1#!68r58@7Rd8 zIl1^!9kPhSml1M0J~ys23D;bt$kB#zka^gSG2gU4hq*${x06^}@zLYsEb^22O zkyt~l@^*>B{7hyg;6~QHe(5fHf&cb=degGV>A~a6kU#;7)8m`6$hpvN(jaq#WI%Hn z$b(oIU$b}%1j!YWChxI(;t_2-qy$hV+eH1 z-a9@GJlOt4%Jh}r?$*1a(;UTl@nxNXpj++sEZKpnuy9tyouK;Vg~O$DO%iY&f`oA8 zi;XLrM27xJF$2-rbsD@&W1uHjPyYFP^NwL9g`+QTX3MPZAohB7sB$KYHa$)yen3KJ z;``vg#JPbYo%+&e&E=%%-(s` zH@=&vPA5~(fiN3MU69_)J|`C10TZn2kk(h<-PZw5;DwH6kZ=hPmtsYYuXRl#S?f*D zWxZ^Jk7xlTX~(ULAsoQykpr@10z*(WNK%n<5c+dL2`NK+zP$rju#i`wt6z16Mtl1s zp@Ut2qTGnpv=ce{JZK7fZ05K=dtYjq3)b7|TfB+m5vzUvMC5>I%fqq^E=%sWj`Gn1 z`oDXl2iB&p7o?t@p~*uCSZ>{Cfn4 z1a0~XGV}!~ijYq?7*oY9nji;w9Fh>C(ARPOH|wc9DGU&k=s_UcB*b_OW*LJmF%{H2 zE`Z$1uj86}Z)*H}O%>1_wp=QsCI86|5Oo#72f7W()JV?Q>+@fR5={*(r+?L<3E>~5 z$kKZI)!$ESkSTxW?MvB+;2260wrewwc7<~Gj9bq-|3ZG9R~t2?qVb|UJ&+nJZHFQ- zY6|I#DwXf@5v{(Io3O-b}xTo~k&SuYx5a7~Q| zKiXUWffLDQOWL!|TNBDRy$sT3f~hLE%fX_LswiN;N)3`@2|XX?wqxgsV1y@xDl0eI z&yD#)H=9EW6Qq;IdHl*mO9Z4Hfh;S z4gw?l^a6{PA4Mh5zGqoye-kbAIGDb%{zSbEc{t%xcIfv%brR5Bap!5ThxnRL;SDoI zx6fOXojyG!IFN38&A9HX)jui}L{WJ`t{yQ9jq>oCZ(H&z?oyEH_6?**5=B?8g>SAz zMHIGL6!oR0`)Rtg*{mI~*#vd5?qR$e^`Or6RKaNvoroC$0Rgon51KPB88T_U)j`y% z?Tz&}t=o=!6xE^kciGsmoqBgV(}w~4g>~oF0glb&-TB_m%k~GKJw3iiQBR7ioio1= z`vu9Hhn5s^mdCzv+Ue=A!^>`wJ6O+JG0d3$2i=cF19iq^F(Ejo28R^1cw}046fuz% zOT@R?H4Or9?Y$pFfO9HrtiL7cN%!`d_Fc_h(1xGXnoXO-qCLQ3w8fuB@g||llx?MC zL+B%MGjY|+!MK@ua;X^GaH#N=2v@g3y;C$MU+wZgu$PG9Z{9^Y-2Qka`}r(JMbaHf z6ES^0h;3Pwl7hzhq0c+_n*qkXT!J@`ory8faQxm+Qy3{Jne=?{DEP)s!iUL+;{gf| zbtqogmemA-!Yp$?+7o_siNo}FUagXXmzA$QRQXCC+_TxG704T4*ogk#4U4PzRpbsX z!iYfk_UlBMN_fLf46=o>UrExFAQIqD!_NOD~|Zb!RCNsFEFboBz;& zJ7l~kht5m#lA6ZR;*Vt`o^{hiQXH&oG`|!mkh#`pgC7m0XS2bBORQp@cslyd(aeB9 zMYBg)pRdM~H`8y=`S@19d)SSftH;<_8JpE^e5_oriNsg{2LqLQSMgEsSY%x#gj3l_ zD~G752UWf-)yaw3X3`W4Rb6$52KX=~E|ffzx0*#TQGlS#)UX@OGkE4tlTiZ@rBbxi zDVf?T27F4|WTmg?QHDTVq++TTx@xA)Uvg(n*;7ec(2_%+4Qn($|Fwb$_c zELc<&)r#ckA%kfCK;oGi&^AB$z)}!H)q*UB_YFI;1$Wb)5RS-noCSXj6ojFT1Z2yo^)0sx~xmzIs76%JcZgA*fsh{CTvErW{_?U`|yCAp8VuMw0No85P2x`fpeh_0-#i z=sbI}l=u9E>;H&U_4-VpA3slGA>HLua50W+QuxS6NROne@;LtfPEO7)nsOOGG+FBn3oLI)|JgL_q0oa7Kns1*BU#1!<`fL0Y<{K^VGA_zwQ= zz29Bmf2}{P#TwuYocEmf-TQf-{k;1m%aFjh_I6X?e)gdiZWc zy(58fI0-tvRUshImefWS-jU;waZRV;QYxnpKrWxT^ALE%$^CqGhmMASv>Z z7zv00OpcMNnNbJ&K^@1Ftq>LdEjWd=h$5%YOUyvJZr_-QE@N&2Mu4o@cbZeQM z@TVHMm(KB1#1x@wcRYc}NF861?p; z@E^;ooV-Tal1#A<{s7E2t1QOsfjYAHn--rW(~n;O@OR5-t;(V3!^ZRZENm1m~n17;U)Lb@A9rs3t#Gl@ak3Lof=W^Oi?k$*JpDuR! zgK2WN2<6FLnU~?)&oJW{7Smp7EJ|t~qTL7IVGiuLXdPixsxF>PlQIshx8nvz`2^uT zQxxTfGQT~j`q*JsU<(flME6?7s@?~ovys{THWgni0RAu1n=rug%KpBFRp%nKbVVZ{A16{3bazN31-$qgq8v5mFh17 zc{koYCs8K-du#4M(68v}Wlq!9VUGD!C=sU!oPUm{96xrseqLuQf$1QUAbuc%gJJ-K z5Yq&E=lD*9tG{qIHi_gkqD#KsnjT_q zmD#zXv>DxHf^OJa4?-DjEA7HAYVUu0Q2toU>;tzdWfJBVo*U?GfePr$8?yeB27n>q zE4Vec-N(6Xel}W2^$_}W*mB*^X3kCcL*jdL6Uhbyj67Y&YZUokTOw z21U)%Io!Esllw==PFd=qU17a(9Ox6q_R`{_;YD|~Icz#178JAA+C+R$y2(V`U{9(W zvNge&Vt^HFw7!~iD>3t}$ild!KK zi~85;=dx_GlwK)k?fZt z+@0{-1h(5D$}-Y&-@7OT^xMmfiV5fHJ`6Liu?zr_qNRXrwP!d>X=?uhMh9y=zq;kf1!*n!if7yo|$|vDQDi}s- zt~bu6+mFz&?@&vDRQDUwG$nPeH{8|yl}3G^IgvWal-E@DxKZ5mc_%(gWOs0~yF;9S!6c%OwBk4PdYU$A64sbCol4~iFxAMtd$e&t~V%?tBcY8xgAvIoihr(Soslp++3ePj)Y>rhFV=cU*JKx zy5r~{(U^?b;Su6V2QyO#2w-&wYRV0gWGf^n`b)JKNy3DEU^=zHNhtAyRHc?4ibf5d&fc89GR}m{=5ltr ztR>LHRj z?gRMKQsqmf*WE*`mV5L$m3Qm2g_*dU%llb0IEtUia-MGYwFsN&92^mY)Yzo>Xx#|l zv(&a*S9YpCK#n_U(UT%J?=%Z00G7=C;#qxTu6ZR(f3{YG$v8|35?I#W)2v?;16Qhd zReW5BwCA$N2I-fm+%e1qH8Yh)nECBSN%al5WFTr`SEFd3VCK;*#l=0*N*4Oq*ootn z99KFw)%V|Em?PwTKaR#dlG%oi*ZwzG%9q_#DMdCe!}DZvPWtm$gk) zxBWlK@0X@!kF+mi{NLpN))UqeU-S);wDrndBOLh=y>{b(znd=3^XYx7V28uAEj1 zWXsQ||IU^tFNM>w?}-mN8w3qg6FR925B}DKYPHJ$y67%>Uiek1&J$pJ9bGpYS7PyJo;UWGSq8Wo{28n_x52h*Kf_>EFDk$sic9}aZmr7A=zJRzblW@;Rx-XlN8fYLU#5%m?t|m)ilz+Lj z?1nhUR|Gp2Iz8ia2Y5lE+o)!Xs^{ss0r;!bu%!b zN`%2ykj%!K1htWP&h8#dk%2v|VjHpxt0}*|x{l4Q&q8XEY+2eyo zS!%bVGM*ILXy2gAu8bC5Y6YaJ{Fxx5;#eoUp}{RB%To_}8YjG6Rg9H8%c{B5Au2G@ zvX#iIWx7v&&GKk!eHkm&!FiAG&CeVS`eKR!>=ru0A2lWu@k)TSRZ*Wr=FAaycGu4r zgogV-K91vfF{d`ktzi=Q`gjEBDpIsJ6#Ef~YG$`PpTFr>HC%SL&$rGFmCE_4M;8m9 zs7cBet9#x>ekT*n3c4U(4FaYd>G+g&sDN{O=m1qAA?~XV>5mn!N4Y4tjEyE|I!gq* zt;{uOA#yd^38{z~W21VGL@V=6J6^afO^*ZuhOkcYSmk)QuLco3_rrgSBVMaX^J%!-v)ur(%_?kPZU;NV6E@J7 zxAP*sww4+G-&s>K=@b}*3yA~S;yZvSslsq_VW!SS-%Wmd1jn7+^-%3?44_NR?4 z)5)l~k;E#Z$A^K2dnI13%~kvn*M6No(UriPvTfC2K)QBnSCG83$b~R$Q)%n}%Y`zHiH)Jzl0Z?MkPMc@!WTypjg60>jBoY02S0&+^Fg!O zxxhGbo?#B$#a-FE{s=fj@DSGDSLJL!+W<3+ktm*jkHJX3Q1{r@Mw&1xEjZxG3b>Gur5U~GJ%X2@rRFYEHgWe zj?erV!4EYqgURLhe|3j8a2pHBz`)p!5)1+)`lL)lu0ARbjF6aIh{RrIYqB=D7RQwpT? z-^#_YWbDaX)Nc5WP8nYP5A)Om|7D(hdOt>5^cWSVexny6z%<=b6M!Ad7Y~AGja2#c z3+?mxRx-%{vB-ybgHJVzv*J-4FFkwJ8$jvcL!pIOwTC8L(sjPf^aZgc@NDg;6eDw>cc8f_wev}3 z^MK|ZL(R4+WB!*xga|!~cZ(adi52~{+{_ogL4tB(MftiJr;Usix9t1>WXWPyO!yRs zDbpC2+?ZW0)46Fz5fn~lm zsslngkv}4RjeGq(5%hzh-H5KF_f<-Gp;X15S-o7#{Gf|an=?SI8=fRs9mEDn(lApG zHAGh$Bq-L^_cht(fANCpOn(ooxC|v~Jb&!Ou@{Vgx~vU=p11q8ZAZm`O^;!h1bAx1 zmm24*ZPyjG3flwamu830Kxhkr0jPw^^{TsCQPrcII9*QHpo$lM#WSaHJehPycIL6J z7flmFDJ#{L?AW@j)T`tR+F>!a$EB#7EuD_J@qP~PwTjVnd~q-Ngd5=hweB@C#u@wE zfk$I0m}A6tO9RCKf~)$9Z0doS%|e+~dx{p@vIlBhKwf`NDoF6>j#mhEL9lhVEfD(E z+Y7HX<9DB;HX@W?y;+y9_%B(vL88!IKRa{>uM|hP=8kD!*VFv}SHS&HRIHpn5n~;W zSBya zsoVL)#sH)r$4deFB`z{-wg%KI1ZP{cH13{fBbIck@KBoVJcFuLF_83v^^COEf>iR# zhtt?%K_J>7CAsIib*nO3_j0brCk8UcTvz_MjlVvK0PabQEeuh#E#(Cd+u7|6rn-4g=7Y6kd zixLY>i*P8~U9DRi@P&T=o)#*b++kfj175XsHwagO*~8fnYA#>4R8_J|0-@_yP_JAO zXc}@RiK?j)T;Z*-?NvxG^MPj~!7k~*oV%jDt+Fhay(Pu?8P=u_py>0bUTpWfkWY#r zG((av_dd3D3t^nQI`#(99`oZlBEgUO(~oZpHX1mM^-79$4vP-R4QUSg*d{&m0rf=#37r^Udg>rwENV>J7pt0G~l^8HtKkhv|$?Uqs{x5TZ7x4 zGyCP`%jtQ+Mx6dCQ*-zy*0>ohK5j0^JtqBE`s#>=*wAy$x$=b5SPwlz+% zU6=!~TZFav>(c2yAVf|jy_Ua-B(p%}7#^HT*d(i+XTx3fd53*`W}h%sAH|hW(L6_DZw9Npm+K1DU2(QDOq_3APo7rTGlwXV8&x(w?8DK-c1z%#cl6Yw?Tkr=k zSUyBKjxJI8;l7z1KiOH{ z!?d(+Do#Ly$f-b($^J`3j-qfLxGg4$qg8@|qR!}=CnI@H163J0*MUWR6tTwKuW zAuqqNx_G4Y^cVwHV>{9Jh8*)4>T=$g_1TtWr!$Gpc*2`BqE|x*Lihb5Vh^N-uGoap zaT4^WEJ2n9e2z@RkqmS`ZD7A#N)0#5mEu9^Hu`=*roKt)%Wigd5EuFx58M%;IQRhO2!pKWDeU#Hmenz=BOqtm2*&k0CTDQmLQm-6wWL3aED zRSYRDFC@LKnw9qQZD{RS^bZ>H=Q(jM4NbSBHFpFGa#{F^q1r`1mpED>i=BR3!z4C8 zo1Xld>#yr4Q&vUx<4;7oogb?S=8ff&Mkz%sxG;p!WnxEqoe9z;C3*Rzf?oJZjQznW z>*mca9B5z7{#9N`@nm0DL!}Iw6gHnmqa-PCHY2{tSGIKwud$(n}?kZG1w{;fP&#DY5m?7E0OMGPl&vfL{ z+jRKi`W}Ct>Dtg3?Rf?{cJpp-ozN5hjln>;YzwY>d@nB_aDDUdZD8ALK+OW%@`NzF zAE{Z=#E}3(sjoFbNSNKdw`|}L($;}#Hc+_x-qDib0lx-;u#zhfIqda=8Gmzz%7zdW z-1^%|RRnP=E7{Sv07~Gy?!&Z#Jx>H!=?FLBZ1lt18QXhtf_Vh09L0$dF6r-DXLRtH zfB>zW$F=RwJL13Z+}P$9l#3A2t-qhxIIVr&Yc^4r^_<<~%!`+yT9hYrb6?7`2xTzI zCI|iwd0oz%ung?ug%>G*ceyU*>w0J$6G)Bv!!d$5{!DG1zuBvC>(mpS8tk9I3UmDr* zHxB!mt<3$XxNf32Ysp2uUUx^yGK%dj0HN}@Xx(e@*^l<(BZvWO+3tvmE|H8Dte^+z z!}xg(v+mL(f4C%KjgRW^e+%T`^gG2lT4-WISE!Z#VEo(s;&C&%LDG7awh38yZ36o7 zMs0ExAH@Bx0!Q)lpp=YGHZ3o|_})m}FQJ@(WcB^~6=^$A4V}QfX#DH5&fsM3!x>;^ zENsa~1=f#lAF`A@W>poMDg&_Cy{e}T}^bpzX%<%8_DFDcsIQc-y{aghJg zDrCMUocu?uXmI_36E{Ul#+Rmk>QD}EYr5D_b(C!2p^v50)=TU51=4u7rX05><#GKf zmi&3!y2aZHTvaIX*fN79nadWL>^3W{wXt|* z*(zHCg=47JPS#E9j7L1(@RWSH2mnnv_CBCaj-Z}TowTc(7=u4-36_(C>7jm(c1I9>>5w^Qn>xZlF4|fce+tN> z)&T@ACFgCP3Ibg1C;lwe$efFLj%OA#<0lN#g8Mra-{(x@UJo74ITbk@{CizJy%o~LHsm*{nD7KAdM{8s8f&DCtQs)QB9A?&?4&!J$ zx${(P>EwsxV{uxH=2fXycygc=wRFMm@~ z6m&pWT}|9q#hw-C;wN|_-p^&K++~Ssb1ipq&OhCqpWXxyP?SaX1Y&)-zkrQ z{88m)Ao5#ic+Z!4U){6(mim4U+HD|wMl2sTPa&JF7EcGjOnJ-Z=tv3|W#$Dj2I_># zL;z0u+BRFNasgl-0{EHV>Q8DKqgqZ@B`c|kC!QPL+SW>@BfF_?qZ_ZW=&*CrZxoAja-&b4?6+ z=SZMdbLplKvjU#si6ec#b}vT_>yck}sNT16G-Az3S{=aWfT4w^w)Ul| z&|~?y4?rVc;3`1nb=iSU7Ou#1+SW;TCFovPHRG>0WQ3|+@eApcd?SId`~0NOTA<{( z+1>8vKKXsb2|N@e{?LTMQ^8>ED}v9x{6@mA?p#v3Kn3d)dR>{KMfU2Z8I%o6CyLf97BNo#DFh-7$%RZspCLiO-owNy!-O@ho{=Ja7MUm?Wzn{W$zCmV z(LfF(FUFROFA~Z-cwMQbL9zIJX*pHW)S!dPF_|m1xqNJeion+enD2AtUOd*~l|O^x zfV(t{td*KIcj4%pix)BEr$B*^Z5tg3Xs%2o0yBG zy6z0cp_^Wia&{@kD0Yjtx=%Knx#CHlwYq@RhvNgd=oTF zq!ih*umPgP9!ZmlS3pmu3`{0uZfH!+6ya4MA4crccQp|OJs%hCs{g|ODV9C*9(iEs zex$#Y6@WtiV9_4^9#Cs(0TGAW5VPLBy8nokX8vsy4G(Y;G;dv3AujY>x>Gtxy@j8E zaL+n6Qw|6?boM}Ni`U5ewRS6=jSa&eH@AHrkPoR)To=r@S2ex(QtLC~oK*cfSR%D* zn)a9+X$%jfXptEG?1aNjJ@f{Xo3zyd|9q=n5vo87$dX0ca1uMk&q1ch%stIK#hae{7c+!n5GtE5>AZ4Q zA)rVe&0_{mL;ftRBu$GhHo*k&{3@m2S~bElTZ0)uLCik%do09c#QJCH9P@)g#4G}O zGYS)y~QJT$ODUY18nuxJ`Su6rK!*2;^tjj>$875#-Ptk;V1`HZt{Fg`tZu=7B_nlcJY+ z$p`O5ac2qBD9!I}jfx;9Wn4IZK+tY}lX0p57%({40vYnD$%Ofbid(^@IBAZ4@*9bV zyEzeZ4$I@aC4Z1J=1psJ)19c?$Ys%MU#qy<_cjxCwV}h<*ea6bTzEc*Or$jn**@fN zWOGGG9GS8BmmpZ(+A0-B&sFmHxx6$rw9WZz-*9gky=TG87kCq{w6-4`S)Q6a2Yja2 z?c!oi`LhY$%&jNi2p+B^CtpV8Ix^1YPgJ=a4&+j8HAN34lMSY*yy?O;J2SZ$)hqUV z(`xJ9_9CW1A%<>)Q|a`z#mNbz<{s$JaUx%Oz*Om3ne9@J|D2J3RzI$1Qq;`7*^fs9 zOF2?~!_uD5*al{b$d;{oeEqj_{CgY4eO+ezK2cLDN4IB0CTC=*zrsIFsaB)#geY_m z5PPO;iS0Ns4wy%tZ=LNg^WU?ykTUr*uGjT3cUuqpbCUOeX%jEjrA93fO4ctU;m#HqT!UD{*h6l_kmX9{d;Qaq@W$L)k`>XUZB z&FYf&lsVUG%_gR`K*q*9p-_}&N zc5qNXJUndI_$I4wxpi9oGY0&7aLrPwRYjazscQV|MGa$7spIU`l>2eLfVf>`F*?^M zwf;4~aY@LR>p%znLpR&uxQOZ z4WO5%v)C$%^1Xn@9qmTV#$;9#RnRe1>1j~sih$P}lKOiOqcRLlC;B?PFRzove77~Q z>FDUVVHxyTfs(N(DS12)@BxqA985NqViYN`m(QGZT2IgY;9-zk=O~sU=Fu*d=@u#d zUSJY@d*lnGh5HX``G)ebKj$3Fhr(*j$Ch*^tD+}k(B;&J<%l{x_FVjFS)D0LoA2tWJx*>!X~ zyK-$)!yhl<^kZw5jMZMff-%1A3(xV>mp`Y6XEJ};W%k2Cu8(=P9;^Fe#8N4(H?SN$ z5TkT9t7KmXrba411Y#Ii9@_%7~nvvTUAf}kFu6Zmm5#6~zxNv+y zAZoZL)14J;drA;|$)d6#>uaEB>znE4yVx*HO5O1m##Z;B_ldm&!{oZ2bDLj`n-vWm zeZ8Mq1{Au!iZZ3!`M7)4<6BmtZ&>I5NO^#bKT$T#etdWLH9x2)%lL-&OX)niKDsFI zB}-S1>1>wRx_AMr$92H~_pV>-pXPysO3Q%W+OCDVxk>@1r1{fv!@=jrjPA|pt%{rx zRri>9wPu_uESLHURxHoLn)(T=9Ht52JOr+Gv)gAP(c3PwkxvAw3qW7v{Q1Lzl+?}R zY=TY4ZXo%_I3`cO5@Xr93#b%rXwjFv!Df!{oilCpc%LUK% zOZti&9_p>`hI&%HpW;{fbUA*g0nse5{4bXG%S$QQ;InK~9Jtff1=NMD2iaR+DX&S& zBDQAw^SDR*?84qOS{T8+VK+E;LgjdF5-6f&bzb@GK{3lT4`>Be2b~b(X5e^ib+Q80 zL~W`%X?-wRcfU57V(NYm?pqA?S+4U)ci%n@h=06E?@g>9eQ2C{Dz2Jr%JawWA^ypb zUwBhLPT7p_c6Kv}qtQW3Xu|@_h37+?nFhv@^4$P-a;@xujm%zu%sBnGtD{211Q6nGClAfggpEB|2mL{S`T0pyb~dAZ(Nw(cf3n z2&ch}yG8~EFP + + + + + + +MakeBlock Drive Updated: src/MeGasSensor.h File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeGasSensor.h File Reference
+
+
+ +

Header for MeGasSensor.cpp module. +More...

+
#include <stdint.h>
+#include <stdbool.h>
+#include <Arduino.h>
+#include "MeConfig.h"
+#include "MePort.h"
+
+Include dependency graph for MeGasSensor.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

class  MeGasSensor
 Driver for Me gas snesor device. More...
 
+ + + + + +

+Macros

+#define Gas_Exceeded   (0x00)
 
+#define Gas_not_Exceeded   (0x01)
 
+

Detailed Description

+

Header for MeGasSensor.cpp module.

+
Author
MakeBlock
+
Version
V1.0.0
+
Date
2015/09/09
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for gas snesor device.
+
Method List:
+
    +
  1. void MeGasSensor::setpin(uint8_t digital_pin,uint8_t analog_pin)
  2. +
  3. uint8_t MeGasSensor::readDigital(void)
  4. +
  5. int16_t MeGasSensor::readAnalog(void)
  6. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan         2015/09/09     1.0.0            Rebuild the old lib.
+
+
+
+ + + + diff --git a/doc/html/_me_gas_sensor_8h.js b/doc/html/_me_gas_sensor_8h.js new file mode 100644 index 00000000..4c912da1 --- /dev/null +++ b/doc/html/_me_gas_sensor_8h.js @@ -0,0 +1,4 @@ +var _me_gas_sensor_8h = +[ + [ "MeGasSensor", "class_me_gas_sensor.html", "class_me_gas_sensor" ] +]; \ No newline at end of file diff --git a/doc/html/_me_gas_sensor_8h__dep__incl.map b/doc/html/_me_gas_sensor_8h__dep__incl.map new file mode 100644 index 00000000..071e6300 --- /dev/null +++ b/doc/html/_me_gas_sensor_8h__dep__incl.map @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_gas_sensor_8h__dep__incl.md5 b/doc/html/_me_gas_sensor_8h__dep__incl.md5 new file mode 100644 index 00000000..a75568d4 --- /dev/null +++ b/doc/html/_me_gas_sensor_8h__dep__incl.md5 @@ -0,0 +1 @@ +db6435b06b8a0255fc0e079b34ade37a \ No newline at end of file diff --git a/doc/html/_me_gas_sensor_8h__dep__incl.png b/doc/html/_me_gas_sensor_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..c933239e954658c8feff4eff24a422f77d8f6c80 GIT binary patch literal 13470 zcma*O1yqz#_cuxjBBiK=lt@W;m(n31NVg2#A>Go_4KgqwC7m;Li7+5Bbe9a>-Ekj$ z-~V^NZ{4--y@$2tnZ-PFW}kg_{PyqcC*q^BEZ&n>Pf$=$@Z{yB)KE|`{DAk4k1>H) z%Y!;E;DTwQC@Y0>|L~XHQkaN>@)|{6>b<%Lcz50#tnZq4ZXPqL$; z)UyLLA*NRw%5v|9Wh?}Qa)dX-x%<=mw!!I>E@01JPJ`*B>!ehfhpN4JG2B1%C|*8K zuzwdsjKR}EMv?GNh&UnJSqUwnb<7Y!)x=~_r0%Zes&!i4cYf=&`ciIp!CPaz!hN@8 z>s${<>i>J>yVB z{Tyoee}|ma+d~@QTMt7mKj{Ma=D$&-rf~B=_oy?{`TdX7#Yu$X|GE3k8x4isIcY%5 zXJSr=f~(R}z2rfE(1JFuFcUXW>lmJ0hHTYAj`h zC9POynT7#1sa^ilP<%q4MR%V^Po1GkIqiVl_1hIee14k3kE=&B-@?P?Jk^$EfhBZH zGp0C1(}fO`Fsdf*CzP1LweTy-fHfsCxSkR|dlsKSrf5-mf`~~Pdiy0^>x?B`pA)~X z&Bp>QTC?@~(1>rcmGPC&cnu@84XO1sq?4StfrouB;>4;jRn;rJXCCad7a|b;YP8|j^kXF!micg*7GaKI$=;F=YzJn{%PB~ zKbRJAGLFhOwbJqV&4CzyxpQF_ZLQrII*DHYMU@~yg}sTeIi=Bxn(Lh1CHfEO&v`T?>j!Qha zPy8#FZ5idVC!%_~9{<(m?ejDwwF}2uy%Vg1%xMi}{j_7u=iH2A zshgSTC?pV5%ztwHjO(4Zw|DPyDwFfc^de}-c^%oVL!vyU0gHb|geO!l=-o}N07zF{ z@EdRrxkoyUU4;`ApwLJCjur)-U&2V&`rFg6o2v*2i)OdQmW)xZ=ci+k+=HEMk~=nqNKg45sXlmImQ|3~HCm;sJ3VNGO{=X?u6iD=2a+4*Qk;?+eBEyY<74193PPz8!lVHQ@8!5pZzw-dUiJs>KGkqh@2N zfflC$v0SmeT1QOVm!OQ_|v49C6SHPhDZ>e+%v4zMX7MM=or_qllJea%E8@55026 z%4wkz56;Ns_uIAL&+l4R)6Dpi?t}&}w$Qw(Z|@cBJV0?PJ16@ex6aM+2g$kD8mQQ{ z7b0CaxEa4^@v0jk2H6elDptsX0HezP^bo!BfLTlTJ$B?QpJ%5HDtm!0oWSKVCdZuUZQI!AX6qqXLGK=; zz#1Cp#=7&Pa;`+M+tk7;!zAFvSNZhof%ba~_U9S@1v zp`x0<u($1+wN zxKn*z7MG2-1v=3T2FKSazf28nLG^KTt#OS#tEYJgX1|E*yCm)50yx@ru<02E*XCL? zgVv7Bu6F9Bdu4FPy^d?hY3i~z#AC=vi@$vybCN?Kl9>u?f^YW3hriV|7qXDCsX z8$86?_C4W!ds)tLs({NUyH>YyD_A5>xQlk@01+A+nzE9e(28x&0ZG%uys>QL%f#^T z9*>U?8xs7?Vq5B7{O!cFP>6NQB7)vDOPbf0P35*BJl^3h7p=LQUd3^?@zDhLgm#MS zrRS}Kt{;&WZ*}Kpca5s7mHBX7|nh#mbuon%|=lPK7F_0 z*t4`hXt%VeWoU;kEuP&3bv?9bZ_B$gn?mc8lJ7^9*}>WvPd@hTpDWH^IzQg8?3mV* zBt>ycKla!NCZXa$65C|hIpx49%AT3y44538oApdfte!Qozj=f9;F5B9J$D6dBNp4Z z`MxD82kQ;5u~W(VUD6y5@R$0>=n+D;+#7CFlo&TfVa>aF6w(wO62{&nM}_We)l@H- zyB}hxuj>s_Xx1U9J3x5vfMNT)ooiK$FPghe6QoPvextiffJECmbT|b%;ASTulOd^B zD84rAo#NQZ`kQr0XURWH57DSb8(=@ZvX2+#VDjN}+BsT4oO^|VDM9R+ww*yM#yY;s zV87rsgZ1H^BKR7Q?f5OHr;zHhQ&%VbA7y z+$T?uBQ+FvF8h6JU9Z|u{GW_j+#I8HGYc@slK+kD@?f3ezxZ7lW4n-)pFY??t?l24gaIpc1jChiu|d>XkOn_IqibYX{pDB{cAnp+vjU@^6D$@D30!TA!2vu+S_Th z4hIpvUSa{GXg*H`Uamij!V4Uw`Xvrxpz|ZI=Z`nGVlJ}H&f24yAk$Wrx zg+)YGjV&$eiAl#9)Rz4>6U}cD;r%Gx+&?9_(5k7NM`Sd1R&0!qj&}l>6b^2np=OL zC%pfhAiJ+`8seJC9G`M(C~oy?9iLNg!v_=R^Epx^(FQj3PPA#iamFy_(CQ(P|BJaM z<6adi)iUOo9DTPQYCuB&@I&0f%+_xz>Xx#a7z7c%#>>J+J3BwCav0>xDqFD^*(JD0 z3PfeYMq3M!ilD@)XBq$Dg)$W~Z1*{7LmvO2rm4JUG3v~tEc1>i$OxtWc=z>E#RSiE zC2LdIKYUXcLuby?t%Jd{Eb?tQKH#+E`|k9~F>a#B{$_Bdv^)d&9tN9k<(NSdm`&6B z7h>HwENzXcm4mxN@qP_i>D3MGF}dN==uE8c?)gOISS$ofMgH&#P*L%ZI_)CgE?U)g zM~^n`@5YXDFSDz@HO+KRw{2q|k8T3xp;Hx)|{6v1txpdejW{Mn#%Q!ErZKz&F z0aNgpV=a$TjGB}OmGW94@wR*jlr&R~b&K~|+~slFa{(7H(g4NcIUQ`Yx1N~X3)gFI zI%pVF^n2)U=gy=pH2|Bx{qsS!I{TARtStdyPZOogelu+gCzHrki)hQuaqRgoQ5KU1 zHen{-Z=_Q^JGW4e9oNu_pSKXPBfogJ!%!MK<90vO=mA?4^O8ICtW1ph5=|U8@n*ns z`vNdNZcO^h@KV!v#><_!8*s%hwXl%F4$!U78Ct0dxBS|HSAy+e^yMHR5Zy(?KB~k@1=CHsg;XSs6jhCBlLz7t|MEcl9q?b^g()eSx%%wC*=`s|h3z zQ55A3DkN%krOdIrQZ**7q?lS8gxv)|wEoysm-bmSxri#`bZfMKj>4Loo|ap%P99wz$~ot!5Zy8is}<|_LKdXN*UgFBDOHN{ox@mk?OoBr@;W%(%XR98 zC>dQ@0GGrD7d{cy)U+!kKrLL+-P6J!QDhEN#LO37qBEY|GT)BjT|!&kl3L>shmy0^ zB>s(iRA>Ppn&f65O)0524;gi=5-`lqOJ)V55QP=+T(r4R(5cv!BYxc0SJx3diLbZ$ zmcj-x&QK++1^a`mF?xo1o~+}yDw;ERV@Jvms$V8xI+A@fLlnNxU&sYNXu*{xh~1+? zw7nqw41~7r*vfBN>`uHBpxZ>#Wt^c{@AL}&DUqKpunj6C0#Lqd^3MiwhGO~U)lmEA+Sv`vYvl8h5T<7-cLo4CPbYuYBBfC6Kv9^C)6i zUrfHx8p^I0Gnb0*k;vu(@Pou7%K>%2BmF7KbFOb9-oMi7ihJFDlhWj+42SG=#1MN@ zq8K`@Yj9_kP%YgW8QQXUks>Ww=9i-*#LDIA0?Qe6(HiH$F@YHFi>_s&FI~bVty?A; zR1tc`qNGWT-USS*&fb)&>kUOk1EHnN4+vXfJNxY$wSj-jGiI*ym=6>y2pcR7PO7b^zQvYfHT6sPD+6=l7!`S>%pQ zVQh4{p9yg@m~$$Cx?b@IkfCxIp2VF`2%`4}P@!GFdQ}fga47yHoq3M}!XAXHaj(KM zMxXtfoMf%dbb<>csMsBj#!w(fN`nvR-ibPrtVi^lexw_`AX6w`Z6mD-HRr5PI$EJK zRn56#82fH0W$N?bXliRR^*w{7qmD;OKC#w29D$Onh8!Lu`Kd0ZFeSJLGe$WJT6`>a4kjbEIK#h}^h%pT{#rAj4dh70QO;ER^m)t3sgQq3Ly2S0Q89s)_BEe1t zf?5?imIPhon@)BaH)R+i_~aZ&QJe3!1no!HH(xnA2m%VPqt+CP2zbGzRTrv1zW$ya z*vyXcp3n!WbW?y@L*K6WJsRF=rx9o?pD_LSed|dCK+inHMiV|$6Rbf#5KOo*k8ihA zFs}6-z8ci+OO;5o#B2eT=pWbvcuMPJYwXt{n&zL9x46xWwDq3jO!-yKc3&#&Pf5aG zZeJap9?LqvQ?nK2uRCf>70uk5Q|o$pPy9=KVcHa7dUri?eUl*dm9-uDTr%bNuve>k zb;3JVsYfey=wx%#_4YZp0&7okQgjGd0Bj+sin^aG(Dvs8W{XcS1qHtj*IvEi=io+( z^k_77Ejg*Yo(JP%ta{dHV(@{d4}*(P7$1QacEW0TSKVeu0QSUBMIBYkz=hd{?zK-D z;z0#M6E*bDgBzKMj-ca{)8%QBEJbD+zWHSSkuJwTsE)2jGN!DaU*~`BIS-_w9b76< zC~M*YCo_vq-Q$n|Xu1iza7CklWiYvo^H@cr@rdQen?KP-O4ott?S^43nBIY+dpp?Rmi4wgfbL!jwDqxz3 zi!3d3YlTPnltHvh1Op$2^gaBiZxDo&BT!nZH;exD=7F)XtsMQOTUjd~fKj6DOWl#&+uwK2fbE8w z8TdsDFFtC8!6M9(#g6kolFDaigr^Mt3!)z?EL@-i!2mXhC`xR2Ya_qC+P;~GGipH_ zR17uOX`QLN3T`D%Pkt;&kY?kUCA|I_jMe}7ATmQMaNd09ENh`-)I_5zjBIj2~3@lf@`^TYzqnmE{IA+6_+ zloVdv{99B={D&jz2ke1S+-Be z$b|yffeKbURyeDkW&h-o8o<3@580L;89$eiU3UGV31ZEw?SFHYM|Tu~s@y?SU)T_vR1Gyk3b+Qss)L-Uh=&-#)C6RS!N|av{WqyY z!zVR4sXy@m=;yMRvGn%i96q87Fa!rRq<|iws#G*~n5joGJs*3ILK%=7B(6o(NP zorz8V)dK`R^91kg7U0e9|0SecO{)AuEdyMp*f%Rx=;5>;arHnti_s`ry zdnSasi+i$j-G8t+JyeN`>Vaw;>TBXmS@L1gPysawQj9qvzT52d)`LoUiqc<+<3{

5LKMtA~(dx4&Yju z*Pb$KUZacArJLe#Frx13jN2l*DLx6>Y@hg}-91?+01P6g9$CbrSa&g&ow_}s9aZz# z^0()UT$=P1N;)p(l*?5#8rmSjLCstISS2^L9`G^eAl4ujeIcLsOOGc=MwcvSP-@uD ztF(5uaa+P7JV45^>}Nuz26A5#pLEuW?T1i6$FTF~Ue53t5YKi!s9A{|`6`O8JuKkU z2!HtPtrv}pprivrYO?cZLAi|Z(_$+hw3M*$uKE1luI?R*ucJ{?zE z4|f_w_XmI222`9EI^Aou9Adlg>gRg?Mwrm(LK>E&V z4bYrDaY_Qo%SqIrD&(5AOsahEcgJH>BmvZDD!d$1WKyrEN9>+C(p1V~)WtaUw1|93s( zHpJ5iWK7XWZRz>%m0q8h7q7d2L6y!r>p{gt4+i`r)<#V}dpnRZZ_5LZw*I=@X16F! zvXrFk{EBwVv+rqd_C_QgU64ZYzd|B?b5rLpbw9z4hqEQous7;vx-RKtN?_IPD$UNv zc&qp$AU?{GHrXZeH|rt+n zsD4{@)DsG<9r%u&HLPfspBUc@UlIh7%~|Qz4f&C~e@HGiYheHm-)!&)0&9$cNTV~y zsgdzO!k3`>$CadcKQ=O|8*&2>ZvN#Mk@)TuC)bR%=g3Kloz-6)u7|H)Jp?UJYu};uDHKJu-mH>vp>ez4(?i6S^1S8Uf&T}9 z*P5f&XnaUro?MG)3on0R?b*WMz=r5Tfep!%*Oz}6DailKx1c1~=$R=ZTxlHIgl35n zvvi}|n|%lc#4FoIHun>v7tzks;S#0qbqQ{CyG5qtod+wcP<$!b%a*eOfCU%+jF9gu z271>Yw6Wa80yI#a&G67P6qFaT54`~5l>{EIJZ3)Ekv4VGHr>AP;;|__dNIT2izZUQ z*Kw%3uz5Uh_dI&verc}1Gcjgmi={XOeOEQbjC`?LSPbl7R3J|LqG2PB4VL?`JIKYM}yG6yzZjafOiPIJJi8FFD3bW9Q%mkV>5w%Nw&-;&>2Rq>?o~ zo+?uIdUFYont3P<3BpA>elad?VFzPKeo zset3=IAPvj_j1{*RX&B4NCHq|8`DF7SE(;CMMpgb#&!<^3(sF}yW;FZkTHcb0CfMf z?RA;eX-eQx(fU4iGLHMHq>#Btw~BgU0Z*tLW`5h4AS3AuzG{t{T4Z9YCPC(h~#yYol0Gn`wOEYtz7*Da{nfihH?1>_2X?B59->`Qr6iW{>G|>Xhf+^^(-Kc=3I3z0vC-EZ7V^3!F$s6ETbNj z@I2ui|1;Mk5knVSFVPI%p!(W}L$)nbwm*%0_2dE+B(HV7zKD>1Ie9xPWM4gLg4ft> z2K&LEwm;ZRZU6^#VoIEbzjbl?{n6R1HY7j}8<14PCfosi?Wr#r2P0I6eegZEmjuWg zWj<##Hzjd=8z{EC9KK$f!}SU*U`qQmOy#~e63TX?%!&^Vbo7Gg>A+S4ssP?agCH3e z;hgUz^h~{<`p;9{{c{`Em8P{)-I}30mOT&afd?{JteqfW;ZA7be*Dpy#2jaD_G+e> zcyO11BFBQX`eXP1!20sWUsuSOD$P6#bgGI?EG@JO8d)wm?!Z1chtZYchuVIECA#b| zOBu(yEk^}j)n!?x)TVi7@pVjU;(8}Bj&qN?(w~a&K-PV^?W5XbtjxCze?{_Vn8$6x zVVhb{p`(wWN)@jjFv>L{OS?AO+~a>#`d?HE-A1)Lfc>-%QW7{XwOb<^D2Rl!8i9~7d-8@{c*k8ah0iK^rAw~Skwv5o9M6#gC}&xhFvXpxEM0vh zN1@EJ|674D!ZqUobvQasKo!S0UQkTI%HYEH!3Xycct!DY`gx5otwMOfMp?2n({pm;PQEH#g^x$?|y z=l@e$xLk-04FgPW((g#4nDqA!=nHXP9+g?f?XWux@!^C%u2uV80xnV9hNtUapR)1Q z_e4d`2{J%6DoC5i-Rf&P!Mg&&&*j~$FCo9*M^KS!rGH|KWpMq$bhG)2InE$NeEi8j z5U|$l7B$2t8d1YuW7o*AG4W+~tL94$LV<+e)Fyq==uSMZ31_WMgui671UE5h#V)j&Jg+jyYn=!+0ika$o;BjJ-DoV3YwbpDWPt+-IHq<&iC@=m+VgG9+9TH4m36Q7*nmY( zcATVkW|fE2;Lf;xba6RwhZ56k{q*XTZa!4`*c2^mm}xpdRppoGj+)`WW+u&B-A?|z zN>nimF_l@{!VJ13N#&SQy~tZ0xjNGOCJm@B`DBFU0hOTEwx=Nv=rJSL*KAX@vF4eI z^)rBt4^0?`)rV{>pLxuhxRw^N6{SD^Z#B_KvId^?m(;lnQ1T?8-|Uoc@9FJv%Bc)N#hgp71lQ=Ga>7tC<&C1r>9kS7j!AbIL2T0IqyU`r)>==j* ztG8XR+}RDaYR>OldmpTSDR>0W{L~5n*R+YYsPuG8qF033T>m>MRE#*=s(gT3UJVOT zT>_Ck8{ugmoMQ>GR@rMB9{s0y$aG;=d?-V3(=$LXyDIy-f6=OJoNHAB(H5R+9x~_? zy7di%RI!HT!}uch2KJSQnxZ|1yUq4;+fws%lp@6f8aUnSgfz?u^MKji z?^*E85g2k|Ie}_;f8hl$Y$=c zoYcLdA!YS@gpR>K*G31j&$I05Os^$s_dC$ML=*GcK_1F~4=8&TF!NIpvhrvk;XxRN zt=_-tg5{CT11L8%_gecCIaXc8&pmZ0uwGr|Lb)n$5HwkkNGQ&%Sz6D9+u0UHLqeMI z`mvZhoWflsVY})9JGyeMH#t>>>92H)klD(niM?+&sqD)%uop3_q;bqTDl_uxI=f%? zkC}ZQ|Lw)XLB)Q4`Jo`!Oo8542vKg?*|(R>cfi!laLWAO14jOboBC&m%r|xOSV0zk zUIFV6rbx8h60Hh*#xB3v*;&20+XA(nrjd(HZk1#A+O|SN_A@1 z-c_A9*-lrx4D8&qp7|;6HJ@kgx-7W2ik?hUjoyFXQZnVNIW5sF+j`s83P087`fQSk z@L1OYA5XZjl9MdKji!Xy;K`h1TVU5?ddQq{vuC*JP@lm3X3S6QsT7;^+oRP!MJ`yr zz}MFvD>1@*7y5uvfZ7{+e*GLxlife=!gY)F9yc!R#0N7x_8?r3$eBTC?W}7=_nmsG zr?#k)gpLmE(4-o;O-6|twXZ99AYIB0AqKVQ#*pKduyM2TVw zlT$v4(#Sa;dnex1+V~rPZRQ-1U_E16c5NU-76by7E9G^&y1R$9klinHm$V)wC+AQ3 zlZ0w1XYlRP)L0yLBsNf~>4dzE!{ zb!2bH2Mz@wiuj!+1k(4w#5LXPX&cH0S>V86M6*;|^(Z^f1GomV z--Na8?XG5x@st~KyDjfCQwR!+ZxJ|ob$Whr4x@4(<*^`_~38pzmX&z z5M&-#It(@)0=Ci0x21XfZ#7WTq30#M@7Os%2qe&Nf2pOfI=5uj4>ae-AR{0-KAu%A z7$ON*E_3jvn=$O}uC?K6&L4E3zRb7OFWBz%9S)XuubPWrOZrmcrC-GVL1Iz*2jEob zL>#Yt96bd({(w>KyJ_wH=t6ai;OV%XjFG2Hv9+UkScoB}6i*o=jcAgda#6GYsF z!U!bd=M;-mB=U-zkij5qoGsJ)TcKqHB)&i%k5|K)w!!Z*v~MKZZDv*Old#KertjQe zN@i09Z7A55$@fFl$#Jf4sXClu&z1G0e*A|T+_>BU@{M=mXx@FzM!obHY2s~+q{44c-?bK{zOzcXWyX;E~%R0W!5&;d3!H68zYOGtFy;D z7x2f&KIAvgNGp?IlMW;3jUJ~-%yxaJUB-TwJv2)EXB4Nvgzt(=mSUfUf( z;GCQz>}J&0DJ*+mEd<@twv|^p!DiRh)GoE&N}DBZM17sm3_v(x2D}6 z*PWP2i(~Dx5+|o4P%;nOla}&7r-E9=$Dim%(gbyKK=hDZ*TFw!`hcpsxnPREQ3@Yp z_I<@Bd-9vhBap47ZzCX8^djHPeiC!s?$h|_iEVa$Up(l?y7)?lk}Xvnhp!&|Oa0(0V=xy3zq5hBi%1DUTtMpJ9^ zKiMHwj(kTx~f*~3@Sv%hK(|EI<{51Wj)QyHTDmu0_Y|L>yj-H;ar z;Kgeb_$NkC>D#VMxHI7ZIGS5+xgd_85pui6Jy86#bGKwd%<_-thbX#&;hhroec!U^ zB8lW{67sDZ?zy{eE_|Hm3X<7q4QfQ)cR#8>zB@$K5Pf8G8nOQPNo#E0_ipLd>!Rev zOSR#&-g{2QR%a^z+y?x_o1|-RBZXC;EYkCQ!~E}8yc4%EeAr2sE)6CmTUFNLMe4uO zdQSZ;5Hr2&Efjm}-ClDNCV!xazid&(o;UB!qB`{VhaG35%*fYjlv)wqEJ*QB<>}6s zt%e~YnpRAocZgh!y1ZJ){R~SA0QDjoB*f5V)pn7Oc+6$IY(+M}8Vg8v$aZDbj{jS) zec3v@DwCe|R}Ca^Qv0S4NM1^X>M@%-+7r@yD92rPGu*f}*23Xalv5gluS;nEWn*krv*9?GeNHpnzDPV0 z2tm366&j=UB)j|0)R4f-JKLN?4Z`U3k?3?EyMSww31hP&>QLQa}DTq3LwPc!@*|G%CZvF=$O1b`h0LLd+AA*nfqy3pIfT0!CVV@Yb3yQ0?kKQb>6bCl-II?sNG-#>POUX73@O}62+@5FHIl&plJ49s zL%XaZWy}kMtrq6S?(S}j7z*J6PHLJ>w(*#t*BAOEp%nQuZE{8R-dL5Qdjh6kUXhVO z7{~oi8+4Nu&IEtDM6Behud|@IPYRYqJ$j#wVD43~M$r6sHUDoH!Qp#?1-BSA)QVX~ R;DI9)d1+;-atY(F{})49x2pgE literal 0 HcmV?d00001 diff --git a/doc/html/_me_gas_sensor_8h__incl.map b/doc/html/_me_gas_sensor_8h__incl.map new file mode 100644 index 00000000..ec84b22a --- /dev/null +++ b/doc/html/_me_gas_sensor_8h__incl.map @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_gas_sensor_8h__incl.md5 b/doc/html/_me_gas_sensor_8h__incl.md5 new file mode 100644 index 00000000..905cc795 --- /dev/null +++ b/doc/html/_me_gas_sensor_8h__incl.md5 @@ -0,0 +1 @@ +ed4757a04fb8b867249cda89a9859a79 \ No newline at end of file diff --git a/doc/html/_me_gas_sensor_8h__incl.png b/doc/html/_me_gas_sensor_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..0a32fc79ef6ba152d7371508ceb4cea9c0695846 GIT binary patch literal 46631 zcma%iWmr^g*e%^5(kG{r$RIT!jdV+Q*V!Y!*Y}-Y z=ZrtNgw5Xjd7eAgz1AY+jfxyL1{nq%92~ZSyv$oTI3y1^IQTbcD8P5P5I(g6Ur;_M z%E`bz!2V^o6~w{8J%dw_dGYRZ`tH2j=Y;jT`=bMQR}>1gk9Dk}h|WkBmJ^fb@pRGf zBa>vcWp97tsGVvBeLR|)B=gYGEpz^pO%nUOYLaX>+o)P-lesSNFyV+cA=b`Urt2qTd zy-t~&7|sX|#oTcKrSb8E5{Hbt z&oVNmf8I{h0l&}t!-g$<>rbzkdws*lKU-w89*dKm>K4GWT`Dp?Ia@|g}9lW72h8>5#q&sQ~r0=IJstx`&(((UFP(yUFTw@sVQp7 z2H@>#t;mudZxa{t-nL?1E%?_2o1Sh~;8r1IuWV`tUuu40=8T_1Nk--xG2`zUk$z}) z?0XV|lxk3`7YlNkHuKC9!SYdm_Mx%E0K6S_Y;V?GEhUEfTN_!;n(cHZ^=YE!D^ zV!UWqkLnEXz|XxPamY6hK} zyh|OPLZAaYX&maRL#u>M ze5=4De2~T(^&OK6vQjrLq)(G>KUXnBceC1#j)2|1c+Bvag>}0lB#RGoaBJ|3vm$F7 z)PysrDhu(YhrcEVKZOqs4JjG$4;k$DznA9NwW=@;h{AcR?daG6Xa@>;g zS(hnD=}OIpn;%_c{nT1~IB}CyD-$z!)vE{Pp4J!m|I zgC;Jmi?&vZ86J2?Wo+x#b|<(N=(42uzd25bVxa80B-^bsE?|26=7EJ!d{+M=|R zB&cd5yi+*&bc#{e*MfUeE4dwqhy>eS@K`ejDF_gZxQ6EqX2ov)R2zHpWh?SohTon%3QV67TQI&2^VTiUeKf`2~Gdkk>*yjrN# z9z+?ew*Ri>Bm%039y)d9M$&-L5b6FkjL$Jv##nVYf&O+H%7ZJDUiuYakvQcoBa8{=AX{U8%E~o=hyWB03;`;#vg*!(z zaA2~6S2UrfRpVJm%`L5JU8pgb837En%sYS zJVmK5LV!mq|Jab^3u<=;KoVPl?NdU6pT<_U>ht+3?6EQJ1nBIzTdKiCrp>PcB)lwK zx_X<{cOmbLC=Ttz7n^J18NKJ{Lq4{BgFREp(KnxD)*Zo;of{I)v%mY}{Z!{TzPt>I z=wrZCOEaKn89Cr{Lo$#v_6Ekj184DS%`vEZYs2$f^@#Tbxijl-2xQRA+cJ8Ek0gsn z7=2pFz4WG{=EIyWPoLl`eG|EQLWH_|5Xmf>pUx+(+#Ms@(X7Y%9%CEIbo(US+A$RS zJ&E4v#FKm=@Y4G?lE5rDS!JA+gl+H2yE47AodOOh>m5=_vpPlU&I;n}#`*KLK3T*F zywWjZiZ46eO%x)Xc!B0buw@0J416w@|M~S)r%ayIo4;+ImYTa}!8J_4k-;IP8-$Xi zNjQBsuV;bI4SD(f9nlP3O2xSp!TBi{-;P&9cF36T2mik3e<~5Q<`&D{onOto9zMsW zsL$9kI*16yP1nG&M#xTm9XV$ligDeGDOgWB6ILS{S>PKR;! zuN42>5^0IECmGI*b}ocALzMo=pw%LOHs5(-*&(N;YhY(wI}!Ht`S-sGX&Ri?G>97^ zvS_t45Qow9`9+L?lWSXb9(By8MED3Q?k4x@w%E>34T{FYV7`*ci)!CtQYBPLP;2OLp>0YY#8J34&JvmOf0*k)2}rz7it~8cWdX7yFcKs5|g;TQ>{->o0^(!*V=It z>k;O6f{=wflFX7JP%2$pH!v<~8xdBb&9ewqI*Rph&x^McCyIYl0 zY2mZLoK%JyPs70&3lf>v1DJJEz+B*@~ zM8C~Ohv5+znR3>yTN=Wrkac-QU)h;%*mzV^jBo?`v3{nw$#mDv;qVU41YM**JXay; zxm#IOD_SXhCQ>HtTG6;lslIThpqxfcuv66I8ebHaaYczOGD^%d(RsQ34rB7o=Z}T?Z6x3c$W~qWN!cg5 z42e{#rf50zOoRU&61WGyJ&0U04dmB}Ulct+L@nTVQ?Kzqkgoe+lOZ$;{a~RJl=jzUW4)GxK>1HtHo5TgI~BWqi7=F zyg=z71|7r0)PuA5Y|b@&Y>*iwO!%3wu{(U0?PRa1aECk`c4A9~&({8MOOV}LhV$gz zzy}Bqn}}O&sXtfEdn@j?q#|DSL?zGS-*ol7%*)LV1;^RMKs~f%pS>EgFl`NeyV%AO zmJg;OdizGhH0lf@nF1hY(ULqUt`M`cNnmFXcP!OgH!yc1v*jOs0NIpEh5Xv5u;rc% z&!vn+z(K6`Wz6ne>KkzjC5b{*)ljY1gzYTczn%4sXSfR{xP>byY`8wI6*}==WFn%2 z-`$6_xDZ z{f9qdyi0BJEeZr3;NRf1nm`2FCXx!;CIjmSuhiZ8*#+ zcA>a!AqVfW?9$x57R@9VUT*saYK4!nGR{C27HY(FDi-6B&f7c2BAqrr@|D9c>>S{U zwim^G^eQlHF3y9hR{3%@7##hEyB&Y&t*33uC99w2`DWJgk|3OqWR-hzlxC#8EGnh(mt`2w!uoV79m2F^Za&i^}@%e?l zFt3&p{$(E=<5tqGz~)GiWIq#OUoma?(o*)yC|R9SEK7y~Pt)j}!3a!0@o*0wyP{MZ z+*kT(yVL&=ym|P^Wae{{-ndMR#4fkah(NIRdL<(_*}2Epy7hIUSNbjTu8(8G7L$4D zA+A~e<#!R{74Z!RE5k_PC?+p5m5A<&n)5Y9#O3DK;>*P3b4y$3lCz^9pqi|hdqH0B zld*JcS7*^1u{PHCLN>n$Xz_Ga`AEl_E>N=^^W>`HCIQjp3dfGV--02(}P^2L$;?-i?h!3 z!1Ky7i#dnzJAry_-ZJ0_(8I$hBr$JimzZ>`8=Zg2+-Q#1DO~8kIcTwSOUey)3>TA& z+n;s9sw7_mpMY1v_&BPj0j1^4rj+JX`V+JV1%J^4{mZffD?8eG)fG7}Sip^bHT-iZ zy>z32>|$oPpMie#bqXsWnq>)B1NnT>OE&?FfiLmWTVzIW$w4w2^Ih!9_hOdw zm%!6E;@MAPzLsf%N4h;^sXb=tQ@_t;)b>1fpElJ=F7jTsH&>2i z9-N3il_b6_7Xy`G?%jB``7r*7Gx(z3DcD8jKa+r5pIxyN`)%`!`(j;Dh_C}`Wrs8e z{L~|`U~J3vlC}(Y^y7mp3mXkj%1Lq)8MOK4as4}0X){I7;Y5mZ-p!XmavV#e@?@>e z0GP)H_uznvF>SoFrlM&KOV3)3;mLh>aa+eMRn`xe1Mqi;+AEX-i>nhdGp?DkI+HQO zyWOIFcZ!c~6@WD^PD8XV>EsPX=8?p)`Qb|Dv<3e00J54@Sb~qZ>H4{2#OB&M59(zi zY1+$8>xrv5JlUwA6|$)Hbv5{Oe~=0=A@1*x@p2e!UXT(rw^gWtFyH8E7!}BAB*`me zWPRb8GGaYU?jA}bYXTiPDFXR*%8`K(+x|F&tH#6nJL((#!U}d zb@%DsvOrNekpmG=-m$QHa_0xK=Y^S;_y0ux9 zEp|ycx*#r4Bn%h;lL^CivyA9!j?S=`5G2XhzPYAAOv=`3SvTza%mA?Sh^qgF9u2-f z_`VXp1W-&nek3R>u9g|ky`IP~gJCDiqpwK_;qG5Q3Z(AqKE8~5HviV@Tobx5@@l3Q zc%3kAx2JFiAvxo)iiRE009zV^m|#XKx4fvKC+;3U9h1WQt-jF%zOw|azJ}ha2;D30 zv5XR5+?E<{hkI9U)VfjE->ENje>RSgSU^d_f0Z40PZ%j%@-LP4|KP9uobm8<70X|4 zNW{nc+Z}^6b?C0|W3RGf*505~aI7QE2OG{c)i#e%MK+fU*6iHoep9o6s2_Y6-hax(oQ&y7l1%My&4#f%QD`04Y4#U}K(zQE zogVfmh0DqdL>vvs#Ds-5N7@Huu-bNyuN{?wXwRKG_c zlTSSAsp5l_1#Y^o35Q+*S7N>p;nZiSog2k(7wo~85Mv75U94I-)wq4cT9jNGrK6vd z1#$z4mzhO2^^$78v20MvKiaJIex#cJM_@Yzw)Ehqhd4@9CW#2uVy${$GEHw3Dq2_Y zFBgd2cBLDlc<_{bXcf4aG}z2=UFb6=F__fdan($2Smb=MI&fEhW%&e2Xu}hxa}8Og4;lhwD9ffKx4eXoL80U4=oq-XqQ8Od=F`CmRIGxlfjs(DBv#3aGQ~@A=96La zYe!NCD?4y$Y@UzD*eg3j@%efg{ah>#%wt=LN-C|eMt1#J=9H7LuwfJ)V#0HxrxuOC;XJkdR*g44O*`Qo_h!QXFVpG;672s$;vxHY_P`0?X!e|PlY?X^6Ur3nbh-Dtt$@%Zl+FF+R3mIf@=>g+3{9k~^h+uOE1~Cih}UVy?!!7+ z*`pD|X^t+ysD1VRnzu)VA88d~rznpA7a)KL9t>NU)jM(eLl#^^;tJ(K9N6N<~`icM?m# zpFnvo+q%&wkk3DlJKGM!y5=a+epm7?{8%yLY;~da)0lf>fJ1>BQ{1^7v(qC68?Gok zxS<(Z@0HPx-lQMlJP3Y*ti^BX! z1ED?igcqu<5l}C@-R!akpqR4^MsI)67qPfvrnFaXVLwsd5&b@Jlqzx}%{qzRL0GLg z`np)z)7W0uS0i6RnlSK?s9Ficp$YRCgD@b)k?P!!C0Ue_8`7*@XGlkqp}kNQU-sY^ zs6rsIh8C1y5}pSCbV+uD?c;11oo@v^@usk95@TCwBSefMh$9w#kLjZV|KB$MGa66z zvUf#+>c=JWp|6>vyxF&ehr*w!Ipwx;e+NEzBm1Segn)CI9}Lc6Gv}x^yMONXvUdKI zHJonzrfn+&$_v21aSUmD{)q6HyXp%Tzo$^WF32fY&XW@UlkG2hd$FL^!FI5N{*V67y*Yk~)PFtB;n=3ml1;THnE*6@=60zjgwY$>nAFSNyH zsjTH&cozjJ29a{DkH+R~PZ0qV+ylfdI}b|SdvJl63p`Bd?0xoVR*?m4=Ec(4Wb{g! zi)Nck#w_g>DRGC>oBGHFNDr1YTaW?mAp#BM8f>*GdRoNUE|zn8ZWf^Hq6j_7{l>q% zXx+Dd^S6xd;KyW+^}&=+Qm6g_31)@MaEeV*Ax@NjR~!-dXQ%5{_U}hkf4IS2k}Id{ z@W_A3j8s`lCf&dHv+!`2wbre$zj3^|a5j%xXy;@cO@aYO8`VgJ_6-MF8$Rn5X9Egn zecE~Fkr$|K7nAp!zaKz57Ou7LEzbW8-iYdYeE(zmcPXs-b>5@bBtj{C3mMz#z9k!g zj*?SeQUa3|GXBX5>?H1swu_>0zu!L_pPy=YaI~1*-#(#5e9`mS8pV!9dn1fv%>z7t z^fk+ZhqE}{)EXER^J;KJ|2)g|xxd1_y}a7YTHLt#eedOAZM(DBa@<}%zK}3w8>Iph zhks^s1LbuE-Ea*aH|69#YY+NFfXl*jEO&s{tS9e)_ZDGI8peiL6Yi;AI0*@F6}|vz zPHt^yVz`=emt@*hyd#_r=QjO9N_|ccl|+A+80+En8PEis5A~OeMrbh|esve6F z=?GN$nls9$@s(MhuN8{ zQO}2$k(Mw(?F3jRwhCQR#K69ajkx*S;J3X$jG0{HH_(2bg2a= z2|FRXV2@SP0+CYS715S1X2GmS(1YNrC8nDwAZqjo0CK%xOxYIy@Xf!Qk{o@d z{^H1?Qq_qe6bXP{AhAlAfXOm3X-zQu$1?*BBg~xgqK;|zkD9LTyH4w8ZS%e&;-7v` z$IA3np}-`PMN)meJYo%EEicCiYN-#xp!r5duBaMwK(0B#+~We^;pq20GR+(6hN=6! z;mKh;TiqQS`zXr2MK#Jcg}-S0)Ps2Zrd(GL)YP3IJd6sdy}GLB-)?p<{vYW;se--M zP*z{vepdAP)^?QZ=}CrHd4aPN6WTEyM#qOkW#7+TLaVJGAfiE25b1`dg`8fYLM($E_bDtZ715%xkG^)mm*xsQ;oT%mcP6UjQ`uuAM^0YBj3HX8h!9+1Lby-xDuJx9iD|+)zfS@ z^BSAC9VGr9e7hu%neq;xx@7d@PW?6-(n^?qiyG+%9k@1B)8BlhL2c&gHzt5bO$8Z6 z;~>i!@2=x)JW)L+Lid6HjJGQ5f41KmeDsoi=_&^I_^n%0fY&uo|A^5>!W*6w?+z}u zFkOG&>sZmOVIs~7$$3Fp{mkIMV{eSN`3A2P|AuF;?#(d?g;dALq>R4i_js6m5rPC+ zC?d$BDx_Pay!UkgeyuI`Oc{ouplP4XZo(%^;o8dAsBb=*Zgr#$N<2%-iU-8yLhFIN|B*?) z<$w)Bni)ycSuslYoJP8JJ1PJ=uA#M$S!cBE3mPe@=nV>_YTt8mX^A_q3VsFM2N+^z zi?ZvzUvv^p7SmMN*c!CoAttNoY<4(aD!5>(#?!ae0(36W4^5dLnVy)CsjH%$2y*O5 zr`7s*IGSAPM)t3O!%1ND((5lm%(RB)SaN$dc)TB#3*ZtzHmuUX%;l7A&OWP!3aX-b zRZX6JLcrk>MiTz9{DdzONu_(bm-6k*S0Icn53%+ZurjTn>oWoPHlQr8=c5MzvZz== ze~>t&1MPDuU+yVG)?L?TXMwcmjeiUkNue8WDfYpY+1m4Ug#b@)0QLZ}Vjs+Or@qhb zXt7>toNgchQ=q=@Cj%pYb^W1&D~7LUdR6$f7QS_ojDD)=NQUern)vVQb4lB~FYG;9 z={#j|KX4o^cp)!vUX&L3U@zXMHxn&J79#NLIHgY?c`>4kD;)`vx)t_i={J1CDrd&1H#qR1Eq#NSDuzN=Rnhxw( zrOFiWxxY;vWS{GZ=QzsfX2(H~koN0F6rNjl7`1PylRQuC9HY4%TBV}Oi_ zp7DH!ses)?tboc#PDXyU0qC^A0G{VlQdpS0zwaui-}~Iy+#(?%q3yrHXLJW9L*#SB zH=fu&gS&^xSX`NQUZ;efi$Hh41i$oeIUi<_eB%BjBkfebIwKCy=|N-;PYx5i4-ich zo(t8`q*dPrTpk%(EvGu59N( z!w45B0%UZGOfoD@DrAR-QL{mpO;mGnxt}61)HrUY@BrK6yZN?NDZ@3y!QF3w&#mLM zJu9r31ct510BMJZ+sCP+2re&vS8D4;vERKhKrO+5vsSu`L*c`wNv3Z*%qb%37XXWlsr2=pRuZnqeh zNHh=nKnZr!ekMQxmlUrbW|{>}Z<< z*`W3=WVje(Hzl)N>J4mA51zl0pYFmd8|%VBj6{OK(ZNyN`<=v-V#Bxt%gCx%G$UYs zST2QE{R}s8C@&n`oV>q%kc;tCdMt;bv7%BGt0?|OIEpndIg6OdZgU~4=vkPaxQ*q- z;PUY1%(4WIBMEhFC5L1ZBqc`+siiEE4k0Z(VMUz+5$C>Aokccty+4o#xR%)V_VWyw zsG&IpXii!SX!~6$yYTn`FzJW3+L^cEh6xaRsi6} zd0yYz8qjZvyRbk|gmaYl@UEuhu5~JWPe(N+(>{b_BS5}#3pzlADKK{@u78qW`XD?D z5_mzR`d+1WDz{YEr4(i~_&q2zcZpI-z-+a5L`O^d$Vu|DW*$oTRv;uHSa(G$0t^u% zUed(Pqh2>Kn5>>+PpFoJw6$dV11%C{K?~&%k5e#A)3$}aMM!+7vhi!*+qDf4QW$%B zHsTQu;52v|^TqtsblbX58oQUA{J)g*J7rY;xEO$LoZ00zx8%4KV#GCRemteZYXTs9tn?ONn{cl8>$B83isg>uJ#UjNp>kwi|>T(yY__`c>!V~246dgsCqGGX*(MiSJ{cl+~>Irx@J&LA>Gke zRd{b4ajHO1yB9HceE2){fL% owRqoDb`G$nxkkBuMN7HSM?T54|wE%tBX;9mTo> z0iep6_)!>Pj`#vwhmR7~tMj?_L#l0Xt>rhHrYQORMoMA)Mw)si&8>?TdGp6sK*gqT zDdV5!Cq17$6~9tEi3jyJ061(cYG{TzL6f67!B~&^eHJXeqae ztXX^6_R*_-B16bKQ2Xwd7Zs@S%2&^OVHIV3D|?gaIfZa;F?j!A`zg$Oa@eB9=V5k? zc{TZDOESCXgHj1FlJM1?Pp+UZc8Bvxn4&;>{esN8`bPYc)wf<6d=GK@-bU^h#U*3CEZJc;Y?WVZ&K`sW%c8JK7SNAn#n}Z1b?QvMyJ9v z-M>D8{tqk;!2twLE;{dAot@d;89f205Qsd8z=Fu!VHm<_K*;4eGB7e)Wz z2)l%kTM(sJlp>6e3NQi^8}S`BcE3(fAgZi(q_Ym{BAjS{{|LkBM&UQ>A|mw4hHL&= z5@S@Xr;;|sp4X7BlMB5S7{BM0{79zcF=ZcejA?|05#95n+DGXE`r8jnud+Pu&K?ALtIove06dkm78bGP;4pUVW2{H0*3 z_45brrlMB}PB#>TG5D$$A_rR+qau46ahb5f$9TQk z$`tFyZ|q*+7r^(R1b`WhLb`LdJ-tgH(6+y3hXV-D*KpkMqy2Cu33PT$t*Ddi&TbUk zS%cE|4_Q#_w%5&Y!q}Iu3=J{}NdNpLtK@_JN1;V1!R9Puuap9i^E-g3`ixnGNcMq8 zWoQ4-aTz2>6~V=$qUuv1B**oYTNCPzsyPN!$Tw_ZAd=KYeU|V>IQR&d!Yoc+(-2M-sku4N@_8 zwewlNku{&umHHT(#cUL!7JW z30{n`x0lmTl=pe8N(%-5wEitgR{J!^p?h3)k$4Za_{pn+`9|VP6BD`~nDH{h%hoaC zfL}aHwU#;zr`7uK&8yxV*HOS>Y^{#(xb)U2Ub>8Y(IDFXVT$-BiSbU!bswR;jJ2|a zugRqq`mhFHQhc(vqEy~OS2otaq228EDNE39AqMas@2FH2q`me*vgEdKOdiVl#xGJK z#jL%YYqd-e?zrKJAWVhktI2c!^(33r=l6p#6?y+d$9y8dD!+EunPOwvoNXSW(Cd1jUik&0l>JI?C7{vsE8=mMuC1y z(Z@;SvpdB0mQqA&i`ovo2^|8 zsEXnt4JT!5W2)k_lcJt_>PR!ly?Fu-a-f1}Q3T%V6)0XC0F-DlC>AwcN%Z!L zxst6C?-Cz!fW0kbXL|O=`b!5#S;3??B84gBwBPeaA4uy{&BwGZBOZ!)E(wt+imuph z`TpjAtMIx2&GwP~dJF6a?%?sZuB1hFPO({=BQ&eKk4Ypk#4&RDV}p@CTW@-jD~rEp z=%p>!$D3tCbCGgX)899^A5rq*=&MjO$jbSfhMD^w=lC1A+b(0}=pNDp{Jpcnk28rt zQNkWJdAXyI$LGr)v<_Y|UrlPJ#gBl|;}4v2_=o7>s>_~a)0m$TFA?9^t9Y5gtKzIv zDZ%(oip>Hr;Nb*@Y;O{PKEI2B&Ac%*yIx*y>Ae)3Wt_EAvih1nZ&D92DZSA=I{?Hv zcYQ}0E*k}3vbA3ICqo0+$9+94Px#MNmue<-g!)Zi5<7M7XESab_o>c&;!h!j2`gla zEL>5p+$tsg4Gbv;9c<={2SEWmiEv{0pL8^0B#6u;V7U7~e1hTI;CI7K6xIK&-1AGF zjQ;AI`U#d!bw3GTY@8^P+rDr@uU|jf7GYXh1;SLbdXp7C@mWKh6Rny$%+SV*1mJEJ z11gZO_26gB%gHwf17pCs0wi617J&d@W5fto6;t9jVdbv2Wp5T!#7+bZVI8@pEoEEP zVwz;06k6+t-O3Sjq!R+s0QQ~zrXdCiYBo@WB?oIsRqqw0QNND znR_ZLM}#~dpSDxZ)%j#!9{5Y7O1{G{FEYsMsyJ@zKcu$dI~KJS(=Ydu-J&psBP$jC zZ0LBUA1Ckg_fHy3gOd{u@jpN!_B}CHsdO51Iy}|psA168Uf5L|Y%za@=|Ha=A-lLs ze*jp$3axF`0q14j+d-uE*Y2e!^F*sH32`>IwFxh*GN@M}2M+J|cGD+kv5R!ctrn-I ze?rytG-fkL^OBlQ@Pm5N$U-g}u3hrZ`d6C3NxojbC`M|mJ*vcjkuIl91%|kxhs&N= zCe<(Sw)%XOad3_1vJ!IY0Vi!lGjxF)78nTo$T+ytP^~wnxB&GgKmNBsVSW1FW)Kqy z!^z3sx5Axm+y(Nm{k0agkCo&jriXGtgvLK(k!2^JIA`dlX>Xz;!zZQUqrSCc2mT!5 z>`_xkIXEkIgVP$D{#o0OCbWXig=_~zQtQG(iI@)gyG88MI(A91ClzVHtJ+*Tr~n4` z)e|sOI7$ngX5dY~Bwx2Gk`tJpD_GG3(1?QIaN)StHh8Zl(a+x-?&_wVRzVb=z9U$c!4GJVZo`9o2s##VYuQ8RQV^7$&F@&$iCiFb6tmYd<&;%g=%`-LqujFB zGnrvfn?162yur1Rv+e)47h+oxRt%hYdt3OboY}8^;NkZmIn>bu2ZmN3Dn{g+AdZ$7hO5dL+lY~S2v(~ zSmzetmRyB;gBSe_k)d3h#Fd|(-QU|}j5`xUrPDH2?#Jzw{~4o5kzn%PTRq!XK#_zp z0F;Ttxbs;83_Bs7BOCNy`im)obhSqB;}xt%aa}A#DtqpwJY1=$HM|78Z$bN}aj(H; zcG;G?YL>D+_2ZnOw0!VM&AvJW#^%AHIpCZ+x-p zhLx}J>iyC;+u7t4d;hc+KDP2)jg*`&r=@2`8O(|fm$u4p49>))P82jWwrwtX4POaM zFFB1y&F(PcHsM?hy4r`;zZJ^iY|E^Dsu4NyfAh zT+&oJXAiD#ncmA3GtK5$xDe@}+hEi_DVEe0ytu&~@%!^}K8=X;?eg1ft$^ROL53UG z{iUSXqP2w~a)kX8%hSI@j&Y@qgMT=496o2KmpZ5OHk8G8&tbiwyX8n&t9>~)&#L}h z7$t}$#}jj!a^3MOgCEg8G-2_@i30F)@8FwJ)2A8(oG*OoWg@QW_bNP zOr*-?OY4fO3gi@(?VJR7WjEHEiPIr)fov0tHpCedGJw-@a{QYA8!9{#tJ3onG_0+? z`ad<>XJO@UxVplqzY8-EC!P&!6=i|q6=jN$>O(&TVLViH%w}JI(8)+l5-lZ~X3F<8 zc@faMp~)H3c#pZ>TZPdyR6%jg$~S(Ehu5#aoK}Z#7O^PeW~P#n=>5cqwx3`L>sfXs zhSuBhF2o6@0aVEXOHn+7B00rSdzy6QU8X~Rho~Kg3Pah2%+#uv7wAZZsOKvAXq?IH zT$cbZYEbhbiU&dxXVJxWX6bk(aHz3V4yUJ08LRBQnP5w88BhMU&1PrbcK@gfJGZ6K#A%013pD(gDblVw_ibL>UYhi%!*@VJ%f zZG~gkj!#7&M{**R`9mDuE5D&SWQ)ph{Pk(REI+sh!w`|SDtd0!RmGr0FJC&AMFsgg z+E@8u4|gQvzQd>6AX~U51?z^lI}}E^e!Y5HwO-_kx88PpgW)KYWR@RDxnC#5p}Z}r zAx$ow2F?Vs79t38%K@ved~zG2ck4Q6tuD&7{iSB07PQVhAh~`V)NT_-6|qx-w_d6xO_;p5vp)s!mVZU&^6uglAEL2+Y`|JLw^lREN$wq|B)}2ptw+hwJVNcf8 zW_yf#KL;Cj=7${%PBD}I57_ZZCm^5}1!_f86SymymmI#HSJnHTt@Pru7|p)<@END# zN4B*n?@bF)!2%UUsV6EglF^lr76=>JQgQ@|HHY89cI#CrxaPmb zG!9~fisWq`+o&}*zu7o;YT^(rWt5$V;;7>EIyXO8T81KKE{ztmI@ZK_4G$HKjb2bf zpEhD#roW`@ue-YJJC5(sd20Zb25UNsND3-s9*Gqwc`Q7HI5^N?-QQU{)Eqiwr;s9+ z)v+|c#-;1iW>rFzR5Y)w!Eo()d0f4Cl@ckt<3s`v)ieXhzkq@_cA$YquB7+u@5_I! zjGGg|Sv*Up#O&{ey)yB?S7y}+`5}V8jAB&rGI?NZ%=TB!L_1#Dl%mEZwu3Y~{o*i$ z#{+9SXo#aA7n?)b#RrDdzA;&IbGdk1{~tzYOYGX<;367rRQQo z?-){-G%-LjDQfC8u2&hcJTs<`)iX%R@cRuhVA)*KTe^ts_8CfJ9=^`dw0|dH`HOrg z+^T`YJq}Dw_};aS!~K1&8+_CoQq0$7Opc=5eC2W?4k8XXm3WOJBVDbYR^3H_W zUP_9ZzlcJ>7Qzd>Sd0NbSwD&38-ch1C(e_DE+LI35@D4kE8_CS_6XFwOidz%KXuHS zaC{~-+G`e^5Ysq94<1nvhdj3{s z297L|{-U0M$7&hLZ8O(C4^slNfrYd71kU6zG04CFK};#^7pkNasev;GepqP@e40RVuSj2@0;fV!`4=4~5rJG8i~ z8O|;y?yosnwSPoKb>aOs4pha&(S!dOtts|@kM^S|LF+O%iZI{2*J=x#-%jopP z9y;E9%_L z(OZdp?He6Jx)O5IHPvY@uG7s6fJdi+^#y2}AP0J_MA}7$8c9J&g2)KzZ@qGCe51^B z#r-R}I2$00eH0y_v$4{~NS9^tQ9kc;hC97FZaB;nH<$M`q2-fp3P%}AVN)HljgT4t zEAQG>+0|=Mz=3XOF9E{8HOJ2+UaQ5=*V|es$AjFp&4=Z_V{@Mk0-z@qi_dKkhL=3S7p4$?6K|v(Aig-Z z8n7z*?dSRg&_*xz?Ziw1_SM%MzF{Q6!xL_ZvDnSclr4i^(3eZmv~hTFq-wztX3$r9c=h5t;b%u5 zh#+IyW7RiRbg%Ezr&ZD*MqU1*CI3;U!^_~Ml*ab41V#Cqb?kU*2&-vG7E8kffQb5! z5i{3@@9w%*CdE z(hPPp!0NdozWDlpzs{D*GKo&F;U-G-A$_RyDvA_ahsbh6W=T9=U4b}EGpyQS)+O=W z#cZYYYi8}k>iE@Jx>g~p<`#S(y%Yfr`(Y~@XajkD_%1~{&%j=$aS%@>i#UG$j&wHJ zrs@$#F~oc|@E_1Xi^O2%)J2e`cqid!o6;mM1iub;_Sf?U4bWR{TbK5mi87OSv+Fj< zGPN;Wn;N+;aTpQySHB}I`IKJ>^h%J1mi%UgA!k&;+D0Y?8^shKMdL6bLJmKw4#|73 zYMc9M+wC)JG))X8qGj2oNmF!8kXPngd)XCt^!_0<71TvLylGYkz4H1Z*{9cT@x&CD zp5+^V5(bwxP?mNmJ!fUnW-DhRhb%|Fso)m~J7jhpfdxl7iZHGH#eeI^*Z^Sk;OUaB zrWG@WgUVS*b)63{wQ$#&=+k9$zYwtg-S6#E)@5N=VVwU%*jt80^@V+-bSfb&jdV(P zN=tVP0|)~sA>FAU2na}bcXyW{AOn)Z&?zDe-ObtK|9Rf`T<6RA;H4jg*?aAK-S@B7 zp6#s-ywJh3(EoZiX9S}_^fUY0rcr2wADR@VKSgVY(bWO9?6s}=rkZhO2>q+8Y}~ws zTq@Y&tsyX%K2b*}oFxMh`U3g6kdu2M@6v!_O$k?&Ps4d{Rbet6_VDcuHk)*wOmOX zt>_6`VGpAs{~P#Yrqr1^~DHitf`ZoH_E~;ThR$`$rq8m!X?t`pQ8@4A9t5lEYQ^b?M~* zfPA{y`g%=I|3eeWiBgT#^8|H+Jpfo+dFqH%Z&F(p?JAvWJiO8ZJ^aQZJJ>7#XeWoS z(~1e9iep!)hwZZrcP#(8Ja(M?DASg*nD0kV1;bTHTO8g^c+}ECDfy+RY{oK_7Us+n z{C5b9>8QK@PWum1j&`Z;y6x%56YJT)2rA+-7#r5*bOS6jh=*${VsUW954=4?x$gTV z!r6_JvEwG|bx^u-NdZ;(BdTX!0t)NIhmkDQ03)~eqmghs{o+z*?js5Wm0Nm4I;#<9 zX!4#++MbI^@Ws0_%yB; z=0ZW6!8qBz|fj%a}GhV@F~5CK#xlH?a*@hsX_ z$VH1|3)jtXFYAIsltyH@Rl?SJ)^Lfmx^ZO(0I%C|{F*r?{4*yQB1;JzIT6?Z2&PB<2h@rxBMAE{6AO{uND)!iS?R*M!_dWXd5icugNL=1ONdJ zF|oonl@mN@D0igf*mv$%L`#3q+p;HfAtB7W!P**;??*E@;a$UYb6eDSjZuC4@Cah+&Lh9! zi|))tP0UEFhekFR<66?Xv@m&Klx785eM=y#E#$a3h)lhoYY@@rLd|nz6uwGqBG9F} zYXdM4<%i{-`EyV!_z+FX)Rdm(3V7(Bna{jE+Gy78LP--hxSfEr$1&)RMsDW7+A@8_ zBytUXi^XDpv+?c|C9u8s&#_DCtpZe+16_MbABJK_@hvO%ZR8`6nYO9w0TwLKAgNH zK)XO+!7wO~n;_=c){GB2-%x_8BvrUaWNdhZ(L45V$Bkwt7=~n^a*e_rEIa_ToezS2 zG?Zk|s!V2=|LUtA(eLeO%BoC;2O>FeM*(Hvzqez+HVZk?;AEV>A1mtlX_6OS+TWrV zfz%&NDi$c^s{i?y!H*At>a|Gf71Jkt;Z3~{?k8Z?DGo7V462OH%_6(37~SyOki<>r zc31_hxMo%|GT{!}yQVR5)3vH-CiUXK>2{{0|B=+up%`yVq@Cw1IN{;986Aiy{(6}@ z2>NCjazs!)G8(Hwo5$bx97N+9_Wh1-oOprda=rE8R|st*X$NsSQ@~hI>=FC`gGK3? z?^7uL&b&Ph+4{ASR?Mi*jVMRM$C=YcV>XN(hS-eXWVp;Drc%W)4nTjYPz?akSMMR{ zPDj6J>=TdMlRo!EHw9L0856_o!bRei#KJ2z?&giH1ZXHty3WJY$BgE&W6=@>@Dr;E zd3W<}xqxvv0LNT+i=hTLJx#wcNYRc8+*hW*$+QEJu<}&&lI%u6)3>%(L@k@H5>;W@ zYGty$NoTlsvpnx*uey5Q%Zu{tOzdmWAb8T&M<4CP`JGpu*Y7=|+LtIR;><_!RmS#n zn;N*){+1ASXRw_W22*1RYDB)Wq8F7SO@w4UjFvys_zOy`_m$9RBT*> z{51_-8oUX6%LWGVcGTh?DUs70d`Y-+CXOwwum2gS-=NB;Doj83zGz`fsNBq#Q7AZ* zFX)Yq`)ddu7Fj&s*|779M1xYTd+p4Gy`!!7vj8x?tq~guYfF?CWfhE_XLAN#{rHfV2a1P+tXWB%fhqn-uLrlUV$G-nL}O^gFrw zUx)s#>fTK>dyOx<)H70|MkbpJv}nszt(j`_s3vZ2>lx#$6>ay6ZMG5M{eWQIP*Aq5 zZ__9tB%CA=L>X`26%A1{H~zW4$%MLkvRYEqlJL78j9t}5s-;O-@q5o_=;wcXNr}H`xW6*d9{i>E<1}zPp+OH~ zBf08KWs|!{hD*ram=t_(X#{qsT8=-_g#@z|8rw%EjB;Xo8;xk&cyLolkh$j@6SuxXj2>v3qPWT zTXOGlL$gsj3ZCd&V%6F!dFe7S;c=_h;UtKee%3KF>yp<$J*abI3NDymB!+*$B_MzN?rnZDHrV!mM zdOL%lo|8mdm}9rp;h*+wso3yM-%q`g>`U5|i6fn(0KSI@zkiWQjthPCr5H(F+4cO~ z3ZMW~=c8|!ZhhG3^IX3(48cBOO0)rq={RM(yPo{d-C4!SO{gsFpb+82yqK4ImZg18 z$SK^?ZB%^LST7W#f7tB$SdAoebw1p{vxg`|T^WHxR@plqM>;JXXFl%H6ToCw03w4eQwM zdSJcSYunD=Yqt-Ns>NBjIfvhaX!h^w;Yc@F3*nd_#lh$gM zr)D7bhu42YiipANz2fBZrFeS)JjY>Se$z%g$6xr(_Xxa4Y11L9zhdG&0g{K;{!R)a z%ArA=%=sTJJw z2U3|YdBt5j8#VwwK(kR(`fp|UsYxJW>?@6dUBdf%`>~Vr_ok044}Ok4D;GWcv9QTY zu?>Z&v>e4~^5e;zW^?=7)r*$>zvR@*Ei6NO>?Lw>UrrYvgt7+ys!RDO;P%W-&v;Bd z94_B;?~fi@DfzgQbX07f35Lh~-tt)dydqKEb)D8Brj#XFE!kz}6?Et*b*A_@D44pBAXRovnoS*r-7go6anub^Kz%0#Aj$hIBQd#uK@JpZZX`C}& zi$l>-8u~dr@_{+|cI2O6B{9>CG&NtI{qW=4$SvtjXHIta@ZSSZ@o5vSACB1bVmDn641nFwox4p3B=?#kK&;B4LFT2g!r|*lBYZSPI+%hVSwo!moD^p6~9NjN0IV z%cQi0kPP$urFBY_d?`2#=r8Fd)>xZ>URa9waQ)w2C_oc=V;3i!?A0X1WKwHcu~;!zXobcW2Y&N9^MfORHnQ$Qa=|sa{V^gl*0WT6$U*r;TH7 z8ax;mu}3)mt?)2*ml^dYj6E+Tzs8ZG*mm#kfJz15*2(A63_u-ZHSWJ?w#Yi9aCJ3l zV4!xqE-ihggUTe|I(R*EXZ-t_zGd(L!iQ2K@-1V({A9TM3UFhJ4C|ti?Kk-b$*1v6 zOxt`-GT(MUON3u#cfBMqq#{{}x&~Qodu>A^B`K5Dk`hELKAN_2O|a#rRQx~ciMINmMV;^WFqUUVjDT5B>#Ynb?|xJ}IP`rWi%oQsXN3~?Hd>JO-l zIXG=#uI=~Qux-3iuTRzqL_5)_94=GWl&l`IYuG-n!Zyzt$NeWW z=yN3791UNAIw+48mRC=|rfj!V0O7Z70}=VKk~@ul`+$4NoddCjwA%}T@PmWJj9cPS zkHs(DncK|@Z7Wo6wwoR-t27N^M8C6?<$^HoBuq+LU~2Kgoss(dvMVv)&lgc}Z3de> z1C_Hc*pn&dD!+{UL$P$tP812Yc!XSgz%r#iG&yp(>HEA!1?_uO8pU-4OJgs6DDV3F zGW&nni-tYi0G=afTxF$34|s-N7Wf`Uhd|GLVvU%*9iCOyh;EA|{pxcl+@rAMoBXe^ z5%j?@BDG_IWQyAVhUP0k^;ap>h24e=`cv#wkGWF0E}TB&&6BwW#8d_~csf zqH>vOAWHmsbx%~C)%clcfK@c|mRs*@RLG)-mD*!@+K-Q4(Soo=K-igwZ!57+JPW}! zy6fTVNzW^?SRar0vMG%Itq3}Mr_NcY?wAXSpG~G zq`5;wg#mBxo#Jtkx;uKc;%jfwyzV$(Uu3@Fu+o_Zyx6tI{LR)gmVM-0jr2CE8xgR?ft(UaiZ*9 zbie{NO4Poy9T>|i7eQInp5>@SP3EXnCp{kR!#)`s`(6q7D+iJ3nvVgnk5{*-6>(nX zBYm1vqRY3ZKW-mGFC~1dUVJz>7PW4`#6?xb$P3R7?YzL8Yi7G0IxMI%Z8=$T8^6v{ zl)YVCefZ;r6S%Vqi!Yb^Fpk`EX1~Nq(F;?lKE7*j+Frgh2xx2s#Q)cXPNkq?=`x^q z`B98>ZNYw=;?pX_;NLE2&ZA<(xc0)BtZLw#1rWXQ4jkCc`?XRstROPaP-;l8Uc;& zm_g0ENP{?~70wspdCtS|G_m2cASrW-_0(Kgclk1dlfvyA2yDdP@4q+Us;IT zKvF5f72AD@0}*g0-`W0K#md88Nn)AB{)G!~oD&CnJ3odn>yjB+a5D>?IoEO}LTc5L z!tFV}H^deq+G-*oaFVo&k;cQjBGCyx!*$js^w_LOqf@BoB|H)O_@GNCRuXFo@*xtg zd}{+UYmE(mGB2vSNFGW4FJ!;D40@|*7*G(ygkzo;Yq`4xMFS&74V3P%VrDQ2#7R9& z4}f=1o**Q_)Ie8+H^SCyM>tq+gTaEUgz_<%5sE=FE2>%`Ch#t}sfp!?J${~rW2BgK zws-BDzd~q2u&y#$>WZwlTGEyRa#)q9=2aD8Rt8zVjo=qDLEY;phuguWDa8aWdZCWJU27A3+R= z9wbk1e#?$;4xB6XLKd5O9ftL;C*a=2|26vhO2A-Sad=ah!S=Vc&q!O5o+`6#xPuk` zD{nHSsd}V+fAQ^JY|yV4F3Z$gXrT!q2_bo`HKqNoi4e@hliLSQxlz@>D%GxJN3L|e zJ2NcMPY;pQDt}wFtKH0EGNn~!eJJb!C;bVxt%P%0ueAkH?GKVaWB5=-9xF;+<$UZa z7c;!_syHIRmLunXX>EX-G9<^h0ymnRX>VbkXH{)Q&x&YzGIw=dn}m=BZxd#-^qvY5{oa2VogBZY)F@MB{6^B-RQ}6hbu9BC+nyg% zhXEb&d3Hrd`rD|+K&uI`BWy!h36Plm`l)on*px;vcNn+qRfRYyWeR|m?nzvZL zIKUmV6hQZVjw&@RD;IQE)*|JM9ut=UX=~lcfcfV5_qdKC6 zAY9p0WJ|@5cpjcd*Uc3k-`837J(1&kZ-9TJK+|{Q98Sa!n_askEBMpqMWivSwIJY0 zFlgiaqNr=eMtnQr4ZZQYmlV=uXpDy$J9YS}-dpW0DcII5;5wl9xbY9-e{BV$=ncr# zm#nstTVZ4?gC3C_{>I{e;_LX-jiDA9#&`fci+{-#Hdg(oCXMt1$nkH0?z=y%VdO+% z?+R(s@VlPMo=MxO@Q96PykzrNxA0U~{&Sn9YYS+f(I-VVmhRkD`Dv56uTa%9@kf!R zUfDE_&sK5PI~xC#d8PvBZv9sD*X{rF`CVg*t$D_C9nxSHU@i#sZPw+2_B=RsQzP#* zdI7RsUN9r}UcfEU+5lc!3l43{=hPYgIU`1WE$^4?|0~VA7U1N?nrhGK+a`-n2V|$}@+niH=uK}zcKtL{@R;Tc z7c;uPEJ0bHnL~*$$C-SpNgjbEmeCZcAjszzOCTH;QzEbd;4v+NiS_GiW zgblpQ`lu`&8}O!S>|$Tw&q#T=zvK9>sz~0nd>QF_8AGbClGekHmxd%^3_J{_W$mPB zj?riE&|fTpLQkAJ_30BLpo{LVL+-d!41FmY_!(T5)!M(n4gPH!wSOw}t)Q&vGSFN? zWAq_kHl2TWem<#$9jmP)=qPiEUiB3HFr&FMm10|AlsFd9zW-V@$6y$lipzqJMfbrY zmlu^|h}gv-b07w&O!XWY0?O2sRB1`!GgiKTwaZErag>2oI znyt^R*X#5xx~xq}-2bb&X`4Pco|rX)S;}fr=3bD-2i<1H^4eHHJ7;}fubrjGah{8T z0e69TJ;F%28&Npkh(2-*YN_x@e9B(wmN@7Su9^nZ169J@@au{`S2Stk%zu>^h{5C_ zr$mmFrmLKM0s!)0rWn_~jEF+0Y8ZB}Z*Fr@L^=TVse4ZOi+TP{`UXHf24wGOUR1!j z(JVi4a0~;jc~siTjq7Yx+gRFhJJML5e0*vrG-$2=ALMeOsK6`GQY_J-V*XHCuaMY; zV~?I(I%SmjduKOc3$^ETEZJ$Hf%_-yqOuxr@XV6LLq5ebPCH4ftelINWC{M*N(aJI zz3X^WAIVP#xe^MojZip0S5NhWQg9X8+C^0K8S_T;%Br6Zzw0>_C>GYcMmg$S^#SlY zjt7di-T*wQK_!I+RZhEZm3Ulw!k2UsoOEP{GYp~-0;zLlF3!9Y-j z75_GCd<^R!2Hq~^qa=T2b9=$ux+ujaa836NMn;f4@WD0d-*#_4Qk66TWj}+csfT%k zLu0;sB=o8a(q9+B>eMU|#awJ({wy%@qn%|ms+Au3tDB!2vT3Gwl-_vWH0wSg+wn}5 zW-q~>SIG@S7&?f-#4~*#_1YT=(#XpHj{P@%kK2hHAc*UW@Di-m%K4}jU{k}}^~CVD z%ck<70eGYPv1FBlX9NF5&@M*Zes=w<=C!Gh39IsLOa}BlM`9qx>eqznZ)DSUfnqX3 zu(;E&P(hQ*3{ggO;GOGYP*!zkv|1JvoDAaU)R4SB6D1>Io*(TYFYi3)5Jd*6F(GngV_d5aT7 zTMA!JILy{rG#r_UVRjG_J&eqt3L?TvKpKyd#LjeJU$Fv{cU5duwa!YSjx4=Lb$te+^Y^|1?Tb%z`7j|dUz*l`+Y$5iN zlAQS{m3^jvc)D?(UC?QbdAd=cY5A7%Gv=xbKPD&jE$C(UDXEBsF z>?$weIHt*kLRSU>UCNxj7rDj&!==!=S;Ww?3(J0>$b|YiQ}5%9T3pNh*rMia_DmO` z&2p zjsjU8+~qo)iEHxLmX46yuk#K5j_+U@Znl$q1n7ta*Ts{d$S;&blcD|Jf=T?;V&?&^ z_Cya(y3JY;JXvT6r&7GR^yPp??N0pdHGx5vfg!R$71LO~(16l6wVQi4b4cYjFe)Z# zKt+n%N#ZQp2CJl3D7my{ODW0CNRz<)nM!v1Z}J93Viok7J8rB2sx{J-_EA6^QeHdnBqr zq}DQ;7Y`2JUXlf~IFMRXOyakH<(m5MN`PQnH_|Uazb{I0K@6Yv(MbItww=*dI8lfW zZUuPM%6!9Q3wY{*1!)Dup0ak@-YQcS9)TZgtI4w)9ZCEK7aHn0GAD2nJM?|Him1AB z<-n)nC7`psk)#eZ5mEh7o?zp^?ah(}U5L2WQ#~ajv00BY;&ovr=$CchuJMpIL6SEg zJ${afsII;3Nq9M!8dG{=OBi!35i`<()!{=uL`-TrZ>2`sgr`oLQumMOK2oH2qC*@P z^M(POh+wKxC0T~;Z^un+_KgE_*}tM00+xeoO+sP)jrDc!VWX>YA-IHYiKj0#Jy+t7 zmsFcIfP0?`xJbRkyn2#0BW2oB|Krp5jFrg$GbR3KZ9=nSUAO5{=+iuH-){gx94xPa z55%VST{~<5vzf-s!c+f4^eTaJCQlo+vPv?mgFY=usx$>N$s>wzRh?!ROy}6kgh&4 zzE=sRRM~aLB;rF04L3vomn;+Q|I|A~Lm5>mGJ*@ZF&z>0oDK`7QCL-k%p|!i3!_hm z%$NJ~JckYGmC=9)4;`4Ychp?4mGbP~#@qhe*kaFchev>#*(x+`li;{0t=C6WMR|e@ zbY$P}0Hv`0AFhXN#VBd#{=`{6gKNwjGh5f2z`Od#*8DCGxNb&l-m=5?yv7(?a#;TW z1&oI#(taa9zviWJT@3t9pz=3XzKy$Gl?;~28ua$|9)LZSfckbpg$%f@Xdr1w-HJeK z<}psnXXnR3W+8=*_W$9_05WM)m_GFdx7{=Pz!3PU7+16W2*QIZqTnz|Y!{yweDC)b zahWzU&^B>%DSpo-FA-G>vRriU&u0_A^@RlH#dGY&<6{>Zs&TPiSG=0dPVz{* zmZ)~EVi#O&;kO;udwU^X|WfIo)^gMj!==J(1(dO(Wk-2*+>hWK|@%T+NoT%lt;R~$W)cFc9ICj6 z9Oi*+mq})w74Tt?3mD1Ll!Mwktsto?jh0-7q_>Scq|4 zVfS1r#FP+4hVHbA5o(Ccap6wi;5YotLd89a=1)6_6*@DZQVvkTVqgv_8{B4mkNfK;!0)W|YB`yTqxWZpZXcJ=ZPJAtytf%0GNMcw_CdHp4Ijs& z{2Pg8jVu^0S!EkodtOSg}X1d*=eiE8P zln3q1?`kc)v3q+g4wEBP`70bEu62=nim%yN6wy^lU3QrN{{gL4WpUenzR}KIfm^|R z+4cIN*DrKxdY-M%rN>2|Bj)Fh24nSjL~S`UtD(2c9mTmA16}7Xt9iO1y`~RgKQRr^ zs9jYNlq8)Zl{1Hx7_ zZN*zQiO1XHhyhbOOs{vLRc#z7hpT+oFQjlAytj^kaHox<)a>L|-N&4(ZSfW7OBti4 zFR?OK>xiu%Z4A*MG8V`6w69cFEUPZi4l(^xV#chd|00 z%MYzo5hJz5%n!t7RYdm8KNh9#u!_ThbZFfzo)YU4Z~_4^++OiSI+qz@!ba^SJnHb< z)Dbo9?Swc>g%ck2(jZA2r9d}>0yh!6F}JgDC;M)zT%cJ*!it|l0vM1#t$5xZ3bao*H@L~NQ6vb&br=ZLcg-v7w>=6#LXD|pe^B< z<{e;?ctSPILW`=U`n|4Aaz4@cXWMflGYVLM?n~;_D(GdtOTd3RL$wDaudo%3{<9Vu zm15)|G*qJ$&%{N{ut>;_u{MfbNO^@kflSXE8Sc+R^YF@aJUq5j)_(Pxa(ZMX649?5NhX==Eq{Ab#}(SF<5 zi~o+WY=(@WF{5S#E9@Qx7kZ;$HA)GgsD$C8X_R9R)836NxHD%?i00o3kXn2BtpE`G zBO+_TN{QCJKG4I(4?i;+TE86VTS0g|^HSYxYJe^qpfi)J@Lq^_>SyIIm+Ah59>$}c zQFS3U0WsAA1g*1O%)EU8oGa5l(4TuMwepSuS#buKet_~sO50@11q`BnqN62U;FnN( z9aUnzXkw`l2s;GGuC8>Ukc9$~3HGSIf?W%Ah-C05e&kQu9n1!Uzw}PQxWN>?aib}V zHSMm1I^~(Bl<@=i>A5=wjo?Ea%UC02c7&*Gm`Q zIY+2Rhz(5*;J4U{<4=nN%HG)^UbW}CQa|YweeMlqOAlc+HDv`h6=Ha5?JrjaSOBRnIF!yGx-uq4akptqZ{S zD-C@5c@gE40FgY(ntyt;SIP3bwurue zx1rTbIQMA;7eSlkV2~`+!RLNc!;<{F9^XGvbCQM^$P*U!>-#HkQ-!%kp&4~M;%WlU zX<4A=?3oE*?vx%8iE*DXk^oj9>xj#hqXqs(^Oo;pDp{g*xZy7O(3Yj4sA?#ZYOl-H z^COO)Q%dD@ub0}?7+&q!0$nJtf%8w!T`>}CD%>s0)c3*-8kZ<|p41#M&#g|P`s`UT zeO-^v!j*+srq3ct{7&?MC`i3*Du*)~3abiXOfK0#wx)v{o>hkBs+ztl>Yn4@UtThpZ=F8)HU zThK3!#2`RvGpCdYHFYjSqcXhywCeLzfE&aRm!AO>%a6b!dw<2(ZzJ%xWe@d95PE10 zN2zJwX5jXlXx=V*;96gFiHdyGc9`kfA>p|Ao%Sy!9GEXBpGZu{n&ykIXDP)q6E=^p*&MIoE4{#IXTlb}bn@v(M+L zw~zB3r&p!BZpWKB+iF4tD5M}&l9qCkMtzr8RWp&+eL9WLo7jo@=()K(k7s9B7R{$u z7Jx88*RID$HJP&4M2-q{X~>)l@DDg9l~e8c8{GQJdQZ|s#}8xEEFu!D<3~r+wtRZP z+I()wwyxc$lG_s79lf**W(Q3NUi0))|iE8KAA987avs1!ajnXw+s5mqfc8_ zQ?t4gMTG@-2RX@*zk2_%?pe?*?Wxd_u>QlRqeLF)s{iZlebO(@LGY_w%hx4FQ_l?xWMRubtRi>`xYLO)esS95b9K@qFM#%0v}F(QEnp4F#5`h5@=7bx>XY{KCKF zMPCl7dQwYAk0@||916cHe}y}A{$9MIbMSXAfq4=WyX2NW;bK?tXVL3z5Me{GR z(@s;?R!O^3J)oPCn$wy}-eY5DZivm8?Lr$QUCD+%?n=gCA$iP_N z+uud#l=Ly7l*@d0+aUcqqP(6DW_3fpOMsv3zazp z!Zcl?sR;*=Tr#(rstDCV#lT$dylAPj^+u-kb~m6ki^{B3;Eeyg95H2^&*dGop2%nG z)NT0SSX~UcIUg_RO#8H-E-~wc@(nmN!t#a0sI1QmIcKnVf0=v2t4EV5l9{G(9+0$w z*X^&{8P4`EVAbp%yQExaH zfH_Az{p$eyEP28`NJGwBa)y5ncwEe%`#W~)z1UlJSZ_HT!0wR_JAQAiq#(oD61vg~ zQ+ys(|01dF5l4a~G)H21z^y!iZ2|t0+Ln;utl#FAp3^ij24w@{G%@d>x6Q>nu2&+m zW(SvIq`-eIyi`6_skC3!*86^0Xf6T72U}@@Ke+K$p(i~ z>3A-l;k^-Dg~jV~_E*2^5X;f>`G}@gyqvAVNMVk4y-3e-oH(YD#jo95ru1FkR(p3g zGzyPUR^M;gMw2&f1#&azNi%XFeXrtq=9T46zPJ5%4Ep|Y%Vb^EGINJX*vsHfB$vFBbq%SIEb^7fYSdLdBQZ+mRauaJJL@j?=s5wN}z-P zKDhJmpkQ3a)tHBxXTzqoYf{p3-`Af*?Im-rY=l}7^=)cJAA1?K4ScA>0o&Suakf63 zFML_Iu4{h8L(_u%&2p>SV-e&0w65;D{Bq%quWRb4SXsA>dSgv?x+Y6Umw#KtSeVt~ z{fE{PZbGwFI9qmi;9-T&odr~#FXzQ%x3B%!s=0wD(fj_9`o(}pRJI(+;groR+#xZt zvsrdliff&0I$@}uSiCHls^7T6J+W_{I~kDueoL{v!41ZGp;ISmPKb#t!p&3o#;>@x z&_k$t40q@O6!*kBOAp@ucu;pnV)`EbhlnS}@sjeZ{Nm1zx5w(G%*NjePDWEFj8jqH zo35Ub^YiP-Yu}sl((6s36o4rw8Q69KZvmE|h2I~N`o_oBSp04k5 zd@=ceK~$jv4vKNyJ~3N8d@w10^SA8Dc~jQIUcuU^24zEJhie}^5})y zDu!F7-=dBAGp5jIO&F9vn*E~e>9$6ox{rkg59AKUN4w-WYC7Kj4{z&d5|Dtt5GM5@ zRu##GA~|xu4eGsSEWamjf5XKyxTn(c;Q8fc+GNv!M)6q*aN^8CGsh}-YYb|C@%o%s z_`0ki)BS$OF>P#BJrG{@pj_N(U8WLKKLw`)ek%#7<{ztG4<^B3nvi3Z@!~h8#YaZ< zEZCyH$BAB@-N*+EOq}y9m!Fe0FWjCKE}aW2CQ$51{26qIx}PjsD@xH$%P99??S;=J z!Ut0&2<<~o>k3)tQIC@W??z^f(J$U{cL`Xbt`*vA|H-YS2dYK2feAxn3T69@Z{$C2 z3=F1uvLG!jn<U>?;ob_@w~ee0$SzMygaU zJtXs{u|8uFBAgaLtYem>KGg2EEFb@NU3hLYku_vOHzg+odU=92uU{NrCVj&Z6|=5K zXfP(ND%Oejo!m<2Z-L&Ei9J#mR++C%expc54#9s`vI#EE{P-Seen{OCY4Y9D{IG>{ zbc5p6hlJ)2bOXAwM_mpyjdwKLcHmt=*U)TxEd=K1Xw&t)y*0^)ogRDJj?~eNx@gSs zp?T1Ms?xnLv9W<%9YcqLim>b1`gMqF;e+jA+W&^b>vS zyni%QqJ0VHB=v+cmg(%T3E9@V9R^c7i{za#QubUdJ9{ysilK{TI3vU~ zuMzQ2#B58zUxmmPfsmYs-%(!-vruvOp(VPovV3+C@p3xC!alWNj(G~DpGgs zJ4zS8JijS2#tic~1h+V4ksW)h#&#V!H+SBINRasoLKc_crOTolcLnFmL7ns&+1_R= z;2w&WZ8+JGi%`+KRqW>bzqf}yZ`|fLCUoiW9IxyLwaa*6Pw;aasxum7_CX2X~XUsa+gO1Dc-SoOr z`z?VFvNtc|g|mJ2XCIH-5*;NJtbc5)E`QWmg!u$+akTH>Uo;*%&mBMxhEsx;ecbLj zBszX8ESR>G1mtwpx|s*s1DJ)V+qq5ZYd4gs&2&#LZZ zibO5wGB4tJqFV?L3J>d25w{mtCWBBC_!EGRKQmN5TW`O?X_GK)cC3G;9u;UD=7;=Q z@p>@7?8K|aichklLU+5#N)#N*AN(HW7NsWljsoK194WEo7@8v}T)1iGJs9$e?22h$ z^W={J+$qLcRE`S?>aSg0mBUa|;QN7}VV1HznNqpuhP(97As@x4mR}mr7K=&g zig3XCZuyj2&yul3gY-kZKtQH|m9at6^Bh{>D_{D|O|b z0_Pb|%h&;u6Ky{Dud3O6;RVrFdlam7EDP2NcxgD9Y9CXox`wn;T+bG_6sXMd3_X1Zp^?c z)c{k<(>-ig&$KR+kxWkw`P3NK>fVFz34cX6t7_shcVhSS>q~U?3zDDkY=c5*k;C&P zqWkr~4RenCVN4t53Ly=^3jgvACrvbU|11tkjA||n4V$hdx+zNItESEoA)pFr3R>PL zv^QdMY?-1O_lQ-(^3@!UMtI9&eiD7-K+aKor6+w1qSdS#MN|Pm74O)NhIs^E=Q5*%wo+uz11JC-Na$oD4PO8j>pHn z+rd~z5@ye2933kWo3sdl+_4+~28cLN+r1Gdm=f$wknI7*Z%n9#)LCotZ2Vk2MAJ}g zr8Aa80qD|No=Cwt7g=WxE+q%59vRI;QFLs&p9>ubYV#|MMy#hF@yUJHL z?*01XE&3oa?vP16_vJ4EIC$5Yr?v*m7H0Uvyfdb3!mLxx%aP|zJJz&TF%pE;o*-RJ zto62e=j0QN7tcV5$xjSD{Tz!b5Xm3coBAqeUoJq*R5|@lpJ+Cx^rT?cKq_b0Aby6! zJ=(7FJeEU^AQdZ`K^CPHP&mr=y5C2$sR1*AwR2`IW%r@lv_mgkG3r_-asE8%4XQwf zEO2wQ<6kk(yURaO4S7F% z3sGUdl(bKZVUMX*T>qGlr_qc%v_xo>$Fk;%e-wjN0^FEljTO5d0D{~LQ`uyadaZj& zyp=7}h+Pc3zhotT8P3)av|Jt!JB)gU#K683>73*tDs)eXwd1?C?%=JHMThK8_40Yd zGfFgHC6vy&b&{ z9VPjKQ4DUDS-yO2|GVM`f$Q*=uW1f2(T3<=mGi)B>6%TILO&EN5oReoBjPQ65+M<2 z`<43l@GN{$aZymq|%qWv=;!rjkQ(tx*^xSu2;gYF)07y3^A>W71fbWlq=;(&c+7c-II3f|^Zs;^X7V;sPL<*2vY%msqq& zosPTp*_WHqPwc1t>{Kk(7;-g%h;p7WRUl<1C%zwb#;}GUeV2~qpB4K#;gnq%8dq=( zvrrjEuPF{(j7WxBil)sm{%&N%`wQ=Uo>(Ei_>p&)dEmsV2P*x2RBy3wkH0u|U0UCp z;p{-1&~vTCA{jk@wab&wHvYB!{2Rh5ED=Yaa4&!N3H0y0v@Z+HD-0b1ZKc%}sf~R4 zCXZ@arC5g9O?@`2@JflffiNs@qwXY6m)#+$N5hPz8;`rP%}eCV=Q<5`{KVh` z+63C#>2ZsfDpH&FtoO0S1o>vwZk!Z1^y4?xYwe!ds4rw4#$mgkaM~ozj??-qhqIAO z&B_Z32JSx3oi*xzQ*B#?rvlSbB*(cKXB7nx1*~uRnZ1SkY$O3Zl;U&@J*LlPHGyIS zjg<>L^owmGzvoq}-nZ4Ylo{}l)f*cgSiiqiGSdH3*muXn)plJQy(EH=5M83T=!_a6 zg3*U4qa=FtGNOwhT9iZ?y#_HliC)GKq6E=KFVVY*Uf(14{XFke-rx86&(GkT>pIuo zYpuQZK3{+R@^ZCG*@o#nE9l#}ErE?#<4Pl-BW%n^H*u(TChp0JKCo_zkL=1QMH=lZ zxYSZErJ}e|2PGxFHRI6`_|yJ7wLu&NxCPxsCY^Dl#<%6xACg*1RVawMt71{LnTvV_ z37qhf4YqKf*R}FrmC0_vNfottd}r2);)oMBX|ez%=Cq;>d(H@Zw(O|qCUB{?ojPtw z;pMXBkK*&gVkYmZCEjg}<{ts##xt2T+52>A@e7q(F9iK_eQLPa73tZQ7X-eE1jef4 zZDVC5vh;P=wE9;)(#<`6d&`=IR5vFL@7*IW1Nua&mm6&}i{3zXV)|$beV&2iW}Nq3 z%TaqCOgsD08Bf0c-q^kUo;5&cQ@+bTWIXBj4l#Btn=Ttl)^Iq(38IYJZ3pm7bpeRh zT$_z-Fbee@2-ze32X~n0?iI&|+Y*1Lq*gt=@fL}ThLN5dCY)AS`m(2HsAEP7e@|4< zF}93@L-l2U-$XgAmy4TPX%hwSdy``;oOoYQ8Z5x2!l5GTv3srzSWn^=l01imPf#04 z#M(7G_CUfVuISOM?=>m0RF`CDfhb9c$<(glYo$2rzbq;6PUHsy+}#lPQCJTvS1*nV zw65*IC5p9yMAf(Q&CO`-x-4z9N$0|szx8RhIIKNRyOpygUJV@4jvG&zKJE~o=a@!; zpm|n!snBG`{T}`y>I_b%#7*Tuxk$b6wi2Y&>Tj3r^C62Oi~zi5fm5=Va-PmiygRo& zg?J{pNDU7-bPT&bT76|@@sdr^1!7;AFMKH(a70Pr$-WnqwnyN6c|jpydAqH+Es&ztmM`CAv%1j~b{-sC^wk%exQ7qric0?kl(j#7zc75{Fn_eCv{$#{U5tu-Q%*|zqKX~WA)LtP}h%v$NMOHYTSqPSC=Xn z{|QNckm%X8bkGfQ{VnuQSjtQ-xHutaiXGj*&b?RzJnHX`Z%(%X6Z!p#4l?7Rwhml!DIj5IT%G(e21Si0q{ z%}N~>q4i+6D814H|0b_jl^b}5`^3SFn@w+}c_kdRzkZPB6#f&|lFleQkgiW2=SeNX zA%2A~hyOFxX4t16iX-CK>XJToTLw~jWAhzh?X(lTm{|pG;gd&UbTp+9-Y1Hr8@1TC zICXg}9cr5P=cUj)O<3wc~=Hy zWI(GE0hdByVOhMaC%sN3ICJ!NL-Ox`rq}L7l3$*$K8c{X>n7;A5cQc$l_}+;NY^HG zgair9@f$#q*4#FHlMQ zNP|2do8THeb>vac6>C-B*B*DwmSQ6}8t;H=uhYHLhB%bfXD|z30ZU6TBA~!eUpyB9 z^QjlShBD!<`Src>;ta=F`q2Z!^$E-QRjliZuwPd5MS(w>Nr3@9#-cvtN?eO*)LstWmtxa{c?F359=9%6eNGmD1a5ZLT^8tU2i@1w( z7nFl$Vej5qFZi}$(rJayHuJ^rCMi2UdrzB5r_R%V(r0XnR8od{jx0)>$6gZ@avdKv z9I6<|;GRE1h)6E>ECe@j<-xZ<@rRcesQrAQ-St7*mXgr+rgJVTv!+_GVaGD*2SE@SCin(|-iGk)to(q|oQHBHZ8S!|qidY{uM zFdavN<@_m7a+3u+>tfqQA;*8S;*PryJ%434=K9Kf<SRj4 zrdiRi-0stxH$pu^6>;%sEsa`KVQ>JbTcmr^EUy@3s#oA~3#2H+*lE20 zajdgAbd~O1F(=ZbW6bQ#KUHVS5SRY%ygAKD@eAB14?qwNU6GevyRLmy#{$k_s0%LG z-Qw6hU{g--IME+Vb=SN}7+i!)u~jG#F}a9qCorQzQEn)FvvjVFi3!gsimQ(O67LZ8 zI|%2`@y2m$iF7;YgKCaI*uBfPMSRsm3ppU4;UN*BFSc0HYv|7Nd((<=SGiL5>p znh7Z4{BYMo^n*Zl<5~}U&R6=<$xSciz2oE+?YIdHH)5x>YYZc2Y*ywR0oaE17MmVL zf&%{}$})~;cXgRkFdqca$O_9jv;HF&L5%LN3?|H(@22f7KQ$y!UVRL3PdaBYXJNG0 z$$oGpfTu9gOUK7*ixMb?_6+>#e9}lDdZz}BU;c$Wv5y@F_+>Q|d&l$Hif==`$ZGGe zA`F4x$%&*Obd%V%(_NpONV3*oG`A`n6`b`@*Fo447LaVJOL0cFY1^H|O9Ns+gD3ro zG%$Sc8F}e%c)8i7`^nhGSZ@Iz@y0f}r=syCuRf=kH+>9EBM^y0aT;QoK#PeL9zQtu z!V4bJE@aC^n!MSK%rf;*wK_?OErnhq34=9&u>vxhg(kp;;}LEo4{skIWto=lf%Bo0 zKfJN5BAiJd(k*EP=f9ZmyHsy6q#fl~Oi&`z!((?-m#LBZM7oxY9hGyQ^(S3sz#jf@ z2JO9c{C^}*HjwJ!g93miYsBw_YvcGn=#EkkzWTn@diq-#{xpEoxy$1@BW z&ojOdc>HL#vV?umLe#5UvQKY42U-#k@3**4X>WKioX`6!34=5T9Q$S$tfK+ZF! zbCm?4dt6I0z%E&de6L4z=hRxgYJ2&1b1wQ-IIA$NZe3-zcE)dTwY=^hvgt)tE3=9)1@@||ah(eMM0oVH zlZuTHg8Sq>69`H<-z8sLDip#_Hh3j3E~C$U`wS*JO1!$hg=R=(5?eFtVu%_3yh=&6 zP2tI-t)eT4Wx>x%KQNbD{=z51i3A zjSmo_Ey%&JCI2kWhMMEA&F_}ERB7^$Du*~UI3|yQr62-+-ZAmS1xaLSPg3o zIV~cz#^+v~fqbJbA2Jp8*D-90dVKJ@}#lsc+r#zUDwEuc$%!Jb@6Sn9H+AWL@OU=lpON zNvsO3gJ+v&?1M)kYv-w082pPp^Rk6s=*=bXr2bBdtf#?3doK060H8I={6=02c{VRK zCpRZTwXJ9Xu8t>ISAQRdaY@++68LGaNvY2r3D`$;p4@w45~@-Iedg50XkNy4qXQoI zoOe~@mymk68dhPOc>J$+h6uSDTulKfy{G0fDLiDVKkaYl_;9XRsJf0IzYJAJ(ck=4j22R9k}6zGr&5+u|?dzD}w z?%`4Uklqi{YtQ~biV>70DueI{=?rhPFxY_G*S%CKVz5*z*S7MZkKu&;CkyQ#|5p~8 z+6V`n32-0soydoE&GLGOpJ7bJky@lTPM2yS9oED#tUi?kQ{}*09WHrx6S*P%M+Gt0 zY$CbsKK52ql*TpRx9fEEJzqYid*N3nhE-G8_R}}Rq#pdSh4MI@P{&8oYcXmp?tM?7 zX_5BqXh);(YQ3<}m&B85x0HIwV{vI2rlmh5G$p1a5#kD%m?U(g30Sm& zuv-IB&4ck-PQD_)=JWSl3nZ2wh~j90Ed0KYoh}7}{jH!leFsq^b#rVn4cPn_S683e zpL|!5R>-wqwXe__D)yl|8JjtHZVBkCK_mYg)hAkhi*rH}B{bj4;C5tB) z`;gC8sa?GEL$0XLI9`p8gwyhO_KRODQ_WlOcOCnAfMq32LA=-qdsX!{4q#&`=C+qJ zSP6nBdWtoL$JEsum{rv`K9DidB-46H&v^NiKm#n3pVg~WrxP+Oc5LaVrq7Rm$*qk} zQY`p(r%X1q%PDcQ>%}j&l~>s8_hGR;Lwk6J?qAT1_qbSVhc^CI7{;&M`XjW&bp1+Q z6MD^zU1Y4ErZJ?|sloMk3QHMC87f|&3uXQ3s=}u+!jSoP&&14>ysxw@wgs4?DhK;7 z-FP^gGt($Ld2u*+-{o#J1#==)Q{fRV={6MKAY9dA)mFj@KofxTXKpmh1W5t`A8= z46V^*Efa0#r5<4BVmZel)AbiS6!6!6#_pJF4e~(js8*&*Wpo1Rn^8$Y$Sod}2_p?Y{(1lP)A$OLz?PPqvBZLJ>=Y5I(P8DTp^U z%ZqxG{d_&bH}d2Ci+n6yY$`eE9CL`JcDwOG+#-FMx$yXXvcVl9Sgz)9&x`lIHq(i! z*Tp81*}JS*3cC8i00CmRu`}G)hS%cfQHNp6%$dg%yh#uoS=fE2TnN;V(kPk-c|q6R?9e7xPkX53)gdg(Np#(N8;javE zsc3tv1e7xIUF!v`W|8Mjh6y`u(UI*-D8|6AIp<8qVuI-<++owcXMr)V&&X1Ia|yo# z9)Q7$S@)uw8;G3l`-DX>%aGhDNU>xXPGj@Yy~D1KFXZ^XKlKZD4!d zT>dt|V&O}Ya*3RNOApP8C>9n~ma@VlXp}0>;P1LdcBBG*Hht1g?fK3*=brXGd11W1 z57H7Aj*)t`Xhy9Jmjt0Z>hF)RnT@e}@gp=1B_qbKu5*0Mrt&K zl$sX{Z3(EuevQ885o0$;My|R3xW5Y}qlO(=MYoa1;U7eQqofnEj0@p$0(7817miMm9G*%7Zo>PP`A2BemoFuBE$5Jp5kaOv~| zh}NuzrF{qBMRiqYDh|!z!OH=L4`ehn+Z{D}mx=)I+P$KOwhSQ_Wi(m~1F^++vMK@lUUFV=!&*iDWJ>G2`v?&*UB zR};1u%6jlf6L$1h-wDgFRP$1pJiTCZN-MGBB?f-;&F}vPd&1dC+D;zoBy}~)=@)4& z4?V6_GIMM)y<-LD`)zPt-cI=j)%9no_}B>!*_be_YpMyw6XEsdB>i$ME`n%q#g{*o zDYv7DycAzW6b;eG2#g~=O0N4)))TQ(u;Kyg@HsCbV0i*ZX($9a9Bex>wn&>vMcY{* zKJT+>Gd)y`xyM(okfltZdbpUCqFW#O#30J`>Cw^8@0T%MiQ^5(#}hox_rg2#0B5B! zT_2I&w?RlJennuEA9|cCO|@9|@Gtq{@@2O<4jUD$@MqiwV!&BKEc_C*Tese$f zc!jb1MyFW)CZ(Y#beGjS+z-A+MJe>8=0Hly;tPfsX{c$ zvYvPaM1WmZ=*-_eSdk}XR&|in8d2jpd4q@#HzeAIs9_R9KVEPR+d@^fnu!{*VY3t6 z=lNBZMwq2_J-Z(plU`qe2{E*+-56IFtczoPmsB5^9O#kmNzGf8lbv2gD~RLMcr1$0 z`?@sPzJyW)_E@8U-?=2JbBh@$kP>a+Ak*5dcZzaRXDCPM;(Lz_DqhhDZKe!<1c1Ej z0I-R#<^@8s_r}esK^ZsnoYOEtU%wW-^owfOC;@3|f^_H4Zc@4W;kTW=qc0INV?$q} z0L;N6<7g^uV6tl4^hX5kOhqxE)}vXFgFh?+wuz--#%RJ!oh`T~<`e2@{lfJz(tNe- z8ePgpix4XfNK51?kekFLx_Wjy+34nhd#SLm!uKHM+RcL)F5RegTA8$PacH>form~K zmT-O1Bt6rPeYSy|BO)krbN?a?3lRQ$ce(h6Y5=3xC$tp7a=l7w?$k##JbgOprQyC2 z*Oa<_;+HVuoztAOc%UN`7wt{a9VFejMO;gG7qAR43f)T*kSGQMN7IkK)@eg5de9A4 z(V(G!iX;?jj?WvP-5%sNUYb>?zcEPHU^sQ-I5xP1Me=oLPF`B|D&@(8`++HMEV?oP z5;go=IdIzBc08M_*Zx!Nq|iN>Sm2!|`CwC{Vy8yA%&zPYI41=Ae9}Zy1nM9W(68W)@0@kZNVb#JlEvnGspD0+vpDFL>=U19xlybrY3PH3 zkoSS!=1N5jKzXLT+(H^@3D=_JUTYK>zq_f&38O5IeGBcR1WfgTsnGE_6GOFmR}18A z^$URlgI8{JCJLN8x%uJP7$Eq@wQjpPMlzI;2IyJ7l2H?ULg_y|hq$_~^gYgHO^eXR z>t!14KjqX)4DX>Q$?yIh6xEhwaVP3865Ew89}yrmvG$u0e?9^CeiqvO1)>l)~AE=1He$Ccve)kl9(Q< zKlk;WD(@$6nDNcvBg(249UZT`U-k0w=?RDLDU_^LEqTa^;3{I^wMRZz;6p@&b5sXD&(YR?X(j2rH+gL}i z7Y$T?)FPGf3+t>9{4s!hDW3k>y9$MVNi9axosvkvEADrV@PFuUFg^p8jGS8W4X&nE zF#C!IB1ZbAct23c5Ut3-B6Av9xbuUB+{1k`iv8?LG2Z<47g4cm#VpSJTHe+U9iq=O z42cWVT_ya z`BufthUp9pSbS7N6j^$+5V)V@8o0PAFCU=&M5W8S?u6vUPpZLN8XF^ZQ~X*-%Y+`|R}i$O8ck9IbC#Z?%zr87$far|iMPmKt{H#K9{^Z) z=*ZgxRV_==ZWw$_7nb8rv#7)L6MZFeytF|RWd{(ZCtd^`A;(co6jVz{=5D7w+t+pL zu`|G{v%EL-2<(-{kq>jTwHefu=zxS?Ni3E_*J#ee_?4;_&`q}?oiaYxTC}Ji&`?ae zKB`gY24T2s$y)xchW6;%%ZguLCc!K{80e!oRuywcL2IrOP-y8_o8KuTu8j<~k~`V& zaH}_syB$S^l(vb3_dT*AW;%)@!zt_rWdTw6s6e*zGP0k#CS>g3g~Hqq2fm@oFB@M3 ztgNSR%b^5*{UXZcC_|RFYK?v^2nrCNzJ*5KgFlt=5F!cQcb!vtfwLD-Hp4H5E5A-) z7 z3O<;1u0!@<4U$v&{@e=|$E{JUz^rn?>Z`ImEgiSP9uuJ7bb9?nQIp^IwF{W;4@8aBIkmk~MwP;@r zXLeMV0}+tmz84tB&S>jnlCjoze?9HCO1f~D>bE=OTUz$@{zM+IT7Pe;X;k#k7BEMR zd|t)l;=!+O;ETJf{yxJ>M3~J1I6BrZ_0|{^YUL6PgM)tZJ4GbAYUV%LycN99Ip?gE z0iFK|qmDCU0@814Y1?#8S3nF@vvVoB#GzLW6Bjj+2L@}mC$J22gx#mpG-ak8swmrj znF8m31`H!&{)I46uyv-tEH9TA&3nOk9Y=Lknz*cwitr=V4w@U_vx4IsGY7w}peO5c z4Z`td{`j@7k5Ueej!{ThUx4et{_J;07dNK3MMNhR9~*P zPg0RK#(wUA+lPJn+af1SUp1Z`DlVi;6sxdYI?!f}*q~$pcJfLU<6jRv(vEX>s4W&A zfat>ur~J=_L_ntT`c-43xX^_JgL8ZpV_%|z{JT~J+>4{o4hx7%J3dVSlYVR03C!tE z#2;Aoewt-#(`55u2bG7?7!E=}e3Pxbro(FU9{o-;!2mP5_mub~x1jZv7EoDpIjIFq zU)Q$mID>z%z3|*zCibeS*#fE#u(`wI0|Was)DWADNa!M|PCsnp-XS!>%AZo^9}e?u?kDued5`SZQv}=AuW4X_gkkQ-i12&b4j(iBg zb83|e!srb_Y`I`&Ldyy&8s3Op`EagVKzOGD{EHT$Mviq$Es7RSWee1wVj?`IEfL=c zBqYu9k&gAdXp(?cI9=WHGTy<_XUR6z$w&{*4UUOCci`VO#cjL6D<@PuxEY%-nm$MM zFC2JHQ4h)fr$ksV^+zI9z%bKY^N0{tMUL@`N0yRrBK9Vq(zI+9-bH^Gn>~Nr>B5$O zG<361bT*9nagNce&l6W4Jr`puqj@u;HK0aDMoUYVQAgg4D`<-}WQNF#cEYze)}E1O zYxw*E-I(Ofn}k^0%0Y!4Yn9Msl2w_)=n)Kq6AHtL46~m$)rU3q_h?BzIWM=L$_t^#~zkFrU~x#eWtV3 zc1w0~Ax74prrbh9Hk|finV~HKxK25{Cw(Jb6S+MBI=r-f3&2d}x<5@-lvg0L>!Of2 zL{nVb><#hklasoBg1}fu?2Py^h*`n_>kk|9~>O4 zdJ;`Heo?}sGrIN4sc&tv+QA&KqGxPQTHFO{ciDbN(+K)5thfQ-%>rI4>8~0|%~8#J z31y!2@_k-sTaEW-CqH&&_-uE92n2-8FGyENUfl?#|`46XT#p9@F9 zKV{|Yt!ADEw}FkYIMa%ppYj{4_+p!4-79K4&C)pO1CZ?`Jn;Q}rHKQ#4>SH}4x?qJ zJ8)_?5}@hej};$i_fYATRjVG%!_)k$NM8{%LWheR{VL%Au*76bclT=x1QiK{tXJVA z-TSKz;GF;`8C5j&sUweI9(5~wcb+9$708pI7j3=wgvhRYi~jo4aSRn}Q5FL2*+GrKBT-*5YhDp7D#8|v<$48)VsZ6Lq_~PS}zR-TN4;ZgT0`IAk zMrw0c#rlmp_u){z&J-x{q(o1?n)UNqN_Zyod+5uX@@|%zroC=%WnRpM_@s*%V3kH# z^aEED7YW`;81yo>Kls$8_ty&GXaANTOoBbP90gXRD*y;7I_Y;^!c%OI_6;?RQQqEV z8y*x6+%$EATfM5%^bIr7woaW*vXfhkmz+=+VB+G6m*<@B#vZY3M?)f%%{ui{!Y2QuLszaG=&vdk&qg5g(GZP$Qy}U z;@ayceemq*E6gYT@&p3InWDK(&a-(8ZPkLn(or>`DdHd=R1Exv({xP(_@PJ9G+ zSR*W%&Q@=oMK9+=5#t%v(8JOz4%NX)5sQ`wQXcZ)2%dZZ_WIl)qNe8KU0cep=D zV@Q`XJ{4dH44(npKiFFDLi3MP)v-u!2Taupe46hQ_V<}gnzHU zlK=9`V>5{`n>sAV=8#s7fvfxtxo;K=y_z9zY<70u>!19peOk`!Mvck)qdxuW2HFZz zm9$7h_!0MxczKz?6Iyc%YdKCCAAg7fT@@`d$!(^RR)&fkGnzshuy)|T+sDa5I!;c~ yU`+u1ytn;q%Ec_et?zfW17edD>%YD(hi + + + + + + +MakeBlock Drive Updated: src/MeGasSensor.h Source File + + + + + + + + + + + + + +

+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeGasSensor.h
+
+
+Go to the documentation of this file.
1
+
39#ifndef MeGasSensor_H
+
40#define MeGasSensor_H
+
41
+
42#include <stdint.h>
+
43#include <stdbool.h>
+
44#include <Arduino.h>
+
45#include "MeConfig.h"
+
46
+
47
+
48#ifdef ME_PORT_DEFINED
+
49#include "MePort.h"
+
50#endif // ME_PORT_DEFINED
+
51
+
52#define Gas_Exceeded (0x00)
+
53#define Gas_not_Exceeded (0x01)
+
54
+
60#ifndef ME_PORT_DEFINED
+
61class MeGasSensor
+
62#else // !ME_PORT_DEFINED
+
+
63class MeGasSensor : public MePort
+
64#endif // !ME_PORT_DEFINED
+
65{
+
66public:
+
67#ifdef ME_PORT_DEFINED
+
74 MeGasSensor(void);
+
75
+
81 MeGasSensor(uint8_t port);
+
82#else // ME_PORT_DEFINED
+
91 MeGasSensor(uint8_t digital_pin,uint8_t analog_pin)
+
92#endif // ME_PORT_DEFINED
+
109 void setpin(uint8_t digital_pin,uint8_t analog_pin);
+
110
+
125 uint8_t readDigital(void);
+
126
+
139 int16_t readAnalog(void);
+
140private:
+
141 volatile uint8_t _digital_pin;
+
142 volatile uint8_t _analog_pin;
+
143};
+
+
144#endif
+
145
+
Configuration file of library.
+
Header for MePort.cpp module.
+
Driver for Me gas snesor device.
Definition MeGasSensor.h:65
+
MeGasSensor(void)
Definition MeGasSensor.cpp:49
+
int16_t readAnalog(void)
Definition MeGasSensor.cpp:142
+
uint8_t readDigital(void)
Definition MeGasSensor.cpp:121
+
Port Mapping for RJ25.
Definition MePort.h:128
+
+
+ + + + diff --git a/doc/html/_me_gas_sensor_test_8ino-example.html b/doc/html/_me_gas_sensor_test_8ino-example.html new file mode 100644 index 00000000..07509f1e --- /dev/null +++ b/doc/html/_me_gas_sensor_test_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: MeGasSensorTest.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeGasSensorTest.ino
+
+
+
+
+ + + + diff --git a/doc/html/_me_gyro_8cpp.html b/doc/html/_me_gyro_8cpp.html new file mode 100644 index 00000000..bb6aa248 --- /dev/null +++ b/doc/html/_me_gyro_8cpp.html @@ -0,0 +1,200 @@ + + + + + + + +MakeBlock Drive Updated: src/MeGyro.cpp File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeGyro.cpp File Reference
+
+
+ +

Driver for MeGyro module. +More...

+
#include "MeGyro.h"
+
+Include dependency graph for MeGyro.cpp:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+

Detailed Description

+

Driver for MeGyro module.

+
Author
MakeBlock
+
Version
V1.0.5
+
Date
2018/01/03
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for MeGyro module, It supports MeGyro V1.0 device provided by MakeBlock.
+
Method List:
+
    +
  1. void MeGyro::setpin(uint8_t AD0, uint8_t INT)
  2. +
  3. void MeGyro::begin(void)
  4. +
  5. void MeGyro::update(void)
  6. +
  7. void MeGyro::fast_update(void)
  8. +
  9. uint8_t MeGyro::getDevAddr(void)
  10. +
  11. double MeGyro::getAngleX(void)
  12. +
  13. double MeGyro::getAngleY(void)
  14. +
  15. double MeGyro::getAngleZ(void)
  16. +
  17. double MeGyro::getGyroX(void)
  18. +
  19. double MeGyro::getGyroY(void)
  20. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+ Lawrence         2015/09/02          1.0.0         rebuild the old lib.
+ Lawrence         2015/09/10          1.0.1         Added some comments and macros.
+ Mark Yan         2016/03/09          1.0.2         Add function fast_update.
+ Mark Yan         2016/03/09          1.0.3         Add function getGyroX and getGyroY.
+ Leo lu           2017/04/27          1.0.4         fix issue of z-axis output double. getAngle function just return, do not call update anymore.
+ Mark Yan         2018/01/03          1.0.5         Adjust the initialization sequence to optimize the Z-axis drift.
+
+
+
+ + + + diff --git a/doc/html/_me_gyro_8cpp__incl.map b/doc/html/_me_gyro_8cpp__incl.map new file mode 100644 index 00000000..b59c27ac --- /dev/null +++ b/doc/html/_me_gyro_8cpp__incl.map @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_gyro_8cpp__incl.md5 b/doc/html/_me_gyro_8cpp__incl.md5 new file mode 100644 index 00000000..1a33c802 --- /dev/null +++ b/doc/html/_me_gyro_8cpp__incl.md5 @@ -0,0 +1 @@ +e2b732a8fb292e69d7e8e2dbd7f79e2b \ No newline at end of file diff --git a/doc/html/_me_gyro_8cpp__incl.png b/doc/html/_me_gyro_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..cad6bb5e5e2e8a7ae0d7d2298c9c11763c9e8b28 GIT binary patch literal 48148 zcmeEtbyQZ-*CyQ|oq{0J-3>}A-Q6i2(k&taFD2dGE!{66%}a-LNOw2RMf`m;Yt8!B z%=|ycKV0j2-+Rv4XYXe}dq2kzMR_T76k-%8C@A#z(&EZcP;g#QP|ztz2*49nrqn^; zF9c&5DRHPjPk%C73u2(4UO~MVf2-=Ay1(e*9lO!^=VatU7GE6MvQ~|uu!i}?Bz8b!FKH3Y<09(mCzg0v*BjI?m9Z5B~hQ8}9_+JGulVSamSIaREtl<J`6 zrPT9NajIb2{eO?K`YHbR*ZY&JM}+T${wz+p2ocq<%ZZDd(hi0-K|TG3C>bJrXJgm6 z5ifsqw8yI#&O}Mcj%#Ta`Lr`r2|qYiy>O2~rh3aD;0c=6^T$mKn&!x+e#Muj+vM#s zM*aF_m62{Yw#zH8QR{Z!R9}%JaHOC>hJ%H*!(h9P4a^eFd_dT?zkjEvH*dgY`p(`! zDu0RGRsaVpT6TQk@0NDzUc!c?!Q(C>%kq~W_KUBKspV|y4aXE^=G7koQ%h5Sd|uP1 zkG*B;O2CVYyEWBiI)H`5f}XANtLSm*-P8mzU=`D?nsAvX>oiR!OtCF4rq|kDD7wL> zmDgDuxXW4S6yFMz&S|~g*3)AEEKH~U>-CeV^>+KY%OB@XYfBsjP`z*2uOOTAY>d0_ zZG}8!#l>@382@vanl{O#>wAF(*YTAV?Z{_6oF|((Z+X_v3-4>Nyb!Is>o0!4D{>~KnTd?g zuV!DkpaUOZ)q3{hZ>9tHxdg$L{Qk(OAIj)+-Dt7&?Vm5K{UB~AQfF4!UI!?*Qy5Jx6{|nQAFF@~ zwX$t>pC)Fv?R!U-7p}LNSao=(d;98uPh&Iv=ie5&y13V=h9_v89#lx=yE^;p*uHlHCZPNW zV+cY#ho4?wrr*8FR{_GnlverQQuH4-ejT5s!Zsg*{RiXj!`}FK_eVO$RKWy37 zXG9sGB&~-U-NtOZc;*Ixul`VYUgz&GFMK0nG9IZ#zGO)0eg}R^_54$5c|sL1JIq`P z8wrUN!4JW;?@w#VdWKY|cT=X;uUnIQSIf_@fL)74JOfNW5t)d@mkUw1C)XoIxfZf^?#_-UgUXb#NyH2z;w!hiF6w6BG^k7rBup1{(NH!02lc%7^3Kchq6 zsG)g-SHablOKN!!K9D#;gIm6BA6@FMD@v z(qFbOowTJ7B^(@>0DBe6`sb#Z`-D&zz4&DjCYPVu(u6dCbAL7ZoDcewBTBs3v0^_> z6?$l#otx^aQ`Y#Ef@h&b>*8YS4xaZR$a;Wi?1Y+vyAN2pQn#V6WMBvx69ho~x zhSXUV6+{3jOyVEd!wy6Q$ZJqQBCalay-~t|sagNI+=HD4`ggB6QN9WE_-5jY3YXAt z-^Abkui&iy7x1JZzv`H*UzN9oL@Uf!bN3`b!wf6cuoiRUQ24dS8g zA&lhsnP$xK6_2+&=JESm6-!RUQCxoOK*99#B;yM42X+Z@D(!##;zwQ?e0s~)NwQyt zGNNMRY;Z6hHS$lacL zgwvKdDsM;H5zI_4$&Co{gByvqJ1;9)F4K{{{IeU+<;UcJzC{ItO2fB$Zsldgrz`foY>;pq()<-!SV|xx6#4q>jmod9Zxi=vGbw>R_74r!d!5J`cZ9*R4_5n)8zQF#emACWy$T0zzk_YY z7s9+ZI`@oOgt%UL%{1J-=HlY=I~aBrD7{ZIX8pN}BT50$4&Fc*Wb;j-t@YctDn;FG zb&vr|)nCA$`k(Or1RIH>S$1jJ_skvm1iVYuNi8@`HcIhQX$Qz(@ITZGJ29Y;A zH<0jbzX7TeC9G`Z(wgr1>-Byvy_XJT@Cw`f{Fx9UsaaR$B6wT(7MI%u-{`b-(qgHJ-RrReZp{tcwk!;L(>=00w(cOnk zrJX^2#Azt&1&h315PP}$jiloX z)}^$nv`hHUTdc|a+`*5>CZ#(cGifL(oAaOZ4mA^&7T4M!&AE_-$89RXBBhuf zbDDfm&b*tA9_Nkve8LUh^R`lUN+xe(3tpq2Xyf)15!ai+q&=~d{+-=D${5Bt;GJK;v z{OL~3U{7&&LLiPosQp4M0uv@5w%XFZ?;c^)u;*cCeX$wsfZdFS=F7{7cdxLb?f!W~ zE55?5zMc0>>KR)4ham5ZX`;)O@^lRVfeKC=33&TKBh#_7KV&C!Drq?Ai60CNt+t2Q z6A`){$htI1bFVKxCtccb?yks$j%g2(ln1B zUG?);vqm5;xm?>Dj#a+%y{PWLRG;K>t%-TD&H4(VX3gd)tGox?1x@`wH6Q=w26Q@S zLqq=L<7f;UJ;}pyY&GueKJ==iM;WK; z$Pc&d@+yW_^nf`OOJXF3Byn-q+-INXS8E(UQ>kzyQ-p6Z>A_n(7@Qbu$tA}T9XHa` zA)BzzFs`_g>7d;wqNOLeTe7_wf*L^kFl>pQwhR+yxjIvuQN@!}UL}AF6Vhjx_x#Bv zn#F`IPYw*%Ed=}3yVe_jGW+uwheJ0DJRQE;c9Gu<`$X=Wj8~YyYuREhR|?>y`4|!L zYrov*H$S8!d>@EQKdNxtmVcMYoq8egRWyZrti`gfmBjIek{#|}(RM%|f5WSAVvAH6trmcEPvmEZK%$KbyH>tZ0$sGm$ zu>vwM>kzq=kD8qGb&`4}`MQcnLH3BGb`V|=GMG1$@ER#f>Tbtyq;cX)6*X(}+?=KF zo$cdynWMmOrjdVrF`A-O%pjd%$Q|{11ePo>zj&Z?DMBm#+!@Vxw@1OMz!A$ly)o2H z-e_b67YMUM?`aT+zXA*i`mW##q+6A&f3qUXrdW69#+HQ0mM+w>XMzmM_U?$4Uke#G zP>qD=Ojg0mBBXEhnbn(q3+1_GOtlVp@F($_PuLPNp?+XrY4S z{rR|h?=24tfuV*WS-9qsx3w)2B69T5Qc~Z7Z$5$;d3b=_wvgt!GG6-!20+akkM57c zm2z9SkZ`i3+U-#?>WCx!D?7zxTb3g02xpp{v3pvJqGaywDaID*n6(w zWov~1T&N#X@T?Lrvm441+O|ZnQ^;$u1wxQ-?evFT??lHtlWe|qHjMm->ctdrbxpg1 z9N{ooP7#on!fPC``uU$Zu9*0S@p5ySzkP~xTh}_igQIb>(87%4;I5#$YPTF%5ELpN zvKSxWG9M{+6!f>~nVX zLWna;4*~X@%M`TO1#1*9r{x7aVaB?+BCr;32HWe6O1OsCm(bs*VoJGoi4jAe$O;o% zXrTWI1ui1w`b7liwc+h|p5w~{LvzmNYO7h+$NMK_$PEgU&Uj86{YEE}84`Uigm*AJ z`1q%-vOZBIy8B%!H}}}QSX-0bpYCj_dk#>8gv16LWxPkGy$1wMF?vqG3}D-;DEKD~ zD%>L}tP2t~mpwm^X9eZ>3ymkVn2zES4?}YXQ4D+73hE0DE`|KC!`c!4w_{8F@krzq z?G+rttMQ&09FBvZvf(0bL6M=hM#w!4qlu2zArEXSCRah7=~)cv=aIxi&WSQ!6DNOq ziii&HZ+nQQu^l}E-`yxLXRy9}tl{Y;v+r?tbIpl~>43@kSdUwB@feCG_#B*0(q`jV z*3QL4-(X8%*4N1)mpK=oiU>eKH#Ln)@Ml2Jcc;yxk1YY!>&~eZ^%EK?Y z7GSJfh;49I$UcQfS%uR#cv&dwSrG*U64Y*gd_(jetJH!;_c^1BvNv@U15FZN|2Yz0 zW+}vtfqsnv><5+dvMs5oP4MMU@?+SLDm0qS8`+nZ1^2Z3(Gm19Z3ZZtP-g*=P$ff! z%(N?8yD}3z&KlRO)<)i=WRJ3$LQu(2AbEpRgi2z~gX36u!IvEB8Va>?SaFQ(xzET& z^m{E_7dPlBYn{$3?_*@Wg&^xt26Xo8ZP07;47QxB3E6zS z=8!R^eNNZx(rTQy;%?>e^4$$Q_zv$cRCSgko!;4))raibiDZH&q`F9k$$ddwYHIkBx=nqV&$+`iiq2s7E@rLS zTouaCX=`n6=hD(|n5SY%ga~dS@w!3_3B9O$x+1sv9 z_2v~7Ydg=T3kXf@L^KW7?joKbf*h&FQ z2HRgq8Kg&S^4#`gxR5y+*pP3kD*Tv!OlH8ry_B|3RXUPr{(1d5c&IlKPSC7JL1(30 z;KM#p{gYUY{}I91X~1Lr@)}(@vF$f{syU`+Ue2lnf5Gzi}e4 zDMM1(yRF4~f9e%FXLX!P{@DSQ-4Uur`M))69~7rWl^-ulAf&ggL?<(oiq1l z1Pzb~KCGOI7wM&i^Lga}A1$+AoeAJDzDw(I2=-&U#(`Wiz05k zbIr@K$hT}re4O2(@R^VcwpOW8R4a`DM86h=E6YiEq-ev6Jj>(Le_3WYFAs0ckXh8O zAscEM_MG~lbDgR%6*ioqkC|4;F_z1jYUiuj8=K>JPQ?PlNFilRweVU=^_Xk#+X=2o z1^zTnv-!r+R!#g+jsIQPDDw~nzHxKjgifp;4JX0QyVRYmeSf7&?bBZ8|61BH7M?W3 znTi#o53vqL4nYA{A?VmN;AC?6&81bYMA-S~=M@C3WcYaaBJHP@wF%D0PI;6TezRJU z4X(D5DPtx%yHxWC^o#d5NIqiUztPR^_Km6Sq$-G8-g^Dn$a^fU0w$R7zMh1KD!?auKPDL zMpjsyS*`+1m6m>O3;b#2EJRtx-1@MsDRT*R8Qp!@C^Aj=Qoc9}b2~7}R9h>pR}$B; zxI+RQ0**P|EgG{ zMHdxb!3wS*f|I~Uq|AW1X{xolp31_veHE;aasDwl6Z@++kPPIF3w;?d5dwUg;6kXQ zRCf287K`lHSoc=)gC0KfA;(!#UY@*q_lMWJb5zd7>h4RoxF(DeRY9`*5c*7>Wz(tb zUzc{dL4#2_e`APh5MYYOtdTOv4U=i@tM^jIO-uu>FaHwv%@ZhAZY0`ab=YlL2B7*0 zG)ohnZObzMVBGY;ox;^Ws@67nRUd^KP#plJ`GR<6QQMe=l3DI{49KGNvz=e;UZPg0 ziGGKFP8B~kfa5HOzGUB$YUb0BtXecVgl)5Dlzh#~F3o1!A?w9G&t>{SEe??+VgnD< zx_p&+a=R(#Z8>HmBcYg#X0&m2gT#BW8vK+#j3;}*|f)5yj|piUagb9=$N zwO<)$&ETK{)Tp7w%+XIrPTWu6$P67CklTf6En_PII56i^wY*9j`1)h}ONqORa3h;N z_}_wN&b^;reTXf36D%VW3#!V&-CV4LQk9GRe*!`!w`EEv>{aZWAmdG z&t(x?=-Hi#RMj>*Zr6DyR_HTdG+4R!xhVbFv-TLLAz9cuUP(zwN(-au0{Uh`E6T6P zXG0xbvb)<}I%-ksCExjzV}+f#tjK`*Im(4I{pX7Nr}15E*&Wo%j$7Jm9W+s>i9v3( z+`JfdS4>|0Msdk+F>RmEnLRgqDe{bPW=++1Bj$0*?9xzK zx@nox%q02Wl4Pvq;0}tKk+wFU)*5>!Vn9+v@Kf9B@tf2Od2Drt*L>br_Om7$`P@)Z+-jLJ11ev@)$u$V#7+bvu z5_*DcIK#j8NN$4b_Fy&HmX6ZZ#tv=zxgTOVqHiK??O;wh4G9ncPHyFJ%nGq{YDzP& z$4T%meEsXM&O=~X8qZo=d>Vu_G&bJ5s+FI6`-O|Cuwt1QuYlZm5oS@PS6j9v&+2Rq zi?|*qvrH*}|dSi$4)%}f^_H{iE}MGX%DI)a2LzSlnU zVBvd0Yu6_2$whkNU;CAaP?8K3B#RBXbzcM~1>60e+4fGrr<`?iSe%6-mn|LG-Rsj! z@^Zg@hX4T!pl%eOd}F5L5on+#u-Jy>@{%%1xpAnsCdhj@wK^bSs6ja^(zNRzaAC}Y zsbPYl*;eFMv@(;6h;C8Yz|I4K?Wi4O#PZnr`{o?YlC;sKgRmQK|tZ&+!*|Y{VSUA}gqP1aE%Fq%BqaO-H#n z^S7rpH4a>o!VbT--}&;tsFzEv@4Rxa4>Ewofi;=?{P9wndn<$UqcV2^Ni0Ahso#7! z;9CLRy#Mpo(wo3StEGe7wV}neNeI`)hy6S^(!n66Z4v#2{jn5V#QaZ{vxRGaKGgO1 zkXi(hX7eVY+Jg?CtHt_1p%5&+AfYs-f+qo&Fsl?@^5by z1b4h@ZOoFo;DY;6Kl~s$2gEh}SZ$T;Zu4emLCFD-h$@xOuLZ>WZ-v$|S!DoXV=QXN zn?yi=bxiHT*$DUTioaLtx@+uCEr|Oo6n}J1xTRp*x=TMCG;uipyfcmKqNi6Rd+VDu zwhcjA!Kpp?Gsi+HCVTM73-{VoVq9eX_(2oYyZ+u_cJ9N}LG`}9(hQB*NFgN#rcpgJ zi-WRxO=C=?t-+U5j2?dHOFzfSsvL}m_R<4M$os!OYTB0qln+0(8&adfNcE9Ylei|z zgm;@<^Rve=<@p93>gwv8vV})Oq~(ehHPp9cLM5H3A$T`8-c{Kh6(5nWS6{xlbe+8D zAC3MTvNMsX9dLhu$yMrcZFrqQ?W2R0o-fq-e-L(Yr92};7bJGdI z_`cG2BN7SWM43P*C^_SNZB#4t>`Iel0_UZ#D1LMn)1tse-4Fiu=E85ziw)V}B!jVS z4VyV}%7+H&cJ?j@-_KRkV(F1YBlZhJa}w1Di-p!C^nc-|FACTGSizpv*M=1mo}vuz z?Y3$k%)t<8~s{s+ZGFo>fgoQNxr z8|cMOle*Y0V%eXoEEe@%4{sZJ+X1V_c9Cl}dJ-1bUD6hBW&9$TzN6Pp9I%97ryQ_O z8D#(tFc|X~^OTd7W~i}i12OmuCo1kt?$ZUQfkGRIYpQ~$Tp21^v5?$r;E%HMV>pE` zyRMr!yS%JcPKpN6sAo@Xo_1xPeY;m zU$@`3NRP}#h?4zUO-&1l3Lqo~xL>^&S9{QV9p$}?45AXvF#)*vcAoZ^?Dz9+p!*W` za3RnLF!rPJ)p~vvB6raf!c(|41IG~>0BwX?AaBsktFJWNUEbCCw6CM2L@c|tv^6(* z`dXYFXih+S_T-o-VdZXlFN;qR+UG%gNH=1FJ8t>Px=lc$B6abh6q<5`A8B&gTXJ50 zi}wtT-hJ^fkMOf_Ewc88oHvI)nc*9rBtWBe6Y99r?tAO>9&a`@*?*#UC`d5hDGHGl3Rh6D&X~T zU=C5zhEHeak7le0LO`Rta+TNDt|wtQNlzs?<*h=m8dod2JiqnmLX4v)e?jNVewPqz z9a8H&!gXyPW}rb50!U5(nozcmErN5a_tgv~Y4( ziZ&D~R_3!NN;8}Cy7RHoUnj?b542BuV18# zi<0qWcv8;*4VJmuXe7JdHar@fPhewAlK4m#P zZ=<%3+ISpLdMtyZF*GRvMvYJjy(Ix62tePoIVRlG(b2p*Y;F;p6_e{n4j=NHuFQXnK)x<~tc{*X=+-)5VhPJVZc@PuJ>*SG_rfhMos1M}~P@%cLLTzgD6SGgM>VM_JB#1|M& zgfGFCn1q4OxR4^d{Yb3bu1r5DmWH#>MAk3$zwxoWIPL7I*Qy6{)bQqB%mOfZ7=8TR zQEPaHF(ZThF}%$N_C+>!Nc>;qBzgffDH$$^XOgSh1$f+1mlb}`1_y;A{K@XJ<#mf> zrb=JJpcrS^!JLrWnZJ9|Ky*@Jy9iB&c?o$539VV-d3iZ6sSqS2zMSO#L3fANwC-^p z^+knAm*LsM+fg3I^@8VRT3RtPzmI(!l25L@oGuDq)cznMn_DCd}T^7> z!BxB&P#AEh%5*@b#0A=NcqDivf`c9b4wd|urx5$`oBa7~Aj&(`uaO}>c;WhYcA*uU z@5FqfJDzWTh#Tt|kU2woJvvu&=f)QV$KE_u8-HNRi>k;UQ9459SU?4x|n*qA=&{gKaVW7Tme3yH0|fB8|pEskc30@#B#OyNta(j8$Wuchohsqlb0rdgc|*Q49kp3eCSBc@gz)ip0~B$76o zmRs41^gqHuuaSDwK(^Q9_vF^?iq3;f0)FjIqEA9Y)JXsv_m?#=(Gf&*?hb)yG_<+{ zRGT$MDyp(wimp%l!e zOHUW%b}J&sM)i2%?pvbdDHYPXn0B)sUXysXk-X#Trm#701d<6LZ%~P;$NZDNG(Jgl z7Nfr}pVXyAXcA!VjF07@BNx&-I&*?p{WSG#80>pTLW=bv!eBON3sP2gpI;1zoJnJ# z`e0EEIja{!4XOZTMQ8FxzgAem#AmNJ|N6kS+a&H3{mc&=4tzZ3{4$sKkB8^55Bn}~ z3V|e}RK>*DK}bN%VaHS@BB`e$1&{|;fFh$nR1I;TukzIMhPQq!)&a!P*P+*+JMu)? zAYE{}Q}ZSX>zLO8-R>{e-z<05oMWvwt2Pcvl!er)MW zQav#Yx-0#wU^xjwn{9d{&!TQAfh4Nb4~qfq#mqQemknt5rLaZd;(Yc$S$f>F7F3LF z`)!ulAD$1D+!?j$Kv?pW?O+{aTtw*g`YZU)IsQJ+ zB4k|!oHkyd+LPEc$Ia=GI-5wxD=s9*y?gQ74K%lyhQopzLX_@|OV;>n)HS zzMg-GHREL)v9LP8)ge)10+weJW&B}#=tHnzm&3Ft7(4Z6bMSpu1$p77@XFmLeCm2n zkmyjj&dc(~+HUT1vxU%&$E?cmWq8TGX~Gz|JB84AOB1vrADmpn&cOQzpeI>l2 zj`PHegrY(mmw6QKLM$?%f!h!P^#ONm_~Fc%Sq1YeUyA`sN*%X`l=^!3S`$esKN1uP zZEsYHkp5|Fgl)ZO5BvqQ87eIZ)#aw8N92c@+^p5cSk*VbV$3r=UquLIFYR_g>ovZsZmM*B?Ql z2qNrX&W5kqkH7NO|1M|{#?eUyl9upWFv=^DxV4y8zPOLRfeBwEon-p@mTaW<2A(=J zcA~XiL|`7AJXf{+o1=p7y@!y=i{{tp~7ttI5I%o z#vU>vzP_pVWJb&NPdshncPMdOo0E->1?r;ba!)%=4cQ?R{aIu0ESP$^tdQcM?gcKk zod@H`jta&;dJonCH}{SY2sKj9@Kz!;8MZ7La{k@qiYD6wbV)$bo!|!j8JI-;(_yUN z>c@`MK)#+et3GghCf1M9n>_+^39H|6-6|l1GOw9hgwQ#!3eqFf))DHWX`GXUh z-}^CJo^B&l`kR4$&AorHFwhT>Jis`&CDGRUaHuTGr=HO_cBbrkC8_nAp%<2habN+<*zufislBu#hN1d7w>lSuR`%VjZZpIrN5^e zMkLXn=^0EHfO_jW%LDC!aSGfRHf;(z;3W4?#EZUUkLkH7YU_@I5H65%kx}H$IcZc z5!!1o7hZL`!Pp@{C{e>x+yDmLI>b9HwrNO;*|G|01;4D#6BJbSTQ(m|-FOV>RHya; z=Z^A0R@T9Y{!HKxD_DV2ry!}?gYr9i;(J*hJLpH6WnR6bH0i5nn7jHfrJbnw?K=Ld0oG#R^Uh^~Z1_tBPod)v z*^`@QRzr3WFN)*W9Qbx~-5z1)^V2qv<)m}0-v*x&tq*h}reWQhovjZ(-N{T|pyNI1 zFEWmw5mPN8$l$TudOstP^+FwHcTWFK# zy8Vj-Q%`R|voam?!7$q_U)SPVxGpSE{@U3VF>N2JRC@qxx3O;`bt39P2Ga+VEG-P_ zg_-Nnlbrpz(6n<~uO^(pd2@Lu8(|QAu7)xA_byiNL4^CbOn|{kDFpL+K~&p^Rb=Pq zVQk}x*<3v_7i@j+%4OE9GsA}`d5HdJZ$Kmo>5&5?a3OSJB@!bND$)+wBUhx}7DLiG z{toeUzJcT#uIDBMyCl4cIyyl1?^OUOz+Fzy8nJnCuJv9VPr*;@k0{OH}y0D>rg%Yx4AVYsk~gQHv5E1cT8JH z+Mki7wBTMfbxhJf=>oq*ljG&4e+;Nc!N6;YXDai@)WAclys&(4kq;d!XX?0GfQ1K* z1t0w;EooX^R2e_ZmVE;MGZKC!9!i~m-}GnNSD&Ka3@)7Ay~g>*=HixMZI0N zt?l<9T=Ed?aJ4@B;QRZBSS=q1Oou|SR#lYXiUxCQW9C~K5j0k;JQQ9$2i*8jcDF7` zvc8})%OLtD)q3Z7UiB5;ppzt9_cB_A)lsU^8egHoO@+9~d&m^aYOXxqH&})E8l{by zBTW;hBs?!*4~g$CJ{qKFK?Bi+2q>fVPfSsK|S zRBaE#MA9){I5B$qsqyUEL9gnr=!&W)PE2>YI2ZJ#`2NOuzsm*AL$Nro<+rMY=oISI z;hv-;;h4PDT9W`h7Tbq?Xty` z?p{a@N$Ln;o;s+BGhv6{$O&K*C8_*A6#BM4wio5V&8S%BCv=EQoT(WA}=kRNdIL&e<0)kA7li2OaOw+0c%Wmf;>UVw!B<3?kSVMClz{ zLfsczaSW1Db+?=`yKj6E`iblPA_aOoqHw|Sl(=;AJ)}QT*XSo1;8FSh;v}CeTpEaZ zW#Xv6$Y4`w?YQYTW_w24kt0Q68^!LO!eU)+OjK=?BQdIICaRMqs!&wiq#P7lZdn3j_jL|r$=xv^ZpttG4h_0-Jc@0AAp1BE`srySTBKp- z9E2T!Jy(Fwq^Q~C2phSnOdgZGp`Gd*Tv6zd1U90LTz9bbrbK;McsETkS4dENEE9WH zeX_SG5vhzH< zpkB;wOhR%%uB?71CfaDF9(4cfXn|i`nOHIedO0HacT;J%?CuTtYMtW7hIyn?E26qc-g`p&SONJ5b`tx^2MjfvfL2FV}=V=lg8z{Z#jh1T6eQc3yR^_ zGps{ej)dQ!(E@qJf%{LQyoGhx5Q_l>nC3o1T_MTV#X~*m($x&&(p0->(z-#SE@9Ps zg;Yby2(uZ^oW(Yyu8G$)r|mLL`jcW!`Tbq|h**GnfJpJ^N==pJG}TSY$Va;$mVsnh z810BlwD|O>H-D~VjjI0!Z;XX`?x&iZdpKTHcgcfe+O!l_A4Q1{gaQ z{$p???7&MDzuAU>qQ+U#dcY$#Xt%-wUa&xPj$>^)sYY zy{2oG)4Tkj+IR8`BtV$dGt85-&}{U2Rk!5`!3uz&CaU40UG|r&v@1ethwz(k-U$k) zhH2jvn+Mp%FdKVsUagxN%EW3+8c{Hx1)rVa%k3N%Qw6Nmh&e#SJ^GJQLH*nemp}xt zd1U9XM51UwSu2(^*0c%M%4yeZnnXlhMsMTzi-}(oZk&{xjCF;3W+S=5UcuL8%^jKd z=(&7sx@UJd`-(ofVP*6xc`^ofv&6xgl9s?sz?Z7%iorV;sh{Xqgb?9aYHA7+2RUC*I2ec5{{Iz$MzWvYyg%hOzJz!tJztU-bP_fa%K@v;W)$XiqmqA;5%j z>j@Npa91LHznkG-utw3yJ70y!@O^TGj?v)@R{3#Ux471!o4lB2p5wQbzrO<)g z$X5QuJ#_|(u7`vgB^?H={IK^va!Zy&eP>!%k>&RtM{aW7Ii)uKl6T5apkMcI{XN;? zo~bD9P#B7DvIgRAgoz4(lUq_BQW|e_0{&~vS9z1M_h)z4R35Dby}>G;0krLKzWA8^ z_0@51_RN-};{b8Nxn{0R0OI(1r!@1v|7hVBTdUNd`^_7NBZvZPS4F25Rgs@mNH4?h z0^e@((lh+s_%ew}22#3#bIqWIEjM}n!ZJ0B;Z;(2S)5gC@FuOow=Uf)lfzx@D6YoW zsgqSOYP1Govtq080nPpb03tLm-(2Js>&r;Sa!9SHDixdHIVCLf5yhaZ?*nPfbwNQp?Q3zU@tq=eo;r`8#d ztGvHHOAVtd?j@3S>+j&Ar>K9-SL@r)`A!dwkxXx3$CvweIF$>~wxFS>I@G`jR8y-6 zICb)c(Z$duz&uS`tur%!Rh&}8INFH}=8TPj(l9Ebb>^}89q@S1Na80>a*o6Uo)PCm zpT%%j4iXS=d`)oo&F7t3c37i&oQzr{r4oh6nZO&9mSNr5AS3KM2Jc=PlX5R`!g8I00kvfng=QFI zK)c;}AbyCdLj^9MffS}xZPoWZ2aP_R!d+U%&eBZEr?7bQ;+j^9D}n$XtW8V*Um?h+ zq02WecyhaFL0aJOlUE7aZ^wQ!JVO;9bL!*?OgmIhA-jOV?WuUeuIt1NCD8D#mDRSk!jdUR;dtdO2f;{nzKV-t3NqTDl2 zqLz~Qe#`fzM5!1qzW8|9UGZ_(O+Rp|qH6oC7Mtn``w{nY1uF!L+M@ZFV?N#X&iGQW znO|(LV*@u?Ec~w_6IwG#t3S}!!Q41QarsTrx#`gN=3NK_PCM`$`A8y}uW2{r1CXwHNPlvHnQyM_JB%xO!lKsiz-; z#4QPPsPO+%JH%S87huWhK@p~2eg>+3HUs-{CT-zOWxTes<6>~$NfhI$Kt;#4HKXT8 zqVRf9!XGr31!?7a7-D}t3FIF7-@mdV#$t|P`QLp&hE0IUfIpOMu;V4zg~~>6s^%9& zDP{S%K3FdwfAs(<5^GRm!CAd`mv+4nNXVM3bv)aqxwfNdf7SXwO9psaWlfkN7ORc) zciWDfq(LMu`|%B1)LTcS4>E1=6uR z76mqkscmInq14CgeRli@aYK<6*dS^t%}m=|Pm-{uBi_N2=}YR1?b_9x8Vlv+1YMNk$jB`A-3ySQkJ&JtiFeEH}&LnmsH;; z4PXqu1^=dPcRqPXRiv~sQ!J=C+4D<%(m(kP{|~0&_o8v4NY_yAFN_|yv5A8xj)vcz zJQ1?IppV5s^AM+jyn&hQd%^t>!(3r+Q6*FsTP2sp?Jt|9#4OWizJw^Qa%-mM3%y@3 zu%FG{#-m$D^N9n$mC&77lRv6z`vHK(Hya!GY_C!mUBo@86Ml-ySToQJrBT{rs4b+6 zlU#@rv{7{a0^emX=%;S>=xX1LlXH-8CE_2t#P(OAc;v31aS(sf>CHl>l`r7qCh%Gl z|L%$TnFMn{71-1V(<)yjy+a&#h8HW{O*p1N@@7UnY?ywk+xo1{PLKmsO_atbZcWp*GO{Y^UqDUOOY;4>r6VSyo&OE^_)Pl1qd z;678@>%u3#tmr#FmLRpVrbVH(;iliZW5jqXfE0;l#dr%PL2~g9&rbY0IG0aQoz7m= zOH6|RKj;4SsASO0&mRssWZ@1$U@ELfl>b53TL#6|L|vn3AP_8gfFVe5cZWa-?(PuW z-915q2Y2_u-C+X3Ex}y^1R30&d*FHB@4HpE?jNeCnlsan0v}%ofBX8XQr!dZqB!CK8xbPBmy!rmM2e+EaU}?bM)3@)@tO8(G z3~zG3X{9eOq82k0k)L^E*XI1~jaR(gpL^CS3LC_FxT-cL310NJ$(8(VUfX}aU^&s% z6Ca~jDuC*J5GyNs19G^gmP@9tb>N9PLZfyqudnKRDxYUEn0oSK1Rj~%^{a^TPpqx+6HJLW+ulwzpH%q9f_L*WUfCd( z!~DZVbzjCyX!4aGcVVkj!jM4~j=Q|OC39?HQ>Rrh;g5O2#WJc=c1r`hHxtLpI8^`T zYB3u2kI-?NKoNRx7d<`Y#R75rdQ7)O($@$9q+4HJ&>A(o4qO$u_LHGy&i7td>VaFE zZCuMKdR!}UWSIB$dF`du6*L&d!zl|#iJaiKa*p3<20I%uOuXbWa)$~bStw}H!wUBv ztbceRl2kY&B!Yjfk&6FMo>*`}Ey}&*TJX5c7(Zf^zY@3~hX2S2V!+}@<@Xg5U z9*TY&#%a9yV10OsAwp&r5+1@i*_^>(Pt(GsZSi;ycAnS-(6>|UHH!p9l;jU|o4q#w ze$1Xa{ksb>Ggq}`-b_lCr4=iUo415G`(BY zP~Xrx4&HK%$Zl#;?|L@_#dEYR5>>@adPX7eLD6mkukzjR@KL#_E=}t2;ct*~4@ss0 zbzS3-xc_o2nc{MRX`mShYaMf1L0zJGmjek`tWM`wj1m|J53fa6SA&)rgG=2u9rk|A)t<_v70F@-AbjbfxOJQM(!PWu}I2Y4)DqWQ)SwZ8%r3i*j zHvxI5sy1EgX~br#M|Yi;@yqy&MBr0f3at7T#SJ!7sGCZ;b??@tM`4HJffPV?!;aNl zQ==VljyvhDV9wr>fsSm6bT7Uv)32R!2f2bX;*h0OF4>shWKyZ>W7LN!wwW}=cl|5jbB#5_I7)yUsEGo?9m*O zQFW+AYZpa8{EUU!wCd5HQpktGAa)Rc9FSuWVzgLo@oQnfGO0auOAlO{gRN?g?)yK( zJaxtR@SMX9JP+tyVmx88xuKUU!dJawPF@^^8>%hHJn&ntLFsT6BSW)Fv#|wsi0!Wv zE*wkfbmNc*nd^Sc1eoamSWag$J=3L=Hv>wrJzl8uABDrMO5J{=rSh;-S#@lp5UZpe zrd$1UrA_ZY{jt-?zQ+$XpcZxV zn;qAfwwAg6qzuAsvS8x|}y z4RWsN0#ciB6aEV3DMBPxG(9mB&1Lm95=R-+NFyw9Z6EWcMDys-+HG2jVBw zkR_Or3e-UznAn2OueILA)>Sm_NDJRLtsUp=V_yjpgd$WYLvU-}H<@g7qElb!2I{D` za43;+dytH$ONcOO8|JO;NlJ5*Jqu1ail4rETA}ma9(o@TW+rj$FHcn{*&V2F<%y|*w6o{ z$a`_324$m<3iMulQV~v4<)U`)EFxv&hgy&++RCjQag~X~uzs(8LWiX>RzQc~--$ z;0|ag8VLsO&QFc7;^YEvbPwH)4?908^I@0{dq`57f3gP=qAC#4@y||CSji_5f*Ef z43etJVK@P9Fn#EMZqUT5O@K-w=AGH(g3-s$G2}yPnaq? zhGmJnw3McGl}b!Jaj3LyAS_RnS{7y$n6(tg4v2v3_R5hbv6Gff@OQbo-lHPHwJ>@; zq}ggOa{oF|J&3gL>uG%M9lDc>neNRnN*l^kgLXNxg>vXHHnwR?4DF>3WhqA4sdAp^ z*a<(rut}qpyjW@}x=#2+-_r`T0>yRN)}8}i1t5~K6rMVX6<)jyQRK+0QK6d)|I7EV;S3Xcj+#u}C7?zGSBu;Z zZrOm#ucPjOU{YCiCIPT*+{138V!!i}7TyB~6@w1%kTOYWQUp<&-qgS9Sk=-&=`&U4 zEBB?RN(wQVe{vT2&@tfeeoN#Q$6rkp?k5~Y`Q=A>g+m=;XeJ!>aO0vKOe?E4cj@A$ z@B{gQ9~nB*y;pr^!&{N~DX>0?m#h5U#lc_jlf^a?PwVZa{soRm9;*6Bt9=v?v!8=- z-=@8_c*Q)~1bu~t*GlT#m`t%yw%1@{!W)6phX6;MS|)}T8Ti+A_i`jYD%F4$iX8g5z80X%PPH|W}&2E@0f?BwMtaM4B97gqrHIV|C2m_642k`N@)^C%3BzJV@^{}HpxA(SN9PG9*_m$b5e=i5AxmiXT{QdSaAT?%9z*w6%FZyIKwRHd$|2tcT+tWU6Fgw zWd3J`qWs8s(Z3HYk#MFdr|f>rRo9J+F*u5ht;#Dct>v{Mx;#;)34GD81XD5GQNbjK z7vXSOnR8EGIfMI3)TLje6LgAP)t-Q8oOOX0p9ds69LDvIgoiUIbab@B% zrisL3*!9L-hp1{SliX8B;5*fY3`z`mxCh;b8Gwz~nUjX5>h>KK4x;3gG7n?a_@h9& zrOT+0=B%y|;lYcW_uJ+qHf@~k{H9EWZt42^Jl~uM2F{*dHY{|Lw(5*Q^-scK<&YS} zYu5DdzO-k5ndT(^j(l$~1NM62=mdhl8ttflFPmBQ3#TYj*v@bsi>-u4U-Dyg?P6`q znna8rf{9lBMzyYPp@(T()|oLY2ac{%U1PgEf3utx&Ba^LY2q*YhAZIS^DJC(G1=Oh zx+wI9E!wpmNcKC1EIVHv{_{S(Uct-e_c-@f5NOw0y!A6M)(D4V_G|o$gHKEAl)lRB zB)p=S^tkrGsYC4J-WueO=6bf3Zr57cUS7_?k+6Nf5V4q{sI_uCHq2k{|F4&fZws83 zmZm1=QVE+nUlQ8Vtpb}oKCL!1?6>)ww8bI2z%hfnNnjs>_JNQI_x{8X*>MZMY zRI3gQNc5T})2ur~>QtfXbdV#=4@VOR!)e9=6l8d+V(2677Zjv~ zi8LKe@kcv{fzjKx?VuQsV>6`pB!;&lk6w7TrmOx!*TUIP>r-NWEUGQ8>gwuT+GqDHs;+;ufbUiqVgj^x^xi2q|2 z(ya}GzJ><3fm+v6PjXC+wXlURp7%f10c&7qu=e%};2{4HsQVbx0>EsKSlM#XtSFAX zQsk&u9Ok~o{+~qg?Emc*19aX^%rV~L_o2%kW;dr>BWauw^B+B(a$?W`iKRYLX`!z~ zu)UyJ&JNcuezV%WOi(Fxl zLr8j0;f-zX3Uvz=(UmRP(+Y_d{DYv7dw4sc?eEun)#W4WSNI$j!5WL@e{oM0IZC%_ ze)UNCl3~ROp(^*8L~vSgy@;&8q-q`A6lca#DaU)M2cdr3#*xfH%i;tMF$~7Cei3Rz zM7tb`5HeDpk;__EPX@|5L_7TN8q5>p-njiKfweDP3*$(_EL}H^2H>B6{-eM*l^$~j zf+fSB&e)Rb(D31g;bB1;Kw^H*7?1z=lAz`1a-MSd;p@bAC#>UdskE8fJYxGrP3AF`M5`Revc(Yn6k( z)8GSeYPpQ3?>zLSCIM>a@kTYjh)(+Rza8o9`a*8ORVX$csXbNgk+`Ts%P8E)OMkbd z$&GLS17um4yS~Tb1_nom*U>S#^`+Y+dp;p;%WjJmi%){8+YBy(daFP6uhxBRmoICe zqu%9fi~v|PB^f_)@T+VaDn2r0xxMu~+Pyu$YV~yVbzbL9CrN04xCC1Q%G|nXd7kYx z`f+(tX_Zz^x;HS5S^vpt=3aC`Z;F2BgR_0!s09{6J>^zkog&>?S9Nf0ZjZQs>%e>H znDH#^;5~yjH2l5I9CBdE@B=xMh3ZaRc;Rf0-(iM@QkFWPI>@-@AO3rpd``?Y7sGy+ z*W4b!0=GyiOx@2Lq|vz(dV)_=L3(Xo|)5%TxeO|Yn#0DjP%2g}HvdOSj~ zW0_j-X?b>hqUc`0Em^|8#+!fK(0OOfq21n_?Z>w3`&DQA*^=VzhOYjLi=)7Q@r-B1 zLlSuzuYGcTDDk}r=>a7arRlqqPP5Y030o4Yp4Lkj_lV0iUELt&=>8(Q$`vQVi%tNI zGC2^G4RsrCXJ0z`a}w&=-`1PC%6aHx=4q;+ za3$prV*h=1bp_gIim7Dn7|8948I^eG04?txyt}x1d^h6Dlj2j$2=vs$PgN2~X91a5 zzwb73xG5m{Q**vq3*PfekNu})sbr$Q7p&MD{EV(I#I<_&aDFBJ*`VKcXy&WWN)n6e zEH_dAzwi;%qRfGf8mOQkbEW}}J7f8qf*m&1aqrnP6X*(2^i{>Im-iTwcgJmOs8=g~ zC>v5$`Rc$lgx*$^1f12Oa#kj7={AwU)J<@u*Lk2uY}`tB$`1=P^|5FG%3*>rl~Q(KhXCkerH@94j}CLe%}UXMKDhw-pkT2x+7Ejy+6RCpV6Xs=kb- zQTn5D?diWAl(^|V9KWB+-sVg`6k{GiABqRyd$`jksj|_#@)mgR}Oy$UT*F(9#yUyEAVcP`YuLvR!$pMezf1-KRV-^ zyK~?XG=J8&d!!zO1Jk>s_~@0$n7weH|Ar7M|ecmhSYw|92vW&5-=lJ7^Y&7;=p zvd(44cOK@;dD{3p??7wdJ!LzWntTaITn}{Kmc{PabV5mIb zSyON)Bsb-VFi!of<_Bl2nn5F@bH0 zDl7I0$4(1H6bJOZ4;tFNL3*J_FrlNm`v>YwFbPla;X`mfi)Wfe?_Vw-@h=5zIsj~C zPMeq{r|sa&m_j`KvnsH3)DFY~&MS=bU_ zoZRX2{c3&4`$s4np9tgeE@6PKb;9)CaWlMYqKh-DukqV!vwZRD~AX-!V^b{~NhkE+hgcTLOsp@wJ?-qgRxt?TWU`RrA8am=@d61Bn-t%U%D zRQ}6zJs6*ciD^u_Tz6t(BJROndtPV#q`aR5F4!x3GtCCzVE5kcC8p3T5A%~B0=RZl zq2kx*YnC-g5GB9AD1)g{UUTIrH+8covPLgS>J9vQZ!3k}9UX}wF$>iL6B0}zTm?i1 zjy}MEygUg;p_gi)i;L6FH9m=Vl(^#P(YDQh*|Yxtcma}+&ey$}IRyG;WM=I4JiW=q z3!}ZSN4|Mp9UTot49*I^W^>ve-|>sTa(X1zDcx<%t}^GBXYmIYgwlnk6&(Huk%E}4 zAsDhJ;3A{G^!4u)d-rTUOG`vJRY6vw9cIdN7|zM%|5H87A&G#Z>_an7qF>I>H`EIr zf%y!FLAR8Ie2PilNI8@ur`jPYOp1JL!#5h}Of~5Ij7JCU|0D>Z3gDtjPeC<-jj0s0 z8sVe}VD1aPtU>=5l$RZZ4~@=?6eH{@rgytUB+fy+=07NNRi`OePEM?&-y&glN===5 z&`XJALtK}{N>c)9XwooU_0esiG5>XY;gc5-uh$Mv`v{&Z!yd5(ex%K!5!dbb58>dw zh5{c1>M+H82Z3WYOw{_fO|M1!-sp1_7MGqbj_NgDs}*wGWyY{lbpib=(D7LkO#Zg~ z4}b4>vTAv>N%ZYF7=yc6eQby?+SNu4kf?m>V7yy~9+5YGnG$ygLcWiX+0&L|Y8F=W z!O**TeciUU?!BNZjy}*rR{6wBNKkRyD1u`8@qgN*9=Kg~7Sh(LErcHkX})MLzph<@ zrT{=$S$}L2lI9^PU>l+tKjAwm&8Y})6MdXR=Nk5d;exG__2yY)pz~n_#rfWk^%BHC z0gZ-#yI*GDW&vrTV)g`3H~G5l^^C6OKc3huw$r|Op4k*K-q8KJ<-jm#c$i*T+yIG8nT55xw1e+FoSH6hd{bc)Qgp3 zqyjPzam~+OYtzSTZXGJ8y8YI@8}?($n}k`#FrChU)q&+$z`@&+_QVEv26$GKoVG%O z7O;?+bU6bi(-6u0l>mp+9qPGBXqO7GBqpDDtr7i5Fb36toqIF>Tszp2&ABW*OC54H zSo(q=*vnke;e_A|l=L->8uAZxs)>y*%HNmOEjRTZ9cT#x;>w@sVP9l#o*}|II?62x zP;9{rtcvskfiu*^Q&`6_pO$31b?UnV-VgOHrXZcSWHo;n`_9SZrnV74k-?kZe%oIn zY2U1WUX}>j#-%bdRH=@5s75VU=v1VKW%^_N_>l^?po$J?Y`T&BC2HBF%wR?v*u4BE=V3$!Jx&Fr+2QRYOsA^rj64fJsM&?WnTreRpn6PWdrEsj=)j z(D*BY$bGQgPl-x|#1;sFhq~V4DsQdRj@6`08J#8GMl+=d%^4jVdH=%DU;W z)XQq~rq_3MX=Ggnrh!>_X;dzWe!ZOjtYMZvxGoYD-zs8QHLBNlE4W_#;sJHwasaVt zuNkTBeNJ}tKk%?TW9K%$$9Zm+$v|&usFybW!2O6gN^w2_|mxJ=c8S((Rq$vgrPh?%r zdvvvu?jIlqN|jL>12GR{NDEDvmAqe>BNV?mp&WCuaAU3|0Zr_v)f>Wi+w}rJjrYL( zgI+d?z_aAM{}y8~xjmZmxi1s!jx!d6^kLmqAU^wfZU%`+%3Kxuey=>45NB7;%msCSh z+~vhovqb1IOzX+^9A}*Pc4DqROv}u!iKlGG2Vk!UzZ+!vJl}?Kct8t@pVG`p^mu_Z z0#PRkwZhV46>m6zaE8oKP9B|t#8qKuy+Mjv0mo;1RE%fV$DxEP&ybp`_@YG{Ngw!{ zVH7p>gv1lsN;~ttF^83`>3CVzLvFAv8PeU^IaRwR25vI7Y8VxrN%ZQ?c@b6NT~VS{ z&Z{}%^^aRdx_v3Sm{NNTYik~o=oftI9yNzFO!g%#v{(tBt2R>aje(Ym ztb7T0Hcn}4KQY7+kikQr^eZT;rHx!+)c4O3#%E{3q2?>!Vlfu$yy8-moQ12SXjFiB z`@YJHrpi;u9qy!FQ@v{Y(R1<0=QfU(KpwX_=hbrF>?Wj!X~!h5!4%|F%YKT zj{;Z*AaOAJn)vUs?DGhpo+Sr%%4Y+JZr?yLy=x!r9Sp1?#W6RZ7Zd_+B+tqMl%4~F zJ~8HOU`&8frUK^>hX2e;vq%Gy*VGOEtFo z<`Zidj+P>Kt437QE&x4z_a!#))yAy%M^r5d#Zea%@0eI~_W`V=9IKl!hKk=kZ}RoR|c~$Xi{ZTZ$yY zDSJaPEyUOyX-lfh`JFT@k1$%9%$hgE{b9_!`YrA$!LjBA`LYn^nhn+%HrYG5y&mvX z6w}7z!pX!x_pHA2brCGP6aLr6k&eN^c}wc|to?Ab%*NB1@1Yb@zDmJ8u=JNHur-N* zf(BA!o;Zjg>1*xQ4E~1D2j@MhPxA|AzcmQG786nC`$L=e$%-!{+NN&b8R zE4&);xB}d0JN3|}W-!M!fP4Br#ob1t_)8*e`+f@$$dLabxV026j*_frrJy^6dN4uq>#SE{h#R$ zEBVh&yY>VDyAO~lIhl%k=}i=>jDzF7Dj}{!T-Bzz_XoBiAwVIdW%<8=p|GR*n*&QV z@9$UlXhw<62fdjtME+y5YD68+DX`mT6&P6>Vyj$h$||gZ>Q?)w;E@ylVw?Z`i<)HJ z;(*U_&s|9WIg6ZPWl)Mnb)P_nMHqfdx7&rcLjiAJb?~$8w&CQ5%>l6I2;fuwJi1BM z=DDBQJR#r;W`a_c`bWK)-LxZ##kU89%Roe&BT&Jx9DYzV_Z^1y)=d^Sr1wWm&x zjOd90#l2Y~^i>5Bfn1j`K*_otRR@NLWR+xH(>c828^z;Z@B221qC5-N#5LD`vid;l z0o!(}&Y?tQYw*i@{fiTy*HlNX!%kg)%o!|@S@MIf>ufMY7S;s}bfbPk&L9Vcg}+c+ zjxB4MCrbSB)@w8+JD+2dV3I6u!b^<{7+&~xOVUGfi}OvS!c*HRUSO08;GE{JT1TbvOfdn zB-c``b%ys9Lwd+ffEqk;v?S|Srd8Ry>pq|3AWu%|{4fSQ+QA1{*8qvy<3~k@pEFC` zRI!>A72PJkejn>iF91F_OMuq3S6!;Fu4yFXahXHTPsT8jzMSb-(cpvWWZf(C&)@8z zJX7$Y;Vcw*3EuZ(wD^F3u8EEqc&Sb{j}+H!rb6TYO`dl%zj4W@Dh$TkMVH~M+BpHr zw%ICh0D%R#`p}UNAguI^d=?zR%|b!Gn?~G1WHuI$^QscjVW2GbB<$bBht3qpSC0{2C9lm*xLPE*VTY9g2Y|S_DjGTYyW2^gS^l zYWT&_fWtyFkKTw?aY9+Z*F|Mz_pjwhdjYM0BaRUrAME7p$vYcD)S#b8WUet})pf>k zLy>8gflPX+x@W8K251P-%qN+9Bx5Ydke<{|_qU7iMnt!pcaTLbD_{SiA*fY&=$k!+D=H4J9 zJTN7WH+Zgipwj;kz;vPI>Ca{xw481oaJfUm%?yXm+EdYp8VDD({Wu808JMgRO1Fqs=Im4`J@BW@}q^dxqklDbS&cpFK%{71WtG9>LrxvOMK6Bz+HaA9@)Z zSvJTaXXonS_3WHx-dG!7+`a=n|q1jsv~W z*{K)vajFQxoOF&4y>xBhe~V3SiUl69hu$kpZf0h!dFqg{dNc|S>-;J3lgb5YGQ-M8 zXTBf5%baw;lG?ipq_6)zP7Ne9zwP*l|1XWcI*s`fPfAWJ2(!i8zrOZg;Q<(D<^Mc1 zS4oknKX6~^$+R6G%98cZN>_>tBrh^eJ4*9gs1CFSgiE=FYfi;=ccB)GM^#JM zfADA4%B}X=rLQU_@y~hyYk_JZ6VNSxG_!O{qzgr^FV_j>eBkQaEYP7Iz5_fvJKahF z=Di@aYJFXrudxBR-m)*HPOa3^B!(;W+b166L!@_PhT|1e!a)$Y6 ze3TA_e#P2dt$Cn|0v2l1&Kj=r-(Zp z?Z1#l<*~+B&;vGO%Pzg;f(ChZ74a5LL%?`64&RiV^tMT~a(5)~o0=z=3I_*(b}uN0 za`j(fCcDBcnE86kJ^`vGP6F7AaXv2to_PJeBd=ueH%V5m14Sl)-G0DQ4|ga-rN>gI zq8btgQUmEltswNt#yiRV`C+6p)+@68T=c|~u-dt!jF7rd!2) zyjY_8eaHwFQpIFz%733@5vVVxGpT6W`gFu|o{02u|a>^^Ws|$;K&^DbrMSGz*v6-(~$mjPE(_N1Ew1||8KCJx^CziGM^;T*5 z)n621zI@bz%}}ZP#O$so56^^P1^8IWM3-+bM$(1Vgid+oHopC5K_Ua+_dTnyMH;Y= z;lr1Jjd^iC@iaO)cLLU?ux*zcfL`sGfQ0q8kz4NHq^0H^Tr?f@lU5-*z2Y9R(e&+w zfcbEDhxuY%ZCP_-c0|u^>?_|7`n1`dM3r>0ILY+)2qpGdW@G7w!K1mSk9YNv#6Pn! z<<%_29AFUOZl9jtDyr++@pLk~ogt;XKqbzlWnvJ{IPf+}8SCSM*+j6Qrj`|7e8^UK zj{dLZ9R+d47Pzl*W}=J{zuzNU#!KlS=lzC5(@@lACKp8|j}XPr(fa4(=RZ;q^rIl& z#B7WqdwV0cKR=b%dCc5Per&`u`-nUP;r`e5+dBO(?Im70LQ`Ps@E&}%8*wed*&uD# zFuK`QJ{6m#B)C&$>TCzY4EplRHasBBOG7rsSs}Po@EFC$L^VtZ_{0s>{gmU~pm>$N z1 zN$ZdBsM#Uw?ye`q-2H)kYUf)m(C-F45 zU}%q&#@xnxCcMj(^_uE_lM0zdS04?0Y(Y~t(H4&c`<+diz#5Sll<^N{J-4Jm4R-it zHgu~ab--}j%Ee_?aPiYN3A|G zhQiaffnu?A*?Wh7ErZQfd2VNNY>pcS1U7!kBlkmoe8fPmN$F8#*e9&{)%z%IXlfe) zB5>A(3HrkN*hU3Dpj*OB{W~u;NOcbN^d9|YRqow| z1+5XQ!@FPoyEmA<*z56-yf;b7O?&1;tASN&jDL<25}o)&8HXO$xgO9yB^VQK1V*yMRkJp;?(j9y*--of$CO0{|pko>h^e)+1 z1n#uNNI656Z?G;kugdo|G>XTD(IY~xKj-e%RC}cgbyy_b^ExNuhV)IEvV+Zo7q7u6 z8vG#eY3}c0J|p$5IdAC`*DDT}I>Kdz99 zTrSI{UrVlP4GR4hl)+xEGi3a211yjN4HzGF>6c-JG)y2UVYW4#=gSGljr*%%dYW9W ziiGR>OXJ^HNS5-7hRLyR=^TSn2vgfAy0FBE*=jz6+Rt7`m(NCXKjnrq?w!X+cCJrGEsm_?`*ADPj+>PxiVT#*6~80j?!J@Kd2q&gJjI*N~4|8yJ? zi;Coi1!J`P$qG(9ZhIJ0aTV6MiMX+crnZZv#HrecpNHJ;+XzQ z7`k?FTFSqrTrs^Y+YBn^0;@YSmw!z=l*JL=isaC<@|sZsKQ0{OmY!BpC#-7!eA2!uU&6AQ zluoEa@}LVLM;3f%zjp_fOK)D)W;7WaEgryAE$g=R!P??OKnVZYcQ9Bl!cAtfgExW# zizWa4;@CqjLcT63^07>B>=(iQKG5H@1VGXmM&QFl&6i-d>JzV#W6invZ%nqcCwe+J z_O92jjtsKgOPz44UA(I>7-t1fQYcvn8>4ERY1T?=l@hv2#6lro)Mlbpvf3SsT#BF% zDO06-x!7M=$uaHKs+Z3{r>wQMn}1X|EU}%bVJ!sp%GAs59FUiy&|@CHQ|a#D@@S0t z!~r)Ongr!Lu^{*3u55RU!kZ?g;EMQ6RT9py{Z>doW*KH!ImiJ9-P%gq^|M%^Kzty| z=z9U4*K_1;r_^2608}>eQdTei z-<&kJa`qAbg-=Z*#&o{HI3T2$3XSSwJk91~}k7AST5 zN&-&dR!@Trxx$cd=<%1ipNq-e_AhcZH}PvRIaPCRge{EJl1ZPG?qWqyo#7Ngy!9tf zsbJK}`rBp1$HXGnbO9iWqmd;pn$f!D@`x+Go$;0<_&Y6z5>jmCJcR?xr+%mlI#$?8E?2J z*%Lmwth?Wtl@Uy>I|$=vo%<53uZa6w4wH23w5IRw+RXr`8HAHAgZhL&K@7>I8&4n$ zDAqv@U>BPeSqUI$SH$u4&P~V9pAF#p41IyhBr&fGnJ=%UZQ_|t6)Vji>Ui2bf#`%fg8t*}l>6 z;u{f!>_Q@jp)lgc@Y(`gIfp6a?mc@N4aJjYRWizSLh%2Zc2}ZnSI&5DW>Qb@RHsZM zSyKVLmaVvMiG;30kYKLTa;T`9jk$FdE8W7D2<5yv5c?Up?dcscz$*cG8c8p3>Wj0y zP{z;F0@T!GTtaKvI+1-Og2{2_?S8|1INVkwp8gIP_gs0+e^5Wkdw10350>HXgt9Za zM_x%d&PS)<L#tu( za^SLW+1j**!PY4Est>HB%=`GO?2mT|_Wr4GlUH@jBv8^va|4WOL^nPLlC8~5Rlip} zLxUpQNsI!qak%e{WnX#f-HS;>A}}U0CaU|fF3%G*R9fWYpI)J1085@HJ7eVW^weG? zH~w>D8|7$z?Z^L~3*Zg=;~trB`L81-i{Tu6_0!|sVkakUgV|_WeJDVKx3)%7*{Kf} zS;egF?20NX7!MX}&Q#Y2eswmEcb-d~m_v#KsME(1uap}^fwoZsfEApd%ZdvBgBK9? zL65b83I4Fk}EH!;D2 zT9t=5yReU0*Omu&y3=o$jYMgY=!wfu-tQP*@HAV6;c;iu=fAU=ef}~km0#C;D5!weJ`VuX@twWh1%eCHGiYO&$8-wq7{?`uWU&$U!N%?6)4Reywwn zu7JDj19}yzto#o9-Cya?DC2r;}rnY2BDcD;~v z`Y%DG2aQclnWC{{zKd6@5B?!-l{Rw<`M#tNvz!ZCwd+s66j~hiiZ~K$Aa?L~TOe)wGH%<0v@uzS4a0Qcv%&Q>=xn;jE-C1{^%2s3l5N_&@LL{VDsm4Npz|x4S#X5aAI;dR~*9Zh3rN;whTIdUaESVXeLc z91Z4)PS4hA1mH<{$N4t_GM02R#Z06~Q?55%s^#N2N%d|U3;I{3svT6*w|2s*|BeSc zxw5Zo?C%V|zbU>GeX@-yh&~`e9RzXbdy;;85L()5yn5W9BYCiX<>kA&dMD$Sjp1r! zxedlRg|b^z`%d{k+1RJ*DkJw}n;hLx;NCBUX7zIfHZ|Fp$bIGlj>fjESMw-Fb}-VV zo7tv~4@`y@5BL2yl9>5;6yGiy+oP{$)uy4^zzq}0RZw~M%r|umU-@=E8JB{Ms*NqY zp@d^x-cg&rlJx_-~s*sz66O#;}h1`9vs|wZLzI=m&j5hVoh7t+_SH=<>xCx*s z@Qsn?3*rI8$&Z+uy>=+O2# zWn^dZ3$;p!GXrJYzTuH^L4PJm)jad`-O^_9%0|J_xZ?2nquuGE;dYEkbh3@gY$fd4 z9l4j@ z$(a>6XA@1*Pp&r&M*6H26SeY!Qr0x*fEZ^!Dj?r4EmM&&$^-Z>VQ$82?>O5%fw@{S zK_TLs`@&&nV2V<~M&A8HlG=-reUke2{Z_YyXLBT0PlbPV%|fV&##AU+HDNeZ58QlA zKUacON-0^3;F%dSK8)Y!MF6u9j(lW+(zk!J?YNH-S(hYeR-nvgHhy_XRrG~Lx9i;B zKKQbbAsu)RWy87Ntm2(@z3aK&)#al>2$*8}$e5CIp(cH?-;QmOrodT^>j1hki%yw} z=a;{%0FQ|L&Gm+`)JHh$eOq*?$rx!*BIliA%D3u~BQ_xAC92MoM|PSj#IR_IG{n1> zmJH)$C7}Hlm?G)^>8J2-m16#%!=9AcB88{@Vi|L?$z-Qo9=*IS#PxgQrn#%m)F8%8xY#N+c8YW2Oq#808*IZ{6zBQi5R+^( z7n-}(TI@yq0kkTA*9VNFuCXA`H0BqQx&Eq0tBw3exgwY?S?*_3C&1`QiA}kVvnG3h z+zF&a+RNyo9Mc$x$*)$2)Y##$>SA}dG@lk7ixu;`nN2!=H`LGr>v$_S*+9Cw0Ne}b zO}&@Af)l~J7VY-o-BBO#a%{qy3}kOrTeCDD)BpE1!G5v;btef>!6mBdCx}n>a!KeZ zRAp4s2nw?TE(!)NddbqVNpC}cKWL}z|1~xBc}1`|DJS!;jIEEL>z7Lcqj%rI04#Vv zXC`VmQgrCm%X1HrticlQOGLCrDm>sSIu{=4P(GJty>f6ig+2OloEAhSVtar-wQ`!k zctS4MyneY^*OV>CIQ-f=e25Kkp!@lpG9aIQsoiqL98=x02+UV&MmD|D#CjLKcLq^` zsL+t~vS#glP0eFCZLtAz4Qg1^KH;=$Bg7;a-(E<(u>j1Z;=!>0QejvrW* zZ7ZSA%81gC5*1dq(DfPetjmW^Pr3~4NiaY-ng#x_$myRIx&hzUL6C1VztO96sfo|T zPWLTD5MR$li3&P^{-N-93!>zDPFNu8PEf~>r*;@E7J>~G1wplxJ3NRK@u9xL-Yf|L zyr7Osmp**Jwr5SDOmeNuuChNWAv4kr;>niE1=AvxzFMK;cg2RKZ4~o}q z8a#Hu0~nbw5Tqc1e<>+I8BDAcd$(w}weY%=?8lVvFP+ECV zu&P|b5Vj6)dMfVvq_CYn_RnAF-@`_YM5h1!WA8`k_ot`g;0>Nx&#c*m$_sOLSK>b^ zT^9yC;>MXf+?8^>tud+oaen(d&RZDVJ~EFFO-(8-cG$C%lg@-JKgZv-_mo8^eG@tp z_uQ>9IGM67dnoU<7Zen5?d*I^e&@$*=81t>m^wMwatJU@XZ5e(`JhWYY1`38~*+5g9FSao%P`%yONZ)|60 zqgH>PVH~osw5eXv@%L3kllU~e%slii>~+@zBYBgg_Jr^YrtffXd7fx&Dc}oqB z?5Jq~p1iLdd{bU2pLx;Gt`;;881+6vBIpDHBqoJo&NTHhukozjn0-{G_CCgcf%B0Z zi|9=|N<2QVuZfS@j?b8Ke~uYZ>4_={imoX{9}foOvRObh{*#oNk+-T3wiW-@4Ri+A zs*~_3^6BmjOsxX(LrFnA%^%S(!S(Ci!w62u)u+s-~hpZ29Y{C z8KQ3j;oqMgEJD{L<|fOE~Q^}9OUwdqFHINqxWJ0TVhczNe@>yZy2@J z$$h^3fZ4H4Fc-#zQLE-!d^(I`y`fzyl9>{FM_*|5sVZjG8LX0sZLf57SqOp>qcuDu{k~;G8e(m z+O2xYsW2c=Ubxr|7Z_Ny9MXcWV3ERDnsPfwiJ1RrBwKRNpb;d$THfb zY3BF`^oVRDg{lR!aY8`b@NWz*n^GvjhoepRaFwA&0R!Ba)7m|4(0E8P{a={yjj#(T${Z zNQk7gh$1~&8k~T1OG*hMQX<`5qdO)r2ZD5r?v(B>d2amm|HZ=#KPWewyYF+Z>s#lX ze8lSsfzL43&G@*3=L^NzKCO(u&W2Ag&8Cg48X!T92#;889F_FWwEF&7k>Sc&AKh8l z)l=j$Q^{maGzu7SHH2I=_NajzZrMgr4bJ*pZ*Mk95+kuaOkp^3<9%fcopp+vZAqdg zDcZmTL_>RH)q`_8-ulSiPZb5@<~;g`k!_X%<+!xjgG*pt!qJ_M#GU)Ko1skCj1v1(2e$e&;%bk(_-;|@*p>ufZDF@7ZX4zg-CzUp#<`k6m} zs4fZ<=j_FT-OI;7iyg&LxflUINkOI?ySZ)JiU#O$m|&}d#K`O?zK4oGAx=-ZCb37Q zKvW~|nLFp#8^K?O9jg$8K6@(b$pjL^;y@G5k$|Fo#_P|JJdX1n!BDXJXRC^GX|dgI)uKYGU|YBA^up%fOn>M@UrGNTrrsDRPSfPc2A4+ z9p77mC`c?!zTb5T`u#fm>aemFD*Q?EL$LmdoYOf|w;n>;-vl^QtQlX&{+s%ES-?r! zcc$(E<~Zlt`4dDY8szC?tck!w*Ll$Tj>`3@tSVIbiEQa*CbPsiQLNIZtEpt+n-Z>i z8+P$Y6<+~;ic^*%uSWW9FF}l-1if9y2?t8?oAP29y^OvGr1$DTeK;z+{c>AT(YwlH zF@1oQq8DTxG5<_?12o+QvmfWTXD391Q{LC~)n+WeQV&t+znjNPjv)xa;4tcsfXA5( zR&gudT>}^7XfY~d&S`plMzWmVTyi`%b)f&EtXNj|2PVHwkH@%Ob5SrlxpdQ~hR_%p|T z=}f|X1ccCRfITbxp~Bs%Eo)DL@+X1^&jZ@>ck6GftTpwA-a*GWO1(AU-LWRsgVLmgBm!PBnf^uDfy@oDD2g)yeB7m3nkw6*CXY4xUrw9|vXpx`r66cF%1U? zRa}%JI^9gITMEI?&@-6>oL+<8D*wQhcf;Q|W#Q1pUvm?(Yii}<`|N1_JXj(&|8Ezv z33cq#fIiIc zc_|w%Ih_Bq)7oxF9~TyDTHYKelbZbSW9wOn!HGtYO^4UE#;ej4l}n&*gM~`H;=%Q3Q5}k+?n9iw z9;reniiV6fC~bK)?IGsFs3{#gG5=RBJQ@_NvzeO1Ds3O|C)F zlw#j9I0N(jqR6D9X8T*6JK-uHi2j?faF`sx>7|3>x6-o@#-u|*>-S78v2gs+B_-kp z0uuRynP^8((8mEC*|N>khy&IaIXDYpw9G3O)_e_Elz9-XD57^*b1rXs^+c7@kKp+& zUVE@*NbnO~Q;{VTZu_1Pt1wa{oIf~Zor;OcDgg$5i#p8&izM=*Zf3!N#v~ccL5w$t zP0NBbOc{RS2Ef|z>7TAki~Y2w@+6D`XuI}_yjwoJ{Kc!96R1ZA7w6;)E(n_Jk+bl{ zwMn0J;i9;8 zuGRRrCNYUKtMg!8K`e7KF+k7(5CRzvU^lRK+~8b!(^~?byYHU63dZF7dOBV*Gv3Ga z=H#+5YfhGBDwe4YP!ER3qbG?P(wcvE-Bq3|jCk`oGCgLU*MDse|BDvS&{K>SkA3#0 z67Sdci3#iU7KQq+;h7pPr4Hj=k3}A=tU`fL!jGEziTLSXSW#FIW1vYbC6sNhrg6+i0UN_PeY8CdK7NuOx220;H(1#)UPYG%_PO?W}he;iZz=mv+ zU3VslPB*!bheCkfT7JV2?s2Ows4*^gX=aNdmK3|^X>GEUv#oTeD0ZKk5B7?F%# z#9%C8Ddx?$0iZA+8PwQ@xA_p4X_@OT*bgjs0>Gozcicjw{C)5)Y1ly^$C|KKceC$! zOc>TXG*`R|@1+gGdoqBhzqtnN**#_xt`Kf^#%6?LNnmNQ(C*gP6`e^N-G8ZUR$0Lw zrCg)(E3XtP6L?hsH6k z$28=!Kp_C6(1dt?-31#&7P!ZMi{>McOq^2Q44OWc=NR4P-L_d4%IgOK&GW!%DANSA z^7FObnkDo}G2mUhihC*rJ!pHt`;d0Dwa8fwn&%^#c5(-6)Tl?~+**+3{ucEqo|9DZ zc)!2pT}JnVTt1tOUrmmuS#sjQ13|3#bGbJ-?l2d4UV(B8k7>+R=UYAh_RDF(%ni-YW@;uvcKT)As|ZgH zKE|1a_tlRR?Bf&9Mr$@Pxdgv-qTvgynzwFo%8l+cC=cBfxmPv;50b2Q(lLvHb8jo;Oi@Ta{ym7NOte_@ z3B0in&yNQ4p*}c0eQuhL976PP&4kHo0{?%0QXwrq)T~j$DB`k`9(A;c6c~Y-P%N^; zQcne^57% z?KIm7BUJuC;bG@12(OC!hx`h_RJHh@^C<_$ z+Vp(#9z7B&qL%bc?ZaT3omULvnkv=VCRk$EU9ypzcC;rTBh-1kqmTQYnC=`<-EB32 z48`Sg5*N~T!FJ){!V7YGM2=NPr)O`6P`3oGx77NQ@N8-4GO*DoC>%Rpl;77BvJRI^v;#Iljwt4-GQz(}l@ z2?D_E9rrIz&0DQQoAS)BRWoPYlHQ1_KEKMovHX2AoP2$Qy*qk+@^wL1mrue3;4-dFGA!JR|A4!hk z6ar7y>fh;w?uP;Zr(Qk%Mh2wyL;nhopN;pgwH}=ru3&L-7p%y7k77HmJJ?i)0Xpn6 zU_cjlt00yDPn{*h!fexy$NxEbw_(7nKfyxXkZLEb^=R>n^Dj6*K7lLbyeBWg&R z^g{#wtCv1&)hpaXBJ>H*U4Y6cN+In(d=#Cxf_RmW0`veQtI(Ly(VT_Do3+|U6lQ}t zMICsU=Q?fy28^W#@lp#BS&lu9-;pa6>akz$kHjLSkxirwJ!X6d91zD z+P*Dc98hq|yC_JLX?JC<@A^e-2G{m|FbXvq@mP06cx&P{e*qhMx`4k^Xlt{@LOrLA zoux)UGJWNa+5{Efvp^fb5c#RtU_QiIHM%ziHd4{r(@CT%THt^W4*1={&{Bh^!%m4S zKi(d2$cs{NU?h?tzo?52IRI+i_Fe=(*pOy%!)vkdyVURteLAHEp(jQ-c zT~Y zTSZM9)v5ReIs4`Y-f%w@*)TPWQUf@A!fWC)w3rv7>?Uyb6Yc2|C=|`2=&@QR`e)9P zd&%gtGbneW>h_x8Vl7X{jLr*N#t+1WRwx&(Mw$i*l30^-Bel9B!1B_2Abqb)WAW1m zor64CF)7f0IOl2o3QiwzOwuYe?1zt~*}yMtpbTOVP!>BrU4S_jBh?&AzvBCj>%2nR zd66ov&au+I;n7qv`FKxe6+vZ++l~5wky$Ttpi2X9Ux7Jl?SVR820B}i^!&kZ5Fv>z z9yUqhl%qI3U$3Iz@f^=XGw1DI1sv?jz2qmW|L&Y6SU~3#kku?nWS>=~e>S;(y1()E zWz~SlqRtJ4EFCf_8f_{5ka2V~dH4%mNym&niVHA4KGcNuD-e>r3 zxC=?&TBO(zQI4)#>(hvN_Q7P6i&;+?PM;lqpo2xCMmBPT&*RQ*(f1MZr|Kt{8qfYM_+}vxtaM^C}gU z6sa6Xzg*dt=CoC6fERPEkUrq*BYTMJT_wi>TN6VvY17Yb@}ET}RdoT+f|uTB_PNhs zAEkfPf00T*+}@HYA^njfEcH&aH@cLaeCf>PfL3Ngf{}8I^_nuwY3weF*=nPhfT^BV zq8P{SqqC$r+kz%XoIH~jI>x{}>pT8VV*r^h2#JHx6rd+4`4|>Ub6yWfvCde{hHF^P zDb6+)hWHg8-cmnWWe2*+Vb4Rf!Dxgipq=S)(2kA=>=6o)wfzOcp4!0<`llwIcpwl> zgo4~NEt^*{szBB%y1iGn6~mah!zx!a>^y2bEd@~WD%Y~A1^|BnHb z0dONTbtyvYSpb=fqZRx286gXB4B@2Zufg@#^IzmAp;Jfa#;0lJIR*&lBU{yM?Aq~`Xy8p&9IGL+94Ytl5ktqr7id*4R< z?fvG~`p3}CeNY8FC)F6oNE?JK)em+Q>88Y@hI2SEx-uSQNCwnq3l=$gx2Unx=@((Y zA}kJ&KQ-=a40c}h(+i9L{%9u95pBQk)m;WSU+be^|Yef}YhscMbW&2aajV19BQPf21MlK^X&9vFRtc{^e) zE|1)ql(CV~nKK*iDjPMK+EFJ#Aps^Y0uSS|;&<#Y1OCxEKl^#i#}A;C$K_5mf!tSF z7$CG>m$A>@Sv&^~grcv5286YKfdRN$y7``N`8|J{M}q+NM6}#H1%EhAKCrj0lAu&o z1$#A#z?)A2J)!kjchW6atWHjwHlU*6&(bm^F-Dz!kl?p-EPY?qTD!?V`R@PH&e}0w zHod=zn)_OXhf)4LVJ9eaXg2wVrfPU7u4R`?=(9w2poKNpdoKo>dwpIz)OEuV?*F># z+e#QS58P3W5BUjyU>x%fIET%KEhq--QBn~H3+>w?!D0h9X?YLBAfXgt=PAehshKe` z^#38LEh^G<|E2Qc?O!WIgFV}$rZhN*(hiJGs~@GN_fVSrFEypI!}3kpD;@4d+=aSY zVy2d%Mo+K6C(?li-cPM)qj%Bm%iTda)&>((*dCDA5kYLZ=y{Re% zyA*nA&9N*&CI4dT{GKMMQZL^`H6A{dKU)kSv`$ugdi3wG!9@016r+pwtwBHSY3TumE?)IjfMD zsNsHtJBsZ$;n>NcBJDaJt#2F6|p&dyTYdGcMum6*;#6!{@@(pF*Y+1ZPkG zBLiA_U)kNE#}CTV`2Y#hTtCt)%Or3`i){6{Gfa zF~I&SLDgD`>=3keG97f40Q=pp4XLSv2R-)KfiUG+OFTc5`K|~Y%Ft|Zt393~aM~rd zvlTpYZ*!@VesTMSz>33%j4jl+9WHYF2}^R5?!3y-|3HNIy-)vA>&bI>tLstk1Ma5T zinS6zFy(~?Kaef;VnS+@WIQGFc8FA`lkj9$g3u$Yi`^ z=n-J!0pzIe07()xzlWg1Hzjogmq=23)Gd2=+~uD}r>h|PSkQhA(oOhzt^zxd#gx0F zlqavjWKSO#xGRSMwaFw-sJ)Z+UHCoLZJR6%occ`%;@_YbII|oy0rO#xHREEKpLsGF zO}D%)^34@M&@NFfJ~PD~Oa)HA)UDs5s*eeQ0NWwauaY62$;6$lFXc>nBnXj>W`KP# zfkT7kFX#l!N!txP{u^a9j^t|9Z~B%wiYbyKwH73ULw;3{y=9Z+wHf+$MmwiPCEfmJ zuS0QSGN1TV9!NPCIReLNf>UT$6S!s|pN+(jJYFFkaCjqwhiqtQ#f!zwN_y#5AoF^u zmCgTvSij7B>8B+cGyR`fjF`W-g(QLfaz0b&0tkz{?0cA2JhH}Akq{arp?`=|{^c;| zQ|3%;nV8BVP}f3$h_N_j=XoiYyg1Ucvh;e6bMbyKMgSAJRxIZRp4umyyZ*}2QM`WD zM-@u=Wi9(!P=iy~q9h&&P!@i6xim~|#RT>dntA=>W1}FO#>o@OVK+~7$Mc1RJt|qd zTv_T5Ty`>}J;#pYi)uIo2jWP=-R5LHKGjv3e?ge)52uao51Xphe;-SJB1-P)cx_K9 zW+5ueGxfRc0{th3#B7A4K`zr3`n9ZPwT85!NJ8QMi=~X(2(*xlQMH7VX>U7VNyNl* zg&!26W05&>2XOS}S~KZBW7`rnd}ri1vn=F>R>|Ha*8$Tv+HO(p>Aus_xE=$J{~Jk( z#ycT@+7T+zHlkfh_DXP@? zBRX@^2k0M?ynNxT=V?}~@#U;X?mxGM&`g!*}UV|@PYy!AMSPF6jQ?V$3f6gR!3+LpL* z!om1mkF1V)yl=h$1`WK*l;{4tNnI(&*LW;xg(L6HO z{tXjg6US!n1pF19JkijNbsyNQTpEoIjcA+@LR%+w7)%i z%Q86q)O1U;3e$NUL;S^M{Ocmt_<{Utm9UW;o_vGKb1*(egi7}QFVUz68}EoU0T)9_ z>4Gy5MHS1(a@Eu%<~GJKphawfVM$7;Wumd@E0KKanc7*!sw~u43V7-Gok!G2UIs6X z^RxU2pAjtVeyLiU8je#e%RqA5V~eu#dtdR{ z;H+$hq96av8lnY^pWGzPVL88G;TSI{71i7a+SRkg!m&(lTF1TnUk>B9oc-r9*!mq% z%XH>$PkO#MnzZ5dpTZw$XQ%Z4m%;u~B_^$5`YK_Jg01&|cuC}*eEGD9N--yMrBZ&G%?#Q%LAj&ut!I#;>jA2ve4+_-#V z&cl5kPPz%O>ETYf)~yXm{9;!V+5g7w!xl%%L#4^_SDIWT1=yWKj>J^}s4%eh^aBeV z&`ev^ecQ1Orq4ih?eNz4Q$LmL7Xu=I1L^juTM)AwnNCZpUnaov(&o)}%#UM`h#Uar zlt+cWLc+$vo(tW;sabK3Jpvzfm$M?qtE`CNb7OR(T3Nku9$fQiGh=?2+sQi3GK=G( zA4nK%@ylkth2~$G<9_{%kXPOWGk~`d4{yss91e}}L-kfT6`*4i5iXL$2T3Eh7a5#|D!2f4q%ut{qK+6(!s zSNIf8hp{U+*2>bK<**6(WEIj!Q~CdKK|I32N9aP{&(uLA_SF}{qBF0N8Hyo%BQRa? zHRxh+LPHW=O?>vA9kn%7gB_ro8ok6f=$WDI29dyiBVm{_lgu;u>{-_>x64aTu(b+j z|2ceqZF~EYSU!tFIZXsGoEQP|`kSZ(S~y*{fmSNXQLNheXxti7m`=CkJ3;u)t>K%8 zR`=3RW0k6#{ch`Y7#y>3TmlX_iiwgXqQvP!ej)@fU5iQf$>KW|&u8vnjn?*C+h2-SFDDdEova___@L0f5i#j=9dDrAJ3fQcxr9M3_ z=aC$W*JV^-qwE=?qS!|^{}Uc)vBmNgf4#*69p;>Y0Si^8ui(f}9pKYizP-kRChap9 z+7=diN@gtVVtg=>gXd%*0=;bJ`8yr#B^`Sv8H4TB8He?l-W$L|G>Qc+5A& zG1G-8&?{3!IR`;Q>%p@@hiffpgT}>rmPY*oId|cmFB9!ovkhMU1Ow2><$bT#pHPCC z#)`m!Y0K|j_wLqdsAx&&A>%xH<@P`O9Z)+md>O=-7=tjfTUK=#14`BVpwEX{6t5%^ z(@Z``(BgN$Y6-LNR8l?8>d+7=0Zh4Nh8l)B!UL<{CeIQ{0f`{DDL$F}(#h*Q7->n; z*>-h1t_XydBc9#Q_kwo;YoqM-IMtYy-+rzPCb^Y=flvY;(R>`1`nJ<&GuHg&OC$E` zYpitv{O=L_RNY1XIs0FkXK4KAZ(y>Qend1e>WhWIh9X=C@$Zaq#sO$KEtO#YvJlWT z&CRc$FG4@gC5F}?Uf8p6%n#VQwNXZHY9iF9=^+vU;%P?rFJ`?)5@mJ%H@ooZ+;lTV zJ-rgdA%L`NqF7ySZVht=qZy;9J~%X;W!3<;WA&zLG(7__L4N@glq_;nl_@o+n=+sa zJo^NaK#xh@e*l&Fl`L$O*X?wSMRb5hOXt>5B+ya6m&lpGmCHlJ-Se($`|OH1H< zUL%TYHnQ#eCvYP>om@8g%47?*rd>%<}~i&{|-){4N8c zNJVY4(>9}t?^eC+086t+%Z`~ia+AW#GDaN|LPKro7(5#%%yxxG0*b?c`txw8o#Fe> z&9$4@G5HVS%Gc7@84rn1s1Ikr9V2LK0_t*2^cj?TX`_oB{! zmdP&#N~fRf>nAuu*z)h~)tV;JFEw7rogb`biQ?>}cT!fFe=5`}3f*Le`8bP1IexYh zd0)RpQM5!y5{^z;&~0G?s|-!p|J)h}4VEezK_R}en>+YXw`rb<*PeUE-g+{y@`$^GLbOcrq>L`71(3j51yND9W zU^2Ka8zrN_^*)pX))r*BqFX+#Kzxjm+xUGmY1G1SzuR3v8(<^SSY=F7_}5C{+tJsI zrAbr1`6DmgqNu+24l=e~1yOawm=?EP-RNLes2lCZ$a4?Dmhc;O6wJLC^5Xh>7~>w% z*n-m|q!Cb6Eo-I|0a*?_!;0*hzCU&8B}EeZQ66pw9nQ*EY0d8*MT|4usrz2Nzm6Xi z3e2fLdYTSywNCv(S+#@CQDbQNSw00va?{ByS7Y}O&IavW$0q|Z(!TI1>9b#O037}A z{3Uv>Uu^06gp2R|=&oCbJzwZb;g)EmUrY5k(kdFGhUa!Tj2ct9T_#X*2}3JW-Y)z8 zJ_0*`&d7@h3V|xe67h8eo&O4=s@*zy$E23arU=l>Mgp{(4?l!m4%Oo%v6EQ@@~_x@@wIIUap9yExU(W5UCZ>GvUjTAQY*s+@McO?!<_0rdNJuGEfTyNi;9`@1hW?Mq%)m7Y;^Hk->B#$zvX`0 zm^$1!eWOtcQh0Dxx~HLVtMOt_x}lSzIud*KLD~_q0vuyp)!m2_rK%vVoq}~zC!|2G z5MXFfT>2|3jy&RQIQC1WUh9DJJfV?E;+&nDIUS+@vET;iGI8u^{FAtUhs6z>f?vEA zf0ryut?xvJSnL_>%vzlM)6~&E-D&voSPWk466>tQhm_`IxA1i}*Hf~Im0avj=`sW5 zOXqjseD`Te)SRW;ucfrOFD-8GqImL}Te&0pE;3dwrv=U%Qh zy|=FaAX$1d;&XDpb-^~%@~xL~eg?yLZ9nD1@{!TYYq})1(aB>Rg>Q}h3g1$&44eF_ z3u@8QsM8Lx3*@(_^*RGqW={$UTdtUPaB_PvP^XY4!+bh6JKe%!!zN_znO;aC4gx#}mM_G90S}P58J=Zsuj3ttStD))l*pbMSZ~`{7J#h)d!m-`U>0-+2BuH?pPR!@GUu z@6h$8+drE}d9`sH-^vwQo)XGUlsqY#puhy1ryCpGbYLb#ww%w2`!&DMs{2&i8k>Q7 z5nzQd%G>-<%rXwQy|E&zl1X@_!C_>Y6;BX3u{eS*mrp<|x}Tj(Xh|nuFN+C|-NMeJ zO-f8`VB30l$X5DZ`hHd%S#Bb#+P)Lb)$-WgH~8XmJ;NG%ke$^i|1&{mfXk(UXL%Z3 z#t~;ii`ECQO+?BHZ}UQ#cfS1gWZ_L*&uZJQujS>uEe5woXJd1ZM(eJ%<(oHwHaAk^ z*U`Uz^_CgI1qB6T-KZq(%*>uWdNe6DxHZUAM|&o)>U_A4#7_itr>x_*S) zKS7BkN4ivQ9{Zq5tV()O}<=`Yn5vl+O4Fr4*W*yR<4t!*O zKcRFP?EZeX@x^ekebcRNCNs3Ug?)!AfGMXM`|iT8Ul48|la^*Yd}W4t6jhCOM1xWVc|7q^utO9#I!7n6EwwI&%~Wyq`ciqii5h|KQLB*xv# zzY10&Oxp6Wl94Yz|7aY!If(XELd^T_C!nH4`pV~eouFf8`$0ocTU*=O&6bMAM*hrA+Il^ZcYQyVoAX#Nr~qepq3#>(_B%Cmvn;g4UK_6pteSsErN^L%}qvv5km zaOClh#hy?K`k1ZW&HL=S(a`V8;yoJGRW{oBrQMSK@3#`%tGU7Ek;bIjAqK1P!quI+ zaeKXD=wsD>HomhEmMzU(gcvT!bDV2jC{hvoOL(;8({XMyA+`olg>t8KKfB47 z-z z5Z6*?>!~%ImDjle{pslM5~#9yIhJg54&LOUcHYBz=ZaAC{GszT+93-srJpC|=(5I* zPc_fm>s7BhISYF>O0(!$iu1T{;`)DIuPL4VC8S<`2JefzdpRq^zoQm}iTp*Mspk4b z^4{IwzxuhJfH!JhCzvde^GctP5JjqnE+tU{{0T}5V+{?7a7jk_Qo@yi0Fk3 z9_i@nRuh;#kB^V9B0%HFMHQ&I_?RyoZ=m!-zS{h=TvRjyS6R)Ak3`vlvxg>8A1Q!G z)X_rZ`bMID86-Sjq*);9hxLzl f|Ns0sICYB_<%qq^FaK5K?lOfJs&Zwrrh)$t#PC7? literal 0 HcmV?d00001 diff --git a/doc/html/_me_gyro_8h.html b/doc/html/_me_gyro_8h.html new file mode 100644 index 00000000..49c5ee85 --- /dev/null +++ b/doc/html/_me_gyro_8h.html @@ -0,0 +1,245 @@ + + + + + + + +MakeBlock Drive Updated: src/MeGyro.h File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ + + + diff --git a/doc/html/_me_gyro_8h.js b/doc/html/_me_gyro_8h.js new file mode 100644 index 00000000..c88c5af4 --- /dev/null +++ b/doc/html/_me_gyro_8h.js @@ -0,0 +1,4 @@ +var _me_gyro_8h = +[ + [ "MeGyro", "class_me_gyro.html", "class_me_gyro" ] +]; \ No newline at end of file diff --git a/doc/html/_me_gyro_8h__dep__incl.map b/doc/html/_me_gyro_8h__dep__incl.map new file mode 100644 index 00000000..dd8df82b --- /dev/null +++ b/doc/html/_me_gyro_8h__dep__incl.map @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_gyro_8h__dep__incl.md5 b/doc/html/_me_gyro_8h__dep__incl.md5 new file mode 100644 index 00000000..43cc939c --- /dev/null +++ b/doc/html/_me_gyro_8h__dep__incl.md5 @@ -0,0 +1 @@ +7d699f6a54e16209f520d21256f1bcf7 \ No newline at end of file diff --git a/doc/html/_me_gyro_8h__dep__incl.png b/doc/html/_me_gyro_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..4b176c95193057ea924f5241dbc4d7e4445bd519 GIT binary patch literal 13000 zcma*O1yCH()-H+!NP-0jZoz{)!AX$d5+Jy{yF0->=mZ!bc<|uv?g0jO26vZWwnwUA6a~zz28eb8}It-e=R7;UHs%D-(X?IcPS-Eh>M$SNXcdJCtFSx^pb|bd0!u{rQ~avZgO=M>s()kmIoal8@Q(wnNBG5 z@AG;Jvl?0mTiPSRek&k4N98X%*iUWRI3O7Q3KnIFh`d~33XxJWVGIyha{FAZOY;?& zBrofqBvNWYVV6D0N&~L%$CSi^VQPw$m&OA`B2=yn+utM(0;ZBGnslH5h6b&;T0c3F zB12ZSX=lY{>I^>yfd;v#rMOjK6aIiC0t(1O(`jF^juS|pRns$RHEvw?2}Q-VwwQ1@ z7)`Puw2eu&S!ArG9y!(&t!h8Se7R_F|xxIg#EP8ca5Ka*M($iv#axwLQ z->zw|AfqtDZJ`vshFSbX-F8PxRL#qa|b<=pEW`eBXnzAU% zQ|_79&!L}~D9C!%Ukm?Il5-S#ALil$inZa=kpfmyj?4bkm!Ou9`H=e6O9wRG%|7+w zlgC|ufvcoMbA`=y(R`EfOrb+`#ks_mO`O&a%_9Aq_yaLE6wa0A;?84cwP?T`639nc zs3|FxH`0!;q-A+-57_j^u7u2ZWBFWOjOCYIUDIGD>W%Qy_;)&MW71-`klkvpCAVby z5eAQGgC06owZOZ;(oyRZ!Dhj(?wi*8sy&RxY34P+6rGC9DVF0On22dE38uKuCc5NP z<+XVsytrV1iSLVIqN=86cpt#}Vfo-$ftws&7?T8*I@G&@FzbRk%i8WHsDtGv@mz?+ zvzC-Qu$W~hm59AdD1ezo{BuDLWIMeBx=S?<#$@r-t+CQ~SFC-SAG>m241EF%5iIkz zcimzr)Dwo0JdHab`ikv%26?0VZ6JSGI-x6iWA};^+J}*q8Q>h~9FVwlM}KM-rV@HE zzY&TuCa}aORHi$6@m+$zyctV_o2&j__M>~Tu50=PDgUzSA0etv6-Jiowwx2db_QPj zOoPPFw?WwBwoir8QQ?Z?-@(LjHTjgu-{#|FnVycTIIZfB_d*?o0Sw?b z-2;zAw(7D$qeGXXP^*eG7fN$8%fubHM3ty(`0>v5&6NOZxr64pkkrsLAkb`ngt=)v ziAk#=dMdJ9uT=ZQ=z{fHN0i{aTLz6JwwQDCGm(d{0;*)IQ9{S3wTr2eyDa~Po$daT z;$pLD2wFyAe5K>*+9wQBeu(cdbNz^3)7TC*&cieE)yD*q(ASOY+e^!n2D5P{_uZG} zX`S(8<0y{TXbNarAKky=#`!;Tc$-o$;scQ)F3AK?oAjWml%mxHD4-SD8+p~`x?{$E zX0fCsw30da2rj=Dn7 z+o7iuv$J4?H&gxkY2x0i+o+U0Akl34T=eECr>uRI-kI*c<^xz^iyhYhKH#e=QubGB zI3~8-oPsKU#|pufGB>RcA7A#TveQhX?#YEJ)&wJqyk1ZFGw;(c>Ybz1T$wY)n7O|N z=}1l6x@SwInvIu`W{3FKFHVJAUi&=$}j?Tp)B$HR= zTvPvyP>8S-XSeic!C;lX!w&uTA&M|n>Lx0Ic@1RoYlxnI6AkIp9ouF`$LjU7Ze-VT z+QMBD;j=gdClBAD8p5s41yz|z^T23kR4{Wp_Y_9(LCVE0P+XIvlNo4vX@gAG zIS+Oq(`+1Y!?W9oB{({5sC-}n%p{uT-(xKi6d?E77|1Ma%%cX{ZARcSmU^@@AZsq| zseB6p+xO96fQWQnfHS>3E4s~sVlV{I+A>VJTakq@^yk{Mo=KLxe>N`HV=q5!7lVF% z?w@A9y0&=oPF~({_488d)F)g5%e-T85^wO1w8>KY@ zBqI2tqXMi9M8-}84LHZPU)TskKanxI-H%nP&jp-h7kWh;ElR2{x?XFsL*HUy(R0C` zHLn!S`NEAyyjM@U+0%K>dMxvaZnu+yOxrW&kv;Yn^w>dnbLAK)(W>&-f4fj`<={7; z15cq{B)NsXC*L1YuvZZ7ZHpkjlu1R0g!_fQ3ydmKy>|5$Ld7-^F)x&utW7U_s7~;_vlF1s;H4i+&DfJq1YtuXn{Xq&$KA2PbI8x9b|m; z+(wgWVS2{^_JP}}--`f&ZmL~NL$5Z!e8&%!3N3zD0az~OzsJraNfu`>Ae56|4#+?u zN!O}D+1Zope)BDWl(FKsFZ(evoczsS>SB+_pTR?(;ybJGuaemYgX&qUc0zT{o9hwP z(~RvJ2-`a~S0)WGF|XRTUH$N0xv@hU+n?R0Zwnvq?|icDnnWh|`fn~zR|8oIRK1JM z!#?fyO{RERGxxZKIva;6Vv4#MhIxOv#O^&eUaRhYM3l_b&rMD>%5EU#^Y>Sn)g|Q!vwNu z*!k+-#9*3Kh^5(xTra8^38LzEb#d{H92jhhE&|dL_ZIJ%f*PBEgIOb|05|9O2xL4D zlH=QP5~$n3!r8Puzcp6QW-?2vK2L765E3oCwBG+Uw8c?L)Rb&O{wg3ilE%Yhdh2>b zs%~oOSRdgD8EP6do_U9=hW_Ew*s^)Haf*N_3mwcbzEqMko;?mG*22?Tlrkc=nI{tA z(HvA>vk&*8Lu1<9Z%HaOTp$H$etErbHo0`Xicn7D`!a4KeSiG|+Hp5xi+ThKS+P@T z);AlgXQz$#yj3FqQkIg@QIEJIP|y9_(xHoHT40;pAtmiBHO1>5G|^KF3t7j8$3Mwf z?WtwVt`Qa^_FHV+%r6|rSljCcygpZtPW0X1i^(a{7?>59-KM3wq4Ck!o(b_bvo($G zxf#>JFAwUur7WC@iHrAP{cnn>g?p1Lwn0}9c|+&$=m5=lR^{{ArEKkcq#+D>d69aGY3b#8*!d~t(JXTor4 zHG%%HT4wdTo%rbbd;)S@@!=LXwIc8@4rzwj!&b4^qRxOVtLBNhSBLwE##*N1_RoXS zRA?Vc`2NnJ8`L|vX4E4*tB`KW&gKU76`#jF$02iOuO4D=6#qfO+uWBf>~ zvrtumZwg@E;;EKOAs#E0kgzW)WGv^$`cQF&}{HiOq_F@w@SD)C`8ol%?824xx3Y zYDY>kdfkWeTM6;JOL|zTL+ESMs@|^EOQ;#CvaL#-zhs6&=tGrSY1T_HKA9jk(hpJC zc3SJ^J%JYuyB}?Ieuh6LeGqReT3#G&1gqNPh4~9R1hg}VKPGRxJrkXNL8;HKVD}Q* zjGd9Fv#D7mi72>#kU`xWa6HpLSsh<|y&Ma2xy@>HMo|h0?Eav2aD*u1D9Tlv%9V zR}fjxH#KnI;98aXUW%Q{7%=%iUn1q%?flf6$4mTB*s&itV| zY>NB=?gS~8dlzjz{qnSR=4LL?=0vxuQ)IL6Ltu~@lipYRo40J`#e<0r!!bAP9#WGZ z?OyGx=^Do2S}opL9iOhQkI>0dXhm5;T&~nk#{^jG@guRiCtZc<`MM-^v4PMcK=lZ8i4*47Vvirn!s*BOgrNdZX zt|L1?k?_X6-?rC6S{-tolea3!(*NP?OA*$2X{~b^iTb(zY1}B6sB8b>$W?xAY(;mrwTF2&?~~|JM3}php5ic%QrfAR zxNEFSe?>HS`sj`NC4PbWl=qAF%D0JR%l&g@_3+@U=orB-3=ukjpnR}EGqkj!P*HSf z=(amD?%*gw(cG|eLEV}Z>1LLomJSsY?+t1mv2=#|*K^Iq#+N$J(^fF;ze%)M*mw>( zqj=c0Mh|nZEHh-HF}d z&${GCZF%lh=H9(%P9Mcp@g%|EPn=Fyw6~s>UT<-=p;jVhGR)NpMU-owiwPPyiFwnh zdOh^zM|0|?ay1LwUi6Kzb&e6f$|O4A7X*rF4p=lu3XI3IcG-O$&Ag>-;zk|X@I}^N zRBy7E7e#hd^ulkgTfA4o|D@0Tm8G?=1+g)Py+)BCn+Q#@F{i+h6;+Q%%a+W(jA6K@ zO0)munm#W_O%diC0>tpaShm%dy>0jNao?3+BofmLB6OmWUGxlc1lw+Ox+v|?lM9KC zy&@0_wO$uB=1SW@W)$bjgjQu&kPyhhY_7lbjagx2*tmkPy%`QJUg)p><-`t*une=q z%kLS-ho{E7EL-B0;RE8ifLBPpA}AO*6kKb7>Z<@BvuyY*FB1+`dT_dCl6a(1TpiBto&uM=Jx4$z?@t;~uk)uP%ZRu5UMu0+=PNJSdTg@t`cNtrJL6gcth91~F^ z+XsKI^t5eT#-foNZg&K8oM#&dWWJw_e9S*Cz!16mev#O*>$;9um_KXtN-q&F6g-gCqo-nbrF3(#MFkZ_wr*4c<{Vr|sQ9P_90-Hr0dlcb{ zGpshbZ+R;T{I3Q`{K*1>2GMx%#ujx&F{?POWV0j(4_W@&73VJm@&qo-x?hV+m`RrJ z>1B!IR*Y|j7A=Lnj5ag-sa)4ERY>i1i^WEtx_JboJ%1_xR?i^+j%ZFb?z#59w??0% zX7BcJUp=|4`U&$luzYcD_D8sN=X|;^_PYNpM}a5dKTgkC-q-m0SD)vbT;|lx%+4%* zK7v0}wm+a!UGp_no!5Ot4p`{U!bHXHCZO(=GmR2iag$P5>6{SOo1uq8o%)%)8f||m zRRp$xC62Y~@|hz@Waw9W?O17&kVNy27^SK>{S@e^9&N}E!e6S)+R%Pl#s*AiY2L-P z0Nw(QW54SAQQ`+w0)01)l?8+PUQ$JNCfG$K9{37Wr^0JLo`Pi&)IiQ0M)R0HPWt5d zXvrSza~pq>14iq)=TbBf$*A^(7}56y4g473oiW(>YBgq15O54Vio*w_V96(8Y&ped zEt+}+1AC-Th4Z60^w}JdEkoYzv;^UTaWQoE0Zh zc2)_?@_KLL_J*{2?Cc#w&jH)w8U$iQ@q1Ay4QcRjAX=)mFV?9zjD}L#0*Dp^!4Q`$ zMJkd%sQK;0S2}CA5F?zX0h=~87q8wap%Ky~rN(dzugOQ=_Vkw@Shj>Ym4s7l&xhJ} z?#es!gIlUi;~yE0e?;atE>ykP(16nH= zD6ctU57S`N3}w2e)6?sl=fH~9?haxRA}?;dZ9&c#r_K|yhM8u zSX_1paxA_56aB=T`ho=Oj6y;j`*oS1re;5VN;TFykLw-q`?y~~>UAtJdq`EjG-_Y? zKG2O}uPvk?Yva318Sfb%wEmqAs5jOLx(HN_3uSR$5N&97%@!haj}EzxR}gtx`?T^s z#Um9{=VMBy2lSEm130eiW`C9;75Cba#UYk(r(->fkVLveFsK^QxLMO>49V>UyugrQ z9V1r!I?VV@|5-YJJf|dgb=TGmDU>BC=80bQ3{o@LM;!i|4gk-Aqh>Z-JAn~Sx$G-u z$U{-h+_lcKZ%z$G@yfI;L}CT<*w^hwNtdkp!bEq9XOIt~1@d@-gxHfOtt0o*SSuzQ z5c}6!=2!JOW5<3CCK#NRVcywZFt*Pj!3^URr&!@Pz~}~7bW_LecZP*0p#qU2FE3y5 zOKP_D`MgQ$bwj&#Rc7>7g-Es$1*)iVVCP~0PN1*>@t4k-(PJCovAeBVJWa(?__*vd zeom#f6qj4|U&h`MnoAd}vS#-)|x~j+RtGL+lemtl!hv zW}5BGcwg)kM41CLK24{e-T`5IgS#2On zAM{V790!eFERix{#_)eDytsoEd#V~(nIpqNHLMERf$uNC8_f*x#BZjRX~v14gfaBd z5r)|G)yh#<>w@{B)xGf)+2^!5!Jn`_z%{`#66A4mm+d#=KM3FJ12kv<@+~H(oz_=- zMrbUZ0-&Pex|9st`XsBYtxAD8 z%duF?{?pCK;ZoMj-F{GShA<89z+D(B4?if6ruv%S1_L}w_Pend6qDw}?*uEB!Pcp8 zoQPW`mO-pMxwueHfK_32>{oeBq<+tyNLx7*joS5Hq}4axwU<<-NJh57C%^))e%a0^ z?t2{}=GjGrRz3A<&#?IMmmhHetmU=Co(ihjXvTZ=W|`oYakZLw?2A9ZGLYQ0sdzo- z2Cx{!vZs{F*8qx)Z$UebM}T0BHn4?ViVt-Z#Wj=EDSf&L#P?J-o6`&N5J2i=htSNDv55LWP^P9jy+@s0Y=}ZDgnJi$9;vJ%zU1{ zrY3mURlL7=C%`SbZtttjkKMuR&gy!kF`u~D1G?{q?{@+bZS0!I^rEBXM*m0Nu0YKw&bB84E=}0l}A%3@L+|3|N zV3FCtyKBA;mJ@OBJwS#s6G$C`IS3ty*bK?1-!pqmd9uxshg7C~{qjS6R%5iafuaLg z=E!pWliF$c8)9&#%hP6T$hG(qdva9%ksf~6H1Di|4nhlDX}^UmSp0q{s`SG#fviL* zMb>}HksOLFDiAX~rz+OUlhJ)K79AyEpaa3lMV})-k$xs+qp6*v0I!cz@?v^M5HNbhfJ?0Yy~%@QG5) zcr*q%nss%*>c9g%02CbHg@F@Q5~J%cy=J)-!YV3JR~v_9N;WgQ=P$ImYRnH!QV}lY zKjQwz+?lwf|7dUho7u5nhvlz1a@SozXOY}mYT&t}aacQzgCE>dy}yWmxpC*Ioz6+& z3wRM^h6L%A?4F$g?uv_QsnZp}280dJ$I`^$50aS%?7}snIg~qnc&K|a87gEjzReh; z@en;Tls~wsBQ;B=2P}W-@WP;?Gv#vQDR9E|Gk2WgrJ)lgGy>RtGd+f74}%WAY)M_M z>X8L!7fKpeBY#g3ZPyE~x~jMQI&cs;6bC^OH zgM0te_hy=#d&`x6#emF}*DFOtQn~I8?_84{8VPuJPpN*E6{MZ`0mL>9pzY;1)x&{S z?zq$aGu~GvU%`gb`%*M|ljT!p*voOIzH9lJ-IQCB(s=P4-=VLFI0Pvw1CHAm>MVG^ zd7!ZvSWuuct#v^fj@2Ff5;K+f0OE407cyXB_Or{v?#4MF3qd<^nrX6<%D<@Y7RNyU zEBOiJP&dRG>Lt>PfQJx+jBa)rI))j@gML4(7}_)Ze^vr#?^WWUkUvKkfrCZ8v1rRY zP2V7{nFT-b=yd@Yk`xZ(#P-C;@>uyhn=lD3ym`c2xN8HBeeZWC4-w8}+bwzF=*3jZf}=-%Io;FZuRx6O zA8u2-7i6GzG>D&%Vf%xM-m?GkQg)R#vh>Z1j5nBEVQBiZl~`u*+ft z0e20TkQi9Ox1CjPSqsD*{RrDXI8mTFIhuxM*ti_M>zYAjW;X8T+RtwX1{vIbdHd}V z)_ph75(NmSMB(nP$&rt}wf__UGt6o67X9VP;7yNnT`4oMK4U(qSx2x7#LXr>;utw@y!~Rql|Ey$4X*e6yW#@`*z?E zEIQO}*f<*#!^c^xasAu>HVNjy1MxA`0pmFGm>!ZQJMZ${C$uKzC(zOT6e-LHu7h<7#f>5aThSHHPq;Vd^?l%8RLUrq9$N8iIF=9C+9xV)UQtR^qIEtfNq zsTv4o_ec|rRkh55?LQux=GY}H@6&3o2m`D^jtkL3^3~h`!NeN6G#X=zY`)*}J2^Lg8i`J`YRYX^dfJVQXv~5yeBJ zl~#5fw)H2`A&9UYJVs(rE;0MS8L>|l+L73y7MG9_hw__ycZ+@cPogq_IeJ)RB`)}L z5Usym&U>pWSua@ud?bDC2yv2vsKIAhTmG&9EMt@QNaF@yT*xxZ1*%7*BO{g)#`QS+wzb18r{~$soriqq;T)DY zW`5G-K5aA;7G(O7veDPheMwZY*rtj|1WcB;>MI@Qx@!^L65M?NDMKtbJJ<5g)JQIB z)*lT6hgS{=ge-oSkfIt(v!9c*OY6_*J8seAz)o#@4{014Bnz(l&H`9WFF-cGNo*GK zcU~WB7GqAZCV8L~e&r|#`4qAnTj=5vT5(O+FRkbD^d|C|eck@N*+&o&l(l#skqmS2 zJNXRi#0x9$n43h@Zr8L29;`iDU#3dx)76d48C$a4s~>UX<-B@{T8A`($>P$CF8Mjt zQ1#H@q23PZkL176h2$9o(g=U~F#SW}3o-51W%aDRq;V#7dCMY4r{fsI+Qf%-fOg}h zWgB!*z$k(!HO4ja6-M2#>SX&3&FGq5O(5rLZWt2X_jRHzpjD-WMQTs`8ZnC`6r8y3 zx9O8Zt1~uVz`R)s4{gBCQ-mkvyD> z>y@!RNOVh+m;u(%FYWk(k$LmpZfQZwJ}X>+j8F^cM-V#YTMJD=zOMizo6!7!NPltH z%^Bkw8igF+Er}Uo_vi#oVazaCUJ@!F?zRXev;5JtDJG3Kxc|QqVBvnAc2a)i5DO8zIlW?{e_J$h2?D0CE_ ztNOFB5i9xHSUPOnWoMZ;hQOYx$xkb6qRyY3R7M%p_CLWjBf2C#D<8U04?*wLN0^1DL%>{H%GfooExrY{5eqyp2VNkqwEip8AD}$O?fy2zTx?*F>~|O=QP@y2jz}9-gQUuOD08 zW0>(KlNpwtKgtHR5;zYe6ap1#{>GbX6m+3tsx-GI%32Ms%lAjZ^m6CB|F%WZbd6k8 z6HM>UxA4OZZ=ZXxqN5ewym)pyD64;>oU(=m#G;@PjGwUq7ovqM0gYt176L4_bEv%9 z%m&s3=M6|U@ zRquBQY7?n^R=#pRUN#j)#5_O!ytzv8spz7tkNWK1UQTepLdMDRc#Gh_HLrd&>n?)l z&Xqr~EK+MVUA&5Kylm{nl70lqN* zzg+>|9os7}MA|Q$yeS?ZoA4QZKfQTaj5=vDbv`oLCK$Q+?n$siI3n9#@8mJ_bJ&3K z^nIT(?x{sx7-Y+{EkSN4H?k8o#E^G+rm6fD&Ijqr4l`oiAk;tX-f-2g+p}ICFu53P2fmOGuW^Cli=IP-M0)d!liPJ{+ zukV$?sjwF~Q95kM)!Ez`&rMBLBfXbN$giq87oyAZIWH|zDa13rN*JwP4SkWww{v+B z7mYyN*y??A{%|qwjwsRSp(-GKgYwWp{(H9lc%gxcP@!@WNl9Hr#o1O@S631m^LWmU`hd(ya2Uab!oSKt@xP``aOaw@Z} zH2|z+BPY2<4_^^JP#@usc)ZQ-R2Gk^7bYdDHH`7H$a ze0A`AtRgu6jLg8EfERGoqWTR~97ep~`QO(xtw za-D4XVE#~4J*dKH7+dSnL(#sC^S1u*STd$=YV_;k%M6g(v(4+Dz)*$z=OvHBhVNx* z$Us*E(8F@M1OQibL3E$?XZPU+Uxr0~VVUv3_E=U9`joGrMa~Y+4$LY4c8`p#%$L6| zNHb&uZhEo7ZvjLGl{zhHCTlvP@^9il=7mirPA$SnY;!W1FY9ky&?rrtpc=R&!lYey zcm#HmSz4EZw`c(YU6Qcl|5y8~Qi62KlaXRKt}l`FmtUf96Bs_TGvGE5X=N`4r=I{>ST*ZGn*)ZqDUxbE4rZ;&GW-H<1xa3Uc`~Sgu_<+|3Yk^^sQn~#`j&*y~ONTJ7e$tLo~2j6qgGM!{EfkAVj`HcZn?cC+n%dP&PGYE?l zUm@B`q0bHDl$W!nSxXJRQu?5KJ4cy2_3*(DT>7hPP*i8-_CnidC)=EH;gxZ}U#=z# zVLtVVCp+4^*Gk{lMT4H_#2%j=hGQkrs0cZ@RD)zz>wS!f>~y!l(o7&8b`1)nSnFmn z=JbQ!V-HJzB{JLJZ$3AXhy1-y^43m$e?&cN8)N1_&BDQ|T}tq}GE-EqJDRrK$)5Em zkIKMN9G4ntb)WhDuM-#<4c>Dl8uPvKHOdq z`Zx{MWr+IPQ9a&Af5=}@=-U_MO}i@AC3)21tBvxhFyzQkiF93IlC10{)RI1YTBU_xl?l&w_t2!HP{qSNQgWK47-(<&c* z{n&k^&n|Kku~2aS)y|e}>XlSv#nQr{2IF)?q-{%WRD8MlubY^i^rU#DbiyZJuUid4 zXxXFm@z7EANt`{GP{z=wPOqxXgjbApK3Oez_hLhkd`n9DD;{?6x^R2;b%n+~|HPtd z+fXa|&>X?Zkx7kWD_t?5gK}mM9z)2N8>1_StbY~OhwQ5nHt|*r}!v_hO z@UVkf4cipZxMGW0+bY*u<`l!6H9I8FSCc4OUZQj_uo6cBEz*s?1SgE&nejqfTLTtG z94cavNULR$c8LLw;^D-Ea@$GD%A8&DXA9J1H_L?&0a?w`eallQK4 zZYV%U81+vRrPVq~R_O%$H)6~mCdYki7Du@Yd={R?E&P=hY}saKFMLldZun+r`(=p( zC++BZg->E!baB=RI5HQ2j@aQlu)UM7ecM?wPHpN&ZK@9R4?AQ1Drlcuk$s_F_`d6* zT%$jFedg;gW1aG0++v}(CJleY)rOXnU}3Xrf;)Os*7mcwiHAgLmnWqoYfR)AC5Lbf z$dHdx*~P|Tw=yS+SU_$zd6CM6mmZTpP!67FlewmT-P&67Ijwat70-FhTy#Cj( z3-rkXO}hyH{;TkBI1lb$^X$KI`he09dl0L>aEhZ8;q4@-?XCMu<)-4O#&b5bMC;jd z)1!sj-lgd1Kyk`=rkSQ`g&}qJMWhbraUu1x1ERs?SQ-wn5qb5;8zY?LF?DG77im2A zXTH-N_8!XIq`!x+%L@w3ZaRZdrfE%hwIgdc+S=OU;1i>2{RjnoeSPmE8|-QmIlhj# ztsmQdRIi+2J^NKuG_PCgdZ0nsO@GcVdt*dXu5qKoub*6Klo|I={QuXtzMyB+KrUCq V$Yw(a;IAog(h>^d<)Q}P{ud@#tL*>) literal 0 HcmV?d00001 diff --git a/doc/html/_me_gyro_8h__incl.map b/doc/html/_me_gyro_8h__incl.map new file mode 100644 index 00000000..436c13bc --- /dev/null +++ b/doc/html/_me_gyro_8h__incl.map @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_gyro_8h__incl.md5 b/doc/html/_me_gyro_8h__incl.md5 new file mode 100644 index 00000000..eff6e2e3 --- /dev/null +++ b/doc/html/_me_gyro_8h__incl.md5 @@ -0,0 +1 @@ +257f0adf539905eddbaf2788466f91c6 \ No newline at end of file diff --git a/doc/html/_me_gyro_8h__incl.png b/doc/html/_me_gyro_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..074d88b23139c0278557b6cd017adad78103a1ce GIT binary patch literal 46392 zcmagFWn7e9)ICghDAFmRba!_N(%n5E-CZIg0wU6lba&?f(l8(?J%}*UNH^~V+|Tp; zzrB|q{DCv)T<7d_)?Rz9ZKRrtJT?X?1{@q5wxWWJ1{@rcKO7vq8X5}l8+HV@cHl1* z3nh6Oxci4cIUPmuaBwf-6lEl}d@^>IeSM6rTkifH)Omf>uw_8wBE&$LOlo0x`FEUh z(T3hpvKwEk*wHIZ<5?9w$Jdth#BU<7g!M`G$2~W;zc$RZYUWt42Cl-8pa1_qTNqJ7A)kOprmDQ$!I}G7 zW?Jyi?b2;rX=!P49)y~PCQM0X8eRr?==^NX(7D@~x5z1{SefV}e z==YCEb@{Je%(|7)LhnC)!qSj@`qtw&{k6^>KK1ZmQ8W2J{O;lT_$*PB=D$b!(=g?K zuNy}#^E4{(@xf=gwek<2Mfu=+yxDQE=x98bdF^%gm;LsV<@xhCh+8hs%ZDLqOMriO zU36@6JcIfBXR|IF%E(w1Pdp78X=IAeVb}_DY+5eV=BJ_I$}ib{m@JNRaq_Hq%yDQN zqEk9Xz-4H-H?_=aka*pWd<7Vv5GnzE4gUBOX%bU#p(rV5fH6m^GCSD_sI6W3YW%*2!R@VMQ(z zUu&!EJA1<>VBn8EL=cOw3Q7mA|c;U(#V6 zn+8VwF2($~nfdaqbundCjRB53o$1U0e!^iOrEyJtIvN_pa9Ik8hv9Phz4w<=ZM^1w zM83%Tf|nYqGh1%dg6A#n+5H~5K^+8)*8SfyA3px^nd3U%!w#8OSQ^es7|hTD>m+*$ zot2*E5b&dP%+uz^g%+FP_E?U$zI1)FVJ@MG7Ch{@p_<6On^~L}`DqYb__R4za7Xvi zb0Q=c25>D~Mm;iOZ%X3vyGl@5;r`kJ!03{C4&TnApFDNW!wqBOB%UOdJRh6kY#!0CDyp*rg|`NswRUy zPFf!h+~2>a@V2s3q&>OJ-TLbjW)l->BhG}XjlrIsl^!hzih~#6U*aFoL%CPh)XbXB zlva?k5Ys|t1nd#=?5YNQ8gqMkg6?X8;8PVpotg9Dte<)E=j)o-6Yt|$ecf*t^9Qmo z0&!B(qBzk7YHu~m$b&2={<7XwZqgZcwakrI9cLO?D5D|tx7Bs^BDwcl?#gcx1=Ak# zvuMHz@*wwbH;U-6r&*C*ZH?eRj}yyz+OHIT=M`6TVv`A~@!I#IjhMLNr_T&l-qqY! z_`RzmiXqN~4UFBVh-zQ+-1}9wjGV7H!EO$77%juPmhRtoT^}TshksFchBUYAwdfd& zkTLUD*ui#9FKoz4>N8Wc@ko~I=4@nX~;KnMa>l1n-u?t2MtQ0f6GarRlri%~(!6f_48pTY0l z(H~1oL{?^eMPD^!@wbK`N;|WMm?3a<-Y!1hOYX3#7UD@m(4!EtKZ-7LVyzE886sk& zp%MKL9IleuUVRIoTt}6Fci9;HO6J7Wh+E#y=y-Trk$BC?SKr9x`47v#Ksc6E#d^GO zGe1CiG<8=^!DeGTV$`QEGeLSd=ev;8{r-NSI0yN{{Hhs3|C$wsARKlC;d2s+C-73p zPK`gZL}-SGt%E6A`eh9bkiRKhQd@nF)O9mptjsX4@;>+NZQ0!_&+Q3Ij$K#qeodzA zb%CE6?~|PqIHC(-6VdanZ#df&B*kH+;o|rYfy&e4k2ph*jiDY;{!Jq_ZL9R`acO_X zKP-qkzL@lmc7G2Wi+AVS=VQc#Y}dF2G{+c_&X89;in^nD*Q*KB=<~)8 zyw9us4#@8eIENN$GvxuO)tCn`frh3-M}4hZX~3ntv4%LRPmAUkK=IblsULR7OTj;Xgoqqu&v{5VI31y;R}~OUI1b%U<*| z&Rv0--w+)BMd!6=p>4itb^=o&B~~h{et6C7JW2c448hSB6SZ$%K98%= zeA=#MH=VqLYF9*}hVczwP7XE$;0hW0)wI3RFhV!lb&-6#5`&WC2`b zql_x1RH)}mQ9PiBcl~T=C2N1iP?R;aQR#TJv61}qC#={1-A*N;v5gkeLF7s&r_HNZ z+>VyICZ-xYHR^d6H6-X^E!wVzDSOdO{#UB{9aNkBpis?_-a&lvEyDyLqD|?+oUezCtq{TY~PLuGIisEqV{sOO1uu)*1O)`u? z+^1TWurr{CEosfXC+bFtqKM#(gxE+)^}nMWpVEJl3gN;jxmhe33ii#)X1W?`Aw&+E z{TCWBGvK&>X>eh5$?82uA<`b$>!e%(F>1YKTF$FpQ!)9YB-Nsy+%01mG#I&YSzefdm3jd|njy>T$h}y~-+QBKzB_h0txvsbi=R z-@6UA^{Y!2XHB)+vYm<=G<(WLRw-$wFk#2hH9V+@SqvG`EWSaY^S*x4QRMzK;&{`h zTDwo}Ei;1w7@!hiX1Qo+K7&m)5D1~+{d3oP*HW^gIQ@S|G>6A2HN~|PclfUDK@Ev` zw&Gj|TPxI>aH26aLTJ7VnKRmbXKwXFvUE)UO%ykouZk1Bvn2Q{#?TF+GchKw8dez4 zDqSI55=UJm%j+y-JwCzHv?5N}L&RcMDD1yh&S4qXn>pip?LB>&J6S`)g8iaN4WR<@ z4uuE4j5BT0@y7Kh&$WMkw`~6S6Wo)aY_7mi!vzCSi++4(qyN+Hfc;j5?luZc6DE8P zp?|&+O^_%mZ73U#%1+f=L~di5f$)cPiHtOAw#u?)bKWXp^+5O|HR=ZlQgr11F%~d) zUC1cc>Sq0sl`3j&)F3$T5v;7xc6gFu0Z>8c`|ajeb)NUN3FF={8-AzC)L~!saV_ED;>tQm-w@adszyhU`(wr1KaA=TcwqpUQ`PxsFXZ98RT9pXKR9Ah8**xm3t0*=DD+<9jX0C+#uS z$(m7CQ&roME~1&K+ShGnf`Z36BhNzFXN~SdA8!Q zD^YRW)@L2YHhg1&TyGTPO6?Nlx#Tpu(BZFWJ%0F*?SlpdRKRA*Qn)s_MQyYCf zjsG9!D00vEzR^$Q#w7M%xeCgQ$gKY+$gN)yf7jmt=7|t;6KJxjtr*(me)CRLM-5y7 zX5qHcCRi|@Zx41Z*^R?_AWDvQDi~0#h#~L@n4;z@@_d>uFL@$xUxo2GAkeR8i4qat zF1@nPlxE{e&~AASu^`+n@T#i@w)dYHY6q+HpJMY>i7pVt&&Cg92`ieUCSqY}M6J8c z_+~Ip#`{@#l)-ELm^WM}dk=JyG)y_4ag;!n;bntpisHrX1I`@&Re4i-WNRNIu=4e= zz}lqRI2v))TO`2d)db~Ua(ggCeO)atG;$GhZ;!z}>VM!CrR0bpi|j5+a6f>^mN(C0 zS*Y~dqHLIiaaC-tWf7|9T{wq7FFhY5$5*@?S5abnl96nfvgz`ggTQAdhbyFXxVeMS zv-7(xru6q%xJKu$KfDo%6vrVJ)kkACcloT|G#&pPyJzpRN8Axza>$w*^ILYmSlI7J zfgTT(TQMR|^;aLy8quFb<3lKkqLbPiBR8~LAuSS&)pgRME|zbpab*Hamt53Zm(F=W zzX>;@P@+O)Etf46b+PMH3aST2RDY2Iq&Z9XE~iw5`N2#Ee_;MN{g$jySNf&uD6_6c#0RUIU)PwpmVuvJM${I z?xadrV5~|Y7dvf{#$_>7oWEd!mI=@!vcvN`@sw(zU^(q^r{iE`q7%PB1hx0Zfg={! zFToOjJ1E!ZyN|95v2dT_PBYz^w&`bv3oX1$8=2DApB(qPpmuo+u+F`45J;M4D+WwI zgk`;~MS5ZExpY?+tU2VO(K#wUNw{9NnE>zT#Nu|*Z6?sI(&~hX_#OAPCSMim9Rd$L zGcTq>?o*vkhY)EUl;799lBsHbLql=YAS-(&)df?ydIdgTZpkkktlT<)0aI-h2qZdu z-{nj(Bxnl1%~blBeRLf-;E^_OW3&sYBtA!>o?~IC6_?9=d-YKVen_I=5%%(_64_6U z7mk`oGwLWPn?jDuiWYirDSs^EF$Te9>~M6wcEY?8l}-wH;@fwA<34Ww>-AhBO#VTba zp)?$YNJtq)$I^(OYm9=Qz))%WUw*KoIl;tpFxy_TEx}i-C-EarEJ@)KOUeoSi=vrP zJo`ZAl)o9qa(v^Bun+e+M6+}~DVj#UG4XX^VfXmf$$b-!6Qo4?`{=jss`3?F%rysY zn>fLZt*e;+G15(u(H6rk#9evjh!-v?f)U>sL(b@rul2dJ1fOGp5(Uc)EJP}TovjR? zj^9a~prSZa$WExL#m##@w#qCUcDY1Ybb@m>>;~_G7=DU&UTjwWq0Z97tU_G$zR4gv zs5BjjNE)s8rj34mBxa4>ncn0oc1QpkY-#ys;7vTKICT=wl-M1zL5R zC&Fk=0tvzi=XEtCu+HjKOFCLy79<$#v&GKHX8*KUUhE#}pmM3P`f7BI*(rcv(ACoX zi@UY;l1Y?MI+hVdT?mU+E^72ZDqJ+}@yZ=`#%o-?$U2Qh@JIe9gw~(*Wy77=J&Y-S zKvY0=kfPmCkrXl;&Mi5cV>muZoJ=6nALPPv0W**?ElykgW$Ie>c2II}?Dhqpp(L7v zd3iPWW{T^Epd4*KIS z{^Vi~J+r+(d188oi(tIdApZU#l-P9l&G$6dmR_BB^Mp^kFZz(9>Bcr}65xY9U^i(r z{yf`86q~cx15$Y_(V&&L?!PJeW`WJPQ!_ZAPxOh6-x9zgs#f ze>Hp~v|942|AWdR_%#A5BK%%as9-r?-cV-Z8k!CZpo+D+9n>at{f1U zwEK-2ubid>ZLE_4Gywpw$rgv!+Zbk@*Wlnw1Y{5fnyg5cwt zCn(Ez^ZG78{jt)m#V#1RwN-LQ>~{rIZ1I>H@{HY4dRD##P%BB2S8gLkUa+Vt!W@z* z>|L0;>^ZG2f4X7$@xuUBF!}$g$8p^imS5|7gUSA+xNA1Y+1snso&s31W~VYdfaLN) zP~NBTMi7G-GbFzMljFW8j$IfyBRg&+JQGz$S4Ripao*;&8hCzpfrrx2b$@%1GGDT> zv2k#H{EEI*;z3nHTrMx@)K$S*t^LXsy^0L~f=Ic6J`d6$SimSgz*Q7#Y;0_sd%orR^o0c>Dq zH!%LlPTlo4T}G2kKvr*F;-=U+W+W(F@elkt&Vv*&PzGJB1(F0RTwJg6-+QY{io>1( z+BnJK!*!OKWFH#aP__9%v8grSI4QyE2UI>kGRUymD!-gN|D>h)dGU|Vzf8zUcY_qQ z)s^0*PgqVDQhfd#JwojE^@F!D z*}aT+YVr+IfDWWh`>D%-`qxfTd0!g!_jQs^c0vy<614mF7K&*j74BObChpWVZDAk# zLvgU3Sd9ExRO!Eov2HtX1tii3;+oAl8pBdAMaeh~M5k1v-F=|*%QgvSrObZPPj;x9XfL(i@{6rqVEU911EQ%G z;X-yuYQbp`d4B^+EWJh$zoU_n=$J{gP&U>J$WNSmKA)8g@s@uXz3zmEMy-jkM$f_S zpNWaLi5`Pb0%fnpr3Mwr<{>Xa=f`6VNXd+BBi**q;)4u#sDjzmBRHJN$gBBQ-ZyFx zbsB#@ubC=a;m8-tWWn?5ThP?UuLsNO4r9PVzdI_6-D`3VvBe4vxD>v10pi5fegk3~ zuX8d|7@VP%#v#FyRi)VyZmOSvQ|5q8@yas!$yhOuwzm!@0*7g<~viG^f2 z@MU@T{QCFZ@}&_VT|L-4)Kw0t2bl_27En&_6<*ljcJmnNAYzIzGoYQbjva*NG$g(# zT|a9o=05FD`W(Mc$h3bK8k?2G#pG@!Pz;FPb3gW&IoH*qgFixg3lvS$n#a#$gwhpE zx67ogUrvoaczPtY|EEM(6T+s`B&&_f>STs-zsDqyRsE^gFcR%Gi4}_f1khmVjHnlk z+2+*z&+xi!FBd)Yb1GYO6!CRe-r~=QcZj64DG_tcP3Bpq`$Z^S*P{-Cthb zkwpoUjdwsi>;MFhL8(d}J&m-J4HQ$7T|+r*9};0N7WVeT9@LJrYx)MH2*FY{hcWJi83g1(;Aou4=wil? z87Ifo76@Pc_I=E&R%*hu8;i*^{<6>;WC0Y|bZPTjeL(I0B4nsaw;f2?PXTtcq_jM9 z5%2V}Uu@>%&(W9hD=HkMTo8`U3yBJ?vtSi@a2wQNc=JhL2t?*raCr6X$dUmLh4qGj zfU@0#r6}D!k?c}J)}4C}@S(`^AhVhPL?Z-HHMat)kz6L|rCKQMxa{6J7^SE?DZ@sqI0kdcVf%4D6Lk8lC_tc}o|5 z)w|iO8DEsbu%*@DuPsNd!u|HI1!R1ZXxe^m08b==QW>a3YZ)sxeZ?ytuZASRxez%z zBQz~0p#5>YuKusLjXKl;1^qpK6I=mG0M~ebg=@&ycuRJQ47H#B?UIgc=G%Pf0lrFz z_pbp!v07Rq3nvg{b z6)upCcHHs{fPXgHg-$M0Iq$&Q{EVI5Px8@@!lKxCE(j%Pw#Zyecr9ak?Y~|I{Vk8| zwx1n7e(-9Y#AWhh>v2DK1)RCv+p*;1>BT8rHEabief<5*mn5T6E7t>rcHHTw!&5ied{DBYx6O= z`m;k-5OW(UI`)g!;|w?Ymg045T~+rPwFDd8w>y;Tk7rVY8M>~sdf>DPp9&j{D)Ykc za+6hrZyUOP-UwiT$b4>6xQYTR5wnw&d%|8t6IsHu?_P4S>uTx!sxr;P!nH9$PAnMd zU~_TuDx!`%$wq+LMdc2HpCogXg!z$MaLTc{E9v)4qoC_Hv40)&74QWLbMF_KEs95;$$P8b2!q~^( z0yHwvnz1T~e+=0h-_RY1(MRUT>xozLrA4IP1v~Ygzr`v$AV>>v4s#(%Z#Njl1@>4_ z(?rcQfYL8UC?4x=qU(+x#mV2oY-ZE77Ds2UkBy_{FQv|~GDQ*AUA)CW)uzO~J`{M0 z!DD8g1Eo1%d?mZ(vSto#=cj)Uov}lsYyG;W%)38@Fh=^ZSFqKh0vDT${85aH8>HL5 z<+hL6!Rl{uRT7FFA$nWOp9e{Fv}Vjs@!AfB8M-q#1#9vYk11ZJ9QF;|nL2Fb7UwDO z*H_KX{~pd^XFY!39)gI41Bc@x0FHJAM-sQSNed-&#GNE#-N_ZR(cmc0510_uRl`9b>SNW^e~7sSW^2(yeyJ$Z(5&m8$adhWS2COO|alAq_w6@+*_U;0@lfuGNGYw2k?mERy zAHhK(yX-;B=GWMUc!$7UWN+FynQ%>AZBYc=EB&AK!bxoNEHmzC&pmS;aHZX8I0$`4 z)|x_Vc+eDdRBDoiD%qKt7Z*pxYUb1Xju6CuPg@4W(yGt}Pv3Q~i+7~Jg3l*ys+JMP zS2@S&gV%TJ+i!y zn_O>E9SLY2@klH5pd7~vXN~<9r{G88($Q@y1&iX9J%bf<4}lxZy5Dy!2ObA^4x*;a z)4IbTftP{eMB2m;yo?fXa|Jmn-C<_@PDAJyIveoiy zC5^tl`tYpqshxp;RTT~!2V1c1(9B!K`jMtnxRiDWBccki^j@00jSDo>JDg3J_A`-$ zKZhH5ab!BvcP682lB{sGNDR^@T2O60ZpQ&6BUBj19|m92YO0+q@~rbq0Vq<^z>n@23pk+QFr{KCz|`rm~3JCV2( zr4Z)OGC=mToA%|??ws~kgmDa+yFKF=%j^gVwz!$ip>|1X%-)=41ujb^=eh%bC&I3T z&Gmw}|54NVs|HHuUva{&K!Nfnt)wxRxhj46FRcY@I~g%IA-;jJclP4igZrQYMu0|v z`GIM)RSz0UY7u;u@hke6lwXfF@|8F&p`3Aj0- z_eF4SdK7;SJ!Y(~yBOR@8nt=+AR}ZKg=DKd>vLq5quRdo-vS>w8(kS-@{(MTx`iTy~vF9GA z>ULoVs%h?HjEF1nrIs$1su+1++Ve1)m!WiFKH5t`t21*DgKhtf%_BE6@~)f-%B`W} z)pe&xd{e|un2I)}GN3@1Iis=Qb|=G%1M`BsI#bdTttoa8Mww|;@9VB1)*tPfFGz<* zd|>ra77-a(9EwO--LM(Kp;k5XxXp2Prj@+iBs~cW%2I~Dw(QwrF?S@^tEZJQKbR;N z?3?xD8=O#K=|DEsh;Ih51o$q@93#>C+Tny-YC{hmkYsd;jq*S$)-ICB0pu11yM{dJ z+>3cRBcF=E3dJ$_xet0X=j`zNVUpS7q5jnO1(VV2;gEWu+rSI9VSO5uLRPjUC}4Oj zfv1>_a)YHu@G)aDXjo0>!QcBoKc0L$WYLm}rX<&5arodousz1riTt+I>BYge;n5;k7&Z|fT*ezo zb%N-M9%s;#JN=^1&OW`uHYogi`TQ%KO68Zuz~v6v>o=jRKMdx1)1Ch;D&?CZIucsS z&EWg<8J@3b0VQhsKVRI`@PFt~Z0{iWC6gDhwNR0JyPO9LP}ktX_HQ(Q$}`dz*sl@% z>rKDSV-Qy3fvnBSSJ=k5!}g}zzvr-QZ0sB1mY;-7JyaO#AUu-YC*+LA@}^OOlDbE1^~0iQv2Nk{h3<;PN@Zp`Wp`979BSS1I6pt7|{Pp{7A&0!w@p@ za<=+{`DSqm{oyJvn25KSsisxe{*dUK_@K|--#9P-So?cQJjlqIBg^2p(0_d^qe$CF z+(29=?KO;;< z0!{=X3*E}hRIXoX+dwX;H#x}{U?75ES#U&X8$$EDhu*hiLBJiW?0vPFp{{M^eRd(1 zIs>n(J>Xd6u({&`;TjJfXvSXms1<4UHC#}AD;zc&oh=&j+RPP;@Z3Y}+s%OBh{%0K z2s)?0(wa*~9_JUhMpQnyGIAYgd36ZE*p82vfP?y;^P`AqP|PEM-Q3!e>il<3KOgiI zj%3fYkz?bWndr}+JH?bv_uOLFVymKrwCKC|`Kh&LX}1OJS@C<8Kif)0w){UpMED`d z7EUZ!lSZ1_4(y<7eQU+8(KU>mb|EM2juzeAm98&w#a|ZT^*=XV!su>|ph7u?Eva?M zqxCU?m+cTHCJ~=4Vlns(^L{%pjzFvd__z1eO+d3l_AV}fon*$~Zo8CEoIfAh3(%wK zxKaPw@l*EelY}Mui}u$M5D?0d`ztWKy($Mc&twh&v23PHrv7P&C=Q{KI&7=KalIKeeIAIHF#5T)iv5u;fTZ!D9X-fea8z* z@jGJzZKV@VTc@|%x1`akK)X;1%a6rUz%xiac88W2ttT*id7J%!=wzt~8KLfY&xCkV z>Y9B;&(A>UyhaZ#WB2?odcFd2c&!OXA!qaK#E+X2H}C+`6i+~c@l>nmBrYGUi;Oi$#7P^Q1vHdSWC0`#e<7GPiR^}!0`FjNNZC+;P!vhW zdR_0Nk_j*iIoLQ;Z2GyuV~Yisil#WFtQF@UNHCWk-MFD)(RdTfYI)D4&$X^yj;Vp! zRHRY=>@zqxR7TIv8l9}|PJT*a(j&Y=kp=simGu5jlcJn3gLP^?ba%V{t=|zbp6?xZol)riJvAiosMPYCLJhjDz2#|R`KA~6Ra`=xU+GjB<- zqo}u_t^|;(_TY=431;ND?YsS=`!`nROO&yImG2@q+%%3YI2j#DJg}~e;013mG%D!- zONtUBbM>r|hw_Mv{?r&N0QW*)DEr6(JDZ4P_$e0GKp2-!b~0pbz6>wg7}cETX<@_k z@vTqq?D+SQgI1T6hrXqrIq8}jYV0h=FhMUM1G$I?q$1yDfLrnxFv`9cgd@3#arB#~ zlCA3N*#`fOg(Vl<9Pclo2UGzX2IzPt(l2-rQD+u^p=G}Pps_w%$E(cxBmMafbki|4 z{RDkK!N;cfL_XxTd(wv%7D^R*7&cM?cBi;wMhNH6jP+33P&gm#b?S_WF(2Cld0z{G z`=GX0?mHbEJo`u{FUMe|Me|V)h&%YSAb&i@>`?a(693j?Y3H>zUi$f~Vt3h++qwMN zwPb*^ZB#mR|N5hMLc=BPG3O&e0h!#B4q8n%%;$rRCImOL{$b&Vz#lEQ&=R^inqnuf zWXKGQN7em+Zk9G@W}jZu-#X*)&Kt2#kHNArjWBQWTT(9(9c@(fhv`3ZjAXFGQT6!Z zTPhMCaaXWy1xMx|I6!JBUC2|9V3uGUun?3wdX~bJrh(Ey(-G}n zWe!R_wkTT>`>z^N!q6j*J%208{Xf3_^2u?!AfYIVh$0nL)QUDxhW>@LfQdqhLekUH zOLifI^(;1*?B4smE%u{S40}$m z4w_*RL*Q~R5=2|HlGS1T1}}oEIFq7>@;V<)NLPVHt3)U$Br|l5f|A>3F#6*i@ozC` zv!VWHXCW;(-m$R^(FvW&NSU_}F5@7F7Jw7T$fKy09P6ym#a@7SfgUxwu46^@2UZ;V z&n{vJXi7cX6(C&B6bftIZoU;BUZRjrUT&F&z5u_8psIA<{8HQ)nlO9q3IH{IOOR;M zsrHvg+!nzl*Q98=--`ly43wkXt2vP=g~XC%m=HAi=RxXO_j(Ie|9#ab&W1B_Unly& zqK;190icM9U=l#MR!#1d;pMz<#HKlqi^M@8vK4{pd#YnTJ(=-&ccOY$FCXnKu2I0R z4f{&Q;f3lnX_TeHRn&O{CqM*qz|{K}YWXu$+>C`nAviDSA^i$NwZfD_V})4iLYN;K z6Vx}~upHB(`@s3QD2u%cY>XpDL+3q*XN3NhMGx7Zr(wEs;vUKBSVv%4Hs6Gv*80seo@#W5Ef0{SUof` z)^FuMbo<7T_6=|rlH$h;URL$3Nk(70O|q1+G{SNr^F%hQur^fAAjiWvjz51MrG-?P zr>+vKPt2yiA9RF1NP4+1)y$LXdE%W4D$z48@n8L~Z7O{bk>cw6vA$X6dG%%|fO#;ReN}hxF zq@7|pIM9T@o&<8;^F^>!^mwYK4$v$F=uip?k647Ip1FAxKxXT8A@`QL3HO7ey!tk= z52+A0)@wxCQQx_kkPs!gM%NvQKtvwz7OLkTjo<>{eMp*l3D;+b85`Mt+a4&=-NHd7 zp?x<2g%2%NGgRZON|*dgsm2sdh}Y}BqMZIMRK%G27!J<;Ak<@r#0R$D7{>@Eu~Nyw zq#zyDCtpl7l?BjAtQc68@c!WQ52J^pqcwRU-q@6`#h5Yvxk8*AWlI$-LmN&&PIlJq zYq4m)Po?ioeju)K)V5PCBA1r|MO`Z%xI7R1kd-X;5B1d8C&X*G`<{y!!C0Uzcy~ih z4>0kb4=k5Y`iaA@=r?ESe5a8lKJEVG*-F;!R%GpKvv zt3y_s*W~Esp6kh+mTT`z&a8g?vjX}=1KZvs+-3KkfG^60{o#X=_t7)jh<@mE65rn{ z(~06t3yDm=%W(7m-a!Fe>$}JHPb)MA<9+{cn{M2A;5XioGR9i@JjjeGpCDl%N;T?X zFmacA5nESGL8fjh(BvWRy^qRgFgRUm;V)Qwn9k5KC$BG701gN56L(=qRqCr*1xE`l zCXMQEwxPgxAzJ|A@)rwRXPT`p&I@<#rOos6I{(r@m*X+8=-AjOi34yuteqz5n>By; zvzUqJ3}w7Ry2*c}q1gdy53R=(y`02F#2Lz)*^5yE=O5s`Sy}4EWio4ohc(1FJ(A$r z{RZoS`#la2!V{uLfhA1udUY^}-~y%Esd;o`zUL;=L-&iUv$(#k;GsczqR&IC`)XIn z7y}@H+gf*$nIgL_7Z0H~d*xJ(rU4qgyTP5fzc(e7b|7!ijr+dU)EjVxQ;ux~gO+*? zt1*GB4MOe=>2xj{x3pHmyX?jVgKWNv3eTOM@mxHv(D%&61l?9B6DPi{#j!sq7D_$g zSr^_}yHXF0igt+=z|8E%67vm{i57E#?G)UkoF z&pS2n7p*<1U~_O3m;!zcl9qEb13U41)vkjZM^_e_BoU%kDPBYx&#JS_*-vbFq-9gK z%5V+Nu3ZCfN z6rUo}B((L+ZNDB8>T*9CUh-oN6bI8Kyn*gWNSI?+w-+b+zbhQR7AvxCeP&WIp!nJO zWd`yt`yrA`#Ewgmsq6|MVebSn+QOZw6rizY(TrbZ#&ep~S;PV>i3jzRoeH>K5*)sQ zHo_UHzxXy51WREEmhBr`Zv%l`rHht?N<> zujgvF`rAJr!SBS9v7m10J;-R+X^@L}t(k$Mh4DdQ+}{t*{PGhXshcBQi{ehT#tyle zYG{P9UTYxP$Ze3*-ted#1);6YD~|r>D*D6;;@1zWseM`v{leHrBtmS|h;>8!hI-fW za3Q2oR^C^ULg#z=&4&@Ht2$Ocp2{M|rB}lpkd@IRd&9rm?>zYeLm9z|4D0H5NTZ95 znb%3G@d;Fdr}Bk?hmuh4$`SOa*CQz6$3p?{?r}e?TS{JtVOqXc725&{bSie#~=JgA~DE2I;x>CurX?3VJ-CYFuHN+Rdzl--vD@ z;~s1VRlVpgolM-J(gc+9E%U7Fl|}|NDf;MosLImC(a6>X53h^-^tvr?v}s%+GR>5~ z+JK&|6EDLPhX!XEvXgYC8`5Sm!fyxG>nVYpWhUo1XhdZ$oE%7cgwHC6lDi8jwArR4 zF4gvBQvWc}!-jFp*HA=_Klp1F?52%(QSHgDUlD}+ht3(VP0LEo|M6A{`t;f(1Cv`u z5c3zREkY6@ruPbILhw~a)>d?>jLtDZ0;U44*9yvXL4x5;#?I;UQalxxc!@*?(45X- zU{H~ja-)9D0IwwMc2 zqN~(}6DPWGa#RS4+gtah2LOS(uOL?@^gL7#Zgb<vDpDv3cni#i5W~j8%DmB;PCwWd z1hW-mYt=dbsbdq>8(zALTCUMt!bWF*3&GZo>`yJ~At!)TVGi#-tb*^qRZw&5Y{U2U z-H;0qU39D;nqtxqX$HY&h-P98P7E+Dg&m?+SPtdG833VQ<)KB-S^0fE0w{U{=~7YT{s<{|1;vG72jzhJL=iz z@IOE{8)`hnppatpMpMSO_Hqng+6019W>nagfV+lIV1tGvtH4x_kc4tZw?C)MHq|iN zg=wm}VF5)7r8jDJy5`$I^)%6M3uedf@ub%OZOGPdl}g|r&DozqKH*?(u~;Ye-bo#rsE)2Al#2@do_>L|xq(Tn=q zL;*wFfRx+k)fS)c>(I^Tv2ND7bw!19_LqC{){9`9zu5{#=g-!ZJySyuWuX+>`|wG# z;TM|JqkPOfb-Fu0D@TH(x`=iDrxzejTK1oUQ7}e;YND-iILjF`u4V1eXHg(qL}%Y| zC&N(8RMmsxaNT`Nb+#*qEINOg8=jmaQL5`DYUudzrc;y8p(EhZF10x_gBk*vL;%1L zM{_A+il1J?s`Az^0dBPPu%O|jGk75920dcu$nzJ7?)$O&W{!hP;tRsJNx|?kFZ?=~ zl1todjKf8s-dUNzIW+$Ovy^O^I529*kF>{6sTxLRcM_3S=+B z?8%e2Go+#%iNDFs2sto(2%41=WjzUw_=D@XDP({9G4yz=K~Ni+jCPXT%1rO?!q=}} zgqEqXMQRU@1^qGm-xFCIrL(nP(MPU9mQc9wL=?FL!w-7JLD_8l`NC;W#@9V$a<>j= zF*h440f8(e5yQU8c|BOTvi_eG-S^l$@-VnzXG_Uk_n>k5wDcA#0i8rflYKYd4wI1) zavS(ncro;)J+LRHbnQx6ib=Y5mA^1fx`KG2A~X>$U?yA%zw+5e`vOMG6pW`0KXPXk z$*Bx`XeJ2uyJ7I%?YGt?`f9;v(CM^zYuW$-vJJ%#w=S1&9co8Ug>}WpzU&YaL1;zS zLE@9++DZu3blD&fLGE9J?v zMV+wRyU!b7wRp09OnOC8nYZh0}|&55e13}fk3!pXroQ}bYyJKC*v zztY?|4IO19otx5X=~`wc)}?;!g75N`p?d+tx3FmdbHLLgZe-*ki;6CLZHBcv$MuFY z8DSu4>HW!XHU~9*97m38zDqf2Jd{mkZ$LPJ-@vGI>nPyBoAZ9&Dfsm`^(Mit#UJih zFM&$1H?t}ZYmxd|odhRT2xtAsaV43kv}|Vn!nYGGgT7}T?8FfJsrMVM#u9Ie!HS!) zw$Zs#4=$1oV!BKT$8>lrH`um{az0+pa*4l0Gz{Rmd*P&DPYT@`XOAo`# ziM7Rh!nNjwoc5)~b=luS$j!K)`lPsu$`)nGP8bL}5i_vcS%=?Sk#w;o@THa}w%V6| zm{b4QaNjC18SafNMus^Q6|^xI|8VqJWp5VMr7)T4*1W|KtyS{&f!5wViDzr~GMDdd zK6@f4YG-{4CwAtxzq7Q-OF}jfAQ8ab;F;|E-H^*N-pW?*_WLdgjJ6Z+=M9BGZOuLuMNw80Xe(hN|Eln?z-En z_j&I>k0ePvN1ao)GPGeEkC6~`*{fvh>a?rnIp^1zd9%z**2}WkC`;e*>IxtDKOop< z*u%qGB=&9v#m^ll+_m+j=BiBDqQb3AoWBr!*_oqg9w9);tw%B-G2zx;xf*mNJsCmM zMN@vhCJ5yp!b|#dB~sA&8OS*azGy1+t4;*Jm|UbP8%t#Iu1FF<6c@^sn|~8Wp__70 z=FEUaS+s%oM~k5lW~xz#X>%2z5!)rJClbsz$y%bc{a$2RGtR-UBk2GS`c~JD1;a&U zY^c`LjEhR72U`fkJPS+*ZG?C9R0;N}llb87?usg9>DT)Ra>|4h*nWI2Z5T8!(JC;+%P@yy%Yc)6f?SwmgdDKn z`+X!{FVP-GM+VH16TrY;!X?!jWSoN3SfG(n?ekeg`0M4V99<=K&i_Z$TSrCJz3;<> zbR#JxNOwuMAR*m3fV4D7w}2=hAT@M%4c#S34XJcU4>feR@4@Hu{k?1H@*ijB%s%(N z?)!>;hE@l9*rJ(2$-EY(D+Fad*!0S)T+LwJi2LCQx@Da-yz@v@3gbeAl)7ZIc9{^x zGl{gRHA~xI{&Z15Oh@7_WMmGanj1lja4{~%*u{G%d$V>ta6KwjQB-DJ6mm+t^x371 z^+zk_P5vy;|Jxg)EC8&>R2yFO`Y`>aW#$ZW3&ZmAoR$Wt0^3puFSSAv{rp|B)@CO4 z+1*a#j&#n_u;Z@|pv1!SMvmTJ3glO5b6?8^zjJ(xHczOGMR(espSt+rlyO?NC z=Xy6UM=ZI4h7L{cMLpq~lkZj9@ljzRWx&}ppILbOE!|QM0l`+EOl|r~3wD9Qg~)>I zwWJwoD|0YXWivb3es9{{dr#wm63x;c;0=Ru^4Pti3^WBbKp)yngmSw`uX&Y%KT6lj zCAkBGtXCimH2BoKO5ayK<0M@hcM5j78|bZThSv*Sa2?8Bmtiq^>fG}&lKwZJ%wyDT zh`e3X(D6K|$EU3?8!l_b6t=Kgw_Hvfz=x_w5>F8nO{2oHVww)BIc~Mh_z!?R(f3fp za=JIR$rr~8-sObB+RJ)CRG9oU4E2$8tUuq1^<>0k-@kqC`yJ~{RQzo#^K2PzQ!8iJ z>4(K@$SLZ6e0%GlQD3& zp1h$`$$)R)Q`u^y675)R+jP@)b&{ua6o@32GHuGbS<dOd(9~r732XOp}J|EeG*sVz{Zy z%ZkRECWhSOgW)ngTi4z;P94deG^_H=U}Ss4C?T&QS)aw>l+=(NdyPv@&+DGCdJ76Z z_5Tp>{Ec@w?sr0JX(8;^fP54s%xn0U0iiOkY^l$BaQXo&mg)#kU1h??oF%+xArHZV zA=9k%{C#_J2{6-u>+f!w(=Vv@ioA8qZSNph^nBZ!R%W1_q;M0QikP1ln2Gj&CuQ=5 zQPY~?%)fImTvKumuuyh;LdtuPn7Ush3t)RN$r9eagf7;^jU0=DLj>-m#g(Z#b7h{9 z;nx4YIs0C&R8S>Df@k{)#TEcGuy6$$ZcfydW<2Ou3(M*pB@LGx+@oD&38#QEg0CIa zq1&K&r9^zjWaekb!nA4luAGPJzcSv<-+RlkFeM`n#W*+KL1cOuYLjXfppWtu354QjKJR>1wU{@n^_U6LA}nA$`DDQ0#Ge7AliGq3>%b z-p(I;YSOh-ef5|j&0Ar%y3lF9dLtIpUAoxx&F!e-K?;eYS*GvJ5`{`{Ov3$Fj*Ra$ zO)AIw$Is-#$eFhz)$@YuE5#I>Se#fCPfCp)`i7ZwFvP_Q?+Zx<9n&}5RiDN`4^ZfI zbVI9+VtgA>X9ZLaM9R-sZu>WSfWesq?v|2IGdnEX*>?eqgCyMQU4 zsu>#0wo7{LXuACA*e}F1$_?~8cOX;DT5!i^IN~^i+5LCK{^iP^u15=>F0G^~QGCXt zw7rc<%7hx7Ka%AJ_xld7=^1QCL8dFMkcQUg z>#2zp@2ou^RBYBt)pZQcnM3)|AB<)j=1g=R}U>R~P;f#*2f^Vw2m=u0XoR z`{r|@g=j|i9q0Y?wNV5IBSa;_N7#2d$*Y-j1wI~v4o1m@vY6!YoNeobHos4r^77kR&MsAM=m$ua^yxv zwBy&AYGay71~~rHt|?z@gV<$DCUlW-!wg)-XB6>XJ5!7pE2&ks(_CmP2?tc~Uv5Vz zgl2uKmVGI3ufcigR$OH(Q?A`YY_7}B+;zbk!}DO(M-2>E;%VZ3mu>{YlSg9ydLqx# znryC8ubNs~b;dephc)gD z!TIxxMDR~ooX4B5)l^hQ$#eq7qAdIvV2SuHb*(&$v0Tl-GZq}EtDAVUs~`(&yyurg zwWG0=zOTSl35i6swz@%Gr-?SRj-3)mTdm6yu@M`$9wDOI%?+H)VBb_N`l?x^6&WF6 zlEl9kyvaNP(;I}Yz@?+E#=XH^D@eesH5wG;>NqFF6FGLa4hs zarltAm(o0?hdcZaGUuN_H{p*v>ThExQ%9%H`ja_~yf3Ep#AEqBOff^DP_ftq`^Vea zF2?lqyN(hL3S89XF_?^+U+9I%&}(GZKe$`le;nZOGj9`x!*BdMEl6H+gsm(ji4+}B z4wB8g@6RIgmY(~lOH!oME&mO*Q0DrFb;=NI3W4a27`Phv`|j8qJn^XwM_%_2z8N}` zNhY52;Q?2Fn!3Ek{g5^G=j|aKbB;}_q~^r++u1?OM=)Bn{Pul!+ztVKNP;mR{_KHS z(DGBYghLarnIb)a_9!n0TAv{N20I(=4W%=-pR~ z--e$Au>MU30^I(gY(UksUj6y$lr6-Eb?Pl32SL`^vl(gP*5Tcc3{b*FpV3Xs|42xG zN_#xi^aHr4;90Rf*;{yp+Z zeaI}YB55iJBS-q{mPnj5{E-y$ep+XcCd9ei&4b?@x%J!M|JofO`;N(#fAlib@74um zx>i?U$P$FPh`6};2xGNJ6JrfI2dA)l)a`lHgMshz^`EjqW}&=1ukrH-Li3Yy{L%S@ z-Urbfm0KJb%(yHZ7yJ9V-D7%d0ajD~^qQFe_nPnLjqrt5Hj0O_KC*$N<@ z-s)XB-}wz3HT?Cx`|BwNvRQ#glX6%Gz7TfXj0jo?s(c6%U2d$i_~^N^Oj*~KfhjF8 z<~*?YkvO00W|NrX{=J<l~h|)p=VzUsr44U?EK7^FYR3K)V?jQGzvPC`MQrRFAJLbcm%dZ z{>mO;*e=C%QKxNk_3+3%-;xLr4|In77(3k|n~b9L^;?mdT0HxedN`)x41qivM?4G- z;DsQ#hddy2+;SZmbsrRnn}z3tIf%IS1n&$)p{ z-R;=`WuTJu7;PZkxfvTf8gr+_MP=sXTzZeUIhM0-Jk)Ec=S(vz6L>E#1|6jsaF0P3 z%)KR+6}vlUoao80taa(2Ui=&Oq2=OV{O_$AJ^%MRd-a|hb?Wwxy;SR zyJ1;RP*K;9c$lnOfD=G1Vs-*Pel1prW}t*BgGt zCknFTJz8Ih3*Q@U1*80Q0Cioq#fgjFrCfP3YRik8MBSLJ(fcSRr6A9a+D-jwkJh0` zYzw*jS;*Kf6X8uhOlCCygpgiTSR&$%4a>7fN6HdZvEpR9L>E)mQ;*>Rji`=|lGdGF zt~*0g87oyWrp(*ACKBI{Kdtz9mp)iXP9QtBwV~dLBow!`i#|r1z|@&%9ld--^d5xK z{!rC5#o7l!dj0)I;`@vZGB!t&tvm6SaUGKBIA`eLEU@iv2B1Jf)BhorcV68mWz)yy z$rInZhr{)c7k?kbLC&Wmqyglo^XZG8fZnEJWdMVEorMsOlS>8Xi~@r$zdSJ^^ws!lib^Hh{S)KO8m( zzx&KqO=rR;3sBaInZG|_FMrCHR+rT7YnM+-Y8I)||4m#XIxWiY=q`Mfg{t_@zp%V| z7_-SK-HQl{=4pA8q=DcBjTFDBP{({0I?o1a*K~>9Xso;^@kU&e2MrhkDua45=8}Gc zrq_i?7P-HJ^^+?HXoyQVE(Of;EYZY5ghG_egtpczPEWES`lz3OQzi(`yk z?mYcO$*@U!!05!&ILy+4NSg2)2zZmLMYhN!h#irfIj(--vPk_g@C2lMUjQJFH;4I) zplm#Q%N9*=UC|>E59+R+54os1=7!?LR0o2I#t&@U4+Z+aiB4{xf8#+-R72*%PId$i zRw0*r5?;L}yk}T-L2>CUu3?0xe@E@m4W|jyv#)T9zwaIPws!dkxI`t#AO6sQe<4`} zyQWI!8>6GwBXD8zBX-Hmsbk0f0W2F&&x-jv8$7cufP3JqaZecnH;f)so-m53 zg2YB#g(Wqa?0DY*$&PfMuMPKr&-ffa#|8m2*YDt;H>;s|-W%V3%ztjO8cs(1dIlV) zKRIkW!d0j+UT<|W>keg&DE-a7>RM-34Pt7sep$8n+%{S=xH_S`ixAN7e!yCIz z4m=Xn#QjL>K+IDpjoISXK22A4qthSgq?+V`*9(*b=b*dv6_#r&Gt+lvm>3c`OZ+*m zb(Z+1OfCIq@R=;HGow-0-!Hzxxn!F=KNLPTTbH%Nti+lUjgUu;modSJdcNet*wpJ@ zNC4VORDJk{tHLP!+m-B~hs>2cf}3QH-JW)3Q?A`zrGv8k9Ae`i=K zl~RWP>@(8%S2sDw@F|;D{R1UR{6BOsr&;d{IGH6c>6E=2R0+Y&a9;CYmN(fB)S_t< zu6woEYxo3@Xw6n|-M}Wm(Xr%<;R)5*lotPj09ieT&C%Z^tlW@UVCp?7r8*;w1WqM5 z&<4;z6yv#HnLmw?5J`NHAJsUK#J?RJTSn1fYY~aeki@xD(rcT@(@jv2o!^uvR$L7V z!ztr$5D{zPXFjqL1s@xV%f>4c3(2i{cT4*anHREN&FXxyp;3&`+rekCB5--(qQg!< z>qCt7l5m!|d#zNnpEK*FXsyrwlSLe}ElW_Qu8OvdN)lC_Bf!jM!iF_!c^~b9Td?~mxPy4C3`-Hv9m{8SLQ09?I?cbziDeOVT>o&P@B!I% zmyigZQgV&{qbK5D-rP@AW^3G4d7P=QaCs(5YN5O~T)}wnw{aPItp<;*^g? zbU#)e<|_((C9JB9TWpW9!Ti^jteHmq)vr7vg(Hb9sK}yvHOeS)i4vBV{X4qry7|z@ z@mEt9zMgJLZSC0j>4LQx;#UF9P3J?Cv(2H@cmv?Hg`B!kBQM9I2rritYyb1V@KNZb zgnKY`J^&Iqzq&A40;I?FA))(uO`LbDXbew({ZM_Z1Ue-N;6(tH`tyRC;Ia${iUAtn z4Ih2N-bpMSKqb8)$w!Hi5ymvH=+O^RvvxYgTP0t$)5y||u#rzZ){`{!a4QrqXPbmK zw2zo$;A^HBk;aDy!U$vF`XL@=#`=1+H6hXB|3wLibCt~Lj>Xhx4P_6;4s)!Pa{&ur zg;}qUb<_I4RhpjOb9gb%)*Y{}P<1K-dXm7Uk)o@_4IbA$#I&0KfhpBT9wQq{b<}z! zu9p?0f`1~DluobLSx!G^3vV0x>FNQ)ej?`8SM|4%eD+Mk`GMPjvBnjgs`+y#1mrQz z*!nis#e|cH0h`E5*JOGs+_IA9hAbh9m#_LU*JWL55t`(d!;8csc3_{T)90|S%P8r>^)MK^E{ z7-ehfv*q^{VGoA*2`lDodxHMW->hk=-$VdC`lj1>Rm)QM&fyPKb1``uoAGZ(0VV5(7|ijg zYEWV!YfFn^F&~Zncs$->UDaqGuoxqtO8GX$LoH^vLJ*9Khp|brah80Y`BkqM{V6|& zbdp7T+BJnxnit{Td15*EZ!ZWJD<{t*DuJfD+3utZr&PZ6*|#Y7Xml=SG1V2{wD;5X z>cPn5RQiSZZbgdHuWA=1>>xYPQUgnO^`_GeX}<6#ucgS!Q!Bul&C(K-P59KhbzZErdTGv=a6kA&60>lz=>!GhwKQh{1c!Wox29f77c+CZzv_5O#n&0Q zi^p7;i$6Q_U$~dV(Zxj?rATd$UVuC z^P!=w29~N!%UEc+L@rnhR!P* zE*pZb9#buol-BwZZ~oLd;V2JB#2_3kMBIY*rs=5}qZW_YX9_+WE5RAUglvRUd<;RC zACNiq0UpiSWAUUuZ2KBl<~wMchvxIc&OT(uVAcRQmRi_l z(N&r3kef_3(~-*A-&f&UawVE6=wf(N4I~Ga^aa#u!sm{nj}C<3@8rW%Q>?T<9pEPBws04jH{ez0xN4E{j=?*3i{H2(S*r_hD52s9Bap) zyI~Aw9at07G1O@p4!J=-`81vKSn@B8<}fZcyR`dM&C;CWLN^|X>F#az+ zfMRO*ghG8!G>)dsu(b@^-@O4yiO(|pIt-$2%Ulib)K8-a~Ezu z07YRG=fiaD^7C7*(WU_Rxz0?`GmN~3^tiBnBz0W4eiF{H4FOb^EoloOx0$P@h0452I2OCW!ep4`G`G z`T=|xwjuJy>^rMzRe7BJ{TS2YQ|v-0>$zNsj4+iqg+6=FCm{N;57fQvx-WG#cQxso z4>1Y4U1tE9PzcqfTbeigDFJd01UzBckk@@Z5>2SEY=D7>KY5Kr%}+3svfdr*;F`sG zxDRd_vIfXpHDVzPf{Ib&$t=JPVK&Qw)xbiH0@_n?YC4LwX7HJhFX1=%i?DzUadN#u zXMytdR#QxC1oz-IB)oD>zP#uaoa7{X#;bpUA|}AfiC$?Tv%v0t%Bs41V_ChekU2c% z)%|Z~FFEa#xt|#F9sq6~%gd+PMO&!sfn+;9P53RZQAYW3J373t@GVsuefQsK)kHy{ z(A8$Lrt1tasAxx**tnJc=YkZ66uErw<|}QwCUNOlx$!P!q)!il11|74U@FXUDMj~k z{$TA+U-iz!{4p=b;Z#(OueoGc-+qm^e=~lOX}Hl==5Gc5Gck_KXzvV_^!~}{UfN({ zKV`@~lo|-^E|P3B=ZEkV=)ozaZ?AmWpzeDUo87*%R=t-8{PUDC^@j^}NIj8H!QUfF z_r3~WaS&xPMmvFva6X_g{yECHCj>}#FpUsP45jimE#d4N#iM2tL@0r7iKZ6mX6_Ge z$nZ5_&jcY#ehatEdRj2$bQj|wIu}oN`UoE?AOp0Gl05Ty^TQKpngdGpkn58Tt1q1W zI5=S`gbEht6SSj9Yxl3lQ8}!PZLndOJTORe8jr-?x~w>~+&UYPZz=AhZT)zLQZBNU7 zi14>GRfw1W-QwSK;u!s@eIs%ls{aLE>5V@9oL-nMmsALvosZ)?X10iQTQu|=n;k7# zes+hTYB)U4SSO=EBz_{PZ0cz=T=7Zkp~KxEGB)&HI5GxijSg*=SkyFEMPBOT`aY9Y z27{y zl%W_P%A^Y$X^jK?Lr!2i*PyQ&N4ltqGhVaGu$Ad5=B%?IK4szBNa=YG+^7?Mz^P7C zcC)<89fCBtRP=BHK@=_p--a;=fdEmjMPudrBYi(z&+zAlA#QD~kb=aGCjldHJ26Va zrR6;sK}!n=X{H=_Nd%UOsx%_MmQwi-C2#@wNGURA2M`O#~VZxWhvDx4+x=Q%9?tYg&nZr7hF z;T;&TRf?C>{EyXW9Da<~o>oq}dQfEp|CbRVV4OjPnRlHHG4N4%=;x%Kg#giy!HUcI z)}%rK`sH&S`l@skrwW`Qu7AZM5=npVpNP`dialB{>i4`@di*Vr5-ylCgsV6MvwKS5 zj+-qn4Mo~g0j|mmvw%N}?G9>V4;BXo%NUReT21KtRqfR>fPtI|7q$aq7v}1*Hj722 z?ValrJ)s=`N~fKhf!mJ5PGT&Ka4oi76DF)~MLz|~< z6#W!q@{jt}t*?mpf(nZg$ZwzNg%lGXqGWNp`IHrX0y{LQdd?jhAlrM&sJSLB29qKq z#*_;i2;63Bb(RAEz9qbUqfzy(>X%gm)3E76kYw5fK)_rf;_^}|3IfQpfHFW4k;o^# zrb%$PJTL`$zx{jH6C#@Bhr`w+-CFQ**zW21Ii?mBEF&T28*~ z0i7z1LeD$TEzWF4j=595oicO|t<{0kk`GQ&}V*JiV>{ik;E zbae|%b?4%kvXn5R?_pKyg+-i$Z**VsA>>i!LxB<99B_8MU%=S8kcEyxn9PI{YgUw6 z`hX6~;+>lHH(yR@!9&Ai!q(r&tYH*dVf-+?GlsAGwO2OR8M1cg?B@zV)W7QzRiMG)9aqpkGAfV;4 zk|c^`YmL}FMd$<8vt1lG`n*_bWU6BS5?~qDr$#XH9 z<;~w9qyfW=S@ui6;e|TXvHlZnVNS3LWOm$xav4Z1;<1kVlO^#hXvY7WrM#>Oi`)(G-w3&Y$77EK(JjHlf+H*!% zK?+6zI%ARdM?kX!ulV4R%w)Yj<_-PnEPE}RT1_+!X&~l(h2z_Z+0dOZM4$98uTpHp zJ@#&gNh$F!YA5aL9^eNe$e}Y`CmMpFBjT<6?J^Lze`FoWp3c>gFt>=@sR{8qG?a)3 zlw|p?wQzyV!fi&>$j5v~T>>A*=dH8v8YeX_$hY;X;@j|MJ3wtm=6~48N-Sa6Q*uY1 zr6f7 zWIqn2`h}WV0o`>B(sLoIqBa~$#f-p`eNS9FI8KSBLZ54@1NM`3**Oe-E*GigPoOVs zHbk7Vki(Bi3M4t%kVZ4OdW^%%8mA?UnriFYkb*oKL@2^V1sjf=gumThJRLGXPU+m` zGH-v+VGP*iCl##nz8=SPXd2<#-3!giM?g7T=Y7Z|fg4fI%zTD1=M%@+Ep8cyk4hzU zYZ9kvDpEJiBFHHHb+^R`{2chZAgUkHfR?bIyQv9Y|+wOyh_it-nZz&*M(}La1 zdDj1tRh-CA0{9-vO*VF|;%pxd3?A7$Ti%8TT<=tnArLTxyI6RK3(RCPEjWLjco%Ix5J>dK!Kb(|Z&Z9^ixnm8=W!*Gd5-ird0gjVO?_ zbz-_f=|)imQ;_OvLTb8$uB}@lWB5f(^^Zp3D}ehm#~i~843%l@ZUp4MElOE`=h zlH=>nF|D=~18*X5u*yR4*3Mbi4s+!j3alSd!Eqvzu^ux85;6w4NEN<@?{$%|ku zSrXBL$cbQ$^oGy$uz3$Er%>t!bc19Z+fPOEzfe0=!U2t=^uJmn*7-{BO|#acuO66w z&>KNafv|7D|Dz0mahewFbQYk1k)nJ1P<0~^I(iw{up z>FQbAU+xN2n9@0**B>i9xy6e5kjNM3I@TD=?PqXfC%SR8?=V* znL1KTFF3^XHgm=7cWtQR9(Td;MZqqy{yL^0AUjQk#JZ*)9PV@(T(k|Oe zhUvjwV}^OdLuosH<_pTYXs7~52z&raEl#vmnu9C$$t8WV$1VMPQrmml(#)g@8>+Rx zO>6F`+Ym!bGRw^*E%as$9%g{bw|NWlS+3}#`;q^gf z)3onmIjCHQF=wjqYvcQusnYBV@K2bA6~9~a);}o`6E?-Ap4~sDV0;!*WE>jFFvz-s z6EpDH_%LpZuDFl6cMfOM_h1Aw`0+}GE4lhmnb-Gl?>aiLp-_rU%b`RPb-wWMu~n_p zUE+NM0`4}d)EXP>9J^hAig7)`92%JSXRb4XfRT8HeWH`gbgoHD%G z+1aCWIovQ0RLyoKCN`2gZjEP~{$Q%x zBVrdn%wy5iHqQHNeDlTOrWmZ|)yQF3&zup1vkezk7@!nNdr%WnrZ(j*aGgHY$#XX? zGj{oblCTs{aA&`}!|Qduv!>Yy=Pq`TO*Im$08T6EZjpe$b?X^^h7^pjaB}DrTQ)Z@ zN^btGax6GQrhv05mI|R6w;RfT{CJ#&zES~+6V)OB1E*t@RHCShabsnZ9+I`8!=+1} zFAMOP?>l~Qtti4gRRZs{hp7pKL9&lKa@?rF22!u2Jj$urT{xgb-QjAZMNR{GJ*HjqU-8uN3$Aj?_VYOt)cg{<>V>0!z-tg^{P zL1iPApg;B8D89$!evWUnRMXJ-E(>h zn?w;}P7-w#Lgn-aI~nbySV9KhR!ZR6{Gyi@BTQrD=V|t{RaU?9-TTnp5GS~CPg*mxIu2M~u zsg`OYZ|t>%c@`qlYckJ~L9IO80ZR$nr^r&u52J~^!tP&Yp?nk;ZYjNs-A*ijiYVSu zd$cC+^B`N)xmuML)xln^mR^smavD~(1sab?t2&HChZ5k*q$2F&DVLOM6<4V)VMjOs zZ%4+*OmizlQpjEgyt;pr8|>wxnZEzEI}nLGL*;?PUfC;oe@I$T8GIEizac4FYWJ(- zniaPOG4m<%Zc&>(tcVUN^hKor)`;HK+sNcn6(&FhXh|IJRKHg~a5;`JvCk*i>=i2+ z7FE4|S`kH3g3hv@2hae(S>LR+w!iApC|xS*_jPVhggU16m|6TgyxmVWK4Ma7h0atm z8~_@45B%42+*0Z~G+Zf;c?(p|jUj4+-K&+*KTghzJ4Y9}hizRCM3En<7Z3j)-tbL0 zTJ^fV*xTM|sm$dB;{-kDg2~LQ6v{{}?@G*kjd35}5Kpx7J>;8rn_l642nZ~f^abNw z$k)OcQUiQ)ZADErtWre&Er$TXGNPyaYb)Y%^t)H>DP;$#J>M@a)yA>VbyS*-uV%G; ze$mpEe8^th=U|*{Ql?p~vY0=!c{vmlQk8)F=7Cb&;D)N%n61tFxLpX1L1ae!N_5VO zFd*wOSyB5DHU7B9t+mdfQqrv@M#GBtIJS@YeQ4|p3%9iVcAUhFS?Hj)qgK*`_WXYz zO!}u8)&2QOL(GtqXNGcBZLN_|?T!8wi4i9Q5~hX#xb!1_3Oke)vH^@IfRAl>slHY1 z$Jz+c=R=HWsR{}(d2=GYpRYY@MoGGMkQ#1+0n;>T$=AziqqAMhCNLN2uND^vKM?-a z3`5?XUq|2M%F)B?SQ@1k#VvRG1wGTz8#E}?Y2DG=z|-$Ah#OWXc;nXYzNWwZsnZaJ z;gu=$`R3bHC3)V#C<`H*q!~4 z_E-~&!;1e=k?`Tq)e2wo<9oRMAOH2fnggF#@wTEJRFJGYYGulYq;SjOQFRG<=PtaD zEsqk}Nq=%73APW1T~~?wJV)^U-+N`5J|4Jx2V@MBl}viEZ)g*l2A6MN5x0wcmLpI_ zS<0iM9vsB|#>4ncDX)D6gLywb@&H3weNNYO2wpmu#lkMkbK!f1Rru&+>ub~qaim{Z zQGfq>h+?qjz_9b~PTcgJ4t7UU?qefgT!1I}$hLxY^p}v@T2by)&bH9f;rRKi-4*p1 z57WhcwY)I(ycx65c~4VUoFab%pBE_~r)b`AV1cOKgbZQEa)_xk`Va>5^cPH^9ZO@p z0c%m0EeTPk;|Fm&_uTyssz| z0}_K#L7aozyfEHf4h7`F5*{c+S-g0IZdV zQSGPUsy{P}(xp`UlX(-zH^vD^kIj?KH1&JA6>Aa^Bl3}`g~5ggJMh>HnWN%73O&cV z7!*&fcb6&BN<%3?%27qR&#W1=doz!DkjI`L@xo^>|zSEkeeysf$mQd7>M zB8zl~tI|i1+LjPrK?Qcf()krAXc+jHfdZ2BXNjc^Ie_CA{KmVz4yKO>6Dt0Y`s3&8 zIbVj<6?dJ+#8S%{8e5;C&ldXACB4r&w_1(kFEhz4l&w2r3(N#K&5@3mWxCph&*PM7 zp{Y*B|5^s4WMb@lUT$of%74hmQrHgZ8O(L=?}zieNqDXWDgF@Ym=Lf(mu75b)#Nf) zBT#B>g&AyzX-`o!Nb%qIWB3@UnemB3MT#9jOD-nE%aVl={u^ja<&ci9CsqWNeZmJ6 z(;{sYs~0_(kT*b6(SH7=Wc}TbB3xoH4$E8&i@NZ4pdCClup8P5C_y&}m;FkF1SqiA zq>Q|WgZ*6Z{nW+c}k4}PEGO)iO*8{dI)MI!_Vd9DvZ3-+7}kr*SSsB zMsHcfzW-nbcHk@7FYCB9R%(eD2pY4%+8+Z~`0v%IDpWMD3N~NlW*#9^UW) z0C%3Q-Fjm4p~*m-WgGcvnDW2pk^jO?08>v)kZsmZikDJY3=S%D;XgjUk5j!~dhw{C z$5hpn-A!hpDIZqS`lf9>c~03_t(ci!E60~3Oz_V~Eyj&OBTRI{zu+qYrzP8gnS!aA zN+Z77Y#<_e(oZ2^7d5-=e>NJu&t!6uNT-lIH2{jr%*G7Oy!&0eExdYFJb2d~dP0Lx z_M*Y^qcGZA^E~7_SBt{a0zye6&^JA{l-NK z?X7n0fNO?I6@0nH>5mB4`bi?S-wy(Z0GPOsz_}8%v1JzQwLN$iGt>08bBDX{UMm4$;IE)b+u#S^t|vqLTSLtrA0 z%^gePO#2KF$(zWEzZ-Qdi{6og)#Hh+Xqk77AQhg;}i+9{+Qb|P5XZRx3D>y;zsY&*%HQCDwdE6-}p!=0PJ14EAG?+EewND7oO znpR}T636V-i2B9Q)=N+7D5m&m9!7iMI%u@X2+oIhLk<6e#AWjx)FbkN{k@<)V1pUK z;OC28zbA|y6+&XlR7W}%ho{wWa6_A!qmTO zC(=uOLs}a8I@LcPID9)oL)(~w@nfESM$YU$>lRtZ$T3MAfTXkTI#bz1^K_J8?9veX zOLt|wPPss)&BU3)^I~bb9l;J~@FPs2nc2vPW&^+P9!?&`rnzX93omuQFR~=5Myp}c zX)5Xc{h8%GazeqN4~HRW>$qAkmVNZes+%k4ch2 z-v}9#XY`ypsK%!*5!z0pxz3SQ!~s7HtICCu^D5XxAr8T9SifzP=tc;I<_Dln=scg1 zEPW?mt=TD@a#7yvivuk{?V?QBn^QKgu~g$K)7yO{%q1tQ#O0g3NOT{Vv`yjYVK<|P zzCu^&>p2kA9bDXsYlrJPsHzE?QECKoBt`4 zZ6Qx#ffimQxmC{cq^2xbQ&DrQX(zIpF>)h$YbF9`AQ$uOPBR8*aU*AkvJT6PE@Z=K zFqF|Ai;mk)3YT=fB4yj7hc_D+{5<^mp~HE~5J+OOwsTjRMnL}XjSLYZCS_TTT~sWZ z1hQ=K_D(Xw2WK0T$@x=_vZn!4s(d-LxA6yKBQmWCvKUaPeJr@6L}c$S&uN$2A3Rqr z!_Gp9-MmDunsVgcNuKjC1U`31xFz5=>nAMeIGmp^N-xH$7~Fp^%rg`D^~T-wWztJ zbqS)*sk9J3stt83t=i&uIdZW-*Y3InLuP~j&T~!`*M%1hnZ7oEs9}|Ku-~Xlbzm^) z&>Z;MZ}_*lM>a&Un~ab?IFe56JM{3bKc$BV-LAYR9Vf7qdZ)EvR7A{h#4m585<*0g zGmrh1!S7aMx};O%)lDYm3IUAtB1sdR`+&DI?%ZrIlOeI8*ceeG!rl zk`{vAs&qI^^C#7ffTyMaqhIS(n1>{3CzBGwml7Ago}?Mr9JcJs0(eM7?V6&;r)Lwc z-TE(;9PoFjFmhBQm=4m0$@uU?;;J-ZeV>(D%(~%?d!^{*#^(NI5rjNXtx>TI!@iPr zmW|!fd80>JB5BXJOl7}l0M8#`DRg3!;*ISZxR6h)X7f{;?!#wHm2SLGfi3+}WFLBO z!%I%Nd&*Xctmjim=eZuKx>U`rB8Git;yKTd0EqR^-~@WTC4q%LTaxnE*q1&|9_LB)gL2@gGPk55Di?t_y8rjph|uBY z%%f7;{v*eyU#J{6`8&qw_7I`K`mjD(1>;0pwgYQC_ zS>e*Qhw_=>xq7xsBj(C8TqKZ&c`BoBnD>33_{BdS8XVB?Vvg&O)H4&?jAO*q`bc?oahy>?O^`ZQaenY>^$!D?VU3F=VCbngyUA8fVXGII1rhP%mUTW6IQ1O_Bq$ zVA36}NWnc}{0OS@aq>*cSSp0D;bfj2l{8}SEc#`|)QEosA3F)ohQeZ3x@if`qE9#> z0lv<+EWuzaybsL2?_?loW<2P>m1EEMEuoK+Q=d(Y}4R zrZ!IjtZZW6%VEcsb{pDn)^pz<+B+TW=RI`k)j_!6 zJ8Qg9W?xN)p#sQH=Sq${XV8?&J;A9}4;6`RuU>*m&_D2loOh6(R@;nQb^ddPtOZOz z)?RM_qzx1MN7+JIX%X$2tzAnzS|!OGv?kr!Ppv{c;)xMf&vV$~$8~SYXkd42lRdnu zg0wUW{1aPo78Nz(!uuS;fjdbTl0b66JvD;(IVP5o8Hlon{+u_MJmC7)IfAd$Twp_& zcHFMh@_atZ^*PV&{uD*v1m-;r>hQhq-;5&Cnv6DB*Nz4AkkpG;I|g%)gK+qc_AgJ_ zY%WF5&zm3p6c?Q~o!vV~^^?2yR8Rq-c;AnYERS@p#o4t9x;r%m@0VQ0sokn^^6SaKt#W`~u;yrAP%vB$)S~uBr7A`Brv7XTV zX4)9Z9&cP_^lF>!#XFo4jT|&fHao&3u}AR3xVs1S6MU;lP}LLn4WWcXHOxo_Z=4X$ zKrKDTxnBobjq*rj!DYc0O}}LiarjCjIX5p^^Q1DG4QH>wKKr6MZaSXOQhSdl#Lg8S9?6VT`rDI!3 zTgklC&ETXiArZcUg1=I?HcILtYI0|vS_Kz(@ve;p<7O!Q^u?MYzh^!3D8vF~UV4;i zg~cJ2ipTu4inykmpHRdo_fTilQ)@6j^38|W+BoQ%*~$i2u{4-4WWAC1X4hkP8=*{P ze*mnO@-vD{opc#k(z(*FzzII)LgY({@?=q|JyhpAGBHlKzSzSFqh5s=pf{!z&V6ys zztHC?{Da5rMO)6Iyt)R(mf@{cW;AJv^w`Msd1>&Z9CzEB1|SRnhmzjdCADjj-;#MwJ+ z$0PChrbd`kwHtBj2nosJL^S-gq#!1TVnPBU`z70U&LVt&z%^Ayb1aWJvrqH^9?7Rk z_dOg_ETsTXSS}Z;h06J8%{r<^2!&BX-6XFXkRS|Ml>z6`IKI>Od01kB5v>sLaU2D7 zWIC)7S{3@tP47)R@_cl@a5+0wp0RB zm_1t@hx8YeCM`k$j);bH9yzB)SxUP=p>)Zcj{>}Y9z8X(%5&y%X4oshdzC2|#f$h| zuXX>YM@n#Kv_x8-?P&BTM9RIrdy9kt7ut0~dW_#qx~R z6s2*pFKOs{`#{-8wpo0g(HK8t&0>i&%csO5!^X4=ZM7G^eNt)vq6Dk-cLB}JIu2B7 zhXvBCdQvg8naiR#GK?}F=r7_@l-xD#bDoy%0pRWF6yenW_?0)SiAb}H)MCzX4 zr{4=$l4ji#FN^d-v!Ouj8_@{=NN~ryk=}1`bktM&Js^#&-#jGgeWztjV{AdB)aAuCR6ud>QhYsrE?U2tCF_*K9{(Is36#G<6yr<2Uft{Tk<#&Z$M_luvmi(tdw=g*9QGKagjTu+Y%Ec8C)nV{;F;&yG7p5Wl@=%*NARrS zYb3Ba=e1)5EC&pt5G{(>re@(2k2bg37UG`LNmKiacJN!+`V)g=2kpY zsEDn6;>94jec}|5?!>h)5Xb&q%i(c&oZq^+(q+!!t>+1?wiIzJ0uF~M5V0JQcB^~5%tAOvkr?W^ z9WkCAcCN+@S>Z&UcXYm0-H!tj?-;8kB{^&o)cjaPh1eP#hjR#`(-!oz!C0e>iwQ&L zvd#nU`1=wjLCtZvQ=Z;0i#Akmj&znOlSw@hS@}@#57*>a3-PejyqD#nSuq45792~< zvvxco!ji?wpF{s3cV?b;IOD zwTxF8z)?Qfjqmu|0$zr5FmHK$FbTc0epS|rP1~+`lEo?XbOk^ut`U||HNa9$;8st# zWE(=Mmj8h1x4*%ZoRj)jTeL*J)?5KA)8*6WRC{R7ud86m_Cu3LxIykhL+SD~vk&x5 z4#enUe2J@2#F8e1=uwdlycKopWUA~OMe3kV%1ot>Sz z6{DKjBM=j0-^|hoGACUX`lCdZa{uxy@gS{VTFKMNZbZ6SvIEyO_=4jbjYk`@8~Oly zlBGA|t40a@kF2o&b$`BK?e5~IbkkLD+Nd6Surf#j2D=u3%2`p+ukPh6Vbr8 z?u~Zj=BT#=@spqYvcYZv=mEOGL(cYwvY$?TW+EzG7ThrJNj*wzkU8aYty2$H_Gcm^ z=QL`nlM(W!HIxjk-PGTb6CJg>5ZD-(K+Pfu$xvZ9QOEEB#?;ae8LGn{76E$1Yxgv4 zH#re^nz(gnhqW+%Gxf%UxA`jXZ1BRFeJfPbA%l=J0|cqEppf*0gY4yWDjn8pt_r_jBtb3FZZ`K>?HTKOxs zr302iVMo8wn*+U>q7IU3O{%Satw#p(t@cD#sP{DJ9@}t`I}YZOGe~p&`Z0LRvgsd zwG(4u)V$qlkM{JMOq&rNAG(fmPfTdZ!koRLFoq~lu)VYv@9IwaR}5eyx%M5;iRs-u z!duBbyfvWWr3@LPVv?7io~1fNRpj+UT^sOP?DqQ3lgdmmE?;E@x%}~T-VnqrfIRD3Q1@LStpDM4)|=iG@7pL@ODksZ3^s-IeJTg}`+j4Zv@PvH@3lnxA? zhBCploXp5H?Hv+IT`rm#i7yXJ-!^I)KP^#X4VsfC%57)Ws%+R|`Do+ye zU|)(J+h~U5KplgvqP0kdyN%8&aLTjZGT||$5oJ&>gitScl@GmigISO(tL zgB}S_R`vVoRGeCO@V3}{?}c+%M(VmG-xy?Ey8mV^Pq-z9$018*USBpBe?F|--*CD~ z=4zKh(Le|<(<8cpH~AMG!TaMgYnB5_^q&g(82|L2_VYpe-2*dKJvFT}l3pBG8Wtxa z-lTgfIq9PbUq6B(EGOYs(I|;C9N$YhXavb=k%`SnU;qO25u^fSdBk}r8EAJnxZ;_1 z^3u4RylFFg=mI|a=`Pv^XGoHVugD^6j5JBcuZ+%8*-#k@+KGcW@g*J`-mrj-u#nsfhm`$89SKC#KR0KoNSlNwW5$I>*LB|}BX6#2i z#JVVNFyh`HT)EGEbFVI8@I2hcmPFZkY;zF7Shd$ToEUkPW9XpQLI|N#&_i%=(jpXI z%sr-AtOgE*n$W-sIX(2!lgKf@bQ0e4rV(nITUOD5Xf%2mL8kZRVsY6$U;~ded}xE? z6jk-tXhDD0{4800?qD~vv$+;GKOM)H%qOD_f1i(R6)hgs++SgTzwmryg??UPHR48Q z$S|aCg=rYIwk`1-yXbdVc=t5mL@1VqgT4t-QmZ&bECsH4tr$U>VRI|BUoM+`(bnDU z&YlRFgeQ*TfmHQ6L58NZKHp5GQ6e$_;K;sfo)iw=97Z{Ty=KCy_UEL=h%1W=YV# z-|E|n7nD=uP-S5rp4Z%e8~IW)UOgiwynTY|vSK>C&WD6P=mImi9F4(Dv zusL<(8%`3vP4Q%Zzsf3I`)l9uzr?+flY|vNxRkM0-B1bc9d^9ShwJgBmO>mOb8pGH zuUgH>o#CyI@wk89#B06T5|6DzJSg@x;#AiVZ6H1rp$E9?zw8EtC0)k{Xb7oy4;Vd|pr=*%76rtL@ z|FYZ#`kth@J91ni!nb${s*I834wM%`fqu5H4Qz}pP{@76I|;;XM*zIlYhAn*wH~i89NbXI5=GTim6RkGhP+pbGMqk z{&4(5pV%zQegj?nRWRL-+u6*s;*X@lLd4uoq5Q?onyE_N&1)bIBYy@R3~0Of-@N<< zE0F&}=CogfNo<6J_xT60XKkWbh1yLBpCCRRiVjX0D=Cf$R<-VXG8bQHSS(-aux3fo zg=-IEGyVP*^=R4rtHXu|DkcU5u|UOvs7(y-PniA4hI*giNk0EAFM2QXNt7ZjOJm1YM*r&Js(^|#)gvOh9#`Zo%;FyrIlv1u$I{0LxCygCxWR|t7QWz5e8$>8dK zBcTuTHwj|nc{Vh^1@fOkdnj9R^M?)PbjU7Ip7zwn1re&jTff8&h*8cPuydOPV-obg ziuHT~e;jPrP|r73wJ8j#i=E`MBO;qWkr!p3=(5BKI=&CX_VJz}b0!)nE&V8ECHTPH zRqyZEzAumu#FWqMv2xb}JUU6F8`z>)lV;n!N?EdW>v~(l+^MrfJ*(?5_ZV>v8-+MKQ@!STp_p>Jm3ySWxz`i8=v7F^zWN}d4Bq|oGh3-LUpL}F#F6C{5Sbw$ z^TqJFhPdqP!!b`MCZ@}hW*MG7b+1Q>f84npwLKmC0v$bW$>z_>Ba;K*(&gy|AhZKS z2_^6E)afo+Yb{VNt5Zg+0ewpO5U*2?SR@cf_)8NUDc!7!Bq$j33*%io zCgMx^j$0wy@t~4olfAaPBvWvEx%Yb^nOUlkrh$%ly0rq^GCfx!HKtH51xws%zHT&138oE zZF|&ppkWknh~z|^xNlVodlXjNjC2=K05HFTHFT}GXzXCdop~c8ax@40X)RAA?M-o}nqftb`MFbYpo5_Wi*{ zk5{Vhu5oX~uOsz)zlS^?_C9jh-WmZ%Yif@atQD4#PVUsJ=!-*qlE;P;s(`zYnh$st z;Sv;LOGNO#rIFpB_i-XsxfJ0rYrs7@Z<*k5S2LBjZD0~O)e*dU&vGrH`It6-rlwjz z%2-Y4kM|nNDVL`~_(UWfBn;)4n@Ws=~*^($nvWrao~a``&{Ahyl(rQm!a?nW({pMw3?hn+bkV^|4wat2)`JBN&% z@qld}%$J|sp4e7KOzjJ5{Po-gU$fzj&B%AxT$2|>tC;qt&SoAl`_Ho3k*meN!m5vg za~?~l^||2`^j2=Vnl;~-{w2foURqzo(7h;1419M}tv5bzB zXN)Q3p0h`j>2HC#i=vlfyaj|Zb>bqyh81QU$L_d6)kGrrl;2{)m|k#e(CIGqYcop| zC$?yUPI)Dex)y*lyv7$BVAFaOP>NRjzO1TQW<1;VVt;TH18VZ(`-?|J>JhqD`_yb6 z`^+gxCJ8q-rPkdTK6WB%i_727Fmlm{6mlltzzY&hLYd$g^k2tcG+nchQjgg ziBr+X+KXuu;KZRiMwq63?Mfsy2z7RmyroBDGv-|NA<_8GM4{|CKDN;Kg=P6fd1AXI z(EXLpOYJ$@PL(lC3oV|%E>nG>d$ZJUlgE=oYbsnaL!926UNN06R|$W2H$MG@&)c|H zyD_ik1VUbO#hA*P3VugjzY(-fsX8m3_Pp<*lYFb05$JyW{0vNuhBbqegV3XcxT+oO z$(=3DdWT7qw7VB=hsh%v1KOX~UX?<9kb6z@((L1tunmR}((L4IF2)L|p$~3-;i_RW zmv_--(?A4(EHd%2^29CY5mn(U9l4VevB+JjFs3yL#m;wEX`pcSs$jVsg9jS&`c zJ#y@ZQ|{aQnOOPym#fG)RKbE#d1|PR@(XNZ(Q}BozLf%xZrTTW6uq|Znl4(A_ zBiZ}S59P$lZn}4B^?S1D`seYk>FMdNs;$-)@opC@0(wd4HPJl|tdqJI6XoW$JVRZgpKc56&JB#HJRBdL146D&Vr*0RP*todV zhdxK^sZN%O6?84WZqKgQGovPJ9Fkctgr-1ZoW9M%>r=}o{H^z^{H}cFeURLx9h6nP zuQ!xULO!|)ISmxoCV!Pio0oLf;%LNuIBp!@PBJ{!!X9pChWz2*mx59|0?SS0<_ z*nXpTTCGONi8K~seguaGh8+FK?quB)O)nQKx^o6|;yvgSn4_SS@ToGEVtskI`n|}s zWghuJg}lt-rWf;{!ZnzlSCW0EA%6Naxdg-Jo{UtXC=L$IE(a2%$-aI9OUrqIrE88i zmW%!1Podb&pJ_61&}4s{)w59Id#eUh?hT@_GdPBJzDs;)_26HH10Y>m;>8I3)k(P= z#^n6=E6jNfuleB8KePV`%SOeo;_tc&@c)KomMGKpUf_O?KC^p&5VyQn)Gif3QSX<* z+&J{wsw5bnLdep#g2?;;1|mrQ*G1bL7yV`#G%NHi!excPqP>V zPb4P1ekXR=+t~g%uSe&mM2*t?T{==`IKjxwavVJ7o;M%}tz}H%5|;Gx^u)l)xYftE z^um+af%7hWc)MS@iMF9R@}+6_YlfNa-@l*FD|bf1dxXMzolTF8GfppNOy2AsAJfu2 z{p@h;YWCDJQMD>H7WB4dTt{9`&s2o@sf|7KaN;wdwZrPevKerZNM=5PYEB&c4Nf$) zj2~WEEGSpmpHdQU3r|t1>=Iwi`OvM+M_x$R&KxeFdpj{)Jm}&?=kB=Tj_Exg-L#B( zTF|$p4*K7K;~Bn3!-aN`=fY$c)kv#lW;^gC>m5%TILa+JaxFN+f5#zz{g&onEG)ya zE_+j3a)279Mwu@{htAF0y%IOqQq>=y~t`t8#e!XGP+_Lgr+ThpZY0oWfvECw3a9Q8HS)W=w z9MNMv4!-JG$LzRh5leI9cx!FpcwU|3NkeP@hX8`hapOVr&+Eqljn>_>D{r;OT*7K5 zj(z!encrJJxS+(jh+NIlj-Q&ZnLGBS;N*K(x z>uV1Dvj?!mf-1znKLP56=s=YB|MwkgQsvP3F;c(9uW7=}LV{>tEa)+QNQX(tbCr3G zv2}opt>AajgAG$rF2khzVo-Ci&>H&K3p}=D7$zX_#PZwAOgjO7n269QyI30;Eb@tKV^=?S6S6M)2Ra i{AWx1f4sz`{g&EYs`oTdB5XhbKZ^3t + + + + + + +MakeBlock Drive Updated: src/MeGyro.h Source File + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeGyro.h
+
+
+Go to the documentation of this file.
1
+
51/* Define to prevent recursive inclusion -------------------------------------*/
+
52#ifndef MeGyro_H
+
53#define MeGyro_H
+
54
+
55/* Includes ------------------------------------------------------------------*/
+
56#include <stdint.h>
+
57#include <stdbool.h>
+
58#include <Arduino.h>
+
59#include "MeConfig.h"
+
60#ifdef ME_PORT_DEFINED
+
61#include "MePort.h"
+
62#endif // ME_PORT_DEFINED
+
63
+
64/* Exported macro ------------------------------------------------------------*/
+
65#define I2C_ERROR (-1)
+
66
+
67#define GYRO_DEFAULT_ADDRESS (0x68)
+
68
+
74#ifndef ME_PORT_DEFINED
+
75class MeGyro
+
76#else // !ME_PORT_DEFINED
+
+
77class MeGyro : public MePort
+
78#endif // !ME_PORT_DEFINED
+
79{
+
80public:
+
81#ifdef ME_PORT_DEFINED
+
86 MeGyro(void);
+
87
+
94 MeGyro(uint8_t port);
+
95
+
105 MeGyro(uint8_t port, uint8_t address);
+
106#else
+
115 MeGyro(uint8_t AD0, uint8_t INT);
+
116
+
127 MeGyro(uint8_t AD0, uint8_t INT, uint8_t address);
+
128#endif // ME_PORT_DEFINED
+
145 void setpin(uint8_t AD0, uint8_t INT);
+
146
+
161 void begin();
+
162
+
179 void update(void);
+
180
+
197 void fast_update(void);
+
198
+
213 uint8_t getDevAddr(void) const;
+
214
+
229 double getAngleX(void) const;
+
230
+
245 double getAngleY(void) const;
+
246
+
261 double getAngleZ(void) const;
+
262
+
277 double getGyroX(void) const;
+
278
+
293 double getGyroY(void) const;
+
294
+
309 double getGyroZ(void) const;
+
310
+
325 double getAngle(uint8_t index) const;
+
326
+
343 void resetData(void);
+
344
+
345private:
+
346 volatile uint8_t _AD0;
+
347 volatile uint8_t _INT;
+
348 double gSensitivity; /* for 500 deg/s, check data sheet */
+
349 double gx, gy, gz;
+
350 double gyrX, gyrY, gyrZ;
+
351 int16_t accX, accY, accZ;
+
352 double gyrXoffs, gyrYoffs, gyrZoffs;
+
353 uint8_t i2cData[14];
+
354 uint8_t Device_Address;
+
355
+
371 void deviceCalibration(void);
+
372
+
396 int8_t writeReg(int16_t reg, uint8_t data);
+
397
+
423 int8_t readData(uint8_t start, uint8_t *buffer, uint8_t size);
+
424
+
450 int8_t writeData(uint8_t start, const uint8_t *pData, uint8_t size);
+
451};
+
+
452#endif // MeGyro_H
+
Configuration file of library.
+
Header for MePort.cpp module.
+
Driver for MeGyro module.
Definition MeGyro.h:79
+
void fast_update(void)
Definition MeGyro.cpp:276
+
uint8_t getDevAddr(void) const
Definition MeGyro.cpp:339
+
void resetData(void)
Definition MeGyro.cpp:661
+
double getAngleX(void) const
Definition MeGyro.cpp:358
+
double getGyroY(void) const
Definition MeGyro.cpp:434
+
double getAngleY(void) const
Definition MeGyro.cpp:377
+
MeGyro(void)
Definition MeGyro.cpp:63
+
double getAngle(uint8_t index) const
Definition MeGyro.cpp:472
+
void update(void)
Definition MeGyro.cpp:207
+
double getGyroZ(void) const
Definition MeGyro.cpp:453
+
double getGyroX(void) const
Definition MeGyro.cpp:415
+
void begin()
Definition MeGyro.cpp:166
+
double getAngleZ(void) const
Definition MeGyro.cpp:396
+
Port Mapping for RJ25.
Definition MePort.h:128
+
+
+ + + + diff --git a/doc/html/_me_gyro_test_8ino-example.html b/doc/html/_me_gyro_test_8ino-example.html new file mode 100644 index 00000000..f245f27d --- /dev/null +++ b/doc/html/_me_gyro_test_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: MeGyroTest.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeGyroTest.ino
+
+
+
+
+ + + + diff --git a/doc/html/_me_host_parser_8cpp.html b/doc/html/_me_host_parser_8cpp.html new file mode 100644 index 00000000..d5eb7f3a --- /dev/null +++ b/doc/html/_me_host_parser_8cpp.html @@ -0,0 +1,227 @@ + + + + + + + +MakeBlock Drive Updated: src/MeHostParser.cpp File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeHostParser.cpp File Reference
+
+
+ +

Driver for Me Host Parser module. +More...

+
#include "MeHostParser.h"
+
+Include dependency graph for MeHostParser.cpp:
+
+
+ + + + + + + +
+
+ + + + + + + + + + + + + + + + + +

+Macros

+#define HEAD   0xA5
 
+#define TAIL   0x5A
 
+#define ST_WAIT_4_START   0x01
 
+#define ST_HEAD_READ   0x02
 
+#define ST_MODULE_READ   0x03
 
+#define ST_LENGTH_READ   0x04
 
+#define ST_DATA_READ   0x05
 
+#define ST_CHECK_READ   0x06
 
+ + + +

+Functions

uint8_t calculateLRC (uint8_t *data, uint32_t length)
 
+

Detailed Description

+

Driver for Me Host Parser module.

+
Author
MakeBlock
+
Version
V1.0.0
+
Date
2015/11/12
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for Me Host Parser device, The Me Host Parser inherited the MeSerial class from SoftwareSerial.
+
Method List:
+
    +
  1. uint8_t MeHostParser::pushStr(uint8_t * str, uint32_t length);
  2. +
  3. uint8_t MeHostParser::pushByte(uint8_t ch);
  4. +
  5. uint8_t MeHostParser::run();
  6. +
  7. uint8_t MeHostParser::getPackageReady();
  8. +
  9. uint8_t MeHostParser::getData(uint8_t *buf, uint32_t size);
  10. +
  11. void MeHostParser::print(char *str, uint32_t * cnt);
  12. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+forfish         2015/11/12    1.0.0            Add description
+
+

Function Documentation

+ +

◆ calculateLRC()

+ +
+
+ + + + + + + + + + + + + + + + + + +
uint8_t calculateLRC (uint8_t * data,
uint32_t length 
)
+
+
Function
calculateLRC
+
Description
To calculate the LRC.
+
Parameters
+ + + +
[in]data- A pointer to data.
[in]length- The length of LRC.
+
+
+
Output
None
+
Return
Return the LRC.
+
Others
None
+ +
+
+
+
+ + + + diff --git a/doc/html/_me_host_parser_8cpp.js b/doc/html/_me_host_parser_8cpp.js new file mode 100644 index 00000000..7dbb9a80 --- /dev/null +++ b/doc/html/_me_host_parser_8cpp.js @@ -0,0 +1,4 @@ +var _me_host_parser_8cpp = +[ + [ "calculateLRC", "_me_host_parser_8cpp.html#a59acdd9a3bd91179b07a28853591e88d", null ] +]; \ No newline at end of file diff --git a/doc/html/_me_host_parser_8cpp__incl.map b/doc/html/_me_host_parser_8cpp__incl.map new file mode 100644 index 00000000..87c99d76 --- /dev/null +++ b/doc/html/_me_host_parser_8cpp__incl.map @@ -0,0 +1,7 @@ + + + + + + + diff --git a/doc/html/_me_host_parser_8cpp__incl.md5 b/doc/html/_me_host_parser_8cpp__incl.md5 new file mode 100644 index 00000000..3f3a1755 --- /dev/null +++ b/doc/html/_me_host_parser_8cpp__incl.md5 @@ -0,0 +1 @@ +fc09c39669d0535e6b34d1e0064b9a6e \ No newline at end of file diff --git a/doc/html/_me_host_parser_8cpp__incl.png b/doc/html/_me_host_parser_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..beb7bae78f7ba6c89a27de70c7f1620f4428d3ba GIT binary patch literal 2332 zcmcJR`#;lfAICq*VL7a!r33CcBwvRiIegLFv|)*qQ)p5M-Hu@n88u;2x{*UUFIi?$ z$)U~pOGrr08*Qm3Mwr8j#l0Ti?)%&Q2Ylbx<9fdy@Avi7`+7W{*Xv4ku(y^HKOhbO zfE3yWc}Ac_!KQ&k1(~ghvJr^rMO$kmu>E6|G?B6Z05ph3S~x`)EKJ!2%KPmXTiVv| zC%Pb~uiZsHEP={6tlf~=m8vM7;cn2EB%w^;m=wy&!Ova&)Gh)Jl*v6BkV&t&0i?dP zbm%CxL4j>-l1|w94vNdGNF(HHvln8FJ3K~dHTo<4W1Efo+r>VervF$pqir&II6rKm z2;oP7vnE7(dwcKP?3P8`ERA;<8PmZ~SKqBZQ>i(a+AXX6jPB_+e0&C=*y-d+Om|c` zk`7cSZ}@q8t3<{OUr|6->_Z;8ZlNmsm$dmnJ{TibL*8Lg3{6@~nsK^gf;yv}LvZN` zyR{r$K%K-t-`G2nUss^0JEp?j#Uau04gUL19K3`{rU=gIY@#RWl|x=_0-Z{91m$|a zKzPCz?oN#PVxYB>eKl>})WZ6pEQ7mK34_$0w2s;>s-jLVmQF6ESg{Ex_Q?Rw-l>Y& z!;SL_)!{|=qWI6TBwi1r<@1MZ(yO}25eFx2ivk4%u5bCi$@Q?N1k{&=LHCvPpigCw z$@JI`wPc2d!O;oq$mWbmP`3%z)qei+?`{=bazPQFEhPru@u-I6|7@&+<6gn3i`irs zejI+hR{EmiLgQtc+os%pMa+zM*81Bj@nL6Im)kL${iA0iFmB-q8lhYKZy|(k4fB1B z^Kd^#m7$?w33&$Y*%ir(Y}n3yUc+B;mZ=m95XUGR;mJ;2Vv55b>uh^;|le zkv8DHr#xSq3j=nLR4=rM-*>0|YT!OFVnvTH(`t@-BHYPh&2+a705`9LasWQZ%R_@; z5wXM%m`G&#g0T9A3}+U7h2&dZ+ir5rBBE?p@IUps$9-VZ!OvYBte1Q`v&pwcmldyB z?+sk$W&17tM)1$~O-esTtQ6Zp6E6b~(8$plN)cVKoRU^4SY)&!lJ(@AXbL;is(w{l z9bvu#YHqq>g_x-*D|u?IWg7+^EPWs2Dx8bUmNgN5s;a;;S$%U*Xs0tJR#QDx@*-Nt z?9d`%dbf}&um^uzFmc@?)v^=jQi9h6WOl5VHq6nA{;fxV&M$g9Usspb3b>Kq%qdm$ zXnt6&&3ro+HzsWozfrCXJqH!h@p2s=kL)l`Zz)jiiMoH8c`L%^w-3s8SwdDT(j_CcccGf-DHpqnpW+$_Wm;ShirOj`pjoNvt zRviz{5FoWcxA#;SEeES58h^i$i))=L@M9~OKc1S!an}dj7q2iY<-3fsEVRfKN|&&) z4qdY6o{u(qd&s+RAQ6!KxFninOw2iwlv`KbWTo?kFFwBQk!P!Zp>I@#p+W^0!~di% z_`lR;AHeBDI~pZAQE*k7mQHvk>+MV80ymkiHmBhc~sjH}bRM@4R}X^eK!y z#{v2cMw+1;Ba878z(*q{?F%iZT)~XwGx#T1Y+Cx8u=M}o`IFMWLn3A>)7*7qom+Ob zg%h_Ec2u&$07z%PW3P-loMNV_v-wCLS>C+VMYUNX2^&BDP3Jr`&i4`{q~6(8?um88 zQTH*U9cH3^ar0Y^SF996D$C(4`N0gpwPbu?+)J)CZNYh1N|N|My*(1Jl`wLUpKztr zxt=!CC8Wd6v=fr1c|hjf5%IQzxy9LiIlbbFiD&VkDj;t&_LQ@#O=#zFbelKCcKnp? zc5%HXOh{6>ak{jOrAIi#|4QNSY^{bm9@fU=K=Er2{CpVaecxY%*q&iM^xxp-T9!oj zc%v=6A-x+A^V4374;c8S-7@@PZK!jxWwXgYKn zK;_ZGwrG5Rf{1(8z7BCj)mKzmgU(G}R>~52G1l@W%w;LDhI>J1(#dO$8}O|)>X_08 zQV5v_H%SP~pA=r1%@;5v2b^ERbWwUzLOU+)W#0VoRga0-}&>veu*eudnhXdjZ6OBEOWkv%WPguE*F!=1{O)5GgH|sUnm%6YX34l`1s!iPbk3 zaVO7k-aeQ&iw0Ye5~%T3jHb0>nh!LC!)nkJ@49nbz{3cfo48fA~Hvh>3L2l6pgjQ{`u literal 0 HcmV?d00001 diff --git a/doc/html/_me_host_parser_8h.html b/doc/html/_me_host_parser_8h.html new file mode 100644 index 00000000..2f622705 --- /dev/null +++ b/doc/html/_me_host_parser_8h.html @@ -0,0 +1,181 @@ + + + + + + + +MakeBlock Drive Updated: src/MeHostParser.h File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeHostParser.h File Reference
+
+
+ +

Header for MeHostParser.cpp module. +More...

+
#include <Arduino.h>
+
+Include dependency graph for MeHostParser.h:
+
+
+ + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

class  MeHostParser
 Driver for Me Host Parser module. More...
 
+ + + + + +

+Macros

+#define BUF_SIZE   256
 
+#define MASK   255
 
+

Detailed Description

+

Header for MeHostParser.cpp module.

+
Author
MakeBlock
+
Version
V1.0.0
+
Date
2015/11/12
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for Me Host Parser device, The Me Host Parser inherited the MeSerial class from SoftwareSerial.
+
Method List:
+
    +
  1. uint8_t MeHostParser::pushStr(uint8_t * str, uint32_t length);
  2. +
  3. uint8_t MeHostParser::pushByte(uint8_t ch);
  4. +
  5. uint8_t MeHostParser::run();
  6. +
  7. uint8_t MeHostParser::getPackageReady();
  8. +
  9. uint8_t MeHostParser::getData(uint8_t *buf, uint32_t size);
  10. +
  11. void MeHostParser::print(char *str, uint32_t * cnt);
  12. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+forfish         2015/11/12    1.0.0            Add description
+
+
+
+ + + + diff --git a/doc/html/_me_host_parser_8h.js b/doc/html/_me_host_parser_8h.js new file mode 100644 index 00000000..065a4b3b --- /dev/null +++ b/doc/html/_me_host_parser_8h.js @@ -0,0 +1,4 @@ +var _me_host_parser_8h = +[ + [ "MeHostParser", "class_me_host_parser.html", "class_me_host_parser" ] +]; \ No newline at end of file diff --git a/doc/html/_me_host_parser_8h__dep__incl.map b/doc/html/_me_host_parser_8h__dep__incl.map new file mode 100644 index 00000000..49eddeaf --- /dev/null +++ b/doc/html/_me_host_parser_8h__dep__incl.map @@ -0,0 +1,7 @@ + + + + + + + diff --git a/doc/html/_me_host_parser_8h__dep__incl.md5 b/doc/html/_me_host_parser_8h__dep__incl.md5 new file mode 100644 index 00000000..1d46be4c --- /dev/null +++ b/doc/html/_me_host_parser_8h__dep__incl.md5 @@ -0,0 +1 @@ +33f35048fdac6fdcd68714e663fd1bbc \ No newline at end of file diff --git a/doc/html/_me_host_parser_8h__dep__incl.png b/doc/html/_me_host_parser_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..a81262bb4ef889aa168edd821104618ece726d92 GIT binary patch literal 3266 zcmZu!c{J4R7yrs2!(`2pEtF=gku8#lyt0H*WEuOCb;vgM-5?~%zBDqn7);1gmQcMz z*=jJ^B1>Z(>&Wt(_ni0q&iS45yU#h#^PKy~y`S^BpZnbNB%2uPLBJQl002Pr|I#r7 z06It79eI|KwqH^TMbHjLM*}?_;PjtW`mQ1i09b?db+pVw3fHD0o(Q@KF>P-6?$uea zzG3vP)tVI%-(skZpi7CxJSCC05OoY-nQ25j$d1!!v_B{R54~x!yyT@&xv=8Wm}yh( zkoKufvoj6PC)LLonfssJx=d$U>Wx{OT0c4}3l0cV!MEep@n1W_HTCIR@YlAdCfuUb zw^s*l0383d%h|c-Ztap+R;amX8+SFPgp%rYVL`#8iWR|y*L?v%bqU%ADyD9@RQi`C zlYMW%S^s`*L3%=toQhD4wpV!gj{s10kAhG%8oFYMPDZmjiAsnmJW0q!f4a)!C?@vd zUne%v89$MAV!eiHlEqC^-+gk$r=RvnJjwfHcOxS=JZsQ(m`GeY2;o!x^_W23Q8hJr zt7jPK)GbC~V(~lEDwL=mcrE0*^9Gsx*ak~NxQW}+WiJNjKk(#D$q7VFArLR%Fs44X zb_q_`AcxmG!A(nyc`v7_Q`o_9{gA;8;vS{3(Bpc@B~DH0US)AV?sva?Kx_6Qt~{*Eb7pOTQuqbDC1oMb4?9#fH;eb4eDkOly*isVSM_Xb z%dhfxTTBdH`VfcNYW~IlN9_Ny9ipYjDyWL=3IK_D04#p-4_^chHLo#EN9@~)jb4HzmSUIFEP_P6w2W$#Y^ptm`&Yz5BBeI-{rc;0si{;dGPZH7iLpiipPY$aW#l7qaNq%x8h% zqodQYKM^c^{L4=@l~iE5LSMxtqN-9LUP<;W>AVhI@6OVLVH4wg&0?%TnP<7V^c>Il z`I}d+fOqsRjyuwmUj8j4NQqC#J-UohOWp;}0hQxXlCc=@I^X*9<3Z-7DP+ZJQi2G5 z<$7TK?q+st8$w7&@x}M0=jiCZ#MnF4*$VrIA|!Ac<($Go>(5mRiiYpC+`t-` z!EA~R2&JPt>#;%TpZfrU$n%<+;6ma?NcWDh^9Z>$MPBEiTNTHKR^6q+)Y*c9GAgi} z3_NpOhjLlOHDw!Cdr%6~HPo@bFOIT(C!O}z71u`D@D@Jnsh6w+HsfrpB0bdLxkjha zC|=OLF9khDo$qaa`dx{lKv?8aBSplo%=K{4wzq)oZ6Qj>ilONctq#>8K(q_2Zayuh zQjjgX(shc#R<6qj@a0am>=v_W?+)U>XXJ1>+QO?FKjoA!UzFSv7uIWjpVsWxLs(nr z$E#!8t!~E497{R>9Z(1TePMX4XSCjyLDRgiD^vVnaoH+Qu_$%GQ52h^d;{b5rrD9Z ztJNf6NzHjI0IRwzJSwG&WQ&d}jaO3FhEt#;*G(vf{V(52m2o~k*`9YGdnCD{2 zXR`9N`OUlo?5MsEsl38i__lG367asn^J7uRFlrNf&#zse%Th7{a-8#7bTqFLWr<#i zC=edKHx63`)$7CvB#uyCtr+T$WD!%j`MS3Xm~9DVPZ#WoAUf5P`OKmo1T-BJe_pz0 zP$l=p5*Ayp9TP?BDjvuU%KM@-*sbw1etyM#?!zcUR#Jj$x3VTiq}kf9g2_ z83HN)B`0_+{?A;v`0dVcDf|4gNJGDNA$x}@>c-}sqpjY$WYDs#yIxg1FN6Cxp73H_ z)waY*mjNE>`}TKJLge8?HAZfj{s#7s{CdOa@|k9WR{9Bt+-g3$YBz%%OXZ1VDy8pg zrfKPs8W$C(juVjX_BG#PjV|zig!&jDK}k?+Z7<8YN;=j9WFPa|HXsURVUN=z%d9T?}3m5%U7+_L8)KjeY6#MC#hG|IA z&GlcSpzrrkXO~52y(H)$s2lf#7TSGIfJ>`oZ3LcSMtqSK<(LDRVz!yZqXj18W7r{<_{oOJ?bpp?c<@Sz}KZ z39^^c8!o-`ylC;Q(fMPU)J;h7qPsAQ-zPtA2v}PJr*dYQ>FSqZ&4B_q8b7frNowwN z5@Q`Kcaye$Wq`Aj2zwm1ux4=}&H@k`Bd3W(-cRS_^gT}7mJ1U?5sPQ2+s9m#{$3Jx z`%(h@k9XejB~tTO?o9Fv8SC#I&gK)=WnB*|5Q+E~1;&m)dV4`$Bw+^jzeJ5~{zQ3l zTZ-BBa5mSvB0W1FgSVb|DGP)^#c=uGWG7BwXMNUE+>F>c`1`dDb)5NFfG(ZbNCLy#>(n> zg{k*}WDRb~uPcgC>hSg*|jDXN`QfRFPOnKbCvIr4MdA=oed*~FhP|9O&tr;>uWP)a?P(@Vt&(P+dPGz z;+>(2{!n{IK}Tzh@~r)BOO&Qv3DGC(E;*gx_9;h%e1ZBva^t8jNOiWH4n#HL?`?dy zE*f7;*LGZKN_bo*OAEN*_L}9vOcc zRxe_e4%-AG+ zzKrBO!vB-WBCY(&1>UabFeVOvDqQp7==*^x(SeMO?BAT*(imI4nxnvmPuFtL|253g a>5ZIs`|ocF#?n3|fWEG=PMx-W?0*1U(K;mn literal 0 HcmV?d00001 diff --git a/doc/html/_me_host_parser_8h__incl.map b/doc/html/_me_host_parser_8h__incl.map new file mode 100644 index 00000000..467f8874 --- /dev/null +++ b/doc/html/_me_host_parser_8h__incl.map @@ -0,0 +1,5 @@ + + + + + diff --git a/doc/html/_me_host_parser_8h__incl.md5 b/doc/html/_me_host_parser_8h__incl.md5 new file mode 100644 index 00000000..9acc3e96 --- /dev/null +++ b/doc/html/_me_host_parser_8h__incl.md5 @@ -0,0 +1 @@ +ffd08c62cd7c84b6d8fee4edfc4dbac0 \ No newline at end of file diff --git a/doc/html/_me_host_parser_8h__incl.png b/doc/html/_me_host_parser_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..a5c4649da75bbb1d97200116f4466abd16dd53a9 GIT binary patch literal 1419 zcmeAS@N?(olHy`uVBq!ia0vp^Q-HXDgAGXjcp2#cq}Y|gW!U_%O^81usV3U zIEGZrd3)DCTRT*O?ZflAW_n&nTW1&jb>886-Ra=bSPpTPZt3!S{1>i8?))fx$N#}8 z-yH3%i??2}XA~A5Y~@yb5$55vK>TiG>m}dWd-Qx#jON`S(!4$|s8?K6S79S5r{%!Dd&k>AuMwHbN68Kb`6-SIzXm zWYWy0Ipz1KBM^))I5^N7q$T5v*y*>#zOhEeEght@=k&$jvd zD}P6CsTE9=P^-J@8)~{Vu63=7D&JVxB~}&R?(eH|1*L(Ueo&^B=6aUHLmK^6;X! zm*359+nez>?0opdx=*h*Sn*F?v+!ADu*%)(-xe%V&%4N;x0CO*bzRW@i)NK?pV#jD zG{y4VA|EEv`O{+7Hm-_VAzoYa+2&tm_F3z)*n4w)X7&bz`Xr}jt=RN_Q~&xGC38yO z?AqIC7&&En^zS0VQyy#sGOGSSEduKt*hwN`Oytm(OU1fLk{{8tskEFfT%b9c^7*t0cCTg;E z`4|SIbU{MVYww1e@4ruvWH&uB*MZfsz)-Hge#f3YC4v67wl&Wg84^BRmhaPEIaPr} zFXsA#rE`mI?^<5J{KvL48;fCxD8aCY45{*eem`rs7ca~2ez5k&vwpSv_WgMwNAufn ze>z>H_1XFD|HaQYt$dKGVYN!av*BaP=P#|_B^h2wG;)N6eAqWz>veZ<+?m(<58N5* zI}=#Du06>v{dBcyk!q7DL%sjEr5tQp&t4|)Y<*zOk!Mu4JMh8m<^4~~GFvN~8od@I z%Q#;=bz`Y2W8d_!3GO>I{1<6iKd<0>;CM=|UT$A|xWb~-I;YuX7EbyjK1Erf@Ye3Y zqv1TkMr>NGOvfD_ZMn{M;H4h#@;yA(>A$Q+@{i41dhg-3Jr7qbx%HT1s%v3OLfWm} zf(NIsJN1!~d8%Xd4>7CakK31a38%AGHZ-34aCEnkz|r+gJ&YPGcMs>j+_`S`If)fA zT0f)?L^KGBxUYM?(wa@{ct(pbYtzOASLT}cyX3MO?i$x_t6p|K=K4eCx?2f+S{6dA z`YGoYhFxE1HTT?drBAb7TRqAPyB@`GVb|Vszgjm6uc{Jkd#Jwd^^8?lIYe0wvS(*! z^IyMyJ$Cw}N3Pdd&+OQ>>(JM)Ul|yfr=}$*GtZtqd)?^|PW$g4PcSHmJ;t-|v@&WY z1jhJEH`Y~m^TMy?UEDYQ?(*zj&XC=Aj}=&~d85MHe%R|*?yO@hU9TR-v1D0gxw@|} z+dbD}*3s=tx1N2i{C3}#U$czxoZ;X6Z;ygQN}~Tf-*nvPx8=)kd;b1- z71tBs@JlM=qHsp(qgwueIp38-E=@7ndw0v^r_Aq}SylF*n!QQwWAF9gxN90APgPmG zu6GEoTCrxsRNkaLwG&yZgezoM?3pZF`#gL}?!A8>e}B%Kp8H&Q{c@XC@+esXnpCq& zWxYb(_r~$>mHW?fd5=rVlU;2qqFA{O99Q}@>9vy0=l<7B9YC;RPCeuFS1vD}J&Q8} PmaYt*u6{1-oD!M + + + + + + +MakeBlock Drive Updated: src/MeHostParser.h Source File + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeHostParser.h
+
+
+Go to the documentation of this file.
1
+
44#ifndef MeHostParser_h
+
45#define MeHostParser_h
+
46#include <Arduino.h>
+
47#define BUF_SIZE 256
+
48#define MASK 255
+
49
+
+ +
56{
+
57public:
+ +
65
+ +
73
+
90 uint8_t pushStr(uint8_t * str, uint32_t length);
+
91
+
106 uint8_t pushByte(uint8_t ch);
+
107
+
122 uint8_t run();
+
123
+
138 // get the package ready state
+
139 uint8_t getPackageReady();
+
140
+
157 uint8_t getData(uint8_t *buf, uint32_t size);
+
158
+
159 void print(char *str, uint32_t * cnt);
+
160private:
+
161 int state;
+
162 uint8_t buffer[BUF_SIZE];
+
163 uint32_t in;
+
164 uint32_t out;
+
165 uint8_t packageReady;
+
166
+
167 uint8_t module;
+
168 uint32_t length;
+
169 uint8_t *data;
+
170 uint8_t check;
+
171
+
172 uint32_t lengthRead;
+
173 uint32_t currentDataPos;
+
174
+
189 uint8_t getByte(uint8_t * ch);
+
190};
+
+
191
+
192
+
193#endif
+
Driver for Me Host Parser module.
Definition MeHostParser.h:56
+
uint8_t pushStr(uint8_t *str, uint32_t length)
Definition MeHostParser.cpp:125
+
MeHostParser()
Definition MeHostParser.cpp:63
+
uint8_t run()
Definition MeHostParser.cpp:239
+
~MeHostParser()
Definition MeHostParser.cpp:85
+
uint8_t getPackageReady()
Definition MeHostParser.cpp:104
+
uint8_t getData(uint8_t *buf, uint32_t size)
Definition MeHostParser.cpp:365
+
uint8_t pushByte(uint8_t ch)
Definition MeHostParser.cpp:154
+
+
+ + + + diff --git a/doc/html/_me_humiture_sensor_8cpp.html b/doc/html/_me_humiture_sensor_8cpp.html new file mode 100644 index 00000000..d432e679 --- /dev/null +++ b/doc/html/_me_humiture_sensor_8cpp.html @@ -0,0 +1,196 @@ + + + + + + + +MakeBlock Drive Updated: src/MeHumitureSensor.cpp File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeHumitureSensor.cpp File Reference
+
+
+ +

Driver for humiture sensor device. +More...

+
#include "MeHumitureSensor.h"
+
+Include dependency graph for MeHumitureSensor.cpp:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+

Detailed Description

+

Driver for humiture sensor device.

+
Author
MakeBlock
+
Version
V1.0.1
+
Date
2015/11/18
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V3 or Commercial:
+
+
Open Source Licensing GPL V3
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 3 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for humiture sensor device, It supports humiture sensor provided by the MakeBlock.
+
Method List:
+
    +
  1. void MeHumiture::setpin(uint8_t port)
  2. +
  3. void MeHumiture::update(void)
  4. +
  5. uint8_t MeHumiture::getHumidity(void)
  6. +
  7. uint8_t MeHumiture::getTemperature(void)
  8. +
  9. uint8_t MeHumiture::getValue(uint8_t index)
  10. +
  11. double MeHumiture::getFahrenheit(void)
  12. +
  13. double MeHumiture::getKelvin(void)
  14. +
  15. double MeHumiture::getdewPoint(void)
  16. +
  17. double MeHumiture::getPointFast()
  18. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan         2015/09/08          1.0.0            Rebuild the old lib.
+forfish          2015/11/18          1.0.1            Add some functions.
+lanweiting       2017/07/11          1.0.2            functions update() add delay more time
+
+
+
+ + + + diff --git a/doc/html/_me_humiture_sensor_8cpp__incl.map b/doc/html/_me_humiture_sensor_8cpp__incl.map new file mode 100644 index 00000000..47825b9d --- /dev/null +++ b/doc/html/_me_humiture_sensor_8cpp__incl.map @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_humiture_sensor_8cpp__incl.md5 b/doc/html/_me_humiture_sensor_8cpp__incl.md5 new file mode 100644 index 00000000..173cb5e6 --- /dev/null +++ b/doc/html/_me_humiture_sensor_8cpp__incl.md5 @@ -0,0 +1 @@ +40e80bb6f0e803ec40b6b8d883967647 \ No newline at end of file diff --git a/doc/html/_me_humiture_sensor_8cpp__incl.png b/doc/html/_me_humiture_sensor_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..ced13a23d3a2fe4d8035f6a96df02f0c6b62fa68 GIT binary patch literal 48160 zcmeFYbx@UW6fR1GG}5go(%r3uq#z(AU7K!@E&*u}>28n)5jM>RWFxhaZrQYScX&U* z-<@;sxifdp%=zB--DqOCCSeU5Phpx zg>HdxP22H_87Zvi#w8yf>FZ&p;)7?bZN_Qr(s#$3G*!kwKWYGXuw#BA&ylcJDLZ|q z_vk&Tv}N7I!t!w8Vey|U$^jkzu+9L4Jyj$2Zx2V=)M|54Feu*k{a#p8BT1xh$h@PTa1rz zD>xi@mmtnved-w<9o-j^nw!(vSk?U3GWwx%RW19SSS`mRiZ%D|#GtB@J^^03f2Q-R zWu+gU=dq02|Lw8&8K(EYkEIX8I%)oW9w(ajKfO*att@eK?0(%;yVWFYpklZ{?aKwS zIQrfm4(#*!e`^g3-W-oM9zZEYd|D)|b!{x_&L(2o7<{?1!@}eYfA!t15cf(lFeEJO zCp_nVk%H_kTM<=R-EU2`Cx4)n4%?0cFwOd7S4DLTH}Fl<&6K`pJ9Ttzt&rEH-;BRX z)1mjs@RUdzSfqVO%+t=@hL|8OP;s{5?iiOfr;GhDyL;O+ZRJmOmmMg}YR|s!H14*6 zEB&%((2ew`N5;n&;(uTN-uZI_+8PSe^a~GL!3z<)vk|hKY=^8?<<54H&nnD*3r z_N-WBucWw%2PFGS6F4y`pWE3?>Da7mj1lx(v&$lH;k1O4*o~cPo zA7wgVmvM)jy`zw%8wf3)V*sJm_Q zd}L=(F%`aOoo$7~V2r(z54%o9^i9NY2*L%`u}{>|8L9GJa`kqMtB5TEDlEzceVSql1N|X zUfO{eJj4#~Q%rkJ++|2DYvz@LjI^|~;)7MOwKe4bw&Ta}=c6L@Pz^x1s34gi5opR; zYVl;>mjgExV@a8OcU9QhxM0-JP^KSDD45tLFFWdc%1-5o|hpdI-y{^CYL3=y9Z4Bd!xJA0PL1O(wp|NWbNI*8Kg%UUX7<83~wMej%X zQ?KVC0N_dg^B8Oo`?<~6+tjhIl!_h00p~7wz)iH4>agZO@WMe(jps5YYfKRxu#G|`4G6THf2ThD6goG2iP|33 zK=dE%Z}7QCGTa!uMtwl)L-q?2C0AfuO-&`m3$c0`j4y!9lSRQBd3V>`^Yfj2+FBRK zrzaPuzJx#ym14Q40xQ&B%{O23)!V-r%SI&>dS-gpBp5bjQi#8Lj)BB?Gl}e zZM)o_mX!sK(QAEh)fZgkk#+u+P}P&A;};@vyCvH!?B~_qbykyak-de--XMIsWXfS) zb$H7px;s$C>C+xN+_HiC+vkGI`y{pJrer|?HQiu(Y}#hzua}op-kcgSj<}f_7kUWH zBdP|J08cQ@p#6mHD-z%_V#sTW89k238}hVlx-b8PVTQ8NCmXnHvG>z=ERjw~HTAeR z(5X-)w8_c$6~x`TcGu8Zvb3 ze!U3_Bq5st?VVplMEf4|X8l(IZ=}th`~xXp>s>KFM{Nk66EhVFX>f+F$Y9papP9ab zY|v-N2B!gJpSmJwr~M$`&(5sVQqqg84Wt)BO8ogmQ?wraaKF%15Nj1nU7{FuyK_k_ zomtDPaPO@uGFgOX5W6Ri1CD=v$V;N?BEN4Hz0fPbsVn~_f8V8n?zY(pBz6=Sau#A+ z9AmAS#bi(XEgzg2{!Kbne=J@I-Fs@(VAYwHvLJPvliUK6^RWjk(;Tfo^3%5!()jH` zgQ56Gfk>vd81#WW;=x@wr!c)kifS}%9A4w{Q?fTF*(*W=E#RZbu%9CT@=w%6hb&5b!sZ(*(4PORIukmWhX9wzh{l;6;c zR?28pE()9CsU};P=bFiaonq9NCq~!x_&+mi$V_>XZBeqI+NQ=Jk(8RtR=j;_cP%#{ z`S}0KFXbglmu5ElnJ(3o0^tlObgy+>L4g~ zMhOHXgO8?~%tF=O`^L2=HPRQnCJFtd9Nys(`q;*f$oEM_wrV}nkP)vPRv@dt4loZ9*((ssqQdEOd$)K8J^4^FN?pLC=!>!hG~znoClL>Bi@(p={9E?zY=_q>pyf zXOTd{fpb^=61M)=Vwm3F@|joBk<__c{rarLLbi-uNYo)!n?+NEjpfBVTnBcNIW-WJ z91P129Sdk$ea{a(>b_^wf8?LjasT>fR{Ju)UszpQsmrj~01%HgzwMKn{5H{9!{!0m zf>Bm91y-~7^Ss_qblsS?d)w62Z?m3qhJ22<6#MOqm-Fa66aBi<50fR|`kRk(KB*ly z?xScaWDB1cC={|=eFaZnhSh$URd|xa6kH@Aa2TwK6fP(J&%E~**7zev?r%RH1C zbwq{nhIR)Yj5n!ySN2yKu9=QlB_W2?d}gW}-JZ6c{94Tb=3dw%7v$j*N3w-zufdks zp0;mUW2CSU~D5b#IxmEzbqOv-mqoe+J7V1*q>PD*^N!}v2*g?;lW|E65gyjDk zA;^c;v7sg`h)x^q#D7$s8Z~^!aVVyXnG$%Q6IAluK3xG3r!7S04p9k`r|3m60)G#a zHThx`JX?}^Zv9^d=JxfhMRb3uAYSwr+@V?cIg7A30*+=MNGb1lEq^GI46Qx5Y6uQzk`( z9si?#)0Nh#u}8dGNakW2{iB+q8>55Te_$i71cpDmKac`z%-+Q<8|pv--#HWN$n3}L zT$yW74sHDJUV;O9NbXAnUSt(hUY(!TAuoaY^MPex6tkU)VUGCpWYjv*d=RW^o4Xww zJt$2&C!KHTg~yx`6I7*|u}znQc`&`vVmwCN-BVt@IOoczclE<#wdMEoRV-;Gc8i`K z3Bk8y*;l&4|8s{%Z=yqnH96>zYYfqUsS--slTLo1+tNI=bnHlHBZbM6u5cmbs;!91ToLZyLeNn!Fz64JliJLS!1@YRybo ztEXX|S=Snghv82%K(OS1d8b`)Kzi5U92dUIabM9ii;r1{=I_5T_!uunnym5QZg3qU zq;PDC2M<2flL^9OVqa5&Ux8W(g#YRr_OVS*?WzvLr6ObJkx6p9Z_bwB7(y)~Fmog9>`Bf3=2#SOL4G*G)=v$=iti~0?T~TESbB4yN zpUcKPZ-T@`34781EvhZL%JZm^!qgBxlSk*5Qn6f7MtV{0`m`M_rbmcL)xLcQ+R&O? zZQ)pAu;N{Wb%6x!73@LcfX~^Zj!nL)VaThjYA;p3^kb{Y9YV3WIdL=+t+rYFQm1T# zUwNxaHVUM{9{Q zzS9}`){T41Yy|HJb^@+p9Q)l3AQTmipE2PqyHu}jf|k+)J;S-L+`o_G*#4uKg~leN%4oV9 zzj%LmY=2Vo7HTS$LHkc7(*y3!sS@#&fBg{0!ExiRc%40Z$9CkD1!CH-lFToc@UsLm zS7wRA#ShMcnW*?cGANz9^_JpAt7eYb0}>7dKQZ#TBT~N?F^sAP=&KehSOSnNF{LyG z&_#XjK*fBX?&9@*HT)Cd&aZd%P^n^_ELh>!GfefBc$UFHN$3t4%!< zQEwfP4St&4BQ(Dl1X&2UFqXTywmPl)y49~W-tVKNC>LH=S)KN|F&aH0fVUdWV<1BV zrQDi}#&^qY;w$ZExuJ)fA~#}AzGNKnnT%qFSM6qK8QPznjr+Jz+$_I>%#-;?*cIkU z2sCRSeZMDY zEzz|zNHjQ^8f&67!m&&VgwsO*WJl@rHc?XKDiOUAQeV%RwDd!ATpSu_En5!dGO?Mo zE9**IAd87PO<*p#9f8ChUi0l6!wI5n1nl84ZBvh#L?(( zgDm6p9@xXkLZhx|?>Z+t@+tTFVN&k3E07!Kl1DX*uFYK5D4+j6L$H_})1FE`G7svc z*{HB<_5B#2K0mz)ePjGn;||lt>To_-u%FJ?|6t@Y>Lh^H^pyBKr*W{2e_W2<8vQ zjT+zc4PZd)Y}cooeyH^eXv_3AWp&faxMGm)6^k2<0A0qya7Z`txR%-v_nK9;4~(XO ztQ#Wsh0UVCXAfk7>&U-v5c(QU!RNYb$V?&1@8f>D&@sI4fS{7A-eLCnfyIyDW!C>( z(0vPW2Quz08A^tLL#f!8$i`*)cKq{4j;eVB?ET#tVygG{Ujzs8_*?}+IYaTtuZb&m?{xuR{{wwj)(pL#|LND*B+CmKXPJBNl#@_v{TW(_C4}C9at`hSZ}o4l zWhm|1Co=hg94ot0Pt5r_7>-UQMK|1$vW5Q5;_vTE2&7B8!4vY-Vhu^5h{8jasvlTRvp)WAwip z{YN}TLwYBx(?xk5rrq6RNX3E~?+rmXjVWL-bMkrdqw~58<*uxu=L$RSLM%#$Gk0vH zK7<2#9Wfv0Hk(pHMajHIGBB_>uOk$j14IQyaltJbc5rO^JgbSk|IpSwfm=pUJM zBm<`@H}vGzOm-7IU(R^jvXTR%8z-e9+k?vj@-oTw!;fN(`R&XbknXwy_FRkQmc3<=p6@3$g2xs|%X=Jz7w19ea~?+!o@I^~pElA7RjIfCnwr4~UReM3g1lwv z?EKaMGC3HIY$ZTqr1u_BD#M!iH$(uSl2*hDMMYeedar_J2%ma<(;08 z)(5X}Je<4nFuP4O8M!&#rJEh5Qke7&FJP6`e-p*Y*MKoRCWznhX|>2NI4pLvf5%~1^F`yxt@in^6iYy4 zK(=beWHd5I0Dxdq;J4B09nx>kn8P1{DM|jXK3-AWzFaAI-2pl6sSdav(D(7e-%d=k7(ni*dW%_@5x_VSR z-JVxUpI%CFqm9?lezTnGw0*61rAWjV{=Kdul?O%-33a+vf)omOC?Z&EdUQ1LnhI;9 z^76a%+IZNU*V+-k6-+=M_b?FtZ^4YT!!x1~pV4Tnz!O1I*@_se3V8IyE}Bi6(B>(#6)BZ=c)IyeW)wJXywTbLBM$J2$SwB(@hF zCy^yu7Mdm!%e>As)&4$P;i+c*S}enjT1Ggo#n$ttIe7Q>yP0v*%Q=^Mm9+7Q5S|BA5EO1=bYiNl13d+!dMNLZIF_$nQ{uzCM82+s zrV$(L$Ffm<`4o<}Os#+&gL*okcbM1J2ho|H9fd5(x09ZykXyM|GBPiPwx^gmfOZDu ziXTwiRbAHCliz-&w9No_f%>4p5aSwU`J;4+K8>4LL0{qCx!DN{_36Lz{T>Yj=nQ-2%(4` z+ort+6Tk2_X27u0&n^25LxAO5XDxvL?Lew%_#hF2;=VcGSYSwP`1`W!BoTML!NtqB zkv@-|X%e`96#yf2RVSZ*VN1nZBwc=oxD~i(H}`V~P-TQSXP&nY8Z15w8dTz({f%rX z>PS{m9N7Bk8b|vLh*J9%7T!4QI~Wo8mZu=mY5SkQaCjQ<1fKy#m-CrD8c@I9>6H4w zU88gQMX4KC&qW_y&f=8-8UhP@5$^dHa)!yonM_}yg}Fu-i`40=OXnDxN0?8x{TZ~I zuh!QG(kZl^#$Il<2=%08vQA#qUVP%j8WN@p4a$P}HZg zX-)-{vP)FB*!gvMzpUZL0v{nl-B14*rI2Jm7X9l5ljryc`RjeZ)z^PWYCdcK+jguD zI=$H3+;qP_D|}LFa;IUVeXP|yuhbQAY3q^^vNW6J zuI$B>pMe5|e=yx%1<^2L^p6CF$yhLK{vhEmY6GXLwSQETIJpnEE@t+?+%7^G$H5g> z%zUpR*4$KA2I|3ci>%?1oM(YrHfJ&QPEJ5-PQ zDwsB#gw->TZzP|s!W`kIC+4S0V|?LqyMrv?cBJgDfJ_Rvs3D8}5$~6duJ`Uf3j?Qo zP2ysS(d_CK7|);IohfO1MVA2Pnn>f>yol?G5X(nT zeHo17zJ@mYH8YVM%61(!ksZlSHL7xT_?-`Eh3D21t%qo1t%mbUJc;}XPZCPqDvCgB zH~oPD3Wec`4w4@f__w#8QpaDLep=KEt$|8qMUxM;wZ-uPfL!#|hLZK)*@z66vh^JF ztT%jiAozXNLK;H#V~KQGm;W?o`= zm8#u7f}aVV6-F{vY5jUeC*pL2?aiiYZ>WN<1o7yURMU_*BvH8t{%S)Q*Y=RH(L#7g zuj~&B{_;j0kik#{ipCSC6D~$=-Nx$NWJFgP8b`wpnunz>20qHy3vH%(bq;u)_{?qz zH=QK5QRzM>B~hv?CM@LdUnIo!UJ})7{NW(_Y}H#=!sRpoZ;?&>acv`7feQW)wbP-d`3OVRLTA^m z-a3@JhHOtIVH&uYJA`dw&N{9lXGN&|%28WomR1FbgHxS4NtGP6p6OD!{Q0oOz9kb) zP4 zwBE|ER4Hhlsf6n^f7lVB5rGFF*Go*C9@NLW@oHYJi=^eV4DAfSHaFPsQT~enpxIM5 zAPC|C_5Q8REpM~H(zm9HB506XkE0mAKo|h@*I#WSBrO8p)*CFG`e_Aa?doxGzhzCa zRzV(JV#>CH4GntcS%(|8E#mlP2#qTiENn3j0IRdvOjhn3H`*EQS(d}vc402_C9NV= zvjld_Ko30*vFh>_N4bJ0-~MxaboQx+I6RymId?TrxkS?J;Q2S9+ReU0o+c$#U9hWKN16;K2L%O>~^#CTOI!Ql5sE?y0+{CV1X46#4u{L@? z+eH2gApAl%m|Do_jZR%jybCbfH)M`LBMVTr+>sbkxN0j0l4SJN$3Bb+>MTaeo!+Iz zz`b_@mv7h*wJ5LKm^Z)$Qm|}^!CPWCU%Jfc`j5psHyuj%#U{4gy*jRktK_b&gqU5L zZEKTPSyo({d=ciF*8MU(M5!_zgeR@9?w|8g_BlnWxCPHLQ}zbT?G7vHFF{W+T0o9w~?rUuk814cN1o4!9Y`x(fiG4Oig{Q#<$h8l0{GIkOUfq|Xs z^fyLtXHJDFEo5C>-6(Y`HL32KaB+Sdqsi+OaAf3G4i()y>t%wNs)vzZj3-TFsZNef z&Y&~Sx3<^zG<)egZ2ghPUkTZpCOjvCT80wfY7_j3zon?AS@(=u4?I~bKO@^p16O|- zeQ_)FOX^K8-cixaGh&?ExW(=a)BT_+5^?p!V-Nk*8;7yF@R#d|itcHgd#qv8!$*Jc$6Gv)C=ftZ`?;^uRKIibb3z|;GY8)w365o2*+)Gs$f?H1!~&yB+Hg+5%MlHJ zcy=I7e8*m#MvdP-v0TW+CP{@KYzi^`b%X2e?S}$YgX+5P|R-+9aprp0jQSpaxIaLe~hJz0gJ{YSj`yisn~h$Ew+_S;H7 z(nI^yal$Pgu!Oton^k>rQOzGI__&T_)DTNNvLF`}n7n;dCkD6iulB(8IZs#=AMQ|h z#yW=Q?g?1C*)hp(aP=zwI*t(>qS1d7Ys@o=sJP5z80PXiZ{U{N&5kbUp&zwD3II&1 zUr5;i*(z+v7fV86MQ3@Yl>SyGG~IEROkcVM7_yPpkH^+ag~HyX&Nc&7NhUq>ri;vU zP!L}bpUj4nT#%FZ!!xw*?qDD*A$#Czn?iYhd0`=Cl>mv}`8dfepcGI`5Qz^GhJG|6 zY7?tm=!C0X=>txKt$FVt&(&Nge0}g8QI(mXnQTwvNfTygzHar^15NV9eF=NL!s%<+csn61nO7KFvDD z3d}}Io=BdNQJoysz299v@68%Z@sFf&Y5kbvUne}lW@n{0j`u(>WBkkpc&HoLJ zt-Sl!l6ZffMebmdangoPf(zQR2ctS9~9!`{e;a2*hdB~ zA5|>6!i1E?D0ehwd-b?qC1&_DP@IT_~md^-Ui#pjr_z(pZ9Gy?GDtv(dgrFS=S4#nn<3;5hKr^_aK~ae8iYrhj_SS z{B!57O!yrm_GI5cJp zxrV~?1sUl3cFur&5eF0@(PSNQyGqd1a3?DKrE65vIP(6jqQkdf3i)PT^9U6rL!J~w z(QU_*6gvC8-Con$Y7O+SYk6|+xJA&V~vVMnw z4}EQ6i5B1~KQb{x)w!TZWrI3$kT-6Hr+N-Ov_JpJ;tYdNgQIv%0g*Pt2@*D7&e1q( z2DNVCLvglL3;GjS2=J(r9%o!fCP#l4p5i&t(OUvHeYy*|djerLf7&Lx?|auAIw_p{ zvd8fDu4Xq)*NNg{=PerKsA~tvgD%i*$4^;$n1Qi~?s5)VP0xI%lD4S{Om!@F`*gsO za!}TXQ1sFm>tw`Ac>H4bRHD4O42}nt2C2B()bB)0;lVAMw}7mfbZWM1#~gpF6O@j< z%VBG*S(NHjH9qE1y-Ox8`7%Vv5a~ltBdw`%dFrgS#SF`I3WMQ*{DmbCG!7(*&-q*T zuMg0!;Yq$Gv~i_jcyGsznk%MK#+lLsZK&072PU?+Na`;jfu*|g^g_>a~(mf%g zuf=YrnaA1{?)g-GlVLXPt96Oqu4xc&yp#p##R_>uEfkq#nbk|>=ik#)XD+IuLHE={q9vT+x1hY^N+Rmx$D+1rq z9vLbmOp8sEo#`Ka&+_;{_ty9=S_|r2bdBRNev+#@<(!emy&6XK$)$l@_LHN>+Rt;c z{TEPXxT-r%IC*TLz>$ZRR*d|@SA~o9xm5J)XQRukhdFxBX&)}kphRyoU+zesX9=R< z4y)h*U*%V_Xq6^i2&&YM!B>&;uRp16&D5ysINvqE`ZZs8{>0|#3*ds3k^LPq60)M$ zDwh(z*S zfoU^RA{40aaT*@W{Wx9Ow&k_|omy%x9z!C&2Tiur&piwl!m*!AW308f^t$!YY#ftK z<>4Ad{u(@C7ZW;id1i$SW5&~Nw40n1pAqWxLOj}w>JRk z=YIP@umj&+g^YPJ?OT=slk|OumIy8wUc28eJyq)t&@o==!wk@DN-nDso+^g#;E>3v^ zr-PclI~r^UR`zpZZ`3DdS9>QVJkwC`8m~o06`q1z}t=0i!}4DSJ2VBn}OG| zkjsT}p?Wv}HS2PhHx}_J=7o4c*IITZV$L~-jX7ZR*cAi*oCbb?AZT{&X0$TB5!>}hs9@dFkNUQD!lrp-VXIwBrXfG zMIn0mce1})0@DT&-{GR146FIb7Ed{0Q6Bmw^W<)C=#U?V+owxLNiMvxFwbMiH6Vs; zD|2n<`x5x?{)g7D#g=RKhn_qY)YoRq+Q*f`fb;02D%!vAKq(q&}3BY<;zVz_?q&aWj7>Yxpf>vTe!*C^?+8dL4RW#nvE=>m~dF} z+lThU2iB(U29a4=U-yEh;f00A%VmfIZtHJc{A%hx+cbMW)^xucPF(E1o`Ij^iwm_6 z(DXqYG!(Bj1wOn)LuXDrVoHpcQj=ny6JvMM?>1X z0)_`=t@;1%$y1aAy|W008%a0=L{@ z>P+n28L={YkNS41rYS_Sj$gwIrBercCsOn?&TJsWAl9ksz`OXYXv}DTmip{x`ybBP z_h70Dv^}C*E zM<#^RU0fhV*@tL@>0Y%t#Jy|yN;Y6F3&QJN)3Cgpu|NEF1bamE2UZDX=oo^Inl4B5 zXd-_T&!)47>V+Ms8Wna8ElmBiyVI^nkN)0}*?(9bC0hkb9aH|EDuqjhQ1iR~O8W8# zpl@Uj;c(IsF+JhKYr}aJa^7rp&PALi>!}-p`du`Gn>AiEcDzRpjel&OG;m6E zP*CN*UV7==%sp%BZgrcW0%@e|c_henH$C<>pXUzNL_Wphzcq&SLhJ?4bRmQ3BiCw+ zlDitb9=2v&p+&}YFxf#tU{X35^348vTJn~N#mH)hXcph8ao7c1`h3A{S!8#BWh%1D zQYJyJ=iXtko$W3U^^mR!*V_qK>p3@@@{+8c_=vp4^{KCQT)G@Xc`HW_^1{j7sl^8tPP;JolVVYcghYGb=Pn=m2Pkq+?!liVxZ)c)B zc0uNT5>WS6!rPsOMoUM`@!EUW%+#un86!ahzfUdaNo3eN1s-`_d`?s*wv7SafN$YT zx1$ZYPw1X}E8rQO!IbNx`#w1EJ>jwv_GBvxx;?8B2mF4Mh5u1;1l_x1EAK!z%8*@>}0bmQxsdOCNLiRws?;#w(id zMY2v!51DBclP2xS>V;5sD`Pt&z$<6rUAzcYm&pjKqym8pxA6io`dqv4O z5PQfOHzu17qnEMgdZPs&1sox$8XL$`YQeIZt1jYH1WP24+lm|~UY6y5+Pdy;veSL! z5Xs5(p1!{&j7uB%qHmSaHmWev)zD#Ut9_pAz_GeN{K_m0$aNz+b8{%HYANkk`EwF# zgzE$Q(!hykUQ5UH;ri& zR}n@?{3TO}Atn{h938zLNhagpLy;=I&rB4oh^HT@KDxZ{PRV- z%TUWjBhfkCK82&{6UZAs`@a~)$FhtINFeA(=Q1s)P4y=K_nxm4oQADE`^p5R2;{9= zncFqB8?2r!`e=v8O~Wow6K0eQi?uWw`U5Y9nRPbY{a%dv%$k2>%vKi+gc%s^A>y%! z=5+dci*{y5=E`Y-rQLB+8nDP%`g8yroQg1*I)@N@M{z+@=pI{5%#STP!)-O*A0k|-k1H?3T0uqqqXsvhiio0cH;1i${q=Xp+|+& zS9JsHP0=&@XZHcQ4b4^dty-xCtJucXwpp%c0^hfC`TGet0;rqz_X0Fu) zi)O^rmzznOZHUP-5KZv{^f;Kg5mh`BN*ay2yo~jyVl?5okEp(go zj>;&kPDJ?HL*kpL`@%5^QI%g$k>?^8>IBo<*|8p!^}O+K8_UxL*FQ#MNBy8~iOVRF zq0Z)iDgtI-O!)LR4z*}r~qzkv<=n7vj2GY1Wo^b_?Me`9WDZh87yQsta@mxBr$sxgO(a7K8N+M=6z z_FE{%P~n0_XN$Ud>q6t{i*I`Fd6`EV4H%3XPYss#BcbtT6$_1Sqzao#fsJ%N9PjBR zdQIkNF*7Kz`Z}f~gx=i;ZlWQQAqfz;Pb7YZXlQq7%ogari!q77x%1gAvSl zZ9MwAXw?LHzNxUODqru3LTl%1*+$inEt6NCvwL%1nDi&EfeVO}-5(FfZK1fu$1mKb z1q|32Ks>vSW)uR3vCiwzH^I&aZIq>{{ccy^c#F&Wm4ZzJ!5WQ(+W2^fj^dM^9 z^H23Vg9o;jiHvj;NXL!2*s+c-Jh2!~2qBMic%O{%YWCLpt(z&;|3gxIeP7Ra=V;X= ztIgdL$;G)ciW7d2;Sr(7zI2Wa7_>Q}b1tl2jJXVvjv|g)M(CT@_MkcS*rI+8gh_`v zInzoKG&*@P8RJ|`0chFEl5G#*vGyTn%ddo3W@|#9eHn>=XC>*uKi^RjGWJrSMf&Us zB=sf66rKlp!@N8pM{we^kgs=Z);Y2ESwXBIWC^6*i^?N(5bJ}lQ6$s@6KEN4jB zj=}Nk?|QSZfdIDsW)jNc9>&q`pdUIHF6lHWv zJ?Wi}YJX8gX|Vd}r(?wQ77P3&jpLq0Ifo4OF!W*qv0zmj@0Eka6W|h%xnb)iE|Iw= z5b_Sr%vkzZ+3C5X*P0D2Tq9(b*nY4WZMp7ElZ-h%7$^aXdp>?S1_Iz)_k;7$L_R-8 zA@+MjRiL1kxJPnnmT@W5WG>6pqp;qWSpv~+ik4v*+%t_|O>Co~RoDp0(?h-%B}s4q zvFzRIO_i_i31>Xrw=*&fSqs=7^*Mho-11H$T2TQGo2M~PG7PB&4iWP>QlnqxCQL$a zonyjoR?$*T@O47!uyteqUPjBWUpcUud_j_wr=6sMY^pTGp%=U8a}%{sY@B5oOO{cr zRolXzV7ZoSM(2;tEH*HRSYaN?GqXu`qZ*mV6V3N#iQ=Wb)RvAbvo}`onDoI zDr7Ba>A7Z`T`GA*6G;Wecc;gk$g4yU4Q=+m>*(|b3r>lCC~X`_YzAjvMiqwe0f|O^ zkwn$Lw_DtVRxRKF z1b5)AAb~a>t7Zyq)l!=zyVq*%9qP_}BBUSG!6-&9L^@*}pgv+$bTPNFRiP!hUhLD; znYN13DxU&&4qXYf2ma3rN?!mAFm#k0a`?ytlzNjp56#PdxxUAwg4C~}({g2cZ6)aN zguCoT9z=&uDOR(W`dP+pPDuI*CsiAg4}mti-s}r$(s#YheyhAxZi>h7mjNVjjtyt! zEP+?z0RI{2t0JXZRd*>}9r9cI)<`FR6V;gsDXVnsn`72lcUPYNlKR{u4Wbm%73ju1 z$7Z$GZN2gcNN}xJYLWKy6ABd{_*ZUu_bEC>aX1CURSk|s+Os;D#L($W9glWnomDGI zilV0VG`E2mH+9xyEFnbkdlaQ%Zl8O+8qPYI`8{*_iYn5eVy=p1WYV+8yp7t`kZ8^?$2RJt_4@6K=?iZl`S4L@{2x@?91?i6LZ zrB_J>sg;t{oUh@28Wb)Sy*`4ubr|ia_VW#Ka_p<10lAt7gv#%fzd`9-Wvl}Xf38rj zaJ%Vl(8c$)=8wiV=Yl13al1BM!B9 zK(!4$#OUmNDFWtIP6S`WhOevcoT$<)qBD8Jr`2B-{yLWCKPO7zsQWWvN4w8Q+*Y#x1u|*!N@oe!IM*-j<3r5H0!p9%M!C*8s)3Qy0>z|D zA~gHepHb&?0Q*TuAVg|I^TBSQUhMN>A48N*a}#j$z@K_M(XnoyLAQ6Fsh<2+l7n#Z zqxRd=eUaq2v0A626xoXpTn<8wclU_J`KXXY5QkA!8;zCKYCXo}k5fXdTb@Ww}*u`Yhc#X(lZo}(1|9HOf$D$}PI~o%6 zfJOtegIDEO1$`d$6aH~FfP6TMct8kdW|5RqBvfyAWFveZF`Q7q)oXI7w%pkbFc|od zuHPqmD+&wtL{PkKSCVxv5JLS*jDfU=bVkQYrT&^O+dv?)JNdoqRy{xH>mjibt+3X( z9ywOuvfmo9^2Pz9BL3sRozz{6T2Is0Umi#v6~6q&`nwBy#{gy*Md5ShHd~cH=B!>! z`zX~ujCTc1y?j42%Z2Gn!Q%C>LnU^_!1~h<%4rfB29zZYzTwZ0@k!fQJB1)3d2@Pc zYcqQ9FSyBS3EwA@?7Ai}0o6gy)}965R!oc(*4s4YqiMbEa6;uxY7F~wg`$hhNUcuA zlhIA*WXM(^0)s%-a~p3Fb|9bUX?$ayy|`fd{?45s`F+CsV3o-IG%WX}Z=42fco&)3 z7Y;Z$n=M}0#f^QFs4*z-sa7L|#=ji06f2n?)0Y+~d{|*+IZu&%VBt_%H$}IFfW!F8 zHc_PHfk%DT?MIs`w5G!g(jG?Iro*9(Uw%ctYam&q{j&DeGP(sb6GvZPJK`|*CHlAl zX}{znG2BH;qum`TY&_8)Rd&g{pLma;JEP=2}u58Q-<=j*WBVD)m2V{*MXbr=V=<(x)tiNcxs zz7XRbT%stN<|h94ygQ~a-4KoWvPj(if_bJKX2OR^1r)96sWFQks!HDH1n|^mi==~l zSO}qf9m-@}`Wb)LIx{HngJO6Ucr{I4Ws&FU7rlj&udI`MaV1i}2QmVT)j6$rJt(kA z`_BV!8I=$Rq7cnsg#lbej6sc}@r^>{;mthi{R!+fH+=IjN2IE^RoGfebPF!3@hz)P z9tEkhuLRf_??3Y%?cM!>Hjln@=a_d7#P&!-86;;|E|0LPBN^FX{}($cXxK&ehH3nT z`8==m^v6bWC@br*9OKDeA^4F&zr3)rLYR3t=HePTBloPp{7CBF?>1Yw3fr!@@5E7H z-q+@~6jbHXTouwMac#$QmS9Ue{HE#kufsI;kWb6+oA&d@Ng+whygo7igZ49UsRB~$ zY}W~|1fx7vdR(k$fHev*nxuc-}r#dlrV|#G&fg=vC`Mg@=_M1O(l9*TXI`7RP=^4rv zj+3f$?D9X1jQ9aCHL<2ZA&UJlKS-KeyjSDiU3Q*=b6~0ZtYHw5EOFbGRA=5NFr&_D zt)pH+bLr`ce0nv2w~9GR$CF*ZJ|w%- z!>iYp2SMzZ5{`}C>}h0?FwdKybRLFj@mo2+&+tPN&k;%96Z;wvvon2~(s44Hbw7IK zRYRLL_NFhAytY^cHV&pJYpq65zjNt~>OYUn@d4Ur8VaQ;C}L5~k_p5J`rGlXK@7$~ppda#&Ibz?H*l>nA8E6BPm>~nQx4Es&* z3wa$tDY7076Q;)u0X6Ifmr^V^r-;dBPcp9d(ELUXm(^pkD*K85ov8F5xwk2kAzesI z1JD=~E?1B^{IH5!zq>|nR|o){VZX{4cd_|&;b1!7nTF65{}hpFE-RyR8lPN9vU5cR zBRhGFx(B+c6{)u^>*)SIZQ?-u`dib0 zI5(b~R6L&_;>ml=t1F~-yW&G4&@fHm8kd@Uas%xEd7^Ah$hz+dgnf6QzlZwV9>$3 z$gC4hbo$S+a+!FOHw9siY*p09WI@Qp#y{78>{~;kmv>`tPdHi-;;x*u-WjhZNhK{! zr~2RG>ZJI@E`LZ9Ef^8AILd7PBErKSGj>v<_c|@;6cqyYciF_*E!uky&Ia&wNZe|; zfF=V?VaVhBm>rlw2T9*?tQ*K*Gvxx#Z!33Nu#X$_)dnxd`j%V_^{*5y(h|dh=E89= zLiYYlYwqGirMjGW1)9ui<>2 zS$u9oz|gBN0?WjukhgHb@X;ZTlXlT3ccMp=Zva5SYExt`&2O^O%of)>q^W!#XZ;`# zk#2>#_Fv39O%Qm&YDl*K|Es$-{3>^M?6cot; zq2F~>Xwe~kcj7CKQSy8&i7In!mglb|c9cG3rN7N+oA*xDWqL(B}>O|}_W%6H#|lcxVMJiSqU02Unf>rQ!L#EAbl zl=d#@7Qj_Xwmz_{G^r<#y(X4@qSq3%WHzoB-R~byRZ z5{A&~`_==Tu>$ex>eFPxv*=SG5%PSp>Iirrq)F zSyjQuhNXXH{P4in9$qnJ$E<%v09D6FJtJDPzY!oa!2=qDgfzbcreQSCA6#; zI1ak8DU-}NW=LSA==g{AZ-NrHNx9437^e!>A%LxNe|?hk8~Qd_|3#$HG3!h!<-!uz zuFH5@4$H;CcvG*zHVOI_PlRBr6hrcG@5>3$Kp$zE=}eunQ{y5#pP zXxDJ*m3$DXpfC7|6#MAAo39urrPpHK4OG(=(Nsqg-JA-m!VMmq-MZ*ALcUzV51lxQ zdp@8t%D4Z;UU@%8Y%+f#$3!$h{S(M9BYJ@-W((2^tFqP1mf}mjs~f#=&pFM2n4mi0 z3?WCM*0O)i5>*rnPY}nR%fi5fH$kF1H?6a4F)Rwo(54kYHA9stMlF$nfO$UP#RcT3 zkIfin7YY`Wx$;)73kPLjWW`5kv>&8tm`7~1Q{WeO)i;+Xe1(k)L(b=2Min4zE;&tE zmcF)K<&f?Pr~$N{ode2!I6XLi^sMwC3n^kd$w|Te#n)?&T> zi}fXQjTT`3NsV*pdSrO|hYic-J#b4;P^_LhplBWKC?or33?^KOt$;};f;B)50L)x^ zY1*_OH}vYO>OE#bsEXwLlvQ*(l+5TC3qQ>~V61!!LGPdVXiJ2K|9-1^Qd)-wfK(FU zrQnqrSDSzs>cA3R3WSGdt3%D1!mTR=UOhLWRj~gwg2D7qKvHkgpW%BHQg`rpX(B)GRWL|6Wu^VQ?WCr_Lqfm1H%p3z$=voe_v58r zy9wK!{xH4>34cns`7)6|Bta$&Ghu5TG7LYtX{Ol`l4hsuoE%9i^-@5Gcv3J4vN!aO1 zDFow1dzly1iZFI`9}M>SLsq8Oph!Fx;eOX8p(o<0$$NgsuMXc7SGk{2XZMJ$2^JE~NMfq0I;fM+JPM zvUpK02eOELu2<7M?UXT^PX@wp>66$kFq}#^sToTH=0Q0qo9>Rvf3-0qGK@f{5` zIIMrqv?RUT5_;+_Q7`3>KHE|BO)0Nmnmgle-0Vaqv+;g<7}Qy)(+0F7gZ{+L`oA8T z8!0vm^?&c1_{P59@(TKvwBT7yh3+1I4(d8$wwd}`S*QKC1lsmlWmr8VDCX9Np9UT; zFQOOEdc@{g*2})8t+BF;FH8NTol$4?zQFR8XDG`Csdje~1h4$3=D5{YzpiC)(w>>g zsio2;>H@=?Qr#S6Pu!lQ?0;f80Cb8>p2a$VPd*)R%nu>Lhg>7tt zJ8pkc=l}Z}J|O#tX*L0BY;rPXl>3ajuU(xRo!e`|(&tc}*aWHn zCAvhgQXRG2(z?L**%BqPn!hJ8(}Uq(FKD#(_@&{2OHCT5P97-H$Pzb^Z19)WoaJ8v zMqqLp-DLnnLh_t#pW81X+;rf!y{~$}!)QNc)2NlP(`?XLL1Na#CS-r}60T1IKR*R9 zBi;Jg_qcjT<_!uQecp;ax&)BI;OXjf`mdP_uy?TM;@QnyQ@Y8t?v+9Bp3hcHe^bV~ zmrsQ!U7l}0==J&8()0!4KKN|yb`#>nRWCCI%Z_Uv80(RcSS{nSqT8XGQc&#k({2Yq z-v6sdW$cu`VM`N@F7dhMR6$J0*y4mI>SNw#ZofYb$^12fex>vJQU^b7Xmg;FgCk_m zmG0(!rVpvphhV+2GY=f-@EuAhB4sfM9weqOdUZ~xu#PoGiUOjll5L78Z4EP#^L?2P zszNZXX%kWJw`f)>q0pK_9j8s7gT}244FVdr%QQ@zaY-ilDa1g;-}3K{foDk9;ALav z3&xG@05e*^{32MaCohGuwc^@0J^Ikh7kgynR`$3)G;UorJ$YX}UGf{+FYiU->ki!4 zZe@7-Tu(k6H9ggDRkx<+*7sm+raeH_P$buGFZl~93B-D-GefEpRagFIJRZho_>yj0 zSULHSdiLkG&pf1CH1M2LksZyqy@tAz^tCs(TTe`%@y@Ix-JU6(^(F+3Z+I&gz-N{a z4@wwxhpG3H2N8)k(#DM_dJy&}W&B%w*VJZt>#QEvC!gu7rZ5R_+>Gxr{YufpU{7;F z!o%C$+rKS)<7}tdej#aFaD2380`-GjY-^lRxhdf~bm z1nTZ;S{5f(N9+u}>|*}OR+zErk_?-T6{rbX>+-PCvgvE*g-shqnho1m6kzXP4mK74 zwHVLE!;v;GO`nZDL^=*b`jo<$C@xyA_!a98TfJKBTc?(t1Q+%=M+7FOTe)L++|0VD zn2-(j-@H@4*pE#yocvrGyD5j&-DH0vU%5swt{S@h>bYiNq+0GMJ*=qjbbx>EWijoF z(9(IxjliMQ@R#(zbjiPsF~Nk|0p12^7dM97@^j|-9BUn2tN8;Fo%StZoEA0rjBz7J zVaLBfznG#X|9fljm#rZDC6sOiW>-X=SjQ_>6CBpPX6JVC{-hY(WiWQL{EhMQyiTBx z*~J&Hpp(C{(V5J{*e;$QPhmHbMpMpys@cByXQaX3xd+w?ZC8%MwKtW9*_mJYMdw<> z%wErMF#&_t9{C+_UG+Elu+;1O*v2f{--flK5ufB?P8V;fKL#BIH*cZKKGZSj0!PUe zlg8ey+E+Dx+%Z>`4-64$gWf~P^KVNE{SW_o0rK*dAJBAj)efvK2yV(&%bLdI0X>8{PvQb$NLV zJ&W6cF}J>O(?Qt0)CP>h?zr^8-yrN;Z!8}ig`L)Fx|>qX>WF`J0mXBTAB26G$h^x& z?aPK~ZI4%=;ZI5YXMdGayf8Lr9#a}HCRV^%LR%EfmG-{Vg-R9WD0d&+F26HqzP{Qr z&APL6BITPQM)KHKB2}fiIuQQul-`UF{q8t482Rakm*)_dt*L?;O_eH9Gp52jMUd^L)1%5LeEXB6RB`dfD%??+1@QMz97M13WYwL@OizF`L?r zgdVs?g2m@RdElHaf!6Mytm&~m*ED&dPE!hwphWOc#(9QPuALPq1t6g+4o5&ry-O#vbnxTPh%@hUc z-2^by9X>FWBy}}C1nf0HMF?f6~^))~h4EtJ-ME8kbOlOS`Pvzy?Lnb1ml zckyY$awCBWYBc<^)9Mb;+Q@e7$!royyEVP16N;ecgOqk?#-Qr;0#p)Nz&H)8p|KTg z8Y{w@1k8OiwN;;B`uK9nl!JpwES>eI;+&5YfoGC-?9cwfXY;wwZhNEvD43G5VfHb# z1EI-1D>Y4NmvpOUy#2aEb)oS$XCT}V{y?ETZvgbk4KsdKy_c^-+BJ$@l}*5uuD^v!w4ZTxCw0Ct6Y9LZATZ$vH+Gn;24)bHCfv2W z#zB)|OPdf1J0{7R>(?r1c%eq8YCz&NSwF*!zK+;UM@$0}C)!UV{BRQ0@eZsNI<}2c z%GakQVE@gFCC!bw^`7n1;zEcKdiWhR%YW9jJ`W!DsylcVlO^ifq4CyBzE2Njf7~x; zEod1T2W86i#-^qc9(-$SG9g{s(R^@W7lOTq3d-%hXV3T0>^Ob3{$vM7&PqNPO_rp@W$G$}7>V>*B^kxFh=DNp|!sF2x zq<{5uYD(krqH?f}eNZl5!`d9@n* zcij{bu5s0<>wYBc!7WTxbGTDkWv@H>E{NP+fMXo3hH)YN;P#FRUezzwk5Ng3oB_@* z5)pbtfm_ zcPREJL7ebc^1rM>F@Kzx&Ax{Jz*X>>f=chGcC3%mg#wTfHv$x6T4{nMftXpjo(!>g zKCma!mc@tUeQt5pUbSB=d^=$0{MyGGbu98BU%}d(^^!~HmQeBdPS?ITX14bnGna3G6RZ0%e+$0d5{fLgtfU!+yS{OL$JZcESgpprT>j@6qsard z9TrWZ>nrXc2>OJeLKEIc|9OE$wQWS;Zko5-z}zG!^f$j>!G zT!S7o>T|ikgYN;Vd4Ha?YVyW#|Y#VW``*kRx*hs7(d;U?W!wXx%T(F^H6!EM24M!Cn?dup%j z(*8=>#zeK~4j9`2x5)Y1rgTsO7dNqY3__uQYSgvZsg{FO=K@s#r&Tck{SmYntAPfQ zpxq>?*`B>+)vu|wHfof62tFieeV9N(ftvYDCCmv5K3SVJfC3Dbm$EE;!YGUINc`9CvD6 z2MSt}qo#>)5Z4b4C|4lSnn?91WA`~l+C(AZAyC}o`!}rYKp&Mr3mhsl6LmX4hL++s zS(m(g*P9VhaQ!lSx6kDwYpK&$)5gRQ?l>_v-Kxv~h)=nyP~A{hY5mnx*_XVWpktS1 zZQ|G--{=>Zj++udDfj|TNToi>Q3{3H0aY{_lv_7g%U~X{`0(xh`C660Zge88Do~24 z?^GEpPuWZPkn-u>uy_4xJm$<)IeuXw!A-71N&hg^L!iq4tU`nIwUL`mO(;R!#h4|hm2ST$JV^R+ zUc}5WmFbTR4uq8$CdwEaxzbuhN{=N~I)R)eWj3yE^&P>U8ixN&gjj`6zeinv zjc$NwM5XmVRvjfUt>0%HtG<{-xskca2q-}9bde@>4b4Efx=v1I^+BaPSHn8Ad`suF zb1_4pdi}f=g1Usn8yJA{s0Rsi+61BS1bB9^RJyF-_&NPl9TC0SrYZdP;88Y3h-{P2 zvjGl@Z>-ZPEcBYmm`ntz2*EC(??*VAm+2gy@fBu3WSueL?s1`ETEFjSj=Zv*&{pSi zZ_-dMXbNHNVb0)T?JW7Fr*6|TS!eNNcIy$ztF!hGT$#F))_?*OW5;22mRI+l*0aFO z(^3o)DU(?<==oRBN%}VWTL;;UA^kzI`)u@UdL)hF*6G*uj8k(@4I%PZ<;tsgEBUpK zbI}PUpP!BzyhE>jYn?`Cf0JIwnxTRr-rE@O4@}9MnGDlg z#-)NlofW!ac)IX6KFZTMxIXBQEH{H1fJMr2&aV`_;?AqtT&8AbCV{B9x$9D}v~dQU z6Vot z*1ho!q_PDQ{P&w<;B>X9EEwOxT|KB5&>Y-IhH*%rvv)^PKxeR3?QOFncrq*nUms2K z!j2 zuhWNx*$}&|;1Wk}*w0>roZNW;lOfK#@kEdeW}nSp0S-WH@Yw?Vtt?JV90V(-cH}#4hIggRneX6& zCMiK*On$ck>U-{rqD~49_Kxx3?z3D0_rVhALnwcz$ z9I?_7C*#RE>}EQ?=^dq;%Gm=Bo8omA9v#Zy>-2Eef(C$hc;ZlNFj9L00evDAt{<*S z)`Ue!NSyugIfF454@}r)YKVxB*4T|e76fYh@*T_DyXEkud@^odo`b6|VRVb=(#t`u zS8Y&VL0ADCKRG^I94bHs?k#tVJU2~ZVIBI%xRLcgtK@OR@JA(Md40c~tW6`AfffR- zT*ma^KMg#)P>(KINajMu3xaD-0WeB&MmY9wO zVrC38MLXXLCIT`p@?SDXKJi>0ugjG_z}?l{H)q0aX2>YM&H8XbTkCQ+nzyK(#2;pocB!#e(`yr`FUqWs!2we~oPkw_A3Lt1Q|A!yVZylDAA; zo6s+Q@6+i%#46^J{m6#48wkw35kilw$LQ+sWL-ACbyMUm0{+ez+K7AQEYpEpVpWuf zyrxq7Dep0iU;b~Z(uKoOr~gt_H)tJN#on27?pcroBmXgz`%sy{(Y+B3l40(FMri%s zUk8^x7x5Y#*Cp#16P8;C|9e&)CCmZ+F99u>8^c7OH=GY87*-dKq+|JwM)O;V9x;@Ztkg3?G-b<|Z%oAsV0h(Muvb`C2v;^w9l!k5yXKh1 zSJ=*!a03c9mCsPo?fj~+Ryv+>O(c2Oy)3T+e|2w^&gz^uftDD^&8UXc+O_I!(Lq`N z1+NeGz#+q%2@@T=8c|lM#K+^}@>|&t2!5IWg;c5Qn^8I5sCm!#w?&gbZsHZ()vGie zn{~zi56jbry4n>~O+L3`=-Q}pe$d4_9NeE?Pnu6@eF4q6{UENK(eYSP`MP+fy= z)|Y+0QS=>;(Y-ugv8hkXAKud{<-V!otEQG}gnTS=e}M)1aGCkysDmY3)Ei?!IzBw+ zE7W@q`}Z39viF zKVTEV?Dun~A(sd^rp9ndF;S48-S!6EsMHq<{!x}nL&t1Uvv7M3(xAMj@<6*h`9Qnx-HOJ124~eQt-zG}A0f0r--;_cX-tPt`2zPuB zf=L&O-c#1FNTI59(VuF-ElYYf0rMQBSC@~QF4!J?A{cy^K3H$&K&2946K zB0Iiu(n0MHb4cmPSX!v&6!P7goz&zCzw&H$iM#lKI6>%AUMX-vb*o>E-R zQ$WH)oV(FlS99+#<<8E_U;_0dIm*~hmJu=lB#9ltn?qg@ZidI{zb6j)r3>YZYFz9t zV3}HQrFSiGQvA@dS0=WlPa~Fjpy42uc4RLxS#ItZ|8=I`v#1cC%PkS;5%ks{-_J5D zJt?srCl&HWVMl~Ukq;wyF!`h6Z933*aqj$VRWA>$Cti)?QLmXPZjkA-M9GWGvWo3ANi+q zKf+TE{Kv7(8Bps$Ayitn@p@-vS{OJ;8#zJadFWdI|8N*vs>Y+2Weem8JN2wo)Qj8_ zOMoet2R{mtpZ?O)4}DGaRRj`{)+0T~x*{3xZ>@a97`UrSdfgu)WD95Y5!Bqr{nb&U zR~%L6%+zNU_;vTac_m}yhx;mCx(OU}>Da|@P5@7ln65XMGtefYOOw47c5FmbJiaDk zwR^iXAkk#4O{?h|=M=@MbreS^dpFpGXA9Cvrs|`F>xW2tBQ-R(q$S}x%DZ9^7xbwn z=VSwAwUQpCsAD$2hBD+4jJO)=UD@gLP0}zM(2VWDMWOOB`9525!)ueLO5DZD{?>pW zpx;HO^E+7TjB*7vh!Ork51D`8HKXyP>U|34Ks3;Xwx_}jftHuw)5ML;zp)E>>D_zx zWVPiNKz%<1Tzqt!+c!>*&>De-GLoPm){#HZ&s|Uj@EV-5ok1OKCgL$~BD{3;IC`Zy zb+?QmTP;_eanqyOONOICy^8rnXOJjAjqBy*!)H-NQ2acW!8CSMtspxE#haBH=ak-Z z$^rKa%S&;d*Pu6ZoP*U`)rE=xQGJ!B+b-9B*pvpVhcFQw+w}kP>6Rm>ly2mI#-lFv z8-OPQK-&)Fe2MAL9_HsJI%cta_!${jc1s}kAbtS+$(;u_DFagDRhP)b>Qmu0IwTr7 z9K4WSbRxI8gdor1Itw#RE57zO!R%dww_nO61#da@fONa9;`nV=v3ydiQ4TJbR3G2b z2$u(ruPC>EHhd@S8VSK)k8-523DC+I+9gqa> z*aW6^SW#QyJIT^pb*%{c7&G#A;zLCr0WY;)f{V9eC)V}rk}s7a0r-^(!G6Jjf;Z$3 zvlRkrL;3kxQJ(Kz}S&hAX8CU{+y$oop?7QFFV#Xg<-~`oOT+kZta*!{+)o~pnxrn?9?B9TmmK`L-mjrKNB<`st zg=52ec{A|(h)^Ii1#XRN8!~Bes6L|W>FbxbYx(k1Q>elEE{t@~XNNFd-ZT`Or<9Qm zG>KxhvTcHfb9PQezm{_Kl0zIi*16nTSgD9Yj?0>eQ%WxGNW>?b9FnuEt9ncW!xMI0 zYz3)8Z4SPvk4@nneWx4=>lebwz%A0u|4Z`sUFxd&H66vRdyqvJ?9CC#z<%);TYs=% z8+BFm?iBEDm-u1V+Ot{+I~~x6Bh2NdV;bdP>=~Gwy_|&{s5M~BhIjc|ckPQWWmQdy z@>Mhs1I)K-f+tzOxZ=Kio9b2d6eUgl&=^v&TY0zkhgO!fJBmfH_ z2o*_@Rr&2R9jukA!LEjPnN*9$G`%Rk&Ira{tdf~C)(jPTDCqcAQH2ftN>;nymI8LM zVCLydEVB1vUDkx&!5PBZ5$#)-duo`Ya_u0j$V@7x50eCu_pIK|?ckk%)Riyh$8S-L zjv>c`FBJ7k%TQF-!xBVhkTG%RDK-Cok9MtbgZ$E&;>7S(=hU>VnEeNkLNK z%dRPnx;;VqS?VSWs~k_fGQ@Y!zw4Fcxu`$UPO18<_amXF8lJGh%o%h~(kAZilmwG( zp^DZ*s1I&GHW3hAi0$g7*||ggJfb?xI(~NW8u5U33h^|Qg7>a;{z9i5InLC$tbU_z z1;IP|P5&k^88CWYmNu>>Rbxs0Vh&2rht3cMTrJprqh)HqO)?Wp(U)jx+*E*lw1h58 zLX{&2hw;IOzcsjqi*?XF98+h>9@==zgDop%yBSND0*)IW;>^(#^*UZs41^<3Bk$Ao zb{^LG3LFhhb#Yhls(Vm%fQSD`!xo+Se30#KAi0O1Z~z3>*`BA=kAR?Z&?GJ??OYUQInw1;7TC*+{ZrOul*bRmDWH3sS{P=yq#uQR-%8@ zNPHN(!E=}#)kac=U27_m9yySl_iclVK|n@}TU|>=*@ecZ(x(e9sy|ucMmdm={_CLG zSHeM`)ZdP$@zoYZTkI9|$@b2*5hmY6@{U?<*~P)X#ZMK`^>xl#*y`^3HVxAH?l{>U z$*(0OC3u=;%8tOgiWHaAmVv*m_BXmpdR3tZ8U?)CEgAyrezImRP*9#OL1PiqkexGf z*kRfM$>1nvj8AZt!SoO^Ax-S))}YO^u?5DTho$xAECX%UJPPkg?!L7fEm^lN@$p z%=8?O%=)4auOB}4c-j*OEB#dLR3M8JA_cEvmLyK*xAtf*FT@hBZB)woxKr0XfW>`N zW)$NoO)UIE^KGQ~q@c~$(iSRc{riXDC;6X)MG3(S_InK94EWG23`c#y1MuYM9+Wg&z zq>W;o>~#}X$Qyfg79$Ueh^w3H|Gs7HD^F(Sn#iDsrCKJBOiHNWYP?_IDGBkkIkv$J zwIrwjfDpW`!D?Haxl9XRLOUP5;BO)w6P%{D<70uJ&VhQo|fFBbuzXHU8slagB64LAV2Tl|TSl zbg7uh0F~g6;$ApbG9mcO&-=!jtH#K72MlXV5~>^C_NDBLlk$ns&UlYJ=MfmW30H17 zH^^SosR#&hT<%6P1Fb)p~b1-S}mR;Za$?i1gXP2}pZpz63o zile)(Sl6!q8$UVDsL3akPhpO6sAFg0rQOI&>BJG+K{Qffpg@#hE9!X|61p;6C@rqf zA&nw9YK^v;WdMD0aCdoR2y+t3=NB;YVI-TW&7gZ{r#IRW2_*kchLZwEuR?15RH%gi z1LVtzDp>}dy}N$mj_#tGdvS?K^bSK77nK(Vn&+6P9;%(jO`J4!m z86<+q12YU3g?QX}Wr4~%wZqGt%a+141cvjb*Cr8!bod5XGdpYMB&pxuZS#`mY9H=^K0B;6ZBe=@`D z=x@qFyUcVQCwG5n&r64odQNz_eGGwvqcC3o?)tbDD{`*}vp_gU|IJTyPEJnRo3#I+!|xZZAa3qkPi5`i%pN|Ml&bBS-cj&~ zCTN75Q_;ReLWsE!I^1)WZOVvk=%vdOLtLq?c0XcH2w8+mJbC*(rlH~W13%h7<^skW z>BK&&hcZ+}KF~JAk3V$)j7)LcK;sL(AOI~O4OWs$DiGFbiY&=hdwVJ&h{Ts=Lncl@(Pa{Hiy#9k#581^u)LS3V*gKTl zP-<>Q#*;Fdv*juokqoi~XTeg<8ne!#a+UzSUka9U60@$bXZ(9#-T?$6RLN9`Dj ziNTLrazN*+&(t12_q5dww@pZ&T6AprQ}1s5C)KO-JPKKWE70PMKIQbL`?Lb*9=*@v z55NjPytCxTjJ3PVs7-7lE1wlBQWM)kBI+mcGTFO57*{)5MNb5z~iPXc@ zZThPo!9`&c)sW|VI;>Dskbt?Rjo+r+*=g5a*D}vjqJH~xM2d`_X&&zp$srB|{pb)6 zdiCedF$8s&<^VNl4OHg(_xX|CuNUtn7p0B9eK7`1f}Wwrb*Oxl;B-M3cwxqURxuM} z#qXsV2!&F?#mvNAXb3WYwyZ6 zm-JxY7`tvsO#=A7F7SFu2z!m~N0Jy!RSI*!Rr{&(JRu2)x z{{FLS>o47_S4ejUPh^+$!S>}NT;|U=I{=1(I23An{*4!sioJFk_0>`LvZ#ja$L*|= z+z`O5pP$$5R^XWLBN;EIuC)VZ1lTM&gzv{fRS(uBg@J1t~`zz4&{4_6; zhgaS_sU_bHdHh}7UAyPwYp{NDRi@;vphtyuUcVXSDKxQWbw<9xYiYT7X}a}bE91`d zWB>WWrcrdMe*)q5!~9LIeKP2gVE=?I$<{q5z)HBMNR%jTmLL|uDx#Teuh83=I)xd- zRj6tC@J4i8H1LYvA|HNDw<}-Q>4%eyO6l&)J6(&Kx_JAsR{J}T1Ec9#??zKn6EV)Q ztI=4JcCkd;o(e)iX2AfYv$<6!_N1$Er{txjVI#6Vj|DFV)nT$(uPEgtRDO?foZ0=C zUyKcRM8j>;QzLLZ^m$ryvFs7ucAxg^V#B})RQyv#1v9&T_K=c+30vv`b!_?m%ph5E zOXXdOElp-3)dSm2lFX}BoH*nbCLq<9lrgpLh>fezv-kS5_+ zCGAw30p9X8?OB&~vKLi)PdGiju9f5J4PJl6c6I;rwZVbdv{^~VUFxSApc|i~I|*lw+)D}O+DMLV z3b;PaZ~ALNZ?|dL@J1rAy0Nbp+iB39MaHLV9?ElpPMbUpb~mxvdi{P^-?lB2-jeJ} z6U(fN*Ji2u-_Hb**d_lc%~tbq>)A3g0?#sx7VGt0P1>e1ZxI7>DIYST9xTb5`bTn zm+LlaFxa_SIz5opraG8!`?}Ls@pw7?d2hSz(Eri!wv=M_$b_47t~zzG=g_F`r{Y$L z+}yN&<-wql&UK`-&;{Q6^GT>hgX4qSw*lS)B&SD$l8D)0h)tlGL85U4Yj0kkx$y?0 zCvT86T#0R&tfW5G(??ss&Bwzxmlt3m<6!}lR9OF&Y8xvMzAFcNEoUiCI+LfT)2UKplwy0uw8ta+UqEpK zNh%r9Ys2~U$8%;T7vr5J4g4?5t7;}a^XnS&{hgF_D$PT@l<3(u&e^`G#e3tsxsRzN zs#$$)-f*_U~H??VHqZl$ux8{P`f_aG|f zR@`Y={4n+1Yecs)=011+AfV+cY}zbO!oc^^JW1XNrGs!*8cRs6*yz@(7uGW*HyVKlgZssRwyx?BQ(^FyK zI`?!_g>Giag#{a!cvQ9RN{AaVH~l}?3hCXZ=nUVOLx&0Co4t$W*r%3bAGT@RHC{eG zX4q~|?Ep`$8)e6iUc*>TvIhahrKY)lotCND+2oo(^vRhbyWEgR>Z9R9${seKE0al~ zubMZ*?T72xrAME;Z)0ie_AG=bq%`#ktnnVYuQu6>?N_Ugq&*v@(y!3wxLQBj3xeDE z!P6#x<`(1Z>oG596Up%8e_n}U3BZ~;*e2`2oxuDz3&|#rLy2=n6c$`Agnyq|Q$Y3J z-s3?KxTsHv>5n)K@!?+SJ7?$DRDfIFbjs{B+D%`Ws@P^?eR6e}yrn#S0An~#Gq!pO z5i31UrV(`u1{tmr#`Pvpf;0b1fL*=_ONkH;^ezf?3sI5&diFy}ydGHtHgztDc|nJc z?4#2|w`X>U0qVU>9N#CqFCq`bH~;OW$Q_lGPHOuS$4Vq2rXdo;wB$e@8YYe|2%)8+o~tw_No zUTR|a5v&T$|CnfT8WJQRpvJXJx(gDjLIZhlzmKMNdI)7c-+KEri>^g4(~4Rj1b_O4 zt=?=+R9+_vgx{yxW#*_#SBIrnd?!s^>fe6Ym~txDlEfjVIa-!`Z@W+iVme*~30GV; zQJq;qWhXTC23~Q;g{xrfqXP1knzj!93YK`wk<>gUGbDp4UU_jks9(GofmiJs9x@qf z$KCx=o+d{KdGovMtZR{P>=xH<1NrJNZv^3^T>iUIn4-Af$&aq~5xw%+MNG>0#q_bK z#;t-ru_wr@DlWBWNrbP^JUtv7enr{NLr74@{gk-hOWU6=gRcmK9pf6|_~02k$_2H6 zSH;Adh{Tevqhi9gVsyLmX?XLpDab*sDA~hb8G$d;ClepIcsgHmPxLM^(d#cI0BamiK$l_nmW{ zGk>@)W6#)oKV_};yYJ`OSq*;4JpCvRESLM(CLYlWJnmiXsiH9)sta}YSEOgTEMkZU z`&k;^5|bWU4+kg=A)Mr0{64%QsGU*93@Yb0X&tZUEi2Xw9z8>iV-?f4*-3esdjKghZF@< zh{FALF7Zc0z@9F9XhVBN+U6zppSgNTLpRm@Z^y7!**d(g!*E^4FjujA5kFQb@I0}I z!Z*?Vsr@~5-X^APmkW8!mWYz4!;Vt<(6vWtksNnriBI3Fj9{BmPCOQh1gtYvO~$be zHMSl_T%d`xiYk}xnPqxW3!qu3*7>Nj)#fn@^VdHm9j8`pp(Nb$mxa3z4wytUFZzPiWLE0U$7ETzf;I@$S*Ak-9&J?y$aZxD4Y!ksL)5?Vl@0c z3{uVnvs?0t&0()_4 zQ&AJ>%Sz+67-oW;g6fc2#oLDJ^+vV8Ka}>j=>qi;wKKCl3nShBdy!K?$ye-M&GnPh zTqGT-dmofMG6euCr?_akSX)vuHfgYC##xv&-rDjRC4H_`r-(RgpxfjDv7*VKC8?(F z(Se#5kdEXI4~?-HC$k9!+K;Ny>Mek)3Ez&_s8^bqoVPhl`chG59>p5B<1ZSIl|JM@ zwROYoGpsg;_%Zl?nL-TBfM>{0<=2e=Uq6ONz6^M9YqMnXhp1#6ybPA3HSjFE1HYx8 zvHfAV0V}@xthS!2K~%|()XutJI(E_3$sqZ7Jw~NgNPaS8UFKG6SmbIHBxDtnuCPSW5hjUN3gB=d(nAuPG)Nb?>h!m z-enIQR&w|*4G-NMtNJu9B@+_w?oveGb%Y8##GIWS&fJ7}rvC&zLYt+sF|ChiTeka6 zs7q zlVEMA93PhC{QfQVqs5&zI^56bw}VBRu}nu#Y`mIsk%7*p6+Js1(HW7TO&kM!au5~# zR1yrs5GEq%iGAe`Gu1eSt~~|61_(H|x<+a*BOrdMvt-7jqYBk_7D7tR+A-x((lP%L za_dEthOUC?*4jEA&k81g8&Z2#r<)hn$GuD;F7~^DjwJq!`X-je71#n2o!avW@BbHM zrziiKq6S(*CkwOORR9*qb}vH0{a#Q}$EfzZN3K42yj!*4maQFwQ(Zc%G5`bA&~|@A zaH|?bv&G;jV%1;^`EP8IgRG~e!o2q=;YlCBFy{U444+?wyj$OKv?5)mxYBg^lg7%+ z%* z@85nlvgNEKf|>N^46FEyGA)I5$|NU7-od za{h0XGnksmmmbRsm>L!cZ##>evw-pE?}Dms(g?TvpSdE%va=&)s;%aUq}kOh^rg~- zyRMN;Urt$`!t&7pHIV(dN)>F;e7EI37q*UO8*Xm+7GiIg>n(Pu#(_3u-}YJ@|4gg_ zQ=FE-x3yYBbic~LxIZf3@r8bjZBXCp`nMJ)uKGS-Qb-YAPrC*{AA$l!if=DkIEC9m&qLMx(4h>)&KyrM!ZiN5U}sw*E6UXTs!+pb;wa_wXK{v z@99V4zv5UD2+b|}lP%I2z?B7_qZ;{gUqL@cM36biKVB51rGyLQy#V=E7<=tIaQ)nh zPO#jST$B{ocr!LNz#C@Xx1)zLQ)43?&Ow*1MoV0Gex8Uh2i>Dds*}Lp&y@_zs(O<9 z(YMpAjfcrG@bNU0yah|iImyajeCJ+2VLVC`d1boF5tJb;SCByFL`bzzL$Ds9sOb(HGyu|*%>i^e^w2P&#H&W_!&DUS+D8?sL2!m< zY><~|i!P56p9f6623Ok2Gf-Q+zU@U@WW~b_Q3@SAkEih+sgS!|OqJkBx=u1S#jjB} zK5c>f)r1EuNv`EieP!=b$m}n84)<(AFjJq5pl@0j#CMLS;rMy&78fQy|K*`w%EiR> zX|Az~F_|kS(VqmxtB;Spx_{RsVSysO*{rc(pZs=0Xq`_fR5$ejMx-Wi!U<`Ktot%n`B*r&Z8N= zcNdhZqT%~VZE5C9vvpJM>ef>b>myOf!($x3S<0f_tM`f?(7$C;62l9XPk1=e$C%JP z1RLBouR`>0n8^7fg9o(EM1~f34D^^jJ@u})D6m1ToAVunHGs;fEPApnzfioeEMQ|N z%V?<4@BxNJ2l(9>qrDsD8)AaLfVtCQxc;*cqG!p)zW|rQ#KWpl5x(i+_)uQ3-DHt5 z5W6>X!guOP8jwJbk8i&h@K4P2QZg)TgF|#{3u0$>Hva10x#-`I1xT;`${P;kFRQ-n zY2Zs?TA%=KaDtRD=xc)81qoWznOl=fVbdC{x@)z@{Xv7L1X^hUw|kig;orf30~XI= zwr$72^b(MMA7`vx2rgrMYuUrin^$9{ZbDe*6Ehc8Ho|^3V*^fFT`eSrUVkodx0!_q zA~RnEVkEi}kqrOB z(XBBDH<~UNw=;PHmnI4Q+~C`vfkw&EUQnGgvh1wXL8g=Ixw7Kq?~W@A+!H%O$O&-% zwN7Iy<%+Hc=WiYq)9-RWr+^55RJw2m`(z-efQVX(I$8bD33BzlH}Tyl*;3!&vX&te zuJOz@kmEiLeiMcicLA@yXwNAyu|c!;7PeNb2-sCjD_QufDeO9y3l8Z^t$03Cgl;Z? zZ>S)#M}VWi>pcrvl(M$5aTyhl6JDm!6qF7eFM>_&q9t=e1-&6B==olN7`#iR)qZB? zG{73uJQm&j9j!1N(onpgHBjF({v(JMd|k@-3bEm_5hh%&s4SvMQ}7;orP{1&;Det# ztHuf#F_ii6q>t4WwK8Yx?Md+NG!US1EdSqVS|_t*ZaBycqa06p34>@Z6}7!F2q9Tv z=JR%4$CIg6jFHiez#WWg^@K%k{Zpulpr?OC!*(MywKf8Fs-~}+Jnv1oc^ddhsySF2` zFwIzlm>Ep@6iVjR>Gy7szN5vw_GS z8YYMqyUu9$-C$udf)QlF6IiQ<8Yr{F$UqUxI7;PJ$RZVLtzUOLV$9Tv4INlk zQQ!6^28wfn=%an*KKPBPglLHz3;{0U>lk#mx$~!Nkw5b(`?3agy0t;{@&r{~zMIhI zH-zscphtKSF16X-S48cuvodTm`}j zRO!Vs`Sg}WLU2(avxR-<7U{P?E5y-9n`53 z^ial4s?{=h$1s9WiTjdrk3m8YS% zUtnMuDO>o^srwDuDLPzA;H6e0v$NKn9m2<~kW)FGH27KZz3pq-**R~b%Fe35A`N$g z((W@gQEza5`1VxcET-;5f*#vu1oP-WprP(xW#_q*7pUKMETuCe+^wzh#I_gw5O^Tc zkMHCk>w)KnFBQGXZ9JoeXe_C<<+VS@ZEecY;B$k$6}>NgA`?>~5+=~2llyh=0>@9@ zPqob~Ca)1&{8#N^@@JS)1(YST79*si7QH)PN7nAy`rdqug9J^<2dF4 z3OV0)Jh;FAN9Y86TjeO;9EHrJ1xuDS9JqfZDV+&X$*SUdWtsWvhf~XPQt-VSiZgsW z=62pCwe!60oVBL&&kgXE{ZQP6Lbg~S%ypZzY@405&UXdup+yPMFvZF9)<1cA5-sldzdBdda22(G5 zitY!Ll_Y3`o^9L#7sFg}GZYK6hK9jF&H3E&QrWYXdialTWaHw z*g(&!P`5=RYX8z^k&fZ!Z-W-~GL)B3Grspltg5%nQj1-Im#^R2JAY#k39um(E%K7>eamSH!nE~rYV&DyalXSRx2hSR`)Ji_j zK*N^>c}lx<9GFv4wUen8=;(*xujSY1)t;$KH`dVjZ=k!nLOZG=#ewPb6q!QJU!D%Q zM^>GcdNp7r0~ad^?CtD}?2Dj9DA`^|j!$W~+lvLA%Qc`ktFevc%P!jq?wcB5*uffA zk|H<8Oz`-&ppP})QD17is=*0>M74HTfWRd-1RbuMA!Wc_CNgwiSQ(I2N11dSb{jwT zD*mzE$WS9^?GndMt94llC1MuNg(jN;4JB#dp^^{asp|NL;D%)-#}UGypnp)UCv_u> z{UfLUh?fXuX4-#|+n`h3AIVolkVWOlqG6IBWHUbPTb? zwd0}a1Ng2018RvcG1}1mHiBbf(D_SuZu;(k7X?tVVVLp$r#882v~w%{zQC`?wm7AM z7~K3RCy7@;2(T1qp^174K$TeX7h7D2eWLwKJMos`g$h^+gB^=(B3l{H z0pYK=j_zN#kikBBhM4Wuz$lJDon-3(QX3QG6dgNsKj&|J%LoMswb!m9Bi&vPdQ$;K`b?auTFku z5~XvJpg5)ga-u0CA;P$cv_Vq|>R2eLPNOP5eA@7%?jWY{uwtQ`jd#?UyS#C%P2h%`1q}j zpo0Z3*uFZ^%epBB@Rm>uI@BP=;0DX3RU+Goo_S2&7NgSi)2w`0>3z znuUGU>NMznXV#d=JDE3OPp*=@?pqHlEySXwWm}DrYI79gWU>$E1NkCPG%a&o|4y)) zBh;EsBn+$CxzLr<-#5?v#7+9mx{Ob4%)|?^9Lpr6X?e0wyC@zglV&&GuI4_rGtDjc z$0fU?^00F-wtCbAR;wu@_9G`Qp6T=i-_OsOgr5*?{!a9Z>vYrAHm zms`agRCghL<>R+FJVlHvmLl-BWBo}Y6+je!G5H|2e>uJZ@7<3_PFb?D*+Tz=E3bhU z8zz)yjrF@8O=g=f?lWTxjepORoCJ%it?62g8#_pFJok&ha*-3h4gvL`23V=hzk}{2 z9ixGBhjuGgIk5x^{MH2suF*l80pG%Q^ z^VE&+;4bG?V97*_VFC+5-M(!Q8N8ei|4+VLybJxmifL#1-Lr7hS~N5$(=Xmo-xAvu ztN=VI)j+W^%qN@9iOqL>zoz!cBF}E(&M1Gn(NJyj50{>L!8d&8L!vV#?z>i0!jcO(Ux8aUS9V9-w#k{Jij{WLIw^+?xxBy+d6jxo& zAV?PvXcZvH8&`yXri(LIln17YSWqKV>Wvg=wd;*_+Q~UH>G&-(lI-H3-rhixIh5W_ zXGtgN(MWbQV8+Zes;Ap@)W#(h;B2%~3<74RBILtmV}h|j4C2G8Aw3{FP{yhBM-L!~ z`P`;2m5_m?=sZJstxJb6go!|$Rak*xnr8R!3cY;7#Vv_Ad`X5F?1s>0$TY)N=H|T8+$2Ln%CwgXhas)?fa%p; zBa_P#46v%DE^{=ZFue7gkEoFO$sU$o;LkwZSu?;<} zoc5bdC=^nwjDDlCie^0`@m~|bTW;Y6?Ljq{PCvPhF22d z{KJt+T*UOGgF%OVc8R)QYIGhtoqj+c*mJSJp(|4~w1+(-G#O3!i>&V$CoQrYElAnt zJmQf?phC_-)`$nRT#@idP&jarsFm@mEww1|9BJ~~Rd>%dz{p;Zanw9b0YCF4o~g^J zF;0e$Q}~)ohViGzlljg9$!scNDPGzuj;>gZ_A- zEjDCT^w9bCb&&TCdIk4`oLnHg89Y3|w6@hX_}G>M=ocJHrc`h+z!Kk@;{}Djf8Z(z25cu?v;OyR@_1-3Ef`H)XiG_br6Fde7G{rUGUly*5_pFl?>rj zUSj!oCd4;(^22s4Bt=wDshgePD9a;RS-X&vP86K!zsy=S7Ta51fG{4?$Z-(#g~qQ$ zm2^wsFVV$Vwl%y7=TSdd%eyPiqxUHA9t+9EI*_ds-5&lXAnIM8Fl6Gn$0!6{HVy;K z7apn8-tQqRCI5rJi>`HF2aW+n!o2`Lo(?qaID`(o;BV&p=-OFb#R!K!pE#cl4&5pm zNa%kN1M0~uE7~VA!-pdMQbMi804m!c{BVd}BzZ8k74xwt(@fsT8 zHTl^4KIA^d>pXLQE%8O`Yq#9md0ha*I6q?>SQP;*`6?`#u`GC=bDkeEn>LQh(@+>p z1CiVI5fvVseW7-?yG{d#4Q$ZNq=EBJUl$Bu8B1xqwYL&HrEcaDA(_!;rn){6Cudw? zg(q{Ot7>Dq*g8WHvokU!jo<(jO^*G{_L^foS8O|@iblFmaa;4tE2&aNC9c19e?YD= zU;MY+uHYq83scoo3(Bb*Lt(mg?ii1*<{D^}zN#;i)k3%|x&kO<9SSqE^T1!f3U9Bz zp*=SS#5~oh>~U7F__J^?hD2u`vodli=eV7bp>Aen?EONvg?%QzCj|S(jHK@ztmU>OYD7%X-qDd*H`WF8*=fg%pGYPVcu_!YW^1t`8JLFq{uTXgDTw9Qxyv$-o+}r?u^-7x*Y3SdV;Cwx zUecz}l;5rV2)Bj=Zx<&xc%I%eLYYo~>ZtrXEo7qmtAs3vPRw=uHQc#3zdPXuNUaaH z_X}(|5O!D3a}E))uI%h< zY`>{&N4~YEva3-I4;I;BLU@RDm-U-G=7JtOfg&g3kQAfZ#_+3oD? zRwtyOtOCN|Z({4pdAFQSmrI#ZF+Ht3koZ;>v#kjCXa{{nIC=Mn)zBOsZawuHrNS6-}>0cNKUEK5jV4=Q=O`U*?5_Z)5y-3`xZ! zAhUsdEef$9o%kWG_Jz!8(q0OSl4r#7AKg(Rk%*3*NUt>BGS^(y}_GihN*LU!`<&_cYsr@(lK@Ybgm;eK<`Uh9-GDSiM zZ(-T1GY3_g05jBDQ6l#%jS3B!V?(GYe;cLz0Y@jK)ncySRqY@{2S9N!u?3B#naSVs>_T{WD=6PXNxN7QOPzLb35%qR7y8h0i zxxWG)>lCOkGGrMWQ6GAi)}Ur7kNQ2D!cLptHO(?8g0D))YRUBPn=rq`5gAY>a)f_MX_~;po#aSnTY5 zw-YCz*{b<07l_RFQ2_R1vIW*JR-;Z5mbUm*%$u?%7VB8AT5N>$e^lY6FFK?^AgW-Y z@wF?v#92UK?@IWxb7!)MK6{fy+lJ?a=Qpcbto=f|Cfp?H4^Qu6^6yrK6h4QWNAGKL zOPa!cGz0VeTLB-OyPt~2M;61yTfg4kvm2{^6=2AGyi5GWG!|6~kb94-(1OO|kbMR7 zF3yz~`c@mx(5}ZX@2OeC9y2#Ex~=!%psxLS_;kt3+1J5q+Qod9^>{%{kPqcn4Uh zCGQf^CaLi2_B*V#!_`3&{*H>sE(WGCMQcc5K+(`3;a!Xoj7A`DxU6oXYQ+|tIF?%}eKA^HV{Li%yv#H8}^JsAVxJ)_IaqtH-lc&s>9s`c7_0f7$qm*3C7{ zB~7JFrPNO)y0N)ypTS|-<47y z->Fc$QOAyUbEH+;=2oXPlQ2%bs|;n5}%dSBEE2@Q9>i z!=q#5E9_&Z(%B}*IdR=`FJ z)bA)k9+%e5F1rdfR8@!rs?%^s4~c4Q*U7zItobj;v)hF}lL{DfDU_{COdOGuCf6sE z;g>Z>Cx^$uKTIjfa($UomJ|)*UBi*V6B7j4scsL0<}h7wV}u`;LIn zS|2=5SB%Bf#>i;dWI|$9N$1*!*sG{Vfh*5^E)rw2f75o>-m$UL_Z^0K+LvQLbS%G% znv>dXcnz263gqP$TXkO9gdjW_ZX=kNmnZv^P-3P?vj~;!NHKD22IKrC(*65&+=aW= zOA->2T6-~muw{6522V5Z5^GF!$XI&(fuJcs>^G=&2BWO zTo>(;q-edkCxYh6*P8StKYz|&O`V?PC#Jp_U3}eI(``QceB-$6w8$fE~oE(K?VPiZ0oGdTy*tApto_HYo zSGLazaCSe0?ya^hbp%bda+kHVAlBA2_Fn4an*KaJnvcY=FjzWV_m~`fN2^ z_C#z|ISLu)+6E3dmQSyp=T^Ra`IWkL$%k|C*lR`o8x|Ipd^~gGHv_`#d}S~?2zW7M zZj<~T1X}F}^w^PNx2aNp`)XE~Wot<1*~K1EX*Ux2h7CXWd$qNAAnD z(lu`BO>g=x+R1021$F^j{R1yQ4S_AEp(E{-(TFEgw;U_e(M~AA>sKSm*)OB_5?Zex zyngF{HfeQtC}?Znxl4PuX|(ET9%iDAoJU8pP2X08*PQ!VX~RoFOHVol?GjDq>{pkx zyiuO`zyEwjZ7G|gf6FFExi<1v^_Jk_5L%Qlmgk>86(rD=7io8cV!-?s5Wl6RC6QYX z7@g5iGU@Y@&_fYF25E~0=`(_0gx*5R#LHbwalP!6jgg+9)i+Q4zojNq)6q>_U0tR6 ze!l;~LmL(xAY?l9_F>KYp`GlAf)1l6-I?mM>4F$r+1)DlK7Pf_BqUJ;Q$=j5l)0Rx_u0D&i&|Yr_v9y1?c0iZ zt#6yX|N2HNLwo|RZ3b!MS;0$w$Ja4W&vlI;isvd;*Nl1d$aR0u}6p()9j#CSdlJDn2nZ&+YI>nH|_6U+u29!9Xa2e zRM*^!ceDCK@P|j5p zAZZk9Uaohzc!cyr%Ae2tTtXgg20R`R`l_s%iKrblJC&{K@Sz!x}Zq*Yd3TgUx9GDPp?b9f0rh}s;rE42Dw8ge8dK?1^lj^f6a?Tr2YNB g|D3@8^P}pw7}!+(lLz=o*4+_u(yyfuk_I3C3xmJkegFUf literal 0 HcmV?d00001 diff --git a/doc/html/_me_humiture_sensor_8h.html b/doc/html/_me_humiture_sensor_8h.html new file mode 100644 index 00000000..e577fb66 --- /dev/null +++ b/doc/html/_me_humiture_sensor_8h.html @@ -0,0 +1,233 @@ + + + + + + + +MakeBlock Drive Updated: src/MeHumitureSensor.h File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeHumitureSensor.h File Reference
+
+
+ +

Header for for MeHumitureSensor.cpp module. +More...

+
#include <stdint.h>
+#include <stdbool.h>
+#include <Arduino.h>
+#include "MeConfig.h"
+#include "MePort.h"
+
+Include dependency graph for MeHumitureSensor.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

class  MeHumiture
 Driver for humiture sensor device. More...
 
+

Detailed Description

+

Header for for MeHumitureSensor.cpp module.

+
Author
MakeBlock
+
Version
V1.0.1
+
Date
2015/11/18
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V3 or Commercial:
+
+
Open Source Licensing GPL V3
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 3 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for humiture sensor device, It supports humiture sensor provided by the MakeBlock.
+
Method List:
+
    +
  1. void MeHumiture::setpin(uint8_t port)
  2. +
  3. void MeHumiture::update(void)
  4. +
  5. uint8_t MeHumiture::getHumidity(void)
  6. +
  7. uint8_t MeHumiture::getTemperature(void)
  8. +
  9. uint8_t MeHumiture::getValue(uint8_t index)
  10. +
  11. double MeHumiture::getFahrenheit(void)
  12. +
  13. double MeHumiture::getKelvin(void)
  14. +
  15. double MeHumiture::getdewPoint(void)
  16. +
  17. double MeHumiture::getPointFast()
  18. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan         2015/09/08          1.0.0            Rebuild the old lib.
+forfish          2015/11/18          1.0.1            Add some functions.
+lanweiting       2017/07/11          1.0.2            function update() add delay more time
+
+
+
+ + + + diff --git a/doc/html/_me_humiture_sensor_8h.js b/doc/html/_me_humiture_sensor_8h.js new file mode 100644 index 00000000..6cd5a008 --- /dev/null +++ b/doc/html/_me_humiture_sensor_8h.js @@ -0,0 +1,4 @@ +var _me_humiture_sensor_8h = +[ + [ "MeHumiture", "class_me_humiture.html", "class_me_humiture" ] +]; \ No newline at end of file diff --git a/doc/html/_me_humiture_sensor_8h__dep__incl.map b/doc/html/_me_humiture_sensor_8h__dep__incl.map new file mode 100644 index 00000000..b2266f92 --- /dev/null +++ b/doc/html/_me_humiture_sensor_8h__dep__incl.map @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_humiture_sensor_8h__dep__incl.md5 b/doc/html/_me_humiture_sensor_8h__dep__incl.md5 new file mode 100644 index 00000000..c3026154 --- /dev/null +++ b/doc/html/_me_humiture_sensor_8h__dep__incl.md5 @@ -0,0 +1 @@ +df6e9abcc2505b88bd602aaacad84ab7 \ No newline at end of file diff --git a/doc/html/_me_humiture_sensor_8h__dep__incl.png b/doc/html/_me_humiture_sensor_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..d5720829d2a7caa3ebe1db5b8d1f61360e46a1b3 GIT binary patch literal 14878 zcma)j1yEc~w=EVNl0bq>AV_d`3xVL0;O-LK-62?l`{2O|?hZo;ZozGE8QccfcgXku z@4vV1t9tiL)eJSm>C?M=_ugx*-W~o)K@tm{2ptX%4og}}TnP>iDHZtJ9u*mQSGy*1 z06vh7WF^Jn9-m&>ZH4i0aBtwG#YI)z(+?KCymiifppP@q2wU!}UtBB1^-T*em}xBf zGJZ=`S4n?(o65{&#i;-0Hg{ps*6-kGrq+u4-e$qMp<}o{ZE~hkdVW63yrxXDu`|PYj6QMD4^HBQegM-;dtYDnPc*Mxi_Pw{@Sxgz9(+G6vdIZFg1-tic ze?$4dxDYiV@L^$LeZQ;BhEuiIqeM-z-=JdK%vP?_I`mRdQYxYST*H1ZE-p@k&2g&+ zVGF~26|&k8(9^j7;^oU?BpJ?d;O53u9y>DgOb;`NVHn);9c*+rTME|xA zJR&Si%Jfr?G|<%F3;jbl&C7pXbg0y+|NcJjO~MzPe|;Yt_&;v|u}+t1&m3La4{o-! zj|uxxeXAPjtmil`Oi1+f1`NiPSN-RSzYQ0gU94v-DWJ=;pIu9Xx`oxm+Gx6GGl8C{ zkexq0Bo$2T_w($8+b( ze~PFZnUK1$sFkQ5(UGnl6Yd~ji*$LqK}qND$V>GP6owAF7u8Z|z9nT>57X1hcVzr1 zE}qx;PkV9PWHn`xR3S2~vkx1$H&GYo?}Cl#fcv}ijaHtTsqPt%f7cRrW-qoc5qFkS z)RxwBb0_1q2+Rf*&p%@n#}&7#)=iYkHGRI7x>)`qgnmsZ&b|85yz(5gZb-_KeY0iJ z8^iBAFuyxhjflXc$A%jp%-0FqEeVbY!iE~fUc#?jL$jc>RmRIpwHC_8kgBICK=`Nm zR!Do7`Lv3|bZM`<<-I4ydX(goE67CS$O9dWOa4i})pU|8M!s@TpyoHZ5{fP23F8%6 z@GWU0c6*v{N*s~D&O^l_3O00uQ*hEifcPs5*%0*?;5`NtJ`bgcrYi9`+xvb{=broe zX|j3WjZp#jdGPtBcPSUH`Gbt#bNLIXf+^jWtl%Gu`NPYWHbWQPXCowsJe-w->UxP< zrQo@2VZUqX7%^9Uz_)B>b~cr!4!zXC0HXgh(5==TQ=X|>_q-!#qIktLyC+|XIRZwT zVA|NzlWUUp?E`K{L>2ZQ(al^+MiG~eMs7*Vc^Z3ujJyfPg%kNMAOUns>4$hcFfN$8 z^%=r0j$rF_O+&C;`qE25p*N|k^;qkfOy`^x_X=0tl)>~$FRU)FYE9x8hOc6}dNGAp zMhN|h&*17bztf^hfofO^>;Wf`iTXQ)xRbiWz7mRD984w(UxqkSHdzM;gWd))r@uv(MB@#FQQ5zOhCOo*=@~1N<(;oht5_?g)XlQ+ z*W>xgxB=HAXuy8Vw$k;!P9V?r!HR#`CsK@7kMiVVP^Imj0mrUG?vG2U!7Z5rKZfA% zI9-id48v-Jy(Annc*8})JerKx_j1B%lNQjJRBvp<1Lw*&S|iE^@KY5+U9eG+QGugY z#Km3(q~q=vhYrSOD|wKje!CWxXFUOwhakYIH9tSahP)xj)V?`YNlI)W4AEGag5%d& z2dP=iVfgR4Qz-aTR)DM+z*zF23G6I#}1f7 z7B_6)*ALSxK2s)GG)2Z^c2PD3ooQ}Swz^~{zKu>vs7-V>{#1p1BNAV)0eV43c5oq? z@9FqDzHr9=u210OLJwh$B5b|GbLQ7l<(CDx(u-R94(FX#*3a5D;i*V)qW-kI3N*C1 zTvJI>1pX*fs!2r(aE;I4!&B+KR>z>$%Ryo^cHUcc(5uotGspS4LXPVpIz6WwlNvA_ zBc_;Js5m9>W_Xf6>+1rA*5)H%nUj8Y?^NU#f3_#mQqYax40|-VDeBOfj| zUcVu>o?MJkYq&b%^A6ufnlT^|1W(j#2b{Pqbwe9`2NWV)Z{IpxDpdH;t|+XCXuR&I z_o%wJs;aN6pJI{aYZ=UqFlx=ex8RRgI%dLr!KVXv+4W`u)&}Sj)Eb$1MLl;+^-$C#S}7L80i-7 z{m}LTS!=qqu%UD61PFbHN)-A`WcB#wTy1hA3rMN%N>5&AlK$j%XKIpYx$Qr!??dZ` z3m#)?jZHjB`7%U3HMD8MUr8#4bG5Vzb82BOIbJyuoNiVy)u^*aS1hhiFmC+JgR#c+ z87HqhG~G%I;rj7+YJOeD}Zi5b50Rc362_8aL1<+q-~OT{u)=>#t)!Z$eoY z1lA9-75#;)dczI2TN0wA|6@9D+GE=ZKe2ScW$WTYOqOcmMjEngAMK9YxU4pjwQD=Z zGSF9N+Q!}pKXZlcB>iZg=P4jXMPRBr5HzBlFeKsv&}ehrE)B*DCGUDR&!GELIvlvMn3+(&QQm7ndu!1>4l-kVcn!0Ue z!`fV0XW8NoegT5-eTMCWn=TUvRynH%s*d!TmxAY*t>bG2VLCJ_)Hm>)Or;~keTn>$c%fla;e9nPuB z5YvUy1egbKXAfu8FZt7Ue73WDe(^Q&`AuRt(q6zQrW9{mV}9pW6z5XAlLP^EHsqE% zZ_AOL&kZvt^HUz~=N}W&uQO=%pxp-zT9$bWcrRbl(fp03A%7Z&tqSCz`(Qqi`(S%y zd*K~Jn;k#>_m3=pdfx~o*nlhRkw^~M^$2z`Z0IyQW=gONQjF>F))?Q&&@dq|Q_n;7 z3`8Vaf}MG5Q6wa{@602#dAX`ytRdOnVM3SfbS*{boQJH)&SYCtvA%lGq7+MlKtiJ# z9el&r_Z@m>i@{O3kI0Lut~Dgk(Zxm*6hsaw{{6*q10Fn=Tg_ChJGRh|$Y?x}4-kYX zghx{~EbZ^H_RYqHevGW`k!+EW;0;Ce>*FNTi|sEBQ3L{JMA&4E|IUD;j z$%AXm917oC%z2Vb`@*vFsI2F5SLL?nAAi6;2IUhRj&x}gTc3PcAO6_(0|?3KbWe#K zcY0Bv?c#ubgkA+FoSwg=z^O<>EcTntlx>!1AA$f#PRpPN!Hou9Iz7nNnV?p{8A;+c z@0H@F%y_BoiHPgfTlTh85>_Pw6twFgCRrP=A8WRdt?=TBs}~duthUI^ogTP@x(&S% zdTvW-5zF%`cEiEnj9E*xysJ9>x|-16esuM6tn?@5nOVp*>K(%$Wqyq4^qEr+@Ifmq zGS~f#qu^G5(Fv7IhRINAQm6M;xuPM4ypg-sb$6z`i0SAd0@eqO;0@Oq(KeWhp zSQa~Uh%e$KjxSURK6IFu6WV+C6X)ASfz>=CCIa5q%0D0Q40XEuDc2>j=EZW~`d_f- z<iM!4 za$^kqOduJxCo8n_nfJ++L;Wju!Ybbi^|r}w{9pbeRYlBd`UfU7WDHXvML~({YARsNK z5^1@lxmB$)(&|_WN-j4yesQcX0Sgv3mjBLzX~;K%9`PLEh+mL|Kp;+MO8 z%sfpLecd!dy8*&`GcR(j(KaY@*mEiPvx5`jGHn$vW`@@$tb)yO>8YEO)&&N2G47f< z$FAX~CC@2h5O)0x_4bWfYdO@xRso%ymS)-emVZ@K{+_i{nf`9a`R(V(GIBmnb>hdE zQLnqh482=d@DZrWR<=#|Q_+3j*$YnNmuL4n3eI=8)LD$3B6fP#k6J}G`160G4v`u5 zIPtEM!iA^G)4&lXJS8pma<#+r<~QA#afL$z++8_HN*8~y35;C1e{QG8uNZtb8>APt zBEQ_-ARek$;e-q$;;k?uF~8jn{(~quqn;v=J&apxcTa`VpMk)nifTki zJ83>EN>Z+=)b?D&(Of9#tdWxFaOQiB_n^|P9-EOAZR-P(2G-qh5^{?`G*s?+bJJYJ zCNB?s9j^#Lm1R!KR&k0-4ln6~x9fPUBXo6Q6;J6_1>37SqwqK~KWNr1n8$pJQw-o( z=8!HbQlGij{QfY&2lD^5{o8#6A(LTKJS{BjRmjt*D6#&vc`rS_rqR_|(i{16Wc(0R zaRwYX5Aq`>L2GfZpVdc|RW%D!n3l5xExT;I8_Mvn=UFn*=fgJFZ0QJ0AjH;56;b%PbjlJSF|o~2*n_>CmR>5dk8Or>Xw@*yX7Qn606UatdnSEwWQuh z9MVT=OcvZYND(?W)#MRyAY#}4?6&Kj6B)NLwRBnKM96}tF^y9|n^luRORw|t)?)8Z z6r;|nULH*&Dixacmn?EfQ%n_3yf(b?wi^j1qt4z!gz?UeEFoml?wVe=YM$9Cp5EK&4?S8;vug6qws)_NOaoFa(qo83yS*Lz|GZG?I5sfo|!(4m03 zAH1OV9jG_oE-u$d2DqqLwpVvz<)i?4>Etgp^52%7-znr^K}|94AyJ%>r2HA3P#mk0 zcAlWmN5amFMDoi$mNhk>sdUXCf9Q|eJ4AC&S^TZ`Z}A+hrlw9{6%Yfv zZbG*ooB-2KpwqGIam=9t=ZlB;>GBG+h9=4Ew$%dwRiS;r2Q2CE6ET;+4R}prw+$fBL_-KSN~TOFxtwSp6}wpb^4C$1}h|(>0))qN+i!B20MS=`pA6hrT$T4 z|K9L$Xh_BG1s3rR+&syA5WTNvxQpzQTX^Cy_GrMD!WFDPrAmqgs9;Yt0~=wJZyO4V z2zZ&$dmzJ;2f!RhAj#l_#kn@q;>A~P>4fr357A&IID!hVzTThdCiE+z;O}*H5RDPE zQRkP((FUd9>-5g1ym$qQyDor$$U)e!p)jxevvTJ05gB2oH>sl4$h=W771vXXEk%!J zr6p}pvu~0S#YiB$bkV+EZO}+ugG-f5Pa_6^t^P^~uir@8@y{J}q z++bFUnV!bORHx=I;Cd4Xz7p=?+k#Yj6#Iy5N!@ZDoLQl|Be?fRMBA1(Ai_Pt&|gR* zaG85-MC|~C?j_!tHT9f+`RB`s9o!K`hI7t0I~zSC#a>e5_GGoP_23l6z6jP9 z1*ON9W+7gd*vt&3+Z=v)$(9Iw`c;f|_kRKD_@=ax{$@(`7d}7so?ToHpCKOvjC~H* z-*wddo6Dd?AJp7A8Es$MW3E%UrFLnNHC`fny*=dZ9o$uWj1%Y}CTOt!*|4?Wt9E$W zq}rozZCkk<#?ao$S$Fe@zB<~WW*1uh*nTS7!5(YCa{PNE=5^v^yugyJrMFxa( zmK29cQ9QY^62i@{@)=8MhLE!MMeUdmN1ZA2Hx7>aox}av()j}p)Cr*k1-z|xY}d;!71x;(C;}&^9lc6q(H$3ZD4?cI(kshzF@A*EP~KT?2S<<7JAuX zh7d;}tFFvD+hsM_`^J`gOs*;{gyY`9#N8jaeqtmFLs^gt3h{|+c|CacC*+A=#zLM1 zH@fQf^82dHW*&L|uw(B?oWP?#EF#*9%6K?m*gZ-<) zJ{)ZT6uv|j$N|pj<}(NW{{?)CGH+l z#UB6@oJku)-_O(?gwnSq_om|MZ!6>yH@qDFc9BDTnd~)AXMC?$!4DbENAwgnjobaq zGW=!ME=|CukWVB{3hn&mYuZqSoJ{)z5Y=Q0-G!eMsEu#|J1p$C9H4;5vT3#S7E&t@ zbvM27Z?e@{AsdEBsF>WgmUb^A>mgw`JF%kXEF-hHe+#Oib!r^%07n)+WhVm1&mF%Y z_N27Y(ifN#q}T^!r{ABL|5`+gN~y(3Fa=;*z=`OJZfGc?vE<7B?5u(0dQ{abz}Gsu zuTus5DqV{2O@a9u{Hgn3$f0H5E_BPLCZCWQuPI$P`Vy;&f1}5ZzAXFxO@CoYxb4^U zIB)bl_q!$HQikblWBVt`q$LDIl}q;Nknxj)|ibXprHxqfQ*&U(sxHb>Ek-{Gr ziRIj`tgrlT{-h%PuExa`cQv%d&`jW(SjZQ5i=}loJREDhrw}P=PF8#|rFHX)HE}<% z?=`Djk%rpA1u@eGJP)^ZS%V+Bo8Y>s%Xhy4LxJN&CajAVhhE%dc%cVjq*mnp-?N## z-;-oYO%to0s9?0GP;d`r&|W}IU##~}nbY4ruP+oz;giGUNWmmCL~|Tn7b~rtmCPyz z&O@b}AQ@S+Z&IdDIuiX7Yj8aaLV+oh@E6MBf)Mj|$Dp>?g9>u*=YpHU53^bNn%}1X z=G&H#EMRrZAI(;gDj_?)PBIDZbPSC~ln#<4Nfldf58#OIFIKC&!a^2sXs^o;5TMaw zw^jZA*xV^%ba$QPdAr`Y9=@=vmIWOd=8fDjEa>$|VXIe6Si9njQzVBQp^-eb$eC#! z+`J$au4xXz7;bve*thy29fOUTvW1tg)xV0|yra|CDN|OpMxSFNT#D`qUJNYx=VXjw z+R)-kEq2e3zQ7bivEHOayLPDN~?NjRnSnv%XfZ87u-a9a~u&nAh&MY>UBu>Z3^Ebco%tEeR6>QG$)QjfZh;zOb^HpSUD zg3;vxw$T|3A>cX|-s zWjT6upiQ{#XDEi4xnaSyB(oX1Bgm^Q^ z{zTLmD=;n3EFQ&bUuWxsq>g>kduauD6!Sohjuw{Zs=R3dA`n2&`zDa71e&`&k!mQBprv>a%|W0DU?$L zo_)VD^W4)5@xSIvR7j<8Ds@j@zq%m=DSNB1{_U?K5qZPnYWFRLAKLNzRhgbRP3+ETs zTps6k6zjsYBe@MCKft%q45tOYDs zV2lS?Fv0^FCYV}fgZ(L9uNH+@eDeJEV-P-x9;-Wr)bU!CG0F5Z#T|{?M)lhgojA}A zQwi&(>HGK2f?0!PM5}1?4Zd-RxMi90Ri*kzow74dSQHF`M0jpY$5CBN;Mvd5mhTrl zz4#7!89H|}ga;9Qky`f`88iE&19bjs(0BP=&1G2ibbzxh9z4I+RF$@+l;NL3q>BzQ zwylt{f9#=l72JAZoSfl3aO15R7|=OhXY_CXe$U{qRgLb1LU#UXT+Xh0qH&m39yAcjs+I!NG(bKM6lh_}_Q-if zMy9xv`A!5A(7=St`PrKQB|Hnk4;9j$-}xYX=sxiAKWushS;X;6IroDoT0(ra)s5)# z=%)Cx#SL|qlC*C@W_9jA)1#2h{sqT!>4}D38 zSCR;Eo&`-xjsK}XjS-sARx>;-;R7)W?*2&vCWduBo~zah^|OO%2qdM7#GH1J@Wi6{l~({A+SPUsvH+2rTt47sj|f*n>C2Gn$@*SW#U{A4+}u zmT@l}9Sn5#lQLhAHhq1E#>Lk*>yUm=Fxq@#{o>R*#lSDIN?%OkBYh}OzkXq@K8<%plWV0wzKcBqLer7IdL)t>KhN<@5gm2WUM{Dqz=i}W1&_6+nPLyAauZ-i?d+}vXZ501 zQ|3O#?q8+9Am770^Qryy4E&bm?C6Jd9o2+3U`+k!L7Uj*h?r2e2vX5+N7l{#nUMlL z;nw$_&#`^|J2liND5Ab^6g2j16N-ZL(n=`-uG>-yUw=UjPMx*I)8cL4FO~ z#xqM?b@26-9Dv7iOvVFCnYZZD@fWxIn1_S_LgUvq)NG8cTm7Um)LQ7s_o4F;g`4er zk*<3ka$3>DaMo-~w63%{)R0Gp(~`8TAQXu$Pm-n!{Utm(`f9wsRVD3ORI!q2$TAMV zM9aV)0Mk}EDI1pE-vQiBJ#wMd>_&xIp_4M=BVIM?I)4sGefjrwew^aE)uvvS-c(mG zpIJ`}PD-j?DX}|Qu22h#U&uG#CX28;(IZ}c9bR-=DnjDk3&fr6xFb9gUj}&lb zB(6}8?1^k#s6Q?5iv9a%?->TczaTppvn9NmJS7$O765Wnjico*uXJ0B&_+(CTic@; z9Bw4!eO@?$nCjrFk}>?8ThF}Bp_lF+P|R4GU@ZX-g9V;eQ39DV08<9y{)ZYu^$-g3 zM?jngqKOR8o1IB1mE;OLjdIW3NL{nO8~=?7%4}@j02s?$e<7gDWy#=1M60&=NW`qg z{TUDL&yXcy=1LjuPphx+R8d+Xbh^+6`+mrjpFSxy8-GnG0ND4sN zgQ4U4RHDq!W6J|IuF;AZV$A3n!35vOIofp5T4~#)T<-(0Loa^n`L;U*w-K2`;<5nd zqd+kJf}a61>BaEmm6KDd@(8z26SGZ;+qEap0|B(2N%nwzJ*sd#&-{4dna=J=FK3?B z-BY&i)L#!m;zT~)I~+p7ZmbH5InX9{S8)kNf2)4lk5DduDejBm9`bH=X6qjUdZArL zyHrG*BxiR5kGsyeVSVFQ`S^nO`n9A%OYi8L zbx+uJ_y3_Z%|)AnIj}>A6+R%z(x&(FaL;>W(}=1;SPufXU_VFci86^p zndIsaEVVpu8NRM2bORKSNQYkKV%vosWh+E7c3zfE@3W=+iw_Vsd2uT(?;iq@ws*ui z7EpcXbzka?Z~ujX>WVp+5lpFmiv5aWQJc7|jz-6D1mY>Qs{t#3^!=H((7o9aK3*7VhmA4gcn1^@!}Y z0L3EQVjM`_VS=?_ORbR%F%Ok_VkR0NV2cQ74zqJ4t#iUD_m#WkkinT+oilfIN7~qW zJ6N?X;<^dqc0Vn_H!HXARq4BXCt($wCe#_W)Vmq?^pzOKxBEn{7U@?)NOyh^QMNTaTVGZZzO7^})Fp$gFC?P_CChUOYQitiO5Cvu!63T)j)^L9jlI?wwKzeYSN)Lf>X?r|s`^$uR~Q|svN%6W?eqaCz`(G1<`#@Y zJXRDYM;Ck+xo?7Xu-i$qsSr*>=k=6c<8gE_bzT*iJ8;O3ZXk2;&5b-xt$GAO7u|(X zJ%qnPgDm-7Bn{X8qAg$t0YGo|cwdk8f}AG4i|c0pTL5;7?5vOj5vC4lV0)*2L6vsq zS)N-Jsx7)S+SHg@<007peLbCoeE2E4*8NHBMTDY&Pg1F}u67*-@Z97ae@>MNk7lGf z5KYu=N5MZgvi5`VmeHFDJph&n!=+>8g;}DUQ)hW1X5LA(wUJtZ#}!>gPlvd^+?cr+ zBtiSfULjhx+CC-mUY5A$)Tw!lCZ05!--7cLdo+a-*lA4(cxA}89U>5$j5>pO@nORMG$Ss)3!q<(swpBI0pZnC-zo)LzP%k+`ar< z5NY27CT}}+JnjCk8V1x>4eh~5nXTmd0+f3M9B+Px9cPl+fSO!dgF+ml6T%d4gr%%@ z4?JK;V)x_Pzlf*_;R;YJR#*Q`mT?0oVsNgS_h=A;*z&N^9Wan3{O za)lBGf9bSL57^Kak^Ro8pSfKqdp7f#v*p$J?<9~CFUQ0}HUQFEybnOdmZ~XUMw*Me zFn>V7{kY7{gLe35m z-ANyQG7eNm?F7Z1N6a+_q;0J>WtzR`9kzRx(gh*s8v$K$qOaFsKie=S`)A881*R`m; zBKP(k8_Fqbh5FiN6~759Fb{yO!-d!OpWUk)9zGZZ5Moq&ikdFx9oc`GVHJGZP|bT+ z-AnfT9eB}?=+pM^?I9{8&iFKw!P?v*IkKH!kQw{xu(i*j^+R%Y0b}I|-^QPEaz>BQ zb4}Z^%0^fK;^BUkzuD9)kh|K^nI_rs+ZEFzvnpX@nTh`@xc&^B*xb1Yy(|4m^{*XZ z$u89fb?QdHCrQ*PjQzdqDP4)=Rp43IeVpRd@$B;S!k|MBLl?2NL@WHcRPO0Z&E;-{ zT(KG&Sqh*|GB*j7!GL-b(lAW!%pE-Rf+v>)bEoL%T5|KBn27!QSHC`BXnsA>%dyy? z05XG|q3!F21na*A4+=qqgAPgX@&2^K7BmLETb@=xnPa$Qb0JU?mphXYUBWDF0n`9g z@Z?TqO!K+i6<9_kG!)>8Oc?Tg9^a7wWBG3U(XqJ;!okaD@WRvEzHLh1zBLBMoW6hb zu&v+swG}w7Az*p6S|a(3LE=zC@?uygk})p$>K@J^;AL0x{>1>+_cKS(t1W&=zMS z>oUT`GS_vC?0qyy78@sYq7*9D(hiemmf@7{Fj2ag)mt$#u=K35P45B?xzd2dUuV!4 zFd_mar>Q`S;f0C5Ci;#Hq4U6m4P7%uvo9;c?^eMs_TE0QE-HvZF?+N^GFfnQ`mNa9~{17{IjBfb?oEz zV7sT(!n1X3g7ie3`>E8irG!msjCS^7qb8F4>*cYg$*jQaMj)b=xf;L1K~0lrVcz`q za?3mg>q4qjpd{PPhalvUEy}>eI`GX^2~a(KM>S*Yc62uH7AZ^0%(Y(qf|&Z0%WRZ9YQ|Rz)O^wK{Q53>$OS56AUyU=A~}|sA5{?q zO9-vCYwFhxfN<=z+e$`nTbe3SA7!t3?D(_C)Qlm*-39f# zGrE09Ci`)zJB2|A9;&y2G&*>(O$(Jn<97R1g`tR0Hdv}A9!1J=QX$!kqP)5yP zh!%N?9p~+dSh$Ede-o#8?u;o%Q=wT?@XkgX{Vi%>7Ep%1S^*3!pJ8AASDh$_Cdphq zJbOpiE;q~zzWpwbZ~lc2nVv9t?2Vs@s`XjwxH{#dxjzFif(>~WhJ?Ki>Sm(!P1wy8 z1y7I+32f~wPs~vpA<8;t_Jlo~VACV8P7dLs5;lsz4}pmDtkKAW`0HC9=B-cV0wGq@ zrJ7&NvUDpA;9Xo?5Xtd=w6zI&)6OkoIwLOIe^Jc4+9bAv-D!MB+fApscj;uf3~)fM zpzkzi};9-%wNTo8G7e76-{Zg_66L0T_0LKr|dg%w3};;Z~KSxym^5gnQFv44$8qc!AHZqLn&;z;8(`E@v^IyLjx_y^*w?VDrw&)U!rPpKK6@ujxUeM|7(nR{Uxp?}hXa1>JY^rB- zYm8Mehr-=TaQBtr>S@O=Hd(V|mb$44V45hdyi$nX4HV^W{N_=`bf37?Ee@#11`3%W zPpbd3yLb19;^*hBAteXfEM&p5YZwaOD21#R*LSjnvzGS?-Oe3BZJyan%buHx>){IM z(z<&LVfTX~_k+{KHkW`v`APbpa~pKDKzW5g+U`Mb>#YRjM<4Ia0M^CyH1UDM!maso zT_w+VZTcaef>EwT+#X{1; zo)ju!hXxEf5lar7LZjM_>UOqVXIj#no4gW1KoXm7UFj*t9cgc15KtUs@8eXI!{u zjsg})cdKHZJxUVd<(nG9S2IQCd%x8!{?MC=wQayj@VXtmOy`80knP@a#le=oT+q(w zwyYX4PI}o?I-P2)6EaUbs_y>neT!?Dbbb8s*HHQo6|a&$n|)5IlG`CmY?Qsx#LnowAJ~{l?U_XF;&7+*5?mD4Q_c=m0aN4-4Y+%aO@H7 zUPYd_CXe!Qd1;H4Sv5Z5pSE$&KH&X~Ot|%WHn4uLB-IUBma!yGoMe``)zsW~)s#MX zHfe_5bU)Vf(@D*=zQcP)ByPRfILm9!=y%Mh%c;G?R!zo_X|A{{jPul2`4Y&$4b&3Wqy`w?z1u1I!?n_yUnfOuHHFw+MG}Hs5ycvh4k-2Vu$;7vHAmzx~ z;fA9BlE_SBhNl_*nchQyghm1UNEBK0a&trmg< z&k)bd5y|`FVa!Lt#jnhnGFE6g*)2$<$tNXr&Eb;_0Cj3Tx^k5rEBf!hHPngiO8uu4Y?Ov z#V929bK2*$aAoQ`5kioX@I`P`q0YR9=(m9AO{&zzg)fcbV^Y{k!h6Go#B)-Zb>-m~ zqRIm{MvQEcX1d+{7r15ek>dGv9ZD*tOM$^l3hff7WHVKQ=S}P9zJ#_yO~Nx69s%kW zy}s{&2cGJVihC~O2hGbpL`$zGdfpQ6dllMdN9q=n-x|?x0_TaIXE3PE)K`_e)k+uc zLpQ$}R`$~0=P6;^P|lo?%`(ts84FCpdYTtwewxmm~dYv}xP|ri~rB-`%Vy=vPM}&!P@VtJ8q-2A2l@Tz?5?-V{N{LH) z?`_N)dwYULH1ii99P7ekt-Wd;_GY7P=RN=}yEszRb4)tU^^^#`GTnyQ`;i|kOWZvE zSQ|KZZ@-Nhbq&>i)R@*}mZ_7+Jiq*r1O!R)Jy%$y1=WH6K?SQHgEO!gV4*jDKj!;B z4Psx;N;RlPT+VBVkW1V^9F-N0l8wl;GbC?I@?6>GFJV$6h1bGvc_)dub)dC6koWo@ zK8B8tXg8pd_24hd{1?I3+EpWjU1cSoppD+i3@U$@XLxBsO9^mXFRX9HnUwZzKKENn z_SV4jFR4Wk+1!D)ryLOxQNC`HH)$p=9#SZ-48M&iA)efMj_5OEf_y}qVu9{u;dN{D@5HBH4iVzB^ou5n>$j%Bl{i6&Otx6@A-#2nbPrfOg zjp}B|QrV_)+Zat0$UB5mu>FCmYW81yILqYpFZyBLNsM*H2FjAR1eTPP2uw~*<#SVX zS+MlTxG2QQD3?09crGpkL>ZOoe=7m-%BQO75};L;gi+l;P2#7(?|A+#d+Dmb0^j_B oCYmtJLt~$8{{LK3)Yl@kr|6Bm;1UGjz$cvaM+Ncn4+eq%2SL`3SO5S3 literal 0 HcmV?d00001 diff --git a/doc/html/_me_humiture_sensor_8h__incl.map b/doc/html/_me_humiture_sensor_8h__incl.map new file mode 100644 index 00000000..243ee1ec --- /dev/null +++ b/doc/html/_me_humiture_sensor_8h__incl.map @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_humiture_sensor_8h__incl.md5 b/doc/html/_me_humiture_sensor_8h__incl.md5 new file mode 100644 index 00000000..47578d17 --- /dev/null +++ b/doc/html/_me_humiture_sensor_8h__incl.md5 @@ -0,0 +1 @@ +4c0817460a1f79c5c2cfe04b1ed19a08 \ No newline at end of file diff --git a/doc/html/_me_humiture_sensor_8h__incl.png b/doc/html/_me_humiture_sensor_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..535c748b8ec3db98a8095e39b5912f2463b32dab GIT binary patch literal 46611 zcmagFbx>6AA3sVXExkwyigb%~C?KE+2vX9G(%mH>QX!Fx z0H5!@GxyG&d;G&0=IoyHJkL8`@!n7sB{>4zN4O{`C$;{g=_2AA^GO7)3$mV_0Ln#RnO%I5P*OS2ocn^tz>sz<6;8!DesWF#tHIx_~i~i`qtuiuA zuZ^OBPs`stoOK!&rxJEF1#Un=&RCW2t)9G<9}D+w@$kI zzY<5kl)3w&+gIs*oK+zwbAOpWd_VQ%zuWn~v25Mljsg?eEFtn#7O5^2^$VU>A&a|FGm}lZGhUyqh864vnHd>J^gd4C zeKjrz@GLCi`}abhimxMesbMN+*NL)iJ(?iwnH%Yk-?9BPqdLFs*LpUU>d`_QSzRjJ zbm9KOPf6r}f8BDcbZ9m%-AN9sGoJr;g*GcBz2mBbBZjg$7+(gvR`lGjo}E~kpV4Au z%H8Ji`5$$&e$Xp4;+Yy*S>HOCokwI#{&z#5Iq<5{s71`|pJxP*=Osu|U zHc$>mM(KqA1=X}g`qkV{^R9&X-`?o=35;kEtMXQ8ie1~;-Aqm{9h+^`;q_82>MCtf_i(y&*S4+yK1AZuLT4Dq_Nz`WP2&B z=Nfo7NPsX&x&Qt{bR*Eh?Je)68MZ3Fh}Yv0Np7noFMg_%R4?B_W*LdDo;e`AJ2fW7 z`y|t?HV&s|w|~;p34L-#4*GDPfAtfvDE;Tlb}4hVbR2!{;+16!nC#Mk$_3hn@w=XQ+)yVE0 z@^0vo2r9c%LJ(0t#9qUcVxSp~6j!UjpF&Oipk_Mk>iT^ehn})i4V6Zuym!L1`udt> z0nSXK@}~D`1TRFCu$>5e(Yw^Pp>XW1*~4LnBzA- z6jzB!;KJPpen!8ECVGaZ;D3|u`y+?xaQz04)v79Ho6P-RFYMqaX zE%wQ+GjWAqKTeJ6Pdn0+<|O{(Ax6j;Qo`RwNP;*PYeIANd?Xg>y^^AynwE43og7+3 zbomn}ynXVF1%6iV8+Iy8b^v%7x@RFN^ z#`v-*jVz6WDc%(2P3!2T+OdR)Z^un|SclLGi^!LsCSlOXH3fIA>^w!!_TBZSD+3#r ziYMiBV&F#bGDP5kD;a3ak$(o6?9hkNBO#9>UPo2t9n0uL6bVvfWIRLfOHf~vwgNr5 z&>}hv#n%GXJ>EUx;77-o`9qCJY-tEQH^0Dx>m}m4gS(h%M#}8oYbqG#k1mhRJ3zA` zo@3-2di6x-Ahr6Jo9%aAt_Pr53N+ye^y5L@Dnj@8p;s9`bnx!}H=EkS48+9$m9uFl z^O5>tqQenbr>X~}Gl6zkSHxQ^2xlYhvNAkbPjWtMqa`xS*_nJ0HDmwsW3PWsG0;9?wp>v=$8e^{_ zV_KnlU$4bgfq-mqptUa$t=;i1=GXbMOyEla9fAyH(=C0mE_wQXYShULM^cO@Y@QWW z0#gVn2TzN28vbJJRayR7xP9S35NnIxJo%LuL<{Tyc`1c&*`dApI=kah2o$1KZA%*& zo;Ulotw>EKr~SV@omX{8-;H^*rw3OITrFkg(&y<;+Zyy)!AVEIL}_Ts>*X5Ic!%p% z#a_Mrxk{87l?kE*F|nN^<=;sXoTiJ)DjN|Qo-Oo8e}NYOMG5(-uRRfV;HdM!6nbDJ zZ}JvmQcph9{C*d6YNFrr`FQB#M!a1kpZTdYKRv&!;QK&#!`{Ir zS}%QQhV1w-ZA2t064c><5u5CUTOo-2DXM^{MRM^Vv?#ljY5CDX-C|nc7f=WWY)bLL z^LS_J4Y9`<`u6TK8N}ItA_X{MqqqSwrab>GGj*hldw4vD`doj0?3W9$3wf|PNm7bA z>(_IJt}f9-!>*CIUgxl_peU#OvB*M*JKO-&?qY#6blKF*Ty*rcpFHirG0cafTL@ga z6Tu4#alokXS*w~Pm1P~cHEVD@_1W8Lz-yO zgkNSPh)k-}q--KHT|^SU9a7%+kH6C9WynU}8altll~scmv1ftlQ~ zldcyNRDxKZK0R3m#r$L%Dfvi&L%Hv&+iseHs_= z>cSnQfX)WmMjYFTW4`NUr&x)$z0bL zhNgJVh(1j_9A4&dwOFk%0@HMB&;*MI_LSsA;exqQtNjCMu1SR4uwXVmwVW001r5V) z_|nI_k1-y_G@8;PIZ{HTNVm`a6;VX9{D<0J^^-{O@|3wC3lg2;NM#hLgl7SWQ~U58Xpmr#F&aaiKt+-zd~~su+F@rxoXQMo3JM6bw>6>mY^x9kf*+!@b~zH6K1nv6&d616z*c_J+C>BXx%~UFVTou6nn?fv z0Q5UPVQ7e!;Gm`H)_;e}j@n2&tB1?G-6MOdpqcaih6BBk{0q}uZe_2%pkY*?l&Y(l zCYV{xrKwEuKaZQdSfE2+Cxkfr2K}IisQeP@d1U+(w^2ngW9QjJOSaeL!oRh0G;#?{~WgU zwIp(08rLhQWg&{`b)#rLs_@z+Zb2E>@^yh`8o_h30q-2)6$dEViafSd2-=wx9Kefsv5M6gD2KT#FRI0rKcymop0jNp+u-ooCR4!F z>w6kdQ)pS+hl%#c3{aOLFf8`D!bbuT23G8F zl(P=IN?h&*%T{#hZ7*NsSK`a=T#|viz+dp&mU7ilW|i6Td={k|jMz)lCJ4G~K|d#H zHK&)pd?n`t8AkKlZ8leoP1Gq$Xc}bny@}{Z-+Y zAoRxXMSX!9snx_#LtPw5rmT@L#r{Wwi_iYQc$8xM>1&Vc8=*F$;N zw3)xLZt8kQ$H^?PlWx7}w!5Aw`%5bb zez|sEJ178fXiDWwD)W&0PqN~Jx|PBd<|)x=a?TOu|EdVe%*iTh8c#z(Q}6XuiWAHl z`G?meNxDC>4?VN66nI={)v5&aVkX(T~l~;oD0ER@D73cCk$vR(J`~Uz>8B zK{P5rCFgFWe(RB(rHtsocjzzLw*&~MyoF`m3=;R@2zIYxAjguv)(zlar{S_bVqvEt zJC=VjsJqnl#XOJNn?ML(YZVy-)@#h(u(S$ol2F)$Tb}L#SS;dDqrxIU-BbxPT$sHW z!14dsDAq;qqvO0#(IAa_aB4U;-JO52SbTconq1$Y8rT=1V{IC5GS* z>h;u^%zD;(T_*S1cG-T=4Qo*Lki6iS%U}mSO&981AC94!OSBK)h_RUzJAhaM$;fTN z*kp!tfez9`rd~W7Gp4h3_H0wp5c|i$2S2GJ1FHLt-WfjMIeMV1sqqoyvduW3dB>h| z(i1D^B!9*%&#r+(4idX$eLQ}7h^>#>Z_xOrRpIyi1#= zd`B#T`!dE|y+u(eS7`7`__9CGi`Z`NE){sId`j(kz17(kZwwBOIPtF(TJaAIK+z%+ zLx28rp}!s~od#l={b*)+zkHHPS09fuj0J&}{#N?DCho=eTy{wQxkNja){`e-L6wCe z7?|RiZJpAb*0GECxGdGW+-Chz^bU&^as_?GJ7gIBhVOJekH%JC=+8Bki_M6S*~#fQ zLlAbIKoB9gk}w3l*^J9$-te8}^W_p%Y0LGf`+_RNQk}deGII6QcB{BeY&(wmQY<7L zMY4#sYT(>)$NC$yHzty5hy_~4mBP*Z0T(oeu1e&A`&{HWwT{RBF^N@JgEdvwe~*8x zzbp4KVsq|{1FBc}qnw+ij`E`A`)&Jx!@x7f7w-**(+T!+5|%zx23Pdl;pE-TCewey zZo#|1=M-rgKvT1sY5we1%(MLkRxu0jKO#It$?YNL1esBp^K2PIQNfzrkJs`3i*c21 zh#t}7@x#CPGp>!pSgpb$%PmyqkIWd&4~VpQ+v*Qi@A|rT zIz+ma`j0KX<3FX1o~87l5;4MV-r8u1tjJ4*(x5IQ0v*;r?6QovNF zrDIos#q~ledrc#wEw5MUdl6SOkXCdi-#b3Qc|$fQ1s$5toAJfBHBoCfF`b_xqX(JF zMN39P4SxbP^j2)~)CR)#K_i_B5gdBy-9|kw+HhCSQ0vjVA(WrPIEZCwr#0e{>sakM z^EY<1bKp@d=|m><#gZU;a!4>F!Ct@fR6&hYU8Lh}fBc!e6LckFRgyhmMgvs<)h`>^ z)p-9NTlN~a>|(9|A;Z?E2g^GmaDI^6pZ?tUFRaD+*JlyJ?N|~oA!G7&QAa7w>eJ$cwh?G z{Rh)dvKtx_@D;27eNFetXv9uk!xOojf2#G}LJ7@@5FIGf7F=i8NFijRa8yj!%I3lv zl?@e5@_js;DqOUQNyT&tW^W9P>dSVX;78_&Vix)<;60mN%qq#Rk7a6|dbPm|LCtor zuvUxdC|;IWCKzAQaV ztuy~k!6)$?n!-z@qwux`kqtXNUWPRA|A7f$hXVb(w!zm-94 zZ!=KAA((0vl0M&9P&Y;Qy{YU)HT5NF<{v|-8nr6e82}!#dTIu@^>XMmTQt28Kss4v zayiYg@{>yf)Kx+!|0uKrW8_s4qn9|)HSCibJKb*ysF?go*Io+nn}!`|7@c3=EJ+{de1!uocrTx%Bg|Xv$Md9A%X#ZqTa=l zhpV5;IhIKAcN`l0d`L$xx?HOyR&4j4wwJU14Z1$$Ctkl5GN|86CFS10rZEv~TI`zZ z-BpKq|H&IObphJF?h#J{mZaE``0Elco$fB&4dCzQB z5B@D=-=7ix9A_H*Lqu`F{9t3A3rJFzr{l$Iy^mh2IFi##32T>ZQ<2*0ayoDAhFm7J zEodpfE_JsG___sSdfCuFZ=Kmqj>39rzg=3tFk`3T*9RG~_0nWgL79u4>{l15(mQ{% ziaYF4n-r)DC8lr;qLQoGM8|*~fTC8!%#oJGm1={Ht$|}54q*S+5!F`DW&=|Uc-(g8 zR=zy`=XTR}sA&Y!_d1@o@PjW>-c!t3mAb*GIJ)mmq!}y6pmJ z|0=UeUF|&mRwslIuhA^oW7w0~^mK@_Mrg^MILT9CtX+Q5ZPNg-xpi}CQPJn7=EcSy zI8R=`H1c|O(nv`x*v`ak{GBfh<9~8*=5B~ z%oHRSNAd&o^wca9j#lRY4@1L1N$~Ny@K5VLnj|0TZlAWtam&W=tV@4wGliR-bCf;*a%tu4ciiT~k+lr;*Sm-8X{`REWS^2S;VNsDw-T z)WWm9vqSmbFQRq}7j*x`mhc+x=;RCTM`X+}>VRB6(K^=e2N_^{6J@tF_4?AdC@_xH z->SZ~vaX@QG;o+5uP>c)m8a`S{%gGyd_8iUMbar7ok@=-zu{*Q6v_zF5TVQC_4)ib z<1lv5SF;VbZA_kCJ?)L7IJ6S79p9C^eSv)_7{@MVVe{p)V4Ed$9pGV_V*;V_&P8vx z$l)d0N50Yzv-zAU5}3U`aMuR8tK_oFl)uKuIy}D-CgR0V&8fGkWfB@PFJb!oNiYou zF6@*>6p1iy-XCFz;<|2WPJi@rJ@D&YJ)s)u-}JE~I`w^E0lHjRDwtvPV%%t|Tf6ie z_A?`OGgLhG|0ED&qka4M8=m%Gj{??L34Fg$Yhof1?jwH0oq~L=>N1|`PBmTa`1(8u zZd)+~5{xO9@Oi1xhSt&ESzX;gUBvQ^I7BlP0#X@~)2RrmL5~MHq6WYLWG;HMj(}#p z)N1Y<=oBj&^O-s2`#wc9Q6X2|;)<{J8DATmK@$^d0N_#c7zdZUzH0e$s<`1B4W$b9 ztTGdp(Pu)pM$E_S(FDXN!M4}E<6Y8(v=3e?i!C)j7p$fMS-@~=yKy~bOxXupnttzu zZ9_XCg8q2>V2l13eE>tz(uHvTB-mCS`)PT{sG=F3q#>1|F=F5L-okwcjBYlJi(3FC zExXJ{=N2NseGT2<{NvqqBFjIUx~(^{tF1SWk0)IY|LAx+Sw}BuxYX2+kxdhD3VRPm zHqV`{f5*IJ1wn^bP)X+PVOM4ZZ7gkLCy`Arq8G+=0^a!LrQKSYe3q$6hua6zTrMVr6%>e?8Pp2B;#T(& zqTIL~>hiT36;=MBg|Mb)#8guhij~X(3VS)q{0(10k*hd2MphD%AMXlj`nN;yozd2t zp{Bk55-3%Fg@>CQP*sG*{;r^B0z|F)r!PM23S#hS?N`xDl0)Yjw4Oox6C%CYQO=J# zO@6bJ+jg6SG_9?AiaFflWHZZCWi+_nT}vZVuP1&{w>;lyl4-I!{P$?FKqMj z&u_1Kp92)jw*e|{yNlPGu!#BbOHfkZGO7UG;+=%?(QG8{aL|?)g)k*2RZ0 zRlxJmQr~;8o5<&CIh@;euddF(&ZdO(s)@bcCHJ^&&d#c)>elnc3cjtcz=09D_k!J2 zS-%%?)>UH}|0cCVj?SMFAdBChc^mQA7F)JA{Y(qSgJ2Wf59rT(R;KfO{&VOrp8w4PypYw? zaqA|Pz&=H_cX=1BN8uuV6@W$)-IjopWS7`Dwi|(|YXQ|WBk-l<1=MmN_vLnkz6jguYO6p#0SKzZqx%?9U`6_Av@WvvYI3{QV7>aRHf451NGHWa z=fLfQoZY?ReYJ3BfKoU9TH*s!qMOXLywV|Y(Gyp{Wn>igDP4VQisf8&&Dmvz^)_@F z&PSUzKJC?$M>XGfFkbrF?@i*j5j<2reGQ%*bYECUodUrr9 zXYupq!06oIIH(aqj^4_xoD$Y8Ar?1KPV?O@@uQmcKz5mer>1pZu0^g=x^exhPSqRY679csqMBY1pAp@Gni1|e=BxGzk;z99E*8E@?29GI=614rnzxdT zXzq(D4544Io{h&&J$XO*)F)$gK7JG?1kf3&qmWaKoj*o8oP^zM=szENccqXJx}xy_%NiqakBQ;-sxdQ zR!Ik#D;l%?*1G>N`2=dwFg3bQ;{nfT+!5GMtc-(SO zfTv8$AsT=A8@qK++J8JKVz-*$kO}uk(5DJ!D98=h z{Jj(mNmA9bK6*bH_iit@t-QVpzc(`2JI_2!oYLhTU&Wl3@lcK?mJM$~q5NrDDa;ZL znpmCQ)U|HSAac$s_NC2F`@Yj?QUlBrvtM)ct-0R6J9b`)rB^ zb~4l|(u#o4VI}?pohC=3;SIoPtl5>%Ph&?>T7LhO?lW|+_tF@V3+5KzzcDVRkkJcs zera9{qtL{UarxuO;_z6*!I;Xm5RU3o$g4(T-9NQB3X*PX`Mody`lXUUN z>uyEi+dJ-^enfMYu#x?s#Tjc|N1e=8Y8M+u>3g4j-Kjd^Jiv%>k!cjLnD)ERm?l6j zdaVpV3va5PN{#FK>fktp;l;d>++?zbOCMhyI^3X!LAD%WGRB76-j3@BteACdi0uzKtT4G8$PhAa8oPl zbO7$$5Aw?egjLY(D+S+Aso>Mzb9)}_hKKG8k>vzyOxM*h662Y$)W66dqx@GISP_8a z`b?hpj}hbg4-0^n5Dst}DpdUaiDspLb6^v>A{qr<@U8Tc{rgvX3fHK}>twe`%l6zv zE#8$CQ}~q2q@w=%tC#ysi^su66~FzBDqydN2yf9p!bZWywExldGDp(2U-$TX2S3B* zIGo%3a$HTUnib0b@rc*`*8S?zC?W_8uu4uoJq8p^){Ukdzv7~zI*q%P~&2@KFhDQ)*@S@94zImV)hi-k#ck$k(>c9Kg1LI zp@?F-K70|q@Cgo?se8=AGm)eEJa6CqGmo_g8Dzdcfp<2QK4lM$!Qunu>_)-B&ugoN z77wpxub!K>-jKv;>1vB%-&OR*@FLJ{Uw-ue_U9;p;42hcM>IIaPz#PLt-Tr)+eof6 zb?xj4<{3B4>atL1KlR1e+Nlt;(A?SWFI2phJDO4Rsl3sJAenTCi`wqvO!E#MHJ~|R zV$KnGC;zx9Vy)~EacXz(Tm9+2u2}i$kC{E~GllumdhkX58r9 zDc`!jP~;ki;|cEB~Wg7TrP;#I*=+7pU>f%xx7YE5DI3@?lV&8hc((F3Byh#)Z1g-5su(M)kV_0698 zp*;=}cuAKKe@sfxC1+~YLFQHfvQd%~!FKc-a0mWI^xFGr_Dwd(v4 zzLqd`MVv5xajQ~%jtCzT%5VBzl*NTJ($V)_)G+x8W`p)U#0HC*n#?6PbMuy<+j5m-K=TpgGt%=(H@8ON zz6<gQ$_JX&W;hrkG=f*=C6@il_%XYVX`{}=l^Hq}2R`Xi*}9V{R6OehG3 zW8ngRE+Jq@26d1^HVg&RU~9ulRVErEQ8-{xf87Y~NwOLGtTKiF4SHz5uN-me^5bJ4 zP3ZC8B|L5uvjIXwLj|I1_?3#k2#<3l?MK6AzHqz7C0EpV6*)_{pH$L6|5 zlQxbdo4nx6H3^c>Ub-aMLw&U5A~kXp^=%xL0bwd@t!!NuyBh$1yXM?GQv;i;vkIQ< z1u3KYqKXlJ^}ZWvqF$-f{D_z(k1#Bv=Euh!vOGEr3z;>hXUNPjo@LuP@M(#Yo)a2d zQW+`shoX8wo@Edta6-nhlz)Bn$oibzO8)83D?q9+Ve2l16hZ_l^%`~C7iFuY@7m*` zmUbueBV8gIICO4}EWzTtJ>B7L0e6wjSnI%G!Z<&r9i5idhl z%{j`sYShKkdgqr15S)=JQ4@1J-oI; z=Y>J9#j6~z0F7|oQh<=8mR1VhI;Q5}4F-N53Cxylm>$HYR#vRw`dO-GW2ck8&05B9 zDk~nY=TPbhY+#P-=K?N81+Im^@6Jm2^`Rn01VdtoO6SQ9sh<58Tlex0&pvDQ{| zp5qz0y{VyhA+vaZh&aNhO_{BmGC(^=x!e=yG*|SXy4LX%OETbFK5!HseD(ctE80IE zxZ%i9pWw2XtO&|SDvXjEJ+18VXRX|%MGL4~#2|z9a7h!!z@$3`W4+3~)6HQ8*9j(| zwGEY(E?w-ro!nTXiATB6k$-QY91aYn(uJoH7?hoSF#?7r-U8~U8Dc*hc9$O=s);1P>g5W9C8F~Q#8X-(IB&kyOO7;n=6nrXgcW3)5m z>88H);{hm8onL(arh8hD z0g5i(*b4!N1)w7r3L>n^t40D7qL$PkN#6|MNdx|} z2U_7Y6@vmM;)subn)Av_usW|+?c@_NJ?&3Mzs!hmZDyMWPo1pT^SJ@WCZiYAD|N5F zikPvStbVdH4~+UwH9(_ktC(hBX;m%YD%X=GdO06);pNETX<=6PUKb5acsUBz(Ft+5 zy0x1Y61ho}0WRqQs9bNOdaRK2M&5OKz2Ey@dFZIe9~wLP;*`Jy+8%aSt^| z{6R=wop45M)T?KX&!4!kLV7Io6?B&jRqCrJXAEh}JyMljKOv_ZDmH0J9$fKMm*V8A zW1}%ib@m*d55%G)P5y`$mvlt+B%1JaN96mb)VZqfNZ$*4VS=~TEBw!Yl~2{@&nXg%Zo+tvce6nQfb#J;9FdkM5Z9U2DJ_JtSwBf25pjV-Qt90%^jLm z7}dNDSL(afqqcf%Z`6FUl~D-0?c6qOc#U#8`~9RK*=-SVlK%eOL=2km@C>CHjWg#0 zEN;m_6a?G#di03Mb4Q~s!mh!I$$s+L6W=@Nt<89qdY8&){ZDcIVBWm zw%Ifr^QSwPuP)l#65GYr^P8Nokypu#&5S7~J=B+|L|W=PmXxMWb2fcojTe(6LopXM z4hMCEN~c0@Z^Y+6oSR5x3x{{=QV{0G9GnLN!1}Ak_a2ZPEI;5$0E#>93Mv?T$lY)^ z#KW59#;2KS4@)xo@RMG7E_j#|Fm(Zvog;Zq_;$mYeICJF%p;r;%nO4jca(IJJa^DZ z6@lCY>z%!^s57*7CM z@Bo>-2kqmPa;*cCO1s9eN;-R*btHlmLI@Foqed)JmuS_0?+N)xddb;W^6`RzXC?xW zn~$3dtVq_&??fnh9qweSfL9UCstg8`&3P&daEk`s#SG6~IU&2ZyLEQ19Or$IHb^^< zuT_N@Cc(7z-#K#fqwC5EkO6_A>%S5ru+EEB$Cb{|8>@kP5V05Iq5UHw|DPo1IXR zOmJB^H1AnaQxzs>cx$lIZG&Ja0#Ivx`b zgXa#rZU933y9qg&FVt^OJGhvABNAP3r=U}P0q{q8hQE_P`;a^KDNJP-uwDTp#Gk%K zlJzq%???e+7E*j}!p2jzt>x?%58^0ft@4xAcGDR(bK~MaC9CLPV%|(?5HGTM3`loi zs)0F$5`*FOR`s4iEP7ggeU$IO2PBW6G@o>sYwY+$MQ1p@Z3~s6c3L6*kw`syF=vR{#mem( z?(}sk<7I{P*S$v|FBHKdZe`JRxA1aQE{O0jnuhN`Eoa0H55-Bo+t@JRRl1=o@i*WL z^=2-h`D*b`(?wL3xwq0QKElp(ZYS@Tam!vzza_>YvyGv^+&IMw z*T=@1_7;{MqFe0C^F@>cez0>%B@{IDU3T%`)7zQf0xKIeVDLNf4KL}b$ht}DZVgDX zAk9=+PKPR1@YKlmlF(w@9+9(PE1&u)#|PlUUD;Dbbpopj<@Sht!te<};$6EVo44iz z%SjMTe{uiUhDL1N!?$`oGUUv^zao$uU`NMZeO*n_vq( z#S3nDXgjEcxY9~V2F53Hz$(V>QXAh9Fw!O`#JB_zVj*%S(BK2y?aYGB4Wb1}ig{M& z>^Vc`jA?ij;Xv1q?t`}_yc;5dg4G>z*r=3Aq}Zyq9G3IH#_{r}i{DRT?Vgl0(rb;5 z{icityq+gplBB(t&T=Q@?m`n@T%6o9(+fKJzoij*n{Ob42>G1 zMQdJF_|O=(AMzn%xwL9P@j7x(G!2w#rGz5$4sOS z=dHgT`fjK>xt-#+mqe=iO2pWu8SWl-w*U%Eo+v-ywfMIsmW!Hm9iSUCga>R7oz6+^ zl=3+R6NTFtlh{97C;j&-WOa=rVjF6gWv#?Te>=cR>-P7-t2~b;#MFBTR$vHCd=Pa0 zeJUtXeMch=jw{$E{<}^o%rxb;%|*YoJZKX;JM*qD*LOY z+}6Y}!0QzW_fs4WjkIillh3;bQp8NNZ*Wcb_WiS{^d>p(@O{7mHhjB9L#f5AsC8b` zDS_z<3y;b`&AR7g96V19(1#rkz7>!gtc0`9Ku%9h`R?Z*Fr$w@uB)9Hk#>fmU7a(p zd_~95*RF3}qgt9bb4h55kLNcL4o*9$J7rvT<9{@!_>ro`5w%-JI%29>gM-F4s zN?ken_nroJ3VVg|r(VJvP3Nj+x!C12J<&UggEZmSH~#*vJy`(l*)^~-um3IIr1k?h zacnUercrV@H&K6@)sYLy6e1$AS06HsKkT6#=BK#OZ)}`XKL59av6X>N!%=X^5ff&NO zii>$E8B!RqC+v2Nc8xVhE7YE>`Kv$R^n%|>b&^(y$j152g<88nblZJGKm6ZZg@a+7 zDCGpjY}fnAam^Q^6h4nCn32z*^mE!j7yFlwixvB0+R{Z&P*XTe9bH0ONwoJ;Setv~ zv?RvSR^=Fco(#{+{zeO9uyP2Q8EL%M(tJ4{dVwlSE*8bGyor?Z}sN}&Xb@h#s z8(f2zLeg;Ok*HZ}7NSPNlVPI%7+=H`HUEld4*EcVUjrBU0drsbC9E&;+PIs}B!c%@ zl$k_yE7>VSg;~bn>bmK*OcC>JmW35GqIBKfW|I6S_|%x&Q5#3nx;Fh)EcHO_~jia|^D%_pn^tnPzl<`NyT7~Iuv2SGxG3vfKhTz_mx6fvr8-GlVPY@}g zm}1ZMHhCG`vZKir-EfV!+EaPE6ddx0F&#Y8JUD>|v&q8t)4-Wb7w{ z<3G-*z|~S6>qH-C9te@hw-h1PFO*XVvts~bZaqOhw~yMiFE@}~NK3AKb%KjgfPJi( z`+zHvgZnf!hF8DZIEohvim~WqKVoq>6F>^U%TRQ+X@5rgBI0c5?ZVR*c&*TQC{B5* zy#_zyAmxWb_Y>0SxRZacsC#HF`PJE&6)ke|+kE9x#=0h)OJ-Yzd9zNbbB(5|b&rK3 zg_*l6$7BBP`mU;uXUI|~Taql5Bxi`hHR(i`vsRm|-V%qCe@A7k{4uxUrleo2n;RIz zs)U*MAV_}L%M-(>4@t7&WP{SEU{$ZWNn=<5G2!Bvsf%Osm8^F)e;r7O^Slxtl-sX> zUN}CDuc)yFti)trCZ$pAJ)G5{vBmtS*pi$6^w^)ee=OxiU5>G4=?-Vo26eJg(4!B* z7cw5drvsCGw+B_#b75c0`KTIj&1m}5{Zr~~S2CH@m{#SKe4;!NyhxCq-`Kh;K9 zNW?kJi(=kL3B90*y*c7fpyf5I#Ofb76Sl{+m*(gt!fj=$R(H?cdBUZplK0sAT~NKQ z`@;mLTJn9l_5*&}6t(Iof|ntN}kEie~U$5Qe1*vrNKvv*c_^3 ze1?Y#M@NWgU?dH=r!B8&`)kim`}SkIKdS1(q#={`!V)hO()L926}=X2LhTJ1@UO4j z?W>XY8A(*=rM0Y0Z-|)swAmEV2^smPw1b-g+%RqFN~mY^#%|KgM;wFLrEers z9lrA+jD6oFAq|i8e3~M`M6wpxZ5eHipT;h;Hh-#_NG90>3?6uwKYQ9fc)Zt4qF;*r zbD8gb79>Q914R&VV4cevF2GX&mPO0Q4f_0QAG_V@GkNGH6C}!*;jCn_(NxVW)t74( z`GDuw`?e(ZZUITtvi3c+(ST9^RE$TuS|2p}rRyUTPOe~oygxeE?i6wkl7!%?Pg84^ z*}t`s*SJWfE+Tn{WDge38Z0RM(R``YmuOvepTN?2+@n6>;b)lkTu85;rS`RVu@+ab zV!@(EHUEapp*6Dd2+Z7x7$Mq3s>vs`4Kza7Qz&yZmPYz* zHA^4L{wxzBs0!aaeOdcpRM*VWM*fkve7V|^=T-27OfC8ENYMmqJnr$Av5rv?jQ8f# z)FXp~1uwxloz4Ln4-|q|A#&SLtN+acWIb@#O3$hYV`TQ=BD*^G=)IHv{aNqyZ-Zq+Re$8A0Ex_JfVWiH`nMoA9!sUslR- zHq&90g_HEw^HA;t#kjRPgYwV6vj}DjUkb@B>C`fK@aXW0=CUneFry^kfHB0fkttVi z8ky5wNpZ_3(3$#LIb{_;3cXyoI;CEJHLUv>4NQmEhr9T5OXg{2xQc6J@ZYEHPJ6E| zI)=K^;YBcW<#)xS`_0UK6W2q(C8Ha5o^>W|@X;<=!o}6;P$b|t+BCG zHsBX6ExRYL>xbn{&p?9LZ+F$-^}j<}$-fy~Z6pS<^>ZH>aVf9z%?oP}{@JdRy^(@D z1h2B16>3&fbvn>;BSD>kI`#G%oB5qi8#Ra7C?`dHm6ER7NmW{JvErQSau)rgUZ0T? zPWF7M8XRcQ4}I#))o&f^Qsy{!sj$!OZ~4kjWz|s~R#N&y?h;o0B)UQ3D^it%h4MT# zJb}?663t27BZsB$Y7fXu7@I{EypSM(~@yu5an;z}liObeSsO{>+0{btrT zHsb#I>8Yrc~&+Y_ZMm(|#q99v}w zhzvl<|B%kIxwJCPGW>Wea-g(Qfv;y*_v$%-YV?Gn4kOZA6(lt|@gbewX{qYpvWi`l zRlS))Wp* z=A8Oq?tbq=%u^H=&BUZl&fw^VwkZ2gelUxDwY=3GVnabqq3tV9G5!WHRxmeexBsS4 z#8AD5fqp@es>PM2&?6z`py~iU6*|h0VEWt!yT`RHt4;k4JE=kRxPxdfzNrdqDeSD5 znEhc-BA1ZttwH178J>cg#*ljfeJasfVfaPk+n~aY<;S`Y@f6-|)(^k^XYod_Eu@RQ zs3mm2ODmXTkAJnUX`Vt)yKOP%va#L3y?)59OVb_I=;=etlWo6n`wsww++5#dbV$V) z!}w*)kTgHNopt1yh`Wdh!&)F;g_%;dv&Ozi>Njh0DhjGs`C4<;BsCIzg4srf*T?R= zI++?CzgadUdpZ05)dAbnB{zvHGuObKk+EO%QV*AIWX_7r!(7l5)YHBPgDm*1u1#JC z#$zT66AKZoei-Rq9?#;KYl_Tm)k_j$&t%@d5OVPqXQn9XS8p=l>m!nVfG5V?3HEq- z=H$2buyB%^n9C_>6oF~x;Rk*3Oy|B|n<_lboP;})f64w5Hn1i|jQv5`(8`=^_??un z{XC4Tz0vIF^CJO`+svo#;?Sv=Wo~6UH#HQ5+ZdAfSAC!=cFZjxE}e8z*OEt+8*oJh z|6NO?VW*kor)d}_N6UJS{eQ@M>!_%{aDSL?5u~N0yQPMd?jE|7R6@E_K%|ixy1S*D zaS)Ipm6C1|hE7R;2fp{-wchovrOUs@IcLZ7d}{A8Cf5&aaJ>HJw0lk-&VkMxb42gr z&=4NcE~#13O7Gf@wq=V}7WTds%aKro+hAde9{Uajj*A~aXW)LOV(a3LdUTH8vrixH z^viM3_T?XfvM60D5zRFpOOBnisfgxRH2bwmLNyx0-Z)3`RWFIrMar(_=6*_LJf&Lm zqmFWEgvzbf203}^r@CZ|QAM7*xnjy#`N96%^rUjno-0H(-x=H5e3L-Q!|Xv>G~*1o zjL*MqtaAmLJ9PDHz<7j~lU6)p|E}tJll`67fU=+J88-AYy`$olZm(m^vf=}-qZGuS^x!#ScR#GQq!Ri9WY|47t{0>-??qx}i6m$asx)xH)Vk zYUYD`Wh^S@yzfqpn!`Q?t1dwgMpp$)w({01NGbQ=kK~$P4jn-s9l9eHbaOZVwmDdU zmK^4q!(J@KNw}rhm%BN0Z>SCi0OYmnB9luc``3A#tD;%HxFP2M;E)(A)$DP6z0UcD zFUvnVR_aoZGla-t2Zhz1eK}^D2LF*y%?%K|CU&aAe>5 zd?=WeEmZd%dvR^@#)wQCk@Oi+U06${OEar`$T-_n#ZlwcD_?#GDLMS;DFku&&CZ+y ztQV5z_Sb1+E3oc#H_oM7L9R`dG|B9CtVC+GdQv;S?;o<*4`pOx`>$JLp_0|@!nXaM zP3*dQB4mH5>NQfBocVAaSiV=)wBoXyU7`%;qbZTeWr0OoTV#T^4Gtoz-7*fc*?+UI z;t<~NVPLfeii^i|D#Rpb`6#U-+F}#blkB?U->S73ei;Nf(j0Q*I>>kp8|-yZPe9jH zK72BdBO0i67N*SW-GHztg=QYfYUGWH)@MGnG^MGFGmVmqH*n~vL0 zG)NP9LRne*g@3E3LAqk?{`bXqijGv46isK4{G~Cg{N`QE;!FeT`sh~HwmARez%awg zbmc9cJ-s7(*08J+_`C+`5_v9WlbUxFzLN= zM1EZzrU@>@GPo+PWWt&#nu8yNs@v;;9SI1QSfa3(;mLx5JrVf1$!Mlz&ww`-djK7M zNKy*zD2CHI-`a6mzIU1rjNr*x#5F_`yLY#Upl$71#MdgCR1JMql0v0!=5MdNTDXXdaWQLgyg|sd zqmjZdKZn;!`wEjL?F4QAT(Pa02%BCrVV4VeEsaYpMcZB}_m0E*RWGw)Na^%j-;6$E zOAC-M57Q1w4kb$b=<%^mlg400-<>qvRb&Y>c@!uxy z)_Y{H6|$o72e=Ze#ZtaxShL~QLEeLT4Tj#&U#27YPpy6`{)w%}fJB&d&O2RU0IsL_I`lc*JnTf)?;>+h-ba!&g`puOXbiq*c`ojxAN{K1 z`v&t>KTxw;5_Zm27;DEXbu3Kiq>jYMdLK&OJqJ}BFZGrwp$c*0Oe)KcQ2!_snHkbnBE<-^@yaIX4q6E_#}jm36h;X$Npof$HkIKSexHi|_UNs~6LUK!2o zj90U-g^$U%N9P8&F|kG}KD&5Ws$BjYqV`)th{z z3r=kVNb}%)qTbJuT&z@Ra&cY`AaF*~srTQGZ0ntxM+N2cn8x^-eT|M06h;Wyt$^956D$cTE$61DnM45w4uXo4Q_DG$(5FtKKnXa*`W zxDs@sRX7f4x!_2D{5_SQ^)yEB9RGU1*Pg(^vXnRi|q`zdEcgvvk z_LKu-U#XqB6t{Wlx&85{pZz2#Ul&L_{vtBn+tM)m5w2h9h6x)n)Cxj?sjRNykMN>H z&|#*UiQcVr#rJQm2f<6H;RC)HxQk}b6^jU-`)grsFS1`xY(C+Hg_?mnve?;NU9_XY z=~HtmDZ9J7OqH452{|0dRHMtKhGeELp)7U2l~q-WRl70fR0|wzW#J)N({Xb_ZeP*K z^lVN;BvP+D0vyw~fZq(o()zH@J*DwmcH*!L{lKKK!$bd zws988l>dA*)N(#yZ#7J$m3u}Nej;rh5yU2B)b$T@FrDU6MM$Ti;J3z7q@IRwGfbu` z(grpyELi`Z@(`;k6%gBRBJ$sFHn2F%y}T~^)p&Ez**MHi%?)F>=jlF6S{atbm-Zdq zrt)*lH)m-tm8x9`z3<9$>JFqy0Dn(Xl8G$10+3LsW$|Dw>hW>JKzw20ymv)$1T>rXCPAS6&F zC8FgtbBN?W)ejJ3l?8kC0a^BXww~p0JeDW7IIloKUw1T77U%nNH;{{t2a|y>$zb|& z{i9$4e1`!8@k4nB>4TY^m9Zz$@3&Z0%Q$Cpx}w1*birsnMR36%;ZObu-T$YN0-q2g zj83#=6TSm&0$^EJY_lf^87dD5KZXNP03SZX@qeFD{JBu;Fg#X$DMn_cb`XPZ zL*Y_{B^-(HEH-dWQ%kiq5W)S$0UjAO@8|oUZ`#2ATq|7k=ir8Vspni%X#bCEV~%DI zC9r@Z|K-(K;d|udtn}nw21vHjQ@wymk;X#ygSL}~jcGRmf~prdit|c%I&K0F_ioS5 zx_n)O+_(5B&EeC~n0S|QKto&yXFsTJSOOtRP3Gh0?D2eNUmnMC+(RF0N3}o^EOnn; zgQ9w~k$G_b8~p}R*PDB8McUDm8b{(Tjsv zLv1o)+rz`{1H*==9~w*}O!V5ifnMeVRO|Rhh@qz8!1cW;b@W35AG1`H3sMV_0Yo8| z{B=Yq@&L{00a!Dsm%$W2K-jcy(1)VRo^=I%rlbDXa1Jzf=hI_J^eHVWR8#EFnyI@i z&8fWO19b)?Ru+Qm_GcIFTknoR*XD{{_I#(4p9mQw?V1|Tq&Wx3fyB&sD0z@nceey;&WG*v)GTU!DeA8 zcZ2Qn#=+*YR>Z+!_h^|^{|6mhPO<_(vrh9RDZ6HUi`}NCYxD2b*5V(a!h!yCKzbH_ z2-O@MtX$mGtT=Fydg}Y^s&jXD2i8)4zOrsR*F@l+&S=Ig1if3lXp!*kn@G00IP1BB zSDh{x#rBAEi)w;H?r_`Vsu~f+ESEd`$Nqj#yiycz(##oQxjPd)YjxG{|Inl2+8mcSR=e za&l6bVrj`)(HIw}or}(7yH(0Li^F#63roE_9hpDK-*mo5+u6c!NBswrNrL~)#@TE$ zBw@B@w!?4a#;>QN^CPH}v@s*hpi(pC913P#NtoIpG#`ite-FfZDx$I+R&%#7}n>?ghOp@Sz?SR?SF$-W$M<+C;#gqZZhu;2LCpz*ysOoF!{JcA=WFV z@Ut(&WZ6HV^>(bEgSuJqs=sy|HkCXm2&t9j(E~?`Ih2_1byQ>5ZJIQ@v>JS=)J#+V z5pG@y?_Nv2*4mdd+5vM~LFd~540RSZqhFg#YByhdvNM`!$AkBcL^0yxjpXdFt0mWr zH{;h2o`N^`UBR8;WCy6aQ5a!PO3>(gH-9K|vG>Pnc``$5-_x7xcbG5HmJ#?3zNu8_ zEAL}|eRZt^OqyqqT>xlr0>k5I^WfO5H1quNXr1VBX=?9MevOf0A%+r;xq95x)Zy;jna5E%TlX@B?m-o9FH?TPb00k1UK0@GHr zodeVJEh-PskzC2zz;680eLhuEcd%=cKvvdYWFN75qv$rnNmB05OV&}3mdUEdH<++cKsrFPHN4nI8;kj1YqM@^nm`c^Ol#;bImQ(bq!5dJkAD#^N}6wOaS%qS;Zs+ zAPdw+YS28$PU=881o{PaWh|PDuKwPTU4+gH^6%!scjq7csal=aTA{;OQWv0^+eGoW z2Bp0}bJr~^Z=YM?t-J85 zOkytlTJ`20NQX68R~8py-x0#^1Q2I-0I>q`Y$)>?yi0;CzUe_V-LT;lIC?Ck7>R5# z&DKhyd757hL$z^=(0hvO%ZkbB9X%{-IK)4?6){vVvGvC+P}cUwe6boo6AiSAMcz7v z4x`#Ecmj>MGUI#LXS85!5mW5!!?)GgCmO}(fGH5UmioLZhxOkPe=ddLzz0tPvsHp)kXLOg|&NtxkN`$EH5)wsyzbV30nHw_5Il^PoY2*$KA~{}RuyvgTsy zHNI$FBvSdU_hkfLozR98&I+K0Z2~Y=s1qv>TQzDL zN3}ZX@dyn2;Dc|Lu(vw6ijsR4Mae9JTe# zVUd#pI;&iJeB05yy>zP|n9?M-eyvLATy9z_RRMVDz7*qJTk+CF22Ic{C>Q`8sF8mk zs%^UFqx-7d^G77s?R8UItUNjDUQ+vzLWF|iTRlSr7UClC13*Hfvf}DEL`YqvM`f*GfQ2Dj83+aZIUkhtAFW zQGo0Kn~PFq3LoI;UpUfqR;uKjZ-|(OtE5bZc!#3XFB%c0%r*e{B$PRO0!Mo{q~OB# zJNZVli|Ko}@Wz}1DlK5teJC9Mlb#(4M`|h(*?FuoLccx`nMqA<|FO9m9AV$)4_Nv9wf<$6AYMvx=A(4>>AvB= zX45{(ek8N$G9+;bZ{i+G+@a;5?KiP(0U6Wb!Q)+$z7wZDu6Kkkb2Bw~z|=^dfO6R$ z3w=6g6=1NnW|HsN;(%&-^;5L5Fm0VrXy71Ed!TqA8k`q|p5JWHo-3Jp%ZeheS+81K zV!^9+>#1z!f=X_Cq+$pfpZO(KEuwcl!*cOEk80@YeFNwKPALde2*Yp9Bv12!%tt0o z@zj)=m*N)|r&~n(X;{P8;a>y9N%k@hrV!M39Ghsp?tBAycp1~stuKkOmmvKIlT=yg z)3aK@4eg4z!^wI8e72Y)h6Vnj{ZtCkeE6|n*LcDB$kEF0-}mURqObafZ(|u4qK2rwF`x;-T zLg9kO*^A#;L;JMwWyyNFvTjj*XnZtMwx`x2)|hUm6ZCUT-;VE&G=aEy+zqk9 ziGNRhw9d6?58nVOSjMrF&FCvtOIeLSnEVmCa^-sINL^@CEyUW5MPlU?y5&Gm6oyYf z1V#=`WBE{JAN}rQP(3ecQdM_6S(F1-IRvTbokmKp5A`@P_hT&;%Nd!Wz)eBs0{W3d zzk2JNk|gnF%Z9FfyRr6}-02MaZkkeABp)YdkxH*qicW4 znn7^ou~FqSzy{OJbVmD%k^`HCBY4%ptW+zsjoq<)rQnyfQi>wM!=x7${9qmP0XQ+l zoaD8ux>oHGf7*Y`3(v4SqbBU3g&(;#& zWZ7E`+nmpz@~7s>o}i6!8ye&8bIxE?Hy;#;crYu|kzWHr64#c~h?XkPZ)-|mFO(#x zs*?c%Ek$seZtjowveTBIzrG!RqiYbpX#u>eP@?S{Vqew2YSe3trC+82b{K$Eh)s>? z&;#LbSNtr52i6YP;4%;625sBM(mq%+<Iw8?MmO;@NmT38YRZ##LTK z_>}TKplw|(z^bbdJQ~BVza$1MJ+2AOVskr& z#R<;6IodiRde^|`YsZFK+!vrUHZ}Pm7Ry+^!08|Fa)h%)b@;11^?a1Wn+rL0hDN7B z)K_}`X#tD5o@U%FcAmB~DiVw8Cy6qjivq07BgD77HO!Qm+Fue_nnj&3tg7^$zHPSb za>Q`1t^8>+^TKQ1@qe=b2^&6y?BEO&^D#{ZSF;ze9KlzLqW7EN(jkT3nIHB%IcVdds;Iz2Oc>QjN)%AW0imxHP#l@R!@d920h%lKSizk9d8W@Lcl{oXALjQ4s)IR&Ef9k^&d?mVsF#Hi754MThaQO!Km({b!YHJUSm$^)@ z7C3RoXyHMn&|VxPhNXxkHu=?&`bmAuLpscTzB}!3-zcZzA&{Vci`S-;x_bw26UhsT zAHgU8SESY9#9?vnHyB4P2qcFvQUz$*)GYby2@N-K+_y1p!p3(fk_CT&s7vuF3F70> zw}S7+2FV3@d9=)kk{kdWij(wE^?K4D3aFRWKW=@5 zqk>UZU6m&&>3yf&`OKq1-bVZPnTm)$o$Bpa1rO{Tq!Yd!a`<}^=fj8wo%Rcq6b4Rk zNr%w)qL$l*%})Dn4V~BMye~VImjGv7l_x643&D;JvnuK z9$?S0X={~d$~k+rd&)q7dCjCb9k5E68>jx#<%_1Sp9QS&u|J#5Lxw~Tmjh*_bmi)7 zAREMWrzIjEt`dO_Rh4#9B@}#c8G^R$)GXwPt^>iggE9?yEA8Y~7%fVsd3sxO^EmC$ zhdIeDft!uO5>4mDVVjtg6OOS%l@Cr!%9nM1eQJe*Sd9`9Jv42bMpg%s85~aSk}s@7 zlMlhTpzR#4r6xPG%sQa7U<2VPc5jp?Ov>>v)3E+VLrVoFcnj8FoS zDYGSZJtGi{0v0{-*6unZ7}#*Sz#uVJ-HlDAFKcbZKu?3VU&r#XPhrbxlhhfEF`MP$ zVafM%DGzT;MjbFmi2tSy59e1qWLe&Q+$A?fx}UvRqZ6(_2{b z7FX}-g-k&!u(uw9eSchVcV-G6jVCa8{W`~>Wu$u2iaHV_eA4Qb@2|rEFFBtId^fm= zV(J`}oPVKJ`0LVza={QL;Q5EtbCRZ10c@6BpgzK2S9|>=h1KdE`?phi55`(bbmvO! zA)fAd8=RPjMPsH5ub%&l}jpK?#IA8C7IBr;K&6W^K zoNojP1ZEtVn8Hw5i{vx3b?Kg7k+m zOT@Xawy1DYJ{bbiBQxeFR#){GYAE777p&rJ@CfrkzKB6URTPkZ47A|z8i#*@8d?$` z$>*clW0)g94^;p^ABOwPoN_U{k4QfhqL&4!m5Y^$tT-;t1=U_VDk8O$=)bGn)SM#3 z54rK1=Cz7#@t?=lLwLA^hxTR?b@wSI@ z;R4r~@JrWl>lP7%H73HDXw_!WOO=p+RT(c1|K_yjRZCR)3lM=!Gkvryi=l4?>5PC> z?Vb7>edxAs)?Xo)u$3#H5)dP0C<2gUvw$LLzQ#{@url#&K*^M>9k%$G|I4+t)P?{* z*I*Mn#Pp!j{|LV~qQmkr-lMoDrWA@T!j42m=D0|wX$0EFX2lHGn6?6Pk#gOPXv*2) zIY1Dm3x0$)*A90$E!a1SQoS{6wnGmunSOOuwIcdEI>XbiT7;9-M{L#2@0{_fb4B!u zDRY7rMan}b!1YB=B#?xn@7^#*V^uV)RPl65RK$dJac}ejVI%ZgPST{TJ7D`+8Aohf z>xMR3(TV;-7y>(!vA&#{an^@=m>3@rkk#U|fHc>~l+!CsJoS$ZE)<#V%7}?gCR8VT zH_gCG362cs@t+?4`W`QUs=y?WXU7dk9mW44pNw%qy40uA79>lgn}qKkng~==h@p}> za*tG*M(}NcOSCjoJ$uqB)4K73j$GXADb5I##Hio~wX^EyA3!i5pG<@1h5n1LossA^ zXRAA^ytiX9wetH0V4=-K{Ey5D=n5SK1ojHP@{_X3kf&1xLlQRoMuEbB7WLMdz7$RY zeQHJLT)$2Sh_{;~;pVHX!SR6OgzAL*$Anp#s22RB)?o2P41rIHM!LdT3U zX*y{8El!L`EZF7kZ_$Tdo8F>RB2H)zV;T~HPLg_u8pxAx+28^FByO0TRu8bDOw?mN zQngWv1Z0yFP%hw$o4T^emjDOFD-LZ7e7$cZ#trycaz09_fy84i!iRaJafp2!I}Bry zrfciDO>fB{oJXBtyPThr9Q9?i))JaG4-WobswJ}+J$AQ3s(^#6TlqtWQS%2T2WhHb z#;pY63MeT(9V37wx!o0Og%eY=$2Va0P{8?z$QJO`gBmj!NW5h1wSA0!R(S@6)z^~e zHaU^_56m|mCnn7bJNT<~bTKqO$?DFE+y!=Oz*+pUFv`{eQOyTgLM@W|C7<9ZHH?{?4E1&%{ngP;mv|C+r zal^Is)x=?wn^CcO*^5OUSU3>C{_QQT+Ia2nKS-4WR2*c3C zAEjY13*fFy$61|m&D1ZuFoms{^37GVU#$vNhOi~)Lr7Ynwl}5KE%EcA=xt2( zDHZ5vqKYakQO-RF{FvAsB~HdVKvroL7pi)9r(s{gt`vqqWzLCHFjLq-UHh6R8 zl;grcHj{42++own^bFT+?}=OK+h{Q@34FpQK)6;}rv{Fl$|2hHd=E5c2oOGN{Tu7F z9>vg4MFC<-6D5^;vlzZpIMx`_DGYi5EEfkDBIS5N_LdD2rlbj|*fMk<~Rbp>gBc@gnQq+yPsW}$f~_^U7U20rK@+@nRE9xxYc zHoZ&<3~iMuzoq0;W(3iu8Iah&kNS4b1rE|Rp%Vt8vw&F1-1xSy+oYBMdsQ43yTMLS z1@ZefSR0VR`WZuBdh`oUqs#k{bjx4*WuddPKWg^68mbL7N2+v`vqz)RG9(Kb0Km%} z%lGAmi|YHvAga{(;jPKtv*G>7OL@dOFA2@Ff>`3ge&!*fpe-Z&cd{p@#pZ`ZZ6tI^ zX#6WGg#l0M-)NHYcS1Ok)8q_x3TlTV3Qf(ji`kPVY=EKtXx+Txn|c3O?r%PYbyol< z2%19raM_sZRYfCFH2nz~rn7@0)>tok`p?oy{MF3g^-`t*TAxTZV;*u6dlw_j*tK1k z`uP&E=13mnzZ0>;P}qFqwS{fsUv;cJHX_o3>(Ln*+hX%^{Q?Xh<_v52Lsn&chcx!| z*>%RVt=`c0*lpK&GEb!mVXl%TX%K$*1a3gDt;*pa)3#}WRz5;6=MSAuNcYee^0B&1 zbJ@-nLIAHjUnVuD5l>H$yFxK1@uy;(xEqbVLIYHN(f9xHbM(&%-mvGmv5a@6?|My24m#KmI*mx+1UWP#vCPa^xi7RN^ zm=%aaGP_{HwLt%lEGUF%!qPr)&^w7GZG7vB72{ zpDsmze$7D`UxPhl__(1CfUO^kRrT(JTLjr)o^~Ar3d|w?WXqT2B!!F*V2P;`%w^#Q zyOM<&p+hi3ZG|7-LNgjR{aF!HuLa@f$o7ku*!M|u%d=;&J&YwL(NCq+z8mlNjoKNE z>yq_EYt9dG;$ebe!=k!t1ffdRGQV#!tO}wS&nS0KLa^}70$mD~T%(IZZSK-cLo2XV z7+k)_Vs!IQe7m9_(Jps1+i$eNjp<-NG63>I=55}x0>N2J`F4v!=F5kJXX+N%8^jK4 z`~#bDWO`SH2ADi<1Yjj}py!@t1AKsoeb)Yq^ZM$H5T_zViHjUUXq(*;?KwJW#YDQw zNlJ6B_25VwO?!97O}2MCflsyYW%EV#qPw|_6sjI7+nE%XTw%UTI(u0^`zGN(eonP7 z`M2-e%o9*)6j&A64vs#`G-Jkbo%jp&}8UbWdP6f*+IPu8uNieV*^r^XjOtFEO}@_ zv3<4LpYYv$k}`MjJ0d_ksCW~$8OP`QDuPVwBJP`KD-hw!IY;6SbCIUrJI~(X%bK%l zsBC_MYeUSNc@~f(t8C$rr9D$A%b@aL*EB?sJ){9Fl4+1^XLe{b{D$|Vid(}mwnhyj z@ZJY6IL|kx0mb_Ot8S|3+m^C1?PNR_7c}~poJMQTb{AinhN=`6uYoCj&TZ9v_FVjQ zE<&9D|Eo(B<3Cl3W(ko-STQ8({nc76&P=@h+FPw|2gA-`fNNU4@@m}XvQm>w&zM+? zZ!lk_G{0ToZ`4Teqzba&-17yrn2i06EEsUCW0D2@#Q02~h+%0&g<4ob{Aw5_Z}ic( zDSF9X?HTUbGTJUxh%G_0WgcO+mR!U9%u?^+w3%kJ-Lb3xOhZWhlqB-F1n{3Uy%rmf z=GF0UP|^Ks&dDl#F8dBuAK+b3Q*gLfRe8&LY_8In`4eCIJF0u`nnc zF*M(X0|lhn6*lPffmiKuA=v6c;9ne3GN4%M7`^()9FOFs@Q4hZ40~k^$?Sh0?jE_Gz4P`vvLME2`aI*iA2QKm46aLAjF`y(P7$GLQvu`bcuAK zZsCmT|KaO?-JdJ|z)Q0>L@d@6z#nyB3{YC{&Gd(~OBPD3bLXh9E>R>>JXGJ*Tq{xm zleB{y0f>{ok~I!8fbuu<-tLPC6e_V6~{6GrGsO_uMQAwA`D|Ax}p2c{U2 zH{n{qQt`knjN<#=qsm4tq#^FC%(d>R%qy&@AdzNUN`xq^$b)O-s|G>a!ig{6+ZBTF zc0DBC`k|+_!MFhbwS6Vo)VWja`n_$=0W#GekUo{*z$RJ5toFs_=IYMV&yE_UJ0u(z zn-wnIL7v^b2CFV;T1oU&8a&YwdGo)i288;SGb*79>W3ej)s)}6J3AR((dpCyQaYH` zp;Js3Q_iwXI>|!c;Fn5uKq0a-L{l=jjIkTpKxHz_;n0DUrs>u8eL3KC0!mu~#mjUP zmkKm0gR74#zE56qo6;v1X3c^MKVgy8{ln=4vh}TdsCdEX;dLD4Ca{gia@9=-L$ES* zi;9G4IZk&!K5E8eN;s%cMlOZ;1#5=iQ$-Jtyo-hGm|?^4KG!R}M7{qb(4>9ILVr2_ zg+q2_2jY^I*QU3Bw?&hmgomI*boy)Fp*w*WwH%u1GwO+J6smC|)IO=km~}M|ci#!_ z*ElsVFI1UV$uQ?nl|;4BCyu-z-S>Qj&ZYm>OxyKU2~Jcroxt|h9Ul>%Ym!=0hG?Vs z;Vg%W?bubWom-E4+I9e0oh-l%gIs+{3h1fjs~Rwm>O4}MP9RMFZgSwFv=oRtHg~TK zYy8Uh!^PlZWaEUqMq@<~t-BAz*>I!KL2nhN5JRE_>rbnNBhVxXQ96R39f%c8(2{F%84Pu1PbhUpK}LVbf5*YW_tNbYaH5;NIRa%Xp^#G%8a;qB-Q{U^em=P z^5hsHl$&CkSUDR!7=n#!aDjuY0N+-zHN>y5X0;V8fB1hm(3Kfk4w=lB*wbsx1P{Lx$ZxkJ^dX~pQo67a? z>||%GB?6c1=4qvF1;sQ$3$23!_Qpvw}tJek?cA6yh(`DyW-?ve3S z>^7ZGUEv>7+xunV*@bjA&aQL30VOtnRp8m{KXp7+K1O$LFx($@D1aoJzSJhAM7u*v zsyq$-#SUYR;;wPpIY?Y7tkg=UULvq}kL>kCEnQ2xlHd)fbb(rHhfjj8yx4~Yul9Ah z{N*;~2(OCBzLF!^qQoIhbNQ7+Jz0~H$s`4{biCKGR(3xfmG$e|xC2)njAnV4e9BI~ zPK<*DP|}9SJv}&?AB(2PCr&MpFZoo57Co$G!A6`KQb)|iPQ=E}Mr1LxFE@`#sWP7= zAulgKt620SY!Vz)n>gqkeMf6cr+luVjGH%piQ=LJf{)F*Cw5)Z1Ajh^T!PX#n@<-Z z?`jc27V`^ZpD%>6XVk?kEwK>yhF^s(19^jNJYrFJAKNE@t@5)McCDjE zzY%cjPFi0d6oCPj*V_}*grzp;o~z$#1Fu73xI3^uc>=%vrxBrwt`~|nX&anL0JiZj zl+!FLN|5y1_KLmw=8J0XzCYj0Y1+mc@g*R0L!<`|S1HxZ%bnRz?*UQ(u`VKu1~Fe= zHM(o9eg7spG#0p%40jKKLP&B=Rw1oAI{AD9))VV&U1p6*`?aMu*XQGfT^S$U)M*f6 zp_crJ5ZwWs#WGkca^67c{u14UcdsT>G&4={9FV`{W6oj=p!i!g>q>4l67s3Mql@Wi zPLI^YKM!bfM5-6*K@HZLEpvZoXLs-T3z}1xTI)aKe%`0ixm07Cx9<6f@UM`@`AUgRwJhaZx|kr&oUImUG}0YcbCEu zc+=!>Yt)`|!l^bOcqonuX&$r5jrn}KCb09zr!+q|shK_Gy~=FuUS`7K+j5 z>1z;Pq-#_<;P<{O8_uu(x}NVLxC6YV-S6rd{_y0ft)Mz9pp?DxgXks9p<))K?eX0~ zj;#|uon0MFSJ+oH7NeT=80Fk!>^o^fmuT{RXu4th|`7RBD*=4TcwsB#zrn4;{Da(N<8hsB)}wF zWQKJ@bIVKjpzN?vES{1|ab1z0xqCZ7$OV4ZPnxlKY0gd-$wpe-Q$F zfAZd+L(mTIukjx_(<}GG%^eOHV=?Ypg@H?fov3EaKel%qGUU$dq_AnL$~xgQ8;abt zR(cs|w^rH_zgCL?4)>e&5Q&MbiB}wKQ|T7MPN@sdWux-_5$Eti_&5iVzGr(gw8>u8 z8NrZs>8bf;ONTz6z{WjC1v6B+u=)gq53G@DrD~g}Hu(OfgGM{VQRd zo7B}^lUpjj_H#=g0af%!t2fo;W@@sSnD>~_IPhAzm)^D0Jh2G|J~D>h-HfB6&@;vIJr0x_Z=FbX<8r}H zUE)$4!vxG_yJqw+oENZ9dMVo+>jX%HTM>FGb~viWb{o50E_>tXL(((K&9w`MG^!R~ z&Rd)%kKe3#^%5%UX=vV5-LzmnQ?&4;oAVP$AOA6VcxP5yH*V+YeS}~%?nN9fF?Ejn zcYbNIny&2vVV*Z7B<;*3SKSm4>=IcY9y5@1%}2@;YG5uF($kE5$B5%&jsuAQ1TyPh zTJ#Cp0Ec5$-Dce5!)T~=FQ3a))KO;UrtR0n$}Lc;RWtkE&9&wXdk6O3I8;Ozl!2xU zMDONo%R&RXBaZ9159-d=2RB14|-~OrNoR8F%Z+rih@8_E53!nnY(3ZXlv2Fd-haAm0 zXNAFPgZlFFBD}tACHd-7x@9iUCu#0NTGGVgcq_?qzIDheZx?ZHec>Lws}j7cZgF_t ztQNd$)^KdRG@8?~urm9sJ2&A*%;e(S^1{6`jY7#3Ric*h)V~&<21*^dzN_JxtAASc z-18IEzzj0{vxg7JGgd!MBpw-Hip5;E06Gi?Z4#TD=p>-mKVDT4c|xd$@^Q7OA7Kcr zl#-OEdgPLS-#B*B2#ARCo%>am{t}wAe&sp$zgd96i<%*@zBg{ibYf z^9>YdO3RU0;6y)X;ilBlif7Xj{R~L=4^MVQHv#($mBi<~1d&?BDhrYo(uW~l={Bld zq9{~(Zt#aC5-mN%cY%eN_8b%~ZD@d`Svj06FJEoq^08}Xa($gweXZttNIc^!E3g?E z9y{9*=3#xk4mVnxM>GD- zU#ocH*C=q26kWMC)6^tsC6mzLN*B(f?_G)U{}!L$Ya6iCw&p>}t#lN_%R9n4$J2hP znT{8;GV130Rfh|&1h_MAd^f?tdiD=;DdfCpe=}1&HB)0E(2(Pam^uEPCG<9CcG(Y6 z6YI!gHpnKQ$SF$W&*c@wj^}ltns=}rvXaM4i}bWV7^(c-RMO`yDyj%<{1KQuA-C&V zXO>1j*F>RaRUatDQ_|25`-PPnx4T&(|MxTr){Soi2)?kh3hRUoku1~MZil4~PxEgZ zY!df{40G4JHz%flrc+Ye$NBu-rqBm>#s2xo3P~JyIGXpOw{9cI23>_p-YsCmgU-4y zmp6dFsXbCd$(b2Xanqv2(}kQc4KZn&?qfFA%^mR1vZ5lZovimg?R8~C zxdok&wm~zGYDdG4SIbv}H_Pbj5`@azuIyXeFDL?C+T$f&(|R8s-+ZUk>}E&&`)dlv z(Ilie$6u9ut?L8z}x;OWq7Z!0G=f9ld=-KURzbDBxyQbf-5&PLQYW}O8rx!ph zVxN|p#3`|Me4#ii_G2?#RL>%?Mbro&*jUZnDNHIzPEK2S>f0()8wo)12z>S_KLyX@ zt^?#L^c6yIpk!lOdPEGD?e3{i@%&^FbtD_Ug2r-sSn)@d#<1Wkqgt{z1MDc>Y_wU2g0GMI*H;f6Fwr#K+W zz9V*)Ti8t9vpk;;uBoROeN}01yt!$1X!fx~QF?>@!d1jLl@5vtgaj}wbJ!8{^FHFa zO8f)q)!LJV!CJ2kCwT1e?eA{Rc;gygQO7%_b2{i!=dn?x?d>p66mHXTqGSeAj~Mfs zNveS7PGvymsq7I(SePi3a&M#mwmBVJE5CIhI*rP#r&(nO4&~W9*(iW=@n*t3OWD0Y z9n}Dof^T|@@(@i1MAAm>V;n6~1_U_vJ=K0sRz9B=4iF)7Eq}H}Wr+tL2I7a1QVgl5 zcBhv085$QJmFAUwB`NP#-7MdS`|GvMb91YMrozuma18bdE{t{PXqg)|mfmss73Iiw zGKUbvqkKf6hT=j&>)82ADJ->l^gHjV?EulS9D9eBB;ZwVwm{-JDqRlx)KgEk){P7b zJk<+EUY=?eg;Xirt}UENGH`Lru*|mZ_FwfOHA|j1nw8GrNTw&r{TR&3pK&vryGGUs zLodA6QmlEnG3g0@=AlZFzJ3=Nu?VT%Psh_vl}_gfv8d2lnHdQ1|B!9=04&RLk_k(T zvRUd`ju}Dt!@C@ecGnF4se3zm)8$Nk!=jq2n9w!WryDL{7yjW!QDs{<)qHtc*lVkL z8QUkN*)-3j6;V1rzd+th`{H%{_QVxO@&j;gp@O+OSO;=p3EVyP0$~t&Zk!VJBuJEd z`U?=q7|Ny5tNV${1mm|X28}4q>W<}T7QIfx5(r&mO`v~Cg6qAgM|W6k)ftiRRYR)S zI)OsP%sp7v?f;-UY+|zu}`prAY&V)U7 zS&<&HK*(#TZXqWbWPwa0bz1`8Rk{n9G4N6$3&X9J=3`9k-PV=W(3dxZ3G2cr~mhN%OD*Fg_uTPck7-%?xyuy4(0yZUCmL zbj)&0UrQ)+3o4x%syM~ja0wg!C^5O}#Tor_*B$<FKZ zlvmEO8CP}Q?4aE#x~bIt=8BnMCQFOkg{r5^rQw!~Xd$-sWt)Yi+838DCWM=&dgDP6 z{w2~)jEi$%#BDz!9cPJY*z@v&zBGpSi4Bg{#|DgoilVSi=N#_$z+JGGHo6UEy7@*4 zur+_+cco@S|IN`&l{H2b4_OGlzWdBBW$(1rnBmA|)U7l4X~6hj8w@Qp3d;J7F$7RI zGT;X{zySbathX^RlP5tH2ZtTa!yfic>6h{ux)y9g(v1|vz{?d>Y6miWJQXA9;ezw* za+Gk(E>P=8eo%&Trci`b)#KRj5*)Mumv8s;u-6g)_3O4svvpf&G}tL$$8sQE=Gk4< z>vS2R4o&rY#_f&zKE}m1Fv9T+R4N1RR8v%p&Op(_R>Lq2jU-M}CG`Hi@Jo3v9axV< zGpMG2Ygv(B6vDW$42&RFleD3UwU{(xA6cfcpGmVI6@{{Xd6n(yKhJ5c-luBXvaQ z!XuOXp11&gP)V`$%@DdE*R>}}X2>Dtom&kV-_*x*TPVXSPOL&(2VP_A4DOGwDZ`bLPnwmJB9SW$J1Cgwkv37$h=YJlR3q03z7 z!&WG7PxkL?O(qLH*+=lNx1b*1Y;gdBasApnM!yY4tDWnb+DNMY*;|0RZx0NrWQ5P{ z@>8zKtp-}6%jhD6GAH>a^|&jr5ollT62tfg$4FWC0&(r}2;k)a9)4ZWr?xtX z63O~9rtkfS{Dfdr4a9AANnrGS7;dq9YJXYADM?c`ZR@LqR}7JJ}sjNI|=I zRQ*@|r!sxl8f>YZchm(mVqTiZ@&5|@3aF^sc5PBh>5v#elp&=>80nCf96B9BrIDdi zKsuD6B&8b!=@bxT=mzPM7?AEd8{hZ)&Uemx{`Irgu-2@ZHM95Z=Z-7xXR|Hx>bP6l zu#Hrh@eE1m7O8Lg+uymW=s>ykmRgn#tIL7}!WIV}zj#nBg0%^TS(`rN}w{Sn}RH7C|UTSTLd!LNpFnc!`XK!*DMf8h{iOYLpt^;~$KjXz*%Ny?2A2z`#A@V^ zSF^w8b!(TwHpyQN%`+M1F4*t(yeV7e<$bHYP9nyjWtg#|Dj!Kffi%FWHO? zKcrJakX3BI~tNoX3PV_oIZ6stwjj!e6|C&R6Wfk{Wnv4U{)SLCi zWyjq>s!Y&GNOofijvom#33v{mih#@eZgl(E^myl`)D|Ct>#eqR(nx1ii@3}n_Oj6v9XBgr;IxsY7fnGNlN{Mx~A1?6T3O|I|Q-g6Z6T0LO z&Q5ghl~S{Ccj^~hd3M_iNmwb9h<8`c9iglF?U_?mfhlA5Jh~4H68k95DR^SHWNM_K$FyIZLWpwJ zjII>_g=HOltw(i_vcx`rAN5}GtYl(u<>PH*rgi#~2rr|Ab)YlPFPhnpebRLPA*@2$ zC>4_Yf|0aku90Kv2;=cNEO2ML;eFF%VLOfQz*zxX1^bj{CwfwJ7CLE5=ZLJpmAwnz zj6PU>n26OYm4sf4U*wldxcJ*9^;jq&7F?H@jkNezRqeugIkyg1uFH2xii#rV$Id5B zyjzPw#KxJx^!ux0^c|M@SWzQr&3ZSkIC&!erO{$b*z>nt?_k;Os7d8bt(sR7fwW;k zU+R8(2qkNAk1Zm0bL{Xkq|q75@2yfRp;0e4xrL7lQsfF~$tzW$fYPLcNC=4IV~Jc$ z!hm(Bk%#+!v&UqYDJUpIh`WI_DeE*%K9!FbI{j5lopQ$Xt8t45uXY`CTLpqNW!D|zF8p&1-(V*a;ImDQu+5oYIW34R zm}Jh-u`T;nycU$@ckrk5#t8Pk!(kpj@nxk*Ne5LPE&fZM1f0+J!c?T~iv-?a*#1c= zUdBMlBE$I0*2Kd?y&TWifqfWxqZg|;ANAHguGU{fG0l-Iww>dj!RlcGLG2$!U#pGf zH}5-@VwIwm5^C=*8+z9BdB#PthdNc)_dXXQabwW+9~`ZZ{FVEbc~jPK&vLQIf2f)8 zg)Wa#wHt{X`$}8ua9yEY6{YQ)wS6V2F1;9d+hiu&gsR$ zl#-GwC!+^oPssP!umm(J%*?izEJ*uX1O)`m9q?S0_dP-u9G0GT<1S74LYgXbb734g zGYryXLi)w~8RV~|-G7owbY`pCR??Hh-G+kjfKp=4hXSAtK|XhAd5y}_OO0;elz;~B z-ma&=xV^Q-i;=nt0N~xpJQf4dMmlL<{@Qs&GUu@PTUj+d#a=Vf>H@J>_XglGp`(&n zxLq7xmEX8sJwck)$yCF8g<1t_*b$i3Xpi?+>?SQam0F~LCc8dEucwFZSJ*Bl^cd}W zy%idCe)7X&?D5Y><-X+_QAZF;OaT1p);P%5U=3nrL|_4tQF1v_6ztKtQokAJ5m77h zS(a{;N5S}oWh%g)ORfwtd6|Z%$kPI2sSZqJ(Jx zs|pE2O-}uo3S;pY>rv~|03SU-?`jhKlNkXZ6uQ*mtoZepG(&4l;=bHr17-+R)By%?#NA=~LBX4)T?Q7*+m=Ex&L!uHjY^_k}iOg-vrb5UpT$S%_ zpsQ4$D#2ot5cX)sVxSaQiq(h!ZS53BWTsbHvqmY<-y8C96gR}N)}Zmr)XiMmsWm7E zKUWe0<=_K;63jGGi@MsGW`{zN9mfzbI)G5}JmTo(5j!Com|m>NomAYLq*=5N3M(ip<``_dvJe#6elE(y4Vw(;`7{`6nriCk?02sR07 zBuyX~{))y11&Q?mE>-$1MWlKfk3SENAGFb0MZQ;b??+AIL$~=rG>?Bl7tS+Gd=}v% z;DbV)&HF>TCh?CrxeTSu{9>_wlSl>^c2EYV@#SYUT<*m0q~rETmP1=6(*7wC5VZyvw>S@#EP zd-)n*tyW0r+Dp|*EUw&XDL#Ru*^uiNuq-+~-F5L|{1s{3g?J61Vdv~bHi@`a^HvHs zd9yll$Gk{AgaPLiKhHsO)uD8762=Xom+|K*$GQriu;M*PwUp*aWk!a=K4KJTNd4E-vAVG3x6=gC56%dZfo4dTyOd) zp^=*$+-t%a%*m zw&En}eiJdn;01|4(R7gJmV%B=%nz0AOVV15T95fBm)WH+49k`kYfc3^N7M_K=0B9Q z0{e15qx)21w}PW|oc#hGo))ny?O)Iu-g<9H!>(EqHo`(YtS1pb>G-Psk^2p}e)Q4B>lQV$}n#!S!DKmR0;4 z0F}i_yi+mC=pZO%TP|g{2LW@B-ttIXEfQy7KV17-2iMOp2#f&cLd*TGTVqumb&yEV z_AM&U4|q-zrI|RgkkHT+#g_Uj$hnan%C3dJ?DtrL;1;I02~O)?e=%3x?9=-!Cqy_; zX(m{%f=CX_GW1*)aGys_?khAx2P#{${xq-jvEl%M14c`aY-v)$_z_uQIYjP0(c>10 zjvILRBoOtE!bv5X;Jf8VZ~EG&>j^#lRHJbAMe@s|MC5M{)bXX_Q5T z8?P~ZNmiABr_Nw$f!ppt?>`t}c0>~Xn>G)>qGA%aOizyZ)Dk*V$~OPjJL;d9#Ow@2 z^o)0Twj%QJP|DEXYPDa#aX)njse-ZpqJismg`TBz{ro2b+^A+yNx=uKE0aGhg%)N4 zrsu<%thO-#j+9J%SuIR0@jyKJrkJ!07s=%@sxWl5KjAfgxqRb%P4|3D%qjs(O`weo zkZ3GbF$LXGf47`uW=;T2J2B$qU(O{dEVQ0L#z&pbCIVa{se?9;ms)3)tp=q$qVwru z#)HMH7KG8bUrz+ZRQ_F9myEJVwCTF<3?}OckB)P{f`#)&Eusqa3YthJQ zE{Qxl8-%|GlHS4g!d-aMdk0G|3FN&@fyHu827|{*D}Y4$_O`2Z6JEo+L=&31^Y%sm zrRC#ou~He8aO3>8m(Wfs=s(KBr-1hD?<=w(?_-4oTje=^# zr$1c%=gRLd0P<3E1tvEU99MO+5%LQ0RQA-^8`#;I$wgBLD62V30To=B&kNfl41M=? zfpQ3blOr≷=_%=BLNhi}gNBBy3QNbLNBUV+lXq{j6weq{lh!+9y4;*%FyL?8FDi zRRFK1PVnA){-<&*IwROk@9^ApQ$(yTIW@pNSw(=PMQi+`>S04lKv(`gKZy_Fma<_( zSasE~+7FmZj%LEQlst4_&C}UQ4Z9k<*oH#DJlL^nMsW?>%9;VBFuO*2@#WU#BcHR} z30|6!gj*u-Q5(rDse}m{-NIvkD3vZG-`#jAJhF^0kDD)ZjnyLTZPsMB3J zh}-ZUFSZ3b62yL4`i&c9-R6O}Yx04#lT%Ek+T%)C*$3#CD8ru$w_plUEVdb@#d8m4 z7ExResb(g#0zG)d2)4ynysa*?JA?* z(#41Mysi_0dV0|yJ^ij^g=(6mu9x7-n2!H|vl_v>rjpLGFKOv;^6mrYZYa3B$JDZ<%H4Fv85lB+IT6M4hn*V3kGE4 zMbI;@twwo6^h*+5CgjO5{Ncz{{kzG&8irHiTB^_8Ps0WQp#Kmwty1%|+~+}|$h&eR zR2za+>8KA7YDHa?nzh)ZbUzk5Jq0n%=$m}8j=gcaYBn~rXz0PN8>ZnXmpWpZ?fUJvUs5Op$O`eKa(R2n88QE$*BL zGMa#r9xMH;>QxZOCCMtaj<7XQ6`v9h2er~=;O10iC1Tp&63{}Ushir?L%A+<7|&gs z!NlqgYVqc8j-zhZivpr@%tEj&wDqDDKQMRPR=^4top{v8cp)1!gu!S?UmP?49o5AhI;&>Xv_s?bahpnRZ|`evmezOFu(qi%vI0cdS2yR; zYyN^UyU3rL%u|2Hi2T%gklUosMk}}I{~*&B&BxOz#%DX^^aN8Aa5BN!L>wuT?b9R@ z>ZP)$a6lih;1h&3Y5)lJVUMs7K3UA9^Db@|T8;!QawHxNX`hP8cT($@Q7cdCIx}(S zYJXO%)ABBm?ANf`JcN*ZjO@sC!(d;s$Q`-Q(s8B%CR}@hNLAo9FqiLd;}P;q!b=YP zxLYa#3@dC>?RuV-LeT;&{lKS&wVpg9MmkU4DCAm(hY^{2J^O+#+rZ)pk*O?*nGk~|K7SGwuJscnhKKwy zZg0^^Po{F0g;)t-)l(r$Dnv#DbHJwg*6Hk@@if4N`UW{(zz9!mE0BK2IIEd@^=F<6bSfI@Bekz1K8| zv&Y$nn09jVmc4iHIES?q0vo#6ZK#s64`#N=h5+BTvmx?&;{9PImjGt)3E#M!oI+qz zMGnz!3WZ1Dz@mM_S1FB|N%^mhY{=1bMRy2jI&Hexgk@Ui0@c?cNNvj(Rx%;!ublKQ|)S0dJE#419S}UKP*?z z^kSyM8H|pmsLAQVCMVX4^R>=L-1Hlocdopb`M+fN8G5GGs88i$8Avv-^JWNsBhJ=P zdm#xT?joMIy_8L*9#}&-f5d-!&HL=>bHOAF-KN+qZlbz|UWMZm@|UADXxJ2L6wT9W z4<@X58dayJJTNUE(Baw;=ddj;SAUOP4N4m?y2TrKjd)ww#lKlI*+DADYbB!($Cx8_ zsmF|Q;F0)Vd2`%Pvmx)V0byqCh)g%jfqXVrQ;~e}=oOn>?&W)JXkq)M?t-{_8lE;X z;aorGpTq~w$YxLC9G3o}vA<%RQ8NQchVXgf+O;a#Q(?O_i|!OXP;@MACq&W{{0eg)wZRaY&kLc{ZaT0kKB9k#f!OViLyI^q=e zG8Yq<|L7NUThlsXz0`9YhsZbT7^->M)Ih^;v43axoasu+CQ%n7z(msg3iU$8p3e=r zpk`ufnaJ(ZXzQ@dnGzntsk7EBOpD})DfNTg10K|GeF0$g5~uWL^hq!&bkaYXpBCJs z7~RGXwm*zPgOE-}V&O5?L{!DI?iv$GYs+9aV_pvAMWspwvku593Qy_pd~ya_C&F7o zyuHU=KJcN(_6@c5<4W0S;e50AUoH4LRo|)M1x|*Po3xz-5gO9LYd?!3RV(4+nW-hB zrvKY<08mz*jIAsqT%C7{$hio$<)sT@_<`{H*2uyw74DK;2VuwdHG1*tM52)~j;2+aZs(XKc*!4x#Y-|W_ zOHo-22Os$y*Dpbo4qY$~X(L5)A%%8$wEgO^KsCU@=?!%$s|O!odne;?4?Y?0m8GoxcdBlr=p9FK2d$ zNm~qZe@3@e1|&BwvPGK6d%C};SB)${ZAbqtx@ZK0lL1!{px7%30K2f=|J<(r+i*Q$ z%DBtoPVOI*$S#82BnAtQ;U!-BHb(3_A9s;u^kYppAS5GSKP$Tr3r(xZ5^MfxKxG9} zKG!N6<<0yuE?&wbY0AVC2GGx$xT;)OdNsbU5zG(D(GSuL0gaN)DTfm~8WGy(Bi8t6EozbzRAm6)g+0zy z1=9#`js`S~kd5KnBLo9+GNg`0-L!qHKyVsBZc8I>cK!IGZEG;mCPUckEz1R%Tw-In6n(d;+ZB-To^{~dkDKh} zy z`Yety=q zuWsm1fZ|wx)XUYR4aO0;BK5Nt`qeH?f}LB1o*1}7Tw-Eo@59bjL{7hY$UFC00rs2g#48R!58Cu(?&wy>zh6)1KEi_->B&O2iF4fU>d_* z##(2WBMsukUXK>eJ}r^42Ti&Q&k^|$A&i>m4=-QsX>H8eKgnaJvCg7O4UO_8I$tex z?$89zz@!%3JsN*1d6-O)zYLkAjd%fW+t(rtVgz zN36N`HRsGAREeG}5gF-ZHBSHR^if$u9)F^2QVU{kC7iI>&tw}ODSqFX9m(vuuiVEz z8;(m=s1fcUf4QnMq(Rs{8gk_yBZf`KhKyx5{73*Jy$g^HKC|#zC4sY@5BQq^Cteci zzTr`!{>L3us}V?p?HCxa$zcwIRF4?}F|>?75YF@HdN`c*UTHf6CG%ewt}*< zA^APR_u`!FJKw2DsmQOf3oPunT!{6%{&B&8Val7#@@Oh(Vzj=V30N_-7JZp)`*yxH zyjD5%TW{UzC86#wjJWy}u;l;HLygf+dVm*%h!}Un)z6x4u{emLVrH3G#UGeA9#ROT5!_io9mejc#UK!q;SOvU;G-kNmLXy!Z5SN>PJ66FwYFpRYI_62|a`2 z#mM{u`Xi$R6gmB?-JTnz372~Oz(cMDj#gVH&VsTScmb#Qbl@&YgQ2R3Kek(Zhn&Bh|n43l)K2MpSQHulgPfwCy+UBq73OkJwP>=Qw`Y31Q+Wp@2h*~jJkuudBK(SV82l_I;5Ma;U6o^ z_uWYqiv1V%tJwO7A`8{0M|w6X3ZIj36MnV(efOulC)blWbmq_m$!>8lg*BN_0wNll zAy9+(2q-yUDZ-OLLA81kB4=c4MPjlK51 z-=zNDK70f)xkmcsk1S4)pAvD}`=TP4YP{vtSF(=Pr=K2Qbj!Dd>>5w`WQkW^#XWvK zOIY4MRpLAy<1NO2-cBW$mz7q)#J#0=);s?BqA^sX_zT;J@?XhNSFISL7Zy%$^9M`8~UzoojpNB6blQ=}Pga-`irH zN;a42{psx?vzos@qJ=$o%R~_q`cnd%VOcOCwm8+M{4+8y!5W?R9-Bc9BPvh5=N(f* zH?EumDrcX*{1LNWomz4%&P6YrT?{MATP7PDAJ=xT^ImS6>#F0S&MRDtxX=6Uf%JKt z^!kWcBT@UY{OhF9Em`vWBsU7_B?dLabHBHR04oIN#tsCy5<)sq-`bNo&n{!u`JxjF z4O8xFEAwY)7Zp!zk8BQp_0jFyDZy-QZDIO?rcP|SK6R$>f*gAdP5<0Zd8R4PG+NJ3;UtIbzvTMI}3a33(2Zhos-79vwp zQW~HZb}~PysZiFdnQs!#v!8EHwVkeZudt0Z0t$A}@w~6E3m8*b3N=x-wp}xS42eL$ z7*1$jf#V8W9sFvfnV-(?p7Y%4lf(h7!0%(PcQ@`0rOdZfAsJ}!BkH98a;px7o#YN-`d%w;V7F4IjpK$=-^B$8&VTLis53+@}`7;Qn!VbX6uI-ka>&AT~NBa4OhhKSstexj-oX$u6(hHyJD?4Cs z7w+yf;M>4d@Hvj0gZjy+EU?crwIR%aB-M)SUOzWuv;{nWXa%V@ZMd9eE zji%DoN9-Kbb;H}eN}}5hbH}gkFPg+xUA%o6cbH#Z%$O(3z-w!kjWSOz*vraJJT3^2 z*Ai{JR@-8bkmOgQMckcKXcUX;g2`sArV5X%%Ljtj<lqf#-wvYY23ii9zR}TbWAO8zKif6XnLUALPFx(MZNH5r z(11rMX&JBWbT=lj#{1i3iElmolnnfsp6m?=Coi;3fMK1|8rYlqG7@0Vrr~cNMcp&X zFr_nT!>$oSSC-6EPB`_&Q_u?EF0D%yPbFMJ7tr(?*dS-Kc6r1M zsNJkgng_g-|K{*JmB|Y5ID{bHJz`QXgZ+R8dCU#09@GM*`Zgo|>PrSPQew)jdijuv zzbWd0PHkyJH|qYmk_aXx0xMcyXrqhjtj8qi+?&4Gf%bkh6Z)b1j zf78XFq51Kk1)Ov-xsbzfE0`y>J~sQH{o`+U1Y>i!YH3uOTj};S1=$xerBbHv{tE(< BY##ss literal 0 HcmV?d00001 diff --git a/doc/html/_me_humiture_sensor_8h_source.html b/doc/html/_me_humiture_sensor_8h_source.html new file mode 100644 index 00000000..c0712615 --- /dev/null +++ b/doc/html/_me_humiture_sensor_8h_source.html @@ -0,0 +1,181 @@ + + + + + + + +MakeBlock Drive Updated: src/MeHumitureSensor.h Source File + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeHumitureSensor.h
+
+
+Go to the documentation of this file.
1
+
47#ifndef MeHumitureSensor_H
+
48#define MeHumitureSensor_H
+
49
+
50#include <stdint.h>
+
51#include <stdbool.h>
+
52#include <Arduino.h>
+
53#include "MeConfig.h"
+
54
+
55#ifdef ME_PORT_DEFINED
+
56#include "MePort.h"
+
57#endif // ME_PORT_DEFINED
+
58
+
64#ifndef ME_PORT_DEFINED
+
65class MeHumiture
+
66#else // !ME_PORT_DEFINED
+
+
67class MeHumiture : public MePort
+
68#endif // !ME_PORT_DEFINED
+
69{
+
70public:
+
71#ifdef ME_PORT_DEFINED
+
78 MeHumiture(void);
+
79
+
86 MeHumiture(uint8_t port);
+
87#else // ME_PORT_DEFINED
+
102 MeHumiture(uint8_t port);
+
103#endif // ME_PORT_DEFINED
+
104
+
119 void setpin(uint8_t port);
+
120
+
133 void update(void);
+
134
+
147 uint8_t getHumidity(void);
+
148
+
161 uint8_t getTemperature(void);
+
162
+
178 uint8_t getValue(uint8_t index);
+
179
+
194 double getFahrenheit(void);//Celsius degrees to Fahrenheit
+
195
+
210 double getKelvin(void);
+
211
+
228 double getdewPoint(void);
+
229
+
246 double getPointFast(void);
+
247
+
248private:
+
249 uint8_t Humidity;
+
250 uint8_t Temperature;
+
251 uint8_t _DataPin;
+
252};
+
+
253
+
254#endif
+
255
+
Configuration file of library.
+
Header for MePort.cpp module.
+
Driver for humiture sensor device.
Definition MeHumitureSensor.h:69
+
uint8_t getValue(uint8_t index)
Definition MeHumitureSensor.cpp:320
+
MeHumiture(void)
Definition MeHumitureSensor.cpp:94
+
double getFahrenheit(void)
Definition MeHumitureSensor.cpp:346
+
void setpin(uint8_t port)
Definition MeHumitureSensor.cpp:144
+
uint8_t getTemperature(void)
Definition MeHumitureSensor.cpp:300
+
uint8_t getHumidity(void)
Definition MeHumitureSensor.cpp:283
+
void update(void)
Definition MeHumitureSensor.cpp:162
+
double getPointFast(void)
Definition MeHumitureSensor.cpp:416
+
double getKelvin(void)
Definition MeHumitureSensor.cpp:366
+
double getdewPoint(void)
Definition MeHumitureSensor.cpp:387
+
Port Mapping for RJ25.
Definition MePort.h:128
+
+
+ + + + diff --git a/doc/html/_me_humiture_sensor_test1_8ino-example.html b/doc/html/_me_humiture_sensor_test1_8ino-example.html new file mode 100644 index 00000000..19e68605 --- /dev/null +++ b/doc/html/_me_humiture_sensor_test1_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: MeHumitureSensorTest1.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeHumitureSensorTest1.ino
+
+
+
+
+ + + + diff --git a/doc/html/_me_humiture_sensor_test2_8ino-example.html b/doc/html/_me_humiture_sensor_test2_8ino-example.html new file mode 100644 index 00000000..6e74a27b --- /dev/null +++ b/doc/html/_me_humiture_sensor_test2_8ino-example.html @@ -0,0 +1,133 @@ + + + + + + + +MakeBlock Drive Updated: MeHumitureSensorTest2.ino + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeHumitureSensorTest2.ino
+
+
+

DERIVED FROM /*#################################################################### FILE: dht11.cpp VERSION: 0.4.5 PURPOSE: DHT11 Temperature & Humidity Sensor library for Arduino LICENSE: GPL v3 (http://www.gnu.org/licenses/gpl.html) DATASHEET: http://feed.virtuabotix.com/wp-content/uploads/2011/11/DHT11.pdf GET UPDATES: http://feed.virtuabotix.com/?239 –##–##–##–##–##–##–##–##–##–##–
+

+

+autotoc_md0

+

+autotoc_md1

+

| ## ## ## ## ## ## ## ## ## ## |

+

+autotoc_md2

+

+autotoc_md3

+

| ## ## ## ## ## ## ## ## ## ## |

+

+## ## ## DHT11 SENSOR

+

+## ## ## ##FRONT

+

| ## ## ## ## ## ## ## ## ## ## |

+

+autotoc_md6

+

+autotoc_md7

+

| ## ## ## ## ## ## ## ## ## ## |

+

+autotoc_md8

+

+autotoc_md9

+

–##–##–##–##–##–##–##–##–##–##– || || || (Not || || || || Used) || VDD(5V) Readout(I/O) Ground

+

HISTORY: Mod by Joseph Dattilo (Virtuabotix LLC) - Version 0.4.5 (11/11/11) Mod by Joseph Dattilo (Virtuabotix LLC) - Version 0.4.0 (06/11/11) Mod by Rob Tillaart - Version 0.3 (28/03/2011) Mod by SimKard - Version 0.2 (24/11/2010) George Hadjikyriacou - Original version (??)

+
+
+ + + + diff --git a/doc/html/_me_i_r_8cpp.html b/doc/html/_me_i_r_8cpp.html new file mode 100644 index 00000000..b106056d --- /dev/null +++ b/doc/html/_me_i_r_8cpp.html @@ -0,0 +1,153 @@ + + + + + + + +MakeBlock Drive Updated: src/MeIR.cpp File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeIR.cpp File Reference
+
+
+ +

Driver for Me IR module. +More...

+

Detailed Description

+

Driver for Me IR module.

+
Author
MakeBlock
+
Version
V1.0.4
+
Date
2015/11/16
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for Me IR device, The IR inherited the MeSerial class from SoftwareSerial.
+
Method List:
+
    +
  1. ErrorStatus MeIR::decode();
  2. +
  3. void MeIR::begin();
  4. +
  5. void MeIR::end();
  6. +
  7. void MeIR::loop();
  8. +
  9. boolean MeIR::keyPressed(unsigned char r);
  10. +
  11. String MeIR::getString();
  12. +
  13. unsigned char MeIR::getCode()
  14. +
  15. void MeIR::sendString(String s);
  16. +
  17. void MeIR::sendString(float v);
  18. +
  19. void MeIR::sendNEC(unsigned long data, int nbits);
  20. +
  21. void MeIR::sendRaw(unsigned int buf[], int len, uint8_t hz);
  22. +
  23. void MeIR::enableIROut(uint8_t khz);
  24. +
  25. void MeIR::enableIRIn();
  26. +
  27. void MeIR::mark(uint16_t us);
  28. +
  29. void MeIR::space(uint16_t us);
  30. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan        2015/10/09     1.0.0            Bulid the new.
+Mark Yan        2015/10/29     1.0.1            Fix minor errors on format.
+Mark Yan        2015/11/02     1.0.2            Fix bug that IRsend and IRreceive can't work at the same time.
+forfish         2015/11/09     1.0.3            Add description.
+Mark Yan        2015/11/16     1.0.4            add data recovery when timeout.
+Nick b          2023/12/05     1.0.5            Added an ignore define to allow the IR to be disabled.
+
+
+
+ + + + diff --git a/doc/html/_me_i_r_8h.html b/doc/html/_me_i_r_8h.html new file mode 100644 index 00000000..d4ea64db --- /dev/null +++ b/doc/html/_me_i_r_8h.html @@ -0,0 +1,417 @@ + + + + + + + +MakeBlock Drive Updated: src/MeIR.h File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeIR.h File Reference
+
+
+ +

Header for MeIR.cpp module. +More...

+
#include <stdint.h>
+#include <stdbool.h>
+#include <Arduino.h>
+#include "MeConfig.h"
+#include "MePort.h"
+
+Include dependency graph for MeIR.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + +
+
+

Go to the source code of this file.

+ + + + + + + +

+Classes

struct  irparams_t
 
class  MeIR
 Driver for Me IR module. More...
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Macros

+#define MARK   0
 
+#define SPACE   1
 
+#define NEC_BITS   32
 
+#define USECPERTICK   50
 
+#define RAWBUF   100
 
+#define NEC_HDR_MARK   9000
 
+#define NEC_HDR_SPACE   4500
 
+#define NEC_BIT_MARK   560
 
+#define NEC_ONE_SPACE   1600
 
+#define NEC_ZERO_SPACE   560
 
+#define NEC_RPT_SPACE   2250
 
+#define NEC_RPT_PERIOD   110000
 
+#define _GAP   5000
 
+#define STATE_IDLE   2
 
+#define STATE_MARK   3
 
+#define STATE_SPACE   4
 
+#define STATE_STOP   5
 
+#define NEC   1
 
+#define SONY   2
 
+#define RC5   3
 
+#define RC6   4
 
+#define DISH   5
 
+#define SHARP   6
 
+#define PANASONIC   7
 
+#define JVC   8
 
+#define SANYO   9
 
+#define MITSUBISHI   10
 
+#define SAMSUNG   11
 
+#define LG   12
 
+#define UNKNOWN   -1
 
+#define TOPBIT   0x80000000
 
+#define SYSCLOCK   16000000
 
+#define _GAP   5000
 
+#define GAP_TICKS   (_GAP/USECPERTICK)
 
+#define TIMER_DISABLE_INTR   (TIMSK2 = 0)
 
+#define TIMER_ENABLE_PWM   (TCCR2A |= _BV(COM2B1))
 
+#define TIMER_DISABLE_PWM   (TCCR2A &= ~(_BV(COM2B1)))
 
+#define TIMER_ENABLE_INTR   (TIMSK2 = _BV(OCIE2A))
 
+#define TIMER_DISABLE_INTR   (TIMSK2 = 0)
 
+#define TIMER_INTR_NAME   TIMER2_COMPA_vect
 
#define TIMER_CONFIG_KHZ(val)
 
+#define TIMER_COUNT_TOP   (SYSCLOCK * USECPERTICK / 1000000)
 
#define TIMER_CONFIG_NORMAL()
 
+ + + +

+Enumerations

enum  ErrorStatus { ERROR = 0 +, SUCCESS = !ERROR + }
 
+

Detailed Description

+

Header for MeIR.cpp module.

+
Author
MakeBlock
+
Version
V1.0.4
+
Date
2015/11/16
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive for Me IR device, The IR inherited the MeSerial class from SoftwareSerial.
+
Method List:
+
    +
  1. ErrorStatus MeIR::decode();
  2. +
  3. void MeIR::begin();
  4. +
  5. void MeIR::end();
  6. +
  7. void MeIR::loop();
  8. +
  9. boolean MeIR::keyPressed(unsigned char r);
  10. +
  11. String MeIR::getString();
  12. +
  13. unsigned char MeIR::getCode()
  14. +
  15. void MeIR::sendString(String s);
  16. +
  17. void MeIR::sendString(float v);
  18. +
  19. void MeIR::sendNEC(unsigned long data, int nbits);
  20. +
  21. void MeIR::sendRaw(unsigned int buf[], int len, uint8_t hz);
  22. +
  23. void MeIR::enableIROut(uint8_t khz);
  24. +
  25. void MeIR::enableIRIn();
  26. +
  27. void MeIR::mark(uint16_t us);
  28. +
  29. void MeIR::space(uint16_t us);
  30. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan        2015/10/09     1.0.0            Bulid the new.
+Mark Yan        2015/10/29     1.0.1            Fix minor errors on format.
+Mark Yan        2015/11/02     1.0.2            Fix bug that IRsend and IRreceive can't work at the same time.
+forfish         2015/11/09     1.0.3            Add description.
+Mark Yan        2015/11/16     1.0.4            add data recovery when timeout.
+
+

Macro Definition Documentation

+ +

◆ TIMER_CONFIG_KHZ

+ +
+
+ + + + + + + + +
#define TIMER_CONFIG_KHZ( val)
+
+Value:
({ \
+
const uint8_t pwmval = F_CPU / 2000 / (val); \
+
TCCR2A = _BV(WGM20); \
+
TCCR2B = _BV(WGM22) | _BV(CS20); \
+
OCR2A = pwmval; \
+
OCR2B = pwmval / 3; \
+
})
+
+
+
+ +

◆ TIMER_CONFIG_NORMAL

+ +
+
+ + + + + + + +
#define TIMER_CONFIG_NORMAL()
+
+Value:
({ \
+
TCCR2A = _BV(WGM21); \
+
TCCR2B = _BV(CS21); \
+
OCR2A = TIMER_COUNT_TOP / 8; \
+
TCNT2 = 0; \
+
})
+
+
+
+
+
+ + + + diff --git a/doc/html/_me_i_r_8h.js b/doc/html/_me_i_r_8h.js new file mode 100644 index 00000000..73754f57 --- /dev/null +++ b/doc/html/_me_i_r_8h.js @@ -0,0 +1,5 @@ +var _me_i_r_8h = +[ + [ "irparams_t", "structirparams__t.html", null ], + [ "MeIR", "class_me_i_r.html", "class_me_i_r" ] +]; \ No newline at end of file diff --git a/doc/html/_me_i_r_8h__dep__incl.map b/doc/html/_me_i_r_8h__dep__incl.map new file mode 100644 index 00000000..b2eb8fa5 --- /dev/null +++ b/doc/html/_me_i_r_8h__dep__incl.map @@ -0,0 +1,5 @@ + + + + + diff --git a/doc/html/_me_i_r_8h__dep__incl.md5 b/doc/html/_me_i_r_8h__dep__incl.md5 new file mode 100644 index 00000000..9fa81a2f --- /dev/null +++ b/doc/html/_me_i_r_8h__dep__incl.md5 @@ -0,0 +1 @@ +45750a7ca0b286dc6fa1ea4d09d135c5 \ No newline at end of file diff --git a/doc/html/_me_i_r_8h__dep__incl.png b/doc/html/_me_i_r_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..7d8712d2cac396b2052e4f1f5a40335f2037242c GIT binary patch literal 1320 zcmeAS@N?(olHy`uVBq!ia0vp^l|Wp;!3HF)zTR&HQfx`y?k)`fL2$v|<&zm0Snhhd zIEGZrc{}%D-klJUw*QZLR;-QKvPf%{i&>5UQ_GYM3pco|5MolCYN8|(vb8hqyzmE> zH_JWc7kJ7mtl6YJ^+F1BM`+kftwk-YS+ji}A67C>d~_rE{EuI8{pbICPD}oM?&Hqy zv#a0q*l;>SXtNO29yEbo1@8zP2JsmN^6WR5WCI;&; zMd(W(>3qWY`SWMJ!!wuNerwe&YT50Q#jPscFp1aUB-?@%=73F%Qp!8;=FN|KzExW) z|3mSuM~`gm3Vu}=#b#{3{i4KbOC9!R;tcY#fa&w0G zX1(bX5++SnHNDaxqPsNo+>ce9R+C>F6il9TIkfbH>jvrdM&`eTy>8`yRLd{{36;Q0VDa@AZ#v{!4se(k0+} zG4F-UvPrvV|1v1y+hWYvFuHP^RB#z=ntjEQTGt5y|+-<^EI@1$Aarn)t5Q}ajq zv(lKI-xq#4l=_Ta*!bs3?iw~(Asz-py?r%Z{>)3Chzd^kdt_hSmHoH#ta|mY zZ{PkU<~4)A=#B|C%bK3Ab&lEhz14<$;%t2>`^k%$YgQikd8N6l*j=~gou%q~lekS9 zd5jib)?$qA0(U;mnN%(nyDmTf<7V_`ZMNf~=br5| z%{Xo{B1?eX)ez++HZl11o-)_Ry~Qyueq!+vKabcPu&eudnLul8~Tvmrun`+!i@kYF=xq)jKV}iJx04a>e}8iZ+R~?OJy2>n=$v z{q%aSo8c>UW;JJ@3Y##&Li2j+y_K$~pD&0Kk=?Ln&ZkFH_BzfsS+DgmZry6Fw|bAC z9WA;VA1}IoQqkP)^_OZN=S{DSz4u`H+xJTE op@ZHL#@hN80Vj@?ivJnC9-04{(VXiEEczHcUHx3vIVCg!04i^5(EtDd literal 0 HcmV?d00001 diff --git a/doc/html/_me_i_r_8h__incl.map b/doc/html/_me_i_r_8h__incl.map new file mode 100644 index 00000000..52e90786 --- /dev/null +++ b/doc/html/_me_i_r_8h__incl.map @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_i_r_8h__incl.md5 b/doc/html/_me_i_r_8h__incl.md5 new file mode 100644 index 00000000..27ebea19 --- /dev/null +++ b/doc/html/_me_i_r_8h__incl.md5 @@ -0,0 +1 @@ +a61f679528096f88dcbd5ea0cb61a8b9 \ No newline at end of file diff --git a/doc/html/_me_i_r_8h__incl.png b/doc/html/_me_i_r_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..c5ad58f8892338bcd423e27b3212bc15fca20f35 GIT binary patch literal 46579 zcmagFWmuG7v_4FOq|%KbA>CanE!`m9Al=d+0@B^3v^3H^fHVw9#{h%GNF&|;AHd%^ z=l%2!AG|Jn*w5Z;uejHJuL)OClEFeJMTdif!;+JgRD**<@_~bcS3yGoe#4I7(gys4 zVk$2q3HSH@=SzEWA{^XvI62AJ8XvNDm%Kh?Sv2?mIk;6y`OcH12+x=_G$YmEf@Cgu zHqMvG=7g`V@}(i2$Ku&D3*mm&{f|R=fpPRUtf(OxBB-Pp>1t6g(cWX=Tfa*Bj{gH0 zNiD@P{ah?S;p5i=`;_!HUH{yjj54{+Y*=%#{KVzxF$CxH|Nlo;S!W9Q{;>h5wxMB1 zRk|PTwooXU=U;nw_frhjS!x=Z9(lw69uqPH4L*MUjH&+m@y{Oq`|RcJvwt5F>Bm30|2^glbRWropU`I^qBQ?L zJ)gTN|2-aWB54x)@a&UFLRRnDs>RmI;x%`F$Pz2r@%<8YZ6z2_?;qZ(kcuR9o>b&_ zzdr3)SopByXCNtQ&M`UkuoTG&ehcvUN!H`agXtCa;oA=KTFQ;euPq6bJk1>J-IbL4 z_agOUSZQb`h!*9Lr^sGi4WF{jh&!Mg8%^{Y2>C$CaUQZkgtehqlh!{`5d3ET58 z?$3$~zha`@cA+PaSFC9eQPcG%gM0>6deU}Oq}jK!Fuzh2ScCrGB|WP?Bb*5Ex#2q# zY@5$|;*bPyCh?`@bBg4|U+Y72Yo1k+X9CLm(3?Lp+!b`&3&0ti)aU-a1?Q-`9Xm7Z zxIp-vge8XLTyU3A2oH=IuAE)LFaStKyuQQ0Pwo%`up@ zMuBU&%fp0+&>msc@G;%OpDq@we$q~2YD^PYHs$e7;$PM^8rwShe>uxa+=gS)x}e-b zPy$`PbV?w}m4o5YCUkV%TI?hH+j~LuL`SvUD2nWo4d`YxW{O+x+ZBxts( z;FS>-LEc$dK|fD|P`&cLPjmpoCsWN?u&vGPgnCHER6 z>DlL5j*{`&87_V0MhiMdyd#_`p$7^*LzrRDexK=jJ|ZPaJNp=Q10JmJ>V7wIV2bBP z*OXfyP;~bw=PC@7v7TLT%e1yzPo*J6&xZTu9~3VT60eu z{|f#lBSC%bG_A#A{)Q&%CpR7ioBS|yFYZO0siwTj-#qVB&S1=@RJe@BO zsMf8XILC~N6;j|f6LNw(OzCo@(8{c7@kYThnaST!FLXELDEb`y<^V0w7?bIE>x;EetXx96{Dc#5=aio9Q{BihzrV{(G+#VZlurTxHiKhm(AV z^Pd@nFv%f?wE}X(5nD6MX>yf*AYw>UX}(PWUpJY#m(LeBSeGXiYD&7jMByx#kf+}hqhO9Ca9F5|ks5+@FpBQ12UB{T*y{1%~KwvH&Y zS%963%qLc!=Yl4RERd{EY#?M_r}=Aj@n1rE zKQ-&553=DT4Di@DL(rHyXIO&iqJT>MOW<0z$R4j{f`P#E+JB2@1qsZjvy`)WEN?Y$ zChBEJvy}?J0$*7kzPK@8DrchXk*#;o+R&F4%84p~JQo7qGgR`k&$`aHu7jMWeF%9) zLvv7AEpuOWy*Gd))9lVo>=qf zAAjzCToqD~&Au<(2XJ;0@>IVELwcl`c>B-brzKbyiEo}iBia8C4!CU%yVAws=+8q& zriWqgY?UdE-oa{q<~Mgmed_AoZektuh(`B80e2TDyA)4F&x7!Vl+Im>a|rJms~Ac* zKHe{8^IytJrt>T9ng;S*%1Ir&a`A)^`&{AYObR7lnEEu`S)~5dw`vB`W9`e=uQUGg ztl>iixZf?w!4J2G5Ck(`Y`rI=9;beVY27pbTRO4JJFEz#(6MG1|<_ zaOK3Gt}O}_qLg8Y%`QGIGz~dO1H(L^NMW(lefI7#Lz;8kXjzFz=k=i@oNGMB86j!TCS;oSAU)cCO!O;P61Oxou+q=y5|zeNpLNmccsl5=&B8f~EVW;wc_ZODb`H<=glp1QY1 zBvEB}Xu*$Ca^!o2-qJ;GI3#xGe1&BtbyiJZHg)MkX`%LE1e|Nd4Z`0_VqM2VE~CYm z&iL@q(u_Htn0*vZ4Ep01`sxsW#+gfJ^Xx(l`KFn@Y**5J{ohO9Jb3q}Gs&T#aWI)t z32Q^>U6gLl5#v4&+*sWPr|UeA4;^#wSsd`z3g7z9l|=!pH8-eaSb#Ak!r65XQxDJG zui2yPEjuKuA4!=T-pqxcS_R_}Y23We40{KQvMQ&mHqEP`H*(-h-b0v}fBI&3(nj=- z5hL4CXA^myKO?i*;Zk4z+zKK&q};8$3eHf?7vPPk5CBXTdz9Q!g_`w*1rFQ!1DBHn z#<8xJ@F<_8!OE*r0Fc~qp?cO*?5aG6dlw{*Xd84&tVn6*w>Kz~|5Vo8T=Z!s^{U zp2lUa$&CC;b|wqYi{Hlhs9|8*;Bf53k@U};9cu}*gP&e0g5HIlnq>5+g1>i4YuA6q zM0(6EFF@U`H&BjP$6rZ8Q?L+UHa*2eJh{L4)l*QbYr=%j--|zY=d4!Lfz9$G)82F7 z2w55}<2gHZOv)6GX23!R-3F@0Dj7 zi})5x|5M&VYuNm}*bs71#EkG7%^UjIl`ot3^-T+aq3bIEKOJ~eWK52|3vnKlN7<3cXAC?wkySSo#?c(D zY0N9vlk`@8$oB&rQ}e0)*^UWYTk**qA_jB`{v?M6(1?sCgPaQIYYCIFfh5_hpv|le zC%(Q9+>{s+DGjjW#2^P;G5q9;BR@3ZD|q)497HId@ARjE+IN89x%=uQ-q z=wp%Z_C?Qc4=S{yeHmXR0{vPr^(QzT zs{LB<{pYcvHSD>g6<43RF>ZQ=F%|9PTsy&s?yrL)u3W^IB9%qsG{M0Su^VraSKfug zxrPd23G+T`;#e#uOrG&7FZoOs>8eVgsm^;8hml!)289rnvBW{4Kql6*fN?A84E8Yyod>8h0iyJH8fJy`% zQ;(IS2w~2(uO*~9Q6f^(LH~??7c35i7>s>de?au&i39!6I^6i~*4yq487SseFXJ+0-ePOt#|J(X@$q9JDoA zW0{sMRQ%xjD&AvrwvO2FDB8zt8TuurLu3{Xwb|KBK7)M)2n<)w*$2o>c?t?5#H~uV z!GW3P*a7!qm<0Pihu?ia{#!}&nBM>E7wX2hJ0g7E{AZ0kiB9whTc|uC_IAjT zg0`i<&eYsABQaV3y(jKIHnz?tV3HlUBQ5-gGko3tAd+H!Vi`M`xsJ^?o{b!SZR~J_7!w)zA0$aWb5Rs)68` z{-<95bYrVD|LY!8aA&c^FL}!aaTh_OhL^kXc1^~GL>=}?Ezao zl!{LCZTK#0`qzcRB`EKb#4sKS1XpviWmi|EV9ZWcivZvtrx&(G27Pe~|=I*rf z;PAf4`#!UM5$P!ROhdEVqvkV@B=<=3%*V)jU1X*?iW7(%b_KfFebrvg@_^h>4>LC{ z-=bb)d^sxkEA}aW)EX7UiOTJSiR#3_9>_cGeC<@wI~3=kG_*3Cv$f+|DeQxIYN@Yh zVAmPd!Z+W6%pI=`EX zG&f9hAI9pR(`I0nYoOD*ibv8%%7VX{%p%h}zWn*!=IrfMz1&K6^F*Y_XJ?h)3f)|< zpZ2YSz!a%%>(zWtGeYG!QANGIJm10_G3g%zh-RuLWAi?m@wCO2K!y8|;mZ@99q__`&7~W`ux!yo{LmtVC;J!lHZ5c)a`@+9H@n${iwZ;C zX>Ylp!u$GKdZsI6zb|X4O`;h*`>G788Oh<)w3uN&R4>6)YUEH&D1QIf2Z! zmUFj&zcs6RgvDY@J3BdQ!TUj9=MXcMFX_@&SRSIrBpT>QZ*-FwNFi@i|E>r%2^Qmoama^u06nbF0J5bo>4)j8%#R|Kl^G6IG6tEF z14~2ut8fbfS%Ezxf|vs2#LAo3y4+wh;@FHopF>1$7U(IB#AcUc8k|UWA7f>G;9~(5 z0caW&PAp!WE&twf-c@zl)nmw$$?1;hf*-*Wr&x^Uz7Cd$qz>}*BZHzF`P;$!-m0|0 za=l9(MroTgVJ=??n)nO`aO$U3T7>SIjJ9+f67o>zrk+)lu=p+HDeRkPIxz4HVjNig zA6cO37F;N`;CM`#2^Iu$E3Hf4cwWGlV?{+05-mFBmv7wz6W-ip0aO9}**<%Nq|@~` zUPF!^Ft_Ja`K(S32IP%is@=?yNEc~3Ss@XvSUTh2D%GblQU?`sWHLWiey0fg}_s)CVF&mF#nXtP?% z5iW*qI6O8nU5`a(2Br~=_X^C)N*g#F^wVL=SYK7R=MLB1o{J~zzDN9#X5NSY0p@|0 z{?r-o5Z@rcvXCIgHarm-5R8Yk*+E_ zY52LNNdF!kM_1e+T45e8%)L1)&w9Uie?&ZrMV8^wrXSg&kV`qJubIH#%wz~-#qmc@ zDe|OHMuV77;vYw}W<8*cQKy6x>+rV6tDgLXiz~GTGBjHoaAs5mTFg=Zc)580m&%v; zo|Py{pbIY+=&#bPGv6t9cov1Lf~Q*W>><>2_a!Q?l5rN7v6B)e61HQzc9veU18~9< zLMtXGY)P4}jMWU%ih9f|hJ5{oKyoHo_}}`zJdc7RgXrU~f0Q!`A|#re%ANiej?zi7 zwuXX}?h5{edoAIS6Kxm!SSrL`>TO)dZI)RkAqF_X@)mG?o^Q7ZvDzI5U__&EQw9i+ zGB%FXZI;-QqFG@1eUlT z?vWA7Wz|k4(3vx7C`7SSYep zEChKE-s{R?DG^#&aN(WJlZuSN=s7%YChe^1&coTo=jpt#oN~8gMEh9g(6UwZy7o#w zGzC1~pZ)d=T2tkhY-WFvMZ@SO9ujJyt2~PL)H0v?o}tLV$sn}CL+wBxkYFakVGGfm zoUjxJHPn7*gbWVww{(+pN3X7E{^bw)PmzN6VZ+7*p{ts(ELU)=f5#*DG#~RFfE|U+ zC~E@H6t@g{)V0=az)=N$pJaC=_fF9UI-qdX>AfS)n1&TQ-! zk4x>>W+@gC>zFWK2v(j8*29Uq*r|CXIN>=5o@a8I~i%EX?``0M#r&u3OxQQu(Qb#Xex5P=j zUu$65o@m){*pTZay&#nK0^sjccR3oa>i56S#(+kSk`%Qy(FGP7-GA6B8JtTFq&XK& zT0cjw;sN_atE=-m(>gEu+%%}u7~VmydIV$TZ=6R#gxXcZOQ@HZxF4ZWhcXp&^F<6Z znW&>#!h3!(n?921-m~KpTip2HEQ}4&pu8iL&Sk`o;Mx|Jt#3M@jbL}pJWL~-HS0Tf zN>j9gLA%9m1*dl-bFu??4k84g$xS=7=wdUUL&&EvE#HwP@n^5MdO{!a2+7YO?W+#T z!@Z|qu8ZUz)p}<=B6ovD7l4`Y{hFL>GIAIw$jfb~ImH`3097$CjYX&(BE1pdu0)fd zd|Pk>t80VY*7o5aDWA=wa92g^8MtzX!5JZmQ4t;{WeCVux{IpH=Y0);-fJSJ zvfNZvYSgs074WK0)FW-GiDvw7<6;kYmzU_YayI zI`!%r&Mv@Xt;@5Cf-da_3g*wJ@fRcJC>2od7FQE=Fk;yiE_X|IaJR|;`?S06T-8^0 zI(Y4!^=%K5i#Ask*IPwu-HW>e)oL9Ru}j2j?_Fa&iW{CohwsaDeq~wX5See0@Nm%d z)*B@wQYx>521gP&d)BAhJ8P}}%ZW8UKJ5c4D(-dl@UtluM;nAkOXJP8B3tK3eaM=< zXXaC<;U`l~&TAje=B-waFKfrdTBomt#FuAu^sbxu&rgfamPH)&>b~Do)uAECj8vJj zS6nz36@rchljNFurjenhi@#=vhrj79V+|rklairD_9!^ ztPbK7DAw+`znaiJ)0wJ2mCEZPGJzmKc+OsL#-6O%Hr7X%0dJz25C_mldyS~T5VUhN zePyEi9vp|au*L6f>31dW?Wss4Hx$GuBmXxG;2aJZHBLi!tLwPmB}GuXNfk|lkKgt5 zp;fc@O9pZ)$P;KUetCFJonoS(J4vD#_RmyOY0%yl+gyl&v%?Ek_Th6YvP}ZQTg2ik zws!bRS7jgFWPnlrYAU+_`^=ZVY~datYyR@+jl=Q=G^`Wmzykqa{{ke@Y`tc0(%&VV z-v>aY5sUJ?&cc&f-$3RVHg9QfyC;NVr3^9$QtC2bOaE*iB{_lfF~7XM|<*<>+2!`8xz=-LXw z2L1p~_w`4$oaE#|59D{P>Ddq%L+Q)v?bV`kH@JO(Gx*N6J>ND*D%fg_Bn{Ln?Mc3z zoE`7^wHMExHpX-yz4o^rB*N@Kh?Bjt%<4?5=~|^5@Ff=_Gd)bG|Dyn)`m))?&+7vK zBfzI3_?N9ylyHqc3w2n{zo!JD<3o>z&x`FVN#h-OdB+S6NA}P2Gq<87uEVws=Uzq+ zz$gB7SuMM=JchREI-(K9Hb7%(mLF0~UPAVrKKATp;ObGhD<3jNoI7(FsV~r00HYD!=%IAI#;_U|G-`HrdCJNq?Zo({>sBCj?SamiT z>z+mR<~{`>VWb;!Pf|v;&;vp0*f6bBiv>qs==)B)PEM({{2I`66(C6_#=i8y*HSYp~T(gBe zQyFfHszc;$mFpE%XBlW7x_k4u^v)ri2*H&jfQ>_uVPmT~1@^?cQFeQ~{04UoP%Wq^ zN@ae?W2bp(TFTGLziNbs0;1aCD1z84vTNeqXwK#AKk&ZetCGgzS=o~|b01jj!%QgE6eE3E-t4B>|A;(@7ZCjWpJN3}S41D3}{MrBGT~k)v zn4k!rKy9hKoyC;9h59eHm6b(ZLp`QU$T8&xPe$^1Fa?~T;~NC1)@OG5s%kHZiUXNIJhw$E0vg)L3rltu3Cm)PQwgg+QV)*R3{kEGX_ zf}a4=f&obTev}}ul6i4RU5sw;{|G4C8CSNihx$XuL@y3%>gDsBMAvqi)FV%!o)Qu14j28MUl!=t5!ju! zy4I33r2e$`wCMWmVmV^N%ArDcp%8z4wKclm@D6W(^`U7P27`j-d(l@oN7g{&0%!uX zffD4{)UITc&hum_${~j`!3?7p`NdwPynX8TK>nvDd$Zd;yGW=Ot%`8-yaClnOZ?@0 zPHAar^S-~{lshJYrH8kaRPTR1O?+0_qgdq%%X|gro8O$i13)8qZ)EX9-2c^ch|xtq zgOx6oF2T;kt|NlT#Heknhh-q0XGpYVMT^JTv#F`62ey_}TOQRquc0zo{!s^hKN#_2 zD5*qF#8VGPs&Ws`7Ag+A4bXiTi2g>V@c$(&zgvhF^->UkZ8Kl)T$vw+Z5y3gR(fuV zTt?=eWiNXo;jp%HeK6UR_aj*|SW^^n|E`>NYSG=GUB0)sVPf(#8o^9}&#_gcQ|V0{g>yQe@yE6}|)*OU*-H8B;dPduw;U zl?*3z+5Y*}d)?x5E^f3gI3qTnDq^zTlI zp95b^92=mXjDxovvgC@0loADpmo9RF`qX)E zibZG3r!VSw=>oHwJAKb~rIfWs{LG^qzyt()-D6IcA3${rBn?Fjv6(Bs^G#XXD2QDN ziS+y&VS8@(Z40w8=OH6B5_nTym6<)z@2S5@vjT5{u7m19qnCYSLRVR6>8!b|ob<@> zcoJ#&0(cbIsAs!P>zX%4@Nqp?&tv-^_>gkFhN^pAY;GhKa)ImQDKz@Auy(f!V3oKa z51o5_`CD2)eyAFh#@LV8NLe<=aPu)u!j8Ip2DO02W>C#RoDd~q4YpIDKo zK%Fe@A*A`0a^?b$)S|9xP2X{kw$Av^)c!z6?DGzhY=ErN()bY#65-y|B+@HTq=NxM z6Ede|8Yh_*X*Kgr{i~|23&+(gTR7~@LQ2&WS1uR%249CLG^+s^QF%eO=5eo};740FkR4-2j9Pn^ zpgP3tDXG2gJ=28jU3&@RLDF_P(npxS$i0FeN9S2Bcl|JBY*3!EVuto5bv80`ymd(ANetROHN(i@fT z;7b!R*}KVqRq`bS53?w~nZlyaGVA(bhO1?6=FEr2Q@-4^K`{4pLC2h-rCxbPv-G4+FG_HFaxdI2y1nq8cwNJznwe zz6-7?pioz?XmV#4>{UHz2h3;5M_YKAC0d|fUXDbi; z@Fji~SH}aL6E}Fz`{}$|PHmfPqA0dsn8Cw=Pf*UA{`6#+>cvO@fge)$FBHyoh2hoH zc~}|sy_CPQK^g8RREyi29DA5d^mRau!HiNqEoM-Og|#i7%NJkLRtJu3X^z1+w$#$< zF{euBU3y*`z7`A99e8H01xJBG{MU;@xZ>PE@2CV7yDsj7vU22h*)nBh4i>;T z<*CAB1V#p(!#5&3_5NzA7~2%tko%j`W3icKU|=e~b1cAE*JS$~6Htgm;l|U;#ziRtR zN)b|e&8?N!^%vs>(Ci@AY8aj$)84*;GJR=iPCrfss0V%UtmeZ&S&vL$?Wh3a90?2_ zL+8vRLr-StY%oX#kYfPaJ0p~lSe?Zjy)PaVV}1oEy4iOtU~5)=hKO?{X;B#RELD_+ zmeluIA1^4F^CAgBF@E_`SJcXx0!+!_wt(n?%0Qw=-B-ey>_OvzkAJX)5;p}#W{ykY4{?i?n}qaAvHr& za0Mv;vd>19JX5Umr%dm=bnL8XSEi>z<$PAU$MpNe15e)BbX7a| z8c{rV1J&Ob?K&2R=WeoXoebRe8#*UXbyB0ve)^P_cPWFKMvPNPVi9Ne;x-wY?KJde zpij67TU~YS!~NKq&FI@_j1MxJlFiN9_R<4V16~rYDP?hRC=H&SH5g7${5JbYs09BO z>usPS2tCZAz88|;2X20tWaxJyrj|kN`?*i9xJg?rV*CPpi-JQeV(fGDxq3}=LGnFq{7+H!=oTl^8 zYUqRHc$N8`f8=RwbxjhsI<0SZ<4dkO@e_seWT{211rb3mLWIS2aT~+(DjjJBfN9B% zFmjtd{HQhOA_N~ed-JQTB}eM>5OCEM87YoWdg2uua!2%^Ngd|M(#<(N)l@pJxyL@$ z^BZuPTd9Jv3RKDbqZbPuI4YtEKB`Il7cxsth!={k+=auig+)<6JDcnSj+W1Bt(1}2 zZT5$Y<&=@j68}j_k%2YX%u5%W38vReuSSe=j+C2@xuJ`^&e!kx`jvPt{3xp%0CsF- zvuSbC`Q3bUicOBlm*~t!E0YO^X7%m#q6sRbj1gVR&00I!>@0rb`@zmSSA;%%*BI0o zBm^j3)V0$-|5}G16?8TJ=GMbjs6lBNK_t^dtfTHn&OO}edQ4AkF96O=Ks&Q0R#^Om zutU?Q)IOr6@}>Jt&XnMd<1(dh3xggVo&}X z70a$B?}KKW(vH}b{}y(bmm+mfu;dyUyR80q_1td!^a;WPXo9G%7h#|B@HIe+;}p@ zMkO{)e33p3M(5&v*Qa(mVPY2j@JENf$=O%tf}4VP^3t!Q7B=?k3@-AW3{|ckmj8;O z?AFA$vv>E_Cw#Pin&c4dsS8%0At-h#wK#I5wHFvS_#wE0Fw+Lpaf5jhGowrjZxfZD zbn_!B@i&nR{4gm*_HDEbU81ru0EQ!I;m_gDV^|A#Qp+R(dN~c`700u7udg>}6!SBY zi5^@MR&olAWmN%_;TBW8ry2m2l1pp_X94Om*9u!o!7kCgm!oZ*5zO!W+Yk9qka0IlZvmP~I{8AR~O8X$5E z8hfdV5CgM7<<>mnwSlqC$Ed~#dgPHE^KwfM(~kA(fSNBaH0ldgk-kW}2(oxMYm;`pAPb8dSvCx$iB3NaVu z3?U=XVv9#yS7`W-)ZTsK+r3yDyV*m`jcJ)6cv;oEY8cgeG*MojVFS=bR%{xyeg}1~ z41Mq>12*>zu<9%=F7E@&(W4La`1$RD?3u0|JrbO2u91;@jR15aZgXX6QQwtr?jruu z3+2Zy>xm*6`AG+2h4?=y!_6X6Nb-xOYuMv1k%vIKH?a;F~xJ*ZS^T>K}#e zFXB%SgM5Nu=osnF0DWrqe3MoAl4vO%81)QBG41F`yXOQ$%Hce?*2KeH9Fy<4o|z#x zs2vx>cnEgcs4n4R;$QVzNLL|nC_t=!_G#pg!dOjyU?Z0QjtUiN=jZJoAiL7?6XUfS zUsPaHJ+r>o*S+BHNMgMFLmYF|Ss3MXzv&QEVQ)drj4|^r_8zd~{sr;}F%x(4z#2jG z*i=q0E29@%J`e9{=?3QpI;VHp8E5xsUK1Qmc6q2x0PP!AmJwnVVV&zytkq%}BCn_J zP*r^#BQKpt_p8x)qVR%)O|T1hj5BO^0rz^P#CE&t-!L~)dVo9wVio);_VD}2W*PPd z)Z8Bi9i1DTli9i;4X$>7N=_Iyln9tyx2_{NQ>NLl5a37Pk7YIgX?$(S$o2FAI$^$` z=(jh*$_o5*tOM!=CV($Xc1UHDlPTMr$Yol%E7o*Q0#FfJfH*Ls?!1!6@ClV3%Fc5G zopjB(HJC=j8aqcAu-M?~*C5J3>(5<66~&(O*v`7Lr{}j8W1kF~hok&WN5vQ$Tc!OiBO5i|%chTH2!ohkwkpMN zJ*{`xtbb}TM`FlX?qA+=;*ptoY=X1Xv(9&V<*B*PvmnjsBUzU@$01lu5Td7>W0|zd zS6Mk*Z>CL`zUF<*Cs1Kdk)>-KBX|NOLH zHN^BqQ=fiXF=f_Qz9aEaje^PIQ_ul|4-Mp?Nnf-|jq+Hyaeu^ae2F4#1u;k?!t924 zfh>GS0^x57#$a=EjHpU_*C;>Sxx;+-$Qv>UBvaR!BL8hN`ee{;kb53W*Q%%cYp?l( zo00zMsgl~eNZ)6xnFz&k{t!c{=2`b9TYnYGQ{n!*wCR#u&kzETd=MZ(imEOj2{V|v z^hSvG5t}K%5Bt*iz#qOaJ~mDto*cai*Dz|38rx;5!<{3xev!n^ewSb7j# zg6(48lzw+H(!saE(7R026wMWkbZYvE&7v4p(kqIp5XBgWcn4i7bvRx(TxO?g=RH}X z5->EO8KO1T322lW^Br1z*%z8Q+HCPncVrt3HE)}LR*|DHaZg>rKV#BgB|A+tk6sbFwSYRPg1BC@%(@1ITn2CGV{`_3L#MMjHn zW&tlNR@~YRFy2Prfo=K-GrJbvKAf7uTJ+Ojq7izYd@wr@$DZ zx*f6b(O{i( zVf8T*cw$1&@#KRHbjCd53R!)fr1N;k?*1AXAWYrnAyu1h zG{xR(7RkhCV@_!n5p{^fE|dFN-QJT3P;3aGEHBKq#?WJE1s^Tb-SWrlSpjH zV)^5NN5gN(^9<^B!Zb91i2@7#m}tcmh8r;BWX?Ho1{KWU0C92%3xvwrqR-gYKB96$ zLe?b%eKJrvkz}{LyP_tp4eIG%Wcw3^;&ouHMmoIjyH(C4vL%=Okz#^K%}8F3@{isj zlN#yoj2Lk)vJ*KCt4(7$`-l^(H0W?)8lTE!$4FjYG>iBx5sK>Vk^Pize-*NVpxyiC zDAB_dfip2mu%|6d@9^n;pZV+Qtf4RfRK3ScP72=+EVM37sZYWx~}Q4H99( zqcIs7;Mz1-DWUG#0yfpy$?8i)+mI@=$;Vrq<~8xgGQ7}Y8`1N)ym;` zEF(-6CuQDb?M$mqn_^*B80Ua^K24gwZeBUaiW=nmXJc!veE;Q;mFK=snpl&6{d%)h z2+R89|9y1hcdUIRHnVC9mRwECTEp*o-0&SbP!&>#5mAC|t=~<~C+!{hf+m%umxp3c zF+lDiB6^I+o7VB5S>!kF)R&1Xg7uL zZ^fKtNR{AoqcoUi_x;h}GDYl@esAS337k+4efn1eHWd>XZoy^Z?=$Mw>$Unk76{v= zpkwG|J`04R%o=nV&{=fXr=@1Ezn#-65n1+~qM@=OD53Jf%_1+PX}`1=n6|B}8}^dk z;+LwYQE*LWJf*fdqHcExAv@Kk`D98h2m#K*+NKev*0+a%CzY5EMyVC^5kxjqR1Wh) z_3}k;ZTkbN?i0*niG+Z`>Z0IfftF_XlNdxcd;$0mZ&n+xQ=EOM_vrBrD^O(n~#=#L-ci*9Aof_KkQcsI5<;Ath;b&G$&)`3qhk| z3TyM|xOjZiK27(xZ7zz{mrx4LeH6m!unT$45k6+VTCHu9%Hh9pGE#qJ^#ibPUKwi{ z$ZlRIhjGrE_fi6Z+^76Ed)Sq?y6ojFVYhzHwndBC_oRHFLf_?pdeDc}ht#Spxj(H5 zy@pbM@@cT!tUFT<+qr&g2SR@E#sfo*Jc|Yqkm^P*0s{80DcZGF9oYV<*vS4{R z+!nQyEc*tQHzKVIW9lEtW%-Npnf`=HlTB@7%9p~N6e!(jW4#|;Vpf_zFyhX>V+KGLsH(Tf&blV*~QYJ5VGo;u@v#+lnSA7CS={E)Ai3g^Fn`JgMETIVl*eUy+7Y6#j>K0kh%?< zAWt({TyMbB%C*0Q`a-zn#xCX~Ph6+F;aFJK=XHBu0z^@1 z_EV$;ciJIar>~n?Xa7VG(m&=B-K6=HtJg`{jdm7x+O=qTSVC_o{GVifeT&!qcPeb1 zk!oU3mA10=3wbI@x&D(Vq~$l(xH?M+8mW{6rd``;;J9r zlaJhtVu@mQe&D92+A<7Bwl8_~p)b|`SS2T5LqcF0@l?}qZ`bRA1p|)v)?4o)VMM$h z{s5i;o%^`GkOOzt^BLQ~hA+Li#k+kiZ?L z_CJ$1uEmCoTyMKu&HTwa2Ds5s;e(Wn?qbnoW{@{FIw;w3XBk25uUH5Z=9iY(7D~cO z4@IGRpv62$0t>9McYz;YozdoDci0T>-P+5q zUdaiE!nykCO9jI9bxveYB`?HPI||ZGvtOwt_nT4oEskXT&G=cc5u_D^3YNSS+A{s~ zUX>8YD-(B>3R%hHcxPT|D4jWYk(#GWOZ@5UGBlr%a|lhqZC`G9Qw1e|d9yl+c?lJd zq;>qOeRT1k3}c21(PGe<*fJ65c8!GNS<{<=uV)c}2!va1&aMV0xW;v+hu!+^Fl+5r z2(wR8eyax>1o8)Jz8qHDC?87Alde-8Q!$}l>hy1ZNtm#6I0*k)4zhzRwuwo{nEG~=tp1oxGj`Y3uVH(HOyrosS-yJNH{y{; zQHZ&tv*hgwBoGLaZ+#?tE841#iht@(8+un1J;i>VQv#wD6FG(*^-@Ahwb(##JHcQP zuXQgr{IXkeQ371?EG5w2CtgCI{Xe$8GAgRDZI=`Tq*J=PLmDNeyW63=M!Ez<8e!<} z?rsDD8B&q%k{Ibu&qm+(`_5VG{BY@Fxo7r%;=ZqXHcmf7u&eP>k(Sb@baq5ngD3yz z!I3|QepDCdndENZ*?1p30VE%tSP8m4-PIoXCk3Ctf&=lYC$$zO1a#~BC!K*^zbED- zVFlNp#w8SWQSC7y(eXP8ezwlYy1R<+S{IIQm0e9>Y>YlNDbYtz4N62fB zzaNIB4q7DsV`T^Uu`nb#y|UZ&&cr{s_$fVteL{;J`&8+Z4+KtfBv^$X>E<7b@wT!| z&hB=bci-gpjW~Yq!j6Rr<&Pd%T?_{@GY2Q`vlQiJY>rB{BELSTtqEx^bxC7#4^n03 zD?L8DdE?DzzbZ`;$!AB)#r!Le#VB2K0JY_GoOoIcNgK)jZDad7LsK24rzLD?3`S8tkI_l6x^T`M9o3DRy z_~`pof>~~~xYBx1N*HRMvT-udN0=A!7|)7DKdQxQl;_5BHE}R`dUiXOIDS_}lASU) z^w3zM%%G`pQWbC0YSQy8EnU+lcn{Ocy*Iu#X!)$GJ4k?)b8gnkdkUjI zgno!zLoif#!bu@*Um$07k7n(7LBj+cWH+2^sUZIusV-QJheWY|8YP)gtSfJfVnl#G z9O#x|yb3@x!nLW3B)81fwk-v|yrJ@uBvd(?#yrTS%NgCV7n=?6$iRxlBoT(h(<(^` zs!#10?rsRl_kyX--TgXwOWusEU>)N@qJp&@=`-s9pmbn4%8Pd!p;07nmZGs_XKG$UVD{cCQ*wOyl#d;uF(W!CPo;B^Y@>rN!(agk@U>JhqD9p(WOjn(fYxF%_ zSBz!3GMPp8v#j!`exw6Ernf|xMg&f-2=_eJ{c0^zba||5E3sh~?ZDG6R1)~)3i}y` zp>iSE6u@?9b(7xu7qNY_{UBrW#H&RrkuUQyt~3%%zPC}Y&5==Z%8+_=3NIlSl7(w_ znsn&^{X{Y8R2MQJJ&`;Q049cQdOW0b@7 z5rW3;F4|KNt?%inVNPh=db2i!Oiy{}F+ba*iObm1MKAtFDqcLx`MFiROabIybU%4y zbg!XVFn-JFhTrD_;gu%N4{EFtm2Y8odYQ1Hc{3NO`?eg<$3@}BkkV;Ed}!zVR>8X$ z*7>YruL3+vEq|zW9m%reV?0^uG^t8Y{>XAX_l>7po%c<`--kS(*|dLBkyHd4UGO-D zewgeILtY{o$@la+|JhMS?IF6ZVzOo+e_UFuv*zF5Vf}bo$<#0v{`wHLR8^) zzKlS|g?L2+I^nOXpj|+uG_nJ>U0$2EE z`D}+j5_Yp5pDA7B50SivD=$S<2FnOn(7l{pWimo?(As|GBy@ILALj92YN_;=Xq`vu zW0AW^X73%xJ^K0>T&3z4St=7sh^%ur>mOy);yVcDx+T6$8f%e}KI(yi@$m1-v+CYq zFtz@^r}zy+rvaABLh4H1*vP>4w>b;%zN00ygeN+S2JL?6;Z#JBxAK^EvTHV_t5#pL z!U-@Yf<$#i^RwnLwnF`xBx1FpHJ#Cxqp$z7Yzu4(va9k2M4DY`4xU{h=LUgbGFfN9(SYu>vmDP!6)zpn@R zF{0ld?T@7QRB%l7DJPLYcT3W%6s07r&PS6|Wx;9*yi(NOq$cY5T~F~v+J=W~1NFff zZRk|MPGXCer4_BIJDFAPZ*p`Tmgc0OHZI<3Il;ZWUk4#+BfC{eR|VNh%#2vc%a8ZK zoH$dn;eU$p3O(ywDq~Hbw9|HyO(j8x9(6{7{_|i;HCAKkP14dT7a~}zNiV{ZtLDY5 zP1Qal`&6$e+sOjiwuO83Kw@^9iQ`*yfvyp;*b;+Cxl4& zkc^~0?t>#*0eJ+`r57H>Wyw`$o_#AL#l$B9h0-s+U7>7m?>!)23N8|xyfpKIT3SQa zW4VmXTl>c0Qz#_b$OIgS3uI%UR{O}Hsbb~M+x?2{A)(#e5GGE}D^Zp1o4eIN*$%cO z$N9|;bCg~pIp|{KFJ@qLt6LlGNNgA-Q-dzT%5FWR=#_904y?>**FFB~S=Kx)pZ?<@K)AxRp2atiIxsl~V zA6(H&fOa#S1wd9>mn<|eAOlTT2r3psQ3|gaYOk;@^A0+#PQ(6UEWbX%ntGn;OI)Tc6MLM zc|!LP{=A12X-9!kYTixjLUV$T%H6#A%n{pT{`_lu#2~bBfMQsidG+c5BAt&5fVW<4 zyYSQo${@FRk+2dbkOrl)T=0^5G^W%=@5TK0#=gw!^gY70K7H-E!xuVl3UgsDb^xPs zf*j}jyn7pB`!@htpy276i2u3f^LaCDp_vx;Fg`$>_~+dl{bxq(ec*Ljv2Ra9pise@ z`RsQZ%eL^-6OsM}ASZx+nxTGvc~R}O`pB5keAPNXUNRZ;lD~Z9&%_KjO2^^&(d!9c z>KsFyOQQ80bcSyN05Y;Zh;yZun8_lTy5hm^dg%1@47l}K=@jg_IZcgW+vHi(muu|; zfWryP_ZIpyQ9PH@qgtMbw9*@uTDU6bKk z?x^M06Eda~U~Y9w$U%0U6Mu(P_-f#4Q zvcX{X4{tEkG!a<{L#@6H5o@MO&rvQ$RLB8)qQ0+}3KZvk^i=0jiQre! zU+wF5Mr+rzt|HE~*UpV(^+xYS{vA)R;);AF-GPkDz#~-=?H!PZ=by_S&qsryz@zKc z@gdm0z41x@z^E$lp|{7XLxC{hr!5Ej#Ky}loI}5vOWwuDoGso6ED!9eiX+QJ^~_C8 zfq&c_bv>{-PE3Gwz0dJGN;Wb0!mIJOz>6`DqSX&K*}lSZ%VO33UB=FVN6zAH_~;5^ zwML=sB+3Sd+L;TqMeM+1Cp~=BacRdz&W}o!G3sM<~p=^x&1=QGo0-o!|KHD zrIMbZBN+djHboZ5=d+aQkzw?$k9hl!DWQGX1%Euuh3e*-8ruxB)-yMW(wn5@eSPOA zx8~m8#|l|nK(iG7Co!sm*@8S;${C4-yu4T66DH=$~%>&(>+d_b@PhBakVoCRmstW@V6Ru4G*T1#5k zv=nn;hGNmY@M%q{dza+K*tZ<3AyFV7?hBO6_w)gbW&kh=IHG8hCg8`*TLH9sCpbpj` z2!uPvN??=d{QMi^24y>K9QJ*zH}A!kerZ=e(Qq3{PPOgWV}-7kfP~6(mSk=-MwRn!cm#a8&;@@~zehqw-?*L9^%ym}wdVp=@c5b$I!WGQlZbXzUxhJ&xHmPZiY z3DlV0>3_>U@E^Ss#w%}FsUDEza!wE}Qy2|qwSKjyVlr5c4mIxW+Rz|1DVG9vMRe6u z{o3ppN6uPlHaI$(ZDGtAAELlujr6hS-M{V=Hw+OFp=g*~6+CAk+G*+7BpPYcPMM$* zJ@TY5*}tCK@yT^moiz)zK0Swc?i|&1kVS5{AILlJ*ir4|mVhoVT*-IAdNy(T^$`Hr`f!(iC7+riRTNmU)VM$(Rh5SOJH$t;v$tUE5m<(dZYrQZL>xxChlJ zuDolPEBl{rGbQf})49uer(Xq9;{Nm%Ok}1D_8LDjiY6JAjd`iRx4v7=#^;sBW;b2z}P$&OL~qLa#|rpu8KW zewaR=E0F{ERo*133T@JfqC3f_#%pezptLVTPu!gM6X07>_p@Frp$$Hd)*+@n_6`%H z>k6_gK(serr-oFJn;&2@XD`oqY*$5-dX`V@k%BOoa^SNm*%qrwL2eaJxL4A+_v~vf z&s~yB>KLFIpJlrw!zjaa?J5Hj?x#k)tX%4zwi$levBENG%69}1kUEe+X~V|0K{mm* zc@_{-Ta8cACB*b+e_yY`Y7A=r3z#y*_18ZQTBErsaMW>qnpn=P`1Vx^wVXyqABNUf`9C9H%{Hm?h3FYj}sd;9*IP|! zkD~x#q2f^7i?_Jv-_6l=YFrUol0j`AJKpV>X_Ez4F-b*3UIK20^ zYON*cGEU-k#w+JvWhL3CA~E@wae?>!NBH*%i?a#kk{>4EW_S3Uk});__~#X{ym01Z zULmHjK;zn_6IuaCII8xlke1Hqon%+{+_0#{HJUYzr?nw}B*y6x=iV@uEJQnl!sVubDxl z8;(F=WFmVZ$P`D#rn&uit8nt0cJFTvVictt(})m#ILTxH0jLAaE-vNKbpS+acA)4e zmd(1@6w(Q`gCqvG1S8WdX%InD8h}3ag#pkM)n5h~AB@Fw5849@ViR@M?Y-q6pudle z=rv?`lq3_H5L!AJ7ya}i8NtAOf`F-HLY{4hOSopysGC~6A&FuA!Q{boP#=OBA%zBE zKKr1ii=h*qgn35Rk#a(Nvt6}ry1wVV@`dP1&a|S1(9;AsMf0K4ttXIdFZ<9L=P+L5*zs}FQtk@iY;k%Jc< zXsdui$oaQ|^o-i|5%Jcj9-fGr0HT>ut0g)uFf~}6vDT3pPY8-(=BJ#ZQMzPEi<`b!%0qeJbS;yM0izp&s985#hnW&kl7;@h7aWt>JVboXza?cYqJLKw*b_ z5H}{~L18Y!a4BseVkY{ot{a13>!1>xY=+(`Fy8i<(XU-=U!9gGbM@U?O8HO6WoV|+ zL{phTWpE@K1@cN9vd}^WfmW8x#;q+Cnsg9aXi@pk85D0WT_Ix4(mvORsNT)Gc&~Pm zSnk2bk;b@cILv6khp5?<+3;yW?U+X1CawXcZCE|IfO{eP{08ZMQQr~5^T{H)bj&Mz z8F^pbFdp+ALzq;{`gv)?k3A&}z^6rG6(UnF8}paUsj)RuH7OIk1GaHvVS2&*<(ZnM z%ymYC*;BceN9c?ZYE@h~UYMoMta(npo@%_sdcb{BLPh{6Rj}Gd40;w07&`*dI|OFt zY;-B! z1>DMaSuw3JUl}IGfiiI7HcpQ_;Hw#!eS~lc&sJ0~$ms4-SC0tghXyB%mRBs?##dg_ zQi4v^t)9(D5X6oRIB~UbTKL9HVl2XSrP?RFAXY^OUu>7~WLUaPHV7YuE zeG6OIGgiJ=#lg^#%SsAqJfCzH?zIT5NR}RSivu3R3UPE%z^CPtaDUD@ou?vHQo%z? zjLsLOwusQ;U5A*#9Y*(~bcnh#8TazMg3CUdB$J1IZla8NjfLm@Z5-3F{b}WmWo{)fxBd^zr_rlzB%9%Y zF@s|Fj(UC!fE3&zs&v(X2s1kyA$gC}W?2I$_z?j$Kx@U!|C$xWhy{4dr4(JFk5a z#V>|7-Mp{r-2#78VE6TpZW*NBc82_6Eh}+S_ zDc4RjRR1zT<7!OR$No1jCK_{+$zzZN4k$4P=FG@4g4Rg)86%vhH@PYV1;4K}+qnar z9$fpx?K@}t?Xn)^CF1-Yn#O0U_=uq8;gXIM`|^T$Q_^Jw>vg!PK7jSK?Wy9A1K24D zvzw=3f8{j4_Cyjb5%Sa*(b!&ZlNLU2FQrVdc16!qd~WTQX^(;Zg;E$Qe+6e>@Ef54 zptyv_YFfr@x?Fe4pB6rKoF{CX`o z?mmMS%8hU2O8cLM7J%N|6s+C=d%48M$eLwIPiOG(l}fy)*o$J8&qy$2JD8+fTS=Xg z`d_L>^yIa95M9E|o5mR+O=0Z@C9Gl1zB+;bjPj14iGom2QvKJX%x5%9r6>`{_{Uw6 z25;i$nd$zo;x?Ham>~&x+`}wDb~Pq!OCn$g^t6v^z$@5-MI3aBU9m(?KMkb?0e_a$ z2Us|iPit3n7G_6o*@XrpD{70^g?Z>i14A&(#@|h3qg*6dH0c=))Qz295tzD@#c_vp7D`_>RJ9GuFTeG&G7F`APr_roHttYbWnq^CIm$- zTMqeCuY-uw?p1GVMa~0#B78ev9o0V9tZFFx>#2CUDJS7KD<>i)2TcVd+ebovc;OlH zSnt?~XH}C4&7RlNwJTt`8js^_*Z-j72R58$QL{K*#l!ei>Z97WdoLh!nn!c9@S#ep z6V&LAGZ<66K&3C@2uBRO}FA=B1jh@X&)=R`%(sW6B6Akqz2dF|w@*K}rVJ znTfI$norOB@V3D{XP1(7Ex<;9ii91xi0#efRmcKC6o7y}W%7VfW&wFPL#XE82$Ns4 z9ALnJp+d$<^SydJi!Cj^j+gRz%t*kV4yk1$geX3#M!c?>f14b@lNR;n=^knEGaaX}jHBF^HQc z8gUT5Ab0{^DoAGyIhVvnr>LznlTmE-9nS>D%w=V^G@d~f^aWZ(0-QDeh+RrH5bZHG z>t-xGh;iP@`Yh3a}sqdt-BQ z1$VggSB~pPfKUjX=zK5(wqpj6c2Gfog*KXtx^s5U@N!lg)mN~Cr#f}jL1zeDgRg{Q zg-DA;p;7eSLg?y6a*{p6AD{szu?!7Ky0tzb3XI;yXH`s|Ug(xSl^TcVJUSL(hjKx> zT0-T-5*|D&bpjlq$Zt>o1rPI}b>QYBA!f=b;m+SK;##I1ZuR^)5P)6Ez(P-Kvc7P# zl9W?Gzd|LWb8$0%n|zz4SIq?I~_j_F`Ce4O%|nGd79Fz+}YKXH04^ zM;rm8(M=VRU?ROApTgkS=b3pTjyGG)!}av(lRYd*@TyT_00!y*c+$A$0%tZrF=Y*G z!c>Im?g4-)nqlls3x~%)wyi{;R{meeRUn+Us^qdVsJ8Jb?<+Fo$KCKIjxc-x!5PU& zr7Vk$6G*w4=0AVHIi_VC*m*YP{pst)RH3I)6dVDnqIOvo*6EsA>a68GQ3R|fI0qQ8 ztfv7}>Tod%WH_$Udy9E4tV35l@tmz3eR%t6^YsJzapKO?##krt`$a32xb9-~er&1G z-{v&oivV9+jrdGlTPhLWh9+fZ0k%*lG@HiCjzgRjLvRAuTweST~-wLpa|gK41!r5!l}gaYWw*fE9Wzk{+&cQFtrI&L=m0+l2JD zk||{xhLj1@0Xw#lQG(H$F1FjuPpl&~R>M*h*X9fTuvhOCp=WT4H1UBYhNfR-%m^{% zPr!tOv6F4F6d(^;d}N?}{yVL0c<3X;(HUwWsS=_qO5Z}mlNpvnxNf3-sdJs&<^8AC z#>iPi5J<{UH!(sD19mn`0A{xjac^g72(EkGfZD|FvY5ZNX7b#so;G1}L|dpyoG$$O z?}z{qH{RD$08sWKVN9Q-EFG!TEAoSm2o|@_K`B6@I$a9k^of4eo0D6!211hNC_o}* zhrY{Trv(+Ju&%zSQ|DYM#@f;Myh^%FIZ0Oo`Wc;No1n)XDo5FBR4)~Tr&)B5mI|!u zfbu`>4#;-F3;z%!&HejNZs1n+BM&oxBF>o^H;Bbzdo3N&MROOkmfvfK7Kp}eo?`Zm zn+$OSZvz6>jLd;l;(%r56VvSv3}h= zDej?hU1oAoHhx=uAwmRD7q*1S1~sSo@0NPS%kvq6F}LiYhM+eJRZT1BNk9!E333W& zIIGJW9^0R+grAwA92&XY66Ko7-p=|B zU;BiNRgxb%+`HI|fa6q#4jl>Du|8crw`^CnWv*c+1J(^g&l#{*#(6|^#A~4H7fBoQ z&AXplKL!mta`Zc8uo(jGU}RL2E6G&UljihF%rHC-OL-;oG_y~bM=EiVEW1{pU~y=n z!434kY?;oNcUmGC&Rv6fM!3od;r{25->I_I;GCTq7;JQ<@WsQdnPoL@@Pb;~PA=I! zr|K*3GBbG}4wFIhmi*tPTm4n?6bNlN3-0M~Ohk&6I}ip_!+(SaIF*X`&A*6>5(2qkk$&&C-ioNv1*A-;eFYg6Nvc$#lCCr0l*_Z$<;kB(Snnt@eEJ zKM6uTX`UOGD>(Ycqg1`Nf|C|9N&-^p{eY2nf)BMddFHa#g|9~A*Y|hZjZ$cy^N9Tk zk8nwaxupUq8zsK`aaDc$IZifGwo;Lo+t1khF`am?P2e{7)~B5lohA&N4)hmG0I^25 z=d1W~Reb8-;3#@Ef+I+rkrtDi%poCOw?156d%glve9fxKb|i znkE>Wz=9T-eB~M#(z#5{S8viol=3u}kS}U^H-<~!LDsj< zq4FI8mZbHAS2=k~R5AZ9kucU#l)!!-%Mz=k5OZwA(+LJ>!yJ$tEqhzA!t8=535ROY z4UxX#F&oIHuz1g@kH8iI1ow?n+@;$p`Q(-9@+3pr3aK?;91;RmMHI z)fCjv%S>OZi5w0W=Zix-ogNUj&UD#5a1I z$34Y~FGY^N0F~B_llSfY%TQGadX(COtS>e1kJ43*JWMZ|v_iWlwP431YB25j!&mI> zz+h+e*4tG{tk=)`xW$Wf;(6TTI50S;M>5@1bS;~E%ikJh$doz;FFL?Iu2IoP>(bAs zJCz9l#O`9;Dw|Ru8cX_y&4j?0jBfI7Ecyo3ev`-BSvC>Vv-w2-GnQxHOB6EcTjgn; zABvB&@MGnC&dUl7x{6H7vz1~af!{+{Dxl9_mjy)~Z;oZO<>!C+AIe?>=%DxGO?uL} zw=dSLAjW%-{dkV7=AQO)FI)d#_KxTdW7*#8rT{{8rVA~ZLk!0}cYh(o5Iq3ch zP#_&<1fr`%d)@2W?AX*Am#hO-F2r^Bb zLfVma>;OZ;WKG$~GL7K*`IiWqBIa0x}l{dvURr%(Ag>{a`V(q87)7P_IzZon;s_#m6UfCm&DCO5)8#3n|_|9N7}gI(XG%mu-=PVK1byZgcsD-Ng)0}>jj|P9}BUd z5j8S36kjpx+fl2_)Ji+&eo2xS(bQt5JJ>&F7XW_0KNy401*Fky7ER912fhHZphyFGjUxb{nBXPX#%0 zjB+?wpY{CptKRuu3^To7IU+UfZa5m{nd+1Y147D^=PV1QE#oAIDgjH29Kq<9)217z0lyVs&jPQL z-eLhQv0QFX)YO1`Tgjq`^YLVL!!D!MkAzep1MjT(n|rS(U>B$t*R0ATqaSGT;$o{uHpKb0)?dUsKCgg zL*&-kD&!E8Y)x2)jDHZHFicnN@@#8u59_moO7R{M>m`1vOF@8b7nklD7m`{64VkP& zq!{JmFS5a=K9jWaURmX%k4;MQ&hAc*dSTQ6D5m+z3h`XZDnqBKm7*GMYD#Lxt%$b? z%GfHHSY?)X?oIk}zP2D@80PCR*(R~iI4n^?2-E$Dx#?q64nL&b{mauNBnEv4y>NHC zDVB+*&l}eB?GuUet>YbBzbX8B1={{&;N_vHc=@f-{q>GeVhp?4mm)3K3WGO>1h0M? zRJ~_L;GQ*Bnd_04x&HUL@N==lJ8O z`1WAu+kpfzp<2Qim-{e%dSrQv{k0==L?Jq%8CP5m%0vpo21#RIeE0Xj0 zW9_x!0Y)fcjT8X(16;k4^JvIrD(ZQUk31lbrz!NlZqnKX$&eIxYK|UBrr6bQ&Z~hZ z@CI?|4YG1VIWB4`PI{XK8Gz4&a}BqxANt~TA`2{vMzq`PquUt@J)t2+EWcIr_kX}N-FmHOz2-*Vr{_Z&opjysnA#H5 zQ*r7U%IK&5cxWgPxMS1!fNqPn?DchdC$wuD?vK8KQ8V5KE1s)@(GUsE27bu7jwu}e zs|Ajc9#eMm91Oe8Y~WSy#g4KW-e21TLpR~vLIcpL(T`-DVbf+3F|B|EwHFHCZNE$I7~8;}>A z?or_oAsH#?(nkIIwZh185=3aAsAwO8LEyP4cfZOXbZa!0DixL%D*4g3;Mh_+Fxe_z;u8=Ulg7wi zDeB&|Nm8_NUk0Xz(M^lcv-^p!p7lQNF^QN?yg6M#KVCtn;#r01)&IP7H!W|gzC*Ni z7BOB}bTN447`Qxp@F%O?uc3Q=`-%`kHr)@_U*zg zGKvz0%BpEpJnSy^eiL}{e+CapIQ+Q8A3v%YZ7GN_0SB%cGOkj_gTACzQXC$=k1!Ci zG+%51jh2kRJWhwrRDss}!kDAC8_0%Ev~_fNK!eeZPDAI8^YxaY{p;NZ(J#`oLeS(G z#^v81D&}ZqBO-N|AOA+^=}b#Nh~Z`kAynNyNKf+nZD&wy`bQK>YRfdcRo9J&%Fu8r z9+26~LePzP%_rb^BoN$v=g*?fcS1GxHyb&xv|iD>+8GPbvuD!M)7#3y6D9R?z;?wY zW=Q_c{a`Vi?a*-ITr+cL`OcoTU-~AJMf-IYx?+$Vj(ApO}mV`GaR!@3geP$s%r#G9!jnkw1%?5>a&^@V(2r+wxxG zyGze^AS<$BX)Ca4m7-gHf!U7yC5t9MBFKBKk%4 z>*ZKRJRtt~0-WON&F5W>+&RGY*=0E_wrTA%Pgzk0W9jR3v@37&aNzjEN7!jKYIsq- zQq0AQ7ju$jdY>5xutACr-w7mE>H4!z&F-{p%1r=!@w0=!yp^E|)54&xHc5Ug{Zr^kIn*=QSWS68 zSUc1o+eAs*yV#{rY<}tiK~fu!WA@@g%f#aoYWaeFn%IDaPs*PEVjCy${fzV9SHVBb zYjX-jDtaDL?7_1bnM6Ce(s%85?@`*7@+YQdc_Q{r198Q5R6QY8LvcppgQYwq*E{)W zz%TEK;T9TGUx8N`cQltShiX|mYYP;Yi)sp<=9A98cG?h`<(?nAOdQtM@kEysID%!r z8!3{0O%44eoP>#xD5HM>CIbRWdY|=1D4=BT9xb#|S4UB0%vradak*O!zO_eHeJ zUtDZ)rGYj4gVSvc#rShnnmhg4K8=U@FFt%|E#bg1UWGAdcLy9*c;B1tEA!;gesA`% zA73@q@x)76w_HBxehB_Kk-atY2wakd?qg2?iS{c~jVA@OkPlOFUatS17B*PNCQ=0E z(k%zS4*7NH=Q5@V-LH>uu_I@|zwnbA#|Njq*XMH36M`!f?TlMi#ge<o2UhatcaT?>dZ3b0+o=*JkA#17=q{6yN7uy$9J2m6Lme zG52jL>8Gj~b+4qTe=>es*_31PYQl=5$wX?Eky*<5{Ng1@>1C4iO)jDuadPA-5(AS% zRn69g7Q`A&QAMe1QpZcopkLS%wJ4XyX7asR-i@Pn#fZwPGg;4>Y zN|3CyPTLEn=O3mBevU9vn9ru^#WtT9O4j8C6){i`9Vl(IiH_1?VIfcy^j8leC^qq0sA8x{Z`+Rm?- z9L4!{@180IUOE=P+pVa^C~O)t!?5tLsMt#xZ(m$|R2--qJy#VVD|wb*f~4kLXZQe( zHmcGrE94@%?j`9rr~v_W2mh9eV7b*UWslg*8mK)axsd4jsoANoT0m7uI?Sn>~Nl9cb--It{kY}a4SJwTX( zCpA-Yf}vNpNb}ky2|@wqx`YS)wltLnF0CG3iSW6ag}&Fb_A@ zB}V;w@5x=-u2u^-{-y5oNN~TsF1}D(QMP1fa!Pb14AL9Tg|PHN;^a&l2JF z&!_npe5w|I8E+^9#MNQ7YB(^V#muTWAFsq5_ z^kq1;Gbg%ku_Gfz{2B2jedW~XZ?9oDlFUvrKYn`w^WJ=s(Kul5+@aaVJ{ zmcp_NYsL`a8*$=@QA#OBy(JdZtM0^Sl**rBep7IqVHSL3)DzG}bmFBDC;SJyx%0GJ zl+=gb((*9inuE;e5a)JW!ZbxWu8YB0tc|2)2SzmHDo|v%_#7H=-F3CH3H(ufBiuUNW4WCz8}EmmL`D zpx6Fpa5Cv*mfm2u!t;M)h%T9zu{!!?WdHboj`4 zv@P1QZ~1WDb=m0ba?N3R_&g4W7vh*#6IXB-1yo zVo9!PeVR;I7q`VM)6@aihkAV44lG?5 zWlrBWrS;hR_%8_DY^x!T^-{`F0s3Jb@DZ{%gTP|KssZtcRa9v1Ocw~shH3^o11B&! z3+|CE`=;h+fW)zvvHHATLQ#V%ux zGg;)}uhguNS+`>kk7lc|}fI_e=xQu!Q~R=&j1*8*eR`lyxS z+=+*}$G0Z1#>~8Nemi{HJjYKwG<7WGivN0Irc>zWxv(R{qv8C2YK8{3IiR7kCSbSXsLac`~084rwZ#%(&ysDNlGf(!yfcW@1+> z*{9cU12K&l`WkQ1^pmO&QZdw%UZ*Mso0e&;&J6nbe#kWbRr#H#Bx@7fDmRn97X5@y z7;|KwmCpK>);H<*p4N0JJuOs7aV@;}4HMRei;N4}NQ02Pm78L&3}vr5s8-VIMR6tt z?(1;4{H^|^H)WGb-W2p<4!h8mO@=V&jN@jw` zp-jNx$L6r9EulCmGVGc}F=OqPT~|~I+*Hham*FGf-7w*FXC90@KceZ8Qvh2GWBhi{qA;-W>yN0 zZ)WP8UrX74tTyaW3YU%YHiZaXB)voA%Xm{~p-Nf)a{84UQjhMsNdA3(x5hqC<1+O& zZ5qa?WZLsqw2I(j%yo{AxkKao{8P7JXMoVzGPH>KHpOzp*6OT3p^ zxDg#Uqn7;C{U%!jV$o_E@lYyEEqk5Ri{DG&_1e4*-&L+VCJPcXoUQV-eZ!6-aN%fJ zmZDw4z(N8KIH-Gxy&?0!N!vFFyFe5Jn_d9*{1QnmydUrVm}T@{-0Qcx6{qi{iZWM^ zz=r2^q0`k|9Me(}sePc~Y`W>tCY>Z00Kl8v-Z11SfW@a7-cN0!h$9`ou{n)l0MZ_N z-?Z4;a*Jhp$|UiQLvl^4FKIq5)CMq@i-y(;3x@GJjz;|^`V(tfQCq*fZDcQ>;vG!T z&M2;elUnWa0hPSkjdK!mR7Kh#1XPOmNwLwgX^2J&m6p;4*Vo{O;Zs#-THg6;cPo=M(w|&>0aYOr>fod^UF@1ib1Je268FVLdwQgv}A~#Se37B z?3NYWg{{(|^!(;orO=1ogEu{+XFSPmW4HW6=0!|B<62Q%Q-MIqve6Xjp?i<$yG>z# zBX6A5YBHqFw6R$*_PQ*Ra;h0_L_OKj-G&3gxZf84dylV2Us1wC5U*9qEHKQ<^;+2_ zQgj#Wz#uXmdhQmc?^|hEVsJXdgX{IZf?9 z87v13!^2}WDe9gnvcUA+w&C8VF?>SB%X3YtN|Zb{#QY7=#}rk*%@FeJmp$^rI-#@1 zt*k`FBr4(aBj@P!^r9Oqs&TBAJ^~mFFH!CJ6~vCKa!r%H$m8a}13av~G(;9BR^wVH z#PskK*hO4G)6y!_$U`H>a(HI2ArEt*9`{LB1eO{Yyzh|yl}|f>j1twetB>EYYRO<1 zi(<57Bay!I12%@vH&x(dO)V~65Cib0n4T^vgl{qRGf^lZgT&6-;pgh=hgdpLth*)? zht9b%7OhuW->UW^C-5;9FEL&p@Q~xN|C;z(TvCOm0|h8OUyJ_GT_~@X;Qy)XyTjpn zyRJuz7M+M55|hzGM0BDALG(WAM2Q}~mmncpemW7ocM{zo1TjkV61_}>(W6KCZh4>Q zy}svtzt0~t*EI*%nRDM~@3q!mdmjeSY%3p@UozYBjW5=h$+W49EQSmsKdc#J?3ZJ| zCtC14_|^qaM;FoMjkdBqQD&-#)?v(>zpJTXF|ps{AC9`Mr8SAVn|%11-O#VT#Aqf3 zMqX?`H4v&u_*26wg2{)g9J%St<@7{!cEJ{KO>R^;I9LV`c)Tc)^?B3oAUFM3Sk+`t zG{X&KD$TchFsg9&nrtKNqT9^Xy$n&kPQmXlWtaGXz7}|4Q0WSLXR-9#BmF_KS#Jhb z+Co`AiwHOF;H?uAq-n)(aH=zzX`S4m{y`);g7SW|O}uNd;l38@)5bZUXfypH`Bi4s)Zj)bZ&bCY z8?hWgC*vhPVzXZ45dCIKS>tqwaS0)soH~JqagmQaYM;n5eZD7}q|)TvxIMOwc>T5e zYW-Z~{Z#ESDPfjPXwNOR_kko9^BX9Gy)UYd z!$(3p1?(ioKlv#gxi#G>YnFraYMM)`=b#)aVoSNFjrEt~X+Ru6g(XrRi85CX806-r zs|mwWao?*M)VK3F`OsJKTS;TH`YSB1UD)2t;(Ww4orijzWg75L_pS;S2n$5GhM%7? zI_jbWGGjm8O6N90#uPVisZEd6w=aaGF6MFnY-( zpqE`{I$rLl_pts9^-~64$|joB$>~1i95Q8`ZLruD65u_CnNm5^d3$L4Dz&xe?q;$w z&O>X>Elwu72xsSd+@WL$zL(Y_o!(SX%{)Hl_xg#MN-I(5fvisJoH|Ejym6suo+-si z^S^K)zqpn(AogsoojwV9z3vZ{VO$(uVAac`0DhF8TXR%pbuWT!a@CLps87OmSmH?gYJ-KU#}8@vZMvW$9_bn zu!2b$#nN;r!_a~l((M+@H!a)lQH@Yjuo0VX{yf(T1{d<{(z`|KBqPt(b84sIvnI|q z$D)Js=>DiIsXI=Q4AEWIzxZlP4#b@WLD-3dG` zF`s)H(*=9G?&#EqYR&X^iVXE`Bn zz|Zb|oTgp}5ASJ~Eypt%9N$)N9J}C7{+p2PXmsnE(?4*PPt?c*z7i3uguhol^>RaiVd?gwzZss47DhMi z!{GZO+E-m4!YZ-4Peg@%zTBMNlxHk{PmH6yR?_sy@N@A;Q_3sS?dqh=DLhA)5$Xra9OeJj0XfZ1?o zfu1i%p@>K&cCa`ack&*!A7Tei|3IY|JX}RoBIv_`5YJ1G9y=LWsJ@;yYMh!ODY8)T z;QJBBitG6QPM`LV|1*8|&Q%TQCk2G1Z?3yJeo9If>8DwGTLN5By}?{WhdclDl^A_i zGOIMpXIygUzF|B0vf9z=%8@WDLYj_{QrgJyG+B@AFsj#moa@l}mA6XdRK0mkOG3YB za8-qRm&0yflv|HAQ6#(X2=`FVeO5tMaW2W{y@#)O0N3=&bbdo*jq?YmvZzWs@k9K8 z37NL4ex)|rmxzWWz#x9m!SdOmCKGGEIE4Dtk1;;_VIw+DgzLa8Gd5rPm7gE;hYhh{ zujK=ExK)ueX%)+E36WTd(m>+%?47X0Bvt9(WJ_^3 zB~&&MR)~YpFwuOAPIb(;mh6j@AS`-j#y%?FsBd1=zQPNas7RRE6i!9j%J_uH$lG!K zF~Gc^)vSLSY2vgN`Y zJAX-!Pj6eH;~*Tf2EPv=ZJ-jyUP|}#kulIK94u9MrE(74S25GGPz$-vo+MhU(O(jz z>J8d{3YXyqP#yGr*Q9W*D<;Iq>1^XW5})NyV7y%3mEd;3iO!!Tp4AEcoEhy&5wZK+ zUmqPmZYkQqf!$25hFY%bH0b+`YiMH}j#Owdxs zdqq)}fI-Ie+%zF0%#sZa_T|H0$y_Zl9OHHM%s~ch>4Z_z-nX-h^&60Fqm>hH4wW^~ ztfAvyIMP$U^N;~(l_s4FTL7HWt|jI^Z9fsFiV|&QRsc($S|9<6?~o1Q{cLTlhrvtj zR5{$V$uqZ}$FGT#4&MW?YE`>(!asc9Si?4mOulhGVz;ePTt85Fm-h#B^JPfm zS|x~0(VT0_8Y!>`Cg!i(`Pz^FIp139y3V&%BhI`1P} zCSykP@{T|9OzG+bYR))3K6D*?!0nu^xed~&z3%^{sL)Dy1KiV=&*BZis73*{CCrW@ zZ7lm`RXIlG%%G+)@LC{}T$L6!Dryp!mBbqCBW#7P@Im=n_www7I9K z8u?sji8NS&Enl1cVUQkgsqNVRE)V9aCKLQ#)Sh#LLas{k^&76TcJO{ zZqIs=+x|@AR&sMt{R$4h(}8G#N~v)Hf~`vhuLQRMQqhh>)R!MFX5XJPYtfq#oO%s{ zMbkNUGuvrt(wLI_{$fG|m*68FpK7AEBloJp+Rp+X0cnW2(GAhC2$6PDgSZQen?G)W zf+4?61m?*Af+|}~|DiE)+U*lb1>A>O`N*pX@XxXifh^-hy0Cq@nol&?)gQE_c3GXt zWa6C!v+<}RaCKdXQIE-ENOZrAGQUmNsKtC1Zc4qiDE&&LB%q|_r@P8@9<;2s1pb$& z&bAtcqvP9&=BQW-2~_lipM;X?HPYHVE2vHHHA&i}O9v!ENY#QKOm557_!p{Kb3InhFIYL4>sY@}ZDZr>p=gC$ zq#8mTC!h0@X&Reb!Juv+dwSz(K-CMi4efs^J~vt*a9SQTltEC)ADi_fo}di{zMx7{ za!X9lY6dP(P|O{nCH(deL>MtDX(mbLCd-=hnLe-RbtQL278>-WS^jxdJ$f1O$Iq## zkJesSES?v{ZR|Z>WfJT{*0CF0t5%hWeHnmbY28opQ1uWwueq>hB6q`IX;s_hsJrdC z<>md{s~q;$l@r7AOoH#6^E%RRw9TU3Rn`UnBbAb;8P-$QO?U6dvioW}4H8LAy*h~@ z_!L~8Gpo;t-uN$Ck)*a~yI4m!?sJVppuUQHcGlhx!NWXvNi(JN^C_>;EtZy2wZ2mhv^luKiN>AWp~Crv_M z!FU0k#h)Vc(g|zUNQ&k{w>D9+FT1Bh{XuS!ye`AalhPJB^Q-4|u!WW0()k9hMD*eB z=}JVV!&V&Xq~aZosiZd^Fk50*zhxWZ!P34NOFfbj3nl&S?rUnsTUF3dm{cgMV&`&Es>cgDq=%@=KXaYH=2{%(oe37~IoTZ!tZO!m?uB#IYyO z=U85u=+avCChHswPpir(Mr{$%J~}}^tz7BNlU6Lm0#68`AudFZ${XqAo;{5+qXd)v z(@CS`uiMXQZSCr0ta>vJN=-`c<|WuJQkp#uZPsb1F@IO~TeJ>di`0p&5z^;y1^bG+ zfH)cRd`l9lXn&qLn28fHx3>8n^6sgZ{hpwA-)NBP{54DcTpoTbm!fIPTIyrSOFqF4 z`-6Ak;s#y$n|Tau{xA7=_0MRJ>xbHw{w3DnqxtT_;{TH5p#iRb(CXG%h9ILcb0tYN zK4Yd4Q-X8-(3i-M;`>iGd%xwkS85kK*&zZX-Hd_1sn2gl*uc2pZaO8)dzTQHsxWt7 zkFGLQ1Z?Q^lBYa$8iNMdQn;iwU((|rf`rf<%LQCnYsFRiiG*PSy`jA%t`omtYgDAq zpjfL~6Fj?pA2M#(yF3SOit4MtA5^(kiOfYBLT+_a#V;r3BK_Ijl+)7W>ovz&>SN`j z7u8@?IGCV>Wr;q=_D;T&doolJAIn#!Zo~B zQ#p%p)S6Lb-4frU`I30x3L(C_i!~A-1%j@U^X61ibNO1hm84j{}C(F zFT9VBQk9?XKecHx8OAD5S%7NxYiB*n!VV`A&#HpIYsd|#Y1wj*g8JghoEZm~Qor*t z;Ep3JpK(!A)j#%F^3A~wDk6%csDK^dI;cjPl#%LXQ{!l~CN46TQ4Ld3e813K`wc050>BFlq5=s@#U4kWS-`m612S`*EHW^zkON<-<#v zejTiAD%zGU?YN?k6WAc%(cE&7%{My_U zf5%kNk0Ly_wJ~8cT;MT}+wIm0YW~jZNiS@VVx~*o-INkW$1H_9_}l-q6NMIl;Q-c% z$fEgvLQJn@vU*N@WXB}Kc};g@gAXN3=pVc=e(XDN%Ch$hJ(wQ8h&grR#va3fxGh?R zy}i#?S=wEgky~aWs2T^-fyQ~C{uj^hff{~q0ueDacyqL(OnJ{0@<^C|(hoeC?f=?5(zO+S<1=G8GF8V9^Sb**Wzsdhk z4nWrrVx{`RrPbm0BE+^!0kSsXL_E9!u8k|UxdeeF9XSp9dqrnpc=vJcQ1-K`FMPB< z4Cq2|3@^FOt@0(22L2^e7)n0CTRfhBykg|lFs!iKX(Ejg%SZm;|Wn(OUQ22$<)0+#=m7jPWhS4=a%yAOfzc(&wV56@<9kx`x1Gs&=lpeqHqbb zc*@VYCYgoPc(wDPDy7}fg_E)=VaYDS1%xjqqkC@BC4(JXRTTJh@yCIc;}MEJ0jIf* z*6AqlMP2{A4%3KLaJ-T@ue^4m!?Lp#p#PSlLg6I#n^c49OWYP0)utNe#hj0i?-K&( zyTB%AWOVx7E#tGD?3p)hT5yOD9VR#TUPs0B2)@@frd!)RW-?^uaJ0W?I8SbA=$|j1 z7~}BWVWKi(w`&_GfN+t` z!F?~xSb!p5#91^j!>KY!JaljnwML|`6M+@yG>1)b_H;?17Z9YzbLP?-fUQQ-J zjlmuYxn4x#SlG?P@7tXOyIxhVbCJy4yplSY(t826BtfrK6a6qW%7t&u0P!kArU^6|yuf z-|i^j+5p^Kpa%qKJef0jnxA41zU%y8MBkvPSl{f{1`hO6XRd042{z7_l}H!Ais(KN zkoRE6$Gdf0i)`t7pbQH-zq?nffU0-kBZlv0hvf!)kT7-g`G42;+0$k_yegr2$<3(1 za5uU<5s%six?NU6BY6);+>QZ zPY%!{Qfw&d*;Hbj^df3Jozq%I{HOn?;Ic2D*e$P>zZNjnohR+C_?^5Vgm(>rM}zJ+ z%NO*%ou)K`XFkWi?D7xM?_f$DM^}Hi4mFxLZ139I{DGTmTfwZ;)u*~oPMs<*`(8w4-pHmTsHQOg9=b!! z)F8a!Z0wtmX@x11pE2@n=cX9MeVQd6HKffw8-NJAHh&yS2dNbrN0I1qz{$(rztQfY zCcxYbX3(CFHZfFPa?vlLdVaxQZ{X>{Xd=zAv!Y0aS3z`!?g^Ru*>X!lhUqc~#p{>$ zA_{g6LTDhQ$hbf@mpwgH6R-c?#P>5ojiksv2jaqB*O2JWloz0oW7+BmN42Zh2d?z= z^;gGH9QSmhHyCsVlXD(un6-3-o-~+e-t|D9{!0L=cU7<&e{=9#oYDcS-R1m&Ge#1z#nVZutoRH>fOA8Jr&}*D@b>hYmeM z)ogudGs-8_PCg|@fCeUO5IK}bswz}lyQitDpKMb`W6m%0Hg~pqi0>0JrthZ8mMBk* z<4;1J)_a7Ml3yt$S%_6g&(OnB_)}`*tQX+oIks6uvHQ%&oSpbM8K+0{uWKPSd){>$ zUNv;c1uM1NfNl2fUtJw9+r4?oN9w~5af7@{nd`%EMN}bY9L1-voN^cwi)tJB*MTa> z=z6Vgi>5Eb#yJ_)HnTEztqeoMF)r$|`Qjg@Va;VpBn3xh``49Id5Eh={JOJ)7(8n7mA#DGoh*w@)I*Vu4b>jP*8b^rCM@2aE_t? zZ6WU{40RfD^heY=$ZozcS`)JK1}rQz^&k#HW20x8-;pWb&{KdfG@T<_mbg3;H6${% z)lQY!?Fu;d7fBYik-kSs-HtaTUxjiIbFF6Id@~8kxUI5&K^hSQ+`n@$&T;I$(Y?Gt zR#U)1gd4L+DkuMSPbhP)%BtZE-UZ>qnx^&1=9Ar@6GGjf2=ZW8(eEGF&`&BTPtp58 zZ`xuGK|mVKYt1h-wNpa`)R;UdlVQd;PN~Bib^}4J*yrhrVgB7*jrkkTSOXB1a`KH9 z;rkdrdb0}AyvLEw9!_%`K@Kn@8Y>}fROfnlZh^d-`jSrqPF*ZIw*ecJVNhG^Q&wt! z0h*eZX6Qxpq1HBIe2=^V9{15!{~R%Ca!jzJoueX|>!Krt2PPL!gSz3~ujEqvCLY8{ zK1hEKKf0S?xj{U>2{oSv`u}OhW<}Bz<<#$OSmb<7J5U3KdgOX++12vHZU6W&?;c5)J`k)WqNwFtwkjDC?y*~T{q+xs3%b1I&U4~MfzHP&g{ zb%w%bJ;dSp>hs8Nvttjat1r^nefOoWw`YrTzVO(h0L_>DPo>GPf!PJvVG5RkjEjf; zI7@E)3q=Dv{Zdb4q0(_csR+-oJ_GWXircyM5T9P&-HhuDvmwMQ*9gzj&Yq&U)HP+j zpNH_30G1&s=f<2q$Or|E9~j6Zj4Ku6qQL1$ZQEg3y4#kc$QP2>^Oe%{7+gZ7khu!} z^}n2gmIFSyn7jil5p*ey=5w8|rc-QMGURaKVWbMFja8Z*>oJvWKi?d}6by*7P#+x} z((SZl7~*FrKSM-ct2N(27FV@C#2Q;#$xaw}@MqmC15CF?MV}t1-@P1iCqXrrJ8Vt^ za}@lqT!1_Evq{B3P{${2d?@8J(3>)f4a%D-m&A2!DUM>>S~v_*m#OsCQsg7|gJk8r z;bFwC<|?m)0jhIqBK3R+y^_#;!jwEySI5t1tR{4wofIjOBh_>7#8f!}`>RS%T~jF# z7>t)hDBgTE^})*j;(oG{Lo}W6&Ow`RoZ>mhVM+RMCa zKk|pKbMu1k30-yd!zK?dcMVY|`*%$P1w{lD?jlGaYxn9`DHRc}!^3XCFFj)wP96Vx zU|vKiApww#XkS}#+5w)o+%jW9o%yXDp`T@A7k<3oS&KNom-OMC#zBhzszb*byrjCQ zLkK8`&^Dkbo*V14_DPTqQ^S;xR;wG$C7!`c>?l|)vip5j12O2ks^%EX+w=)(M5I+V*A?IcUSQ5ZTmu)*!oK<-%EMZ`_Vo! zM^YxoZgAxfUN-}#jz7Z6BVEyeLRS7>63#aYj=;U=!v(6@)>!r3mESE^REP%T8el9p zxJf_T2pe|y55C2K*c^t#fVrso2Fw6UpfM)NpvvrtR!QGx*0Ln8)b!a*2^Ai@Fjd%cF%Ta)d*mSh zPwWqcz?SL-wWnwDp~t8r#@~&xrt|3&TacM_^L(SXo0pCJERt8cq8q84`{%rgYEE=b ze;8n0^dAJ6LYH7&Y{C_NiV%u7cM`gEK|+rqVlSCpQ0GX_7Zr+Uas(|`3lZO#!2lI? zmRnnb_WG+A=}Zr_bRK^UygZfK6^((ru5_F=|M*Ceza`&^5`Fh3G3Io)tA5nK;<>I- z?;!ea9r8ono_C96ECb?ftpnYp)f`Jm$#7NpdrjKnI6>@QP!0t%Ml@75OFppFxtf4| zhFH6fwFuT0k+An6!-sX&Yb9FBnbBI)M`~`-Z<9gfg`ykg2+SO&j-}U}sO}owi?Fq` zD{Yx=-80!)fu}@ijgKnCF!sJ@y+E-Zy!4!ZyChclxnItMohT~mD(`y|kCBbju}AtE zFiRbHe#9fbm7ZN9^~0fl&Vnyt=f@u+jw&t|>lb1W-zs*8!_D&gd5bGgBYHbKJBHC3 ztoYxIJ*gsYzlQwZkg;sL!$RJt?%0<2gSohV2g3?{SV^1f_h02M%({mPyilaJ8Ti&H zYS8R)>QrLc={i6j#@)6bc70M5UWt2_# zd?3paEHsyWFAGJ1Q396>{gAAcsV7z2(9q|sNF%qYEzuIybg?}kazd0{C)h*! zOcQ_nQT4QE=+p}0DEddJip=IVpuz306(4kpQ4&8-DtCK{r9D&j z=P8rPFT^A8yfOqF-Mdj`GRcfCEKd0{o+5KNjinO(ufIv54kvocaqsc1RL!VGD)h3z zQdin739@Q)t7tlce>DpLpTAP#G;SSEc-jo z`fp>wXLVspSdzX>;l0Z=@K_#U@zPzs#jwFl8$v#}kEwQFUgN2zrrCc@@dKrrzkLkg z<>gX)bGxb=)D@n=Lds_%rept15;5}aUo8gU%Z=pB^I7{ah46=c>)!0e@!hJOv<|2- z=KY$&vyXO4SnITY(2JQ}z?s|8H3gkzY;!%0Zj5AGx9v2)050TMi9A|H zC!1dOt4-pBGI6`i^zpT&kGaepf7EpS|2I;}^)9-N--X*`;cr_kwWtd=!iS^ZX+LQ*z7a`V^s+fyP==6ogPb;_hNxIdO?fNuyc-Bib|a0i3M`sE=ImQu z@BkFCHW0A(ggZ4vs|G)^H3@SW5J)QH(N3Qdd^snI!M`VIo@WtwP~Uocr8Z;Zh0{Xv z<-842jhXXB?<%m((n>eeTl?>iW;*y#Cz+6tEh^4 zAFT^_=a+=V@JCE}Pv1tw#s5mT>rv5C1bgi?DueX3hjYKb#G&4s)nlhgblLM1zY(P5 z@sa;JytQ&wHPG;M>bUnnPjsUU43%k`k8z(f%4dlGUS_ElgINz6zkp0;hL{`&Tz=dk z`MGFAo02-b5WLW|(OOA`oX&(Oqcz!toG1ID;!rVv_V{Mp5A;zE9a_M41vk zrrYvwU(oeSyh52}?CI6k>=)Iq56Go8)aa-7i(c#6gc6NFJQw^|mbviCIxQ;|tJ+2D z7D^YnGz3Q!sc!9k{7nvlK)S7`aUxF!UJ~xM`Gr6r=j_&S@F|3%Gl71B~5skZBOe0OkD2468wYChx4KX`7SDF^p`9A!J+D7DXs z&s;i@W?PPYXa-A?xKBl)hGcj;Z0Nf)x2r|5m!!ELv*YF)u$#CR-f$43Kc%n}L{Tn& utdPFazEV43Qs>~iHFtdu|M}CNE{XMdVl+`qRr>P!h?4wsxe6Jx*Z&7f>qVph literal 0 HcmV?d00001 diff --git a/doc/html/_me_i_r_8h_source.html b/doc/html/_me_i_r_8h_source.html new file mode 100644 index 00000000..b6e60fd7 --- /dev/null +++ b/doc/html/_me_i_r_8h_source.html @@ -0,0 +1,314 @@ + + + + + + + +MakeBlock Drive Updated: src/MeIR.h Source File + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeIR.h
+
+
+Go to the documentation of this file.
1
+
58#ifndef MeIR_h
+
59#define MeIR_h
+
60
+
61/* Includes ------------------------------------------------------------------*/
+
62#include <stdint.h>
+
63#include <stdbool.h>
+
64#include <Arduino.h>
+
65#include "MeConfig.h"
+
66#ifdef ME_PORT_DEFINED
+
67#include "MePort.h"
+
68#endif // ME_PORT_DEFINED
+
69
+
70#ifndef __AVR_ATmega32U4__
+
71#define MARK 0
+
72#define SPACE 1
+
73#define NEC_BITS 32
+
74
+
75#define USECPERTICK 50 // microseconds per clock interrupt tick
+
76#define RAWBUF 100 // Length of raw duration buffer
+
77
+
78typedef enum {ERROR = 0, SUCCESS = !ERROR} ErrorStatus;
+
79
+
80#define NEC_HDR_MARK 9000
+
81#define NEC_HDR_SPACE 4500
+
82#define NEC_BIT_MARK 560
+
83#define NEC_ONE_SPACE 1600
+
84#define NEC_ZERO_SPACE 560
+
85#define NEC_RPT_SPACE 2250
+
86#define NEC_RPT_PERIOD 110000
+
87
+
88
+
89// #define TOLERANCE 25 // percent tolerance in measurements
+
90// #define LTOL (1.0 - TOLERANCE/100.)
+
91// #define UTOL (1.0 + TOLERANCE/100.)
+
92
+
93#define _GAP 5000 // Minimum map between transmissions
+
94// #define GAP_TICKS 5000//(_GAP/USECPERTICK)
+
95
+
96// #define TICKS_LOW(us) (int) (((us)*LTOL/USECPERTICK))
+
97// #define TICKS_HIGH(us) (int) (((us)*UTOL/USECPERTICK + 1))
+
98
+
99// receiver states
+
100#define STATE_IDLE 2
+
101#define STATE_MARK 3
+
102#define STATE_SPACE 4
+
103#define STATE_STOP 5
+
104
+
105
+
106// Values for decode_type
+
107#define NEC 1
+
108#define SONY 2
+
109#define RC5 3
+
110#define RC6 4
+
111#define DISH 5
+
112#define SHARP 6
+
113#define PANASONIC 7
+
114#define JVC 8
+
115#define SANYO 9
+
116#define MITSUBISHI 10
+
117#define SAMSUNG 11
+
118#define LG 12
+
119#define UNKNOWN -1
+
120
+
121#define TOPBIT 0x80000000
+
122
+
123
+
124#ifdef F_CPU
+
125#define SYSCLOCK F_CPU // main Arduino clock
+
126#else
+
127#define SYSCLOCK 16000000 // main Arduino clock
+
128#endif
+
129
+
130
+
131#define _GAP 5000 // Minimum map between transmissions
+
132#define GAP_TICKS (_GAP/USECPERTICK)
+
133
+
134
+
135#define TIMER_DISABLE_INTR (TIMSK2 = 0)
+
136#define TIMER_ENABLE_PWM (TCCR2A |= _BV(COM2B1))
+
137#define TIMER_DISABLE_PWM (TCCR2A &= ~(_BV(COM2B1)))
+
138#define TIMER_ENABLE_INTR (TIMSK2 = _BV(OCIE2A))
+
139#define TIMER_DISABLE_INTR (TIMSK2 = 0)
+
140#define TIMER_INTR_NAME TIMER2_COMPA_vect
+
141#define TIMER_CONFIG_KHZ(val) ({ \
+
142 const uint8_t pwmval = F_CPU / 2000 / (val); \
+
143 TCCR2A = _BV(WGM20); \
+
144 TCCR2B = _BV(WGM22) | _BV(CS20); \
+
145 OCR2A = pwmval; \
+
146 OCR2B = pwmval / 3; \
+
147})
+
148
+
149#define TIMER_COUNT_TOP (SYSCLOCK * USECPERTICK / 1000000)
+
150#if (TIMER_COUNT_TOP < 256)
+
151#define TIMER_CONFIG_NORMAL() ({ \
+
152 TCCR2A = _BV(WGM21); \
+
153 TCCR2B = _BV(CS20); \
+
154 OCR2A = TIMER_COUNT_TOP; \
+
155 TCNT2 = 0; \
+
156})
+
157#else
+
158#define TIMER_CONFIG_NORMAL() ({ \
+
159 TCCR2A = _BV(WGM21); \
+
160 TCCR2B = _BV(CS21); \
+
161 OCR2A = TIMER_COUNT_TOP / 8; \
+
162 TCNT2 = 0; \
+
163})
+
164#endif
+
165
+
166// information for the interrupt handler
+
+
167typedef struct {
+
168 uint8_t recvpin; // pin for IR data from detector
+
169 volatile uint8_t rcvstate; // state machine
+
170 volatile uint32_t lastTime;
+
171 unsigned int timer; //
+
172 volatile uint8_t rawbuf[RAWBUF]; // raw data
+
173 volatile uint8_t rawlen; // counter of entries in rawbuf
+
174}
+
+ +
176
+
177// main class for receiving IR
+
+
183class MeIR
+
184{
+
185public:
+ +
193
+
208 ErrorStatus decode();
+
209
+
224 void begin();
+
225
+
240 void end();
+
241
+
256 void loop();
+
257
+
272 boolean keyPressed(unsigned char r);
+
273 // void resume();
+
274
+
275 int8_t decode_type; // NEC, SONY, RC5, UNKNOWN
+
276 unsigned long value; // Decoded value
+
277 uint8_t bits; // Number of bits in decoded value
+
278 volatile uint8_t *rawbuf; // Raw intervals in .5 us ticks
+
279 int rawlen; // Number of records in rawbuf.
+
280
+
295 String getString();
+
296
+
311 unsigned char getCode();
+
312
+
327 void sendString(String s);
+
328
+
343 void sendString(float v);
+
344
+
361 void sendNEC(unsigned long data, int nbits);
+
362
+
381 void sendRaw(unsigned int buf[], int len, uint8_t hz);
+
382
+
397 void enableIROut(uint8_t khz);
+
398
+ +
414
+
429 void mark(uint16_t us);
+
430
+
445 void space(uint16_t us);
+
446
+
447private:
+
448 // These are called by decode
+
463 ErrorStatus decodeNEC();
+
464
+
465 int16_t irIndex;
+
466 char irRead;
+
467 char floatString[5];
+
468 boolean irReady;
+
469 boolean irPressed;
+
470 String irBuffer;
+
471 String Pre_Str;
+
472 double irDelayTime;
+
473};
+
+
474#endif // !__AVR_ATmega32U4__
+
475#endif
+
476
+
Configuration file of library.
+
Header for MePort.cpp module.
+
Driver for Me IR module.
Definition MeIR.h:184
+
void sendRaw(unsigned int buf[], int len, uint8_t hz)
+
ErrorStatus decode()
+
void sendString(float v)
+
void mark(uint16_t us)
+
void enableIROut(uint8_t khz)
+
void end()
+
boolean keyPressed(unsigned char r)
+ +
void begin()
+
void sendNEC(unsigned long data, int nbits)
+
void sendString(String s)
+
String getString()
+
unsigned char getCode()
+
void enableIRIn()
+
void space(uint16_t us)
+
void loop()
+
Definition MeIR.h:167
+
+
+ + + + diff --git a/doc/html/_me_infrared_receiver_8cpp.html b/doc/html/_me_infrared_receiver_8cpp.html new file mode 100644 index 00000000..9dc5296e --- /dev/null +++ b/doc/html/_me_infrared_receiver_8cpp.html @@ -0,0 +1,198 @@ + + + + + + + +MakeBlock Drive Updated: src/MeInfraredReceiver.cpp File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeInfraredReceiver.cpp File Reference
+
+
+ +

Driver for Me Infrared Receiver device. +More...

+
+Include dependency graph for MeInfraredReceiver.cpp:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+

Detailed Description

+

Driver for Me Infrared Receiver device.

+
Author
MakeBlock
+
Version
V1.0.1
+
Date
2017/04/06
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
Description: this file is a drive for Me Infrared Receiver, It supports Infrared Receiver V2.0 and V3.0 device provided by the MakeBlock company.
+
Method List:
+
    +
  1. void MeInfraredReceiver::begin(void)
  2. +
  3. int16_t MeInfraredReceiver::read(void)
  4. +
  5. bool MeInfraredReceiver::buttonState(void)
  6. +
  7. uint8_t MeInfraredReceiver::getCode(void)
  8. +
  9. void MeInfraredReceiver::loop(void)
  10. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan         2015/09/09     1.0.0            Rebuild the old lib.
+Mark Yan         2017/04/06     1.0.1            Filter out the 0 value of infrared remote.
+
+
+
+ + + + diff --git a/doc/html/_me_infrared_receiver_8cpp__incl.map b/doc/html/_me_infrared_receiver_8cpp__incl.map new file mode 100644 index 00000000..c7a21b43 --- /dev/null +++ b/doc/html/_me_infrared_receiver_8cpp__incl.map @@ -0,0 +1,55 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_infrared_receiver_8cpp__incl.md5 b/doc/html/_me_infrared_receiver_8cpp__incl.md5 new file mode 100644 index 00000000..cb1bf536 --- /dev/null +++ b/doc/html/_me_infrared_receiver_8cpp__incl.md5 @@ -0,0 +1 @@ +c97f7a21319f5ef2936df87ca5cabe68 \ No newline at end of file diff --git a/doc/html/_me_infrared_receiver_8cpp__incl.png b/doc/html/_me_infrared_receiver_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..e9779a944d2c52e37456442eea1f31a11117d64e GIT binary patch literal 66241 zcmd?QXH=726fQ_dr3pw0RX{{33IwEsbOZsBUZnTldljVy5D}y#p!D9Ww15zb5Tr;i z(a<|0p~Jl4yZ5d;vu4fwn4k0V14vfR*=L_;w`cFfzS2-8yTfn?2M34jg^I#!92^2p z930%0TSUMs-P1}Dz%L?8HDv{yYwXXL_M#LVoclO06l8V$q1y`q!8$9a*Vj`%4{=Ry zJ!uXnQC+C<>H5}`%56=xY~{jO-oR}u=U(ya$?PoW(VV7>ONCEGR7SXwiJZ*NNbUeZ z@x-K&QE(|1VE| zXH7AFOiYZoqM~ANwykgQgqT9$-~y}q!;~r|n7o3*164vT;=7cT8+X7Gi$lBd;?XL! zP}~V6W;yJ8+^R7#Dmg;F+tbAyG2U~zit)LL_u1LUcnEGjLDaY`{{ABo#vRr3>{;*f z1S_|zv=LHZsj<#`3e3+H6!M>DJ#%4bS_%znH5-{SIIS<}%lu)YC1VRLHNZTKU3KH_ z;wyUW>Kjk7yCmaUsQn6;NYE20m)7X#?Y?3cc)13QI;kzSR2w@4@UbcwduYwes$U14l7+DzW!e2|4%S~R^28y*{NH{NuzVtupGS~n%0 z^%Z>VYWj11eQ~(63fBG*xDJ@re`tv-(Js<>R(Fm_WM=fax3Tuk(@|NUEpN!Sn zzm0~4T|nx5)}MdL0M%fh{~Kt`j*c#JV6WKg{{bI2Xi9#CRng7Eu65T32dg#zgI>Bk zEEw6@rSfy%#l-x3EPJ<{^!vVu(`0$9xazg=**FKT!Bx=|hsIbHp=`C_CKgZFr(HF- z%ZZxIl+lMAkZj|+z6kjE&7&aq{{_o8i~sMke#Of5|BHorH*tW|Q^6Ewlb)gXhdWGW zFdc#8Prn^nbGs(3ab*BXASL+E(5K)V`S*aE zy;A)l0$epwbvv;D#Yq!L0NUNy^tQ1{4k`z>giE-%C<5=+Dq$}w8MoXK+F(8(KiZaR zJ4{|ziZE1Ld>b1R(;xl?tNMPNHMV2aJ=cO4UkT?^nw|q93Yy>8Npb{ofr_l{4rE>~ zUbn;&10OmBsR8Sr$=tXS(7I7PnV)Q{nrP-ii##FLzYP%HI5dLjpf3xYOz&}xz5(8g zz2)l)Bk&9FIs4AYZ>H)QGvcTDe;UISl7Y4IbH-m{Kk2YCuehJg$uw*`1mR8uH1RL& z2Jp9VO#2r^3A2Jre!|Y#Nge>}TxQ=mP`u~Ej~nNqVf639t$0;?citC!0f$n#F1W!{ zaDReC#LxSYUiuRO*lohJZ>&T5(|~)9{9OhCigacl7GPiO1A5Lq*71dXha?w?75CCi zwoe`SjP-pF^b;@1O(x*Av1`Md*UoYr#tWJ0qJFPvt*xgvg7j{|iJh_}?8WXA%I?R{ zxpiJvX{}-1EQOFZV2woi{G`W%bx&CWmXo!Vlckqqxw7w*exC`yIf3Dg{z>ft=N>Qq z_8;3>03gi36IcgU3heX$%}l&MW*n^t>d(12&!u9d8a50V`xYg$eEvsF zQyU`nb35KTW#Gwa{Ab{m!L!-N3%q}tm+^lIQ{UhV*G_spleU`P^~)CMhT%Dvvm?x+ zTg7!{y^Gs+<>t$!H!YKWTa%93rC%L+gJUo!*r~MBBw!UPO9eOQ7pp$KBAp4f2^+tf znkrxxO}oyQa6hcU7Pd#{?hSU(2VYyD5~7tDOd>)W+a6)pxX1x`ChzZM!{ z?UOTAenorPn5BiFx`uy%UKDEOv8K5(^~3}exHiv!QjPsEpO$?$YwT3#kj zJR8tQe|X`I+ZMBFkhY)3Y;WRn2>5#0`9)Haw-O=xf6fd;7X*CW94(E(?(qBGXg(Al zWBr?3v++PS@IOFnl$0Yp8SdKQQD;jWc?4&OoRYVr zL4t`6`Az){R@j^#Eg!vQHZTnNB#i$OChj9>d#reDkM$`ESh)vU9+L#Ce6Uz9>?NAL zLrTOk4@#(^d!<6c$i?rBv*>H3{@lp}*MPL#(*VDXB~q6b{cH1}@mX#(HafCP-N4@4 zST~ipiuH#pA8ybG3v2W36~ykl?O%HS)A-Yo52J9iXc-sX{b|;GAid;X_;$MXZL4f< zM7VDGe=vLfEa`x5VwT@y&1kF=Ipk_E^Q^T??u*Y-)X}>(SH$1O3^Glevi-&k^7m~W zyGw0?LA5ry!Oqz2$0V>hl^{;)ud`LH!fi)tiCuTJ%3^n#{$=%^RA@ zn#}#a2!8^)-cLMU@b9%yG;e#^&++vjvtbv#zj@#4mrE~3PltkQs!%4z;|Vq zh;~fR1W%d?A zS-b_eAfx0Q4(2*UjZP9-c#*>XbDnqXl0kJIX~yusKMi!j*}Cbcdc-@?^OssENU_&) z9C5^HbJ-xMac!VW#`evCT9{EyZ==%qZAmm28yu*(Hg$o|JQwq+io{Tun&QFYtT*eP4(yj@hHP_?`{uW}><9dwWOZ(G-K zibv}cMh|L=vquysiJ;ryH2?l7RKYWC?9je>TVbf5l>_|%`jhEcVjtJ z47nJ)EUQwbtGm(_XZ3;sYQrxEYC3NUjBMp(Fd)2Or)hGM04uTY$lyJ3d}7`yp;^;Z zcb74|#DSHXK?eT#`)NFANdvJnveUpTYhKEk=G_8*iZWaMG{Rqqsu6yZl z{YhfVoQdKBX&EdcwwTs9k?UiDe+P>3{(I=nuP{oz)UZ5%cD1;8Q-0>(UJW zx@s~d_%3IN$yakaoP5Cs^QCY_k47w~Qw zdhMYC@QCN-6&ulNyi9r-hi8Zxa;K?UYmD{z{cp-_wKhOhDK3sV4?iGJas1Qxh38n) zWgjiS_H>s?N8575hf7{@c1?^_oyN;VIx$VkE^$xm75sR(816qW|D@`1O{cH7nGGzA zm)f1}6*;MZRhrn8X42dr6FXWU?c~E|Txa#QMy&PUeYdF*(@Pd%U<{YFjJXU%>!N6X zpQxJDAnFir9}h`VBbTP1)YPE0Lbp-b_*Q|>{i6gYEWom(MWH>64*gbV9<%P6__v-HMiG;gD)+d;uSd5bLF>C=fM7)&F2D{m2&=bYb+|S1*{HNa^_2v%tM7 zI0MVUlfYSWabDJk%~p>u3^Iy>nkP^?s29;&4SU$M;wHaoS6Y!|O&f5(U!lfB?!ETh ziSIcRJS=h4WM{vv>(I91eKe%bS-zj7PPIaybesKjtTDRBEqufu{#cmW*~0J4fycSc z%H2ZH6&(0+11i>`Y{53d7%T&7+6o-g_xl6{w(n7%?-}*+)bP={8@(8NyFJZ`Q%V98 zBIxb5JM*;h9$B_pK(f4y&7?o->yosYD@L`8>>l3jPKS$G*X0RidFW-SIG7K<%f~C;Z@&1RE<1p2=l>Q#StxuysOGc!4Y&Fa-M-V_-WKmd44tm zGH!D$W;}0@&(EaL-^Jn{(H`Ac$Bb}OVw|pxDaPZ_`ciJzg!#=Zl800#>>$og_ zXNIX4uy7DR*5f2Kqi~lzth)2N(pMV@y@OUKcnFFJeCAE2P<{?qO>3EYAXA0|X=Oi-E;iR? zM6i)ZQ+XCMvQj|g7iRJ*1{hGF$lk9t1a=N;V6}$dSt?f#7%uumm%2|?OM7;Q^*UD^ zavb-6Ae4NeQZvu2%a#(j$D~Ir>`T+p{D;oROK(=ZLh|2V+!6f+TmHZnd^zcXan(O} zm|L>S71JeG7L`(5HBu85iAKj~Cnn~>Q@?MSYdrk!XQxqLRL5X|Wt9L+%4aP} z-)nu(7H!!78~)YBjTm1(oOGXkzg}$Q?*2>qzyH4Zw0%i=q7e8wu0Cwxx1B9ChqrOl z`8Y@ATrfJw@ek(G`S|iTeZ~7EO*ckQcl~4c{^-XPXS+4@O*loZU>I3&-l~xCR0Y!L zc>R%Z^XzYTuie{FR(tuEfcsAbV&oWc>aRfO=|md~4Uc3tN;P{nrq#4Qt%3Whzw-DAFyfkd=&*A=OT&QpA;D(W|&PcJ9K}Z}QvYjS`~kEu`%3kiEliN4_9xO3E2Q zAZ-Y2`FkE>&;Jfz&W;peKmv;Q5UpnZDYxa3#rmYZzkdHXgL)?+#wuP#3$ zqI&ElFP+t=qDvB@h8lVaT_8TS&|Bpx%!Uz|Oqjq!{jx3H);!CzMLWCvT%xi(I%2%u zpv5aU2TU1RU1M&`bWM-LG9vLh{ETbbQ+uZYS919la3$?3rzWf~`q?l!A*={IVqDyx zF^BcvEx~Ecb@mJ5v<{d^mFri@m_w%5@Fs1KbB9XAi~LJ*)UwVz`N%JN#y8FICZOEQ z=xQHmev`I!5LoI`73+xl^)l+|vA0_c5N(B=>9yxi*{Y@7f1G__9pP?3loJ5fxp?3ynn!Rd^)iFHR(l?DeY9<|NC|% zm-MXw)vDZBQYIR*D?>k)p5hlYbBZlYWu=3WseQGRzyD@7tB@Q?m?!N9a1PB={7HXXj zL3fGza9V#Fh5M5m5b%21X?ekAcDWmm*~xg>lL3X>qbT5e$AOT#vQplm6@Qu=Pt^m- z``Fv~=(ClJlzWXQ?lh(JT(;u;1NJBuieWu_1TuFe%LjgJQxXcI%erU#&Ubl&MNKq zYj#a2pfLwo25^zmzPUK(e|&)c^?|~7>;*QGsYPiLAp~}r$e7f(D4~3Cs%S-A-a9a^ z$qMufm*cnSg{EpRREi?E!$Iw)a-7-ogRkfRJ`faJObJTF{Jl^z*V2;7(v%I*%JYp z#YDJk;3R%Ix(CrEkH@pqvX^}Qb0{wpmyI1Jydt|KMT@3H!H(E+hSyjGW9wzC5r3^~ zbeElmk|1V)f0S-_>F*LrHPXHZ3e2tTqHy#GrK6W0*zdJ2kxHxR_~97xN{f;XM;||d zT;HJ+U@Snl0QCRPJAZBtMY&5>^X)%DYO_?|veR0>aIlSSXYw$i+{hc;JO0{bezjg5 zLhtzp^7>qVk;tz}0pE==_$jE#`0umbhsgg^)fq=B<)a6qBfH&<|40B`HegwXw7pJs zU>*IVlacK1&u$y+5?CXZIV=FsCV|v6oYwFXD0(i6kZH#~m$7d@Cr{Kk+>Vq5pJn9T zh06q5GHWYg4akA8r2=1BhLyYZL)5!q)+9s2HP#;lZ7Ae{FehdzII+FtfBB#p(NT7) z3c_qRTp1!;;b($;b3gc`YnKRy?4O{FLonx@?CiBP+^Q;_`WYBXKKEc8uEybTQL0Bc zro#UB{3X4w^nP|z8%43Pi~V+u6$0~1vv$7#|G_A9a6H&-Cq-wIA*vr~UbeVLxGhce z2u210wYKxPlQzr01ro?x>ymZ`-Hu9o3EkxMk@(i6%LMvc623VgbRSVrfcgMgIi^hQxQBv&AfAJ?4AyT zCQCB3eN*mocvb^_gzv--jJrt}@dT=Qa-XaeX6 zo&^5hZ^_sOS~eo#!~QCb24Sr=n&b#Btvx!+d5DK;>GW<4w{pPjIBr`8WUfWaX1W-g z00a3F+XxXZg{4VkU7bWk7ax#xI!=IE|CEbAoqdRS>8Byw%&Q;d`x3Sl9nIE+tNiVt z%=Sd%Q=KV*gIZa|+Z)noG$+-q`xim3?$(^QGV*6Qi!si7tz0gYni9d*gu{)!Il2)wy^6?{9fN zu}EEdea89f#$>mlZ08JT3T(nu)~EFwIpVGt1n(8@)yvuO00jA~2ng~EiA{WMPwpXK zz+b@o=AKAJ9>jdlo9yOjG3euAAERD53e5!_l7%*$F5W)X(^?A(gb(sB=Yt9`?w<^~ z885!jp45mH;e+ls8m2S=3HM#u`toA?{ik?--wvxq1X_Un;B&kO_qa4Wz6>GK*B_oh zVs~$D&;$Y?^P?Jo%&OO+ofJ0wee_VdtvSl);dS#C9bFfzax7!y%j{!WsQ_jsyRFE> zjHmk7JP+am^j}sS|M{sRLdP#zx|D-OB0k!YM8(|N{Z7+F5=q6k z*w{nV*>@yx!w4r`_@&1gCoeu1T{;oz7yfAs(gDpTK7hGZH_2BwG}=O;@njr_kCQQ% z;lvSg=5pMwPnR9bYmJs{r(adNqg5ec1bk45kX)&pvIFeZ13ln@vOzKFwt^2M^sG<% z=;gNt=r!>utS$t=F)|}ec6$o++6wu`+;o8!w!&n#Ow|_nee+@irt#v`&vU!nz@m=~ zow*b<^BT;xiGhsLeib8>b(mlsyO7>#-7<>tXT?#Xe*KZVA#B;R?S}jD!#QU(N#W>wz9yH)%Ob1ytagUd`7@=gmDFR^Ifm1gtCpLP-&3rwy0_;e{KwtB3-Oa5j;E z8Nnx-T7TFSBSGS%x}8F)@FP}jGk8A;Q8g?|W93;oy}BGY)M!ZUhj*TNFuY7qcti02 zQv%SJ1k+z@B|y9&FG|}75f?_(+;DOCZ?uNI3HdrB_nTCtVndX_EBJ^m$&tHsDut6!o{u|mZ$ zDl8AiLWTCLK_Z;-JH}dTGbV~K)-BwyVbOC80?#A2YlQOw;dJ2-F-rj@AVH;}RQe(9 zSEk|>$w>Fj!&SXzc(AV;FkvVN9PwtjncdL&*D1X|;0?h5@-+Z12_GM=bAQ*Jou9zK zxk62FRhUq6p3yg*j&h*rzeGQ*&v2|cajZD$${Aok%!q8CJ*!oB8zO!+ibBgbFF|FW zlM+V)Rd-puxbbAeu9T;gdySa(M^4OEFsU(6iru3*z(-~6UQEJB>^{wQ{uO8hDx^su z57_~TLRtCvllra_xPrM1%H>NJEP#)1X#CzQN>Kl-#_S1xwXrRK-@i%iNT4iW_M!q@ zoWX=)qpf3mn4r)Y{FPA>X*)MfQ;rf7kH|b<@~SwbN<6sbp=-k_!#ByDBKrLBE?20& zw)4>`wiT5xWh|bkM)Uvq5F~6B$JN@kfq(P%QTMo zjxYM;ml_Eb4$--28)Kso%%v2TI7cwN@ykqpF*g>;XM=6WMBNyH(Gmpt4?|< z>hr7m$U{wQIoD@vT?(^RZqCbdbzE~%!H}mw6c!u)M2{*g40(C0$ko$ijVMx?X_Xih zDgt;1Rv#r`--pQO=Vf$m<}{obOyfxXzn3Z?O^8zFv)wQMsq{iQaq`87;$N^-(N`7~}2# z;|s1`qTBs9UYQl~;zcnkZmGq`DFS1nOPZdy89BbbFBy~sN-HcY2+iE zuW@BI+pIV@w^o}gVX6zKq7ZGdeaknrcA~u*l9TSy1d47w+*$N=E(a1kCT>+yoK&x1 z|H2O=xH-hqB=;;OUH8L56dF0^no3Ms3i+DF(6t~tK}n1KXlntp%_C*K#ty1ZmSUCO zoyx>aO`y+Io3ZdY+M2lzXXyU+obc`c<|K?4z`5m<#56P>GVVGLQ72gHB>Rtx_?0l+ zM$`{s)Lb3-u{{Sn2qWn3pcxxl8eExFPnzR(B8NDEfEec;;OVrs#p8){?Cfu}^|m4f zLALm1nUKGxW*=~<$hL2hdK&ynJulRNW#%d1|M<5tF7eA1V?FmutgrLKV{2L7{7TP6 zR(+`fy*1HAWdv~t(1wtw_p`ktX1N(@TDStVhd)wqtN!C~sY1bA-AkjP*0{sF7hPY2 zL!z$T^h$)4V8Gd{xET;fqR|GBygh~`k;Lb|c68tvLhp^+yIRW3sbwnos&?^IIKNW1 zF9C!KX!n~L-zh1BqPbRr8iBY%kv)ZqCVs_;Ffho*#06&qXJyAviK7ZJnKSx1?mj38 zN+h2ACNKi)Av)=7{S$(wumd2)tF>p=-GZ|QS@t((@X1Ej(tp4GwdD42;ud}>*UaW1 zQO+k1mSIxMhr4#mK}txVHxlpymh;aP;xyb+)wZZ<+LWl~EglWAt%)O=vKMd7yn31327K zlpv(+$N1IzV$b|PzJ54;cpPo-J3o*3RBQo7Sh==VE}aBWvGcj@t5G?Gks8<{PoHOo zQvYxdNvv_i!hpMy8Sh!90Mpc1LdPSZ3<%Hff?)eOx``Ve z#%vi zfFTbWhtB@ryx>0rK*l@~@QuSeD$8L*$*jSppL4J8#D9IL5{gz<^m(}k#6aG%qw)B- z6Em>m;MQgH+c(VyVJU#Vo)teDCDG9hsQyErNQ`WJh$LtfHn=O-i;}&-VA-h&kfH+7 z#}cp0eg0)}kxC7kxwhg%@6Tf21%^MZm$`B`6vl}^Jq+gpzrUa=hH$IRl@IYyJ6zk{ z{V;S9AHuzMx{Phvmc9h)Mj884rFU501vIt{19+=44(z}Pyrnukj0(afSbct1M^;YZ zK_}96e@Bq*7$?lQ>DhG_scj0Q1Y;ZQhrm#|@|1{M>#1?2r%&M>qwNE1Wo&*0Q6bOzu!ujFl`aK9u4ayJ}aM&2gHm{_Bm>ulaEK z+Cu{H`i%9h4KXU-L}DV0+W?*IYqnI^XD%V)X*$0+mU3K4`(XaEbMc!oz5B@4i%c8l5Jq7wHc}QTYB;<3N+p?@-MPFQ$mTJF_h-yR_ zz8}6_(I1R|50Jd&s|U<-;jb}3O{Es~6ktVtP+6i7*GP?1w~Q_m7Ns(6h zIr75vhS?8)I9>Szi$d)PS0Y%H358ZTrRsQ{8S2|0)FD`Y^}rX zYNicnF#q^b&R!l_VXKF>pzE}##ga-j~3SuDPlPBVc%Jb69>TZPb%|qvJKGvC>Ko| z$<%t$zX6|fou~6EE$Vaem^f8XSnkvXXx^c@AwhI1qQL~X6kdkq#UNW%XVc>8e}}^) zjKVRWP%%UWzztXd!B3gCP<@W7s7i0*oW#`x;1K)U zSVnK-)hg(pJ@aK+G#R2?&h_0lYuR7=~sj*M0!D{YKmQbLoAcyBK71)tlrY z%>rM>GJ?g2)}#0Lx?kR2@-1RpV74F6mGjGKbL;r5pl`?J>@bvlk1B9(@m>j4>jG?v zVcw$)zr$)G;F)ULbi!^hWqRXZ16xf))WVe^0H+8=FlXQwpm>vyr?*q$L~g(xQHciq z|2AI-32X)f5U=^$A|3JJ2N`!Mz-|L}qI7yGE%eAby>A-Vik?jZ($kDH&1_dGkwW78 zJEB-58+aQjVb`(e%s13iqMkMl2~NmTIoB|SlgmaiM_5?&SHq{--dRL6(K5)*c1-#X z8+Uf#SL5Fm4R314t(RU4?fZIrO$xPew-Ibb9L-E7jbrLzFX&IV_69;`+eR(EHGFy> z(|v(|zp3wwtHY|Sot?h7-Kt#U9me)vY+1bG(Ai_|duq~IW&3tGL3~_E*u(fk@u3Ip zD;a_-_s~eqwuprS%7@1MeQj<0$+BD2t^Z5n^Z$ygU8w3duTQ33DYOTIQ-E3$Vei;1aM zR*dCq#`ZJm+@rd5cem~KKQLaWWWw>YI;ntCJmfneFg(FW2>BPzA-6{B#d7<1y+UM; zX1@xAIYMg~>03j;pL2*mi7M|lq-Jm;H5EJ|sdhvU5dw2VR=*bCx25Lc$ye2%rkqrU zF3vbHH*5?x!%myQIm#}p3PE{oi=7TiJ^}65g@rv=K=Q24saYdJ?I1J22D@#*Z&R5g z35)~8-{9v7x2kiYXCeg!N%KhvIu|~Tv{2%eFDX3-%2#8cA&@{C6vY;Fmwyl{H8eAx z&>kTbA@!`@b^8{ZfzyCRzF5>@CMe7gEld)?A!JHo+4dW>I3G-_$U45fh)FLnD~;7o zu}4AfqcF8bGL9JQEn#Ii9(JS%7-*6!kNsxQpHn2cj>h&;@{oXH+JSKl7jA~&rJtvP zM94fJsXe|7QW0z)QxT@FVEu&$sA3cqw|A;3kdH`a7a4$s|mn)vCBj_tnq%=DCz z^9W==%x6LCdg(>s7G;5lp?N8sm=P6LgI!@<@yr?-@ZrmLeFQ4QLeT{GqO+L8#dTFQ zXsuj4iQ=~ZeOfdH%~9we&PkZ2f`YgMoQ`vF?c6@Ir5olMsUNZD%>U7kW-ds}j+zqm z=t;?8*A`666khyurqBG7*tzJo74CU681EJ-+@E6224w>+5ItNlz%7T^`0v1uf%!D4 zFr?afa)eih#F7RXgiCSDK?+ajtR{mKf zR3ZC@A2o2^c&&A^>D-=)`lJE4?qs*MNE+@+5ZP*WL_N8I!h@Vb-hDRNsN{P7S#yX) zGy%fiPpQ)lf@dj8U)~qMY}FzW@3D&F^)paptD1risV&UR6_rmm38b$eIfAYe%vMos z7$x<>+@A32sr#WVwXt4cTp41GByr6kAbmYg^}3jN$wom{{lzjn=M$5g+RcTHGPo7^^xJB(r_yCu&YW}K za=pzQAsJ1_Y?kD!`3Wftuj4iMScf)MCL7jq89&@~ z22Ae7iriD@favzwtOFbf1}EGWn!3tM0V^7AX0>Y}^fA61I5g&MbZ@8&-*t`)XtH05JTo)uIAes=wrR$)xZ$ ze$K^0d360)F?KMZ!|&mDig2&+HU5qdQ23?zq_%?f7Etc(uhLubqHw&(-O=|W@xf&? zQ&)$3eX8JWKeU+FYWkrGSh8tk$zasjmIDe5Sx^d&f9)s)2vTuP>G#O9UEU>wW_ODx ze^gj{F^m)cyQa|4vl;eCD@>iOfge{eGAa~U|8U3{ zELV3J)ATA#50)cTHo6eCCSs}macCBW4>DBh^#)@lpaBg0* zK)QA2JJRE?Zsy$Xd1lCR{(S4?HZQ^C8Y5?ZSc0?hU@}j(?V)J;?5r?PhIFQPlpA4D>e4IkB!K?zAJTX+KH~4e&;N!&O{kS0bna;P?|6SB28+#P0-l z@s-doftkK`!$hVGATGtHc+wkFHx=a~$CDd#$8y4DgrEH-9CoIm1c{#Y{!NGzm+`fM z1EWE>wl;#nz_&kwI5tgyIdna-k!Tw^awi^frYNswLdbyV91fqYWc;Bf>Y-P*Lj)%n z-6nV!^9w}f&Rh+n;pf}r)$&-|flrGWU#1pa@<&#UcYpRU?P?YTr_UW84K})&KfpEU z-`aU2vi8|^UKePZO+hVxNNl>DDFj`86qmuY(@!zXr>F!ulxG~CeV2v>w_ zM)*$zh=1g6wBz1vo4~(%B?K`xNAWdLQG$xkytQ&&zAYV*o8gS%23rQs(<;N%6duq~ z0V9q{9{1eSM~&X~TTd75{AEDBfOMkf8M?LSqIp@0)usw3gFJ5Cj;@`+S(F?>x%fpL z*XIBph!TA#G8QhwJUCVH5t3{TccY=b-H{t@!u4CcDOAeP81 zTs!6Q@?I>F42Q1sh_yiARYuFysYqnFOj=QhiTXUP0&@w+!0RC1QIy^9i^AM4>~w-= zF1Ctlnd18F2FxFQ$z^|n-$C3)9xP1LP(zeM;Oo@dHfW)R z;`KCOqE{=VtFyj86uJ&+Jo-0+ljP&e5EiBjuooU2sd2`iMOw=NXs&p?B z0>*RjC=`zB(o}*7-9xxt<(no7u{j3f*iryf%HrnKIu^Dfxg;^(y+G@p4+OW~ohX** zL<9Dn!-%gXmWew&og7pSo%fm-A>fo=Uo-4i1RgY<&A*I|3zQj1$Qq_s?{DCfKZ$*& zK$YB4zJRANZ4~ZqMN{1mos%@DM4G+!*jhfo!`IfPp2C?k#{H}W<8*W_Cn8E++LMAw@vE_fgiPpMG`)U9{Rf=T(bTIlphH_q z7&-=Yu%95FQaP|n`18{(iX#_ywDxZWz*A}eo=mj7gpyMLg(vv6N9$L~opZ(^mHf*B zq_YXY>xby)WIXmTh3#45iqJ!EUr3`(#Or!Y6M=+EMIQ=Y@?)785^!aT^tgvKFtU68 z4lZa;iI6i-u3BRa`Q1Of2)G29hwfLF$WH)&BEBi9m1VS-Lz>VBMs_e?W(D|0x{36c z0NKp^t}hiH7~eDzC{9EX9=1$qcV0dwRK*I)W|x-~WtZ{cJtK-0J0tg}KV+8ENBSg$ zi*QI=HdnXsLsJFeTl()2pXZ#k#rmS72~D<w~GI45=^uxh0Pu#bicHaugQZ|Dj7aymy((m-(=3sJf)U z_h+%BdSRhMfrC-21iodOTw2sN68>-%)To@@*7|2y(Lx&`ay@!Fxbe@ z?q#qf=4*A`@uiYjNM+03ma1a8*kbwj`m~IW5p+#`hj!_dSa8l>=0W#ZGPFzY>iALp z3^kvzgqfX9o#bllITE?vEYXb#{n^6Q=K;Oo+05-(ZkcT;hZu8SzK+ z^#I=2?I>!|ha7ELwcsW0&ha3j?O^4mdsrMp?jEHXh_bsaWk|T4{InqI; zb7t1`4w==qS?s&g&xy;HsJ@zdjbeMQz_|g;?qoULC!L0NDyK0Rz5cJEF*iHS`o=F{ zAEgBYW6F_r>)7|H?1WGj?}vRJOkCG-m@}pN7Xsi=(l+#YPf=2n3?Xd5gUJrogO|$Z zvf|z)K*SM|7xC5GqSF+h{m=$jpuwqvjIPF}CtM z&K@fsiISUtoO}d%IvKrFvs-DXl9DCFJ0ZY+(rw*vDY!2AhEmwL@mUqAKW{=>z`(-MqPIKRJcl8FB2(%@BJVTMQ+OcW8-V16I76Tb46 z>m@G%iy22Y_xtG9#RthBn!Fz*;h3tC^w9>sw5f?NI3n8j3SLDYkfC0pSmAtgXBW9T z2*m1@Ocm}!E{@3(o?A7LRd%8W9KONQf)mJ5jhQ>H$`G)}(Jo0#?Wa45HTAAU8V(K? zIj_a|YBYE&9N@YgBlO2gsc2D+z1KR5vHnV2cwo+8>J*03ovtrnvBYr^#l3MHZm~h? zJpM!)CSo1D>mGlCgJMvU5Com^8dNuB+&g}jhGL)~uS%N!^X2efmVwa-NhxU*?#LZi zlbLQP%#ZpJ<)P`BsHxR>$c#y_lc8rV-V@Ahn-;SisI#2*o+M)5>yg_ag zyEE7PjOgcJq{}ViH$O9&`Zg|+1M4X}{IkbmqY&x{O}1IWkxc(vNo8^_lCMR&(uiTd zW(Wr4K$`?V&dyEfyrGt_z-l!3rJ`1kgDGl~zKr(l&_}0v%HqKxvUs&Su=I`^mae3s zW|6c}*@5cz4^@&!zc3Sq2@H!P#VPi2A{(VNJg2fXInNJjFZj0(RthR!<|{n(DEHd3 zHx@3?63*`H#?>{!H@SCXbw%fRQjaNNMINhOT>FimSL!R<4u6X#j?*+83iEGyN&dMW z64m;1|9*T;e-C~~U(Q+T;dDiwi|$WD7&6x8p5jCh!lPi)n}5l3?|$D-a+90n{_pivVaU zgPq$^kMt>(+Lng-$p4aa7DFq*b$SST;AwL z1mk+7&CuZ0e^Lq|3HJn*V4j86Uxl2PfMDD4VyUU5k5+PxB`baqn5il`cUFeF@K)4C zd;*8uy?oeKAN?R23XQM%+wN zG^DMa+W9pXs~lS>dA$w>{r5{9frV!ZP{u9sQ_{7${jn1aO}pbZo%BLljo;qM?$-Wm z9FIde{#(mi&m)ICv2+!Py1492h=G_II0imPPr)cu27CGUK@i6}R3o%kFf;rlQnI_meJ4?-EIs_F{^t%7i|zP$B3MZIgDvZX%W`U^Sre95k+=fb+DkN{TnDp#H1y}&T)fq4z;>}%@9x4Lm^ONWZP zCZFOALMW7X1V-z#30PDWoy#&AC!f3yz%ZNA3Kf;^@B}0_McAicz-U)nz6U`BvvKOp`t(6y_!uMrTsOTp3pRvo-SG_Jn9bL=zF_d@y_fq?Y*O!@ zrCFbcs#(2ZP=F!g7UHL>!7H1sGdcfY5#z24P@aqWPcc}xz1y0y?I+x&JK}0=3Ryyf z;L5uYS;@G*k^ztTP8#K3X3E>YIM_&f%s-4a3@~n$Npw#l#?HQWRUAMncQ(eUN*sf1 z{^BM4n{6id(C4j4k#iEW^C~jJ+ozTt2QswsP^c80cX~xlkW8h~*r5Lihb~yHkM{f@ zHP-9NOPPM^XSR5WTf&wK)prEfF!wz!uLEx`Q7G9d_S~0~2qG~Gw*^1JNRIhfxxB#2 zn>Cw1a-zf}Dgm0Q_LFlTg>2 zlT9Tpy!-XkO?ICTrMiSrP|4o8e3Pz!-S#OgLL3=2;T>JwgHIqnGBo`HW7aHesd(^MN<*ai z-n8-0n7(6ew6m7qRAQk|K^NUeN{RavS|m>v%il~O=N>AF=*&ef81dv8#TwUIF3Fj4 zCJg^#d3QqQULEVjSh}PCem2OJV4xQ%qc>0(~ohXW+t5A(|t|z=)Xce2ZMamsA>I z5-xf->3g8DEPG%MkpbuEuYH$D<_JU6w3NeH)?Rkr%=^Ad=uwU5L*SPVkFQKh?uHs!@Tc_ zNKy7+4I*jcZIU+pd`d6w^HFagPSH547SaDI6n;eV)M6e=YCIq<6f!Rc3aMRKlLXP> zv4O?~D%BF|TxI;j=D)olF-^NvtpPc=y+GRx>GJ57XuH_>P5po^Uw{lTWR`N8l6f^$ zezz70kt&MYr*d{DD%pv)$!kp@`N$_9z571ZlOLP2?I+|jitULeY74dnKc#mYBc#{Q z^ho4U5!G1o^;NpG0;$Io2-lUyt=LLJij$MmL|yx-w=*Hr`PL1?zJ#~!v}b!q!jETB zvtR0#x0k55j)g#x5xS?3RB-Cc zt;P4Bu@$aZwO2acnhQP@>qadRX#$~yKZa?`x_4xFy3hp5Y@N89$x>s-UrAhK)dS^dB-Bj(ZE)3}7i?(iWe2ffdnTzMo04x;vei&=913qr3xeujGM%ntnY)d>*`y%&Hh~6VJmH}m8 zF3dmG6S8w@pD8fANFti6{TAt_v*MT}qjn*t>mn?>He)pUFrho$)}3mft}7{8@9&nJ zW?o#8uo*CzR%5_+JRI$B)N~u8spRb4F!(jeX4-AJ>6&8AB_q>=6p;Vgdt@5IHq@Zr+6<{WdpG2XfM z`g0<>5$pJ1M(p;xU((J^I)a7EmfFr^d+4|eDC$Ths_LBdMD<(%ljf=UuxVR;C&UVk z;JHOCYH`3h?4*%O#AroTW{WJEbPBlK;In^A%oLZ z_73WNYW}E|hqIjfV!-Nu+|Kt%#EA&G^c!$PCCVWX{DHFY+*nFoY1d*%wgmxN68wLx zXsPqN;(GYRjN#P-DFl{<>E4=w{K1*T;%X~qS&yug!kRrcMH5!=LwNP4Q-)mxD+R}N zLB*%E$pON38$$b0fO%^*N2#uLXR&GjumY9BJ7W*RT}<2|fMp2{#2S>J8nxL8hn@u1 z(6`g@CeQ6eMw3Ad5Bfb!C2_ype=0qJT9-%CAs$l+aw(gKR!1yYi}A>W~s?l_lx=t zP~^0R?;xVPCxQfuN3CLZJx=hAfv>7b9Il0IKfO$?brdZLZP<|gXdUO;?rg&TpC?bm z$yYxN@a>R>>Bsi|&FPkhiPA7^EmfiCbL^H=P7;PNhL z9^jNgwzeTSIBch~JxPlGk;c1Xs63z>+g)uEZ6$4a)7FqXn7T5OhTuc@ziNlrxef>{ z7o`C+e?kKTyL6u)P9&x0*5+2370_9X+swi2Qz*}5tsTXo4~=x%Iw0(9eOds?(;ed? z1cbI%T(O@lPAOh#BA!&{Zjg^nBEmKFNM?Uud# z@IGVwG9yCAjD&f+krvKl7sA?uw9@14^y(AEeUNFcdqVuAfVuMff7?X7T#<+~ZGK{Q z@(dV!c+@1NE;Im{AQ|8QEtzLQU*8!9VqW+qKcCJ|w=nKUE1a1@khmH+748Q1Oo;TL zk0Z*MZA$4&dFQyT&u*~@(#r6v*c}TsAc{wj<;c87*Wb?Jo1$U+D9s#%m}6(@i8xb^ zoD}m#PXIJge`Jei?} zA#oySY2Y-csp{Jv&U1> zz*HN@ZKe9Lny-7Z5!4%GDU13AWc|ep!g2q1vIU&QjtNb^k34 zq?X1H5ZRJ<=h^&o>fEX;sc?z%;D%98>YVAEqaIp7HBf(t@q1^dTng#=PNj`L0a+Bf z)60CR4-;lqPfEgL8H3ZmU1{UoXMR%}KiXB3%Is#>f@FPiWsj&@T1&tSf3Wy;+&B2!1%MRq-T25$8Ga^ zV%g6QX=>k8S9gZC&TZu8ILcVkA(T?yHX9Qu?O*FrIJQQQ|M6tQO(L3oH1nzGcmmFl z{evJ12^?`x_nW;j-9*bmG;9p+3Uc=`F>P3uqUq-@?I4O2t&!f;={De(L=F~xS4PiK zxU4^T&#-m5%(q;Q<^4UTy{;>(dIyN#nT$npAEYK1V3=TvrblyvjbJO%=F@MK=WZj3 zO6_hns6TsKEPiR?Q!x1G8Q2nMp-L=! z#OEo9L4vA#@`Pp;zIbqB)Up0=*)=jWno7?06lFs@I8}@y*0!ug#NDE{+_|}yd`l_X z6*GNZ_w{y;=V()t5=0$8w5a*9Og>j>9Jl>&L>{MeXML6LTazpT(B1- zQ!B!KURRbx{_W~}E~%9a)kW5ijwO4JEgN#e%S_BWMC)-p2R|pO7O+|#F7F@BqeAr$ z@M)Z4MC{qqcs+A&k@>h{N?^U zu%gF6s?#mjEs}>}dU=Exq{iuIA?!^@#a+&7%jRyeZfstMwY{I`?2>}w;S0L~G*6i= z&R}O_B2v{d-(Tw9;gUfysW@<)eltsCM1cKj`wg+l{u+J>hgAlOg=H1}nTom_&jlaY zk3D~WwIoabu*Lu*tz7#%2S5e$8~r9Z!I!mJ{$1!XXDI9db$&A<<0cDuMU2Mdq82V$ z;~e*BRSP>#q=DdSaeQUpJrA3M39@FQ6Z>-{V?^Oc3@0MU+>+DUPe-z?QoIv1`OuTT z9~UiE0^TVw5rY9jwBys?0ak_$fxlCbKLJmHD#o+%P50^z_CBR^`fDC}L-#mt# zxEQnL>=A$S-4yIWZsiaIXiq-SeB#WYt&Her4O9xmolm7jWmmHQg>wg2>XA9!-0+L}3vIbRKsAQE1WDt0xsn6Cn4UdDx| z&)TDhkr-oFd>;A2x&{9^`BfYHe|=0Lj0K-2C3*)H^wK?f13v_Gw!v9IgQd(jRWQE9 zwl07%!nt&`7eA@l862GYdJi%*HE>E*`OmKM$42(B5w2jhth9H$0G7enl?PgV*W!H> z6mH+%ey^g6lZj9V6OXoYJ^c$4$*5F47wN)x6fb3%JOK4SZr_FH0+l?SjTO#);QZGy zmfLM>-(>7OP{0Nt9}`vC(To1#WZ1aXB{#HAnpU|1h zG1?m-qy(tgLylP(7qr<}cE69AnW4K`)4mIPf0VGbZCEy+%(2Y0!P)1P9F4~QY2##7 zh1W^M84FlAqV5Yh3Bb)#>S2<;%n$hqlpvn@4ldxwQICs`?6B#yNSd%#1e5JP<| z`4(lc(7)YTg!ZQ;LNKTbj-5E(sf2DPP{#RfnA6b0U84YiKYz5J1Og>JJ zT-^2D?CzLB45vD$=PCRH#szIYSTX}X^AOgvwA8D7_D{`R7nlM3>?@-!0WB5xP;fAu22>Q(v?Go6 zKbvo6K)Xqj@@;AKp4HGn*e-CzJ1gl|&9rL+jKQi5)}* z+UjG8rgm;*v8!EKG7tJ8yM8>cxn6BJQDOBYDTljPGZi*%+QA9Tt<4?`98sgdK;<9(J4A?9HKNCdEKvreW^6sZ z9SQ0Vsakl6>W>oUZi%>V5xULJ>0g-?nleFGt=paO%QcNhwEed#S8b&94^pY*o6f`z zmYqse!LeHag<7z?%r5#Lg>vEgJ~8g*MnV^dgX}3Qzjl{2Xi@cuY4)Z(X8yY5jL_WY8Dz2YE{+hdAfFr;6C?zcvGg#&v;~^3Sz%G zg<0LUiR1CcMDm|kiBak;-1oo&035ve^_gazqyynb2>wZB#J}U#>7-U57X1PfQd#~l z4{C28dW6d^WO`Oq{cq z9gk-s+GBSMY!z%ZwY3IWslMKUZ>snH15rzasKrv!|D&|?M5&{SJvF5UM(|^E00t4d z+Fes~`gsF%TGPngB>x~%i6P`6+4D#0xWVb-S+U0J;by|`qZbu?7P^KPjegQ>lQ=T7qf$XUr}4ESztBM9S5kAW`H(-k z#n(ZeL6=?s#}=EH0pMSAy>NzPsX>n);&g<;kxh(&MmVux+)SX3mvA}&&y5_JHgMbs z+rQvtw|Ki|0TY2UH;P)=e#d<~1eh-Bhg-N5f}5v3+u1%%pmNqn4l@4Eha+|8e@V2nrT$rPyaCPW(Cq>n7UE-L7l!2Tq4&yOMJvvg8x(zM#Tg zwWc&~T|21)I)4=4bQ&~Y#OE3FojGVVXWq_}nT;*(TT+9`GvEb7?{ylVmRZ z8^(Aj;YNT>GZ3VsnZJlZ4G`5Qo&na!CAXIfXAsZCaROkSY>SpkeTM#A`V20FgA8~o z?_EE4O81QP;SecBke4O@0Y(;eMx89EZ%?gYQKi}I4Dv3xf0Rk%K>DzvuS-V*RT5@b zF4_lnx8YhA0TzY_VA97QJ%w{o_#@vIrb$$(0FVvvKalh>KE!RmYu1!P9QfTndUYQa zEiNyId;(r8w|*z&admZ*Y416>{hi7boJ{mt5NXrOl-vkH=!q{bu!5lN`ie*f+>LZ7>>1Uv@2x3<|h z#{GKSR6JSx+8*P3os^^7QJZ)H27;FM)60)!mv)cmJA;62N^gM_YOC7Ikr3vTR$xS z?#nL^A0KnAanDLyk$cc$~2OYVP?GJiNmmi?e>(MT}0j&{q~XCnu6&aO2`B+d%VZ1xx;yy7-5 zbUMFc7%-|cJ7+dF03QsqhqW1p%%oN`soI{*MYH(+d(1`T)_%7%d!%PX*#k!ewxIoF zGnm&{Wx_th6qtwug}!})+#6&5>>(p19y9?wo zBC1=$7l2ckBw))TW{*2Y4*#vOx2>8kR>?Rev1b8^84Ngvnk><~A&f8pGYqIkx@E-s zEHg-%8P$W-l;?alC(_1y3F!u`Gw6E?jU-^=%kUBS^O*ETw^HVtao9$9)!AwA{+7-1 zW)iq?4>CyA>`#S-M~i+^-f%aWg&0Cz$?gFd@6;*8bl<&kXsI0r?5Rzy;9i86m6$gz9!Od1XyVds0RC}~^LQL=fhc2wiw(z3Ym$b0=AB_6>o z#+;XWpVrLh!0mEKu;&v8uWZ_X!d2z zs^+=o$kF0Y_$9P$y73UOjRvD$tk9g0377IUjeOD)<@_1MSQBVi$&SY<=o zR=?o4S~9=1N~W{yZ^9SUbTtv8tlN8&d{nLtP>LOH2&#x+ee6o*0+dSPe8hjFf7!lz?#``2 zk}otke+PfJ8*IJXI1JcM0`pGETOqB87+d+OIe0S{A|@DR;!4EI3mv-`r|+hqAY?xI zSj<1)+q7JtIEJ`>B$y$Qb)f!8BaB=mHE}o8@WBe0M(C6t9BSvG{_73leCZ-of89&@;LogZ zM#(V<43PMi?f$}fbCr=G1grK*A_tg)Ps58{DYtGHb}?2k$;r-;a_8$mSXbX`JL3YWOcy>qa!f5HyHitVY4$ULo`ET z|J-SFp21IxE@*PDll0`qXJ7ry27DL7lDN~G$MtX)*3p+NOHjKl;Q??SzbW-ff7biP zH|ywISOhdqJIDefI6kDc!!17cZFr0TJWs1%fj|Dwdj9{FPYl2^XxIR=D&P!u4=Lvc zy#K@6n|(u5fejcH=bs>O@>2hJs4MMdH^huELg;6Avk#7prNX!m@`siUFbf(8qBYbS z(wtw05R?0WKKhEh|G%>UE5uB^yb4%=g@|cv_36nNrWcK#Yp-U90)zS?0S1Y1mserXP zLsLJ-@n4H26TN9scC`90HT&#vN;v{MbqF5f=lth9d0G%0pS5!%t$~TogEb;onHVs+ zU|i}3+2FX{WbMO2e{giiWxGmj}U%z zqsk}?mm;wJ)|IR3Tg+o$ZsN=E;2KVPlt((be(7Fnl97t!-Ku04eytZ_iZ*5XTC}33xx?hOwg;px6M|!s@&kB%luqviIC&B|)We zEYHgg?|)Pj?2->B`dZqCxUof19~a1^4!CY`AfN*j5R6*F2=l;nWVCj7kuOXT+Svq6 z?7j;yRry=*9Uk|N>=yb~55+q)PnmR_bPZnr(?vz^pYDtITg{x?XRe$2e#^arfD0kt zjz78aJ>+v}6KU&jt(_kpl{a>l?_0a2L~RY=BlM&42$ zpDLuY+mCb%lVf!GVKYHpA+OLwg_kTCdgRxM9?&@sjC9^l?xRJ>eH@o$Xzgw^Sec(! ze|f(8o;UlqN^hkaUpN=1H8B-fYiI{ahGEy<_aHd3C%pUGdHC?$Tpgrg5nKNXm)-KlxzgGnuK@0zbk z8%xGZ>O_^jz==w-5GVKVmzNEuTN!iYGL6VjS5|eqQBB&Dc z#(TgEhs}T=|L03~YC~tOY;xQTBoRFw-iNZvxJ1M1xdIUawGCg?0>Bpqb3V58qSr_3 z%m1k6(lEt;>VEC;|2Imyzl6ipZ(A7|nVZncb{6>GaC&(oro>Vk7yVR0s*1^8j89=L z3m7gsUHAs0qP&j3Lmn79r#^M#gWP9G_y|Z>uyC~gm!#6MJ;!qL6?y|A+gIuuP2B2 zabmEW_=EjGe)p;{nuF9)sb-zVTl(bs7e4ym--gKY2D&AtAHle}UuLH!ID+m1o;X<9 zR^nZRAu$TlM-D&|{KPDa1Z*&rIOnDzSnUhP1L4$eDRz%dq+22eX#u*ZnSgRLN(7h> zDmz#)8vpUq@PG91Moi0o($qkEPemAf-vVx~M?3pD9gHx3B79}8x^nbqsZmo)pb>AY zf~J}Tk(qw6oBiu`cO^0TLPHQLf-1*s@cP2U!dG`3c3v}KDkw&Ng>P?G0{q{%x7}QQ zY8JN%w;4}kOgnnWIwJcPr2~vplO_X$f_EBwqG8d1>tT7@cPY(5J>C%6pi~-tjEGeA zC=K0(2l=SCbX?YtvR>XFuXvQ^VVA1m_YSqu)--+yg0yjL#SkrhGPn*e<*okO(Jp7X z6kKA+3U2nlc8^4i_`%}v_u#_rR?|n1CzXXndwog@`=x2LR6;63vvVy&sI7j#cZB|O zQpY_HYXbBa(J#kQVanJ~+WEK9#jb4Uew@Y@c-E77I|>X!FiD|eBr^-%>2NgjMQ6rY znbC_={{ukD)1naER?S4~<>*}ECRA%>><&5r4PNE+^Ze#Vpvg$S4yr{32f{XJ-41n` z(m-Ts^*Q4ZeRDMe2u9uhHv0&FzB31c%ZUcPd%IlHKx`S0(Ai0Yf%9$ptACeS8>p4* z6)~CFYCRz1Hw7qF`tyE@yl$rh{I4I9;EVIXK-S`xu#i&>#N;~SN=YB)GvgvH#_z_H1v^= zk`PT$HM}b*1(?^(Pb`Gkri3mryVKxXishGP^9Bq$NUZtQz6CDZAwZ7?y%BtOHIuCW z((qluWLa<4-!SKF14%eHR#800Z!$2c_u1nbgn@{IVPL! zV9mswUJr>W-4uxsdW;UjoMkUiF(q6E&DcP&Y z(qLapSruGwzDnYP_U6Bg=&d`Tu)4$XvtF2NN-}!9ARgt+`5lI2T8jaGt>SlmEaLFdd`xI&ANvNgG zv>uHBYJuvv&1m{>6&2Z*+eb*4!TR)&6UDilEGllxE$O4Bwn>%A&K3pX-G}bf=*9IG z^Xh7jx2p%9B&jwTd}NEHnr7$VFnO+i^=tP<6RWNd9(7n6yl>{~m*3XL%HqxcN=omT zXxnmu&k)@Vhi8+!$|@mURT0cxhjJX;lGiG@S_76%D)VDkS2mLckZZYm??q(}1lb!8O48TkTe(x_|BJ&W7S|JcAEaFngF~C6 zu48h9ck6B63Ct)EU1ula92HT{li2@G=QNj`d9+|OUVzIkXFE6gSl8h5#of0bNW0Sm z$5sXFQ)AOO2wE=jLJzFcU6w7prjN$2VXq9N;I${ZwFm<_`h27eNla9`j#YYZ#+uJ za5JE0{UaB^MT{+d(gfNrF%5k#CJnXT zy*m;Isy@0#)MtiEVeBS)KjlqB^8OsgLC!;IrO_E~2F9@7fAl&8toJNeZk=Ma7UE!d zNzMcJhCYoSpIte8D@`*d68gSXi;n%|6nC09FAe(l783_E6d2>#{4OS3=h+_nQTK<` zC1;Hh5Q4Hg55G1>RKefT{)eo)0I!WJ&n~oEVY<(cxC(sQxtQ~bAvuWx>dPavz$#l0}(r}U_f2H(z{_8^gK z$Rx-fMP4?j3_C+^#S%G(b%d*pjb)3 z8-m>C_ij7D2xJ{RD17{dBh~^%Z6k)~0ES2-biTnx5uew@Y9KHd7!Ku?-qPb;H2E>| zVs4}U=c+2&znk2baJ{}+D*gG-{EaciIRP~C3z+zmG8tEZ-uS(n_~K#EgenRkux5Ki z5JN`p(Hy9^zVb^sq(F}bmdXh-Y%_QY9z_aE2JhW5f|ukbB9=GD7Vd{SePxp+*O z+R7Ip9)4Bi0}-HDkN_d(`;Wh##*U7W=BgbPq;hqc)+Dmht6G+Xnt?_)8rYbCy;2Lj z8&QJf43I8ogDs_@;^x`^+9h9e&c#hs9}M`nZ=stusZ<61Ibg#6ijg|hsycQ25X}IA z*bPtuqhEQ_f8;(UA-(k=jPPbqu9;wTD+iq7LYU{Yo;Nb&&0DrMu?1d@56s;r2Bz7C z*!yAE`y*y^0M#)%?@$gl17+L9ID5Nfe1Qh+lH_J0UtuPE3=$AJ2>wA^z+G|!z#(gT z`#oc>8l>jSIS(m~6MfMNP1=bf$fC_>(r>Amh97l}(J4$mS4orK7J}|gIE`P& z7hc{XQ6}zR`I!$on557@*IEvVAbHy8}_H_G#qnORf9 z^1BaBLc?DXufGV!a;%KBGL<1j5GUG5+!JpY;_d;5z7}RYaS!Nu5}DV0T&MBjB^7p3 z!VCIz?vxvupoKvHjEjCermy%{$z^Z&Y_mOelVR?Mj|4rLaP(zU>9>MD>kc#{UwiwFLXCgUT$j)X7_(f@5cifkYKWJrXY?Q9a#%Lt$VG z0ms#@O<Rs$x^T(XHS4m&k+xe38+fZj9u5=`Hl{~77x{W&$6;>aGuLPLe(l zqk!z9V3)$IR5MA07^-(a678s*iV7ij?)Dx4_bEtRN^%%wcIIC=9CC;X-}l|RbT1f` zx^@3(`Q;ozq_j~RF2UJnFPlH*wFYDNt0X!8=+iif=$DHtPbbO9hU|M4jY03fHSN#1 zj!F&7eoL^^5hXX&=ieBO32wlTG^2XELmjJUG^Mot$0{g2HKc=%UR(e!9HanIAuUF8 zn8A!z^Se;pbiiG6srew0*-UT}EkcWXbLYzX zy(>7(fJ=HXKE>RHx#k0R?5B}t9)YxabBRKDmlW z)Bx(6?$|Ez`)%;#7_Z%}O$&ZiA`R*=Cy-E5h-I1rRl&E=to3oBi zQ3mvCaW=7C$XJUI`#O=$%#7n8%3@rs%~SWibt+Pg`6servvrkvK0DWrYk5nz{gJ+W zbxX6hO>xV6PS}E$_p9-y2v*xLc*$i=L3Va5cPyZ@YeM1ad&zVqJz9S`vz3Q}PAOk;nKUMc z6nYEw)L~ft!KA1J+2mI(pXiz#YBq1uI1b3QdrA_!5Wa_I*f($tr7Dy=_pXv?*Mw@- ztk|6|q^%FRfCM!f79mj+dz%eOv3&G0XtV10;HPCGksU5Jy#>;-3@3JepI%!7iSCCA zF1YV%9_cU>Ll8Kb_C%bz-2&rsM!a}Vayg@_ujT6c zh28n$d`&RghlD@J!NR9mt& za6Zv~S8n~B{H^`4a;NcI_F8dYw^0wti7PV%_#_2`k(Z@gHrYX+5aaO%ZqS3SgN>W& zU~5F;bwmOoay{(1!G<(;%D^^rrUqn``&7xqC3IDW7ps%ec@up%U)^#QY%@0R!npc$`2&ey$!Qltm`GYx5^_MMhRnK& zSaXS*G?)!zJ~m!3hp4=nm3F#(?4;|o=9-?F7JE?-%k-}1y5Mxu*y((8WLc)Sy9m?f-U#i9 zlk})5k7&ftqPO=Tow+r&E`pzNPLxc_a~L1wkyroMI}L6EreG!-=59r zwpNMTvM4yt`-avTcHRp5jh{->rRU2)IEQt9RA=y`2$=X0gdbwUeHUwG6-=+Rz1AmC zr6Js|1vMJ=z;$5^5}L>b#U!!op-A17d1QG@(5sq>@jAM*)4dfDKzWNX5(6U~3F#v4 zKn97jo_73Hv9tl2MFk;!e5mPy|3LqifXiOHVqKR`-ZU! ze7#qr2>9e%cbW#{k(jG?po2l4LSa0oC;PT&xFsRJn)>0E>lbInzR9A{R9IL3p3h}t zkYZDBrgY146bZFJ9UliVl2{r1=dNiwH01e%6t8zk{wPno!QZ(>U~H2l6eXXXoarlw zRm)Kzi*_b4IX1a?q^Qijm?S&Aa(DdrCea+Zjqx}oCKWi^eKZx%?}}^Merlo8j(FAf zAC@0*km|zGm5qMHR)FjN%u_j*dE7*UO_2rfL!?>RN7c$4z2oq^sv3kNB&K@`?S^IK zn^{s+FtF&6WsXXJ*qLT+)Te_eghMm=&vtM&;Z z=7TO7m8+=Ce_G?Y@N-ymJxNtskfmH1WCV3-i}eSMqdERM18r`F_fF|geSH8tOd>Wb zy5irzy6-Xgog+?ri4Caxb;cI|*QVPH$Z8IGs%hu24Y+TD@6SxLTp&jS3yQ+kE2xN&oij<2xa zT6=k?HdEnm z8Ar`JonK|3LX5qF7-a(+`~4ooX`fCW$Vnyt#25Y7qi`>1_#U$I%+n z5vJ?T0gVH@OiSFKmxCEC7)M!n-kUHv$;`Z;i%GL|lA@F3b~HLi_?P_j zSOonWtkQ;*$=4obnnEwqvr8mdrR#I@tc+goA^i?0Jb`eu+e%L{mr zO|tECC?CAQRezPPqnMgG+h*mV(+`x=_%h53MK!YXURdXURbvZL^FH{I2dSzLB_OoW zeo2r1P~cPZ*w9T13$28$7@DfHVjFieJK{h+F|j4$;6=H7>-L?W&)dv z0q5rG7uUfOm{Y`9xCx{uv-$-NPa49xqrgUn-nim9}<+Z+(W#!s>`*UtIcqzC+h zAL@GO8v&4ot~Ie{x11?_8eZ>m$M(Mno$zoq)u`QF$uW&%+l8v zLtJ)(nY=w2aZoeP>P|_5sQX)+nVsAtJqZelb=t(iQ_Rq<+2F4ywz&IPlVuCNU@bbH9Q+$P3-;d-?bK8?TQX7RQo8-{B}9AGt*&n0*`o8p~zlV#obH# zL^=A}>4JQkF*RP<5Y!6U-8+EJSmDJTOnGEA)AyjI4o`N)0_}OMg_&VGjz)3y3|9Et zZqnEE=l-KKZJM(jMY{NKUM$VZ5h0{IiRXrq?Q=OcID#YndtScu@cZ}Y6cItTsCUc- ztORE`cj_N1aN$qkxcM>Ga|E>XulY+Qrj7pi0SZ+g;Ayf~MRh^&YR{~yHkdY2fe1S*B`SJGtc z`+Ybpn9KCUTqsN)f8&hz*XP2Db)*=qVE|v?6$5&>FuqL}5f#4tukKbFiX=pmtH?PB zHYbI{&P@A%F7DJFsRU|)Eg5wWjEA_QRj7Xe{LB?Z_V zwN}opRG@=43jx~%->rX=TIw|;#a^Kj_$4Ze=y&#=M2FWqIw;^*5hw&%>zW44hMzgL zRx&j&)!xY9Ul`2qt3y?~Y)#9g!{y4a_?vrk#h0l6mE8;nP;xt#42 z+odE>5pbulFWV^V82~zW#xl^T78eo|^p?G#r0MI9tv#ecaYNF4jHDy{Od-mD+Ui2R z15G5-_4H`nJ@H1hnzcEnjN1D=L6+Dre;Kh|+q~D_c}`Zg%AKh)|JGZjR8UGK8kPVf z7%DYLNmTU^-~*Upn#6w2-S_LN9ABnRVG=7Wp+!Vx*Uhj7iD~6!)oLqHPO%tC>PE>h z$({gXv^iw)IL&Wdtp=VJi8-d9=IZ&fbHUM-TI<{?wl+Opjc()#Sd~RQzYins8K_Gp zy%JjM?RIqvJ^2n{NcIAK{2HF5yx)w_#6WhNH_-5%&N}6tz*aIIHE-O|VknsvfF$Ip z8GJyf)JICK1I(EsqTHo_e@(LBHMc9SZc-S!D~(i+?l{((99DjlV^Sr;e9rsy@J_RU z3cQPl#~PC~LJ}wb5kfcv4{SVcVsU?i$IkiAmGo@XIkf+`uobFAv)$Vq zn}*To;&x|IRFyy{XpyO+a|;1S9cKKZ$yH_z2(7fosYhH(?iFwa{Mh&DAZ(N<(%nc~ zovr%j4H}G3tv*D&`XTsgD5`vUcH;%6o4uG&bPt8JpW%ESfv>&g6Q$;=rAnI_n5?W0 zwQ@^x4Z^U17!#x;gY-No7ZTKc9re3Tr)I%0Y9%mxVgHm*T;+VR!>uK7R7BPZHofPH zo$T35e&r{jJ1tGVkP(^4xitbO8Y}XES`8n@|LW6KwcL7nRh8;qb0ME}2xo5@x@YtV}>3?iOkCni*DRD>Sp>yaxZjLqRqIGhjDnUc$;}O`i-`!s|!3(h*Ya_ zPM(Wwub2EaJMgFOs%>P1v{MD&>daunE;ff7I!~N~lzfp18?#IFSPa*PBs@PQUrgv$ zbv%*8%HxkS!`{LP<7?IzTbh@DENYmny7q(~%Pm*dW6wHsO-Wl?+sj@E;`qlivIbMb z7|YM>o>ZvHOQ*|-UAxT%6a)Z3J8hq{5hU-sK*7Y^oLq^a)gv}dmP1%2QRh^K21x@L ztL=ka0F@*~o$=iht`OkHcc6@rkYK>l&_rP-`8Edo&oSq;N}H4wgAIBQ;JE%zgW?=Q z^2ydo8dwu!KTro<%Bxf@{!DiU*U4(Ew6P9)s}cMM;j>0~eFpu-PVEF7MKVtQxseW} z>@vx~uL|fkZb*1i&D6uC>?6@BgrX4S9|wGJanR2nkp}2^(aB_xQWp^~0sUc}V?NPt zV4cCl*DuF*%}g15$b?eH6>};uvJomeLX!H5?j-use){8xIc)C~Y((s6)6qI6_qI1G zq%Sjgl-$1mPvAk@#R>)DtC1+x5F;%teML5j9{!$^G^A016Y129q5%!So0C?FdhJ(? zZFCqBI5+rHS3N%t`^c(ciPw@d^Z6t8(s=vdqLe{WWYJmFnSvP8D*0)`c@7QqxgSVY zy%6g=r4TWQM%X0Y_(~@CdEv`9MJmF%OuUKY30C&aE+LJ&j@02HQ@uDuRX$o}T19WX zFBO0X(3f(@r;=2OEmgs}&ahK)7;&j!G06bna011ul3>7+uRLvzMy0Es|W@upZ3oDJf`k2fd7faPPv;tLNh> z18MlhwmL)V3frIglp$bS9b_h~8BQf@0nb+WU3AAZJw3)1;%T#J4hR*nHsUiT{H8QMyROu#0fUiI4!Be*VP4 z>~B;!D(g5L-P&hnOlF1jlbOzL-NKa zbR8xR)9K>w=G4(C^7jl3jgI_+rFh=7njZ;6BJuKzk9swRJIPx9c9BF>A1-!}+_9`r z`M3J7h|TXVo4If3F%We(Bol7v5jq5uG2OQ;nCG%lGs>|y=|j^EnE!4ry!TYzK+41V zmPfgAs2FnC^c#=$h?$`Ri@;%acLExguSX>Ilnat(YatyW=&T^;Zs(>I4b->2y6yv`;E7?W1^X;>h^lUe#YRQq3{Pg-@o^K<8DuKpj zYw#$)W@PY#lklPQs~K?&$iC07t>_+MtuDm%ZRtX`6L08gVG9Ek;a?hx z$p%bwCR?WA{>-^8Ibi1~?S93PEZ6ZpymB<;mfuF2JB2A(NjGKGew1^52_d#+xgV3kx9h;%BurX%NS8aY ze!6^5s>zuY0l+l_2r3B=2~{suWHF&C8&%>HqXSGt$B&ag9TprGcQ=%58t{c)EDjti zrt*>$Iw39LdV1 z|E?h$Kn6{KypiHine8045-O<8JYya?UB`YHdqvTzqc3Y0%nvp=Fsu(nf}<)zjBQmH z^AlOLzX_|5mrBx(CPYKbqd7`e_({H7IVl=Okma*RNqSaK8ClyexS!R0%O)fD&*g)8 z>R`P>2^p#2^kmBR&9H+%bm;^IBZ)&hqiWoH&RT+m)iI>fHzupLPob%8n3}^CUnFc7%{tATQvug)ZAN|966a9G-Y_z|C|~PKDp$GifF{|*T~{QuIqjMj%s3i`mj%;db z2}|`JT!yvZin+ z2kvp(?i@XMAa)A`De1*H7_LMq{~u}569by&-5$ub+kO>^zH?3{u=v1PrXic8%hx!7g%CvDPljH6`;Wu4n3o(~_nx@ASx zLeN4cZxNu1x4-(R1L0k=P@S=cQ?lURGIi+2z`Gf>UnR!H_>grAA_qd!I3$~!2qqHV zTGe^idiiDe!;kbBzY2BaIYdEfnp;a?Na0LABJXD00SQUqdr%2T&9AKDr1>Y8(b>!dZ;*{Cbt7*G7XW+6 zxUefO2J?Y0xsu|+^`GZWd;ec4NHhNUyVk{puY!bgYSfAE;5*JG)GYi5lR4quxw$1v z_NJ|EI^X*-vbF21ZA*nv{rWfaJN6rOpDrl3qT5?M#F3u0dM4rj;_0oUs_dTkVHyMp z3F#1|yE~*MB@Q4Qx_e`z>0=9GMaZ@ z9EE-qtZx|O@2J5li-N=vB{bw3&#&v=KM#kUz@41fzMenuz}wmkH%tnBa<-mhm+RY% zmbim3VRm^SQABl)qvjNgy^TJg&G`wj^Rt)vb@Gh^_f~}PmoNQFPba|D=`w8y1K}4s zS;YHfXJw_;y`SpgT!KVXr-iwvE9&b4y5eae7GS<8XWcpWWL?P~B2(uu<<;M6ImHG= zjw$G?u?a)zuGjHo5l&@j|GKx2UO4!cdoF#9>3x3kb^BnGnKAb7GU2Uk|L_>&9qBfQ z<${Ek4TC%XoU6My$&UmPCU?FP*%MgO04;RxvY{Sc5eL(Nx*{(74;U|6W;xy7H>Yn8 zQ~S2IXr5dOWxD=s*73NxyTxAos8FZ=fjpU5^mBI+cXzQt>_zWZ!W)lq0(^JZIHG79 zv?gUF&~{{%q5u4Bhs%#rq+|}+#E33_BnZ74^Ez*cI4z3&nSO)8D@5EZDTw5Cpvf~o z!LYs-5dZ0-ry!)ScfEgl1Ur>=;34APPCE&9Mcv#1aijXtCXE_WPD&rcSP4MGFiuqy znMUuEk}}5GYSQA*7&3#u;wWfKngBtkAkmEONBo-mm|AXA)_3bM7bMp&DTUxLFwqi7 z5@}?6 zeFy(NUF+g|8TiPJWq$+TkvNO~ed2zx-9n2qCc)5rF#o5)ce@^-CLz5v5hA-UDd4}!&le!`0-;0bIsAL= z&j(0m{-+SsTQmPA!`V!1VAa%veRP?&~ON@OpbT0-CMW^|R|iIRE1;(u{mh1%^* zVGQ_>A;xP`Qzfygd}+uFPxel#NiUcY;ykp(6;Y6vHSeZ-fPTYJ?u0JTuVrjpGQy^(gwJDbzH+&qV#z=Het#Ql^jHg`2{Y0_{I=j@lNZo_BUus4QYf-@c3& zeb76KjPzD1;o4xJMzp(FEa=RsNwd(KT#>F`Sx12Fp|py|&p#tQ?K_`f&Tj-o3GBAN-k_ZR3xOY{^ykXoU#?@V#Gs-k9L*FJ-qs+q zZ#{1K=SH?$R$|}SD#keHbheg+t>K;AP{hQ%>8-Q`pC_bweQQ z?FmouJh5im=FaSWx=y5GoP*0c79tA2-^4oSd5XjDuAp<}%oq`c*#`~~g4;dKn~J;L2( zs6e$%CBiN>n>#)5Q>T+N#f~Xk{-4^k+H{qOpJs@?@kGnhcHFgp?wck`ftDr9qNv{&|jU zXUp=|7Ezi2RN(uLuw#oM?uH?Nym#sR6Ph0#9=gu*at$KWKP85*`^N-J)zu~IyJq#f zvyy_5a3Y=J(RUfrhg5OzkEP zaa-@x6pDkI;LHIo^`?Q)-)q4PV!!?aCK?GC* zF_j2_hf!aCj+SXbRbV~qfyRs|$o=WXu$`?q{tLvXe^N0y&EjDXd99TN=dup5t6*P! zP!lNwhO8TXrRgBAsGy4T{$*?D!O_=t{#UO+%NL2I(h?8uF`UpXHbn(b7M&tXxOYMO zGx1y7nvI44XF%}wf}yH=cXKPGNKvEo;dj1Tp6vEk2xMQ>XH;31_aYn3DLB3ztN$l> zHdVliIWYoYnKP z%)l&<8~68CAqxk4f*DV~K2EMP9@@uOe4!9md<|fT{o%q?&XYbl-tv6dqR*2Lu69Se zg{U94U1j^&{oY5B6nw#td?o7iLn*|^0%7?Z0@dSVN3&`d*?I4!4#$1CVsiaRGekSD zA7HWdPhN`wi;c6BrsN+7rg2|FbnP`axThCCSxHbOv9523kzAM;Yox?3nNrbHSIT&C z`rmUdET7x|^Yh4@TDH^s*Xe$|a12|VI@JJDPg!ZPEv@20fBY%kU^;TEH?FNKeeuJU zpDiEEeNJ;S!DukE0Iy~TncF<38Eq(D&z}HQQ+{Bplklnc&{W23O1^=(1=qfq1&w9@VwG6AJKCYdIQ0@mw}LHRlJoIV1DYA(4Gu;0$1qwH;kXqo?Mg3)n^_nnXAIJ>3H^@I^3Ymv__V&= zVaK?kW`s9Xl8GEgqwbbIXKCqfBdps~h5_rin$OtP#RZ^oTjQwwD>Z!5?j)_Cf|kZQ zNAe-w8Gmbew};(6*IA2g>@FH(@lN1RzsdO4()|Qhr=QaYCxuOI0BO&<8+L-3i-d$mdTFYgbvvIymbB3Mycf z)yYQwQ`=_c;Koxo%j`~_k=1h9Vln0P(@vfD7cFJDGj>lN_o3_b3oYa(GT#Tmn=(+9 zBc0=U*?D$$+Lr_{&!R}$3+Sc z7~RLCt2a64#$` z*ppvW!xLppO2Oj$+6x2`y$vC3ym1MReClXl##|-tSb+4fX7k7FQtuiTRkw%Q!z+31 zrngPb_9c(BGsiceMdQxnFt{SU#i)^v*WxP%OUD5NV$gw2^*%fB&Yrl>edm7+G0$;m9^%af;HQHuLE6F5j(OsmMiq%k=GRhqXL-YCpNc{;f33W(WY*C4Yc#ik~cO z9Ins&(@yW8A&}m|cC4Uz^n6CTW0*Nke!VUf#4aHAH8F9cu*DAuL>y3>S&+rt$qT&z z<6G$SWhfLdQJHo>a9N$i5I#}%a#5;0M+!fp-`@PDrY^Aurkr<%I_5Bm7pK0jEC8-> z9|ahy`7_7b{&dDaXd-lH%9W;^P*>H%gqXkVq)$fCobwK8`O+d|C~(0!#Iba$0AuU9 z_I@pZ86XOo7BeZPx+|Pfabf^?sM%oW4P`TPSzV~NJ$B>K!=r##K?7*vHmrW4DbdoF z?P0(-z!nP&gWsONL2u$yrv`z6*BR*Xk0@+8rcPD}&X~!ep0NXvbinM<=48)X-!V9a zpoccdz|Z4Xz=h1HQ1Nzgf~A%{r_?%R2))RY0CzK00=%q8(h#8B;ESlqBZS{hd%@d1 zvwhnDK=j!$c|z~Gk-0VStZ7R*fW>eYcIt7c{YA~YCj@mw(9$X;r4USsVyxlJZhs1q zk`}<9LnZuhD<2H9-z-c%BOu>!D}QlmmJRxTH0$JUbE0{1Ta2?gxW&IRshQR1?O%ci z-z6*&@eAuxjrj&ZP&NKaB-hc)y!~yyH+m-LvfAfLWCxy_&a&vYM4RZQ$PnrIQDmGI z1d_l9g1@)f#<2u#;LnUFNAtA;s-#_!~7bc%{*mrUxgdelsj#f|KtY>UW87bhn6?PpJaaO&mnXdSD<7f zBt;CzHzZWOYy|)uHR1zl!$kCCgs5JBFTTX%vC^4!^jU*EI}}amPxIIMy**Qi444o0=bnG4YV|nP$8q~dJ z4?UG&sh=x*(?`kP_vql#P|6~r!uLzyow4Iiv6E<86LAC*2Jn9ngRyO_V93s3O9#>g z69b$Hm%d*}u6Je6^SU~g;*8a|AqBU;eu*Vb;1EZoA!o7*KogLwS+`pHBA5+xE~b-H z&sKtShZptc~{B^ZV~!}s{fj6RN^77d2&AGyGAMW@}o z41)h0sC%)@9HSn%iuBMTOa&6++ppBcwN71oBPSiK)NxR36TP8>H$>141TnD?CY%3H z2k3g`0GQK!K;vf$`b_LG=kRRiMLYFjyTvGDCGhN6G-_TrF>%52MNTL3wYT~ut_B^G zm;yByMw(f02AB`#Nwd{IM}Qzb*O>NbQRqn$4E>?w@4|s2cUOsSOIGlKoMeMlgg>Bk z%UmtlNHZ4U1V~nnjhp>oBbq5d&^=E6xPM@(rHSpahT7#3Sl^W%Lt3J6gBIF_Oa9IY zq84_ZONL0Mk{bwJ1$_>!YU>)<1jTRFyF!hlISqjC&Iu$J?nv%%7yzkC>iSRT1>}0& z$C6&51ic<}XS>pcUoUCiS0xKi|EC2I$kg6Wlut=0D%F31k$B}(%x}gplezvx&TLn@ zP|lE(`bArFKbf!qbv1~5@c-VcMdf`+4E_2xvrMj@c4}|1u!jVch|1yW;AJ3wqET~=8`VWH%kZcp- zPKiN~A_E(7l3uY8nBOg_|DD^70|Fj5-3oD{nH%XlYe4e*V=&NJzgT5l%h96sVnqj?wI{>(-^ICmlYOaagwn&o#Ew2+Rb zm-XDhXQ5x}rrw$t;&HtsS0}bP-ay{`l+O*{kyx_}NkkZy))Bg}HrR_DDCVSVbW2R| zL|ESj*>UmzCk(KcPar-+*<|?g(7fo8F0Ti!v ziW}5~CqQ+S9AI9$`k!vLmu1ZaSBB~I`jvPYQ(~tjQ)t8gQ><8Ph+L9(sdNn>Fn>yF z?cr+tY2L0c`eLAZmo&qn5?S{icdWmek$wF67bbqb2c&z(Iu$J&}JGp z6H01eVxI9bB}27wCRSe)Sc{V2KGQa0?78rKqiSx09tnI!?cI+NLZaB~mh0;7bWD)I~%3f%*w>08SzGk}xT8lOAd^BWQc#+x&=ls+vz9<8ZHD_W-wDS1>?;*5| z>UxNP2}$dN$}8$tjtM9sGmt9i&Z>uMjeD<1woJk)P%p4)FfgsfQM!s~A3kvRLmOG9 zk%hh#{EDpJTySzwB$ahwE@>l$LoN8cD<}}-QHobBxd%j%_2SJ1G)Atrj69=fM7pkO++o)G*URUqaA2wH(e za*ft{L%3nZg-|BnaD)o-bE)GLVbq;e11*~++uvnBWU`MYZm|(v#)021n0f%u98t4m zvjgmiUsL(g&dRV@92LyuA*qztOoYg$_ihRF8%|i6;-KfGNWOSxuSbj~@uOtQ{9I+g zl=x*c1ra$2pAFk|J`No^UZ@>jVK@<&Vdbeozc=+Vcm1DHf1~9v*R=}7Ps$Ww8J7r( zS7=Vn7<2jwr=a9Pec%HpN+?yn-R{{if!!}7-OU|(!db9SO6e#6Lmor=3*R}|=bYQ_ z2Iz{an&X^QYS==0JaHpB04tIcAss?6&I8TYD*~D~N@yCouLaq3g5yd8ok7_u4ur)obIs9RbxPQ5imOvIZ1nMn3k^+Ly-1i@-fY^fP*oJ(ZntK= zpeq`E$r-I%GcCvt@R}dtlj)u2tdHZO;nlhH*$oqBiyeNe9MPWl)udH$Xc>LM^L^(< zxWyVYQ&EM#?M=yZRQ)yCWnWUj@O|?ABkNh}=Gjbh{I(1rsViyf#e_Jke0;Tva&je< z3HvcTq=iE9*YG1JyqbS8)-F<>cje(ll$VBC%q*w7`T9OCsuq1`DU~34e#m(jCjxyg zn5!!XkpKP<4UC37&fByAmd(V6h8BX5>7)-edq6Ep{;HNi)8hmv)f~|mebH|LLmRI? z1K`%59c3?`Rp2iM`15hH9)RqbUr-Hq;1gIGKSN2SQ{XibQXSksX&qMkT$JEj&j#<@ zwoRwGrxm~|?eJU(2XWU}18aajv#&2e1{O_`s(C`u^@@3m$+-SHNHOS%z(&pgEn|F9 zJLFd*Q|^686PE!wR53Sj2QV?I;LvGMX1XDrtti$EQG9=klEV8U+H%6CHt{S^H^%A% zXh4t`uxm0R=`3Zg9Z^Z7Q@+~`I})2l2N`KnB8y=?Y`+FrfnWe*1f_wmH!k-HQQ@$v z-fTOdm&xelDfAX9^O)H>bw0D;PkrnX0f9qKWgpc~0reh1>C`unr&@wFkQD>KG=D=@Lh;l; zf^~G}y_xDyngQhijhi5Lpp#ugT7vvvB~R_dEV-er z!qg*6gDhlFz}}o zNIo7s91(_9qnVPM*U_PmAEz&Ev4)_?S$_&cxvmzXfYrno*hd46+;{^|Wh@CCcFQm3b8VyHzJATLW) zZHt^WlYNnL+iP#Lf*}rKD~m`6=mExq9Ee~AizKLI5Wfu zpl{&NLYGo00L+FS^%>w=MmI&fg;eK8%gzZm4~AKp%qu6LQ1bZJ#dYpJWH{B<0|2Jn zh`STCE?hdoYPFv0TP9Z}+AZ`%8N7PCrud(G^;9nbma?I3JOzO;oUE&4it)%f##i-1^7a8 z?}4e-BS1aJ=U-%|H5!ew3UGj|`E3*PQ8M!sp~}e%SC{`2o1laIeE7-Fj$N~;v3LzT zxu%o#7a&R#q*8OS7Ig&8v3CN~$Pg7>k?fskFdCG)UvPK~Lx6@3YYz#CgwHP57)arN zwh4F@KfJ(pT{48o8j>DAj{K&T24`j%neF`U)&!6-uDOZqPrD1Mt*v%BZ1yj$tYQ=- z0}fi}6>71g5|^5jNEQ7V;}C{?E?da>`k=44ERY9VCSio9I?L{9gi}<28-s(EY%m9Q zUe*5ss=n0Ml@iie-T{HCprkZ!>3F0g&xEylE?~h{tjq%Vn~w^aqX`6Xlb8SFWT>j- z*Z-fxx0|cpSKuf_o&2rel`Jj5e>C3tf@ix1ew_;t4(MAT@_Uo33IUQ$;wl!Rsc)ay zQ0&imovn*i96Zo(-2&RzR3Jp3GagI7_MubOy_Z!-OAmMcD53)BlL+;+Z_nyKISf;z zy_7TeZZaJ{$98sF{;;3GXAs86r<6#N3(7qb!(SN7FIY=LxWHc=;Zeu`^r;K;Yw@QK zl=+f(1u1o3G4kyv_)@G9-EsmK5F&r+;3w3ez1^d>n;JVVvjYwzP2WtYDr+ z9!zl&+fPYPxyyWbUQyxj7FVY(!G7mYzy$#YR!!Z#2BDk$DkW5k(q8mIX{r38QR?Hj zsb3La1@x8L52tfQbTk$*k(00h73M%6L}K&&xJ0Q&HjyIMB~Z^^r|iU+asIuvrWod{ zb4gzrj0Wb~{=^iaxJdcSG5Gw}wcG?(d2i7oz0-*%j5Xb6@!OaN!z8Ux0#0q9B3yiR zw&W7n{)yMw_#XF|@7U-q^c|nuv@&Mp zD12baG5?yp`KHw~`yrBU8UZJEE7GV zlCTC^^FYB?ET3yjS;Z`z6oACD`vGGp=s+jX!W0eS zm}Z96`4x$`J!n~o`f^4<(-0$N!wS(hJ2G3C*5+Vdkm=wO=OWf);>cAL2)8U0b8`^p z{>;?W%xKbxoV>)S?KaHAbbKk=Cxd$_BvR2v{{m=&a>78OHLIiOu87y5oUxqV*)ul_!OveN-p0zm5JOpI+{vWAM2(!d50{-LX+MA5n> z^&uFc;l#*&`PdbwpkOB%^%@o-ceIsViyxJtbtHi5De1Uqq^rV{yke8dsKRZEaAr@1 z{Aet9sT7U6`Nl^S*u)xF_nHZC#makfD5!ljd~B3K3Lok~7=efzGjAy-{BiH8&h)rd zzPw&6O%HzA$18<}pQT{M8)xKG>?4*eP^T_?36gVcVq1}F1&T6B6LUk7UKzYpOzDj` zJ^?HKuPi?`m&-^sdICeY;csP%zo|BZ;P2UzCWyZpDyGNjmmvJ+3oc)~^_=s6W7a`6 zD!+$>Er#KXa4XC)z)CN~QLpHhT_9*zw39*)hme`XHT+#G_;%Zf!tO*sf8RxoI%#@< z_M{#i%ZALMa*O8W8`r6y4Ht&{`BOba&|b4f#17E7>x}CO1AAIDrC!IUAxyxcXrItD zh$aZ9idYAu{GISqE_MGVrpA|H2?(*>3^LJ8ei+xE_8bos8w<&S+cU&9Q48M=&ZDGz zvhamqt)HH(26nqp-D@%8S*kI@$I_C8F)Sg&i38oMOwI6NF zu|@I6LL;JzWV)=y!T{>;Xm4-gP2+ETz(&EQ9teu;5ToJ^?$2@OdjQI%ed)1NB6a=R z+uY6!uuq8gI^K(+^XyV30d2>#)jPoi><~TyC_j`Wy@?z)uC-{$r*lkd7e4<^ z$8Ey&QIHbz6iJmxQ}fF%5!VwPS<&hHC|2`A_Gj$P*l;|OUf685X`&Ez2kqwWWH7~> z^w;?uk|;pWW3AUU!-EEIY^V75jgq37C6B?M)21J%-8!Gwi6>ysC$vWCYVuBdX6-uFVGo!U8IoZ~Q*j4)u%?)F*+lau zo-H1wb$|WMmeT&_7A#^C6CzZhA!LI`a_aL4l%x3+)@G?1<~~WiOAUNwUoyVrS=LMg zjwOncHw|7{koXd*y;!`4`?l!i9wVkGj=U+dkeiTb2fpCr{lL7$jQj0UPh;WJRlr`( zne@O0&XNruy18~2S*j};eQesSr%iJzDa zirO^Ba+7KRjs%xGPnI+pCYhAQeZLPp_FVXFyoi=p)xyo^O>9$h&bH5G%2px7s?c88 zKG2}5-&{5d_R6dLgGj&`he|1>Wl2UrhiQpwcbTV>ZK@UXw;^4uLiX9J2|lq`VCGmU z<=ZL^&JFQ8YrNhiXGq4PwcsQ>d>DqVnXjM!oIj~+gEPpG{j@(`PyuRp8LI$v?Y%E-(Eg&vD3Sgxx|R<#)g;ry_6)V};p^BsKJg&S;0>~m(a~KGUkAc; zuO3aHeRnb9$v%h0GWR6wwcsa$MM0EJt!{g|=rIgjxQ5-#BkZQaZyCSYGy**Q+Wo6e z@afWSBO?ZKe+{wF3&r(|>c`qHy8bK>V5O+`LC0^+H!u29KIYHcr83HG+(xW{qaC(z zp7-iWX6UNmte<^XwI%?WWW@=k*bqRqxv%sQ!J<98T}L6dpI$5(oqH@$xAn9v*AOw2 zbtWJxHmSA6_0k2uI;8{b|@v z5S$-|72u?+6t4Z_g7z|K6#sU+92wT-aphP}aKETr1-i*vNwN|}hS@n+AQ037hfrsB ztkYaNtq0cod_tc(L5b999XV&|oH7pdC;w!V%4-(Ogr(Z6!=e$~^xnd_+tt2XOC0*D%Z? zCBHK&f#>n77r%~xPXMR>Cm`nLV>Ds9eF}9yMHk(-)mIDewZ5#3oT4~OQ6)`)I>s40 zZb!Zj!p4`LP{xdSt8%3a1*c-SoqiiNaceG?(u{hNWZ`YZA4T{d({Oj5I9Q}F6E%c6 zXG{WJ`erRy|7IS)gH(?sM3EcH{qV}`Oc^;Kv<(C>jF3oX6TQgo4pa`$8+4|8Q@B`S zH*+&`i@$tz!j)IZ`9+-3sQiPqMOjbB0CfcV;=W(yhgKtZ5tCWelu9!2kLeD^EJbrL zmL|GCoD%okF*#{eCA94L5E)xgeujs+PLALdWP#uB*_YBK)|D1c&q)E*sb(Fm^cNW9 zyLRuK%%_l0g6A{!tDDWWW+>dQUL$W&CwJ2o6=NUy>Q@?P+~Ru1vJNxyPtD3 zzgp2a87zkAOH;@1!=G+NE(ihooliONj-tmbMM<${e0HDWhw2u>IZ3$3Cu3?oKuP*a zamt1EIG>LSbIhgjywPs;M1ZNLV;e~Hsh^OnavpAU#Gr+)k$Fq{(8n^n8MzT1d5gL} z$mI`&odFsxLU7H+4}Fy@+_m8@d7%eVoZopJj9>Wig|gz+77KgjorE@cxK&UgbeA`0 zsKm@8yXz1Iii4WQc(ciZHpm4mqW42|(lK-lB(rPb~|wp-R5Y6xFsEM5FtX`jV*m{reXJ%UqZ| zt2UV>M_lrfZ5W{4@B>W3`?Eho=ZabvGv@>Tu}kX_0N$Dq{q5Mkrc|E+%3F)hV!izK zCk2)G^PDfLkqh6|-YD-mgojO~9O^B&+f$V(o#GH1D*ua0T`0IWo08Te?yB5OD26Ab zO{H51~3;-&!Y){lJH@`=l)P^@L3o=fxT z3lONzpqb+MyJlq`i9^Ygo!_2j7V1S~7>hK5^Ol^rVJ0HHfuhoZGnjbgt09=c{A&&6 z+R*6Ijhf>P6mECCCE@Q+Gptj^nvwtbOv@99k*g~*s=GM8VXYB=19kBumoW=@ay`iQ z4#po7l$R(45zDPd;(i+%DG(YX1nPi0hE;<90fp@2KnmpsXvw4gyKs6RPn#Zc1*#Biln7Zh%Z$cYd_sV(|( zUkf%FxSgC9G|43IecHQ5%fs2AiZ-u*#d|N++|r4GEU?Ya4?vaS=%k;Nwv*j4@kb%x z<3^on9%dvmY4IY5K3&(UHKOrbFeFb9qLF{_!`ne&$pQyDu-e>B0&P8bYc1W2zj*N% z#tbUCCW{LNih4wy>ef7cWf6aSel`J6+K_3YWVt%BUvw;Np->Hhee?<> zf0|oonec|tR}GwdN-Ew2eOr2Lf9v&=>QL*)`XLL;s8c(OyRgD)o~^L#mml=ztB zw_u3lAZ@b9@xyc6hg}BC%-yH$iq;eF(~8wty1HcPcH-pJb>>Al8*MH&eonAsdiO&R z&2RjuRitODGt>xr<;NV+J`H;Vi}NVjE5GiJ^KcMqMgjklo5>k4qBs$Q+j1=3#^Pq% zbkz&5G}!g70ruVXxy|b`^|Jc3rKQDt?cVojaX%&BbaynZQHb*4$PdzAboiLvhTvf1qPm;@_2hO(Q-!apZDjlQ|z~C zyY=Z&lE*6a?l@d_MtmuI_Co;0*Y*<;2m~s*92Xb2%%V@vw41963c(=UxhB$Y=M!l$ zf6e&IGI+N8WW_zyhy2K5k$ByWV@dJ2CRuHsePD3!gqLBKFzysSYqcTfa~G@NibuA{ zoOZS`>X}UzB})qJ9p&9pdYBbtssIsN^VCfPU(WgdwQuam z#FKp(FM?6N`G^C$9!mgYhGcy8-?a$il9!)#8JBa2Ml3*+&Bt;+Tyt1JIyI@&i_?Lo^ECwIwj( z_ZJ!RkyP=empc$lR?Kmc6DV7ibaVB^T|KwxT5oh-ri?PSeIL-Js;mFe`(OK2VD^&+ zy0dNqTornUsVoRYFbO^tme1rQIoB1Z^g%g0m16SZ8mIjUO+A$R~W`y0sf3s)iND2EuX(a;X9cn+$zwNuQlID?gaIUF=luoM&cB zy<8Fac3<1@X-VkkF(!jg_%@@ihp(TUiQXAiC10D~L$9>jF$DSuI|u!kfT!>O>ePUF zD+L>7H2u1ZbBZn$_TN*fF#cWyTYwz#9QRt>3wI8QkogvF?hO*q%-tPdDut&a}eC?{HO1-wUIiVHh^+{A3w{lgfdG^ zro|hnx^pRjTtj%~ZAkfEK&q*PRK_}jWi4?IBct7JOY12C3PJPlT3L_+j6hRR%k23xM!ar66sBrb5Y_ql9bnqPIY^zy#{w*sd3UT~-Cl(QT-IPmi~{KtBE-Ztu^mix|x zU2(}CO2}@b2I`1S#!jxcVpvP5u2;pr5`3f6XjJpW&E8E`1m_OEy;sNC8#i_L^9^86 z@Ka;yy-eparCX!iNw!qWW&QwW&c3{BSZ+UO>Z_++Md__C(=qgMe{MWgH7+R{@M!dF z&a_24x##>OoaNwQFRX17Ff2^j+9`PNoUv!W=xY#vfA4#IdPIUC@hq>0xRhr*Ss?#ChuyFelL= zz+S3js0J``&^W^G*cVXK_W=sD@o{|GHZi5u?@qag^y>+^W1)e^LUm=0|CSfu*|rZ( z&g(~a9JLk=v_K`?Yr@GzluqY}g+^_em=&8gRY&_icRv z#4=tqR&(X*@3XKgL175lC5b%r^|-0c94iuTJk?a%<`VS!e%yVK_DaAD5TyOKeABeaiy`IzoC4j9?H{s2v(MUiG z8LDLf=7RxdKAstw9ccaNTY-diIjcd~cYbO2*W{Sd>3f7Yaz;NeeUmMeQ&^?srw^nZ zzHR@Zf?-noM0b7bhmRO0+lg;7yNCU-9+gZ)=tmeow>{yKr&F3NYFrMx$YhaafE@Aw zf+qpcxL-i{%AF{4Ga)Wnbew?pen_7=9qc?_)ZL$Pda*rb=Y^5a0Kew2DQmR&9jgMH zNy-otbF$T*5?b9=7_Gi8kX;9Gqg(&yF_&MJGfcW>+M!g$bJ_xoK2l;H{~tdx z#`P#uq=250#7p31Q5XkVF%JHF%c=M-ps&9vMc%9Pd~BDvNdI5yn(T54p3v$h{}&(p zEj8u8;itfVzRIWm{cUzOjZ*OdH)0j~L&+id?!(T0Bw?^JY3JB&g%T}Bdju;+l_W+bj31&2ebZ>G5v7Iw(kmGX#rwsO#jLMSADIXfKngv9wAWY| z312WxoQYQbatO>CQ*IhN@)ICw7Kg>kb)R0BZg_#h5B~zN`NA)}hp2|slc37ZbmC*= z-$LayCUoZxDX9scvA#@e#Jf9j147p`)G9)4Mh;-ckPNL(}Z`*DS&&JJbiq}&(TiO(ptI_j2#mK4xTy0I_i4dN(qc@4^8pCiQ)A|_VAI_3R4>Yt{{ zCn)j+7+I-NjMt>8?4UIJJjr8OW{Bk?H~Ks!s?-}O+B~vH5J}2_DvY|KJ}l+kc?(1E ztC3=5EAWJudm>*0B2I2iksU1r$-o8q6}?q;{tCJBUaFO(?dweG$4Zg6is^5#FAad` zA^owmcugkoQ_F3UBYrKAS>kU==>M9gyac2NcClTvItJdt;nARER@nmYJIf@1f6EDF zb?_FU1TNPiGj!;bK?X#I5HumE5vWlq@Bi!Tt-|7JqHR%vyA#}kYanRQ;O;aK+}+*X z8clGA;I6?XIKdiscemgYau@$T`<%DS1Mor9tXj2Z%~4~Hn!`Hrsk;9Yq0QKVp9mf` zRL0;+12&eS@e`LnyI*TKTyhca!17OnpCB#(7*>~W8+2(IvEe+RYzN;c-`SzAq>JEE zTkGISaK77chXWhJ3i+8t6i0GN;j}FpDz3?r8pzK{;jBQZGKAm%tcvMF%NY(}9P%nT z#3q%E#GtaKR^-@`Aoq__(o+k?vzGu&Z1V)Y(r+KS03*4-cyiXF5f4JOr12cYbjwk? zr_CP*G`u#$y#4jaO9!v+kR8uxWc*5Cs$r|;G@U_}AP;-IjmItOm81()#eZp@@H@eI zE~t`q8Va%{ttbSHX;Zj$?I94@Np(An33Rk6I^x$!Q4m9f$J6C zr5KmMD_N&tFI%xn%rWkQDt6n7V93|ZNqN9%N@p9Zo%>KA1T=+91Et=xr=KDGSmT7} z=mJb5V$srZ1XRILR4KU639zpSG-lz`A|n@@HOxZp2&#iMx$6Lvc_M5+-rg7-tgL3&Qg2{q)o>V zscW(k!dX`PnZqdDM8Py#UgE__Kyl`7$q6Q6bMZ@i}36zsn7 zTs$AXW#_gtwgKU#?FAI}SJ#u*9)Gl-$)Y6HrQL}Fuv;`Or-yXZlFLLL4|4YKQ5K_? z4Fg*)Rp3xCMD0Aks(i_Q)#zLAgS3F{FGM~yO`^UgYe`WY0WCgj+$x|d@!2D;!LW@3 zzSRD^WFh0{IYR+QR)#q24hF4rLIdR}Q{Vc(REJsFU>YvDZS;_n9iw)3V2brr@Mxe0 zQFl_@Rvt>dm`knZk5Edq$ySW-6{Qe#1TmyN43bI>s-xV_NElncV=JDIzukDIH0W8a zD8yR5LF~;A1!5UiKv)6;(B2UKs#JEqL(HOl?jO;~`-(k8AvoJu&o)AF4YlERQ`B85 zE#I-*+W^D@KfADA}B#?ofrow5y>4gf_2~wfSqWj$bnN-Ej{2NuUe-eLE~=#8n6hw01P?#76+9tJI*gk zUphlPBJ!pM0FzMX0{e8yqUkJzS=$IOd{>?V<{6v6x6Otp1rQRmj9|=ko729*Tzlro`Z}J?m7Su7?aN= z3&p9iLT*ykCNs!WfW$Jqke#qz&KqfWbbGU?mj7XV>(iwG^!Q0q6R<0*AsX-$SKu2T zLKO`*3r_!eeeLX1=aS`2dzI1i1K_R98z$@#FH&$E4QfQlW^$N< zG~V?Eynq&9kn)51wsn7rwa)Ed^{ARP!2!TeYKNlXeHx}~q_YZ8m=05ml<_5g;CIwk zTlB|wtbAt!D7zY~h%5%h`UJ?LXgTYWiVcA*1GEOT9sC@5h3x}9@o1bbB32q)RP?IP zIbZJG;|8BP&}Y9iVXXF30{rBZlF_Q(*fnusEZ16ywGU5X6>Zpj&i&1az`1}rYrV`$ z!_pLQ2bHxr`#Nw9E8f_*X!_ww56g$^5D+$@#&~svXLeno&*vCz1$ z2u}S--5%U_+ik`df|K|Pb9brfa-0y1D~d^Xr%YPhmdRzCnN*v!1<277eDY56Hta-{ zLn}lV4AhnSQ^y}%O%{V+<&RwREu*o&rI+9-9BY7=rf95@T6|96Cl(9Z(d0>Fi;quu zv&(^T?Mf^50DdH4Kz)vJvkjAzM}1}Vos=sHUBqs~`t>5+A;|#sayd~9{N{jqRN{O2 zrV{9=dI<^Mw_#z}p>d6Cv(-nTpjONIynN1>?6is}#+T<@7-GzgX^dQBeJj|65Eo5j zxG{m!^(T^rR-r0;4hkQreE?J0M>dE0s_gZ04$(oeWQJvckQS|Dwraa}&i;w>PVznQ zwG~_LkQjTxaLf{QVwpT>hHw%H;Ca>%RbA1W~aZ0reCG%)VmP65JTt`^gS zf;EBNqM1{3BHi}vo#e7L<7<9D`qFm)nj6#Y&a5{p=Y#BT3pdUmKAoHfxjajNv2Yzp zky<5MSYCbtm7@e$D6>_4=6Fxeo5}5D!(LgLs)SO0b}>am6fq=rBR7cKb6UW)aAv-TGX$mqFgZ#^z7q4W z7eWV0_Lgm-R}(s`27l)mOwJ+)inzk^V$7F zZ1y)|z%0%xi8<`sq8WkRFfILdbqoCbuXcBx2Y_CKMhI4&A_wXm=O^fNyyj0^y-FPbpEuh- zv2w9@)-C&Ex>A?;NEiS`QKfo1Anzh{>1R&X7f1f33?v|)9lwc{OSQSbbHD3FbdCb! z)TSemQmIhwd?0^C@kDPK67~J%6#Vz|p>Ny{ZVI`v-*1GEg1ph#x3_=hv&YQ3S-L+m zZ6>09-%cy0UDS?=W%Xg=cXl-b#3F6y)I#v9-@@k_ks8w`-1hhcgeU@%Tg^m#Dw;qg znNx_T7`j~h?EA31)1TSUa84fyWn!=ULmmXwfzj=?v8gmm`;;&d&=FjC$=?l#1Z%SU zn>nV_y~i8nYBu~NHxBu(Vqt7;()gG8P+D<9HlO|-+kW$y{}ygIUTL43EO$lB+%I z`)r!qHbS>dx8{(*Aj`l_PyZ-qEh_*Q+P!t0wsC2F^7Y9otZ}r1htL#o?93(!<+2U! z+zUfzV&7Ctoc*!1LLuKTje1{d(b|kpA^Q<_Yd17c%JkxykIeCnho^%wccKCJ%|P%) zGFa{4cJn;I2*vK#(d*}ry6uOWPEmV6sl=4UVm(Vte$QHGNY5Ad>wK&$G>1~susyKp zo(mJ`aXM=?iME768vf?gqM@vYONR z)6u4=82}WQUG&Yk>Z!C}pr>NrMV5WNF?CUvkc)EsJ>7dsmN?cul77wcgZsMBWmo`U z$ObG8C-EX5ZS9WXRT@ueCrIna#_rw7Ule624f7s#{8%=fdRd7>Zw#QZ7zktDcoSPyq(A*OK9bGsmtC`K)4A?STiqk<8cYZxM+ zY3z}gJ#=g6QAq+|-sSg#map5+n>pwv^MZ+|<9RM_Ba5O)cS(oe)3<98wbU~wJvUFf z9ZZlKx31@a8PMuRl8d{ziUIcl;t*%$v7w8QuhESbK9QLUvqsD}Grr!h)X$oetx*a) zo<4gCg%CxN%>F;i+}U%Wf@=U-4{aV$r(w*Is;4TU4<3_O~VY zO6wEisjM+epo!Vun~afhgw6wL6Zs9F4U8LhR=$)th$r&BzcT43c+>p0^Bl?xE+QAL zsO9rye3*y-IoEXT8dI}%W%(1tG`7#AKj85zi=H241CC#O*-3V zg-Lv{RO|OA1Lo0Pb5TFLQR`oWV85zdT}QQq1($sNuO8M>x8v+lw>aqrS4iO(O(sU| zHwg$4AR!}XH<2}2Oo0QYuss0)WDi1aIYWs6ibnA5z#PKuh+4!SZfl|Phx%}#=a&5f zh&xj^N%96MpgX`7G&~NLHm#KG*;6+xBF3>WRGA$;aK z6+DH1$QkM?Y@LjK-FN%BXvrK0z&Tv{uncc-ptYN}r~lNFqy&Fm zySgF!D)|1Ln7pp#w*5wn$0YMYIu(#867(nhx?y`hE6jyu&R^{6%e<$7+E=PKkVtGp zYN_J>G4!WPzI1|#ppa=P9ukfHZ1TchLztCS4wTc6kZDI-7MIfzAA-3>Y!5O0-4A%5 zJthfBhZs;YQOkqTzuVLm(z-@oz?^wzE%8oiym^z3Eo!F#Fp^Ry%hMCkGZb${)1JrE z-XQez>|ptCdsDkvSD|g2i8P>f5eGH^X&G&Y@m{FRhyUY()!=6#k`|LzMR2-Ue+_>O z`7rNL%!;l^{yk71EG&-->;6g$0c);&41w&T$`1qM7)0F)cUvK_7>qxDe+2W`k(vF+ ziwifH^Ats3ZJ72MZh8$;0`{|be6MXl#Ae9>0@do;h99lCD9eU2Wk3l^6JM$7dm7 zXT5yVq2UGv&pme4eAcpidn{pibeQ6yK6jSm8Kd~WZ# zhSS7TLgS`bGy(Gi^H;fEIruH`DZo+i;56ak=?Km5WAp8zn*6{0( z$xU|>FO}Sh1fmybFMn9kTCt^Veh`3p~TX3|{baCUgWO!bpX>OgsVVT@2 zTSBhC^xSEZD}t1ulu)|37Nc>N?lXkZ+-iMV@6*fw+wAMYtwOylMH~XVZ8Fzt%qnBNPX=v<4(WhXRxby)TCX4tut<^pa6gAG9!XPU&zMNb3C$9vD)QX|{o;SjFn1dfELF^qPr zPyF(7*3Cb)U`cGY$Gqk=ngT*XKwklxOw`B4%vz8x?JChqCfiqO(fJj=Z_|teef9Pk z`x#0dkq3q1%@(+)zBKOF$3rVmmb3r3ei2fbEWr8b|1c1El? z^FDd-lu2_y0~~|;UEIY0a0=vppfQqvzVUj%QnWetvekwSZI68adVz(^N+2!|H5wb( zfN2eIS0`Ud^k4Wn`I0&O!E3aVIpck7a6MyR=G(+UYwvpX?k$*3PF zSi%`z)&TK7&N z{aYFJ7Y8+A4c?JK83WG{kbFjHCM+rhN-IfL$60*}*lj1?j<5HG+R7%ep^gez)UVXXUFWn%oG8@2jsG(CvUHhS-n@- zJ7|M)zKDqFSJaL*c~#1zZf~SF*LZnZ`L+;8%7C_;;tqxW*Zenz#}7NwBVx0%c({oV zP!0JfDX2gj`Y+DU(YpQ+0nS}~B<`F4Hu{&ivXA$Obc06{Wt~2mC$s3dN;LEei5z|C zp*;pcpr!pk`V=_fGE+8o6Fd2{D5j+Z_WZY!!(4lg!$CyO&{bpwa4cahk7FN>`fNQ zkUz+MdyAbT_k?cBu8FT#{x`>tvQl3G<_~~D?-h<|!7C;*RU=msb8eHv(ntg>o-7eV zPW8qzojS&hmonsWy;^iT2M@E{5?WixBEUk!AEE#q9?cllL62nzLX(8K6lENc*%OfG z#xu709pSnhn{-%limI;dfSKM|GHZnl>ZP2Zsy4BysDTF7u%oSU_-Yu8?cQejKipYN zQ77y;_#$J^=ibWH4p2eGv9p>Wrzqcy0wg~Q&16NT%Inzg!11SYqhPz$BPpMEW?YqA z(*K=(BbS_&&N3g27J9+W<PlRDBk>a`_Q7+1BqR6Hnp$Wf+zz?m@2B6p1o zO8ZZPpLRyf0Vj9)pxz-*95j^R&BI2ylINV?PrvyU%pI~M$g)8AGfa&|Z>BQ3Lb9$q z1i@G)dx4@XWZ_%B)>43*6B4*6;uU8b3}K>vC97$2aemf8C98W+${Zh0Y0ahxw+@wJ z$V>vD<(|c(6{oB}%7AQ`d0=DrDySITRBvCzDE80PBk-@giOb|dv!y6GtUrC}r_#6c zSKqvli_RDLC_2MZeXo!zcAJ~BRmv$sC&)+#3mz@g^v;1K;P5MW;`amdq|tWVEStR! z8)PK^K!fuK;-vMU(SAd7Zu*E*p`pB5nq}PvCzzINz_40e`Z68ZUvnPHx6aNuXTRSL z8brD~2sF9-s?Z<`q5_-fQm{9cEt3JXch`UVZp*~dPbRuexv?CGNp?WI?yHg>JXb>P z_fxr_L4>25j-g|AfYXV^6+=MDV3Y^_z8{M~iXskPXnA0NMd3wm@IBbhymF{TkgUmI z_fnIQ3BTFORU&GbOdcl-%@+2(5i@EmtqQsv|!}660%;AH)kp7$Z$EzFT!Ujm>Mg%`lzO;ce>OaTJLA#=9DWLmjtL2M($k3wU8C zYuX7xS?Scuyi?2gyhJRF!Y?`okmtz*KX*t+-JXnPn+Vu#OZNEi_l#R1#@{;ihk}$0 zvo_`qq7@}w@RNbf^=+Ruw}(b|bfcAUktgON3(KIH&mwP#_*Z-yC}3Y}Krxr*Qf>=vx zg5)?+983MS=Dg8!LxkU!HP%cAxm^DdoxorKa<=cjrf*x#^9*!|w6#3q`FCEz7XLAm zRn_ygI};>5nwG|uSaG5qe4vWg@uhA=8#vo(CDw}D5Y>toA(X4wuk!fHQ;)*j1{(rnFv#^h2q?B9bIvgP{c}nt63xy15606sJ|B3jU$@`vAao&<H1zsfO|?}6`NbQwlpJvpV3S!K_s8-1Z@ z?+&h>(xA?)Z*q^1#=D~nV^PGl6*9+V)W-Nk5KBvI56y~W2FSxDs01iPxuz(CSDv4E z%NM=Ln_W+k@mMLnnOo`q?UZdJd`HB9h9P^<`iw!zSq2hU?cFG#i>lX1?)wHac%2_C zoAx#6+SDe0f)(jFEAogtH0g}Y6FQ3%R$w2{Vl%ZXfque2L)4nr`-k>6`zf25yVf3vPqp<&>k!{ zpH1|-zE-Y1L|E(8fNIbj|9soy6NVL6CKEekY}(_C7Io!)iY?crM5l}uawY9p7Z=yk zkRReq&sg}_Q7cTX9 zr%(t<_@zm9c^0TtO{&rjhfQ4IA(JPf8s8i{^HWuDXOKhF5bIJV58aHTm$ByZT8DVo zp%uJHU=p=Zf2)0OFYJIgOY8YLzxL-0U9*`><}2A>+^G}2r0wm?a7HHBu6F_-SffYW zJKTttmuHUzv-Oj#u4=&88e1cQO8#1ri;OBWvQ;^3K?CKwXe98fJ5H^%{z%=U3zp+T z5q3m=6Yn=GeIasN7{_afxiY*rQl9LS6hnJdaauh0C4pCgA(*NyZsuH?w|6cKm!z8$ zA2>ZYe_vc<%}ApuDt~U#rDJ=yXBOrLec~FJcU!J-ww>qyJ4k9XFccP=*x0G|HK%9Z}Ro` zE-t2Se8ktYgOMgIgdB_UHSZ2YJ>;QKu`vRB=k(&_V?v&|87E8ZJ<(0&&HL^Nf!gUd zeW3q)v@VrAoLis#=)ULE;-|%leEAsSPuTBZ_f9y-cAlJb$3Bt1=J~_4WWZuD zei&iSyb}DEp<#X7a;1wYmopA~9>?o@68HG$!>Pl>z_B~x9vpQ57(8HetECibfpKg{ z?3WSXVNu}Ay1@QZsCxakBAMjF@(DWtrq~ z@R?Ihe1x09>5-_)Yp5@lJ{2>2Pryr5L`0C2gp<`Fa-YjPdZ$NtY!%xmk8U$DKA!hd zAX@P2vq7Hr7u^Tv5+#4ke_c)7ZcTnk9LC_tYoPa`h4|M!@74yFoQ|yfO`ye67s_uDhp8C?zW`r!W_HMVVV^e~< zrkCh>_I;n%o~SmXu{~gjGPB&eaki+=4u*5<>#B+>+*AWt5+zrfqIIgTb@O?OCZP0? zPu%b8>IiV?2UzFDwkdA;L?$vCuEIjZ#X#_ub_{L(pC<+*f~I!`m=bjX+!ZpP+zF z-K8^h9+1*4nDU>{C1GL0W#>xLP^H^=Tb@C;a+)WF9k2(JgFR-xmK}^A75+ ze+Y#QlwA1(s*XSb?$drAgt&B@5L{@FPgif-IsfS6YUI-V+D|@fhrLe&s>U(OMbr!x zmB)B6RqUoSIJz0;lan^BZj>wGtA!^>1x%qR08drY&3xa1l-~n3H_D--1m=hxh^&r& za?SpS<6eqwylrN!AkegYF$=@ZboJ`%UNg z_W_}vy?i&m0pe{kL;K+LEs&mXoMSjL{<|Tl8YrfLJ|%ugvc)wS(5E=5G==Ohk?hLk zU;&~Ou!t}%(f-`6Z?D+!MVF=2jL!oD1qDHGxV;Ni$|di+%+8u4iLJc6tF;+|Z-FIJCC z)0mU3J=l)JnzvZFljcQ458W4RiiArUx()J_4?TfKn@(PUQkW`DD}?P&DI=M{L$G0olSF8~-Ar(2hf(q-Na!9-b!MSG0mXgMt!@7ovzh zoa}zw4|RUm3EhJ9_pY2HYH)~i1SYcUZ;)2@qt<2pYd=24axZ8j+CHTwG7(RANv;x8Zx|w-qI3Jr z2TCOM+wSjI*P(jT1rcGokT{lwN2L5duVxsGJXesEmgW>taZ|BLRdfS9dc&B&^TXl` z?=-_CveBG1bNWoC__9^;erP7KU)3;#VwNihGwQndgb1WuJjgpStZWg3EBOrW;C!7s zcbqE^eby|fppeNBQi_1XNz^_tb*#C_N;oSK$e?3qpYwe3&J_EC!xg0Iv9Njr5zMq5gs-R91IqzG=pY`EM-tHO2qi(qR%6$x!R2ux z{20=2{vaA8 z;P4(75j2RTrK)$c2d37dWuy<)tA%2UZjcO4Ip=)~enhpg0a2}T#=_AQ_Wp#pCS5wd zWzq&NA8mtyOT0ey6u4!EDpZB+=%lat*mo(lq9vtjq3zXUDVz;y?^w5rVDn;%Nu_I| z$F9lI)fEmzAArD3Ws7UHb~7&U{ahL8-(PQB&}!J|k&Jh~xcE|aulOcr*Z~P5%wPDx6KJ7U?$kN}I?%NE#?E(8y(k!2SQLzr*?EoMAMuuLS%sxz`%PcK zJ&Cs(Y%R=Td7oODdB2GG5j^BsFeU=#1Ij;k*q<9=Z)t&sNuNS`KC9)2>>?QR?CF1Q zAw4Ot@2N8DA$8eX(;b*!tV#B6+#g>Xy=k$yDLjq)tivp!og?T^)IEQL zYpwm6--Rxl3R=9w6eUX?rDE;r_NsRa4Tu|VSkxuYRoOe~-gNB2Hy0Rr zzUKNRCD+_kcBud>;ia=F>5xXg+&E0Fb|nKAsnX-)(j9lp_id_)KPvmwT{j%4udH?G z1oYE?CFCLj9nyGgH@cquD!r65{DUa;dH@91xV!uyff`u5%`J@Y6p8b9Kx`9pfHDlw za<_x=9{T=beSF_I*R+*jAZPF+;zMB`$86^8+XC}@R9-3#?40zaQ!*7*5Z;Jyq`xH| zcBsvlQ8TfvYXRMrx5}mKg)7snxpJnDYm7Y53c0hJ4~tt|mwR=Jz9z2tbl}7-|3J_F z9jmek4z(NlCtVC@xlcf9rZR zgB?v`lBI(~F3i~Qt^2D6PsutZZcf`lSkhXQeunSe*M=u<2j^ax@AxHIE|5A0p$Efi zlhJ-i+fMN>?ycDg49~%H$wUhYy)@C8U1Saw>6<&_oUK%}t6yErEo zb8sZd{QXU7in71W*bM{!iQ>ahS-XL!@pk*l`tQvGhvufHyBPD8;Z^UGsuKP<4k~=J z1MS}&gY720!W{um)kCu0uZ8pT^OdX|I`SHoTI^j-P4lV8f`30Xc`L2mh~4wypp#z4 zW%6x)HXTWuT&WpfZgf(s-d^T@98)EHjZ}^YNXkjOMKuoRZ);U_H0LyZ~ww1{%P~sqY~n!x}7|1;XmtE zZe!lrXqAXV_8V01D`#VKl0uSfhfJ|{{sLE0uF%cn(wQyhAxyfq&UV57G#&xP3ffG| z{w1;%-5Sfxq2?|;k+e2J^?`0##3qIvYPGT)?&zJnmVx&|%9gxmNh;FCjk#`0WCtP% z&&W6((3>Ar{3X?8dmrpsk^ zCGc|EPq$FjOr06v8i5SP5_Td}wj%nj6bz ze28!wqri&P86B55bh_DqS4;h10?<4Eztzf*LrWgY+r~4au1%g)vZR1ekJv7 zDBF&h<)(~o7&(`8b-m^V3{>M9b3SSU+{)9Fx4z%)ToxH@P1ln(WP}@7GssT0jpWaZ ze6j|bQO?YVlM;HKGamxPPU_~Y)EF5*{P&-6M-2O>OjFM^flDeDQ1?~+ppv?5x|XYI zHjDE&t2|4-O)FW}gBiGPDKKPdxEi4kZASX0RkoAN)a4f~lS9jbs$Pv+BgQmKiR!Nv zQMnR@luG*|HFC9N{u?(NgbYyv`T64VnWL-))lTyRfkZn{7&^tmafE;j;psH)KU1^A zi|qi&pnKxqtiyjtDZo|G-hUFbD0$BLo}{O^5Mq0=puUIJT;;lvY4!Qb@`mPTzvcn@ zsn=Ks99kPHb8Y*ViS&+?VeS|(c{!E=&!^6d;oU~@3sRzxIh(|?s0)U7!$V|o`%uI4 zJ!S}H?1Q+9$w%XNmL?1mMfC<8OOpA-!M6Q|k`9H>JRm<3h1T>WBe%Z7 zPicn4l@&(<$_mYjX4*VwSr(E7l|Hhlo!|QZt)s&OS9>H~^4;Q7Dj)+c7kEZj=%T4` z=@VSzHZPQ1zV3!(7ZW78sX}Ato}NJg_VI~v;%lJs!#(3)<`qLB>`UM5{eB{tnHScB zJQ9+P7K9U(%=mq&=7NZFi-7qv3C9UoljhcM(?O_(f`Wc8BQB!uark^@ZsOUxSd%XB z*l-spLj&@YZ$3x$%bnv<8%vl|s%WNN80jhzFIJ^tuKzwJJ!dyTR0}){y5Ttu4cU{` zyC)(|_crBzpLIPRAG9RvW95^cJ#?(G1<@d;V}AK<9MeyhZhfX7mRdQw(9Qnjaevh# z9rs#3Zj_N)qNNG1cnPVY^WKnd3mhcxFB3{sBuw{(03mW7bMuk|xh+blL0DR?Df1Uz zwHel*DD-2?co@BEXZh)R@4`?Xs_sIk z!^L_h$KCmw&Y|)jMUamRsOh9F^ZEI??!?6?Qu>G3?=mg^ef)O!Ge%eXB5S!HFl@k^ w=CD^R{NI87-z)#$CE|Za{C|Fd+xidTbyAH>9CLyK3iyzbP!z8gH4Og$0Jm*32mk;8 literal 0 HcmV?d00001 diff --git a/doc/html/_me_infrared_receiver_8h.html b/doc/html/_me_infrared_receiver_8h.html new file mode 100644 index 00000000..558d9ea2 --- /dev/null +++ b/doc/html/_me_infrared_receiver_8h.html @@ -0,0 +1,334 @@ + + + + + + + +MakeBlock Drive Updated: src/MeInfraredReceiver.h File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
MeInfraredReceiver.h File Reference
+
+
+ +

Header for for MeInfraredReceiver.cpp module. +More...

+
#include <stdint.h>
+#include <stdbool.h>
+#include <Arduino.h>
+#include "MeConfig.h"
+#include "MeSerial.h"
+#include "MePort.h"
+
+Include dependency graph for MeInfraredReceiver.h:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+This graph shows which files directly or indirectly include this file:
+
+
+ + + + + + + + + + + + + + + + + + + +
+
+

Go to the source code of this file.

+ + + + + +

+Classes

class  MeInfraredReceiver
 Driver for Me Infrared Receiver device. More...
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Macros

+#define IR_BUTTON_POWER   (0x45)
 
+#define IR_BUTTON_A   (0x45)
 
+#define IR_BUTTON_B   (0x46)
 
+#define IR_BUTTON_MENU   (0x47)
 
+#define IR_BUTTON_C   (0x47)
 
+#define IR_BUTTON_TEST   (0x44)
 
+#define IR_BUTTON_D   (0x44)
 
+#define IR_BUTTON_PLUS   (0x40)
 
+#define IR_BUTTON_UP   (0x40)
 
+#define IR_BUTTON_RETURN   (0x43)
 
+#define IR_BUTTON_E   (0x43)
 
+#define IR_BUTTON_PREVIOUS   (0x07)
 
+#define IR_BUTTON_LEFT   (0x07)
 
+#define IR_BUTTON_PLAY   (0x15)
 
+#define IR_BUTTON_SETTING   (0x15)
 
+#define IR_BUTTON_NEXT   (0x09)
 
+#define IR_BUTTON_RIGHT   (0x09)
 
+#define IR_BUTTON_MINUS   (0x19)
 
+#define IR_BUTTON_DOWN   (0x19)
 
+#define IR_BUTTON_CLR   (0x0D)
 
+#define IR_BUTTON_F   (0x0D)
 
+#define IR_BUTTON_0   (0x16)
 
+#define IR_BUTTON_1   (0x0C)
 
+#define IR_BUTTON_2   (0x18)
 
+#define IR_BUTTON_3   (0x5E)
 
+#define IR_BUTTON_4   (0x08)
 
+#define IR_BUTTON_5   (0x1C)
 
+#define IR_BUTTON_6   (0x5A)
 
+#define IR_BUTTON_7   (0x42)
 
+#define IR_BUTTON_8   (0x52)
 
+#define IR_BUTTON_9   (0x4A)
 
+

Detailed Description

+

Header for for MeInfraredReceiver.cpp module.

+
Author
MakeBlock
+
Version
V1.0.1
+
Date
2017/04/06
+
Description
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+

Description: this file is a drive for Me Infrared Receiver, It supports Infrared Receiver V2.0 and V3.0 device provided by the MakeBlock company.

+
Method List:
+
    +
  1. void MeInfraredReceiver::begin(void)
  2. +
  3. int16_t MeInfraredReceiver::read(void)
  4. +
  5. bool MeInfraredReceiver::buttonState(void)
  6. +
  7. uint8_t MeInfraredReceiver::getCode(void)
  8. +
  9. void MeInfraredReceiver::loop(void)
  10. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan         2015/09/09     1.0.0            Rebuild the old lib.
+Mark Yan         2017/04/06     1.0.1            Filter out the 0 value of infrared remote.
+
+
+
+ + + + diff --git a/doc/html/_me_infrared_receiver_8h.js b/doc/html/_me_infrared_receiver_8h.js new file mode 100644 index 00000000..c14153fc --- /dev/null +++ b/doc/html/_me_infrared_receiver_8h.js @@ -0,0 +1,4 @@ +var _me_infrared_receiver_8h = +[ + [ "MeInfraredReceiver", "class_me_infrared_receiver.html", "class_me_infrared_receiver" ] +]; \ No newline at end of file diff --git a/doc/html/_me_infrared_receiver_8h__dep__incl.map b/doc/html/_me_infrared_receiver_8h__dep__incl.map new file mode 100644 index 00000000..3ce8d0c7 --- /dev/null +++ b/doc/html/_me_infrared_receiver_8h__dep__incl.map @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_infrared_receiver_8h__dep__incl.md5 b/doc/html/_me_infrared_receiver_8h__dep__incl.md5 new file mode 100644 index 00000000..ca31354d --- /dev/null +++ b/doc/html/_me_infrared_receiver_8h__dep__incl.md5 @@ -0,0 +1 @@ +4d478abcf3879992919f6d7ae07a5286 \ No newline at end of file diff --git a/doc/html/_me_infrared_receiver_8h__dep__incl.png b/doc/html/_me_infrared_receiver_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..84a2c8e33f9809b04c058769fb02d6b0b204808e GIT binary patch literal 14338 zcma)j1yoe;+by9WEg>DEgdiQ#pwcZ3(k&p}4N3?M-7s{wFw!Z=00KjIGr-W@2;76e z-}l}BUH7hU-NRZlFy|c38_%=fz4!A@*aszP987XdBqSspSs4jcB&0{F!0!%E(16!g zSdJ6$hGrr!ErE3Z@RQwI6pw`T97$H8 zzV9UdKMs~{B;YDDYwcFAGf4|K#c{`P`HeTXJ5yClG_I5{Uc5-mW&ZaP4v5Xb?wm>w zZQP1)M`7{Tr}+3KL~>kV-@f(cmsV6n3O>U3^76{X1)iI~`bY)+IdJ#iV_jL60sr44 zm4iO@znW#%nP5in@8_`?YH_mvb%H_R|GL5Kw|2AJ9>#rCtzP9^zw68qiA{BHJi>IGDzv#RUT$%YP7q;BeCh8%Od zmYrtKJ*X+HJWSe#e1D`!N=VRok+U%Zx6|8rj9UJ6o>Zz|bTRKf8MvsyK~r)Lf?Yg;1fOvJ??}X!BmN zNgtwG&%pA`8kiC$`+r7>-bT1p(V$xo_NTZEeSMz73C!eQj<(h!WbLCURu~E=YVY@(=-Z zj5c-G8eycORcTrE1~x~<@P|l<9nGbS2imzt$5UAw!@e&9Eh}sO^KDm>(_S0VyL70lZz0H{W*_35kl7%;HfXT z8vh1cEcg*E`n>8HB^7F^8eaFj2P@1RjV7Y|Nm}zCPj^2vXsgA1vmY7W*eHR{?u+2z zAA{^12={?T%m(O6L7kVk`?w=8g$bB{r-P2sZkNUtIgbJEZ}}M7Ou4v&JGelJx#Y3K zXDW7Izlz4B`kYnlbmr)hR;qI%nLS$Nd5rVCgHcB$xpNz}D;Q{2fyCcX@7w;m;J5uF zz|;5()?fn%b|W3>eanxpxVC{u?&rN3TE=P9nsUnh;s$#|&Q>Vaj*BKx*Q1ySoPkJW zFf$0LBd+zbFm=oxy8lg_1egn^ziFxPPSO2Jp~}K8k&_R*Vc57*fCQNY#W^s-VZ#Fj zo5O=w=G;sUsal0^KLEe!D5c9Cr9q76TG~)HpPxWe(*Nvpl*XXo-GS9@JDS%M687dF zjou5&ghM9`*}tFLq2X$5^qt{Y_r_817UQmL$@(w@-Jw^mCj`=hSpm+F#d(4aV}!j} zM)`WOpc6#zkIwe|%6^s;{I!D?1$T894R?j|N5Ddk8mB}jP};SVScy=S#S0dEsMR@r+)d}uv8~!(US6iOkuQ>GP&N;{zFR4@Lj^+ zxb8LmkSQ;n1z6VOw~qLIrqi1+GE2fqu$Pa(3BR2Nc=p0JO2iFs|E}#&WQY1ZX6R!_ z1uh0W$T%zSfG^*!3v*60fsr0Sf{^ie0EzNJYcX$|NK>4JTjS-PlTmi^e}iNgW8~xT zIXscSm?QlPL8p-8YFr^+C1pqPk2b~4Qub95I}&{PO%Z;2bvl%~(}N8fUv75bu&ZkG z7{{aW895jIK7}j%$EU4I*<`&aY3|32xK1z!{(I7oJ`Teo)N$W>WKVlo6@swaMwMSs zdzo<9h28NRzgU~{9hzB0&l+^Uzxpn4q6A+Tuk!HWV3}2d>G4D??TV`Y*elBLo%!6p zjDt`S$-`t3Xelpccv8WPW)w)KF;*7MPLpmR9`hNUdR!ep#qnOtkDOBAa4y!(xSAP@ zUAH=B43V*41m^9x06V5>DQ6}5jMHL^4`2&(QTH+SEd^1{B7I2(bDR!xUjZhrei}$ zS>PKa_qw`|i+xEG`gio9(Oi=;ZM3vck?aoJErb4CC2LLRy98Qa$yEuqO4MFK^o!Zo&*>J|i%s_GfsWLL2%BSg=8o`z&AJVp|th zl$Q2&kJQheH@7#98c-T;KIF6FLq5mK9>yw(i5PT0#^4v@AjWrkmvX%j-!-*?!p*HI zuqf2I@)Y~l&Vi$py;yPKPQdwNptR$i_5N2Mz6_#|wOxou?9LS$C#~Q&7TBwF16Qjn zc|O%oMMTq@{(SuE4XytD{7}y5&mEQPq`=56!eqiijJ6>9Mi(+sbsTWe?2P+CWCJsx3kfD>r)`(@+f}UI^(qnBXCksp z)%OV6Qs;`u!Rg;CtxmF;-H%{_6$LQFiHn6Yre}UCtM8tfyp<`+64f4jfu|$EjO;3m zZ$4o9YUKRI_jH$IrbJL~_`-?Fu5Ih&>P#IwkWHn3VK+6Kl0fDpV2n$Xj5mMPYNb?lc{!){^_L0A?_77_~B8q_nl-5`uu2`3z$U%wAJ z;(Q*cX8v8o*k@zM_1uW_d}?&XvfJjeFjy}+Gu4)b+F>HZ{Cv2} zVzfs;zL_Z(uQ^Q7oqZv|kFCjjSf6@dImtX9L{}QrUYAtu%l(XzuSK}qwd%v(DEzdOvr~6Y$@Mb0Xnd6Ef3uPK$E2gCNCYhW?Cxb-Z5$jxe{ zShRYa#%$}vYkPwAM8`xtET7(j#nBS2g!-A?DcPyuY2@ThUSogzmuf*?B5Xd&&<+nC z7tywyMK>bmeW)UJx=4f#2l>1wqXUxz5&XwEwtE+jNej~asHUYDlRD+h50^`(FzZPq zf7zPQ!7y2NME5TjwrP(Fs@E2jslckQ+c9WXx3l)W+j?0#@T5;DX>JI!b*Yf8eG+_N zG(dNA*vQ|v))(L5j)G`*A3ymZic!Ryemlys+)v8a(HB-B@nx!j5L_YDvi(*pnLe91 zZ}Po0=i(Fad%-YFk+;!8B1M8?-tn1d+(Mb#b2bY*<3btB_s&|AAJ7+ z872IY>B4VJ(GZGd#(tfRy&$Z?R0K45UyqdZWI-S~hZ-4I82)`}Ih&r4`DTItDZh6Y zGcH)LBe0M8iM|5O*6G-dDGLrtQqXsvvw~|^?1`^}X2TTZzR0H`w7wdS)CN;VRclSr z6AO3v;CuLob)`-ag7WV3BI=(ViEyu?+J{jhUtFPmJ=lQ3k7rqr?y~CgtIQ*x0mjYv zEXD0TsN$=}pPzh{^-BsoQL#LB$7wSVopqQY1vs-}xR#!f)KJ^d-td(s^I$+0(P~}@xuBo3FZQ`3*mf2ZP^T5oI#`YstLge%*5Jg#l3_hHYc~OmH$w^3r z{~bLhp;XBC44xp{HENl@YiZce6_J=IGUa>uj7WZSFM%f4h@mumQ^!pfUhUQIkr?c_;cj!Hy$`8UiBkvVJ!N`0k} zp}9kcdelFFdADytn$H1#?jIpt{Q zte>CV_p_?_82LiO;|3HD+|ABUS-M@5dhyRA(|w@3see)_vYd+FAP~0wd%usM3ji`Y zTR3_O9ue`&3(vq0T;i&x;AW>Df?f%k?}=*I|G}fa><2tbNPsGenrz`l0T2&4gB?PowX;TiRP5-n#wJCpxH`8Do zTua2A8OvjPVop4o0bdmpa|*J-%;3;j*gJ5weEH#PV3!u(_)HIkRj8b*C3wx-4@=5> zSE0$t)4ytV8_NVLW=#313?jxne)4H{gCvE~TPRqn;^#z1s+p{CWWDsVnHu{mfGay_I5#hxksU-!7G+A7NI2BR3uq8XC7IG&>^$onSh_juxDdJNhAT|B*W*+GqWvcVkMmxOK|B!oCZ90VLX- zsS7IDvHx!POsFuH$Nh#~ZSR#0t=-oK@g<{YQ_pNZt)vb5S&_n*0$+11X39sFPb{E>$|2DBuTaAELp@0eGn0pA=;Z2*}S336?<6;3K}!c zMlE_tZ0XE&M*cg_!;9PDO$?G-oPzL~$?3}cl%_qq1oMI9n zNP)u?yO`q`@}9UeeXN}zQGd*Wm4Wuv{4F*D85H&W=fy$82z9g|6vMH8!|sk9dSIEp z0$XW%5Br`R{gBG`0U{k&shmwK8Z0tp;1iF5kCj=Oa8FKvkIF!x}=%2DgBM%g% zl7Y{g@dFvRcIT(A!@^A*bo^MS z{D&kCXs&f}HX!8^!%ne;3S*@r`UEMR)x<0dNci9r!!xGehm8G~ch3S^(QZ(tFIJ7u z6F!d2y^8!0)SP7Igd46M)J*iF&g=WV^`eZ-SH{rJ2^4md&+bLsU?|=j0~>ZpD$AVw zkigqV9%P7BP+7%OQ_DH7B;vBmOAi3s8L{sIb8>tgvq`kWkLqn*&u2Ds`z(hg8f^5 z^bnGlc%U|{qH5>TrSDJindl$1s{-=F^cY~I*g#u2%nXpQ=2H$b6<)*CKJO;jElXIF&Z!k%o46BBE{t&S?jQgc&{_6yEx+nZW9b1t04?H7 z&F#N}vjN!)03gfamk}eFcOX_k(ZY-caz^9$5R-IS{iP)JAx#HlaR}!p&qvBTY7X#l zNt2x`O|(SeVU;8IN9NX4)D0iSN@xt z!H_Au=n~w7Z@p`(fEAXH0<5uQ+(XNM2t!`RP(qW;EwbV6K~%WN=wl=ZPJXkm!W#Qs z)#0|xL@O|9`OvIqRTjZyuN{-(!H*B|odq#AwSje4rAJ$VX8+t74NQX$%@%4;uH=L? z&FQ|sOcNNQ5$KdGNYK+=Soen?l8`QC>UJFzc?a>hdlSOEmWSrH_YPj*LY@N@2|F~A zj!>yz28MD;gPSn{h^Mx;kz%F1mt}+~%Lwa$?)89mj>4)#k^}nLV{3+&)|AxX z+UGNJbJ6H8{1-3cWdV{C%f+z@`s~;8eH#qwRxS=sXe$$%h_FJu*2T92@x>`*zum^t zr+?_rn46)QBRQA#3O4Ed&hQrU9!1j3&tg+BcA48HSX=A@iJK5(vF=F9o8jbWqvFnw zn@!Kq{{D6DQ^?2KnW3`qqsA`jOZd4iOYD`lbFx3>WgMCRk2Y8vxym=mBLKBp+rvZD z-=9hueJo|u_I~lRK9r{2>AQ945JuEdnjV2NCnCr7%44^t zorzPbio@PX#V=2}*ztk2G@PYV#NdJLIWuUbSC6h_pe3UYq3Svc`UF&}R(h&ovr_rV z<%Zjmo)E(3-mujdjpuF|S6WeRQxPDOvHS-ZGo~J9IQY>CeC>__z`Y%$yywaH~d%yPL zMdO3-n&0b0`nxV5rvw(g(zjyM6w^EKa|27F^DT)2CAQxz!2hxiJR9KO7$q7-tz zE07MPQ8dxPi^PE$rp!5uj(!E>Bj0^H&Z#tBq3bir19$BrP)?5jL+OQ4G==Kr;AJxG zEKTLBRwAvuffK5N8H=~PJEV!uY#@FBwb|1SQhp~vr}`Hyf|_}6V@`003Aku1+sIBR zH@Huot)b*YNZt!GHc$iSbEDm(nAWenyR1`8rSc=MBpb#I3$Fti1F4x?p16yq@!j~8 z<+8butDf1Ilq^zFal$L*6beCFfZ;~vpLsymk{Giyt2zBrrAM7*Q2$PHS=m8!xNd$n zFUpdue0F8b6m>pEj(_3N0NV9{Rdi2-Gn{Mgnd7&|V=l=<`5{xUk9e9mx8D{-RQJgG zL9-G9N=u9p4_4+&UxF7eBntsd?|t=AS7iELNbe~*7K--U4j*^o7zJupqzz7<*KbH+JUv^VARF^wUBfnBK1LkVA4l&(9lV12mdJ-WZ4EaXl7t#4E6#G&V!>PB}0d z$Rw_lKz@Or+l%z zd`ONXZD=%f*x9J6&D^Q44P^Fdc2>O!Pl_|Q1Abqon?CWdr`#7?ue}-vz`bcBe&iDq z^9%^5=v-VY)dpQ>zWVf|n;d6&h}RsxtBi`w6#dKW5%2{vB2JE9rMrG=$*4VC5NcvI zzsBoqQO%EBOIk~;8gaxBhjIIozg>NG%d874wi(iETp}RPv4N~nBB}9BPvUnbkkhJ1 zQZ3CMPAYqFUgDYwaa97V<2AJ)Z;s_y{}RZO6q&og<%8$o6|=)Z9^j4w2@uWh%7EdV z%@?tA<>@Z$`6FPADDVxT?Q-sI4+gad0+iOx7vOHpVqXTylAuyc2%!g)%PxXRy~J4S zy zL*pA@9`(u>w=3*?h!K-@>*p24@UZs}?aS67i5(Ls7+NB|UR z5e^IPP_uJ+Ix3n-&@e-wOzcn~#2t|Ac(-%uxv(YRm2m$VFzs@qn#Uh##R2oi$7dwo zy(Y^9Ao=HKH^UCMUHr`fj88l|GxYhJOILS4P8khJKWqP{pa^8IjI51kZyB83!EG6w zB~DO6gLo_GNR%H^YxR3&bNxe*H;kBSHiL0=RH8AlIizAU`R@xT$&e^%cIA>xSuYTKjh7_M2 zed^O`I8qtZ&w{ZzzD;-Al>UuW+R)kHVaxWq|qvJF>C` z)t90nZG0vafIrfy_B4m#6NK7^HNqee{|%bR8XV|jJ+1H8pjo{P*K;6g3<#{ z9NfI$GAc<===||mNdL^S&EKyvrfFynMFT0_b*pMUe$h&mI>z^G46Giz ztTJiDR}u45eM60okNvAo&vkbvWWKU-6Ux5Tcz4j`B}Alu`a*RZ&?T`LHd}{~mhfN< z)1060LBT;K{>GwxTTz^F4fo71Ytcf=#=97xqOZv3#ddG4$a9`t>;yv8B3izUA&^A? zIPtM*^09jI+L4^2k`u1IIZs7Ob;K_={kI+jO3b%PXNSblG&tUb2;O*%A0_1K)?b!e zA=E43=iC&p0d8mdL*lXzvPM?fC2pbaoGq$`v-5i8_Obhi~@JLG2JwWH_I zN>dnH>)i{ruRutlfCR+nP(ng}WF$x&ueltfrcuXE=o4=N*?E5J$S-T;a(uL zWrn!0`5dc}BBPPzJ~!R^b^!;!C!d9!f-bB!`l=r!8ZL_8BXxR$7JU)&Srralfc+LnSUyXgXa1+-~>rZI%fICeg0FlG!MZ)h6dgIhR`PAIk@1 zAw|;{R=+=pJ(8!F^uwmC40B%4(wdC`2o96o+^VH+hf`el-OeB>c1Clc+x695i2LkF zu_+6Q4uP^g3QS(a=lv>^!eIad4O7c0$1Mjhj~Ed@jq$Ik5Z+%9;ztEr!V4AdrUHU>wW_=g3+!rJBG}pl>UO z=D)Gj6@>DilB`IOm9X9dVn`0XM(vWHP)Kde(;%__RwuX$LY99A4O%~PW~difClX{(Sn+Yi46!E zhM7>oKb_m;Z09kO#17R$BosaIvX+I!@<`r+3;V*U%$2w51D?NEg=;H+W=8K~$h<3g z;%;vJQ2kL7Zwd(~yXC(SaPfNEY_Z79`kxA{kUcCozSO=JwFp6kC}gktephT->hf?! zc2>G-*xs{_Q+40^bBQnZWxmRKOUU~q>dRlw6eom<_AGu^Ng}*;5>O$Wf9WEOkA6+S;E1eGE z6kBQe7wDM>(`@fTIM%3_d#WJ~k`Nii%p_bfdX+9A2l7C7RPIp>M*0@4vh`3=A!o z4jG~4zdVwE3h+0JWD^#dF7o*0Ut1Pb{6938DzEKX+2E#Ik@upDX!Zqk&E~I{wsEcA zxuxGx!Y|hSiH34bXz9~;RKOOnvRhb%6p~d@&>o!}KQYs5ij1(FCj<0I$A96s{ zbTkONuqmGTG*LD@DwbtEFDHu*rWHbkJ94|>k_(ZjpCrI6UoZkzh1sLj$LKx!W=>rSf99c-8^tCK4J{?^!4Bj$2a)yAOcQfV<(Mu_@CymqP9Tj_xYdD-ye zk$+rsZ!~-QwWhjf=Q87*8cl^2cbeQy4sF~Q@6ufI=mj6d!88(IK7kS+G9*ycc^1yO zKi@FmCP``1ZQaywsoJ$8Eh9_?^;8cl8ja0t)0mlvSzr!X9742`cx#UOR~Q`k1mc z+V04z9mj)03Ke#v#wQ2JLcEo9iljMMv1z%Be?ynDkQ;~(dk5L~S)T!qw1Z!2s>kSu z>rG#m2xTE+2U&g|Ciy1p_Zz$JJ@yj1GFjqPzfF480S90G$4b{M7oqG!iA>6R#FS3# zkyj|5jnFlU_pE)jM8c3bgLG4761}$I=j&C%2nUK*Vg~P5Kv1pg)OHo2-?lu<`w32$ zCB|CVQA&R7k{M@|9!`?X>29;VYV)oG9Yd$uukrTPc1&R!P;FNVbz6RIdv+dH43DMV zx^{ZRlje-&KwT0b-+j?_m(hWwHpot=>Tc4TFe zm1O)5Hk~&M!WWtf6XbyQC$vVpTyLRju(+947g$(3BTPUMvIdmM4P@vGo}(*$9Ui0N znb^yHch+wHaIYK1grRo~hN6-UhJYNB#(6W;^rZHF!p7FeBXu&Wl(H4DwFso z8oSotX9#6I0i_=lLtw@5)KZ{cE`qkyc{x`nc=LJusJHJybpbU#VRp6$(dGDCc1T8u z6xyg=+btXKz$g83?DF>hEwj+LvVhPtba70(FODRz|#tC2+3BfD+ zs?sU=CZ7~ezZ=^Maw_Xz5v_>&q_jQI*;nwS)xULfrLRBbLhDg6zIsy$vaU7nXiWp) zn9%vLbwYRHk_A=)6mN7@dblTeU9Up1+w7o*l~oXcNl=sN0P*F$G{F0a2knsBo$XPk zQ{LAYH~Q7Qc-A8`WUWH4op$V9IuY>F|5jd+A4B9P{F(;9@`3#vY>Wc0&rqJD@qZ_= zWQ4-`+iL=PP!L)>+j}2^aw5RMh9f4jtzFS0GtDIt9W!?MoV|hlf@ViIbg8A_vFVZ- zs=~_uUj9@;v-lAXj79l-&PCFa4Mj=+hYCBWT{4=7D_Q#Ywl6hyMoCZ=5%mBCeNMi+ zJ`i426~tAg=cVl6!eS7F`tqdC>!ulqqxpxL&^}Mo(S2;WX=6`hbAkgi&cD@DoSman zsbwOgr_+y5W8{Q0w*M$}b;zq-OEn86<2#giGb69-p@B0$?s6Qah-dv&`r5OK?3;F_ zlnZPcQz&&AOm~UQH-_-A7<~deS-fBNh^9N^z<;)qboA*#s_?dSiEE}g5;{=B?C>^! zZ50bf&{TQH<46I`)^e`DM}|#tiq2?S-amB}cFJ`@d5VahOPbTljgp2kK1i`R$>@v5 zBj5M42$9~~QbKidDH-7cZ?~)j56q&I;Ri=5|6PCaD7SGaY}9z_7nY1)5&5qfgj7~R zo0?UjX)3lHm+a3-E}J>kI1-xb@mw8Cz2V_EfjMsZFXp)n{-Fe3*(1wn+2kI-z_1|5 z*3Rp4_SL861Qm3bbx9 zWC+aBS#H}yD4W{7W1#q5zDt#kl^0h;haJP3Eayr6yDIUlaGl={|C6}ly863&=PHn* z-o6+DFz9GdWn=$6`K9x+IDjSgKui#F@3#CQUgql{2Axl*x|EPuZOJJ|nb6kesMt90 zIxqkv^WTcK1o`(hI>^hnO+2zmop3;e$5G-Br?biD?%0vx(WjcJcQqRq63Wtf$LC`) zGAc`L8QYe0&KZA^KI>NE0ty~CX8_NWR1ea1ipxCf{VS|&zR(?{2t5d^y8@UWg>3>s z!GEZ$@vdrNfPIk!iv7HLJLhB*ElAA-`j0Z4C!rI!)J<%cOW9M`t^PQVYyD-G=kID7 zE{}eV8Fjq8#%5#h62dcMlI9G6h@BML8=ananF>yF0o27wICgF2D0OyptkDp2K!J5K z+IcyMvlV9NT9)wnqu(Z^D@L9R5G5_d{Cu_F!X4xdH0{rxk@_!xP(H4l8=?|?a``ia zVpHYCJ0!cEb3Sw!UZAaX)S>8tFYC+w$(Bfes1DBjyrzA690xaAE3z1QSL9GEqbYm?$Kc2!{1wR;Vh76qQ9+SSaV2-S;tdaYE@|<=0 z!WJ!OrnPs+RsJ?&_ZwBYQH4Z}H~xn0ez$ifpS@Lw=ppRF!B<*_Df}0_B#)JEFCD#2 zdIDu^XQEle9gm5xCbUjFK z1-fnqa&x?_rMGPH2CZEL8fyH^Gc1D`TF%*d`WeX94ds=tUg_FW~I_syweN%c~lo?AX zF4gK4B5MhUXh(ixbZe|=sl{b$)M!^yKD6D7ofy^HCRvI~o=E^Ohkbp0kt*J*#3{u4 zvw30~cwkyM^VZhJ|4{Cm(ngfy^zS}*c)BTb&&qwYCRIVf%8$_M$!Y8dDoEY+_tDO# zp%$oT}r-pvYAh(HalBu6G4$kG!DFDB>NwYb<~TabNfX=2&cnN`~x$>VtOpd zqy0UD&k&GkC{&8AVfo7!C~M*hcNSo#-rwH0*e*1=R&>ut!{k+A40*Sclar&v!yis> zWma5VT!t4G^v8V%(s*qgfQ%RmZz4=3LdT0*ilLwNKUzC~m`^f1y>Z=eO|Jm$|#($(n4GhZZk@62UQ7s{Jat=wQv{?!`90nUihHNT!vpoqLa)>j6lRmdfD*`=WE1-`;;V<*L(>#av(*VA)ZwmaJVmZ9DN)hzlP<>wz5f2}`Bk zgdexQShuWMVw|DQ+I8NMaqNvz{X`O+(C?{|)kw%aF{e;1<~@NXtyO-I3m3_}h6!AS zJMJ>VPhKq95|xRlKQk|TY-Z7rC9LwX4THg*#xcDyt+$EGG1!{$rET7H4`1o6+zQcg zOTs}LgBp?Tn{5OOp;qxlpGO_H&y1?aeQ#LqCz5WCNl%r%N{2%0^pP_Yt5+5`6gwW< z+R|lDd;EUbt~vSi*Wx7TDKlgUoAcLVgr&`9_fF^fWtq+SUqj<07`NSM*QITxa@9fS ze4}s9$TU8>>@$JC(5FJT?|4;7hO5oIPa>1>2kM2kwDmP1w?aPcc_MEzEA0}UYM3tG za86!diE5VLMx8fBxwj|g>dhKi2seVgox;3ZfUhF-v<)95j=)N;DuotrqY%|jn%f8Q zN1rY8`JHB_B(m%`juW%vW+f{TZJ+1*FH$yYl;~?oKBSW!ocyj^@JX5ycwI6+XUG=P zlV)@C8*wesBRXp;Hv6VVB=l(CvZbefcrWL9*Lq0%bl$ChxjEy@5TB5N$jNN3tT_)8 zavR-suqDPEkQEMFh{7Ryjhm8;3h3v#|sGU zIcDgNX65faU)5b-#kDI<)w$w)x7dTms_DI&xLK^?K_aL7D`=^+rg>evUcFc*yu>ui zcgEybOk0vN#n45-(XQnW+epT{_pJ<)C4D@?-$zge*Moom$$d6KL7VKmG5d|7CfZ3O z+}5O=Z{4F#V8q%GKVkn{ZWD zx$G+YeXeP9E?k-l_F<2%J$TiIN=({%KYdHZ@K3}{+O80<=0l#ew^9iQnI)JB+qvzV{sKZ=f9Kn;}n zvLcE`XS3ES=c9ZD+rmy=UZX$W=}YKOjxnJ)SU~h$9w)Op3uq*GrIYq+_t^hHXq6)b zC+5aI61^!X`#t8wX-&wslwf9OpP9#-xXemhm7%80_0@9LBv%H#J11^F;}+uOXx|(-Q}P?ln9il(211cZWKw&QTD`h-`HSi!Qd?cMy|0A{bH5}^ep~8x3!bZ0 zC`M`()c$;LFI1|1?8%Zm+1)u1<`Sx)FYuLPLs9k;^Kn>NyM z3nzaC%&PIZC7C6GJh^Y`ajIhH-Ri#)sj@U|TIFoEgbQ|U7)1kTHQgMerip&4OrdXL z_dM_pA`|+nscc)r_T7a!&F3~gkw_)Z-(?FwjHTG(ImgHJe%JOb+qE0Nl-?cgOjpPm z52fwGN|jAzbYh;IcNPdS9aUR3l2mc({E5Cc!beQ4$JviczM%dgCw8j)vYj=p>f1lt z=4wxgq`K^$=+=GU1i7&FS}rw04KbIHBe?YJ%G(h)^+$L9KN@O8GIyMN&D%|F{a?(n zkQB@U5PkEhf8BeYv1v)qlwA2H3v&z&4&jJGOvVvh_z z2lk}Dh!fK9>hmZW{Pqo`C|ig!j1KxHW1b?{wI(5PU_&NWONJjiV$}fti~hiiLJHus z{d;g319sKFCwhbaZt4B!4B;D-m4jNFDJ2U^RW#B2D?pcgNvO1nuO`e$mXIP2G0ufR z;$bjYv3RUwc(+NIiQRo8A~U`4q-aeJK|m&7J*1Ou(^evvrIok>Y-(y=!fRpwqHXp? zwWo5qP&upZV7l7Wnvg4L(Zp68L0>}DEvSt83w{)h0*R>gWyT6hCSK%B6D(FS9=$|AunCSO!o|FndJ2{d0XSMntU-QAYVg>oC8gaF6$$>BR PA<0TANmRZ!`trX3swpt_ literal 0 HcmV?d00001 diff --git a/doc/html/_me_infrared_receiver_8h__incl.map b/doc/html/_me_infrared_receiver_8h__incl.map new file mode 100644 index 00000000..89affdc8 --- /dev/null +++ b/doc/html/_me_infrared_receiver_8h__incl.map @@ -0,0 +1,53 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_infrared_receiver_8h__incl.md5 b/doc/html/_me_infrared_receiver_8h__incl.md5 new file mode 100644 index 00000000..cdcc9cc0 --- /dev/null +++ b/doc/html/_me_infrared_receiver_8h__incl.md5 @@ -0,0 +1 @@ +9769a8322ef585c7f82005758c572513 \ No newline at end of file diff --git a/doc/html/_me_infrared_receiver_8h__incl.png b/doc/html/_me_infrared_receiver_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..e50435a4d2b05eae812ebbbe2faa7cdbd9d91d21 GIT binary patch literal 64066 zcmafaWmuF^*EJo|B3*)kAe}=ilF|s$-5ob{-2=#gI1JJagTzRKbbmKK z&wIV^zi<43)ZFLnv(MUVuf2#?SCuDvK>Gj<4UI@qK}Hh|4eJ>i8u}MJ9N;TQ2kbn+ z2OM)Hc^S03`+r|Mi$9~GJw{WMd9CG>wX^6Oki6b{cQ|sQtl-LQ+mCHks^4$)a;~kB z(jfyss;T(nTpRtM^6#;^ImWa-l{6Ez$tLH@7nT@X8V)5+oS)!mDf(0;A3S9>@>urr z>q@9U`Bp76;R_XU=vn`@yy!Bi?!Z7CEu49?gu?~T0v8{%{C{47ak31rWMrP2XqHa! z@QZP6(X-ICUWEw?3UbS4zmbtCEM|`p4T*|U=t`e;v-Xmo5RsWXf2dC7iAP43l=D^= zpNwo1ESJE@;E6>>$!$yzd>~6=DZ7U0=Gx?S?J@Z7&9|An zGz0ecSMA@9goFY|TN|nJc75IEn@kfEs2X=WyLUb3+lu)!ni?KFWwP+z=t2Z#6C5@I zp-MV^cOM<#NhXH!CoB!W<}pS6V&rWaiWSCZYunqb?gQudoZ=a9RLd{Fr$VYM2b+hT z^j>(Ra#rg8sY)TgXww0Ho$ZxDOu9e z@Son5x!>_#=itEup8wh4NqyRK1SS zo0>Eh9aq(d?tat2=867o-oQwA|Jgo8trC*Z^H$pw57X>r;I#5@KGgniHRCgV5Rl~Dvx0_S)fIyh= zpSV&2$G6FOpYlmg?A1rV8E|TC(E2c_<7h%h6lo;6plarbW{hs^Zu1N#9hO4Ojm^yMGFa<=<7fOuWYk?lvf4?n$x&~D z%#V@1{m@E4Ue-C0FQQePo=Fn4BW1{q(6w1&~dLFYl$rX1eq z<&DQ~wt9y=Av#l?!!bF=t}~gB@!o$lJHPT?@@3t6A<;KzafT-qw88q}s`}z(d5%H* zx9tk%z$cbbzVaLTfUt(O?My{#AN) z9;LSD#LachIx=kVdi;{{&PEXLLyCqCfI6E$CWw>)ICF1~X(fykVIq1X*WjE-9nJgD z=IMckX{3;MM@%h-O#}^hQ;_irGdIp~2cPGM%9u4@g{SOw#?}a?5UC2IpCSe?g^Fme z^@Sx&W;~82fi4*hrh*pNJzrV4sPCG5C{p>_ZM+A-2COP{G1-zO~tT;o@&7{ zpy$k4&R{I)Q`C}PG@VfEUEoVOHvW`flCfnRa!1z`QnqDJ(Cl{ej+m$szr7`Ub(x5e zt}F3Lv!Iv%{fRp|u9ZW*L*Koa0(t*95m- zdvX?OG4hwW72S|90Mlm?l3T6!#t-~bVrW~uY20+EH<2CU2A#Kt!4qK51BjGMGQD@-!O+*!n!dQ*5U#RPX!F7ms&MxazF6qk;zf~E=eqXDpWZZbhPETLe@W_p2J*}ZaI1;o}S#uoC9eDx?m1KJ#t2&BxPsVvO(msot zYV4iuTeBXs+^LbG$~5P%MaY^3vkaP_a6M=Am%WKpjXe=B(^W0;AD536Gb+Z(4V*J;b*MIcd1xVN&Q@6)8 zf!js*CMc&Zqc=FYt4z;nvb`@G>z`m%5(r1UEgd zfgpa^yaPjL_Y-!$pt_#w5X{94;|cg#(_}|uevdqv>+9{U=wI3Mi>=m|AOp?8iu)uA z0xG^jcTMZZPfia=nXo@hDcu!htigKU?Alxur-mx2eTMsCBLt9Xo8d-NN&e+qfy;)_ zBb?kS#hE~c?Dh^s^GnWk8pubF1;qBB8wPEo-JaM1*VG;gC>k=R(V^9TLuURjZ~iO3 zRVFu9I~X<;4?>9W+yv>}WCNHRoeCi37^{|!f6ZUpkK_lnQ%;muE%ntm<=uTSCrXtD z$9mn5wF_@jv0;3|sg*{3e4cx0OHVTnAGtnpwGuU3-urV?TA|Ylo;+n{nq6R{+8s(f zxq~TM&?m*uf6k^UC@9;wMDncp?*%aEIwSf8t=@N6Ug^iuvZ62ZP^^@qN$oac~37i%&;t#+aWu5~I%yvT`iEUmCEs7tI{@LWTs zH)yVumoF&t4RF?0*~1#Z-iIuF@O(J4Yu<^9soE$bE)Sp=!B9Qodd$^rLANU#|GjL1 zc@iRwE^C+wlosslx~hK?d|!Hu?~fq?>^0?0ZM&03Fe}A#3buJv6TCfus7wn)6DJUl zJgg8Ii9qo0iAx1$b<${iCGDvv9li~tbL&dus=wQvc)a&MX zmrI$IV|?lA<=)@d@1?O1I8D>vboQtLm#^ei5^y3|09z=84sCb%6l

S6`VXi{aAH zBRS_ey=*&oRFHOaRRMUqZ5s@!PUWH53c;U-E;siU_FPq*db#$7bbnOnP+waQ(|QdJ zEZ6^ENb~UQK$NAg`s)vJhtxCdam5@?mgd$|&HD#CxUCW*&5=A|zRcGhLS{z(yLKkzIdI~^*G~XWOV|4x|rNcBW>WP z&m1Js;rD4qRk1_T(D@?>ejLwMYD;HYwVPPVvu)N0P6=VTbntqn=XJ-Mek$+s^q;6f zw+tHA6>(CiT5*bAQ%EfkflG$_5WM+BbB70G-lNB&{{a5lSn+}Sfho+-JN37C*kMB- zKXi;iI%m_-J2>gKs;*}>&yC7eNmNx^vWe>%f7he*4Aq&l_MDpj|BF`~CaYdkg%^@M zGf=CIfO!Z?x**@Hf^+K+2q=IYFmD639UnpzY7?t_nvxH|&#L;OG~SS;bT36@m{7j*RZg}OcwcEcQ_wLUDPCAJ3^!-E*$k7=%QC)5sz`5Br!t6%N` zD64Y>ev2CDbdFY~9a{`v)4$m&}FJpz$ZqdB7GVB}!sJb)C_=akX> zB+$QjJjVZY`(_pE8oNbUC_MUILfyBH_}mk0(47M7&WC{bb`8%)+?NR}%*aNMURAd5 z^hPO;2ksCysA%NST=?+zjxGg}Bs)*nw(IkQhMqHrhh93jV?g~nHUd!V*c`afA=T!0 z^pIQEZEX7f?n}vzu=?+ql&c)XkmAf(-!gvxQrSX(Ez4`yFn@Z+CFZq;0O2U7MdRAJ zxR|+?#mte~`L}}SHVf%4oGwsLkp=K` zM$Z0dSm=-^*6tC$)uoc1HRCe`9>?R;GEz0Az-@?fxuoWyp9_&z!3layrqW> zx>u>wfhJBY9(t7Cx4J!b*g;znee7JhU$;yk&fs8vJ%N83#Jr(sb>k1c5Okw^A9Xli zHgt(Dg2MM^clhZjmxtPp`Ek79h3cbrXS)~u!Lqy{oNw>5JnI){V z)d3tL7hqZn;bkcQ(VuaUIm@g5S}4~mVw(s$B@CNdTn=I|N0uaF2_o7YwKlz0K|+#s z#cRyQwgJv|>X=~!t|31#F7_K8h%0r0b-#s=qn`3z1=P-GO}Wr!BwB@Ign)} z*t$gW0K*ycR0vfrXmuKF#8BTh7eXT!^n71FTCSnpa&qdDD?8sV5E4=Aqgaykb5H|fboo#rL!;N#8{LE$!JnrNCe$zW?seynDfn{76Z7B{{PYb_}@+5?}sjYnV zJ?CHa6@xD!`u&59 zJ^P@UHgjg6WGpT6E_V-S|1Xa9Xd&uD`KWw-`LLh6Y& z1X1Txki%1%E*KTSXf^?qoQ=`yBq6|*v^&7}j_0!w;Gv!gIRe4@a7ctvy2nfY9HaQu zEOnfdlZ+MO9}Pm@y;)t`bh`rdpltYgHri%*U~T)xLdl7*6jn#7>I@sOg0xlxd*Za# zBYtGOE_uqu&edo8gOL_D3fCyH#(s3E7G`IcHHQG8PTb2~N$)3*I{y?A(eEMfp?{_l z!ffp%o0El9UQAb79KxfUBzs#}#*~Wqf>Qb}K&#_cr)hgxVi||QzY7cOL9>^={#`T{ z4!?zjV+ik)QLQ0FG;F#fihCl*@#m4C7l4`EjD31IX_(KT>;LW7;M4Q~g_4Mic{t|c zWK9RNHGNzILz-pbikrH*k)M@|wMDJHkqt93hpj_{0ivMfjR?G5>^l0$vgB?N;Iu&7 z2HtD>UmTj+b^2T{xsWABBuA6=?sHB1Uy-1GBgrW9E(e$_^Z_#8qnGa@>!0!m+{4R= zDQ8q@@O7l~0xO3RX*Zu*h50#xR z+2#>DpCs&S55&RYx0l@`8ep#zkm~90PP&hdn*RrY>{ri_Ll7o<(e8#28bP=ACtHx+ zlp((qv2M3P%6^c;7RpfteFO9(dppz&sy1D>il(Gf(~KF;+ImX(>axbM;^S6x6EE5RsuNfXCYx@#}fNRNzc+Wu>&?6i}` z%q)~^6+B`B3#P{L7$1vTN@-vhSHor}%5q97?j3H&E`rMbr=wjL>P7X@E)L0WKH)AR z4s?VP>rP(4$P*wKi(1Kv#>E{73$YaU5W0b8=K&BI_3Q1VET}jH*S&v1*aA`+FHjM6 z>`?i0p9w2xNwSb*=wrkW2)7{WG?TA9p8bsh(ABgbIf11yVistS$k0PnW=o*tRscgv z*_j!mD{D<|AC&{SP&et({eJtUzoA(yl-hZ4wR&b%a(*`ij${!aN}GqbyIO>+K3O9e zOz2ZI*9@r8UoBD`E4MTjJ7Fb9F;Qqw`ESWg(GPNj-OYFHnz+h1Y^MA-p&{Ocw=b7f zXvE3@#7)Uvi>01M?!=Qd1TG-^GsEK`>?S&f_X-~F1P1x=xxLE5H%dzu@A5(SrXKE4 z>qwXB=Q|r8;LliCG);lLNO&jsv)P4f1&iQ9fODQV{@c11L?`4bs=M?T_4+ z>Xs6m8|Q~PtHus`G_{ktQgBe&bLZH0HvQLHmK|eAzp(j_DTy3w(JY_0Z@xb^eZVue z;{Sxwy)xz$$ccMhZ?Ou0`y_JG zIbZ}6HXYw6qJctJ5IRq>&eHl^GpeznV08oDyZ-TYCeOB>ibmvdM*O_W;uo$vb~zH1$jQilP*FT9G|++{1%99hmH+|s z)ztUVSuZ&7jAY?{d$vbmsIu(TRE+0{^Aq%sisZe3vfe+Th4+}WtDGQQ^ zA3cZLhX09I9c~`NkrEZy3bj&^g>+w7`j;mjHRhbUlk+?{|8WpuSgK79?EN#)S7U3W zoM5^$vx-1?SNWl&NKT}2n7=#oQE@{3v(ayl$bRH%!KBuCs9Hp`Yh2{Biz_W*xxy`_ z&&{ObLX>=!JQCS4k@lpI}PJQ|iu7$XsvWpSm-n%JtVU-OJA@ z58ffG^OCX{n^PjP-T_Bn4;+05NNih-&^5k4-4tO5RX|FFVG|$0(}f+;?|!ulvW!t_ zBTjGns0kKYZN4vGXsTTr3)^*(Km`9*(b!CU-#ybn&6b>ae8NF0+=BbRZ*PY0j^30$ zU=^8{e`rB$O6jgS4Dv5Uf~~K~iG^th1y{#DWaHf9A~ul!#elqVFjgBtuh2q{8(*|O zGS2dtj(WB;#>eNHm_+$Qc^s#jGfE*6v~gjs{0s=kssxZVLb_1Pm<2= z=3*Hef5smqa&YqN9Ddw#Be5m^n^WqGfS94~ml`^jcx}>u z^zoIF84C)Mp<&JKG0;KbeesxXFa@Ly@_vMBF&$z%RrQ7gGDh7q_P2xGio-{Xea}_# zF<|XSdiwEOh98r#`JVN|yMrK|bZ*LINrOdoL2Y85ds>5-7;stOOv=E0+dJ}O&=*IA`a!ZaJRrpqe zd-Za;>bd2!izGhLFp*p{`hc=))POsXsNd|qK(Lk>bFQ41K;TsFsbtLw1A&8@tQn-T z0il0UusbShP>%iW@f$$cq!Wm;7zXvP2!vtUid5Az+N8QXe&?TA87o>0OmvbnQSJWx zBy=1M@1^zBT>bz8V!@ukMCz<}K4Q!`g(%3w77lcS$ddX;`ejRzzR*A@-O}KX#moKb z_M#2-O@y|!xN>}b+p5;RoZ6(7{D&2RxFqg({S=w?;m|j1(KXc{x(KS5OFo#+xeaTK zQkeKJuf*8F4`9izX)ZuCaQ=W)!&*6vtc9Jo=fEQpXEQv6-IENhP5s`qwFRALmwuVF z{wM8cuSu^jVRSBrHH{9>hYxSenS(L!i{wt5+tiH8VMuCN?t zn6}J+Lw!(U`joZ%q%z9qk1~&oi1V;1^MOMwP&!9u$2Dvok!`BDySR(MlBfp?S0%b1 zy8&t&l!hLwVOuMahcNQX?4~@UuVr3A<9L+@?w?PPH^x`vB6 zU=AXmE|#dJom?~J%gXrWPZbDqyQgc>HM15V#u;l9jd=00g+<+$TTwX%B?>oh<-6j6 zmd6K}SM19PiA1j3oxesexQU!vHD}ea43OlpIxvl|9y(9+oM?`UdXyRSFc4ZO(q%%b z>8#G!^oV5%4@qJMwc37vG@U{2^k#wvcxJsKI6#V|72o2m(}HunsG2`E??=)PRJH6| z9Cc2>!=|-hBVbmeQ6#sFTbYtmuX9z_YCGm?Pw;1-lHeT^T#JX-p;}$mrr?NKHAM218&=rf8{12$7(vCns{vn{rYB2yY|6 z8=ruiaL(?^23>1=Qhro0wR#b0-`B@I1OSeKUt%6g7)}~8CH*|areKkgX)|Hp*512r z?xD)}F`LO#nA`myFMt({^o@bA9|J#k&i)UW9A(Q4i@Zl$9?&(H3-G~j2k5`5sB^tm zA}JYLRt$uR*f8$!&K}TKCVWNvvY7Yg+D7S&q+mS=T+0g}KbqAKNKryek>z_hW*0>F1x!#V?CLMh3v6*OlwmO#J%1Q0-< zayJA%F;Ah90)^KzJf|b<(KAJ-qND;FY_|ivdu+Igzly|6oh(ZNoWGur7}t9ZtuhPM zd7DnNx3oDR-0Aghx3jta$a%Ld-jX}nqu08aFDS0>go5Z+-6?}Jj{PT~bQvvl>+(i2 z(JCui2i&a?v=#ztaS2~^l)`>-z6=&3W8I&K8oCKxBPI6sdG7j+)b*W8KGmKcCE4a1 zU?#M4kdp4UHPO;Z>zTvlhLdq9msdPH7JD{KK_kj9XY&A4gNpnw8+C6{t2Vt2ta9Bm z$gog8u=zOS+>L!(4PCfe{9_pV-rs2ZZ|p2A*+uy>!fXJye~arDLx-YHMt4}uzz?Ww zg6}1W=0-)`&oaO*Fo=n2?EInzYLh+kVWhFAdDL}rsl47hzEvBH1VZ+86trK%rYw4X z|J}*$C)@?AXA4py+r`QW^Ft-z`)w8EJj8wvNIIG{-K7o5!o0WKJeh=DEnb}d04TSz zD*#7JNHyh;uO3M8OMppVd8tFVIa$Mtqsa*Y4_ zOMd(kjHZF}dNHbEav|>Dwm_w(pwQz6qa2*GB%C@V=sa@*++H-*_{Th?GihkPS;*iO zn$t!5GYB$hYkGO}%unCt!CeSJMYz1XEBT%qoP`8*F9CHR$cw^Sen6Djw^0CHi~moE zzvjzOrA+&}Z9Z1zFJMOnQ0n3sGCHtGcz)QV76P0vds%v2X(Gay!jrJwsgfg){=$o{ zcN+1ZNWJhfXUJX<#gPFj;A6|LbYe8gXkut#u5anza+>;oecEh);U#-!Z2Swtu-H^< z7g|tXPLXfCp2*!;Jli&ebNAL(JRPo{@{z6pfyD#PcY@x${6VM#S}-0(`cJ0LRu>?E z-beyaaI=$vc8;1&m_1)v_7uA1=C9Kc4JZ zqKEO~_z$W=O+TcL?Cpftk}q8@8w5#E>j#s}kK++jBP*+Wh@P)1!=R>(eK_EyexK<$ z7}``g0@u2NBy*bT8Y`lTv3oWnh2VnS@%YjB(9Vh_EI7_hwrt5}8d9H@kH8AaC|>zw z2{YkaEwhAqD-B%42XQ?lORCh+$j1cuqR-*yEOXcevBj{@yHAFg!qs}_zb7O$8>(InaOOUVQNS{|CFY#t>aU< zUz%FyHFapipz=^bs6BY;Fx8~{Lp_$R1;U<0_s!rHWzAgPC{n_~+K779IC8u9VUUCc zB(SD(CnY6?ocGGzCf8rS+1bPEi@eU>{w{WOTocK~ia&bsLs!gSPiRe?lT~K~e^gZW zweqG|9n{$0*?TrdXrO={btCfT$R-aX-)t(9xoGCs@yvO(UwWK32=U{X(RX5M+nXQJNnRgV!$ZFo zWjBab@Yzt*Jn$LE$m!FIYkWjA_lWX+d;Rk?i#V$Kw(p$I8osO%A0qS%PHXIOYzR!hE%4U~VdMwz#qY3`G5}%T5+5T5l z4UuKr`Y+W-3i7|dFWd@D$2FXpQJ_$FbbXh&+R!zDr6N-()mF2lG)33kegx?YqtKK3 zoVZBzk!EKD<{G(3_z@!v-=OJDLsznsmqkhsd!#m~8Z)7_mfiJz>yg}_4vj}OL$SJo zJ3&j31Eb&6>c6NyeCdkX|Fb`THPckJIoPp#;prd5)VR62vt$W#APf>~T|%ib*|^97 z%gqd5)J{6&-eZBM`_vUVTGxy0sNMkysT6vP_->BbmEIzQ*%Dz zISb3YkX_S08KJ2zX`PNOgvW+D;JkL=szw-rh8E`Un#qAA@;3JJA@UhQa$9$79DIzd zV1J-{@){!SKiiG1!l+K~iN}^jBF)7}txnlMZzskEv=wD4GuK+M0TDQ&@^`}LjjK%w zt94){$As)}8uo!_G5JMN#MFE1 zn`=^QZK3ns@gWX6&u=P|0Og6nN%*3{B=EQRujpOxy$-nr2sUHu>~z$3~qkxT9uCt=&0GP%c|ZMkasSCHCPx7F|Cj=k3Cz-{KMDiO)@~ z!7TvJYAj8AO@YW&yqx1N70z5V_M~kt+x<pZRZF(Kb4n4%*9PB{hb*Wo0g# zZ{H=mHm}jE>TO=nAYCD17Os~QEfVCO0)T6-1klgY;;jlJc9>{!(F#ItLT~IWbq6C^ zxw~SHI(qoBu82};#F=P+j^X>ai`A(DcA3RCmPBX|ZeGm88(5~`bz4L7 z53Fm9bN30~CQH9w#!}mZLu*TLc}u5XSFVNxEc0JY8T~^g8x3^uM;ub<#OT%^nQc^< zY?ShWax+G!oVhPHizAo8&mN+YS07BuV_#G+r5fG*h;a!k2R*gzGj{W%Q*pB13x5)IG~zf4100T>!@%9XsvyL;k%?!+l|8CYv+4Y&#`D3I)6=YMvIS zN^ym5xrN4n9(?mIm+S3Q)cN6B%fbrCd#@pcf85QV?>@~XMn#SS(q?doYeO)HL61if@C`%asYv?3E@g{(wajfWg>I5*!eYtT? zg_n^6KX^~uMdA4zAVNWbbua#DQU~PHs@@i%*a2l;6%wSLTtHnwUbhFLVAQy{=(uF= zQFOTIk-y-3SZEbJdKlt%Fpfx@s9KN3`HDY3xLt*c&ExksnWxi_z8vd*A@|I2Mg@d4 z1{a05OW_5SzIg|sz2ZH+g`@fyyhPY_FAm~P)rYT%Q9B_EY&u4a2CWCgjP0vQ!9Q!K zll%`3`MZZc&;?n!NHqHyte$sSoUTOi2W?eL@$;V|UG^UIef!X%w0tSJ`<`;uAZN9< zCrlCJUAzBnd>%{dUFmq^)s5f3Q~@XsNP(*3!P1 zKVCi~*zR1r38A9@Hu-!fa-JT(_(`ve*pOJ9I*h;g`OakT)BPYo=OGGsrqg@N51SE+ z70^(!x(V`;# zEkB`#no+uki$u1%onN`WLX)Me0fxWsJ{UGtG-`>fn>lmYQYN4Ds-cRcJl~`!pQ0`3 zS-Ap}s`9E+)Ad@&z=h-ieikksNRXjf?;_KpT>2vh=vw{|2`CP_Nhfshi_2NP?rVV8 zG*8yT#fhes5$A#E3rS%EpJ=3tt2;6@7T^iOj}B92a05tMo^FZHYmzs!{ebLS!Qx7B zf{VYwZ%O}U9b;!ukqqB9IbJKR1qryyus;5$jcUWmJsn{S-?}h9c7IYJjd~mw_Qs;2 z$JW-j7U%!W(x)m`qBF=V&m50O!hYy6F@n@U6BExXOaz-9%NsXWumM$aF~#ja#snL* zW!{tPk) zbRpdBZbqYAh6_~jrOMXVbWm<-i#y|5j54c}p*ZU-+4#@)u-V>{CqR0woXn*>{A_)d zS4%zpJ4*ptsX}*tI!wN^eosl(e!?(hh~+FGO^Ku2PDq8wU7k#a9KlsKf{ZQnSn#m8 zxJ5@NrRQGG;}AM}W25F&CYkJKZz&Hb5s8SU;GTfx+S;V2uDmsLuJZ76X{`afNS=wW zc581s8e0bd%~<#|&7D-3%X^)xiPNfdN2d@!Ygt(RhGDKjKW}M8t_FE?@Wu(gM}4D1 zhNk|IFvdBfDNtK{5Ir?s$Ns?!7)w?^)I#=+?ikh556*C{u-tW+ z%3hYPf%TbuHtX9`Nbbf#@$MTOV_^jCy#Ml=-?E@}z+@ajsJXCx7`+Z)jY@k!?fpex zCnx}LizOMfS|`&eVXQXTxwW?!fD1P+L&FzV5P1BWfOa1^ttnsbNjDz1N3UsMt#q## zRld~O!^HV+PA?2d9M89ufk_Lfv+P9@{M-jA3`IZ_rmEJ3J1faMq7;0y2j1d>zedtq z!E7M~gv8!9V*FF>M=xq-vim7(YLl=paXAy4}r5)Xc^E&4SZgq4R3qcwqFEUTK_mG7Fjq+-I6L z8~5Ea4$%hHhT$KW=k}DVqRS%2KOtE&$JM7n$jl@f5TLU8f1a^(ZS3!f^LB*ePg+!n z{M!h1r}>rK{oq=<3cD-nsNHZ-xKTz=#xJ(4RkB57U^Emg?LZQ>>MCh2M}9z$Fpper zt@pV~j1>DD-*nw>NH$FqfQ$@50=R;m2l26%^;))ANv#=@xOF$t~$k^(36O-yRJt)blxrv=K4(2O||;NW1(v< z-hqmSqg-(&t&I;=h;wHPKWA`F6hTcT&+Z!0a6jZEdP;>>K87#$YzxGok#rc1(+vhS z3z?1Q-y`kCw1v*w!i|f)B{&h(ZcmvGlz6vUE#DTcFrv*na3xt`-HfrNx$>EQ4`&g@8Yc-oEV($viw>c2~>ukDjR7NlYCz z9P94E-~~f-s{Rl8nkA@24bd0gi_D+p3N7XA?u7FX?L-g&v$HdE;Om)iAH9m`Bfkaq zPnEpj+*PTD#GN%iDYr{dyYQC6uJ)IjHb68pcQxW$P4GO61|(ojABnmbNq}?7#ri?b z)JlD$)!oHje3Zf?_Kgck0Wb#Q&^qhY;Oke2xFV=IvfX+?3Yh-bx}btL+d|R1(VDm) zoWGyY^ZS%R&Y1>3H`v?xkD-%BZIFaF-kwt~D^qo*q6F*(WyG3a>O!w^=JZZYtrLg1 z@v2XzC>k_t1wKhR^ryE6W9kanH3i$jeEjoYu6h;E)e5m@9CqWNOJRskIy_;2LaEvL zmpUFJNUC*7-enJ@3$T$+zlqa0Ai+U!-pM@r^Ie?P`R4DtodA+5+-XTH#~M5S#sf=Q z9k6+;qIqF2VN+5sQ1#wmD*5QXY|VdnKP+{Va`h55YnII}E>^UKw{;kTA_X6}WUvxUVPS3(n~BZAaN2y;VO3 zS{CzIRxJqkn33W4R+BAp2Dg7s1?pIOV`|<+AGJkuK>K5uwupIH>L&%mbjHLH&3gBx z#urHQq}w9QtMU^MPRav`oQ zaS6rk+87Ebw`&ZqGm-ms#Y+R4e69PLA!3|Ze&YE~?dih!CCZ|erg`f7?pT18okZ{1 zmGd<;TPhs0G>aGZ9_4T?{nq+g(p1G|n-d-I#`Y00dZ6ZjE2KK%3uu^9`P^?C1WYbP zT_bvyF+ete?I%t&HR?Fssl zxZsiU_67?Lpz~?BB(AJt5fM@k)l9N zqM&rTSXZvMX|n*Kh}LJ{_K$ScKugK1=W_ifK(e+qgQE#rR$z7XnV@OUXW6#N>nfN;@eJtJ$jk4$(tQO@fa5F3Iw)b%F5FJX%au9}ofR%302#(4BDA+E%IHIojx zY2n{N91Q>FD;hR7fsy7mwKUb0dVMy)I~z`90IlQ^i%8&;Nu&w!8~YI1_us$UvCeO6 ztdS;l*?eaCt|(9++s7Umfpg~o>&UDX9~)o(kz8poJJ=lZrk7s+bo#@0n1uub3{wsC zR6f~t{u>cmSR$3g<5d4_iBO8s!d=m@yjR6d-o!jrPVQVo6ksk_?V!)-);S*?KIz>> z_Bic{XJ)OM?3E5bby&S-&RAzd@*#Hs4RV6h&ELfx*8LDf@K&jnx<&lHnvD4_wrS=A z<^e$De7MSzRUS#Qrs=6hnN$V(HOoP6t1OWJrNv7S<6frGlQ8{);Sq#9aXVPk3V1CV!av6 z5;P>o`h@a_V?dZ=;&z3HUH1( z@#l}G+htzFT&{nw>Imkk>ZSxOPQ#69Hd7T!bxYcx5@e8^%eMMKR}C{_BkCvI(k~>_ z%u>kLq>NFUF%un$mhxb67y_d--4Hx%hMe(K2sd}08hqq+!Ma00_({6P|=B<=X0npM< zNEXwUUY6u1d2W%IE?ypZrvCgS=}s*rcXSThBMoyJK{Obft;ecWey73wo+8o2 z`nlak#P3V?p~_mm*0P@t6I(81s!q11w)5~fH#duzWdYJked3@RN&z~7f6tw9D^jJO%Q}56;3Qq7uOTs?9!f)*+OjLd$}rsL;j~73pamn{!5DQzo9`HPFAT0+6v6z$l$3u9 zx}IfWENpn@RB1+nzpwXy>N3PP{PXYLF{CA_Mytm$Li!$(8NXmR|3vW=!i$y^CF+oX zL{8K~+)c3#$aK0!Ng3HRnD=GZRl=`5w{AGfmWKF?XFB`n|W_HAr(zpxkUvwNv% zFRG_@FHhIcSm2swh)YjkVUf}=s=Q-dUwMe*ZXDINxJtj&YNd%R0H27y2XgnzTmRzk z75Wlz3QEj`N`ryuDQO$!{r9!%&1#fx9c{|`PqISlaBJR1;Ho3IXCflO>j8~FR2*n8 z@Oj{F8C#yI9{5vRw&AgcX^PMX5y(rNJwqPtPZ=}S{p(h_B>JY*c7KEhg{Us^1xSKE z91~hRs*){z!O4tw&CBWFrM`8Q&mZPy^n8d(>C)X&HZJG4l}$Qcx3-n953fc3!B-uT zwwIzgt$A4QWLrfv0es+82JnGtY!0|?lQ%NDF$dpI6;-qNU(=4acJV%!()!+LLZD0r zLI)AQc;!pDvR}4fqW!$uCwp`)GUl1+i;Okd(CvKmi->98wkHoYY=+5{3s0WM^=YK8 zxH`eP3F>QuUsN%@G}NR>G^ndJ5yf^mktRdLVOzS+O*!tSf=cs3J3IZ*pPdAb8$s2R z`7Ny6)2Kwyq}>9kt&A#^RS($Th=%`e6F&IxLMkp*5f+(2YXRBpYVdqpSY;W5S)OTX z4}b6wcFaye;F$*8JG6C0JdkvK`E?%|0-PL?Vs$ai=iHH|%!lh!T$H}ui5SyfpVXgd z4uAK)?^*s%xq3lwi7&dZ_)iUEH`8v8{S3-6KL&gK?vJ*g%D#{vfPMQgW*f_d-^Q1BLT5#etgH|JMs9+;+Q$FRBN}_H(X{fGc!i3>%_uQp zAO*m(W<@29-^a9^WNEUmz&n^jCo{3+Fyu*Cnz3qZj;s{Ndm`SGv9 zgRjyhEm7Tb;xyw7J>jXNqIjN;Z8jX1eIh4q78XyKkr<}JNasU0bH}WXHO0s4Rumt7 z>%6`3Z)DrN8UDaFR1(kLxOI}XJbg56%kh}02z(R&HqbejsbVrxCh8f1FJJPn&lW+x z%wI%sD8P4_a!X!D>>)~Zt=?@E4F|E7%*D@F*dMR`yMhKN5ARTgPRe7q^K!iQPnHXu zLB8A!JrLejHp2o;X*UTet#Ty-0=>$ieY8i?D!tCy=oy9-iSreY&Dsjg^PIVdm_nrn zhSrz>oQD7J57-vX8pQreI;Q7!OyFp9H58hn@vaN&X2TBx@@6%_yNZr~!6*B}BDcwbC z>P0WWjV889#Kg~!KUy-olpSDdY@mgeU%Ll+e5g1PW#Sq^50iGgX`9w)`zqyp8T&A0 z)iRrXnmtR(B55ya@1#A^=H#n+e9yY5wli`6NfUU>bHH)evr?y0Se8#;pP_7-t zuJ<+S3VcF6jfs8xOr3^kFky@a*h3uhW=`kQm1StNVJWkgv4y0iI4|@W!MC@coAFiD z9#&0SXh&h71~BUI(6sTNo#U#H{erG!w6X9rSi??8af9%(h$|kh_}SQOtpBBG&THw4 zy@!(SBT*%JZI00~%TH<{b-J&9XUsg&Dz{;QAGQ*n{k2ELMF0iVX~hdE2JNp6Sx7vT zFt{_GicR2c+1YLjmjw|*r{Ps8pVz~bZ4`>t4N>R=&ij1um`wowzO+rSX&6_|<6p~$ zv*JElS97T3wSKogxwUQ3OC7oiJyU-`k&4#y!FumUqmI7{2@6Dvn*HDvPZj>OS(6K| zJjOsvZ&Is%BHlmX#(It~zS|2wAzH{N_nm*I%RJO$jQaBkD2^HFY@^@IBu2ZQUGr={ z!BGA=A(>6V@bZqcda7=$>)J44IsCVuqXt3G7uFvG0OEJ(2UhiY{jO6rD0%a$aFIYa z;*quaGUV;Uo`ILSVsMOGq$mA-#o5x-$ZrTYVL$e!$0!wgW1*ab&+1V~FfJ=XGxPtr zdh56*->`2OMuXC+l;jBMZjg|Y9635ABqv=0(jeX4ARyi05ReiTbkdB5QPS;m@w=b< zec#XfAN;jl+i@Ppw~ljkzW5yzu&a|EyyL!+zZ$$n?$ohyD`ZG9iLe;HR>8?r!aiK^Wl^w7ENSx;v=gRc;q^b9pW!m(mY$<`Ya4@k^Q245p> zVOfzs8H%xvTyHzhv!uCTxA#tGY!Tz(7pOXjo^9`ccq$N5iSrNB8P)>#!{34c z=q(%9E`BurI};skEJ~@kbegR*dZsWFuH3BlLL1|Rs0h16KizNm009>u&U z?#QE#M|taa2Y%r*8>?*vQzLeql^aPnWLEkUkN1tT;}bVbBaYtHO3~K;`Z|n38-C$z5x7t*a}NbZ`r+3u zB&!58RjL#|_2V~)*wpt&4WFuxsO%%HOOs1h?LG377Y)tSHu1Cim3>I{#m;-FPfU~_ z4(-6H{A>xFl)F67mGU_2yqE}amgGCfDGsuzK2-L8bMUWx0I`2Y*h_NnCClE$z8et4 zcNhU3D@vTl1L$T>x!wo?EQUxpk@Q&HsPW5_@aWqauDpTN*K?*C{!AX?YNp)jt4}hV zL4KGQwW@&Yy`mo# zBeXWe0Ldb!-_be7y9Kiy)rMB0w>Kpm5(L4I)cSiC7KuI+6nB`vLj7u3j>cMNZa4v+ z@T%|?Oif6{lmC-mvAg~IV``h9jHEj3)QHC7j-^e?#2MBBS!X+TGLoH*1+w7gZbbtzB`@ET`9pTWPa?=cY-@B2WeC`9?;DXm=# z=Zhd2g9tJSp0w{p@M^hd+KgkJpNAy+nAL|to|1J+gg(wm&Q7C)*`yqEUk^iB#N7vD zffn7c>#k#MuYd!R)$LfN?C;6^tTCL$lhdbt@o4C*M7Y#f(F7lI}?X*!)~wqS}9p&%S_S_IjfkVZGUa-XLdhWD!4g@iRz1~ zq&lV3JWpkR z-Al2i191v7?K?(OQp)!6Pss4L?F~!vs3s5|p!}CWY;jM?T2t}WKSCC?1+YL#|NIeZ zn~8tk9pGm?{SYIwPXr+owv09!TWN;QI^g2e7kG6%-0P25m>?O^o|fEx=tp>oVk2K<4Ypkp)--f zqZ%-Km8a?pjPO!BQsAx)9CI?H>TBt-blz*bO!0*p08NC`+@BoD z#2#|>s=Nzta%Nzl>$(>vC27~7pHv{(c>t%}>iOn4krBg&QSNX8u7GjX4`zw(1xuAX3yPXhg0Wg*-l(@vY&5iHifi*z##lk>Ht5D_J95KW z&vOAp6ZkZXTOktucfb^Mk}~%EWPJT`!wJna$<_=i@o5eJ;rg8{aF@>voyFdO4BQiYQ&Ajt+j`<-6p8K>&V*O1n4t1Y)dg zsvdjr)f>imx+*0MbFzO8Y3dA7iF9hE#r0W9^$7;o-@t4KY+OouXiPq`7tNGDr64@% z(E|;rdiF}>K}_H~15*DT`5n2+FY!wLp#zF5Io#{~!!F8v^*HZWO?I5ur6cAcS8`Uj z10&S51Yd`M=6qFFog6Mo?^*q>M*UZjH7I?N`=vhj%znRnbexOHhs%`j@kh!4V+hcb z2U!+a{6=#Ql1V(07;n?({-JBBBGjz}GzyPj2(u^)`+&p52PR6q30t8TCMhQ0zx+G@ z$JZEp!g{Tr=G8qFYYCZc9XubOY7^c%I81FLp`CU_0jzFpgeB?ZMoJB5rNwTTP`}z9 zE$)zE`UIkWK4vHP&nP?3gyKWjOT{(`j>RnKI{fAOxF8C@qa@EzSe~;>G8$&0;PaAF zw-&CmZP10Du3&lmvEyJl|L!=QGpTwrSO)}*_}M&Q#2;(FR_@TYauTaw9zDOGU%mdL znl6bYgGTJQ@YAOC?Bp)ZT|sMi`2nb5WQp!|`>aZj!sN3O=b^GqV_eC4ltg7Z+uTr1AGi z)jnk+Z;>nzHD*W64t(exTc)T~HX|sDHXC9xS%0l@8Bah|g#~kFM3}4N; z@&y4SI4FoPozBeXv%acGmj;Cq)@gJ$sp|~Vo}^DQsQ6$9MhQ^K{Wg;{Z840hgPqi` z34h1-o;)WUhWUf*r>dH0sh`0+A3r{AI3B+e;ewwEO_O$o!--dPECiz_av8b0yEkWv zwh<|+^txgirb#YBt&;ShmTw=?WIzU-Ur1`89ct;#CS^7+3IkH;(kfrOUQF#U)AF2R zEd6aV^#UfXxn=!8tKcq-y}{FaW+CSI&`7R64$D@bWDh+rvdJhy8576K6OeW!yO#3F z%053YdURREPQm)S!6po@5*hhcx{80;*EMcAdh+8Bk^y<#EeHN2{$7PoucFilC<lm`ae;m1V-Pa;~uhfE*SSq?>5 zjRn0`?&lZ%D5OX8@P1OqqNZCYS>IepOl7>R0V83Fa7rFm?iED~GD8g6BMB{)#nsG< zP%v?R#&^0{ivC&+lBn@P;cH8PHtm0vfY{hUJ{eSsjSWn&eJjAyE9W3b_zh%JjGr04 z-RK40yhEIWDnL|0StKWdU*?7rRFf>BBe=JiV2s}-3#*(z{K(dW8k)0j1)YC?yi;1o zYVh)YPq`l|6twy4+)&@ZK)Gj53K2o(pU+8Vjeb>uFm3}F@BdYOX}=0Q&T1Ijt`YDP z$_@CpqZJa1_Aj&kjQrUSx!%g#dYkhi%*YE=E3&=A7T>noi!j$Pu zLSQ~$bZBVk`QZD>A*_4r2UE2lD%uuQ^G^j zIe>IHDfgad%U0Z|j6F!5OZGTsYy{#@z%CxuQ=arT$4e7W7KNd;$y0Poq*a*ohIWb& zIW~vx4Ft7KTbWbrN1TFTq)|h&i<0bQ7;peLlQIn{>Zv*e0Qmq=d%GH{BLl+df)Z#C z|2vR%A|W^L-N}y*ugEqQ_lEh|LLf8S=AR>$R>XRW;o>E?pAi$GfNEfvuDWI31)#J& zUw|7Ro&jO0m<*6)QO`asu@3T?<)3(^t|)}D2=XTpW2OXa z(b*;`i9NuqwL$f!~itJhO#?b1)*z`cnU zfUT_UkpUb9pr2k1%uj44+Dbr4@zL=v>&gE+SueuG* zG&ULzi$cmWk6BMS(rm)Id%vAf@Z6E);K+WCGFO?UEj(Id>CxZzq;Zb{-amq(^{Al& zH1n4qzdLe}+NSAEDiGUCvPS!^l8%u2YNPQAV1{_C-p6w~QXJZKpXMS5t(>`KMfPrN=XVcgosa|xQD5y zpStR%xtlt6@7ghrn#cvS zo+8-hZ6*+l*&CobiWG(&0;-HN_T?0XC+<1^c0 zexs;BKzVors3K%)y`jq}?x#Cjn}1+MxnyVKr~y09TkgE?$$-dWwubvp{-Yjn`g=a9 z>M(KCDaBN1U2)%d#Q#<9w*I1y>+?*iax6N_qQc;M!wx`-sjqTTj>IJTu+)*a7mmXj zOa1$Z{pH`u(gHymW$mQT&}l6ip#*>s`YJ@l^X5`HH!O)C$5%hyk>`$vkVasAoMAtt z;Vwipc(3jE?pJy`KU0-vhd9m#jB;R7Rl3Uj0czdE)$;~>1>->sF#cw(@jKnHwxK0r z$2o1B7#q~?jBW=s{&d7_{NK6Z$k^u;JYCoK`yq?Tt&%ss(|8Jx#~5;!*IuqzHLR7L zPSX~0{9q#`@fo&$d<88~4IcQ1p6QqW`s;^hJ%5Lv=H6Zd*Kz(?ou3QtYi(^iJ^9vC zCpas461+Ggq3((yiC$=H^8)zL>qK_a_$u0QM__8IcvBp=cu0AY^EfOPTP(ckr!9vW z+q-19laIUhCM5C~r(=n;QzhOV<*bb-Fw;_~w~+q{lM?IuVSn%I2Z)QT1ptSG4&lh9o%P%+*952MCW5Z#n{_;YZvq9YMiN#1 z5A@F_cd2ZC^mdqIqY!lQni`D^|NKd6-c~x~wqxUGY>ji5r$zLR-lJh}@G|e^PFC12 zzoWqU!fx++lH4-}CIG>58$!sX;QftC30IEPr6Pxa*miak+w93SbHwU3Y^4%+E9STl zck836%EbGQoIt^Dg}$*9kEBc)L=fw+0)tRcQ_5-{`5Uv{`n)FhB)6ZN`e@t1&sdjpyCc?Nc4Nk9lgewWBWEimj$}Uzj^P^ zF<9DvsWz6w+S*3i&X=Ktyq&6nVxj*H%cjX#(uxs|hTkPAq~EZa7Tjm?Y+bRW?rLYQ9?(6>`3KeQ~mm^9Y2mD2EP^8G~mZb&c4@=E1e( zOT{1B5g}i4T^D7V?I-6f6xsZ)(Q^uhkcS-$WlFR-QY*%U#r-euCsQ5W?x|<_xaupr zj{sG{5JVM_Kk8yEpqe~|Q?LFzP6g=F^Ts;xQ(QskQ|b{Uwq*oLpg}HLADgAY!cMT$ z4L}1NPS!7VY2FDKSw-W9hsqDg6@`$I|GX~gt3Bd@JEgUUQn^=swyT5BWl$P~{KYz) z`^&UeUi0_(Enoe3Do^U)CNTN~5+b_Lit9x8<2S0^is2JY`)6|0b=)3EappeM=vl-eVhn zHZ$mD_dvR{vIqDmLWTeOb-`4cF3&$qEN~goy1bS(QcS8Qamtt)=aCfRFb1V_f zKYS`;kjCf7p7wndEQ;10bBxN6f!e&_p3Klt-zFU538)^_hUrB{{q7`u5%x?j84b6v zZPN2o$qOP#*H)sSvp3>DEM2LtGqmAKD9;FU@}{Mp>+4oh$nZCwM$y=?_3#{`R1~OUDX2 zuKSzF8isV$hshc_+f4}rjZ;)?Z=aKy_o{Uz zV`KBVc}gaC$G11LN%T9CDH(vVr^yK+fMrw-@&O#6(fRn%49hxtByNbdnA}Rz^C2jI zNPOTbj3*VlhP1}&17%ZT$0HT$#3lwl+CS1~Rg@-fO}>ycL&&A*QO?xHulspmQzgE| zmttAHxZ|LX4`Sk$D^7gbfNQ9D=jr8xAVloOa4LpD9zUjC%3pm2uCHiMuyMuI=h0SBp^+d?R>(9o`TZ+kvd$KYnd^(uN1XP4-cv$VTu8hJ~T8Rzwum zZcC&hpp4Bf1|2Jj)r)dH#53e)7etL}sbbyVa5IKCce;sS9U}U4Cv=Mjw$@%sDy-Md z3Y*+^4*I9<0QneTbMc|U8dXM&a#SK5RT~F+vA!8p`Ir&rh{_xI=Z|}v1A1|KT2sRS zAB^TbAJj67?GF)yWEszsK!y!gh&eXpHSN77!M}_}zs33~7f7Qb4r^*4Q8}%c?uv~i z3498NQfGbsibZ_E8fj5z|8ap!y^s@3M%2ziq%6(EyY{A_&V@H~rCvl6i#Gk;~Y3w{t@PTM3(b@NFO?^h)Z(@yj+jbC## z19C)gK&EL|z=m}V---V2NbAP0F0*CQL?_WCrUm`b_p4p+W~A`jv&yAkzfm3Zr{6V& z2Y}c?{bO^(3L(h_qQK*~Yi6{=@$#9Dj&hXWVB7oUSGTL-Gh;nD4@^P)4<1XVTjnbu z05rWh_}PF^1lF4rhCk^ND)uD*n*|8!1oVcux13fChBVJU^>f9i{hlRSE;@5oB|CZo zj{^q2fdo7*;plij_-bP9QrzuYVX^tshg9t`l0?kk=maE`LLZrv50G)lh=MXTa^J^d ztdt*Gf&`bU*PiY#yCoA2kCcLVCA#^F1&1=Tg@H@wj>uL5O_Ew~J>^Is+5TtZzWwLr zS%Z35v5f;SN&4iBe~Tnp50pxg#gzHKJJtu+r-PVF(P^@Wq!|o+`#2f5?47lEC)KuD z3_FRC@GOhqEm*-4m>i)-a-ML#0r39^j%=GxIxJa3s==peding*k`BlVBjrfKz|9b# zBxe}s5M*u*Eh8KkLWuUhYlYDT%|PPl9e#)|(hspweuci&@-5@rLwK)+T;OxqYy1)P zr|w3W8l#HOKt(+!?I_bR;hG79|57?xT=9^;0H3#ua4P5=uhxJ3F;zBS?<*f3M=K_69%AC+S;##)H`sBrU~Kd! z62&6H1rUcd&vwpmMO=s7Q7uDB*1o`h5y4a&<`lt38=2x}#x}}zgdQuTBnkuSV8h`t z7HLG9_ki*X!4Zt|0ZCkStlgX(Bky@zKQ2?ht{Nb&$R@i&w{i{0l9R&)#T~)1?&cG` zkl8=HhCqZ*nc^F{mF^6$de66MQ;mk{d;(M7DUynbvvG`va6s15R{*)yGM$-xsz_!) zGsO6ZZa)M%ju>h5?`b=TVu@Fz-T^a{6QcJO_?f@k0BZ-M6UU>0M5#Jg5a+NwE;Bn6~n5g0a6{i^7j;lL`iH|$y3 zcT;U;yEV$h|4+nDYWij)?f1dwtbtLn_@snPJ9CxY$L~Du`UVz9t=~49_5tJjDS*g~ z$pDwzBZ~`;3#~V8FR<8DoA=ey1z=TfuJ~6EG29Kyi11L7mbbEj?~i)GTtH~WPRWCx zt4^Ku?pv^2|8JuKTir-p#_GDddxC576NJlMcIBIvPNfxcicRvp39RhCSr$5_m>G$7 zbUj)zPeAP6+ca4=xa=HYNwX7!J~3jT>O;`_ z01V|8@L)ptbLDba2^{44FM7NnGc3*HIx0$C59Kb5{c(?r3a@~Ja__;qkS9oc33Ck#>Kc?nQ<2flZd=zPd7 z6olLiZ*pgGjvhNnmzG6z$N}%6RB-l}t(+z8k!XY0LvymvCuJ)I;tMYgvx)XN;Yx2O z9S~Sl&LJZke366NgfDE6iia3ss@VeUrpS|E(n3>*^Mna86=B`k6t^H zb>N+H=FLGK<6~o@a?WDREp$Y6Q;VEfsQ}}lt@DjHOl=^u{X{D4*mKaIt*o|+G9G25 z6CBA$ilm2K`9ZRKQW9IcolE`5|NoF9dr|`#VP46zoP_m9GSy;mu+{%PJ_LiIRI6_p z`jf8OhMNdo@^U51<^FD8b56p`o!WK84yaN|ph{`@OU-XCpTwY1F@1q#L4?iyH@Ga! z{zL!IY4HP1X$kc<_$<*@Kn=K3J8;3orjl|Zu02|px9Ntcx2)yyN*p+^Ft3ZG-hTp8 zH2Hvxi2-=C*ss4);YNF&g^qLz%xfL|GzI{Bs}Ygzh6T7k4tw2U$EX%4C*#oE$BEP)tI@)Q14&FEiWSJFf%XDPF#w;Y~Mp z7_&?Ef9_kGe3!yUx&bCp#u!Ay@l`=`sQ9VT6*!&$ZFmSD)2ke$i*PCi68)*KBh~@m zZU8p_7Hl{hPkKS;9zlW=WfGC}n1M3XHgse=6tO5~aILkSz~FyUX)Zv*%QSa)I~Xwf(da!RzyC*1 z4S8Y|XZ)PW2UEwaR^6$2mX*am{C<{JSR@s8R5p-GC}p)A>hBD2^uNOV^=8kk1JYDT zC|{!cC_Ok3-*8)G>pi5k=b>`n$5$b2fRp_o2;o+C@nP8SX_>j4C~eA ziN>mGnI*C4#CI2h>wrhlB{3!kYHPTaj5fn7&jaH#{ZD9iq5Kb0(gnW^B>Ix)(+ksQ zOxf!PQ0HP9ARr>l)eaiLkWISk{D$fe$mUej2T~;KH#5w8O`kXBvvUwYyi2LPd_tQQ zbc%JK#l4vmD8>dMK?JMXwZM%=tV%coKn#pCrQBpzK=Ek7Uhh9y2028_F5q6(28m_S=TwmriiKNxDgLKjiK+C&~@_wAch=8iLs=7_6)bQWmuk3sa2 zJgmM?faW2LynrqgJ6@eFg<7Too(F9L0J=IEaYybGyn53BLIu3Y7s;MH?j%Je6CSyj znr&`6JBbPJ?Gtg-Uf=j*!ZbCxy8z?k*N-zGx5z#=2e{igF+D(-juU=cWl{g_%k>pE zV8F~EpOMJ$hBkJ(+j18InR2mD0+b)JAN<^`B|v$p82_fW{YFzwgAwg^xSc@u&{eCY zKM?ZMss*g_!@qA{b@6?pMnriDcP`4I9MNE&+rZgiV6ogs8}_0TT#4R|#uYZ7liOJ; zs5R5{T(<$sS=2onUl!*+gPSc+y(1D0+eyx#Ea@`hjGPc`VC!N0o@>Lw0v@4`V zc$b<@Sx*J{+n=S*!QQk!o|Jk5c9IqH3QzfCf};kmw|dBP2WMaA5e%K_MVwd%SF2sj zNq?S*AoNbdp)fJYp~)S$sPr^8MI-^&Nc-UiS&~z<(%$$QkCi2 zyxP@Y8$WC%H0BffS&ra{{L>?3;hPk@6Sl86OKifq(|yEYp0NXO2Gn#Y#m4qKy;1Ot zvVyc*8Zq(?F(6~q^R1;(gNhYR0q+iL3@dSvY%6acMUow<4HE@zRMtVvzYE#ELMU+*AVEnM@wD9vulgMt3Tw zVwJm!OwbD;EKH_YrR%$_^C~f8)XUsqF3*LW^y6D9vQad|O-{?Y*V6qDU8t`N}vMRm#2o9g))2 zs~W_5TGj`@*@|su_}(B)p-u2enVRZkoB((Wa<-H(hYJtE9T0KTszW)HEfb1T)ZY_?~9vurV}3pcAnfLAhfI>(Gy2JaS8W z$vq$~y;1dB`2?JZ(^r2~fXiD-TlbKi+nsK;a8e$Vg=Q{(oOhY$1TqXwkxHCw)##079<>K#5)tXo7if()5mtCwrOy??%g_xQ(mlpmJoi zXAy&|iXiR5!_JGj!(J?qdDKAnDc);<&q9Jbr%@X7DRm{7avcWjRY#%V=~6pSm5Ph` zJpIq-x+~t6;&8}=hRUQ~(elp(FCHTiqwEebR>Jb13)kJH(qS;AUF@`CbK002Ex{%n ze-^w#3}G`!A1wtwau|@*!$}(k2@F5X9~%>3{##irIDWyfakCr@O1wz?L7i zA#0)ep*|${v+1u-hfS+dj+HU)%DdNt=_TAnq1}Ki#@cWK171!`{~6n-njvIbpdW-c z7XY%s{W$MrGQ)ehv)+?lYp!^vc}9kyXO=goGG<}|Mm|_jF}nfo(L#6y`QITbDfmd} z|B+V&)4SPo9%51n3z{hChw8>q?qdnPdi)`n+lpP9o{e48z<(dL3574+zJit0s_d7;h{P1K9)>V^ro_W03i7=xOI*qiU32ax^{aSM6T4 z*PY&=umpZoZ79y5N1YcPPxTYt@!qd#9E1xWkH}z`4imhx`R0|9RBYlYzfGfu@uB+P zzfd7Nc${-p_*ZlaX6ODr4GYF~bND;BO|l7qhmBwU*2{ehEbzPHjsgmTmoq4+xauXz z*lt+RWiCPofOoe^Ftw~n{NKBeMv!cf0@6&qQXu?<$d<4Hl8dndI+iK8Bh^1~HaK9u z1F9)T7aUrfH`-lG6=u&?g)A9XG${^7_Gu!cMfUC69~o4A9hrSTdys~PJA5V=#*WF8 zfW0m{JLlv4u2sS$qBg7)YxfHhUf_KoOO6=APXMf`p1<>bJv=nS5`<)WW*QGOv<|_l za(6tVj9O$>(3#<7x8D!nR@G;v-TJ5B0ZroqQh|RZba?>WfEsY3;Hf?yr~RM&C<7{u z&*Fb(ya$F_BqxH1d(+`cV1^%By9|1zZ-qZ5Kj6T`{npH$3RgJY?l=)aqq)_>rI@!1 z@58NybP#1)LPG7N?TRdOEuod{>ABUT(_eOKgJQ2xM~ zK}QBa?=WYx%t{5kUQv!)Zi~cKmjv8&uul}_&dMJ}zvjDnPK;y1PmE`4wIiD=_z<-h z9zi%(ujd=Zi~4K-)IBw0EzyaNSiA1S7k%%1hQgrViV`VgRuac4uGS(s=}81suFYD& zybXLLgylY>es3R1 zQ37?tc;C&Q_dONT`FNvYo=edGra$sw>CY<)L9#h7Tm%@^0YK{liUJltU_mZpka_q3 z7JGqy54S$f!$X>`E_3JnH zlNazQ*s?vyAMM?enerPOn=uX`U3*zye+07xA2F;1d-#1S$#OXUTOz!y+3+)22I)fa z4I2nl>m$PgUn#a^(NEjZc2NCMiaa#HE}KJT`H$6>VX{>AcYIPXt52XDcMItLN5{dX z=dh2L7wJyNr;$DzT+A)p#JCkvb0$I3C-^a%*V{*bF|Ff3zbKDIJMvfrelG{|Eztil zF?lAHj8e)7Fm;OgbrVLFdm9+^4Rdw{reTgZA{^ma+d=!md0GbuA@F`GQ?$tJ3Gks% zpgFowE!yAzHoeu*ntIK(G1zy=~hYl3E?btWp8DSEDI#KRy| zm{X+q4euI5kkwZYaD^Tn(g2cCJ?O*9u4Ybtbt1q4z^LEjN*&)k#GaWti>2`(Kt34L zkWOssN4IsKvQYs|WffFR9(V6J8>){J#;pB1y7$v~et(X^d>Xb2vQkPN&!k|BCPsUY z!9XCjs4LWL&BS#qZk)|CUF%)8_KEmqS;nKFS>U6~uZdW@B`D`H;hydxdS1~5iVMS?gs}RORvL3o%leBI{$I2J(`uu5)?!@x#$V5gO4kq4 zZsdYlV=&n}^#o!<84`Ciba?cTHJ`&fg=nXrVs|X$Oh)2IQ67Jv!(RHVg4>aQN?HcxvetDAC#ysjo%*4+B`Cz@n$HUeT;pa zoz?5?PN-j64>EyUj& z*c7-5;nt(t4#vVt15Jln;cMYd%&iI_YU;NNX6|ndYDq|PL$PpAc11}J$CY*~40j3= z2loeFm)ySD7QB_PNO7HZf@R(_gxtHSmKG9WDqu}Y&0KE<9DdncqNPdglDsVeYi-P# z{hZ)-&d&@}(&RxZHkonIeOZ zfFS|S<5fz_99%<)#=3vQ!3V{fGcFz|6C6PyL!7lwW}l9;zHI&l$mDs49sGa}u;5gH z^YC5djc^x!Ajn9bGyS@zpf~{K=wH3HYn0lDY3z{4>{x4>-|oL`Ml~ItzuyG*(dvgv z^f~ejXwq_)_9W>lMqpVT(B}#-k-{roz(ICsGt+M;?@<&tj9kPDR`kraCmo|QN%~6g zYa9LNL`Vt|@@1_T355*B23Dp*InFJ6^)1VtY-a0qiVXKS1+19xFUqO1G++38N&sX%eA{kKhDAme$)j1SCa-C zKrWi*S64elM`j(c!7*xRALmg$9)m9>J`=LQk+{1|yJtH%@jTUR&`sZGJy+YTaXXR=E{6YNl7fC$6l2)xj9PmF zXYJazNS*Q^aVkN_JJmHRBum^0TscxCv6%Q}bvs=Hi@=a2d-kX&;uz)FIB_CTPdQDw zOWZ$5s>!pp)ACBBYS1H{%+3$B|AIfr(6WK96$SpBJw&QynCBX6|B9vacvK>S6(pRH zz?~;(yrgCrGV8JnTAZ>N2nXR*I1PAbwQzCivCorQ)kWG|KXUKE)dUxIxR*0S>v+6M zhdetGe`$cdBpG$J_0FH1(w}CLBr4QZcx)={qhm{ZA^zzHJ7hdMNL@?zh^Sv1!-3tV zd53WRMNQxAEk3D#dJ_c*9?}&P^>3xZ-bN7%GK(2F<%N33s*6PweNSu1rJ{ zgSpJ=v0}~wG08ziq2aM9+Q`}~BMl(ncAUVi6x};m=GFyX_MBcLs_L#51f`q6H|Kv=y*r^u^tl&)j zLU<{l$j-Di*l`!|Tr?Jg0++g92B?TtoG4|N?OS{R3BB={ogRf!`yV+x7OUmNIUsyqAooY3>DmSC5FsxwX)W8eNIxy0 zG=f&NN*0=53ksST1aZ_tfM0i|SO2wr2@?V@a@pp{BeUpQO0qUar)uz9)KIXbl#)q%L z5A9Q1qw>9VSJ96tNl-gFSg|Fnmor?TQvmFBeLQLgpavc|tlBM!wnGr{;&@$Jx6Tga zVX31-GIAanfr&PjKlgd4T&@|HC?Kf4lRsPW+9(jZZ%4aB`gp84T|Rq{B^8taPExV% z^7Yq9+SwMLu00*+TwsXVp^)DHxB2%tSplnvj+F%s>PTsq)FylJITiR%Xm-=|1wm(j zrN`SLI`pd!0kH6oA}Gz{u|_O7F<=T;V|=49l5!+wP_*t6qn$2PUX{T9)zcA1_ION_ zGp`uF6OR4Y@wLVUx^HusMR6W(sOK+WCnl{jtnEe0UsqE!gTKsTCD4WM1M0}Ef~A`u zz@giD^pqpnO`nx??FmIN2b|%(%w&2mKT%7I8j%J|6nP;|Pw4T@_2h*5^JRN~d6tUG z=q5Y+#@lADDK4`j4AS6NhE_ELigLgO11C?Q^vBoM0=a3wYW_`P7wCwkOjU4!wQKmy zR^m#a`a0Y`{?zsjxdyd&fsa4pymi{LQo6JkVkBxkF>1gE$|bBHjk#3bZxZGElY@L3 zuLK&!hmDkhT`A44Mk2F#$i!aBlk-$P8k;CMf10>+p?yE6qe&8mO?BTO0PeqCz!?1{ zE`rwGcG41on`wZ#o>4HI`O0-yM}v{(rW;oacSek`@pu~8U|QRYp&>Z?5Rr5R3MYRf zcbV$wc^Lcs;~3Z38Ew91sS>cer2?te|Dqpo}kEHj2wjXef!0N-6t>Aw1=(?9v}>`+}$ zAlY_Q(<7^bhM4Y$Q81yBAE2v;7K~Szf9rHy@)T+g>dQt!_PU*wHMTlNyFjjoIUy-v z>kAh!pRs^p5b))`gL|dRi%+3^1)d29ZDX&*;a=R3-hK>BxvjLLNXgjO*Y*(SHQ~Of zD4wz)fNDx^kylsKQS1ltD6L+9=+aQ0i=We%`M5k0{9F&WNoN##_LzP`r*2m#p7~0= ztCe2q0nBl~3HZU>?FbgabE6GP@epcIYPPp2xk0IZsfKG0C>6|KaEp*DG8-8-2 zcS`tSC<*5T>4xo!y9w)zHfiD@V*2j|lYY6V1Yzdu+}FkUoMS;hti`+cz2F{q&&K}! zsQCjNZvw=+iTux$&bg2k#^JUa6%V0N9sQ}~8WkjEV;TEs=XWOQ->RQNB%I#4Xc^aC zBi>k5bz~MXJt^#L|J_F`{ zhBiH=7;O~ri$-HVHO{GGQ0@9xWPI942g%L_>v8|{zK3Fc|6D5Gow1OW+UKdzhX%AH z1t+5*=1NyhMKFeTfpUk*?Sd)4{L&ftHqY~QI%UwR=fzu*zcHSBz;-Tr@DEcDyHqQs znUAh37?$k@vOJbI4W?<{J2~h|qL#9O}n1yRf+0KS$ zo-Fn`>zlD>FIdc+5WcsOhm;Z*#ZDq_R@zKh+cq{5U4c6|Osv3VY~Rq+H(FYXE%&9g)NP zYVv3&EfuWin52Pr=mgmWCB+mDa)uu}sJ}ez({2rZjx7mEk?t@FivG{I>7RS}(3<}KjCbcfnpKMZ zR2(drKfQV z+?Mkt;Q_4|X_~pdgpR#=?x`KO{m{JQ@4xf#nw~xRfc0ESFz8c5S0DmnPKDHkWHd-8 z`wV*IKeRVy54!0X`#5xRwI_Eyw6V?}U2B9RfKEl!ZdfS)Icc!?z`tI@=bsrXJO3~SFN%aghBejS2qqs2;)VulSR>WLV<5Xipe zqf?)Z`A2s|#tPH!uI;s(7#7k$wo{AP9$4P2_ zdoW35U$>ET0EmOZmqt&8$sltup%V_tqkOTpR>G&ey?!cRJ7##L}(Qwr)k4X zu%(gFZqmkU_A#6cPvpCRzr2TDtJndri@mZ0sd#lYF)zm+(`YsO{M`guac5_?jeQ{x z?`g~70lpzh50}05I+<%M=#}8~IKa`&hXC`r!WrmHrSLd!Zk{AuZl9-@_8Zwv;$(M< ztJheNO|+5f$|4wNHF*ou)^){K65lyi@hFsw$r*)|Fm(ScwIz3$SC2L54Ot(?QjVV% zoaV=kIsN))&s=IsF?ma>{in;(UI7gJ)Q+hE+_4-F83e6Rj@$TAFf7okc0nFxy&|Q< zR_3oacXLaY{!r zeFY|3#0So)I6kAaHLkb~Z1tDE%q=gIV6+7|!%g84nBUh~GHV5;(~dlPTU1{meJ(Sh&pnL_-h(z}QPSxam zMRKI_%EFNX-2qID=J?6jlyElK|H($UK~l9`xMS@#(L09BAbfmZ7l8WArX~V4?C&8C ziD*Y(fV&d7f?Sp+nn8~T-WjLb!nCd@sC+b2t{;Rn0mkJdY`Zj~^Iz+IsH%ztB4V5h zQ5R(S4&-{n`wPkAF`R15A(q0y0!|Hi--z}5pEI5fGLg>qU%d4tuJ-`A=Guczt0%5Q zdFKBJFkODaE8NyUXhWx{>_qsy{s{CT(rXs;gXKR1^y4D>GBW$iqFt#Qh zjd3>E%ohCIF!^9K{|{Mj85LI(Y=Pn-Bsc{3;O+z`!QCx5 zfg!lNyAHu!g1fs12m}v0xWfc@3-%6Q?p=4i_txSsbNck@uG+P0S5?r=hS56tIyt6f z9`Ptt3+Ow4!QS=2wJ?+LRKz?LY&3xP5YOT8|>~NEoi8s-3TJs44#|vu`{c)M`|cF@Ufg z4M2I}FERRq#Cls~u3l1vFt9s`<$}@V$cBKB;vdZy zVnakmISvkgsp`f^>Vwsk!}-Tx7+T=m3J$dCSy{;tFQ2m5Vms;vzy1iWwt%jPJe{0( z3hOq~s6ARQ)KR-Gn5E1Xx37G*>%4kD=nz`izA~;`KO!>-p1*Z&$II<3Y-n({1vN$W zU!sH(n%WEXt_I@rjz9l^f|I_ z?%X+&PYzcFVmnN4TpuBDBz8+ko-^r)hJR^FCz^Xh8w=);Y7VPHUBisVzUN$Oy`-Z{<;O7J5g`REq**~yemv@T5Mb! z@bmQS_yUX#k;HE53=xN;4##v~hG7d@pMEJapZ=-BG<^*> zpu8-aRER&{=S#lZsz(?!$FFO8NeeKHRP3FfjgiXyhWGjL34W)nK|0Tb57{*+#N zdysHf@pgm~-7tA_E8I4O9OiRb4oF0ZuoNoDo|uSqi`>Uk*-ddM^_<4I58F?=R-c4D zcK6GxZQY+ANmlz_8YaOfC;l?oXbDxe#RYnV!QT1M`~^Ormbx~~gQ@?>!eo6R1@GZcit|4iK$zF ztxF%ksl6vk|tUP)&Zy|=|cva$TNu`LP`0JL=h9!CwVnIrC}XUov2^aNMHV7O-Fk{p>#6Ij zKZjjhtACEqGMw%;#8r-!H#EtOBe@bSbThMG)VMo+-NDjmwoP@N#t+JQoqN@fBz$%AHfB16yZ+0P*`{hfT97pt; z!Hk&b8~%5uj{0(&xsA>=G%si2m7J`5iF4~a^5yTR@pkCGnGwR2>{%@Kwa9B(xZgk= zlTupI`0OSJS_e6eD@C1tOIGEbQ0L1FlApDmUCj_+u!V(^7yC|G)ghz`?PzV4eKHMV zFLmF|=&-XSe6a6jA$8<3Bc-*ur?8W-ErK$lzq8c2=zu0O=wOnQwNTx;E#@T?nw;Zi zMkukw!|&-ka$`eg^>{J&++>Q3spX(9c}QCRt< zMey^hhb~I;o5J?TD#FQKu-np!z(wY`?b7)(x7FNX&03Xj4j7;Re%X6w0g^9dW0(&n zwK}=4vV~;1J9^}}T(%wl5t>PQ^P{T6AiJw+xRX+kvr?0FTzqmvFS&H9Us%9NYe`%} zDkADwxclm+ve??1Rcy-hzUp#qb{=qB1z|CXr_v?5N+0jidU2C}o;$WJqUqt|9yEI=tV6l2pvJM6-cu9*&`>a#Pfm(BkWjuGhxE+$V93}r zP<~aK>~^5kLdncSGv%!9uyAYSZGbSkQfB4w*BjRF@s0BArO(Bq&+L!}i@c-+*8~lK z+O>bbUS6J$YMl-M;ncaNtgi1|uoZ+~^XWJ!)GNb)_DUONkuvAzZA<8bm+k=^!HkTw z!{^S;IV?7;2yR?%dY)3cwG;hC`REQfKI1l2g-F3 zB(y#g*ZaH;#aAT}RX8J~2t+@Ofj))COZ`Dp!J^$iaA0CO$yA>hfK+d#^7qr~v5b}v zD@RJ@v-%e6C!z|@lzxhC_d>It^L9%VJ!x})DeGzbV%>1umey+X@&EQpoPZ6=k2{c- ztm^CU8`}qsyH4s!I(?VC&|Ng8jzC*hL;%>^NEJp&gmLpCQEK`VvsF;pb-j>gwMawi z+JIo8MRp=1XtUIWNeIB-tR@9nKCbWUj0HVG?&pg{v}_vd;yHZ|X(boyOTEmU$_^bx&xlcw~Jx{Ow#gmVMn!N+ zm(RydkTgEvSbrJdndZeIgt-m&?IcwoWlSr7l(^;ocsCkxuJ`hNt`3l)B^YVkGOJ2% z_rP(1@cEKz7M3hbAXJ+I1#Mu31vbD&)hnp>V(!BdhyCazQ+y&6{FVdP9v*90+P^*~wOyo9pYs_(xG;{au-#_b!<8cAey&2t^nTJin`2FbCS_D3 z2l5@TA5t34z5t0a47|IQ9Zz}k&Yn}C(YmPiu)beb-pCOqxXLE$V6bqs&!wB z>&eVZM>r$1&TRC!VX~wP88j8tA6=9?f1`SkNwSa-eTo}z0=BnjG`9j}@KQtTjxZT0 z9w-5>Y%_R^9AeCcCIz35C`p_6i16*leO0kVF2opUb;?e%NJFopNn^`bL?k{x66Jpm zjx~g{3d7}~T~WAky6t3;=%VpWK7RRa>qgNH`E}W9cy^!9Lwd~1W*Dz%jo$X+I}p@s z;-enEeQ$r4g91oEdcKbrGeKUlEThKZb%KQqTOX0|l4i?ZvXfpUQGjD8vnjTFU#T`< ztVK2SsZhhy2(E~HRQiUj{6A<}m?zJe!*npc&;(rOi53=g0ko8`va8=fFtl*sF282~ zkI7V_j1H(Y3~O7*o{v69>9sVt69Hk;Z@q-2w8%Wi(#O-4_tA%^u*IUluRn_ zSY}_j=*SA_t$_n5a707Rb@%GGr0iu+h{H;`%m=a-u9f`vNa!>b!*n^PKb@PFG$N|vo{(aSPU`Zs%_p`pSVY&d&EW&=&b19DD$ zRk3-QNXw~n1D&(bHAtE_SrhGl*-XBE4N03U-^rdyICy_^Tmwwwq?Y9(G#A9v(Mnj4 zYFeMNeVX+yjdIOGXo^L3EW8rQaLrcO$QG|)2+dU2cF64;;+yb#w2jK7gYCzZ>E>=U zM$%(6GOwBno%6Dey4#rJ{$s8Okc@=#E-WXktZAFlM}lIsEoDW-Dws_B#;z*mpqd$t z>{NXwtEp=*;5vh?Zbq4bzSg^)Z!jf_Kj=K?;DvV=hkb^BB19doo?dW$Nj|5pZbQF)!2a@ye~AZJe;2?yfMdDou=9SN zmq5-^4^`Uq-Z%?|y*G;Pkq%LTqlNJ*;?XHqhSIs9loK0Yjlz^WJw7l12^qM0m~Og_ zNR!fG3qJ=T!^9;Ymat@{_-DYl*vq4w{&2zx8@TI?n`>XUqI-;HzQZ0J&c- zY#(``r|AP49?)r5R6RAu-e*VLLje0x?EJ>FK5jCdP$qzbbRPaz+K6CSRZF|BHM_8t zC;kNumai1_&mguLiox2Uc$ZSrDP6xTo_HFHqp6NWow)0Ig4o3e2(}id)PRj|2l5hl zxG!{bG^93l)GE!Fg2i;k`28^5x_vxUku0x5GmJlxUrKvcMHRDmL?1}@o%1K}Hh2sL1}`^Gx$#4-eUt*sP#;@;$5M_p8e{VfP!P;r+|>BFvM?tQuxT0Dsbn?7N!uXZjQKwA98{<;DHuHJz!9 z;yoWJ(43q^=G{1s+1_aG7uz9R(`cD|Z~~S?C%oB>g)+^RxoGQQo|H4B2yPXwss#BL z^PVLy7DP?MLp|{fU>UXl*%@vCy`goGq7FL)V1@+1K3xIr?0Q(ySSjpPY?ARZ;mJGW zkk=KCA+vNY!X-;~1guE_MmAespwX+OMs9{XX*Fz6mscq6HYT$Q{HqC zDCsK@e_y3l=IFphcYg!C0u#>k8^ouUpJqAjG%`MfOZq6*Rc~e4^le^FO`CnAL5#f^ z7hPWm_~-i&z>pP_g|(zJ@zb-IVt|p5zGa3zqx3R3Byf}W57y&iZ|leQjawE*x!Cva z*wI1DIqHWt&aDaAvA}zV0h~Tw_PJV&>cK#yMGSOg4m%eK?w*0DWuyM2TcXbf#M!(? z^*x--KRMkTJvi15a)A`cr!biaK#0?)@$P-(JU6x+d zG-pzfc@k(@0rI)#5puNYZRALYo|J&c03~Hj%Aq!#h>zI~PQIqmc>MCfSSpOC375O! z7x|POQc{$v)%-JFYUa4edg=FG)X7|Vd993>7#}*t!2Gx0n5s8q(tr8bMeweyLi5p% z+rA`2*L7N9&Y#b~sCtIx0B0XTlfL3wYy~jmmAk4ph2SGYSP>-Bb8ZK*yDvH?E_x)d ze_q-Ks7%60nf3X0zZ~Rty^3Blf5Q+R#XuqknxPDX!MSXpftD!emhwO(8+dz|<8u@U zW#%@$bZpnO2R}gsST;4ONSV{XtwBXAtNpT+T0hh8``GcItVU|PW=N*cX{gj zkq&SrCjc+VB{F}j3aV}36Q4&d(0f%@AEGhedmHG~K7`78fNin@i z8vVMpBYwP;Wut{O;G9*8K3j+B%((#|;)3e<9V33bhiaM1GeNHL`M`*Xn`605AdsaDLvx3<1-1#-$U-$XW+ln3nxJ z1=gMOb~=hUw;zThKBr)3{i14hW;X=R-5iu*~_Pt)-}~>%XWaxq;#2SJ%Q5wUb0RD#fElaEkSIW z+-TY~=Lh_q55d$Z+!+TtmOss7*ahky3&b4_mS539C8Ep>>=2WzfWs;oj5o#I?fxP` zT)&CtEb-oP7{-VGl`6uf#&b3h}Pn@S6C~`l|WYl1vQ#r+W+)2vWY1*xM>0yVkS#yEhSd4qmbYvp19*pl&jRwY|77hzYRb41Q@QH(AQ#+nA|QEL*fNt-T9RWPYD5YL zbbBtb@PJe@!S%c4V>&W=k?=jQCyA00P#V?MGE~TGe1H=T6x5bTd59S&0p%B^7rgb9 zkdr^x)P*CBJw7?*>MexYiP9Lu%?PURtME!4^U=GMNfTWR2B$Tq%bk^S>?2T8;6fPG z86IAe(Virq`LhfQgCdE+DcjDm4#SNxtDOI$3Z~rPTOcUK;V;iDu+; zC#E_J02G9cM7ih^rX~$abc-XDSy*0uIar)~Atm(jA)V=oZnG51Kw`~LegWLHHL}Ky==;~72jtAmHa!WN_qz5p_@^8I+lO=O!9~aGL83+@ zUq0*Gh4jRztb>_Y-T^LdSG}_AeP8VQ7WUX>{coC>&W?ix0Xub-0B#F0bDc}u;QWkg z&k4hW+W*1sscn}IVC2Jsv1;Cb>Fm=0y0}P_)_UH+Vcb%RpcD9RSqK@RQ`MsEz(@U+ z=-dD_T%zFwu7bXiri8LDz^L04TE6n0bim*1rE?&lLK`elyv^{}l6jY-7gDpRP-8v! z-eYa4L}9T6z?z)ut(flY8>d-%rOm(fH!M2|H>8Bg`bGez9oT+s=8*`L2OK^<j~*%{`^4HiZ56KfwabcsF0}s36C}}L2Z;Q=UdQvZx&Uk$mcCb|dw5{g;+kPh&86kTE^3_VdIVee zeTUTe6Suh~KwmEz9IueUXSBL7^~XhUZ^rz?qy`G_?ag|2*Ef4h8>=({CUh-xs{T5nsEKdLb>R=p>pP7n^)rX z0@r^O)^|%Gnc!k?mRCvtV!)R)O??Q}|Cnl69N3s1tM|o*GxQZ$+HtJ7_X?0k{r&oq z@F+V{Rx%F~ExRc7J!O~MSOz=*iCI@~4F!LFb0wVBivwRh>#)y6US8Uoz(tyhR5U8a=8FU8sI^46Gste+#C((_3lMwx94#{)vs%4x;MX^uI< zgRt3`#OKnQMV0-T7bflG01v;&)U0ve&*_a;xqaiu7_y?JGq{(88I5*` zJ)pLH(*dTPejyO6a!yK5h2nFlov_imhi-a{vNQl9U>Vh0CFwQF7Qz5rJ6r~0_E-As z)`XFSe^iH+yy5I#fp~##cV+KU4+aq>%0{X$`t4Ya+2QK6{6Vy(&^T^3Zb||G8tb@1 zUT$6ANA|~zo?75&&;Nz~(svBxr3F^S)glhHacbFX5mg)~|D z7{|DPK_m+4Hfk2_PM)vojSA9LA)&t7W}Dh~ELfITp$zI9r{%*Dz$l6NIvKzj9dU&B zakW1D;ag|yVOz&eOp>l+37Oc4=;8-*HmuJ4^q4Ptg7BOF#G{$=NJ(#c0b76;ln48v zbI|7JrTKdKBuvfDuCrcywrMhH*8U<-6yBC~Kj{ zc$ztf`Ra}~WVQ=oEzP5?W79=@frc2u`d#oC*%XAd4Y0I(3T9^e6+#iyDpjxp*7~*i z=+T6GRsV~kfx`?&NDqK&Xfv?Ld5_H`D`VS4YrL{KyKwvN1IPXfnYzUT z_YRzh1AL7x^vqWkuuti9n@s>rh-!}83H|L&B8^Ggz>w{MGL-ZUz<4i3W7hrk>?_lS z1>$>fD^w~y{3_$6faH+_SG`G&8f*79eZH{R$-i%wQ0sdw2VKH6?n`mXIQ{>}-1-Zt z{fC;lS}%*JDzXWTTn?}&l;v}9-5FjKa2KCby^{#DF2cIHWozcAHA1eK+6ICNV9LegMs-MPBn!ClW}AOsM;;x{m@i|Zzu@PH|-01VglY-@BG zutX;zo8nx5JJ_5S2`2eZ+CVg``p+1<;74#U#I4(7BHSuV&-sYby9H}JVt33R?W_kU z^|Y2mqONcYX#me`MAZv8CrZ@4Vqal-*ADU@A<5x;7=D!kCjyjCLSwM`KCLrguEPJ_ zrkhpgC^~##cvJ(3vb+a`oj`keXxVxDfB6A?Cz%EJuQW-&k!%CMoXOMv2v*PA1SU7W zB@}n!D*|F%Ni4hWSQUsSFUHwEt~a!pc)tWu;qxPfI3OT;HOcY+P|_+6^$ni9i}zA``edP z$WS5NhBNL{lLxlQarw0A^iFTf@$8{vElLXf<5y5y-A9vWGaS#m*0?cUR$3InV*9Np ziRG;HGNY+OK!WHY2T$8naT>s;ne@~nfHH!Z{7?D3$ZmD6(j1TVkBn}{tO9~3^gT3& z3}7B+DV^D5?%`^JDXun`<9zK8GI=TOnta_N})961;(^5m3I1ii*bVi=jk!6hn`KFIH^fw}*+vo{8$>n&3b&|$!;lvr^0@Ffd^cng1F`HtyIh1Roik!24 zbe-u6xVB8NcWNwYx}K47c41XFuI;jAZ}BNkMlwyZ+%8n%ohWwC`rjp6B`uz=giBt^a5Gln}7!>e|ngK)j)DuKaX7Fq{7eg>oNHgA}{jDnR zN2A$jmb5A!LFOO~q%{yez4tl=?kB_7I8C2#Tp&-j5j-m)2OG0=Lw$jttA7sIYu{y2 zY-KhK)?Uyoa)yk4w%vy^HfW&UGjIlO(yikI%q7VtJ5xQ2L|dfSN^3v8L?4T+wch*) zc21@m2zWbn_9z+`)&cAY-TTFw9I8U(P0PmmPtzb98Z(9mjP{FTl6%GIR~Q1Y z0;zmJcfe*Od|)Pmu5$zdl)R$4Twf^|I-^roGbH=Dxs)9QgUhk&`PKJb&X@9bJ4lUQ z(jMdvuZGh^;n(fVq3*pG`S%fZSL5Y;45@SnoKxdA=IpP(3HMDF4ojP8)=R*gxyC>{ z8WVaUiWWDguH2M#3)O0>aiy6B?mk~|;yWsSEaQ7`mU`fIaCG}rV~+MW^UaAXtT6-S zF->rOzZU#dq_CKP&-jT%P#KITjXL&Md2vf;UAft$6CT56QZPEEwvOoCK^t=( z{shi472JG01|TH_!j9-M?TW0AxZZ*CZn3X>0{kI9XYwNARxJF=5^CuTwGwLcyLPVj zgT|auSPLHU(5A*(r_#5zE5vcsi$A>$&V9gH0z*$+nNSPuvf4eaYM6Q~<97BzOp-x| zbDBEw_Ee4o;a{dA{ZC(xNAXW-Hf202L@Q3CX`7`ln&UVi-0i8xL<0m7x>hLsvDg*T zsdeuJD|YDv9ZV5An>KD69Y9@P+` z%dVz5m*5OLs1?a;ZzWJU#mGn6+w*-)4VvmUTFm$KPrNMI^n8RRNCpEf=w>LmXAy$@ zGjWl%iJMp|Mh+m_;ug5_`c|HDy2)=d<6qr>h`%=g@$N9F*G5viG^~?)94>NAJ_%() z!{58){je)EQ@w6Ysqe3~H*2w`{ zIP)`Jm*Uox(i()A_4Bo2h0aOJU;@6WG8sfil6G^li3hC5Ha3L_=BxXHf(^+C?*jD) z|6ywpHUNPTQmd@Fc!odw@X`K)5=VdfJI`cOBWxp|`q>H{mn-*E-^ZBavUTzi96B%u zAIdz61*g0AZw80w#YRCvtKbfB}3AU1*Vsf~t z@%w{@MfUVCbm zxrWn}gG09(K08lmcl90UBS*M!C4>NHYlX7({Dw#WE~2Obs}}uI*am5y+`(HdOGtU$ zLXr1G2VgGA!H7+-RwV_&4mr6lHbggWWSC@Dv*7(rvo@btu2aNV?eH|B;#0nHWouUz z6HQsE+fCmHs^Q1&czu1Lc;uz*J|D1!Dl2~fmhrvHe|PR}!Tsf%HNN?NUwpFBr(4v- zuk8`qn1Q%1Ol-u`?7!aOg`%?v9g4N*SQkO&YH`DLx z0+&!A^z)a@Ujx0t?ggde!UXmWb#)FD55Bw{Q{jr7G=o-0$8Zu(NE<>?0H=A#{SogJ zkKiU_!pFQr>02)JMmisx41MdoiH8N>q9J6uj;msVBQu~X%Sxr@G8nMN9f-7SQCuycu*|@!Rr({@k}gif3SrG{X3_>=C^aD30&aP z7@Ql|idkLJ=`R1u?*&fv@Fn4sk#hMcTtT@$CVO+93^SbNo>>6on2A%hM2)SG-nueG z2KrXRxz?38Hs6PDF*-lM$86o~UF6XLe({()4Jzj{7YV55uaNQEouZa5Rdm0gZq?GK!0Q;3u%_n?3~T9Zg8O+a3Ab1%aNdo(N5CcxJg{;fIT9Qvy(SD0}K zmzsnW1#0}mS;cMTAS>U5_sjdH^|g_CebdcHrj+^0oUjlKuk$|ON~nhirV=myt~q}2H&z3 zQ1r!&sGq3{+}|!VWpp{z{GdHuU~eB93B*NugP0Ox^s@^6JW*f`XPgxMY_qIye!b72 zC9gkxsy1K&-|NdW!}>{27ES!>^|Hu4#=%>btm&1&uXAzC^6vwbxS3|>7Y3I;i$NLQ z2updL@{+m2Hr3u#efV8C8cu<}s$=&PTm3KT8&IKhZ>H{N9C2&VDSxg{qWiPx53Iq!$eSXn8L@UF)pwC`!xsm6o&eJ$dP zk260TqGi|o`;|0PV90=R)NbdJHhso0Kmf~Ffb|cPqH(|OCGL+TBsXI&uWy+oO({X+ zJD1hQ-zAF~b(kD1)v_L`{s`_A`F4FYZ8DKkI<&5-H^R#q^`lyi#ea23X=*i6aW-kZ zDR;)-&iv<4aV<|K1d|!wHwY)gcLe7-?CeN<{wbr_UGepZj>_gtqU#?VR>I78=u69b zLUy$l+9gL*Ngbi7-%9G+L;v1d$f{ww1siF()o$W^{Pd}Bg1WV}&f|-Dx%ou)D(#j36mOUt?Tt&$LAOuZ8JQ%gS*T_KT&nLM-Xv2fk zP!*549a5i574J1enC)_b)u(*P7=GjD#~ZSerBQO1p6kLh1C*&yR3hzGM`}^3Zz%`C zUBX1!i)Zi^TC_=fSL$w6g&dDf8ii|3!&S|tveo$1CuH4{R2%f|oUncaN8lc=URbT6D4fV;^zGc)6y4V;2mkF~f9u;26jnx6Ych{u|e zT@LD3v0u4fl|LMi%DX3WGv86a0CS6|cgC4YX}HvEO`O_(rj?ySGhyS_bJs}szqYcy z#hr+0`GBWsk_~9>T&NLzhQ)nrk~u#RDA6&u92jl}tR{Kh{t*c*(XUHEWT2oh3ZJ zrUa?8*VibgMXXwh_P~mX2MMAx71!LuTJTME3M8bsXBT`t7Ni0QtPjwg3J^}|?bUdR zi}lPPXznccvvc(4f{VqMC z2fb|n!C~xV!7*p-34FpuZS2Q{T4s}9J}yd@ny9DjKYn_I@9-(cwR^-j!p44i?#QoI zS>5kjSov7-h9)h6mvkcIR`fUff2(wm74wyph2iiu$@@?z9>%56uyePl^!*p;^M$*4 zNo+Zq!+T2gfX_<34w-IdQd)v!&Sdo6)!^ zrzs;+q8X^tDgY+4C+W^wEmU(xp}r_z+^uB8^M{z+p?uWkP#Nj{PN><9-`a9QQGvqK zWwL3m4RP^roJ|iSYpzn8z;RWJ5MeEA@2b_OZIg_ROeaqPKh#3Djd9}>hPeq+T9H6L zzsu!k(ZTj=dBtbhqt4~WGci0GCl5u2U5K4Q6qb{vO&q~Z>e;mSaj~f7=+@YG!Cc?2 zGJhqb#GfWP-~=Tir4F##{wVYV3@5KHC0XR1-lSGjE~|A`7w*Nu&`{@w_kweE+|)W) z?dyn@3S7_42cY+lw(KC(%g}>o(R&Vk2iCM{(^S+2nRHl?!>+Qz(8D3`FDYx}9Csqd<+^ome&Kd%0c#LB)!sBuks<<2iML`?h4lYJYi zih)0F>M88oLOcAOE_uU4(IX8&Kya)w-fVxELU8(9;XHHfmexYFD8`xZc(BIxfBs#V zetdqkN0EaU>gqlkxzhe*4~-q0eROX(U20eLVs%@)v3GjABRIL%bSFrQdUdt9wB>mB zvLrb2tlj&bfLiKI?eNE)#V8wV*mYEgg5Z9Np2$OndoX97i-^aSpxCu*@1aND;ZZ+i zDJ6Qt`_BhOQbCY%G8Of?jng>p%JW;7j31dwJU5w~iEA#ogCBwtVkfc#u6cj^hFy4% zufN@KziB*D2CwXPJ!k!3y!7&@A^7VFj0qL|v;blmm&r(=z>6i47K_BXpjk2uSd-Sv zBymwzEt52h#CpPzl7$INJ(DJ-{4gFqr6u8-%Sr&o#tFhRJACJi20BG@65hMxbQ`C) zdtC8gx|-xs^lgDiI-r<{4=WqI30mQSKnqMfJKq)1!5R&C^pLXJu9t@_f~uTdQGE); zfmjUb`r_w#2clCZhsIl4slf$e4ug+}guvDH8}|8iCCxPtNC!3)4VSI*`4D_;k3Vpm zko$Dno_i<~S`K(KYO7EhSWUpc<|M2)oR^aX)=-G$58&=5Nm8*5RIeX?Ja%&`oKDLVr{fCVBN7gSdA9k> zH34Nz+1l2r+909meO&Nj_BxH-3US&~}{q?ka_g8On$s?~? z9^QsC^AVi~A{x7QazeGStie=Wyju6x+545}_?UPX**Y#}ni3!(4qw0D2cH&)`Zl94kpw2L zYsJK%yzf(XH<7M>sx_U*E9u{|^N8H$qXyOVoe~!lGo_k;yX?RM>!msX7y(Ozc=RmCR(iM z9NGd?QpdpZmSfP!1=X$1JwSiDsUVcE-Gauu3BVs>Fdgw48H*@I8hnwGY zW8l6HVaoBc^T(7k(9+U6^PaYk1QW2zsPi(JEG=LhCOMONX46Kd9l8Fg+Kcr&d&|GH z)UkcTvYH879jc6Elpoj8`uY`D-rXPEEkcZT zE;^|9CVKGBuO32*wtU$Vs!*Tny{fb^oRc?(NfW$l-r>(HN_`| zMZtASNy?c7&|+7Dpn0o4w{-mY4S&v7V!d?KHT%}dKN>stBC$?dbsDt_v*J=nF`ajk z=OD0=qR?l0lOCHa7P5fdI=rCv=&b>8Sy4!MFkAj>aCp?c*VbLvd)ta!rLBQk883v_ zh%|S-&Y(M~lmF2eAFY8^eb6Yj%syq%1%}}Zln3(oa|+zV$2 zHIKW$pd@NTCFqd)wwO_xPb`9E?l}0CIBzwKid}Q01vN)oE%iRi1;2GGF+(wSRs&Ay z5E!A}&&CDN0##fPLT{A;4Xd@y_SQevNyjEa6w+SSaZ#B*L*|{|jazMxbo)}?j>Bt8 zCj5;_*&TGE$*>|Z=tr2qC&qRL$5{+;*zDM>b8wo!e&^=GAso(HF2o&j6sR5LP0$Ud zHan})2QHz>+zZ9GK}^T~!|0=zz#vREK`eZ;EYso<#S`)NO%bsFXEE)Vtnk=&sYcJJ z3?tH-ToMrrYBu`s3#-#C!0)-60cuGMv`B|z(mCais+ah!HYK3_mpzK5x$Ksp16&^I z7V>&G{#f9^3hB13)_bSS-uBwLRWQvgjcH15ePW(=J(^r`>rbNw+Wp;N=A?4yb&LzC zk%@CvcD+bFdadH>=S)5b`k6Xc;ab>w;6mf|&Btx~(1DlO$7g^eCY^Vc2O$eokeW1w z)176-&M=mmT++CPm{r>Dp2aPhpv&6AFqfy?F<$kSUyc0(cOePC4;WKk+e}{K@NEaB zb|7CVgTg_h+F?wtQ?Ee&?(sXpwPQ74$OdB!V$`tmBn~x9x@9GG`pgj$gokNn5Tw+& zsU0!_g7-&KNfbS#w!iq6*R2E8(#ABcfTmZQJD)^<;DH<@LoHO7kc(ih zz9Lht4zyrz)ipIs@0e)UZ}EM&YKyiBLQ`SLi)y?tbG7Z|L*Qdn8A-Zp`L?p5RPosb ze;wDnKwN2I(&`N%(bc_180P|Z%(*tHOxXe_;Z|c4Ww_qBS7&1~$kOt3+Qd#zg|a%2 zxl9WW0`r_8Wiu_#_?O6A!R5MMTUGcpN?Z2xfR#=CyLD!2Ahq>dj#G@ySVI7Nh$-?e zQ@s3#**}4{%c6b9_TQL2uQ^0zhv})9+&AbmT*V5na zB-;?Dt$nykQ%2_n{xIz@yyROZxO+hFcYptIlihn`B51AEuc}My;KD@DO4>w*m_<)U z_|DQW9-)rHG?;MXSMUxKD{^}boJ@}Bd=|DVFXI;yJYds|vSkdQ7Vr8~To zbYG-91mV)%9TJz6&MQhvcelVrx*G)P?grs^@bi8De&-+7I*T>;oS8j)_I{pc&&n&WDX4wtdsUDK1;BvxYb0|5!^z#JBe0SIstx6XXeHV(U$% z<1EOIv?us6+w>K&l#%l_H=XgD3Xb?mP+MzxBZ}$ zkFqb`c{N?tmVmXN^VYVT8LOyahZ+xMesSyg-vzjY{D4r|l05L@`n{F2xf zS>V^?YuV8^{c;l3B8gy583!H*sit(es*x;@3S>qm{!~eyNXaTva<+}gCI5Q_eJ$4N zL=d|9RJ4rRCYrpT=H6u8-A%y?tWKhtn(`*&HG+KG4$8d7XeAv!!Ix#@;$=)ks~fIqGCj z6QaWGyE(p!W#YI*IgK_b5){wh=#sLbJ}}01Wzf%`eskWC2Pj2J-SrGk!Q^w@#u_=kd()~U0<<8I zf-Ko;e}Cq8s=AaA(iQ4U)J(iK$ABaJm_%tS^&7rHlr^#F52|9!|Wo+o971$-kt`c6g0Z32YP3o=ORhkX1_XY zq59HTKR)#rHNQN!=s2Zvn9nwzcVIJ|tO)2uvHZ_Mhg8r8;p(^RlS}o{##2UsFNdq1 z;_^!+kivd!Sc|oalBE=`_F$2l!(SPT7YO_k;(L8abYG*r;JVpAXih<+{dr8al9j<= zLnJIx(~*cSARqlwzeWnu*I;g5ojeHpS)!WiCiCtD`Ybee^82apvPziWL?xNiWF z67tPqceXkh>6p|}a0y@^mRiJBIzeV_62RSb-?-hNe(SA%dSB!Q8iWA*fQhWh5QwEU z6uAP;p>v*(%?RLM5qg=zJxc%b#V5Y7i(u;{oB1(;$xB@#(>$!pZG|%eRcr>g!#*(r zr&pEfuofltQqdlgYxQW6zN{?!#{JHh`8FH5rP^cg)rje#+z{yXHjr{=ni|KnVx#kRSIlAvEKkygPH&VrM1sD;UTxE(d=#@c-2Cy zm)|#E9RSD+-fcylJ;v{Gc)~+z7O_YZCakxqLc>UYWO_fB?{nFV7T`lP8v{mdyfO7< z7OEo|i$S%)8lpyelat31o$iAT(h>zxIegu_P*nIe8+8= zHLKgmV)sK3`Unp^sUVnWQlNVWEH)3AFoI%a{y8qR8Y|t(NC16nt-WlvP~8h$E*Bv$uT;Tme5?3kwCrq9)n+D*c`TQn#t&_= zY9V-#DJ%pe6BN%V4;Wf`PdrF!^-^2D518GuFL(SNY9?7C{%mf&-&D)qa;kQ#-Uf8@ ztQ3p*5Su1NiLT(=VmLp_KH#{KGvrvw7%G>Goyts`qyXVfYn}z(XC?i6O)^oYCiY&q z7gj}pE2G@x{Bpn!cZO@>)`@Viq!Jbp(BsZsv4xX6Mwl{uf<6WvB*SS9NFxjk?$tRI zDrV1aTzuk7u|Zm#vY%}oY4b*C>;T+cnxAdr%h95;{Zw5Nj6B75<{gynw{pE3tgZ4_ zsWNJ{YWgY!1CJj_bJX<3vRx7t0mzNAPLNt|NJ?MOwDOSIA_Z|xsXQwV?`yB!`(Cz} zr}CX#?@(qc)SL4rd?;1e9ce41SNXnm5>S)(?pR*FnI=&x!XkS|Lq{#A#LB1a_krB++{aI;%^|D&EKk4!Oua8$FmzpDLWpl+|FF>~H^ zQ@%#(qOC#4qS&XwO?@yAA_uBji1%fpWu|D{j z40*K+fh8vkCdd(50xOBvsvI?H8Zd==9Z@Ub>JL&-z;~S+t)T^-(b*M)Cmar5dDCp` z`vTWJ9+F8+@pOJg0;i2-D+tBfzbVt78g2wc5OHOjw*dkYO5Fc;W~f%y;WRzf|IOr0on=0{gh>LZ{_7qPacVNJJ#SN+0k`;DwcVA76fJviG| zo|RF_yqYKe$???QtGKRo+oTGO0W$_^o`cXtpKv}o*ZN>fU>K()F6rt#IyCW8sr(ON zl<<%MD{kGK7=-jo<*@p#wfu`uhOobw0^Cj7qFN}+e2$hsVD>Tzx1M@r)kKQb7h(_= zFUzm+;14L?NM&!uHp^VX9Bai2I=5D9-DF175-a zrZoEIlrDbqyru#5L><)KnOD`{R@ef>y@>|CkArE926o33FWCwU|J(s{hP%67WLR!X z{%qB?<(1NjC>MpmAv#F;3u*lP9DiBzb!Im?=o)N-T$3`GBwH+EVR=a)6yzARBDvxT z%|lJm(3ns~K8RP4=E)21Cg(1bot&Q&+j0yor;WsWwnn+$Ta3M?<}nz%_&xY^$$myF zKS@spMey0Bua! zNw?O9G-&SE5ZuK;2|)0aFma68O%|lgKQ&kN&6J>-@&F_%K}6+OU{KI7{+j8!Su}!s zDY57~l$IA0_@!!(QeXCMq2W!&xok<(oSO-v-QuJqA-gGkbb#u`o@fz&K4>cA#V)`9 zX*2XZDd_fQKHHoHzsg!N(*g&Ngma>iT1j|^9##m%lft9+z+M?Dx{p-^m9 zcLf5iV3th`jt8LDMUE-Mh+Lkf?p5u`!-$zVrJH#z0OrzFL)xr1rOMcU%kP_GF{GWZ z@*O)yW)dk&#wO4MXKnEV1AlW!8hLLY5xzAF6$VI#jfYLGXBR7zVNJ;RBLtPBzUp$4z4oD=O8Ro3tubpceXiW9-f67b)pIvB2`YrKB7&V1laD5VrzV;b?hf(;C z)q@sBG7ozE_K8WwuagNH*08y?n7K)h62+b@<2JNrHm7%OK~sRonL z7UIni-*f!S!Fv0!FhTFxBol7wa1gNNKOf8q9Ts3+yHVSm96tW8P&b{h{CzIz0X9JY z&B~q3qB$Cb*{;>D0f|1Qd2`>65X6jDSc8!0Lu@4N8_y8c5cR zSG=LRWh@(fzviaq?d2v_Rr=dy%3zZv=_-^32wPtoJzcSmCjbQmnN5|kRD8M}M{{X3 zE8r_!Mm?+Lo)N%8LTt@qf9uqhi*gj7?ZI z)0g;xUwEORAH%6&0+u3LX3Aj0f`bA+2I(p_`$A%pq+p+fp z@a)@pX|Gc&ieMEarZ^+$x(v)ekqSET{^pJ?$ziQB;oY*?A zl+}~lGoheV*KEq}HvZJidcR9H)MV!yUXHk>rO8Dzp6z*h?N~Qu(dZ378z@GS0ptp4 zxC|3ghv(Oln^B3pnqaWyfV`ssTpd5_d!#V(BmVsuciWmLEriORoe-o2NT5uoO`^3> z+-Z`*_EX)e1|K|}rQ(~O3%oqJkc1iFyHEneBM?=MPQx2btp#K$&&ZN@zv$Q1aA|K` z@d0&LVs?p=Z7$4`K4W3N9EORGf+CpdyZdcVDaqRTfOaI1kr03T5sAl5XwAUhBeWub zFY5Uyq0f`pGcPaqw)?iGV;$u1LaMHUui39{^9d$5*Eco+%nAU?H=H|9I-muGsl)HW!WsawB+|A|4wMyK>67*?JifvW zlFy!z9l+w z$iJ$)E}crGjDBj9DxEAznm^y&#H_@iD%Kq->kvf%zz|J96ECEdIIGXCM!E&X$GISu zdG^?2LCAA>`Pw~YZwUl&bNcDE#G@LS6ar5e9j9sID@RlZQ&--C*w1b*Fj&cz5WlL4 zv)K`oJ3BaYFU*4}ef&tmq4P=bK1$*&C8BJ)-*&P&8D&OFuxqSrJR(`TMCsBN_%FN* zYnYTof+LC!&Ga8A*j>57!V4|e9NweGuHo~?h5&kNT_*l|yo7@gAb83GJJ)ZW6olrA z7?emQW`1F*`fP;JW^N*#J#2>oidQ2hbP4c@puJEEX8xpTSyY>RC>oh}j^KkGH8W?6 zBs>DVKo98hR7k{9THmCU1W_7^0JV)vDqMi>v-I1Ic>6e7hQuE!VStVlpAAclwn|meAm5IW8xZJy~sRkR-E; zT^@ktRlZ{_MygDGBv-*wqqUR#%+d0Iffh$7Rn3g|68hf!URcHY&i29n1Le~qGZf5v zqZa;yH)nvz9RZUGbYn1g-s(;c>CTwS)?JppY>pda%%TDo?ub+CW7^RCZ*CJPs5y5e z%X<*T3cwDgb^U4px8)4WnFaK%oFx7`?ld|00{kl0DMa*B&%fMMaiU~la$pm(U_&D} zC+BFyWXNP|qza7nXO5(^yM+9R%WD-dUttD>=FOKb597p3sb<;$SwhBpiR|G+CjFm_ zyT8luaYL_a_Vg3k-Zu}M;QSNIvl$Q65Q~-%KcH~@s~2*53HPIi_X2XZK-7aC{&bC2 zwr&}PtGa9D#1kF(hmOr)PAcmuLt%K9^CJ1i z!L)hgKx`Q128cxxE#yVTGm+FUFP%G=Gk#wF$vomOOpThGTfHMof`^qC*J_a^7mxc# zQ~eS!TCLmV!J;|gW=bBn3@RS=4qa|nxCeqbZ$g3TaC{(qB@q=T4{i7#!+<1$nos-l za!7mwIh_8&jBA4OwgtNe!!1I&LJK3V;7uXS*F(Gl_Im17-7!4tX@U9*a6*{_{1L_g zi6)z5nZAc|Gq~yi^oR3XZR)?p7GAH}%|~qiaX2Nz??ROMxPU^iM3U%^0^I*G7?*XnEQNO{GSAB_Fc#b~k~jrVchHTE zyxOsS0OW-NBc6`iX^nCP=bLJp)QqxSQEf(!+(DW_)ZgbTTRFad9#gc|?2=`FcIV2} zOtd7Cr}bIHRrYeuHs(Db+UTQ|iba+I8}S|HRCgtQ(0KbKKHT(7x(#!Lu=703$S6 z^6qG{b5hv3=tU^Ys~MbX%i(54+DpS(X5^!P&%kLRse*yMfeCmYz4^56STx2GH{)&= z=hvG$e6VActI&|bd9#7Rdj)@os^-NE9<-U}{Mt)Z?Vr@Wq2%i3_Wcy7Ad47*374lQ z>5%fyy{eN#>5H2r2<&wBrWX<-+5rGQtEkZNUzW(&9I?U77M{U(Cg8RU)GlxGJsylAq+1H*7=(FlB z00oGRsZ5-vm2Rivii35)htBT8P?!dC4ItlnSthq#=oq6U?pk)NT&N#XpD%PH_AW^B zZ$0j6J~@txwCB9srklD^#+KuLCiK$d4L7Lgdr2f7Sx@?fUzCEGPud_y z%^3&Tu#}O$2;3B5bAbp4a#jkW^>}!MPkG;%x7x~ ziA??dn@LDDJDbc&RmDF`iE#P-Xsij*uzc6#Xh^4nPtT)~gqR^#eWKf)Xl!3O)(z&` zafdU~XNqg`Ct2i*@a~o{k6JG=yziRw_VHlJH%fm-r}yN@8Pb~Zn!#`e+WH3Cs;&+$ zRG0kzp7{hVdw4h^Uqy)`P`B~o5Ts}L`Sbg@52_A%IAhW(&uhef@7oy4e~*?^NKaXE z<@=nNk6R-}ob5If*HI?1#{xbX0O@!`4!fwhGs+ma-4FL$7Cmo#bCae8oku)I(P~2f47!y2vyv*&(4_c<;-Uf zZQO)V6%r)$=YGAzk%rtyqSkxl9W^A-t;7MQtEtx;xYe?iWOnGVrWPVN&A75USACw6 z4k@u{9L@-&=!oU`%9}dSc^)j`mOU>(+osokKvq?7&B}fFdY!^oUx~bjB=qq|5U_L#d`f( zRfL2dNT@8t4&N>(7_oaIA@ripRo?0rv$m_*ESDH%IXxhFxOexlhB*qkTneSu`CFU& zP*cM!T;N8iex#--9kR?&wRE9Rh$>ebWwCFj3e=HIwpSKh+E`&!@RRlFz%+6V@e7;DMxHK+#bD^HlOv& zQ*n(Ry0s5Gz9AkM7nH_k2&rb~wi$t!t&#XMylY#BH%FxO^RB_C%t&kXA(2k?V_iO@ znab~4QtpSwsp?P8oD~!y<8IE?5@cx?vFT?h)B5&Jf0B(ptz^Etvi;>~#LuS8YCq)) z!z;G){aN0Bc?>a+BEViJb8xB)w9c7Mr%bzqp)S*P1hB8ZK+vkco!<;mp^l9^3g3zL zvj2|TTuMPHfs1SDn#1i!=0NmCci~sL)JMkFBa)UO^|AH+KMk9(V^YP2D=pPUl zxIgY1Ssp#t`F(ft+*DmL89T|Kz#vR;0Mk)Zg_*^(eHqqH>mSy7Z9XOck*og^$qhjZ zN%XbRNJ(erJhU{gB4X$ORib25=BwcSqWXLc4|DQQ)uv^X-(r4=lH10CCrIvxBHqbR zZBHfxnrVj-Fppyb3=w`sb=f`~vS@!S5~beo({Sa`X+a5V;peX?QJZ0rup{J(^!@{;uX7`>c!0)RL(?75!W4h+G{^h^^)=e>kk+_>C;e)|Q(V3H)6AUa3b&GkI)qqf5PX8neYe51XcV%yyqcB1^^( zh>^mYWgtQsatprE5!OyAzV?$Lt5+9)jKCcA^yAFK)&aJk2hPdit~7fa>L22{L2~PQv~l)Io#gUv4X$-15xdr4Tb$m5@G(C@(X35 z$n@0XW*A+g%4Xwr_0v^wbDylPR{>qE%8T&R8=s2I5*{d&(sqGHMsnH zG0o7&STgTK2JgkhUwE|P-VA4sioaG~fdmi@H9B(*)qrYfBS3W1ZwD>B^@gu?^KM?j z&F_D|?g?xoNH$V-G%6mlF!Z=Q;ykV9Etlb|{mC1GOGizu8eD0)Od;-OHQT1C@b1q1 z?`_8oIb5`0r4RZhqg*R$$>Ip#&sLeexgd1EJU&LMsCrA~sCCs=pQxlln5T~H1)|`K z--iy-oe=toOXHkfD%i=0{&MfZMcbYrXbrflD!uEB@brF;?qO||HMzKU@n>|AHwRqX zz&^i<{J2kXp5D6DD4yGC)_>gT9zoil-u8~nV0pIY2s_%B@OUeY>>#9HFT6&jpt~~| z?d2CLuSo~Tn8}Y7fv*Qgwh}PCF(}+tXs*@3Aks9i^<$X@UIMgWk4%ETG|2wE4Pcb(vPW z`ba@^e3N>5dLp`NtSc=i=uy$o$aF#y9d6GpW2i*Gx&S5F&Rbx%=KZSN zE(_+fv$MIL$qr3^=>VF;78AI6re73uKwG`dCjoHsz5X*{Vtz`GVQ-$7@15U{FlS_C zjTiz&jyoK=!}Gg{qR)dCJ38L$^<*aI<UzO}bs8T`)trWw`deJFV`|#H}O>VXqq2(6@4~E`jXSKm*np{u&#hpQI$7 znxm&I?td*#`a{9z@c$aEI1KOUKYn|R;pj*jDv&e8+$Y`T@?#Zg(NW?-&lXkpYm6xyDeKlWf(!@AhQ?{D8q$Dk4F_ugr z`+*iNZrt$b1q?4QbTXOj;nh@*;qKKBry>%QDYmXkNlB1Op{ZNrnOI&gkG$|BgU!?T;Ck!33{8 zIZ%K!nZ7fFnX9bY2`s7BpZTGc@*?@Jb+UaenTDD=TI+yQ@X&i&&5Z##MyS;&r@vTT zYw=1`4;$z1Y&UnLjv#5iy~p;alWn)v0P90*`b<%wMDDdp^y=b|%cg?#8TnRs+ZX-T zg_<+5i2yj`kO|p+YSVdOsb=J{&6tx3>rTH+?e34Nrbl87fk>c)JdXlKNAw^eGGB~q z3ydm^H(EyQ7i||W5Lh4ZWNh&ZqO9uhapT}RM<>F=H+dN&Xcvp+D*ol?x{Wi%mQ<5? z{tQnu-`u`ed9;`I)Ujr5Z=G(L_pa+8&?h7Cd7=L^^qRUDivKLV%FvN=53soT!Y3P) zY>H>&qmyTiMTUk0C#U#G0FRy;-ghwi|5lOQXAs?g4<%`FZFvhMi9-t$7?kNLr1i87 z4Z$E}+_>cGni|P^m`rkVGO1xNnSINc>s>8Drid?S2Pb`VvQSN_Zv%`M`jKgeI2Y7^ z)}J^7D=Y=kvFSIAIiO*L{kaNm(WCjGd=^FoD^8HOx!r={{SSYOKSiC literal 0 HcmV?d00001 diff --git a/doc/html/_me_infrared_receiver_8h_source.html b/doc/html/_me_infrared_receiver_8h_source.html new file mode 100644 index 00000000..dd42e46b --- /dev/null +++ b/doc/html/_me_infrared_receiver_8h_source.html @@ -0,0 +1,204 @@ + + + + + + + +MakeBlock Drive Updated: src/MeInfraredReceiver.h Source File + + + + + + + + + + + + + +

+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeInfraredReceiver.h
+
+
+Go to the documentation of this file.
1
+
44#ifndef MeInfraredReceiver_H
+
45#define MeInfraredReceiver_H
+
46
+
47#include <stdint.h>
+
48#include <stdbool.h>
+
49#include <Arduino.h>
+
50#include "MeConfig.h"
+
51#include "MeSerial.h"
+
52
+
53/* NEC Code table */
+
54#define IR_BUTTON_POWER (0x45)
+
55#define IR_BUTTON_A (0x45)
+
56#define IR_BUTTON_B (0x46)
+
57#define IR_BUTTON_MENU (0x47)
+
58#define IR_BUTTON_C (0x47)
+
59#define IR_BUTTON_TEST (0x44)
+
60#define IR_BUTTON_D (0x44)
+
61#define IR_BUTTON_PLUS (0x40)
+
62#define IR_BUTTON_UP (0x40)
+
63#define IR_BUTTON_RETURN (0x43)
+
64#define IR_BUTTON_E (0x43)
+
65#define IR_BUTTON_PREVIOUS (0x07)
+
66#define IR_BUTTON_LEFT (0x07)
+
67#define IR_BUTTON_PLAY (0x15)
+
68#define IR_BUTTON_SETTING (0x15)
+
69#define IR_BUTTON_NEXT (0x09)
+
70#define IR_BUTTON_RIGHT (0x09)
+
71#define IR_BUTTON_MINUS (0x19)
+
72#define IR_BUTTON_DOWN (0x19)
+
73#define IR_BUTTON_CLR (0x0D)
+
74#define IR_BUTTON_F (0x0D)
+
75#define IR_BUTTON_0 (0x16)
+
76#define IR_BUTTON_1 (0x0C)
+
77#define IR_BUTTON_2 (0x18)
+
78#define IR_BUTTON_3 (0x5E)
+
79#define IR_BUTTON_4 (0x08)
+
80#define IR_BUTTON_5 (0x1C)
+
81#define IR_BUTTON_6 (0x5A)
+
82#define IR_BUTTON_7 (0x42)
+
83#define IR_BUTTON_8 (0x52)
+
84#define IR_BUTTON_9 (0x4A)
+
85
+
86#ifdef ME_PORT_DEFINED
+
87#include "MePort.h"
+
88#endif /* ME_PORT_DEFINED */
+
89
+
95#ifndef ME_PORT_DEFINED
+ +
97#else // !ME_PORT_DEFINED
+
+ +
99#endif // !ME_PORT_DEFINED
+
100{
+
101public:
+
102#ifdef ME_PORT_DEFINED
+
109 MeInfraredReceiver(void);
+
110
+
117 MeInfraredReceiver(uint8_t port);
+
118#else // ME_PORT_DEFINED
+
129 MeInfraredReceiver(uint8_t receivePin, uint8_t transmitPin, bool inverse_logic);
+
130#endif // ME_PORT_DEFINED
+
131
+
145 void begin(void);
+
146
+
161 int read();
+
162
+
175 bool buttonState(void);
+
176
+
189 uint8_t getCode(void);
+
190
+
203 void loop(void);
+
204private:
+
205 volatile uint8_t _RxPin;
+
206 volatile uint8_t _KeyCheckPin;
+
207 uint8_t _irCode;
+
208 uint8_t _preIrCode;
+
209};
+
+
210
+
211#endif
+
212
+
Configuration file of library.
+
Header for MePort.cpp module.
+
Header for for MeSerial.cpp module.
+
Driver for Me Infrared Receiver device.
Definition MeInfraredReceiver.h:100
+
uint8_t getCode(void)
Definition MeInfraredReceiver.cpp:175
+
MeInfraredReceiver(void)
Definition MeInfraredReceiver.cpp:53
+
bool buttonState(void)
Definition MeInfraredReceiver.cpp:144
+
int read()
Definition MeInfraredReceiver.cpp:124
+
void loop(void)
Definition MeInfraredReceiver.cpp:192
+
void begin(void)
Definition MeInfraredReceiver.cpp:100
+
Driver for serial.
Definition MeSerial.h:67
+
+
+ + + + diff --git a/doc/html/_me_joystick_8cpp.html b/doc/html/_me_joystick_8cpp.html new file mode 100644 index 00000000..b4291a53 --- /dev/null +++ b/doc/html/_me_joystick_8cpp.html @@ -0,0 +1,192 @@ + + + + + + + +MakeBlock Drive Updated: src/MeJoystick.cpp File Reference + + + + + + + + + + + + + +
+
+ + + + + + +
+
MakeBlock Drive Updated +
+
Updated library for MakeBlock Ranger
+
+
+ + + + + + + +
+
+ +
+
+
+ +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
MeJoystick.cpp File Reference
+
+
+ +

Driver for Me Joystick module. +More...

+
#include "MeJoystick.h"
+
+Include dependency graph for MeJoystick.cpp:
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+

Detailed Description

+

Driver for Me Joystick module.

+
Author
MakeBlock
+
Version
V1.0.0
+
Date
2015/09/01
+
Copyright
This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
+conditions. The main licensing options available are GPL V2 or Commercial:
+
+
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
+application with everyone you distribute it to, and you also want to give them
+the right to share who uses it. If you wish to use this software under Open
+Source Licensing, you must contribute all your source code to the open source
+community in accordance with the GPL Version 2 when your application is
+distributed. See http://www.gnu.org/copyleft/gpl.html
+
Description
This file is a drive Me Joystick, It supports Me Joystick V1.1 device provided by MakeBlock.
+
Method List:
+
    +
  1. void MeJoystick::setpin(uint8_t x_port,uint8_t y_port)
  2. +
  3. int16_t MeJoystick::readX(void)
  4. +
  5. int16_t MeJoystick::readY(void)
  6. +
  7. int16_t MeJoystick::read(uint8_t index)
  8. +
  9. void MeJoystick::CalCenterValue(int16_t x_offset,int16_t y_offset)
  10. +
  11. float MeJoystick::angle(void)
  12. +
  13. float MeJoystick::OffCenter(void)
  14. +
+
History:
+`<Author>`         `<Time>`        `<Version>`        `<Descr>`
+Mark Yan         2015/09/01     1.0.0            Rebuild the old lib.
+
+
+
+ + + + diff --git a/doc/html/_me_joystick_8cpp__incl.map b/doc/html/_me_joystick_8cpp__incl.map new file mode 100644 index 00000000..a18749c9 --- /dev/null +++ b/doc/html/_me_joystick_8cpp__incl.map @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_joystick_8cpp__incl.md5 b/doc/html/_me_joystick_8cpp__incl.md5 new file mode 100644 index 00000000..9ddb6231 --- /dev/null +++ b/doc/html/_me_joystick_8cpp__incl.md5 @@ -0,0 +1 @@ +c531cf0a131cf54b15351ad62ce4dd2e \ No newline at end of file diff --git a/doc/html/_me_joystick_8cpp__incl.png b/doc/html/_me_joystick_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..3908d19418cd1b38f6fd2d55d91d714846db19fa GIT binary patch literal 47720 zcmeFYWmJ`K@HR?=G}5hzbmyiGkOq*mU1NeLY z=Ur!=bH1F9XSgX({m!aBxVTaB%SHXehuF z71oS?;2#ttSxIrYyZb+1TMFXg;GV%ri@#QJ%h*|P_exl6xcfVFBKPKt40u87_1X`n z2-z;RvdJW>XHO!2*1pzGenW?pY&&M77VPa_Lr_X8+C+-PB2+Bl8&wL`LRk7Er_G%xUJssgmUY|Eg7`9FjX$f!PFu`Pzx^<3Ypk?4!p-y_Fx}U zzsBmaqPp5w&OCe2^=(_$CJ$Y651d`=*4pRFbAMfU6}Go^8|Y|gMydXtax-$QvC<@flRExlu4sOG?^!gXsE2N`6oO;nl!yzVLT$%C36M1PL%3GDaqaSZLCx_<_IVksVd=l(fu$fE%F&wKy> z*Z*%dL*xv9Z$g>{C9UnMZ@~%3r~dnvIQAPd+_#A5+o$wzyZLSM%-S(!P1`;I8s2$y zcbXeD_t87tjw&-AL|957Dd;m|eLOK(d7|rdQ!0WGQ2A4vm8bV6@#$Y)g!=%x0A0Mw zdX3pLcboB3r;UC~3-Fg}iAT>n)-EEzIcIAvaDG7qapTbD1;T*1{C__?Dws_N+xbO% z{LLG!E6KVfpcmDayUqB$`LGpv{qoY5Aefk#s97s z?p|lFqHip9hc{mG{a2qnel-sN9kvl8JnLXe)X58U4I&3=K$h6|kAYU;n_~cPyx!o7 zz1^i1piOwmf2(2QG_QIfPEI)t6vE#+y<`REj{~VF37V(>$DF_^G_LhxAKEXbzA>_qmvSK=nuqvVJ1K)4TU41!m@!vglFAOEWPPniD?E??fbyxoFh#G~XryTpH;yPRCMNwKURex4%(%wqpU(;SOW3*YPqgkN+q^iHRwc-zhFr;osoABLRd$hM6W;g^@QCz(VBq-m zsr9aW{^>?XWvMXAT5v3WoP#V{+CA(#`(Dc2Pj&-sT8@+xL* za6rwg%x3eM=CzDS32i6$irFgX%+oL;#7u&40TxOGk!9hTm0-sWEx^a)b3yB+V!i z3jq?u!DkNv$#u*ur9EE+qr}~EK|W$=u2phzsFf}CL|~X{Fs1PW&e77I!}jXltuH_S zOSaWqnzy*ZzWh5kbwaJ?b<36R-fDfD5%V|4C-KEToYo|gO-@fCVW4<_LvT7t+s`Dh zxutV#%j^i~e)rlnZl+HVvPcIKD=10iTZ;?fNyc&t;K$;{k)~*QJC~nWJ~jo zhwm-%kc-RpxMa-yP;{nyl^E|`{xtc}4Xab4d3KYSp04hV$Myzb=i%XRUbB(xaQJ>J z{_S99@Ey0Y^evx{^Bj+-x%x`B=0ErAy%brfT_;-;6_c zdP8WkyMLbW5Rn)|NL*cHmrg&o_YG^>Ojf^Sk*hMgRq^Cru>&Guqujr&Q9KiIGt3b~ z{X0RBr4OT_{$qH{=wgehv{?7EW&7?P`ipm_--C72to(vSY%-VrH1XS*2876Q8*|xn z9F(`mV@G^|b{@%E%ez8s=O|_~IZ=!`ql1#xhrvQ_vggK-kGvs7cwwLaWfZ~(yRJJ3 z*grYoIw%vbdMVT>mUSHANA7Qh-{m6Vx=!)OP*K~o-%I6-QBGayB_jg*n74ZpDNDp! zRbI=4s&1Bf81<{36fns|vA{9N;O>}}++q_WZ+)1CM)T``;JJF_NN-6dRY(j80oKN6 zyILT0^`2Vsat%B|vLr(=6Sa`3ZK&AIR(cdL$frsRZgxu! z>TVmjKS#ku$AgWdmG&kELb40(h8vjPfkt4nqd@wG-SN!3dfJ;u6L&pnXbxXLf-G9& zzBthlEwv4bEyynA$=XbL^=RPFZijSIhsbd8*ok8kpJ0(p_11wijC4kHgW|V%tOZ_W z2tD%^rdR?}pXH%hUIY+wZ5xM85x|A{R`+A4oxw zLxLdQfzK1$xr~H$L`FPrKGlqBQS&r^Q4HGjd9|B?TZ?6$NnV1fW-CVLQ%AsTn`tE9 zqMHrG*l&+pHUfE5WTAdE;|MEDHrUH)k-+nldPRxGpSK?_gwZmrA<4xN)|PZzO4ISA zbDlRr&`(w~hlGe(oaT7&7$p(b?tI%yXtXq=ypQ_I>u1V3ygsloYj7g09E|M4BA5DP zHm3+EAxWkRjl}A?a&f_Qd}^_*q2jtK%ZcG2V>o6${7dj6a0NS&gn52DWc}GHvP{jv zl@ibM{N6`kJE*PxL1Qi$|=6)w&nv7s=#H~HH>a(2kD&G4Q z-#DL zn+inf7nc)t0s@3Esq%jrZMWF1??~CsLG=BTW;=-Qr&@MJtC~0;IXLMM-a+?- zdESx5y~F^e=`nQ`mgAQ6qf~?ht^TS##=s>3mTF<2tf=@FuGi1MgdVFu>TmV!z5e)C za9wTx(v=qjd24G6^cO{pbOX;dsU}gmiTj;8!_KBBRCC>Pt>8RINS`Z3Tvn=je0js$ zyGv2>UN-%LM|W{y(BH}x>B4&D;CgxZgGljGg`23phE^3!dPF~+gqeH=R2!GI+}q9e z_F$e2ZjNw2T#X%jUk&hY>uah_d31mAyo!I>Dx+rLtWWkYq7xhVBEIt_@5|Gsy=Zm4 zeSPN@g}^HumSE$JE^9-fqLc7=KuwFrm~Mv7qcl?@Cl}Y0MEhgprOV;xgDL z36)|-s&4Zi8mZUGhlf7kGypD^sp@ClajfXV#BjUC5-Nnbaha5+5;LfpWF zt$<~1=ZQbh&#Wxf+`ON|MI%9tM8;NFI%Km!_zKokQnj`dSFH&ZfBWxDN>#&Wwp72) z1{=W3mKgQ4oHJD0oAp4LVP;w7Ga!2Bp3}28@Ty@Ur;^@vu>4Fh_&_zX0^tfFMsQ%s z?E3c}jVJroWsb^eB@PyflZ6no|GV#YnmEk}r2(H5zY1qnWLfw|lz+qn9N?jJb=0ve z!(n1s6^4loP7?^;=_&tONS)pTs<1%x5C1yk!Rty%aNkF@R znHMtHFjh#FSK?Y`F6GwJEEfl-mV*tA1ixb%Op4zTJNYyTzB#b&7=g<;QK%mkXFWAr zzS8vttB$zGV|J9nj^IE4^v1Shn!5hyS3hdAtw5cwH`H-`8^mB~PywCHj(RFd9X-J* zCd<9sEvlL2kqc#`l_Kx)uS5e;f_LlkviOMTf=ZqflE%3>Hu#M*8bvg&bqy;p@mm$T zxw}E>e5JoChS~Hw!!}VYRQaKli3>D)d6NQXizFKH_t~JA5a)zm|M>a+2G$r69PdIP z3GNc7S8`Dc_~@P}<(kf-bZ8*dlqWlZM?uK*6G&&+$2NMIsxXabzX6zB2Z2 zf5i>e;#VUr{iHz{xF$#{muL4_p2odpin|>#D;SLgRSI*krD~hRm^(%vnzm;1kHPIk za0)1yFmnm`C^GECQqDC;qGu@k4}v?fT`kkqr&Reo7H0`wuy$!+kS@)vEQ_7eva6_R zk=UHjASOR#{8)*o)* zW3O&A_lV8{bU?{yckuTccR!5fE1U)lY6CQG<#bFxwX*iCI+b2dOe zp!k9GYI~~YV>{*?ndS(MfYif%kP=f}gsm(z;DMg3v}=IBtHxW~utO7(^g_E*^Z;ac z3=tLqz`Khn;D6X@DR^KB>~2uA1&8l@Zq+*Z8rPh1cJ-fA1hWXy4(9w?Cy406-aO5< z0b$3FY)!0BzBK@O!kGsdP;dW0U$!&|8meXbvZ1*lt+-Z|C8){Qoq1Z7-ycO+2@s_7 z3pzIx>5c1N_qnEgl?b`B4Pv{(B|IfI5||G5(txn?sc~Z0`P&omEA0g5h-1{pJ9ZhS z=I!2!QR;fGXLr12Y2y;8=u~*}CB*p3USXoDwybWw4=Gq=l#)=^TZ6>0QHU5}#c$0_ z#bz43AZROm)kk&ut=#|{>oHJ~d7)3Ud-n^0N`wvE;g~zWsJagdFC+(A#9BXk_~=xF zws5aHM>+B-=SJgt`?cFG(%fkJSQ77f>iPh;6va6$@o~s50pJz|eOouQ80YUUX)Dg= zi?9ysi#+05aDhYVdTO_Gh(5u5t=%pz`s&dV)M~ZAVtx|v8)m@Gr^`6ZTo;|1*$ruD z9b-_~!u!NA{1&=dtN$1*631vNdku%dh-!w23MY$cyHpt~abL##KBScgmYaP{UwJr! z=HGl-*kh>kt`4v1(CSV0Og!nxox0 z^ER}`SXR=)8h{eXO!OK~v|Tc7s+ybavnv+?q=cXXcq@OQ56JVJz5!)1jiQ$NGo7Ld zuOl%KqU|@(YLcj>v(e2U`fto741_nJN7zF)vppDsgmR9-k5@`G&*&SD^qSN20}&WC z_EH67ZBsQ@LsKH}0e)ZvCA5UGwm~zs4)wRRFD@u5(^r3+1m|V=4znhctfPwXCbet* zv;iFewi+1go%LeNA{zNNGjwf{1Cu$_w5CV#dyGp-#^i;eff_l!AsZO&z2$OC#Ard zw{rIqO247KFS8Awp8>Eh8NVxOU~*o>*)WsX8r!Yk@GNuw)Th|5rJ69K7p(L*VWZ$S zMwzn}nIhzf#Qq2(FPzsZdb2d}j+)BaPzRTTF7GAUR^{^_YVgw3j~JSkX3g2>E9x~G z2;=-GfGWC9t@*4#P3>Y_46Dy074bP(f!x-=ex3SWZG#sn!;+&gvwx0bPk}&Fcssb) zZ*+^GV$6>hT&5kh)fBPQ5-J;yx%G?b>j{YYC%RNl{sRi4?Pnso{K65_k5)gB*#^7z z%=txR(iDB47POBvFeA|s!fPhr1jp`62LsC{Vr?jHdJ038zG)2|Y5i~MyLxisG-YgS zrxob4E=2$jZ!1mFwMdrupI@s1Xg`6jNHUmw^bxq;L2xR zs}0J#->s*1{cLXom2SR?_4sX^+9kAopJh{R#liH7uV{Az6yF zg_H~o`X`CJ=Yyb)+L^weg!QaS*2I#k$vwf&dIwn!Nu6Ar8R}Aq?ex5OzAi)hh%_?^r@s@3enH*t-P!<~>`T zv(>>a?Yyuh@OIa__fhmHL2fl$1&6*CWozSv6B8|f@iCzIabp$Y%qu~Whch}l^(*;2 zjLI>%U4>gM2 z5m}eS+HsX<=iX`9koFqK`Y|1FxW1vQma8vKTrk%Nl?Rx_PI!v%7wBpHn7i=Z4drq^|yjocG(U!YFMY75)xhDDPerZX<-! z-&lV|$^G~XUq?gJ(r}#jB;RdR9l_X-_-Pj(-Ij-VBh8I#ud5#yOg^K8-_~dmV3m1+ zfa5#6h&dbiH%sqH5GNIhoGkuTvi};`(KX2q<9uvE;#4nxJ%;{nidk@ShXz>0s%^GSph-luPCbnem>Z z1C;JlQS(Y2hN z0Tv>bZm@5*Gbk1Ec=S(7p5E>NWdUhD_FY<$ZlkCtTd5Y0)g^WonR%+egNkR&%lPhP z{;UIkhKy~(~#ml;N^yv zvQ?vcI<@}e5IvltZJ!)I+wsiyU${ALaN3xBryFvtznLW}24{wFw|#JvMng4<{-ifQ zJXq9Z?pZY2n`k;%JV+8z67H>^&5s~4U&j|{88s9EE}tzSPbhAidM_65FYR`Os;VmY ze9QjL)u?3Z%qAfrA@%v$OZH-;2M#mvh}`?EOuK%389jp+{A0^Vo5ESwMpt74c^`Ei zmB1Z*{L4f;uB^d)C@Zt9=&}ru?454Fs-L?=Eq01X&0+;QOvp_5eQS`a-u~T0@@25J zt!%~oh4&@=kL#h&BA@?;ajeE~!u^Q{(F=Sc5MMVmuwOJ-DKVA4Q}fhriWb}|)bpZm zSe`M@wmEZu47$71i^&B=VOE@n{{4~!2TR@#bH6U4TCdjWZc$07N#ZvYYP)L$?y9<} z(g!y$UjjHs8erzIILuu}?Vc>lM56Y^`Ba5mUo|tHT8y9cg5yOyZn})1ppL$P=fCYVzYysZZ-fbA95mgJ_ZQ2*%pD z2iw4=TqV$Maou!GYoK;?`ZHcl;e^Q%xk7oXG6}1*?xhyZOO_pQ*P6L+q{s0&h56E~ z>#S`8ks&)n+lV>0yyOL;^qqwTPdzumxwU*%3x%^hO`P}Um$M^NS+D9~9ek3ZqzO-X z5=T?lm;s{Au;pM1st#MqMOfZ|g$q6PTou}ycO>sR#lh^s%4h0JU(LCwj7K85$B!Ry z@b0wwfG-i0dRQ4n6ED?>opptj7hxfJ8Q($Lbv7$`P5E>BIpxygIjY<N2wf>ckoib(9NNRCB41ZmEW1Nq#mL#N!pmF zJRaNmt3UeQ4KdptgqOKrlQN*PE!D@q_!wR)x-~0U!m_ymW3ex!`irE$zc0csh_28` zRtWUUs1~qH3D$dFaoUB82>zCa2>lv7H)6^b14;uW%d&0&KjqaOt9>0!E;7IGbgh;G zgul+zuPCq~pmySez+&mz=Ua`9H2bW()Oahs<`K5DE9^1#0qD>N({lCBGk&g?1QC6X%u(m+2Kc zh3nGa`O}KI@=D7a=j|(@lH92}e*L*L7d|~#fL^g0ZRslqn8ypojnBhUKnutZ)vLy= z`UYSv#2brG(6e~0CcR({fjFXW-A-lMb~ien#y?vY7b!9uYMGmg3rZfch!ixG-dhpI z1$$~>N^*GNuDml6+P_uZCxbId)ot@?{+XVx$x%)@BRVDWn^X_)?Fu3C<4Tkyq5BVAHAfYg+xUXD^`V#&=mu`8EY36}7$ zkM-S8OKeU7z?}1hh#x-Ne&sZuV5!YD+$OTIe6R3-Snp#XJCHfcE6r)Hm;|%aq}CaH zwn1TH-n!mX0ha|`^JN`-9!AODlMa%)*;10V6)?-2lUI-B!R7aG6fxm79aK4I4RNZ1 zak(E8N>dZM_n?TWi^iZdSgth7Nb#Mnvi{dslC)%-qUOrKPxL;*^V>S3NvLg;KG0-$(FTiGgto|s@SKF*(anPijNvspXd6xtw3k9=A@5CHuq5X9sSeZN}#q7eXpsvk7GFS)6X36V?(K)#5#ql z{K9Q~e_gwkk1eAGyDc`(JW%NRpB=tx>oU+IdF8Fw$UZa(?!NK_q9hX#MO4CHg5Tk! zyjRV*lBBG|df#|?Ql7QH<1JE_EA;xyhOdboj35#ZyOW~w9#K*nP(rOpD&V&VG&eXW zZLN$3*9V(tmfp(uVgcO~9nE8(x5 z9S?JewdYWI>mJ)fiXJsjWIq|n`t9-cm!Xn@oGigiiPBW!lY2hCPg=0l5}LbO9(L+7 z&MUo-PS)zWGT-221#iZ8347KB&%@2c@ea@N6&f`b%-%J>o-^)C^R-vc&=MY68AKzh zhRh9dqk^ci(H*y9AlqO&*V~orecsiHN+SRH2b_k5s5^DFeW#he?^@sKMqMA;46&jc z8K$l3dg0V=;TV4Am#NaikCjfl!L9k?G?l1w=0w zY6$#m**{LW90Vq!qTDxz7hp~&ty{%=lTv^8&1S;(?^bZDgW0pQ*MaMAPMJqvORR8(x~ ziZY{sL0K1nsfJO^J$--QK&Z#xxWz;M#SAbtfMM8bXTKR<|>$nZB0-DUg#t@pteH zmL4Y%W+d(f19CTlFXM|jOo3fp35N{;tS(h5GnZQ7@ESBEK1@X%}ug>uH)B?(=1J75V%ST~rL zSHeYN{N#ANRFE3~7lTa8)ud+C_e7=S7Ym<&<~FJus$1jk&+r0a-)%7v$X*ni6(>*; zt{V{*@uJe$b2|E92`Ny?%pGd)chs+_jlJt)2QgUA@8uK+8j<*cYH)E*ny^hJ=)w?=vteAa2*Zs zU}B42M}vj3f9hBs=6g(Fq5m8Ee`_7kLhh{F^6h~Gn@1VwU{EBO$yAyeC#;DVagxk60cJ&y{Pl>WZt_B1F!^fsaP8t15{jYbr03S8FACeB@QEr49J75b`R%VOf6f6c8l-|HodnG5ioD*{{jdLeuy@r{o|8W}r^}zt24L!C zZE
  • 0Z{6ufAD$YNno&lG2s`Mh??EAeEv-Yf6jJna#tXy(BoJ19kYyyFUxJw^+ab z6fLwTIfG>cIK0d0@ga4VZvr6u*^|g2AvqpnGJC(yr9rpxObL{T#?fpbJZ8 z9ci%`d{m8fW_+F6FdY-xWx=DNqie0dKVa1tcgr7m2Mo0+HgQe40IX4&5V4R~F3^?Q zhmzPp$oHX{U=1y@XG=ggir+50Y-@A+X7HZBv-`H`z3r`DWA5a0dZXtt2o=`6;rl?lSCHGc*`Lm-RZrLG z%+<7&&sYcLx+in1+55ciI4PehHS@S?FF`OPiW6PK6pDbb2b8?(o`OEUYWI_co{qST z*e^_ekmhnimLpLka z9@s`MTS8}N0Em#(71L)~9k>lrfQ?N!xH(EWNk_kqWvbk3kwRof?=i&jY+}@6~=p#1q zz+os(wU%wPVMval8*M$6tVV6NsZc_jvbFX6^nTc z%wT?Gk?XbCzvL7gIk%+YCby@6dOkLL9`|rA0TdgTAjdp zq%=9eY(}B2YtrAO-5IU5btA=31z)Qfsa#AygCRm$^ApGmup5$i2O0k{KjDz?;DBZu zVGV%t7+UpeSZ$VQl~j(bdJRsY^!A4_7-R$VB1tKxwi*I!O#5MsNH4}L-?;02nj`(? zY^DO|3e?QyK0^^Ek29LRp`YyH$o=Cvs3MVdw0L^~u0x$KPd(>R`|yL_C!+jSs*h)-_r09|aml2WP^$ ztEV*E^HoZujy}2ji$4;dP;m`L8X3?Y@ImglHQt3cZZV#E(5*97oV|Ek500!r+)r_m z^a)SruIjQ>%iPCD;z775BFNr`7Rl9Yw=nR;X}|gGY%ZiF`7rAPuZnGsuq00~$D2yl zB=Xn->SF8yjYPHu9bmj60vN!352rmHm8#(oH!5Rg$Ou>oMRN3z1O-%?mK499)#(O> z&G;`$GS1!iFb~fKpdbTmyudhjrc)0{n7EQANhX*3nUshpW<&K$ z_nxwqi_8}NZb`~9kEpO`+d1hr+J-WqNT4)K-i8CvgJ|{eQol~u1LSyY7ZVS^i>8?= zxUN|JD1GnVo}tCRCrvQd-y-76#;pAtHHBMr0nvhmb&dk3U~Om&C4-Qv((8(^vO%Jh zOv<;-RNFLnqs;1e$dBXOM#;HGagTS82huEQ6~0Py(mgWp$tc3Pz3D0yywkxwK!fZX zX*2E);=HtpmdM8TA~+|9*v)II3=ee3@!~GtPd+)*a}aJcfgOa>*c8o_=)?}PfI+!H z#3Tf2-W4YiO(msC7;)Osf_T+#cG2Z5U{pric^qNl&l!An;WzqrgD2k_$i2MKHd34f zSw*Un5M4LO&&)j~G|OeqVg>pl|B`h7jx1PnJNHWxbLw}<>TqLP7goI=R?u;TGM1bv z52WCf!kaOS6KqmFqI1j5ECzlAdW5rIutWcIL;6M77#7vRW0x~u-OXBzDD%svtsG)B z{09+1qLz55?LiCyI28aU*Af4#jWy5T3^C46NEV!_E+qpF-Yy8h;obHh3s;Pk2yXBH7m!fmEbeE+*Dw4+Op=}h;(-eigr z_Vvgcw!J8vyPMaVf!UT&;lN-1ijJ@I70xW3ST0QrH0Yuw_Dk>E>+4^R7S8z%T)*;3 z{q4MO3oWKpJOHvo4h~U2fT^=FRqSS|IMbd#H_4e6P4|E5T5R-fpA!4`YuD&@5O;BI zuB?@JUB@>$rxl7o8tyboB6!#CQ<~JMGBd=H`#e22T7B7_X*>ub0)f2USt0ui?(M-pRlS-5|yGJes<(|!I9u4ch~DkIxwaAUGOD`eh7)I>=n&L+tjO^RMZBv$C!m1`rqAt-qgd7NU_ctKs4`qu*#jt6z+~Am_8cy>DowAJx%& zBVDLdnrZbX<^BZU>c>p(mujahl?siBf*Y9AECYZ4UMn&95 zlZ9A-AWN7^QOEsTnjOU_x`sv!_M`R3r2#O|+Nit*nX;Vu_yfJ38O0UrSC+O?vBp;C z2Sx=r1&;H`P6zONgZTD+N-ET>>8FQocD8dnF~6mk@Hc!S;}--f@_(&M>c&gyKawYY zNv*;c7dluO$k&2s=j-#mr*h-Y5=H-elUk@rEZlfR=tYao7G@x`UneCIBL5V@Ty-ho zvaPAKZCw(0c^sHTIM@%fbOGNM4-43`|a8?u+{dsz~$@ z?)#6>R4^4tQ3I@-u6(Vt{N^-q(!<*Ac}RhQFf`0811S>a4UCkZs^-g5*P+Hk9jary zI_gWWkF2u}od+z!Ul#h*GW#CP#KM;YgJ=8jcE2AQ!{WN?W@51o0G<5 zdUuZNVK`IAt9wLhov8v_5c^RrAVl4;u3q zY%ia|{T5%hID6D38cLK9g8)IG1fy3oqbxX5QCYS%y%_Ys#XkF*N4Xrdobtz9j>7`eRL)>-$e)Hk$T8m1w=>-S0!88^{XFjz(8&k~eWMW;y8yi)Oh~iVFPKuTpYv~sdab$V>O(i@HD{W`psxb@EXQ7X z<}XP=rLughOSQ)S;+qtIu4bJR#U9Ej@i)l+n+nd0U*RGU65|21r#6$BK$i?Ar>cd^ z78YU>yyU(XF)PvN{p^)Y5UXx7b!a6Hb&Q0sB1|bb*m7-AK=rV=ZN`TsV>lO=4L=1z zxXfO@w|0Kdl|91#4LjcQ$6zOvv1tzm8b%SawU|wwY-qvf-`x0QpMsYVhh(166Mj%~ zepeHXg*K)F!kaO&g?B+_%lJRMRSaX9F?1dGpHhgQ-(6mp>Pm zas&|r%R;?>$YD{8^a2;FeA{5M%6Ss_8$%4t-qe~4<7WQNBxBkzhRQi_pL>JbUqWdM ztd9Ne1m&!4lx~!=0p~rMu!zyY?1^11fw7 zRe#Xgb9QJtjy7>pKpV808?NOdVQdqMBhUsW9k_&ITy}?Z(@ux#+5P!OVChD%HD2oy zNkaBI$6gGQLU^#rolX};=_L`X=2%~aUq!@WE(BL>AVgK;t?F1_x@z=qH^O`jB!8D6 z32-x~Dea+6@Pw4Qeg$;vg@A@maj*4-Fp>rFc|7`{0&0Yrd@Qk-f>V4jzDE$+8G>DC z|2X8M`@()k`Dsy5HOpX1c>{sURiy-@+D34MU zlcA33+F=DHf6W+iVYaKWAUA_vCbI)YvOy_$+vvG_H*gjV`jdWyHq`Qn;8pU5NJ{BV z`K@a6W|`3xmDbn{^n`!C2-X>A zQgg=mH23KVeoY&73~KEgcTGy7-&}29vg>vxdnI0_GPS!U3h%orKvvWKi9a%vEE(MI zH^Gn`^P^SxgjK8h@-24qfYh-xxShr;^ib-o>d$ge*0T;u@PfZh(MeOPgX=;XTN{#2 zn;|0Bg%(LD-HCYc1=BnUPG4|CG_~}W2s-tzw~ij=#yAo@-@A)OgAQ~W1LMPs{B2EQ z_ulv^`*TzhA28X6#M9|vGE0Ulc}FCbTCPYX#QVqlb26|;bn50cG*yLnW0W0mdl%U% z&$c5NC`uMV3(CqNs{xNbL`2266_LwPOC}#r&rcD}fzOKP;Gb^IqBE|D-08|HH|2jXtfISkIJ9d}Wf+ zh}`Hd$tWpfwgy!(V9|x-#INI2F&=8!#o!bidnx%~UDFW7*=;cGw`MGruI&qC&>ZL* zCTp7+ zL#*q1bLiT3w5?dHJ~;?ZWian9UOn^KFp*=^sOly$j%0l0Ec*4hQ5 zJ)^xUOOGqMP5*$wc&&xR*Qgc0n)eDwI>Fy_1{Nw~Jy8#9tgrEal@{O%!W_{L7-0^C zwuEbwUOO*N@l?au)@4*%i~9IiR2`$17)e)nnNNXZaU$nw>t{_-ET`85R1fbrf1W%3 z-Y9P=q_2`f`-Zm?zmn*igh3HAOQd3wFXnkr@l$z+sE&)`j1||{&(cO0bn2xN7>3I` zSkct6w>%GL2D&`HZXd!Oyf@JPc)jDUavy`#4qIQyv94x^Kp}$&XQ15yk|)NwL%N09 zKa)5n{A&oJktg9X2-hKj^ZEl46>rqW^8A&w9ZT~BD3|+R6@gpOYr2IYzrAM2=5%R` zh!NTl%KMTNGa+tW59wGA{?BOg1`|MX0ly&Uqsp@HH^pOVaBP9S!$ovM!sS~ajLf2H zx(tmu+W6M&*HfNmfuumZ90~b4FEFr)qmieH)3Iy><1xUpw@Ducu`}#nB#ylwXB)ji zgxB(G%kLL3go5{1o1F^~pEC&qA|WMI&-=_lDr@o(+t^)vUy?ngVXdmN6WP#?L%YfaBOo zNFZNT{eX<(H#(#<8B$$ox{JA*G%gRtleY?fWafHOM(DN23E-P9bmjre~4|ppEGdkxCCSE2vR2M|GFfQs4ZL+|_Z~$CnO|VUh z$c|=wd&A1{4hFAEc39Ty#q*86#9qk0Kc)NpV{5rMmznb84e3>m&GSK7Mo%E~|IVaC zfzh{g4Yevn;UN-X=nrAmJ6%}!B%lLz{B5vx(HYA#&1Di$fH)zY#;YPaCu0tYE{vllGQq*R|W26#3`bo5qv-`HSsH2Wh5AWQJg*E~Zo#B!^LQn7Y@6Ta}*~`)706uud zT^Yg94ggG#dgEg{K%h9s4luvJB7*BP9o3#-K|hO{y*z9j`0akd^WRb3{Y^d_-#i}mgU#$K+p6|Wu)iNitq9R)3gBDmb6Zb{1U(V_`l|F*53+0xmF};-~F?W%O$cIe|9T zJTcLxC2;pW{t`=DxP(vm3Dg=l!TTj5j$9S)w>59zyC`M*)0xg%>Bn4WlWTP1N7LW6w4kkgf9+B#&rp5I*yh;B_f9|Wpj)xtYmI+mbW5ELf=T=saz%^p zVRAyY%jp_ky@i^T+GVD?z6WWhRmKj+mED`b+F=$^2^l z#tqOH8N)BcrJmFBmu~zpvOKqaNB3yOP6naZ+w2VfuY{Uh^>sfi<-Dw@!*faeKiGQ9 zuqfXzY7`h6C8Uv3y1QFILb^d1L>NN4yOd7p?vhUF7>AOU96AJ~yVLi<-~T<=IoEZ* z_(7d#?&prR*Is+=d#JFG1E{u4jkE1c#{p7`1XhQHLnkCLB45TNT(pd`#Qz#1+?7Q~ zpl&E=&#TE|#3^J+H=6Hzc%B6J7NT82%`6=PkJdXd}@ z&PjOQI%&FS&Q{C<5YzW8;U94c>Z0BU`UfjK)H;`ME*vx%gkXGS`vtIQI_#CJf)5i3 z^F);n213jWdUI#B+tS01Ly|1z1MRs7%+K4;@`fzzDwCgsgmfE8FO`vaWUoz4)nayb znyZV?6DZh?HP=KxVC4=doF(|AzUDFfgx_k70Dj}p>aPq%$&Y@Ob|C!;6n_9e4S|kF zzq(0Sx!KU5Eiy@bDQl@&gv5xbCe;fuYW=*lrIhF@UXrH!Dcz-hP@TLQ<`S5TPJxLP z=ox4$k8QrEBA6%8c3l6Ile?3~D$UhyOMotATT~XV$8&XT?D8!YV<(krOSvfH&zuP1 zscUBcK-Qe(ALU9ylNHpvD452x6CMdH`n8*UjGssr98AYf%%?T%!a9)BDDSoqQzDESKH_gfgm33n^;DHhNROBpNuzrryw$c04ar(=f!Q2(y2^xC~Q`Pk9(+Ncoh`t0t5#vF;>~)7$E1XcwbBbkj+zi||@u z$snlu+mK5TO`yAW3w|mw&WXJ7!s;jDy==r3V%(WhCnr%_ww56uvu*CY(@(k5LAP0y zMO?Zpwy&8UUJUvK?nQP`r824fmzMJN620brAN43(tlPsJ94T;t@?%)G zH3hYKDcJV+t2tNBSTUBO97gRJ$yDY+3}_Y9pMcUO2qi|kt_efJul(I^$>cGn+H${% zRnUzoHJ>{BAT`(nghyP(r@Wzy-BEvVQR}R91*647Q`84f{f+`w? zCBQ25ZF@^iyP1|U-gt|;QVN6NoEGm;F{R#9oRGo!Rpzg~-nH^=xhp64s&!7288c7j zl5oP@R=QSa;Snp$??`vR)e#HYX-kv*`3{Qy)W>3rv5kq~7gz(|g;cy{QaiPpm=0F^ zB`J!U+GzaaJvWmfHzCg-2X;KS(~E{xGEdK+9n zK+vm;=nUd)dPQrG1nf`lK|7PD;Ip^f`uQ~86snzsXPbX9M@Z_C9A2SfsbOXptg zT&EO1A-xc`rq)~>yXiOuL~1KC=}p{{-DUfy6%>qItwf24?&*5^`fq!Y0Z-{-YtWs{ z_2)~&S$UfFVs;B4<|@F77M-Y27mFPW#P%Jf5%82Xu{hjLb(QyYOKd!8bV^pJF@;BjtW=FDHJV(Pn>z}ErN)Gt zO=62(6q4cSI0z}XOQ~%VafzeSbIe5X>kp%Jy7})eG}HgM80Mp!YFpvwRrG&B=}qUe zuRF{5e*b`wp#CXf5_!AUfwcj2q)$a2g41b_wU)-tl8#_VfI9 za@T9}+e2R|bRXkk>@fdIA{Io0skMn~GyOlN5g;OkT~Jv&Np-yQ{b(=FTxGgN-mq3^ zrOeK%|Ivk8Flq*K!wvv-oL;>4rFE`Up+)M*Yi+e(4b$p3-lhWK2;JwWGP*_h@k8H$ z;o8p2mq3{1l3SzgU$fi`hMZ>omjFmbuud2`=+VQHJ8Up^r`{F|CkLFvqRAs%u#+m^pspE&x~2s z`Zg%|Ff{XEGwiYzVvr6Vdi{aiDyHGUi$3T1Mwa|j>^6I1gMzGYXUpn;6{P*?v~}ss z`PN>2+zew4b`I=DI*8h>{-p^7uJNFm@@^Vv>LaGuT;)qD0_!}Bw~9E@LX<^XDB5&u zt>pMv1Afs`R@>#jG*hNjMbh?Wjq^%CmYeHa_SPjy^&w|>Kjn6hm)OgT36(kgRBH*!SSchZ%Re|ze~N_+Q= zAN(qe)|JUY@YgpwL*g7-4x9}~K;*Fy7y)5=yZlX;48=O4Zf80Ufo7!Ncnk#!7^V2T zxf~BJmTENgetA*>j=#2wu0pTK$~U`6gm&a6~qtI3jV=Ax~C z7%j(zG{HNgHC|y`xnexawRnkuWY44o%m+sG8F^_w(~@%1UEoF4(8k>KX`^l}EYcOt z(UZW#)j4ILt29}s`Xeci)<3wNtact1+CqoB_Frd(uACn`)7SShxQ|EMckEVpAMm+f z)bWj?S$i89apyV<$22pnoGYkTAu-cVdbAiJAj{pY^c5W(MD0`xI!-DJP^<~6{19`u z7FaP2b#J^LmNH%T+z%WPp24{$Ytwk)@tB~^&?c`RzHn<7ezz79aqfLowfs9*WCC(; z-JHQ;?7rlh1oRQ*t%;VvvsW&gcLy(jjHX6CFI^rIGyZpMcbqPP*b8}GN+Ik&zSURgY zf3nOUvry}KkP(biPgt{)hli6VL+gcOwY+vgV$3gg6++qJZkbA|7Z&L(I-mNPVvm)WMlo9#L-=j|KGKSFaDf{Ew0+?>RfNNkB)yYg6H-QdJ&$jm&a2f zbrN__!0eEA-2ZlyN&Lpq5?^G%w(4s?8-HE(wS$@B-gm(xQxxlb0lhsh&!n@=uQr8) z$`nVM$zuO$YP7~7HNRxll74`-^VkQ%w`Jo84P0&u7B~hxdu}d5!#ee*pU8Iy4{_=T(BRz zK3NaVwnV(!lK49iLC7K+d)6}M8^hK(3p*3M`I8q)`RQTxi?YFDqXM!UXqhqbPZQ0B z_<%r5v%TEu(b5|K?8^F6K0a=qRfrv{BY3}dZ(e!&DMPzL@i3PDf;?DHuym|fdct06 zFx9XYbp$BvC?Q4wB|Zx@$jFn5stn?yNv_F2|8f`yiDI&go<8*wR_1d!_QtO7uu)nj ziJwCf!0P!#yz>a|}R z`Uo=N5<}RMEw=02edi?wQD*@bOT6wm;}uEZ-lyszI-dF{4p7?Bb&MiK|9?ieUh`5? zF7zor`DXB_i@O9@qubP{b=$W`O_L;w5LDqc{}@V=={xWLmw}7Enz&kxeC%AFJjtT! zw$dCES-c@=HF972-v3w3aEpA$tF2SI<1pCAc4>I_VrD7jtaznmqkeR&`D@PJVZ@F% zX~d)7vUi&}sKX9yxZ>k6YK{hZ&S|t(A+Mo&#jP{Y=!52AFv&a3_G_dg3Zi8H-^BBD z5WWe~*jAs86%Q$gPCT?1`+vFl@-VGyOmXQ<)RqU13*kL2;8$af}A0<9`C(#`n?BO1j

    CwF;YJd-+qd>c ze-|ERvq#4#P0^f2JDr$OyB&Sos3zY>{n*fymzf=5I{m0>e5G(Tc6X;gpP191eY(x! zX1qoE30sV*=dMxUizgWEOzg@v+RGb^=4I%ggTtR=m?ohtj=TA6wLYn!1v;b$h@NWA zQi&NbjHQJky*?LD8pLMtLm^alB)!V0Yf$whAVM}g{>QB}Y zk-IOvd9N1a`GfPTGxm9H@L>7g!uzN^QI25Aq@@T?h^qb7fFvc)>>18Eyw zliXOgx1bJ6v7J4#=jV@PgT8`^K2DXjirGY)7K{?5)-z)5Q5P5~_6Qsi4%R^N_kuf_ z%jmydT+&J;>Ggg(A(Fh^$ENn`j&wUR>M>>^u@a@Xoz0}V%AP%Dgm{ivNkpT^6z=T} zZtYY%1nZG1jYFEVuMW2craN@Qt}5ZTUZbI29k*?vUTwsoJZRMwD?bULLlkd7W!W8? zXBnTYTqiP_VS4UtE0@eMTuVvUSph)p7sNl!oa5pT=UaJ{)cbxv z@ZL%*lfyH0jqlgicfFjyHl5V$4^J`qgwYp+X=K8SE4A8C($t|6# zKq8CQs#8*>1PhL+9zwa^%YL8E+C33gHxU157VY0lkvPL`zcH68Y#=tYrl9n!wfi4f zm|WZJI*b3xR$IDo=OFrAhuw*TJV?=b1j)Sha?}owsB!N%=-h;`nnHD+DmVk6B`o2G zXalN!xBy+w;T9zZOT_Jh`P2o@-P)&yxr@x;M_8UjOLJ#OR+nW}Wu1sdd%4$YSI(WG zK*PZvCAp1icIWBgqu6D#^!Q?v@Ai?w^G&jI*U>=nYUvIftR11Y6Aw>;%&EWl%|OvY z|Ag6dxm*wUQ#|t*RoL;myy8(L%BDTIm%HyjBpTP0GUv>>a_!=p&csR<-wx{+a ziul2ML;kbYm(TH_`iHfD4)JS_YI|dNiC$GDy7w!O%g?OF&n~tKyY4JCDMfyf-+J$V zpwwi&vh@#f%4#FpM0Fljj)v#F@gC*3`=A4%GbRkR4q(deoBzp|l;lHNRND!Tt*9o3 z4|$kx)Y%$7#T5Y>$Gv1O6myP5;(HYsi6;3U)r1E0lw2)2e6J{Y?Sz#%621;qp9_a+ zTHMHgwIqS8_f5hQ5s>dOT)nvf)Z<-BdW;_#Mv)GxZrftf$+EjF2h$W$w)usFL%qUiI&c` zg?-QjUH*KuZ*oG+y{A&sz*}9&?&qe7|Cf&3rvT;raQ1QE0wyuK_z4!6g3&6a>xqfq z79@%bK_#FAK~dNS63b=o(aSKzy-KNjW98f7b!#9*6z?8DRp3+LR(rSuVddf0|6*<$ zMfzixXuEOeMc=wZ0P`Idc};PWqa?~N#CGbz$tJk!#vLe%MF7#Q-~vW?;by&436zS!gH^Vr1!r&nP(k6%E)kzhU*;OxQVilc5WKd7Y zBHu?a(WAQkmRVqFG2p}V$UAyYsC9$glCZtz&I^m)2tuLoBztjyWo7nw9=2>TvayXQ zRQOEH%p~908_d01i_7e%K>h#Fq~!9Ibt52|mJ!Uu2|K2MPJYA*D7c>@jOW4k+OA-} ziG-gF|NQV24ww+udRswu=1JI`h$I={AwS6$Ns;4xsM9JOy_^<`ADysaoI%#qD9e(m z6EpFh!)JFTNu=}dsPo9!@$Y!P46o&7d4-mBO8ztInMdDB(Hx(V1nL6!+n_`5`|MF; zGF{77Qx6v1g?(_T9QfFC*|63CtkltS>)$R>u|}{zawl34*%GzKF8}8=12?n8IXl? za!Gp>U%8@2T%q``xz3f(z|%JR`JfsNFjO#*`_3gN?WcucpyQK6DqtQT+V)@BV^+8X zYcmdkYJ8SZv!C+E?j&iTfRz=(1U-Q|Ld_Y6@Q4te%Jx@l5!2IAi7|Ma?13HRYs30d z`rERZfbqlvx@i?S^iukCXie1JqxNu>k+_r_MDl#G#6eT^=R??RJfkVUI#33az+K&O zNeBH=inF*M?I+P(%xCf?^T_97RIfG#+%TWf{c$&;PsXx6kK*fp5z*%bxPq{`obUg7 z0Yt*M5h1Kp)w6SG4gvhDM`k*Eth#!o>@4QGLkr*yZl2P0LqSRiGYs!_L%wK!jhf-% zr;22FN7w>W`qUT;FXA2@R3W;5pdQ>8Nqcbzg&4pd!RIUh1FaiW&t!a)1*?U=lQhlE zN>#??Hs8)?5|d3@u|2HowJ$50KJtm;>Sarxa1JzXL?PjEkH24-`~WB&wMuKfdh#k4 zyvd|^{|FnUNP#|!09H*&d6aZ2H9I~oHo{v7j;E$c3sf;!8&R)w-Bk3wF-MiIkgMI; z8$hX5fRY3^A!{&V4YJ5Da;iVBYu{JpGgWGCdL^3W2Gx@RH4Sio#nT`avypZB-~6`X z>1jmI$k3!|PU^&Fp`DcU-*~$VpUM|+Pe=nnxP72I;PR?Aa~yp%(aPf}8qur}LW<)i zPbp6h;+ql6nS-7@#h`WdH)ava?u@hNH`P4N-@^7l8 z1g(Zm_t!2~nD~?p_{-w?kh*}}T@FwnddHqXp9k53*Ba8|5U|cU6YMxQEsTbggD}BZ zU0O3ZK1{?ar^mahEkJ=)td z%A21GR7Sfpg81^~P9m`9Ctqi`iA-;C6?S=$uJ}SW00-K~C{j{@H@*+DAf(^=sBK4^ z*Ci@qM0>)IEWY9pa5=mCZ`Yo26Hk+1AWBy#74XT6#f|rBaV+BE`yRd_mK>=M=$A{B>uc!7wP~Kc#EK zZ>ECFv!YY>-AuzNm3n@(_NhqM8CPEvd0gQmsRtcVJWqQJpL5*dCaTA%dfB}f&oBYn z6YEma;plKZwfnB(e$yycu3Pp(!4c7cZ!pUid)(00Wbd7u|GjM)IYo7R=))jTdMoHz zLrUa8JSv?i9Q;uP;ojibq&N<)GtxzmbR+-+pEO z8=$6H1zy^I^m#p;nrT%t*TdxD;zS2SVe5jjmfz2K7Mf7XCb$?@;R!8&xX=gKi zTJv^I)cgTn(%FkbYy3%hS`0h&d0#nc^vY&zSDCgn2k{WGQBH^t2wrztn(lG3tyqYU zAx@AAMZe$f;$P?9G~YUOGQOc09Du%uE=mTx1digg-sFgYH%R@7_UhC6w@Uu)M>`wi~r=^X%eZfgE`ivb#hHSLiB|JvjGC~Bg`sVA^H zDD`6HIO9P&X+Rl+KAeJ4F8$V z)wFO7x6T^1VdDVhM2mripLq4mjsn#}{UZkzurkb(Ia?aREVyXQ_y4JoagITDRNN#w?+JJLZV z1CBG4pLWvPGxWu$fO0XMZ>*Bn5TKlJ&3D~R!2f;@Ak@|mRWpIa0~K!iRfDGynAwBy z10^x04d9#%5Uty(LjY!yQ^K*<>lM~4TCB(mlojqrOE~@+kf)Gbp?}b?N+-TX*46;N zL*?JxeH&loH7pR(dfzyO!T+c083i+)TJiD6ELQeX$p9m# zaS4w2DF_t5_N&jxo?h|wEI+%c(&$B_K|hMz2bw{wbS6Jm)}Co$F{bnbeczvlkerg5 zI^-DJZ}9>TqgIUbYi$sRH*HRQoJ&VOw+Tk`V#KL0m3NTgMJhoo2Jdei1@oF{7C&&r zDF4vJMwl0{Th;H<1YpAOCH&+AgzlxtgceA^lR`BynEB>!Q`mrNV_iSVdKy?~j~v}5 zL#)tJXU|19YN6gM>0k_Gn5Vej7o92LpWbkjHBJrT+IQT9H+z$isi zt0h25%C!ak`5v5yW5t_+bTYx=jsG7(C97wHi2rbN?zO@LC<4Dc9=|y!9u*f-eE;!2O;4MO}tbBvVL;ran0hoSl}ZR1#9(;WuJgb#Rv zFq<&QL7Bu@3I%}KIYnOM2npK`|8i)n)b;@=LNYowBW%8ddYAE*IvwnP(%*Eq>wBi< z#yoPXCqH^DLTozxljzB)4lf*Z zg%1Vhljj2TNR+(*QPxwITxXS=%41$#hga*wsg_VkI64T}q!fCb|mnHx{RU z3N6gx%ZdV!Ub3(fY!*-8+#r2D<<wc_MbnxXjT3i4nOHDkoz^>v+rHm)3)?Eb* zm}>VhyWGgJv-tG0PepRp)Se8=-8cDWeN8#f+EIp|BR9Vy9-)sWt(YfT;{G)#l25*( zM>pcP1qlBDp)7(?txL6VqScz0*Es_o;tSzqCiW-UM-8ZIluz!nTJ?nwA?v16r`hV| zj8dMm4?fZRI#Glnxb14o%_QxC#c~Vx3jk;6MINsippY`&M4Nuk=b`d#Po~cIBsU3? z1F8Lj`6RaruG;Vl??MW5B$E%;fkcE=k;>+4@+~FGj~U|?#t!6^1Swp-?FJJhnu4#H zI*?K{KWf*70;gW#p$w}1lD}qJ{$^p}84eH#d0?4<0=Nl7jOo@(QF26EqyFHW3-UlT zDQZsptZ9ta75(U#w6@F;Ms)XA=0@y~UZCi{Ob#pFl_6H_(2 za}g?zDZn4K$*4k*r?RHEN|(#^OQpi3tl~mMf~O7uicZFh+OIb2?(Be~GUw+3%h8%+ z0Mm_mld{B5jUmNaV|e!fNz@ag>GirK(d_Yh>4+^@RzbXJzgx2y*itoA7X4CRT!Z1l zWhHyl&2H?41|vKo7Wn&2H5^e7t?`cm4d_9<>D0sR6QT63(F@uk`Qio3#i?6%JozdX^3Cv6?&&th<^ zwsnBxYpQ4gDy)5+L_}NY%F}gw+R3_F$B7-Bcd5W&n%N&b+3D(a@4aa}t33ou@lg(m z1+5CBC8CR6KJRHTz|tfQk{0mn0Hz$g(vtRDr%CDEr1e~`gNi7v^8=8Mm;6AS2Cll;ODIgel79@2TK`NlllTd;jisV`cv!LGSa=fU$UJx@O3d2NpNRsAgYye(UQ6Zq|;_xCoUkjq7!zTXb#uoiIn)@EAKuFe(QK+X!>3BkGr^Exl!Q)8dB!-Ospt856PquF2Y4k33cK7(J_KX z2aRfCK|!K;8o-c7V%i#6d@i+m6fG6*Maq!*>zzz9@K0R-mJpEf*5lIY*%s>J#oG9k z#nDr25wtuslQv_xSJLTmvX#fkz*_>=H+R_Z@)w9zWM_;km4MU*v`nd+eie!%u=v(J z;yQHxHAK1)Xx6yrwTQUKZ?5YE`_}>-F-#3@v9ma->9s=EOLPb6f2|~<$|f%a_13EW zwoIb9#55=!*UYNB!@7kN**ao?6|CInGAB9z#p{VwBY=zWC~Z!=&RnOQut1TWNt}3f zKh(@Qcg||BWSlFKoa{u*sgqO>c*kLO}2Cu zu0i+~D3Cl|$JZEQL?%|=7z_U*KXVKddt>xaDtL-*e4K(}f92iehFdT(9nbH3K#x&e zJIVNbn!MskEWD7NBr^9X3NN4q(Pbvtc3Pua0`_#U{s7a&5Bor7U~c5jN)%plQl%QF zO!!VHvN`CtCQ`lC@XBEZ(mmD-fp-bjT0(lcwoAelJ55~l97{lE2zZds*vT;PBdpC<4h9c@zPZs5m zCb=?gymaiQpV|kKUTO=yOU&6n7nG=*w)g_L7a9PmBL*EOI6;_=GQN1UTKQ>(lbn?0 zge=~Fxro}=o41EIT6Rnh@~X4H(0ieRV-Vj4wY1#Hy^{9+t(o5{by0t-oU+`bXWm!IaNv&b}$2NR;R{7%@U z^4l_sx}D9w@NX0w65-Jh?z{QghUcamx;ty8zwfRR%nGK%k&B;abT|Oa00Sk-wSFUO zKF^yqOwJ@l;E1u;Sr+00L|uQ7oC}z;R$HgS9b~OpB(NFI-GW~Jex<+Wp55o4PU>)6 zxZ(+5yRnw%+n}#0Tu6xX6ISTWiJqkW1b{;~H6LiU(@Dlcb6E=-QEbEHh@T5_ zP2p3%%my~x@>7R|0$M-N_oJ(79Q%|yw}94w)LCthhes3%u`@}9r|5f-el^u-6(brV z_M5h1p%*Nd=Ve@sLxIi!&=yqH zEzAXzKVuPLHzEWg+&iEL0 z3<<_YMw6t@g^fcwd{nrOAa}BS|Nn^Fd)pXAUH#oD0F;A{9(x01nSJL)J)3E~xVU|Y zI9_-(OCh)ja+R~DsDL}TICrYaa$uKNwCx4vE^oK z)=g)FfM47MTcZzT0ES^#ip&1;kFj5npXe+(u=ed2Pptrz(Lg9Ahao$r0c!adWPUVZ zEss~g*mcp%k!(dj75F%h0mD7|r+lWOG)qb*skTBEJr6-%D%LFSNDBo)AGMvj#!88z zpS-OH?C>%NW<@gebEoa?w2^%wEbvc=U+;%ef*S@0h;PT^$BQ)|ygck?Uu71100#wd zS3>~%`Gw>t(31!OXw{ZdGI7Vq{4-)aY*2R1pOe1SH`Fji*SWFsvlPLwGN7*f#k7|) zfq3+(rv{aT;dGp+0;94LV7o{!9X#Kf6hVEoliLVc>oEkRiIsP^2zB}ZAD0@X{X+fe z&>bQ>@vQbm!Ds1G<{W!_(_q*n^Sy+(J0+E_(UJfCg%FQ|;zGmEPU$&Jwx1d^5tc=^ z^hUFqaYe;ER(e(F+b9IG1rmf(o0#Z|=@?1M^0=&432BYEl6fd(?75AGGL3aV^Ig91 z4`q%W#ik|lnvD%->Wh!{)5Oa0IRD8UJI~BaI}=~o+!jHqo0)v=9EBx9O%C!!6{GI? zh@DVdWAXC^@!e41W>U15u7l{C4!A4OsVhl~YL%T>cF`u@GvAQ@qpqgE(8!_m@D-VTX~K30U+HtVlLn_?VAF}^OQkba3|WNh%pNT!tXB@?NtDdq0)-e=sJFj^M##Q zXBNINVGSs+P`zwbK73J)#o3bQlooTay?V^PR6~ytiYP1j@)+~v#MMB{>csun@WSS% zr!C^_9b;JuLvi(zia3SjWy159*M@NYfySNeqVPlg8ZyfoV1XD&#v_sKikfuj0wmD} zy=_s*9k;Y@+{uQ9Sbls2zCyW{pal6>P{+R)$Zywgy83<^hspElT_Mxl9?n~rGAQ>4xjS(a z)InG_xw=kC@J_m7yR`tTYia;Do?znj$vNKOZV&Gko4BQZQ((&OmOLxP_cYrifj#t+ z=$A4riPx(g3qeS)GhYvScesoh*eum^>q2DQ-Pa(&;~=lVU(HvT<_p2LyFstLawWgO z0$pr{$^$rA$iLEM6Q)=&=L-+Gmb#FCCW|eRScunmM0u?7qxs?D>z5vgA={vk=nqdE zyaB^M0u?dBh;4th&YXzkf*)bobjQ$TS%TT9M1WSk)Wt@Zb)k1yUqpQv%&Ol!Fsp1T z(|@pU;uc3uK&EF@A`qlZ$wJif(B-+epOuG=|h11 zlO=_BueQ>bRYoYG=Q&|8KN>xV=(12jIlN)ms0vQt!igh3Il;{Cr*i-4gygcyu((7= z72ldH2SY2EvA-2t;+W=PXo5XF#E&&EOcrWB$^a%-jJO^BZ6?wj0^*n}iL!OH#G~1ssL-@aW=4Q7aldJ~BOQhRY2bkz9Kw@>Iap z60cb^X}TcM!anU)WvQ10y(e?Z&a7S(XU}`W^NeM5Q(tj@0Gq^^U%HqnmA-YvXTuk6 zlP`mD2i?6TILUpUeeeqJdABm~?6-!y;VaP@S}lrLWwCe}vNRN0vdKc8^~OI0dX40J3B- zIQZ=mJ))T?!8vMQtfVBgvK#A^bpEE8)%|#qEF5k%8rutj_q;x0ZlLW;ZC*xW!&20< zC4QVM%?GaYjdY}{0fDGu%Z*Hj>BYa64j^$+0qq%z`zE?;7-)yPjKA}OHO;b`rqilE zl?+X+I*BRHTOrVIqmg5X?ztM>P&Y?eF|LP=-EYhP-ReQoc6)p6EGuI%jl40o^KH^6 z8Ahz0UH4&%B*9k3Q#u$+qv3W5`7tTqHG>>tqMD2@d*1vVR+&#;`Pt>~@3NCXcLp>X zFT6qZ*W^sFwfP@zl5LpfvYz1J9Ff5@3L1}P_Gix0+V!{a#uI7R7E}k^d6fC-UU;{l z*wT&qD1x25bg6mj=XVz*hL7)(EM%KC@25gb2ED;>h?lO2Hn`H}m#GNmw{Q$&C@i}H zHw9@GRl8A+kzO2fpqE$+y<{xFZ3Mk_@k|3nsYCQ-wZ^KM;?UZ^i5)R9fUw%xy8&Pw z3WlS&br$N&mE;CrP(no%z$F8YIW3c}Yr(|X+pUL9?Tmc^>w*Hyes>2f!u~l6x!y## zE#P2hI=|4mqX3oJpdlDc*f>)f3u6h!?FcQEbu~b8&>+VyZ z4={U-H#Cg{RefnNdvsU(b+-#X$mHEdVmjQ5J7PZUp4~b6V8^Tw8wZw6o@b$o-&pFc zx3cQhN7}Cmo($Ocm@)59rSBAXmOi3TG8&<(@cLASS-m z%5YfIjcpP8Qh|Hvu_yK{jxs&Yda!6t!VhDhCUhiui|7p5Rn+eAo zfnGViXMe6m6)!HMw z{uVrUZr6f(iC^%riBfYpvptNl)ukwkl=IZcW6r8Po~-SuKQiFoM6jZCSpl)vj0103 z*JP`(YO+}i@uEq||7c~Ds$(eVtY0!VCD3LF|3C>e zFGn!HI^37KUp#mRje)rCzMB_bLkNb)e-}@X&=5C|4a>dVF_q!hAdh1l0uicYwY-p!?*mMp2GnL(#g8jQ;^`UDG#LAl*s9UuqWa z8g>a0{^A)uVAGhR)L3UK;BR)?d05%_!v~yxKD1%VOc$i7MtRcu3|LL}xJpD-jaH|Q z`ZQleiI2dRYcC8E>)<0iEX~j|Rvt#XO*iwGIiOFP3W5k>~5x_+;blr%?$#xBbg@Y>wEa!v(6rlerATxs|z^>Ut?v#9trY zgc=HEQ;WouY6VGw_q!t?UW_#=iA|9(}MqQM~N+Vv}Tz8pOjBTVO zx~=b4-)Yr>6Ksr{B)%t{fx(YsApj4!Ipuhr&*@c{md)@ig3|(A3 z?$1&@T6=lv zd-_Sq&&f=cFm3U~*%5p=nMwDYlft3zrzg#Pxo0d+-wpQfD}+=TC*HQ@?%2+C&Wul9 zhG>?PHviaP7~O0WUwNoCoBp-HHMQb}T0f#9?MVe9rTJI`3?q}j90L~xEylg!FCAyLpmiI8O{wxo| z+~p>duBR{J;`ev6l1GbI4fm2O{c167KV~c^Xp-(0Q&o1byOg~)PQ{HDMo*x6{V+;X zCA%9zQWI6}Bw@^Til+xblxKN<6_0kXEx^~m#0?p@wsWWYW>k^gis*z)%$o~_oO+4q zXmTX=+Zo?+kZy7F2&Oq?lSM2e<#v8*T4xcfyGT`}59fOBVfsVKbMA>((d)}x>m_iS zkBRhiVUs}Eyoc53Aj8>@hxGKOoQBmd{`NPQMXU*zw)Wp$jC76fteah3jNJYIa`;Zi z?O$;vk{!&B9GbdQFZ?WV)}}w$8--t*QM28LwB>kV;(G0!@@TdAiAtGMXo7_NpXv1N zOPlb+UQ`bO^KYgBN#MLs7Nda4AWrMd&=#;K_{Z~0IvcyAd*As||D_z{N7EdWY!pkp znlbjBqfNLxkZe=ExVo0SJo^xn^n+aBK@7ga{YB^y)u5W9ZO(Zg`?5Bha;*0ui|Niw z@J>j7=vh%!UbZgksdwXGqUk5Torc^`*A z0@kVt(F)%NHu5TV`T*}EfSgWW3WkyRMJPo7xUvC|ZANAN!T?xRnF_2F($)%eZ()m) zfuy$JKbnp9%Kso?wv&Iryr1A3H@=>Z*n9DlCu~=!O9geVRmrR`H3NY|I+@TUwroTx zq1-C)kK%6CO;!;o^FK! z!VaS&I{U=$Kz4ESXU2$c-5MrSVP(MIvv5(E4`r(_)ORs2lmeL5{j~ux9dNq=!sFxk z!PVP{S=@;2HcYmdiF|CfPJSJ&v1A-?j{&9C77>e~g`KKt5>pN3Jk#c-W}iVBN#NIS zG~x%jJ%0kb@M$7=%<6W0aYxlQEdvX*n}OCMJw&pIZ5F6A)R~bjm@C`*3u!*OHOo9A-1bzruV=7P9M^uwXd-<%;4R~HBNw>}1df)p?Jz{nq){YP{Vz7sa@ZQg7 zvc11rG30;ehCkwM&x*zUZO0_#Bw2SJ6HCdtBZ4ZBAKJ;C!VjnrDc;9-fk6R#t+l<8 z#PuF0AMLS7xriDot{Ow0t)AU{EM0!fJgO;dt{V3JHPzKrIql!=txIWfucbZiiPzN< zccL01M$3rHh-AW4EcP=8zVEM5u$^T*je@xosVvbZI3Wz-`7P<=*$^N@9l2d5ONNpkQ6&Lq!T-b7%?$8=Bu{#%Z5s*Lq8vj+cHU zTv%9GBiV!Qj7OeAPH>e4t!ArmouqBcahIyL?fxz&(qsSDJE8W`EaKqt#%MG3bjWoY zW_-8o%XPs<-j~%L>wSLHmFv1*etLL@Gjw((pi|8aS^2 z$fQ85MICy5Kz#rx5U%Y(l5*>t{in2y`Gj?9d*nV$#bwPNo4k>l+RCbt;?q=tLo?Df z*)h@a9)Dins0qFHXFRbttDbV#u+J}c_*Tmei%ms@1r37~YA&{Lf7k!?3#tQjF*O69 zU-4C4qyQZVQagMx>W;9NR%ZQZ7N(iOFn5E1Dk20A5ByR2%}q5ghik2qh?ZK z|Ku4k^#6_ZfYRfCiJ%jyQ4L#K3uuoYwoPkROGtjT7<(G+P`a2LVT+uy_c-xGadphQ zx{wv0gMMW7N$&AyX=2Gl^Wh->x(B?ij}8DL5s^Z8q1@_&0ZW0?l3$o3twEyUVOI~9 zcdN3qlclfA)(x8t6ESm*f>&q^bGAcFl_r8-12+d`I$*4$-U)bu3u2gFh_AduXu#e) zT0oYhs~A1+@&>{artEhWqryh5!I1OYYvn$wpm(zaqo(G9tou7Z=thKFU9qlSD}mmu z1<-a3_-`#)kPoVj;?1I1A|9SfW$|gM#M~%*Rj`Pn-m{Z`wJ&jcPl)%B598K;ENRs0 z%owyyo5EtB7VFu3wJM1>TFMj$0mIG2wU;Ysd~B6yC=Z8G8yWDj*S8+it?K&LU!e64 z)s$#Lz8n&;P$L_n?juay1m);sX(bSpy@)tvhEc)joRqnBNDT{n37lk_5G+Mc0@dLK z_ajKurb?~BuW!G?{>%qtiuAx&F!qVCf1cB(n4d-ki*+!TYp$en-4iq`CQ`wXuhq*s zsckw~o)d>TU~`f|P~LRxIUP~(Y<$tO5r8KN?D)kTH=vjES8Pq)3dNsFL8R3mga_Xw zM#74myvv#_G-$?)&ZIsRs0xm-yYWavzQjZkIw`(h6`~+X64d2K@E`s&6PJd2>C)Pu z9x3j2&3tSW_=S+n7v}2g+QwBZ@q=DWAxNVCqmSR3(v5Xlqq9PN%yL~Y4MivhyAnZ) z0(w7EFcdYh%k6oJ+(2_?>%Gn<|ck>33)eL`YyfM$=DAv zTUd*jqRl3tGYv5vxu&*h3naf_h@@DhsFruSjnd|&bFXK#uz65-f~2=P9>WU1EPs*p zLSEP-ax-QTuOV}6p>-R*&>K84-5@e;%CnnmgA3l;ohDHN;5cH|2XF^k1yDig-uSYA z|NMXY`UB|MUFLKak_$==hx7-FUz1-aAwXbP<4O95k)i2Yf;)Lun#1fQ(kQXZRX>LwLSF z&p^s2a9Zk)lR?!8*43LZOF?{doqHfD98N6p{8n4=8vwA#YuurZM2WHK2u)4uD|w#Y zZe{KAbbvX(8tlpj;{i&koJ@_4m@Z*xk9KF@yR(-893WNSIq*eJPptgri~diV z)yYMjrmvg+xsxDU3PG%?@B?|^r#T#x+Bc)OMaVkYgSyF0s_^?hhXpw)>UAIo=4J*+ zyc6e%QX*s^dhL3o2Th`&2$G?vrz!ifw3};2S3~T<`;;JYFfrb7J7csSGwb&63Xa5x zd;S@Ct9LrWQpdpcxX4yRW#FldV-H5*X&(lDv!bn2yLp8C=eVO77A_jDs0PUAhP>Xb3- zlxV`m5V+LTBo6Bz`h~`s5Qdb?0rhskaUrA7b-W=@UBO#p4Wft1$7@s8iC&m> zNgDWQGMOYm0q*5Znnny;;~leF@_s4lNOQywkb?0}BJ9>IsQIx8V5P|<&P2mW5}1Z% znV;uMEYyl=MuZ;*DjBzasbof>s zziywz2K25lH7f1W!hDz|dE9O>)dETWl><_2LBjVvXy2_F4UZ@YZP4>2OZhXSa~_+5 zDl+EG7YS8F!ePeT68;EMxzEBfdX`XZg->jOd^ur_>QphdpfgAfJI(S?gvhEX(3s6% z%AWb$)>V73Xw8gEFj@bpe#|rtutWe-TthttRy+1q(KpV$n^t?6ov`LoPp>f&u4l|m z*jB|s=Z_zfa7)P?m^ywyF@&L6fo_mVorEa>N3d1LxT|C7BWl!6 zzH{?6kd=~OOG+SLPm)#=&zG@ro`ZMjcsl%-;*l+GHrZl(9?`4!s+~nr2>5%l4$z+u zlgFuz-Sd0Z3QaCoO21~OSj)6A>TIuwVYngM5FLu%HSFcMlOqya*T$>u}83{CCM^>(##}qD`kTze}Cd(G-zGHOxYhV zjBy}i5d?$o}g`7Jj-na8`q8)n3F4$w=UM4`?1Y`nHFMdPG>0k#Z3??5v@};U|_Fi9Wi-K zqyW_WEzSj@+{V(d{*Ej*W)Fdix1%RO!-4?Cf1DWYMe&06z zYqd%FLK48l`A=Y^*wWmt;}Kbcrd@CG4=W zsJ+M3!KHu8UX0^y-@4jI$~~7udgfJf_++}zNX9N^{a7e3UgNS#nJ#!QT)N8b95-io zKJjET;_4~~LeOo&33WiDs<{7+nxrzW*+sszD$N-(s7B*Ljfcq-zLCZ5Yt^F&h7`^L zpu=50+O;H<$-2k5Ko-G<)F-J+f%3WU_C41aw9@m; zZtc0{Nclf5Dc&fq2waXc|3+&y6j)-Nxi>}5KX+wQl}4>YBj&-x?cTp^ES`;I{O{_i zO^d0XX`+0&m_c>2bY;Dqkhs$n7op!z1z zeagtctSZ(+0uP<^!ja>o42kZBCZIDL~LB=A*B?uTsqY5gt! zty|534|F3TLeu>~oACL@1<083PMi!Rj}s^iH@!5%k|hnZ=2k6sS)oqiNZZU5Q& zCY|o!{p9gV!GX=(&*?663g(-V!!@m?`75Ah7L3pq!0aC!eHq_Rj&Vu5)bbg$b-4vd z*2T!%lok%!Vy9RspHquZ1JI2M={N?lAR$ISBY#@S^_HgE;STZ}#T+ej3E>b-@{X@s z1g=|IHD7W^VZo~dw&slCUe$#!Z}~^v7rR8J3g;;nX_1)-AlKlB(BywYy#Boh)o{hD6^*0<`d)JL;enUH$3Xjy*&_FH4_#Cv$wZ-VJ>Z$2EB!CxinNgg#`|_p+^RO*+bx;Wy^PeK6WKs8 z6x*33t-4}Yz1eS*7iEHTshV^#;bIkh#W20)rIA+r|KO}#^pl)dyj#-~irRBUpH?ZT z+re=-8=1Ese)!!YVhR|^`Jzkip1!XxtAPsL4&xvFz{tq(lMf_y%QfV+mOh6K$YK9c zY*tR(@7c@JukOh>rqTsCBT^_~WMp@e*hIu&;mZgaJFW4GYYF3X6q+snQZnUFH3z>I zKg;z;+!~`Kf9jp5Gj)SVia7Vza?zB_-SCUrzYeU>rHa|R;a+_4xupffOsQf9Ba-?n zq@9+e?-)QdD*shNaoYb=Lest=?s6%G!V5*CP)Sx z^oDqY=kLCBWs4%C?2EV?uzZ}S(4U(`33Z=4fd4~G@9cOEb+WfT4R?tp13<2FqJh^h zKyb5oeoGU%bQT!cS&YNn*u7;#3dW6b{c2_-+h@J{MXGDEM|5fNtD{)}5H|_lsZL{e zfbxI$G&k3rm%{Z>I%jf)4kSv#nX|uIwDb)zbQbx?H9}*B#Q^f;i+HV)y>O4O_zi0_ zw%jt9xdzxRMgyXQbVix*yIM=K1dv#rYbh8IDmY-dD)ul430*tkU(%z`t$aZp@BdN?isyKQ zUs8mmH?J>s{Py;P{8N=%&=N=i#ft!9G;`v_%-8!_00{xWP$F3sO)7pX){i?pODBLO z9y^IzZHbBcSuH3F@6z_p%emmUoA_>A?^?Jl*clPMB#giKESGF5 zlSzG7CX<$}+CV(v=rKt`=lyUM0Gi#-#hZ#c$j6prPXQIE=El`^V{1z!r zK8F0jOcACs$8T8{*w9<*REt~i?d&lahS;B{m36^GDOieY7)nnY4&^2v4N;8JRB5fg z1>~mk^CQLFd&uYI?hjoJC0RQ5o3qt*f$V~iPVhprnVVzz} z2Y@?s9>HRqYqY2@LbF)%{~(*c->n0CEmY~ctjs=k6%genXZ8ouoDiA1zNJwkf3(mM ziU_?RbH+>Qn}_oAt$lGA%VLb2gq=NgivF?WCBuFQ0~qzTevc1vNcW;GtR6BG<@4PU z3X82g27OHX`_0V!IU9b_GAr}flX`4atK17x)Xx3A`UD>I zp2IJ(zW($l=kdg=Ly{3`E{6s>O*|w2KF^bRcR)p~=pcXc*tasUjA^A2x`p?7$-U>L zj^D&)x(**X2&j@-c)qe&?^(uP$9))UKl?>O81Sy7;wfQluWJGthVHHmdtmIEEeuE` z40!eU%RAg}U$<5DT9ssDv4j_dyajgDlQ!Ry+riVHeuiKl)l)cDj8I&pXsXXywGUag zS6w-@6O7q4uU+0=v}Jex+XfHTT%?F z`*W|k*poo%I5Hm&wM)V-0t~koPCS*IYvF1|?G3B)+Qj*n6O&)F$3L!q@|>_eh>eh;E6&$G)rpJ@ zonu(73tUHHk=c&`u_x{J@1s+S(S&(~Q8!zdl%z>Si${>u?*;ccQ>kb8&=04ozg7k# zZi?cKj-p+qyUx+4UErplo9XY0DxL;?{+t>0IIa6Ra+Yxw=JhO2EyyW^;}CUW(Oz4_ zAp->QzD5ixmVstqXEI&KsL@qMUBhq}5QuJ3Md6WNwZouNR;7PP4uDF+fIhmUfg=N= zdW>)GW93qYGXA~`Isj6RvI+QhI_1LoExikjp@|My2Wvmy6N>#dCHqN$yOQY%c(Sj7 z#;w1zVVrA@2p}&8=lzBG#d_)Ug}u#PmgwCs@VU3?pm+UCbRN+vLntEZh3|aw;HbKR z!ci>2Ael2!N}rg?WTHKg`ig9X-eS1lW#FJ{l{P6xY~c4XVGkt~@7pLsKb5Uu8=Z6E zP~3m#wVEgs(7rYb5sOzLgHa7QrHA+r2UGM5!e9XSKy5QHXY*@%2SJ6LT#M?3zZxB< zs*gPec|vPM$RO9R`N3K(pKgpC9*SsTVi&0&l1dNK=X*CX7IQxJZ;z*O`-CiqHQh75}Y5FHxI+p_jg@ z(VW8yRoI&`SV~ z1*q^x9>*UgQ6i3UX=9E5QiG9bG4vyXc-h5fY_@}>NtE@wfl?+4-HBY$sGM@(b4=&2 z^bbx~;}g)>*<=ENd)b_suv*K%EphTi|6a%emivb$6Ar>j$nf_EbJKekg%|x%ezd_@z#^X7q27SuErF>?q6a;9`idZu<`)RoV5S3pYO8NL76*-pLZKsQ?mOty5?J;M*v~8f^)PHp323e6X zKvINs55t0jNO-!!7AYP`Ygn&VBDuXLvisDNcCk3}q4+=Q%vniiQrz&wf73}`eh($_ z+AkyX4*!D8d|v6V&cB|A{Y?n%{Fj3TI#txT=@ZG-s4$b86Ch*}Q%V)#YSJFk7uAraMv5ho5sbR(Lu*yPmBA875mtc6zW6fov|*m7pc z9asrc+8dTIZo*!a*VbD+MS=1C5jL6_Y~|zx9lx82a&5jW*z`ac)&8SQ$2i`}ur(>z z;Uy{RhGbXvX8sExM88PsG0vhL&cAvk^Zb?Cil!aU5ZPZC_x^0?&CRXgkLHl^b12#Y zP@GE!P;%N!dEU8l;k}HJqsWqef6_q_b~ZqeVh6WyWdCFbxm#A$4ga~MjM=!MTvfd~ z`Z4t|5AvC`HP^M^3)$aQo>%)XS>?qcU`U;NQ2ZDJs%m4-QXwdSN<;bTaP!!&Si2l^ zL3xbUGJB19B6=9zVYtwKmR4Y581*MjV?Y44KKJG%QKH z(%Lj}?=Rgg6`fJnIt#OC9%DHBoXBHwxz-4Sx1VINbgB6(i2JgbQlwZg^HfukxQNJH zxW;f%+r2_8O(h<{GqxW;MG_QTJljfqMlL-g+VvCAT;!X!wN3-BQg#@s416f z?|%37k(d|P#~H6#_oo~cba?kD;DaqKr|n4C zYB=L7dWrLso_Z@*=0=zJ8+BpdT103E>r=il)`gYyn*!74ZPTDvZ`bV?daJg|k`nb1 zy;=9NwIxBET8|VT+)ZBWH~WI9lBVhQrM;@7W8HtWAIRB3lroTPS6=k!l$Ud1i=TFl z8LURNQ^B|R*6|KySzt8N@56nfg_`Y@-P`ikjSBWM+?C3!YDca)pAPXz_NBXCZ?(Nk ztJeGl`nN7F9CXsu&C>i)%f?6M71@Sz&og^kDI39;@kX(q{IDWqpmPbX295U*u`UC3 zKfry8vSMLp?EAwrMjfB3fiaPB)m9HEO6#t-4d~yj+Hs0m0~}d8$K=~dH}(Vp9B8bf z9rs{roYv2ZS!rWQbt{K65quz*?ll3hvVR-oMl~wwvH8tvEy71~nvWQy;F73%h4gpN z(uG1IWDGF~s+USP-nG4J5DWL+Iw|*l8QV?$q$<0$Ds8HkUNzY&4)%+N5-K^shf7k0 z&1@RwUo0(qhBgr>LtM)CSon`oMF%OJRW2q4PuKVMm85LkfVAdv(11n6hZ>D2oS5=& zI>y|+Ma>Cd-Q<{}OG8A0ay=8SP&lr3G1$RE=&Sm8N)C|1aF(1C_?P0&J#_babsNI+ z?n~t-bsLPi)ZI&SQQ><8MQu*OdyFwL>Ir>$bVEoR)t#V$*B1n3kICDJ@xaetL2BHx z<*~o`X%E-1aKY7((~Iy3NESXaUuBb=!~<>v8-DYm7&&34Fig>?jGlZPQlGpjyq`c< zD+Ti+QsP8Dib&7yVb}JxNE$rStBc~o2yzy|(FhH_m7eDe23b%u&)0$4OE2>qKI&gIJc5A|KD;!~g;ZRv>6 z;w1A(2CgAGP!@1tj`@p<)~`G?YzopbT#^bo4X(1Ayt4r=`H7MRU}6dQ0)V zZ_V;WHLiLlFc286SLNPQFXpBH&Rq2}Kq^RN{TDzB$Y7UtYdC!zAs?!dpQ)?M9p7KY zcYFL$p(*zI#(7rTS@k(>)6Z~#U!r*kW=B2dw$Up6JN~zUF&Oh2m$I^6b}E3a<(T># z04=KSMZ8xy*<0MN(OLR4++Dk&3hsn<`2=qIQQka+_M{&= zSB#*)0-S;k%fdFyW{@+ceY$fw;Z2(%xi7CbcqfbUQZ%!@7l;kcRE0T=1ldjhZ_3BT z6B~TR;|}d$;1=p_=@6QwIn!7mDfvBrEdX$-_%*E4p_tq`KL7Y{iUKa76BQS!kc>|N zl55`BP^r-_|D2b(gNUa90xX>z1G}GxeT41ETE0#&N+#uHvhM4(V>gyx98FVe__ufM zQeNDbox1a*=2W#x#fI<=(&o6@Y4u)24uPYxz)dxXllk1+#-O_8HUQ>9MXhS5l}>n` zrL|RUVXPQp!eNq_sFjBB zhETD0DP53pAsGGxvvRuP2E27Ijr3MZsUXsdCYAYO5J`+}~G(2m@;ST9vX`NQObI7wa_CCEf7VLldvnCP1JfNIngH zJC~zIbUz+VSmmx#e7ZY7vjO2JTVya39UutzpIkNRU3_ZBjcA79Hxj5>Dh4_M8JUzJ z|9|o6eOB^o!q3}mPqblQk$lOK@0zwdOKry};mn%HA}CMjUMQ_nbD+88ToVQ#PSCXP zN?poPu>~6tMTl!VlK>Usf8a?AQy@ODReAhgsEo>f1lXyveTgu4a>BouNjcrp{aJYN zfW#nbP!SLN=+dx~U>-@_S3QcD*Sf`O#Irw9g?Q*-!KrPEYYh+_%4&NNc2oFBMFDVq z@{?ZkmxPp`ttq-bbQ?!F%bhy_2KI1r#RvYi-`dl;td`i03!~0(M!DEc;aNA|j@cz4 z+#Q5g*W|Xy&%!WZVK2OwZ>qPb3b$ct?C$VAZX{I%OhhEtTY-{~Jx>9h$|t<$AdTh; zBU*~QyKOc)x^Z$kEqAg~IlljSa(SKH!hh^ccp(XQWmEqsCDHPMR9|c985A(goVRf5?j2_Ltox6)L5l2l$ukYb6s4e?qZra( zs|5hwDA#)K`CIJVb!wUje=0r6*;w#hp8RI{RHi@wv$Z>DrDFRVE7ua;XQy9r4^~s?HLj(Z3eHIL4!h^_M z`j6r3Tf$#NxWcukqNuu7Hw2<{n;CmQ?S%CauJDdtPZ`$izsd$JinU|V8 zNIqHMNaU5yCE_=#Ou_gF%gfZ- zN?zIKR8+tb%ww?k;M4P2KQqZMH-kWz*QYwP_{?r7W&lhZeBPUuH${)ujLeGY#z`J4=n%Xgo?J+8a2YV+kJd0>c0KvZ~|OdtJPdAWaz z8Cc&t2&}t@1sFq^&8hi)SbhMS{fk#Ee*-Y+pnHK$Ik}bP23_C>wvDsm?9{-JVT4sd z+A04k`7{2>5#Zf;aiT-Qn=1X55rlVWt1uc}Kxc#E7% zmQMAMn_M-}N`l!qK=`aBXL&Jpw7xh2G|b&iqpUSGyx|==U^g9dw}LL&7~TkAh3DT< zz=z!6sz2>HH3c>$0UILqfW_@Rk0Fu(c0!d$Em>ErV4`+hUk)sq`t&a4!gm%U=_foq zt{Cjpj=kG}AgndP&FHS#G~&LIaoe^eV51|lH4U9K{0X|8(47RPbQ{kk!>Hrd^+K(q zO((H@x*2v%BoWtdyPed@OO?-mu)Jgf1$O0OcH`FCVkXQ|K{e zoIMwrYto$FG^M$OnS@l!qaY+>6qrQSd`Z`8@fES2l}<{GmVyA~B1e_Gl9Sx~0K{t{ zb}vj;<9_h<9d8hjopM8u%Bjo27k%>K8H9JASX9&le)y2IP2X~j7yG9h9p*%bl0j*c zN!x=&U>IORji_D`MYC)kNfh{j#Q3bbs3BCEW*Ldekd*z*PQfHs+`Gt3ucJ9>fqdqi z3Li37VUI@PK^;4bL7}~L7QfS2z9s{cvMMz7b_kJL;JT+vK2^_-72;x4Y zZco{9b^?x+0;+2{U-GU$B2uLtgP8S%TBK@PShtqCcJNvVwq6dJ5Cq_D@sbRla_QT!pok@N5v2(!zJ?YA@d;B&h`i; zw=^H!XX(d3xZ;s3L~Dx-J*fgVHa0&Q20Eeev!D7s;-9h}3tV5V(yvbZk)N)=FP({d zkEmSTd#F^^-O4f0>9_zg3~xQ$I+-uE~w#=AP@Oj`QiwU%?}OkED`Si@vieC#Osr?`%jwKdylmcoEUtAAUzC(Rr1^73+~DgM-tA7dN#yr)?L z;rHq<3|)G`bwWKR(`_Zg2$h?;zMx;tLC(GFbtoyzxSxkvYZfQ(*XXn6roS&85nt@5 zjw^3#V$;*p^T0D1ZiUIbc_|BAyas%QgxFW7&kJa#m)BPeJJoD{)mFi+{EkbiW|Y}% zXBsR0S}t2?3W9lMlw$uzoe+V?@;SK*<-7K@X1k7HNq=8xaRs=kN0=Y;5;@)q&za5h ziV1t=cSARWjYjWw49iW~_*9MF)mde3`!qRXcP&?dF)!`@^qtP(q)Iy8sMda9y}och zZX99A*Z+MaI>*b!`Ri5yuXUwWLY8o(*f4zfJ=_6-(tBC7Js4> z%+o*?9|Y~H?q}iVMm0Y2Akixy4|-^q5&UxT$wFRw47SX>m$ZZW zVj7p>4Et|x$8rizCAy80|$);ob_f?@^-q2fd6R$?&)b!zMAJuQ0t&mv9Qr3X{5by zCL^TCe2EilGV4_wi7$Vv;`->Kt?BsjfwN#f=j)nd>?i4_SzF%i;cefTLY=NK8dEYmcJXW86LY79vomFRH0qoeF=j zvF5cY*?mcyoOyq1F5mNd7v(IuY|n``=e5|Dpz6*H!HZ@hTB{Hp(df7n=kJT$w~?6zuakJ$MD(FGi5K}J8OJ35y)4+;3Oh)bzQElBVxmHPB;Gf9Y-n;$%AJ7V3n9RR_ z#fQ$=gk=pVRI(=xPHk&zrYB7Zd}eBD;Zhad)1x$E*jM+@3PChE zF+sB(AgAc4yAa=*O=T~h0eq`GXFZM+QhA=|a_lejn-|oyEcw*I&oAw(nY)q7bC&X$ vnVsiNjJSeuQYL8b4bi{e#Q*2-+?E&MRXRdrMz;eU%*#|1pDI+zo4x#B0{t&n literal 0 HcmV?d00001 diff --git a/doc/html/_me_joystick_8h.html b/doc/html/_me_joystick_8h.html new file mode 100644 index 00000000..adb9dd1f --- /dev/null +++ b/doc/html/_me_joystick_8h.html @@ -0,0 +1,236 @@ + + + + + + + +MakeBlock Drive Updated: src/MeJoystick.h File Reference + + + + + + + + + + + + + +

    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    + +
    MeJoystick.h File Reference
    +
    +
    + +

    Header for MeJoystick.cpp module. +More...

    +
    #include <stdint.h>
    +#include <stdbool.h>
    +#include <Arduino.h>
    +#include "MeConfig.h"
    +#include "MePort.h"
    +
    +Include dependency graph for MeJoystick.h:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +
    +This graph shows which files directly or indirectly include this file:
    +
    +
    + + + + + + + + + + + + + + + + + + + +
    +
    +

    Go to the source code of this file.

    + + + + + +

    +Classes

    class  MeJoystick
     Driver for Me Joystick module. More...
     
    + + + +

    +Macros

    +#define CENTER_VALUE   (490)
     
    +

    Detailed Description

    +

    Header for MeJoystick.cpp module.

    +
    Author
    MakeBlock
    +
    Version
    V1.0.0
    +
    Date
    2015/09/01
    +
    Copyright
    This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    This file is a drive Me Joystick, It supports Me Joystick V1.1 device provided by MakeBlock.
    +
    Method List:
    +
      +
    1. void MeJoystick::setpin(uint8_t x_port,uint8_t y_port)
    2. +
    3. int16_t MeJoystick::readX(void)
    4. +
    5. int16_t MeJoystick::readY(void)
    6. +
    7. int16_t MeJoystick::read(uint8_t index)
    8. +
    9. void MeJoystick::CalCenterValue(int16_t x_offset,int16_t y_offset)
    10. +
    11. float MeJoystick::angle(void)
    12. +
    13. float MeJoystick::OffCenter(void)
    14. +
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    +Mark Yan         2015/09/01     1.0.0            Rebuild the old lib.
    +
    +
    +
    + + + + diff --git a/doc/html/_me_joystick_8h.js b/doc/html/_me_joystick_8h.js new file mode 100644 index 00000000..6516352e --- /dev/null +++ b/doc/html/_me_joystick_8h.js @@ -0,0 +1,4 @@ +var _me_joystick_8h = +[ + [ "MeJoystick", "class_me_joystick.html", "class_me_joystick" ] +]; \ No newline at end of file diff --git a/doc/html/_me_joystick_8h__dep__incl.map b/doc/html/_me_joystick_8h__dep__incl.map new file mode 100644 index 00000000..d4b3ceb7 --- /dev/null +++ b/doc/html/_me_joystick_8h__dep__incl.map @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_joystick_8h__dep__incl.md5 b/doc/html/_me_joystick_8h__dep__incl.md5 new file mode 100644 index 00000000..873ae1a8 --- /dev/null +++ b/doc/html/_me_joystick_8h__dep__incl.md5 @@ -0,0 +1 @@ +e9f3e8348c0350e4caf9571a6fed75b5 \ No newline at end of file diff --git a/doc/html/_me_joystick_8h__dep__incl.png b/doc/html/_me_joystick_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..d8180fe968bbd552ea5bfc8ad7b4251577029e0a GIT binary patch literal 13207 zcmb7rbyQSQ7cU5cNP~0<5=wW63eur;w{#EPh!RrLHGm-D&@eO%AuYooNDtlJo$uoJ zz4+s;_13$r#mrjg-ZT5`bN1f9-`@L1zE_pQeMnVH>>RpI1IF`yL8#SN;{dNoxyJMH3bg5%G-v zKNA3R5EAyQL{k0xLP!|TTF?~(j6YoR$?8k8{}nf1@s;ZfV9JL}y&$RKzqb=Y)D>qQ zZq?GSGVeCKC)IZn-_B<5cB)8fVD_T}9%iKd&kbV(srf(0SKfIV3eEe2l;a;BD%1Ek ze=*`K30u+*0WjyAe}cUFLBgg@ef9g!XRXbGBXeL-XdVp8YD^F-D6OAt=)ID>4!At? z5a%I<;uq|d05grIgf*Z6&&OYV%aW(qzJ5EP%^Kzgvo1X^NL0QY|FCnW7-IxW0>s%$ z^!+FAJ4+VA9!1t?iG6)L9(;NVU)AeG=Dd3{Yts7!-vPS!{Mq}UhNO3AE`<#VPZI?k zeyU%Wn5hBFPf+-ekeP}&K^gKm$*~1Q*Co0C8Idjkej}fqc|;>WX;Hp_k^lFwAJe?x zz!;ybgaa^S$-ebZjUPY!{*$YS%lEr}uBuLGPWLISB28by!jVhNET2{w_z{i7Zkpf+ z0n(d2PLC;UgAXJL+47*;Im+jg8g-ZcV1t6SOsj-^K*n1y=I zZqsb|!=v!g`?%glN((G{+{iZxMgeybR8mjh(vpW7O?r=Y%6NAN|G3 zFalK7Ng<5ViO#s3`3!%J zh)`Df&+;1zGGR>QmV#JT#JosT!5*d%LhrLdPp3|+v`!%xr!CuhmZs)roskjs#Xcq{ z+&07e_C73UteJ*{m+|YbHLCvV2=A1edIMYf>EGhD_Wx$yrY+K2g>z$C3-&n3-)_UL zB8YkNieFR?WfcWaJrf?v7R`Ni-7q3TSix@1&mJM78l(2 z1cYW$E(YRRBXT2hS^7gzl-L?6XpE7~H%S$CGZG!7G|wL11G2BEgrOK^`m^*z8zMn2 zp?|Wje+6q{c`qd8RC!gO=@hHk{l3rwgqa0|5m-NNr;=u=tQrwQMT%QiP*|fy@u+(C z5=s9VTW@onBx&FKGxenkdr}3hSyky^^tY0urMjmoU?@E#Q-s>UzV&QtcwJO=#=t#< z`xm;TBPpyoT`;)WEDlrYoBBPx5n$M6momXYSMh+O2@i5->lhh4KXBe8&5Lq=B28^E zDV;62OlazN(4J}~c+>l0phzu;cEuokw457fs_hqghQ4(h&_ zHd*1FtMwD(Di%RV3hM zL{1+ZU;20H$nD4$LH2qVxI0 zlV&r2QQYlvqgt3k8iXf2&@+j60aHDly3GGghb2_F`TV81F9 zIo%b?%+%BFK_4@7n%Nj^!@XcU$SDi)DsP0}{UAc3ZtR^y6A{dOcb@Z-;{^$%B*SCt z`|TH`2*_(9@~UXPoVP`0@Xtzpk0qjZ7Y(^QoDXcx(1O-b?{S6ww=Sy4uYIQ-v=<*o zLEWH2;>j!gVH!aOn_a3_Ls=hu{IN@Nf%Y| zQnL1q!6n=1v-c7a$2bSnZ|t6Etl?Tjdx(kdA0@)|Z0ND2EzC??X0wFIybTh5uB*`D z-YiZJuv>FQIvCvslF-kyEwVDCD<0j{XA8EzkEG|GHE7|v!4>lEQz2(TvG_w&!OVR zFL_=8q22Kzw8uAjF3UOxmPIB~m~m1FSn)dDSfNFZE``q?JcgjF2uSqr&n?B=5tY%p zNg^(t!1!QHWlY)N-S$p${N`h843-r=t%$1L#kldhsX}%04c&beKC1(ByG#qdFju^^ z;i|&H!1upBzgD>wV5*sPd9<&GXz<{KqaciCoshp_Fo&$n8wsnMt`L;B;V_IKS4BRP zGI^q**`}*YoP#!XDTU}-;SXGuK|8kfL!`}-2+1}$xWW`pVR75p4wX4gw<4^Cp)Syy z+M9~=KWR&Y)2oPto5kE^4Vm#zCD+#@LQ=h}&-Im5wc)_=?SB6NLhSSrMF-(zsM(zx zxX9-SLJvOb>>u&4F>Qic3z*PgM#l{!dsp5ZKdDQIm>l7(@IFf2BZJwgY3^Ur>C#nA zS2t96bhVw%t@w|m+wUjaa)K!L53&&|cLIEpJ(H(L3GG8f2k~0FXEWY)iK)#Vv)x4C zHqbKI-H|kuFnmyA*YllTy---WWY8b8+&8~)>j~&C}%X4N#s8$#|SUZn#P()^ZHT6&$MqI~iy4{a| zu;CqM!?ArnFx!ZY$rniZt7xJQ$)%{*8$$)Vtj8*E-$W_LC|sV|cWI^&LhZGLee8-c z!@dm7em8Dl2e;UqS=q;mZu9acvt)8$ps)N<6a!+0u4~#gj9bX;o>tnksgc+UuIpi6 z+_VOqB!ONcehq<|c+HT{PW=RU=?&kD4Csn0STgq%*+CZa{q;ke*NdT{n| zvoq%pn1^g|k-|{%>P}s-QEnCV^0`=BOIIv7PX&nLPaYtK{JRJD+KIJ>j#@+o$BMlB zc(UCP-JR1rxr}h)J0su0ijjykJHt_1hIph-o8mNc(-)kG%L^O)7RlcTiwX26sO(;B zD|M_t?QX5GfUy*+t(z|pLl)ojMQ)|eh>F7}oM6ARA8*X8)Tg=9{E+qt3n_YZVJfmc zz>eG?^J$+)Ni7U}yGot?kswTUV)|WOxgnBsygG2-b6sg=|B~oY7!>-AcvK*_2ZuTrJJAD z@kSEE4Se^K;-;voY?aSXkIaJTVh$F(eZOkyhs=qlcMl2>r$j_V|1&3E`v0N|rdf-y zZ;5Y(T}$)6;|&$q4~`BvaIp#bbwZ`V$>nmy!r0WD&nbTkJQB~=+kWBt?OMm^BbT;l zIRHBg(mqe*TB^Jb7iq($#>YwfOC{)LUrtdZdL0n|#X;FfMY!_r`>+<`Q_X{eQ;x_!>6XdcO~kfC06vH5!ZtJVW=Nj$Nn4$&HbWAh{>qHnbDflo$5 z{GxE4hF(ILct`WWy`N94LN!g$I%fwIvjOb7BDHT z_Oo~3AGmjxgACVF$q`WKP=%1LlKX6e^VcmxaHcQml!*>Qm^u6Q`TZV3@rcYpm58Lx zXaw5VY7$AVj+M{#XdpOf)3%-}%6q8PG@@is_Y;WePxLX0tTS)FPzgOxwL5g^DTa>{ zPe0i0+^{775zJ%Fik%WS_p@Vq@7P4*PJ?6BZk!_~z}wVcKJd1JXKV1xG+Syb9f@(5 zmvuJWi1GGGPt63mrH#W6rEp7JM6U+)9@wevo(bRS-AMKEiK+FVWbUhxPFGeYfoB^? znYMGo{>qz7%u^#M=u-gHaB$lvH=bT2O`9Be+Tn~(%TQqA; zF89z>DMxPbWyI94DXg`8f^r-?dwWo!)uv7M(dK0cpl?%~>e~$uTQ>6$wAZ<-ueU3S z>mlAw0ijCd!QqUCJmTZa>fV4$g>StS7RUSnvo6#RfeS}rsD=3|jOYJDYGjQx4d_KY z+?0G@pZWdLtt=j_>!o% zD#X+jA@;A_GlaR+DjEZX<3^=mAw#FQ;gcX5Kzf*tOT`kpO zVqhTt0i1Vv+y>VlLinOkEMW=TVa*z|zD+Bz>L`fWh+r(lI%F23xpU*KzZXg~J|1*? zoN1@*lqx~}BN=Ypw=d-DgiO%9yp9hN8II&=iCX*(MB3#i3lOiPa?R>B{RMP&p$XEX zijs<&-sM=c(WIkH40D; zyjRjcG8+vnMdWo{pBZ z^~7>;S&s!YJC`QSu6IuAd_pF|$CjR`ia{3-_xUJ=+^%(k=Tcx`=X8d-WDk1aQQ4X! zo0J^6du9m;Aqo#?JxL+NJf4Mcwkv-%Kp*lcUXJxW|3%-F#nyM(cXg$fgL0A6nkr`w zFUPA@T1R4}dK=5F;{#sodH?=+X>?b|y@J^uN94RR{XiXNc#;jQ{BRdu?16E1JT1`Z zVfM(z3hjGY5EF=f;gMJDBjd-kFBEkhJ*>Aw&~8eN6M8KAk@ozeRz*WWFND=r6}JGk z(0Uf?`5X}d$fx~JzVDwGmAQzSo}JkVYuHvtVW92HkNpV-JV-xbVC$ZupCrPY&6btf zenj;8Ru*(O6|Gio3)OP%)o=o!zB%7jNVBTr+A8`SbJ;%K=4j{+ZGlyFGI&Jr;2#&p*31CO*mST(4 zMTIW?;2WKn;}HB25v{FHmW-~Fs{CDRwnDAa^82>y*3A zWFWTdL)`1pe?&STAzapRLivKHUR&4=>jY3LTv1vu;T7YuA_ecZWs{CuWXzkGkw zVnaRVR#^zEpZ5~1T((D#nord(Vo=xFUQ|VlVgtFk{Jm#C1vE4XO=D{5+8(_NJzo@8 zuXq=#RA4!{2+(CV_7y*;nU=c2JB^t`<&=*BcW=Ut7nCG+&w5>ZiBmPzpiII#W-U|~ zxRr!Igj}fuPIa+ga`;93?C5THU6EfK?R4;7tv*qeqJNS`Mt&R_wlIjc=5yjK3gMGK zaaq6;KjjjSw=wNiI6qW|og5IwUp>H*(R{b))CrA-$bpurgW$))Wy)1~9R&A@)w z#%x>M9pu~2U_89>iT8_djI6=_FVp#`4=U}7XgDW4KD}YfcT z?$%ID%Q*!gOTM87@QWw`$1^G5JnFm8ZbB6fa-$g$lBQ^guuxR0BK2S9(aSDG>k2{` zBfVx|An&nT&|pz6Yr*KDAEF28P8ubQFU|$T=ql`@$QZS^O89Bx;$z8ZA4n!l%w+GT z?^~3UDSsdh=J*RPDH>50Yji*LV?j_ZK!F|l(y$B>6gs(vgn(37BSAde8wY6L>kHD6 zZSD{l;Gz>b-tAvKY2!B>(c>LrN4fC{q73S902d^4Qy&yGTR9w8AN=lh z_?u>m&fMdG@2T{ye97BMtMY5?=&H(qn7k~?N9`O@yI+Kt%SaxSL~(n&wu41Yj>aN% ztP3NVA&u{UP?vHa`IlgWNGC%o^(Z`|(~PN(< z%YRc|Pv7Bniek#29tsV9Ib2Dg`_1dW& z*q-2ComwQwwVRV+?4dw}`gA-~Bx`uNdq5Zs56K_kc_TXRXMRPM=GbqOrctbPBNno( z5k>8}=!g|qx5j%NCu~u!MIm8d&eT-p(-VVCE`6nPJ}b$WZpp_jfttDzX6XP(f8L(6 zbmKI{upJ|otq*-*24M};(M-ZoA*5hTZr?A?sX$y*n05ZnEvW$)j^@&!EN%u-A47etLACP#F^q$|lq*E|7d^FL_ zoHs#$ru`9LHtr%)aXeZLh*&8O`E+TC?t#{`3`k-xWi24zwYOyAl7c#MQiIHL4c9FB zFBbq32$DF|$*N1&02_$wf_Lp|0sQ3-Hf zSIY_IjJ;5cK_$V>mKnIZb@wV)RpGgDT6kwlEV~a;aZo?piQEKomoK>7nmhIh+-!%; z{e<_@>{NPv)!=CzW$oeIq^C7gam%p~!z=brwoNS%I$l!HTQIb_F5d;emRx|g3 zTgba5FxfJBR1eCJz?qv+K8g2J#Q2mO%P9|ULCS~X*Qx6$9YExN-Z_5cm|X!8^@1fBs1JG||I^Ts(_*r|S!zshH&kWC4CY6xy zu{~;As4EGg7k5sEHIn$(1d#3NU5c$5_xFX;@d@`K;kp}$N1@u$^=K;Xfnbx5%pldk zV7XHl2=55~{gI(b;WmX8e!A2sn*siv%o5-@>=!i@oMA&-!?+=c_4?aHA67j(Xhyj6Y{s4nM!da#+w z5TD$4{S>AqH{EwAD8#QHdI7S8jTYF%X3|AGWp>%w zicxWE0gMH&-^g9|mkr-&+c;?G@LX{9qQ$42Y~BCpxuvgdxdbHU)4%Uz@L5DNAw*(4 zUB1ZynWDBBSF(Kc^yPEDCjX)wqSmM4vhF->V_9Wp*aqW3X|@VO;xUk^En-Ua7uKm} z27pruXU$@RMX48%GEx+}qh4>yes>lFL>?gsMUx<^b>p!y?qa(5zq2OhLxxI&>fe=> z7&7bR@FyCyn#`7NflAf@dM1Ks#Kb$`W5QzA@r<_&A0OpD5LqcN0@-Yg0rfJ2AU1~X z4}kWcOnsTFR#lc82Y)!dYkL3P=75mT>L;653lOf2QTN_gTOE0vUB|55Kq+zz|5}v* z(b?Fje%P8HbH>8u?MS1{-;!PnpPc%pzl%NlsK+5JvlrzF!pT(+^%}7*Js;mjJT$Ss zG>=1@^>q_N2kD39t`-+1`c8Uq{*bN+i};P|FaZ87PQ7yYP-)@`<5Kqk^r%2#!MZ!6 z!A9B4u6+6(YjSL~%fh5-)Huc&-;x11x`MNR_KPqO0*d3Bapi&cXkdex%L*VbBh^Kt z1_LT6)&e+(0pS$12XnPLlXDFg8NYcGgy~o^R5t$?=GS04XM3T>yYARN48YT$LJlqe zQav+$Gk;q}5jTic+ZF68*7A zQskZRa%$uzVCZ^$!eYv}Aobye>BJX$Q2fc@;pQN^+bw3goR66|ltSaphnKaEo(~9` zM9AS}IW(B=5pF-@zL8gf1f7?%n=aA1{sJ}N3lq2ORbo#rC9$w^Nrh`DTd=*+rcT%M z%(M;sDrzSzaDBfH>?}I{*~<2S(TYSIM^mAt0IUyD{yoHG(^q9Hok&PMbwt|m)580* z^hRM&BqzAAfK<$lb@y9H7)D_2mK&1Hew9cYEw`hbLV>isO z$ry9T9fnAM)2;{kwMc-Qio|sgTITVh?e%UUtP3g_45YER zV0Z_(s$%_KUn#pQ90dQmGPdyFMF%fLwGGY=eAK++Eq}7$fy~B^Ji54Kf@SXmFull2 zRs1l#a5V<&m=_-DTSAdsJP0)XvxvDiBRY7Q{Zv^y=l|ddCDUk!TXP%MjA(&4;!`tl zlC5{T0J?baX@3Z@?5sOGf@2g3x>&^0(H@FNum8goI*VQR{-Skkfq-HlElwI);TEaY zGx_+#ao95fJF#Tj|6KHBLd>z+ce239suHg(r9ZgUfVZ14n}=Ic{K ztFk3ilGjnol2wW-iZdM&iYJBQOBHsR(ge||DDb*!j6|2}n&KU7)Q_y)s=QH^;!{3& zu@D(5+w62_FRguB9;Luk9x|6=<)lNz87NY&Fo)M70;Jysj)*WDgT}PZ%)y6>fe#F1 z4NTIm=fvJF5@jt7Tk+dC+5)W!!KWXo2=ulT>Fg?PjRL%zaQa?R@VL~Pme5C zfg=UfQ@HRvZfmWqwZQswA1ftzuNX&*`2)VDlx;}RtnP_k{BtS!N6f+B zKqzCZ;(rs3(%kSdresZIG*nBWb{fe6sG=7;}-saXSczxOzqQFP){)` zoF*JkDCC&Za(<+!vi&F^cau~$_DkRW%Hs|J0h-kNs0N{VYrhcw6g@|EbS=y^ThKzs z1_vF2mV@W5As3R@A*YOl9Il+c>Cd=|XC=KQUYL;V`e-j@gSix|5L|`wh~p>7TBLREt<%mR1%#$FJ@lNIArauEP3(u zh5cl55>US2<-BBVUI(iiB+nMr!1FqyjT^w&{HT~Nft$nbv1kAw3<4^ixOhtPvo2{o z3992iw}TuNPth-2fx6DIJwH%#S@At>xHG^L@O4A?4ceWB8(p2xW{- zEua+?vDb^Iw8kiRaoNPSd#Q_-k{9#gi2nA^Rpl!<4S-aU1P&9@Y_C#?gc5Yh;clkG z9TCHv-@|Dl_zTWPwHNYa-h~!L>{#MbsD%Tz>p1Im4Yy1fY(GIatS+9-juK;jRSHUM z>y4HKJ7--z&l24m4=>0J(B|$MvtsYi!>L&i4<61`K2n*z&}sWO&}Z;fVT}>YA-Xo6 z0zhgja$YV#GxY?6zE4HMjJ_z)4$oIu0>&EKM`Qu-wq+`oNaV!1;ms}rIBZY`=^q-9TFObPD5V9v=L8L)&`F>L=Lq{v(mQ<58T2`=ith9_p~+ zlRDhanOsV(+6uo=H6_6je7J&W8`LR&HxgLDTy8#kx13?`bhRl)@&}V? zBn92$=~>%Hfg6a4an5QFo^TeXjaH;}Y_yA0b~@jW?ZfDB(-NekK`E+I{|J6BhXNZU zfv6j=c|>{$vK`Si2=v@>;&mRVEj^KCW`6Q1sO54kbARYmA4pK*m{=L7S%!$LH&i_r zDDbp0TL{35%Pe6187{upvpjz9Rq?oD?+U4aB!p1h-Q5R9(g|$a7+(+GwI`m3^$y+J zG4X9SKt|DLrCX;moa6g&uS*-L0bDDo(+=<(x6+y7ls`lWS(+ zV7s{fTY*z7Q_Nq=o0=%qg_UEqDi_Poe)m2D`3^eF?DITqy_LssO9Y`r257Ld(f{)3 zYmMWpxaUvy+Ai5lE{n=zz-uw!kM!&0;N9VMf4m>~awdG<>;iwsUZ9JAJ?^`^-9c!{ z6K8_`0vh{(D8g3i6`umim2e@~9dR$Xev!X9kSR8O$IW$%0 zi2NWeEsZ8oqV4#z%L?vLIBkkcK1YTh?@$H}P=G*nss! zx-7q|O?ZZYeZraI*IK`GCu84DChqHATJMC7?Q-}>^%snYx?oT+bXKG{dQ}*NlF1X= z0feDvc`~ZLlUgplIn>=96Ltsw0v@YkbTsh|3I!Ds-#z8V?fGInMTG2ULV+H4k?;(ln*q+2e&{*3*(R2KOs15k*4RJfWd2gAWab z!N;iT{nUN~au@CIdfgVkkfjKDr&ne=w*n=m=*0o0osSE5qZ9Nw8|Oc$VnFa8W;!y` z)kFJVfaqXki+O&L4wVh%`!v?OdQj)Hp4!Oztzv+e4aNiT6$63}gM zx-#F^=rKrV?CCdS_Aph1{Ed1d+RQv)E?zHrBh?jJI0jO=f@a}K4G=U+C>PMp@^JlM z`g8w1t@-L-lO)j1BqLL-sm1IB->D43<`ByEP?HfE=b_jxWm$D1wn{lJ8CjZk@&Gc+R^Fv z?CEzr>yVuQR*yEfvih`-TLrM-X=TWDvOR2B&$zc#zP7&2+_G2S;hJ*jG*a@~Tk5)M zJl>v8aaI+Q(FVN&{f|d-F-Iq7B)}60_wJ>0VcogYkz7ZjSK1o;&01}>OQFLnzyWH zE7lMA+Hrjs)IjXU32DvOOl6 z>>NT1SU+Yi$5=D$f=W*{8OHTLlsP(APanvP8w@#Gu+~JWS46pG6|s77mcO&(lVhzN zdn_QMQ|0tiN1b<7-d0Yy@bhWSuJK@O|d1 z8%YVqGO(|Gka~;$_0Hczm3%pEj+X{;nda5@$=X}Qvx-6TjZMZXOu*z%U!7dW)CMI_ zPeA4h6}8G7E7hws&4XBcdBMfSwY$j!GC2q}tISyzv?>pCr(P`S{s;peKK>Y@v9Z$uc zwnjSDC#AWSfl9G|_&No>pLKL$*ex1$ELgpUN6i|aVF~JRL950SXFa0=%1E_9$daz6 z-?eS0fKMp$XbDnbR{hsj4q+?5x&+wn0lSp0qe>i_E{iX&1MW8kF;%N}}xg~Cjr0*4MU9!#tvtbNm; zyX3h4h0NGyT;zk>Fb|}BLzltB`E+Xx=v3k)U&9)9>orslV-PZGD>5x5s!OoSV7~RmGz` z*zL0(@M7~f1RMTL>8zfTK->TS>*_zdNA=?wDgGksR06zdgQD8Jkz(EMQo literal 0 HcmV?d00001 diff --git a/doc/html/_me_joystick_8h__incl.map b/doc/html/_me_joystick_8h__incl.map new file mode 100644 index 00000000..cdf8783f --- /dev/null +++ b/doc/html/_me_joystick_8h__incl.map @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_joystick_8h__incl.md5 b/doc/html/_me_joystick_8h__incl.md5 new file mode 100644 index 00000000..9e80ea97 --- /dev/null +++ b/doc/html/_me_joystick_8h__incl.md5 @@ -0,0 +1 @@ +5281682292bd25c9d2aef0a0077ecd12 \ No newline at end of file diff --git a/doc/html/_me_joystick_8h__incl.png b/doc/html/_me_joystick_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..bb15ca2c21bc3c6f0b8b7052a0c490d0a5ca8ab5 GIT binary patch literal 46485 zcmagFWmuHo7dA==NUOAzfJiq;450!7f*=hJ-CY9=9U|SG0|?UH4Fd{D4bsve!bqod zoCo;*-}hYC`EVXTc!|Ta_g;I&z3z2S=m$j^e4M8^C@3iSaBrhX{a&!A9yR9G|1?3rvoYZSIw~VcMcQ;+rrtAIP8rL8dixg9KG+vjO zBIfMBUxMo?Wc9;;(avd0ly__S`MwmB|Ma+4x%0$8wJY>-!e+o+{_(a>PG( z@#7_aKoXdb_ddQYbCDL*`9Z|w7l`fKRa3c6Uf+!Myd^Fpbm7GPwbcLr)BG)m;2Aye zOsneYwRfa?vu{wv>F!)RxVZe2S4KX19P3ZVw1IN_i8wK{V;;U1HsAv;=BO^p!MFeU z+B7;OB;*G-w_(@kLI&BSQoS~jjfeE~yzmFgSdSjxKe2<#(+sz-03P1YgLE?SKI_awj+DDb*IujPm*`UE0~(jFCf4k zz9`-8A>=5%jD!-sZts`qlx@R2sq&M@k7IXK?-$nQgYM{%JO^HSrEvf0*5SD($fEb` z<(01Q++-ctY1X#Ec0Uu$`q{&2ac6B|a#+xJeo}mD!DI`8{5dwPE+u7R?ew3q&m*Lz;Hb+R`|FMT+6iC{Y}MgrSh30@c3G+yFOzp%TPQDG8(D& z_-8eDRf>U2IxY>9mXgB6v|R!0diPMgsg0Dsy|SQI#I}Z{tvcWdKa&32Go2D6@J~FZ znI2%fchCR1c#5sJ+hV+TPU2uenS6WuKb|G09sNuHt=jHLT}f(znZ}(a_EvS9MKm~7 zhDupV>OA(|nz65k9$tIg;QP4kOYrn8MWBW`9#^`CFj>+q`#M?ho~jz~7Z~x=?mZjU z)c8p5;sLmg=)D=f!E1)aDP2BuaKFM;JV#U&`0lIy3uJWBT?E;u?#?6)bbjGO7_f5_ zAUoa&{g|n8VX9=w+%xA+bC?w2$9g+<{*Rw4)o@qps4pZ$7E@~+_4eS;J=YL0Pb2c6 zWGPrK8{04Q;Jw0{p0RVYlB@RfA`U%%qhwJD#|4?KqGpMM3UhF?_b#>T03l(zm%(20 zMb-)QdOoe{C%W2c>_M*0Nx<kk)f@~J&Nsk}#xbj+SUA27#x? z)TiG`2+8vF89qUJo(YGA$e#RXfznji(F%GaDl!*N-PDuUKsqB)?`$i&zTy~1 zz=f<;RuP!j+gv{kf&gnuwqSk}C$`B}({^j?2*=m( zUyph)sM$V=)CZ&1qWE@eSsQvVelXzg80pGN8mv^ycLD-S^S^bC5%15V&ghbxcxc@o zBdrCx>rKEFEcSa(1d~wMRL?T%EOKnOwhz^hot2PD6+ct$xG8>M&|qma*KGOStSsA5 z4YZ$O8xpLri!uCtHmaX)gSG&Dqvc8S-unzfN6$O=pE<=#N{^PhiG+HWte(*}dRRl; zo5KW8r^&;4cAmm|x7zL4RHnxuB=X)So}9GbQtS`~e&~Kv+)wAVN!K8YIibgIU-EgC zFW|m?KxN2{Sbi8>g=y>;;D=&?evMPwsbx$zL~1+~;yP)wJDd{o!{KYS%x!#~e{Jnl za$WH-Xa&{nc$I;`pMK+uldYI7t&K!G8NSenE8JRdss2n$Lf*ZTfI^E-bxQ4E-`@mP zt`b|+*RFSclR{xUKmBE;T9ZnHlHaBL0nW>+e5>ZRd3|ANDa@z$nPHTTUQ+JyRGQ*q5m$*)Hw0>_{y;=GRCr7^ac*Tzp8m$R&@^@X*URsAXe5xC}oCIIG_uX)yH1pu6pj=X}XzsA* zCh8v@OV!yF0tei-=k~y5{OLBzmtU`iX31R}f~Rrsf+j8fPsB%-JPb-fxGkXM0#!>G za$5(!O;C_}IK5%i!bB;oek^4?i6g-;yU!A#M3I4F^W3}ig3HNh4lFP|DFbtquUA2P zk3xWDRQTXY?CW>;712grbUE0-i?U$cAg@zej6<0<>HLQprv#Rw)2XvEB{CGMRN0AgJ)EGWJa_mDQCqchjitmltbcbCRHsP@tWA)n5S3%jX15{}%pQ*9k;XC?-GNq$w}7v+aF;`n4+ZV|uunZEOu&m%7YMm? z{$LSk9D^hxYU9*0QA|>`cXzW1&ThbEAmHFx8VT|MX<9L#>a>wAHtOW+@*IN?q5rY>FA~7ot9m3(@mkzse6!k0{5$K(zZxE4~q!k>n2fg_m)nQ<=#vM{x&-Q#uP`y?#+0jWa+ZI|b2AYpAe9C1s0qo0~Rbe@K{_#M?4c-L^2!T@2zN23Vd@<*MuhC)@D%9 z8z^3Ij}Rs~_E!fzhg)#;MVLFyRd(N5ZB{_qc z_+i7BzhbpCp!!bq8PKE0-@(&Zx}4HZLcx^_xLUC39|yyHtg56*_tI=Xuz#xAU@2#9 z3$Odlt@FbAcm65=Ib26UxTHL|oXE(^N3$X&ooOyS#MdAx5uMUssYI+SOB#2XNqzzQ zb&Q%aI}d8BtD96vJ=HNux$mWTe{>VIr&DUCK{7j4i(=$SlYXJ6`X~a)H}YvWwOK-= zqnYg&0h4nI@4RZ6`mdKhv@0y)gx~#j@t@8YJr(<;FD3lJi#c`TZ_D=?a+$DwJFj1( zZ2sbSTLepcgaHz0N+ABG{c!?!{&~@ng$Vw}ACG|d05#bp=C_U9Ax93*RwrEW@_BR#nH#V~lSrGBjvPw4xbFspZ4`!=FX zL~6&f&_sdLWz1E(LH=LV4C{0gSP=$A8W$$|Q(u05HAjua=s`cT5hr9esOz=pKdM)Y z{c_*({dlGld&Ho!=baH}Gqk#HHR-enB4t3`+CU`C7+pZ>GZV2{J--&b+Z26S>=$aL zw&eBnv_M#$1u1ijY?YCeiuF8%f0uv^0k;I2jofM21jF0C&-I@|TeI%(|8@4J4$YEW zKzK>`7IfNctrSy&+pN?h&q@cXtN_g9R2^%R<>)|^V3 z)abUF_tl1E<4j0M#dK)W4sg;Sj z%YvxGC?z9B2E2IxWtwb}wSzf}p4U5eK)<#|DFbsTK$9htQS>dO7x+%|ElWV6jE1CaGCZ5-C#lNaX;Au2NIv=1g|p6qNM z)D=Yq&PT44df5BZJxwRGR4fq5eOOo%eiU?nsi;P4?-s?Fx~GPOX_1b>;TMM?hi;<< zE91hK^yY-(66EzI--&#_bk-3F&o-9MXK<;L%@Uq-q~K}8dK-uwuo2jBE572%3gofB zUR3{utts2D+xm-gjm8hO22N$KW0K zKD8{t>FStxc1VG9#qyB5Yt$Bh4*+~trPDJ436yqCRg+|3Nj|#Fy|+t5UxTadI595k^M72o_^S3f@Is1qlamMB z3G`78{H;`U^!XJ8h~!{Zy8GCx11Srn zdC<;a1xNkvzmr2?g(Kb!)_Rp=^1&j`>cA_Qd{EZmQ}2RFjo)xa_%*@52RiC^aNvD) z?&d3t2yB18$z=Df7*8g-hx@93E9&u?2mkTDarxtXt$B&g<~wvjf$j0 zD=%lM%~Ljyzy6~B>WRR8I9_GfA`WqIQn0+fMc{uqOq_XR7j4ud36x_ToI*52r*J|3 zucRYrkV3fNsW)b~-7dxW9KkqHYAlskpRic(#dEJwDxlLq8x19Kq3o%KMTIqTH>@pF zG8ha(?9M$d+8EAwm7cwfA2FU&_qC^P{%<^Dy@*h3@suWap5uHFJVC@9B`@X%(u@120k}Mg(nb?T0*~R;d!d z=alz#(L}D73_69L1#e7un~RfqXxVVO<-wstl%EyFOIdsGR9Q+5j%~) z)t9iLnQ%AJq~D=e*KocW%$K6~$*wP^9DwAc!4+=>k_$@0KJOAem4o7_pvIHEuj+W4 z$^`C@)3c%bN515zEUH#t)b~@}v12#m-9E;WkpZ!THEZ_?>H9iOhNu?-Qr%bW5Kj>8 zOJlTk4g+KV{a50Z*lw6w?|WZXX1LOnq}kcaBx{`q+{XZ32$Q!6A`*@@*yMVJSx)nC zHn>0DCkAwap3ZLa?k-v8+Z5RxWw@lDG9ftOl(~n~HBLEoGBEkCpj-S4HS(f4Z3cNZ z9_HRK%?nI^u&&QWe%1E_B$ z-j!*P|Kqy%UhfZ?N7y?$gc+Y5q3lbe#eK&{<4q`Q&%JaWviWIt#rzIrJRUCOGX;yT zOLPejFU!9gygosO?~u~h`sHJMOGAH zhtW^sr$a&|e2!1GT04EC9Gg3h*Srj0S6$KZWrf;A-`hlw8N7TE_xl}RzrREy#L>1& z?1@XcBIM~M!FllIN$Vvc>p~ z*2cfjocgMdZP&5;y!&*&9~zdjLuwqHQ~EviCH&wD{Lf9Ix`~WlIh}0;gf9s^)_PGJ9AA;L56N}^*f7T!%iO%CI?ps ziA&TF#%qUpfC+zTpyAuMG-~Rp$@l?fE@28WAyTb-E^nHPY@O?0W?8Yo6>iSG6i!2| zEWzr?m6k;9_Ox26{G=S>NJ#Y2PmyyMj05P8;ITx=E8vRHSr;Ca$pz+KpOzEP4gtxZBgvU_&H$W;95 zmVic|AIxjlS0vDHh;fQo#6%?`Rj6XhLDVst%5}g;3;cCeRV{Ao91;PW&5EW>II@18 z>g4&Q4P#Erv4iVfUgLvCAqfLl?a_`VL$L;qRKxTf1oO9nt~X$;QuHL(cKZe1#X62; zkKmPtV-fk`2VLl9TA+e%qU*Ymv&+IwmM|G=7qyqUgxD4B&8xd&7*`pRw{RL>qP4-W zf}NF>K9DuY?3ALbYC?o%H9`b*KoC3r#?t&k-*B48p>F{Mrmt$E*)ty$(8%dVO%^=zwP)lfrPB09w96Z&px{7@xbxcIyeP7x|n!v4{@~Tbz=$a{q zS8C$HQ>4?s3v+E_TN0TrJ(j@as}s`4SA`6rvNy$Pb`=w((|M#$g`keEQ#sK-RY;sT z2awgh0REWPV0c>>xqc>=&OIYKuN2{UI+50vpKMgjcK&9z@s_lcrB%;-=Y-ya4W~}} zW~z(C!sAbj%&g&jT}PS4v$D1ErUkU2K>q}`@x&851=O-&k7uM7gcv>eT%pi;87O_M zHGXE|CP&e`pLO_1@|m>9tcH2Om{pI+o5{xgWRy$+b6X2h%Gm(29?|-vu^k_?2P46F zcMix~nmBcFO|!TC2*Gn2`K=1bS0>|4^{cl9(vk>jq_FR|E}&{7J)SCMVxXmEGz5=0 zz?7JdEI~h&1achyG8=V`x>WVBFk*QTb2#;oNifsJZ4xc>eck@nF@dm9d2w+^9D(+o zK~1y(aKZ46s$Bt|?5NixTmn>jDVVhtqVpd4&{<#yi-S-%->4$rm(UHK^mQ#ypaHFc1ec>#o zET8k`4lV>mx^+oBRXTXoGwg@O9xPcLUUm@7IQi72ewzhIyJ&9&L z7twR&c~I4UPoqidxwq}oDxDfFDMJ@{kSS^O>B2Es+)(w~u7|h-{Zsu*#bTCf^BlxD z8JJDc<6~jt#l?aLxW8~PcG+P6`GuzK7u}S1j_iB(8Cd;Kz2v-_e7S+erW4BEm_8dD zyd4BmRR3SbTPql%vHk2<`Gh(^>{~Le_Y4TzCX6dIOywY+(+AAv6dlVLIEk*0;g>VM zg}8Th%w`S)rMos#8A%k|K6aPzDV$i@#F*tz2St$-f}9UnWrDoixCepm&~-Gr*B#}Q zuPj4FKq@SgqYTc&H+SVdb?g#8IjOgJc34ikiQubl(^dE?F+n^t`imw4tNpiwwhhDk zeN3)Mkz`qWYPTi--F6pm{V7_(4p+~U4Fq5FVbzY=Fmc%}n-oiz*SesjMYiGriGmco z?<8IR`BR7f;Fu5Gfu`78Khqc4Qf)=5(f?R&}8V~;+|I_tdfO(!AdBk>R13ewO z9Xohgp8Zb?TzCKTa2+|Bno_+0aJcnybVAV>WR~x>w}kKY8M5KL3gNpj*;ao%EOw@) zRDJTtWj5zNW}Xi!p8s|0BJ+fQTWd{y=V)VFHAEdDt<>5%?7ET+AC^HvdOpl)jJUWc z*@wq-;9KnUd3&5IB!YMoCKRhWCIDc@ZIVMlyGN{)#CX+H?dh#HJ}u>u+Y;E9R6Zaz zJxVm~mU(aK@!N}A#n+<{@*o#vNBw6Xud;F%ZqCjnDz35E?F`q{CjPfTO8UohG3W|6V4i>gNh$ds0-Amy$M zw1qa7%jb-IHmc*(9&DL=XK<*WwN=>GLE$0Z16BvAbA6dUua(kOA5Hcp5565v>%Epx zN5flsbNo!IKEGkMFo^#Cc3u~-FB46{;8p=op*y&e1QjgRC0Mp2D|Y*z_3^!Wm*bXI zj-2gQH|)OTcK)EhvK~?Mtjqr;zOuJy=Jo5%^%JGj%TbYNpyxD!d>lH|`#AaCN$-DJ zfII#&;O+k&?s~j^5GMwXU$BcQ-H+Wz3Z{KgN^f} z+2qxzO)JZR4h%Mu9&Vy+8!M1BdBy{ZHfpETBq4T~%)rcQ$^Lcy$mM0MB5by?`MR~F zoXz`Xhbsi!GF+co)rPcZk$HIshGS88{~JWOG*ThY;3@6EAVL~eQUTB)_DD24sL)Ub z#YDHO(s*jM?IBuTfyCm%MT@7dKIAC>;Q>QfhsmCcpIevU@5`ZxI)aK<=UI~Gws?9~ zFEek!@5w10y>_)pP#d~hPrQ#HT|-dMH&g5mo`T4V&EaA^VlbPs2k&QhPwByWaloA5%myt@pT%G|z=ykhuBc4ixDTxg)9U7S2l|%R zo@G~+c9KHQP}z1lLh_$IDi5q*+y<74%ZJjz^^TnSay{7%t(czsNzn;GO%=ZwxhZcb{0V zI=$g^a^rN!*B}FX1KVI}pOg5zeK(WHDonK+ehZVsOr}lJVp~sq4d$?7ebTPf0(pjt zl@5vd_S%dJllbWt;dhH*x2`Gl;naPdzoqy~O+U3Lt&!TZ;mBeD-};=_n#7c_)HCYK zo}=3$>dfXSmCobp$qz}Ds(o*xtMPss5DU1AB-$ z+1=~O#M-ZICgDFH}Y!8)PebPg8ozuzZ?9S(w&yi(L22`-CW9&XZ zRb88t??l&>OTlaGTuP_5Wx$*pkOJIpNAZ3;9qBc5gt(B?7t|1U6}l{K0Q4v$`-9v@ zCDsutP>o3PPD=rz?V&=xe?6sdX=7_bl^Rta5dV%aK9T`z*YIyx#Jz?lXyNW@_0D=a zBXFy4$#2(;=dK|jRc-?3hel;!t;Z((o)P)zG=JRjBWP%VOuGn2_Qzl2LhXhiI0Ho2 zXB+evxCSl$`TT$+80dN10 z7+^iloEY&jI1!k5YPnka*V&!+9q+8P(1f&Id+omY^GEU*fnhPUVz)@k?%Y;2$dv^{ z_|y)|xZ;ZBWbaP2V!GCYF5j&}OR?r4Ye9uWMFU?Z2#)ue&0DD!#J_&hm4$z8(vv0D zt^cz7G+e_QPj{8gyP^_i6=1Y9lSJCyZW3f0CX$S2qpq$FRR8iq2p*}KtA@06x97Fb zJrA#~IsI3d%Qj~aW{-xt*TKOtS8EdVZ%lLViYs$(7%d!cXHFvP)F9=xv)w3k&_(e( zFdQ#}`@_=-IC5b0yF^lko8R!_{V{=;pk6=E219MHH=2 zS}&l&w1o6+V{m^Lm^7d{$W!4jIB@e|ws9wh&-ZI`_riA5_o?WRfWSdjxi`+=y7Lpp zMaxCfjZf?ePfaj#F!gZMbAe2q{1&Ov{C|gKv@Yc~tV-viP&=oU{23OVvnOY1w* zVGQquuvgp>*@eB{nv7L8x)7Y&k6VVzxnsM2&S3p!c8{`@>MFuKf>dDTWB%oAEbvTc}|3 z3k_-S1PAhvraL}Im`()FiN@SqF!QF|XTwr}o%qI6E|9WzH>WF(`{Fz9cBddf(*)}H zsxop~r(0!_A@Q43u-t378uS?bI&_~hAkn|3c7?xyCRKOWvnS$k{*=~$X>@j~T^(%W zyR+T~98;r`5BeKuUF7OiZPcN9f+Zs|-#@xDap!X}*P4oX+ZEt$h}~@aVZhD(D}b@} zL|fa`T7SGa-RIP`42&&|QcSyHft@X(Az4}bGn+^r&WGfbU5#*xO$Xvi^Ipb^l^Yg6 zsT+N>#oFj=kDZ(h6t0LD~EX#k>1t`Bn`m2YdR1 zJ1GOkaKYenolHeQd%?!Mq+yUx!B>LIG5RI0Ch20~bp(rAh$gfrLdd-M**rI8rwV`V4tkz*M0i4BDEaVlhAd8w!h&awTjD<`S9#xxR2C5A zf<2%JrZyZ4su(OAv^2*|XSe>PJ}r>atssCNpF?eK7gV4!hnaz`1N6vjM@Zf0eD|lz z0$8lLPJH+mySbUP-(gV<8Nsapkq1aiK!ePVD}&66Wa)R4BSqd6sq<|uzL&p6|5T1f zBu)g@HxCm!HJsw)ryfcxNdPktN`fEA0&kjEFisDj2jBh2tix>FmF$(1_Chf`qUx&5 zUv$LmGRN+q&v5h{ZS>W@P(4}D0h-uU$Nb>I@2BK@%^)ax!xZU$%v!p${(n5w7rsdY z9Sa5S6qKzoM>!8REx1+2g#SpbWLN>#Y>~U<>su;m?$drkr+EqPc2gl=D4y#bQ2aW@ z8s{U`-$a_SQ5iwSSqgx#T*QR_ZL{G{cVa-bdpD1)?8t0uGagZOpX&e=QG?%WZt<-e zsyXE#RuB1Qe?Did?leqF*3x@kQF3s8Br9`@{79#$FtXWE&D5USbjCq_I0B zz2(Ni5G_n9BRc7MF^=K}4-a;a7x#mUK}=2zag;d{_ylfPDNFn?i_&QW)ml2l&ZTO8 zdh_CWTNkVZxST14wN2;OZO9JWxgbXZ3YxiAG3tVRn7l{Nu=p#!N+HZ}fWwx%Ub#)S zdprH*fPWo3$K>${}00ZSTwSP7ED=xymq1GYK2PW+y zb2o8u1}8U(E~3p07V30lrY#>!tlWl66*;!S)U)nC7^>S`({76S(bBu+x175OWWMoH zNK+NJ?0y@-1+k0`0|O@#0!>sB0cnl-WY2EO%NxV*)?r&Qc-^xHkS9KL4%8oJN4w7C z&3@(Eh*y;Kza!KW&5TAxra8W>BtkHdR-VF$B`7&(nJ#W;Fs>|1A;b#s6azXU?kLo^ zahd2xGJ-T++SCCP7h?Ts{qJxYqQss%+imi$5N>a0v{@9lJ#~2z+xhnXECUXi17j2a zuL-W%ZrNPDIZ(~smtpe$HU7S-5b(uAJ1zc^g&#eKBJbiihlDzs zf7-1dUOm0^B+n{ksb1lGWS@RJS3nH=6*xum*2s+xu{Gj#;6zxy`dc}g(ak~G z*dQTaxSV5@h&=D0APb@jcBEQI`zt#dkS&<9ul2VS&4>20Xh!5G=f;$pu4n?uotMU+ zJ0rxiDw%i(@8mYIwyYhCy>4N<=-mVZXe;60T-?lhE4pz4e80X4JNMun(}fn9ODWpBm~lPbI3>MrC7tjJ{V!wJFl$0-q}o)8g?kKlq*E|*uiCpILWky zJcQ}$P^gYT6KJa&_*@r1FIpplHjF?_swZ=qschaSt;7;gq!tvhzU{ECz*=!~CANf@ zp%M{|&eh}?4U*8)G67n5dm$mgb4Kq+t8v%huzgn_vkS7%yf^)L)l?v_koC#W8cpk%c9{qcbZ1M zB`60+0w*9Tc0Q@gb7}uph$g=9Ps@3UIv|)22ynqWp=kXREKba~pz)Udp}@dn->d!0 zgRfcZ2pGHph>L!O1<=A0p$B|p=1mKC{KwTXpZ1?2B+Wz{Zx}?yGj2Rv1okl{0*@?p zedUF-KC0Oa%fRGJp50&2ZrJSr>z~=yCW5dv(S9P+j4}s7k{6{PFA}W(XR8z0QiEY! zV>}WrM>wLpi8|nrv_pQ-Vq+IO6UX)Z3VoXn+2n{Cvx}gvirF={Zahl*9)Hb}!H6lS zPBz_5(c#;b_|2Q83wSj6V~XHUv$X^!?>7(mhR*ORK?nwN`L38OD;K$& za3(K7h~l0fkzBF_EvhTpBs!tdWly%_l}9GIo#b9azVXBimp}SYin6XnN0dnXk5~6H z6A|+f9V}v_IT+4ab-OjrD!xw?B`$vPiEqMT!}0v_P?WR;{^_$l`v`rCQia!&FR+A9 zr2ZRpqNfmvP@*A|-Zx!3+_IIvYrynMmHm%6pO1=Ipz!oBR#GLma1hxPDfoT zL8kuRb3T)I_oTN6Y-6}9N;zb5}JzSIa7?MwEzZ&7VCL?^?mO?0ML zzH=yEyu?X&z1OIRekFr$M5jFtSp#E$>J!l2I*YMb0Xjnpawd=hukq7Ldt}w$9d@S3i)i6dMnrYL``1w^!jPeHKxZfvij$00@-AMiMuB< z8k!&x@2@Lz0~!}TERZnwleSeHEeJ$V!&Q^MrJ_4B!erI%fE6C!{#PZYKbR41{AQjf)|zla+{c52y0<&Nxy!$lmSfh8wEg6M&JYBxme$=t8A?;#Q7 zr;kb)fhgclFOf21x;llsClF&zD%6ox|I5g{bqq3aQ|FQ>q+MCpCQ;dZqx{tA<{1wH zv)}KVYz09J8_9kB#Z~91WiDeR>^0`LF8zW$~@r&T+hy zRsK{Nv*SCqF{)|_&bHDm_I-GN2%;JyADh8O1Wd_j?mZ|OKY=R@>(eb28Sz^Y_p}z| zi_%j$UGa-cD~c+jsU9-mux*8BD|S%TFTBKapvAtmG!_p!+_S#NBfUd8MHcGY-=bEi;olTpE z-IW2Id-yO#q8bLq+8}!c(KsD3{J{t}_e=Hz8}rzerP*vUL>-sAbrGV{py>S=Ht!z- z7@cc3JNMC!4Mb@gJ*ZY9bBeM?Ap(5TOGn7rqA&*j@)&|V%e_$2n{B}<=60+%K9If5kfnp|AQT< zN+LSYSK<=X7EFvoz!U<0#hoka04Fh;m+C%=z7dIx!>g4GvyWih!&7A+!1`e3;3oD~>euOB-n{ z?35w;qQg2H7prRrDC@Z`OvfjECi|EjV`v9J>vDAMWoLh^j`tnIS@%Hm@yVyB|KleT5ZpBb1tIX!kUiGT~=upXfF4 zdnB@`nOx>W5BJ^{I6oT#6Ri{8^$|gSfc}k(rJSFEpwtzab0;&@xiST6a{>AVif`{} z8ED{OR(r-JQO@xRWZG=e^IU^zy5JTN<2%OgQypv z{-*4U{#}JdG0MooUUa$Ri_QSyUiXa8!k*V<4 zuK=#);i;p`7cnvyarcgU%)Y{d;1+@%?atx~oqR@xa~BZnD}y(b2{2 zPbIE}q1Bd**%tG!Mm{PR<`{vkY)Pce&^RY>tdu{e(y@lk6qMCZ7QDB%o^L)?)p_&c zg9An#eas+Anz$0#zt~1ea2;p1G`N(V^Lc6$@}yV6CSp1@9mFTRI~ATBH#i4zLYk!r zABrIdoR(0yWSm z(K$XBE5*LQx<+??*8K70YhbuqBQdkam--*e$xZFN)^7s{Sgd|42RgY3mAmF#ev1~R zchtodeT3T=eHF5(Ir2I4YyZ_lUwKC1wnxy0e&R<_orYn|i)gNr?o@_y*?}#PRp?Kz znZZUH5fCIpCTA{zeWe*=#k6J7-JLP*C%Rue@r!JQ2bd?W;3MsS=hB*mWXs*rDj8|G1Lx+Y z^FKRY{{}ZH-QH$T7h$Gngrg7 z6joOu4_C|gB4L~lA&=u0nTrd7Q;!Ff=Kb*zy0kTZpy>l7BxqgP`T&C^33Z{EfB&%*Ic z0FdF7qv&W;$3^-e6K!ej!!s9ntkJkhPq}M62d%L8WQXJqk~3+z(tZ-Dxoa)^*4vsE zFLLnN25~B3UK7lvv92P#SbnKg?aG~%4LzM<}~J3H+=Na+5k zqKA-#YdQ+ky_Cz`2NfuIF5HAV7|`KeU%5Hd>^WqoQlOXBu{6IUWbD&sRX``8=li7{ z*kVNI-o1ON(3|5T5`ls&;YAmcU1mv`o#WjZ$Ri0)w5}DZ3&ns7K1M`gtQrDw+=F{> zf2YJ^soxo)4(OFKbiiPLz5egC)ndrxW*+M$W+NSG+^+dbN*hm&;>p8@WF-zf+z+*= z9+eLzcjj-u*Dm!x=$s4Z9Z^>7Po(bZ`sdO7kTCz!UwkybMOe8|p9y3@wMd~+l$HuhLOwDgZPGg%DHRx3&2dzOX^;i;0c zVpf-z5i1(cSi2ey>aNC8%KytduWL5`g>zm$U1o#N7ZGdz+2j->dvR35!P)C=1$Nd7 ztuB4uy-`1#V=n)^TobM1(W%~hS)bJH6)0otN5bdbra4mng#KD6b_nG3J5^F^gAc;t z4-|KLurwjqj*@Hl0+xGL``2n-6`aCIKvrBWSgEs|G!s*L3=&jhOk2{#fk>q)tI|Qw zU~xRtCfziEr@RPO(9gdhB|F4j(pfr*`sO>7&OCe$)3jF;uoy`nim+_p@Q8=gl4wBd zI6O3J-BF`IP~g5RV{#PX<|~&Gb`W+Ts6=fP{@K;)W%;d0C%2m#!Kaca`^oBYepCOS znHc`l7`=k7f9JT5-&Dm=twTAdN%e{Ym{)21v2zBi1;3`IDhCK@2d<;NejJB0;4kg} z<@;4ypQ%Xl8FZPlSO<@aYp)h}%6_&#z-O2({Q1$x1UA3asu=bIJ~HF#zA!N$a1{tF z_>z%UON%%+x|DH&KFA5xvVcU;EU9jK=v3y5*=iCll?sVp&5`>IK#TTgNO`h1YT1CImJgC#oEVMCc|8U?FRrMR-I z^e?{jj`Qz7^G%qFbn(DFi$zh`i}Cjh-lW)SSeTWKGw3AW&2CnSz^#^`zxGWhv){BCQk`NvV;g?$4`0CV-kN~8QEJbns#PX2K@zITW)Q*#y0xMEl&Yo z<7vqY*_}{`fu6Gr=~*{$oXfppsU*0Vz zC^XnVS1omGl~Z$UqqcR>@Wr0)QVslyKu3b>xpiCEdR?kZbMQ)~|B-Rp13g0cly0Nc z@;hZjNl}caw_=Sda1-yB%F|+WR-l}E;icmh#RHN6pg>hD6PKI()?1^T`T7@SGT1oY zBx)Gc3~R?NhRA|;!3!@j!+CJ^xj zB(nJ}!(V*H^q&|SD%EleYn{jvmR|8lV(g{(u1Mn2b?Nm2UXt$Zfe%k=e<; z%p>lytz{OW^~IA!Sf{Yd^wq1tGsQ4UsI&E{&ZE#xC0To1{e&|W+&$C}<=lKzU>pWV zZ`$S2>x|()1quW63~;-0hw}@to0)?!K92r_Fw`kW@^t&d_SO$T^*iT+;5lSIG)HgA z7Ud+sm3Zg4_{z$Cz~#2wVM`FFVAwp$v-%Z3H>N$1qshzWIH6qy5{w-`1stqq*9vgXs+7 z+p%Ytz8J)Hh}I?h?B~wx4e9dVwCvW&u@&jxA{1^9L%QGaw$#i@Z~k*2X~)gLZ)NL; z_3`?sGTQ>G6lbIww*418%L^C(ueiIoUOc36nwR|*ATo|A-SqI&hTP9<>atzCUgrZ_ znDco>p)LN;x^4jN$q@18gScW*YFr+K+2mz!1SSVAKjeu6O~2*W@a__6?M4?$dCwMJ zM~yd13nz{nmmZ4jYKbMz9VT(KVUI}N^gat8emX#257Mbr2-54UJv1N0?LWAVuvMu4 zub9NizNzS3WqlxnL6SV=Pft*o37;I)$xQciT55*r`alMrTW(mF-bVh*Ankg)a77P! zfL*nN&%#*~OpACmR^KTze5^ngSH>XpJ9KDp`-a4XHH69+otMNlABK!lSr}^lW2s&z zYABjAeq2tR!rm1QFY9|kx^^y_w-EOI-;;#&#~B3e^YoR{OQ$-vsz9p6W#$sv3)C4J zVN2~C!iP_ZoYsdwsyD2mP9MpZ%y^;bvLqTv0aAHKV2)rvB&}km5+WP zUdq^rH<7GHg52#v_U<-Be}TfNJ1$AJnl&`td?avl5L2eco_S&%bM9$Tj- zK0bK}NauMSpjCVGpic+G?LDd0TIc~-hhk)J>Rt=CH=I;h{ml6{OTo0xF~WrM|M2ye zQBj3$)G(oRH`3j$#E>E-T|*8fDIqOg%7D_+jdXW6f`AN2h%f@u3|-RgcgE*=zVH3< zuJ4D7wOni9%zdtVUwiLs-{&ZQtfNC{-8b<0Gk|NR)_!(&y%WX*@v44)2jZXZ$l@a{ zhc||Gf{9R{JLp{bxo8LfkFg;fSJW5?&2qn;KqNWl1d(J6^R$9{p!gIHeQ60C9r%OG zK8kyvVWFk4_5^KLuXsO`2RiaVqUiuFvn@+CHW4=;?0fXng)3cDdDqV_)Px{oMsPoL@D>LaJ@lMB|?i($tKfLqMQ zuk(jZ>toLvd}HX2d#x^N{7=@*Jzs5$^9fI>V3?4+CVcLGox}oZE370az?PO_h@4yKPqXjso=8@o>iCL(;N?ynu(* zo5*1mN`%SJRRTByZtg;p=TvY$U)E10BaL1Tj+R$l*-T`GUlz6fT4r{?Cl=(RNcfng&_RBGkr2xR0**1WB%Tjyc+<_B^EvpO2zx{6sCxCbP&BGd4dF&J~(_^^cI1#P{=f zGq@Y0@1xRH?Yp4uF zahGR>(Y#{1_W5fE_gwYwCKWGhk=HzvOnV^F*v8)VknW$t;^Q1N`z?hHz~6k`W>02= zks1a*^9I&5k>=FdH3i65lf=zT|A|gaV&tUYr zV?y_$lHbzlEdTR83H#N&6Oxa``@c*gX!x{s`z#`5M^?M99|?Eqa)9`wLl>J0UnSO2 zBdi#)_VK&WtMr-jxeUhhSpV)0#wRCn8}3+&4btGeUkEm1%#h%yMHRy|Nr%t%?W#a( z720bsYyI^>#(dxp%;%Xzk$>h}v=jJg+qi%4JZckVSejHI=|Dp)8mW}r=BR~aHOmtk zM7ov}p+=zcdEEtWRFITcCp^B-v_wTRI9mdzu%Mld?&KmvuQyoYqQk>#Qy{uhf=hI+ z;Z?j^!&(iC>KD;Tci6tYP08z?)x|UE7yprAXS(3`6fO=W1PI>_fwR!0hYd4E2x;Q= zB3%ejpsyz_YevW7Uozy2^gn^ndqBV5F;0-pb6l>rJ^Tz~XrkyO%VY~04~akCJH+5n zCh^CI5$?=6(NnHo8)?Ul>E1~2G`^oXZ8GM<*kO*(+Mon5YeA+2&hx2FrcyNsU|)Sl zkUJ#gA=`AnSF)!fr;eP7VQ$d^nOIuU6@2yvE=x)I*rc@tBNfdLk8O=hWg9EPNkNndZvTf>K;;s@+=e%vv25__ z^kAxN`n$-t&v{du(S7vKz3%~B=}H~q^Eu36!pc`>{@(fXk^A&U;?I}p3{)S(4w!!`?KQ(jeVa))z~182 zh&FtU--oum)^C%gcaU_Yo2VSlzz9+Erz*8;k{;t8?e>ITuEbaJ7RKZxvtD1?(x7BerZ@2v{R?adL zc+VyCAf)Eim>@oN*Xd2fnn%+C=TGGd6629Q&fD{c9$swLj49*J@;UcUZAxL13Rhqa z?V4lpS(_CrC<8oV!$iQEdfMjo8dv z5gdaqD$JQ#iX}5~<6*qr*?v<|^!1A(mw}b8J&#UBWo25Ki-sTw9b)g7(Hh%T+-TM z#{34baZqT1qY2r*ub#ifz22NLv_MQLGZdG|S9EkN#$eF(zl|Wnq)POdBe(s)f~P}O zQ0LTFJgUWyNk~8TftaNs!++^lm!F7h*Pn#kb-_!ir0^vL~z@qa3~vkq#(-)|37SXC_V6*d_CZPmRJK|lbS4O zwqg<2;056MNTm_duv?L=fRJkZ3VpLK`@c_gc}{sOl2eh?rAQB@^Zyn#U(%AuCZN?e zAI~u#ih^z!FqWtujDhG70Mv9?|L?+lS}5I7P->7XY-TE`W3H4=ppFZ7`Z{W4+Ug;6 zT(Dl(=8KPt`5WV#g3jg3@o_D!i7d)3F+=*s)nW*K*EZIrx^Weo z`CtY^GJc#O`Ui!*b4cwP)in9PRr#ZC4^8MH^VdILm!0FTYm%+mF?Thu>wUP{GnTc> z-`i{7-f8D&t%%Xif=^ptpWUY8N^B%vY*{lt^w_HbT?hkG!WG!lmF?6O^Gtwq6x^l= zUEm@0|BzN6v-9C!Rc0Q3*o_(cb4=r8V z__46C)j^!06=C|fsYlTDzNzh?bjZbZAxR8RTEb52D66&$)SEN7J-VKFs{i;`Z^A+w zs8iG5BX5bmw-j!v?AH{(qevj#?aH*fbG@x%xK&mPH?*i3=-F70lna&UlL@m6-nPx& zeR<-OjQhwg(r{M+*-TRZt-NoA3u;j#So;3c`?O2GGe24BpronAgSSP^pA!~H8oYyV z*IU|ODbWR>Nm6>$mo^R;AJ8B!peajaW)0^+wn{U^Ea2LA(Z9NKxT|)nveT)o(Mc#v z!ngQ_)tC?hJ-JuOq2IBs0)`xs$DxHk#~mh_kgy5*C7crrP&Um~(^tNgeFoHl#O) z+0~%)pK-?tRsSP$>>Oury<;pY!!e?IT5QvE>rXqaS*5ev5#5)*qeqagA36ca7W+56 z>e7A?&mGX2JUFGT(O`G5W;F9ywFivr6F^>hLpDdIv0Ys8o5sAHa0amJ%?E`ss$xe0 z(2{jpKW+ddB7~)1`4;R9OgvbpiFkFmEAJT{!>>Xgst< z70QCw-t*f`#K~+*=U~s6`@mnxq>Jg~g4s6v&KqgGC*hAy1bNIsHyp~G`_LJeRLsfZ7)Fv^Ik|f90yyBKQ|oS-&voB?+Gr`H`)jp zl5$HlV89rKW`Yk3_C59SsYA|^xyZ|D2J~YbL+>N+UbVMp1sCVoGwtes$QY=Smng)fpn22Yi-q42*EWcWZ{%zj}U%_Q2|f zTX9h^;M@Nn(@wIw+O#?Z$F@062+BwTUkuIPJx*M1rxHm3(17`9zPY2prs65f9UdD= z4g6Cs2B{7uKP45Vrr_YTkzHQ{a(I?b01PhJK7pi#Y2iEm+Z)8eThq%(I2=m}SfH zmlIXfdEfI`_qt*@1|j7y%{`*83EX0lck5p-qLwS+olRsy1j;B%~{!Q|ef43%-A;QqH3ORKh^|iA^Hq;@qvSZan%rqUe!m#=bSr#)atf%O;SWnS< zm5dDWw3djIL*9A;WX|r~dUJ?s`thpePZOZ+(-Z5E_!n}Y+Wp*%r_}$pXC9%J@@KEW zj-Mj!2zB{FIF;Jy-zN6s@6yMVu%+GSE+ifT!8oBTZgbL}NwGMwXrp8`gmUYf)pyOU zc~P!QT^Y}uW_^!I@gTK5H;%nuueS^1eQyuK<|11CPB();Hol%_UkdqqAN(;z4FbnM z3(!Vbf_HDF-%#NF++&5G4SP!_dMLWoP}2tQ8_R4-5<5&cNGC1cTJtB@mCRCj&GfkB#j=i z6rDVdGPjpz1S>~`Rq{&#(zvoOx4b3<7#Z$JmoB%PSl>&4{jfYlvj|5(flc`oy}+C(`U>sAbNy>E)eBms{#FK z%Q942ruy{D3=Ww4u1STHBs5Fg(4^bEcQfoUGq%pjwq9e!y%C8l?zs z1@@M`NSqKl*amv26$*D37Zufc*zl1VO791^tNUn@H$D%iaeC*G1OHQiec!_^i$d@L zy0L6NECQWCZs7I83JgAzyjQX>i*Z4_f;hHMfoFVfZS!#oa95FA<#5OH5lrynz%b{= zk;A%V)>5qODmU7d&r)G^>M4;1Iu3W zg~aC@hu43EXa8e8!xb`2^_ai_aHIc=4V2_Tnjk(dID#hO^%WUkM*2VXjmwePcH`{P z7VFSGdDb^SPwIz1vY(Vn%TiQOeMJad5t;U*&Ne721r^QXbLkHK57VyLNvE5k;unW&GvtB^y|BxfQv2rv!x zqnjWTMRHQWa|DtO9#In6WY)A)?*~>Z00d21S_-W0!|gl8njl@d&cr^^4B6ba4=^az zXG>hcSup`SwzybphDp3GMjzXwMcyWb39B{~cJp|b; zpzAjrVWrkgf4qEXtz%xNyk;;%rKQCk;V~ZuK7dO6wiX-q$9z~A`W;!P)9A>7dHY8l zw8%o*I6)<=m_Bm{FG577*WEN zH5E=T8s_5zV@4D+sEz(=i|5PQ1yEb7S2{pK;@lom`SyElDvG*dQn>iLx%<~LKSNe+ zdH+*h)OG$MrkKT3#Ix*bMp*}oSvTAq3ymGXeBZd@YpA_0SILzbqf^S9$+_anAHeIo z&QS9$C-8uYE2qr$QGM14-(_!Gh^G4$Gr|FAU1FRN!EUsR3T*sb5uw#ldXDF(QGgfFCB7-St}YsEorpv%`N3Z$S}?{Y8NalK;2lv_xe zDW!TU<=yyqDp`d!e{5}X+>yh7mFo+b(CBqNvNBY#{U`RcC`|?mv+`#g!hRWt`j-EX;wpq+cv7MC{ ze|13yFv~&H$R->^l~J~9o=D~6ZE!LEF86ORJYdaqo%ydOa#gy=mD=)+e>KXQb11Cc zJndhv{|wpp=G9A&y3_0f_)7Wo+*-vjjLocH zA>7)Pou{hksLDGHv)eZHGM%Jyfb zh2uVc^97++|MDbe`Pz$Jr0gw7kcNu=IGuZDVD!q2zjodFBI$owfHPq`Wreklk6twJ z>VG#V{h!NB==jbf0$yK$O;-tfGQ9c?m|q&#u4nWkS(LhFIWnd6lE9Nzsl6y#5=$9P za{7xi9e!QQ+jm{Np7Y(QM+e3^<-m9gU*it1O*dut9@ZwF7aTW6K=rp!yTgUY;*bAu zEZzSd?8rEA(h{8t2`ZCX)^$S~3eSxVS^~TVc!H!bYbhz%8$`3 z7T15IW828-L_Ukdt5aOhIWmn5#szQX@GUmkn`PD>7@Gl*+QIFEhR^o0WHGp*Ys*Jd z($PN6NyhDpoxmr7{%g9}n+#TsJ`&59UMcju9S}~~%;3ukV8fNDdb_9?+~$-Db?3vZ z`c8wltYUkk=ZHvzz7OVJQysE2D*+38!*NwKNP+Pqs~gNVrk_fOKv_bb zR>{eZgLj23d24W0f-+Z4^z^P@Z-cM*^g=$r)!y4qGbc58+YNVTHlHQ}NS^@S6cFQS z8LOIJr;Wr27kTyE@7Gb_TZR7v0EHJ?#l9?Fyv!fL{M6PHTE|O~TzLodb&)!#;qKJh zNiwIkBlp)+W-rznn#XS{utx;C<7{!Fkws&smvUT4D~Aj8$-;iBAFdRH-+r$x_jw}Q zB(78%uhjt%3R!H;mKIHzZv=@1WgMD9`q4QH6_NQP!t0zQ$^!TM>i(BuD3KH}>nA`U z3ts%gU0f@L0(|Ic`6i^x@>z)hQgxhowAki49iB@vSdXEk(P!UL!1(HMuA%T%AgLKO zNrns4ueHwTf8_!hN{T)RZH5k>=qy#QFrMO^F^I;+A zFrc?ZPCZqN6X~bwII2lPRt%Y?@t(Y$AijCUj5O`u-x5 zKX>B`TC=$`-5J<){2Ef6g1Y}5fRsLzxP9t7E!PO7Y5Q^%*rf|ZQ2WmHDE2ho!>DWB zGO#XP9bQ?p)1#%yphNuBm3e5v~8n?&rIiBU;bF zF_5$-Ed_2Dots1<5WHCg(uTkol`xC}#6>`(vc*IKf3I@XMu7?=POZ>2quH1W6RaJ* z0ytI(s%$iL!w%`%rW*kBKmC<`BNc)RkO6Cr05&hM_nsj+;Q&xlN$dYr;}4`Sl2%n9 z5q58WfS&q|$kAl}*2{C8P%T+#e7cxRPWKJKtC6v-jOY`&#ur{wMPc2FmvtmH%adP| ziv}Q!fLgj|1L7~CM-%1K3?ZD^+}hYxQLMfn+h$wHbk@(i&_vu64YnWp4lADC3>92-^sa_hZeE7iMX= zitQcZFTt$&qx$7F_#=+Jr%$1Zv_sr&PfxRvxUOzmuA7VXbT!e2cI9<+XI~|A%!zOW zm(=W#Z46<>lcw!zcBKv&XV_Fm{)jSqfbE-;^8AronJ*R?KjeP*)Lm53QGVQe&MZ{~ zlfkiH$hy>u9y)&u6+!2tH3^DxK9OXQg{JK?md1GMXW+-6K2a=t^RAQfG3JG;U=kgW zS}TNQG&4#3Jc0nGQMU@j0%i9VQ~Qrm@u~1&3p2Yx?hQ}#AtC4>aHH1iVPKGW#ztMs zi=<`eO-^VIkqMc3>X~ECGGi4_1c!_1U~c_I)jkeK6B^x4HPB4~q||`^vNUUCi6ilyKVk(g ziKXJsINVw)e*J{LzXpjy$SX-wtbUO+Xj=t}k*EG162b1OWW4a!p}}-06PZ1qc)gYK zX1*~MxLXWms;pmt3_-!~J=XFn8AX{h$!Z8iIh+gYGFmX7oiqMAM~naeLK&I4RZqezsK^KZHKG75Rk*yrb)!;Jq32sg|MVSPZdn4nS5=oW&2ZG zMCi={|NEm{R@3e%YnnJb@4Em(!aM z9XYe*?x?$CE9X1BPPG4rgdh??=K-zupvbgcisz!NLGh6)8Xg9K$o^jewP&LbWSBPC zl~4h1*})6XO(BbKd>JKI&zH!z<{M&e7stGL1~g{{P_tTNZ0R}hA(}b%Bk>Nv6F>6N zyeA|8;=Oh6HN{nATUQNPmT6+)Gu8ly8#Bvn0yEMrC{qxeXN zagB31j@7H2d#3q0eKT4HDiJ~j45ZNstz&kEJUQ+CsQbbQb>%)CQwyx8_rDSeQ2#P| zcE`ZfPh2xf%uI_-t8#M_qLpH=;7j2vnzA-WEO|<4`g|=`tJ%Id(y&*pL)xjm+5R9M z5WP!RIJa+G&O^M45y}~Ho_9N%t;RcXWO?@=w}qxg@J%rA zY*%Igy8ymN7Q+?&Owd8>B2C{vz|)Y5$L(nyWhgfd@slu2vf0O<-OUrcFR&Y0tE4Oc zRxv0SuX|iKf$nv0SA+gPt^Eg3FX0w`6q!J5l(HOt`{<1#7E0JyYa*w`=_M~4P6JGz}c6s@Zb`KYu6Q1w3>&~Np$US zw=S)6MDf_~!qI-UbH{%;%vT4<043sztd%!3p|XN1#OwMmMN3U9Vujf4yIY}Yn1q`w zIz6F=gY=l#ULhjZGGFG~)W`qD6b}NQZ>;Ck4WY5T>@A;H@*nvN`mB>O1gOC?N9^LA z^k(~O;7m%Sz63QVg&T2jlPxYhCGFI61qZxIe(;5DMp-R-xt$_PMZOpHcbIVUxUAGv zDl_mdtD>H0cCV^E-5v4lQq^egO9{c&68YSt9U&m=o^lWKg&7cU#;bHcsD`gQ$_vl_ z+fb4~E{CPR0_k83{`q%2=s2@5@U=Nq3ZaOn=j&`6Kf<+|(h=`qXW1ZVkgW66-Li!D znjQx7Hj4EKLV0o-^sd*Ym#VCQq6mjnf`m6xte0}KvS3Jh` z#T6JyDif}QH;o*avF|%Nq!{15Fl5N))XiR_vNY~xGqiMk_X7(eSopja@2PtamM0mv zso^c)4;R$n+=0QnRg{N|lVi(vV%uV_KpgPW`lh5d+&!wwb^u-6)7`3EvHuk^f{HLEfhkFJhc(&;OJlL?2NwE1qO|0o1u zH)nsbIUPi#_Rr5jnGI27O|Q2j{WES_{(d8{5_XKH%PU@O_Q`iA4J835X_Y^ItsTdF zw>b{2P%r@AJ`=PVyTj$Bw|}i4U?9AhTfB2oRR)w&?JtB0`Nc+3<0}+}WU_vZ)#7>W zfK2C8mR@-SQ>KvY9`#|ev|~Xx*1TXmIWFSi%?lenyJuUDmfrvMTwA!80Xp(u*L5}p znz%+1&MFVQfQsu04=E@gbweN(<`2X7h#4XWAI5! z9s$fdeEHA)L=2b)7M5GGE~;z+@Rs~{y2~$dcDRW}9=DEJ^plA5mW1oSm>=30d728x z-wILt7VG9MP&_c~4||S?!Q>}R$8&x}Q9gj4xQ5L*dGia4m0X5Qyq%pjSwV z>%+;kQNrTB-zZfQp&h$dTVWODRR`tY|BBURO56bCtjF&5szeY7!=AkaLUi3TUsc2! zb%!+wwH^|Y9_SoW*2UsD(OKoVcpk<($ZN^98(JA&*;IafLjLI2$p=#ENB<7tEVR!<89o+#D>VpdN?03Lfn2hWJn!ob z^(XE**NI9&o-dIpa`AV#f7`>?∨Ir_Gc9IPDd!X!K|>7~jOEvY|_lGwxl!Y9N~b5)S-Xko#}Xhol53Z5B==W$HLB-`2ZPH`H^s*d+jLU$laH~Ehv_6X6-T|{ zB`AdpZ#`-fcm`8t=eh+hO=m~%Hajse#wng7OCsU3w_#aEeQX=>6FQ`K;(dG7-3~7 zp&E{&+UG7#ah0-sjnDdhA)}1oJ;+Qe(>#o=#!U@~z8qe%rY#)CJ!Bb|2B2Ve#E~n< z3SBF%dMDpYOZeWrV9iQ;?GMC`{kS2u7RCZ&%Z6elyKMS zOm|xG>HS#9Hl;BL{_t~;jM$MJHh(z&6P5TESHecx40#I)Po6{Q0wQT*nd_x%U&@cO zmHFFDD5lF~yR0JzOcoGs)|mL46cBFIVQ|l(k2!iQZW>n6_GWV&Cv*ScUhh~PHU16X zEy{oe>Z%jYZt8K{Ke%%Ja14T}xDt#rl9_tD{<~E6F5OGww7fDRVz$RvswGPUpXe4# z??t!Pgeg|BATsEzVBeSF&1<^V1hIq1MfeXe+0|l@is}`){8x?M)1zSaw0EWoSkCQ% zJwW%6z#->kY^wR{KL+j0gwVHKbpB4D9twQUTBF7En;kZJ>?mD_G%0~6)dT;Bi8?%; zwDnx>3-RjD0=u=8%Cn~nwv)>J@X#$_@bx{o6yQ7EYbO};lhH3K8!(S+D2GL%qrmdM zg1zG764+vf)F^U}cYXSM^=A~%;r`@*Hu`*>Qn9Ezl{WLS3~V{!@5EBhurfF=n&GdM zeM1;g-HL8S8@RflI*P`z+JKcbwP5B0I6nc~{dIkG>)ZC$-jeR~78BQi87J_!N68&e zrws5|MLsA7m}x(c2Ade_L$u4~*C>QNffuogd?Df(Va>=889fc|F0k3;o!AK63K;hr z_pw5sEP{0uU}^DYGcov|maA9j*ZwS|OH+d0GtPcxp=NI56sfn-(!>fs6TyL(eI}54 zcZ_K-sUfOlaDj7E9Bgj%_Yf;25sL#Yb$12Po!N~ zL!lKi5DSamX-WyAS?V@OykJ}phBezmm8_k}u^9Lv;cL6g$uKy$q?HM;Y=*-(SWyppE zKh7Jg(5pMUiY`^rasT+>iC}3!+Sa6> zleoI}=5NB^&X!N(gw9o!ti@}zZX=F#Q&V38m;(!YlvSa7f6Z(d||4~ zB~a?I5SAeG`S=o}H&8NV;o0?p9$$dM#v|hELdq{xD0Zl^C^Oamb$!j8dMK1K&$4v2 z*07d$V~$JNrfobY#I`2#LZBbAb8Zr1(*kK2LSqT{&*tOaF%yubY*{#mz-(G2)^Cig=9$B7L}e6!dm&gWzIO0wR-Y-lms zj{9-Lj12L0cJ~KXsH3e#HyriTg}C)tGgrDn?Tj3#Mv$ z(heIM8;`_Li~Q(dnC{)&wCi7W3*j4z7#n{MWg*>SmAow0;+{Z7voP>|n{TnCK7s-8 z>i4PYi0aIgzzs)}5{tjQFq+rDYDTQ@If&Hl4t!30!verpqASzCnz|Pr-yB_*D@=WT z|C9y@(hS*%Kn2i4&Orp$G1O$l;54zvGFhf+Y|__N7w)1_+tK|n@I*&G4ID8zp7}l$5Eb7l9m== z)PJ_>v1p-%P>lTWxgzLIV{5wlvT%@dXPoUsUKpz+Mu#Q{@7(ju2H~^fQN5q}<#dfU zdE4mn_mO4V%QL?lQ+Aze8kPQG*v@!E^TRg;NGWBcPnN>)1HO!7%*gAw6H#rCU>+8| zW)1L#o~`x2KWy%`{$xxe5DsGRoO2g$hr!;ge%rKOG<9xI#^O|%gOvPuZrQ+D*%dcH zWgWpy;xzXnW8kp-*V1qD4h})I`Zo}}72U-Bo$7M8f;YNAt5>(n(YN@_K5yvyy)}w6%O{7B7awO>T^Wa4oURX#E(7_%LT3gMHw)u(7jw3Pc`O-1%os4(VV_OM zK0yh;nq5Fi$P0+6m8n4L$e<=AU( z^Cb!Z5L>ikJm$9r&(KpTtuKleXBfyDr zw27iurX|Nl4IJ1K{(q8vx_VF#m)LmcI4(b?YF&8ZmHftks+2^%Begl?HR5%$V520% zFfFGdOSm8TD|ruiE(ftw*lB(d=N$T#)3k^ZtGDO#bQ;3u>+6DE& zNeg3Yb*HR+s<9gbgK2>r+t%9kw5X0TJay5Zdhe%9(aLInRR`KC)ufi|>!#y%9mUwj z!s`L&8mBui>J6m%JBZ?!2H%`D1{a(4#o6UkA@cXD{>5ANJWbIJ&Y+g=!5=}UL3FkG zLsLNu_xENuQ7kig)`CJNbKegdvc_a^%4=XH){D(=m`9q9X?ERJljXLnM<*;10eH@4h>C%$;7vm|CTM=cxN375J$pYR=QyuJ;!6#-sp# z`p4IPw4NU3t~n$8{-aafxvFsQR)sT{-bj_~9HPd6_l9gE7&$tub)V?|FALyKjl}PC-e-Y$VRbbq zx!P$QQBg*%$6kKTt%HMB9sOD7dcMr>b)HzOD}5juqyP z>kCjT8QIi_+Tz5s0W;Zuy=~;ywXsZ>AEnKvIqvGpI*!PS8J5q<5$%@2%@&r>g8El~ zm1<@6nknbF{n=e%jV8oZHcV)!C=N@i z2Z1A(-)&QI)i2AdO z9qL!3^vN#Ur8O?_mYcsyU-Vns3^d@MT*xk+@)I3> zQ~~XkC+EGl*$+d29WRq?LOW$ouCuBom~ z81=MWV3+*av`YzYqe*Z`uI0;M54i-fPj_~Jyv?QKNEO6MuRwJI$HK5Yom7lcSkjWx z)$7w2pfAu;I&tSu7C#eaq*Tunj;Z_aVOw981$)#&qk@=oBTDG zRw#7Vj;rC(q1y2QcGD-yfO%a{!Z9EpgDRZ55jN5_f?G& z?*u{|2ygYx>53;aVjiqXZe=70XG>a`+HM_fS_y_Mq3x+9WboPKQF2mkoAP;=rn=PGwj?R>W|C7*%tMz6K56TumlFl$oS^&#?yyOL?j^@!_ zu+85q_q;2yp{T>G=K!~s4g84UdWD`;^zE7t2>Kn@$tg#=c{EU_y(h-nnFwQu7OVzz zlLkCkJ)%sNaSYKHQm(taG>#VVF57IgW>&cLeG-w~=WL!j$v>bSi z=J+%56C#`E7=1-BInu37SR9I&%Vrg6XPc}bT&oi@Vrq;P<)h;w&e1_ci{kW#MEna{ zvf3o+MR4oxODy0K6a;q~t3K;$?bV0+AAPCQMqHXNcds0h(-bqzEx7o~mx95CH%e)z zP)>C+aeeD)iaeA+j1MRiQ+%jDm&Q9vJU0sUhk>k4m_avYq|18^XH5AH3}5E$G&Nn? zOfJFH{hb$GezymGTv(Kkcs35b4v}glc-va_j(tlsWY?zb7u2q=-GJ9QzFHMmn?>YiQY@;`9b#ONuV&xiTt~x&$UCCb_G;)9 z$B3*zF#XSXw)paT_8dM-!Y|A(K|}el5*w{FxoG;21DBz$D7C168_mkJ>~UWv^*Z+7 zuz-UnXNT-X=2RQ}i{nURn;+bvAJLLRg;-Tk$Q6B=Qx-2{g`iwSKMbH^GAM3TIR4<@k7Q_TP3md-#XYNXFOIU}^P4##1a z?64vFpl48kyO!w6zuO|!)??YzU?+VI%ZY4>XLp0F(`}3{EXALh-v`z8qnlC?)cFil zA`f1uvSt}ne_ZjX1f{0$J|pdPXJg82gtlTnCtR_(%hsz>XoKgg-T z(Ftt_l6D_qe_ju(mrMS|I4MaYmqVa6|13?&juDN?tQZ!JpW?9^3U`^ACNgO6ztSgU zdxdO`iTb3oCg2)Fqxq#F#f(7inRETDUmEcYS14_m`6FTxll_IoB6{^3?=lVUJ8(4m zF5d^Y4@FZs4%|S?P6YcaR>>k$j@fk9WY|8^thpTh>qn=>EKMrc zSO3SouYj|*tnQ1>>|p8p5YFv1pYFIhs-zq=rXac1BmCg&3psf8>lqOF=A-+D5YQ_T z=wPBWx?nGu2eKN^snrR~h%SXmX2e;IbJOXOAb7nq-n*e4)7PQpm%GsL?WDivPWu_| zUBFF<(u#R6ygX{O*}QE?8<|pY$F0ZLKh`%>JzJnbcbE7Je;*uByUOA1z2;A6nExR@ zUKG8U+q~4}acbdHS04wiWRBhTg#Dd{&x&fYZt0Kjj8+(-6z*5vZc$Pj-p=fjGvQ}A z(7AwGt7S-q1!)rsDB@Sq6BJkOsy$T{?;GE%)R7Ybf%RuYHj%ptG8=u?=fT%Ya&Y|c zGXb=$-TRa8USI8SqS*p4IEiKlv@^rXuF_W#q~EVBBkhM=6E(?Jy(tf2(AN>uR+^2$ zHAUgdW{90X#p)9gUlh=-s+Gzyd#KMwb!*p!B(oY-hsnHuaQ3_7EIS{MnwbylV{Jxy zz2gRR>!U`ZnTF2#{s2KfH0C07fqP|^1Il6-(nw(##OyaKb#n=zX{ERU9yjvw$_BfZ z@zHzo6TRAX>I$IfKK9wKyB;N@cobIsS^M%?XvlPiDM&pT^Igixd(>)58iBXbI5YU< z9!?!=BG7?E>G#?|g%=Lqef)LS1pcDhKCzb$tbM-BDlK^rD($1Lf_`D}8}t1%j;=U? z#kG|6_i{Q-$)su7+@{@e9$kF3kLx#iNb_g>LI>^Ko_Msh*D0@KG5gt&8Qr$1S|Enq<;GSu>=G7m!NtYL!W1MQ+>1E)EXBh=HW3ljb9@uuR30Oc zApEsPwZ`1JY-EjCi|R5s%v-dacOzN2DULOP&kEk?dzQjjfqC2ThM38Br&%AwL9>hj zNWZE=><6}bY$PMGZLv>UEhO8HshDV~Ne~Ui_X5eaXO*Vvr4x z4ip(B6&5ROZtbFO=JR|wtE}nwTgt^22AnpC70k@sxYW#fO8aM3taE4$(e**W%}Q>u zl8n^iy^+oC!h-2leb$8W+`d3jzq~z2L85+=Czowl(y?rBNWXtB@p^f)asZtYFoS{8 z*~bVF-HSRPs3>?>yY8g_T~4JH=SmBDh~`H5B33rlT~!`G2v-h?ZMQ725I2-+iYxxu zPmJbc?Hy>-(B&&ZK%JZ8I2p#o(EE;rg&>!G=w6*HCA3;c!PDb_}H8Y^vEND_B6P)(Obw3eAoT^|2VY>&5 z<7Ik;-{C+9mh)w8;oBY zR%lVLNEe0)ge%LqbzlG8k_`I4#2p+!?YKsb^c zO0vJ6ZM_D>-mgV3hnvTiUp=!X{aK9o*y=~8&({bLhcmhzw@C|fHSl_MCKyG0d_C8B zg;#wLw*8{#U$!?#Tm{y%z_g(UB*ezI3d`pj4pD`EF%y%9=Y~)7ue#8Fo;^2p8CPIM zGVYKO)Zv$YTQ`{;rAztVC&B3(3R1J1Jj&W_A$2<-#OPWOd3s{io|!}|UVO8vFQcVd z+?;Fl;TTx@v<~Op06P7*Fd83|a}G9~DqVXJ9LbektY61%UMTYum8Z(bR_tl|EI%`{ z&$7)N6Otkhyq^!|I#KcIc>%}}q>p91^duam*Fh(?J3O=ssVr>VGLj)&jsT4Yw{l;- z9yWPp?N{v`K$oVPv1N28(mkj`K-Sp&u0z6>oz!Qtma&J}-U3TF-@Zz_5;EF0QM(P# zz>#C`!7nv^o8?sgL?7st>#Y?CO6xxZ$lT``{Sz}=$> zGT@#JLs0cHEUza_tdNF|v{LI^=|orR&@^VdD{ZlX0>@kYL$LUj{lRD9{U=gMfj)q4 zfWdUrG9eWVi78Wp-EZrFs=r<}LqHo|&Sw!d_XOCQos2f=X>6+6dVsvs`eNdSCT?hs ztW~VbZjt|;vU^W+8DMQ`41l23l+GR87gF+$@=9Vd6W(u{Z>yG*p3mn+qJ_19W5g&@ zelNgEYFYTRUc=Jc!-k+1^b5umN=6S!WW+#3!vFH=mDI%CD`EiE{oMOiMf6$T{k z@{`(U8+5i_nunk`24?BZDr;)2;oKcSEb!CAJYQm#Gcft3aISf6;6H$#>R;+;{D%0x zoVP^b{{!s@RyE8``oOo|#-X9`eDwQ6+B;Ct4u`fW=ts&?vFk8S4l#e7fJcROriy)r zoQea^F)QgwwW@^%7eHjkf|$y%fmtl;uCD#AQp&OiQU%|OnvJ`abJOp)oC;o(MK~$nnu#6KkiM7$OvgD?I1Axw#D43&)GL1t zS*_eMawVG*H{tB|ql*cdsWB@xmnc#OIWp@gz55GkH^-mK*m_zXtI3#I&`&ZGI|4Ih zS*x@FQ>1~%gDatj^O(QbL4>G!>m`9E!C-W}uxF4(j6ZKck+y_#xEmHeHc&HZB&H<{ zSluL_oe4X|j7Y)G}c+ ziFOZJV+xhyyYt7!Gn5q~#7HtSh|?Eh>3(kJ4wK&W(I_s@6~*dTnqrt@RMYS1E-QZJ zLr&ll*t91agkJTU(m;MygI0xj zaPSwmA86E$2xr;%Wa1jImVe&Nv49DfE)i10?_2k}8fn`jzIX9ME_DH%u)!{0FA83A-KwGDd*}k|z8#T1qmXBy;JO*>N{Ps{yM2y;^-Y+ON`7 zGiEoR_%+UDw7XVN_*Ex5rO6ZHIbV|-d7oKBITZ~3TKdFMFQVYSRvi zd6--AzUyq(X>l+dVRt z;Am!PU4luUf_+^1i$wx_mFtxROHqKsL>!sKD?9nybnM zU|qWZl}rnO>zh&$)DPhb;SA>9&qjK3{vv)*#ZhZg>EKRP?YN0gT!s6a4j7jlv*M}v zwK6Vj}t*9Xk~$l~W7BHToluyiPB-{XCoceuX7 zhIis+aKQ_+zSM2Ip3JYs0FyY%Qh@#Vi6lLWi57la%f?^!^`8MM!`Llg#*S&W=teRg z@Elc|58{%zy98>~bM$g^xwu1pFq=yZ;0u%`!d8sU^k2-#cW~NQ~o*@=R*zex8h zjJ053GMR|Ab%fdHO+Z;&bvbLe!Jb~EaNNb^M&SqXQZvl1H?~{KI#kW1dIOdZs>s)- zP9zdUUx92O4xvk+2I^RhZnAZDAi3O45-rgw42J`}1xy+&Ju%VMFQ19@y}{&Ts<{N+ zT>Y+pktkFPpiiG9a#6y9pN8J<_iVr*bi&^r)weGoQTVXrp1h+D_DkqkuFcJudl>@EOQrG( z!B>hpi)11kt$b`8B>1G5#uA&sAJDn1l)UgrP2~6v&_V|+B0~X;1cJ7 z!prEhI-ed2|AqE);T*QoDua5YwjG?_b7t7SJt-fWDYaTw<@rKg))A0D!S0@apn9XI$Q@ULV^G;kM9 zsEZl|xiug^1iroSdlLir(4~2Xh9}QNe0;W=0%+Mg+~OQa(S6O>b&7OJYllZ807MFJ zi&sdQnCyAz){*()Us!f$hv!EGT;0pqIo0h^VM(8NnD8$gy;mgpgb{0jE;TPc+xBGk z|0nDFpkGoFz){ufb!4Jt0U=;@gH#=k1dWtAf!8&0zOrlOFUaI%?RMl_n>Jszv8|7d z7n5K9VV4nf+8uu?()%7x^+=Sr!T3}B&OC$BjnyMZcY$OXa!gq{6f^a=v`&h?+dFgn zgHc3k{qNO^Z>ACKPWd8JsfE7P(ZSQq{UD_r>32g0Jad`aymG-N2f11Idjl>Xtbdud zna@|Kzn{X{Yj>RJSvDznN71#4I6ldpMvYQ{{2n&YYv<`vKhPjUk$ICJc?xGfW&HfU zVsM^H@EG5h1#YQ0JL|}?D%dzuJp1hDXhrcR3W@u z2RUbcR!wzY59uQK`M)r~ebE1n8b~n_vIQM(1%tTn2}^x# zUdn1J(>*SpV;6v%NWdZT&Q>w>TM|6v$@*UYu#+9nnX?JN*=nC~oYB{wrG?+Ag8z$4uASa}4k`etlg7w>1RJ{C@EmP_sNA6x>4Cj(9VK!LIgh*}_&%8gBi&;BC&{hcR4samF5LNSmHa9^>(%7Tt&E8Q?`K6!meU-lSLR z--jgVs--N0s1md3=2Jq?gM5soixOX9Kq&*<YC{y$ElsWP?eta4g}-D%3wV;T)AF9!!D4011h6 zSzU%q4xgO+bXF(x8}3ISY##?eX|h>*40D3Dmt4aalN3xGg%!SdSH94WDs~aseLV2;8?#2cqmbj&4y2#PL@x$*Jkeq zV$FpPtv-0_xI8?P8h2e_?rPFXVo0xKg5u()Ln%Fz(OE%tMjiXrgIm-JOJ zVyeF9ZBw9iVR>ac>dN9}ETzfU%cYguA)DaB$e~THQ*6!iF<5`zjlrgHup8acQcGBz zO#q<`$oWo$5u{uLCd1eUD`7At7o#YK1*Nsv8<-)_n7JLLYti<7neW)czx{=OPa{FB zDni`|9U1?4jewL5=2_H+8)h3hzgqi0QMJs}GW^HbyEH93I#A zhcBIrzko?We+dZ9PuFUl!nvWSyLZ z7^LxotIC;}x&U&9uuHt~3J{|Oz#T4j_I2||&Ffg!oYK7cyhAO0%k3i;7A3K&!V?2! z45s=9==Y5nJ(E;B^o>ZeaFekY0xoO3Ejdbtcb5}<1r${Xdoixj`FB*j*KIab`?evW z6lNXElixWHbcE1@0QL4OmnZFKU#KqmNCbt}25N^On`4skiVIK&gzu*bTHQqMVHEAX z@F*1*DZjAX5WQ?V6sI~Csuqr&3bB;av0#aMwCnut&G{=XTj5*4eewd?$lT7q9~phX zKDoT8u+pu&VZb`IlpNC>dq5sio*B}Y1xXSKFT(i~EsuKMD*dS^<)*$F<^b6D3GKh^ zJ58_mq+zVt=i=#{UpV&`m0aY8GkXB9z-}o5dMHGyUI`G+W~6*;34Gjeg7td78fMxO zf!gocSup*RYWL)^OKvhE@rA($C zP^w?|tvS~GGQdP<6qfu;CnkQ>v!2_5F>epl$X2m&7tm?A<}vpY%77=M;?;6C5UZo) z?h}&9na`d%z-8P;=8M!cQ^aC5TQDyxJOZQ1Te{;WWMUy@%OG{!FWvz1B8HjfLmZ*w z91%x>{0rNErd(2+OQiC6L4^r^7STmqvz<0Z&I=^k|45<4LT=A-ge{GR$3`+)yB z3_!+iBss3GR}d-fnHr|+QX<|qo1hQJ!=_|5@h+P<(yznmcfHPLwaPwHh>MZ&xe8OMVFam>BKx3$Cav zGo0*f5DfYH0oQ87?f0jgkIdZK{x@M>dT}-YC}LcsGR1>sg2yuy4f1n)eqRCeKpMhG zWpiiNv*EfSdt;ZV3xjR}ottvUSK65(F3-VJEsD8`iWe0LT^xd``J^xqU9tC$epfr! zds_nVb#ALFY|A>Vz0++H(Bv_ja~-pw`=iNnB?}LAiYrG?AA+iJuZ2cS>NNfUk-G^@ zM4Ph5wG-zV3ZC@!v4y=HcPnz|t}vZo=4#rB@$`hp_K^^vdpPbM9em?nVz$t+W_sK2 z_^fNSykXqzC;%V-6o3yb0_jt?wFYs}k?g^~y7by2_2C%cXcvTg;#=}fF%_?ECl8{f zr)1xvw{huXlRPgz>!Vga;5vanvqC&I0(A!2aedLbb`dav#;@|P1{~dGZ~>6bd}To{ zQ?tvg;65F_fBg*a?T`0qoBtRweu-aKMY4K`Vcl2&GDGtx!jAgDZ}H@!BHPVr?34f+ zDYduG$?Q00YabF$-k}JgyRD@Ib$ItiQabUH;e%X>RpdS-fFbOg{&L8P*j2F;>5clD zt2h@eAlYKg+WY4F%LBDRyLG@Lu;{C0oV-ckK(MVP-9v3iL#>^-aB1@(0R-?H%1guz z8S#_`P}A>fFAoGn67v3A$7tZ_wFE~nKce^Z&T;Vy)2BK|-RHNZkKFobwc6$b%wyEa z0ncJQl-emwH+B8GR%8FuQ!qh>w}7_$5na^wI{44I!91sT^npblG@22J=W|xY)p)4-Sukfm^j7QDUAg~NktUctMzbrL z^6}O3eqkHDBT8)hSrl;fo=Z*1Z$GEUqLg)7>`KX;f2ZMFa^olYKm*;&351(}c8EB` z#dFO`{{r7FDK?^;a8{^~+|?)Q{<*vZcMmA&o)<3oc(d8PC9NX?e&i`7TSxbu%i9&` zf%T0fEGIXIjEqM@C1QD5u}Jp2?^enJ@>1GGkZbfYuXCFCI%%`|R_apcfSQYz48X%7 zikRCTlLoWRQIY$N7vOs7r^`DptYY4DdelAsZeCGrW>a%^X2hpy`v|yn%AkG&9|_}U z4P3HIR^j@2v#~TohQqnNIVY#*zOYLxpJ7pg3DTi(HA}v*P4h`Bj|%DyKJySv zy<=H==b_+zYSxqcT%m6W?>ITY$OycO35=ax+B_Gv_PEd_aPt4@ZAg$3nI4;)JB{=83YZ*^4ck`bBNkWmeh2dY!Pi3U^?ErKadI>v z7RE^C6=@lnjdJb0U*#Wb1xY?#XD{24@1JEP*KUej9|>T#lc7YaNq*+Oy;)c!+SBA| zzI56&2V|}(kQvl;EAY`qGG%HUXW~D4P3~3j)L2h*6v#QqeGNcNsaq0GX5Rc^)+O$; zSuC1ZBz|wrA2dQRVK;mQ*)rltuRC(6n6Hz-6*h;><5~p8$FD*hngjDNOqh`x7b?ME z@1jb*Wo_m;+fke}7hSpuHIJ81HfXke_oK8|>i@-VA0K(d=2xVJ#M9aI=79YrLYMED zFy^_DGdweRF5K6&A(d{g>SS0ik4WK#+n6OeHo@o#J!repy&jS1>%><-!gJ7r{6fjvXfP<_K7SWGvAeUsCCPi z;kw;%-C+(l?0k~e3ges{3rUT0L)kk5#&jcTif2mJ^IO3?9J3VmVg|hrHzRWk47GKa zPdV`S?)52q;PDk9ptGYDg9|rYv?fE9Raj`ik^U}CLbqZ)waKs9*hXr4-i*-s$)=C= zsJ40L?P+bI91eHWA^yqRzSdoN>VWrZraI%bjuMXfDW9EqTI$2sc=7?Tr zgJ-y0v3$kDtC|*hE!FPd0ptYe)@4t-TI{@sTxT694-bMj6sS0ZIgYWg8l&a6il1a} zamPoow(KGh(9!n|*0v)|Bok;|KHa*O@BE7=QuM+ShscK7l}f>3Kba_kI&emuke663v>kUDc<^3c;-^S7yR5aS%&Y5O&l7Nv$EHpwN z9BzJ9y84QCg1(-anJ(O#j*bmy`MghRr624_tmLcUOMqRF)~`}KWklk^#+Yd- z-umlTLqml`pTA|y(*`L=9)y9Z*O4i>p}M0m>(_L<6q>&wdBBM+wXV(%ZyGXP0I7LO zh157wCzmnKT@Ek|X>_*)zyQtGVp)>(eW!H*cK&ytv-V%$X=rqi0srVHEzVk!)*c0aUn-8z^2K)JKc}<$@l%EL}PXoY7(Y+N51cN60ca;ybhCbzaP>53IuU> z>4H~ab|F|9%>8i0$HxIQf#Lvz0ZzV)=Fb0#Hu)f!Ixd5qM;wu(fkph6d@Q<0-&`TT zuTkqOCqF7V7F+pv9D$lh1R0s)8^v{NQ~$(?|P22N&$RQ4mo ziPH3%2ehIC|IDBcA-kCGUTy@h%-on~db?ujTdwC%W9H&V7eq#V=9T#xHgXmVAdi~~ z!@PZKsd!ZHpASE{On%+uAMk0mqM75sraL8GjQFhQM{wl+t7%!=$A`mx=0K;@v&Jg* z&2Ki4Ap33nK{qXBNqxo4#pZ*}vi8#eoO}~o{en;dP`(Lnx6ge%Mx;PkDu!-&!+W>zE7aS0C=D{5A8*vZ=USWx=za zM$YT+Lb0Ni{F*LFhym#)7Mafs-JZ&>q$}4}CWyWb6n46oUP`_hOFX-2iFVbO|GEQS0@9#X&A^vI&!O(x0 z0-6amUfj)TD>~D@aG7sNj3ajI_9wou+mxF$t#e{W|ROiYLs*x|FSOU4O%o$W7Q#@`b}qIKRg3NMZuK>l2xp6|Ec zwFUtWA-P{ltu5Uuc2ngXLrI^!d@4^iP8JRN-XGQh)8JmE@a;Y$T}6yO@yRyiCo<|Sqz`-)CtO@zeY8EC zt9%;B-3L8Bn@{t)P-Y0~_~tq*Jzd+w2hiN|m%EMpk3M6weLY4`9!{9M`O|e}2W_fb zA4r9zSNVHc#qPO|ycm=@T@A(|-k19D?(kO(|G|hlzdxPQPhiy98+cZCte_wU1Chrt zFp3Ggu^^W%d4nl_8cO8F^Rdc?3}VNQ+XS^020DMT&fIKi+ZfK>xsX&%6L+(}zBsmu zu&E6G$BGa5@$)*6qjnGG&9KJ5ZD8w0P+yo1Jds<%H8!=ToA_IyQVQ46=oiV#1Q*|! z_ir5h2_W5Nj_}nkX8mZ=z#I!RwkDHN7&W67BJ}USM+NQ%b&{!XKs&7Up|!LT4wSzMn}&|bd6&a? zg}rz!>dHCw6JqZrX!HEj{s5S!RQ<;`$CBE_I>{qBVOQG-&?as{r(|n2lZ9 zB~1$6(~orN&y+6TYq@;0#XgIY|1iyL{oCmLK=Oks3q$W~*}z)~P4E?&sg+l#&U*>m zBbI~txw6$#6M64|Qev*?a$7DX z$wW`N`do63OPhe<*iWq2Cl``5k03C3F(hVq%S6~jOwKC~JN|(uFrWE{{s#nSIzrIuzT^E}w^W0PLL>e(1wBjq zh)P#({;m|4r2ZNY>&e#QDTJl?1Af!KOz9z?szt*nR((lUbJL?*i@{TTJwnrPQHjv& zMxVsHDuGCqPRu<=f59&2=ER*mSDN+bUDWD8E_zfTewY1HgzS0fgBv=KhA1*$nA1)Xj;((29`h)6`f97e>}w^~m9okrwQiR25*!8Ww5$wr!U36Ki5X;-ZMt%o7>UL|Sx4T8#K6^yh9%w9`JT{y>c1e7t zAzPIsBMGksmpI^we^f&_JpKbeeXl1ugJ*Al+k2^YH-H|kfVjIV^JtBYIu917Ufm2| zOz`K|zDBmaQ>w>xU+E&NsEYe|Bp$)9{^6xo^XV z_N>!8#J;9gRWJU;6`!S@B$Ci>N!{!MHN)nKMKo~xW-oDytIDkSZWr@Z_0Ye*`E)Ek zZP)v9oGLUo%T6_nY?&kwPuz^^|L6H*i#O?`w*@N*%|HF;H(jf;K<}SEX5xqFsK`mC+h!89CsMe! z2XQbZYrkbYE8rXPlv9P7>{#l(g<;Y9wS{c_16v{I!?gjIg{En=z=s}AASwzm3-zJz zd4{7K(wgFIvK3Zs+Tt*boqyhR9odIOemIbd1brJoV|nT_Wu1CqfK1gRJ?ZlnEuobF y9QF9`CI1sp{@*YA|15Ic!^?d}@!{PvAy%16ra&Fj&?7A1OI1-z0WSaS-TwfF2+&6W literal 0 HcmV?d00001 diff --git a/doc/html/_me_joystick_8h_source.html b/doc/html/_me_joystick_8h_source.html new file mode 100644 index 00000000..914f970a --- /dev/null +++ b/doc/html/_me_joystick_8h_source.html @@ -0,0 +1,175 @@ + + + + + + + +MakeBlock Drive Updated: src/MeJoystick.h Source File + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeJoystick.h
    +
    +
    +Go to the documentation of this file.
    1
    +
    44#ifndef MeJoystick_H
    +
    45#define MeJoystick_H
    +
    46
    +
    47#include <stdint.h>
    +
    48#include <stdbool.h>
    +
    49#include <Arduino.h>
    +
    50#include "MeConfig.h"
    +
    51
    +
    52#ifdef ME_PORT_DEFINED
    +
    53#include "MePort.h"
    +
    54#endif // ME_PORT_DEFINED
    +
    55
    +
    56#define CENTER_VALUE (490)
    +
    57
    +
    63#ifndef ME_PORT_DEFINED
    +
    64class MeJoystick
    +
    65#else // !ME_PORT_DEFINED
    +
    +
    66class MeJoystick : public MePort
    +
    67#endif
    +
    68{
    +
    69 public:
    +
    70#ifdef ME_PORT_DEFINED
    +
    77 MeJoystick(void);
    +
    78
    +
    84 MeJoystick(uint8_t port);
    +
    85#else // ME_PORT_DEFINED
    +
    94 MeJoystick(uint8_t x_port,uint8_t y_port);
    +
    95#endif // ME_PORT_DEFINED
    +
    96
    +
    113 void setpin(uint8_t x_port, uint8_t y_port);
    +
    114
    +
    127 int16_t readX(void);
    +
    128
    +
    141 int16_t readY(void);
    +
    142
    +
    157 int16_t read(uint8_t index);
    +
    158
    +
    176 void CalCenterValue(int16_t = 0, int16_t = 0);
    +
    177
    +
    190 float angle(void);
    +
    191
    +
    204 float OffCenter(void);
    +
    205 private:
    +
    206 static volatile int16_t _X_offset;
    +
    207 static volatile int16_t _Y_offset;
    +
    208 static volatile uint8_t _X_port;
    +
    209 static volatile uint8_t _Y_port;
    +
    210};
    +
    +
    211#endif
    +
    Configuration file of library.
    +
    Header for MePort.cpp module.
    +
    Driver for Me Joystick module.
    Definition MeJoystick.h:68
    +
    int16_t readX(void)
    Definition MeJoystick.cpp:125
    +
    int16_t readY(void)
    Definition MeJoystick.cpp:149
    +
    MeJoystick(void)
    Definition MeJoystick.cpp:59
    +
    void setpin(uint8_t x_port, uint8_t y_port)
    Definition MeJoystick.cpp:103
    +
    int16_t read(uint8_t index)
    Definition MeJoystick.cpp:175
    +
    float OffCenter(void)
    Definition MeJoystick.cpp:271
    +
    void CalCenterValue(int16_t=0, int16_t=0)
    Definition MeJoystick.cpp:216
    +
    float angle(void)
    Definition MeJoystick.cpp:234
    +
    Port Mapping for RJ25.
    Definition MePort.h:128
    +
    +
    + + + + diff --git a/doc/html/_me_joystick_test_8ino-example.html b/doc/html/_me_joystick_test_8ino-example.html new file mode 100644 index 00000000..fbbc6fa2 --- /dev/null +++ b/doc/html/_me_joystick_test_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: MeJoystickTest.ino + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeJoystickTest.ino
    +
    +
    +
    +
    + + + + diff --git a/doc/html/_me_l_e_d_matrix_8cpp.html b/doc/html/_me_l_e_d_matrix_8cpp.html new file mode 100644 index 00000000..35ce33bc --- /dev/null +++ b/doc/html/_me_l_e_d_matrix_8cpp.html @@ -0,0 +1,194 @@ + + + + + + + +MakeBlock Drive Updated: src/MeLEDMatrix.cpp File Reference + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeLEDMatrix.cpp File Reference
    +
    +
    + +

    Driver for Me LED Matrix module. +More...

    +
    #include "MeLEDMatrix.h"
    +#include "MeLEDMatrixData.h"
    +
    +Include dependency graph for MeLEDMatrix.cpp:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +

    Detailed Description

    +

    Driver for Me LED Matrix module.

    +
    Author
    MakeBlock
    +
    Version
    V1.0.3
    +
    Date
    2016/01/29
    +
    Copyright
    This software is Copyright (C), 2012-2015, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    This file is a drive for Me LED Matrix device
    +
    Method List:
    +
      +
    1. void MeLEDMatrix::clearScreen();
    2. +
    3. void MeLEDMatrix::setBrightness(uint8_t Bright);
    4. +
    5. void MeLEDMatrix::setColorIndex(bool Color_Number);
    6. +
    7. void MeLEDMatrix::drawBitmap(int8_t x, int8_t y, uint8_t Bitmap_Width, uint8_t *Bitmap);
    8. +
    9. void MeLEDMatrix::drawStr(int16_t X_position, int8_t Y_position, const char *str);
    10. +
    11. void MeLEDMatrix::showClock(uint8_t hour, uint8_t minute, bool point_flag);
    12. +
    13. void MeLEDMatrix::showNum(float value,uint8_t digits);
    14. +
    15. void MeLEDMatrix::reset(uint8_t port);
    16. +
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    +forfish         2015/11/11     1.0.0            Add description
    +Mark Yan        2016/01/19     1.0.1            Add some new symbol
    +Mark Yan        2016/01/27     1.0.2            Add digital printing
    +Mark Yan        2016/01/29     1.0.3            Fix issue when show integer number
    +
    +
    +
    + + + + diff --git a/doc/html/_me_l_e_d_matrix_8cpp__incl.map b/doc/html/_me_l_e_d_matrix_8cpp__incl.map new file mode 100644 index 00000000..b2067233 --- /dev/null +++ b/doc/html/_me_l_e_d_matrix_8cpp__incl.map @@ -0,0 +1,45 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_l_e_d_matrix_8cpp__incl.md5 b/doc/html/_me_l_e_d_matrix_8cpp__incl.md5 new file mode 100644 index 00000000..b15f5e79 --- /dev/null +++ b/doc/html/_me_l_e_d_matrix_8cpp__incl.md5 @@ -0,0 +1 @@ +9f785e3d6f48aac962cc3c7a79f1321b \ No newline at end of file diff --git a/doc/html/_me_l_e_d_matrix_8cpp__incl.png b/doc/html/_me_l_e_d_matrix_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..d1c60113dd2ee2e31e1f066cf8cbe3fbf2712182 GIT binary patch literal 41161 zcmce-bx>U0w=If8f&~a}2{dlO9r6Y3-~ob5f;$9v3lJcUGz7N*f#B{A38Zm%x5nM| zZNm3Er{1}BU)}fqctxs0HM@7Oz2=-_jxpBkP-R6K?5AW;5fBit!LpL?5D-v;5fBiQ zG0=cl%F>gUf&b7x%E?F~+&}zeH08!1AiO{TOa7zgma;SFnUd=4zJEL5T#`uPmx7=Y z6{D<#f=lw8^XCsg(o)NU;Od!=oG~aO&ihwRRx@4I4mC>NvwQWf)N@pC@R=-aVwz^^ zhm4WTnL&P0Kh+5$C7V|K=YLp41qsEb!-HWj5_fbG}y%TS7bz@`+qOwpXa{FZ%Phqoj3o{&R`c zFRw+8f?^4Rt~624epEgUy%3&htl)>6L*!I*>`R{liuLVQ3W840HDV&SsadDO^XcCXVv2`0htOyFqld98ediaIX->SGSc))9& zTd7HO)FH&Pxy_bbe!&|}Xub6qTcaq1OBWu^bM$!kO-5{@&lIeKr1>3Bv~d_P$Rf0H z32#WAf>%Q1U=Me*_|hpSBX1xR1H$h7`$_M5YS)vj(ykmA;nyvqlV!-HjDCWeX8lWP zt{@7VqCoEw9OoHBYU+MoT#<8S+ZZQ%cDfkgPNVoZSmHQmhugTA~yx%pJdu1LCibUpTfd;4_`-i9RrUEhD;;^B ziCKuy{_7>_d;jjhRL9b5YK6I5E6Q#~Q}iw0S^p2C{&0cOb9ieK&N&}AF#Iuu+26Gr z-43BlsyR2Xov8{24ZU#buC{=mSz4L@2K+@{6{R9wN6XdvbD8x!^b;sviH{p_sKNUoMK-xMKl`=mw{<77N-ikALp|eotx{rF7;iu z7dpzdBO_Aw2rrin)fQ(D!5_mx7D(i>R*mOM2^USKHGTF zDdJFB%x2*<#rd#&uu*S2@8ve>EJCv9u`nk2n^D6g zWrhmPoPoY*Vy;)IH+RtRteUN)IDI1Vf(du*!IAm?E7Y1*E%gbI#YJtb{6o|_{rY(? z8&J}bi*>{zT?wMqCq@^ltd6tOR_P6i>|sX{7vM2ou#kt#-w$~ATd3jF%Qj-aNVfei zu8=BVIU~o*->-~)DBYgb7CG9a={SI)!TyhBuWtU2hCZej+QkNNo7ZEf6uqa!U1!=5 z_a{2sms`L_EazK6otz$%Baa4ieAO4{Lai0LMtR7fKH(?;EL_+lV1n=<73*%7(&{+i z;qujgFGot%yY$BpgC5BA2rZZ77n?DP@pGglXdflF+DMhV3{88fKP;T<5pH<8g&K|| zT0@ZM8!~C{WPr7VMjGJF3A=JpUsxv2j@Hq0bD2k*%Vt)4b0hv1*gMHf^;}>tKdOpO{}=FDARg?B6&A_ipI++{Yj6VfeVxe13yaQ2h0( zpHesVKuP7(N&xTW46x~&2mfXPt@T}Zp+b5;*P{5doBkvB!xHrgo}HvNVtX6VzNU-2 zSMwHthDndR2+4@kw){q#s&~WIMr~Sd|9j2BdyEb&BoGgM$f#kA#1<}wzJxYr=mNd_ z%4eJ)1e#BmYlmWs_o0Tr+l#$i|6cqE3Kl4huFi@+<%Vi zgQd^skcrfZ?DvL$D-GPSlV9b&v$|?Pu#WJM_Qm;D`ETIUH%8D%w42}M5f=sd+tDXZ z|L*TsqJmU*1&Sk36&3EincDn1aK?Jw`F9`{uOSL+3eIkag>pGp< zXa<8a78HY_kNZVgRnP(*$RDdE6<`lo(B$Lr(RNlaQh`rmmC$ zWj<)ztEN%YS@}1(?5*|zsX7PbA0BI?pg{rzaUK`NiKH5w)fMr#6$xQsHXMzq9Putj z0A)U-Y<|Joz}lP+vqMRtus>cVKmG+&rFIbI->&Y2;oV@4TF9=rdOjy*Wn9~n%yYH# zxATu4Jpe1me8MjB-1yYDk^w{P17F3|o$)Q&&HssL$ds<93YWSKVcAO`{yt*f51{yX zp}x%2Yt-u{z1sIPLKCZAiw1rJsV)o}Y;^)21$pJptWB&wL^h3N8y0qEw*fjwg?BXu zP4okW-@KaU`>8e5GI_o~g5EnhoxyK*=*75m@Usg7^_D{N&3062-Orfb?$|DS{(BDzuJU`6f+S)hB+Tu}F{|Gs8nS0$VH&wYaQ zE+gdQ@U9_KjNmX<&GL`>UO&s1QCgRi9i^M%ll=tojNjvtfl*4h* zjPf#XORA*(ffR1nYcw5`%$P8e!o-vCrCvA|Eb~b2-u2{(w^K{ncfZhM#Qq1#r1iR_ znJHb^W9&)BeCJpzY6vGuP3q!Yc*D_ZbTK&T%fFit`CDxz}qjXmABC4eB5R(BB!;gXs`UTT@umP#xP>0i;^Dr@ALd(r4RtMSbcmDTfViW zBRXPuBq8VTl0k$2JW^FTxBab@8{@X7)(WJw-qo1so4In9Ww`o84sFc?Zotx?>EcMz zr|UYnH#Th5XCJoz`@Rj`n0=ay7YD9YWa;`IT01}M>9NyY3;P|z7H?7P*aN51Q;E+t z^kR6Z9w`GsZ+j4?66DLhzB8p!|0b~*x6ff;NJULUVSTJb=$CJD@$7oM`0!?cIkU6& z9C_0^>~SvD#^kJXGRTL9G`AFOy`vAvWE49~1bBM{pb7q16x1U;G^P#~8dJ$%Is<}m ziX8dGcg})FfArlt>(q%IWRv;r*c%!e_>pPxvA&tOYfCnsns9hd$)@=12-ql&5q|Yt zxLN0C>iI-y_=?B>F&+e?H=F_uZMZ(A@TCxHs>5wv$39+KA8d%7n6$Qp ziZkK^s{w)YgCDyA_}%}r^!S&kf~pv63gUrxN=im0%6MHbQ4r$=&X??qAyYaoUIOe~ zLU8yPYvQyEpPE|6C#@sTJzM@)S7vbf8Erib6bwcL=s_ zFE0e#DABn`54L0@zeRk0lqL|1M8U$PK>E1DiwlxSUaRFtb%cU-V|;3uO6={MZ(mt; z*5q3{fb9e*65Qj+Oq%zDD{yR@ zn1W&tKmD$Yx_@HkKH;BQQuZB z;nzJ?7-d)x6O&%wKQ&(`#6CZ?6n$)x!PX*da-_xDGR#mQx~p(A9W}-@@CzVeS8+OgU~HyF|koNuJgrp5ZVOb8* zfO0kEVW+kD%Kf+S=@S6;G}~e}khYLl9})ddzjWiBY1(1t$6fS$&#|hn8GW?Q%e{@1 z38j&^*d^;LQV&_1UG`xqNq2ba8!b_a>^l~R&c71i|2%{L-#*D>bOE*b-%9-d`?mc5 zcC(*9AMu5(H-OjugUZ1~?C6zPd>d&iIC^$&-|>kP&~hWyRB}NOjekQ04%}qA=+9nN zM^VLTWDA_wyMH1kXc+_^Mp=5t^#B$|Yfx0QwI-!ex%73@&&1{iAx;^k>5_!UWN=6$U^CH9s^-CJ$#(S zute?OgiQ6!+V|{vvrs+o#$W%wv6p2ryfquqb_;yb4hS{ZN-Jn~XzOE5CAedo;$N&Qz&0Evd(Rv!iV|9K(* zcgF5+(E(|IUGU`vcjU#{T^IJM{hlWXr-mJzB>T93*bQxO;@aBN+OS+AXrI_)`G7Vz z9|8Ek@dCS{*Gt=Vu&w^f)g47>+up*t!~F~noJ>YF9N_bhUXofOa!2NO_H&`p+iPDh z0XWsxA(UtSvFeH#x#uqlP0#K}_Y6OACK{ay?-nH66Q4S*$Hql-}3i;uU@Bd1}H zB6#4|PB^mHlT(SM*bU(cPnNR-?tjNo?8!2v!-f6pPak7*<0@di45(3YGI5?%T*-Z3GQ_0GeUHE7Q1t8 zY=_ct6%U2kepH;6nSxp9-3k~G8V zG?xe#C=9Rng<#HSSah!kbBYBDcZ{Erxzitcn6YK6@zaQx7PtcJocC*Oj!<|sjCi|c&(rv z#-xAb60IYxb=k5U7G$}?IxlH{PJ~M*49A^}*OU9pQ^*Z4a71*4TwjY%69GkWJ}852 z`?Kdy$~G-HtLLHMERgCgZK%k3b1K`uYICS^C%mJtxQgSaljjIvdeVhQAp?v3ys2U@ zA1BWgkoZK^FOTO<60EhX_2jxCZwO85xX$wo*Zd6EjEs``y8h!CQ5(S%(bg4^=Uca* z7~P*K`(muEQet;iqO|xVk_|QZ+S3@q0-BzSXrax;?j$zG&z)v_ZjvvV7PE9`33qv!$IG$Z3s)39KKgvWAQq(yU*f>%> zw;R-0=8db$fg63KOnEMr%Xk2TXN>4j=UKDgdLsE$nK3w4>H6c?I~**X;H$&$V!pLq zls1&X(opTc?$hwIUV}tcC6QpJxtIiPmPGaa7N`87Xl~2|eAsBY;d@X8zA0g!i5g0U zITdp6ET#&w?4L}$d1Hfsn4L|2B~u-=2HL3@ST*BhD$FH-EpZ2DGNzO*V9unR0Xp}5 z2L`o~8mcvDGMrg$+VNQhyA;=RZK-?R1Affp#|Qk>ZihNgx%l#rR6r7^dV00FQVpfs zoy;4t6QW_g=2#3qTaG*tf)VSD$xW|gA&M!J#LFjWJ4n^YO2%y~Qb%rRGqP0l?kNFX zU>C_!?usFAiPD0&oj-h3CGjF+KSH{8>s7`8DLh?BDpJGm&Ut?py{SGy3nmkMs7wpp zT0m}E&-4@)a&ueuW*V=*Zo`56^M_mT#bjMeLtT*DKBAr=#5RQzQCQZ6sO^kvimHu+ z=F+FNpLG)NKr+tSllg$jU4)@5%Z6Y0oT_VO!hpgPEnkOhd;W4QWlVL2t~H#=%^|K4 z^we~MJh0vKSc~I|eb&G^5t@zn_xYv!0GGmfTHf@Ott~7-%e$w9CUMMnQ{B3QFWE{I{S-Os}`KO4{tel_Y1SKvOeiP0tDb)1$>57eg0P^ZaIXR6-_O~{h) zSi{t2`Y;90*;EFW!YUAAe5UXA65^{e!!(t0pa2~(E6*#6w_9KLz4cu06)f4h>I%w) z^cQ<2tcIX$KjDkA)||(SRM$)T_c#C>Y^FhFz#;Gwx?)AgfY4=T{{~dSl|cH6g}g!Y zG)TyMpBnS^J)I_4luReYjw8?}+8TFK`T(Ic(KJDoekR;dhtxV8x+`j9J#$MklNv*d zy|d*kSTWgAC)FlM2YK;jQN%+KZA0Ngi(V(pSe?kan=DyFw_PdJZMt$zDx66DfbgrT z6a?!I)BZ#2ev}siBXMzGp9zd|@S-9!kQ)1>DK4A&p{w9Fd_y52*MUW zTce5M^|gj{&a9_5pNDHZUMV;VzUM#Cbc|D^ZG2KK1M@a1Z7Pvtcv>BQ+Bs8AHsg_Q zJQK$MyZC9dlSR8`Is1&yd-zE+dj?km0Zh>8m?Gehu_q|G!cY~FKbB6%W%uI?~X;ty*E5cG}66EaF=~aa%%DL;0*rC{3r55jSx5ZDB%Ziq_ z=&BeW*blwmZ~paA`Q=~pP=c&QNhpCoLE2NdqdaAJUd`N`eCBwqFG6B0N+e<=y-3`F zIbx*g5$z)9Vi}`br92e`Dr2=PGCkgDl-?*nRkCaqr>$T>tc>EwCCFfSb~~3s%+uf( zKrK}&2pup1er1OgbvW$q&eT*mtaL63jD4T4mx05*7Z^<>Rr+ zAh?M-YH%y#tG92mc3Kj-Pt~tS_gs2n}U%!8OWUkn{%Aur4Y8vLY39_&32;d_#{g6`FJLdwH^ z8OP=zt50CGW5ChfS;}{4OVTB5OZFcaWjHniFk&V$qj+Ipv7Ll znT<@cH?`c>yEBqeiu6%dR-162le2tG_S z_K&$!q26PShOM$q=ux>+?+VJ$kRSn`$Z=?=SH|b_l8rCq5vwBM^`Bhmj|qxt1j3D3 z+Vaa+g9r5Sbb>vaQTf-HqI)+d)Sbj$kzSazchXF$p>4bF8V4R{fv~?lP-cZxJ$J8B zH`At&n6SlFzZfn7Ci0%DG(3BJNJM&!`OTa8TofuaDqGu_JGr-1if&Ph8d68HXpzcr z4bK_3RmbDy(5KBJ;4I?|_6(n%Ko39a^L?azI`VjzUx9@2qBOucMLvdD3@mlGZQsX3 zUxbGOPMK$jkyMd#cJy6#9(h(9bH2_=|7KCPzseX)B;Mesq4G)`S~Gm%UQP#9uRK(G zIDevsxf9#$%XT6vDYdv%j)rs*~V?Enq4jdM>?393-K8M+=J*mnvqs`0u+BUGSFD}fRXrxy zf}xM9D|_&koX*_pKeGU29ABKwR?0lkVZoWHGx2(4Eke`VV6v8nN;T^KfF_n(x=(m1 z1}rz3QWSTXqF3G#y?9-D{d#97+Ub?I-fQOs0(-^w9lv9LGhSTxSB8$H)|=Z%N!oBv znGrBow3EwP38Dd7#E(@-PstZM$S-GU7Lu*whx5SQ-5bgSq5yT1R9D}#FgG`We(%?^ zPIQp2={VW<-wu8g#&_X{tOy}!EW{45y=BL8qk9!EU8{xcgKzIiU!z*OR0*(rfL(Ps z>w%4uANE@9!Sc0US@rlt=B(JWs1+@e9AFlm^45rR+c5fUL$copXmamKcTo)!F zTm;;AN8uhvi;1qsQ7x@+$@2fH_v`<`DY0Xr_gZCzU6=)}CWD0oTT|*F@aLfp?PU|$ zuHjFmzXvo7<~M~`gBGqwhf6n?j-^qIZ||1sC%Phox3v-Wwd1>Xr#j?l6O!#!05H^Q zWryxRgJ?;ef@fVo4V7Rr>WA&^SWY$Q*Am@L8Jk#(foYxiiVFmG7C^mmrj}Mdv4cB4 zM6qYYk6>hf@MF)Q6u#I4z|iiSb0h<1{U?>yd#sCiO5r+>Y}d|wW|DwT{30+c9oZLa zR;9IymUGel;oL5{GpH|W!_{0wzech=zowJ8*jMky4OA@XD8%u{(6*&*96p%PaNg1U zeY~>F=l72?=h_mEJTicoWlIQs9fUh&6fNjgBkEL;o=Ea6gcuBVzDK48)0zNj|J1~h zq10Q+(m>J(V_$!f;ba@hGQ@1ALvdr|pHNk*JF7hnZnvDPyg zXvcYxxoM%LZ~2Rp=jkyNV1!<=?sdm(w_So9!R#~w>Czf=J`zQ)yUXkyY8GCA-Iz^e zwn1wllJszPn9}cf?TUz4f+3LS{s*XJ-pNXD266lT$pd%5g>GzE4F1e7b$|{y2;z|O zs;)P$P#}goaN_b;F_BOaDC)izC&&2LRo?3mNl?p-SFc^Du{v71!91QgDQuggnKN?J zX2k@r_ho|ICr*2s0~A=zbzJ)CXzgvV+{#dNq15mJU~ObSu?C=I-}|fCa~MqP6H%L1 zVv0J?0uJwqMKbJGZXhzvvY8BAWC;XKu=Uu2RcUttwUX(BW8BTPJvQ2S>jOuc8R@%! znn2!`9N!n7EOUHiL`Sk!QOlxK+#%yvfZwbe+vqq&cz7J$yoZ=7*&<^!QP#O<3WLY# z>$pIzNt`AAPCALZ3!<69Dmgr@LlZhnZFm30M$iLs_^A6 zb5Su|BK&W=v#*l4{U6U+8yn48MU&->Oo!AKHJ-QNoTnVnBu6D8`dma%n_l33WDIJB?RV! z>>1Tm%}poRhqBIun1)N!UW)X3Ae&P%N?O60^$h2)LxvcJcikyMMr71~7M1+_q(1dI z$9K(T=}ORo0t#p@C=JmdzDnuan@hfP2f=QJJlk3il(RWL{)F88R(sKjtReEw6OBC6 z*xR#hBK49EA_h>#{6Ro4Sge<&XxXjoWO8hP`~OJS43O^3aH1Ou+f&;cpq-=5lGB}! z1$u7V%)*6yz(zwa^j>rP0LH1%Hjq5dQoR;lcj+TO-#De-31p ztR8QnriU%^l6pZ!z3hJ{f1EI%IGi67yo8aJ&?e$G;w4CbLT}4w)vQ`}J`5i!ev-6g zpIWD7uL5%PKQ?y~6qhYcvu6EA_!Osk?H+yj&qD#>odMYI{WOJ=x4(aNN4`I7(Hi*S zIdi@ddBc72vW{bM9)FLnwxp=DNsc3&Qr#OH>Lh@+iR6I@VeoA5qej#*cR@U@K4g>F zJ^ZjVoe~36Xl>bNx-8<*#S>;JGNV9|KrrqMsL~}osA--5EUq_%$FHW|kN9#Z*>9!u zjVwy(qMRTErmGAh{??Y_7w(tXTI^>RWz86PY9l(^48+e^-T5s+G?28|fw?YcWNxj; zj+5v2yL^T$ZR3nn&{Dyt)n|&!Y1}Uyth|Y^{tI_Ood!?D#>Y*X$?XH#kzsV#k z)P0y^(OS6qrj;z1N^EQ-HYCLpkO?2u^f}Aw?c6gn`Lul+-_@i(&J1w{fYFI0uCS*% zeN3>)Zd{4`Krp;>d~X0XhaY!N?&$c=(MPsgx^4U;$HF-wJ9wqZLLN>$k^t2Wt}wNKPpSV5Huc0TCPl$$Y68g9ac^>%D9ZUW>prOG)7o5p`vEh9 zu7SB=^{16=r|`u4o0>(ZuEBk=#V9| zVJqqC>jY3}04SD-w_p3w@dz0d>p8g3syJvVk#fAmYi$@`bC~n2^)s|>FF<0?KKwZ6 zV&2QhEH_S_JS!SU)iSJU^a_->cEWbe95aOoKiR%X#Fn?9Iva&@B&CX*lz-!^j#zgo zf%4#A)%#@{D-xwha3$aAy@t6G@X3_Y#VClPE?mtvx@9hx^M(->!oq1ZQx8s!t;J5^Cx*Fp}{jVfO>_sg@*??zD=0hLGoa-w?2-_bwvFA=~6TSBNkDi&#@47o7l~W zJTH|&`-rwhsQbD?96rjZ^c=dE+yh$P%zb9*Yx~gl>lHg8i-U&pae|9<#pLMDfvnySYa*Zv^tC+lSh zAct@@^j6wf|LxvG7@_Q8oyyx<{{=B?#^aISmbQoO0UMCVw9&>{FvqjNwNdvMHv)v(8Y(MWNLPA36XbtYfzq>2ji-8MUZw2a$p8D^j%Ogz(1-^ zj}$uWDMKGLm`XXKoB5G3JL$G?kHRQG$c4YpFZ4C|x8#(~9_z6PEyv|=3sF4G9c;za zW|QJKp(e}{KFXwr~SPCYkfYTe`uGua;*0 zrV>-+vXD2vuD?`5TG(&dLA+S9h^ccetge(B9(wT4SkLVD5cOWe5xWqYK;oYHm_H3w z$0v6_X=2C!=7)dvNG(AI?4L$c5v;Y;KfqqrEF=ur+QIkzYMvD`Z#Q}tx-Oj500V$I z^PSt=Zl0|s2v7Kt3#Ki-EH+KbvX=32XWG`E)6Kpq{f=R)^LI?CXgC_6LOdUd0O{uS z8U76>h*)vmG=1xpfp&r*PCq$Yb5np(ZM^`)1z_ydvLHTtsm55Z`nIrt6OarhuW|*6 zcLf2t!#t_hx?XPFQ>U-NxSXQx&AChgS2uy78m=dN&I)?E? z00$RBmbd8}Q7IkGq_5$_7cVbI3+51$uU+mRq>7RETqB4w4{(|=){VJeER>HEg|(z#2Gy7iU!EMKcnIMr%1ks#FqrnfNDrQ>3xzwp!Av-*fh zU1vR+kC{P|uNG4>fmSDwE4%U;fR2u8Km(sQhgHmMH8M`wp$#7UyJX<@j zXhQ0hkA7z@vd@0e&jByofKbe_y_=P*$*vANdEtF-#vbMKMd~PPm`x zFWg$Z_U>ujdKF@*7@ZOWIUVid$F;CVq_*Dl%v>2%1ryBuPrn6N35C|=w|zxGAZxHE z6W^s=YR`mm0!GVPWcSK4|$8=C1{KLPf8~K#Rq!8 z+Kh!2O&Cy}zt_pre(3gqgWv`|rg5`C8h3vZPV!a@%C2Wh~K0TRG)Ly!DfQkDLAz{q=|5isGVMe@+uUnI_?sGfW>#P4T%hl&-P zO;qv7F9WT;Z$=3yp$fc{t1rxf-FU6{8pY9%i9!I>VyMbCRa;3*Rak4i`GvJvP-(x& z(Y1BA2Y$GISYMIaHux_o4v^M3H`tqnG0+e1+oA_c;+@37G!kFG#N%0)t%^_KZ%xTe zMRYywV-l)f<^t|D zdqPbs-mszQhwJ+jI?=fG^Rb)^^y%;2;h(l~NI4N#IgNWv0> zQHcqt1eU*l3P{PTw_+Sty$WvFkc^Ewp7j}T?j=5`4z1??YpVxSjHkcRN{?!yDL&o= zc8LN4|SW;LiN4FN}6Fl$BiBz9S*2_}iyEz+vV5j(IX{n!Lb>dfp=eyP z#DjIM#(=^IBXebY7`OwrbF$Rjra51}nd*Q67(TWuD2B@dhRi)?Bd$61PQvGFjoy{7 zheG@owazYUhlySS0a8y4LWTCV?yhR>N>|_jf#l9Tp4}Gucx*l{I7_sUz;IUWhzg0? z_>>{MWEDMYFMs4qe}svQ*&I8P(2I%~zsEl)H1(DzSWBk-L*qTA)di5%M!z0TnC@-$ zpY!Uc!Fntjm%Z5`scqGWSss28r6hy?+m!N$0{tADI2=UB`+_Z+na)@ z=gPucNH^|#fa}Z<_ib_euTL7?eg?b?nVYfeHLIyPeh| zvO~@P%Mbx%US^ree;Xq5u?(!k=76nh0IC(3c7wU?XKe3uQzH$K@0=m^R}p+Pe3;$4 z#hXWGMf8bRSvpk^%D=?p0Pc-raORO>}9X^gH!o&L+V|`k3Qv+N zRu{xQr9^arjQ=&F`{sD=Ga*2|A`6Pm1b7;>ecJs8J_JxfaoP93+-obCtSG^gQj`uH z5CZNMU=3&2#q`FdZc;M38VW&KaA11BlE&S!CCXg*z$8GuieN)%xj(U&B(kT1XclTl z=*-@?O0!tiy4e~7TAb~o0Zp}@j`7xzfeRY zztX>Lwx!bPT*1WvlgZw*zX%YN`lQ${_bb3p`WWtW9dX!unCqt1=$8l8Lj za%Aj)!IFdDA3iDG`IEs+&)0ocM_q44#WCZ)D=c7PAR8g<7DsjqPq(p<*0vz0eW>PQ zU8G4LUK2tK+5!e;5$b`{4;ksgMU_%R1u^je4dfDwJ3-`0xlgVr1{|2p^D)*5KZRSW zo&wGd53xSh9DO$l0@6^|UE&vTa*!^Mm zMJB&M(^3y}+}I2yohe{Km!HG7q&{s4P~P{Pi!CNu1Pw!z__I}B`i zX7fHAajW%=(cOY&&rA5VY$f(Z_foJVFnunHmm+l(>4{0C7`vE#>Fv%2fK64aqrd** zo_w=nThY#k+lK?fx0qv508b7nb+c*C;CFWhIVOugPs5CDB?`b!oSlDP{$Z2QLFxC8 zx5Fyr*_azYT0{FJ(#BC&t$8eVYF%v7Mq_ReE_Q$^pcVkTYxQowdA%>{MCNJG;mSk5 zS$Y`UC5-3WW7Uq~;0P2JELHv4(#h4dPoc_H^UbW+$%k$rqtlMkR<_b!p;;i%7ae1x z55R764P7en!pytqO292MJv&HZt!0GPwf2~cXk58G*hsh8LN#7n{6;#ze{8(~_=Zm$ zD{L7~Y;UV|p#4^V#5&oF{y>s`;l<=@dl{X!-M?tg*Fv+)3aUWv@Q)~r^`0QFpjk9`kc#i?MqCvy`Q;bm;% z4@_gc3|x!v%I^-NMx7|`i}6@QB6~UXV+S+LCjoZlr}HRWgp;;;;W`^EDYaRfMBXY2v%&#az%SNIrClFeZ@_dDHW4B%#R8dsjo^D4v(BnlZ#u_EsP} zJs0;I$Fb9|vHewbe#T5-#j9)S zCp1{+SiSNd{~+4rcsZBW0V3gqxQpT=4ZK#Nj7B`Bz4B(G`?3vlUi^GJJWwxW3 zROm#-eQ@KWPQQX=xl(jh^u7ExojBm=ElYhtbLf0BTv~RN_&Fg@+{_%lyVEIyKyCJSX;aV*ZHXc+MpfEQ>cf<)CnMeHiAoGfERq0^&{B;(I7IUZMCY z&Ykbso~T&F|{{iI~L8wDS~4Q!Y67LJ#*@Uo9uSI?k+7^|e!Np2@D- zGyT`g@4nh|l^X1@>kuYUKyZ*9KP!x5{z=#&Ot!yLJal+B_T0T~TO^O@={7CRg?Ola z6kGC~Z=3chHg#v{(-r?iffUH6=PxiC{E-k;s)fax)dZ#V&w1?0STMJJ^AGf#_Ft6` zg!Ru=s(v>7WSmF9f=4NhX!iC*+lHo{^tF%YcZ?6IPp$Tjdg9KyKDP_$7?xEJ zMEr!*Dh7*)I;{OjN zrW8&}ZhMeJnB7o7a>osG%j~|?oxDlV%b3G%vQx$h2vL9^xb?dvN9^6tcB6Md@Ox z5$258G@r+Huo-m7mY$h|qXcq(t=yCr&@mEP`6DBf^?Z%9;ZxYo&%(mq%K_WsZQHt| zZkCCT`R`d~$Oef0h+!%e+2La+JZFhLONjjK>Zu{w>hIsD$vXY??w@Y*biJ6iDw)g8 zHBsUoB#&`1<=-0gGV!{uRZ|b63{e_gv-nK+w7`|`IJaJ_ylcC#(@jBg?^sBp`jg(d z&x^^+^B*jyuR`sSmGg&+`%3rUwMJm%x(s1%xV=`JdfC13JdOBgh5qZ#gkoL&5-Fq! zME+B?=SYmKtQ1B0r1v!+qI`OnsKvl>YQOCe-n}FFL;)Ah_i%VOP1F8o9ZpIboxs_` zI@Hv2GQXmGwQ^&y{9dbXW8bzJdu6l?d~1R#H`OI+g0s9ENDK>0%W1f4*>{SG1AH7=~W98Nk(MpEA_>G;_xlefHGbs(UZH*C2* z+rEsT|8aMcD_-Sw1h$khru_8hWs27kjA>4~*zJ0^#{F!{tf4vZ2EcX06V_H3LwfJa5Q;bK9>AsU@Ko3O#yNDer?u0+%?fdj{BCt?xu1_? z>gX`(a7oOgkchb1_h>X9eG33}_G3_cpWtne7lnH!69&s`GwT$gTd^3ZBs5ATAX4Oa zH_+UuERtzx>T|2l9|`4hc4jbte?=VLai9MQW2oIZlETE+>g73m8mK`vWsoH1$9mz= z8|_-6rE1}vo)CRFC;fyv`s(^!wL@on5bO)IYILnYKyr`@Q=)ag?acqiD~-cy(8{f; zJS1e5o&_thQn^{>c&3_DCDsB1(Pjm6`QQn=FVRJMH3kcDI>Uf_>IjLE5VOtTp(1Tf zzH;G^{%KQEgVJX{4W`n}D9#*lFScHEY02r@-`lL6B;2oa{vfvP{bv?nC)G*YLESuN z170$qD2Yw|q7iaLbdbYBF(P8z`={-S%GBUJ30E2uumdBVJQ|5aQ=QNKmzZz#GW03$ zs@#QrtH*G@a&EqrfsjX(z79f)6=e+k$X`V>ILB30oVjd2+zR6DG|oDLBvDUwy7~n* zCF=YkG2+tGYNGOgrecmixz(!q>}JAo<<@v`JW1z z8DyQ9E;(LML~_xbMO9C>AcguAsPCva8Oalw&va7wOL&Xf9tnkWc4B?bw>Uzx&z=x0 zj|O7>Ru8DapaAL*N$otuI7s@$-}Qs;&vuuFx=G6mx`MxQ(nHkMzF;0EMA zuB|&ZVs`z0Ds3PsfVU=~_B$?#zZ1l)Ss>=Wj}*?5`)3;nIIzg6!dJ%7Vz0yq%N{eb zXU`MfoQPb9XU+O|l;`J(*bu+zOwd&kl&D7ZjkujD@JhtVt3}NFb4ln6;S41c`)bEX zLFphc@DM;FE(1H$BfcD&9|fly%9<^dmV>~TxaJ)`3nNO_zCRLZ6nc@X{!Lcun?X_` zqp|!I{-)2~YMO1N>;0K8Y;?gTCN-CX+3ZiTrV_2uSMZmo3xsR)zg5>vN-97fcP7iO zZ}`cLM;tf9BL>9hn>Q@)Ph47le7s-3;@tk3yE3uBr!a9{TXHR?em&uVl_-`>JWing zB>!19guw3{Z%f6NO6_&WZpNHPXZ8xk#1Gl4ZVjlq;oXgbjN&r=$k2#)i zcVXZE&lBcerzPdj8p>4f6IvV@wzo~ezkqH_vj3Z9{%1a+^HM+2Fsjo>5?o^ zJ3GB&B&DMfR|qy8_uSL*e2&o!cwEqF#0ROyAKh6`&BE--+ldR1xr*y0n{`xatcrkL zb1~;wbQ;y;$dn9ra<0aor_}F{-mS11zkZNRX-?MvYuDZc0w}f;#G@eP7?vpM7CDO>8;83#n1FCV zf;=tXu1Y;@Z{x(m_m85Y%_{@D_X~O@S^eiq#@FL9Fp`)jUSi$;rZs-k{m3(%YZdeoS<({?o4nJFB0wir3n?VS8sFqQVc=JoC?)1AeL{t+ ziaxidH0V?_P*;^2W>lA%t_5w4q&o=3p=_f70A!67-#dpQDhW{uTKJ zLm`RrS8x<|2Ull;|DgvaH!2RnhwsEQO6yTUce3#m^mQJdy1N&?@8Qc5)x;)^QJB}0 zPbCD+``=Q=6EA%tWOw|K(!L;7hrKkv<=43EEM_FXE?YSP!JYzc*o=1(_r|-*K%a8M zri+|;>6>-q3+^W2;!P*2oMdC{GH$(|GjD5PHF!_A5ovS_*)4dhQ# zzu8x?cqk6-w%dYRB;}vXs8eIEPUDy(X;Jn}uQ8Pz&(t5szulB1T;I7Pe(SBSID9j} zayu8_l-iL~F^@yr!&i5ag09WJW5j}GQZ@whB0#%5Wl2>nnxx4OZZV;AO%oCGg-G4?Rcy4aNeB^l~{_EzP?>9pMZx z+md5aqpund*$1O{95?@7X&?P2XhN$zk&u8Zol?T+3Ls0QG@1p0VZofLpFa`zOSuvJ z#QVRf`s%Q#y6=0sySqWUTRKESdgvOu8zcpklu~Kw?vQSH2M`&$Q@XoDiQh%v_xt=l zf6nvF%suz)bM{_q?RD-2gF$AiDI5Yo_Kx8xO=^lrLzDf9a^v@BnAgBCzoJ);(f28| z$e@sv))*lKO>67Wo14axTdW(XS0lECCHUBO&T7Q)e82q6S{DL}9!+TK7%>ON@2?ML z#(c(Rzf$hLqHHk}vpT{P;jhK*Uu;tUiBa}Ml3%J^Y7Q2DU!hNmItIZnq>~dbeqbDd z+)XCf2t{xnVsX#^Gzk1ttkE|Eh3y8-R{2yeSAHn9I_CxDkDjDr#qwDob?@Z{Bw@Kk zySC=5c!rsWaBc9S<-SQwA((+nlCWJ*I10KDt>*cj+IvS~%~F4eOLg{KUsDgQ!*cm? z&<=J$dNfXnwDqO#)d%it>ld3M)pev6?H~Z#{JarSOp21?QKyJpI`=pe7++ZMGR0@Z@MQ*S#QG^^BA$kc^xZL4#7eWr z1&)Bz{gLZ*ihlj<%Og??3}7x{yLA~_;hZ$1eqgOWVoTi8%)d$R^p^l(wpF!t78Wwv zL}QfF(21{<1|6-eEG?;ccz7r^C5#x&zS**=*fE|B^U&F)?G#fbPFbJ(RCCt-I)~6lKdAxbAYiQi$7qop zQwG;c$(<85cNB^#@tVx46mFKs8myg#TiG@n`t$*da0P;(9r~n$HFSiEI`R8rI{Azi zWhy#C$cGRn&@q0BLHfloNdjx`tA`hfVQt1(t^Qv(kEe5iRRaqS%Z1hKREkib8-lHZ z$9mcDtbgKu6Y1q)DLWKF4F{Hsc$nTM3G9C;BhW#%{5q=->_|&V zHjKi#rB{?k9(SBrR%M4eR$xQ&E)#%MT#BaiFbTYG*eBQMb;D(Lrp60*73D^mo%Jv8#QV!4}0BBt1xW8}U5Nz?T!X#dyczs5>nXjGrp8AL~v%i{0 zw=8=%yN{>8>qQ0Z`T0>aSr$!`>g;IY0P1EqAB8Y-!(8jqm2GTZrp3gnsUEp}#2g^h zsNIip5up#DFfZmefuwjuY5>y3BkgVZWCDc4x2T1+$)n8CHA zV9Ie{+h1Y~>{;c>2ag=SLpWejD1S~(2h7?BgKADHD4FM1G;C%u{-R(uRwl)CVv&WU z>It6DDCMwC4M`rzwXX$jVu^lTb2I8Nw4yK*=xsnIh*Bb)vT!U^TtXp!#IBBBQX_x( zLF$rOSS|yL!&m~pXzry|cQo3Qcv0|*Z{TOkn7y`93}8$!rf>n>I$=x-cA61PiCzO) zi%bMF@B~Hh(jle6X!rVH-%i)j%y)|OQ1cFrg`Ayeb#!*pju5uz;>fGkCc<`!lN}H0 ze)qM%MIgcILds@tu^inxe+a=SY+A|~42!)ip(sJNtMWbdlDGn7s)6eQFQkLKN&J^s zkXLX|sa=p=dd}w3U1L7-p*@LM!($f?B7Wg1x)H@fl}*iYCE`Z7CE4Qo2B+@%T2D%| zw%!ql=XCNYe_kJrB#s>y^X8pTfjiU&a6!tHNOQ^Sp|O`;UsOI~#Va?mkzeKLSTT;% z2JQeCC9JL;($A;QAR2k$ts-yhk)#mP+OBh4ok82y4z-R^NHVBUp>lZl#6R116N?Rlk-1(b zUOR$15(myiuCxTpwTmz`M$weef&XNfC@!{l8vzeY=Ss0UX7^gp5+}$+OtG<8bTR{p z@&MmD4*_=s&YPw})5^E}RH{`~+mvjE4bhoibZG6j$*p@N z%+jBPgO{iG0i4IKSdPfa^i#1^avw0|1(|L_A-@nHeADk*CjRg{_XxspKRf3Rs$JoG zw$ssW9o%<~7Rb|HbqwoXf)+!aqS((dg_^C>C)zAVgtkDliBf(zz$ZI2P;od7MH0d> z!BE4n@fJ3{w)^l-H`Em6zJ!%V@=R3CW!QNt7ZKWn)>ozOo?@DHDyn7ULGD$bZ#0$r z`Vv;Xy2f${iK=dG;Janl^S<&w_fcE>@-x)3I#$vEEg_09us7Ne&%9G%G7KW{UE9g0fYkg0%kE7 zDO7ajHN=GD=sAvE$oDF1F9l%ll4gDJ8gfj~y+x+rc7!4I^6z|?4pfZi7t=AU;rqJD zS;Zoijo$=&&B#ut9unA((Lltzr3Xxgx&cVF7e^T0`Ye*rFE*2v(D;Si4Q^XImp&_^ z=|ibY(~Gp=sv5!Sr2dYtQ%$lwyPB(dX3=Qax$NXx-PF8Jk?PD9LNJm9dg_Fq7TZTA zb^kG-)Yk4552m)V_KFhQ_bSTj6-hDCT>~5K+bdaCK4YN)d^86}fHpqxF8>W$G-3EU zioiZbqA8pOf-{+R_o$;C*aFGq_b2W|RA&6XwW;TI%^U=ZU~H z>{nvR=M9F8!dJsJtZxW`v^EjrH%Kjhu@KA*cTemG-_QNuutb@i#w_~Qm=f*K1}WDT zSi9Qyy*Mr0rJq;m%y(kOR+W3X5WW!jJ#Ge-(1yHytl!r?xcei^JCAR5RBsUC%+u5^Z z-f@-NEP>f;{k%%pYJ<^?J}D9_p7r!RvSYXDWD+152MNUCSw!5V~0+|1%cK~ z%O1{ORC|ynR6>R9JDoR3Vnl9_QQ`Q4 zaqCTedc>a-Vn1#IYeIwpqY6j{{1~yj4re96SUU&Acf8c~4l_^u_-k;XL`fya51n{= zGK*FK=*b3aQGQA@v3XXI{M{S53Cd=*a9D9wHMf|qPfZ2*tcqt_Vg@`tW_D4E!zL-L z^4JK_V~}6rk>eGSalqZ>*nQ4^vnRX+$Wb4n!}&yXFutN5M$}S)Nl&G`q)g6)&6N-w zyv9z~mdc@1Drp%aq_tM=M{(voTTG}%|8(xS8h5&?wGx`e4%m%T#hjF!Uwp-D88{FI zc#ON+2w^xhWe-Ov{s43fdm4JcD`^-WM8Y@r9Jt>SFT6;w8b?2I15o}z+s++*zS-x? z;WfXj5b&E%KWIi`f#4w^@3CDmd{NcK<*``@JSrBtiBDR9KelSh@sP5Do=-Qt3iBG zY!pi0H(GEpEMhlSNU{1%sceD^_5t6T`9;}QYmhP(UvN%00ZsM8dl9^~&gW)?i46rx z9l4in$a&2xbpH^e4sKLH8fO+l`!AESdhTQ1cy$-opq1o@MO5rm@W5B|S6m>xn_e1v z^s2Lr|6BU9GMF)vDrY`4#FB^1qYW+^w73so_)Z=eeJ`kcX0y1e_hu5UJ6Z`KES=O+5dO7r`I-eYj>(B zw0tPhwqiPEGi8&kcm^3GRxz{xA?m#H4}IaGnOGQb%Q|zr%y0I`ruH|^7!$SvtNCu^ zZNsRd;?dRLqu9V^Gm9Zj5fYuQ{#7RZ_MorCOF;Ulhu9hEmH75IpnpLRSx1P2yWO0d zf3@g~g~4kFDZUzv+!3KKH5`RbD(6G`xe>Pkjv(Y9ooYBcfHGHFS%FJD3snhI+JXhc zLvGHSxg3V*{T_e&RBeoy%(iSF|;7 zxz3j~WY4g6mNa(2(kj;P8|%%lfS8I5x|i)EKFx0 zSOu~^5_HKjXF$=0S-T-ISfvNA+i=|&2%Z~wBI~-AbOu|-=ny+p2Bc? z3Bb-+LB%Y-7bMiyJXS+QreQ^<|E@RP8G>*busFOP90eUz;7>~CBTZ1sCdDgKfl-B} zFe{hQ`u(X!y0W6fqBUUGZL`3R3#kRd2-gqmQliO)HCRb3JG;%lt4A&Nv1SoDfepTP z`amTu=PwNjMOt~y*_5m8@4qt)_lPP?HJ1mG)nVXe;>oR%$UW75BUSZRl2}T*3!??G z7!F`-mrD6oG{kEDMq0AWkCTPqFxh%0)zEe;FpoB3qteGW0D!!1);FP2b~I-&*sWVq z+ozXP&cFD7Y1l9@h645q8#Z?2M+%nJ^}YnlrrER!`H0zVA;3E}t9{!6uUvLNu?gsm z6Cj|wOGr45F;tHAL$mq63qKKY)fv}KGK;SgO4|rOQO7XKO@vQB%I5o75 zfm*GaYWOLy!iv2GJ-|QN?|OmFXzlVD#hRW1(-E(5k>N#7Wl6`^Vsc=)gi9{1Z7-6W@uT3`7{WX##o~ucuMgY%Q@ql6^-E0D{sA*K zO8RThl=N{Ljh{8JD`lc}HGocILICkmcPr>?I_c+F)6?gfq9D~LK@0N|bbV37gSYnO zZ?fhsYFda0%~g>~W5y~j<0YAkI@k5G#Y<_xO_AJzv~&QdQo>u99E=1lghR${3ucJ_ zeP}q<>2R_JCpNz{BtO%`C}J*Nqr=v2Ctl+>^X?8FE&o2mtP zDLO_hRTPe7A=&^%kjqmprdGT3O4gEvth1OF$(*8AfsyYnm{*(fGmM-_um02>3KgZ`Zd z4U(@w2gtZYcaD*}XPb$8k4C2=0}vZ6*un_m!=(729>7@6DIa}`O_#4ktBK9=dq@8z z>kp7oXyq{aV??N}+CoJZ%7c zsxAx!m+)64AW$KgoHn?32G$6gF#jo~8OO}{#<_Z{gWb&T0k8GMa%-q^xG7Q4R1mdS zN6`i^!u;JEUMI8v#e&LMVjUL9Dc%`1{D3JVv@N7BU&z&pGdlvl)Uko8!l?r3dQxnp zGL1cb(ItH{$0882(ftKTzAJ5sX%;RgGO4k=_^yOH@LpkvVm`ka?tW}Ue!n!d)2k-9 z?c2qSskyNS61a)-0Yv?f&IYw6uO)3>(5;LVWs6*3B``Zd6a)G9&?oMYhO&yqmIS7k zT)F>t6#qbldea|U&qV&?;i<6s3^V2dVYfM~ZlZs@&wDmj)?N;WF&Ep*2X~EzY!})* z6Psa1UBP|nN~n@q(CQM<2GP{1Rwy|YhTsAk*4Arss-#pA2hY$+$X)NUq1^vb{m};6 z7AF6>-bnxiPAD!A0SWy<@U)9{Nz_{W$$X_KRhz}QQepDDTl)*(Ca*;BT!T@dE+D-Z<4I&e`T(Bs zrQovx0!<&l5gI~&5vsh9gGLhl1-t&^X*p|`(TUqo%yg-cIm|7|t+?P-elqNR3^A;m$;=L*Td+VAM;_~3 znhL2~m*2_nRsqshe3~!36>uUu(f6MhKmm~vf`V=h{5bE#XmfmB$=bp&Y#DH+t{$&7eEd~ozgtEBEcKwyULn9l!xAN66DDP@ zV*XLUm3Z9tA_A5)(nLwWdPVV=F`W^{P{sKmYc*fm5N-u%C6X>K8poKDU6A3>(+sD^ z*o+=3>ScR=1P=zPF)<95buu4zJS$;iO3ybdTuH<<2W2^heALR6`oicHt$x`~GwLtFx zpm*fOl(4L%yARGAhf@de6GC1>XCpvh!IVl`RoJL(z}|yPnppObZmx!Mt;D=t!RpIV z4zUQ~U=<6kbyR^3s<9gF(0Z0EPQH-}SENI5n3;`CwdjPfj6~tblj;}F^%)_1KMBHM z3^d*u8`G_j*0_qWj`%Meu!_Y1LP%7_QNYuLU!XR{h_tJDbzyegyj0k*o9!14f|(Q8 zS#4y?`ad!k$?Fdgb$<<%ExNEY9Rl7=O<*T4^_p)en*Jbwq%24ZJ!4RbY3Tb!i=?%G;C#Zf@hlwHA2Ci0FLt!t z3{zvec)zs%OOri&@m7Gnt9rK?W1zl-|M8+xyFH)3R2Cm9dhq^1KbO#t0Si0oRQ^aT zUavv{6-yx!IN?tMwf53;?#sE<{-YMn#kdNS-H0zT{xW%FI#o7hi*`hHaS7Gg{e0W3 zv_^)ECUNo0;YEGfASFQGk6`0$wF~)&QskQvP~ak9N734e49^_1eRCQ7Dwf}_-pezd zClY^tbB!8yWf#_O4`+T63p5KA(X)uc0dS?1&AX2IzPA zqYfrF6f~o-b^3SJ?SfLEma-zbGGyVR0p33r$`RE>7ZBnm=b!S*3t3r_OkITq1!XFBAF!w2MKBafQZxFTB z!%acER}UM_ZKmA*ZO;gS?Az6LZ={M;i&aFtTE%Q7FGKxE$I8AiKO}H{GjKT#z=DyT z^Dp@s;EpjsbuK_xOD^ZaJYWaC%Y!tPKj;uBy}i)cPg!;?MfeE98Q*ne^2HrN06cT7 zGq%g=929MDU#IfI3Wx0?pIp;|yEGz-{v{#8!D=k!i2&U-G-x&roz(tJRo(%qnKis+ zHM{UFY-w}~l@pbynb^6G&9zmIG@&9jXvN=yDcEcm5wn%NxNOZE3{w~{Kk4f@RwVq zH_8GUOYf#6zLZ1k8=j#hN=#!gJJu=SU5C?P|%48P1=H2=* z0Z1sFe4IfEoYDOA*-=qWc0`zc# zU*Ik~EdMjRZ$0qh=g*+W`@0R}*@qFBzCr!Cjiq|mHOSSG#yQ8U{IoTq@X zX6Wx}z&?Av;M2Nc|JoZv%XV|;qwsC028{3rimRB-TG3<$NO@9om)zj4$*4FYe2EFjR60)6YrW3!PlHFL|ex*&v@pGiF z=<`fud&?Q6#6n}+iQ*exuScTYNxCu*-x?=jDo`^GX(7T-MGE zCxiTc9Z-;VovnrwYvW<-@hv=-@alSgoG2^dFgeV1cZlh!Xm9XBXW&b~I;y%Scz$tV z6GtYnzblI!Yl?n4v}<0CkI`Id*i`GZ*f=bugeKeZM1HCCBZv)cN zY~b9`Wiy*BkVd2qFMv@&<0=))V#$Sy+PM+bjf{q3Ncl87DJMIu29w9<=2Fj(=6-7* zzrL}cOn-TdLYVHe0QgJ%_M8#p3R3Gd`=d_TR#QOlzPY@fh>3f7V;i<7ml7RhoOglH z5Dn8dfAiMAuN6NtZ9Vdj0fh8~{+43Zga7ek)$?av&1H)pJMQSGN*;WYDp!pv>zi8& zLb}F5d!vg%RY2jT-Vj+Tj`3P!4$YS%jpkNewFP0(2}XUB$;!{z()R(N$@f%@H4l>F z91g6foj>KWC_nMJ=vV^fGk=LOrnJf(p@`>3kRSXnjk-a7F99^zXsKRHf3e6Zltx;r`Lh;6SxLkH^6l- z-$V3_O#YpHeJGkN;De*C3M{(a`6WqYo^ws=*|<^mx6|{8HO4F43U5 z-Te;=F44SE&Rm}euHC4A^$(xkf)>>^Scn-E7?-Dm7A^s0h!b(U^Q= z{+y@Vn4w0wwIh!%``6&VUm5@UtH|y?U?X8)hGVs*2Bh_vU+6kSUE0hBy2fL=)srD_#tEW!O!oV z_wn@;&l%Oq+0KZc|4F=w)?x z)YXm{YKOf8eW^OqUNCBSA2V6!jQ;FwPq``*pR9YNI5=K7RCJMWxV*V|-QIt_bq}4n zPz2X^6IFXWFWNJP27pUW{{vTC=5E2eIE-W*_&ceRI#?xOenvpT(C6&PlWs@G0Rq=xVfI11s)gEzu)ij>G+$(Uhb4r> zE4Y|>@Gic2(Q)+XG@(n^UsI0VUz+g}a%n8uF40ErN1~RuBONrF-YK>`GCifd)w1~W ztPZZbTRGyU6tMZ4lpWVD-ZjL_5;po#LV%l$dQmDKu6>)=?P0>9wer*Q>!%Dw^WW)( zU16b)Pp(O-{oM1Sl1(aY%)8Z|qKzHCf!=T1f2HSJEQ%kc9J@38_Pu1x&umKzJifLj zZ@Dx9e$e{x?d-Bh$TTQkt36M({lOyJ!S6`j=!!MCq`29>x7V0;obbbU zcCp?2*m|TTefMPjL4rK~Z7apWBgKy8&tk5YU%xsh(gDjMpuoZ+1O8edlzXhDvID`g zuD&k^oXDOt8cD+E>y>O-7`G`j**_Cpn^G>RxAv2vDNXQ8LqWq?9A(d;RsW17>&v$u z5tIi@Q~T~E@Fjm!Sm`DfBR-Z)Z4NN%EX#wM zfh3d+(*NYj@0Q$v=iHkeI5_af-3NT99-`hyeF__iqp0)WcX%~k!2)gSKN*$LE-d#( zGKwgCsxP5%KlV?`RTN^4>HRx+y$Li~j?cE>A3K1J{!h9kiM%4gTfX^QE|Uu0NIa~) zs3+LkXyyEnFwN8ryv8D7-bhmMuuIU_l5XOF#2Q)rRBy8D<>b7V;{_T` z5K6##?yMrrn6&I?acX}``h(^wa{bN#k--$M8&Rc1F6!QpMxyEjAIQ!{VZg1g(n>KB zX4nH(IJRK1Gr0+wJIvv)?gIi+wXn}|27d#=2HZ-kJ|1eAS1}s>m+`DJ2`r;8F^ylg zhkQ*v6evBa`0p3vd!2?qwj`SW7D;j{p5-~Dr+l}o{s6s_bT`otB<8BPZ7T*NotUnw z-tWi<_f%m&LVs6_eZHB1#vaEBU6;}ooX?5Ic_bXPdX?G-(UfkW6hBVR`}v$%)fV4b z+1>v0-a&a8P>BzV{1u6(5ntLX~A`0VND zrWXZQeM7_1YtUlpFY?Xfw_|1^$L*6Mr>SS6x4{Wf^^P7?E!PW{F2&VL9-aPCx93O$ z7LtYw+1{7U-QWBmVUo#jpG*$??`PwiogH2Uuq8vg0s|Q#%pjBVzab*ryW{L2MmumQ zTham40j9d2p00qvQ(YLAqFqvcHVD{20h589o+(aYF5q9^@Jjw4M-+|~yo@meB=E0c zG!^w(=G;{~SAM{yyPxJfI zv(S2|FjsJ~ErIYqJ^gW1k>IOM_+j)pzWp*~!Thtn{?ypab(!iN!1Fh7x4@ywu%qa* zZ&gyTLm0cioLh-9@J4!s(41;z$EV9+wo>I*H6;B`8TusD@h1Hpw8zgjT{BmS6!J<} z_<*xZY|X1Gt_;rIuta(h!5KTu%hgM&^8}D;D4sjyrs!8F3JP=?T7g+&J6=o|`sn)& zW-0Nd&!#qJS#!kOptr{F-p=y-jvmCEHA8W5e@Qaw$d#{c`+|)tA>#X|P3j*^^o{9m zm}sr5M5Ly+NqB*D(fP%IMAOG`Z4Agt(6shZF<68OtYx(PVb5QyBsLV9(Ep|V+xO}Mctd8Jw zJq4YHF&(-x`4zneQ3TnPF6HVk&tZGN9iV~zltl#Tww>K_0Al~J*%?zwB}7SF9wU8FZ^nBo#dHE=0G zi^U+0I5JUqPA08irXZhCs&gq4h6E?y52}US&>=3Zdl778+Dod1k@@y$a3V|;aZhOg zy`@l~1vo;+ad`y(*s7wt#+p4CFAM(3pp?1c>QZRhp2=nxoD}ZmZb>c_?V8BighAG; z=90}o?VDNtLf~CXTZP6VL2|M{?Fug8ugZ^T-=?Yg)aUKRebmU=Le?Zw>Ht>y1gu0U z`7qJy>;ZjY1Px9?VU#(9dzJqhHK{mOksCE^X>YziHU_lSOFz-bfI4e=w5wAQO6zNG6bL=nw zF!W%w>WxbV@6N^>hE~5nT`h!dh094gT&%(8j-K06Vp@|-yj$QBLPl|ok(nQ0tGE)? zr7OF4Uul2!Fb6tb;mvvg6pdo%WXnE;+ZJ;`aF$!t!`zG>>{UuH@6)1;mNrbx>CRd+||z6NjP{l`8Y zv!~?#BHMXP88vP%P+`6TYtXH<9JPj%eB^3QjB^F~5%E^i>vrdBY3;;;(Syc92_u$R4rhD}r=@pe z`>1u>7@9a9b$N)6S89fvxO(l6XIr0=I#>`g-p!=3Z`52|BxiCdYRVf5Y1I#fvUc5z zS&`p)n(vb%KJIoC0utcY+9RtP5jL-k(JjXQwM2QXEv`QPipMj8ep#>7; z_D@5N9qPd4nY9o*zhDwWi=Hw*-_zE{VlzTiR)ac5CW*hfc+bK)u(4j6E|ZM1F!QN% zDl`jD{gABJpdOf_(|BGbL1`{Z=v^@9AqVN{cV2>*HKk|DJxhKZZWPHb^TQv|_XT_a zY4c1pWzRrAp9(k&)QvT3wQn49nNcI0e#C)!94jU_VZjjpvq)cWAT4=-Y%VuH0rwB#9E#MF*dO66qO#u7p%Yb<~ z9_FW(E5G+@sncs6hhBtK-wUgrd#{;XNiyJ{xvs`DwzsTie_%=0Odz#<9Y59Oiy^hH#kxTZt}71}zK6{y4^1 z%b=`y1*&+xFFU_g`SVEwxBYi>%PfO!?Cn!QsQ7mA4CuOh|8$PBuC{PU@HuC43Z6NB z-ikQPjM0oZ)yFltUK>$5dT6dR&uT2Mp&?8*R9$T!xFYj_R~-_E$Ip3#eXVTgO}^;m<*EsNm=DE!PC%?fgC{WgSoYCDfjim z54=$4z6eQ|voyQDi1RT}J^q?n{wtozkKTRwF5^F^*QS;w(hYSqyEDA+=+Tiq}0WI1!k8X+lu-_J0$2guv zpE(5CO*o* z1o>uvgJG4=vM9k;rmKAyKTZ)bn$)efLE7Q4O!ku}lHIBYO!1d0K@I{aAJ6$?%PK zr6d~3lppSi$lqB7d3<0qJ7gqhbo$tHRJ#!uaCP7Y4TKWxvgnUs71+_w1X}C7&&y6c zme%*q(`oAD#53t?2-H_>oX33Mind(o)if^F@-6o51AD)E z6kEdGJCGH8}dR6s5P(J+-)c2<&C1RWH4C_%fG>n|f^{ z$n&$RV852jEG_!vIZ`PZ@~FL4U(*~u2Za>73JZ$7d8Zp0q)^yq7cNF^SlW-b{^%&s z6filmi-e*FCXUs=h%oSxeGb- z+o7e0cz7AyKF^dfG^ydL{HohAnVd4BVLZmfuz{X9aq`}?a20(q+FTqNpf8CHc^Ef9 z5DeCmfGB_b_Fx`Wd}XTbBa_$?6}d#^Nu{;CP8ui$9FC~UAoNUj$G`AI4olnoC^s35 z1Eoh9*6gE|(l)F~CB;v`^FAk%=->aLc$bB%9vHARVlWx% zb{7~d_XxMup@WptHauISy2r5AQv!P>IdzHY1#B*bM*3gft#lg0Gc`t}ZrNO0ywBa) zE3x~;#3fsm-X6KUJd2@v(tN2_a_&LsytrQHLdPDfL$Gh0&sP1Kus?dN3JZI>X;(tp zhU_>mYve4c4aa%;L1SBA!}fH$dV2g@%*aRI*80ZeS&idY^M;|-5i*Av!1bU>g*pTa zqNUJL9s;z^e)YF3y2;_8JqTqXFU+$>Fh#WnN`{}SSH7~)$#r~@knsw2+UK~!Wt0!0Je z^U9YwD$uxwT8p>==1!(vl^#X0{Hrn}?0beisJ!$}DT3DkDck6jsoWwqD6Ggh*z>)o00z2k3 zW+*F&PJaGfNG!D)#;wg>FX!>F+0Xpbuy7=fk#GDl9BFihKw8Z5v|2_NI4n372YGAV zQmDgQhV&5E?>@pRRK8X&`cdSaiY7*m<`y(HsfL_s*Bn`RMFDbFU*ly%yK=u)7XQx+ zP@OBCX=@N4W$mfq#K9GPn!~Im-=bQ6TWl#8r`THilo^Vbz|{HiUk^+$Iyh%b-Y zY`H77#4tlP*tDk6>{30j{aEC)?caL5Y{H z#}4uhVBOT^{W~VB@nF|b>e>^5D z`ut}i+e_q3s~X@hhMLdr^%5_Ft&Sk`gOKx^91l#;(&Uq-o>PzNbFHW|Ck`J$NQS{r zsA>ldH8#pmO(u3HI%58Q-U{zWELgSpEBhl)b51{@-cAor}HfIwB(N|lxF1~IeraEnN* z8SPdm%oa$S(h6t`_w}k+sC9_jECAvEg7#LQt8=wa?19MDdm^dh{YY(Pp54QH6x6WU zzMY{>PhZ|$6W6pCT`N8e)!Pwo48SGC=(_vG_c)U9*31<+scD{DK@qjX=|=j<74T%hG7rY))3AoU zv07OjPA%p@8Lmtp(1rw%7mkT3)B-7}va(Psblb;Z^tIe(RgOnec{q}niGh4R#3*c1 zt7?hVvnXe(dPclXzcct5@~*xyZNV2_`6#_5oA`}&OZ@C|rhv}<=6#F=)qAV`Q`ezM zS{)+h2TaMuFDv*5;n+sW+e2TAe=cE0^Z@`3a8bjHk)o*%hh)L45z z^8}_=Z|7lhT59nVY{nM<& zgv20qriRO>>@fY~505@)7n(fM*vJXG)0R*+Y^2P7?M@$q;_?~@F%t*Y;P;#hgi0V= z631^U!|B3JcUx6f-naY4St_UHD{w{R2XmlxA$_&mIG%F!El%`>Dmh0^1;Op0v#T`M z3h%z&%BxZY9-h))NvA@*wkfBlgPd8aZJu?U!;N2p9|>~;Gw2j)Z53I3MMj9F*y`>$ zrjN$By|>m~+3n*Vc9;aKK$ZyH9=ef>hd!WRv)IT}Dk0VEQO-=woD1P@!>w?5`x^q2 zMXOOouy!mr_fe*Z`#bYZ*NgTI=DLt<(x2$UACc2v?~ObxXYXmb4mH_018jky8!1jtg(Be2aS!s@W1orY7R6|EI*^!r@ z3kYvCsfl^kGVEcZrwRbzQbA$0^H2)1<3j^JA)q zAQS3nqc^SKB+q^r(Ni)Wtf3F!BTWXd3x49SEm1+kzMm)&(P|7l##E@HTHiLGD*3ci zQzVfB!UUu)cFB$xW)#=n)Bu-6b4>Bv+RUjVkY%s*LW%7joM*R5JP;{rD=DrudLX;~%|uQ#GajmZ~3 zu22I0C4D0T>c$<6a;Z_glq9j|C^8;`gIs_Vsteo!nwwfznJdQ_u*z$5E)o}(Vw`o4 zJhD+Dgq3cKBJXK;Rl;;;3oPvW`3MWKgb_(NYGxv=oFs0RM2!tTjM#=VWsSE5SSdr3 z_&$tivR_P!iXb#a_H>oGyG_!rpj$_~J2PHwvJsGVrtvf}80 zODbd0LwG<(_cSFK*0&ShI!c)HBlbn`^yZ2OdarD9+2JH;p+Vkp+xIAdu_ zjFO6e=#b@k_G~pBDX!2E(I$C^Wpo}6Qw&j3E62{$yOYjQr|9CrC&bKgg1G9Kq$P&6 zo|!L^6)t+^{T=mTCv^AxS>vNk5qiy@W$mP%jS|}Pf7h6?q8|qAGx0igz{OGy-Rf$U z)a^3pCw6}qzsoAlF7SrxkPd>89!&o$8z1n$O|G1Q{oUe~;Z@HmgD@hTl-9dS#o;di+`? zY4-hy?MM3UJ(plfCSwtyUG~CHU5!R)G|(kEIVu$42?YShnywA9=)UU31fKN6lT>OM z1|;WKPbgx^D9RKx`+LQRoVs&g+_&mw8t^YJL1rDd0hJDMktM|}AuRJ`*X8w8m;f4{ z_+=GVE_YkY%m+$^bwn2X>bdnJ=K>QnG)bx5%-=P1rzM<`ox#+FE~@(tK*P^yxkQ2w zSC!}%;k1HzIIf2>7JTP1MvBgoH9iT_XZp1CfZMq+M)Phg?IUgHtG6?%I<(AP9T zq8iKpfYBkfSwchM(E;&Yxze8pPl8BuDg{Ymfqg~sCA`7lO7o=#h!a^<&UWqrjMvj(HkOU; zXCXWl#fzN!y7P5t&v}+O9UJIfsu`b*$AR^>(CBB!o1Ftg&+LkxA@{76e1M8<^n3Ij z=ijRK5ZsNa$KA1cnKSp2V08t#TRsA>w~;3RYJX= zqspxk*#Zdu{H^CoEbfSm`+H&`2LxG!!hCzsr$kX%_I%=;`+^l>R5Y>A7=z$KMJqt& zaWqy$mqnl1eViCbfScYt&d`Q0Ieo{ric(~XMjpcX` zF4T`Y4yO+}ae4a~&)^FHnf#Zep;@c^?h6vzq*7OU^~w#9vr?%EVojo#Msn!=h`Q z#H#ygpRd(Lr-gD3`PP0S$*QA+vr+SfT_jh5QA_Kmqn%=oITYcC_6qzpLwaAt*T8Dn zDrN}F{WaZcV}rax7{MGE;C3A-p%Iz)=ABh$x#UFn|Eudd!O?RWs1cgJb>J(qzG+ICd}{G%^f8 zMc3hR_$OK8Jz^%q`H7ZJ;<-%O^5}C*QbuXVSDd=z`upDZ-qwG}q+MxxmE}P4#Qc@T z-At3mmg!h&m={w}JQ{KM%?P_)c^qh^tLAz4=v!c1ReySUe0@}T>iOPlEs=}le#9M< zg>c8pP32M(Z{AQiD`zh~^^9d%b6ClbA5#w>MAumA`RJ>^)aK~{B*OTK+?M)rK+|Ctj63T7- zNTWDwe)26n$oColH%y8>Jdq`okW!HT2l1UPI3Xc8L>Q+?s;^0>Jlo2XnYsg*mbqB> zJ1V6XvA$wqcJzz;IGa>Vx2#viq+Iv%_l64dNNLW2tF`W*^1^Y6#E%EBnWs+MbN}m3 zbJsWrhP@(14KVC8fJ;(%V|Y*r;uHQJNcDI$k)OjHq4M-5X{;Z67IN8eE+p=X<`)nZD^6?*v4$dj)&8zNlI2Km}+qyzlVN*3NFk zgpufozxY25!OC^}Ld@4Vzbc31fz;^MuVxLYirRM%Y@V8eaR`B{TCShC9nfmQ-2hAz z=X&8t@-yaNVk=!7QTI=_KV6EX*4DC*y?q@ zLv}`<0xjj)b@j~KHxB5a`abyhX*xH>nc#qz8>L;$X&}+W*x)Scm(&u@+n#m+7i>Ng z`aZWh{rTTARbJkHZg%40Y?mzd{ik&hCgMVIep78=`xn8rDgdKOO!Az{v9Nh)9zV>h zPCE@C)AWZD z=Yk@~_P*ys-}mrgZbmIoU|#aChs_H}+xv$as&RfsO2EGNYB`tMuQmaX*tS`3$%)E+ z#>V@(h>I^Vyej=>C1D(ZYxA%4M|5S!HY-cKeZ{0WAQRrosGqOuP;os zk_lwer}Lqc<;ZNmYo(gug!z;})pIm+7Jz^j6{>$V>^^O}K2Awa2Nye=;MSBsCFpJA zifw#y&(5RDsFxSI7+O70Ga#)|ykFAQA8AbA7U&MMAIEQC*gx!JjjO!TZUy0=)abZw zuL?xY9W1N9jt-^X`)UlufVNqu;0Lef6OZ9Zc*Vei@|N}4^LA+85WHYI$irO&bs4Z{ z_)6q{Kb2cb?eLQ|eJJHzhW=)KT1Ar=O!&UC4{pQUuIF}`X0}w#t-*T+7Ut}Q!Y(0P zJsvmG()X@n=*PKv8Pw0-4o~SfYjQvI-K;kJ9}x}z@a$Qxii1DNIGlcvi{B)-0BU1mTw+O`LoS6WBn_r?T~%Q`sl zN|zeT1l4hYMC5}9t(Gd#l)7F3M?EJ$Wr!+XvP}a#%b3jpv3nsfnNM*`0pV`8* zXlcEttoGXHipGarlmEH0^V7)QYyl)hjaI0uPJdxwu_)D2@goj;SK-<tFOM{q(nK=!`@88|V~a2Nupj1t|q z7I;=4Gakvz2&y7I{tTPp>GV4=bUHkO6BN)8RKlWjWcy6ZF59Jgyc(PtVcbaf74^fA z%2%&Lw1N(+4=lS-n^dZ)7zbfp+{eq(DISzHZFhN z2k4&+sB9;^;@t_~_c_mn!>#&h%I&*tt^^G;^$6F&{$*M%p`y8Pf`i*A4`PSIdr-GPv0k}gV^^x0>hNI|)2 zn0C0Dfdv&dZ5zTWD`=xyWe>{}x`R$aX;$kQu6<@x2*E1KvO z-GLBb2L}6cE6%w&Fwk%uRVL1r(Pp)y2NLfrkR7O0U1R-fHd>6ASAQk}y*k*IiZF)Q z#j*m@iZ!qvjkkF>F*JRY(Z;<~n;@V|;&c}KO8|1v3^y-PAGPz5f!uX1?Xa|TEj7UH zJ3Jn`od6udN)!5bj#H2e&y}-L85sc!ES<4GoOH#I++FqaG0ZHc6z$HZTn}ss}!s3v*K!HBlcY#klRF^?YO)RIx zo039gWBYj_6m*QTHLLHj@DJEmOsX zDk;~Q4({lg+rM7dY%wcWi^?4rD(Y2>&0WjPnPQA$@5#0pp7y=dmHr%wxh(vX*#U6n z0an<=%=?0xNrTSjljQr#Eyd2n%11&+6_ifQR@w6Ab2@++H0ysc&e&V2FAN)K zBbems;}}3~&yj55^vn>ipW;zM(_2r?h(|#{S7((ACeJ)qd{Szpvwf~D%p=b*Hx(ly zf;&@@1H+l6`7noi$KxXbam1=5>n;J1Ke&X}1MmGj+bQ2}Ti9&2T{WqsmQUaT!GQVx zm7m)^@os9n`0V*42}1v~P%0()z6@1_4<03zaiw z%KFk2?VLor$aB9}+J!vF)N|Nq&*zb>1TgcZfVhps4Ax*P{KKzDfBYUAq46lOn^uf? z7#@%=0v-fcX8&M!6+Q?9lrPpm)CmMWrM0%+znm|fuX5^k3TDvf8+i6zulYeb$iYDO zYc2e3g#x5B71oR_xqMT1e#5zD#LJ32SF81pu0L0*cJxlc+}7Y?kEToNggLtC!|n~M zA5$eZqOaci9;#0*&70nMC##3a_z?5akAq!0zF$n6B8mQXyVYY=!s`Q3DAEC7=tgex zjPTwcTRA)4v3%Lgo3X9y0zP}z-_*HQ)1*VQZI7E65Z9!&-i!geKJ;Du5a`E*rmN&Y zCkwtNg%&-B3AlHnU}Hhu1H2LGXDq@I$>k@#;@DG-@Gy{S@iQJAC~pFv4Td}Uq@^M` zY!WBalB77S8Wr*#b|{$x@0)(?x>)~U+k(l5HK2OBbwVnb{@*K1F(D;AbsB;9x7`ikn!Ua4(&Lh;(6f zKaU~8ZJuVF^x=Exym-y0PY)AIPAg@(-X40a_sE-I%GzK$&m`_sFNMUm%(`v)&dZ7;|_!CemF$ZXKn%8r?3`X#Ir8PrIasuS5Z zgoram8(c1>YDhJ&dWyc_{m*vW>FNIW{;ax%S)OEZamL}1kum~VmQlLH(?;rG<1pyu z{RG9kp5!&fy%l3VSH-s+Gb9w(5@T*kD3!|8}jtiock4iMzz#*!PB_HNY2;^LJbkEX)D<*5;GR=9oR zeTTxxpuJSMPWDM`&xm`WLv^{7s@V;rIW{ehJw>GVXo(U zKr&w-Wu-s>E7CP_&Q;nd%Ofh66GfVMblZeq;6)DV-_~ECwMz#q3Bbtu{Xq|;DE;^9 z(Q? zcIG=p50M)nvHW7q7Pm%$E6420nrtyg{#Snq#^tUa7mkj!1J!lIxvNfo>N;HJ;4qjv zN+zzxW4&CaMJW&QkO`7!9b8$WRR`ja65$F;0E$CKi9ldVhTmOS=kLF#?GIFLW`*oe z0)%%lw-k_HZa5uVCU)&;B6wqc^T^9xq2(#att0u2-bkyR1I5oLi7jYq%`*pkG)nJw zAqS^LI;JMR`tqQLvb(SD(`DvEaeR`qUa!?yz3#P+qbBBl$;w$1+H;Bu^+8eUUy+Z2 zA%Om6%5xuWrR!<@<~B*%BF>(vv= zqu~#p4HLA7cQck(`OmKfp{QXBcs4Yf3wFqn^rf^OoxH@Z!N_KqJ4MKSfVz6rc*5Ts z1Bbf|kGyywBmEhgEwnD_S-VQEAP^ZIU1rF|+4)2jMN}M(aucu{E_Usld(>9+ zIm(7(lAKF)N#kl}!#?Q?uV8ehn@)-rTAw zeY8TBy~tM32V}BcS$(`hWhh;Bcez#Cm$MYKAtSnf>;;Vb0+~^G#pIQa^~n1mL@smY z^Yb9bgcX7g3Od@uguLH+peb*P7gbgX!hivpIt9p^YW0L~R%>%nK-q*CC^Wk5q?dy6 zZ-#qI20Y0YhM=?deuz>46x&0R)jdy>vxLvKA`?i%z~H+i&9JJdVtK^#k{JR2=@T1~ zU2gbTR-K|GiG(G!M1z*2afM5=UURBx!QOX!F~i! z7mTU7Oz3ZOWF@)$-M8uGK-eJTzWE+M0TS;b-$mQ!3X!j&3 z(i)6mmSR&jb$TaN_ui@nz4;F_Cw&o(08)(u55$kvHTEQ=?!@ie`wbrSa;SLOz%{U0*#MpiT@|EZ>%2{?}94`?$uO7QB@_F=>!lSKuz$K;daFhWj^^8niL zy1s&x>n3Ts{+LQRxt^wkcl7cV)&P-fDOE1N-~B+HHVe!caujgMpC73L#M@zy#xlIY z4@R4!*#w^@A|Bq5TxLRdjE|3(tc5Cuj-fmgUap*PqoJXJ8r-;U`lm^M!2hRN|4keJ f&y5VH&11TSbPgiFvYjMQ8;yak(G3jL@!9_X_zE29 literal 0 HcmV?d00001 diff --git a/doc/html/_me_l_e_d_matrix_8h.html b/doc/html/_me_l_e_d_matrix_8h.html new file mode 100644 index 00000000..38b021bc --- /dev/null +++ b/doc/html/_me_l_e_d_matrix_8h.html @@ -0,0 +1,268 @@ + + + + + + + +MakeBlock Drive Updated: src/MeLEDMatrix.h File Reference + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    + +
    MeLEDMatrix.h File Reference
    +
    +
    + +

    Header for MeLEDMatrix.cpp module. +More...

    +
    #include "MePort.h"
    +
    +Include dependency graph for MeLEDMatrix.h:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +
    +This graph shows which files directly or indirectly include this file:
    +
    +
    + + + + + + + + + + + + + + + + + + + +
    +
    +

    Go to the source code of this file.

    + + + + + +

    +Classes

    class  MeLEDMatrix
     Driver for Me LED Matrix module. More...
     
    + + + + + + + + + + + + + + + +

    +Macros

    +#define PointOn   1
     
    +#define PointOff   0
     
    +#define LED_BUFFER_SIZE   16
     
    +#define STRING_DISPLAY_BUFFER_SIZE   20
     
    +#define Mode_Address_Auto_Add_1   0x40
     
    +#define Mode_Permanent_Address   0x44
     
    +#define ADDRESS(addr)   (0xC0 | addr)
     
    + + + +

    +Enumerations

    enum  LED_Matrix_Brightness_TypeDef {
    +  Brightness_0 = 0 +, Brightness_1 +, Brightness_2 +, Brightness_3 +,
    +  Brightness_4 +, Brightness_5 +, Brightness_6 +, Brightness_7 +,
    +  Brightness_8 +
    + }
     
    +

    Detailed Description

    +

    Header for MeLEDMatrix.cpp module.

    +
    Author
    MakeBlock
    +
    Version
    V1.0.3
    +
    Date
    2016/01/29
    +
    Copyright
    This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    This file is a drive for Me LED Matrix device
    +
    Method List:
    +
      +
    1. void MeLEDMatrix::clearScreen();
    2. +
    3. void MeLEDMatrix::setBrightness(uint8_t Bright);
    4. +
    5. void MeLEDMatrix::setColorIndex(bool Color_Number);
    6. +
    7. void MeLEDMatrix::drawBitmap(int8_t x, int8_t y, uint8_t Bitmap_Width, uint8_t *Bitmap);
    8. +
    9. void MeLEDMatrix::drawStr(int16_t X_position, int8_t Y_position, const char *str);
    10. +
    11. void MeLEDMatrix::showClock(uint8_t hour, uint8_t minute, bool point_flag);
    12. +
    13. void MeLEDMatrix::showNum(float value,uint8_t digits);
    14. +
    15. void MeLEDMatrix::reset(uint8_t port);
    16. +
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    +forfish         2015/11/09     1.0.0            Add description
    +Mark Yan        2016/01/19     1.0.1            Add some new symbol
    +Mark Yan        2016/01/27     1.0.2            Add digital printing
    +Mark Yan        2016/01/29     1.0.3            Fix issue when show integer number
    +
    +
    +
    + + + + diff --git a/doc/html/_me_l_e_d_matrix_8h.js b/doc/html/_me_l_e_d_matrix_8h.js new file mode 100644 index 00000000..b61e0537 --- /dev/null +++ b/doc/html/_me_l_e_d_matrix_8h.js @@ -0,0 +1,4 @@ +var _me_l_e_d_matrix_8h = +[ + [ "MeLEDMatrix", "class_me_l_e_d_matrix.html", "class_me_l_e_d_matrix" ] +]; \ No newline at end of file diff --git a/doc/html/_me_l_e_d_matrix_8h__dep__incl.map b/doc/html/_me_l_e_d_matrix_8h__dep__incl.map new file mode 100644 index 00000000..da500931 --- /dev/null +++ b/doc/html/_me_l_e_d_matrix_8h__dep__incl.map @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_l_e_d_matrix_8h__dep__incl.md5 b/doc/html/_me_l_e_d_matrix_8h__dep__incl.md5 new file mode 100644 index 00000000..18d9aeca --- /dev/null +++ b/doc/html/_me_l_e_d_matrix_8h__dep__incl.md5 @@ -0,0 +1 @@ +d570f586997cb6e817b3d107cba0a8fd \ No newline at end of file diff --git a/doc/html/_me_l_e_d_matrix_8h__dep__incl.png b/doc/html/_me_l_e_d_matrix_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..40d9c9c9ec3697eb94bcf7e8fbb30d82e40fa293 GIT binary patch literal 13817 zcmaibbyQW|_BJJmNC?s;2qN8GN;eXMba!``NXdaC-5d!)x};O$9H~QhcX#)<@qOdEgoH#P?0Bu$;j18OfzW##p<3&)LI{*REId5?o!%@W@Jr^5t*UV)`aOd( zQRoGNofC|Tnwnbf^zlD2=KZN%vUC|QJ&07P-1nxtTKsO7vBZH+RX^7uR6eUB+Vs~A{n(Kt&@;zq7kMDi{Eubvr;5)Xi!|15{R>v7A7o}$ zzZSi$Sf7z@;RCugH68|00G};*_L^3Jp{wv?5tqCa@ZLB_0t~c{|JY)tSf6NwS&PD; zQ~IUHk<;SYoC80Id)&9RD2Af<;y`!#_712hvt_xJ_}D`le5-c*8LKKyDSGNx!`x-{V;E63>RaUkvxfiY)5SE$Fu_q4bDqYS z6|0rZw;*zIcl&7>4ysO8(wpL_?Nws23I$d|#;)q`7RDS6)%*tAq{^ zJk+W(cN&(ZOW@!tFm80;GhS%%yC~MG%46RD^tf@HkK6YKw36>+PMzzqMG(Ld7&hz4 zwRO8%8d5{IKlxZEm+SB5r@YAO|Xm$!=?$`J_DbGJAuDl6=wVu5xh>llf4fCxYFYbvTx6L`cu+>d)o; z@mz9&&EkIlxLGj~on92LHG?t&U(fO3nd^qTh^BU#G251ENDLFKeWB;z1q0XAAY9EqM>V3p^aJUD!IrqOqw`c@S>`MUbw^C^$AG(?!DQ&5NC1zuzZ4 z9Q@tqg}8D+M|)NIl|w%3{z`iW?e^lw#r49-AGC2%u(D^w_EAfUT=e1b= z07xWV1Y;8e)zkUR*vEw|GZYZQF;cJTn#WT%R+4txnI)j4+%EW89T&}nhbkYB*4^AW z*B_pB+F#xw@3;z07PyAXm3yrDlJ>Zzr}5szzcG1WJGiGhWGcs8kzFjvtuQecZXCJU z1w9vT$733*;W z5_Z&KI1=D5c!!4ij6ab#{lh@m!)|cqPmDhD(0LMs>|^F&2Z~JkRb&V9c?f0;zo#c! zumjelgL_lEeCw?p`+$@BHr*Jzl{WH?0nCv!Og=RGX`2mB{_0AbY!*M*5Mq=i!AcwHfHQ-zFKpttkJ$luU<-zfV;cPHxh9ytmH?zJ%^b7&geF3)BVYkTLjSli0yI{IJ1@jQnhmmL{ z4Fcw=KM@}NwG&_O>UDUpB7)EQMA9V`2T;G>pPM_a@=Ns+kD!0=({cotTdc`3+8iqa zYFdc?(e`nGib=aqRSTyIruc?h!F=(0CN#}WUj?qQT6(J16tqFBu8?gz zZ31ajK3nS`)RtLQXAY6MY-zL#2eQ@?Y7h=)Pf0k0Lg~h9CliOrs&L3>nniAzYd!yv z6XhfBOjK+8)JG@P*cLgsZfGw`F1FGsEj<*s^r1>$*AHE;2KzhD;TUj!Lg--15Ewt% z(YEu>B3)?cR^C;13?qIRN*^p)B>5IbMuMqtFkx*X_i`;Z<4b=!CQ2V-w6a~Q2hRu3 z@Qj_Z+Tb72z|?ZnAGLW5x=k)MtWCjC6$&QfW(+(%E(~mWwU{!7VH-d;utKyyUJ)`S zj!1}1nBu|?m6VvPeRk<3hIEc{2pRu1nOE`UxI4;UN)LGeztR_tsC}yH?d46s=VZ_;2LHS4-v;SZe>6|VG)V9~Y!-U* zgC2O#GCCd8kb~O@$E&9y_&z_^E^fN^Z(W`qC^EBHixg(0BDrQxgvMp|`)OT8c znR>^`A4}FNNcwhvwFJ;UERRZCrk}(vW@T^-L$$Z)8ND-Ee)OLHL7AgI?z&MQMtVI~ z5&~U5k5_k=pkssZ_Zj4Kt=KS^ykrFPd1akyah1u=M)uhvuAsWUHH>c;KHPvzKdT*^N{%lHg;cX$aWjNc#-nq@8%W8SN(BvjQ^QuMswMKKKwc8OFqa??q^LH8!{>vTu8kuZ4xth^1fqfDXN|<2vUL@3 z@%x!%K_ba2nR!fKt}{0t>BP_E{Y0)r&lVG_ncXjvqtjr+EUi6@2Tm;QmCKIhfkhKF zlgMj)?r_hVOH9-Sc+)e%^uq{TkeTeIuXRzY9Rg4CiU0AyuG8Xoep2zv@!!F&Zu6!N z_&&u83)?W>&|5<6%Yg9vLXJ53J1mI7f^|U5J#_fy&edgI>rc~Qvc;kO;$A@*SWW}$ z&1JV{Y2`8DCWREeIr2yAW57!(ggojX)tG6XOD8pD(>%JAAkN@d*JT|Fk%{UVQtP&4 zlQ!iOMrEWvnCEp>wJfF%uZ13zBa1~3elrZR^R~csK~n``7fYw!?|79wkQxjG+oHvi zz5#~2qwOYQx&RGp;o_U}Lj50aY0`t91PY;mCrLP!lTm3wE`b(vbrVZVZBuO(6XfEk ze%;?lq0YO$iS|bqXwU_LCh%-T9*(EC9tI)EB9^tt#VwTxDe7&AWX2fQK&3O$Q;=KM$=gBmL2IbtrZ44YF67{)PFY@a?|{?g z0xE`+7^n@Cx6Vl~($Av~(jRkM586DSsEidgij`*k(d9jZ>X7VCT&}MeiY>q-{5B@w|p7ztQMAAU02%G^XWW-U#;%^#vv~v z)REOmWu4hg@@acOSkF&1Ut_|u#R*lqxejsHqz4;>o9Q%nWU$5rm@CTs`cr^?xqAwm z{LlmcP_XvV06FzfvK<~#YgJyCKT=pEzkzuCsTE=@7B*6b8~Q%8xt8j-r-5s-yANtr_<9Ovih3JhmAz^LjIyFN@EkX%_VRH~VU5 zj5G~*kEz@hABYDE)RM!)SO4ORc**%_Ug_->(^?V#?r`g6Q~ydmQ5k~@=4QsRN8uG) zC*kT?TGMn1x8KEDyzR+?f%H8Zc0xUyMrCmV&2(<1u#;o>QdkLQj_4WdUGRpUN9wx> zpikD-bTzo#>D~}Ll%dQnDH*bTsW8@yyo0C;K@@sxF2m+7TcpoCq#EE?d%52@my`FZ z0ozM^?S;r^^+jQN zfs^kLOdBLHM#nJCY(Mm8B&?=5N&K3%#o3s4!`Qo73#UqOyrwfGKJ0QUarZ$K`YnXf4sZ3nu#7&#ls(PaI`S_U1<~ zf8*j?g?~Q7*vnswHnU0!z}?s~29H$?(b1CDad0cyBSg#7`Qesl#p1pt$G#lRqGBOq zxr$5i)f=%Eu0Ykz-BmK8;zEPZj@J92N++VPGvhSh%eiZMt9S!|H|0^$;>9#F`vrQ? zq^D3&eBAUzWg7vd6i7UgsCuT4a*p7`mU+f@?Lc(6yGnJg6mN#Kb^VIZg}?Ha!7t~M zLYrikO?1$_bu*$uKZBNnx{n#+2hBc?bh)vLxt%cmrI|J~r)}gMk({?x zbfEeWCVs|Roto>@SEjt~o;6)KhYf-b$w$r|IITKS+=auvcdD|Gop5u6^VAXkX=0-l zv#n;46jYYNvsLB1U0NfFh~0WJVINM1q;mhsBLL06uAu{%327C8Sjd&D_PCOz>Qmt3 zWH;yUQ>dnZNS<=jS8w4Q3YEi*Y9%>c+(~z3NqqDd1|spU)TYU*h1QV{P)H)4Wr~RZ zIxU>Zf-N4om7H7qz5wfK@ct-5^zeMe#xwrggRw$QgKHuCq`{;#?tb3@++ zAvya7mxqQBcg0z!JmBNJL8ORm`e)y;$N0s&11S*)czB%89v%M*RDRR~>ORW0PoNX0 z;My3u>o12J5+WR3U68QM}KM`arnJ6y2BI`#^E_)W>@7f|?qa z_mLwrj`a)DeRp$|-WAPlcK^xCzKw-iyEL)WYdmV+dbdFh6peOUY#K}IIL%gyfW?1{ zuxV?(Ix{9DPXjU2xjWhSeZyw2J7S#1L8(*OWid`1&{#9(&sutUY_+icVDL1+#UfHT z>FSR5;wmHpWhM|t7s6Ef!~2t#EQBXp$*;Lh%7drGz!Ka^W<11^yGo7mpxKKGh1NBusx3KA5dD(|2@@QIgt zaKcQJy+dpj6LB>gc9a)t5@P-j04sc_=={WgafqCI0=v=W^^3OI+1eUr~-MVn*56W2^(YkKp$N@=9Lc=#y(<550E z!dr1Q&S?|Pg9BGuoB=FUg(W;sg%lfjl1KcSPO7w1`?+IZ%5tT zyrbrbc|@cfAYg;7&fNNx+LX*Zr zXj}bAhNxca;62N}XO9`c2(}XI@m(kcfPUanMW9PZoq_TC$9>>Y2ROrC<0iMc8vfW` zv7&@{%uWJtuJCv&?nbj)9e*vkN{=4*4Mv z?it@#v59nC2OylbD!#`4O_xa%0$SJYC}BM2?hkTXNZouc5qbL-H5?+d{ci#@N9n5Z zj@MD68O+NA-rxZcyjr4K;_)aW- z-&~^I(sPiD7~c#MoM*#Unf6OyK>_nkkY3ve)U;c2Z3gkP2?SpxbPTgV z9Lk9|_T5TmIfiicn8hgIqS*i&Nrs=tCD#mY+UJ*x1R=m3s=VlRAKJ2nR{8!P&W688Xu9l2K<_FN_fZ~ z6(+vkAA;7`W%Wi|)u>HGs4ypZgq%niM(brvjgQaVxtG>_6cvbV$OOHr`#lo~xY7kH z`_&k`-E}6#G<$mY6pQZ{gOJhctg`2I0cu*AWY!95P;6Jx8ZDS9H{=f)c=cPFBUa=l zC<-s@M7L&l75gxA^okZ;C_!uI`34LC^kd25r7}<61V!)Rf-29TDl3RY5GR7Plk-^)H(rc|1XTBG@Q3rFYI==gQzUGcoQzsb;f6h}L3UudU~Du5`TK)(x8 zYLLgw0)BB>peV9Ped$;Wg@@1>HEf~iUw9XaOC-ITvX@fY?XG@I$KN@y-vGTA9uF*1 zhe?UjDmX@?rSCYhs0g>aFkL^KI+y!@$DWKh`9&&-ys^dh8-Aua6Y12&LY?r)i1YWv z+Rdvk3`}Kl@=BMa6HCZ@7$#@KEQH%B`Y*#L9$|00dTr5b!WEZrYjX0os|0Z{ar3?_ zrI1YRHffY1@I|wqnUa>F?_}KoB@-uGgBXW*_`W}oMBgXrf%%Y*5AvyYPyjHK(@azA zBcJ_CIajpPB~AO<x>V7vfMk>&=2Gg!N5#coJ+;#| zLQowZFl}UkQ|aoq?lvn;aP^wcxad)xgH@8@&=+?L4P*Qhf&+C zjYBkFWTATRie_TXU20V!K%E!HCw>~M5t3vZQCk8xyut!yuEYvuO-rv;0rZ5OI1^lE ze;0YbV^gRcQj)IOW9P1YR2or0gvykp?yd5%g(w_P?mk}gJS_Mh zXnVG*kUfDk%vr%9Li8Lo4}b)5$t+0*FyQ~;E65jH8~g|0^$_H4At2yqKjs3Qu&qCV z>xRh(#;K)|eOze6J1uVQxn2f&Wq+Dq>)-!XKO{A3wT^FyA!V^_+Mr=z9?Ty0Dek|) zQt_jI4b0@x%P3I0Y!J6u)U7tpx?|c;w(kEg^W|whWed!O%Gcyh%!gs0sHp!x(8%U| zyDQqz0&tl#W-*|hSFNSNx1EHB2S$oE}qDerhNOg6No9s5LMe9c8(ULOBSYm z_Bl1k{_Nf1Uh&Lu!tirTXxwBDDSZ1|j!w63Hc#PSDtKtP$ljwNE%mbN5vUzW3LTl! zc!((d>O11+Z3(VADwd+q=3fY1j;_e7pBZLpv4zIA)!X-r&5(G=jFmp(os{<4pat}$ z9zmVGqdJqqk9MR&>|Pw2ID_VJMG59gpZ=}f=*9__a=Ml13Tj5J1qiBpxRMo5(ec|v!1kvQ#7uURq_EvWPWJ+F$+K=U)| zJ8sGp8e;S(>_FGF8IZf3%2*M*Ho@@iOj}orIP=0Ny>rkcpj-87_g}$VxBPf0x(GsQ z*ti+>&H^Rmq=3!9?N(d0=TXs1kS*vx9`7BZBOTlN51UGXFQuessjuKl#rdUbB5MA0 zxM&qeRLy7J(`+u#?>QfN{s1x$eLWt4^Zo}B6>t||nd=0e%w2s;d>I8vU=*Ib(Vv%o zr-MN0w(;DsmXy>DPG6$iO^H!Anz0hD9W5#u@3`Zhf3x`h{v-D|RC&82fjG;lG$eh4 z4VG;@xPd$pv9B1{W)I5X6LfTMsE7;9AKg;Qbp#CBOUpH$vYE8iV%?15zT~uqa0FTx zYYl-Ei^0AM$=5jrD?_8J|B#!y5V?<`MoH=@wg6O~bAs{3Fwbq*rk#MzeXZ>xO8{p} z+wH_0GE8*%{kN6uMzFOeB^X4T{SahXP-Ffgap;i=2eh(9|84!3P4T+E=!7}Id>q^= z^kYH|{w1}|$B}#LUp{v?QjsoqwYfaR5u7k^Kr?x6kh=_UII%{>-RT0GLmWlhNiA=m zt4Y2RH_80{=pH?Wc4ofAvNX>S7}Od#qr-GT2AH^JJ+SJ)Bh(8YzP{)iQDLsOE) zL_QZw4k(v!5W;_B*e+Uz^=8${7%P> zb&9T!zd5-X7mKNzBDX(_Ko)lLRw^IO)fy^hrtRHoU`MsUX>m3ka=rzO-ZD{m)8T^3 z|LH0A_)+6ukl~@=+`Y@H~e&rk7&*xEQvqo^Y*R_&ZA|mYQ|8&=ZXxZZdNS7c4 zCR6+m&9U^$s0qBeekuZjBi~FF8n>^oN*~ktMa9rCT>A1|aS|P#JOwYXk=}e3!JWCYR@aZvWLft`=!^;K@AMTcLvtJ@t-yyoZo!k=L8AU;ZOTXJDlNFB1 znG1@r{tGC{R^u&?RZI;iq250Atf`18YUNtc2MfOGF1r(fy#EX~rSUsQCUxS$Lb25l zqY|0wrd$+8b$Fd|%kIsT%R6>_2WucG5RyMQ>wb^7QSTx`b}ztsmM}%&k9L?VD9B`p z29HC-D%Ux%P?e3}jQQ$#W9}gI(otzsg*yM6+|8Dm#vQ!X${gP5*hgnsa1`s!$Iwow z_s)&(yUvr#!iCCy|2OCaA#meh4Ng??jhlBC0e?KsY7O)fXEzAn;0k@I@{4uJ5SUR9 zUAwsQGWz@vVJAnR9ySUD?f(Zs)x^3V^|GIABtx-+M)nZrg3Cao2h@ow8rMW)xAd=BAxK2hs zBOm`o#{Cu`-Hcq7%c>v&q|uP9xB0kA4PSm{n2knr<-E-j$w=i(^zf<@w6mX;aQ%JFF&Hw$-yFo; zP*BYL7(g+NwQE~N@%Chv*_G26uV zZ+jnOt$jlz1zF~l`*B)Hr zKYA{#ga72$+#PtlRPV;O;G)rXs*oPIWAF{n?O_JzlesSny>E--Q(m<}GpIh$#M3Rk z$Z6P(YG+HgH>Yeo9hQf&au8R+CxeLrpnk6M6!e{zm=VPPLvh|C2;VtLg-+0+JF=lhf1mu*X+;D`F64plg@zS5$Y0XDe;LT86jd9o4N;KLZRmNS@cZdDil*~Of0yyH zuz?eUUN9r-><c>&4_Ai(u^GihI&yMyr!eZ3w+W{+ExuRBwS5W^nIzvy zkbne|zlB@uF?aQEi6O~)jP(C4GEx7XB(83n4eN`(K9HG-GG8!J`RWIPiP*>%z`mrc z-7?hHMW>0JTT;XwgIbp;NUhRea)kCc-7{_Y=ej~&n$~@Mn+6=NmcPAbFw%`zr8>y> zULZ}25HauZ>(687YjU2$Cb;q5ZgIFxSgEE2UqlY==jg6vEjQYy5btN6+~mw@w)hcP zGl?>qXcn@^I8d(n`>hC+#!Jx;$X>nVAgHYE#@D1bCbzP+p4F&PjhZk%k83W0J0#FW zJE>s3ZiZOTCcq`gIUCH2p0AMwG{6gN*P0TUPaW#DVeh*7H;1~_DyatGpTT%_HSB+l zFi591r0ld#!N~V3jPrcQdb;zbVVyFfqSLS*x7j8CvM!2Rg3VXIMu*ucE z-XHd=3%x#*vEpHv4f{GMvgKdglJ#DqV5j7el1bv*Hm`rc=P9s?5nU+MVUhZOk6h6-t3_=?B+sd zCR+M=j#dlzY+#SCeOD*fa7!V7nijJOwGO>;^iExeoz7-gDRkj7sx`)+C&{__&6RP# zM`_=ME=Mivx-ai=You2($;TT{=Ccauv9FDlEigKwJ)e*DFf-;T!og(vwIgZLBDhvH z|NXPM0QRzc{hQgD#MhyxZdTeYEBME$FG&JuXTuVHNGZD;c0AGk!&;b}7UoR9njC_a zT|t(k{c$;&XbW7K>=*4eBL?XJt_S!C`PfFAFN_uA!WJCm>RZK(OTM^_SsLVMs~4=e zHO)uDDi^dVNb!txU;2J zXlcd1$1hn(AEXywyai@`m#d0tLOrpQAK9CRF!})CV*-Du(QIN{OTz zAw&Ao_(kI|49h;y>7?f%e^DjOpp;#uuR@x%R{sX5RY-K4fg$CxE4EVh<)*xnX^v#; zCg)DS;(>ytR2NKmP48&#viVwvVr|1fwpJYGhT zp&fCHe<^PwC1Gl6W>qEQ7F-~=e!80(y!xAcinQ23ue@tgFB&A)-1dboskB`x)J zW8$(^UwHU)W%=62n;DPg-)lGjx5ECT1M=$nioZe}rXD1?U-x<+C)b%f@diPFPPW?f zYAuPBTc4J&89W|e*?O?0OYNjnWsYexUK}C#JR)emtWXYqkz;}@ynm0kc+o=<9k07x z%~+q8m$!jME|AMk^?HjQrsSp+tI9Z0&ryA#^u1R1Ch6GP+S + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_l_e_d_matrix_8h__incl.md5 b/doc/html/_me_l_e_d_matrix_8h__incl.md5 new file mode 100644 index 00000000..35de1949 --- /dev/null +++ b/doc/html/_me_l_e_d_matrix_8h__incl.md5 @@ -0,0 +1 @@ +a746085cff2d00d445f30fa2c039d6ab \ No newline at end of file diff --git a/doc/html/_me_l_e_d_matrix_8h__incl.png b/doc/html/_me_l_e_d_matrix_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..7dada3d32794240208288a0aece0020fa237bba9 GIT binary patch literal 37768 zcmd?QWmFtp*DZ$-cR7F5|5`ut$ zsDh3PoEfNa`wG0Fn##*aBK&!LeQ(W=M?iRrASd}o-2-~C?Cqg(o^tu;vh`vlPz_-; ziz+9kTU_Ji4AC5^6uP!;z8N&7?jjUXyw+{|diZQeK@hCPG&wSKrr@9Ep66a8{?V{5 zt!~UcFI!w}p@vlGOHpYDSVQF`00l`_{KD|^D5jRz&Qu(iLFe|^(?F}N;?mH&RM3`* zZom5I=n{+m|9+@Oy@Vr4J{~!c`Xy(14R3F6w^!XA&` zWv#8gSt<7%Z~=x__rl+eWhGH1J7OQdl0{4r@fCO`9TnD$-A`0nT1tI*c<7WwN00I{ ztQmpe-y=NqBi+9r;|Ozs+y6OoBw0X&|DI=ghZ*wkY00+<|IOt$=GUiNGQRK+&28}V z{9dmcz8RkT(%kae3(N1fU91M?Br~1Q-!g6}KqQVTPf3K(+VOu+m z-*@>)g>OaITR^K-cxLht{=?HxGN;CdIpy!~#O+b|QSG}sEaGb5v)z+eT8r+K96LINJ|5szp$got)P>OAg&|tpSjBk!|6V**eImSaN|ul@VLx%l$AV9W6U6ZoJaflNNKGoYl_>~W`kLdx73pKUmX4mCxeM>sV0`niWwql1ka>@7<}FgpP8BYd~tE{ zr`fbS;-5LOS5pAeM%p!_#YfPUbezwF5t_Q5SGd_3^J(X^e4`XA>a1M=0qQ3 z%hJb-|2eo`CYGJuJXb8^kd!pXFF@1y|AI!qZvNkZ_y1>?>nx!>ngzfd<|nA4g1bY) zdrCVL#-!4|@MY4|(}CbRKhPi%0gFd}0~Y>Y0@#(yikC=VTSSFRQy_FLaRxacu7P5I zT&)HGR1oJkro#32vVOg2t;IoDHs4x;g~%7w@UD8g-4NQnO*GCVR(e&(e}N_I=K^={ z^7fj0S`#}AF)}O1wbG%d?-u(Pj+?b(I`O-py+oO=Avn!UmZW6Fr+*2j-xk7NRnOt4 z<^axht{1$a~-@?VbcHyTWO_2-NO z`&D%F=j%S&tP(GB?{PNvcuXWxU_|{;HPq2&kAKH!SKIZi2OZ{uL|E;h1 ze`;=9dw+k%TqT7ZF0$6^QopZclrD(xTMA5KGVo824;}YrR;_PBZEi9?{em+VL8c=n ztgrcB-Ukr=U(6OXvb;J??OMW~b_?uh_SEXS zVXLs{rMuC^^6H_KBxc&bOHEEVUzWKvdOvNjqvU@vxoY+T@CT~d|8Tx}*mTJS0aJ7i z;dijHy0#L(*jT?c(f|TFIg#$~OV2fReg*`No^RACNS&FOqe7(1N+9(un$c*2Pva+5 z*hT1{h47BHJykHG`1ab2R+n+n&>p%kJ1RpyuoMswkn8?~s2uB;_7?*LXdtJt0`wOk zIVOuYuwUE^!{icT#x^}oCV`x|ur#Ltlc;WtA@t7JN`yCJo#6HGH-uK$6yF@B)Y7eTa2F!FP4Z_EKk zkP`S}2mWIn_Ra!i1M%BY8fjn^h|bRF4Xl5)`6&+jd9Wxw{mHw3%q-{yhMix8?X=8Q9r~wZ1PiP5f9GLk-Ca!g7&v}z815Ob5Hn3k3O)vy-^2tTL6XWL~ zEclL$`y5=#!vcc|TXlbp?Lv$a^bYGx;DK^i;K?@1yor26oC0bFzjh57;R$%UFlm@| zpTlv1_=zs<4L%C1NgrKgCx}XbW2OHfUl=`$6zcjdNK;8rY_3D_85B3*x6Of(Q>Gj4 zO(YlraF=>rKXj1&{QN`XYz%1$;@1DMv79Fsp*(I0;Ew?Vk`V+pRzlLbfRA)Fsg=EH?vOeH$xF%_?~BHs4vuQ!H#ISK2xdy&0{w5q7g%wn0*4N1 zYnLmb9-c{M#Ys5kO5Y!ZjN;`Z!>Imorm{3ei$5*GXUUfhd#rh1#4C}E$VR=zBTph) zivkxof~2Mt)dD$Dt!e~GETd4Qf2tctjZ&|;qF3OfgQK}adpQF;>>&$IxJ{L0)_724 z(5+Aovd8dxfJA5q%`;3laVup6YC0-e&=H@jc~HvK8v$wZqk~r)V-V80K#)=~c6^zM zyuZVxyT4Jr;EDh-MYt@>KYl>!G30ms5b6fUxKDtIMoJd<-lT$%{w zwFb=EIN^;3x*1zj+I_*>Bl@@z_vK9`n)t&yPTZzR+=G7C3T3$x-YO}@O42hSk&(2^W{imDAL;xMcrVc2RZLn+rwZN*WBOeXR50xx;7uMV zM;o_`Q?U^9F7Iy$5)N^gB??aBSQ-zRE_7P0w(l zQSwY6dhmA~edx2T@1Ao-(r{D-Q*4e^oj(efSPL+t{{ z%aPg)$e;9i<7(5zGXhwfQ!oxNN|2k`DeS4jK60|SS zWOVWj_Z}vsp5XBpnj1slKqcbsDBj4AG+Z4cpK*IsP{Z-X1(zx}0Ha?YNq_o{%!>Dz zuxG>a09Uw4ly?rp#6d@FF{0Sc!N*F1p?%XG5wSX8_Xu_yWc}q-Y0dLHN&~G~@pF$F zll0cO<`|2?L|>$lu*@5z1gbzvvgFFC$tdlr^wsJWTAm#f2+eN^p{70EMKVYVJ$>Wf zaHY@W5mCubQOcj9l)H9ePl8Uiqws=$Ra@Cxb)`erxUs;)0*N{iR29~yo6DePCwK4P zp3RiXs3xw9CiUda!sd|9xis9lRtG$XlE#&ZlQfjLPPO{(K_9Xs#jck@ySQL%5f5~w z;g>x1liy!+^KAHlIdo-mJl_&U<5i77tV`+!_W`qdk2blKd^kcCD%x{Zr4eg5u{nyw zW@*P|bvA%vr=b-W_CxM5a*!n`YF_Qliy|UQgMuiSkeEESUGQnze32yopeoVt{p7E5 zZMRtVtBB}tZFN^)VgRvc3kW5=EY$dAp7onQytg4vpwi$|;L3~C!4|`3l4yZcN zAIId!m-8B(c+rUJd1T#*t-H4_@!@@rRexj3xRqts@)+gkDX}74mm?lQlgr7D>STD( z&rXagE5r6#xHKNa+3>(+`vZ8PH&e>b+C|a#&7tR5Byn9$`$$OaTzt=~aAM$2AaKAnC$-(RHjKZ52{o`kz=YOMVyxg!9_+dL{b`j-%+NBWM{-?6;l@fv zWeAXfVM!W@vEi1|oNlH?9+a*Zd;pT=q!1In6OYS{q$TcECg`8tAMvYyzO-KrCVjRt zTJIj*=CnU;?6_&a?>U)q^T^QhKR=SyjH=)9pE1_^b6bdbxY6}zUqI=b=EgC0MNiap zG*-#zZPD@?(NIb-n9>S&d`aaij1o5nMM>V;?ydXjT7>OETHq8j{lwQts*KxEuU;U^ zmUeRHS|bjcl-M8+Qlnx-VCq^AV7fhuGjJa_>0yVsueX>SYl4pJf?Kvom&riQvK6e$ z{bhn=Rq{tvk;Hl5rVT~PBC4B*P+U33kI+DQ?BCaG8s=GvsP6`G#Qu8tr`ty^Uvb-OTEa=jv%^Xd^? zvU2?I%hIhy(lN|6SDm>orP4(5@eNum-0&5vS{Aunem7Ju3W1Gcq%K2yM&$5LZ%*1M z+3ACy)nlQXX|5?i_%fjEPeVzAG($@c6q1Hn-GUiPif_E|>Wqdgo=hdXP>=rs14EYhLd&CXp^Vosvs9L4 zO;UqrwVnAEQQ518&_Le!uE-?t-u`#WFzWtc6-Tna#TdoSGIUnPcZy4ou2$TE%bOBw{-2J8fsnl}Zg%F(oY zr?*lYb)OU%?D*UFXmPe>@clULNXN4(2+D+RKz9%!Yx=)>K78G}8~)((;m^rIwY;pl z#Bcv8O_!M`h@#q+uyp>FrX=p`KM3sI4NrEs*7URf{BcLXL&8JEd#?2JgoI3Y=Y&RC z5;OG?>iv3ddMz(~;?)Ad7+Irq<5pm$ZvOaR7lj7tO_A21Syny=fV-uv&FeSEt@DFAkE3a}&`CPIC_fHIW|05fr=yB%2``=Kgx;lYCW zGg!X^9|5k}oKA_|W-l#B=f6-f=EntU7SWU??!44utFc1c;Nva1d}l#NmduG|#xo)l zCa@q7xY|%TFV6E^m78qQQJP@)Z>kaAy-sJ4VxQh6UvAap8`k8@I9c1(oBf&Q;}AZ( z=)`V(K$-@}eg}i>$ixR!qQLT++LPK2!`EXn~m4a z;#vz)vl2TNV8iE|B)oO0XD=`e!8^6;{DMc{Y!97$73o!>Ub{%|k<(=i#DcQw`gbVq z&^_o7X^q}}5DdLZc0!dv_!}&8-hHJsLP$qVUhxHx*rK3={#a$QI*-?h4 zDQ5}GFrLsfzVZ}{2b}Ua^TnJei~BpeFA`r#OTO&{o_#v(iPhx{3b6+_xvR0AL1RGa zHw8b(mw;9L>@h(7Q(GV1-8C&o2;oSm^$5yH!)_d2$AnM_K-;fY=xr&BHnu_}`TU_e zzIMg@wo6y`X0@#x>b)TfYu_yE(1!Z&N(`PPAPREwtlROJO{UV!Qd50hy#>K+6ka^N#ylJ} zb1`QOJ&aMqyUu=Yv-*qRsq?Tt*dr8K2qRN{^~XBQq5X&oPRSoR=d=8kQI&?~?>+=2 zaT>Z?HFw~~gg_2uL4u%BB{m~gdZ)t2a7YzO`9uNFL^=;_!pMOsyU}vcqv?j&{bM~!THGow=B=O@$_Q>ka3#s&-5cLrF8x$AuHN$ZyW;x#|#DncaZ z1$s1`lqf9Mhj`3zIjCikN1J5cyhGB})YRK|oMNDFeN>!OpE_%uU`7>&GP#amU()L? zv+f&6v^du3!0Mi^1(RsauXwa!62v_NatPBQ423#Z;)mb4Sj;IuXIaZCA*SrD=763c zsX_4n zJz9sO#TKhG%+`ysy?#buk2J){BJ z`jYbq2vQr`%O_9lfr1Ec0YF$XT*N(GJK*r#~)ZqiASTlox zprITy9-=~kMeT`BU!hOI$o4QMsmeR(5Xetwri-rf!SL@ZK| z`bWsSL(~khzTfr&ej}(w&OE|YcWZWoN_%$4x}N-_@3*K3`nAr7)0fgMRqL>rxh+$` z)Eh6e+J!IIYKpK5DyAN$dbLq55hs@$EvLo3nMb@%g+T*F%fHmv04m1{IARpIJ|mf( zE8}~=OGs#d74=z=;qTXSoJ>|%I#aKI*>z=Mln&3A&}Gw0NC44x-_xSzUKtup4`up( zZz1y{l$PGKOHfOwb$UkCP@Z=H8IGarh7_JBff=Qoq0(ow(Cte=uB&L6??pLmX$Ppg zODIa}^Xfk=C=gU=()Sh6HvuhNow-A0=F7Ps&d3LtEVylsBjc+RDpfCLIAMjCRPA9@ zF%RFJFyvkA;R`OyW-!v6?J;O%du)zavtqZbafZgK^dB`G0skaXcnE3L1%_bSfXUeue1WK7)<}D()90csvi%}UD!w-2jxulC~*L} zSf|2O{3HtZ>+0~PfVXo$EoqZ}84Gjt6Y9s|rLi?)@`FD9+HsIU%Rp{JYFS6j(0jeg z^8=^^veS*zB0O`X>CrZm^BdzBT?uRM(RaJNo#XgQ?v9#-O#9?TU>Yd(rMcR|Tupm4 z6Of7RCJ&PIvjX_fDVY9nQZ=QgfD`2+zSH^!#tm7KCw_oJ=S#Yxc9uLx*5>ikyFEpi z&Gg#t$Dh%2;kUXXx*?73xFbG?vR!ldNdByRgdVjW2OmyDR^@_WSaV((=3g5CvW9Cd zC`Ht3i{opDR~5V)WyQtcrbV*ezdXZy&hU}h$9oHZ2U2}Aj|gSr;4!gNdLmTu^Ti@1 zq?O+3v2-LwC-|Gy)e@8fX}NbKQ?anD{7x#8 zH$@Q_g1BDuMB26pI^#p$Lw_<@A~J&wJ&@bp-sk8r#R#e5idS33j6&IC5*aEzKPT-m z(1Ls>A^b|dI@)W@TAVsPnn#2a=Q|NSOj^a_>X+#mku&vIdVW{EFxU%)r6gLSj{NS5 z7wKx0B*I5>MR;XeLz8~YZ_XO(q3ZGwCd;{721L}P??4Y_?B87@dQWZq@cTs{2@SbN z7o5i=zFnei{;J17O*w)M^wHX4lB3_K=|l?Ji+*Ldf#m%H-t;+FUiLS}cP>i8V7fnX zM~L!|$*=pibviwZ8?agoM^np3W@;>XW-Y76s3W%=D_9Ejx+kpBXIwolsH4V0XhQPe zb|^^aSx+=y(Q`HI)p?{G{cJU83SeiT*hXGNH-dYNlL)-kO4iQ&mHj%)>uU4G@;P97#DBZb)BY> z_T3(?D3oZdgTRLUT}4hb34{i{Loa)dt0wZpPj@z5;(KkiiffZ_GU?%&wgqbc;Jyx~T46`Q5Q8>0Z} zjd~>KpSk(80)^AQ2SbH_#FUr1Zi619M)X+Q1BQxOz2}xfrikQ*8PkXxjK}wo-+*WaVd{$z;s+w@|okZ zJiA}lv2LqM-8@!pu)hI`sJ$|nMGy^t{Ksf@fQ=Z^uOIX4J(~YyYvY@v^r}OT6x2CH zCFc7J=|zytspqLC3%mTx^)P7F*=oKhcm@O!_SJaNp`!UAeiX&Nx}f-m^}`3BQv5&e z10^1poJ|V+OqmBAWFJaVyw zAj`TMCR@1=puM4QEn$dJ#to4Ll+?hcv-27xitx}>x$wXb_qxfR`bZbX=tUzK((b&0 z1)GGO_PqDzhBu)WrN%P5&dDN%N;(dCMz{;q008fo0sdw)nUwdo!CVk5VV1`a<{V+d z3>*mLJ{DYK2`Yu(%^2^m_zG1&mbGlx>FFg3QrW*R!TbIfCB&Rgq2)!c**t0nd59en z+^(cf?`K(l``brUw{(mug)D751`Fa)j~EfZ5BuUa*(%cZtpBwn-8jBQI5L*6rg=KQ*GCkxoF)+*5S5cpJ_)wt zWV-oND({PO5U^OjE^hVFC$WO0VEr;(+ZVy5mJl{`rlWl;h2*^>AzJV@%a;bAB*)^+ z%X|AvA~cy)0L)>j)Auq8DA>6_pMz;qgFDiiB9t0d?#Pob;rDurQ}^6I9vc-{2&v6HZ(kpo zkK~r2tGnslanIKm9sTwZ*$`_&==8eY)>(5|0}BC&jUV}|n@SRr?^_%2JaFeCI-OV$ zYZV{JgPMn~;zLj_x&ZqvUU2iX!9T|P#87qF$VtxE4efP?yL>MkW1OIQ`IzXpMy3Y( zKQVm0kq6vy*04{3nKA#1iBU~ok(f{;bvy+pTp*g(-ztzA@Vy-gVC8Y4P=3@Tf?>6q z(X}|JX9Nv%otR1pkSE0ugz6vV+-qp)-DeT`U3Bk)fHmDUR1T7L65%6)ygr`#9=Nq)fcH=)1U|;g6E(Mya-> z`LEx_Sba8yC7a=<6sAunjNC4-33Lb|@pxVqNk3H2=eG*YE zhqU=$xr@g*hup|6d30c9JF-OQa4UGpNfi>4k?_KdASD)^Z}Zs2Sg|UewzQ#VCA{$m zom%sF{ufi+5j$`hy_LAF@w1+7SN`@U+p@#(dey(QaXR!E?gl#)u&X5^Bx z=@zl<3qzhI^2G70Y_w2T!i<;gm04?WOodEUI@9czYMBCz%#ApJTWH*0)K;9N;b zM#L6)mp;_B7|3QRL@J=yiCM?IP8Mf6El;LGIWBpJy)mXJyBzfx4d`TuAy=v5dDG*QJTksmc8d1Y7wX}1~&jqiYm_ixU8E{ib zifFp|$LeD6%7J=|)2wR?&`=c9FupV_k%r5vsj;{d+FF2=aJ_t2o?>jS$hApX7+_?% zIh2xq`B8`m7)~+ zQitcJI5Ld(hrj&<+5pUBsc3pBIhf9HucXAt`H%cUd-BYg@JP>oKqj*jygWed*X<;VD1wj zx=`#aZi5D1Xv@#s_Byp;K(QIt`hKjSvOsx15`*O}aK8bGPB@W`E>PXRu=1Dx)*>KV z{b6hRVrfiWsD_l++u|oaS<0D7=wP6H;5e=Wg&o&UQs&7Z&|{+4+F@|@2ph3&g9a=r z_Q9b$e{v4QUq7trHtBeI@&!Dv;I;?T4f`YnCB8ATdj>f%DO z7B;oj{X0mz^4t9DAZV;LucMK_cvi0B%7J4XKQD1tMa!eC?-QnjsISx)8pc>dgLg+W zw>frj413^7e_4B!WC}Do=HOMCIR;tZ9omHs2E>V_c4YIVN|;Ty@$lG&s}r!G0vXW% zp<6U@5QS?EzgLbb{rN5wnTU4#S@(s~!^FABU>X}g#I5P}Dr;J*HbpWNKE_-!F*G@qW>7sj_<`;SyG{!K>QkA#4J#_YT$`5n z$dH+pK6BhgVnV#dp>d!4HL~q{>rs;svPtp+aEHr$GbQ(+)czqn*KG+QLpy)Ra9Nu| zhl|Y%?sx#-nVf^rU62*QeOd)tzJ`GqeQ>6G>#FIH9v`GF{MRsG&0r9Dt09x78B&05g6f1=JQ^rL0vx z3RZ8JTQ>m{U3YB$6&i>~5S^KZnnOi{M#Hg@l!igm@+j)tX42F5nmAR*U@dt1C$WFW z3KMwRe1!DPYVl{8p5%??BX_9@1vzc*NO_TR9slsnS_w)9Oz%O1?F(-C)H~-; zqlxx55E9~c?F;j}0+GIU;JLFYjo>r9doXBYhX^+gL! zsgkX~Hc_QuG6CVP7!lIJcY8BZGvlkiuWU|bI2iS0KXi%f3C`6fQJ_euetFM(qpmsx zEC4rJGHy-))AF1hUFyWwC4WF}ByuUFS2cg1>SL(gk(haRKM~6QeVI>B`1|vK84mOP zHs2a+<`P*GJs{KB?}17(O-42rJIwn&tZ;NxOBP%C7CL3#ODw%6`Ifuy6W4YAME^6G z1RH=3G&65**VXF{*iY4O754I4zdLo=HoF|uy+KvY#t6SViw>g*WwYeAL&>y9_L9C zMndWwOsR#Ck9>p>({LgWMZ2gysbG%)I$Wp9&TLSPdbKwlyNz4*JpM-29oS&YM)0z6 z2#OCZjX*N+(gjpXD*YxFAf|}PDz}G@F^?Zvd#rzhV;n+7j4k(07l?Bbv6J_E zNcgmj6;KwIJvq>?8Y$bY7rV^9p({#0j!6{pig09yb3)Re`QhlHj94A$fzT36CbjGY zDrVmc|Hfpho$qI_M_(G7Z}_mY2FtA_@m&9LZfL7qVE^2lXsQO(L(PgjL>&wHlPsDd z^2})=8>z*la~a)QCVqMgn|L0xCg#igKjsMdX!UeHly<4=rxyeD)|b?ZmLGb6oX}j_ z4S|xAr#}DMBKSlK`~Y2=#z@0QN569ViJxKcSX5+l0=pNTbPz)8~KCM!^Z%|%MECzEdC&;JbIXmRY2q+0^|(qb}ZZdFQqo; z61lIZVXaSwY@iOQ8)a5}Q})Lgq^IEk32QFZCVXu2zGHZ`^JT2@N1A+4z#=8-T+Gih z)>ZTEYp-ZC2o|+vEM}TgRCjUFhjaWSEyu*N%W5hS$v*ukJOUJ{P)7ldp5MncO3-^C z6%4MkyeeX|1BU+eF)ZTL80txJ;CKc0EFu>o5O-O-Yiap{W}j+%3*?{-N^Wj$Qh&;v z^q1~sShdPZcHxx^j2THf(VKQn*BfJLt7W>@J8p|8PpZR0n#GmK@Rj6^Yw`wcH2T=+ zLmL;roC}%sMB-o_5Vd}21NxT9;SW=e2|QEcNJtT;PIK)>K(pb!%7I6B1c~j^eN*Nf zghdZHRX;l}KYObPUz$0hmi908H8Xwg?|I|GDiBlN)M;fYT2x%@J-ez6Xl*&_-%z%F zDABzXz+B4`_9f4ZcZ;qsbT2X=8`5d6n(0_t#FFQ4_xJWb@2SdP)Ktp0^(%1mt(pW% zRWHQ!c&wO6tliP_`i-l6Xpd=Dit};V`l`j{wl}rHn;>#KKkC;L`Ks-z>~??VmfvQF zQtY+ToEl|gM^x_qeZ8PSGHQZ}D?%x1yVH&>sxqUhP$7>s!S3+HxzEu0l6r*l<&NiM zo?>=Ym2<(s7ZI=R6f0F~>U+c3LZhC~)Po5uY9YTtxu&D(!Yy~FgTf;4kx(bYN+>Ee zFD@e5=apEcpt_~z&H!>CE<4zTZT82L^V%=1ks3WU^xA#Cu&~hNYuBw&*XrKdF780B zlhWRfy-jdBG;#jW4&Wo=po@frq|jxAKYz0-_Ts`l-S=YNo|d&So-X*Apb+*3g^LJj zC-IsX0v`We(DSRKkm7^ghJE6Gh+4kVRwvf0sOG4wiHQm4sl(@rejf$TZFVgCT6}#= z8d0KPX`#c{Okh73X_V3T^vVR}=%MXM54UB-hxPZKD{@R}KYop8hZelpE#67@W*467 z1#y}_$xm}%P@&B;r(y-YFR2q1S-CfI?WL~&OvzhjZdA>?;*s5Jj1Ggw@KIGQT?cz< zhNx{j%6y17ivJ{FX!r*I$?l|*U@7n@_qUgUa1(jP2|S>S%F&ztXFg0OF00IJ?_U70^ph zK+bsPjUG&uKZ%W(mZP(MRH<;3*bzE;yipeyPeZ%zfMZmP0;Fj_-aooSfnMmbcoZ5>E+IqX{!zja*c^gy12BRb%pCZe>E!csHOEUgcIJFg6kjC%A^ zL#Du{lKMvCD}Wr)Rpy?pTuVF)@|hC6!jFY{&^y{Qt)+)t-!%~@>X5{BS~jPzHrGc7 zYiK}&PehU%y8$3;E#0V&VO5`URYWse)+@4l85NfeBuI0)W~VrdGu8PUa!1VlJdb(p+r9=7Eue#-X4t?-2}fowH}EP4vDM zCH+<}ZBE;Dt44TrBFKiW^rCpF-s9!*mpWzo+D(hwsxvdFf?itjvYD&i9T1u8X>tn`F2*>8_TiuzOY~@tpR3ACtjo z=!l}<{^+Fx-M#*Hd|-Nvk6l6V2KQ5rIEt!OOMTqM~%aFzA%9J)!wIx)5ZOa$8mI~E{-e^m1t^$XXo!&IY4}0UOp_18eGmUn=O+^ znAihWky{k8A3zioOVZ_gz@nB%_0ZQ^zR$Dl3%55~7S7MV^)BAf?iHEwL)DdlG!+-B zobR|D9^ogO`6~b3qPn=axy&y!^&Y;t1y3!DGXCEQ{B^t6R#NDzMzv$<(aq8X{j|M;>Lv9%J1Zj(x7r3W2K7gyC)525 z^e7#TNG)Q)K# z{d_SSK161UKm!0iB%Ge>&KWtmK|Fqg-x6Y=9MtF!7>?%R<_>c8aD#J0%<`m^3|#8n zY-Id{J`8V0%53)jw^e(unnb42Z`@$B*6sPDq=&sj?}GfJ?gx1B*!j8b{-N90sN^W> zJ{6vM#{F_#IWhLv0?OH&-;%I=AK{E2$)-IH!kd(sL6SM5+}QGx<{ls)T#qIbkzpq) ze~!?XR53n<5~x~6Mp~^8M>DT|m@iZqadRC%lVE?11%#Ro@%N7JIV{au_KwZOXSg*N z^MIOfT<7F!870m0jz?KB?zbCukJ06Q46D;iru2}uD%FG7Qf-HQsR-vKT&^# z!(g(NjlDwtbweQHWuwbIv(@2awFXWhm2>Qt)|;QdwTpIhbuu;Swz{WI7$?3xg0p=$ z``D>U)jLWp%{g{$g8Jg}l&>-d;$5oV&YO z1CPm!#n!{}@)+8EKH+=s@3;H%Y4kup#ABaM*K>Ox{t*G^R|-vrIl#s^2pPBUvX;Z> zq3z@LIMLDFqeJo6v1d?klcfw_nxhjhHOz7y{}E54y2DY=SHWjk65gM0&#F1qAE6ki zw{-9|+`Wu5dqhniqXpjc?P*S>N#;Ex9AKD`$fl2yIiOrZABvq)ITE`lfW`?}lrTdu zr+}QB_0y;}T1F2Di+khl-B0re+wR~Qa)>YBS3XpP<^j#Z$Sxw`XRSAli4o1DaX!A+CwH-u50=1;PCG(yL5TcYLGeyl2-@lSPuQpc+gn__9OKn zOg$=p><{QW`%bgKFLx_;sH9&H3HwQVezCA$!iM5^3ak}rU|o@0Qaq!hM|dRef_Dna z3=JUQg>Ho^jWmZLL?Iw5i`vn6qWJ>o!ie)reZTfZ{NdSOPX%cG14Mud@YViKIY%Y#Bqef{NC^2f}-s_CDMR>7E^pTwGt*HmUf7e{E~y!c4CFiEe3#f>?*>c~pZW zp7Nqz?R%198f$R~Kl+6T=Curw&#~qWjo4G#*)Y% z%jsL)_nkVK8!xJN$0jDeSdE5{zCChSa%E|3nxk414O}LG$Mdxpvc%PX&L%fQ)zL{q zb$|IYmM=;I#5C|^O%{f{qGElKV0muMZf$W+n>Xm)y6mnIzunptEr)591w}o;6*|22 z@qQD2$4?z&rKuo8${ZQ^%r`?~qSe&2;az*6V>9geYr1Q9lN=F&Yt9&s?M>em@?;2N!SThR)z7w0pygIAkJuBa7g z{i}r;qx8+z;GP^^zM@%VCTVf!hW(d4AhQq=R&1P)r_yQ6oiPEXYtI8$YtgYBa0Wul zs>#hJ@_i~lX9aXg5lTHxAd(|~{}Xn`pxgOPO1ssDNO@{B*2Dh-oG%xOQpfq6pSGI? zX8k1?>!i{5f&1FKh(-;M+#TC4n_vs!Q-9odp)|O!yE@IZClW7W`&${O0)za{MI9JB zGv2c)wC`mC3=TQAt3An7nJ?Bsx z#_9y|Pb`u1kpyeV!cT(*?J)=1CmQ|DhQ`#}^kYafdVN6kPZ?~!i4B9yqOKE2LMFZo z6~#+6AZ_s_y!Ozi#uy-+ZH(e9oLnIc;X<^?@}SBca5TmmP&;HZX**2{?mit=KX6fs zhlAz@h(D>WVH*Qg+fQES1(3=JlkT_6X?(2eEgQn6Vp(5~;hk}8RzO?HfJ6`;N zP}I5!a8Oy4db~Upf|sPzr=mU!P7fD!9|+OEQr){jo;iasbcTk*hVv;*JT8vIQqSKZTWm3L^&z zdJS0+LyYLO0;!d}#c=elwz3Y&)lYC^o}{7M*W7GJ^?XD=VU7>~=>>owUPiHPrUtbR znB|Y_TOlC^lZXkkE$Mj|*^v(k^&}qQ_`;A6KxbbwU~Z(Y1VTFs_9tt%kM8wdK~S~$0zpa zWwtP>mq~ZjoA?q-JC}K8p`3ZZgWw?<;;(Oh`!2L55cBWI9#p?NCX_$BqvAtfha=pT z2r&D*P!EG9y|)J4UWJ3-2s1KjVN#-DBlBe6X$XJowyNDcOLF}@BKNtCU&6SlQ;xpo zCVZTaoOi%{h3md0gBi1x+S=m1TcMq6S|RIta(Y;m`ueCJodp(Czh;sryLORa?dH3; zS+c}Pb#yP0?U!4^wePX#x4AMnds-dU+i~tp?dY1ZFRW$EqBt7|F(vL*Xr}vV^h+I| zbS^usGnFywz3%yK=={5fGo5RktOtV%>)>r@A_swHWR>MntxyvD+U85Py^;ir1PISg zTsw1M!X$XfWrN}RY1-{kOa#e|RCG1rmfI&|28N@ik*WA&=d^%PuC>hJRQ_te5T649 zBG|##CV4~3NulIiN3IGC?T;$7bHN401WG-i`p#%CQE?%{FOvpVoIRj;!4i%swDm24 zHwi`sr?g0{-5X!7)wVDmP2x|PbK3Upk)w8~dxgI(29b8@z&AEMYnqaeZ?4}8t1K`d zs$hHJX@{s}>}E@Ev&}y9$=HIe*4-$ymrC+9k4#azWP2r`4N7?|tiH8jjBZ0JupaZB z+88Pu39m%qUMN5`bCv*D{e$&7bpowS#Fq4|C%`3}xUAUcoh{PBjO=#`#sUKr1b+HN zU(gJ8xO#kw0OH6F6gMUsm_#oon7MMAVP}r3M*}am6wnmCO~IU$BQD@Uik{~d$f3{M zP!C7+XM35$O(X+8H@6S+>p#=RxHBsrtx;fm??xfT^XAj6PXlGf%>uryT`;{_NSXQV zenw!>Gdj<4H=4(_>%x=}F0dOL?G`ShtNeYe8=Nr}lGE?TZsxoUWn3P&UH^s4X3~q? zj8F>0Dhj7pLHM?V<~h^d?dr|hM`nphg=D9a`%Wm)a*;XqFL`r)nm$1qaTV55_Sfk7 zjZdptbZTi!(;*eVMLnD1rAjb~te%p|u@mni+du{k%Txyt%{dusJ2_jCww7dNaUIjT zL1qf}m7OYNBQ|4MCN!dm?5KvPpX7JYEDHDadp5HUYd_JINb6+3trm@PD~ll2(AaDB z5|a6;R@BK4djn&A@p5E)oW_Onx2RA|F0~-+J{BcPe1%Vyc3q(F1doVEXG>@1@aWd9xn-m27^l~KLf zLqTATdCINl=i1+fyT7|{ak5>k*`MnOxr3^!Y!cLzUugYmJK-xPUO47!bT4Xw3#b|S zs4{%iK}SOxjZi)6qOR>eZQ1wfNp5R4E`-;x#nh8n&V+2*|AQq`R_x~hA6BM2Q*$VN z)zx4hOjQ07-LLue-7=V+icMtW3!BMCV47UbC*j;qiUi9fHj}ikfKQoX{@k0bkU$Qj zVR$ukqOD4lU^z>!Mn^TNn&7oIQ)$cpYMHeLr;dNnHAXDpD-4}LsSIOaunc^z(c78B zYynGW7?mPv>xMX@Rp{lFUsy+RTK?+4?o^Rdz&rLWBUs-TQ%CY?2f~FN zfh10e;gaOfLzn!joAK@yPOu~d6+>}tWbWb#AyvLo|A1|bOaaUYy$7zFg+CwM!!>8HQ*lmh57YBZ`m+(SNA z3E&)P|DbaM%}UA7QDP3KPn6IMGuv{VOpaFxP#bdp55B%CDz0GL77Om~gy0t3Ex1eL z?i$?P5?mA9T^o0Y4g}Yr!6CR?2oNB=O>)i~_r8z!!52NcYu8>i*IaYWs>&RpmNv^q zK7kT?J37+>)yk61$jTR=j=#$;ER!5Y-y0L!#)TtoTcX|&K!qH8V>0^qNoZSO_FVu6 z7|kk*4Tmu7icP$G=dvtw%2I&*Lk~~uBh2#aEq;k8w|WjoDi}Q3{b8telRwRDUtt{VY{TvR}?;eT~q-w!f%0M zYs;gCG4i|Ii$t>wtL6KYtB8+`*ohSFlbkw0m>qa$OK(EFvl&pzMvM)um*yJfEX?MUQ7HFv^u* z_teKvzCRf@yQ8#7gdicM(Ocpytcr&;vRiYF+G0_;{q%+uDfA7c&zwi8hMiNCB7W2) zR5%jXy|Z1+R6uLWFc710BT~C@z8#2O(4AI45cL2QlQ5pd4Nt_WSci(m-5TOn&k&u{ zr;a5m2h&dYRfn8; zOx9Hwb=5z+0^244NsfS|Ac{u9?Y7ojx2e6%@^u@*RwX!j4u7n_hO=o(6QVLla}fqT&-eWcnN0M1Nom2t9u%d%cpj~VdKT=mGn(% zw6*cjFLq9D>*?m;NzC~$6i^D7N3flk&G&b)a@8-(OXKSU zWAY;WF3&$uE2Y#W1RE3-tt_`mhx&lWoo?>_REynD1CwTOuc(mDAr=}1p#%nZ9X9V% zEtEV#1;=RS8_ZZn9V50KavM@Yuh8Pd_1z9SpK*8WK8Jn-W)CPeDvxC|N`Y!dswncc zzl4buFx1XTuJ2Z?-@31_?|=6Sr-l9o(zcdTBG1c<^u&wvO+;4ux+Kb>WaN@F^pco} zUBe2Ti*jS@py)3`qwmFZj|7s~KUR0spjyI=N?!8Gr))v+lgs9cbp5r40?0{`lbEJr zjtWE+Wf-K=p}JtXUe7tLOES;WLC6&?J&5TU3yJx(lN;Yh?~*TOaHN8hhuVxxa{HE= zDce^(sI~V7-K)y7KQm(oT#>5lXpmT>Oe|R|K8KRra9r~B($YV){e78UXc>Le*|cQ% zHU-FSaBaNPqxbVA4c}at&1cTC;aM1Q(UZPrzXLXIA)mlEK?l(-q0^3Lb}wET@U(<_ zSQ=?yXqG635kUw-T0_d4yWDGED!!O<&Gd@V*k!Z!4Uf{;G@JGZmJ5fltL0D3u4E(4 z{Ba#Y@Ax!LTKYhcO2*ZXDgh3W+*;HerMG<`hj&Z345^IscqEV$O50Gi!T%5Os>!3I=v2zqBa0TZh6b#XmCh6*HxD9x z5)vf`Dd;0|DNYE{c*@miBl3$G4RU;?+WC)!1svGPdW$|BQW5(*yuqwcwdHk$|Cd^1 zyd|BFgW!GsWU&8_=cn8NFHo_U;Q~Q(0n0k|#yYE@*uVXZ#)Y2|Ow#45S> zO_j7x5=H{*0L?-rcuqfvdHa$cXBX9kVl$6%)u{-__q-6E<#BjhdD9|H{k_D@j(|GP zKhP-jZ!OjNGvtx0I9nj=j_!{4a|}h&7FD4fW8{DhmM>@rmf7 zGQ$3X%YBtv-Y_Rk`BP~Zn+$7eUu2W;lA#7r9%?u(8=W;+U)5l@71L7pdgjon)9gQG zO8wX{qK=VtfOgd9(=>7>ol1|zbe!V|6>LE&axjGh@bs;vrD=Jg*zGr{8~TXCP^tm7 zb0EqCK<&!cPhNag5`sF)&7mF(6@*+k-*a}tsC`y-Ii+%e98EG2eK-tbiF9EZ#?VaZ zGviTOkpHHXpxhPKS&5oj)HR1L$%FXjHen&4OE>0#c@%HFMLJ@HVi_WT(+X$_sC~QkUYFnbB!L( zuOz@+7so&?{VE40me%JBy-4d+9&L~pDSPFF?FfO?C+RJBL<7QFQmQYgaNfeUMhAB z7cALcG_Wm1;%Ue6E!(m~=5>PkS8Ia?niFpmf_yx0F>VkX^1JKD*He2lr2Lj10$ny- zNl63wv%#N7Q2J@0^8irZp{U_RfAudnMk1YH-SREzdCgFf&NqhWV}hyF?>*lNry+n} z7GiWdH5&;Z-uHrT*<{vLcHDhM&OJ_SCUQr(KTOz(8=djM8>4Ntlrk-^Qbv(ZDAWog zg4w7<8bPb!B!Z37%JI*mk`l2+AVKhFxZmc*)GDe1l`K&Vc7!EaRCYEwj=#)}e#Qq? z75w5X%8&plt!gb~w*6<&@!2%N#})IOO$(Ff|*PVTge-c2CuH71%D z-mb$&jGWrZ#P*p7ea!}fjcfDmW^R3$f8+barsn4=u-x^6(=IyJSwiTJmKQ^#L>VaT zf9VA-q~Fq$%OejJH62l!)HDnk0XFq-%H2(EeqpZ(iso5DYVH&hl83izI5Sp3|AVas z=g9ttckdb4BOS{FD|9wh1u4o*6*JPVP!^O&U{W7<Wfc4KqtgDW*)Zl$Dp27|~t z`-E7B{JoSs$$@%d6Iq6vx=$FqNsm6X ze)xmCM6+#Wc|?f^Mds!`Rw1fj^fRXxv5BEYob<>m0DK| zb5ETXefy%FO6vkDV`mMgb>hx&@~rA8<{)eqrdD}_yAI{;DxaK)bB;?nIP#EBlYD!2 z(eagkvJylAQB2Ty4ViTj>5i-Xss_@7XmlkLU1w?!o!1DGfaUZnIZIp|g_W;HOYE2>u_IPU$n~ zvF?r}!;OoCeXKI3|G$L=r@RG>T<4;}i}cXMjX%P#Zr*|9?V?M*Sc)V8s2qm4aq>f^ z=baQlRZxA)DZv0LgAzD9eI1DP-Gb`;*TBGoZ-a3mo#ai)#Kvz z9j)kQDJGdE*aZn2Z)VDV`t~bu@$ZyJz7Xp%Oh`gy>Bmua8Cj2Sbe^ zA47t`&b^GS%!nh;Vy+guD_tMikYDrHcP6;XQByDS$2x`QJ8RS;3`&V}tb5=CkOt3@ z&jv{2L@=!d1{4gb=be-09R2)gdK&bkw2AaE1;B1D<+2wQ@BErAL0dEGoXeROl;Rw# zpxHKa4SI6F(ueBelNl8Dg!~W9- z1mwd(Ay;{T3?ZEZ*U?cOeBOWGOqn5CPB~E~^(H;Vz~@RAbkq&y^mTi6?%wb-^3nZj zk1fjek@fJ9vUnCH9qBynW|*uje34K2)_+U2Hc@cgu$p$rDktvCzK29JT_^Sf;pL1uH)Sy{Y| zy%XF!(wZs0wd6x^6jsRoIbRVlo&&3(LU_V@2U2EU1otnK@56JQHJ)ER_DKUBqSz7K zNn{D2uI<{dmp2uorr&T)>HoP7#Pv<`afmuJT2q5QAlIH8doJtusnX^v;wBVn5TV

    qoZwE4?-ko%%^W0q4d5WvxCRM6a1iY`p8LaBmDAxceR*^H z`!A|erGKg4Zkzzt79ETjwp4^lURpGU0U<+bmftY($^~u%I+PU zt_?wNWiBz_VTmTx!U(@@)O!&TnlJI>#*w%{n>zlUG%lZidWBkoh%|O zZ^vZ%_GIEDRYwQDtO!L=$Cgffg+YO}w#sLvLv-tK{Hbk|&3>s_pS8cMxO6SQB@s~g z#6VaeED@FL?f3FK^Iukb4*})gOS+wyvMQSO%Be_IW6N~YYO@le{VM+T<=}6_O)L=k zEApFV?r(3%O2RrBz<9Ej&?yR}*)(mm0`(eypS~ zspcNt^OIr9Jfa=Uw2n2nI)(v`Eky`4gY_JQfQ1Je4=HDRixE`* zlzP^G$j*0pTyT`xM*=S|{0>>{dfhh|^nJJh_1k@bQYp|I6-IXWoIn0o=8m=HwW+q) zBHR$W>p=W+|K+qcnEK7O)XwCW;nZy_7!Rl|cwtwG;P;^T4?70p!q>%dtc!|iZy$C} z2}={Yt}wfXE}caOs_whkXrs zFY3+6L#AT!=ogsV&Ph|C2y*A54=eBi32THgg@Az;)pXj!x_=|f_r$mRIbP&Yf9n~c zzzXO|92)fQtV(If?KMBLZ|=Kq@mrgAqAiAUZxe(!X&Mp)j>^ez%@vKS^;_eC=`Qo2 z$lZSx9TUUA!lHB>IR1-8w;@!Ad12e)zQQEvqpQr|vyvK~?&Q9I9)W=jAV!)C9GzM; zKY4;a;{SH;WSq$2anbC!wf=pOKa#hSI;3~WXN)U0BC!1`HlZ&KQi^ z99k(`&EP>nPO2fNqeT9 zm6I(f{p~sQIdp>8&2>9khh1)6kOAL2lOU6z(2sDQwE#ZO%P1V1>~a77LJkDzEc};p z_9O81>|`a)Y#N`YSn<}0Yji#ar7HA9`H*;z|6SyR=~YyuP+dC$;lOjv>MkQo0Af{o zU;CTvfPko`Vmr~7?_(dd5V917BN1}~D#Yz#hj>ckySEqa6LaH+9CLsFpDspuf}lmn z0m!>PGirpHv&DkQF*t=GMit)~+XzKyj8$&=>a*LYfPpESsD z1Y6GX^17F_Xi3XLMB*n`h!0LVw!D6*@nm;aB##XVt_^i`-Xg9D68QRMO+K8Q`ZRa1 z*q>kS-yIJHf~&m9`hXD}GP6`$7@@d91y#Dr2()Zay!mic#tn{tJ}=+C72L3X4fvem zLr%QtNlt(t{^Pe?O4j;kWDal+o}FLa3rr7v%gE^sNORb)ITR%b`snMn@n^kM^jxOH zSE&2R=;78)6HrN^{B)QyfKIAnaw?WYuIk&1p%r-xH-VPCijz2>Uv{G5r?2vRR);Kj z1eIy^m)f%gIqr45(yCd5SlyPC1=;W~V0g@if#89c_c66mE;_3n)%J%Eax6GouIqSz zedwT|s&accMN;72wdJ-Z|4Dwy8P#uQzNdp^W@F`ass3~$K<)DJq=uzvd#YosvAfpq z{o%o>1Hu(w$FjD{DNTUozT@JGv(K65dQi~h)ER2Zb`IK*0ExRM^O3?gyYg%mvSyzX z6wC|zub+UY7*D#=Y7j~=(`>O{8qd^l>g;V<{F4NJaQAqQH!hPHip_YG+kV&17hW+v zd%0x9BiK^Wt)hK;w-C;Gv_ob!C0K(ame~_VDNrS?^g@ z>rhu&UwF4xKx$>L*cw^Uj%sO)UPr?K@XCDP@5GUxM#k}`UahCLB!;I>uXUBqOSbPbqEXj!Bvw|G zjejlGh$a;AUKjsN$>|K>{J!rPWHjd6DBKtT%fBG(;O6IhZDgJgyv+`$pvl?-Uy-P~ zT1JxLX{mpDOma)2re;Nib0XrHdiz>I{kzvdx0gpVlsk+p2#Vi#gU$o> zT<9>iX2pfiU05e^cq&`KFHTL>NF)C&?yTw#Abs+w3Yf5gmk~&4XFpZ@25&8*V4|{# z2C!@3Rn-)`e^t$O<-?q^+gj3aGlWdb{IJl1KYNTx@upypK>H<65Swa-yS?A_LJB7UfH4)={Sizb`xTERt`mm*_V7NpY znSN6B$?61|XO)|}s}zTxef+-b5GT4X zsvB%DeN)N%tp7kRCx+)Mo{oR%k}icR90n?Pv&{Lw|7F4R{DLe2e3V0H6h-3ASM@ff z7oa9IZ%F-p^5!2De^KMVcPE9YT!t?2Zuq+~@>-MDnWy_kzi!L<`g1qUxW(K~?da(i z!8*EQZ_mmo=;=mmDeZ8b#0hm$sOvB=XEb!tJZVXiu;~5Y2hL!!l*;~1)KLAVl;S}| zu++>ici-V6;JIdRZ%@PiEsaG2>-o<4Wy;#_NXP!SyHDN(2R`fJ?v8@9@ut1I3B$7z zD*Up>zRn+8@0&4ltUd=H{IrYl7}L+%iK8=0xxwh29LmxY++dy<`nBb?5s(J_@fvm# z8c=yMUi7N{qKRs48R>YX(it!D=OUOqXp0>nT5b)OVM;aIs6f)Jjxh$Fpgu#5aE3K6 z5EJ`ir`GEUpt1y#)Pm3OXe24M4@%z^ZiUP!t|IWfnZTK9y-9%rCO>kChi`WVN*Cc9 zh!~dLydS?`$6x1mZM*!r@n2wOPMquwfMt^o>+L}QOI&2s+UuP)jJ4ZJd8m68c0DWvufYYu8;iBd0cCYO^0iW9PdE>5Cx=eR3CEduGYnffvyBT$G;^ZU6i{%87J zy6Y|(tXUd0v;IL;8=yOeI;qg-Dx}ez8n+keTYOg}%;glb*P;%z*c@WqA|N0L z&F9y=-~ICbAj#a=g3iDUsf>ShXaH4w+kf8*DNRHcD5`%ew}!&eybtMS9~IV2Dn_$W z<(u$G1!|s>7M(YrKP7)fSt8ptNcNJvGYlkg3M29G-~$t+u`YHSSWj5&f^tYVhPRP> zHMZ~_wiGf{abeoH=_$}}Gth+)nezx{F9AJs?xn5q#-RE_mX#I)`-Dy%}M23zWLi86QKJWyW4gY4z;>Rk73B-xV&S_M(^SiIs%5qaN)?RDcoj(o7o`HLxCsb4xw`0=-K>Z;7lhvi;+4U%|kTp>p=a zx1#$bMs<*K9PSw7V#YWmMdrpeWDM>t_(dJR20HM7(p>(A7HJ$_`IV<^PwIlge|6;V zNzNJ+nBG0K)C9%vv)s&mtM=VGkp*9mSD?w8gIjV?fHoJXpo@pTwf&_7H|S1Nf+I!M z^`XI7zBL2-2T42Tca>`qA^}HNRU?vmZxQ`&s1k_(qK`l&(BXnr2&Qq%bk{K;nY=wn~b#a+cKnwNf(w5uQ&9bNe#LtSGpP;nYV0+A1$ewn2b}iFiVM^Uu|; zukWdb?wLT^A)RJL+EO2_^178+IUp{ygBMtx+4@|Yjs;N!F` z8$`6+qzV_%!%UU|+%;4YNI~y(wa90WTkU@&0sz61@<0^*_Wg8ULOxU;%Rh))lRJ$p zNH+>`^`)jZR^IhAeBp@jdfw2HlHylXK(|(Zt9(7;69v*J*P^a(<@T!tdd`rw5NoN5 z1SSs@`5j%ri6E~zYCewLMobU)$IqUUmwE-Z@nw|J(dE#S(&c@tEv2Fpi$}JnS}cF`hNL^~cY3utA~ukNd9bi{|A|7L(Mw0J16~Q~(LH3+5zm#z7#pHSW1Asy+Qh!EGxW z4S?Z&DbW8q3w(Tw0>i(C%tMYE1fKrTCmfsEA>O8)A9?}uE}-y0Q?Zx6Mh z^WnEm+}?iyM9dYBnjSDv2y2Y>vx~f|sEn+@!*7s%c|Nl|++S96I;K+EJOUNtD844^T~6;Yy(E13kF_;#`Sc(9$HU2`;ktKkB(B zZ)+->OrS}q3p5u1)iR?V{{m{&GhVeU{+P(k@7k3L8aIESKuUWZa16eEhO=%ElS8MaqS`Mk-+z(7ip*oH*bUTgmScYIoxHwPp)C!qXuXZ zyqHdqH)_#F&H>9!o+f~KGI%bv5En2mpgsexlid#&9BTf?y~&#qX&}uZ?2lYH&&q9VwV;nZnDhA2?^W=a&|lc2Y(z+cwTc_=d8*qYD&(6{wFj58|e5@AIHd zVq+?$LP>eR9fVf5i`fMMt=EQjcCupz>%U$NFDznQ@GrwL*d?}QcFh+(6)LRokb->< z1jwCm%5utzPZ4+0%3%9xw+0WGa}Biw5Piq_w*SFPvzTx;XO18|bSSCP&!Re7T3Eug zkP*jqYgTHOmz(D5Js9pB6~6jBGays&jpm<0cz{=02G^nQg>1OR&kSqN_-y zRPwi&jQjvw_rI<`*cw-$OKiH%Q-iOwTh(-KejMdL#)RQ@rOvts|R zstVcM{X&lpA~?Z*>fKN7F-|+;CZZEmI|4ByCgisT2A9j1qzFPg0`VyG>K4MzWX@}= z@N1ev(Q*cL^QyxWyC6fPx&2o<2EtN2C1!bmsxbqxaf^ok7W@V!s0#qnnP9t>31YP(?D4x_Z(aLbRbXpvSh;~LyM`{T&HLvZ*^&% zf#2fMQJHgS+CldVzxv@QjoPd*dG2}HCGBt#7RJKz*xUu0njC3w!LGL8X?>}-V^goN zB%lCOD0EeH=nlf+_rQ+74Re+*D9I|CetQ)@@Kj7)8!dfW$7G_MRqdSN)pELYp)41k zY6t>e>K=;MPitz^zwWPII4h(o+`F2%!8Xi(wD*X^vUN30xiv*qv51=pjX8jdBGb-^JeUD?OkN&6vWNf%@A{g=(l4TG*L3wr>Sc#car||BDZmkT zv1i+jNtX>}ORtGSRbsZlo4B?-c8}o_aNBIjK$m)YD-nh?;1{glwg-qsb)5>Bx7a>+ zQj3_|$?s?aB#+6sMkZ#;0Wt{=1t2eQF=K{>bY2Qsa6Y_v?w>|4XiLQ2V85s593U8v7D;3dIGE!bU)GYWwfD7c#$$_EyCsa9fQ{ZYb4W?8Vw!;%xZ=} z+(oNx>|IK}yN3og6eT1M(Qqg2vXpH#Dk{}KI!S3L;HD1nx}Im#KKZ&%VkEuUjr;v- z${cT0f8{EjSS~i1a|QIzMns;_kdWL6@>Ir;3?fc&+XwtHrN^;LyXADRflLzQv7g}io+gQrT|J~i>9VnATRR1N8RcMj69!f0*dAT zlNYgG*xhyd30C}}61|L!xNFlf^U~3ad1`taE|kL`u*MpMB?#xO2q)N8zF4G)8a1zG z?+Gss_9n7Hq7oceX6!5D4%4hYOU{RXt{-%3+fBN zt7TV2)b{mE94r`P3=!CMrQ0zGfwm#6fy{^&OXn5}DdVUj);erp2%B-3t;=pZz(Ff) z=D^YE%U^Q>Gz2vlwm6CSI?5w$?#;+{1=L%zNal-#5=3EH4|t*ht8#aAdOTCYp$AF) zwk8%iu4Mx~FEj!$7dF(?+WH{+W}uU26F@{HDqhD!?S%kC3T=<8LlS>9P+ocptDudG zOnIFU0f5nJYD?dzyH&JUa_-Ee+2#a|a+^8M;3)7TB-M*20FSVraWlZ*{wz31gR{pdysgT%d^&n+KC(BaIYr z52yha-k2IUblp)ztQM=WhYX;VA9!s=3#|#M?E@9Mr5=*Uo0sU3M^9W^0V}wuD1!hr7g11N18DA2(EIaZC)NXl90Gdt zTn25Rutv?cz%kml6?v2^2K&U3Ky+g2XyGL0{dI>9y3?^#CN|Fsoh9ZUz%V~ZJg*{z~nTxA{`WH6J? z+d>Q>!VkDt6W}7Z)&rgYT8I^KD&ZZ0JJa%KqQx@AQnnCvJNp(LXc~z4T7|%4Qtbuh zkx196hfCLGBO8X+B*Ff6G=T7zbU4F%&!sA;Yb5T2XsIP|J4+E#{TTXnyLZq7KWWV| zo0{Ua(Ca>1AZ7}I@KyBY$3S9+N_`M9jtt%D(1<(Aph&b%yiO&p_VGst_Q$S6V???mCrYqd~`6?_xDwAjVlm<@TmZHIKZ!>tO|ItG`hM_>j4QJ z2Uwqgp9FB*sBBszvQlPqw0sf<(7p@U)Z!pjF#fvFd3e0!=%J7YFkAAWelPVA`b@f& zQ+Wg_~sPYX0A~~2W~t8?q2IHp2&YV%ib5}uv+M>5E>q2)@z{I z-HJQ}0Oh(zszy1mD^9!BH3M0c22@-f8@gk-*#7$s>3mvn78Pat@_+N00}ZSVQ~ulO zK96;+Nw_zM>&8xSoAR6U6Im5NU5ASHs_%!^F2?<+2DX!to0jg{v(x$d_BQzVF`-w) z+O^=F`dcYRg#vFetmdOa*Kc{p@)>e=)dp&kO)VK*D0h{Q)0S&bJ}7VM-iQ)>O=+3^xJjlv#vz~>>~7H^}$s;Qn{CPy;x~&!hD?W zv&i&1iR;7kMVPIn$4stn&%iV7HwFAQy0u*t4!H-*RTs?^om%>~mqh1$QsVIK zvoo!&*AUqXoJMDOB5<)x7}FTAqd@n$^a~RwgP$M&D2al=u@mgs5Fb-g)5>PK#jpw8zoRxqH2c@8 z`SPSHTpNnmnS4Uu)C_6N&+hJE1eq_evfXKKDr6)-nXg_Z&rJLEhOV|d!(*c7p*#(? z&Of*u$yo<<_ZK)Y=#zRegY4E18WAc-pkjjUup95kH4eH{Cx25+w1b=1dw{_Jd*s8C z>DcEE&)K%gUDvWG=w&j(iW>uYRa4|#m)(hpUzhMU5s#PQH2N%Q*i=bZw2v7J9z3Fa z`q~x;{g&*gUj5sQuITty_sJi#Y)Csr(Hgj|`NrK(;EZr=tKTqCwc4$--#9}0NlEU( zWtDxPpnjH>d;5L%l*Q30ip!8XG8&1$^cu7BkS)|CJT`DR`RUIqCkKU-`*exqH(Z{+ zov*xUZ56iTOEicZd&W26H$|~2_iGJpdJ_ao>x&zECSs?WXivl2%z>Ne7>b#rD1%F@ zo^kIiv%48G1)i9B9o_buT6{ZMYxpdlxwyRMi}=c{k4_(eUq&Zzypr&%v}NCa^U*kT za=_un(`nU3Y4D0AQ1*uuz6mq@B%Bp0U6fFM_bKW_ZJRlBi6)s*C#MPQMGZv9+k7Sv z*Gq9XdGa^i2pVS(byCCek9a!yvDQ22C=q;AnvcKASE2$PbvwVe43HH`QmyTJVP2If zcC#c1rmE?E+p0x@=|LjhACz*C>!dkLN0zgG;@`x{NNye^ivcbZqqI~&<+cha`EoNq z$X=QBOOavh{n8K3BJBj*!0Aea)=Q>Mx{Tx;J{th33>mp5V3GZYoC95dw#f8d8**RcJ{rH4Xi!z5c1Latp9sDVte(>xvI*- z^rPwqOd_8`sltaw_TxNW;7A7WLh_T{>ZN3X=|?)Ng-geemJsaC%>n_TYTte(-ovVA z$mU`-Lnqsrj=aM?zUb?N?U+5lmIu-wlS*kTew$*W+_mB~86?f43d)#{2ER>7)1S?k1K zH*FG((h4yMDqT71NH&oB;4fprc`&?mCjHCFPwZ!eGy=f#kL=eUU$U(0FTiMn+HMV9 zJzxvI^oQ!!xXgOuCTeS#O)98I|GqnU@A3;##p|~e;n2xtzFS3qFRWkH;{mjB8-uM% zD!ULcAs>JVfw39?%?*#{=I4EbuKjmvUf1vt6MmxEE_66uk>Fx z_Nve_UfRAaXz*P*5ewlHpXNJJRoK-mxg|k!^m=-x4u8i@18D#6CXHX7JJ>CIqXlbR zffmW=$8})eW?LXk>Je3(S}ci-)QE1N4WH2s!n+{ZWZ;eGp`+%#-2K&(JP}_Qo8t95tM5|; zl(RTS9mHpFEBK4vo>D7bL~+xM*Ihj|aC{)TGb7vT@JbOV-p#snJ<$@K6?=l@2~rmw zA%RG8{xgYrC(uNf)^dY1unYMA(UHw7kw}*_4TAz#%LNtpvM+I#5Eo$G zGw)>azHQj}N|u+r-Y^m9eFHW1NkM2QO@Z*KgWHxanYAH(N2E~%-r#hy8y1#XzxVr} zPfm+_2;Ch)Bu;G%mZC8np#>>ULy8czo0E<7N_6@A?jpD6Z$W2PJ8Thbt6aG&_Uz*|oyG5mW0Z>$mJ5mt?QW&~ z*H#Oldbbwc;oWz^Zf@#jd9T{}dylN@(RGfXW6IRjY=9ZFKl+*Kz7Ryx#~P6+PQv`< zn1eyEzS)j|W)lhu2Te{=Ok-Uy88=g8A;ZW)|p&`jNa#)Ryb#}_RvM%s%VAV#d`*MQ%R@z>)`DW zy4ALvPru9q#}j@K{!oo|Uton5f%Qk-zS*mCM%AwQVL%8GoT z!a1i#ich9?W0@R*Y&tlu``E}&0qdyz)9uUhKnu?6wZrqv;LdTEY$xj@2is)JGQp== z!n_jatbDf0akU8io0=`g$bwH?>VT6O!quZ@GNgC(B7yqI;M_CG}&X)|4!{B$*sn*WB)O zhPF&+#e&^2!Cu?IZc)#v^LiX>u?o6!2LQ=N(ChtdBf+!5F2wCyiyM^1-7Etb9&3rF zV}b!jecnxwy+AidyXsbqRPJ)*ne>}Rv;`Oy!E9|o2u^^ekYbHtCgcmO2=1=y?V;eK zPVJ9xFsIWZ*|h*0nJFIy?(&Wjmy1ZW#9!LxJBRBSS!*7hI%o`*4flRE_!vMP1~0sW zus+uQ-ar9Yk6>9nH>;95sGD=uR6C=8w6Z21xOE8`6Z3@JZ2B=@yR0$LePOYz)8C~ZzBc2ae%3J1N4>1K z9?tZ9AU_pq4W+H>UX0bK#7)p9Ct(5~bGo1CPz%lJ4}b<~FR~EX8g>hZtJ~a}aJLr^H_fLu zIMHEu5q-CE4l>5O{gh?&ns-MK;<8W-ghLS{XX7wAM)rgA)eUO3SpP6^R3A)=<$BCd zvOs3&=c%|N=Agypz>kV{qi>l@vtwHBzI1p0RK0sfM(e>EFSP})mZVis<=n9TcziPI z4$l^8y`#&tKe|$BcjKp;N?2W+Ni7&jGCm!AZ?rS}Li)bL5 zHaC7ZG$FUbzIXjXtc+SxkbE zU+*GR*MR~8oYF!=4e`PN;}ia7>&HpE$5vfF5+?zIg4i_EX=Q%TVg0f>2yMJ z36+5xf80pl!m-&jFR#fJ?sfVvT(~jke+j3XH=kir74GA1(97 zj|fz{kHKdU9kk6)0Eo^xbCd^E+~DEGC@S!ldQWd<2$Q>inAV|Cm&LQxj97$k-_nm_ z_e2S1B54#6jplIDwGrmqAX{4JF8}rJ@0#IA2|(K2)qngX$!ZA6TDnHp{yy6uYeqZ> z{I)qm-9Jn~`qV4CBbb49N$ zakD`x7g<|Gli7uqBK{&RG(I#Myftvmg35ur9>kIlA;EVvnB)n6CcUCnzbMia7~~lu z-{NMYV;2lvlfTD^bM{#-`QAXvrq0rCS@N&K$U3k`c7zi;AXy>*&`qb*Jxj zRxf;h1n=QNsy<#n;f<54fJ}r+*o8@W4pNgHt!Q2s2o5rByUjH9zK=-E+1TOTV%h`gcY?GfG@?^!KZIep9~r^Z$=BrQ3f-jWQ1H+19gASc<4fr zVehmr@VP*M*f`aF&5nS&0Cl^%c2C7;bI0rsr1I;2bf&rYL%G>Th1o#KZf!0(*)dBJ zXF9*w_Vc@En8dy^R)7WGIop`&ZVaW2m71rg{wNPU12xF)?o1)6T2OPZDvG~2y6zD@ z&wQ{#qCG=Q`i7BWqyX7_elnP;h~CeU#gH(FT);C=a6?t?Whyk6{D7&L-)a_&^NbBU z`7@)JC#UP#Fr;W5Am~ik-r2YI<#pLc+c0wV0;L+q1ct9iTigTby6l<4_A8)XOl^D& zaj@svP8Qa(VzkFZT;;Ex8}nAUoY6JL@DCQhKG;Fs6tagtcT&;hVK$&37%6G%*1M3+QtvvQesazNFuzWFVQXf zz|5O}vMUIqC8@jK7HVMIxi5~)-m>lA;u%~7ps@?CTtPTmuFcU;d`?FMbW$dUWRxhl z!H8%UZ42WXW1H?hcc{%OkeZDOFH4hXbBTQbt)(>up=&w<^@MKR_0II$r_?Mb47b%B z{Zyw*iD;I^*sKUG#sD=r;A-3oi~1Wv;)S{|I3A6|oBm%nmlu+i-fKpdDnFC(w(z;% zkXWDFRak#^mG!!RaOp80oLMMd(@NzKe9Eg!>*(usmzmqrjm^Wlf*O=Cg-Bcnem&RM zV`lc}s^B_Q4#F7RLlUBa8_%iLBKtxoU(aZ+9zk(BI6z1MgYfy7o2%BKJ6y~CuJc21 z5XJ9nP(&pRi%GOZ6a zWlEDUVo5EphAsr*X;P}sl&EFYkP&HUw1iGOqiM&M6qRN~O)%CNK~yZMB0-}v zMeOv^RxD$SXd^E%Kl9%I@4fTSJ)h70=iYPgJ)e8dx%d0M@gpept2vmHdsku^zp#*q zomZh=gxoz*pWJd^GmjB0jH?T7$&rFy|En1t`J45`YY?L@Wojol@6F!1lD#PDBPovT z*KFGLJn>iR{ZN7U z(X+epdoh^~mek*09$nVDGwP9V=8;`)t-x1>C z;*f*(-u1wV&a&4`{NhEyZh)!Tc0}dU1YpWcXL#Ha%*eV7m|cbx`M~r|GDPiW-w$!iPuSqR!?0r)qHMm zwqpO56m6xvWi|6yS`|`P+AhiyK)md41wihIJ@%&3If&A}C0edcu$zJWCTxJ4uqUbL z!z%rRQayOlXO#SKFY(%bl7Qns`&9$_EDDF&T(H;IX#bYvj(`0#{Ic$cbG!%v^?JcX z93(NMQ!m4pL~`^vRKJ%e4a)yg>q2>THDWFs`G{%#pdNH)APv>1u)6;U^%gCcr0|2@5=Mh3UbtFMAb&5hyd%+8bb?Oa&=mQp#|Mt1r8!9%yPWzV_M`ZaT%>>ji~C=i7bu-^J{ zfS)c;PGnkDH;2mPK^&wG93{VP!fS3G0sci*6=fgW`&e}>eB`j6l^IRLNjzlC1<|LRa* z?LLNMO>sYCY3&u+hd%b9kI^{nTf#VC-#b{xAFNcp-_BMIsQuhOKG-hOPs2R%Z_L_( zR@J+TB}}#4cHJC_v}mOub{ZG1))HIDO7)ZwPYvRDhAa4GDZq0{p>)Sw<3FODvl#FL zfu_wkm5XR8Nm?4WzDmhjY2&Lj|?Vu5(Iq)vOQBP#j?7V7_J;GhtBiN@2_( zOxgzg8kl8qd{!ZXgl!9*y)0uVsN-_DU9L3-0$!{`OmC7Q*D>P)=LeRtD62%O|Lq-P~kl zX1a&`o0+_t%nUc!fdaF`h-K+Cj1vvLO!1MR7T>mQK3pFwBKqC@CFS~0@J;mw5183y z>qS4#nIjzR@f+wcZ~`@#n#Nz!No|MtuE(|{5HQO3|3GCtS*Xn!!!3@iHfbpMBPcWp zb|>bcKC$Z7*F{@yzvGa#wM)eDw#@?e@U!yusYetF%9Lh|G_%WQnGARNl=6C}N_MN^H5F^PI2@d?^$nve&CrnC~_aF__wvq zAH;oHR*nA2Os^rC*CQ6OfkN?toz=AfRhqhO#jv~M1EsEFh3P=g>Zzi9&}U{J2NY(x zxOg(SvQ2lzoe3ujn!lby&gaau8UXe*r^*eVmetZc(dIdVqu6H$x#=Z-Do_~SlBN$q zXtu9%u?xI~+JL7IFO)gIk;!lMveF~DIuvR3 zU`^6=Y+*Xly$&V=7nt~4qseJ2i)-X)n|d;I7#4PaQ~!NZ<>?9_AIRab&;NxH3VY@b z=h + + + + + + +MakeBlock Drive Updated: src/MeLEDMatrix.h Source File + + + + + + + + + + + + + +

    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeLEDMatrix.h
    +
    +
    +Go to the documentation of this file.
    1
    +
    49#ifndef _ME_LED_MATRIX_H_
    +
    50#define _ME_LED_MATRIX_H_
    +
    51
    +
    52#include "MePort.h"
    +
    53#define PointOn 1
    +
    54#define PointOff 0
    +
    55
    +
    56
    +
    57#define LED_BUFFER_SIZE 16
    +
    58#define STRING_DISPLAY_BUFFER_SIZE 20
    +
    59
    +
    60
    +
    61//Define Data Command Parameters
    +
    62#define Mode_Address_Auto_Add_1 0x40 //0100 0000 B
    +
    63#define Mode_Permanent_Address 0x44 //0100 0100 B
    +
    64
    +
    65
    +
    66//Define Address Command Parameters
    +
    67#define ADDRESS(addr) (0xC0 | addr)
    +
    68
    +
    69
    +
    70typedef enum
    +
    71{
    +
    72 Brightness_0 = 0,
    +
    73 Brightness_1,
    +
    74 Brightness_2,
    +
    75 Brightness_3,
    +
    76 Brightness_4,
    +
    77 Brightness_5,
    +
    78 Brightness_6,
    +
    79 Brightness_7,
    +
    80 Brightness_8
    +
    81}LED_Matrix_Brightness_TypeDef;
    +
    82
    +
    83
    +
    84
    +
    85/* Me LED Matrix 8X16 */
    +
    +
    91class MeLEDMatrix:public MePort
    +
    92{
    +
    93public:
    +
    100 MeLEDMatrix();
    +
    101
    +
    108 MeLEDMatrix(uint8_t port);
    +
    109
    +
    118 MeLEDMatrix(uint8_t SCK_Pin, uint8_t DIN_Pin);
    +
    119
    +
    134 void clearScreen();
    +
    135
    +
    150 void setBrightness(uint8_t Bright);
    +
    151
    +
    166 void setColorIndex(bool Color_Number);
    +
    167
    +
    188 void drawBitmap(int8_t x, int8_t y, uint8_t Bitmap_Width, uint8_t *Bitmap);
    +
    189
    +
    208 void drawStr(int16_t X_position, int8_t Y_position, const char *str);
    +
    209
    +
    228 void showClock(uint8_t hour, uint8_t minute, bool = PointOn);
    +
    229
    +
    246 void showNum(float value,uint8_t = 3);
    +
    247
    +
    262 void reset(uint8_t port);
    +
    263
    +
    264private:
    +
    265 uint8_t u8_SCKPin;
    +
    266 uint8_t u8_DINPin;
    +
    267
    +
    268 bool b_Color_Index;
    +
    269 bool b_Draw_Str_Flag;
    +
    270
    +
    271 uint8_t u8_Display_Buffer[LED_BUFFER_SIZE];
    +
    272
    +
    273 int16_t i16_Str_Display_X_Position;
    +
    274 int8_t i8_Str_Display_Y_Position;
    +
    275 int16_t i16_Number_of_Character_of_Str;
    +
    276 char i8_Str_Display_Buffer[STRING_DISPLAY_BUFFER_SIZE];
    +
    277
    +
    292 void writeByte(uint8_t data);
    +
    293
    +
    312 void writeBytesToAddress(uint8_t Address, const uint8_t *P_data, uint8_t count_of_data);
    +
    313
    +
    326 void showStr();
    +
    327
    +
    328};
    +
    +
    329
    +
    330#endif
    +
    Header for MePort.cpp module.
    +
    Driver for Me LED Matrix module.
    Definition MeLEDMatrix.h:92
    +
    void drawStr(int16_t X_position, int8_t Y_position, const char *str)
    Definition MeLEDMatrix.cpp:377
    +
    void reset(uint8_t port)
    Definition MeLEDMatrix.cpp:120
    +
    void drawBitmap(int8_t x, int8_t y, uint8_t Bitmap_Width, uint8_t *Bitmap)
    Definition MeLEDMatrix.cpp:330
    +
    void setColorIndex(bool Color_Number)
    Definition MeLEDMatrix.cpp:305
    +
    MeLEDMatrix()
    Definition MeLEDMatrix.cpp:57
    +
    void showNum(float value, uint8_t=3)
    Definition MeLEDMatrix.cpp:650
    +
    void showClock(uint8_t hour, uint8_t minute, bool=PointOn)
    Definition MeLEDMatrix.cpp:589
    +
    void setBrightness(uint8_t Bright)
    Definition MeLEDMatrix.cpp:275
    +
    void clearScreen()
    Definition MeLEDMatrix.cpp:248
    +
    Port Mapping for RJ25.
    Definition MePort.h:128
    +
    +
    + + + + diff --git a/doc/html/_me_l_e_d_matrix_data_8h.html b/doc/html/_me_l_e_d_matrix_data_8h.html new file mode 100644 index 00000000..bfb9c26e --- /dev/null +++ b/doc/html/_me_l_e_d_matrix_data_8h.html @@ -0,0 +1,162 @@ + + + + + + + +MakeBlock Drive Updated: src/MeLEDMatrixData.h File Reference + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    + +
    MeLEDMatrixData.h File Reference
    +
    +
    + +

    Symbol data for Me LED Matrix module. +More...

    +
    +This graph shows which files directly or indirectly include this file:
    +
    +
    + + + + + +
    +
    +

    Go to the source code of this file.

    + + + + + + +

    +Classes

    struct  LED_Matrix_Font_6x8_TypeDef
     
    struct  LED_Matrix_Clock_Number_Font_3x8_TypeDef
     
    + + + +

    +Variables

    +const LED_Matrix_Font_6x8_TypeDef Character_font_6x8[] PROGMEM
     
    +

    Detailed Description

    +

    Symbol data for Me LED Matrix module.

    +
    Copyright (C), 2012-2016, MakeBlock
    +
    Author
    MakeBlock
    +
    Version
    V1.0.3
    +
    Date
    2016/01/29
    +

    Supporting Header for MeLEDMatrix.cpp module

    +
    Copyright
    This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    This file is symbol data for Me LED Matrix.
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    +forfish         2015/11/09     1.0.0            Add description
    +Mark Yan        2016/01/19     1.0.1            Add some new symbol
    +Mark Yan        2016/01/27     1.0.2            Add digital printing
    +Mark Yan        2016/01/29     1.0.3            Fix issue when show integer number
    +
    +
    +
    + + + + diff --git a/doc/html/_me_l_e_d_matrix_data_8h.js b/doc/html/_me_l_e_d_matrix_data_8h.js new file mode 100644 index 00000000..fdf00f5b --- /dev/null +++ b/doc/html/_me_l_e_d_matrix_data_8h.js @@ -0,0 +1,5 @@ +var _me_l_e_d_matrix_data_8h = +[ + [ "LED_Matrix_Font_6x8_TypeDef", "struct_l_e_d___matrix___font__6x8___type_def.html", null ], + [ "LED_Matrix_Clock_Number_Font_3x8_TypeDef", "struct_l_e_d___matrix___clock___number___font__3x8___type_def.html", null ] +]; \ No newline at end of file diff --git a/doc/html/_me_l_e_d_matrix_data_8h__dep__incl.map b/doc/html/_me_l_e_d_matrix_data_8h__dep__incl.map new file mode 100644 index 00000000..f054a4b6 --- /dev/null +++ b/doc/html/_me_l_e_d_matrix_data_8h__dep__incl.map @@ -0,0 +1,5 @@ + + + + + diff --git a/doc/html/_me_l_e_d_matrix_data_8h__dep__incl.md5 b/doc/html/_me_l_e_d_matrix_data_8h__dep__incl.md5 new file mode 100644 index 00000000..b856735a --- /dev/null +++ b/doc/html/_me_l_e_d_matrix_data_8h__dep__incl.md5 @@ -0,0 +1 @@ +f6ed35d58adca90dba4e7324e21a7d0b \ No newline at end of file diff --git a/doc/html/_me_l_e_d_matrix_data_8h__dep__incl.png b/doc/html/_me_l_e_d_matrix_data_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..b0ac0d2da6f13eeaa2da17202e27e553b09430d7 GIT binary patch literal 1640 zcmb`Idpr{g6vwUIt6HWM#dfJrpR2OOm5^6dbBiU9wIRzZuQv0jyfSU<$|{SNUP4l+ zyO&`jn_075M3gM=$5oriCQBYmuI?YV+x`3g&gY!(=bV3kpL5Pd&!dOHAP7i9Lj&x3 z81B7H`f|pu(p;{=I;5FpXoesT!8Mk?Mp0eawdH}KD}4X4r2NSN51b)NUvo;{>i%F? z`mPIZqUc&3uQ(kaCgN&3JcG9J`0k;m{p;sPKq;if4KmEfJjIEH!Z4ob^` z{CMil8=29jHgM-P+cUC$+lcVNW)(Ts-cnvDNR&OcR2Ed3IK!9qDyjuzVP!SL@*Y2K z_;lUODJIbmgCXPv*o10(yPZI~IWkzL#Yd_ErX@c4Aly)Qx9>+Rr6MXSDwO2`W050+ zw02&6QclzVhTyt*R9R1tUu#=ifkSPhUO_vrt#m1$VId>j!^VF|ZYy0kR8R3_cfD#V zFYO6P3TPte^>AFo2F2*tX`fc7DWTX74(b#J+94^(Eg{No!b93lJrUd4+ow#2u{@k) z)HWKIta={gBB$PqV)9bo_J;eL6-OHKI4&}6uz7Gn!-EAQiDM>o#|0s zcjM#S{!jNk425bN<*l_aw|4ACbk)ks@t&9i&wU=Chm@Np+>xbAU`HWkOR$wWF@7eW zw!rb^-be+i&(G13<(9ZCM9OVQp6LYbcmm54?@ZxvewZhr5+Y_dpO`#A*|#TGaGZc; zP8Y2`SO2)RI|mj64B=|Al2y^PP4lF%D<;UqTJ&A}Riz*I_GK0e@>0i}p#ELgKfZFp z-7YK?mgJsmswcR|_jGrYqzj+KVli&XyC}{{cS}XEudCLD>yn`FQ2xa;=**eQ7CTD* z(F`kB8Z&@Bn-mknzH+X2L|kGsMNk$gcK?i^h0+y}=fA1x3vmNhRXQnBk%Bp%4d{0` z|A3?~73uzx{CUoOfLjG_fY78MQQ{wnq0Q#VEm}BdByLVuH1^@ou{sonU0KKr_65FV zn=LN#H8NqrJJ+o@N2YzQVrB9^ae%`wo82;qb}^&VpSO>f3tM{05mM(up+w&CsAz@r z+D-iSDL;2(u66^&E!~wF8_BRgaz&}_nH&XNQNw4ogC|FCYnt8as}f(n2h3{Crpx1B zNw+yvYUaEjMS%0$`ya+BB3A_-!+7tsU;uVd?KQ4c@Qg(|x{9wO4tU2qMXj*gR;0b> z0{*0KN0-QcZS=!>I)jN%3g2ateDO}lyxI#00tNb@kp317W8>A^K46^`WkPN0TR31y ziVj8W`C=1j(<7lNoJUua0@V|_jTCeZdyi3M#=x~FkV6{~wW_fjE${KoR7YG;Cw+lz zG?lV~P!oG_(JRprFSaKA$DQxJ`hU8qggJg2FA}1? z`M6nGbFR0)N~LnzXsDb~`(G&&$O}IYGkX<(EC1>p2L0)AWc=dQ{ePC9s*14>Z%SLF`w2x1_$)ijy z6pmpNdje)#*;rF`^U=NL3bV>EITjIgpD2RyE7jR7gx5c7JAoZmjWAju&@N30)&QfD z4Ro7N1D^eaELEIk?n_*Er)5?k{wMXzB_TZ_2oJK}}USTihqSmT^&-FIrkaXf!&c>tMv;vQFD+ y1Erocx>^k+RSRHSE5;J|OVSfSon?6)UIOM1WO1HOax<4-hlZ=mQ8?>BQ2Jjo12EM9 literal 0 HcmV?d00001 diff --git a/doc/html/_me_l_e_d_matrix_data_8h_source.html b/doc/html/_me_l_e_d_matrix_data_8h_source.html new file mode 100644 index 00000000..d3a7b498 --- /dev/null +++ b/doc/html/_me_l_e_d_matrix_data_8h_source.html @@ -0,0 +1,251 @@ + + + + + + + +MakeBlock Drive Updated: src/MeLEDMatrixData.h Source File + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeLEDMatrixData.h
    +
    +
    +Go to the documentation of this file.
    1
    +
    35#ifndef _ME_LEDMATRIX_FONT_DATA_H_
    +
    36#define _ME_LEDMATRIX_FONT_DATA_H_
    +
    37
    +
    +
    38typedef struct
    +
    39{
    +
    40 uint8_t Character[1];
    +
    41 uint8_t data[6];
    + +
    +
    43
    +
    44//Terminal
    +
    45const LED_Matrix_Font_6x8_TypeDef Character_font_6x8[] PROGMEM =
    +
    46{
    +
    47 ' ', 0x00,0x00,0x00,0x00,0x00,0x00,
    +
    48
    +
    49 '0', 0x00,0x7C,0x82,0x82,0x7C,0x00,
    +
    50 '1', 0x00,0x42,0xFE,0x02,0x00,0x00,
    +
    51 '2', 0x00,0x46,0x8A,0x92,0x62,0x00,
    +
    52 '3', 0x00,0x44,0x92,0x92,0x6C,0x00,
    +
    53 '4', 0x00,0x1C,0x64,0xFE,0x04,0x00,
    +
    54 '5', 0x00,0xF2,0x92,0x92,0x8C,0x00,
    +
    55 '6', 0x00,0x7C,0x92,0x92,0x4C,0x00,
    +
    56 '7', 0x00,0xC0,0x8E,0x90,0xE0,0x00,
    +
    57 '8', 0x00,0x6C,0x92,0x92,0x6C,0x00,
    +
    58 '9', 0x00,0x64,0x92,0x92,0x7C,0x00,
    +
    59
    +
    60 'a', 0x00,0x04,0x2A,0x2A,0x1E,0x00,
    +
    61 'b', 0x00,0xFE,0x12,0x12,0x0C,0x00,
    +
    62 'c', 0x00,0x0C,0x12,0x12,0x12,0x00,
    +
    63 'd', 0x00,0x0C,0x12,0x12,0xFE,0x00,
    +
    64 'e', 0x00,0x1C,0x2A,0x2A,0x18,0x00,
    +
    65 'f', 0x00,0x10,0x3E,0x50,0x50,0x00,
    +
    66 'g', 0x00,0x08,0x15,0x15,0x1E,0x00,
    +
    67 'h', 0x00,0xFE,0x10,0x1E,0x00,0x00,
    +
    68 'i', 0x00,0x00,0x2E,0x00,0x00,0x00,
    +
    69 'j', 0x00,0x02,0x01,0x2E,0x00,0x00,
    +
    70 'k', 0x00,0xFE,0x08,0x14,0x12,0x00,
    +
    71 'l', 0x00,0x00,0xFE,0x02,0x00,0x00,
    +
    72 'm', 0x00,0x1E,0x10,0x0E,0x10,0x0E,
    +
    73 'n', 0x00,0x1E,0x10,0x10,0x0E,0x00,
    +
    74 'o', 0x00,0x0C,0x12,0x12,0x0C,0x00,
    +
    75 'p', 0x00,0x1F,0x12,0x12,0x0C,0x00,
    +
    76 'q', 0x00,0x0C,0x12,0x12,0x1F,0x00,
    +
    77 'r', 0x00,0x1E,0x08,0x10,0x10,0x00,
    +
    78 's', 0x00,0x12,0x29,0x25,0x12,0x00,
    +
    79 't', 0x00,0x10,0x3E,0x12,0x00,0x00,
    +
    80 'u', 0x00,0x1C,0x02,0x02,0x1E,0x00,
    +
    81 'v', 0x18,0x04,0x02,0x04,0x18,0x00,
    +
    82 'w', 0x18,0x06,0x1C,0x06,0x18,0x00,
    +
    83 'x', 0x00,0x12,0x0C,0x0C,0x12,0x00,
    +
    84 'y', 0x00,0x18,0x05,0x05,0x1E,0x00,
    +
    85 'z', 0x00,0x12,0x16,0x1A,0x12,0x00,
    +
    86
    +
    87 'A', 0x00,0x7E,0x88,0x88,0x7E,0x00,
    +
    88 'B', 0x00,0xFE,0x92,0x92,0x6C,0x00,
    +
    89 'C', 0x00,0x7C,0x82,0x82,0x44,0x00,
    +
    90 'D', 0x00,0xFE,0x82,0x82,0x7C,0x00,
    +
    91 'E', 0x00,0xFE,0x92,0x92,0x82,0x00,
    +
    92 'F', 0x00,0xFE,0x90,0x90,0x80,0x00,
    +
    93 'G', 0x00,0x7C,0x82,0x92,0x5C,0x00,
    +
    94 'H', 0x00,0xFE,0x10,0x10,0xFE,0x00,
    +
    95 'I', 0x00,0x82,0xFE,0x82,0x00,0x00,
    +
    96 'J', 0x00,0x0C,0x02,0x02,0xFC,0x00,
    +
    97 'K', 0x00,0xFE,0x10,0x28,0xC6,0x00,
    +
    98 'L', 0x00,0xFE,0x02,0x02,0x02,0x00,
    +
    99 'M', 0x00,0xFE,0x40,0x30,0x40,0xFE,
    +
    100 'N', 0x00,0xFE,0x40,0x30,0x08,0xFE,
    +
    101 'O', 0x00,0x7C,0x82,0x82,0x82,0x7C,
    +
    102 'P', 0x00,0xFE,0x90,0x90,0x60,0x00,
    +
    103 'Q', 0x00,0x7C,0x82,0x8A,0x84,0x7A,
    +
    104 'R', 0x00,0xFE,0x98,0x94,0x62,0x00,
    +
    105 'S', 0x00,0x64,0x92,0x92,0x4C,0x00,
    +
    106 'T', 0x00,0x80,0xFE,0x80,0x80,0x00,
    +
    107 'U', 0x00,0xFC,0x02,0x02,0xFC,0x00,
    +
    108 'V', 0x00,0xF0,0x0C,0x02,0x0C,0xF0,
    +
    109 'W', 0x00,0xFE,0x04,0x38,0x04,0xFE,
    +
    110 'X', 0x00,0xC6,0x38,0x38,0xC6,0x00,
    +
    111 'Y', 0xC0,0x20,0x1E,0x20,0xC0,0x00,
    +
    112 'Z', 0x00,0x86,0x9A,0xB2,0xC2,0x00,
    +
    113 ',', 0x00,0x01,0x0e,0x0c,0x00,0x00,
    +
    114 '.', 0x00,0x00,0x06,0x06,0x00,0x00,
    +
    115 '%', 0x72,0x54,0x78,0x1e,0x2a,0x4e,
    +
    116 '!', 0x00,0x00,0x7a,0x00,0x00,0x00,
    +
    117 '?', 0x00,0x20,0x4a,0x30,0x00,0x00,
    +
    118 '-', 0x00,0x10,0x10,0x10,0x10,0x00,
    +
    119 '+', 0x08,0x08,0x3e,0x08,0x08,0x00,
    +
    120 '/', 0x00,0x02,0x0c,0x30,0x40,0x00,
    +
    121 '*', 0x22,0x14,0x08,0x14,0x22,0x00,
    +
    122 ':', 0x00,0x00,0x14,0x00,0x00,0x00,
    +
    123 '"', 0x00,0xC0,0x00,0xC0,0x00,0x00,
    +
    124 '#', 0x28,0xFE,0x28,0xFE,0x28,0x00,
    +
    125 '(', 0x00,0x00,0x7C,0x82,0x00,0x00,
    +
    126 ')', 0x00,0x00,0x82,0x7C,0x00,0x00,
    +
    127 ';', 0x00,0x02,0x24,0x00,0x00,0x00,
    +
    128 '~', 0x00,0x40,0x80,0x40,0x80,0x00,
    +
    129 ';', 0x00,0x02,0x24,0x00,0x00,0x00,
    +
    130 '=', 0x00,0x28,0x28,0x28,0x28,0x00,
    +
    131 '|', 0x00,0x00,0xFE,0x00,0x00,0x00,
    +
    132 '>', 0x00,0x82,0x44,0x28,0x10,0x00,
    +
    133 '<', 0x00,0x10,0x28,0x44,0x82,0x00,
    +
    134 '@', 0x00,0x00,0x00,0x00,0x00,0x00, // End mark of Character_font_6x8
    +
    135};
    +
    136
    +
    137
    +
    138
    +
    139
    +
    140
    +
    141
    +
    +
    142typedef struct
    +
    143{
    +
    144 uint8_t data[3];
    + +
    +
    146
    +
    147const LED_Matrix_Clock_Number_Font_3x8_TypeDef Clock_Number_font_3x8[] PROGMEM =
    +
    148{
    +
    149 0x7C,0x44,0x7C, //0
    +
    150 0x00,0x7C,0x00, //1
    +
    151 0x5C,0x54,0x74, //2
    +
    152 0x54,0x54,0x7C, //3
    +
    153 0x70,0x10,0x7C, //4
    +
    154 0x74,0x54,0x5C, //5
    +
    155 0x7C,0x54,0x5C, //6
    +
    156 0x40,0x40,0x7C, //7
    +
    157 0x7C,0x54,0x7C, //8
    +
    158 0x74,0x54,0x7C, //9
    +
    159 0x00,0x04,0x00, //.
    +
    160 0x20,0x20,0x20, //-
    +
    161 0x00,0x00,0x00, //
    +
    162};
    +
    163
    +
    164#endif
    +
    165
    +
    166
    +
    167
    +
    Definition MeLEDMatrixData.h:143
    +
    Definition MeLEDMatrixData.h:39
    +
    +
    + + + + diff --git a/doc/html/_me_light_sensor_8cpp.html b/doc/html/_me_light_sensor_8cpp.html new file mode 100644 index 00000000..f36b693f --- /dev/null +++ b/doc/html/_me_light_sensor_8cpp.html @@ -0,0 +1,191 @@ + + + + + + + +MakeBlock Drive Updated: src/MeLightSensor.cpp File Reference + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeLightSensor.cpp File Reference
    +
    +
    + +

    Driver for Me-Light Sensor module. +More...

    +
    #include "MeLightSensor.h"
    +
    +Include dependency graph for MeLightSensor.cpp:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +

    Detailed Description

    +

    Driver for Me-Light Sensor module.

    +
    Author
    MakeBlock
    +
    Version
    V1.0.2
    +
    Date
    2015/11/09
    +
    Copyright
    This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    +
    Method List:
    +
      +
    1. void MeLightSensor::setpin(uint8_t ledPin, uint8_t sensorPin)
    2. +
    3. int16_t MeLightSensor::read()
    4. +
    5. void MeLightSensor::lightOn()
    6. +
    7. void MeLightSensor::lightOff()
    8. +
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    +Mark Yan         2015/07/24     1.0.0            Rebuild the old lib.
    +Rafael Lee       2015/09/02     1.0.1            Added function setpin and some comments.
    +Mark Yan         2015/11/09     1.0.2            fix some comments error.
    +
    +
    +
    + + + + diff --git a/doc/html/_me_light_sensor_8cpp__incl.map b/doc/html/_me_light_sensor_8cpp__incl.map new file mode 100644 index 00000000..98571b7d --- /dev/null +++ b/doc/html/_me_light_sensor_8cpp__incl.map @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_light_sensor_8cpp__incl.md5 b/doc/html/_me_light_sensor_8cpp__incl.md5 new file mode 100644 index 00000000..a1fec836 --- /dev/null +++ b/doc/html/_me_light_sensor_8cpp__incl.md5 @@ -0,0 +1 @@ +fe13b7a51dca2e203a8b2da6369a80f1 \ No newline at end of file diff --git a/doc/html/_me_light_sensor_8cpp__incl.png b/doc/html/_me_light_sensor_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..5a9ec1a9884c48c4d874141ea719171214eae3e0 GIT binary patch literal 48027 zcmeFYWmHx1*DgwTNP~a~(%m7Y0s_*FbR*qtIs~LPAYB_!N$Kv`fNZ3tyGuHy!LtDW z@B5B%&N%np?|1vb!D7KLW}W!@)g=la+j}?g81I_w-2^pZ#t4EffBNgD%ho^y!H09wkW*Pz=g$^Yk1W5+l4hxcX#K>Kqh zMjm5sKfhEMFEo4h6huD3i(Tl8Y=pxDK30aT#7*p2ok7{95-6e1(e7|4@ZBhBXhys- zyziH}Dx31V-s}Du`vQ2uc@C4K87jxoLKxYIgNN4xe!h+HpS{q!5T1qo`>Z_)5vBR} z5t1~H`S(}`M`h~8zsGSB|NHABUwMW^PALD*O}pt+mX*PN|Gugfz{88xOCoWDzyCRI zPKf75>YVGS!k$wj-y zdp|!t1N@vojj)9@i)CYzd0|V1@a)?O_nT6Cp&(Eh&33Ql#Cz;{&r%k*vz*L~ab_Bt zpwL>UaNu{Xea^5mwf1c*(#_=7mjHGDW|XnI7OM?aDcQ6pS9UX()6x>JTJWjO@TE_^ z0u>~_2YxhJ^Wiqu%4-eJgs+bm6FI-RdBl})e$9T_cycvitPIj>adj)*pBNjpX}UU4 zmXt){DA~QYNDsCC`<^)LTQ_nQOBNF^ZcYD-Vkt?<8P$ioi!;44vC(v}4pY@y^jF&1 z!_BG*3zN~Efzbi?6DQ$S^)0VxwrXZ4YE+BQeC3ZXpJDCxb^)G?Rw)r)Y`ZMWgHfGj zK()kw#`$wHqGk=A4;vV!?M>EzFtjaoP*o^fYMT@wv!l~HjXV~h^mlc)wvAViurRD= z#E(W8X{{Q3xijs1Hf`B|?-uNI&NDRQ--Po$+`9j{NA(7b+`-4tVVeLi_U`p;{k@Om zEDpQV0>;c7_NEeXS{}>i#_POI3uw1MkGgfDlfZYu5J7cBEY4#?P zPoeTcoE~1&I*X@SY$}sHpHrr<3T%Mb=r1q8d~(0Vo`eQ;DyoicIGijklPHx*z<2SH z|2%B>;oH=YA##5@=dg!W?jOfee0%V``^U7QjQ{`Z|1WOlpKH;Gs%Rcm7)vFfo<(O_ zNjIKQ^0Z<$m*2MkIuhVlt#eGutu*`&_>B8MpMfu;S@uU?{=kz4@7UjtMbQaA*Mn(f zt`P1kIAQ|0M5W}T@0mfJ>qP?y6~z?AK3hIPJgybDU>jN_b}IqAXZoMDP>R(f3@;V^ z^4wk!!|GXd`GClmRCvr?SlXC*vuy$52$X+TWK&N<8^52uK^=+&G6Th9qT?3| z-F$fV^xv~Dc8X3UPin7o@c2oNXLmJe0rz41&-doV2KZNK`$rj^Z?$*^qDdA^9DT>SZK0-qtm+Tu}6*NqfkiIa~H|T$umJ{THrb zGGz_ABFpE?_A1H1i}*yh(m-YdlCXxRrosAt_P5d(x*gxnTN$PZ+@{R zBEKq;XMUc0d|_&q%Ekdwy9#o*)3vkNFIbo`b=Q;tW$svKAR70j0?8NaF~QTcjEtA4 z>r-ZDKhOPhvfugwY%Qua8&Jri+xW6+ak#AMM9=%Y>G%$~bFX)gxjsjtq%+<&g!pXgMI7N(!ufhG;Y2mV1I)j9_!|*j{m&h*mQ4tCb*_bLjt&k+rURVZ`Iu4 z`?$LOQ32}Bo;x3K^|rtMC2@7{7N?h^vl?R426SWNmsdO6bilW3t1ItoucVi`uoR%Y$7j%++;+E~BW@Bj>uvG^Y~1ZTMS zz69XK!n4*K1nV=$`MLiV(JD>&j&!+LZCVepDs@L0?1=i5&hwt$-61IDC5bHd9BiPgSK27bqV700a(ie2yKt9>79SD8G* zxs*7%(J!wv+`CBAe+$iv!BVi;v`j<^svfRcx3LSiq73 z7Fd0HIQOY)A&NfeZD=0!!(4e_UPzU#+Qb5opv=GzCXA){FBk~t@tJBhr9o{9)UkQ9 zr=`%*N>NOCgs_|fC|&tr`UjDd%`c4W}1-C7?3Dk$qKgp z&=xEV5YmV*ZYXl;SGc%%qKWEw(Ts1?zbpLPzfjX-LA=(PmYQci1)c&~@Q|^5&iIm? z{BpJ9eQiyVsb=Zv&Bi2|ITLIZj0i(q?I+zFWZ&vD;QfG=!Dqpy+kpY@9;eWe%<)%# zgr&aL`z?MlDc!h^y%fZoArM2+flRxDnd9IrW91#k(chsL&Kij!^JzApLqzQ~*pEfk zJmsBJY~OM@!W|~H2jTP$Xd9^67I|^Ik7Eq!CY$gMfVoHywuoMnN+UGoad=}pp!?T` zzFMouv#%`a8S^H@i_K8`xAe+xSL^JA2s;WpTqb<0rmjhNbZHF34GVM}x?V%)E~~Ub zv1_cPyWZz3|JkIn(+t7{MOzXAC6TdmP;|t}+x9RUZofb$BOx_)=MDXY4i(#yGeFJE zT~8=~3#N}57QFJCa2NOm;IaR#NS3&uqrN|g`@stC<~EAFp|y%2YX!ZH^nwdEX&t$@ zojF)io^PtbB62{bD>xXX3Q=7`gw6`KfwHMN-b&=fSUQ{sb6R4-&OVL2q?VV=!TlG1 zU?!ytGn@ArE@9*X?qkW8O@++36O^6U7C*R{Z6Zrb1x{FYw;HSBTF*7}e}KsZ)dH6V zZA6T?2EXl}U2WlHJfWuxkQ%En^jw+Y`?l-|MI zFA_0RoAqSkEal=tXFiRbM+&Yt_w^5rKt?S(u<+mm6elPd?#A@kDXfk#jDW-t^^Jyy05%tG-8dpSf z6;zf%rB-%hQ zsj5Io4Y)>OcvrIAdJaKT!;kQc5MkUPVh8j~eJu&7?bdUoG&G9dv&>f*fs(YS|C~y( zX1@y+#AG0QywY*x}I;g+$3>r0~g5}PUW}YF`c)y%tXVNqj7^s!hYYqF^^lu?|4d9St zED%I>c!%_(`O>p>D?7ywane^E#&#~xa_i)4wXSoF0G}gCjPx1W5V0`wnJ{90f*|{4 zp{~3DNQ5s|@SAcNsFkraTUulD8?QG3^b`N+&Oe)Su8;L>V6XRY`s)rmGkspiFx(V9(P0a)37ZHN>qfgN8qW@D- za-PUYR!Ti)(Ou<={%)^`qJX%}({(Gh%)>1UR#!`_!p~}z!zYr)N`KwYOcw3rp7B_r z`$Ytfoh@0)P`6!n(R%Z&;CtuBKl#o1{1x@*FthN-Fjxk!w@MpCIHbF<55B-58B3hG z6{RdQ3HM)!O2^)xYy0dmPHQu0)SP`9tggyr z3X?usU@gKBBNBeB{3Ax?4y)PjJJIJ^Kx(b~8#Jb_@qTKQtB=4hseNd^zSW+2({v-X zsNMy`8zm3O5g;C)iH!HvydXdFO#x_0_FaF(!j0eVkk?a$mUHUN{_!D6Np6XU8~FL0 zNa;!*QWSU_u;Vq8yh&+Fe`B)505!kQp7h(hI3c2li@V;wi_c@YT@(?;Y+>T_4V0@B zGbXx}Zobow200aH@9X_O9B;&LqURZR2a>{^YU>YN?4=WX2ud^V2X0Ga9@gJ~4yNIMkD+kP zAj3SN%TR4dCl?Ivc`7>Ew!uIc5x+5a$;ZuTCRCH|xEWgY>Q<;iyVvZBz3g+p*L?{;?3?g=vt4|e1 zT?scxRd47I6%YVUa|j2Zh5U7XZr`3As5SVlOD5E6E^Ub5-l4OLbR@6h{^0~Iz|o|n zAlN=bV1YNA{yPy3d;~47z1uBcJ_yz=`(Ugl%$Qv3qrBVa3K4BMXhz}i5r(NRxk3mA zWQ15z>?t*%akhMjRA|h}mxr8dw_kalnVKwtT~gq7<6GDGn$5{m$Q1UApK=FFqh5Xg zK=asq(dKu>i^YGo;XFewWno=IO}(PgYWNwNcYMj`C^9HplY4e851u6loFchbs@0M? zON~>pONiJ5eiNrJyVN2=l+4Zdc6>V0w~mbqmd-Ui>Kn)zjpVLic>L|P=?C8BVhk`0 zoBRWSzWAly*M+%e{5vc!!!i}tlJ$})DQLKV(k6fQB=xEP83q;JY`+P(;wzV(U&XDE zn(6tcj?8wOdu+fAvqH&7L`66^9s5yRS?-nBLh0m*_~ufTN;U<@--w1YI>`_hKFw*O zVc6`~?_Y#L8ZVz2RI6Ooeiv(%z;3rTl5FLtNPB6yq1?W#Guz{WOBXoxCr`inb`pE@hNG@ zCsD%mb2kBB{9djMCJEWU1`^BhC}-$L1M$=>goVGk-Q0IrH`^pN<`1Dbn9G-zm zc1AI)#qO(49646)w6hfY<1`J@kMRzt5qlcGuZK+$oL=Z?T4P;sT1@2N$V|eL0ol6WW*fAq9c?p$rquj%EqwGKm^F*%bVuXvHh6F+V(HS3#Og!n{aYm&lZQVylCvM;oF(N z;AQui+(_xROS&umJJ4_;$51YG2WN3NvQ?yHK;a52)C;#kxR%6HoyuB%P^Hgmh)j_%GuLML_!`#?#Fc}^2jk?g)j9`9L`Ukl*yo8k-ug}ufr(bVJy{T4u0uMpS zGI@{u%vN`A^3`zC%2V)az^ob*yAJ34-T35*Chd)0XcoM93EKuaVy?rdj%Pgy_jr)s z633DK&>$3LNr%sM->}h<_l6ugTK$r!80yh1&YwckL;Glu+h1gnH!Yr?KEm_Kn=!AU z$R~L-+0!Y)nTL^qREWuANmJ|7DOC*j{Xrw!4Zq{3J&#|c+lSOaZ7aJ|BY008!0cdx^sc0c`^BrkDZt~UU43>CfDFXWeB_rv; zL-7W(_M~RHz=Ba??VfDuW8*Lqqt1T(^}Ej?Vk`Ph_p+`Vox7YSJ*e)OR-8|8ae229 zKRr3o)0;Z;uqj~Z*X2-6^ievHMfH+;<0yz64zuS3`@o|C79hV=5=S?;3Q;0AyAeJj z>{fqL(~m*~ob*fba4-a9DF2d!U=iCA*PCaHGySG@{nh?&b!%kK|J^n2-E8t^J~VTB zyRSD7px?l>XSR;&N~RkhBuPq0LFgC(*3$Y_*H#C7eB0RazHeQ^c)kdT?Ow z3xE5YVt3}qnl78A?|NI8-?fAiK6j!Ec4VNVNW*21CO2;nng$*T9(rIro8`+nYP71Q z>!_4^nfpkyn>_eFj1Q$7p-%Ui;n2o#$0Js!e8qG)J%cZ2X0yNW^1ekxZeA(3VMuPt zU^a`fMYiPjP}lG*zZ1;Muk-L70gr!mky^-{n_g5Zjn60oKyZ3`>Jua|rqvdD@Dcoy zXtf<0WqGeD?}TsMCgFvw|Ch(*X@Ki$L%l&0#J&jXM0TS))8@Ak6x}*tLc7Fb(ShIb$3LInSo?AHEPxyN zdmxowG1#*ih%;7bqDe^ylVz*CFL~33*9Ms>F*#HotsiF&K*0|w-BL(;YlGrWcXhR6 z#1>7_50t=3JqalRQi53#ylY+}gHL69rF)j`<=>rn8@avn>0()wvWphKfXyQfmz7t& zQOKmp;{crfR;qBNh*}gdBTnph&HSaOmVUdD4)kc|o}|BL>kSA~^AHx0lOKiDV(9ew zRci&QtdYlOlkMiMGuK+1p9%LRgsM}H)Vp;@c6B_8e9Cf}RZdDd4a+34&&Pwg%XZ1c z2=rwkgK8piX7O8zd}VH5QGhE=$|?L~fW7Br*y=_a9EWmA{z}fTiO8W^8&nOo5Xc+k zsQsfd7Aw0h+eW-u%&*%}iy#1m+oj4loihNST8SJh+jF7Uluxl*4RuZY!yEa-KWW0t z@;_plEeV%6F=j_UG|0wa1RQ$-Q%(1aqWt#mE)!O_O+#autsASeg97WGoCp;03B+f% z*B&1zgxjX>D5Ml7@b%KB=@Ig%vE;f?|2ldo=lG zc8M#roAMdrv%cAQdOn2Y=znV?<}=)ihEN-VR!xjV2Xj>blx(+;|5y0~Z_02zQ&+xy zmIZlsF~jJJoDUlee)d4PxQt~3&NnvcF3%^ND#odz9ZRPbYRK34S-6n?y~|jQ>|bY? z^J4b%uGp_GNRECnR)?XUu4+F`8_qyY|0&B@g@wmP^A!*aM=~~X zupvM1S{mckakXaVp)3kWcqzWeyR;q`h^^eEz z`Fww;rg~8>)xvJb@QaNVQwGtErN?x4Ogw(bH}tg(RW5%b&APa$c9_y?7jc&kJ?SP$ z%@t_$@suvE10CS<5&y#Z5zfY^yZjj{JdHZe6&rzs3$A{6f6Ei=p7wh65n_3mEVIte zB=c#opDd57*-97=Qtv%793yfi*T+G0}>2gX(DN=zF-G$D_XO=RttdxQ7adt;i3Aw*>Q7b%q&TT!0;^OPfy=H*U?14 zhOdS9N7aNcntNZvwiK%yxmO}TK&5nHE=WK*I437e z1Z8hs#xVqo(wm>`TW)&sP_0b$)OBsOB=wbQe;oWl46FD=Xlf0>(ECl06ZQF0Icy;C zwC)ZTL5U%C}o^kIeFmq~=R#dftZW z!*kZ+9XFDbOc1#gd7=IJCp*l4ws-X*a;z72+xMw5q%>SO?);;Hv)SNcq5pmSt-fk4 zP$j4)6K4dzl}ga6jTm-tbbW`LKwO-!j}->A1a-ja?bBO2q><8v=5%WP6msZpQsD^U z9N?4?6>{nV@6pB|d2jMBK)_hT)a*WC&2t8!22@!`+PR%A3@kl@{T$2{bboPJjAJiW zQj^nb|7+?R03S(7jlmgmu8yUdG!=1drVE4iS$VEC3pv=! z)QDQ^+*I>({kawii2k69p5LMMY?IzjvVT>9p242Q=*^R3c!cPVOE@<8U&=aHaD4DF z^>|2wRyePPJ9$@;aKsl^e5&@Gj>gBwtL9q%-k#@XaaYB&u&^v1EhaY?MBG!wWN3r$ zmz(V8`$KS&mx_@s#uBDlR3^tK?wKZcDCMgP)c)cOYq=`E^Vy~^Fa9$NFxTKx#Wx7pn@&BQH+dYgavd5X@zI|TV-6g zOhNI9A`vGbxizWM27>a}?@2bZ>wY-H?GUu9rt7S`U?;wvp(Xe5`{|xyzy-ellhvt=X5OJF(f;>O zlpJf>j(BX|?H%nY?Kd5?`f9mG|7P5^au5PE+_0ZtG-FSdip7&cv90F-z#1iCBey$q zM|uh{1J_9THR>hwNs zzhoMDur9Rq!$k?)6ac;JS|psm}1Yc{|>em}Tg;9P1W)tO-z<#gA;bMf_F)&XF~-x_^}_x6Q_;~nX~He1Qok4Ged4#XqG3DfJ6@TBi~Au zP+|z><+D&~uzxNd1)pHR5B;i~x50*0eLb?h)66W%v?{Z0W1atUdAh5aq5HrY{rpnX z!hx%M!Nev`qA${zbx%jxcXWpiszOLi1`;M}ui)QHqST%C=m{i`UuSfN@(8=O9xx3? zFx+_G)*Pg)J>$XJ^aAreJGSljIQtV-{QkZL)}J+c)G$zTFYy1ad95-BRoKscW?m8o z=)4`3$r_%cV1L12lqK}V-uyzPY9JlRN?v6Fq5_Mu@0p2VJs+%&lijc_B;q*tuBMSS zbAlmA&8}h|YmUN=GAQ*aFCaYp{K9>1AWoZk>IGg$;RvOsDqyKC!wUYAPqUQ;=NEJG zs_^s3OJq@+N&S!;XBufTPvhsTpcnH6)IJvX9ip3psPVl}_s4B-{_34!G+P`tX5P%A zO{85?Cj-UV56>K*@I_b6k@M(A{@4OakEOu9yG9P!!Jtdah(95|<$jpJDNB$>tC$* za%Dd7Ai^o69V@iUlbS(8sme0Dw5aKS()k5DJqdd(j&r`nGh&Mi6#Aa_mhPHLk1#bB0-%O{s1y_#kbRED?>Th5;)9M82>j zy`|P7dDU{(0jaT>taRU-!O5Dv+Zlvy|DFWqb%bj`n{FAy58@!%Awc%}NsX`s<_8Em z4#T2+K0HSe1saj^JMDeW)yR$hLZ+U9FZq88(=t&Q_V_;R4+_p_s4YjYH3B>!;VjG} zv}mrrz938*$Q(@Djgns9iUMW5C(W(h6twLpj=ncOz<;ko=Tuy!Tx~3X`03#r-Thi%vyDsm zJ52J${HCpi$QI9hgBaQcpu8_q{&_O_U8VU{OLYEiVq|rc93aD@BmkNQhtgFI($>^JcRpZR{3vRaMNHQ>M|cNoBK^q68gpk`v08xpWvt96U{!r?(D%RG zSPe|U(tz_aYsicP0}VpkSCU4Xv-LV( zzpoDZMs>_baOHBfF>Fr*WXI{w-i-16si}p32Rb;|Jt{SroPFtqkK}pheTF0!!qsbB zkEn@u6x@bV-0k^n)zhd&Xh#&*Xs4^)WJU1z>F=+3Yo9#T_J%9H{{Aed8RWU}v&GE% zF5}Uh_v4NOi0Ln@0lC5oDInq>u4g`4FkA0|!Ts}uhY;VYV@|r%R&t_K-Yys9v=}3v zby1m2M0dfzYfp%G)SiV%Z?VPijThL&wGz>`dH!kkJlTe~C_AKn9TCgRL(d6&!p$9g ziy+vaVPy}dr{xf*Iz9m*y|Lk(SSp4$_~F@(Fu_Z5xcgD|%&Yo95hc>~&|?6S^Y^8r zz2k+1$Z{Ja>l%4mikZV({j9L+$3FFTkgU%)rkQZ@jBpbn<|#xuUE=SiVCE@-P^hd@(OYJu+aq7 zwSZIs-2d80564lkl7RN_a$brKCd_x^2X7YGTD(krug>z%N}1YbL%T4@C_4givJptv z;j^8he+czN#ge{$iFJj02oWAit$-~zq?}Mt54GG8+mH-amQ4Hj#|c}@*%@~^|23_T z+6l}(%HjASR8;%pjsVD)L67-&i)2MME7dEcXn=HUaL5N!ym+7jRzoCrbAltVIww^4 zAZ|oA(v#JXL}ieV)`5iXc?)6GU@lmS(-X%hoG>G9N97N@Z?PgG&{om^G8|Hr!@!nb z)`^is)I_`Z&9>Nj;52xq4G?;Pg~DB4l)ub8bpb?Gkjf-IxAsFPA1gCpb?EdOnkd*s z3gQcuH&C{=$u4CX1(=AW&U-1u9gsqjrn568XX@?K?BFvM7Z=v=HR25s9Bx502lQYH z*pd&HAly&6T%eQE;>>Kn6uuEaL&zN7#tSbQs|#;e>~ya=rb0f{^b>qH00D*rLJKOr6+94LMWdYW3c$v`{e@UT1Z%2;|CgjiRT$W3TO z;=WJ^Oa_F`ifI9zP~BZ9BI4%lFJ~S>QbA(DCqF|eXFJ`4#qC8XF+H#BHXRxqO)^~# zUrq^C`GhlI*+4MOx z^QIc4*T!=&`rEM_L2ircvq zQtq=TUAY~|I;nVdrOG7V>=^!yXbgt$dz_+0iSZb*#COJqwL;y1zV5kJ%r+Z98>-+5 zz`1ZT1BTrI@^SRTupm}Y4-Nwy*OH1+L+5d`Xv2_0;Z1ewZQ*F(LKTVF22$~nJzCS^ zx1ZABPa6YM=^UWFtNCuIZkds;S8c%$&^#)6BYE?UdW^we_K;4r?m_6pU*x|-X=>K? zjo(j(SWpu<{=^1@F~MBaU|fjPKKN^{!)N$e$BFa`dfqgI`^g65h;huk^w#P1FZY8B zj-ut!pGR%-r(dW{(%$Lg%a5`nnjm+h}(4H#v>MW;=^j> z*KQ(xh*z@7H)y%)p;ftK}u7sUuJ`E5bW<|axdY#SAfb}Vcg^b$Am*? zR!nBfh0{%jiKS$C7AG8K!Mn^x{aGUWsU$AzJ&qDjItl0tK&`V|t=6@e5zj7_qa}Gv zEa2JUWYktvTi5#P(iB~nTcpB!P1%+wk_+|;R(;uZwpn0fT|%>k3a>^%zbX&^cB$A& z+rHeVDt=d1Z5{|oQq3PsC?xQ!PIr=kdfHW6z~BbECnub!V3Dn<-?v`CK#y?5V;(VL zCvRpXv%f{(vqRj*v8p}ja-jd60MCBSpw|cgndiIWfqlXCK z0eis}If5c+q?>GQZ7_JLEx9{n-o|0l`#B*(9OD{A|Lw(*SxJBNU2;;F4Wii>P0=;+!OWtV<0UI3A4{*cC|A9YSgYqmQK=se~$ zQ*o#zNL<|OEdK1g^v1|xNsBc3e4|B+_u}r^p|p|2Yo4s%ia+BP=#PuZq$dey3o|Fm zvyfAGl#K&4ZFf(f# z^>vy>p2Q)C59s)<%DN`!7AA9`fl=p`>F`&nuh9>Q9dThDD#)x``~3CofWc!Fb5jCb zg2|}RmcveCkGPf;z~fNUeUYa;&y?&o!b?jj;#*Z>Plp_j$hEit3uEG0o;)gAlduB$db?eVOhxPur;HA=6YTDF)EFmeBZ~Dw z0c(Kc0KAgy_XBX3iAfm0W|xxkA*&~x;?xG1-6Vs71h`CaSIT<;6P*5m0AYKxDj4l- z>3pSq8iNR55-mlg|C5Tl0Uu~d9~fp=oA+c+zAo@}tSM&cJY0TP33=;KG+e>2_Ju9K z;+E z8xCdl0XCO$q0jS%i^?}oUp212@tg^$nnBdGTSVb6OUY|LJ=d*G9QS@b%;^_)#J98& zMJ@#B1+#>1`ZS1%k7%}5)7SHie=}l(`i54`@CG$P2>b5n`O-7+wW%)CPTw7~U9?md z`Yvj7@R2l#n1sKIQ4Kq|t_UE!Z=K}38wdq0q(|4kvktD2EU1w;e~^K48;SFXEu<3> zt;>oJK>*v>F3OKjYIfmgZNM_1tHwVqHmH5m1Li}gIS zEWOSem-Av^glJw<8rZNPftAoRu`laGbIg!LQWn#}-fetuu9Y|!#jByI5~$ab3kIK* z*V_lu%=LXEL+?0LI&jv+@yO_=k^mSQ2{QEjIbYEt_+perq?RgD@u$3i1soNUYRgOF zmPkdVD{qWtbr3t!!sf3h!8hd=X`%^R4Zw89ukrvC5Kbi7Up0MOr9T$U$2tDp5J1_n z)yuQC9RdRK4J%Ca6*JbQxDy`3Ta=_82`U&IPCw5FexizS92ZqWLwFR>!Q((uZdYMTH;#_Y=@IU?)^ zqw#kzc(%x&jc`#E0$C(6yhHtXoReie=o2(^OSLj5pRqr>p?&%tdMHm3xu9W5=XC5&5tWOVmTq}U&K9`v9Vtsd{?yRGlFhg?xeH9o4~t_9AqxC-ko&)9rD4L}zg zMms=HC)F|Jc0qPHI%Cp0oIYf1+5Jry?9J^v2J&VmzwsU5YNdecffjf-Npw#dN}Cvr z-K5{QkYKT_Orms$9`;<)ojKA2sc@yPp~A*4JR>3e$bI8sa%Ji5l56F!dQVGWQg| zENpJMsM0KPEf!gpemaMY<+kY(wDm(eHuG^n<$x0u?#~!p#1)NbuasL~z|d{9i3N&e zXh67#=$v+=<1Z`X7}%)ztzVJ7<@~dYlnPl>=w>%6YOeMEFEhCQibpRK3y4Lj0Cm{E zf9-+@-Eh6Uxb_Eo&sseoBYB`7%0b32;j^}sSOhlceVT>M?R{dCO5Q3!*|_SZifAi~ z9!L&B9Kpe*7dYK;odE(^ce{shhf5ouQLmh5H(n)()g15}RSH{6CCBQI*TD<3MOQl}dhiP(E z9SLT+34kWC)E7PUF3i^N_G-Z~i&B=X=c32y4VZ#6OVw%kO~QpbFJ0~fku!(vnHKOF6 zkF$CAkuYEK52#qiKkr_SH!Ht#FwD$C@J{*bf3`0oQd;S?ba6h{gEEq!fyY>6%clJ0 zd1RRSJIlD*=N~Xsbw*OH;LHiSZu9Yokn!MS=?3I&SiUetj_~u05`RRioWelX<)7Ah z5`s~kNY^)aa&1cg#Pn=qFe4Q*bh6e?584-Ma3SEaTsWuj6C1fcc1=qiiAiXf3qO>l z$b-@M1!Wi(ISj{X&5$nIv3eCj5iwYrDI&#`YtZL;oG?Yy4jF+Mc1 zw@in8Aw1W*lzi%&Y{Ppq?>y9kd!k;y-*?jMS>FX_IwS zLO*#CaSzAGUXcEZOijLc$`s561HX#R@l#zUL6AnQlR;1BSB&$&%+M11NsOI@;4O^v zwIP1}Xb{%h5+yasA9ti?R<+n*X?UZD;DhHuRL}KfiC(D(Z1Sprs%U3ju&5Lw3^gGI7sybq%6IuQ5qw=AVt_3Cd(Nq zu>Th_)$c)Sp?!f>>Q=AoX`jW7`)ww2RB}+L(%9}a`WOZyUO2K|2_xV#vC6Xerx?<4 zT&C}ZcA$&mER!Rs1uzhnvQNj(-t3#>DgLIT(aUulG4`wWP}DVzLH@!s78q?LW%;d$aypAuSHK z&tIPMaLuuQm^cPe+9OzC=#7!a8D3_@b6r9sL}8?+{b-y#xl~M`2Ex#?qGOC+P%+1l ze|n3&IDvAS`n1kh`7hx9v2R@%Ec^~DcRt&us&%SzqYj5cMC?R@`0KAJO2ZT^!n1UL zzLX;H`ie361wvI6N8TJwBKrZm!=XDtEprED>h`;S-ZhFIF(Q@Ia)KxIWznJ#wkB^b zfnG|8^CxIDBQ7ae$eZ#3oQYZY(mONTc5G zJoKVhMtj;!-tf_F2&-^`*wSPhW$J85?EdQKidz(_wzSnC!>!x7zFs|k`q&fc z7yBUtQCbF0(qIP7&=q8Z7?a_Y6z>kMS(zCk68G1C2yCml%LTYmME`C=v{M2Vq9y!! zgtKfbZ}C9QV8w5K!$_xC ze@j#v8M3C(=CZ>M85_d9A+Bd9jw{>XcBjo1_}>=a5fTYu@5Ak1$^4~aRS zHyY6SDx8pe+1%LwMv&M;Em1fiZMz-j-CFg%?s9pV7DqueSya&08<8h(%X8gt^Dw{|joIgql(UHe?eIe(DivWQS24=RC0~Up>R=Ucab4VX7#UCvt zge{0o8g%?oaPD=QFnN(j&Myq{&Aij>z212!1I6-M!|ThcMIo|yxyP%=(DQA1xf8v? z8psmhyc7{TmYhGUefnH^dQtmSM%5C*Dfkl?uG8yQ-s9pjEz4Uj`JQNIag_DfOEU`T z4KBm3vey}g4wWI1O@X?mufO>R z27PVl@6ueWoh9O|1j+el)jaEHd=*8B>)mjv%j(?e&8e`!Kn=58P4cl+IH z1p0e;uDEv^ZCG2`@4=NmKDrWudYv9fDgP3WQ_V<9I!$gvDV6~UXqIK7#yVF{1*5`_ z{GMW?r>FPkX@kE(THdMnqPOn0aQj`iSU68E9F8P*i(!oL2|Gu^9saO|s19Wkd><^q z{6=L^~S;@++!=J3nJPUUf4t1p#tREUPCrC{Vs&98Q;WZ)U%60~Y3d`^OOLa2r| zb?--o^vljyeo0Z{-v+#@$(JI(L2!JqJS0POB^&6duETs^X?*Lef0J0oq=%2&!{?W8 z2A=$vT0h$Zt%!SY*#LGge%r}Y`zp=fIJtX1n#OTx<4}7jN-%LCQE54?*!w%KC4$0t zyj|lMBn8gVi^zc=-km!yo2Yzy)r8UZw%$Z}F@9*{q3(MJULy*tu38Rd?`lSYD2;Wf z|BATs+Y{IKSy`URkdph}8>c4N3a4LP5YK~L`&;?*XKR@z>|R8bY4q6OnIr4%WoruGa~v!K%KT>9cf+2EC#mI5z=Wdvt77h@f+%M~KA)kLS`1;(M2k*K3x z`mg%?yq-9!JjOmAgb1$_(3aOHCasiEFz^?MsTF|1*jKf-9@< zU^@9&xo`k+rW2MurAEVJ{>bGg>b#`BaN)n$A@UGnv9x`|MU~_Uj zlwkQVhen{4&{!&e7xtX{}{n@S0F zb+oYiI4JEbd8JIL7^#$G-ud}zsovfKVKdGL2TWk-|^8J@%aF@ zMCw>)+=ALs#73lwgrQOG>kX&{<6_wAduL3POAFWHQnnt`(4`mKuN z7B4d5sl-0)?kd0NO@*G_BMXdb7r9Q}=_OF~hCdK6My_;fM6L20=eL*$0?hq=$qQn! zIiCWW0;JOUxtg^7K%}ER55P!1^HMd^e)LStP;EIKg9F2djW{mXZ+lW&r+vyPsaLN;JTbJ0;`AR@O*eCO{~(E(IeKT7>i156pU{Kt$AWxHenatGus8 zn0?B3c)!2&?wGt6{Mt?JBViPQ=8srYZ>72m~ZkS>xYkb4VnG}ATe>!L5hv1@t^tF+E&(+vp8yFjm=MzZ(fQxG4V zJ&9TWmi+VHJ0{LO$&9_fPF#a`k@jU?xKA7R#+w5 z!iS$&{xH^OyO^!o4g0AlQ|ALdTxf!j9A)W7#CeKNL;>1uHYvtrqOy}|GD8VG1-uq4 znnKvJ1M1L$Scz3zYQhBdGz62@)p(tnZQZ^iIovf%7O;He1Pdf;btu(g8CL0S{lEOf z9aD$X@bu{oaznl6^(^frtKPXhiK+H&o&?N|sn`{Cj}PCUsfO${pJ^CD>y^CDoKw8r zh`Z6Z&;ac`qfi(aN#UV#RN+V$$F@&<@J6}?Oq00U(ea0l_YzI>Khw(m&=+L$7M*Wv zDcIk4U@84M(G*A;!54u+z=GQ2iKUG*Q@s>4fjpJ@BOfc`mmkLH3EKD_5Qzc)j-dzE zAk>M4q5Fz+v_oyWFjy@~5jPb9D3WO>enTKpF2{fKo?4ALlnKN>+PK``R-<`mb zz1I&6secQbWSBFxVu$&(uKZZ;uv}O8CWeH#*sa^;;T^k9&Lj29ET$#KlI%bGC-jhF zKP?a@;`j(1uOtRE^gD1V-Quy6XQ~VY+t4cLkq+7y`>|o%H-r02Wp=)J;KbZ)CPhw6qj)* zP%=n{L*AH}njpo8?9IMW{xiz=avv2EB-tszhZ%71tzfCUw@->Q38xv(PnEi^l# z=2Z(XK8?_n_Fx*sypJ3J{+5I@P1Z8GN%ztM2A3hT*bYLYc|{ZZ$*0tb#9_3wYy|w8 z!xvItKwOPX}TJlx|QuH+Th9uI?_j3w02Ww_%$}L~mM*$$t zWufk#Z|9*FC;lNFjDu^OFg-1U7<|v7kMHZ7#}|NC_2~u^MU#zP1^Wvtx)!fMyzj(W`EhaI;rNE z{45lVu|{;u?rnmW4Hn*#$BQCeETl0$ekgT$4dGE!M!b6URN$0D&Ei2C->GzSrf;Y& zp8c61_*@J_ftrQ*0*l+nms9mW4njXv;}^cqufI>N-1za_`HWe)Loz*S4D8ef1lCp# zwXtonKyuyy<>u!|fi~m4K2#09(+dH%xs+<<8=KXEACvNqq(I($bZ_e)q-z(?sx1!F zV{>njl1RMVHfWo#&?o`kM+6L*IoRe>uIdtd>CMCd;|<{!3OmM58vJ-$*UYO34%@I} z)ukVp!9pA35(3)#3cZY3Z-?NpyXFZKDR!xfIeYv5V_EQ{X#QID(2ClJz+!Etkno=; z$xPFVZc~=MQFe~)VgFUpgIq{%O(}xA7Av zRDL<+S_7hXEpw4i^||%6q+% zSs1HP^ggV95Vvn04h<0B-qKXV0%sI%$jGp&Gyj2Y;$5LmbZ#Yhom{ zs{Km3@5$EsMtNU4*n)u;{>Ih_gfdWW-gTXZmvZOhK1bG9D=-tm z1;2m+eLJujpna=_iMfZh$#`U3isnpV0S&qtPo60ws(xIJ4=X>8I2ZalrT-9o9K`jN?kU2qoG7Dk| zr#Y%(x$r@821X_kSebg|7cTuLp?C{QI}u8h78giiiY~yR>UM z){P(zeG4fi^qYm*%tO^aErG&8Z?KOMx{f`;$4}DgZCDoVIv`5og$zzmG#uo8?mMz70J#MI z{d=>7zsfh!?~-`-cO~cs9$=`%2~qrs>b8b*v=^jqs%On;C8CA=M8$Nq?oxjT$;A6q zGmQgf7b#G!NqLm-C?*Q-*JLq}J)Cr|RZUDxU%lrR_!mmk=Ru2IalKOvpH7c-K2-hE zb)ims4kPPd8`dgK=@$(+6aqe>}dlK064DsWAg zjhbG$f25u!p_3>!xu^tw>hR>@1*wNEJ1w}wh<>b65jL1NKFOBEliORBKrZ6ZUtxls zi*Q=)|H5LxW4Ly3R9m0nPCu||WDc06a)0!Av0*xGY>bLOOOrO;Ot0 z++LCV5jHj|ys&HnRaCdV?7VDU?#3SAq6VbusPN;7j%W|z3|@<%MtXm4%LRLYpaCkiw9U|)aQtPI#GsSEL z(#u>z(|}hYwCj+>lG{h!u+CLeXki0TI^nOa{p5pVhjd@OtGy@QU<`saX)mP>Q1Cp@ z#aSDCbt~KR;h&8@gy}--Xr#%)0KLrs_tyE~6CSPM-hf>m&Ba;$YUWH_%t6%di$Phy z1(d_;L8S;DZ;<&vn`f_k4qjrzJ)y#A-N=uYRt)UWAU?i#ac(@>6tqmdAd9@9M8ge3gA`J!`|JuJyaA3-r6I zyOip2O#h%s@X&LQ>xp+|G^M)zxNRsZDr&+hd)jvV&`aIj;+|wY&~IyN{Pi^B{LJiZ zB~h^}`cP&l`5tNeYdQh8Y4>9v0-c5a z-1D^=V7dvnv|OxH#T=I|Xe^zLVZ<)ix?hhA=i9e;-+q{GI;p;>Kvo;s-``Ka6E5b< z^F`bs551nUp&QMidj89lvsC2cMA?%QR8&i8g?CQ*N+a`bpW6groOqs5aiBUovsexP&so)j|`y#)oz$GJeA6WNF0q44{kZ%0%4#dUt-)oB-nbUTu$ z#FqpGkOcGd@UW=Qj$fTaw~m%Db-VkrZ$al%6@5N_HjLM=;ApIP4$hi2hw0ek)5K-6 zV`%J@cFUwq_bHj zdbug0$Ec?~Z0f$GVZ04bcuNzNPfQ;OtVwI43bE3sccvV>l~?zE|d%OzfS(g%mRVV)MZg&7VwYMXWqalkx~c& z!bd8`r}1H(u~-A-ir24Nd_C%qw=Gz}i2r#}3}-P1if{1Cw81Xer;mb+S^J>O z&(wvTouTZxEwR01yh?gIfam?c&uq-hm%|^%zC7k10UAW78gWh1FBra*sQ%58O7pC> z$+K~)R&bl9?HohI@E?@wPyKW;M8Al@&}?tepZesM=qz@cn6WcPG^)1;%Jll61zcYX z{RGH7-gpD4!8QMCY``cY7{0J>ZZD+IbTa^P{IzdB^bk08&sEWEPI!t2O>t z>eGL`5WVyrx!>gaysuE#1z5m-&pTW=N3wZ0+xP0GJNzJ%+R$;{^ZR_~*Xqg)qV~16 zYbK)$;S|5QTT+5^*HuGKe|D+K^>JUvd8^#{(ddH=%<)BFLy#;PM*z`4ksX|L_^UaH zo<~Vz)ogWXSf~GQ|G!uyGOhpCoFR-H^tb_TL1kGTx4q*}6<;v+*()*?x2h%CZzTNF z$i|emGr~SUAAR7-6qfrnfc)ZZxZl*HPt32JYtuJqa_XCi8=sd#j{$1{wim_Pcx{s6 zMx^Zvn4|08%PATiu>5l4%|xI8_W6y4O5@Im|B~ytXe9>+WWjZFR{%@-pUL3iU09tRz6Hae>FSy9v)1ZG~C5y9pg?OJg=+WAN}T^J;aSw zj1M9S^hX{V0E-2jPF}hiJ}*BmWRFcwgOOaux?GqLd!7B;DW>&fer#)ekX{&OJU3G@ zzLvWVyuPk)pcRi3g-&W8c8zh*kou@cT-!S$UUXpW_#Ph+UtV=!{B3!95?%0fv6yu8 zR!Jo4p=XwL%}c2TIM52G5C;A*oVMU}NE?RE5^Yxpr_6(@3*O}4ZwBcxd zeRbp4Y;~2jITkl2J|eu%dVE*qJP$@X|71$JOZo?lmZUx3+)OCtZG;-k24F?klg(7N-`j+gx4f3xaE zd8|Sf|H5++uhS^<;?P36FZz_C5#ixJVYe2_7hI{;WK+ccs*~hBrv(MBXVxV%6_w?J z2eWG{XX0NM=_=QG1Um@OZy(ehrCZJ3*RQ!NG}@gr%^k-%jouXq;)Q#y%0HU-Vox0d zKi<>iOazV@3?8dAfM*?ZGlX)d(v2GtMl#1n9mU=Hf#*GS4iW5(IOLv=JgHhI9<%oh z$mW)#-PzG1dcB{Q#v!MRQ@eh-qIqoxCq^u4uE zm392;9pye7-8uIL{0&D372jXj0pS>7-jz{rQ}Wxy!Px0 z4(O~F=zKiM%XXyn#*g~Jb4&WG)}Pn;sQQO(;4_=FkLVL-=C9|i}IY9c2nAu3ipwnZtmBfl*EnV=Y{?CwW6CtYBN8*Y1fT~b?9 zUCCEGgbskA7HwgH8L^*}v20PEQa&o(s%oDVEmxVdygEWt5EKlbqtV)x$kZ#hLUA)%4hbtO4VAWXoDFc0CJ&qY5Mf8rD? zv5n!37!K&sN1rwiS#JeY|2X({*UiDp0Vl3gUv}_|*l?g9iD(dj>bEwmW4ZlL|A~Ql z;Xgkz-?tCx1Upx8yi2ULF?EDVY?jt7$G{Yt*l4R@-P@=}pWZeM5_H{RF@uCk`9IPD z{;X;#3Be-ntv%EL zw?|kW@7wVj7fp^Uenvdy1Y+1 zuU+2k?v>;eH#G3j*PhGi>+2tP+gON)A-R%!62{Ej)2wg*?jjrP_6*mr3W)Q>LmMpE z3|(V}G{dMwi^9a7gS9`5$^H4}TE5M0G{8+A@=|3K!-N7tL`xb-sOOc5oew+`EEMjj z#}%$T$QEl(K1h~?ez3cV#{mGl0+pmCB-xJ(-OQf;*P|sFIoqw!gXX^-o!{bJ21GxO zncCglBYM-_*3rLve{zK_>a^cAW=yPY+XnVx))qcAEFCbqu`$x`RL)iq9q$k95U$vz zfSY%x_-JnrHGW?D{i)y%V6gxDM!<5ONu(G5J8fw`xaRKLos8^01{hlxyg#2TSpxwi zj|LpiReJBi`un+n6AW?oz_{yv=bKWd;TN%ZS2=m0Glmz?OuiM0ZCh$x`;EOEsb7yO zFHp`1kn$Frk`6OIqafpuT2w&1OiB*lR-;rnhcz;k!`18`DT#Diw-tsnhXXKC1YIMj zv`4N-i=i9~AHKO?^89);YIYWAS;2;41V55)R14Riw;rqP3+v|ON z%C*|3#-?S#$3fhpzgg_{)fcOlR;}MI??2dpvj_0vIaDflS#g}jEixK+uTHJOs`*9( zsPuo$u>;tL^1gu1L+8&F&;H2*H#8lJp4b*}LpovxwXQH5F!nv`gB5eSMK$jYwZ_Yn z`8$4DD60>&a^Ss?K~xR-BHwGI4UVlVlC?V`mKoD$RG4{SNoadYzt9hA81(~P4Zc16 z4WS{Of3!7U6tDsTnNXoHoZ#KyehFdD3`+Bn2|%c7W9nX9vdH+?8g&b}tUgcCF08mC z8V4{ne%oB~Lz6b$tO(*-`!#dZhJ~BzpC5_v73eZIqt;ZH$4I48vf*H1z`nP@^j0!W z>LCtmgw<(0=oJAOvsY;gx;uNyQ;ZS?p0zFjaGgfLqeG<)c zL(_m->wPsCsJnD6XyafH%-)_g5SbauV}4+6lpw3&g{+qG{FJJL47c>-7FbIjfNsoK zXzuT`qB)CifJUCm>7ojt!y#-NwR%hDjSnKk(ZICY``ww{at9I7KmDw?uviYh;Qbj& zuoPB5JQ933jISl8H;I?zrkt!76?(bwh9g?YxiZ^%#%hIdq*M~JhMJ^#l#*?5Ul~he zxEDu?{+EyX4OA0DUwRgMlECCU%SQMuZNpV`cLfllv#&hfWbFDT8Ej6RPK2kpPOjd9 zwFY=|F^q2C68Z8H`z2k7Lbign0Xayuyd{4_vTCMCK_%y} zzH!|D)o%buNu1PD0(tk*r-_hlgNmUq01J&=;<)tFsCO}8GDhTu!b=qcz{)hQ}%du-Ff4QLvo4$VOPkXDiivS^zdGQxKZBxzy zRBlQE{TvA{6Fn0t2D?Q&=`$zZ3P@Z{=wW1(P&^FBrwqBd871lV@BIRy#)Bn~twmU` zxO7VcCj-9^8GHOpnnb}tU50joj?%x7QT+X-y&)6z>Yz!_N~A{V>gznN7IgVz)-kFn zu#lIw3MYaZ?jfRDrq+Rz%(iHjSyALu{zPUo&^dMYMeqnd#9j767kgh-8Qus9{}tTI zgj0OQg|Il-g*9`=5ltHWc5(UNAyIiDo7)E@&uyx~ql$a7L!0Pf7vOi10Ev%F|6-e{ z_q!j-5^K%xauhduXN59UvqyGkg;w!Kt}4W&ar7!7tUb{-&<22Zh+h}Hq>G=b&U;{> zBwfNvEO{I&DQ~k}r9a|8LWW;PYxwSDXvd{+{z%SY+490rFNonMG6w9L#SnQ@F=l-} zN18gs%b;TSC1)>H2=d4fv;JK6^W+sEwbis$&p9X7qK0qQNnL#%n-z*a_ihB{R2H%? z18-YI%eB*dBgXfh@sPEM1yrmjPAnct?0XVUyJ*oiOVz zn~AJiF~8QJKfpTb08MkuL%KzfV15LsJFp6sCKCa}4KprrZWUPmloTB12FX0m&d9>Q zxrbUSQd@6zkN!C+V}~Mrv;q^BNu0so@n{-%+EZ&58sl@JWJa;3FT;chuAP;0&Ofjh zV$LfpqbL+moq^qmvh>xWsPkPUV5(pY#vv)&=IwSRj`FziAj({+GC&vs1llL_6c2V7 zd}$4#AMT|%o9A;{0ffqb?2-8wqQM%ciBdsVqZwX9Cz?R;n%`+|t*(n7C9^3D&gh7x zA9|DY@T~uHn_hnr9CN0~Uha;8;4wn3&QtE*#@v6T+c|W#3(KZm(+Oo-W&6UY;HCN1Vcgkp8O z0uAYQ-wL0|`yxSugD(l)J-+80=5Pv&X@q|=Ch#Te5aDlHw4t$qp}k2$I6;rWFf~M8 z$zy9mHN^#?1Nbl9F)3%K%sarEA^{yTOdmlRW-KnOaPlPcvjR=2Cro%V3KH~Urs)Y# zPcsD!BF+Uj$Uy0utsX{=6_>*NU_>V2Bug+04L8uUK*(JuqoG$aG`r{G@wd&{Wz~f& zOZlR>#|G%&2uZ0`Jga>njoy_42ec$B+$^9Wh{?cPSZBsn{Le&b>vr8x3S%le=hEuMX5DO0H2hrY9W}+E@yc8yfn(Dc~-^z z1U7UqR{RP36dgn?@A3NqAfr}KIy&N6V;tG>RSGt7TdoIM8_!@tmN=N_PC}Pgi`s zy#U&b;owehtTPb!=}dSK&v;BpifD)K1~X1ofz7Y6BIkLUVrJMlnIhI?#maaEtn9xQ z(p%P3M$lOFOT=*<3j42EWx{6r_sdAIRg!Hp~n}{6@=umPS*sP{GH#FWqhINWtbjHcSQ96#) zW3aMGU-BQ6$g~7&dfau}y}8TZ?-yntFW0Y(9qCG#UDl zrehC7DMPz&vp#e7yDfF3g)=eVHVbINXXE?A9d&$VLl9aZ0cr>$4j@J-Vt>~!EouvX zyd!ZwwzhneOkI&hVt({tz1VcQ9+576qTb0`75Ytm^KZtd^R{(CsNPF!yzXE^nFxM$ zJTairgxSHmwe|G%nD%J&j6$J5-@9y1ZyV9%1!8Xo12tCPOZqId$@A@ zGCkMecOIvAqdz{VQ)tinPB-$D)n`r_DA`Ia($V*R^QM-vxYK$IO26Aa4rs|pNLra`S=N9HC# zR6KSozaZb*5N5n=$GAji+`UJFLv}u!e_02RhGNNottaTnNPMrLHZSMLCtN}n{6YDe zE0&RMu6`g@WI|(lTYE{sz?3-@Bg~3+ny2+0nU>staP?tK*!Xe&s$%Z&ip7G}soZ{i ze?2pi{D7$${)Ccrnh^IO=^NC|$+<1DQCTnrmfArw@k7)bAf zwPVGD|EmSzF=#F>Zuo}M?WVVRtA_QOKP6qz58aEEWL?|&&YeaSHz+3=Q&oIO;RFM% z!OJI^=Sn=K^?1a6P>nCM=QZoMH=cHbh?Ns=9VlezY5%-M^@n(77!<7WQDy~~w0=cX-(Fu4%h zvI>_(nK>TsQ#+rz)3#jQ;dS>GBVfV>ni_uN;osQ;3?ju5hm6D(rsiSr0}3!TaqL%* zZrAha2gY-iji@`H$HlgSTNX(&r{y~>qc|G(ca%NoFYGvAurRp|r?Bq3tZ*QJfAF3N zo9@7%#&9gKJ8&n}FnA%CdUL~z2mfWiQwlC>qWO6H^p)e&1xRkkmT`aBV6l}qc+PCK zu^~}7sJ1MVtUA8^VT^HomTlS}o=pYWubGoZ{8~82PXi#83(0n1Oig@)@qtkgV5aCX zCOsI?Yb7jbNwC>s5NMBqiiB|5kfu~4s4v(hDBDyiZj*qd2Rp6FRvxp zl@j7$JjTe+#g!5~{ZmWq!hTLHUa>gJB;47A(U}yy5@Lg z8Hyh3G_;b-a>k@glSfZgVa;wjfRM1gZq&!w*9Y*s)6s2Ep|*mM5MP`0m8#QB^Y@v? zAvI07s*n*o-~#~?8GL8cL-NWg7y$^Hx4@$GfHEdX zrYFBGk^HOH$6&`oh1+)kn_4~vv}mFR*7MxTC-ovMtp$+S-r2_tD!f2L00H)gfnmp^ zM2SrbT2$c*V41H{VPCkcGW8Ub6O3>v83EjsGvuvl8xI0l(3+D;BSflYCDB9I@QO2= ze9vF#bArfSndu_d%n4WN7V*rPJpdcK2iU*ta7ALd z@Q~m#afOxnz*InelgvSuR&lgTZO{1!^&B_{HgiR%XiC4p&1W}Drv%#3lFU<# zrUWtLHeocllAY$Rd+#LJo!P?HQ2sBprZhL5_c}>BzJTbL=xXy&k_L+ucl+<)%Ougu zAbS&0W971DeGXDcOL10o25iZw_g`i%Jm6#DLQiB?T>^Q16aUuEIvT}k< zUPu7=MPZ*iAD%q=mZ1|Yqvnmx&*G^bVyrZ=`wI$lX zBqBnlMzcZpaa$&a0rHGY{Qv6I7VEZ-UDxz}B!Ex__}O02ZQ~2^pqK;qfS!_N#eblD zQ3ge4mnwo^koV*^0l>Y?TYz%E^0FwTN#Cs|^%y+!W z3aVuzEKU&4O*MKaS)nK9$8P|lV(h9q1?QG3rPe#epM>J`QQe=zv+-f`UFpj zrMl_0VI@|QdR_OJPaO2wNiq&691YakRTs|;L9thdE_u(I`Rl*`nxZfGGdS*5X!zqx zL2;-4``nxu8F?${z9ZtBgA{U50kF!Kt=CZfKUG+kZfQc+XLlMlied8ebO@8IZedOT zKVoDK6}1(-T>pTr^aq7$L|ulq=XYD5k2TQUfBG^~;ZEedp}8S^_SIn1v#O6KeFA6Z zZPgGV7Y>_(aCh+rvL7+1cKsbZL3KP*5Yoq#{jp#et7xZe?Zb^s58}R_E(XyArKsrU(Sbq`Tu6 z5IFKmY9u=ixRWY7PL>>#%XKGn+(~(C#5?DNi+~pK#z)uf@Dn129x{7zeV0Lvb@2mQ zOH-MAU~9k|dTLF$z?F%i_PhwTtJ{_$pY#ffUu}}uolHAU>-l@<>L1Jb2B{!tJqdhX z9h`I|5vLt(q{(HM_hizuZO&;wYHJ3}L!*=TF)GFABJ7Sn@zyr-uAwXBBBXRPi?FMf z$kz*h;^pfdod8MyRX`mNhdsV{EvPh2e_cJyzo~;BvsKsRb(Q!*RY*$m@t|`dw zwBZ-&79hgu-A-`?HQKDFn^cp9XDH1FYG(0)+Fr@j=l|M634m`avG2@wq32~ z(x_1zfYmMy*zr4Nz!k*cpHpnkrC%&l*bdu(_i4bbB^1E>z4h1c^Y18N$ViQNcvyFq zdpoDcb13-_<^ZlMu_Wyfd>+FyO+Igz2V_;>ONd%PB@emi0~t9A-+tzjy7xpuvk78u zhg@?>QV5wBVNhQPV{sfCyc10S~iI<^gRhdDaujfyI+;XQy^~2;aKFEXL{UE#w_km@m7HPf1_1=%CH$UssIa z#QX_^&dudMGmEkYH)@2KJH^ z=OrP$i?74?u;6)gj(;ETF)@yjiDiJOH|teRBAATm-_e%`$4UVr@LuO)KZhZ*M)#hx~!l@tZA!E?Wr8G9@i2aIjYkc0&ynq6Ki~mPnH} zG4au!P^u+{p>A7wsK|e-N0s?2&akc`GdyV`J^rQz_&PAE-Fta%)wwUsNTF0hI4uE2 zo!K2;O&w_!ms-4~&!bxXeJ1%mUSTM316y@yL8y-9bj5<6)>;(f^U6uu@s0l6A{QiX z9n<}t3`n$WeC^Fo*0SC`U&0X_H)>u(Us6zuL#*HLcY~H#W)LL?nNCsmiM%KZ(*($B z?6Bcp1v^C;{P}sGl8>D&Nwn%1jkAo(WZ-;8DdgD6TfXsuq#~bReUTcQb&){eNE{^Cmns1#B;HfAp z$cjh|Oxp}5A52wFVOfj6Qj>nrT&(RHB&fpuTs@ zmS|)ULkMKIzd_Z!UBIJT(}FzfT~{1p$9!ZQ(iIiKlfn+g_`-krD5ZdgsZ$>Ix78xb z?tLQ*E;NH-o|;k>na@F`?RFW3%D>q}>onR)vLb|@iP){I(fqFw)CI69eNOafx@F8D zUp4AsMid@%3@k}Cka)sGb^rXPBU^0>d)5jszx{jOp_Eh*RP@*>1_Y}Ci;kXG3qt*4 zZ-WYk-m5+3VT{5>gLH-Ez4wcWrqau$QCHD5fQ2nbh2^|S z($y>`($;^Xqb9V`V>2gahe({`%qJ#f&bc=EAih&k!f z$4(ZOmvb{(XCVRqw>peL$+1#$~qh(}KZ8@p=|XIaJfh<$HfT9;~q z#$8b;jY;0T1#roON$Y8P4={_e_XoG3W{u2?dGLTo@R-}Pjjd(l6OO_BV=_S>p%dxu zoxWqIJ81XhV&6SZQhdJ5DfZ`y>J`}pN`|wy)}}Z1T-j8I4bG^$>vjSf@Th*(LH5^k ze$y%26ld_F#fq|CjbZRjwBJ7SX{n=h@D1w24XQtG41;E%8f@%3y>gzhe}H)G_>Z&u z-^{A+#N8U>0~D`q4N}6;2$E^Hj{X+b)t&o*R+&Kuad<(ez!f4L6eQRDNOgKp| zbF0vzS@mJZN6Fz{(Fte+HKKC4nv|tDk`eVj0(AR+_f;Vi(Bhj_hY>>HyEm#~aJYN? ze_#y+j+)fHTLyLwu0zQ@SI!O}ua?;ti%7=ZiBg37OA1>4Qqv)P-y*Pjcvm7M)I;EY zu^CQrKEzy_6aomPv^?l%Uvp8_Qc)CC7hAX7`I(R#t z+ev@bt(d)cx0n)jiTPAt4ZrYOm^?Yk#YLG*9G(=)EOD?iDw39nM+{aZZnf`VlG*4- zvQhrHu!Y>-KD0b&P%`M>`5B48!0DaP0f*mRpb_?Lz4PrC2szAazgJm6EBTv0oQJRr zj@^%T>*9<#t@+wW~(hDl$ZS3;d0H7%1io& zvD#k5HzhwEIpK0A5bgF@ALL?|6AGGp0imBTVHme7)FcE<0?1?rYfJy)2YaM#Bs#G80IkR z=P!R@-JuK%;URxTR>+2w1f=jbL9U7)9xv+yPsxxf!x?nojJ4HFU! zi9`C^%72gWS-uRi0~$vnGCi}%Z+EhOLT=LE=h+`!^sm0xiGRIYR8<@UO6!;3>-Q=) zD+(}5>ebZQb7uwqBMZd$>q^Z4_7%NYVK`?<{1tFJ(cR;<>iqJu5YRH%vV80)d`p#d z-*nL3{`}g*Fs&x%^SxMGwQb9=1>`w0rEYUUsn~CAy>x9}^l10^-dAAQZGA@~uKX!^ z@8og$w!kyZ>51^q8P`{P@BAzqiTemilFUWIgjG#%f`wAM$h-I^WdVuJS@X*A?YP7^ z;PUYA0Ychd^MRhTmuJV-a{X8LdRBE!Nsd#Uj=sJ}67!4ht>)z55Z;yR$t<$&kQDoY zDk33vu@J=br93w7uh-N5Y1wPz5)=o1D}GEG;}na2v1+NPA_2p=i--T-m=x}WQJ_G! zp89mnXXt zp>i!<1=G#H^_*6SrHSMUy4_)W4m$0>*9OK zYkSP1*r(XAU~>LmZ;H-Gu?6UzZ=lB^#xt*IXV<~WD!N1H{bJYLp8PuFAs2u&NG{npOJ8@)AhVSWZl5m1{6B^hOtX#}SvNcKU=8+S~4fPKThfRR@ zXIoyrC){_o8nE3_xDw-UExi!fyPKZp%IeNonOnXEQw}H;mwr?iKeceTA94pPI<(k) zZh$+Y8btAZMfW{S)G`79mO*y+=ZWPVT`w060k$G&<2xhG(TfmIV*p1p5F{tk*I zZsF^6qAuP!4%WL~CKce9xYF#G7*kVHCQlaT4AgCw5p{HjMAjO+Ysp6kXFq;H*$s_| zM!J-=(I3f}rEKiENu|6y$;wMphQQ6$k0~*(X+)Wd0xIY-jf&P3v)h0$ZMC*|_55?2u2(ZSgKl{qEr!{_!KA5<)# zgL7`p)&P-rmSh_6f`PBK`VXZ{`5;`?!+`zG)h+5d9+E}LAg^F&wdQCG*b)Nc`6OJ8 zJ&}Fy{VAWxhxm{*#wD6W6R+ot{TFExu8t(yRW7e@B(5$@Vv~N5@;{2suXBY69wX{i zleI6p9%5Y8W|NQiJ!Uc9`v}|%>JGmys>;jOMm+az8cGCzq^zbmJc~!U=K$(l?UaI_ zP$b6nRL=gw`5p6y!*4emBL}uB2}*L`2eNUIY%*n>UV&+!Y6Q!6>NJt6VaC^yR?DvK;!8!qOK`x?8i?^%ij?j*DQ! zmXVsj#8(DRKM?jRsJU_Rqz)`8BSYx!WOKpS5>FSX<~=4cD&miB0mu3<^v*5qWP`@d zfv?=`=pd=E zrZYaDACm!P@&vM5i%>_6?C-bUG;*|QBA013vLFhiuKjnc+3Ew>Sz4E_OU)0m$@?dNm7YWJVd&l(Wt%mc&uN`=`w?lhs; zKaA_o?3tgwDR1u|#J3%TcXA4S$wg(Ke73Hk>+JriBkmb3v9YlVLA6G68{|eF4WwS@ z{LssR!13wk>Z>~ZYIircLY6c69jmWGu}(dMNHqgLw+Pz@ocAeeGal}9Fi(FqdeVX) z2XU8=&~j41L+sPM(E(e&_pLL{P75c6ovQ`o_q3H6M&Fuqyj8PXcTvpj9fq2h(e4k2 zF{6urh37?N2i3I{YqAA?nF|c`j8k=#lZ{}EC(b9-t|4G&<;tg_?!q9!R>NN3 zgv!j)nuRzNz2hhoe*;B|b-IJRk^6Y@RaM&al@@HqQYibn5fufk>tnxfUW5_qgI;1g zzk}JkRnps^2kDCAWo0wEfg%Yqz?}sMq{tn`kdT&{qsLcq+Mr0Qy!Vdy(r%y7o}D&o z!eHeT>W@@I$isS}z-27_LF)}DydD_brEg;XV8e|IKnMtuKUBjSLs7|=Cx2{GDTY>x zhhyc)T)`(c?oY%_9fs_rL`R$4~`m zvZft%i~4m6h8BF_sx7ZYnir=HVs(d{?2UdaXwzWBcQeS~z+Gvlekl2SbxSIa69Z1s z>jiXxzbdb5;OhZLc&*1ZVH$;sW-;Zr<)EcRs>3#vpCX0Y;;cHw$fc`F2f~h^r_`*Q zJkyQaPjJdW2z*e2#H76gGGM-kHl{s!I>rnt<$Y&UBPeA}s(afh7LafjzWK(Z=^~W~ z1I^dR$vGj`VHIMCJRPJeKq=>VzV3ZZ6wZ~{3YP<)9=z;d^D~{1e&Ex4(K$SF*Z>NQ zU(Fh=l~EA^a;9NS&l>tn>q^ij#eIa7gX7;W;!e59uD0^#Ve`CcDoOl%$i^ho5#hr1 z!AEkTyEm;RmgyB2EkEC#aUJey>Q)O6pd!PjzzM@C_(8@i5z6FHK`1ib2%B-6Z(4?>qAl`BIb=!bVx)$;@O|EcRMz@lu{zn5<5P*M=2B?JK}36W-j z1?ev7?h=*~1qCFORB%~R>F!1v771x7L0IXKZ}2_m|DE&2!o_vLKD*02bI;uOFJ^{B zdMTs1ex7bT+x$ZoXSbIm=Cayt11O#Cat`^ z8jOND7WJQEOpNwlR(XUMoCm7Xk&o7@ zuXcRHMm6fGfPk)%XD5`w04xa^kk5_TMF{OHQpv@FFdLzAD8$4dpY@9PNM8x7#Qeun<%9588tceqa z#S8XPJexp>IU%@S$F((A0}iumk&nE|iLGAI6vs-IBk6&$YhSruz}L!y`muokSewboU& zIyd3q?Xiqs+|({}fz+w9sll#;t|KO$xygR56^C={_=lhAj@K<6d(?;n>j_1-Vwd;S zlZC_e!xyS6wVWeT-i0HcX6l9}=#4ES9Kmf=3kvG8 zg=HvlY0lr5H*6}Ip-Xa*BM+wX6JAW>ag^2rp>A~0*}J~C<)3uAR4yfV zj6b%s%jObRjkO&vrK9Vw8wU7%lUC^}jMF?+6|tTs23b3_^$FNHD3%{15lBlQvC(M0 z5bgHkrUIL&6ceWQ*Wg~x#FQ!;(D0}5XhZ*wBx3Dv6nqRiY9j6a)~&jOxi6MG+n^Y3mzthyMOj?M0;M#jzL0tv~g)|IieLrS(~kbdoLsYt)UvY+xNY<>9Qi zAb;?SUv!Cij;fueqD0o}|H*$mL9pdy!NOriRXIrsyk(xgBfa z%B$utdSvqR55$;3E<3ja)Qp#1Pf&StP41LLPCs8yAduR2m-}io7Bp@&ZY+Blgrv*b zHOG{aE>>(duG8a%V1RdiU-6^n#Rd%b}<>%MTDV}%4 z7A`7y5{(k^rgfS~#3xcr*Vp0p^)u0w=5ZY(|D)#u6H6tw&rE&sKPffoWbk;!mLfsVu`lEnD#o&KRL^t| z8|1dU{VADP$Og9g-2nWs3r5Mzf$%iJQ&y_cLvT1S_9`mE-$Wqq@YRT^4y#=OQZ&g7 zV95e=g#j*lo#d&i%@6pWw% z^qp2SJ%5T3-dRTHD*u&UZLuf|k&Z!jA2ZF-ok!O_?Qh-2Ud% zx7#N4`urY>UL@6ZQJ9~EYCZ0kJD z>SF^9={too!Vq&9$=tfOXA@uNciXcGPN?+~6~`IyJ_JN?rXb%N8*vvkmfEp!Z+lxS zVI)Ah6dBe2%=4bMZfBq$aptYZXnp8slV&z6%Hp60^Rf|~wf;jpZ;qPztwkk+ms+Vr zB{)rQ20(9k(t8c!N1w79=l1irN|g@Wb9r~$v8nXy9Z-eNKcrcqhW?mH?hiIaCA|!= z$M7O9cU<0d#$++0FGAW4oSRNL#w*8L97{Xn+Y#H^E_Ql<)o;fTXH7Xwzp%8>6e?6v zjASm{WBVuT*>$vjNI8@c`e9c<_#0a#EUjH7XJ}!lDSbLr^15iK!CZ%9d8DEai67_j zj6Nd=YiwU{dV7BSx}D(x$nC?IH#>&IioR^R3XT6q@?=>0n>_7|idxl@NkNmoup2&= zjH<(2z_? z-3&D2VU7_97U;lq3ns*ImGC{vjyK02;UG`&Kn*bD;oi(Sg=wdZIlONU%S= zgKanZ-`X#w2^Q0?9gE~^uYor$6^6*&BvoT!g1pp}Y*L5Z`ImsMUm{rNY}&L7)oP_j zsxjFQN1)dN5{K6mQENQu5)3hY8lX*2?CU~apU9TG*0&edr1avJIo>Mn?A!XuPaDV# z8K9y;z1>Tst=I&2d;e9(3g^ou$h!6KcxmdF67q07*r|(i;luOXY})!BQJ^;B%Olbl@d+#|MX{;^g^Z?B2ZY>! z7jw{iegVxT`$ZD!-H!ayYTZ9?U)}0Y-7J-6E($*c`G2h)ZdVR%VQ;?&6K|;2-94_) zGESsh+)Ze$e;O~mL*%q@4d=LRO7~#l@?pnePdKW64B(wI9eE+0MzAD;g21-zNGF=L zx7C;~hCssK@piUdlq0`1iwuoaT@3=7cJ?hb$g0lNG@TP5{huQ=d{TNkZOX!<=Bc5< z8YwMc1h^x&g-^TMv#1*E3wK9;e7XU44R=wOW!kGRSlVh7(_La%WLXqh1bjXxOqc<1 z|2y6BYZk`R>)c5mg`@$T$OlA&32n)sad`}5lr9C~RSJuz~5QSfUhs15NpZY*qIbm=C##S~?A zrdKD|t51kffh$p-!~kq7cqjhWlkJIq1QUhMlmRV& z5+R7XN3f(bR1KOw{DtDFGXJ5Org6@D%?mqU-~jRFo_k&CkP2g`Thj=qxZ6!ocVyE7 z$osgSJ-hH&Y33xS`mVNykB?qRyCd|(XirSVSWp2bIviX8QY~9*wC1WU3-9gV7UOKe z3=HWPKRfMGq!aP}-28SurDCrm(awvqaNM3XI}u^)Dp06p!CBAB<&2zVF@aPP_2YVg z-U-T0g>1+tuh$TSsXTSezTMr4!zQ7bBf*eJj%CoC2QAV?I5}9{qc0n}^A3pqy5y58 zFc(~!no2h)|JU}3Z-$Wn4NIdRGJ2Ln%gC2zS+Sp~tS+s>GR2>h+J6>)-lOXtB;9PU z6G3Wh=~HnYj-{CPFfE)S-Je?k|8EShE zZN_6rK-1koMSZH6;1?2Ba;sxv2wU56yTh2 zbA@}9wX6(@Qn+7&IP)BF@t$BJ^h#pf>rSleNk!r`gm@2nK(>h0s4_Uo&I^vOp9sk-5+ zV*UIFo(o;-5&;7=ue=z#8w4I1bFeZHQDO3NhW@$*+4-E|J*7UqS`Qcn;`cXi^e$cU z(f{R7Vg?ANEGIuchf6VWniWK!2TfoxN?Yjho8|a8nz&tK&^Abc>kY-jJIQOUW$hTJ zA@$FWw3kaa%);P+-1y-wmCpMgpmWX95djDw-87tJ0yV4)&LZ-ys9EID#{{@kgnqLc zsV_tG?RHc+sX|>9OE*c&J9cJ26C-J4%vK1pk+c0;?@mA+(z*WI?Ib{MVaW=Sz~#gg z&6TvnNbIx8jroopbekdZ-f@GIZs;oym)gi+K9&cC<`xM`Ag`}K#W=>IR1kZp-*DF( zW>Cgv6=I7N(9FS(;VQ=7y4abU^(L$6tb`Zo`rH4yd-6;=m>lTr-;i@y#(->aZ7RJx zp3DaYl=KC0tqPp}*tBcy)GG+`ADPp&k9^BYaCf+iCZcYrJu8>Ttf1kHkzaR7yY*AM zGhs`8iGt{Ln+OySZIj19Ur!qrWRwEhh69r=>?`N64@sD`(-IDSL#K6-mclRW$5B`w z-H^Az1hw}V5{t9}9#f(@^4oZW%Xc=dMAC1ZtlE+9@d721KcJ}U9jzx*5o=bA8}?OJ zO3tJ>@e_cTabHGJZK-%dZ-Pq+M7EB}kz_;osZW|vht_eRPEmW^k%_58&5t1IwJdW~ zNmY2zGOpE6#(|a1DLDu+>`NcCvl!mPVIHyMV#U9Bu;;(%61m;ZjwVe|9q&XL0Vb3X$anP*I3{Gna_bXvvYpDg>$=$<9~Mz|jJ^CgG5cV%C1@vxrZ!G#sX zKNsj`{jO&!OSy-NU`WMd%zbJ+^zAp^3gW zWi1O1QrA+Xm3s@=5e?~ZP>q^F+C(i{W>r_&%C-f+6@G%?FL9dR0h{9~q(XWb+iuYp z4OnNyA*4U;$<``_j0}5-w7LUi4ZojadriIHWThJwe^ve@MX9=Wu*oy3($7R^rYoW> zFqX9bl+cayKVW5b>jBdE0}kUaa(9OAsw(%3~g(@)B`y4YA)$+xTox6QW{(2wOX4if%5+~KgLLb`u+78U%aGrWX42GZi-%V-I8|UwsW19 zZUkq`@2U!=LnnWkOp%Q1(mCpX7+fWBKIVEPB=TQW?ZJH?=(5~K(6USemZM@JI4|2c zTSMYs%x%JMRfhPf$5N0y0=^?zo_$(<;4oCI%IekmYsPiKM! z%|J&n0SG?~A5bWS%)m~t+N-L@*Z9gD2OejZ1cYUSk)4S;OuL{lE^T?f>DmdF>6m%@S?%4{AQJzD%1>Xd189bR)N07Hl!PK}R>R$YAt$cL&$k9ia0UA!9< zOGP5=U)r}bqKd8=>Y231l5^=KPMWNhox@ThONaa-%5$=kq7 zX*HLM^1Jfh>858Y&=76P#h!0LpJb*HcU@*Wk-It$Z~ueU-7+tjnVXTo{LhT5U#c#{ z7`KIj(&QS`0lXXN_vfQqtmKxWb6@htkl#P(^ee5|f9F}c61+dj+a+T_kpKbKoN~^X z@3$S%{seA?lO^{ppynI3=#EL}P0?<(XU6|)i{I{tb$KIr2VJj35NHM!x0nO>={f1iLyB(H#0-FXpO5e7!?bNCtEhGm3$*bYnBnij&kYUJ z7L2l2h(4UvEu{7~IPkm5QnXD5z+1*u4A$pc{sE^wVMlqa8uh@g$h0L|UzH(7xyMt? z(o>LM8nZD>RVvGMUH4=r;IRdOE%+IhKB_f8;R5_hFv)wmxD9dE2?Y8{af~O8`fJj0 z12dsWfP}m8BKZD?MfTVh78V1!SoOkq6185=I!DX@x?)^c?>iDOP8|e;3a9*TnEh6* zBz*5`hnwT&%b~-qOPV*l5HB?0jpS1_Yt0z_2MPhp;UBL2Y^**Jc9 zszBLxZk*a7{8ntP4O+Ucn1cwuC(lQ?m9?;4E~@k4TR}{VRjkMboi#jJ=yI-4j%;L$*o{xuBZld%otnx48AKi1 zNA((^u693l&OST^c>L;aKlRyW-RDp_yf|h*y`_M6x5qxd0glqVpgN{iPXj_KF@Xk8 zwdgp+?x+4+%T_lgqOd5?l_N}%w+=P&E5b1&eUia?T!pmUen30;3&CcauMyLho#_6H zJ+Sr}G5o`!cmSA|%Tl7DK1zN!Z3q{^f`_}6`=@G+1GnNg%CMVB8XLQ8mNSJv;ws9|^C z&HBy(pZ z-3?a3Dm`o$|IByM#kH&q#|p!w)=gF}B-X@r{H`)z$kIK#@#!mFENR@j{3-0(K4`>u zSg-U5!_K!(>XvHo4Z^d5X$r-;}Xx~9bG?3uDQTx! z+#CSdeWGK~Z5@f`nE(E*-GbGqBRjS=x3jFGnjp-QQL+k1RRiPC)yItKCWotdx zI&(YVI*zIz1!MDXVgXO8_g|*O5=lO!;|E=orMP^=E?u=Mb7cIrQ*9HIGHz=v&-l~g zucKtl7<5vGcA-k3$^VNU5S>2!3fK=uX;aM}-W$I^1T<DPxO?bQ03(wFx)e1HA8pkjGB{+M=g!%`P##no93nblq z4t)6gpSz@an4~m!Bt%p9rvU1yuSy}?<1^O;lQKG~S#C>9!4*TUHGL_JS5?2{Z+Q}> z9HeFj4&6&%}kh;CB~@)HD42}3XxU< za!?ZPiG%y1vF#r|7#DoXQ&a;g1~2~)eS8gP*=E5J)U{mq$B*NM0Fl@WznrsrLej;* zM1B^R1+vct*sz_%vV6&W{tPCyw-||{{plIReghEod^+%bX*)G$Po88{N7d3M@6L?e zeZi)4dVDyhpnkd$eWHxN!MPT;{??zdN58TiB2Uql75o>q`%JdAb{Naqt=YTxww^@9+#9i#5HO;>uOorNY1 zp<*SbjYUGBrdBd(ko3`UKx^kIRO&lakJQ?Le77up$iUP$U&U)&{C_I}A8H)FQ2GWg z=yOs{^Y+hWXgfUdac)C^{jhfqu6$=-dB{sN^d5qeo)O1XZ#pY$+XYWU%?H&nA~dfQ zG?!{$b@<)1=v!4;Siv><@j@IUS}1mSqnf^-XRDklwSESY;2-RiF-H}@MZ!tzv)w<5 zd%@3;IM9e3AXcksd!MaS`@Katv{?G_49~4975Fdm?AN4sDqOmWC!QmQJWRF%PgfoA zOnu==N#di=1y7g%AH>Ikk`S1Ru3n-&tDT(}Fz!?S`eQhEDH2N~wLp~GFXF&GzRCrH zNzJWJBbDxD>}Sn@af~@Spu3O5^fjN881mg%^ZNBHnPp^&P#XG&C8Rk?Ibzzodbc%~ z*rv2o=hSxbXm{LB|NfRgVd#^eNhjuxZu6!^brR`(vj5b_MARW1<%~@iEtok$i?i_I z!1*pts!=%Snn}H@vwV(x3hC@aF^_#Gf8m?6#$=NQf@?#iS4v2=-S1UkCDOmELUqYR zLmm~zkln&`j_o(l1i@fXSu1btrMuiK71*q%@Na*SF}R4s7NB4WIV;0(Wu1U5JpLB4 zEw>L2CU%X&LL0eqGd7xkFulE}vnp(*>WweCT}fH)fOx5#wTNY?c3a7dD6E^@Rs0M2 z8Z!;V=9QMNrrfFOaZlG870SYfw29slIj0T$2WmR890{N%Rs8W_!_VE1g6^AA4ML3l z2e;WCl4tlY<=;pY|MQQrC5r=gmUqev;ik~5DLv-@k}nvdyIOVYy^1K@sNeR)oy_EM zp)G{A>;7iFl^)g$+PGQO#60ACm=X8!UC-GFDDb`*GbbDiS9wY9h1)6B2f2&Q*Ma+c z)lJjtzaS5vk4U0(dLDTg}gJt`E=^> zPo3|GbBPvW0^mAkvY>^{X2`QYRca#RXvqmR!?U?w16B4+n8VC? z?&F6Vr==%77L7!doi?oPpF54<)j1bUj*!ZpXHy2LzYh?_sMnt{4NofR_3=i2)(`qH zeBY_|8w_utdAsL*9{*s|9E`@on2l83TFlg&`273#Or>_^$!EfQ9933%Hj6)lb#4QU zw~K=caJ2FEa`6{tJ*h>$9X-;$o`rP=d6#pCi7`e`@OJEu<%2R#ACTJuV8Ps1nr{hb zQo(D1iHW;Q0t0$Ur|we&`b60;H4n)EntM=?W=GyV+A}Q|d-VYmY<+!Nh2e0k|LDi$ zHWLnf?u7@h)ImC~w1OW4INuEFH%-3#yCXZ)jCEcn=A|-#pP_`t%8l%X^zGijsutd3 zlYX1~uK~mlW-)B)I@oD+dcnz%nEkP)zKuxnz+n+lLdsd%YBI!+-Q*(mOij870P!u`8+hT0(QzF@F>?LU~B9{PWv}gVtfPgNf?qr$qqu!+&T)4erIHLu{d;d?9Fb* zn;kG4RAgo^AXLShuK2tWW4mI5MO?1~b)ZV1Ho*z`)L-gE?^Rn`UPimZi4Dqbtd`x| zKO_89nX<8%3(i|?z=^*}Fayl^++U^6q14e2Ed_U5oTC~aBstQWq0o)Oqe}SguCu6Wl0!apD1Gh~z-6(WeW^>weKy zIDo>Mr-$iO_V0D_w>W(poGd)iDgiNCn#}_{;orYH1_dY#`3wvF+uF74-r9hdeoxOp zUi_A12PbFTwiu$Q7_xg*0}i0gxJm_7+_YuLNYkv|y&0;~5@48#u9vdX22PswSkl#6 zFnjLAf$H7r!Hc00up-Y3J*4*c?ImxX zf5?OWg677boaSTgu@$$iiAFX6^T)7TjbO_oUvh9xM%e*nrT3wS7z-YW?`-!+IpA6O z0M1hM1qpa+J793c>n1|@JJiwKm^#GlVWz9~42~AaIJBtGmFfcpb^ z$i$b|^xHq47$Ix6;eb(son(jL4eYXx&TOgoSRA!)qSgAJIZo)1xnSJT6Z1z{EfMQo z8;SJpgv>+cXgq7Jz;4Q1v9oEcTG3xRSe`RMg4%N@+0k-eo(Xao{FSL1<>D{@GF;n& z@|0i+ADLUS3G5q|g}%AIM8l(CBx4N54Hb)J9c!p65q0`RK9KlT6;BF_-b4S&omTP6 znb%H@*zA@lMhNhtG3;TJQIhGOG;zxG!pZIk>dihz+57-5vwP*<935BM%t?-)28>Km z_UI(Ilz1^xC6lB_Skb(hM+{il?oQ6C-8YZ~a&SLbZfjQfJu6iXY62H>h`D$5G#O|D zYp*`iOe(Va5uvYU8?r~lhJ;_OwAkr=DVZv)QRWfnXd~jAP``nThq+UNH;#19iLULT zaI#>JmNN=)kbiVQ;Xx9f*F_VRb&GZ;aaqPWH~CLpa`JBeD@#z@Xy1Xx6hF~JeDn`Y zto~MP>thGLd~BPU1^kW~ze>*>XRc@ZA2thXWVfKH&s_|&$B%aCcQ@oUTT+2ie0i|t ze<|MAqRm{n&fH&_V?V%lNBKu3kMhv{rH`pfO~oWJTg&Rl{bR+KEZbsB$Pp-qQ{gLq}L77e^EBUg7aoJ;*A1?K9o{H*`kl@Yg^XA`&Q)9(^c62lrX}bU4SyZkT69jRlq|0?&>pWiQBb$vwNa=R#beDG&! zM{HRSbFB5H)*YN}k-m}+*w56Ix*Eu|l31>}(rzwNk{plpL^90PsCb;E?Z~{8`>~ny zW>r<`E2@9epdrgJtaoC0dHLZR=~Qn9pd$C_lrkrOk(7}M<=AFHbCiV05H!P9^V7yF zc6%_0e=L{Hb9tUugxL|J*7&T>rT==j_|1yddF6==e^!Pki&0XMnrI z)E~M7|HFXGde7a{gV2iGX~(ZU1MjL{))!@;p8A&_s`6jF?(H4i9RCC>(W|&&RV?yO z-Py_d9IS0N`*K(-qf>^edG9F^c;s~JHnri0(UFPJh1s({)J{{eRhu7L($ym%z))CN z*dSV4qNu3I(8!1=^cGV9w^fVGjZ3kxHU?hRvzm`Jca(>|5w(ok@dTbf2t5jxvMN{~ z)SZ7fu?zm^9&xF{4o!8DyXo(T(l$v`UFzvm2%2G=w9SJt@AU z{3f_I-ce~Rc>TavdEm{ia=jfmaJJS7XL$vIaee8>4pha^jnaqe4?Ujsc`1!G{P5D( zI9}cUo)kKI3CDSO@U%amN%|fmz4wIduHZD*zuw+d_|tg`!MxPr-Af*OSv*-Z-OqpC z&eCD3)P@mD>+xJp9pqWnOm653KdIoW7kNSYilrGgheX;LP! z1N-HEG;1LJ#DHvzVTA)ha@_CxXzlU{RaT4=q`PaElsa&`Pn7<^vyv8KGg1^vGAp{_ zt-U^BA^65hkke)4z32QmMZ=XgivL$g%kQRLG{WZ5tWP)DK^@dewl?QiNkdl0meg)Y z!xi%<-XS}PLF{bQxpR`WH2XcaCu7b&X~E;BkoXGD_3oyj(4-UNp?9y@ZI7sA&n;Ur zJM->*LiFV=_{^`lzab-V6o?3M-8s6A<4dPJp)_}dY0X!xek5VKY-&$RuiEk@WcE$! z3-)`?G!S%-zJ_{0w!seGTGwFK^P64=H7Lla0NX5QRJrJgzx!wi$*TI8_^Y6}%F$Pl z93Vpf+C3IGQ#25mPV!V{FD?(pR)3&ys*vd}ix=0Z%+|v$B9DhJ*Fp>##XhWCRZAuq zsC9etl;V!~53}h28?Jy$9~Y%}vah{r)=hg<1J6Su9=O|{x=G$Hy+6YXSv4s$MoIB7 zathfVtr|aV-_me%e`9(qapm((pzk&1;Al+XN{z<6H{(Ibd!a1`|3uwaL^EdR-pOBb zp5mUyi-|q{&9x~?U;XQ7TNK1b-gb)4xU>>W4=V{VxKS;gWL}TR?U?6jd7#G+H>yt% zhy^Q(1&1<>HjB_GiJn>&?y|$c7BhpV{_o$boAO8BnRS{7_|ydHeSrwx5kM(e{36ZZ z0g;9^P4j0xPf7B=xiMb!o1vx!Jk-^c~|~E1K}jY4ZObO z`X$$a2OeRVOIcD@_QAnY+hpC}kB)q%ZWG(s*syPtg~`p#&8?pFxBmEHJ9T^2@aFkt zef9M8#BL4_ zX-r|P!VJzYC9hw+-4=oOUgq!c`}^_#zaJYrp%d>6Xh@iFd9E)}R@6`^l{0_-zW^v| Bf8GE9 literal 0 HcmV?d00001 diff --git a/doc/html/_me_light_sensor_8h.html b/doc/html/_me_light_sensor_8h.html new file mode 100644 index 00000000..65c768b6 --- /dev/null +++ b/doc/html/_me_light_sensor_8h.html @@ -0,0 +1,228 @@ + + + + + + + +MakeBlock Drive Updated: src/MeLightSensor.h File Reference + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    + +
    MeLightSensor.h File Reference
    +
    +
    + +

    Header file for Me-Light Sensor.cpp. +More...

    +
    #include <stdint.h>
    +#include <stdbool.h>
    +#include <Arduino.h>
    +#include "MeConfig.h"
    +#include "MePort.h"
    +
    +Include dependency graph for MeLightSensor.h:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +
    +This graph shows which files directly or indirectly include this file:
    +
    +
    + + + + + + + + + + + + + + + + + + + +
    +
    +

    Go to the source code of this file.

    + + + + + +

    +Classes

    class  MeLightSensor
     Driver for Me-Light Sensor module. More...
     
    +

    Detailed Description

    +

    Header file for Me-Light Sensor.cpp.

    +
    Author
    MakeBlock
    +
    Version
    V1.0.2
    +
    Date
    2015/11/09
    +
    Copyright
    This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    +
    Method List:
    +
      +
    1. void MeLightSensor::setpin(uint8_t ledPin, uint8_t sensorPin)
    2. +
    3. int16_t MeLightSensor::read()
    4. +
    5. void MeLightSensor::lightOn()
    6. +
    7. void MeLightSensor::lightOff()
    8. +
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    +Mark Yan         2015/07/24     1.0.0            Rebuild the old lib.
    +Rafael Lee       2015/09/02     1.0.1            Added function setpin and some comments.
    +Mark Yan         2015/11/09     1.0.2            fix some comments error.
    +
    +
    +
    + + + + diff --git a/doc/html/_me_light_sensor_8h.js b/doc/html/_me_light_sensor_8h.js new file mode 100644 index 00000000..2911468a --- /dev/null +++ b/doc/html/_me_light_sensor_8h.js @@ -0,0 +1,4 @@ +var _me_light_sensor_8h = +[ + [ "MeLightSensor", "class_me_light_sensor.html", "class_me_light_sensor" ] +]; \ No newline at end of file diff --git a/doc/html/_me_light_sensor_8h__dep__incl.map b/doc/html/_me_light_sensor_8h__dep__incl.map new file mode 100644 index 00000000..295040cd --- /dev/null +++ b/doc/html/_me_light_sensor_8h__dep__incl.map @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_light_sensor_8h__dep__incl.md5 b/doc/html/_me_light_sensor_8h__dep__incl.md5 new file mode 100644 index 00000000..9a4c238b --- /dev/null +++ b/doc/html/_me_light_sensor_8h__dep__incl.md5 @@ -0,0 +1 @@ +e5d0365cc85ae440c6387965f1ac3a32 \ No newline at end of file diff --git a/doc/html/_me_light_sensor_8h__dep__incl.png b/doc/html/_me_light_sensor_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..a051570e4d57af546afc914c7d17490b3efae2e3 GIT binary patch literal 14054 zcmbVzbyQSQ`z{EAv;xwpgrszb0!nu`GK6#t-60^-NJ@#6w19MjFj50Z!%z;x(A{~@ z_B>deH0QK!q7i{{HSnhRAbr44wel?Af!aq2Ufn zZ+xx59-bSrF*0u&;CCcR#IJ!99}9SWcr}(E`cWLel(^Mv_is_U*(Y)QCr^@aI6jJ_ zJ^AlJNw0(%4LlQds677vx>lGnYIaB9+|$~%%AD(01>)BS?&&j^pIiW@TKW8Us9Lxj z`c+n^TT{NB=D3$XCs;Wba!TA%jD{ET?GIut;eHz1~pE8|G>?~2UBCp+x`e<0J zfFS$zJzmaR-7Shwix3UPG#DgFQOBB|L)cgMw?K`|y$$GcA^t>|(%BsNKdm{PCrrS( zW$A}4)#?SF5oGtZ~kiqB4bZ5jpDD)2AtlhE%l(03|NA}Z>8^md-$CDwW75*QmO;m zeFmRuvjugUK*}e}SOM#!)7iuR89~Z#T56)5^>*H+15>HP>}}@mQKg}EjZb-U$RsnRpxvGbPy^^5X?f?nisW-p~}_7m?HHCnZWuK#s`tLgcAhlRiKZ-5DU zru8QA*sD&8>Sv|A1A|f zX-6ngDE39XUUBlD_X``*cG?-p1F|S#jQy1tBNRAMp&p>2tCRKB@|Sfls|FliwTSmUu4lp`egWETqM-r!67ueyc6Rg5#id_H+$eEE)fnMi(T}& zy5ANRIevXsWn}$s&n?aKnk+j)w(s46c$B&2O;2{mV=qj`glc0eb#xC8j|;n!oVTVq zdt3vLI2jzpa+V*KxH)d^m|wKLk$%A4-!z*|X|_S21nOEf1b+$PpI9ac4exTcXzboo zNq+I&_PoVmx6#^H1&ASC1yr0RQ3N>F)rn= zx7vEYy%0EfGJ%0jgstV1!RM{e;f3F&eTzX>EJLKNb~K9?QgrqC1KT+d<$TgIU5)Aa zKC1*@^=$+X+nPb@;(8`HUXx2ssipbg<_LlKQ>Y^%7>TQ`3rz&&!Hc4n$?xY-O{ zB&w$nVI_e{<7e;C=q6_jze%C5kYO@WZ8`3%=l+E3&+)_DZeT;BXUA0{>58^F{iU`l zXORwU<2YScHA<+q{L<6EsG)E;acCWbz`n2Cs!!OhDv@~mQK{SDFe2yYU{mhj1#gV ztlQyR_*nYVVIG1+n{o-F*!=WbvhYlTnL~V=H_V2(Q%i_oy93Ijz!kbs$^o7=^Bxu{ z@XXYi`#5CpY+>Xwol)4etBc{60{RDybTt~7zROMe%lg^6KDtJVMwi3><%a>J7yRY$ zN<;Zzm@6&NRKe}L|x z;XoK?5XC-X|uq7YV1_CJBb(JE zwukqX%{^FyZWRfzecNf~%d&1y()33G_JQRDbNcKv5TWbMTbw-}c)|$IB5u}$b#$Z< z9lZWd>~45vl$VMRCqEP&dVNIf-|{g-Jz4UWPhD_a;#=+;G>B{NpuQ?89U_`wzwS9G zS{4=9|CT%%0m`~Pv7(*Oo_i``DCx&z!#g{6Mse`Kl}B6gRk6H!*B-;lfZ)treiNOt z)Fu&P#D)`%46Pb_9U~5(#aE4N>Uji3>*B?)NU{Z^Pd>oRJf}!cvh~x5XM#RaKgcJT zS!gd3@scXn^L1Tuf+^`R3u5$sTxT_HX_)dG@`S~nRR*O}N<+U;d5*12AO(+7YnkvD zoeYKZ(C)mi#GeZ~(4pPA1(pZa&dOFc&AbF7V;I{6O_zmW;9SgHv<8d?Z75VO%)9v* z2T!rWrKr?I*PZgY4#|iOkFSuG;CK@G+>CEb(I90BP&{f-sWb@(REU@i#S?YI9a8S% zf2-5|d9k46kMx?S%J8e_1BQZLEHP5WLClIHVV6X{$eF0Nkd=X#B`f@QUa&;Z6q3XdK9tVr6VDaPX zgI06b_QGjf0VIX;Z7u%zzgOvt1~ zV^H@iH(|FsR;zfB)nlDnphWty`RkuO6l*${m~Z#eO@*+D#M+{gl3fO+;bqOc*JW-F2r$s7c z6=J~TuY9RQKp#{WV+#s>_FLYZX|RFbcP=Bb*gCeM z%&&4NM|02lp##D~K#ry)jEPQ`nZa;A07Z?Q_RrucHo;IZkKh82U$4rg#<0kb#y7bP zFGTrc?mbDeY>~qEv@s zdCp9E3FOKH6gBk~3Z1b% zz+~;FVz&77%b%lZ{AsJ4`)BuiQ1;002G71gg+l6lZe@mc_jQOjKTIM+5nY{CF7*p| z7ddvXrG>xLP$03s^76B2v2}?4$#CvmU`=n8o4g07&5JQy_49F)(hvj{O=pC@Oh&D?Toe6)^Di?iU)eZ%%m&RkQEJ2#r!+NW5-I zn9%gDTKF**q_<}<-+J?0L_9`PPc3!!I#ioaF(1>hq7YLV5-25@x%Ou@Sr)6EFc4?9 z1E{_rf+mID3Xf@(l#0>p-l$ynGX{TU(TAFHa)0wtZZ3CgqNO6eiqR9T-DJam@$T{k zw0k%zoFV5R^E=0)l|GqOSpesXySEy8au>;*uGEx{X`+*F%adkJhm zztuaPXcwy><~_7FSS*O4qn|42sMQ;t582}Ssoj%hk3T}AUcygoh+9ymM0D6^H_X?J zY=3^q5Bi8TP0lZZsGvt~!my@8$Gx4Oi%+I201)>D0CD-yId>23PBDfFbLRGjg)&A~ zW;iX3rq@STcY0@|>gYjv-DX5{>RlbDm1lo1q{A*Mfy8^uW@GeeosnvsuKEb)t1$j1 zUe>H0m#)-h#m141_dLu%!KvADroaisjZ4{XJ2)FAGN32 z#R1)ENXGR~I4w#&e>4|P>+(1o)65O2%b)9@aJ2N2yCMB=teZgEnUD5gikYI%GQtnE z70*8_v0QAK&MZJPWNEan7o{?>mJGHB@*OX!3`$BGg!nJ+c-Po%2?%yBdZx~lvJ+m* z$zh>@ofbwdiR9+fhILoVT3dU-Ks0~avoAI2JW5v|7_ZHJBP4SgXC2_Q!9@cqPjDWr zN6AIg#|opDB$o_ANKTxaroA9EXBm}7h;D8DBNmyoro$+?i8q8zbyE+7SfPdG^ZKCh z4Y$2u>U*05DQ_d#g{eirvP7AmD{|=+Z#S|DK5Q_JSVnWk>hc+vT{1;7X`@R&I1?0d z4-^dkttK2D#M)1sO+}Y;*-z*!Y*~tNPB+Dw-fKaY=3- z`y6GA8;v|Qq7;Q6hIj3MR>ReV2+x?>CiKyQ^5=#8dVjK+WQ095_*p2~|Mb;!R|@1z z{TG_S-!tjI^F;%5NA|c%I^>=`gQNIt67E+y^~*Q|1boN4;ANebMy1Z>+ULwPIAaX2 z^I%mMgT+J(*#ez+ETXn;K^h6o!|ES#Fm?o=jix!D&UyAPS3A@b^*>$K0BHCph|x5)2>Sl@#%Z?W*9 zt1x0o&~#9>x^RM&m2cP0NtsCIRPZ-;`VGN?(VSgRMY__{)L|*u?q{l%c2yL+=FZIk3{pPE%mZ1E==X*X%)_v_kh7?B_D^byPO+{qI`v{}@!SGub z#4hH~hX>eu*~)P`RS0E5Yr*W`hsg9fWchRXiv+0gjseUq-FPpB|7+&^!Np6`vGnis zbkz~;qEC|CH2{QIh?%kxEpPKCFPlAY=wmVsTXrC;?j=yi?Qgpb{!77{(ckko(J5G^ z?VW`{0W#Cw1fqGlyBO3edhggTKT|*Zr3ubf50IE5%EhjBeyU52N_|BuLB7tXO=z>o z{>7Dzjvmn3f&pYa9{-UtY1WrWYp;|`eDt+)Q!HY?p{JWGwSL9 z5$sg1>lXeMkV#dajP(rDyx5|tFuPibRRywh}=;YNOGq5`1@BO;1Z8C?W9Ke_$hg? zGeG?`SR_*5Kax6pK`}K^JncthJAJe1JZJ3V{9dTEUc%JG-OGi~frY;f{q;5;#`YE0v;OGRtYP8 zT(6O!jNAHT6Vjw;WguoVdEUNY9yM!U1BzsTB(|Ay&2f3mj%#*8K^jmdUDruYgAHCy zG6^u$m8t2aj=t)8IeE;Od>Yyq_uZu*uZt`e+8ecz`$$sm?Vq4(a~H;CFz7Ur?79;k zZ`;PXe{?SD@xa_***=)cTf)t795KSk*>4zjNLXw3Jeq&Atj|n|a_(tLeofbk(u&Fv zQxuE+sg=~+3=Y=F=GH{B+yqfcv9NgaOU)MFQ-Bfcmyfi+DQrL$L_zrf@PAjeTq#L% zegjQ+d}QfPj7UN;m{v#8$M@&*?&ok8ZmrbO4eKum06AS?d?RAHUcBIj7H7suXgEv} zf&fUSPwm)!xqhYRob?`5+CFsOwL(o1+}P1~$G+$Dx1ntT*#rjZO~I7ABuUuZzOag( z2(54e15NReo^vw3*}=@-M<*9EQScz_==v6HTO4(c(HdR6DY?0M9|`?j#zdT?^bPPS zoj929y=Zjqj;@?VM)Q3ONZ;(a-lZIQf8YiN$VmMk(ngd>V;piFdQC{b zo)&%O=dyp4KmoJsF9Blq9`JXinjN~lH(^<|$udzPsv=qO4;?cVkOi={#|LRAIvb=v zFbZa5uKp;`-&+Niw^M+BKehY)3FISr&~jpf8qOyaM$(A|(0*fZ$TD6wI5ML{FzZDo zT5m<$QyMsLYIC~z!dn->&+x#0+HKMAuh0w21MvN5uZVx#!lHasyyc>18phQ#`BEJw zhT4`D1ZeXC@Sjq52z@h64*vMmX;U)D?pZg6$by=ubG8Bp8=|gaVZm)0JJ}(Ba z0Bqbi`Y1bVLNT8sw17|=O)QJ*@=VU8k5?TrmKD0Je(&?ckKf|@RajoorI9}))Q2M{ zS?-xuG*B~>+;rvga)Yut6~89_Eo8Vobgd1T@tk&hB~& z<&blXlD{|jAZ_-Q1#eRqad>Bxk$m@?&Qz`+^bwV_uM|Sc0+fnD zpYu{HY@durLAOIOp|TV?II~T~Q@PRN{r0s1F?mRIX{_ASpsJkT^z+AtfMmIPKt#wP z{BwT330~^)kI*Z-V~lUtJyh@&So~4P-M!dC>1OHvVo|3#^Shhm8dKEP>MBaNbn7>E zI%1B-|HAu)G8?y=Dd}VECqQP=`ibHRw0NR~jRcsGnN5mqzMf!!_UnWOQjDo z>57gk_eK||&Bc#pm9e#bTnk=&=Fi@+@}}?^DoL@@@1;?LG∾Oq9YJgSefLcz5{ zlB=rAsItF}J$u{Ncc!JXI>aN^;M*=e`Uap>_}tfczTAc8Qp0d1SgJgfZ(kS#iGB@h zqPCqFeoJTISIqxDGbnAB4fqHeTC8irf|t>WRWNkq-BY$9T=Y8bYoyX|qLUeGrp zHpDoJ#El+1g?kgbpQ3brzz`uPYDr#eTyrev9)qTiz93R>m3m8*-VyI+D#qsVoagBV ze+hr)O1aU)AFjLJ*H%^HyANdE6W;jLz8A8d#3w^TBTGQ_0*r&v zGpRKUXEH;_OR_Ycr7A`zKL>(!wc?rRi56rplc-jIG)_SRNafLUWpvfz7gTl0p4l#?CuKzAgG5O1U-xbK z&_$6}9w*_##{|_8+Z&5jWmV0+vNrR9nFX-ArDLO^$Zi z#5+fl%sY09-Cq-v)94Q!9QWJ#WUol4p8NX%E`V@*LPVsm-`a@Td9#J9mS4N&dKHX* z75>aw7H%d;K+g6O2#NmJ|Egv5934K3A1wafUq~Zw>Ez8fJ1KQBKwnB1ZS4&)wHGtY z;nS6RcU5Kmo|C63Yy$)Bf5lm&kq_`xv-kkUarbeqSA#3BqehG?~ky z4ShloTJ=g`SGYtaci4uXn?QC6jC{5oBVKHj{+ZPN`PPE4NWD&~Gbqi}IxCgN=#@wK z?jvY*?PuAtAGFf6ra{nGzu&y>im)+RgGO|{>AI8~5Dy{e@%k&_+)pTz%L9_v{{1=6 z-0Jr5%}Xt6U}@NrRD2zCgCs}fT%3EWdWu@2oEN2J-I5^AEJ4hren-I~v+vNj-p;p!ET^ zJ}gRbZ1aR`oItjs=P9N{^SYQgDO@&@_gWS3eM^6wl9%8TULHSn#l!D=7P`5^ zeEZIvEPjOMn0wuG9-J0K`bIlb8M35b+ZSAfk$EE*8!cqUB!F34(_B(TyemQBGez0n zi}hn?{j?KuDV}CmogsJw6|cS*Y8YBAO@P^>mgIh}yggIR-raM|Te~sYN5Wlx2g$jz zg}0MlhngDrz2OIWQ~ZJO1~sn+dNK7MykSQrDp9_HTt=$p5gS*}5AXpxyn=pjvLE6S zgCu@+rL+%qFDcr|-bUx?B$;8)~tZU3sYOq;yJ;EiH4 z1ZXw=Dr^%P42W)bjC(%zi$E3An;AW)E%xbZ732~%GgQnUzT66-US=!=ulL^Q1Ue6b zKCX>fcQFBww}+*nR38+;hgbeVt*-l~;;Ba#&W;{% zerltg_$GMf3+IKuw%F)IXr85{`+DxJd;p_!M(0M)#cr_lfWEibE-UAv1b-B)1XPk@ z)puqrqNF0nl4VSivW;*(N~A9Q z5c>|F`O@*SUL~5L)bKfzKOgHo6ZEcvnJaZlDmA6b=6V(zIdw^*bpFwG(ly_K(Lf{D}MAWpiSYd36!#0zq~zT{QG>^u+BL@ z@Y$XZ%NNA?^}c^H{exQ!&$jcSnRz@n2vfM8hcEb1j9Z#T8-@@1?6<-G! z?Y?SED3iMTckY4bEe#d;b9p5AUnDJpT0U(Mf3pisEWJy(dV6Xk^?c*)*U1OWVTEO$ zjz@KEp)p#FeZ1jt#kMm+`*Xg&46=Pzl3~a8CBghF zfhL0Fl?%n6lB2z?shR1uCNPyqL;^1xVIQc7=jh*87Me3^hMK{Pxtw(?Nt17vi5g&Yz&FhBmNzk$QIC@F?dmJ0GM-#u+dcv1VEnCqqnAMFnGHM{Uotv|h zdCA~E#p7m)>g^e@<>63IRbS^G84_s+(9)L@b7Qf+5c>SY+z} z<7-`Mk_$&Ed8b6Gtc#87!;1f?5=667i7O>vz8U7jD&avkOxh+^&^K7eung>B44cA6 zF)WEyD4gt|DdMCkmi81wqG~gY7@IlF%H%0*N_sTFJi-X+q{{*(Xd>z`hn z%YTu+T?wJK?RgHVv*jurd#6J^iS%gFD%pKp_6jCB?!}W0Xlx0^ATMAy&VR(y>&5zG zX2|0ih2sfnDMnEpBBFA>h9m3I$ln$3ZN_5V*m#)R=Z3ntYn|gA2K?Ec0yCd5+z?LnZG3s^#ONrVDFy%OGixk=cBuoJ_mJhn+60`SuOU{~q zkv1zbDTo!d{@>QyvN)hxA`$NR{HO*rOr#q&q1qv2&_A*s(^36U^0c~Y@t3NVc zuz5(XU`cz;nz#g*;zSId){F%C1&7(hToG7z@ClEpDG(MV-`rGD?+DjmaXuW9Xng&+ ze!%rT)Gpk$C;6N(Fm!x@D8XT?ic~3@fl|+F<|dnDoRcAGiPOlJt!#R>(y`tuRs#Wk zgw)i%RB=SXUSB?a;xU_XdvoLpO4s<{;rt%Ks`OyG3KhZZZ-{tA(f5re>_>mmevYjG zHkGa4l0zG9Bve}cPNpJJ9BKpkmY)pH`QQuR$hkIKN2#0)!gwA&5mwOFk+`POGgl0D z_S|e5Es10#Uo$+CYVGS+oEYBvsy|x42566w+Y4YE&6i}qPj-2|j5E}(Fn9FU4f*C9 zuXM3oTzv{CU6_ofoQO3CE}>{aPkUaH^j9Yz42c`>yaEC}7IhnXfPmz#1N)D~)rHq# z`xUKFx)^aOw$6CfAp5dhXA7@EU!*CXlM9SjaTRDd@Z1X+jjgU~&3&pgJDq0Sc#%>Z z(q|KZ_TIAu-KQ%DRd4q`iAu1^6faw)3wn%mm9L{U|cCY9a8k3cA-t` zl8?Vu-#|^B-yb8~NmOmCn~EY3DfJ7aw63ng${eOwW#Vg15gAM;&%-D5`tc2XYpOgr zZQs_3y8YceDYpllm?#t39}werX7YPQVp1PK%0rI(KND%4C7#?s=JiDnj&5RhqS5(Tf8aQ_ zI9@`+&21w$lzzwKCn#&~zbL3|qJE?WIT6 zG2#ps2PU{F%ug@{gari`VK5j?iru|#U*5Hl(0PTP2*;jAr02a+9n^9P8l9}-Yxvh2YY#<(;&XNIH{BxRgxGdtBR z1JQj#j`kleSwM-$LzV&NI)E@TrFnusR^Gk$a{t|NJWe#6!yjcgQ5-i>kSw!1R~JQY z9y`BV*$h3yxDNHNYg9aE{9=oqj&>|@1#5a>D`cTv?CJqDsA6eazTh9>oV`Joxb94` z2XuaEiu98P8t_tT+!2Gd*vv(B?g*uxH^JA64r^JA7GnuDz2A2BW^jBsJ?Mz2=XmFt zeHZ5EGo%9jqMxT59h9mE+OIStbGaPeL_rn#==wp~s+oM&7Kp*rIBV&|l;Q4h>}Ghp z_+SuC`{;E1Mqo`_x!<#fO-+j6Q*?h^cwZBea zVl#Sk#HyK&Q_8&QMY!xX#8v+q{EKv782hM#2N2hZ%Jw;mDvm5&j+j_v>%Z zNM74`^#se$I}2RX#c1t-B+d+#l_Xh)IrsIO`#fR8HS)*&Y@-((NU6wqsdzWmR9gwi zv4(U4h{k@HsG7L{4cpVBpz`y+n#>JQF>J+b?HF$f|?`gsorOhTtAc zgH{~U@=SZc{ONGaz^~hY9G~VC&P^f3mnFhI@Fh)9GVOVMSdzs1jU^m+PIkG+1r_ry3-8= zs`N=!1zdAkWf@Vv{K~7n10QT$9(Sw;>lOZim@~SAxI6;l*01D71KUP#U9W$iQ+$$C zs~L4Eg~%!vM-e1AWI^1l|GIze&4hF;uv8;02YF!s~SoV^8YrbvWS7IuNQMcx6$IrZU{} z=e{+9F1=pB>=mdu1w!vsA!a+Ze!<~!-zSmhw|DGf98ZDUtVYKMm5Jwvb$p8M)CvAv zd-7*22#w#oc(igL(YN(wzj%57#MEX4#(OTv(Dy1V;GZ7DYDB*T z>engJ1osV|)5Lqhtk1OLd8N#%vt;smjdV)kzHMgYpg9+=gt%xP?oaK|!SfFNDzJ{= zpA1pM8c=cKt|xS`S__z}e!hmGz*u{Y=+QvNnE^ywRWuxIq)7Z4q#BYks1e*Xd@kR@ z!IR57)uKdC0=m6TqB9rGJC7DC{-ntPuQrKnDd73y!+~%y9b!kgn3TeswczZHM%3g5 zi=(ccCCB5@0yb~&Bo}{if zggsCt)~XQc(ge}3f{2Ynba=}GZ&I~N*`c_X?e;Itt8`Kigt?Kt5F<$*&8a_46uW&5 zOC&J`yal`@B}P=iTG>iLd&;!x^|3X{0x@($iUO@hwuN$Pyy{wv*Ib48nOWT{u(?`lKrZEZ={p2F0rhr}d=}~8U3&m8 z{%M_&bg52n#_#h0q~0m%5sdKMA0+9_%Zpe*x{|-83hr|;9;A3nh24Dp;*2KsmWJrG zwJ&xdKNeBXqtg~~IL78*==W4)vc+M(=vl?miy8I+s0 z@Yl$SLAv0}emPzUofFJ&PrlKq)bhoe81SYHrE{wzT##;%PtdV&KjF;3@9y5!4RP(8 zpOBvjkNLO*vQGf)k{ObS&7dF zH^R7|)ypHvpJZ-$(4|<~4Fm0SD$!qw$EagJro=#BvSul0_sGdrJFw;U$A0{MARwp$ zG-jg?t1#3a{eO=C`!z+a;mKes2ZW!n^no|bO&-RmfUxI0NB2-mHadiXM+NOAl%@Rg zD%q@q%_p1X{x*2+8ckQ3QhQSnW3-#=rnc?N1BeiIThfI+L>Hf8a@EYyTwGj?A)i1u zm64cqk_IXfV;%6}m}wSh-&gxuZE~G{WN&XTrcrgf71+R%iU@q-!JX8TvYq{KWlzjj u_XoqHlOX1~!LuOL%S8XLqv-S=<7Jjiu{p@f26%A|P4SJIT$PMP*#7}mi}XAI literal 0 HcmV?d00001 diff --git a/doc/html/_me_light_sensor_8h__incl.map b/doc/html/_me_light_sensor_8h__incl.map new file mode 100644 index 00000000..a8d566be --- /dev/null +++ b/doc/html/_me_light_sensor_8h__incl.map @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_light_sensor_8h__incl.md5 b/doc/html/_me_light_sensor_8h__incl.md5 new file mode 100644 index 00000000..10b4a209 --- /dev/null +++ b/doc/html/_me_light_sensor_8h__incl.md5 @@ -0,0 +1 @@ +26214bd0da052e7a3d682d764906fbc7 \ No newline at end of file diff --git a/doc/html/_me_light_sensor_8h__incl.png b/doc/html/_me_light_sensor_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..d5a0a46ee503052aefe6ece82e0ede5e10308eb3 GIT binary patch literal 46719 zcmagGWmHt}8#PQLEe%rAjg-=%v~+h#OEbXGAtFj6(kUR_NDB-gLk~)K!$_xeJZI$h zf7kovS&rm#m z0N*g)C@aV!-6Oto+lmsAke(tb$-dO_$=qG=_0ipEzB@Xo^Tv?H5}qKeA15p)Zg}f> z&8hGdE39EM*E#8x_s6js{E5{q3V%_D3K`6vc(lm+NefK$#I}SN^%WCi??A5{NinI7 z%ZYUQs;5q_tyo{Y31QmJN?N%y(dS_@^sf+ehs^sf!O;o--^UhKlxWCD;5c3U;d_D| z`dbqo|I)6zD;y_LGvYB}!tTJQ|9)@AMRu)8@gYJsO9mt5>7zSj>L*_KgoOP(NfHde z5vJ{w6L@C16nGvZ8i7mntnHMjs{QIM*ETf+!{@-4aW1K4?(;-Og=*uxhjQcj{Omy5qD$KL{^H!Me8a}Af6E5$VryhEt9hNX&7a|3 zzq;pY#x1h4){fs}lz~gLPMuzSQCQh=u$5e-V)tiHqCu~~>C)FTS<^J9-sa^*BDbl; zZTeo{l()ZmqVodqCuraQEy{X&ww7sH&*4`hf1ac7s5$e`NsrUbzovt^i{OqUe~`H^cGJy%urVxxfvL`6aQNY6P0nDHxcH=HUk!OKxl(R?(rj*y9=0$ux#I^?uXqGpRC{$XDq@oq53<0E zzUl|{Q)X*t3*e>Vd|9<{#gQMUqsl+7w#yvJxeN|Ni|c?ldOJ|1ApQcEW0rxLfuYuU z77Ba=;wVzBg@}-F=EXxa@c$`Z1|nfb)Oihf_1{7H>i-r%!@Cb};5nAZ`1bd%#6WQ^ zh|$oPuYWc_mWhEOt?1!K$NSy>otpXXpgqp#9fC~j_0iJmWOMj^e(y%w(ID@K3dgVY zTwB4thQv=)g&n&{92fnfI-X_ORA|CUft6~{Fanp!|0vwjXR1&&1Bwr=?ZrNuVHdv| zVs!AW>$%hVYtTp@Ly-t)&AO-eFF$iP^KWVHJzsQaygB^Ej)|_mcwO##1y+W>BG6cg z7>I3HSn9ys$+=>^ck+Agvz737agoSn&u?!2du4MPXD^AH;-Bc=v}NSA;WTt=vM54M zwp{~17$vBJ8@oQ3RkEP*n7Ka*Cq@Ke*M(0B0{{yKK+)H zDklf1CovBR*3ScuViiVRGs;D}SnP|Z3KAS%tUE6B{1#XDV!vm4eiAy)EU?$JDE_u7 zNy0R#^3?rhWIukQyBe}Ls#(uPSm(f`-u~9!6mf1|Cn#IpUD^(79VQ%xMbV2S1~xep zRZEn~H@upnwlC+ZO%b>hiTtQIQv5Ft63WvuPKi;Pkm21B=Vs^z4)$Kof+>~yRf4cm z1UYCnRZnDW^8C!VyLor3v|!SzHG1>nY1^tDwj0qFA%0v_B5ric?TN320;XU}25*|^ z={hZpz`y2`cx;C#w1tnoRjZ2$^sOAo-Z%ZV-1@!#7>ginTb|JE(H4VkxJ*{WxSa>* za|2)dL;JT_7FWG;TGjXu6*W$ zGX=tL;yLG23B==0Cbr)gw^U4hnYb1dN=D(-zRYa)`Ru&EbE128ssc~0`jzIui{6J$ zi=o$2cN22IHZsFz+LA229}P;ifcZq9C*CaM?)WenyLX*F(eA>;A>E-!_T7eX`NWs`GTIh` zF4NLuqlPaoVhe}~`}rSMS}QZKeM{_OLO{Kx79(c9*PomVL~WEivD?@*X0tFcr;^Uu zZqw*{IvR?eeHBzm6yZaK<;pLhsns|B4IQ;6I`GR3RD67~O=RDANgi5Z+>gk6!Xw~h zY1?u- z6LQ`*h5RME{pBYq*OkuADqe6MizmDoKGQL+Z=j|)MYD{W>*-_5j2?5s;wtXK$i(97 zZUWH6Y`HHu1tE6s>D8wuxsRVLIoZbOp?vCd%YEo`ejD#FmcDrjq=1Jue0g|z%nj@Z z{ZHQj8FfkP7T#_1T+UmDr4Bf4_GhEGm?u3-XkSu6qSaD|nPN&f2DEcovKvQ}WH!)a z-E69MSf^#=(I)lFE6?igP)0@9XSktuA*{UVZrP7e(&fL`+4>vf%gJI8KiuL`M$^q> z6B)n1Kc5c|n{;?4*PpHbrLpN$wf%{=sY^POr(&lwGZwtb9Pmzz*<}cc1?3)kQ6VeNr>H`sKg;hw$Wg_qS!$*Z-a_7X$F3h|59a-L-m3wY$x<+ zpKE)|BwLNSK3k|I#F$1+0A8otb5`cGt}{a%Bf@zT|FnmdPtw7Sp*rofX1@dW$z6Yg zWbUySbYDl%2X?}aKV6Hqec^>>JcPE*6*_xjKcAqzCM#R3`hXssbj4RNtpYHMep-C% zWNzcuM8u>HPY0Ts_l1sXLdB4lNs)zHxm+^)I1MfLO$5=rN z0;ha5(a%6CxG3jlX^DT`vtZzV{NF0hQ^%IA-f){>nXDd0cWwaDpiXyChfCo~KUP*a z6PBiaO~>Jnkt~8I$zs2vll#+xe=#ruT2p#Li$Z@Lc3C&h+`%O*rx{TqZ0^@0%Y za}7AaIgk`is^%v=-Icxd{h1AIyI4RvGP4|4O;{^~Bg> z>tjHW*BFz(z;<++hSrX+6}E6e2GJk4r$|PjMGah`Xa4ceNlD4%Gt6W$1RfU9J)cP$ zq&Rfx4L8Zw>FbFqG}Jaf(9b^Y)`nr{&Y%`fs??|OQ-CvoB}jsH0@QIXzISphuR&NM zY%m&QhFND)bZt-wTpdDv3Y4Xb)G=Gi2P(QWK} z9oH7|LJ4NJ!=UBt=l(Mz`L470f$Yu-r*8*xVs^rrN`ATL9lSxI?vBGc#-v{DPS++` zafGqbPP}2UrEb{ET z))Uct$1Pum`?>j{IIyR;qWBhFui+-Fl#o%FJF-HU!~a8Uvl1PZa1Qz=N`%M_x7+@s zOyg@u<7H{hpsF~08T>_gtnbJ^*h$h1qc8vaXsz_a{!sTUv4~c8kQ!u)vuOGQP20hb zf)Tf3FIEx$_44A_9K9IQd z$b)EEp~NL7Psr74g&1(S87RL!K(9wT{3&p)QK^-V@|HfLw3cAQ(Gf7b*X5?kmLo;B z%|_N{NP8{;i@MSoaR2ffghb*SL=)4I;I_7)Dti=86xwK*sC`M4fI)Ql<@#0X5(x^Z;33pL`}M zt>qwAV@5zcY2xyZ_RwMUBrq0Z5=kniUQ;5o(f6;;7WPs~^_tH`EO8faEV?`jdnSC| zp5NZn9y=Neq(9+=w<_U`_~2Tbeo}-&+2^f zC5L}OIZT~NK26LHMP&1asJN74wY^wB8;^w)FZ(1Q5|yh5?Iz3Ff;hBWk-*y(^{!^) z=nx0TVRXun$?w0ld>r+Y8j7Yv8ly>0?CwdU{b{7NQ}Ygm45@B7)l}CWY<+wu_Sz=S zlcQ}=Az`ElMYz|J|BwI_l#N|%renX82NN<#sya3?ANgw8i=F!`wW)1wMSJhY>&Vle zd32efJNjX8c*&D}xG;b5L4=$_JQ=&$>9=6(v#}BOlD|JR^P7gF9b7UsweA0=1wmuA zW*8UPTc_dFI@{_vO-p;Rz>hseS+~UCq8)<5zq2Tx_nZ}} zNHG%Yob@#zy07&b0LFQ#c2x9D{-qb<@RKkRavu3V=J)C`K}9zhbM zC5>UI*amxiPaM@&D2Gvr{s+v$6n#et)H?~>3T+&D)b&C8M{QPoM3BmTl?wKT4!a%0 zG$0@S$^Zm{xv4c>^c&Fe zPTp}no4DPNqe+smS$52U5L4d$v-lmy$UR^-!?Qyaj_NeVFa-9jj{iiVfZFP5a$MWJ z4a;A#s=kV`y-SYau3!iYf7m|ca$x%kCqc*>$UmH+x-;oOqV-D8kz(Adgp=SUlj3vu zGZAkJUVO|AH^eYUi$&2ByWzDXaH$esoXvx=IxIM$@AwG@a2}FWr^jk{zJZkvF!+nK z{A9RQcqoHN6MQLfd4a_P7(rXO>r|#KRo&e@Y0!`Gaa7eBiXuI=8oZexTXRpR4tBg< z(|h&SDzPQrHIC(PFz|<1SEoXGsjZYnj*9a{?qwVr;~$f#QuXn4`l@y0c`%j(-G|o2 zgieeH6;rA9#QLt@%e z2q-Q>ikkb-aA{dh{NTzm&?8F zaia@wX{}Y|!oxM~$hUAFN)PJK-K2JZwaBUr5Iw9LKjjQg2tO(q`B~z1;RT}&2;z0p z|HOLpCd`q>qru&_bi!80Wg1d}+D4rOF0(((OfeE^ zl8|_G#Wq?LN`p=q$sna!Tp!sr&3)pI zKw~0DN|UGTyl%n3TBH6x%tY8AD1E`*XgW%|y54c#E&A56a8}v4RleZa>z&(mNK@a6 zHlzbDXf(ZBRhebZQPVE5ofA>LdJ`}dnvXhTi92Iaph&SN(dgo@`>Y^Vp(pk>e2!jR zKX92If}CNzCVkUy^n@vB+#HxafZHC9FNM}_ZfdQ62CoyK&pyOhwkn9Ibzw)p`P$NV zR~D?@@5b++c94=Xh>j0OzLX|qudK>;8Ij9Uw{UCf}GGz=Qc{yH3p^K2X2CI%g$qoqVO2!1_3{oNh4btl7tQgLAC26d0G-9oKd2DCh% znXwAZu$$fib~AJhM#epI3RK*jIyMjIop<>Vu#_~$ioEko;P3K>Qi zL=X8(sh52iIGcqnunO6RGITho!FGGD)uw6*57u4qwK1c%-1T*8Os@&^v>Gcux5H52;eh)lUm z_f4Q$UTYYRE*-$yq|3rpD$;GA$!4(|b375ZGv&PRqD1|{_aaAvlf}?~yjj+7HBWS8 ziDc~rGPN+%ot4wjcruLOk&5g3m$iY3Do`TA#hvNK9pWO54HpqgN3pBNEN`F)E=hN) zvK3VjU$H^5qAQT+jK2Dh`K8fFKK-7ocwknv$2gPHHQHvCMrfXe#7_jsRTIQ{f3-*K>@5~^(} z;?y7fe3vJ7{p5Ru{7~k$0oA=WK#SQOX%qcd3SKK!9O!63$U~}-T!jO?o(^qnl?tvT z;_iDixmpR-VRU)d2CcaqF?Ce&tP`Vd9eh$WPa5}IEJk_FeY=#o;N}up52|lBOm^Y` zAS53;^=LER&?}ZV)Hu;-v!Sd?Bgk)m+DFzOLz3@RlAoPOXf-=E=Y7YU#to=wPNM^8 z*OI%7fDeoh*&?yxa)f4QVS>8r0IT0)yjVow{cU^GB<35z2=mmFK@0UwJz7`i8NbP9 zc(%V5#fKD|ox4C%vfW0|ubWk4P589dW3;ISk3nu!+rKHeJf;m`T_ki!+{tXSkwSxV za0$@=$c=@$Y^bg1dsE$`yK5l(NWzYMw4J`w%U`{%REC->GA29SGecOSPfCksZ;j2W zEjr&NzI#gH7Tk`jV@Y8K@Za#Zoe}bfE1uJA>56M45wgfcn@@gy^exm!OARPpR615V zv4J5`wGy}>KzOMe+KpX{730Z>qa>pB`$Io}I~0yXJ}I9ihtUZ7+z!gt-aNDk%L>VO z5fNb5 zqW{4HT~1f-*#Kvig{@t3N=nDhNJ?fg$|nT|86+YSu<&Yt_wF&8iiz+9?I%%v z@ax2&gm3Dot%WVWDtAZha{Tw3Z!eo(Dw#9(e*ust_c9cy0qz_ANf1ZYZx3CL9eX>rl40YNT2!2Tai*&<<|P zJPIqS*lP#5*B^s}qK@i(KKE`i2g;AnSYL3cUr0i-=UQQ7C;mo!v*HWt)GLQ`&;5tF zI(77SA3X>c^np6Q9Q}9{tSF6!`1+n%biBV1yj2UDu1f$kx~>#^4^}MjNzt>ka0Um` z4BEMYK9!gI!^Nq5F+eh8u47Fgm!li9^jKl9D zjxuXo)3oB?pE84z8~b*$j|2N2s!6wzVb;L`@)FjHQ`nLiwZ67>oP3s}F;D5q4Y^S> zja4b;PA6##AFC11uF@IPvoy4nJ9Is-YjHzxJc|`d1(+ zp;0H9tb?D;%(QkEXd}2kW0|Utf42VzFcK^ovkwV+6X)ZOaF!(pSC&iPlwJH5bo?Yb zclHG!`a`cn+Ct)VN$0Ex6}E}%oau&Y+v31&m933V{hMuawH3!cjsPJ+HRo{=LIrL) zN&Jm|!<>B@r;w#;{Z#l*Zdl9hj?;XH5ZxT%KagtO$60oAyM|?sBK`-)0*bBRshvUf zMFQ!6;|$FFcER}gd%e4dSAqnoS0PPJ{c1sDcw}n_yrSw`^Z+#_ezHo#)LZPmRh`JS zkl?j>eWL^AweyQmO*`WLLMKuV)HGX!n%Wodr8WwN5j1zjTtY-M1spLty(=nLm83p< ze|GtiItKl|oz@_^t-`?H#GUODhpN4*l;hyW&6hqvbk}wk(B1(k1F@nxA9sZ-5U@Uh zz9_FNZ1nvI43zD$_9pj@bsr{Xw@G&8Cd(~a=5ze$8iGpPr?0fUVie(%wGP zC7;>lwf;6JB-(|b@=!?fhWF-LOxW;RXsm0Lmf+_b_a@2aM3v2WUtH>`UBQ7{cmCoAb)M=4UG=KL~E<*C1+aWm$D6oRddB3 z7#^bJWf1@bCbRn9hP?&v0}LjR6=j&tzX3Gx-W)GrYNd8X>(tX_W82|terF%Uts}rR zeQTMPTst(k4fypc8&ThtDtdt_yq39Q(^u%f4+XL_jITXR`%U#|jFn^L?x$kV-bX;+ zAZ2Q%WPAP*An)>u1@K6Wvu7t#D8<@*0~;`TBNT=*HPVa4XDv*<5^lxvg~!(kCTx+x+1t1-7iYeZK9)kR{sa?sXfeZ>oRg5KU!6avxhY=rPuJzS6IKu<8pmo zH11it?Kv z%{RK!UN5=d1w>@5ur%Gh_g*=VA z>_4E|ha_MZPDcc4-=hKf;>Ma9IK^nf2foxMwWl=3L#8>CR*A#@e)Q=_5vWpe-SVUS z(}45?F;xy&NzG1ASY-qvF${;zMSbliqo;j*?ZKdu7dax42L;M%2^vBr4_r zwX+JTsCTFBXLLrNojfq;nrl0O5rx0$VWdGt+yr9BmDjI$+k&SYOH5iS50VXbQ_)`>U+DTBvd4@ZihJCfv<9wP` ztR*CIE2zNNx)&jKudJNQvx=ObWtRXY?rLl7^UKPX>E!H`)9cwx$KfWc0iPC`jRSRo^Ek6=+QQJ6*LGTkm zz!({hvKD6gEvGe57vhEIc#o)FO&>O6-kUr9T`kU6eCAm`IkP>GJ2K(>(hSmxfr*MK zM(qS8gp^SDx5{v&@Ma&v@v`#EG191wPq7lIf;ym+M97P`2C7N#i%XzGv(x-TB&r}qSZWxIrye6hbBsQH@LV+oQ zR+H?aheoMNn|~A{bySWaPe3pscjmeb0@9{l4CgqrtM+|xduiVth1ZLOm99MerwB(* zFGBI3q~1hLL2_KUSk*9Fm3p=%K>c<>DHd0x%xZBUSF>fb7oD9&OohetIJ(Plr+O46 z8FTR2v+Cp+skz0#fT^(RshmCIkC_3F=IB-a?)_~e9aQb8x3y2viVr(@fp2_IFyAde z&SPSbkw!(p^?=kmzq&tiGeC+Ep_adLR_V2IeIicTwS;$P3tf`vNvz<@9xsjiS_bH4 zqz&3O8n`Bax;2%8kbXe@5IsXfk->$7kD|R6mj9b89>$)}UIaUv&ZOYl_fe!Ay8K7Z`=4~OWo56)&Q4sU+@N?vl_%M2PREAyK$&hyYvG3AlVDI6t&yMfN^*ZKL{D15Ot*MKR#--jp z?`oJTcODz%?XY+W&@Cz+ZBnxahD9X@N1Y@jlUJPuKDl z=Obwl$6j`^;Y@|Y2!?z<#MhNY?$s1q^+W32R=RE%+ODO{*CmE_M*we;|BC5B6h|~- z-Xi#hl|xN2)eLH)5`v=zw0T52e-zb!k;Hr(01n!P#yJ*xVA;}o6;`And^tnBsk?{n zqe}r&xaFP(X?2+Ae>Zgsff@h4B18bM9hZ7lBjO}0{f+-f^|CWUqj`rCgdXrE{=PKZ zmf(Ed3rN>+_m^H@Z@&wT?C1bglh$EI>~7uLNGBWf{W0B{wji{<%q=Kfaiq(E->&4J z(pKbsdKadPP#hMM2;T2eF9HPaR|p}*$3ifqTgp9~H^2Yu@94q?iWrVij3VFji?5c^ z%(m3wAUR!nA-wf_$w*w=f4z!{6QCz}qaE>Vg}FwsnhQK;e@VR+M*xoVkg~FWfWxUI zAnhPw!18nV`csP*v1{b}u8X$L0f^zGd%AYjP{oOa6*S!CMyMKRYtM115>QLd&&-(X zX*nr|_k^`2EIa_+b|P_V*x`_{hU^78bSON$;YZ`ho~LFOyo09t@dejm5}?7gRGrUi z0oCRM?_8!pXj{kxq@o$RM^i+JwZ)yo&Bua96cHJ8;wAaEK}IOwxcNDL)=bv$h@qT%ZJHb{$_r?nACuJEJTTc(15LP5x>X(rSIY-UUKu`l90tX?) z!f{W;vBk-D`_onK+7gFS5l$(%_fzsU&_wuI1Tc!?GC%AgKKBu=Q=feDZI`RTc z=U_4)+9tk9XxBj6)p4}=#g;PDS*-b3=aamgH4Fm3x3#M&bF;4zA_e?gBtgN zKF3UO_%7+wwKt&Ah>=FW`9M{Nhdpe6ei|8JY}J~mp;;5Saejro2qSc%-g0Bw(v>C- z5zi&H@A4gA;R{o++7mYds4RsiMr<8Z3PoD;D4ED6RC8ffTRGr_p@-pEtQr;;_B(A766?SL*Owpgu#(b-LkaD&uLg7-Ij%s8PEOB`NU@ z6C4$=ff_#fluARrCVcxDqTc?9H@D1OhDE2pxz-Mr@b~Y{D>`lhA2H2kezJR@?qK|> z1k{#?#zH{`ruKvU?!h6o1?Foo=6yi>bpoGn&;oPD_s-Fp%XOQp(>jDi0U%J6UJR%m z*qTKnF2}cuF8=iqr3KH{SXnk|&`1f;ljjkh|kN;CY#W2lOU5Imehx%Gooywq@W(4?mt@I4wsuu?T3G1zL~>685Suj zopw1m3H)rf51W{fYj9*a@oGVUz!xr^!Wp;(E{oZ*+G8+!i8VXATr2~kFy_FlIHr4d zL@}Y{rN>YZqmBWIL-`;ui0!gwgsyNImxb;L#w2b8cj;{fz*wnl95arh!@=npmmk_; z41xLo6hpuAL6hwNN!x$ju5*q=&My{gD6lN1p7wkRAKU8(MCP&HymKAju5+v`&_WZ% z$L1O~#iQF&hqG6OIl9S*RU#(nU-ZchCt~M0%?|Fv2&;H%!vsjGuHj5KZvZ^c+n;=^%G!6-#>P}XT14AXNw$_d`$4%Kwy!{GD%z#fv9G#et#i&m<+A1`m z0FETF54{yGv#R#%z%w6y$L6Y(DAY-)Q`-y_F@!cz}1q|-Z6T2CUzV==>IL+RkmUkC%BRfnNY5X3y`~d;?oW!g01)CS6 zamujwHfh?;+k)xV)&QT>D~wfVZHLjQ;Y;*GgUX{Vwpi61z$W*mLIoMtDT4QiMlZdt zz?TvH*ADBs$rr%Ba4$sM6~D$8%W8^5Bj@+{R9=7@=VMoCyk`Ac{e-L#Ir`yZNws-1Hc&C&$y_}dI|CnB^96_jp zfIF8TLhA3QIKeB-I6^yI%hI|L%m{m{yd&WPeFff}BAGiE@ECbNMX{@GYTc98v~)Jq z+$%*96FMZKL23r6Vs84;n3B z)AxVSv9cK8s@Av*Xze3=gzKvmQe54+u1G9~#KMvUJb^{%==fCcGZn4{kY4b@ZqZCk zC6YE~craF#?#0z&x~Bm3LX5K2wd;W2&Pul?E33rcWdxxln?;(pfHKAG&b^vES^o3J zWD-Tkp*(9k;sgh^6!+0aiY~diA=oB7k;&*!6m&glXuHVY6S6_x9pN|ZoJu|2UaafA1bix7(LY&af@GE2cF> z>V=RtVm991a#VgBSfq&_@O`J|4}>L5%I?(Ql(q$7YIdNXU#(r* zC`ol^&4nK5kk1J5`yTkT-S?yFO_9v@r2RNJ^UTz1fQ)u0UVFKnoDC^opn+eDOXyso zN+*gacbg>R7A2lwyaUV-vEFLXRC}00s8uME59OM=@Oj2j(JkHb%F4~sT*arUYxV;5 z9Y6Ms01rU)rSf7)2z{tdKNz!5(}broYO2JfPRZI$LFvxXqWWJ%+ga-IJ76e zab=OaqtQ!JE9xTS)*kg5&vJtK4pEnjhKDnye%Wq*VGexrsBZWYw^|H_N}=2xpX2DI zbRWeUAOuo74M|i?k)lKKMt*@53}C94-5>D8`R6|@yQ=n<)-NGprty`P{t6;TECMhM z0m#%7me-8W_OnTV^qBc}oCGk~Ith_c>g?S=C3o2?+B2q(3VP!9^w2eW=}EcD%Rm-P zk#l+9tl(S;C^l#vlk7KJ;aNg8CT08>Pr3o#wj zay|uJ?!Ii&W^QNZhf)SwI+#EzOz8^d3sVmr8@ha>TXV|`5S*w9h#4=za@Q2( zn;AjF12}A?+1Ee;U{vU^XG2tyNj-5ZYW=i}=8ojLe87Qty{8L2Z+bfZtiz@_gMf zGZ=CZW5@!9a_^?5IpX01m~f_Z&Fe!F3n7cP?l6pCek+?`Tz5LRdG73WWe9k_WVR_G z3S;)QXhQKn_KETXKr>b4hMa_!4fzmXY`W$A&%5R=!T#1I>wuCX$1T+fifge1v--VY z=u-Uy@HWuc?8Cke?wbHu*rL9hKtQo)`KFjVS zbP4#Lf0Kq1y>)Y-0Uye_%S0xt_f^Uv6m3L~GsL&U{h8#+ps9&)WbzOFOq5KFr{X=s z2r2+n<$_?N0B$!vSU6erwgk{D?jvfPp5Dsd0y1te=dwx|XJ|L|HrKNMg!bMY8>naJ z#sDP=JzceUg!PO%#+{tmtqu1b9XWr|jUD1;_JKp1~r#(Rt|oe|ES)nY^4 z^uv6-pfF-6N})d4>=L5gJve(QSrDFrRKS5r*V~lnT}i>VL_&b}Z~o}nBRgaV-(gdC z0*USF{kc)KZnL<~o8uqU971lFy)uA{aY4a|CnxL^UmCX2Z9os)^x{0#hR>w8V_(jK zg@gq7BP-s{X(gX}fP+@6J*@}-bvrL8~$0@wNTA6b9kHUXXw?AqJ%_CFLFftb}$kBf1O zc^56fn5daAj3wL~J%YsOPWwHCdBxUc3cEA(8)%0es$#)nI=Bb^=Yr)HIG`22VoSe z`JFHFAwDfTTg02Xx_@~De^6#kUo(p$RTB^lm#JI=0;`>~Ncsi;0dSdL$sk{Ze zeiQV;&!5#-+u1WMuq&dgP}jFUUXJKPs1mg?5yB}H1>J`y7kDf0~W#aQaE|)xT*o zB|G?Eqz<$S;bT9ZTX}RwNT~o(88s z?)IaU#_#vp1p}s!f|Z#?+9<${10;_nBf32`+c9=yjvsd&OH(y&3?AfO=8CvWuppTO z9$#TxfK`xqI2&lbf`Gzk_zB%x-RE!u;$qNtvng{?(;>`D>R`&WO+f-1>I&_W=0u zxFs<>0IQj$E#+<;pryX!r@6p>tYLt|^~_;ye^z^)CP!Ov0SF5#=ANm?Fckd9KDbQ_ zUQOLq46f$GW);`yD1s>0g<5Fj>WM|Suzrdv!IbRMDN~VtB+f|KW}!88>@!^|o5zu>{=q7pFFNcH1M_wtB&Xraq!b|s zW4b6Nft0_J?3U_p$Lp}iFa(S%xtr|iT(+7wj|)2VZ;~0w3YYP)fv=N#_l1L#_9yhZ z_`{zeB^W5WoQttm=~hix_LCGLkDBWVXZNCKDYYUD`9TDyQwY#-3lu z$1O<*1_+vOET7KhDXjUWcV*?xukChIcX->DlxW(W*rj2ZMDi1Es6)KOygd$%DL)@G z7KQeGC#b}bTxp^1urGBw70B6c+Ru3x{FIs;XW-y=$Of!pUKl#?Itbqc*MtV=IP8sU zzZ1DxKIX?k&o5h#a>!S7$@e>Ld;^niejnVZOl=C;Uy5~=JOYKVLo!erS+vLDYujnt zNuo@;P>(Nb<15iu?6uH?%;=-YhX@l-F?`9Fb83?9jGaOX4EwZ=auHqy_R|Y1{VPo{ zqL1wJ9>2N+$_nM@cdeJeCsf~WoFnScc+e#)e}#C+(FfIv2c{+K>Ulgn^fgiYsG8J! z3u7P4J`ZM~Ho^@HUZR@knkTonIkRwdj;x$uRP;#376^??pxiC*s;G$ zQ3`P_=BK(y?aF5pY9XCZQ|BZrn{sq`%NZ3~^)%o)*_Z1ZAe5dN{0pUi{ZgV&AeOEP zh-43MN>SBZo?TfW<81Mg*2)xQq9#5-imG=vP6V$-UHYOBdkO6W${Qy5+BTu=*umyvMU4w(=a~h)#@w@hH989-T}p8kHNhS z=|Yo>iS9@&#i`WgS6m_WKIR9pfs~VPO`8!ze}$AR$lOG$Bcu~?lsN~Q&!I}k$x9;X z1d)|vf%P%Xt8UpG*QjMAl~n}&q8%U^-8`&21y$)@DmW+q;xt?Ii`4=)e zl86cX3xS9K3!oK*96)oC1*qaUMSa9U@Cmx-sz%4JIoHITqZSzs6~etFoTIWyY0Myu zI=%0-4wN!^hCc1^;hUgk;yGbd;(V{E)|hoG1$H{+BwC00bFSX|v`YR8NhVdvf~g9( z{JU50HMp1*uCtUI!u9`X3^bcs)Utv0@EmMy$2HXSER&@*-WPOnSU6aqxp&xlr0v_> znO@X#ETP4c`wWGbdG9aNcEFS5i2Tq8dLWqwipf`LQG7GjJ+wd;vk-Wu4uU8TUBmAy z3HpgTPPWU=ItLbW^mSU~qzh+>xS5Fh&3!JrT};>&-xSs#EQoI6f%FTG9Q` zMl%Kl{lGIEOCI&VuW3GWZGeD=9c;WzAFj)86RuxJ+2x+abojJOLaYI#cU{zlNa_V7 za4|nKd22aPZfs;YFG~xSLgHjDiShM&-qnr{Hko~5@oC!^m9}k_l*x;90Q7H`WF(^1X%^ghrLZTfa*{$+%9@_JXr50VQO0~m9 zf`Qs?dIYb(2~(w_MkAYH?CaQQ0`+TnX;;NAp(zM=rIl?7se#jED;ZR0et!pSpUA+s zQrYb?>l!){ibPetU0|VBwYxXEE&9gn5tHcOnv3S-R<9hw&9PL_ToQ@e^@R-0Ml{oJ zCmoDW6GJ=zDoe|90Y-Dve)5{?nJm#2+raNfxi>6iOri(ifZ}iA*CAFqX`357`T|tn zYr8D*4^5XDA*T2y^}I|}KO(p4fm#x`20XoKm5yeH4M{O+l3pRwgq4(i77I|TGfrr_ zQ(c~Hi8t8?^O!}I{~jqDY(p_dK~}4fPLcfeR6J5e*)cLU zY+EPseV!sB2Q(#)b1xtCHIAQXv1s^Y%m(_*>VNF5o1ya;&wX-8er703MZr4|(+_LT6lE*WDpx(DK{7&m8*tQV;aF5E&E zE8VV)=X?VUm{qZJP+lWXxuzx?p>Wg)4LA&(W+|F_}H5_9W%gto;|VQwy5OkR6S zlB{3pIKY>*_~d2B*aHMsy0!BoU&OY(j6H28UdA25O*#(uQaO1iXB z;i>ilj(1kxiF#;8B3Qzh8-k-ft6q6rGc}2%x29>rLSI?wE*|3rNwAWYZP)v0@b?qQ zJ;D)Z?z#zoc?seHeH7e&{)k+(ixMZSmLsJmrl0HqeHaoc{n==3*ERUKt6U24P>ke;`uO>O|8G; zk@4XP4nhYvDdmaON~Jpx@0(LHW%RWb9Oz8`d9uG{5uq8KET_iq)7KDxxUG-KB42Cx zz3I4G+fZ*!iB{ZkAUw9sHVqlBt&@;4%*+BuxY}S>h5h*ZH&~Ziv>5;z^#R&Opmce- zOhcb|+cBl>V3}66!8ZmB?+{zxmsE|GsQFV#pW( z9ctc%*X#l-XgHh-L1lOA8H3RFTSpGXWI)Cag3lAuU%T-HB!6T~ zfz9!E*gePB+FIlv`tKirAkrkETkc^~gcAhn7$YI2>`@DUKb&wI6l=w#2JLQqdKbFP zab_9aBEv`JMxsm&0y2TQQH1~tJ)0f?Pp@6{vM?`IKphA}H|wg8@$9GO;W)_Dd$(Z} zD_%j3Tr%!fv11M}sGdy18AV^;q3~{+z6U8q3uMqcSM+`?M>we1j0F#J|8HJCEOs;)+wZ)q>s+YRMf%tYtZ@?2RjInd2*{zOZy+?Qa&!p|ik^wfJv=NB)8P z6gZ;DQ!8Gv){Tud-K8tN^d)E)oY8j+b=z{GV>d;!`u@K`al}5Abk+$CtAev|SR!P+ zn5|;JVl!$vJi$wYLb6nh38X5Msz#L9A-K{!*}PiHh0*pFw)s>-?8D~oTa8YdW?7CgPoR% z5M^f2RJ9Tnoui>{e8s)G!AKL3kr76sLd~OA+BTtHs86!E6dD!*?d+G04JJR~@s)NF zh%CdMdEUWoQH5-wVC4$Qg}Kz^rZFT}$Ow-V@eB@2SzZYjKb<;6VKZ+e`0c4^8U|#2A-mkGg}CSI1*pp zen3yeKb=*JbuUyH_?=}j(8tg4DGo;quDCj zZxR?$I;)4&#uyRFT8<7y_PPb}5W4f$3gFHvs8%2LRZt|^Ybg*E$QIClH;H#=#V{&e<$9?Mf<>H{}ecQsaG~Px;iJ;07QKSs^=>~CCp2E zrKh`A3(FU0|64)MTY6_Z(9FfR6W?w;eBY5M&Y5iV)cb0o(oG z(at^V{G2Ic4phi*#eM1&@<6|K9z9Tc_U#;u4#yq|Ex5Ae#lXS9c~9!LAx-vjc}dyE{()X;M`94LO=brQoK zPrsc7lSq1Om1k(7Kwel$V$bDT@sW$~Xf=TQx<+kk)0>oK66xAB*3io{Pu#@08X~U8 zP<|Fb`Km1AX#sB?Io_=roP8;qvuy3x=na%}yT%ik-lMd}`v9HPk`g=spYVDHMnYS7)tCs{O9kC~obzPH6?j^guI5~Wo%SdoDTIbjRNlmrst&!7wCVXCy+2~Fql{siiz`nJ#$lt)&Lu3aZ2>_FyyF%847qs-w0 zSK4Squ=<*JN&4R)-L_Q1{|Y`;W6Z)x$26+GUv1>dtK>w_;iuj(JVnOn*fm)41-zn3 ze=Mt};1z~FairA_Gvmrx6fQHL!NWXhkm%azJ7-R2>rOug)XpQei8owIOFYV^Sz3l-4P$iZy?glhi)qo$FZTEV^L*P z_+}~HmZG+XGpD*{VT<#yxvah~mh7H7r#c}q@r|`sKo44?)vR5f$jNp`w@7Rl0L_9H zL9J~fj6~jP8no5ga4R49mF8ySx+ae++isO3JQ*d~0HZu$iT7vJqco**@g=HLQl6Y(q8(^Cw{Np>kzd5>wo3 zVu$SBwie8AM^7|+WE}AOXY;d2>|nXM7i}Jmnm>u%)a*V$Td3gTO^^>?WZ0}-7Ndt>qR{|8Ee_^4rc9t}ruQ%vzf0glimylmV1bCYfwiC}a<+OW%5v;Mt!Xt+ERHj~V-uLy9b zV$pwu39%X4wDk)}Nv)oq`l7Ejz#0_54~^IxcEzeO1-Nv|pp#N(FK!d~_UJ$V=Zew0 z3RiYx&t5HnYV>y8p!H(eaujfswV-S9Bw-nTZvE&;5f&Em^0?lbCO^CXaMU~B;Ph#!8dR@@Ha~dQT@8G#P9O!saS0JGgQ1R zY~Osr@@%f(yw~=qv9T$S*7vLW|S|O5Bw}U{jKYU_vuKQqS@FUjEs{gV9L&~A& zWH~FRJDZn%)S+9*vH;qK;W>a~pVO^4+!@gTux{igJlNqp`?FmUW{N8RtirWSAc3U5 zt2TY}Y+lj(>#nufK6n``n%Unw|F4QcgWPuu2ZWuM;zo%{Uc-oY-%- z57}?uCjcFkw6fDPs65*Z=L{sbQhm*vz`k60cMUwiSfOi7-HDT@z1yakKS#cc)iD#( zehAT&9*c7G@W(u5X^V6BO!lr{F83N;8%V3Bdhj!deS(Y+N9IPiwkaPlCbJ z>VH`3#JxqSqUFKk(f{FQAyRsoAp1T+A;2N$<_Ph6a>;?xLZcXqP6Y*bOb@!Ln>=dvF zXBBjVjo{lbk>g`2;b6DnkrDLn@=}~Wl|Wb2MhQ{@@>-)a%0f}*ujMz&Vi4nwwXQa) zk=al54=?=h@97I#7LSx|#5r2%%nu&7*PHK5-QgeLBqQ49CYLvUokctEK;#1=*yg>L z1SuJ`XTen97VyCy2j%YF{?Y6GW4#eeOmG=My}+jA`-=X`mGL2A(W3L9UOHmDdZ|Z& zUGPzR-2)EbkTB+|weAWpN~-U!;kw4>@0R^y`lw)viu&~rgC0pVGugdT5BCo?^hRR; zl!moAO-hXtu6b+reEDLP^BX}gErr!WGB=4O=%N#FR>8kfVhH`okbGm7Iq#ckt{q9S z!{OsGg&dZZz0ZXb_)3td#&w!vi>N~+Qp1R1*0&wAOI3sBce3MQ|Dgplq`Ix+`=3{Oqy0{w{ zJvko6_u+Y)L&enNG88&GtN5^Ad;Gi7M^|iQ`^u&VeZHY1*2~CB!fj@;Ne6{c`748F zIKSg`C;jr|u#TH}8+xm@!KXeJ*HXYdbxAMHKi}E5+{s0)gQutGuL_gwCNOu1CF`i3b{}$F$uvS<8wwQiijK2ql?UXZ_ zWa;1L$1@}_zrVQo9Wy(7a)V#e@rQEv>^|NqZ+9$itb3`sgsQshmFLmXN$8K^i^a)1 zrgRq;vSLVqf5}=?&~x^sJNeP5-$S~j!_Co{U&MC%QNP%z%V54iKulZ5nYV^@?0o#t zIl#$^!uwO$jc2^{F2Vif8LTxj>-Tm+{VwZzJ&d%mUIfD!_A>((K-zHSB-U>Mx>;f2 zgf~zMGe!HOxluR}coHVXi=2gUQ)^WPZnoePyFe7fzxBKR`rSVLT%x0OK&*iQ^bARf z^DxKmvm!Zy=XWOx(5nqA7>2E6Ss-Jo)N3EeH$J|@aa*Gf3SUE*6ppq)di&R@_I_Pj z=n;M#FX(g1Dw0toJ@OD~D=t5I;uzS(0u8{lGO=9a*PAk7V^{)b*Q!ql#|SoGkgoEF zQ2LPDsL4`D>M}dp0Zj0^n-JIS+{g?0Ek){DNV=MkPgeF0yqeIvCKfJ+{@}O%%Dr>j zBYl84n2+qgU+34#JP*J^i(7$&SY|B|5aK+WiS#s|UsgXc?5Pf=OW)LONj!l`0dNS0 z$jfd{6*s@5re{cUIbi>4F~im|VOAsT3$- zc{31;sIxC$;>T??b@@8f0yuPE3Xk0qVh|4`3CRD z;-8QfA@3@h&oQ@r_0z$juojZzeJUTo_wa{v@lP9A`7lMdA zo7YW+<#7PtcEul^K^J^0FvOc})N|>BELRLoB|o&-H`=zA$gJ1a zd0J6gr-pSbPqBOO-VG36h)>(N>2MA)kcZW=Md78OqHF{SbMemSj~_DrL?b0L*$BeA zNCB#{2AqHy0dlpO4+IbIgg`* z#2TIdSf&i=)?zkBZEte+^zoC5bNJObfZ{lE6ViD6Yi^NppzWi?gc+~do?C!vrZxa8 z6XzfEI|dkILc-xG|FyJzdiyK4GwaCUrBx^A9ML<3HVBIe?L%P!wbgXX3q8mRbV`KD z^G60w1`eB2wLvR%V7|6i!(gf;arvLo&L{meo1H3c_(;w0MK#)4;1sD=Cq#e$^SLPx zP;kwK;OWuH!@q<4#vn24B#b#|ia7;YA%sm)u-JhI(q{{Onj25^8PWI43kLv8JJ!DR zfHr>s5V9s2WIz=G-ph&;9XASe~hzACa<_IhCv#-HPy%VduIy z%1Fv|hQ{9TYvLfSBm^BbfRMeRc9(f!JM05j;2sz=L6q_IHD+2h)4}RYJf)6R+ALpS z$~W2r&@5pu0>8pxm8%Pue_okUj4#x7ie}Q9X!Vy_>!^!6Jn>)~NL^3SRl2&yIf9us0%3)ueyMcx$MH1;~y-n|sZ>t$*iOkc= zM(S}~$WQdARA#-M7aERI0#gFhrv_FH12M8-G4FV^u}X|6?G9Btvz+?A=_P4m7%DdC zkDWYlhFlVMM1ChdxP|F@3jL~T_yeqD>GvyX;Oh-lFO5bI3z6CpEgY++N{L*Xx2 zn1qb8B8bI|Ds9uPa#vtkJHeKa&On>4#hZK#pZ6vD0E}ao-i?bqe?0yMIdN>?*K#t< z#Q5L8eS>=^do@s0a8}FOht9p(TrL}gEA-28YUF?e4C&eu2Vqs3c ze(>f;Ee{IBiK#Yhp?08yPLE#nd16U|dSkzsmmPtD?S zI#w&o_v6_9=m=6(rK1j92>$kLn0cO2TgZk0*tm;%XIfj1HKlInpMro|lSL6J8*zV8 zzI1V!d@71b3utqZZq@4~E$zNM({Fiz3g;)D7cgspK4bwNjQsu{fm=SX&W&Nns58bY zBITtvDNeArJWzyT4&(u{(W~`h{W^6y3PT|!@CDb7ug%!La-&+T<{B7>S=PyNS<`Fo zBoiT^q}Y~) zj}{g{TPh?GpL#O)yY`@)A93neh`EH$G(r)_3#J>OYQl6!FU&D5qWm` zeGG7$8@=1qk=1(0!V=@o!!tLuhRZz_kfql{Fb4^j8H>?_me4XcVQGe-@VfVctR?3o+t0CN!(8?SrR;3ueH zr?178_nrCwydxl03b!3*>xYhP_dow&_*Hs=U2RWr{j>idMAm>((vy)e(ZQR17{3Jf zB_X5+?SE<-WvL>gNt+g67Gi-QsU??h?tIFs_RSSm_-!-R&Plo0(9Y!%O|eDark(d) zt-G;Sp5jWdB)c%)mj&C{EbW|T73kZ4Z1Ie@g|DtCn>gTA+C;!92kENn4yn*M8L~p& zx&e&AiBR-eCZ|?Xw10^S@XQP>+Gq^4F&W@JyvS7&9|$0&VB-$A^q^V*^`>^t_I=8d zlogHjGj19k&Eh74mWN5$jqS_v<#9=u5v)z%raHN(KJR%b`{BeKc)`tXobSzPdM%y! zwkMEi3ZkbXN8x*_CM~EDJo4mddy_N>0+>&}J^BEt$Ax16L;33mr7wMpZsPoX2ReYb zMAf2e!|@WrbRIH$rg&EOLPpeRzG#$ab6m*=+6yBEQDopHcTJmPkmgiHb-}0nNB%6A zz~T4*#7_Q52Kn+w;sm}8KvEjPB>q#O+Up`;GcW#!B|f>|=iI5~Qn!D@b3LU+x-&GaVu@aW=Ji7bE<8H-!t>i zzC4rcB4||=^RQ}RuNkm=e6el0Zk5VY&lR!|j$Y3PJ=RslBE^4D4 zG6Qgrp#M(R+pb0{zY5jG25;P$16GhdY&tZ4q;t>QYw{%1eHJ@qc*Xq|4U;#4;=9hf z>Kx{`z0Ss7u2mFk?U@Wviz2yC)ToAK@_)lzRtd*b9+V-d1gNNp%`~mCzvMH6YciGE zg>bRuV%4J5|Bv)AuVt!In0eJIIfzgktsmvvbbM-C+#S zbJ^E)Y-YX)JTq^0a0psFOpwq(p?30nZDPU7nDSD=SUREuGQj>VHMN0RQ237YuB<@| zih({+ywS@p{|nT;i<#Gu`9gRG1mA%}&k9#qDdOAudxC%)!_LO_UXrD$oxwor zjb_cP`ZCmnDK+rjH?@IJp9=!9XmV?%^XAo(8EqXyqS1qG$uRnikj;FwJRs5ch&agw zhmMByYyge`L}4sdbdTC{@zM72!$A&rSt>kJh(#oP9_|TXTJjbInD0%xAqz)~ zx_Uo?$Cb`V^oDT6(!Mk~k(iwae!-nZfN1t!n8reA@-uhb$o@UW;Hm!u+F%r62HqUTfDc$WnrMXA?r0uVr{ba-&JjSOf&2zB(C4}D(3 z8{k|90RC0{TJaD5dan@f?5&SJr)AjU0HqwMS~~oAryX*Dp@^iq|Mn3wkjsA`(pNd^ zwW=BONb}{C@J_T=OV7=cdA%fOIEw-7ry=$7CvA@AgKtN9TO1qBoB6cY zba8mTC{zh>D+K+G4||bj zEjEBGvPc%wn7z;d2Z>n7eVjfayXenE5>_TlM(reY1vx|Ti zsq7lt1NqHTWDG8`L!Uffp#<~zZM#ge)ATlBF#|av3{}s?P?C;pHgdOUk9fdijAOaj z`&yp(Ro!*H6)lOZ*$cFhRRY~AWOz!gqWKpXQcM#h3jc>3kWqVgse{)LpT?A12QFWT z=OG$H45e(CC?~2n;}Peb#bNX{uPY@J9-s>iNcJx>ngt2Pq#78}sL+eEG%iL(17pb`a&PK`q6(q$PP@3L4F8*3w1*2Nl)5MPtgZLXnXk~7JKsn$_ z7=AD*Cdo>h;zm1-cLRwu~VRQ+;^&8`x+IsvSOt3d?B#icPv67pTlhyFtB7poV(UBV6i%hlqc< zsFFKelbGE<#E9c>SZo03O9aVvRJG}NbY>4@%n&Fp1X0bR_9B=A2-jS)2c5j|OxSBS zQrAs^*2Yji;35B$=r%+p6I$|Yclo&ItBjvs$o!o~bb0n8U6v|g8yG;XxoWzK2ApIa zuQ{7deR7+nB@)TK?;6q}m1;ngi2O9lkn@6kg9y7}0U?RJWz*R85o;6GS#b}5h^QUy z3}yZIfI@aIz#jZ>(X4p~=C1yqvUx#XXfo>;XN>s7 zIjzb+hoJ-1W`Mfxr(BD(m)4=0MF&bEA~6y`;{V%6r2xS*R279dpx`~e>$zHrsh`<{ zAyfv4m(9b6@tQ!L#uaY$eePq>sy0;Nd5}F~HWmV3^EK`KriXH9G4K;#ZZ}q{jk8@V zWjc#CVDI+HT4Jm+10sA)2HQk64`%?NN3dXHyc`-)gyZZsAs|d{pCTY+MT1)QTyWn> zPhNO~TmJ%^m;H_$TY5^u4$nttJBe={zZUr9^YQ+Bgs`P5^ze;KYDJXfFD~~bUcL{; zSh=q}V=l)xn|QeA1u3n^;%^ojsxeSlK1t4GC%L8F2~|7)E0hE7Fg{)hR!KCO3I3_6 zk55Zqx73W4k?I3DmiVc1XVa_KF{OwdF?mB_a`t~d6D!6wP=WipHi{EI6Ie*;>7UfBPAUK5Y(zslf5F7zrPRA zNE(#(g!80MS`VL)yp61Sb2fmy(D19TV&%HK065nFZ0A#HZg`3hq> zBbYAf_wOYFdK5DBL*!g2VTk3beP}eSHJI4E!0+?nTfil=l<>;j4cOA>b90V`I@uRW zWy&3EPzVb7M0kL~1(q>W4a#^1nrQEm-d8BFZ{qH>aJMdioaP-j-(}8UE7YzP>u5NN zw^jd(_B|kj(JX2fp#?I}y~vUw8<7%y?oqkjFlgc*q;C4v{Qxv!7&?@}heSPb z=!kIpyG{vq7iK>FBriA{8Yer#yk1pPxwid)w#sJLypq7ud_RNK??qG_xOe|uW|U_YraU?zq=P>GZcDJNNmfm- z*7ZsLlaJb^osN~%%){wG9+T4`WI8#)P1479Pa(eNVEIghiAuP zLTMxOy46~Op_OeqrjNh8vCO#y9$@P>%epCOmP&JkOFzrl5tyt2T9H3r91RR*>HqHj zOM2YdL1`WR7Y>8(`S1fdIX2ieQH8xSUZ(4RoWP6jg$DkKp-4#og)^BD^JgO6iqw25 z=7DN8n%Kn)lR9$UT}-+CelL3{ukmn{Gyt$N<-~`qa_HVsfVLw(8>QAz8d?~-lqsnG z#~4|p5^bK5dP;}1T@K!4d&FGcQ`kWK%&}3R1T&f|2xw^(>Xg|wnWAzT?++PL+I`rBmy@D?Sksn-)fOU%k z4SY$lw{a4GCM9Um&}7P;y({I9Z`k|R@qrK~;j#+&xS=8{4WWr~B!xD{s`r!kSN0j1N zU>Kq70ZE2wY5i|s0R4IIgwE6kE+KlaPjM{8=K;Zb|vITY>T z{8^U+hFTtNZQ&Hn?j?2Ke>LI&RCS`GdSx35!>w3+=~yC2xryOsE}M+!x9v;OeW zJ>=D5%f;o37{KONaBn8k@}QhUn{eo5@_241ZbiIWmcycg&y4(wYyF+>5|Vf@TOi1L zr9++pA!)wI5*V-%`vRrl>i^YbFz+#Ghl6`^$~3aU`ZCp3VE!h z@$_D?s!H!RLI(-x+0Y_>QVs?EOZjcRw#GW!!&%yfZ758jZa@)Z!LKxa$-Ge7QvQyb zFrN8^`$-j1OOpNUfjtU*9`C$}FEDyUU?N?fDg4svnHTA1Ql1$AAprHw76mMui-%Ji zQPt~$TlW!NdIyAx~+IU#`XE2@5hH#)35sD7721!uE1r=yMCAl(thE zHT=8Y{a7CLB|zNwOnXOs%ATthQqz@T`qNIsA`I(ehR8x=q(h`*tNXOTl(KbS5q_B6 zy0a=k4$hUco&dG1yS+q?ngt@{-Lr;)9bU?qS)Zkg=^D2e;q7QA{gaaddJSBX;nE1K z)M|{i!A%+Z(B~z~kKXwZDK-16zuA@xhpw8PCF*+p6jPJAQ7>=sGK|0nO$P`UHHw?0 zXtSl9pE-|_pIZe7gvDBVA@aweF-Ut%^iyHG+bm%xGmvj;Wm zjlF*L&HyC$k-zi9pdi~#83#U?#PF;yuC@CN%2tkCCp$d%0 zUt_#iJG|@V*?E^oa6P7p*lg|1TbU&9o#A5B$BgmyLl&DvmxT1-a$5TvI3I-g$NFZd zmMH=5E60S+KX-z3d#_s6(7Ua50@rE+Po)vvhCP4$t-M5~JW(y8c#*9bBdXeYpG^C+ z;qbs0f95+bZcF!F&Ngy(6nUBh5mVIrt3DyxftFNlnyAxi@v8>N(bBL}2s=D&Y)+19 zK04S{Ts4DgNX_Bo4b!bz;D#`aC%{CS~DLu_Z8T&E} z=cZ$X5j)pw)K=nM788f-ABOE{=JD(oJ5;nvxQ1-Qmc#N%@6t9@9v@pk-}GrZRJ6Hc z$!__iUefp7_60nZAI6%u+6V2L8Nb)`!wTR*EfhGaCu&Eyp{d}&&omI;h-RE}!y+!b zWN|E1BgAY2-+bFM0ek=s5~XNkGykgl2y#by&Wf?ic(fSGCR3X(rQ6yv_%d9B9kIcC zz8Gud8#q(2T{)pP%0M<%L^^Z3Yl(>@k02uEMQ8#)UI@LQu&xREg(<)-~FFk-xpppEZ<#WRyX; zPtkztAa(vr}n_4>72`Qg)~ME?GwqWwe+0*^(R$CdZduD;f0hIC8>JAsii zyQkOgzlqik@6p=02mo45v3QF6U}FE&QFGqMsi-p(YKJW0-2)MQ{dk_GX+OK!GS+yA z^VLjhQw5A*2E&JEjZkVo0gq5Eo(9)?nl_)9$gYZrIf$k!@^%@v?pCKz!&vJR}7tko#;(b z`a!#B+;#J0QP-;yx5?{SzvbtZvSHo>Qn3G+^LTEok&oaYtaQw|G1@wiNunYc*&hP) z=b{YQOFS>k$W1IF06#E@U2e5+-z!!eFbM>#O!>ua8oNk2G!j8G2w~DPAQ>C9wILOr ztsF+~K6m{@d{Neb)Vba6cA(ShXo6;T$2#cbo0OC^lFC6-^}yk$-)u{==Ga<8Xcla_ zlMDG8?h>E%@QWd72PUY7S*W9z-J#e#7(oBxktOHuKjlT--@l!#382`D=C+;Ptn0=@ zp>Mbr@z3mKCg_I0<>s+F;R)(~@MBivK6~>M5En&p%qy-{^saQq0Q@$Rl+^T=QqWk5 zb3;>wEA2Z))_Jr0p?KkW%Z(Lq)y?qt8Lj`q&j~=~fdWLyFtOCW0)nCIa5=r#Bwq4U zYd=Pi?Eqm8F_+^-MiV|CoUNlJAe3_PM4sa>T68rVD!`nL7cLI4<*8^vi%D(k2b1OkSe&bUe@(BHKP^ zQ~s17j5DVX^Iv^gjYaexG+vm0_rJY!kyF`6E9Cb-+XapKsCaT4UanQVcHyU3YtkGu z2JSSC7W1TZn4)Z{xZtp$*6S?1zUZVV`Yw^q=UnkgQ*L;w>90Zds3EhOtz!p#Q5=@< z3{pI#`B;+{r*uxDQ`Fm(G>C2g3U`1B&oq9UMvOHbw>F?%0sLv)Z@Ou->)!5CIv>S9 z7DB)QHh#}Oxr;|1N&UJ+=KOA&awNWvnk`WM32CD7k%Qd<#y%uEzG2U|M7V~>8zOjy5KCw{Lh$#A&{0k zx(pBHLAL2|k(3w}bel5?6D~no_sES5a1x!bI>QuDGIzQD>+Q<%<-oNsZX29WDe>ki zDoUYvZVCGbLnfRDh4*mpC%U~qiDVsKpKnnM5XIQtps#1QOS$^hlz86Xchzj41vBvu z`Nl{+>{syz1nAByb-rRBw!eA8D)hakHHz_IBRen{*RRMm-&FAWyu_%nCyV6egke=P zGl3S?s#8BmobXWi@w&2hZ& zcGt3wo?#PB&8WCAd4YNR)#knvW5_weynaC8XYIjSMu=RXzUKEQlKDK2fkHL8L@WWA zP?NH`>|TV>s;i{V?7xe_)2Q+2Qr$oJueij*XYoV+(<^$dgwAKO#nG*f?v zl6@P&r+KTAAm14CfiJu4EFDh?d-Z~G?W}1>Y2B~3b#9t}cGJqE(0zKv6K8irI4cHC zNh*1klX>Ept6!bwz)!6_-Tj>M;d6v||nbxt9IMVBPhUal{5;WL-|;Hdco z`=_JVCY%K}ky(m+D!Q`n^VuSUV#8TUvxh1BX7=YAR{VSSlZ%{LJsFQP8c$ypy@u2i z$Ssm)#eq*{W=(_01RltLiWi2%L&%ovZ&q9bGBmF9U8wm{CI}EZDxTWpo*p`+c<(D9+ zI@IakL8A=bYLpeeBf0G*>C>w*1L8aW{TqVi)=w#W#Ku-l=CLHXiBa>Dvy%-Y>tdF;K7(F}+Q`fhE(+cIp=`M_A%&YThBw$mO? zI|*^99b{62%PV0Mg-<%!Lanb*q|*qv)FveF`$%1>=h*7%N&W?JgYmF3;@tVS>u&<7 z6|PfZ<>z63b_r7*?%kL_3&;6gGh~}z3&)MkX#2L&X2jUlFPGeV3#V-?<<$Sm`Gk$n z`oHG_I8V;{_`RLXaZa)A)N*$zIlR7UlB(I+I2%ni6HeX8EVn?yofSJsGWQ-O|)(UHcOfC?~iZrcx>ofbSSfw*}E8~=H}H3YTy0sZlOdsUJ%l+mgkNcTXrPkmGs zi6834_HFbe2MG4U#Pc9D8l)Z)(wadGWo5;#>~f}NrRzE~8|S2?Wr)e(LScFm6HGBv zrA;ce!@qk?9H)|ZLTl!RtpiNlnrS^>@QG`3lSQzZUR!tmEtz|zQaOQdnmR$^M--M$ zOrYJOuJk59f*mpAH9H%rdM&v|t~2%g%US?(NisK7GH{t(=h%%E$cdlWq@rBUQi`6lbrc!w%Ufuk;8RJYX@W z352+UlBv{t{pO=MycEJ$G1%reAP7OgJFXI1)CrQAgpv&ClwOTxSpGmDZV$I0KvJQmS6 z<#H0v%8yeF+ONa@?K-KH7DeO0^hWm4==Wl)Qvtbtf;xa7hJN_Z)EJGCI?NTm1^Zn5 zGRgzpBcmbSRvQVuoiCwW#dB6-iQQyvX+?&nf&Gt>RO70f(IcRP?X&`bx9(GW& z`oUw$`*sXL!ke%b!u#K(E7yaJ2{k5OzXi2K6}m+@u9&{wo%SRN?$vDp5bAOes2ST8ew<*haO8b6!MLI$r1ZSzrdVtRz@<)a z{J}4d%%@7m?5h@uJ-Mu?%1I2J(WedDp{}3NRRkT!C3*^<ArzZ zUukSLxt=WISGWCaZ`e3Rf>s(AEloTnVI&7551Do8dEK(5dd zd3pqt6;#uUyuVRHTwgnqo+jcuc|VzZEgqzfSb^S`JA6l>UsI)n?)B;$Mn_TqYb4!{{YkZ2!Mdy`Neq@_m;{L8yd`KfRhP1w^fc$Tf()TKz5uX zu8h+So>#^~&6Nx^p_PScv#8Yf&G(J}9BUlK;a84&kTYE*tixo5W&X5Z3y$V2`^GL) zEWo3o!#Y11yg%I@E2V=Jr5={H=M8Op`p7+kyQXN200?Q7`XNWWT0aE$<{YR>4NLkb zem24&M+~cdJju>w4oX`3eEurLESSKQW_PDl*MwXve+gp*e=Gi8zHQ(jRZ;PXll=AD zHQGdGWBPYwo)U>$>&}aikLQ_#RG438hq9~7^)LBCC{Y!WpQ}$FoQjsTJo2SFqlPz| z7eE4RueU7Jif6UuUCLXGrc1lkwtSh;@DK-VY!}we0>@x+R{7g$0~Z!_R)E4Hb00wN z^yB$AtF>;q;YVV!vv9G0V=RSaMG zo{5Hmqq6~tcTeeX$YQSATMFn#4Y~S|=t3S=!_1oQcPNH^i1ac_5_pQ4wBb9+bVp|;Mh|5x zzc*Q43_S_Qg`s9%igFBf%(*ZX%V#- zD<-R5ac(MEl(}-^rhiErGF|@PK zEP`+>Zhan2-?-|y_d}DlEw@;@r%VFxG&t9&`kMN`g<5~6a-on~0lrW!yOGF4qCYW4 z6}9!tTLw0ADPBPY?F=HyIH}c+pHaxGo!Q3|PpU{8_~$3f+>>IWKBU1L$X8lO72Mvs zJq?|!IM8s-SG!n}1Z^BVod zVzMXNw=%&--IFVBHhPW9q4VNBhY2xriYCBA5goCaK-0d(gHBdE?*oVS*cY1t!eyBh zDSjnGOByoxPOM5X>rcz_E&`V6P`dXfS*6gY-Xrmzkqge`wx9R!2Th6?dqy=Q-%SR% z*)&>f2=>sr!~1Me*xbnhfB-xQVqD)S_$gKvG5b+JaEo!cnIDi#;$0cYUc08RR2ESR zWTG0-*Y-#>@IBJ=NmE=3@FZk?lJIVWR0_}3YqL$)pz6Vpi`%Nd3gji2@t_YB@D*|$ zHot30IeTqZFX<*r>AE`M-Q(NSbATjquN|ax<$tFoV9FKRA20lbk8&W+I2>4do4U4z z_w&{`tYp9;K89e;jp!H}`tiR>lWWc=2|3i*R_Nr0d|LLa;BX{}UbH%vFUxKU9r*vN z>nr1;?7Du30i*yN21!9eN`avphAx#(X#qhxl{I2WT*WP>mW39D&%-#8~C*L}d#`DNq#^#egHAN$d2ME@%v{0Hw z&~D7MfJBcG5kzQpCR)9!P{S|-bl>1rN}%h(=`bvJR5D<%qda?q^BZ|$fmcqC^@d_! zqkQRZ2^L;A5j!j&nL*2!#?nlF$=@fL+ zu5VyU!W`A(8e;uP7Al1V9gT`zXhw=(nDTz7uRdQ@f3;BWi>5d+WVO< zAkudl^ya-h5AryCEp`>i0@04%{>J?H4z{k`pT)eUQwS zE$&*d(%L>g6}D;bts2`%Zk)P`r?m=mWC6WNOwE+A9lnkg1Omc)`=lARGOp9NWz;j8 z_A}N`96ts^9nuJIa7TUgrqy6bp%^#4-#6F>SK~sK$J;bTv(kO%8qN7esw{<))pzTR!$8hP#~JzETpd?9`IgKn27G=yLcQ^s2_YP9u`N>bQX?7ZWh%(({bPszfJ9cEKD zy#gqkZ!VmBmskoZMyF|l9UXtrsK6M;`s-e>6Ds|uD(fu|S`FjtDR%md1+!Y!3R>3j zG8-vf&u&mCHiZ5l&&7gt1~qHGa}Vju-?nZjVJWFWA^wV` z(}))}iJVY&R~4UhMjpcjED{j}+9;bfNgv}^pp?RqYq*eJE0!?9NgYf`w(mq*aIoO{ z4X)wbn1$VPli-1UkwhQ2Z&b8by$@&@J7l!F3E+~#P#A{3+SNA!jDz5si&6cXcjAl$ zirsXgb`#t7K&)xC7;gY?`(tV7D;eSP7OAWF?K?^f6&5N~ngXcuru6;*#Q^p<6o^C{ z6&))e>)lsV)<~Mf?SbrIvJ`?vX#YlF^~H*N@mVn9j;@H# zSn0Q1rLBwiC$Ai1YA(9C9OE=VQPDeGK2_A>+$Bg2kGGtnNv*D_F)m~80?WojeNSp0 zDygZvDRXLfsp&bm@nfK^>r*Xgrd>Zz?m4{SfiJI>ml(-r-3o)tn2okGfuba+9ZW?J z`X%`QX*cehN5oyvo{Ck5k|9Obt2|%LeD8rqgYYys}?*c;&OrX%s!*?N4>x zX4gO^t>dzyF|xm`EG65f_i`o;=;h#?`*2`~FD?E4p*e@wMOGNH_)t37#sAV@N2{LN za(Wpo78OP*rBub9+uG)|uR02vwUau2u6G%}tu<-*vw^)jqCH+WLmsJUb zWKzX=2x&;C=3S@{Yi(7E|52OB5{)HbxM_t4!Q?G+9HE*E2ux6OE2oELtzMF35nzq-k zYA}fYC@k%VhVc;;ECi3YJI0n28V1*UH?_z{sL9#%4JNaE0-ZuR=0$ z#>rG5gc|qyKRb~{$rnmSWCri{m|%bIMd*C?4n%DHu1pg<5I|b>X5PdDPH0<38wu{p z@+etfqllZ4Sh)G3&^v4BCsJ=J*9Z}g7eJW1X?5g4a4NwL)1F z?KfYWZTzx1`axll0{uXKTe&9E!N$Br%r`QnTCU$`N?6aZfGM4^f?)3h2T^|sTH^?e z;m)Gl@~Z$BRih{MVEJ`m^DQ%#oAYHg(wBUanYVO1jWNkb?6^I)+Vy${p@rULdIJ5z zX+E<^h9*;aBiJnsc3<3u6@aJH2lfRR4D%}lR+C0YY16J%wBBs+_F1`CSWGB)v!1jf zfF6RZZ9atj2Wh>`@T(ClF%DWdOdnX^ zp>oilL3I1sZ+W+8uNfS_37V=<4~V_K7AQ0y8Habs1nl9HVMSwz_ZYJILA!vSyZQ5 z%^1>d-#8)#{f6;Rizj$J(H-bU4Q~=YndIn)6fkMMh~W=JN^k58tw+8BIL}w7_v#35 zPJ2PLi!?O~g_u=k{pv+)kON|sbl&GCD1!Q+pSvl#$HEBIv9nXzT!JD|Y!-|>`B(^B z_^t;7Vj`sjz_&m2G-M^Q^1fWuHrTFcK~o*Y*fiG)iE9|w?d6qNl? z7qJbUjlR{@^lc;gVX1pcbQn1wMGtj3#*xIhUBMgS904$+m0xwD->PFl+iR$? z=5vsS39{F1nxjjHzkgi)%y#i}qCInbq|a3$79v7*2U8}D5ZWw;@qJ-8Xl6GRaT|Ay zF~~5G;vr|4<&KU=b36Bn1*4#b2Y5p{sg##h`2GIwT2|zJWW7V$xLx+@m;VZ*lyGKJ z-Cj=EoTRXzE`y3UjkDZX+34b`mA*gbXLQjSaz7Pp)^Vv7<0$9Sjz0G!m-Ckli7Njc zT2scIS-kbCtR2_azfbaqy=YTWjh6Ey4q*?}(9Qfh^SWAAEAOnY-;?q=-kD{~#9s2| zxEKZ&&0RVTuJHYEP|mzc4^TyBf>qc^vymq$iPP?g1g_PA{Euty-j2*WSn|*m3 z{@EHIj21|NR|nj`uB|0EUE7%T*ppU+1#}b7Q_M{-;HoBx#+b!1l1`a#`xu-+dL$yp z-Gy`D_iVn?eZj+fgo2vc8IV)Zl)7x%oKpf>Og6DmKf);y%B;1IVHkJZH9eFyF(fr1DBm(a~7M#OCWZqDH{uF%_pHv*JH(DjK!05|=uDs@S0 zT61(S0Wh=?-_f^Wb5P=Ia?1AoMUG8JV;x%zB&N3ZVRdX_MF!yHx7~(e9q;g6{tl)2 zqfN2Os`(1RY$lH@?mmBVP11i@QTIzEZpt@5Vm~nHSrBC$xKSJKZ0;0a?2yd0<4tQI z9#*&RdBa0^HK_r_o&BeQSi>^&zxV210VPgt9MmrDc-<}Mg#^U5ggYu#NR_QS<@|tG zeZ@G&x^$NRmCF|lG^$A{t(Q_4@Zc<@<6wQrsUO2f{Z&+>Yz&!c4eo?Y9>)=$b&(^b zBV;!mUs0>U6JUvBk#YFiMH)m0=W?G35R#5`3a^TgL~3BANh*BVITzv;pFmIZ;S728{EHrV$zX2UJL*>RGCD{fUhi7yC^F}SVrZbj^- zC=&n*Km}$;e4kIE1_37y%8+qm`o?1|j`T#8+jjpQLXC<_C-GD6dykY~Co!p`0u=pc zh_|&D`T!dl+W6r-cBC!V_Y(l&J&}7F$y|ss(VFvQ`pUi6BCm;<-LtBtp)jh2%FmXhJ;}K^rp@#0Q5m8W-<9>a4)6n%-I2QEe3-FW?ipC#I89>!J+&97wXCf zOi9pI^?U$CPEUv3UJOxj{OgXc7ga^?BVZ78 zUHy5X5}B&yl`S_pJZV-~p!bSpXlDS&zp7l?>BoC3O9T+$v=>NyN2=GO6B^d(K8_|Fw{kUXtVVThC2PvCAlz!IBCh zb~XDOR^iU_e??aK8@2yOEVY`shpz%QExCA&tuI6?^OdLzcu*GR6xl>su3afV`F^tD zU-WIQZH~fEqAY%@WNJAYpfp`4Pu1W*RL4AZ6Juf2+&wCyyU&}AThMNi-3R&CGMG%QM__!-@W$V7>W6QciJHV&x& zFE)#m))23g;_F4?t>tmia7l3>vqJ-MVS&&h_2srkuU4A17Zup_!zCe$yT0?b^8)j? zrh>fEwzz=q{eYoF`w6YbPc1+Hiei|MLGit~Yk0A*zR)km>|dMxm@Eq_o(Msiys3fk zXFxg6m^+d%h(%O2b9BXlgtuGM*l$`2$C6_8P)qDA4~~T5jZa0c!V) zw3rQpDPeBvtSjxhRSd=pGGZ-1(QOhxgw6x|Y*}vUll(TJjms*2igVP<@BdqiEQPj!oT{nT(CaDYUcWyy!p1HOl+WtN^M7rI6H|#|TENchMfkq3z1e`6ro(M|SWL`KsUh&EEMu zpGj1F3HE$~IkNi@87C>||`{uRqJI^Nf6 zbFI>}esIsAd@5M2KkpGtQ0)Yn0}~9{cWiPlyNExp(nhM*l2t~XGBi%nW#95|sDXxy z78opzV{Z=?)j)sRv9hWWHGAf9+Aa*EDRWM5t0lPoUVD$j?S;g%aN4wsp8n$+eD*2B zp}~Z4-T%_K-{WP>LLd|;@-j~}<5f!g;Om26k3aQkQr`4Vi^UJG@XmQa)kI9EVM^r4 z%0u;>oUXM@LhowL&SDlAUxaK}i@lk5K4a6+Y^&2H3BnVTnj(gi4;r6G5&c;vBO)=) zWn02#p{IGW$pXfQ4#<d-?+(wCPLcI`T2rP7$+YTDj4~L>!KYt5@xsp1gz% zsZeW>=lQT)mL0L60#o_ahXg%hKLx~cVf}*0!b)jBZ@OH|&pkQzI(2dpf;GQccnW?C z1cU~@sbbcsel_r)a73G)zs5fQ5w(HLp_Q_(%27iQX$FG4W%gQ%?HY?ap`Yf4MUp@k z-kStph#QIf$#1@0?-Lu}kF#wR4v#4mz|3beO00$St0mgGJRdq7H)nCVmMeV{evB?| z=eErS`kjKj&xeNBKG7}OAuKMkAI3R)G=601jJH^-ufUE+MrS$cYIH9&HCDXH5q`_z zDMYq`YGL9@Yg1D1kH|fR|BoC1Yjq>~GQ9*1Tx67=b~2_t=s#A!o5pL>o0(4bkE#xP z?M{0o&F@DOOr#Y^=+`hj1(Tq_-C(W1$oH1l2o>4gfoXC9O*$p=+Qo>FdnDjj?N@?Z z{>gE|q~KH8%kS^ugOn6>Z6|_enBnd!N3NmH*1q}aabddewPtcBLLC{h-1VGfg?rpU zOND2_kH97R`|o)3aepAwM5^cD-??RbLw~Wi!%=*I-0C4W@%YPl?1R`%l4PBoB-xbc zejn|B3G#{@Yn4U|skPenTU(}2lp>5Gr8&iw`_N_S0O{at#&_jP;Gd!UTzkynwJ6{o zHl|#Dy6?{dwFC~O-3zpF!%^Ee*BmwhQ+)x!({Ag}-FvLcC--D&HW*eFoRkgl8F_SJq$LEP?icbd4b?RLR1X{VH&jz?{NZN+TUQB}4G*5gTA zF{_G2&RId}K!PVZO!^&Mf*MbckoMn}x)#jh9iZHp6ScKf*=sjX>o=T%k+WK3*R{)ea%2b(1| z@6dQrfRD1+dVWuyufullRk++LmQ&TxP8Pg)4qdRi`J#Q#z zwhm34_K^C<_xChxAmo~oS|>)*!HBf>U2${o4Z{Bg!Myd$|I$Ez->6`(D98&%x$;kD z)v4c7OXBHR(e$SMF2J@s6oV$PiTX$|O1cbl^EHR} z9{^Y5KYRowYoUTvN-=|AgRsFWO0@-AQS}2PM4LV*F9a8#~A!@PmXWPl-=F}49(M8SJEH)=?5!|KM(rflK;V0 zh3Ubp-`5K)9hHZqMXb+&y1={lM2znCkA|c~T2x2LTl@xrymmJ-K(b{{8d$tu&d7(( zS79&UwBuhT6AF#~lZVmeaQ2lsv1<}ColB(Hcq>t#Y^0p+f)H|_k;uU&{%$*RUxsZ7 zb)Co2d5GT=8gV3iCp{bX6~KQ-wqprmprX+&czN9ms+C^2s@1+gz9iB5%bKdEFm?86 zRfunXGrF9x-9Mz4XW3$xUcxm>qD=B5*yBAniXX5GvExob7Hj~)-?q`ZKB8kUf?3~S z&+qLVhQH^+-QXfgiqK5H6<_3>wy}iDg}q{pd|E59yDB-kj{AV)pr6mEdzx;Hp}8%< zM#5z_IacztPhUMby@Et8WD^We_JZ-E)N2`Q%a+BR_m)3CU7ek!>#_Y4mQPyT zV)31qPO%C4Y}@T1YC?YkP!uF(=I zomE~u?c8JQDb-(W;)&aOL8onGrN;pwFL(jS_o6>>g4qDcjn z8Q|8##Z6Hn>GydIDd;K`7C@a&-VImngQBX6EzFj<^_B^(D3K3M=@As`%!#{`45x*| z42~MZ+`ly%=B{u*u9`UsKlPS}cgu$PzU|94mcsm*g2L)RaCB%WQaXJDx(HZ(% zB+d^N;1d`^S@iz_E%6MKuk)YanRSxY$=GCW)jk!p7KWR7%uU zJoq@Jy4)TW<)~*4+Q!e=8;Mh37-6=M9rTC8d*T(Yhr)+BPR;L`?fP=2On{rXuv>uf zEZmLeI)%K$K~p$MC5{Dx>r+vaVA$l*aV=Mb?FxAnnaixICYc3kYi&ak`8E46F()Vf zGLkqbO<9_mC9!{M=^=NmNwzE30+ectfU#B2&*VzvF1p)QxHtVbEsr~Jj>@l03s9jk z?d!nzguPifG@$>mLriC)X~x&zv?`KrA@6Knr3kcxZ*6zXCPKcB+`pEjy58fT4v+f( zex?+0r5Ef#>`mO%P!r{ZM$_DUOlr)G|M4_Po`7xHcvki$eiT@Qx^}v)b2LtJddvnP!FB^!LFuOb|?2jBdy5=R#sMk%;~H5ex#=JK%XrbAWhXUl zj0j&*m*c?BeDmz{RO*pVntFqvnX~6l$g#Qb&d}=t+x^L|NP|4twAwwcKA1`Wz5GpE zK9}V($!8AOs8zeB#$;F}%jM{s1ZRgcrj6Ehz${;D&cDQX5Ze1+FKC#NfRGeJ=r)gY8$vTK&!?~ zD*=8MJHYL%UutiZ$q1_?=m%XcaXW-3R=qBe+q@NYfHzO9c28%a192zLgdP-urImGN zAK`6eyW|Zpo1xV2_`{z zxe5DxE`^mSCAGRqatelAu0kQrKC!z5f_MT98O6i?{eQOiU~{F{Dr0gaFEWW9gP-KY z=VFVNRMI}a=9*Gm&h(@wG-iE8Kf=;N>$x@18A+&aq{wN=d1B%$s7DUWNpuCW1o2(#a2sO3CQpP#^ zZIK(Qs~F#-Da@&b7c29t^t&`7$%cFzsMLQHC;S@mgASDEZQ4p1IgsVChsbHa3qAo1 z<9OZbA4FK1O9^@xHxvwg@CplV|H5Kl{-xP%0axg{akrIQw;k^k;XoOFE!v4jXE1GT zs&Dd)Q@B6*L6KA`yvb1!(rvX#MYhv|GtAIY0zgk(Vf!mJvT=5&(;|@b)fD~tPMqHV zB#ZEfUmX$QWt({{cjJ2&)@=dTfn$FBkq@no zCg#n?l%Bv~K>!H!kbsioxx%5KC~W`I`^W89Q-_@^v&7RMXJtMnM$rnmPI=RjH)MTi zeo?T|c+1$a9lKTW*w2d;cddkrQ}_MD#U-I5R?xh3nX%5-Ky5ki=o_8G=5gFRKaz#! zDzP4)?WH84LN|#vL2KQ$afVN??FT}>wkAY77lc1(yxqRKp-|af0LL*ER;a{{ z-grnV8N`5VSxIr1DLhXqjO`dq3QJ`4phZX;D7t#ZSQRqibn|o|jcHf8oQB%%6xjLPEC0IG zoqToeIe*_a5A5pxvv%<)_JQ^cC_b25D=N-E97 z_Dy@;bi&bmtj$^Wj^amAG!K~@-Mou0Rl=VVvTpoXTsx7esj1O2+Me?$KX&4RcO%!= zn4U&ke2Mi#6Q6w)-Ra!T&}bZ#alelr8TseK*F;W(=MKm2=_}dBi3hJTun8#Bb5IgL z?doRCxZ`(zp5wDtu+v#vNI<+R?%Sa^OY3IM{=71vvazwD9<9QR`%Tl6^2l{{*cY_= z-*$t&iA~vgiSpfT$MHG%_LLhVadYi~Q{LRPThK#`XXMWZzch&GeR4l_Kv{NrPTv`o z5P~Ni2V7@^5B%j#h2e+b!8I2QU=qJi!MaguTOv)vDm56pWl?gUvJ*O*d1YMQ2@~dSIbj5?mETX8E|*9> z-dQ;VH%dlE*ZP3`4~7}vZ#e)qC!x<4ID#>~*VGruPN2iOwBzT#eRa3b&?#jEkyHYG zWm$0tpcC-ka-516?b}{Z`1yAxJ}4I;B~VT*b$x-MIaP8lM{BfdE`Wm(V2(idf;8EQ zd+0)Ba{E}a)Zrus{I9w+PzR7q9*Q5r$}B{gq8>Ry&=7;MxZ8HZ6My=baVZbYj%vTG=I|*BlSeh}Y;<8GpLI2FZzMK3}RhSf(s4G>- ze3hEpv?ctwc$a%Vcqr>R9=B^oicNbUwo*!}ZCA37S?_iG=)eB!#X{SsHYHaU7epo< z5x0@3maT%g`N$Vg9`?`mM{;Mmt-Wa9@CJYB-t5Kn-m00f_Ny}F>PqI^M>`~NXLTma z?C1EbbXxQDZakjF6x-G|0*5Ow&Kx2{)}@QhmDqs(+ynm0==xxatkX69C%TsJri}bf z(H{~w{L;7TsX;NXV$}+`UaxG%vBFvtSFP7~3--T9;LWfn!wYy>#X}o#!^;vtC_@fK z)XNNh^!6$(p`R@P0Ur|ZS$sajg-x;^N~5~t@iGb>yjLsLubF< zgzFJ$$gUF+7@InHDO%vD*Pr>AZ+O$e0WY`RqE^Xo6?xOOxncEUCK(a8E;6*P5ofO* z4f_1NGK`y>F|OOt(tv^By`-*XdiXI)W{^;6LB95LK!&7Jnfz1QBow7cH?!G_C76H8 zxh`d6DFv~*LR`P^ifILEKl;^@dB!fi-&42Ytjz)!Uo*<|K5ud5n$y`YkSO)pJhwPw zr?nivWA1F|;AVKNz1F?VX9F(fg{o-OalAwxG#>xn@p0fu$TKvtl6#Hgw}CpZR6g)} zJzH&V@B9R{UN1AXaUqs+O#1m@tnWdH?^72IRKKmt)b>SlT*7U0c*{nqveL0Y;8^9g z+Z~5#JLer8)TNkCNLXeT+m^@RgodwZEVm<7d}V>Z6cvlHH8&2w2I zQ|suC*uIBpn@)AtZ-=5c(+0;y<@@LcW+^*({c9#O_5Z97unhJ?Yc_ccB$-FWy8c-c z@a<}g7+!2M9z(@Q-Zjg)C*}ix04uX&3=M#Ud(~p}<>Bk+yel@Lrhl~^*~N;To)i@C zPu8gCJy$&6Pb5dxd&B?F^4;4I2&7Gl!y9}+D9t7@!AAvg|2^>GAAFL18uYR>e>^qA z$&2J&#%_i0Ts4`=qaLSe1DpJs#0+P75~r{B$zxh8R|76I9%ZxMYt7cyZJHe3$}EgV z)zntJ-6sR~C&i&Bu>ATZoXd2&i(j0KMpaB)o9v<{aypskd_zw2r`>mUrfO%ZM6Yk* dKYw&bg?{sVtE8XZ4ZZ$@ysWZJnUqQ3{{cQ-dIJCe literal 0 HcmV?d00001 diff --git a/doc/html/_me_light_sensor_8h_source.html b/doc/html/_me_light_sensor_8h_source.html new file mode 100644 index 00000000..31b9e742 --- /dev/null +++ b/doc/html/_me_light_sensor_8h_source.html @@ -0,0 +1,163 @@ + + + + + + + +MakeBlock Drive Updated: src/MeLightSensor.h Source File + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeLightSensor.h
    +
    +
    +Go to the documentation of this file.
    1
    +
    41/* Define to prevent recursive inclusion -------------------------------------*/
    +
    42#ifndef MeLightSensor_H
    +
    43#define MeLightSensor_H
    +
    44
    +
    45/* Includes ------------------------------------------------------------------*/
    +
    46#include <stdint.h>
    +
    47#include <stdbool.h>
    +
    48#include <Arduino.h>
    +
    49#include "MeConfig.h"
    +
    50
    +
    51#ifdef ME_PORT_DEFINED
    +
    52#include "MePort.h"
    +
    53#endif // ME_PORT_DEFINED
    +
    54
    +
    60#ifndef ME_PORT_DEFINED
    +
    61class MeLightSensor
    +
    62#else // !ME_PORT_DEFINED
    +
    +
    63class MeLightSensor : public MePort
    +
    64#endif // !ME_PORT_DEFINED
    +
    65{
    +
    66public:
    +
    67#ifdef ME_PORT_DEFINED
    +
    74 MeLightSensor(void);
    +
    75
    +
    81 MeLightSensor(uint8_t port);
    +
    82#else // ME_PORT_DEFINED
    +
    90 MeLightSensor(uint8_t ledPin, uint8_t sensorPin);
    +
    91#endif // ME_PORT_DEFINED
    +
    110 void setpin(uint8_t ledPin, uint8_t sensorPin);
    +
    111
    +
    125 int16_t read(void);
    +
    126
    +
    140 void lightOn(void);
    +
    141
    +
    155 void lightOff(void);
    +
    156private:
    +
    157 uint8_t _ledPin;
    +
    158 uint8_t _sensorPin;
    +
    159};
    +
    +
    160
    +
    161#endif // MeLightSensor_H
    +
    Configuration file of library.
    +
    Header for MePort.cpp module.
    +
    Driver for Me-Light Sensor module.
    Definition MeLightSensor.h:65
    +
    void lightOff(void)
    Definition MeLightSensor.cpp:181
    +
    MeLightSensor(void)
    Definition MeLightSensor.cpp:57
    +
    int16_t read(void)
    Definition MeLightSensor.cpp:136
    +
    void lightOn(void)
    Definition MeLightSensor.cpp:159
    +
    Port Mapping for RJ25.
    Definition MePort.h:128
    +
    +
    + + + + diff --git a/doc/html/_me_light_sensor_test_8ino-example.html b/doc/html/_me_light_sensor_test_8ino-example.html new file mode 100644 index 00000000..e24d6b76 --- /dev/null +++ b/doc/html/_me_light_sensor_test_8ino-example.html @@ -0,0 +1,106 @@ + + + + + + + +MakeBlock Drive Updated: MeLightSensorTest.ino + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeLightSensorTest.ino
    +
    +
    +


    +

    +
    + + + + diff --git a/doc/html/_me_light_sensor_test_reset_port_8ino-example.html b/doc/html/_me_light_sensor_test_reset_port_8ino-example.html new file mode 100644 index 00000000..f720bdca --- /dev/null +++ b/doc/html/_me_light_sensor_test_reset_port_8ino-example.html @@ -0,0 +1,106 @@ + + + + + + + +MakeBlock Drive Updated: MeLightSensorTestResetPort.ino + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeLightSensorTestResetPort.ino
    +
    +
    +


    +

    +
    + + + + diff --git a/doc/html/_me_light_sensor_test_with_l_e_don_8ino-example.html b/doc/html/_me_light_sensor_test_with_l_e_don_8ino-example.html new file mode 100644 index 00000000..3c1b9e18 --- /dev/null +++ b/doc/html/_me_light_sensor_test_with_l_e_don_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: MeLightSensorTestWithLEDon.ino + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeLightSensorTestWithLEDon.ino
    +
    +
    +
    +
    + + + + diff --git a/doc/html/_me_limit_switch_8cpp.html b/doc/html/_me_limit_switch_8cpp.html new file mode 100644 index 00000000..c928baed --- /dev/null +++ b/doc/html/_me_limit_switch_8cpp.html @@ -0,0 +1,188 @@ + + + + + + + +MakeBlock Drive Updated: src/MeLimitSwitch.cpp File Reference + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeLimitSwitch.cpp File Reference
    +
    +
    + +

    Driver for Me LimitSwitch module. +More...

    +
    #include "MeLimitSwitch.h"
    +
    +Include dependency graph for MeLimitSwitch.cpp:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +

    Detailed Description

    +

    Driver for Me LimitSwitch module.

    +
    Author
    MakeBlock
    +
    Version
    V1.0.0
    +
    Date
    2015/09/04
    +
    Copyright
    This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    +
    Method List:
    +
      +
    1. void MeLimitSwitch::setpin(uint8_t switchPin);
    2. +
    3. bool MeLimitSwitch::touched();
    4. +
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    +Mark Yan         2015/07/24     1.0.0            Rebuild the old lib.
    +Rafael Lee       2015/09/04     1.0.1            Added some comments and macros.
    +
    +
    +
    + + + + diff --git a/doc/html/_me_limit_switch_8cpp__incl.map b/doc/html/_me_limit_switch_8cpp__incl.map new file mode 100644 index 00000000..bae5bf65 --- /dev/null +++ b/doc/html/_me_limit_switch_8cpp__incl.map @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_limit_switch_8cpp__incl.md5 b/doc/html/_me_limit_switch_8cpp__incl.md5 new file mode 100644 index 00000000..e6ea4ddb --- /dev/null +++ b/doc/html/_me_limit_switch_8cpp__incl.md5 @@ -0,0 +1 @@ +14c18506b817b8b5c83028b18e04578e \ No newline at end of file diff --git a/doc/html/_me_limit_switch_8cpp__incl.png b/doc/html/_me_limit_switch_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..12108cba41ee9c75b4f439cc13b67ff9c65ab521 GIT binary patch literal 47986 zcmd>lWmr{V)Fs^^-5^MJhm=YSh;-*gxH$C%v zu0MRZ9?p5s`|iEg+G}q^K7NowMg`}ilTtsoW(>Lrwn_*)g%w7o?)&$x}IzsDoza__#q@6^d>8{ERY0Remu+AoT_zGCa%z!nap2R8AJ$ur+H;guxchAZAFgZJ*FUFROkA8(%rNTf z*RMZ2@#k$j?g_a}*pTP@Z!2kk zeB3Vo;HRIXNhc;h=RxX?&y6jWO__|EQ3Bj+J{5y>_xrZ_ZA=e$4-&YpM&75FgXd;v z(sdhhZubu^vjzVixSyna{fZ{+_HSF0CpkQ4N2di_>N_m{4D(x4N~+g2v`rmfM?$OW zA6C=|+?)v8vMK*PsHKt>H#Qp|c-)(4(rL|?W9gPHC}?xRboXS8XSo;Y5##OZ3VlZf zYxig851g7VE`5rPuc)Z3YpWl(kh;&mGQGrVmd$AdRsTRi^1xMEM@Y zSzO$>aFmzz>Hg!1csz@X?Gu{IDG$XAB(Ikg6b>tLhxX;f64SLUA{&s92d zyPvoGVeX`^#$FJWmb2+5zh;GY{B++eG9$o1*qnCp;XI?2mWoO&Oyc>Bo%V;gMm$Y2 zy)KAEO@@*RWuw2Iuj5u^xc&=?>1Efoh{Ho!FW@0|W+aLK!a^EDaRzvur%#L+?#0vB zXfT4iZPZj$W0KG3`M99}*>%A8>n{R@|NT0Z05#hV%wqr<_vv|^tJd2r5<3&cMzC=Wa)8cDZRKdyTx}G>{(2 zpnu01!+?q{!VusLEvKhpg|0XatQZ^q{Qo*|9}nvPAT*si%~q%YyV~*`F+a0ZGmb<9?c#`7p!hcp5F%Hh z4%Xq1?3}B-sK<;X#Ko({=Nq3QjfQ8l1^Bi!-ALkQ(v%cIrlXzvturfVcCJn4y>p%Xj#Vg;sOD3s6Vf`iw zKW!tdV9qic7sxDZtmnw){L^HgN>b$_gvgQJO#@_H^fPi1opr+;KrgxX#e(ZuDr%Th zLLb+e^KYGPy~@_9L>&kz(CjH7h_3AB+>{v;4zMPX=ex$>ylaG|6TO%4Msg9?i2)Lf z`gtp*KM?YT$HUd~f_U{vv^$Hx%3@<-g#AxIxGTY@ zl?eF3z$CS}xVW9znG67k%JqM!a@KKocZYMa;5c%8yWgNck!RfBu1N6fP|tN0UeEh_ z$S3)E zJD)K5zg|BZnp7XpMRsm7sB&vL@4aXr4gp*FSohgCkEuDTgZ8cVAm#I;_ZRCPqw{4Z zz@yUp!NPBG9Xa6%bxHpI-Ia@{#&huq_}tx@xR!? zf~ApGECfJMEWO@71lYWvADpKeOr#KY7&Cdv4hsq{r$^s(=mQJWdZsDy8!J=!XhBr5 z|BgtsoB@=-m;cAw7N+vSE%R}%Qmc}E%C*gc50Og^H3GMSGtwW_qXq;{&hOTobcjS}xqBw>;}HQg->p8kzzrJp>_E$bbq$ zz4GEELhXtbH^|G38{yZBAZ`o_2uL*5!uIU6Eaa;+#k1;*E~S^fs_kqXOBY*gq-0x} zR~@%@?A!e7`B!>7+KuCc;^qrSY0YML@R=egnBN1kaI#?d63p z=YIWqmh_yB+v=zX=l(rH-oDB^mCS7Gt;NX~a;DP>G9V+ed)G8)*k0mhfnwep17qvnKQa3-$43F1r ziL0gP%bF>ln7*4i^Li2GOL_n;3ZC)$rdM;&vti#&2QCd$2;H+Re+FAumqOu6-M7Sd z&?0pI_tKESL{CQKfZFxd%U`Z_Oy-UnHbgj?!FhC9PHp=b_P4z z*Q5x0vF+pq zp;ZECQSgAM)9MUYwpPqq1WPK_o^Z(J`f=mMI!+I1cO z9B<1yy-WHkE&B0U%MmFj9GOowzuq$7v)LYro zE4KaebHPmbEI*g8BLA+i0TE;@ znh@Qm{&}h(uND%Fhwp%Dmo1=Q$Xca;UI%1mo1;w|K`YUby`zcI5DW%_9+$?dq?ZWu zh~();jrwi*e2PHaw-A1up(H3dIPm!AcN)8&D-psa-w~q`^L0RC@A2e9zM@G!vs&)- zZ{+30h{Ghu`mQ;ZpXvm|wYQ%y+C%e1sNzR-JC98~o11^CnPig(3MVUOoWc5SZ|jND zbRw-NIs$8CD=wJFnJwK~aA%vbAjKvQMu7bI-1mb5ZXK2dL!qGz24*UGwDA*{0s|a& z^mplJ3_Q~S0+*t_+tbAxi91!X$&HI=al1yTYD_9mi5Zqw^XJe`^2Nve9i^FAw*s1b z;U0t6lyqb6t+(WFV2?;JujKcgrVKU}C#HZm>jV8B|4WJiWZ}eTb}S-`fBYVmdwZgT zPPz_`kY{LjzLlFFOTWxWK5I)&hpV(@lol>>m4QigTD zMRe$zys#H$D0WEJ!hX0gA<`KCf=h6soelG-vFm!W_rgb*D2Hl0I6n=q6CX24QLrcD zFiH#WLcBm|8!-rij6erPftW(3Ml@lK+T@W1FS@TPw0Hf$i5LtK_m|mshp7vElb(T5 zFB|GSJzSgrb&vqdjo>*u#)?9Ng+4R+xvZNgNBL4}l#QNtN6TxeIybp4UB!r!#7UyWm) zk;X02Nk7AKi2ql*Wm^cv#U`w~(01S2!Wx9Q-qFa%=coD%*U^ynevUt_2z*>UyeLMA zFAewcZWs1lt-97$k0gP^FATAlS0s}Df!wdT;Ush3y~OIre_r@W{Ykt?m$D8r?qxok zg2!>d2q!2+kVy$XEiEF04#fkZz9!+?M&51cJI@sZjFNTN$PtY9c}>xUVBuo^v2zT>YBdjiKEdBETQ@I!#~O=<@P&>&eE08=nntB}&(DG~ZhTE@1Lx}bcgS8#I}LS-+c#W^LOLjC89sdBav zmtj}ftEF4=+~(@B?xjf0gd;BWhv|r2OH(^?z|#nIkuw}waWWaZwDB8h=1QE}gxId$ zp)@-0QD`nEE=R#?+KOdeiu}N7x)H{T9(s-tPVwGY5yUM<1JRY{rHc)>z9i%hq$^}Q zbNMRWw2;>x?|@tK9qKLf{mhw2Q}&BWI>vOd>1(XZ|2ZY0tIwOJeF#4fBk~I$CJ>D4 zNNYsu3+(PT!apjNYh8+}B~)*66awoOeM2QkoCy*^-?7lT#8WkyM&F{WH$Hf^?DE%L`qjW4D2zItNhk)BKIRXoCBILwS65um=2A2 z!92W6%Z0eubZ$APR9n1S;on9nR!v-55rG?q1o~F7Q29Gdg6_XptR+mjl~#Tu@x3P8 z;F0+3h%m5^7bx6RBDAgij(;(Y4XR~L$PBt6V7}3jJ>yTj3?7r0iYzM5aFX~gN>)EW ziE=kF)4t9Ky9?K{f4Fmlstyv&FWx(;hDrMz3X~Pbl{G?_(e7zWlUc`PVxJ`o3bJ`HXE^eA4oAi4dk$sLWng#4cgwCeZ#zbC z5kdhpBGe^FrLVpw*CMhF&)&`d-7E@)SQ3Vh0SbHcls+b+mK|^NsM)WTUxfZVugUd{ z4gPJe7$bJOewebkB&h}t;T9WnH6o{g)HUOBpSCoN2WW^;nvR-bFZzi$d+5+V@U1x> zaJQT~^4VyqSVf8JE*mH}&7Jb*6Phvrq!5=*j!97o260b3@Qs)ll@xwGdoD+#Nk3|B zwcz5Pd|L7GWx+@^2FTds*u%@msPspOo5;9j!R(D(1sllnNJ%8ST*l{R6EBrPvHoc$=7Ftq?ZqWRyH{!rvmpvT74i^ga)mM zeGT_zP}M|w@f?+R2_Ahij>6ReVJtfBD(OMld?zhzOCFmWw8mB?zG*s%Wt%S;C~mcZ zP+bR@_p#peS8*FFXmrH0BL(YL`Jxu*&x5_wn4pEQ!Z->5-F^_|cJtmaYESMapg7hJ zVt4i8NZmk@P^rZ%|DI{*#$j?>_P)&xUXF9?=#00r=So2|E3RjG=n9q65?N!5W6FXl zN&4`)NFXvEP`e^j^6U$DSQ$BZghR}WY0uN$dz`nO!i1N7^~$fmr7kk=MQ3PKE{LXm zao`fcMC-Y(>-jsCFmtas&5IlNNU8^WwhXkZwtW5>@A|yoR3ZQpt(MTIIKzYu@Ckpe zWIc&O<8NluiCfq!Ji)dXQu-Me_|#tYV(GyPWbw zei<>;LD>5Q*ms7?IlZ ztpp!HzCufq9f;Ou3r}y7F&Ovq4C@#i-H9|uhECyXDfXw+%=1u8h=cIq0K1?2`JiAm zW>G{3lyoBOne99ndjn_rhx3J2xA=8X?*RI>MN4QWLh+zhhREG44MRLvNLSi0&O3Q5 z{s>h%t(jd-`xThEFwU@p_TN~sv&G0fGZaGBc;b!6>B-gSX10+-f8SFANM&C&hs%?c zMPMyws2{B6Ftt@Fzi5q+zk6*b*?ynP(Y@M(-~)E^kd-oP6)E>sQ2$VuARQY2wxkvU z3d~6|ha{5akIwzN4%(MIFO#@1nK+l(8aTL!?y|$cNS7g0hA}ll3MSc0Z(oP^5Bg_tJb2?lqOH-t^2ZcpX($V+BdwRHu=<+$f$TE6D05 z=_c5)wj72Sfjjls_)jU9E2--O?9>#bax14yD|hQ(7Q+4A9z0bx7_mCvFjofbwC;Ds zzRF}DN?7Wft%l~+KMmfG!`+Q}78s70T7>TLX)?(<%(YI6yq@|&;CJd*h46PI!qU>D zQck-SArnwTKDS|{DFo~S0X=0rP_IcJY3tL9eOeuc<)TK5rF4%oR~bWdvBYP&C)$$! zfzN!2SrA@=9tmyJAk>~QoD(SfL?|v$G@YiFp)Ap5O}9Ib>X`Vbx~E*Qaj#4T+QXQM zKlXc0^_ahWA16~=?{3Gi2EpsZt^NLV*!%U@vrVD#BE@-uJzso7D9eQXnyrw?o^bC& z&AH+<3(WK0Qz`2m9-jJAKo`JtIP!PY&ybIppg*bQciw@=STH8jLzSY&jt_G5C6`(- zAF8IT3CVas3tGy?$E5_cV(&G(quAGA(qjF#$jXWJ-kgu*&ygrj(umH24QI20o)FD`{?b<>$Czfks@~%v!5I zaosW}TNWX`kEJX%%8PoRmxQPTw}&y&blNkAeQQ}8FH`TN1CL9rJe2&^{-qW?_5Hu2 z!yi((8TAA3lpE`8!@L3z)6F&A-+Lp7!a}W-ah;8oG{-8s1ZsNJ%J)0bd3rzVsW^u` z$|hTcG-EsDBj{jv|HEnA`ONHc`D_l`x+si#4$TtZT+wF?-Ih9y72&n>MoQa(>_9;( zSgY!yCzTIzKpbj~rz7mS#-nn#>MC`{N^WfwYtWdVJw>=9HC2p#!n0|kFXmDN);w{p zkRTLDjVg4m$Zs|*MsB5Wf*TzhNu++c6VG6E5<&$h!f24xlOuQV+L5DP{6^-1Ni2Uh z9JUc3;{cvg-(`);00%;&2)v(dm&0E>vx(HvN}k>Vn@n@<>{7b%--BMT;0J4cL91dG zBOkAC34ZxjO%%cQ(Op(6_Q6bjcy>~NGZE6vOQi8Zf5T&)@ANGUMxVgKie0eG8|Ytf zrCe(qms3))HN4XgHi=8m)^g0-_;_+Fp&(^+*1YrJV_B&H9Wn_3*$1#iCRc2NZ}pbD z7j*WJu@tT_eNp{94FtiTcqA^$z7Aq-OcPJ32WA{NVueJc$t4DHRX z3HLNR%}~FQMbQg;3yE)EZmFqh5jxA?Gh`eg7*HLF%U8*VH2TrgNiBiGRidw@Z{`&4e6QkkEc%8_$4oi}ECCRyc|c2N zj0BL#I*h%&Z-|btAqtZGJc_o6@e3c1E4OY3Nz=YCJfePfPjn~ww(L?BI`d?ACc#Lx z&xJ|3Yxg0nh>hexIui=YRo5e05Va6(Ki7KEett>}nKTBC%K|)Q=ym3t0WgZo?6%7GaI5!>6~2&u2g`&G)(; zJ8ADjncy<%$G*gd2RpC4o~DB|MQtM<#l$#kfCu{OXf7fOcVG0!odqAs+70;0ce*rK ztwz!~vfw#e$INe*U5s||(rWKcRWQ`r#0sMkBD7)%!E?tfAtX$9zfyJFWAT0RXB0jY zays>(kwZaB8LFLUTT;J2S9{WYKX4wP!zotdh)W&T?))yqEX>pUP*95y+6}-AlMF$v2NV3)+M#{+xbX_; zF*F^B96j7}zDb^y!NbElygHQCQ|W#5lhF`ND=u^!Y}a6d!|ZvXYD&WPmkM`x{s0{1 z%Cv%!^%Hh;VyF^tHpQds3;b+~#V;+OUp_%2jZv6lL*mDUzp$$w0KLou8qEjs+rAy^ zXsi6m$)FYZAF}`n61tga=-csvK60YIQ-5bG=jky}#3JPo-$?x?-TF1DRwjgo1|hcb zY-e88-?g%w#*!i(jdF=0A@{jE{*bBul+$A&_3c9P@;X7$m^$3`zJJToEMRT=f6kV8 zO_#~v5hr02a^XWN5vv9MDoT;X4{syT1PaH-(LC?#(#HI5Zd;EV=ZQ= zUX}uuB)rWMsE|+L0`nvB)}OF%Z@tXTX3r4v+x1J0Ra2&-u94-u-h#`r*KNfg(oxl! z@mUAP$HoO^nb3CTf)iR4p-PLROKGwgU{j{}5uW|PY4;fatoB;&b5e69eaqXZui~bo za+W|mH2FDlL)6l42XNXQmfE~EChGcsscCI-1lzC-a`Zv<@Pk)Jt8?{RSbWaDdb4tD z{cAey9J>BqaC<^X+En?2IJ>-r2@iRhjXUNb98N?}+e$%7H}~~Wq%HW_%*+c?<1}?3I{=Ox>fD?Q$f+JXn@8-`a z;$J4qmT1T4oFzJWjQ1*9R@!x;U{hFAHRq5?Dc$MFIJ*1JxEgFz4@a)PMb5qlEN6Kt z?6Nr{ZB@-}WnQvDbN=O;ZyoV;cRMe^pB|m;iSzzn(O($0$FoxW?i%#%^k`SiwHiFi z`dn$bGy0byTtMP%)DMoKrzi~COg25I3Yw<1mz&w|g4zcir_n~}xx|7tc;rmn*GzU9 zQFR}c#t#sUv54lz=o}Yyw6Qx0a48F!TSzAB6VUpyS1PR_Vyar;x>F|T|uDal6qH&`0#uFT4fUX z!hM1#-(D-HaZxhV8Ss=r=Q3EKBqdDP|qXiq^&3O^1A zq#nd+=gc_k2aulXUg}9op&^^HoG$)G{wqTWVu2X*nWz!WpGk0)aqP?id&p%&P@!%=U%k zw=eZc_k{VHQ9ig67dGCukhh_K!rlD&QBm8f1b|BV;F@9n@3U^zKsf`Hc+5L<;=oei z8DXDWef^rBkTdIxLZlX(mLdc}983DjR@0B-tk7~7;ExWYO2WqM`kD4Pn|4O3F-zG^ zt>XF_d>d4OnQ)6>CR9{S<@$xFux4JYel#94d?5SMfG;q+8W#-ed#YQ%;gp!naVbtu zDjx^v!`%_CSptrb>cqM6`*{>n7oXdv`U=7FO7p+Yx4SJRC6_L|`h6*%x%F%I<0X*p)l>mMZAdZ$z5DV$>y9lb_%Sq_AJ|<79=hy(Z5`;%a~Y-z1;u$)Cv5Vr4BH3B3&DdEB04d0-M?HU_{U_K&tof zlJ$_8c#ftuP4+esoz?2Aj?b^;)*uW6UD5(a#)W7db!B5&(6F3C<5)x(3aVQz^Qv-A zxoj?9Gf9%uXWe|YX(x4`p@R5Fi-EH+p2kya=TkWXhQk^-A9wk^tvsO6%iNc zzEqBa<{33fUFC_-6a1R1VbYtb!&MEww(1kN!z|G1BzN@y80EiX)!-g~z;pJZ(lyua z8h_aR{;apr-s8!La&PEh3^`~>l4lmDo9yP4moz-uW-6hdI;l~U)r7~%L!0yc-uOjI zbB}pJHh;v5^ri3m`*whF9u})G?bC^S2j5K2TdOolKMgtC z&PbR{B^MNS^YP&`xKQw3t34S}BU^~`Ys!;GTX=Q(!JUIyDh(l6uvytg9JQ250X%{36&=Lii=FcXCxikR-B-+1cr~=L|q7eRkfVa zl(%+W(P5C=gJvfs*9X4eR{}6o#{DKFJzV|KLdQ z-CYCh_jAHs`zctq6(L*bUG1Rbq2EOpTD2~8ViK=iTiw0Ke2Dn@`0rRVjxzCZk0LVV z>-e(E6~wikO08(j>h=tJ>O>= zY0;&PM`L1hj{;0+3-;^u>vZ)u@AUg#MZ!VPOdU>lN6}f+>CTlAG$r-o$Z67PJ}pl> z=54WiN*huf__6sQX`m~#Z90uRYYPO8apAM+8=azmh~w|eWEaYQV1b-m-}r-9Tvt6m zp5{(2_^LJ_BYR|+rSgvusK#`NT)S<)Nk{<6)0^AI{B>AYkt2=V45>0`W}PJ@{7+`YhdN7Zv{&Z4=Jd0n=&JL{^?u;2_D@m z`5HJ;addZKud8JL4QffN#ZO&VcE5vU2Og#zBYPvT`By_$*V)aY$q^Y9*hqsr>*xz4!Dgq1Y z31_=YvA?^|Lb;-CuD3-05;-IL12X+_XcdhNpd`w5i*PT$U7)OcTTVWy{p6w9Ky8BJ zfRhD;&jilXT*55EIB6uJQ75RAF<8~j!y$87<=C9-wig4@eMIl-YON}$g>ug=jEX`S zL#y7si z*3rhCQA-sc$cfN4RFDrg*38=1Q;N``FFSc^X1WS7^>GBCG{m0_1AXO1u$Y+_DI6{o z@L-^if>g?tQzanT^Voo;w@hqj(%x7r3rzLHgk2`TeUZ4e9{M2~`rVU=JWCA?IGp~i zl7i*pN^O$XQ2CSmYjgR7O4Wo^?fNN`f7EK4hO$vdL~}mm(UqT|7x@F>P7@&PgQ0{_ za3rKu6}uxuofSscw#3t1+paJn)c8q}m6NM?k_ijDSuLT6(&IZ&91VTWxtgN#s1ZEv zi{(x}?cKp{si8Y{CR}^BB6Xm$wcndKrk!$Q{I;8}NqNVP80?xgnnnY+prdO%a^ZZ} zRSG!HuUt%hlt|zGgyW($kOL<}g}>Lo$QDF5;r?Al`Ay89SR9k}(Kvb?_ z0b|@QA2!E+O0bkuqi$H{BEQJSJROrn^JhN-0Zgpj!<)`L9*O!|K4ip zXT;A77WB|fr40yss;1`=U}F`bZAZIu=nKleN5XF(xID&>>0Bb@0z|&<1P_2Jtgle7 zle)OID3pC0(8%pH@Pe542R~<5w|M2^eMHcK+C#sCS*vbe@NjGE7=iW1v?8DCrt`qA z&TR-00)Z7LCF=7Vcv^J_9Yhx*JbX>Uj*E7-FU0lxtPY>be=u5_(hAp`jGp%fGJ0Gt zkMfRFK%ez#A`2I!^n(3(zx|CJT&4O=3;`N(_f-5FOQXuoHUMMm(a}lsoZAO~D&GA_ zb6os*Y7&k1?9UNJAILlW=cZNR?m*Dl`?z?1juBJ$eQs?ERhCaBo}S-~wEhgq1Pk@p zPkD55rsW+XUw5>7XQjAQ9HtW3<&)?`8`&^BGd^lCrTe)kY|3qBw$brD_`G*PQ6@31μTCmr&P#IlDI#e7nF03ugr2#XMVEBgc zA_AX^YU!DM5pM7*V7noT@e6qwd!o6*g2;{<1*3Yy>x!)J@>-bsa(#fR*ztfF?jicX z9^dUFYYggB_dz-{uIz{-_bQUe-XKD7YcgTRUvWB~<;iQ*Fg#MqP;>xAJ0H#zq6v7^ z9nRIJ7m;($hZ`A?9-)B$a%o6}-T;FxmvTd@?F*QgtE61*NUatS`D=#q{vY@S*XQl( zFDi+DD&$>>+kW_@Rk;xM?o}0wv5IYdj`I_96Mx*WL$Q+qI{qm|Rf5XEY?OvH!v_X% z-_Vs5QU|rMjCIK3a;D=}HqfQ%K23__6hR_2wBs*}QuKx0H5WFwVF7FT_XWFC`#N|u`PFC2FZnid3~^xrgQWA7*MI7S>(eVi8F)Kinr^V zI<`tn&sGlm9C8K6$NI8;V35pQm~R?kyc7H5UjnWhe|Q+0iRSLWS3uX<5B@HyXTe!3 zP%zhm55MqTvoxJKZ6l(~IAVhevkayG6SW)+fGvC@c45eVzd*9tLMs=rnJ_GA>tF&i z-R~y>0?sxIYRXm$mzQ@REsn8+=s6HRR$S#60R3Y_O%K9x!OhnYw)2VIS# z_32{|dlh4=8fOBX-ko8D9WJJtZ&78rCf_v50~nAR`3WCF(>ZF(r<>7LE$6)=oVSD; zj93bH!L^3trKzZxaOODNl$$?uF|6W67SDE>Y_ot|iY_Kn1N37{IyT*>7i2QAySF#f z#4Qy{c{JV)Wi7VfLG>|KBYHbx(>+eummmA^QYSO8lYE|0{`+fns zd(%BN1Dqp)z!a*s=V|C>mPMQm#uZSfHAkZvz4uHAomXTRo6!2fj9yyCHXgZkUpCIu z9AU7pN@k?QVg7i`Lk0|gZ#t^)rQif2rD$n}Ip!z#^2d%IsbrgAFgW~gF=I8|EvKI5 zSO*9q!_&*lq0IBy8bPT1Q!a&n2qeE=Ea<8F0}R$B z^W(R*JeGYdl%_4mGzRKftkTE+fi-(Y4@nizBXoT1G`>ZE_5ZyB1Sn$5MgHpi8IcS> zY?sF&M7Z5DEU=(vLlB(_C3# zl0%#^)6sl?@HC}|FIelbCxYW0*;Ci4U>SNPso#z%D2Tskv=FtpaE849MLThiWTXx$|HoS{T_@FWSR@T2arl{odJz?I@mL_eXt}S*}*bCxfU|uYY z?v84uud^2bT1{K3}FVm1ls~eZ;<6vuzfRE{z)Hk0c!;Cr`fjOjwZAkWGD{tZ) z9q+L_lXsPbNNNh{^L-^_`?tH1Vhi)2w0}NK)ME1eG@uLvx^z2{TtxWdK6v5+rthP% zae{%Ga2qVvh_a@!a-kB6>fwm?8DiJq8Z+ou!T;2zZn>SZA`e?41JW6z326<~NgQmc zzudhKcvOrer+@FwZ0y&@32A_G_f{@aKjVl8g9)g;e#=G9lN|>Tz>4;1CQ=+F`_(#t zo+S{Nz0rCT(i|p8Ovtzq1u0&yALSfpVx@CzrSYt?TE8p6{ z<~KQ-SckAgHq%D?J)0&_WnOM4r`H^Ij7KdmS4vP#XMq27hL<5DO_!;ab>`@?oThVklh=Q zi&`wZjuj!=A}6I=2}q&RCXgW0Eh;@TSR3_>^Hp;E0R6eg?H7#AY|8H~6oP6Xhd?=~ z0^IP*b|NNV`%bu*aO93_nD`Dp%u#rcCh(69$&tkY9M8T8+m;%3TekLGJVmPXCk4Ry zqi%QbRDLCs|F5#Lk!*H3lf^bd_fvno1%>Wu3W74zb-L+9j%c1L1o)oX#lrr8BH{OX;X@=I(N7@w?|d!}goMhg-B+$I7y1## z;#9HdORQKvX1xsis`B16rv9ZFiW2?y5Vvo2$nS^ouc2SQ`u>bD$*;rv6(?bynrx2x z7EaSD@C!?-70cImfvnZW$sXQ5#xNWvwg(HEkS(_pgIK}Kw1uXSWUfPxNDeS=3Fhs| z9oo#>xJ&{M{R~#qg0okjSY0SRv4e}M`cFPiPw!~gu21rUFA2kz7>}~L9oYJ^G1aW! zU7{gvL2p54ceh6JmZyly>z%&JlveUV@swX3@>7#SpS})rZmGv!!ZvgOeM|s)>6O5Z zjCDz-zo)ScY(%Ik9h!>37Fmy4r>lKHu*j`xY$DRgW%s$1YP8Lzg(R;R{4fmglJWd)1TgXE4-aN#&p%FYT)t_6%_Ip4@do2!GhGmZ!Z{@9V;3hgw|-UJiw2%KEXvR6z5= z!z}D=T|`O0_xXClVqn5d-Qb2-z?z4c8($znw5&m+;ErcXpUqIFyrGVQ%4bUzgUQ6f zIWN%Rs}#Gvdsd9%BEa6kLCs6nCoHH*5ZyFwXwtJ>%i6?`qrfxB&y z_y^(#-wKR|YkQgg#auZilko06ux zzI^afg5MXjFT3N_QDyh<+LK^6)syOuS#SEZUu!SgDcRv&l~z+?$eI=p_3&2%^ccG* zQMNGhs?P1imE45}D8|i2GGx(vP3gG*pme}zBw&9SF38>~H6bH;kzZnmUx`^M85d~7 zaJm+|F41wyl`fKWHQ98s!ZgmW66=x#T%NJXfeWd*;xiyh3filQv``b@v2c*>SPIlb( zL;#N!haY=`lC(Tr-lQs1`)9K_j(ar9bhgfmk{FVyRer1P*k4 zgB4R$%~&U3e5i{EV5bZ1dJZs8e-O>mnVsLB*@lr#)GfB>J}#~ z?#g>lj8wm>NMk_MhQ1fuj>b5b-N9T{({!cc~sy!ONZkwL)yd$>K%Tg2!2e33D;-pJid~__G3l? zj#T^LSL2P>2yudZ*0gD1mx~{Vb;kXp;6NeD66O<*i=JEk-oQmfG#8DE==wzZ)pe>Z8 zV!O7Lm)j%W?cb8Jq`w-agANWm5*ZK^?#m9waj!<|fIUFjlP+5x4)@p@b-IRM36f7W z`#IVDhP$YMo>^rz-}NIahT)CG~M7Q$Ja`p#= zJLyPQ*9G2Q*DMPV#mYa2&xwv#+iT0HO=dqPKZlh8qn*KV5VQM>LQ*qkcj_WjSo?q= z4opYGa_*DT3U$*(4!QntMp1+f%9UpM)F#VSCz;!HeSOZrFc05(qqo`Kt@Pp4=Odk< zs&6_m`!hXwGCOp*_yXPZ>Q_3R)ul&*1<|~MMQb|zB>ado$&mc5({XceU1|98FWHRI zxKc2gBc6M(t;I)zf%7LtU9R%6HmaKa`<*hKTOdlAn{+788;<{&1&HOCHG0Az+9(Me z_b(`b?XN^rKH!4t#ra{8YOy&d4wUD(0pT`aUIb^yZeCU~oV?eM!Ynv@r&tc}jgQ*T zR}=5z!)i5k;zIg?;EK1h0?6nq8Ie{TGR@-5ZWLMShklx~TI`1D8 z<);L@pZ96F8Ax9Z41pP&1`pF(Kk8RN=5qM)`LzSsV6=0Ds4z|!FPqv--%hPZ+9~y+ zPGosv8QKP#!r36&gaxi2dT;T4OQA&%Cm&`hPV;{e0lzWry=5%Nt5MYla9O{Y^PtnE zQwjyNDJt`!wBvRw!%5t-n;T85&Se5dKC+zZ6?ZyQQjie7aLj})l<3EZkMzqo zJNVm?+e%cOy-pW67AQ#S>#{x}W;Ntx7_xqOpaFrNk)YP-TpP8G7}xk8cLRov7Af2x zHT$FdDqz)nzj!h&*AJmdScj>>&G94ilWgF2s%o$f+{ve2_ZWC5M2Kb&yVsJegk`5; z049b?pteL455etMuQ#gMvQ0|y6%0DWnEiF$1;*ji&)B*iP44BUXCF{8j67h}aY}5? zmAH$Mx9_QD7=tv~Y18Q*fbX|aUdb<_`M~i9r}#a0FAoYqu|xSXyr0?oONUi##q2jN zC>@fG4${l9BPMK<+=gm#kIKm@De5!1w zwYs?xA!__sGf>QGNfek4wv+^ICz|rH2$I%=Au*eB0VA+^Fg_oX1UIn~HV39=GDPUF zdQ_XLtH%i|{v84A;?0Q;d>pj8&D;+*lnt_@Ad>=`Q-Bo3bX+A5CWO+SkE6K2R5W)pIQmyZ4%4b>xMYsF{gP3FVRuy; zwa13SR0r3*w@lqHA4#Yzo_OEt=RLy;PkmL_yVF@L7jQ2U+EG?ql5=~l3 zoF=lG&oO1cn)?Cw3Z7jpzA11lk*--sG=HCTc}wFAC1E&~o}``{95}4?P~Kzx<|EmM zFolG?SKn@a6~5>14e9J16Ii;k543b)+u{{%5Jp$uS6bv-Ie|L58^Hx(p>6r77ce#wc3oGBGW!7FkHX)*T9c_EBhZEyTUci4+o2cUP?l9(WmYV!zA+yQR;&^N!0HAcLP9s-Bl#Lw%RKCGCwVp;Ny&PD zbmVB_5rtD+91cP|f+y}3S-0x7P9f}9-d&rWBdE%%QvZ=9Zq=m=!2(u5=+Sn=SAE-C zbzyx~WV*J=5p}e0wB+DmSd-8}V!-(x-H!NUb|spI#u$XG_tzRdMIcUd2duu@Dk;`` z)$54Z%^d;db%74Y!BP|*=3lMa0$eBdb$J|KRYp;Os)&8%ezw5?&q|>TsW{n=8X*Ub zDj;CMEh(DW2T07lE$*oL;~!b`PWILUNhfh4s^#7Lc*RbcSz>gZ7I7C=dwzw$Fh5@u zN4#=KY6erW()`fdHhJeTK-V{sEgT~4TSL=AGO7Pwyy|Tik8x)?>erBtJQpNj6OSQ= z_s$y-rXfoMNuU>M=jRBHrNK-f1^Bx7dc44oWOx;=(7_kh`?RyX5VZ}aP7$Z_;wDD? zn7+FqrkJrc#e|pCFoNtoBPOTdaO!7uA@DL~Y^3-Eb>)rfW`fgEy60@huR)D7r4@UF z>yKcdqyeHvRqdp}*Y3jz)<&{U0*v+kej2w=N-M9D{VlfqA4*nF%>YN=28pIT?qTPq z+LKT0CUo3M_ykFKGR#KJi8wv#ZW({d^kTYiWo$ol(=iS zad*}e4jR|l*oBdTVTp9uNMn?_j#tj-xWQIcq7k&u$MckS~0ZM7=>&)gu_} zMi$0cC4o^Ezap^{lOj63&yeHMS&ds_vlDvXl9MJ>@Ls8orP(?wextK~$Ii1nGAJtd z%utcs9Iapd4$>=|Y_uut#LM+pX9N#xG}l{m^>rZf@wd_wI$0ly#BDz(yJi$qm|GZy zu(8~3+v>W35j4Ha<(y6s{c?zEf1CF@_7mYk3su$)Zuw}klzFck4oN=;B3HLb!I?(j zam3rEq6!d1zjVGX{s?^qJMh0y^%Z_q1zp!PNTYNr-Q6vMNOw1vlx{AKfJh@DA>G~G zf`ByADS7Gc<~vuP=ly-pA8^l|Gka$5wbouUCy5kN8l^Fj*2|4t4y?u;=020(_E_hh zyk22G#ZrydzL{Fs4af_DTKY*Kve5ROgWu-~4bEq=#K@(nl!D3c_V=fCJkZsYJK#w# z-%dgXn8^M5c3V1w;Z&)M_pvJ?5FsBsT~2ii=%yS3 zUb73~$05Q1dG+N7M*f@!8vOMgpAI@{iNDN*VQ{yrKOnK|lj_>l_n@=SW4kH#7IYWC z>Q3J6wpAYEB^~o>4pGgIQUM%J(hA??*4|vc@i2fk^IyIudYke>*Z=JcgoXLm?Y+1= zd=_whR8{GN@@tp}c7pq}3&IFdyg5uynM8BAA$S^QJAN5n3!%yn5}l>WY!Waq*<=u& zkaWprHiI7*Z!61G60O2*BxNw`d|yx6tjlY3ARXk6A2dD8#Sl;#exbeaU`&(U#utV` z#5NB?%^Zf{;apzsl?kP4s#x%94jlSz$76_)@WDrQp&H|^!mvv4<0ly1CtHjbSx2VJSae>5g=Lm8hzAHOorvNrYIHfknr_cDllE6vnC z-2Uu8xEV*a@q>qa(g{JZ0giI=E3Cn!)(&#TJ!-DRVyR8ouK1;Gp(D6Uwv= z&*P4Cjz_U8QHP;{VJvF0{h(EK-4<5!W1HJW7K%v)!iyP)aZ$p@v#SWTvF8FemA&eN zUwK8KiKS@Kuz4prIiVKT$tGmNAm`{;+Ubkt;eFSmj~jo5gAd=>`$;mwH!*EM>0g<6 zFAjxVy3IzxJsM)#WNQVJq`Ii(_AkUFidD4r*PUhF)wi)PXK4+KySgua?VE_ z_#z0AcgD;uJ?pMSL(av|^3=s*h#j(9h;|-uWF-$ylNKe&ACU~8^(yzK9@TQZxdoMg zb{J#8s5QFSX2w?#PJgq@R^y3kFv>3ffpfM%IV#vnqEc&3SX6&{G99kS(Mg!TbJ*S@ zh)XD2x}_VW+bw!3bC$DmYo-PuDMsmYOa17beC^rjA(rZo&ErX%XW~F9i#S1aO9^vi zK51a|fI(Y-L%w&6==TpVkai%6!K-1<^6L`t=3QCkV@NKv`_PLu3{LDt!P3&-_>j@ zlY6_%im8^62C*w7#0QE5KGOpwCW187%;=ThgC5K9)2dEd8(3g^6wKS#^G(jz6gbB?1 zk?+i7*Vk3U!6n5heS`gzI?zSpH4y#4LGgb0eViAS1n!~R<$%A+jfOBa!Nr3QwDLu- zV+zuJx%6==LybWr#S~^9oNg5vJVtBRdPkkTB6TC$UiNLTz#!zMQ*&HWR%4N~p{&?K#ZQeQ{Kwa-$N(_>V87#MTi`G*86p$i zgR9}5zo_jhtuu9LN@HZ!@Li;I!T&8BJsu=x-SIMQfO+?cGRyv}eLCwJIgV&fksXCBy0(lLk=Cd0sBPOyX#D(aDeH-t28}(l*?kGtXg@GaOqW*rCqzl;{Jb-^F#{P zi-i>JuuEvBzhCcnFnLb5k1<=Yi|O0j_E`=phITlJ%^o|CsLnSpvaw_q^S|`nf{?S_ zfE<@z4T<>*#un}hnAq|kX`O#V1Cd>Y6O7<%SCHLP_CzLB*yhepXvt$_Y+{>jSU{gW z$cvUkQ*zV$jj);%P=#Zq9J;>|520um>1dE@#Hg!AHy3W_d;Jt3F4T<`p3U~oLjM*G z)f?rxUbhUvN+q#^nYb?+ z+JB=fKnY~b7KTQ{@pct=_-h}a{4>>l)Bg$x+2LLHOOcKZC@VH;!+04T)xYO69ay`q zn|x?BSz^5LhmvvrsihWQC;{n)RP#%f9fjVfmb%~bB(&m|KeqG$wS;H(yGmSWwT{IdRt+%m>Zcn4t1S{F2Fz?I>z-9?e;R5`Y^&CY`UV$L4lt|xTmo!zZ+ zSAkZ1uiOPwx~8SM|O*Fpqh)Bn{UVU4oRucJ>) zvgdjsDBgiB=G}5`HBEU)E@h~UvbK}79m3-Y;#@u{9R{;ss^)w%UD`;08$$KleH}Pb z$yAVSYsP?i5SVTPD!>x~0Feb#4yR$C@xsc|WrerpkCOTy4NrBG=Ke6voQo-6I$K_fLF284OcN{JPYGvbkTUTd)5R3c<%Z(6 z8)?z_By8Q;+IeI9>r8mwFM zSl}@?fEfL@x%E?~^&IHaaIprQJI@ECYU2eJLtNC05#3*+@O?I`SOG(Fhp!g+R2YB0 zDQ69QdtnPNzKRiIT^%dD<(ARQm^#s}-b^sJ(;}Y%DCS;xOl|5OI7y*_NsaC)4?`cV zFB!ja^!(eI@PgM%E-_999+4~H8-*BA56(p&SFGiSzM;|2T82)u724ZvjU8jtG(m!e z8(+K^Mkw$gj9C(bBy5dn0joP*i%oUy=^VazboL#$TOiW@f!1yN$C>+svl-q@e%oQa zn59OI{=Tx+P$mD!hxo`208)exQxveVFZphp90?{{A5=lADypk#Vr0qN<#J zvAC+d#g++kG5dgiFq+XeLb-U5_iSyCf`Q4Lb9`UuGI~S5qy&7uba*nlGQXDI2|r9a zXf&2{NP05n{j_~9mh5+PEzQ_?#K_3lSG0HB#^0!Qd6?=?YkapF|0?yypB3wI+4B77)3WQ*%c7gMM6xBU$SR;e{*)~ei&-kWjfZz z2nKIaigeT^c*DcSaiw0~05ChAU|{$=rIOUkJ8-Zhb#HC;sMAT`Ci-8ZO_b1sC6?wg z#xiKam!VT_is-U6Y+|oWPPPZ?@gG;w{n4=Sqakoq#>jU8yq!)Y=J#;&Y6SHBuq~!j z|1ojfN%XQR!7h;I&EAS}ZfwaCYD>-e&ySE#pf|9tVr2+GiHQW5o+>-!tV0 z+<9R>`u#11uZ6b6Ul??|4Jpx^rN40$RPksImF{v+cdZ@s4`0@BfI%O&P?spNOAT_6 zz47{!vupkmZ9tw?V)ZW81yr^3PUutAZ*s&HsC%EmL__mmBLeUOVXlWi&ZM^iIm7rL zm*eQ$q%&cI^7I0a(=2LbR-_Iwp?tOW@JYwuy2hjvMBG^?;0UJ7P+R!_|C@Ax{s$~W zNpJy0HDj|%aC3#To@)yEjz-#T{N@T{8WO4KM{com#%PY9f7=yMZ9EJgsas(n4N*gc zT(QxdtS}kwlS@3gI!x{1udoIfaVT^22^II`E7u9R2>;QKNRHcn6Sjb8OlSn}_#ATD zj!})U=S-MFjl76TIp{mpn%=LzXVZE~#D)Dg$fv;{o`cws?z|lOJ$xhcSVWFLY{wr% zuNO3YzW$J2J9p{k8|uA$e!I|;4w}`wHXPXZ+m0J*$=LAmtMF#bJ2vM>x&t5Y-=SZ% zfSr6@)&#zjB)E0ShtyKZh)fP?(+HihtjZ`%syBXUyyE=!UqNc@LIZ_JFn>O%{A}Ad z_@_jidJ|4lHE*`J7hd5SiZvDjKl~hxK_8D{FGqpc-|2{-Y(eE*jxzhvPZ*ymIj>eO z;L-`ani3N_E|K>ras&8P66`))_a{KT_XM6ntrMXfp-P~*iw?}_B*DM=k#~?v`4i4( zkV!GI#Q3&|Nr3g3nnPinjow;lb{)=Qj-M_oD&6oR?ihtJXp*wYGxx8C+qjl4e_w`zXIp!hS9p&64vY=i(YMlq zd~G|<_U^9mK>TBJqRQr#5{C1Wv%Z|k{pgnuLG8%iL%EjnY|exSAhh4W^-T_Ut?z@{ zJ3qTnVA5sU+LXo7N!`8}jM+IYDaOz#bQ0!}oseL5#O8OKxF?aRp|X z+V)>_wf>$sQ3Q`A^^KDYsq>0)CXL}tpFevAZ>{jFg#l^lxBm8UbNPRZV&KI)1G0@- z#%xoLB|9Pu$Adfj6wJ`}yz@>(y@Opl?*yZRCuaE|u%XMY=tcKZmN2o*o&vqrsMSoX zL-{ua!`_8Ql?nq7?!tBKO1bFVj>CTO*^m6QS)DGJS75Ru-(;n+c?C7dp`+@v((0X~#P-k9O`S^9-qOu^M~P0h zZY+R4(BUU^g7Jn3|7|o$2gH=@2k)$NjH~^}-raqFtZSd30WKr-{DE!b=)=meeQ^v! zm=KN-=M_vd{@G@46?^*a zr3p{?fyQmybJ{I+P3H`LeR%m(?iq`U;>UXg0Sb{kmVsVlizupj zeKbc%R)--O&edDbKgar!3>Mx;&6b9Cv&0`j%15uXE4mX6qfL>M`J^%=tgzP#xl-#V zhO`Sj|83yikP^QWlgI%wHj3V(65ITW@`C}(5Y^Z87Hpjl&ObzADta0Ns4Uqo-I)kr z2A^SR@L)T3!OUt2e>-$rol}igGC)ZoRM_49nqY{dxJP;2R7nbWPx=VqR}tp0vhsQ~ zfwJ&k6KLJS9Jwb_%+8h;RwjbpfYEN=3~E7J@X&V}Am%0k$>Wsj_?=|Z^tOK8X{H5QvX(WR%rq5VN;S5>NK-Y15 zBu_z_QMnBbvEwbn378F(vJQeWLg8u)A6bwM7KX*IKffbqBxmeWZ=#KvFg_%08h3V)Vd4M_mfgVd+GN4X5ftzZ_Sf z?LZWZLU+;RnJBztF07{icS;bq9(r30YyzAp<;UfnEDe}m1)v7Ihipq}vkb!FX?_ft z{wsokNkGHKUurUqAH5|o~FHE>W#D&0ZL`}F^%CfI8F+7TK{&v<&3;5-Zx&n%`V%OFFT1R(BdSl#Tz2`$S zcDvwvN*YMC_tZg;_Ve}Sne7>#(x=Ejhg4pxQ@-h)+!Yh9{l7FT+~-Bn+d4j$ z3uk%-Mm>9aNREl2SL}-}Ei4RnKGpX&zWej?)c#Y&7h8lQ&;9a7;fSxunwCuCfBTbF zpb_^2^~#gR`MjWQB2IEl<}QA z)L%XqfUc;okD0{4mh~;Mo~W^7n&-oKg-y#p2s9YF6jR#yO{%Vi1CI1t6aN7A)2fwwvbQfbg8Ocz8Z z@R;}W<~9}h=tOn7SA|u@9G{)INqTL|Gu9iYnntD1HhY1_%kgzr{4RGW6inZy10b(T zO6`vNL>r`>W7v;McVUL($2OQ9rE!)wdn&(H3k9Dy)KIEs4mYSRs$cB_vkGI^wX&;U zUaM+S-%^$eC39bg07b;bgmI8N7$j*W1^!@C-Ly2X%~I)w(*N{p6(o86d1GVNe-7hwn=f+~H)Ak&8>ewC*U zjfbPZhC8GLv#j7+plcRo*k1;OY*3aQd8SWd-J0uXO9FYU=Ep!mW1C=ab?YyoX3a@X zQ4Es5gJ()ldbK}X0a^!0eho-UdWCX2$ohc9n`qb{L4AQ9ywcQd=n}L(-vCx4{k!d{ z@(N_&bKjr72z-a#2agON3gc~oIS(UTe3C#Vobp+N?4%L#Etrnvb_9U-KeJ_ni|OA8 zMkv?>NR=>0hkDX~*Ngh7S4TNMsL&!X!cbt$)%R-_tAQ))W zE8*OnRQ;bdfZh{nQO-<&=|tMs!p>T&yRE!RB~A>%!<*q>Xhs~unHhdjL%Zm!_wXlU zI!T9tY@=x@q^dDDO#o=&`EBCJe1vB&FAJ*XQ%G#A#p6qzcu^sjj$#RGtzj?S#6kX& zWZ6_+4A?KSs~LTxO(%`*9Wm)iy#zxR`K2F0mC(xgW7m(dOdCMm1Armu)-g>qMxBgFAN|8&x49GV4f zn$A-p3XuHi7pTift~z%3L~!PSrX`bPl}NhyY=4AZjqqaNuk3<18lrn8f z3hv(ikn_*+3$c1R*KP3tmw@v?4!G;$3HE|dt^0Jcp_$D@8-VUlsVpnq9g(06K&;&RGb&@_)g2g)-<)I+6{CT7_8RBcIXQ~J$jYR5MkNI3v9ZD zBsMqb78d%<0qf&~su=7N#zCa>`!d<1OQFIHs5%MvfB_lQPJH-v?33k!wziOaTZZCB zUkK{}a}Ez{Z~NCTn8`7ZuejHUm;Yw&ZR#-xwFU1p zDzhKxUz09iCs;m=7PkJim9Uebz%QcJ6*>Caaz?m3lCxXnNvgKM%!%SBF#JUmqF)mf z-`&DnUxh1t)e??Ln(7sARiNPR(OCC@>m%e+7tz{>=K3DT`8O^fWl(sz=uGCVl#=!` zxK>=|C^69!C2C7Y=Mnxp*yrHjV(X;>IzN!3u1c?C73?*fQg5T~9KR#d22 z;@=IU=2@(WpQQe}i+p}36R0<+tJT^cIyT*y)jVxUk~nDh?{v#IK2cQ>K?Dw&{g_Al zrv=*?k`Hwre;t?`WmUBxDB2dq%>o19Uszi-cXV!b=3$>a_Cbo%SrDN}rcl^Ln9WxV zX42KWHQ~>0q*}6Ki&prfh6%d>xQ(ql)qrYMIYQFZSra!xW?d5ay*-+4&@^%BS?}j2 zt=>E+@>HIp)D08SeVA00z0}Q%@#mqA@8HEYY=v^Z)42t!KEJ`jgQAU`8L=E2&R;A0 zZTc8s4W0a5F|=EvFKPMKEguDggs3O|GJNfaDX78v4S8yiGr_y`_Eyjh&-b!{s>mJOoF@&o1xpN6IYrc%+#<~^CPn@zp#8J~><-ZV6)y!1kn zpgNg#P2Gj+w1C+j?XNRMw}0)IKs@9{=Q+^}sL4Sjbxd~q=4vv4FW@#1hR-5*K9A#_ z#$wJQk}g;d>h761@DS}I1oGP}#s?1agos*fn+nF({?biJXx@i9)X<^5dESwuIE%C< zdB>0!6U`X=8!7Mpya(tBlgj@GCLf1|^unE>`+FnCAHnBc;^(;ZrYt~-x)x%qG()BG ze@Rbtj?#}SAy#|@Xe60+J+`mWZP~_ix-Y8-m|4GhFKl-FbKChj5vlzurHSIWrHY$i zaug8Jq`CJbV@jJkN2pk+3p)&lI5==|0wqBHYs&AkL`e6W=pOB)(RIvjldc(nlaY3R zbP|dX+QocQEh^=`n;g3;>ka7ug6bCG+V9HHi71*sczep2vhATbuiPq$g^8fe(A^7o za0ZTj+Mrn^F_&K|STN*OAVEN%xKQzY5u5AsfEPhtu2D^n)<@aG0eJm2|hYqaSu zFP1VO?sj7@Rq1CF6AAjS$~q)dFRSW$48+CBM9DIlnI1+N^q>-K_lrk?lgX5bi;UaJ zO&(w!TBqz$t2MYWkDmlmT_hP2?VfdwuEmsEl@Wm4#v~Pj81p zPlF|fB6qgs+IZGrZhrSJA2I}^(`B#$YK^anD^v#y8`AJVjWa25JFbCp0X+eQfqH{O zVR$ZUlV(QL+5R|dKLCi;3!SF|IqH1iv;-d30QVS(#w`fN$N^n8XcoYHP}Laxf1H#e zl8*w76g>eJ0RDlAU9uXQn(8OP?dm%Ex9A)P_`^_-J5W*41Q~O54d=wSYH+3!2>gQM0Sl!&R!|;Y^wu zKqZ+xO_(4AM2A4~)g1|5^sHuIuhQ2MU^480zE|D8a|gi`?b>XFP#j>w0Erq&|Ek31zYk z8P7gRbLCaAR}M{lxmx}2_|K@ubG=9@PpycY4*ZhEVl5J{P=0^QAX%3XN9Pem^P7(IOjXe;xfWlt#1OkoZ9cy$oN2pk)Gc(PtqfcAZqn+T?73lgT zY%i{pZk^h;;HI;oS!D`!0B_g1WB_pkd?z!-XL7-iT~3Q(z={jZ+pHvDg2-0U7oFB- ziMdISS^0NzXd7l59)xhDmTw}D=rOC5fC-$|xn)V4B0<0e4nJsjx&RVgMh-(e#f>+V zMfL$s6;+&$muLfoY#Yhl&@6iT0q}d+=?!#RoSY^xZQmDaIRhz}htu#77E zchHAKJq$)G3Y_dPI~%bN97HPO_|^6yoM_KcZW&c1=Wo8E6C3$X`HWCeRymtl4&+eE zDcHtJ8%Wd#)ooUf=jESSJkRxZ7N@eYC&J2HXtca)#Q0dh*YjDZRP-!4GIh?rx?;u+F-bm7Q(={($x&;UlYiK z&k{Bq=h6nwf}y}jUTK?c=5Rq)`xvEg7;wi|t^?(Yvit1nrF)u~%+sL;shTzvAo>1v zzzXs=#Q^hyIwrUM<=h5mCZRj`Z?-uf^=J@b^5%R5+l$K}$?^+L`plwF6ev8@)x=Ha z2N}U?09!5sUonZ-_)S&S-}7v`t0cRse%La*A|>2_cWP;cS)oD|;uzR~K~hz)0w6@! zNp-ML+?1sOKmJMCTrMncI2sK*F_4CcZ~@UZm(lIT)sZ8=dhk0Zq8N73bPEq0WrzZ@ zCWCO~(1>-ChB?JXis|trN1Uyfru%e*l~h*ZcXa{11d78e`lQ9Z+H5@lQvq&MtzhJC z8Q{is8MWD2XoQDkn+tN&T*`iU6%K1JILtIy0j+*l6;>Q=e3`w;E*1#nXIZRGi_0pz zM#eBMMid9FmPojBa1!iKbNB#v?GV-cB3#tygX z2v7qLKumK@M^+sO`o&dlS?T+Mp%0^6NoL_j=Yh9?Wz5lFPqHbeK9S-x;5h7#g1TOX zls3c;NgYp`{w{ofb+Bx3Y!U|??81aKN>c)us2>-f=_>gXv@JIj@~*|9C#N>h8Bw+s zb!-wq4vIFZ2O_}0+Ea$yLgO$Mzl3g%{^=lB*m+TLCKNndA52v~Hv9_(p@})&Le}Pm zi=jxWhzce=X|TJ33$y0It{O;L6K;EkWfJfa6v7k0x_!;7z|A(i6*SO2z zVWbl=a>_JA6X`LctGqVeXVjRl{i!|Fnb%kt9qV0-{7~CLSo#fX1w$+GLwF_A1EJN& zR~Br^W+5YA&#o5hqR4wQaYQS}16N^C5Y+j}Z&Jn>w%X)7i;%JaiDBdC8l{GPQQ798 zqr~^WAXaxO^(B{v>fVcg5^42|X>urJ?eos>uE; z`2xGbj6c*cY#>X@k9VUeOs#d7Zu2G#knY{SlyU-}KuO9sFj8|w5REFCJI?wMp*0ZH z74#pPF3E2cY{gytAEIt|V7um$kc-26c!$FKW}Gm7l33ylI7GE?5E^t^GPm&>78vR0 zzHkv*OJC?e+JOAEh(g)l>eB+@U=J)0#Kg-OlJB`g>`oOY!CItWIRIw&skKUHXa#Qz zh80^Gl50=ok>;P7vA6(~u~GVL?Zl<~XXxiq_1)T^PiMD>sTu4hYlbk*3lVit>(nLD z?6`Kj$;+5|(q(#_rNr5?=!qYTQ5dzvl_%tjY$bwT=P6h$NMMKHTQvntIK%4b;_Kk1 z;#++a$Xub|VzB;|ks?s*lMy3L9%HdJEReY?Ai%Zl+Y!;9zZHp=)8f)Pguys06$aa3 zh)>p<6$p>tEw@|7M!=j(^9)x}UNT`+@qIW9C9#WQw(-o6KBw{CXGvAWU*X{x@lSrN@HG7 z>a`dv*xE&T^t`nC0XarxLzya`IEXf`A93Vz#lv~5=|)=%c(A0eY&_CQfxMy+!=96N zlUr5J8cbST^i*5}<3+cyyxtdK;p}g!66yXuZaEGw!Mw$ei01v7*{Qk{PFrO@>%Ny1 zALfU4^Oj#gOxm^2IsGOWX0QEf(O4@?>@m6vt)dDJqD#Sj+!0>yZpkJv zh+pbp%b`{3T;IhPAcTCUyPuJm@+ry-+cAG{dvrTm;_HSZXapV2E3Ujn(hyy=NLmJ` z5uWayPg=&9iat&U0<$a#EKurI@bK!!e%|zPE!kA@ZIL9H9T$=*S=TqK*yN3-WQnlN zh?|XD+>`s`y+~<;I{DcSOEN6I!-SnRL>xKeq6HrmNrVldKw0^qGkfTcirtkjvb)bK zFw{*R&zV?SFD|y)rR}pf6&5yMh1qY;jjiShuT3ReFUTDcQ~0r9pw)0Ty_7L&-;j*s zNQEC?JTZQk>Yy5!|H=~CbUrft%hM={X>*fXRbTtx%(vcmj6+!Ug}>gbD`81BON7{v z5&%bBcGLn+G}!ir%)?->_5)f5i^xgU1_PNuh!6a@)1m6c6&SxzVL~F*oe(5{;H(8I z=Ngi-ChE2MU=?_DXwt&32Nkwe^b&%Qs70x?oQeY5yH9P>@?M%S2b9`=xN1>2dRd9a z-kj~+9DTU6TE)6t)dwF6CnZjDf_i%Dma1WW<#8f^NqYOUHT+zTzNC=0pmO=WD2e!0 z{5SlDeL<#q&E;C|-y&!;FqbnTOy>wxUV&XB7c(UY*gN9j#`1t3hfLaMMG$a8k8oNw zOvy$J?$I`O3jxuc^kbt87kgO19W!v}6jfk-7w2l+7)x0eCf`wg+)x?BYOC04iV<%V z1KG^K(gr|pfzYt{mirWS4==p5mcP0S!bzvCBAxrup_Ck0Q$;78z%tYAszCFnp5&Wg zq;v`lslzJt$Aa^#T>*NeSBQN~^4Q72 zLy7&)dv%XSA2I~yB=&K@Bm1rk2zXLZ0 zKs)?UNp+AOjwi(aehq}?HEgUs7vBqP)!446F7$vLiD-n+xK{`iQ>Lf_OHPEx-3U%8 zHx?w))@_SQLMP5Zcrs}$dcFEmu`Mc$CAVLwN35%zTu*$i6i-yrH(9r%d8l+78zlcx z^erdtcaIte?%SPlPqh`Xy1J9BdfgA1dIf{D>O&GL9U;ylaBv~U8&`SXJJVlJc%WGz zcB1t63VPP$ye-s`dw;CKx{*bAuit6FUu!eP8|nf#-=iVn?SDld1D z_k3l~5iipq1JJ;!tMWQ$k%4U06iJW_qt`blKnT$B*MnkH**dH48Z(iq86DOIbp?Bm z$(zOc6(A5tH@1VuxPuo}ni)!%`p@2W--=8qTN0)yNNK%!FG4>msMCz5%J`o`4BU5 zw>z#O7{?#{to^&Hf-YLRPZ@NtwL`w)mM?D7qj}eS&`1>Ar**O4w|GJ}k)LI&ez}tL zs+HBKLEE=?v9|H&I*Z%O$ux?fA%d3?ZMoxVgrIdG>#{MML>b&z7KXon{0Q7I)OCgK zBV6Gg#SwZVUO2vxk2<-78^muvq1X@v8Z9+7JztNPVao13AFefn^U>7vBsRnBq zAG%dC4hetMx|<}El%!5|c0^GW4`~DhjkAtduy&C5?e31oI1@V>5Xlx97v@7%}+CW4hHkL_ibLw?c-zhjA<;VLJ7XeuHCfy8ET$y zgLz809hN@0EbE-@-fm|;+s(Sg$lZQt->si~3!2}}BC9k04tGj$JEgU%w(4SJ#H*a{|S8}9g~>p_&M{k@%ZiaSclo(dF_}} zma*#_s`vM&4jYBWc}8f`chh`1U5$RzLJPk?*3M!mbBe-mNxLaY>uk69TsEYfC7Df` zM{?|{{w^|7UlTyaG$4#6h-*GFmdtz!VOvve7EamcX+CuM5xC#t9sVmtn#?VM;BvFx zG6Re>>$V?|XddDAoda}(fAS6wRXJ}Z3)yikVNn+Hl|0jBd81*)@1CnaiX`b^B5J!O za)@lBRz?2~CmwF9`TZO~-TK6uhhtNjIyQ-0U#y2?C-nmhMIdLg540WPT?~zzQmJ>n^{tx4$3u zK9^x7I=%2rTJWmg_bOj8P7J;SUD&|mn@?&P9x+J1Wh#S`iJA^GN89^uUjQ1>{56RIU-5m~u2Dw?CDF{^cK4pBFQ0JVImO zr3A3o!~;)Jk#UZP-Y^#B)-m9Q_f-GEa{wMm$mMxX;z}17go_5~((`h`*XnZ&#rqf4 zBrqRMVu(o5ygBu!)puc@Qf{md?)2wPmo02Lkm*UYPG9f9xB)kjR^!j4)ASJA&O%MX zv<5%d5V|gfgxB0yfJduW4Bf9&^BtVNxG!0ccGbxozD!-RG*QBryRh~bJq3OMxI7aP zI+#!NFI}sN_5t^o9O<7|$+5$3B{dXPPX#FxsegY0`g<)-AE8p1V@`Lj;Vht6^}Jy{ zE~RZWk72xrE6&8|-2{dTeI6*%l2LPqKwUsR1n+Ok?V)VL8o=--H8EO$=S9dxZ;jwcs}am*_u zUI&l?sF=-qKll;XP;TZ<{^`SQvIym;JxiAmk4FzJ1B&CPR5RPoN;g^?y<6Jl`-a9@ zOxJXSB)KgPUhN)ViskuJArnccz5tHJ|}8yqz6 z;Z+)%gWd9CN2TSwyN{-#wl&J`Oxl-QSIo2lJapFq5{=Ik{WKhw0ZP|ZxVl+9q z-}>}tS^OGoMDWeMVj)#4^KJWK?$Lc=r+JNxD5+9x^LC8c$wvyH_8^EZ)CEpk&u0PS z7`Is4fa^lejjI;bN`Yz95i#JU{yP$%;S95#JE`JMwA4S}4sFOp>>T*(Qv*qcI}Y_b z_Rp6ocx6}+ERdp)IQ zQOR zGv;UVijnj2AA=5wO(t?}BGO%nhO61f&Aq)T-iaI?c#ilC{Mn}Eb0eoS@W0b7IQNKO z^b+z%-}D^d238Al2XIAovwh?M2H!}6W|jf9fJsajLVZ;~`d8rVrm=QL8P18b1YHKL z!59~#zDh$_7ry9_CKB5yS`pRev8dgIqm#uvY1ZS(%R_m%K0$n7?>Z0l51@FLluW7c z|EdNaq%spM0&lmsv{>USB1+i&kUzu}G~c*elHCb1r!Tkr3<5|mi04ujd~j9&9OuN! z6%_wsyEuD?1!k|*U8rM%N-w6^ERJw8kPm+}F6l2_ijxYC;dueNYV&2@2vC`+=||U4 z?E}2V_NJUjJ(sfA*WVnB205))t~BLl-7f1pKkG@)x?NvCPiT=1_))wo{vEx1AnJ}> z6XheQWj@hyW6m(5py869EK)yEevxv4_=iIXu2P4VJ*(m z&YwLdGwPKs!q74B8pd$Y(z)%hhsrVNm5JhDssibQ-AoFwazOJmX97P!G1dcFMJ>?j z;HZQatUs7&^bu|(CS%r`j}_U?YbDxEwK%1id{}@Pf#!7%+UK1HZ%V1UV9L8_iP~K5 z(s#9$QHj9lg2)Xy(LA@HT&%^0r!QGuZHLgFk2RAMb{q$>Ejh17p1h_CdK(R(Zlu_H zVFgdB3&^h0+QlEGEnI>xEc4x znME^7QfQC8R9iXvsEr~`8V;N`SiH;7l8C+;_GJ769%i3&Os$p?sGY_opHW;7j(+(Y zhM*Hho~Br442=1rtx{upG*aE}U&RDOj|>=9!gjeW&&AQmY1f#AHHJhIqJ8J{)O&|? za_dvA?m&gN%|KQw^i%h1jQ5^KoWE5=4Vo_3*oY5SeFwOh#A?bhddT1J#=wj;sQc?cl5D2XYxz8CoS@)&rGk zx`0Zsazx>jlVqXRW7^fo^Vfbqw|Jkk%uW4f3imrRk0mYE+}ule%Z){)rb?01rt<|O z!{hqsn`eJn{%Du>{T8=kU4L4&ejJfq=kX)AJbH%yJol6aaz6Uk`qGjCYH8(}Nw!(^pxWxY0JWMm9-ZE?3mdC^n{9_xMw zqNmz@M}B2@(g%#sPuoGlUWdyA+Wwrq?vLvPn>%N6ZkIVLH-EsQmn@`x=~YSIQ_Y=u zZX2a%qqSHAwb!CDWg`l=?%pPuzPBd7)oe{U$;S283x~E z@i}a)l8ymctVf$4@Hv1<0s>P?T+GYM#7jX=qz$PXFy}t!t#ljf>v(nU9W%F^T9jjJ zWS8#R%_y@nkGGO^MXCke^IfoA`(5p#CMs@Wb6I-U*pYiNlFbV^iU!)0GIr!I!*{N_ zWQ{@JPZEV>H#dNDaGq?qzvTjqBAmxQM==)($%$UJ&`#EtFuKhsn1-X&266$Oi&+g% zl%$sSjLonT##830osmyp6dl(nFiBh3Ut3!@kbNAda%w`q5j>$i`Ocf&H)=ww@d-yn ze^p2NW}^G$F3)Nyz=(we`Q?Mdsvz6O>$Si9zSO)YOI1nr9Z#$11kB+?Uz8<};ogV9 zJMSqQcD^oA(}y@+)*2mhgLwuZDZ-{EN_==2Eun(K2nTR!#F)R-2K4>c(H_A+{oUbb zzNi*_OH#SPn~G%4qPd$SaAHsV;k6c=uXptaL6@q=--(z_yu`4t=O$SPFv@n>pe zOoR6kBaO9buNd$#oHxD1BXA+bG|x$ZZH2Q5@Y47;h2%+!bA12%>PJLXp_-I>f3ssT zJsxn=lD~Kp?{AF$=NHf3 zA4HM=O*uun-q*sZ&An-L0M%Y|Pa8RySgAdRGdC-&EDM4!dx*?$qmhes;7iMD2Z774 z$m}2tmS&k1o0UH)6q`kUWpU2lrJC3`xPzf$M!vacWV2}lKewV^(Rd8uMD&K9qyN5IT)#C`3NbH;(o$hQupK$R7LcvdR8+2>539$44 zcX+eOOU!g-;JWUnA7d|X(gC;^Jd7*s?6_Lt5x&LV5T5TRFreQBPJg%Wq+cJhQ!b7qhj4JVpVKCpAkI|#d>Tr3TF#Hk>g4rB(U_tXPL^@R_4-vQ?QW)PVT#(CIYjM}j!IEu*uRoyFADn9us^XbaYUei`GotNyJu>vRRg1-9`L6syR z$ciCR11uf{+tNM^|qF9PdBDk7kEZb{1sS1S>w+oNWo#3pVU&q7>Pg_+7i1+$ap>?Nom z;Bw{rGY?!>MJuq=s2fLIC^}NW?QeZ^S#=~A;>ueLE`nHVL zJB_tIv#xJ*91E8Wdzbe7TC+nzNkn{B*N1TOjyB2-5oj?X3&i1tHMZ7=N1XT`c3ONi z<3~Ou8o^2J%V{lRgUoDmuVf|gPwe4Y+Hji}VvFz-ipqU%%&f11W}h_|1|;B!*nAw? z_T!f?rlqzrl=?mVLUm>W@f;o$>ctOTeV(fYH`-pgI^^~3+MQF|y!Z5%v&F$&NI?It z5mspt2xs+~1?w2W7qwJSAARSJqONsKks_^?1bOt1iizGE)s6YEASVS>E-!xSzy_jt zc%2f@9}5A%`Z%sanpKm>7TlX-I*YW7MYuz{BDg-f@M||jDPMBCuc2`>oLLOdM=P1< zrRs)X4kkmP*!_}x}8#$=6MkynG)XYGddO`cA zj`Q4crVowQpH&cmEr!BTT+BmQBcL;EGyT;ECOc<-?>QVDKkecBi@_?UU(Z};mLNCK zdUGX!CCXQ+c|X4sZ->*I`s3(d%*{%s_R{bgm$fl6}wDbxtDP|#P9-Y2J)#F}> zkn^WmDet%a>Yb4lpdoJtzV zGD9Vf0)=0Ad$KY4$OCkvt&MyjA@J~TiqH+PO4Y1XbkO9QC9~Cm85%$q4zmnr9^^oX zCaxe$!@MzFMg5__v|?W%gKWcK1tVAeU(h6o2>QIgRP^F?S~q{N`*NxY#5aPOPzE%n zVC>O#cP1OPHb5xJ0(JxjU!Gc+QNFcnWvN9a^=%_c{tmM@TvXq>Fn2;Vv#4JEgX0jT zBP~1sgrMt~ zN2tPDwd`Yd`c(%ju_ISof-1hKchu77(`u=845?|~+`0C)lP&@PkEQ2IpmvG))58yH zQkoyuRXi#yyr0u$+Aqg{nUn`Txi@n!5`3$a3MyV)4L;yZh?nG>0XU<)$UoQ{{s0l` znOmu>wtwsbS9L(Iew2Kgeq(8=NrC|g4kX`Y!`&(dsT+oq+I>uQHR~6gB2E<2@ZLT( zjMCa_UdVEqpyt@8k^-q6HK|o(bKU-GE^K4nX=M~)NXvBKD|>9J7^a~YaUB{fwVGsd zFqcMfS5NBoDMy8DK`o$bnL30w{c%U3gI|H#;CW#kUI-pY+frMJ7PTm)v~&!_G^4yo zeqzp&dwm|24*edB=u9g!-S}c5-eei{1)>o8o9{yC*^qP|vTu6Ya$)wvIaEs3-?pp{ zcDAee;r|qG?=vZL3Q9>I$mIcm1&P ztId?W$PPKROeQ;%mWNXaTPwI2|1)z|ckX6X!#MNjd4{kCFbdIwl3+NVO=Cu5JWX_G z9%4nZy>DI99wIkN_AnN9n{U?Y)2n-c2zCtPN3}kOn2~RkW#}|5@A_416Y_<`VR`CR~uhw=B-Op^SxO^$X6j4+ym1qtKV(c(PvKT=qRcrA{WTpgFZXW{fKl!9*D_6 z)TD^FtmyC#4I@uM6Q0C+0Y}xPuisNV-QwJ6qo1AcaZt%-K+BEl?o|wP2EU`VO3uoO zRjxc{Uz|n_L@*Cg4Y`8zBHPLa0_zHnTcOjo$1!k8E-m73m$>cNJAprk2D__12~+Za z`)Txh=s}P+B}fQ-n*N0E`1MmhH#i$JbSkND^h<>;ryRZ?D?vOsrVD(}*Hn}L?q-vT zF0egPU%gRtaZ0r(F?G?9<&sZB3n)3nF`T@5_+ecaxBx)pKJA65Cb@8_k^1z&X@%-t z^%o6EPMW0zJgj5tT!*NpqmHjLbP&hQ*(NAzP~KZ?b|S)%9**oKZV(Bh=9F5ZcWdc% z+JaD}nfF7^6?ItQ{n{I+r5sjK)@y6_0-rI{1r1{j9! z%6I?T&9{#@`s+q5yx_PNC1@R{u=0r3S_9SY8{V7%Ntu0;i%5*O)YK=}&MF>Y>zL(q zVOsd%U~4I~$P38YeG%Q|eI@>MZ*PqeGM zdejqt(+Mr0UvlX}1ZI(q)b9Aey%4Wz3Y zWvV1LjhDW{sW0pg1wo%8qGI%}0MOaH^Qe5t5woc75ETUbj_qc=DLq-!g4cwihoD0J z1CjaAVOMCqK?AiwijwQ>ER20ihw+yd)P*9AF$~d=+?NR4%V9aY5+N}qf?;ABxNH`C*emF9p$l+j^Dtnt zyrp@zJNegrF>OT2pNI=Q8d+H46{_x-HZ(@zQknnMT+<{sQ|ZQ5*dmtGlY1e(7BKy> zQEl*tl5q66HJw?vJAS^3?me^(jgn$abZY+E+0rN*Bjs7FCxU$uB*KL9Gu34WsI9iO z=W$(mYHI?AKXJ>zJ1|2X+La^6eUfxM-o5QvUu}9A##Zq$y+tq_t9QdzP{2AFcr@8? z=Br3KV<#CjfRTIix1wbY_?!y*!IDH-j~k+5V3qTrryG++Ofy%E?j13@VOzd-DYV$p z-cpmca)k8*T+$v&Jf#A2#&UMCUqzZ^z!5cdAOdU7SD0Q{8KL5D#OYsEX;%`jiZf%p zR9R10hh>SrCVcr>;B_y|EkLU6g>D$3$#bt7?2zAzY2s<=gzkpEiE)Q@kSw1@0qmI+ z1*(`Fe}}?Bqj=RPrT}(q80pN^ZX;Ba^QDV$=n^n^PMMz0(x?_sky@l(2v^;(tlWk4 zlLlzTaIGIYgU4h;2xmf$3GqVShFT~*ByW_Ud$)*P9l)9IfRQfOl@ZIoEwh@jgVUMKccZ_lgrw5Ket!{E@DuzQ9b;`LFJQ}C(QpL$SjuKuKB+uO{gc!5XFBcO_xfB3*B*}`SedURkkaD!$AU>j8+q(AM(LUaiQ6+ z#PO`TK0u%Nn?E@LZmR1i(;r)H0NVexIZU@I^48n(b)%Ys2o@)Xk=CCjLC{7sY;aSn!7#KnMeTC#v=LPF5z(pteWk;JFB zoCdkM->3tpJvZvNzVrwH0kIrtH%;>CsM&DoC*HAwF!X(;2x}TaX6Nykm$Y2a^J}e= zbQB?-aNF-ttiP$T6p%S>lE#5&J!VvxQQ>#*e*jO~mhKm&e;KJa=I zSPJG74z7JKkUomcUd59t{;H!ubm6js*CC06f~&4GGNh)QYzqI-i0j(r4rr)Xa6WEk zNW28h54U@{ z*{@q~fEUyINPh*_0-4g8$tR+juB8wR#+VOx^G@pP1;TH&t|piWnb7epm)<9xAN)@I z^^}laYX1{*?Lf2DPS+@t#Zh;`j?aQ@$6uc$+Z?}xOHwmaeXF6fOyG`p_Dc6hso5Vj z7uLpLo1YUidYr&kh*s3e_j?N}>Y;x&okF)^O-6WPOB`z=bd%FPpXRsvjLlH%$=w~B z|A8fStp9SUo4DqQ7tn?SbmDNaWdeng_!O^7hbR4j%8XmA@@PQ0gN=j{wPOgsoh^-Q zDgU5-JY<|FPUdl#!F^j<4-MM(lw@!CMFOG+zeS=kC5Flo2NGT=o6AG~DTT$k1D1{C z@9sQD7^@A%mB1lCM1x@Tz3`U`uB_MEzY{q1#gPa+)fdWJik1HkF(ryU^?^A|ScV}~ zf6u(XSG*7~iK5*YCHV_EzK{hhBM6iro9xwA$GWfgKgiu87d`K%=i=}jgP%92BeltzD6}~ z(%6PS$`~@eVDT||(E7njdH@~i_$NKU{}xzz%Zs{)veH-?L zJbwvX98`qrI(Ox+a^1?~MRgMf5CPGugCJY=!d*S|MOo=$E=@yXAsyXOmASTiv{i7z zy1bW-hR|>((JYD@BHzK*ZH#_L-j1f~eGG#ECP6?F#T|Xu+ai^nCe)~7Ol@24r^deX z0F;5ThtVB!`%x7%xqsL`JvVwEdS|s5GEjl~4j+66c*yDp-=cp}bM(mK+4ieO$)@%8 zMmN^f_^-Y$@XOu(uIPyah&$G1?SzT*ynFpxriH0(a!EOp7#D6r%iDxPJ4ZlgXZ1BS zV_%U0v zz!IV3uX{x=PQL0}x5m9Cch_NF5hbTe7J0fGD!t)X`UFrU{*r}YC9b98+($aARG~%M z0220s$NH1IWyC@fX()y5zV#BAlQ!at$lP(kHB}1Pht2hBI@D8PRs%*!en+pYhdm7E z3t*$8?udSo~xHC-u3;>W?<2?sw$2y%ztsj=hIskuZ#C@u1S0!4sYN;V{SAmI`lT; z+Wm6v4G0C)tA`?EX3*|?cfJbw#itE=q($gK@QwAE+DX8josQh#ELhd?Z9F-;D{wB7 zSu)@CQ*r@xWqxHSsXVcyaX1Z(A(q_jEFW>KEw-!rMoXaqbzxEUFBaK3&<2Zx?Avu@ zPU+PZonH8L7n{3H#=wB_U5zXqXUMsX9w+Zh*O+I`az3Bxh9k6NFLKi#O5k~fAo2>= zgo*YVou-+L$>ZgI3^gUubRh>_&KcN$FQW>v_$bATgf<7H@D!svg?!W+yKKby8MQG7 zYZ9P)H}Ff}@s6)F%w;Z_fEnH|BbP3^18yx+Id;rG?Yr&BV2f!VMwaZmozg(kkM4jN&|5R}#In>8F9WKU3#Uoo_GoJjbKv)G< zGzp+%Vlv-+brUJ@Yj!-WlCaXrj{w;*S2?V0m!mNW_i$gAjY{Vg|B=?_M~#le{w5XE zy6Jd@i<-Zmz@7|D9Fo60^&m-ZN2q9)mDpWi;x3Jf7uBLAc-A)|=TG!MoMhe!GCBo_pS12(Bq-or^0kqw93?v1Jz8OX~zaMR*<9qdnEw9k+3{j0{Hb5OU@ z`F>Z=ak9tdCMs4hmy^6FOyooC=JX7fZN{d5?N>prQlBBXLff4>gE2x%RNhigWYT zG^~9d8=UCv9f3NPQemk87%9!qkd}LWX25&CAvBNJ^^(ES|MaIBmc9taJ?fMZL0`ggs zKWZ2R4}!AlU?8&Hm2JhEb@OZr$M>5+6e^#bp}Me5q2v{nL|gs`bdN zq(cJ!F+>>F$Ot4yoy&O(lyJLjulI!y3w@2qQ2Y*SPPKw1uOoSW=oU&ruczd6O(3qd{8bm+c znD(8tui>@UUkO|GAjd&YoS*TYS}9lZ)`UR@#IWGM8#Mq-+}Ukx9~@cD4na4lA zr+3?W%#&}xJPlq0v{guNs}#_gjQjKyD+#aJbK@m?5G6rhf!UNbR^hzG$S9A=!E%DM z9wXmR@>rt+v z<$x-|M(0tON%9Z{(?4EGOk8QwnKx#C%)wexzkYU8e%XIc7X3pm>6m}9p`LjxZ$RlM zJ)PS%oi7jdyb00NEM%ji;#R3dZF{LM_g_V!yu>>r78UxS{ql5vheYjoNFc&)tbgaQ z$@yW$qsw{{-|?7?p%qLPKcDBIt4eg22a}*>*;%haxuXuHP#1tCFm~al|8l1m9_p^Y zvQqWLk=Uvwt+FqURnA@sGg5mH;f)tUz`W%C0)0T57c@YZSDYPkoVp($GpJnA70uu$ z+zo9isE4*C7m}zm)KqcA+>xnkhh&ec-WJeY7Ze)^=kG2bB8Dw*F~lV~ja8=X8E38(rf5 z6ksmj4LK1$1&A51K#6aoljBDn*x9t(#|5h%TP1)g`NN0H(A`6M?W7A+2-%!M6U2l& zRsTP{1A&HwH;9I5330^J@_7eKP~3@SecZr!Zi^ePYfB zHXL#{v0-lPZudEDBviD+&MxLks4T4M(dc~2=N(>k+(hw=zC(#QAUHmG^2I#1_FWOL z2C0dPkP^UD_|90HvrKqozqu@zM#`TM%-WI?z2S#Lf1|hB-F8Qe@a7anPW8b>5fj)-gFPJjh#L+u6 zN%CUBl-ArqOH)*)F3sM#PxeJ$Pm~s_L||KINWAzPy*&JhM}QU0J22p0+X&V8*SNNR z5T+N3Q2i2j-Yl>}07yxR-q|_U?bKADfNfEbZC(^#%!XFFT|3p?@78!nt6Yk^?+apjY6akP;yf}>tBC@cUxqZf$CA66v+h#W}Lnt7yY&}?;7sm@WJ z5kSP5O6wONO0L}=VB-8NflgtqZ}l&knGXPq9md7$D^O4QzR}hK7GT!WHzZj2?y}Xk z`sDT@z)yevYO>fmulI0{tOD=_5k@piTIq0+eWQ#dTyGSjdv^qII&b*NrlvTR#$NGs z?VEUB=FI8vk9Hq^%9lOYia3pWr$nEs>Y%dmv~u@x&wUesMPGioky`+Ak@u) z;RC;DOd2kE60ei30b?S5IhlwA1N&{CEV_m>8|7*7G3Be3b0sT<#R7Xq5|S`3?_DC9 z+uR4Cv+JJa?CrpPVi};=75Zu=x)_SdpUI>mo-@3EoCplgqzWTB;@_CAY)AGh%UTze zcb$Z&vx$Po`7J#w>Q@BRQY_tCdK5UepGtPM0RI=lUGnJ2PJ;USW4`tQEbr~bWdZsj zOIgo`P`E!5d^zgc0BM)?CTUa(uRJ5I^*mJ(VZy%eJ>T<5P7&H(Iw08L{g<`y8yfSV zE*4nQcCauZ4>A`IbFrDj1dN^|M5)C%^gHfmjnMt0W_GKg!&5TQ13Kk^vSF_k>t+m@ zeH^`q8QdQtYKH%c(bgY3bU7)flLk(deR!zz^0nKGk*_+Ifirn5!&xGm^yo0SBk4uJ zt)NX6fIejJ&^hCPTd|h4H?dKuJiy!6L0wu(lz+R_AEj`ABo3Oa4yD~4d0!88LE!;} zQvRXzZ-SIX#r(P{SK431_&&dz`8{iLlSfmE?=U${`JMwbG7R5JC({OndWCs1n6mF=Uj8q=WIr zLAZ*)3|5qx*qJI0{k1Db;6$tty?HE@^|X_~#=|OW_O4qUM%|Zx=^ne|M7X4A*_{HJ zn8y8RnLKkYBr|Kri9Lfin>xnrE1XNPzEk6)p5Z-KIZ*|b0u|TqM4_Q7bTo0r?q!XVOm&fX&}S5>(GKwNFYaZ}T=QgK zmv9Dy?mhTpqDAcgz>}1Q@=2Y1KJ}G|-r?&<10o@(sUGRVS8Wrz z?13Y~l1}54tdb>Rv-1bV)}SB1&rhdMU1l_9+H9O#D6=LU!~$F+=og$<(3O{$7bfH1 z*ypxT3J5PQAd`kMD<3XbPYV?KGof+6xzvDj>bw(qeu ze@oj{*!Osi_TN!kK~4U0y*DclH~js&1!6^t=2insS&QOlIwv?^WJ~cYw|OiCl$&K$ z@1|o$nhcMQw)1TZ`1XF|G0&DDzmnxrt*NQmIwr`stKK=ESTR;Ndm}1&5JV^AQW*Sm z1Q4=*zY+oc@>P!KdI7R~p&9HX;Xr8X+=9swcyh>92DW|wYMg%S7jiA>H)QXGCbq|O zYvI-Gtxe#g1Np5pjg(7IePQ4OOm_86ez7DZe5kPknl-hE~@U~ z+|%(K`zJK>BcfT-!BR2rRLW-^U+zgCINe@2oS7|swh-~n78Zj*^7{MxzsMsp>*@r{ zD=U?x@d@c+pO+cm+?_5#D%)?>@el7=xArcVe@xW<4*MW|-IgshQDZ~1%s90)Noo;i}fO_=J^Oj}3XI@4%(P#?UB&@F;iqH6w3saRTB$@B1(;b4bJ%G(D7 zm=tN|jEKL@tFN!u`;n-yBiv+DlkSbf8Is7M=^n6Q;qPy}yPLk?-9`ee072Qxh&_fJ zG8Jzu8Z}kEZArLJrrp=QF2ozzrWObkch8QY=N}a|U06nq52>GbL5lQ^b8v-(g!Gyu zW(l$UnZ5=_6M^o&AcAerZyUv|QKstBuZ}9jmDsXe3-uZNjG6-m0|j@fLLXaIVc#A2 z?%wG3>-6^vK0ylOhRW^0%dJPQzdk2Y!?BWR1{?1V0j0Z+!>hJx#EJryt8X8EpG)>w z7X58H{{EBy`~CFxbCT3@8FxCtyCXv!FZ_CDS3QgD^)+}NFDCqo6J1Q6ki2X@UpMy% zb{>h7NU8p2H>ARWMK7r3bN}q_J)p;{pHM^Ffa}eB^hWviKJ6IzofMY;-~6|Q@5)mRf3Oyr;Z_sx@dHr` zdyA@~m7UY(l+@Jt8wYhF)|ltUW@d49rv8$;2cQt=wKE7vOQEw)CuQsFy7qmZyAS*! z@5+3S4AY4M6mo1;RrKj~Vq=y4oc4htA2^2FVNr9YZH;rFx<*2A%Ct!AC-gx1Y~E-| z)sSk3u8X}4-+RE@a%1rfRbDm$Nn^E5Of7vdEJS#8f{H#L*83` z<8dA{as4?#GJmT>nbgp}d}ZeEyHH)_WNd|Vz0e3@GMYJ`HXGGG&Gu;jd8?_DvMvzv zh1IERv0hmq=Y1+M`%j_y(Kh>spf`q@uYg@_+U*1Qw}$&j1^iW*8fOUK8)UAN2^)IM zSF}nflQ3JJ7NQRL>=<=?A`+ekvN}DKS<0V#QS_Z{8}8Nq*@I`dp3k?*BzoKioQos2 zF2(RF8HWJjLfQ20pb)dW)I8{@H@R#G1a*brk-o+O7tq<&ouXdR^v`JCru7>#BXP zRI-yz*$-I%J*+zDJqt%#Si-L!m-4w?vAy4{){~;qOyzWx_3bO3nblPWewS}qMV`iR z{S>0DJ6Q1yIYZ0c1Fo%Xl(_G6A6l3s+ZZ1t+*FHoR_Xey%EIrnWT#! zs^y%#5lGqifWzX_fgS}c`~N=7h9%&hM>9K{&yNafPhPifs<`u3cK|zK+C{QWgLzLO!B`O44;jmelU4EWPC(*K@LAeHb=hQG%EZ~12yf^roaZAXdbW@h@t z!}A(yY7)J10u4<~hs7~+lYqz}(&k=OSC{OK1K0Z+)c)hQNJ!`0>}+0eJR&*}7YSsB za6LV}+Un}}-c<6VL&pSpw!=082Sg#`M}fiKo}S5xoi}@%^fKD8y5)!N(gYS&3=%#a jmjZuJ;{W#}WaJN?F0*jbbGRM+?l@&d4TTChi`V}JlqBkx literal 0 HcmV?d00001 diff --git a/doc/html/_me_limit_switch_8h.html b/doc/html/_me_limit_switch_8h.html new file mode 100644 index 00000000..e724692b --- /dev/null +++ b/doc/html/_me_limit_switch_8h.html @@ -0,0 +1,225 @@ + + + + + + + +MakeBlock Drive Updated: src/MeLimitSwitch.h File Reference + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    + +
    MeLimitSwitch.h File Reference
    +
    +
    + +

    Header for MeLimitSwitch.cpp. +More...

    +
    #include <stdint.h>
    +#include <stdbool.h>
    +#include <Arduino.h>
    +#include "MeConfig.h"
    +#include "MePort.h"
    +
    +Include dependency graph for MeLimitSwitch.h:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +
    +This graph shows which files directly or indirectly include this file:
    +
    +
    + + + + + + + + + + + + + + + + + + + +
    +
    +

    Go to the source code of this file.

    + + + + + +

    +Classes

    class  MeLimitSwitch
     Driver for Me_LimitSwitch module. More...
     
    +

    Detailed Description

    +

    Header for MeLimitSwitch.cpp.

    +
    Author
    MakeBlock
    +
    Version
    V1.0.1
    +
    Date
    2015/09/04
    +
    Copyright
    This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    +
    Method List:
    +
      +
    1. void MeLimitSwitch::setpin(uint8_t switchPin);
    2. +
    3. bool MeLimitSwitch::touched();
    4. +
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    +Mark Yan         2015/07/24     1.0.0            Rebuild the old lib.
    +Rafael Lee       2015/09/04     1.0.1            Added some comments and macros.
    +
    +
    +
    + + + + diff --git a/doc/html/_me_limit_switch_8h.js b/doc/html/_me_limit_switch_8h.js new file mode 100644 index 00000000..1976a197 --- /dev/null +++ b/doc/html/_me_limit_switch_8h.js @@ -0,0 +1,4 @@ +var _me_limit_switch_8h = +[ + [ "MeLimitSwitch", "class_me_limit_switch.html", "class_me_limit_switch" ] +]; \ No newline at end of file diff --git a/doc/html/_me_limit_switch_8h__dep__incl.map b/doc/html/_me_limit_switch_8h__dep__incl.map new file mode 100644 index 00000000..e08b21b9 --- /dev/null +++ b/doc/html/_me_limit_switch_8h__dep__incl.map @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_limit_switch_8h__dep__incl.md5 b/doc/html/_me_limit_switch_8h__dep__incl.md5 new file mode 100644 index 00000000..94924b58 --- /dev/null +++ b/doc/html/_me_limit_switch_8h__dep__incl.md5 @@ -0,0 +1 @@ +7c2352e14aa07f08a41b75444e605571 \ No newline at end of file diff --git a/doc/html/_me_limit_switch_8h__dep__incl.png b/doc/html/_me_limit_switch_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..26110639eac0b682f8c78e7c4d02a039869a862e GIT binary patch literal 14088 zcmbWe1yoeg_clxjNDE4rA|cJtjY@}%bVx}{cc(~q*8tKD(j5v6-69<_z|bKuG`tu6 z{r_*Q@B7}hzROy0S$F2%bN1P1@8@~;zG3f`WN@*_v5=6EaOGqrRgjP#1pw#vkI{kO zVU32iz#nuY1sO@C`-h*e?L`SlNY9bvB;TmHL-v>aymehN507Wyit&Z7Kln1ew+KK% zqj;ZE%vwBymLrF)PV#PgXpQYtMrmuy!BSsKtL9QgOXuR!?g8w#n40`k?RI_8abM7# zJhRm;+C|=X1G?8t+Z-0^zKIR5-f=sLoyTxbDNf08B@C|*D=v@q<>AviZ9>LOIs~0I zoy1ngNF@L7M?R(2B64VGsH~|@z2!8TnXBHSgY1U=ImS$t!M)m|18_-Elh*;`IV~-1 z(!g*fcWo7vDnu>O4JFe7;{`1(mmU))9dIpSa(0%~?Xe27r&xfBW?;{GouL-vl~h0WxQoUfWnX4!l)&HXAOqL zzXk@QLL{xA@{Gm90iNlmbmj5VSi9B?*KOGYE_aU=pp>-3tfr0q?k3)Ml8Z|!xY=e$utqZ(g*xACx0?q(7TgF^Y*RUeBkr8?^Zk#RruzExhqdlSmm3PgKhjfu4%|n1^Lj zrH_4BlQbjE4n?(QC3BUesE7N+|D8Bjfjp?!iVM^uH$V+cDos8ej{&fUsu>rNz@<{) z;512*8t7e6TvgHd48KZqr#|o@CaS+f=uc!a5z;CtjE-tt(Uprg(%4;>-+FfKZcLRI zyPjH_2+XiFqL<1ac$iw@beSdxe{B^XA0Lz|T+M%ZS%2|1({0H`(|ob|VRV|Mj|hRs z7izd(-;#Eo#2$Y5jGc>`)6ee3(KkNQaq?Y>+VyurvhTq9yWCuF zFIJ<~hx~#l+zkTDi!>CGLtCrHRub<(a zrKuf0^ReyMYReOLZcd1?EuH@(|85XO4-~=*c;7_gzuCvzbG}hS3+)$ULkpnbc)&jQ26?dqP=Y zBXRw`UCCRvOnv@c=TSV!iHHd@6or4291>EC)bz|;DXUchg%_{g%-iwSh|g$qd-}Wl z1#|xVPaG=IM5^NVTU?TJCzR+Hra+Z|sY?jNTxe$46?fnWz*lAhRaqMigeVS+F? z(F5AQ?4cq)T05F^V5$)R2?F6I(6wl6^@Gc3H{nW3K^$zF2!);=e8x=ei^^5P=9 zD;rtbm*`W|$({O#n=|TfLy!Pt2^{ZZVuW#FE)TH5M79u_fCHy}+CFX3Hg`mp*dC-Z z4iLufSNqfT)==Y@Djo_34kBdKp9~cb!~gatC+9uJo_^~urJdW8fDtj68!`uI@XTMh zkJHz76rXjqS}nXU;Esc}-W+K%>9v9A?dep+op9{VT9}Z&?62>i?-6z#tM59I+0iQP z;aIsHsvi5$oP|}|Rim$BwDvj|)CKyr5b1Ptp%?L1i@A9z<6u~Cjz>tVZU zKY++St{H+~ENW&e><^QFL+Y~J`8;k(h(w&KtSYXXlu%st@-a?VU<)}4H}%b)#P{Dt zGVjW@a-lzlQuK$(PR5Q@N3(3W$3#Y~cFiU6*97`-2=xu6TF5Yd@y{&|`_bGB4=TDj z6F=(4oQfd5qY!$GV~AsN=lj;&pBz0}WGt(4Bbk{F4_I0GLOLKO$rAV&){b4+P{9*S zkhSHqx^naJC)6tT@`v8YY90t&v)xKf|3<3cJ9Ou6l^2{gHH|rkwHcv+shnXnR?){C zyUBBhSYoz~epnaS&`x5x^xt?U$u)gjLg_}+DJeQ~2@EzXe=bX&(ew&*wh!2{Z&U-@ zQ|3o3g@5P1mXY|Yxq!ur`V4Vyn5v{)>Wi+C$-_WnV|sH+gbUBY%`x7|GPU1j>`9F6 zVu0#<_^Xh_Hw+-|Map^iuk8cNv14Mal91h$w3KPI%TKyHf zDf9S@K6}b-a9{B(sWU{hI zE})AGYxilguA}c={44=^bXf@#FCaeSt=m?JF4`V_GQ=|mqf($y!WpT@75b^UE4kfS zj>67H5Cfm1MUi1@1bXSdxXR^uY6R1Gprhswdxj;(L_pq2e3&ekO=Qz`cFE#^cXPy@ z*X%KK);QVYNl_2x9IUT4tut4(tcq{)zSG9Ui&b&Edw3?GqWk1b#7t3i(R{Jb*eFKl zl5IJL2-6%`tSR&=2AA(4I4D?YYWX9dqAZa%Hu5i=^a{B)oZFpDp<`ScujZk1i|COV zKWV9MX&(@hcUX)&*gE!j)6c%=PBi#LnRNyEuBLs?SNAlqWnqw7Y!51)4&yZA+Dbz( zjHYdoHnsPGGYS5XkkTB#s!lDtVhuX+f!YgRAT!v-SlS5?JE7`G5=95Y;lZH4BF?u9k4X6I{WQQivBx`W{*A+QFYEq!C$p4FP9m2AtcdOM4=hCNTUXdLVAs41Ij>3G) z9h!)XB!N!Fd-KUCNhAZTsLlf|>uW}$a~*tyez(h`I<3T;W~AADs890xF5Lx#{bpzp z?njZBV+5iX(Pa{yt)NgeGm_Sg<#so^8mXHkOH5BHCP*|DQ&aDHU54W;e_&OoNNbis z=2zV@;2Ghur=D?(f`8FM7IpBF&?s(USbGcF8d^wj-~`L~;yiLsfKPnIUtiOgLhwgB z@`O~Wi%J19@@ZG!SRzlfYP{#Y))=BhaXrcu!koJ&d4`!3%E(hL2F-i=3Cd1Oi}C=X zWXUXm#Llf`tj{IO=z_w|1E&?pT21Ra`Wg3PmB|o)lsZzhtD|cU&bx;jT~jpK`P@|V z++Ao}LTy_W9KA!Wa0EN!pRZ!{Y16?Vd5mTuF8D zZ{IVc=E@8z7T4UGkHxKgJ;QZ87Jpv!!C@ZFnNo9%T&!h(m&NT z3yoxLA0t0G%H`${_-x*cT+t&UjHtZ!`Kspl`&W=@lrF8?Uf!b)&p*(CJIGk5blUhXIK@L<;bP>HDPPZc+&?VQHLw*%6__F6!SQl zBnR^+w;isrNu)xKUzQy+qNf{{tS)g+x_j*7AH&w1i6&5TXHX^vKY@{3pJzVDB9leK zi8V4bDaZzLDBoX~TdzrZM`K#5;Yt(r22$iyQLKK@?v7ROnlZEY4z!}eqa|x>!INJ5 z*!YcSLZHAc^>{|ff!wbN&G6FTq@_C-?v9#{feyYnc%$>x@SIZbH;g;jb!H7(xHJAG`kjSGzt@;9;S_c=oblFoW}a7xE}pWR0 zUFylDVSOAy2<dmoxZ&=fR^eUe zGX$qg&?S1riWL?wrmd=#%aJdg9i%+T_}kiG#u~#2&r7lK{G!CgUP9>jgl|<162i%c zWMF64kO|w*E123f8(Y&h4k|z_sq`*PZo4>{9h>ss#m3$GDXk}e{doHhVNqg4 zHa19oPd`d4{plw}A5`I298A&So+qjqPO4$|C+OqndyF;|*t`9Ai1y>G+R{D_S2&vh z8|e(eS^M0V373l}qOf;h>-HIQm$vEXXWR7aV$gxGoE3~w1{ouZSF1$^mNhHMTv-fi%?+Ladn0q*Hvv7V7yp)+u8aq`6!n*at?(1)Y zYOAw&4VcLC3!f?GZItU1C;hbd;Hv2~@$907pyx7iqqq4_!I9gMPlI0EZV2$2@*Fm= zjFrkca*rE*Bb8mfd6LJ1ocUBvw_@k`JZ_aj6?9fwF!i){)4oX1Emrt@ymM1$-du8` zP;zx0;=*RrJ4|=R68hwYxaiK}=|+KTQ=&uNgS*vU^t90&r=XqR%&n8eui9v1=16p* zLvX|BG6qX_fT?bgubN7#R#7urUD1!C7U+~zszJA<5;OB-($!_A_^+eSUts-3T+bG; zpAf|5Dgz|QB;9J^pnd@Ep}h)8xkW=Zu9Q+JG(d)=pCu+})EyTy9pAMGQQz;KA&f+- zOm>zU=FG&Ec4VWOJwx<|MRT!t9pF8Ar&*0J2*(v_?Ikm%IF=Yi8 z@tuRXo2u3by(Vh5?!%5{E(T`a;_*B4EHntb9eP+01eGzqy}oOtZId8|cPxv%9!OR3 zA0G8fReG$4P3dyMH?A%oXqO1{cnM6hzDsaB1Yh9P?5-h%P(-UVyj#mw%XzA?HKc?S#N?~B{Vu&v`_CPbl$#0PZLsUXiVB8R*a_puKH6-id!RkI~GO z`X-~h6Djyp>|zb*PM+j;QnjWZdiaQobo zQ86|*4q6rJ2PRm81Uq#~9XnE)?9=>(RaLhT2qbGm>!5DD$lUO%$TB?@?cTQK}}EJqx<9ey7xQ+Dju>{@~0 zRrOm4MQ0cQbAQpu7iSlqlh?cqSen)+Q%?iEDN>WpxCbgg5&+-8TdMOuPWh2M73Z!(wLm=io+I)pW~^6Jw<1AJfPhR~K=H`+1&& z3ods0&#MT_XE%#5WSY6Md*0KR;|Y+ZiAg5sBAZWyj)|PTAS7UV@sJ}6Un9$984G}! z2Dlw6KKQV|h_G&|DI#csY$^1D3>nktzvgggcY|5#bF4aaghWAB#509Y#fQQ?Q%_MT z7UyQGdwicbh0;$qdK?ny_~3r2;e6*&L~= zxU`WKphTgZo#$c%v?M5vvi;oHNB6%`O%+KhN;39#*}2GY(XzP{=!ay zPPA0i(~K#iM~k(U1Jn_MJxmjm+uY`3W(g7!QOAXr-b;Wf5B)p2;D|GYJr;*PRr#0D zvju-u2kIYNzK;+s{V1ql7Q*E0nVwxEKBix6#iQfWB)c%p7=R(BV}rO5hYKHRV|~mK&|f z1mfX)Sah=NhcF{ae|ew_k#_*uS4)vZ^xfZMCW(9_ncWy=e<^>e)kW>(3b=#de}F%= zCr>8J4B_wtb<4i2Ir;ICI%CxI{-uVd4h~(ZY3Z;@IRNZCtS-2qTqx=DBnzkxeQGKP z4UR1L0kv37_3d+fy;PHGS6yb=#|!@aMy%Z)nk}^7Rv?v6Iwq@osAGhoMqc-P;`>|5 z`l7UgzC`aafLKf?4C2XTe&O`#I(dvt-a&3v*XVB&r@VJVR(^}SI)eu$2a>omY~Xos z!kh3+K=r6~=mkOzE0D(f>o_fA0%DuHJhX={e~?DKnl}IHUQ^~Jl6m^#ic1wAhoEA3 z8vFF)spc-0&{GGQm@$Q}_;GDMN9}!k^z)?$-sTor?b!IsR*dG+qEi1P;2^>dAw2Yp zHm3M)>BllTPEInlHW9-40+Cw*XG*J-lbA0oFLtgn_9mK)S(D=49kJyTz<4Fq6G9w( zOM1o!u(l*lQI1STrKkDlUwc=*mZb9o#wj~ZT7=`hZut@;vX}(yTIK&=$v2WCZ>M}| zlh;dixbYb-@gymE)aJGrUK{{Y(>NFcCiuB~Up@r&YIJ?GfAH{wgAQjUs=gzTJ$s+8 z?75dwg$Y9)t4sUt=Q8oppcQVsbI>MOnmk)(R;p+Q2Z~*{*5tCuN`!EsK$Ps`dL%d~ zDm}M5>~^Y#P$KQiH37uHgfY0#%Vk3r_=bQB@rfl0J1V;iTm>?;*fea2th_Ii0Y4S%CD(9uo3F91#fGCp~g>Q`@>#Ts? zC=XV1&|6-mfp!wvD!!?EJ{Zk~fn>AzV1Q>?WVx8fzk@ShyxjbHX=VXfa1J*Bx_{41 z9(OO2iZaM{G_OUoR)k2Mx6I7GUj!wW0YYw|?M*A$q27wg?pidX(t`r+#kYc_PxB+A zbKDxgk4m+9;HIM4fnvgZn413}(-t!)QW4xhKqS#Ali1&%mAmkdZYPFPXAnx#szd|% zG>&NsAVdiqoG~vpby~vB7n6jgb)V6%c43E*ZRyx@^j@eGCJj6G&P|JwR-r4Q#S3^X zZQ(=o@wd(%`Lx)N7`VE87HlNseYFIzV_M8JFCKKSN=rSV2Y znduS*-+U)Y*6~{eC6$$b8E^F;3h=S@PKd3%6kq$k?P>fmvFH8fjh~8i?Xp*Ue?Yl{(2UWPKUqS&b$~ZMn4p$A)cY(BOm^0nz(a1N@?}!{sMjv^L_WoBR@yQT+TKeY zBbTQ5zByAl*Ah9SHl4#W?Kh&>5-}R<@+(U|MD{v>#)a1&Fts~QLVD}QJ5d#$7-qG7 znpO+9f2r&=-}vO6-5!4t%i|__f)mdeAqziUN{b=-%m(B4`!U{Pyr}KsE zU7M=AQC)wMg3DV6@Olv_lKHF;MH)u3B7QJJulRup^BRgdhx#sEvf!s-J3*vgqfSsQ zu=pbhD5{OFfUnlP|HGo7Bo1c}s#!%K#bj7^BXZH2$d_v53s0}w{Yb%{@L%)$GZfb7 z2cPV6)#U~!DgeAOgY(A#uU2&R9aV%4;4SLu>Y~2Y!gd2XIfu`;rT0VdC-R^Jj6-px zS3axOxfD_{2}z`r=40#Y@=pX=d9)tu;`~GrxPj*8FXC}$J<4=Y~l%! zSCe#dbHTHSP{K!?(x{u!{Iv=OErT+Ef|DthF(jS1)tSEanPPHU6x|2!7IRDVK14)F z&r2_H(Cgs5)-rw(r;d~rolro$XG{Kdk%k0Iw6Nz*de84y zcMK@ncupy&s8*H1j>q)vIG`6?CeQvS7K%{?S*#J=KQ>XpzX5T;~_Jd2^aNTbD);F5*lATjPtsB>% zZ6XVZ`SNZ+&clX$n8M7l3dqA-L2ubHKf=xQ>PyM{59JCeV#GMbqj!G~YjCfrBEcnJ z)J`=19!)p8{IrrN$`?FdM5Han90LS=B5R0c*3-kiNR<(%bq~ZAp68_{Kr-)Gu~o+{ zzV+wjgEuRgidz`@SQ;**FkuziNk|-~9T%W}e&JW5wc3|MrD&SLePff=$wC^K@#2q{+P{abj@=M7n$ z_Tb_$u}IkmZgm034~mdujl73&E`!RBn-`w*dsne3{5Rdw(THT8xWAZsWJDrA0M`a} z3)f!C@Q%@UZEue#bx0&sZepUimSP&3_Lrj@xwh4qKfp6o0qLLXpq*?aA6|(YMcjrW zjcA5yfLmeyPj00(qG5x;7FoUSs`81=I1Tb#o9DZxFY!M__A(nbtS(g#x9j;i{*?KV z72#sp*yfL@n$H`#r`?Qn!Ir;evh8YCddTc}g+KCYS;%(MV275*b4Msb+CFQ``n|*L z{CPnV_F!qyHGrW&sjF+xbfsI;XkMfk>7ooXF7?M0uXOnfgU#YaY(?a7QBR)kWgaN} z(uh}d0dGw>SLzlV{*&D^{%YH)%nfUC+U!C+%b%1b_KOzhtdS||g~oq+*u`|-q@FBw zkvhWhe=?f<`6tF4q6o*3jqDh!3IT9gG2{d30nsMhaONtW2BuProx}Ho7>bAe8k?uUuh1%`^m#~}a z#A1*9Z6WIV@%E0zCUR0ExPoZm=CtSe3c4AfT`L=`g)=T0e4Fqm{n7fd+n%Db0MZnMyim_5-|OIYK=Z=!^A z1rCX{5C~;&-C_p#NVenB@Vny}hcM1fbR@Q4-4LaT0Dcrs=cRo{8Fj`^+h_S<&P_~T z{C4>Zx2NW{y3;nQMK*!i z@ujd40k$q06mD+J7x-H{fC>(auGaaFrpHSQaz>jto0B7Ia^wAAP>u}deyCE7C=&-m zO#>XXw^$W5SM>29Y0G_bv^N|AHWa@015fgSQD((R@*8uEF$RZX7} zp2Pg#RA^p1kdp&-PgqWv{Is+-lRg1c8oTjau3&aL00TeXMn8UQ_kHyuEIlUkVz+xWCs0yypx4=^&|G~Th_i#MX~qN zGOXy=cU*0^C9s^|zwZ zyls|aET)+QkF@~{J?(2^(u@~MTOD%aXkawLtG29P-mNW$spruJ%SKeWi<4RDjWW66f<%+>MjQZ3#Mu-c@cO zRLVKthBK=&Q2#^Hq@5U$x1MLb{8!wfk3`;Nvr{v7hZ1=bqlOJTM?7*aC6T<;2Eeh; z%#mrN=_8(cjs}di=ua(L(=h&Kr))9<{m#_sD@TgXzpxkA{UwwO;s&HN=eMuER5`O& z_dS@t-7h2C_4HL0^~B0y{c9?FQh3T-Sk8%Gf1Z3U)N1_?!rq&{d2f2ivBBbT^zl}U zDWbK>h=hrkJ|N$6L;f^hypDoYUq{qDS7sw`+9r|Sj2ri5UaR-Gxpb#+yG-Fkyx6RZWJEwE7FRZ<4eO?{7 zo6K6=4h?VT23J*f4p2u4L$`AQ9a<@S#FWXRC)Wxqat4X}y-{&_ly3WQ&I`S5AA;@* zsv4HNYpSc_k6&RUdn%5)%$f18RVFl+4&mT=(x6eJ}l^GPvT(eivFaI*Iq;uR9~NsX2GUKA0Qv|Zl!LS=Z%ru^5?0~ z4pc|+-Hie4=$B@FANFMzL4y}Ssa?GFB&VzCtde1Y)J4hZ6Br8>A0F*>49DQ+2?1+{E7!pH)+|e=^eY!RTcdJ3rr($?1t<)RylAF%Mj z-(vk@bT37H1%X?fjWqN>!ZbY{oa&c2AA zXE{w@48i2a_n`~gqwQ?vu{&628R0h`<;M?e-_5YrTRfIEF^y?lE62DiZJ)anJaDHI zPdmw{xTk8unT0{yuwcRDA%VuH-4{ z4$WlPVU-G8?IB$JW%wvD$T2M^sc0g>CtJU}_a>t(!vf=9a}`LBe(%+aJ?N`>QY>ee z?BwCXYnrr`Y1M$vwH7h-0qeXFND~K4sP%7A=F7ko3fpWP)VszggOwB}o>1APDK>Lgb@+ zVl`f}`5B*53w_++;=f`m)u4GSapfY)QUG+IJX`7y9$r6y-lI%-&j;*X*8Ns?Ew<}B zP0(Yu`PQHFeHExXY`?=3I3+(7JT3cfbVgBe$+Y95?4n_F{9$R!8J0lx4si^4!=i@E zb++(LM0a|$Su3DWnHbd&z8wl9mUKtof^Ma2_7Ss%D(eH}<)P?D>fm$gxr*~#&Y649 z-AEQ&TP=7`g9IISTS}g5C2eOaW5ZUlBI#4XW5A~|2c`ws`UrRX?6U@^i)1p-imCts zEyBMnG+A3z`e&1H%h!O8^cTJjwrQdi20dKrIzm31dxDFyKUYuLBu#(*uQ^FMy!`)Q zU?$f8bU~EmDL^;o2gdE_c&g_0P?0Mrso!ApN}3wC;Au*>(7BNd%K-?gRrATEWSlr@0o3eq`B2a6_$Nv!P?J6a6-KNJCx}}k zM|CA&=C%InmbEvN?-2MjxiV4VLk7`3l5|kr&iP z?oMVnRJp(5b52uK&pr!{BzbwF2$Lmz9VG(@eMJ z%lDOiTrAAZ$5{ByKcb|Fd5t?FfB*SG5|%!?Z$BGw+$0G8g1>TUG*YR5_9<3*Ztujb z(Dv$Lr0Wgj?zC6Z&hT_Z@wneavu@m@U|TinKrTBvK{r739Nu>54p zq`to1XMPEuWVDh5t!lb75^wz7)`NeyACg7Me7&r1)?l~P;zBQo0er5$>H3e#UaRx4 zdp8EfZSTs>FJDBG3@o~kviUl@!l3i6L}kxQevIB}R6Gc~N>tosG>POO_S|2$5He`tuV6-2I~|4>@=& z@3ma~YrrOUqSt%1BoLtGxM0>N=#t2HU30cf-@|G#E)w1qfGPr9MSWe;amw>^W@cr6 zeEdmd=cmh~6kmUOe<(D#$(V^zCWgA8vy;Y4K1nPAFZd$e}WALJda~>|dZJrKjMFL7&1K0PzAw4;wEetHGX;x_f0(&x^a>qZs zq+x5;G2_@A1k|aCwjU{Dk7`SF4FWy0kuvtwXw;ZFougaWogIa=;#GxZ)nYM9@+hX| z+O>ss%5usT+O@&<+v0agBdcXE3^_xOo4y+h7`#}W824a>e1|>NQ>rN_2x@kM6AL<) zpwrxL$%LS1dlashDQ~sW74Q(j%Brj5Oox(_ZUj_BDEO?u78Moc_oa$@A;!~rt;`}j z3ldvzug_18V^TWYb>M_#Ba)-q&4dz%bF1)~Uk>#_JSdv2)#PwHkCXe)QGS(HHC((0 z*G8NB-$J%le(i-k0HKQ~nn1NX7fqMke*@hdPjEKgPl(g&`u-POJ&1Jo#NsDitlC!} zd^=qB&TTu^-aHHglSWTgpkW#4yvUj4ew4+)0;&Vr@jh^mpDpVCzIF*V08 zC;94_l38j4&F6*J@;kC2%kGDV9{hdC>bbN)N+>I|4g$@K$=}{VU38hUjIvT3)3&tweV6-5`@)-JVH>sJ5}aQ0 zzMwtE6$hr{Fk{`sAMSABsMfW#N@M96r;VIMm|fes>Y+p69l?RBP? zpA=;mdC&{Udqkt1sKlL&rPrRGH^mO-fnGW=_g+xgWM4%xa|oS315d=ih9!ZcG~Nnk z>H2vao9;2_L<{NnQOhi7`OE?j&hgrXBjO+KD|EEtN}*?dwj) z+ztdg~|4M1QpCSB`d+F%YE0&G4(OJRXO9Z zXIFQ`ULwy-g=YH=5P#nUP$lS=Ec_D1`xSacsNQcywR^7iiP=;!QY|tSCUl^+u<2F( zfenVwY>cC1BA#~cSboktBWSyhv0-9hP-(2V>6TTYb(jft@Q8vLQ39P#jpSyU5zPsFV>xg2Yd%g*Ts*H6Je>OhcPv=K1!|&-Ui+73z3M6{%XNEAI%m= z%D_uzI)wK*H&NUrN4T$-*&1epu`?N%tyj33}Wd-t)a_r=|0QHAvsJi7eA3H-!c6C9cd_J zd+yApkwgWcQxm1!Idvfzy#tm%^KdN^>1mO>uR_pOla2p=i31<@_AXfZj%xi{i@x-WgYK{o(e9bXwP5AL zY{gHoE=4H8^)V#lsbq)MC10I1JYqU^jdNp-Np{JL=M%5J42E}M-Y|}kLks#eJig^I z#;e-5_g>{qj-pwIR{iiM*uEdvb@{UmAqMExrPji`Q=jZThm)w1*kf@jD2>_yDP*hJ zC>Qo(R#~0@o}8PO7N$yA{P-04B`p_k;S>)i!Nf}aGbLkb zNfYaTFU$a)-n3k}|K14t|2~hLC-nqgLsBIRQS*=SyMZ}`Jm0W_s!>Y9=}SyLk{0sW zF7`vCC}4O}Sc$TLe!h4Qblh`G!1)JKM(Me-RI+Pd&zMXliB*+$1JKsZ?}@uPPIW(B z!AfgxSyk1F+v%2a6ebzipv1NOBwjH|B~u1DeqbHLU$9`lGf{~vO+>BKr`3yO+@SPU zL1brl_dLmRMJT1;UEX_il2<#8Wx766tcqEcNjwHH!2j(qal8|klN|q+?Y;)Q>xP6R NC#57=`PT6B{{U%>+|B?1 literal 0 HcmV?d00001 diff --git a/doc/html/_me_limit_switch_8h__incl.map b/doc/html/_me_limit_switch_8h__incl.map new file mode 100644 index 00000000..cc9aa0b2 --- /dev/null +++ b/doc/html/_me_limit_switch_8h__incl.map @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_limit_switch_8h__incl.md5 b/doc/html/_me_limit_switch_8h__incl.md5 new file mode 100644 index 00000000..ab84e1a5 --- /dev/null +++ b/doc/html/_me_limit_switch_8h__incl.md5 @@ -0,0 +1 @@ +9781896e9f9ed9108828f924fa0e89d2 \ No newline at end of file diff --git a/doc/html/_me_limit_switch_8h__incl.png b/doc/html/_me_limit_switch_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..1650bd1fd68e2877d350bc85b3d2aee6cf7d3e58 GIT binary patch literal 46669 zcmagFWmr`27d6a~BBjz&f*_5+fHa7-ba$6@OP7EkAp(*T(jeUp14zSwbTfc3(%to* zf#3gqo)7PJz2gVH#+h^O`#yWGz4qE`z9=b3;XHo+7zqgpM@Cv)1qlh&8wm-d^avez z=QXl(Gw>I>iL8`3(jDT@&zAf+B%~KeGUB3Y9;w?4o*wFJ4Yvn-RUgsGAMvV7D9ci` zlj_ve+{C~91{#@sUR|Qni`%}e6>5D@T@xjgRy~=*AcCY2kV!S|E8UD?0H#gB>WkS<1N+L~6T>Mh|6YCM4_`ohDJZO; z^1ruZM8(ac!yaC}FS077{#(1*6Xltgh|dBq&ai@Q#K&VOe+anmdfzs-Y&CkdEzV~* zl_B1^66U;#lxr@{AAa&QCR6I+a%R74`@`ho33!%#T*?gV+!7jG;Lb-wJZ*c~P01qv zNP)}x%0GPcSlU||ahscn`&GqITj;v4s_McwJu*u6=4Q4U z8`rRJt5hs?&t?}}1e$h(79HIESiKr28L-!pO>51r9y1M%Sfa)$;!D`ZX@oTT4IgzS#Ci^C=gh_3 zD;@TPDJ)NH^>1x&{JgGiz2bD&zJ`UlhWz&h>STkyQPmqavRI9wu&`dEpZ5o77S`82 zS-fZ#7WL^*@Sj`@7427qZ+8b`#+RN8+o`jSvDY`E$O zoc-r-ySA(SlL=)z3w2eTv~fia{LJ>8H_donlJ4)>OZcBXjY%*6Z;!*NzNa&adkye( zQ^~03gl+^Ia09OmIs@O63AZEo@SXIywzxR$)x+%(7ytiys)#2`Dz0{a0QZML!*st8 z#OKkU{$D{OtuPKkyeXc8x6RH;z!vQM!du8y~F?o$vqQBOye;3gxi%1?%?5-QuOz@Y;xFbI4Vk?$llM#FEz1 zZ4LrS;qtHq^a6J5z4>aZv44RYr&{fc0>M&ge!N2t+;fJ%sJ4!?j9(sI2fGMcM^D^D zO=Z|`9=5nobBhRi9D>^M&jh!A+%BY6jNGW5|2fRIt;5@c+9=+{`M+s>-hA9^vp7rs z@neadpR=!gjJ}=@-18+CFN16MO5{;M#oNMm>I#yIPslo}IJeEDTkoBS6^Ws?(uaZC)>4{f?|dV^axi;C zUT^y5CU~9JNAFQIhU57s8r`_Q>l@|fc14<>-@o;dmX!Nrm@S@V<<7hM%j6XFRRJZ;-(bk4gT5uzDm6pO_&?+;>y0K+)0gkg)nV&t% zAH5^^2~*UoYuF5iI{K2F(utmw(Xp z3U$3X{oBCg&F{YZeyPD6E93MVqdfr#BZkc+L15fly0hcim1bVLJCt)Nm#@42g^}%} zRbGlwsw5HJamkJluiH#h19+Yr0 z?ylOuK?bUeFgkk{kVeiSpYI>>x%n}8(e_5lDXU>7c)^JC8bs#iBPeMB(ENN%FMx*#;k)gSWLzJ1uT=KRqBwB$aVwO2{y zXb?OaE*Hcc=mYDw8(Q07ScF*`v2@q_x>8noHExR z7)>)b7ItS%`QTu|-69QZ(BTC!sX>+$2~cIQ{FlIHA3W3FUq@A%Q@K>M)Hqr z7OhQ6G?2gaDm{R;c;ni9eCtudklyHhSKg~qea_BW*R>Nn^Y$o< z-#F`P#4{aomTEI&?f`J43gp_$p>(6%b)TmR418GU5fV~nCA(jb=4lZ}G*6iRmr z$7CACESvX?ag7DA!T+j}cx@5OGCoczT6berd6A3fZ2Y9>Vi>Z$6K_}QYc=AzvZ@$W zb44x-*0Z2b1R3q;k?jW%i_xCOyI1txY3gxyV&kL&stuzq>53IglXOaRhM^S`az9U> z6>vv$xA1W*h||tJRFB>_UHE=4y3ZWn<7klRO)oslH7VRn>R;1@e8J5qVXY+84lki38`XN@UfygS1rK)7FZIUDWBp$yXBWKV%l3s@;!(>jnIw!g6*o6=;)QOejF|oSe*xFMeU9M|d3wMKi6gOL z$@ya}Z^ZQr^;wMVf6NK#H`z69q)kBQymr!9|5Q=loQ+W9)IzHWM*>Pi#kW3nx>Hw+ zv5yMo!w|=N2nyZEiO6^d))9ldLt>3Dt}na4oNA1df-|e3N0LO2O7wIinQxJ7LFu!N zsIzd~_wEh%LEIt~_Y3`vDzEHLtrBt1&#%=g*^#v z!+`Dty2u*ZVQs$#K;)@$Zy=QtGB-#OIjR8l+0*~7&1jC9K|nH9?@~azg8$CeTMA2CdKhodS-jo8wbE#eQ#hr#Fmj0rHMDm~oaZ4$<}I*R*C&su`79 zw_Sdj_WiBtEZYo{VAmww2(2!$zV*`$tcR%m9Kh#()ozTt)XwOpm4NSToTnl68~+x~ zD5l-+Y8^k?xjVc+y}hIwYTAjF^no3pm$28Vz9+Ryo~*&84}0#JTleixAblv;9eF{a z4KApTB#x-%x^r}8KMp+p3ED%K$R~q4J$(L%dxIOtX<}s_?uuRkAPO6e(AMfo3XQDU z=Ixq{NKaZu{XyI;qaMjg0>J0QdWz$PIVT6Lax|}fo_P$V8a5srrO;f-{yw@tJozEbgFOXH4>kr+Y01{nBv-yQ=a)eCzh`s`jbl(ldg2%9dJIX8D4XO3*;!C z_4Vqde_g@Mz_>=LugvRZ8yNTX7Be3nQ8U=P@`AvnhtK#PYhhipOuidZT3nw{Hy`jN zFrMo(vZD_+CP&$x{@6EwTg0l5#EssaLZKo^Iq^~c>CAskPLP~-2R*4C7WsDfwcOB} zXJS(qzFx=yAuJ2P0%6m$UAlN76@$GV{OtL(u|RScKQuK>Vkd`j=3(?$fO6n0#ow@Y z@upVfXd*>n;8F`sx1f1AZ>=s96O0xZTE_ev{Y*32%_g)WR)uA-(VFETNy$O7mkr9(~3zx?@5oElkG6FXnN9w$_KOY$%VCdhwy2 ze^gLsE#cct4nJ@Dpj@4ct*pY+_c`qnpGp2}+4KaLn;H*TU7*|^EQHPn9nYG0#)cV7 zj+&P{8zv&3@hB9rR)3Zg$*xm7mA35PJLnYbN(|sFk7$4I{!0>Xl}8zufJ%;^5-*xV z*ss>xiA%baJ2qJGNmr zh^YObgM!mV3EkxPD9f~}L3b;tF{$Iv5Q2&C)15OO3W%GQGTH2lVfQa2S(TGXj*9&{ zBkNWn#FRQkW{ zenBWB!i6T%!Pqwm1f<2nj(3*{ZGirKvWl+lUGHQSr>J?ft0wSZKNGY6iF}+ojC{wL z&$M>!YW(GfdDBNshIk#+@}){rw_UvUf6dH@6C2)sLA%6+#A&{*u!}|z)e~@nK+b#; z=abK~zqVr*8FZITi{l^vB%dZ-Wy5Qzt(~R}-P3HzI1Cn8SDRR$w? zt?Z%;mk+i^+syB!s)}57v!4&CG#U-W&iuGdDwZ1ZUXqhU?fRkX_?wZB4ecVT)DkG> zAwm6=eZktyzFH%L*g<7TQpiOVeyLRgb?Wlv2?a+oIy25x=FoFHa-23akH=c_bA?76 zmg)diC)YQLX?-B-IT_YJ23%T5sXoGc76;vJ6f2^%{db)+jHq$mnzD5FA&Px%#tgpQ zoI^jd_we1=S7*4cg&wF`VCki+k12l5r9zvlrgl)q2auut+{(%GeK6LAjN6x%CvI;% z+eZ0^$+RJ&j3f^1lg6pJvOinq*km#u6P5ELnkQ2QW;}KII`^zW)>x|tu)0jHRp%B# z4yQ;!>rTAd%=vlGG2M~c8PDmCvlx*b&zDw4jjn-mD-m{>oJ^< z=Q)aHO=k+^!~B2M)9vH`kZe?OP;a?uE$2Ls556q8?Wk->=|rh`>6*$Py7YG&nuy-< zG2Wx&HGBQ+82!1eY!RPfAzLlgnKnCV^=z~QJUZ7nI7Q)cRxLqt0~1+wu~ddB;d!H`^*R9pEvLkiZ3eh|cTU73=;w zuCB`M11*AYPK^W<1lxUPL9xU{KV}6-T8m|K>vmt%o zt4jyZYK-a0dZquy@#Rj;&pr&!fbW~aLb)YAY8wg*;ICjBV*11$D@~T<28c`&%=n+! zF_FHvU_0?Wbmp5{wtYcW@T#kZTXm1n}bq`(d49j7WR^JWH7* zr_?y0SAL*I&jLMKs7yIZ-QcPu?m6#T8w;k>caF$`;^DKD=2_Eq+S%&o_v&|?!DrR3 zH~o}Bd=nD2tzpQaF4hsYq8XOG-(F98x0eS@ z1qu2eG^jK|LzXuF2eTSCWI z&}5)(%qat#=`^?RaWZ`L9{#zm@v}9rSK$j&qBQV;!#IYGp6{1;x{>{;cLO>>i8T4k z$u}Ax3Y6{1`-164lVtYk0c=?!=zaOAr;NAJ=D%eOyJubE?p~av-zh*!-g4|W0Bk@! z=H*!bGvQ8HqU-scE(Q<$xLwJj55gm`+=K2&y^od(XZM>Q7mruikKHLownk3R>16tu z5D@CXSY4Mb%YqX4-+ipER(5q@aU|{|{kh7xwnEGs0&9G2AmR6rYU$c&^FDxHuuKlx zKooXF;N5vqWYhA7aHqy$7#AHX-#NL^Btt z%=26lF4%OP3wtig#fxm>Dc^`Qn;q+YtRY6>A}R z?o{>2C5me3b+y0bbGgfs{`Yv3RKq0TuefP1S@n@AaJHvD_7&kqlL(r0cN+J;yt<)M zv?iM#$+_>tX~p=VYoHYJR>}#W%rHG`b^k!Sz$lF-XTa5!9?7X#`<+HE2J%aN#yS7DYohvQ15~QWKo^GJW4U;18Zk5uv27>;rJT{!Z`P zEHH&kZ!-TBt3JoNQi#fpEr1V`inzlWw#J_0abHs9W{4Co6`i1N=T>$xH}2z};*CX! zh9=S|K_C%@%GpvGcD-lBW}UlNjTcn=?I4q55zsV7j_za* z%EcRA)G!d46Qzrmsbsc55s$r@o2F)I0{xAIyCiA#XUW0T6fLYfRqh3Yffe0n4_WUj zYn8UAqy$L}EJJbN_sJF+T-zu>bl|(L_3ozl;LFaBmBOp`2ekeLjDN>&HZs0QDNkkGJ9szUwvxSn{K4WW{gkDAnlM9JL`BwYNgr z731!TYn3PAqeMnvM^9CJ5pB*+72gBD&omFYqQ7i^fSPZthqi4Doha!%Z_oNt%eVP~ zBA))5Ak;ABsK^Mo|ynp(@|xe zD7rBrC4~frJJIxO-|2kvL~$f1{$cQn%yqKE2a~~_gZ3h))23AyNutY{p_Cm9iiYJz zqWa_7W<~<{fV75d2%ZMjJGu0peeTzg-|)Af_jN^*`r%TYAN@&$h!+WoKIG}vwi_;E z5G2*`+khrNZdmEBUn$GGb$c~a2EGSG=+&AAo@ii!maME5A^+CD;)K!&@w@Fu!}wWW z-|`P4m9GaqFO04~F`i0~H}I<_93QdzKA%?S4nY)7Z{Rq6FX}-uZIZE!bp*3>kQ2hQ z^DMRSh`@+L6pKW<8v!yN$D@16JCd`Sg{Arg;$>uYHGEHy`*IhT>+M>gqu{{(0Mf~R z#)DvgQ&(Y;9gpx8WhsjIp?^Ug%w?{(E%`sAT@b4Mu{WWtZx5i6t*sxrgTu)!rU+(! z-|8Iy#upw=-NIojVceX{k`m8S=AL;oPB2qv!Ws#(=YaqEg#3IJ#}9pXww*er(JG~7 z87lR!-=2nk%GffBCu_6Nz~Z7ySK1 zI%ctUViCsmqayuVjlJMg$k=)@R#d)e)6u*!9_vkUQwEXfv8dQRu3=lPowSx=_`D7V z-d&kpFBHGs?M*;6~e{WgELH zb@9sKWZ1q#kmcY-6PcobpdCmtU&q7CJCt0m;MZnRP7u&YA_gz9ObM4?jd2a>U`4#I zS5ggBZDq5dHA3*xneZmKZb(w1-E}oN(2ZZlRXF2}v2Py%v&}!oXW)5&# z_i3!vl86rTK?0YtRSTGSJ2LEZ!#)YZzZ~XhexLNr?=g-rd)I?sL;L)mshjnN(O;V$ z(4HAzKdYZ|<}GiWW^!PtSTCruQv})$w0W#;OrOfeY03y*mFOhj{dShQE1#Y%{;S>u z+eKa4xnHleWPvHmQf#Nxe0^tH##aW|>w_GBrcGO#n|2Te`N+nSmuun{UG6KrZ)5w!?++}B z=Xg3t7t8lJ>O(W?t#hx01Sy#3VgSNYGF))28}04dS86Hj;08g8A%#mP-ZSL8pUH8* z&}IIN%{(RtcP=cs+d0&Iu-iJ>5!pR&C>4A;H`gV8sUn}r8npvmhD?#OMcG-%H@C}X zL+M6UfvGd3iHgF%bk(q~^`rOMWDk&C6*TrRV+GS3!HOR#?05xx`h_3fc@Ut3&gF)({kkYdCNIRPr@mk>a? z0b;6wX!UxtulCKR4~@PX1cb4_T{Yag*E0-&^c#_>+cPTHGP@gJcj2itV6eV`@#i6q z2@voqxEvt_^K)5zpUVrh!0Wibv*>}*ME!v-Of&oFV%}(8!>acujWVk( zvsBpJ&Wr-bgz=`16-C%O&&h>@fLj3r2{e1kn-^7|FAr*{s-udkKtmPQH8=nB0?>>K zV99PT`X2ET)sLsXM(fnlP1qlnNRu`5p4Hqp^AZ?;n`@_sn0UWX*8nK!L8=ur-u^F2 zyu7?#li6pxFZ{ZSUHHOy=faNaKs*z_7zN#C#&AP zx#-OEym_^~l+pZ}4nP(czvz>Hn=IO#*GnXsR@gRuIbNDRIK2VgsuBv|6STdouN0q9 zM&Ggt-(DhZX^rx$+qS*PdNNoz3FzSFv#h)!z_sm>HzQO8%UUvWhH zz+?v)s3U3iBI2~N34`VGZ_Nca+@ElYaP7X9JwM@N^-*op%x#<2_%fPCJvhf~BK+@2 zzX3iuWxLlS^e`~HEIDlu92(LKiNW%*`8m91r3p|bxwS*)P<)EK34*!s0!MU zS&Ds`L>eIiM_Snc83Ebz%wT?17jI|t_9yAX`>oQq;;O1x2k-o!^0aM4pPbRwfZl!XJz;MP3 zj2S7U$|x+P6djhx!hZDYIH5E#Pyq{av?X-6BY2t_qKxis8tG&yheYLcPFqd|g%%PN zi=-!b1eG}~QBFDyknk1TFsF-q+5S=UM&spPgymYyOAC(ynUOkc(!>k|uvpqd*bx6W z+j;r-U8p6prL|kdgj5=H+=~0v?P9<43m&4wzLdgK*YRXCqXs~hmnp-ZwNO^Q@BdI9 zk(fe5DTHmi+uvrkx4w3R(S@?gZ zD8)>biCIwEAXW94nlfB3qpe|tZa2w8DsSVZ@q{}2o#h^cw?A$8xesroaWncsaGPy; zp0B#nRr60HEF11`nze7*Ms6_&SseD4_^-L@;(PjI4GeTY-~d@h8h+nFNSm$T_>Fq4 zJ`d`guV;+!sUwoF=E;V}Tdm1ZWjH^KUP!T*cGA<1|17)U-L_3{N+?Uk*niM1sTztG zMYPk+0Vp`QsJO1YBaxi}aU7@4p=xZ#g3H5Xf)b&4LHRm|o?eLgw55aeWg0*$+ys~X zk?h&wyNAI`^R{}A+wlbj@}-ZkGTQ!n;axQ(-a57R8@pHUfyhsDk6C2b4QUpI8uDydC`) zihodoNEGrv z3-<+p&|*CZiI0_U5QPnOvf&`Uz4^C4Kri{m8{+0U{zle%GNVY&Jf_0WN&3tF#kCJi zZkg8k7)y(Yr6~uJ!gK56eRiOa3t9B2wWM}Fq_z!VpQxI0*JRUBXNqIm zMsbBQz167wQ{&)#y?>$Brod-Da+2p5piorDuuke65y@Kp(}Z?>>g!I}p2c;is$d0O zH@?mZhX-O9)~WFeCp@s|N6Pv7J;~P_ZBtiQA96gK%Z73&CCzLQ5)$rR97)`BPBVRg z+j<&fneX~wJPNq8vtFT>wa}vSMO!*s!MsB*?}gR+9(}w;A~X?09zW3YXTB{zhzw5w|KJ$cj0D8#e~`16Sq=ZK=$C-X z&91|@5cN7XJ!I?y^cjzzfvTC}$>}YMI-<}`heQXLkk0~IZ9BvmqGf~{&?(|X$&>xZ zIEplim1D91^?B0z{0>Ga2hk5FT4?S>$ozE1-4z4pw|gBprkDYkg0PpqNm?%ll-iD8 zvF-lj9)in90aQqufb?pv44={IQdts;?-UP}5rwF^pMq{f4lsfU1FNccxbp3j_4mAg zM;^_eI~ZAx&P}!I0yB?)yDbR8k^R%0Bhb0z%re&gVlMjubqbBL0P-lu4#x4eP}HNa{l|%yQVh!VSiv^ z80SNHo-Q!K=e@tQpuJozWVh#%)h-9Cg5aVvi`AQJ3AeR61>hb+YiDGr?7EF}cm*Gk zY~_SXpr8TMHEhAJM+NQK5Yu+b;-SAH0)3G)G9qk__9)IAty-!d{3H3}dW|0HDrc5S zJp6MRxXF$!8ni^Z{b0B#{uyuqkpo+35bNZK(OCjxDKw6}Bn}+QXXRM?kpgEV#bImZ z&2_pP7WCKCFN8i^0o4|AQb9zdCSRAX_(p-4Mcu-O!!>UbAZfeJ&CTu6uB*!KxI2B} zSx}(ICp<^n|3Grs5JGoaCO2OP7_F8vjd;iAldP0JNEYR53eG>9iwX`8-zlo^IXlw8 zby;-`?UX4)eva`Mq#GcaDn&sF_TZZA&qj3Z(qdSER1u~Y{v&WKpvbhzrNOT)!tC=y z!LF$cR^+V5WCE2OD$5@slgn=xXsH@3J7bB#C-n6D}7DCp<-aW{%wTRhMkS8 zn=BIJ)V_(fg^sOra{4&(^+{KoDNRuF!*i+yvdnE&cRkf+KZ%SO zr^XWtVdhA2(LyKxKrNv!#QH10(VNBVl~2VY)@QUqbT*JM>O3VR9xL2d{#Ax*`u-mO zAQ)b}Y0^~Eb0*^zB7guOw&cO7T|hGR@2MwUmE#nw_w=4skQazJj?8EYlr(a}COUH! zj=kkU6}orlF&0xpJDtm-7?24fU%u^s42Ep#yy5_@dL#jtF04i)V z9oSa(O~#Zm(76v&_4EW*4f3K)lfpq*TFs1IuS5G!`&yNB;1z%ZoAT*^WR=xSu$u$& zH3yD#GZb~@sL^9|B8*pATRGYhW{UTCXRdMZ+{T94k_Bkm#M5NVem=~)^f|x74_ z+VR3j2PjnR2^_-*=rX%`(BOgy4?rI}q_GBwqR>IXV z8F>UmX`aDSS-XGOL17Aw02|7Iu#)y@#LxxZzE<%~B+m*efHs7y3vPGG0%PCBc-B)6^k`pT1pHDSyKybV<1SW86z& zfelXjvxR>u{+~_ZFz~^75FKC=Y94s7mdP(zwKHY%Fph2!O12{F$qI#JC-V}u6aly@#*b1k36OYN`>xSx0mM{t^`>PoG$*#xj=P|Df3%`s4p{%NDsH+1P zzWwU8|V;deJhJp5Ym(rR}e-KQ+Cw>7@c zyNB$0n6kXFc7(0>uWw!cPIcu)0wq9rf_~IlDs=QTsBUg#j#7c14{1MJuk>I@OP!+n z4v2Bp&NST~F2W#k6jaCniGO#)aHPoI6%roa+TEhPEW+RHt1~6b2nR=m@5}&Ddu(|R zwSV;wauj=j;8xzfp8j!Rf8UqtDO+E07rLCwLw9`&nRVG~`H5PRj-M>JQI=y{ZYWUu z_pcKbLV^AbujX^=R`NW{i^CH3|VIA3sMRV>L03J+Xxq=aZa`+WVbNcPeIaO0%7G-IT`ZM?o&b3Zd{L4qWx_4~0hZAs_Ie&9;R~x^Q(lPbn3*gJF;&8N|jUB*= zpr6_DP0qG$P^|dYGF{#Y?}RqWU1Os`6%_pCTQB}WPP(sV(BS~p!Hf596*s(qhJ6!*z}y(>Z6O!W)KCh<{7ghDtw@AH@!S(v1l>*{0bR^M6a+`oOgbRi-^mmPj12dN;XMzP@olfAm+Znj?0u0|kb+awKMUFx<;8iu zw-n~PrQv zJJR-UPw8qfqcs&oRKq8eLBwB&9IcI;f6{~4!+oXT{QWylIPKdO`zf;hh+aDG=n`w| z^Liw>AePoitLdM#yH2gyjMi*FggJ}Cv9aA8LXCSuv>%kh_|fot!^(*tHmD6{mm*Ek z>W$`?K|pp6JbJ;1Taau$Y`(>}po}o^I;`^txeQ%=bgNJY6u}~d$nu*Pg#iWkRSW<2 zsoLA2EXGr_oMlw$yIU_~eEj*OFpj6^sO2yBQ$>TwPAXWhO93xGzSDRy6X5hlZ|lM| z1*sN2-q}MW1>Sv9U_Y(G_p=?W?@m)Ro)=|KJWYHZeia0G@CdQtZ?Mjb1^m%)O#$HL z5$MyEEoR&--a+^@3kj+M%3_5lFFr;b+#s~)Su>?Ym{j9|cj|-yKfR^*3%9u!J54Dm z(;VR?)>Juy8-%;p1%(6jblZ(o@X8iP+GJNp!%t@=%6GwVSX%gp6ga;4Eh5w?d7qHJS=pNP2 zryh}0hLaMrF;rh=Lno-3y;&Mn|4BBqOaGjKDdIABe9OJpLQ-{qOu#TuLBz@U7%KKG z)(ai#5&3fw%9cUymXq^X#a7lPUWVVv4uTU=rp5`hMQbxA@a<53Ibclc;AT*S&B@;z zxq0c4ERz8aD3yxAYUEU(JXig$+}~=+E1ZKONulSE-)QD5W5U@B2N z09lNfL@BEv#Bok(x1@n1yPti_TQwo`qg1sN5{14ntABDlNvPOh%Q!L+=;))Zxu5?H z@&~B12tRfM$+_S@GP?+osUM=RcB*zqShyWu@9X&qtJx}r!3=`PFW=U~sCFA;37n?GNFJIBxXpC1f8vjl$l7k-r1dYRSK#^;{9 zH{Trcg_3h9lEz2`<`xP3#6twITngic)JU9u`0XU1J_(~Y83ZSx3vN0NAzF#HwC`N^ zcHn3TnP*9=>ll}Jc3HZ9!toZXnU8!$+O+2IHXx$AyIFoA?P+k)u&cOvwJF!)_MiJ& z^l~XTE`TS{95=!S>taFab<$P#`9f>kn$ikX&4^}0TO>Nkg?@i))5M!)Hn?T1c69F* z3|_HNsC2;~_JE?IIXm?`Hi7sYyJ2X0D%>;afEI7~tN0ieg3sHXCS%u=btm%TXJ^H~ ztF@!h#FUwrT(P?ZImoZh>N2Yciv;UVxP=`Y86A0{zNmWI;1Khhg9v!CtZ&A=-Y%W5 z>)G#C;bg!FQK$XZ&n+`;HgS083u6A>VNvR|+J;E%r<%t-{&_-wG|toBd$kU8K)iVT z@WDiENhZt06`!i*uNvsL+iGjpTY2WcJ2ndwibO_gub#jTpQPD-`U__r8=9j zUh?G_?Vd~py#*$GU3Zpy(ACsmW!=&K&>>qDQl)A(G>N(Jcg#$+xkXvhoIg*U0LR{bF&zAGeIX7}PI zCX%9Orf*1|6Mo}$pkfj04V|CI?CU#AbqL>!cmhgMZ>Vm4PkAa(rngbeddUa@LAD;X zshX>M#>P`k-*ye{OVX<_iRS1gQH5}3^!nkPvz7an15OZ&Tk&77=dvt666v7WVpc!>B?MSK zuQC3;b4}ZoA|w8_&;3&^0OhX+znNs8n|Bbi*X`vZTonXi|r9BjEH?_@2^vX#*yDYDBz9HD|^ zOT6}m@Yb+&?kBp5MUX~seYL((IPl9{nJe4h~ZHn1nq zumRWoLjCVf(M*xs-CN*iVr^>SuobJrNMI|g+{~vWrjZet>lwxqd$vm%fWX%e) z6!=4RZQg(Zt!Xo!pH}^S_9H4c6>?1h_1j%dHg0*H%7zf4r>!c)-@R}8P2KhC-=A4C z8z*-V2S~HfwjB!4m#LRc821qvqUT`+OAmWr;&dD;n{%ztAvwoQTIEj8Kpq8#>S;B) zU<};&+3!HNUr|tgFs5VIh>yciEvh0-EuIE;(oGNsbj4W^(-mi{1vSs#d(D-FMRtFb z4U|IF8JI=>9$p37Mo>m=B@*rutqEHiuAkR{W#yyze~1il!5)AA!r+f;KVK1dl{ozE zI~5;}c%H8#Abd`(olB^iXJ=ff^_&C{T%#=4Ybp7`E!mn(FFA44G!9K+oUlf%Z+isZ zvKCGI&xMrq^0MWm&YK^VH9AtU4Qv(t#RERx_@+&CVCkuXL=uV|Xpx})Wpb7V_VKaXl1|NrCh&*)V&ON?VOQ4K zpD!^T)0wIQqZtK1J4fiYFI-fcRCu){NdaHdzddX?jhipIj5JRM?u6Kt!w&YbJ>sl=vc>l=67{WiBekwCa@=@t0fG_{1JxoMmT!&}%Djq}u<*oZ861@Z$#BhxaE~ z!O=K@!4Pzck`kDk+o4~Fww58BZ`qi|6vOTFbj@cpD9s(|gmFzn1n%XgrkV|1|1ys) zE^%(1S?m9N4F4haJwMoI`}K!py!0We2gk2ezFWwJe+u@iA6l!&vyH&DQPN1r)tYkB zJ+}Sw`@|VWkG%8?t531Y_c}dzY9lkJUi>@5KJF7NNK}ZRt`!gt*d=C#kVLe1Zqyeo zOMEpEzfVkH-WA_`ruXzJ3mZj6Qk>6m*yojRnGM5j{Cf5L<4`R?`5^B{Tn**bS*ceJ z$+Qj^Y1tP)|M4#<&LuJ95*IilmA_xkyZlysB*3FamjbhVd?b;quSw^Ao)*h7WA z!(e?WZKKLcXtT3a2Bu@STTo2zOyxz!n8s{08 z-&hU=%37_disu(<|INN{z8$Cp>mJZVU8Ye8Tx=YYj?NxzA@IeM*zJ)evrmmM?U^~V zMV%U5Doh;qEHEyRp1{vZiLZ?*XCb&_>sU#~SyLBNHBl~sXYoq1aij_<3@N|oUFB>Y zZPQbke=6TwfL+b(={1jdIvy2B)n_%$sDjC=521yXFY8Dz>7PxtNbsuaTTuJpdZ@;G z2j-qo-)do34TTTQb9;T?I$ZjztStC!iVCzO8TR|rp={eB`>P)h`Fy?sxQ$9NB*PBJ z-X#sFwy1>C%3kQ@+x=N0^3XC?f3LkfVf)!pj~-Jn*m3FWj!*85>M{cA?E{+Bl4B$E zHS%7MRc6Mg(rxg-R+VnUI%_I^79Vq#YSLip2XNwpa>%&$K1-Vf}2W2F6`kb#~(e+L?9Ll-5Fn zB8*&>RGdLjH_~eq_oB*z*7vuY4j=QXr1eBT@5_Hb3fOr(RlhdBKGo(Q6KoLT9KsZH z$)vq4h1+cwN9YZpa1u+CWBl%fMt`Q8sMYSq$C!FQon<&OexN{Zu)~CW!j#K*i#E4e zq8nP^*C3CI)wJqdFxs}7N4v3Nf`vajb0IUdMWTIyUa?YHTP=fNBYD(lrf z49dwUNp^qF#`8|b+lSsBJ zq!OR8=~3u*=Z<&*0O!QAHH=(6<;iW6Fszw%jz!mqSP#Cn=KjsL085ksiIjP<^<||~tTN)>;XHcBRmO9z00 zBjyt&SwnVuWf3vTDH6=)tnQ5H+(2qTCW=X7w>U;G7qcgGTcFv)Xz~fz_ydp%g zji(M7KSuE4n|!cB2h=>#)|x7qw0AB0DNY($8!I<|N?oXy8hW@7IviPgpc`X9`FFhI zAK_>Vu*mJL0~)6^^m)ABCe+DO3p-g+UOA7KP@%|+Pu5P&(ApRh-Xz}>jP4?aP60pt z7aJYA$Qj`we?8j{w}wKBT+1e(-R>}ChN#Ex3uNdePvv;mRy)!^5kD7E7A{IQNqegj z-(yPsYIZQ?E@>f$Fi=AQ87gtXxnXj^ubi+w-4}jaDwq0WBu?az9mh|Io~UTE#!HE_ z&t2jXmLO}#b%^MNDw|6f*XGHiMBa`Kte{FJ#4!*(9E0{VnSbi_dV#QlpDUHDN*&ZS zaWgT=11=~^n0nyfYs5VA@d<(5zYGe+Dmex#eRW+&b+Z&vPSFieCbNp=)XU!(hClx! zDI^s_=X!U!HmW6UzdcaV;Uv@<*rZSW;=Rq!sF<4k-pR9tJmt0k#|8-3({wa@g@g*) zB{<`WCT%Hk_Iw!3^&+b6QzcybD`mpWokz1#`>hy!laenN~ z0u*ZZ|6%GYpsMPkZV3qi>68>{kP_*Z?(UH8?vM}=rMtVkyS)fVH&>bqTpH;P-?@JO z|K1xz2ZJ%V_nfo$UTe)Y=iK`=IaeU=GG)OXQLQF)6bb(d=_VMqe z6PTcA8=N@L+sLS1{(^#$oksGB`t8OWk!=bQiplg{F*XV zUH2RI(wv3n=j5y&0T)iE5i?W*hGMh>)b|HpT%C58J%MU~|A~dXMUs91vEJtV{Lglx z{A}tzMRIai6-YQ6jq8NI={q&kPbs0Xu8G`7DLmhNbo35EsSXBk31(|MtH_P*@~uCf z!<;3-;KdITnd2pVH3Xg%+V&QBs;_1IX7H#7$w*LtHd5^B%;N1xObJ zMgIp&S|Pqwp^(yvIi(s=cjvu9%kVL6cbt1`VB+TA#o^Z+z=^$)+DE(*UPuA)t)09& zqN_%2nu3e+Q1iEeaQRG(dJmdM{#O9u(Q2m=2P}l@*xc(YN)i8c5YWH}(zoxmH$7D? z%ks$e9F{b6)r@IXy`8*r)L$qqTs~qNw@BWI)6}HGYtKrGiHk`(2WK<1Mvjgf9>*l} z4K}YL4<++Iz-vbpD7C0-E44xKQmq6~--- z(Ehw39=*Jxpx!9oq_+Fn{QEB`x<`-c(I`na)kfmDOcPCYF3@Y)J&cqs%2_b31D3f%JAgaJOq zI@EFdsS&jBSAEiZJKae|+U|~+yxc=W^3%xKWtcZ`j6)FjTJ73#z0$XGiH|tmm0ej| z7uCh{X%qj!wo7%z#1wnSVtA;xFWY5M;`6p4l>t$LWH))>J?E;~9(&F3Sgb5%z5vMA z;Ez|>&jKoC{AKzZNZa#N@JSOAX&g^rt|ImrSqZ-h@luVxTh3Ycwep4w4 zYN{2KZDn+1mOq>Jw;y1pnSUuHSp3+I#p95><>m>*>fm7)a;5H}yM%5+CqYl%NSF~3 z*ZWHAzoAot6;W(pg@mHiv#3S#?yK9^K-*T5IR0)WV)SJbkuPU4GQ9Q-+v##|*DFXX zLN7LSrRZa=fX|r2oU$e+R9AJU7;AB>ci!Q^Rl7#rPQru$y6eO z=bJe`M$Fi-?NA*REzgJdm2$lK=qfdNCzOsaM^xiO0~qB+#Mf}4`a$M3V8SF)!&KEP zvG$@kG$E3=lHT(tG>;nUZykYW$QP!WZ)%_v|8UB%Z&j*=|HH&vo>AnSZ~jZ_m-M2@ z!fr;KGUrg^Qf;D&&%gcz(sC|lL67gcz`JMW%sFZECZ%U33Z7kRwhxNU=4u5O^%dRbu2#yg} zUkScF{N|OI&E-z%`Fd6Ief$ikk%VdzlG;df*i_AY@))L&)5|O^q6C6~-9#r?XHpui zOTN@)U=Y(x9)>KVNp0u-5}NnCo(c`7Y3#J)`OwLR3ubW6L=~w-AF-eq%0L#(JAJy3 zGdQ+jF+(2t7mx~+lB8Gm1da)p8(Wqe`}l&*rK4XnOXNmHV@bas4r#Q>Cz+u*-?WI5 z_D3GSlDN_nVn{Zv2RWc5y9FAjj)1vrhMB8ZN>~#Ko@r09$c$8P=|>JR?Ol=sJL;gv z*HQQ7H~DyuZ9VGFBZwukB4}^arV^6+Zy}nD>Vkd?6 z>3mbEuYNHW#^)k5D2w&MiE_+9$*H>Qo&|g~^U(eI>CXJS$t#suUkxZ(iu9e{d z^(dOtAk3sM$8c3KIf=K8p_obG*pXJw!Qt3d^IhA}L^52ArIUKq#iYo3B3Q7wxp_I5|mOs&D*Y&|ZZ1@8gACgHK=2h<`_qZR%*9KxEB`+Gr(m_rhTUNuO|eV)Olg%Xgn5dFy^MKE>cMJ1)nx5`%mkaHLW%@4`I_i@|xcb!QT zg%E#cIZ>3ua?9EID4QRJ)mR#bhK7bW1^xOXlr2!Ur3u4ZRiB#-p(}neEGGu}&?CXg z)nyfPXLr^9@Z`e#v&^4Jt^+;@2Wm4n!heNQ0e;+zYtCj1UH=Ywx>*m*^J4REXSfEoI|v`O zTct+UMJ%~Z3hmyU$9)7CV7_o+(kifQ&+veU!0%kI#_Hb5Edcma$nMD`#Q78tK#&n-@1yZ}N{HuR%2S}DNj4QB&`$?9B) z<}uwCFkQ(zYW1tLh!>H!PC?gHpf=s#o_Z@G|^geFh#j|8+GCqs%sEymlEKNuxbwlh)<xNGZqB!o@2$PcguBcat0SIn1pey`Q&k(}g_gt>#2#b&Zxsvj? z%Pta0r}dMA>*K%%8?V^RV}G>Oz3IZv$G`UEZgq!$9x*Swh|b#yAlNw1_1+0bK+W`D zcqS$~H(S-^cw#}EUOw^j+AXc!9gn=oWQ$!abFF!i;}L4CXk20eToylRJcgb0n*`|< zS?wnA|IlY=3SMDx!T7!!SKT6uOm*(UHT#BvMs>ZHGxEA3mi452?R$sqtaKGoTAAQk ztFX(5G%UXD#ED%q_U9fe`EeRqWCKek|E`9F%C4wpc7{rgHrX)!N<81T)cUCXh<^jW z-F*E;L3)wp7NFb{QNuq8xLjFZ?oDeE6Pq7#oERQ!+zEh+`*`}J?~&NdlA|^<`;duJ zeA@BSI1K+A&q;U9r2Pu-+2^b0CUp;CDX$x+zka(X9*@35e?5hbwAT+Kh~8NSycY7k z^b6z~8PPb!U@6Z>%A7 zTKy;|=KT~|hguxif#?3B?RwYh&pw&QP22UAXZKTg@7=Z<3&T|(6V8Dpk4>1ii*0Oj zOVFr-CMJd6@RiX3M+x)4{%Nao)nWGF_?f(S{ki+vRMji2^m%(`eR;QYI$ine^53Rj zcBj8hZCj;-K# zri}(8G>2DFZ}{b&VC^W7HJ6favx9&ljo4DDDZKw!Zr9T-%I5AF;FY`Oj4Enlb4KV# z6^Kl*D^Ee!d4JzVc(EmNfaAEx72hb?_Hv$$dULUqCs=ETR(=uN8v1$z0k&8t{?*2F z@j&gN+h#fII$~@6ulu9|y`9oC{prhV{)yU869deK&C+)RHItijsY4%fYd*5g&3zN_ ziZ1}G+Xg6uAz?-?5gD|H5gnq5eMOci{sRntRg#b0y2 zKN)AmhA~JWJ#cL*y#D)c^>e!EWC`>=4b+RZed;d5#+ZCzHPeF){o7(!z_HgGKhGPE zlS75F3Exga^dBI`^CBh=l$vaSy6`2bWM#O4yNQ%{@D9U-C6<;3SYLI*Pvq{qY}?(t zzMk#RPwB^A#c)tPUbcn)VE=0A$a_pYaBC{lAZz_kj4{iumZ5OWDNpaksoKzxFc{In zuLJo(AhEQxOW<$RDpZ99?4ax`ppD3fB1GO;8+#~P+b`}nmQZYv<+Jb@kTtAyz z;cI~q!1nP8@Z%SebaM>r*YF-Y;p*a^T2EZ7DO_!LGIrZL?s;lgo;GOhCjRB~MoPkOmk3{H|j6pAJowt&~AyL@2ORZ`8kMX58 z80)BnY<8H!fwaRuy=k-v%t$r)vTojp-RljxTC;&KEAWr18+01SlHq5e|L#9cX-U6z z=`a4MExB2Q7)^~I;@de0U#}a7B|E8*ultW?yDRfM3>(Q?966emGBd$fbOo#iOza$4 zpE^qG$MXKeC59P23ZvAoeBF6#8ZW=u6h2MRgJIclFzqpagcy#;VjxFciv{V+k0apN zS*DI5mm$x9myfR?4@N_J_z6R*DQGJy01@m>K8YdB-3ZJr#xyedKJsl5gEUhV(JhTL zuL|`P=sDLrguM1HyM$wq3Nt*vsjEA2JYd%}ijj5HN`@(8>Lh>VeW_SrlXZptC1*~O zYdf9K#5*WypC)X!Vqs5fiJcDI=vVFYGkgVX;!1X<4Ry2!Szq{3LKN;c&_@Qa0O+fb znqX(;{*pi%J47LOmS>PyMHutZq0YY35g5x3#uXyj)7_wcXrE8cUTjDCn!N^1L`-zcZ1Y z**_M|QGx<8DQk8nF%zUNpt)dn=I>j*tSUU=X3k5ND~ z0OG)diFZtM@Qs3VQaze9q(OOyP9Hx5NsGyVG-$^`;8s3RgkZhJf%Fhud$U1L+yy|c zu&kdxH>+Mg$IU+$zqSH!D(mNBhX=D$_m!5CDHIRvfyjqdK~^GXHnC;-<5RcNxgu-L z@{h-^Oow(~iW3I*FUG|!YIxW^@MAZe3!AbH%w%BF7Xkia;(;@(C{BZysjwj~2?_=8 z1s5oYl8gpw9g)>Uysg87@`XkBF@?Pv#?8?IR`c)dwE4s4IYYx6NbiXcYGAL|yYn4+ z-CNm?(udCoJ`cI4Dblqb5>q&o(k;Gq?0NR6zPH1_4g9wF5xoYYD{^$yP_@jg)o;*PIwc+I;(%9N?xpM z67tsm@z>kO_7bTT`=7bZO43Qqs$tF%;@HHW$I9tY!B z(!o>?fIAYhe_R5eD}-salD3Z*hpx;LnI2sl@naCp2ps`8zg#0fmtD}SEBbTlghhJh zQ9$bHo67gs3QY`FmnBMD6ZMu!)})2kngjUQ?r*EpEAzf-q#NMA9yH@}EZIabMbA}=hZ-V4Kk3MamlbqLp&lFr5VakTNE$}J(BDUQVWR`lcS9WfgFnXkvaW^0X6%p-v}%oVMvi*8Wu-?58@|U ziys=Kemtn$mH-m-AO>doJZ!2I&iSozkP)sHp zafTT+1d-9iM3Iwqa_SM=Ala}9Eq!_FzH06xl*)I%m^1%Q^E*u&Mw?!8N47wE?qNGO zAeZMgBuEE)nTo|+*dl3K0m2o=Hw2tKT$3=S<|{FZF-^=t{0e7-zYM3|EHpWPVt{7l znDe->GPvLLjnCSlcYNC#Gf3D&jBo8wr=;y)TXmlYsO5C6oLU<)NpEomnSreCyhHaF zE(bXW7s}}2ZK**Lcvh%MZ@kpl@xD=vnVBpF?oHU;)f?SCZB|HI43SRl2-1}%?x@8P zObm>1u0WkfOAOu(x^KZf@bp6YU>2cCQ}b70C${A*B2icP$13 zg32rSXxvZstFq@-wOi?%|0>shQRX5)UJzQ|t6NeKvde6>PB~5NyBxaOyL7jnW-AZ+ zr84OX=U!BTBHl*F3c*b;puK&@PkTojHGWl5={eo(8+zy(%wUp7(|AzPB207m_-iQ5 zKPf%<3M&lHm1B7nIG#pw>)tH%qQz-<0|tI9suW!Ik#JJxk)WJxX6c)jK<_q|H=n!6 z&oCZS_eOW{tNqCumx>QCGa=UEy#;a@-qgva9qUL9p6S(^xkwZ-Vdf>d?J&l%^h={= zI!Y8uhGdyTut4|k;PEtZT$?#OoCVpJ4-cAY9|kd$(g}}tHPW;wlcZ|5!tm}ttFlsT za-Nrz&un@Ks{gZ#kl^oZ#T3}JV6a>38D~akFlP0_i*j-iaX$3~& zJ?ZXHpG5@=%VKI|_gYU=FTee+zbgw(<VhSUK)k>GIAH-12f9 zynTZUjttJwk-0tt;%saK@B86Nuwwh|Cx%A5J^8*l9hps|q4xvBu*R@JZMKLuQ;m#< zaq#rqZ$;@?wyVO{csBv zYv_w>Jh)!Lh3QNH-YklwtVRovU`IF-bgK(NZq)YJ7Uj8c%2@yF1&|Axis30=b@%^uyd6gBh>8 zZDu8uu=Dkjk&=@i*>S-G)GJ0rNx-em5>GOkX)f-0y&g>aF|3&)0E&h>b2`U@&m``m z#fj%59a@#%W5ZBy;*GCPwHxaGZar4j!eV>kj=1iXO4+fl&`Wyv5{71KK`n&$j)2(o zG*Qk5a_JV`pfeCA&ty`*%~tl}46(I>zX*y)z$#Z0sQ6;Mdm+bW<|$26qc7X)vU=pj z3S69VrtGDQcPA@DsUJBrFsl_+USu)ou4Utu-mN@#J0N z_B-Vez+dx&E_kUU&H!q|qMigRD`x|j7O#mrcu;QY^sGonzKR=G&nAm63sv^Qj5aa- zLVcwwAeaE_rGyC6@u&rn{2Sx6u+2TuzW;y8tqHnbG9^jsQGr$&j8h-?xP0Ot#Sx;u z(>!5^Pznw+4+Eb8(n2SyG+^T)sRaVq3`V}}`WjXj+N+rq7IG1t+h$Khz*a_j@!$<2 za57OT(S3|6kT+0oGuoo6Gns0E$p{>CnmYFiRhKN&O2ZIDnQKi}X*F-?f_McCVn}f1 zuWMNtvCyCZay^j90NF-WGpDLH;i5Z+Kygo7qrFg*I7c~CIt}y*F(aBom%ykHC4y7T zfbJgvD94xnMpa>tXAuHI4u)26rPBCxUE})yc$_78ZCs+FPei|Z(sqSdtgWlu+||L!EjZ3lr}Nj zNIZk|_kP~-qfjKl@be~KK`2OlSS!cKHKOalYt4w^`nu}Rzkwlhq+aEBUxhhON~8>W zFGf=MUioHiO@%u9vM^xXW>5Y>1we}ul2s)q7O}GB!!=>stS}>27!@wq3R`RNi)+|= zJ8BeL%mU`i^7MLdicDY2@+4T$?_ZPtajrAe%OKfd`U zUH_5P8_oMQ#3r~j!NOigP}cJ?yEgwRzqvKw*sk$#KZZi}~n2nBGe% znS46*S@sR8x84!S6>%nyauHJaM|kGzG~vc%p+Wqz>vt2Xg9uwPwF`V-E>EsJldR_R z7lU8bj1FcC*tGDG*$6dTA%zkE@_ytx-%cbf+;~~=yx(oO`U31?=Q`gVAflcitOGKy zD|>c0;DVC!9co5Z`CccUymU{6h56OTa4-;N*}YX|q2alQ4OkP<5QHOG0jzKuxSrbO zv(hIULz$X${uD+Epq8Zx^1$TR+U>0q(hLmgElz5;#OwUwQIzGW?Vfv4KP}GHoZ|iK zs=ZH+lLxYv!jlL|e){AE@}-!6-gQW)xE${gme7+E!oBIe7*5ua$wBE6>J{t#3qV8B z4|UuL8+@C3>ssR3;0v^|4FcV26vT(J8Ca1co{jIz4f^}NX7;Jeh_Uwc%d-`|f!X~} z0E2ADvwo#hh8t|d#-zdyFY;^kJyc;CGI?MH=;G5dhsxhP3pvS# zkWj7smGTjJM(FPW&GUqHK4_trA?y0vKE`sj0EDqC0ZNhiKwVFSW>E*Od_03xTbuyZ z5(7%dIUrT4Xw!1*fRAF#UQpZ!yfg!dZ>B(8h+EE(iw~X&8!Qc(0%>Tt09YZLoMPmI z1yNff9}`>i?e}=O7OOu!0er;hZWFp3+p#WlwU8a025kahNVZk|rWhPlGCwS)l` z$UW3gBF%s(Dg1GQK6eZdo`95y2-rwy8<(seJX4n9yl0K$+Z=J)@>yv_t^mv$wa=0; zb)n)&xyi{g`{zh8OG*eG5~CBRW>?Mg8P-D}=PlG|AJnf7jcP48Mwy>0YqX)J|E3b{`uY^PPA7Ev@XL9@`d#`X zk6m#k$$@%^L1H+ z;foOj3`78j{fi@Wjau-`wib|YXoalZ1)Vj*-%S`J=cu(|c~|^|4lgko)y?xSnsi!0 z7gj=Zj+ngQCQ%T`^!*a-&jm`w)q$T8G?#t_26%>*qX$X}B3_RHT=`ZDiV$JHn4qON zd-$5{9t9_2yZHZyq$cyR^-l<1W}wRp3cz~9=2g!GI}ZjD%JiGD!8PME83 zHNAQrQ-;(T^FC!V4nKWfIKB8pm1>j0IF`o!zZSX)AsrqYY7J~Z7r+9R*nm2N@fl|j zqEl%QF65)pAjiOf<#k#?>i(UGTxcP{5J>R8=1sc1`dh-J{Oy$H)SPJ`u`vA9N?&X< z8mq~wI9$6|tV75yx!LMCC*!q;(K8F>zGK+We_l}?gi!n)aJacij5>?lf1NbD@+Y>9 z@E}B9)cN|nxrZ!MBbaUe1hq6mrJ9|@8?(%bIp1;E+^7HKF)9$q+nUM7bK1jK|5C;3 zu>F!VIEEbK%J%ISm@ANJV6=waMOB63iux;~Fpw_rqX82;ySo!+iiWSBn|2zNGfSOF z5R*Q3Mz9|NH*%hjNnG^x%ZAn}A!aXb#iAvbc6ZB=fR2mP9_vDia?lgCM%?Bt;M4zE zD;TNxStcif>tGdu=k1Fi(H(u+q)9}rqkS>Un*?azIpEg^d9;frG0P{;N#J&<0fh)= z5LZsrhp}nSdAz?fUz;fyq4NqRsv-DkxxP4UBjQl2-q$9M0p56|kP9#q_(c<)Cf`S2 zgci!2zo9DsuUIbwrBU(hS3&tXTki!03vi=1oFPA*L~m8X>hS0P+OnBTy}n{0I0&Lo zkS$?@u?1O<)4V+SluYW+D7O_sm46v8;gYDxPSkCY7~kLQC7hyl&y;W2Ywos?>pMB_I`w}&t6|9Pt2B)bdEwie&T(SqU_f^Q6UZl6 zh2Na7De2$^aTKj<9Mg1f2fm%ElDnA5=JIO}opB#uYJ4P8+ zJV%&UwTNqAHz=7;zUJ2)QZWf{pl6~Hg*8MFXNOs%wf1_kC%agP;1)(((yTPMC-+X+ z&Af+6)ll}&?^Qq&1A2f`g0w{fNNe*yx`q^rLVk`1L=v~$QYE*TQiEOoJ zyd6zH$TGN?iK{e0(6X9-k%PWw=*Sl8xciC~j^beQbF~ojU%)Dh1>Y=+_N0s+&%i)d zK4MePbQc{+LRbn2_e73!Tfr#UOsaC7UHMZLH3WVQFqb*xZOB{fHGLUL%Ivv{M&sKvWM~F20XANL4!YU819K`bIXllB^aQ4J>BWuB@Xx$t6IfDk#Es1lp~Vd$v&} zk#lCtE6ww8U1kq|8xkxy>5Csja7mml_KwQj7FupKhzpvq?LlJ*JLTuq)&`Vn#hw~S zy^hAZ42-N&GSo?M(s2dt{P~G?AzE1z+U3<`ua5E~UM27h;=drs5xbKC1gIhL^OGtR zXOalSgHN@)3b~786p5P04mu2G!7fF+hrkK>ddpuM#K<#LGssQ)ua5;A{l7NdXIxUT zmx|qZ%;-BRzv-ssVyOLDVXm>ed_9xXJhRkzE)Cle#u_{GoaQNMji@zL;@oj8xEl>4 z6Fq~FHgWfNjOQ1|Jgcq^cH?3Bt0_UYj}~Dz=v|+hN1L{qAi|3!O48sWkN^TbIBfgo z*}|a%PifCzHGmksp;gF<#0>36R%ncCk|Kif`R4k6?ds{Wnn~~Sm-9(`%5{8t0E@$y z!*-(R6K`2+9klI3hI0vFEGVq8`%htLa+r9+QQUjU;Kg`^bmH_O9?t9#D1U)@LXkiv z(n1a;xPIyV4EvJtPH(kPj-^!13{b17So<54@>hD(p<0OO8aVvb=PqI2BfpqlNV|Ue zV=FZF%2}A5lsM(ibyriHRa`FF?cierOX>GoZXAM1J1ASWU(WV?x4}AnRrOwl|RK)UI7oi{; zO2lU*u87llFZHT+w~C|FHx9GXnVx4JIGErXz3`=%4sA)Bb&3X<6*e=t`pMAjj=Z@E z#l6OgDpBIWz=%qR&2u07-}Xu@S#*=|>uKPkbtfB$W?n;NCSMTh3PJQ?kH;I`xMdba zWsNk35%PdtlPHeQbOk@JEW)OZ$ku}8!nBw#)1K>0mEkMPRdP2^qjt0R>*T~n$Ao1HiF8q zW|P?kLY$OI(^o;h>s;@V@tgR6);+Lz4WfXJ-yqH-fwYq{O)}hHp=mwRx5Ni3eEf zNSGev%rURc&>}(d3@CoCr!hiMmF+6+X|>)=!?lh)h@=%z3{kimKzxsJT+1HKjH1s?}DK z(}YnkS^%H(4eLA4vxSAVWn(u#JN@d`?gNhy1<`VOJO@dtba@EUZ`Wt{yPuiL7HY-5VHA)yE~X>IdOC_>>>rZp!L)v^ z;#5V(Ds5Uw9viBmBD~Ai4IB*(+EZ*-ZlHTF>DxpJUd%dkW#lpy;QTJ?C=Ft2p=gKV zppW4lWuoyQa3L$!q+SIc&qyw z>$LSl>I{Cz*|*LU*@s`j&u&d^_EtZ&={A$vV%|&q1gyfC+>UyB1P`I6$GcvJG2iACNa6iqCmI~+-vglwd4Sl`1A}cDqrX21W zB4<%%c|F%=d&e~0&Zf!Qbqf0KI9&I++1)%{z=Z#PU_7X||_i-;kJ7xBf3g5R*u!^!KA#KLdG zwBXzT?OLiID3L(~$Z?(lZ$sDY(>U;oTq8zms}f=JE!y?3C?@?O0$nZLdEXEvEv!`; zH<^PsIp?&|BxyI8B_l^9BIHJXYP+JuU;p@;&|OB9EuX4;(x1cQL%jo9)02 zz`>gMgXcamTenQi%<00Pef4h4?pxgV)qvML8NVAu9-j~kdyBVABXCo!%rps)K+hm3 zvd-pIY92C3oG2Dqa_Tsa*3yxYvJdY4cCPih#qL~Z{pE{9-G?k*txv^h>q!2uGh4he zMc1E%lNmC+<17I|b1==m1c*uP+Aa3MGxp8Bbt;Wjwkcs9Q#H{ zZ7ul0Lfnp7;QRRp&59s?B0|L2xBlD$VVelKplcEzxj9JL7>Wb%g~acjFEX0(d2#KX zEzJ}#-Mq1W(-tqgn++FYf)j*F0`0kLSmxbR?2&T5|2^8+wCK1f9U$BIIXK3P4S`EK z170I}+rjT~aPV{7`PV;#DB}6|*h1Bj0^4E0iV5uarlfBk&OtqT3-@vHH@IQY-C{V0 z3^>{14%?gMxiKWeay6uO3!8Lm5oRu>duY%4b}Ch2RR=t&0&e)toW-Pu@n8Y|ROTe{fWz;T$QroGaN>pk3QZkfH%0dtQ6BX? zEGg&9?A9OOpZpPdTGiqvEBz4=^Jn?>k?Z0q&zTx)(y9j2_Ez>Ev+O-yFOjtn-I534 z#CO`C-_3$|Tki|47F7ai^osA5xX zPKGjlXSaX*w}~*b<)<%grK~uH>xYavJpm_`K98S96ghL>PWSlQO{^PhdEzR(Cm5n~cPjtD!#6WVVmP5reqQRdaW<=JnTj`zz%4Y=@_~5oMqv`t~)VFH& zLdG~KaJ;N+C8mBQbwwWBH52GV&jxWA=GhvD9e@ASUlQm$9q!<<#W>uM#!D>k?|XZ! z--vGRRkG0NJ0f53`QCT;j$U2eRUKglWJ?@+J#}}Q$ND(&q-bd$|EhFTQ66GQcNA*( zB}2;>6uVxaEZ>;tV2N->+aM%3`y}OQ9mQdzfeS6f6g4T;uvh-n1xmS>TT>XgRxla< zUJmXwVz~17I6K?W?eKQ`85yrq)+jK>VfWl{{p4A%!gQ}3+ef@N_#}=b?C#&O4Iat1K6^&9r%yKzD3x56ve0ze zE9aW!K_^D+uH~;dc<#y@v)rHd9nvS(6$1{-pJhtA%*$nC8fFfufNv!rRNles^Pv4O zOc8vBFj;J>UvjF`K>w1@_bkb)s|Wti5-rOj{mu6jNr!`Jf;e`;7vGB*77@=ypUWW&R-kb+4s0%a(1?+Pak*(J^+Z%sr=$IIWIQ*802J-$JS;rCdWT?S=n# zlw~v+c;k)&+UKMQM}ua053agMy@nwS6}iEq{X-j5CglDrxtmEXYa)w9cYD8x;=>kS z0i%%U!o!w_`_4;3=?ak{QPZY|%w-Fn^w0QehRKRU9d4@<2{sU(-&;ux!Bgs~xxphh z=PwpDOA^XO?wKQFAR0JY6C&dLU6?FG<1lz|iF=^lR9e`p^WafH;FIjD_~;KQjCEO0BNwEp+3a(mdtyh!@5 zV|9QbHc)ChQf*GRIZr0nPpqsuBE%F}pqoeQQ7A_n(Flbag#$ExIUTm@Kz7DmEmEm!h^_aF7Sa8uLv68MNKl8-|zPCeVu{7Y6zWfX|{0 zj%z{qs{xVOh;M&G{Q$=R^}py3)NfIt@bm7fJOIunPgG9`fhC3tLYhy zy!Yx&n>qgDJ2i3SbuN6qr>HFUMj1F9jhviZe$Dr=T1ZIo8e_Hnr_cfDt;JKq)%lu; z@Fgqu$#)t4!}6ru5cA7tDF1bu(8}u2$r~r(s|>-Xp57Z&h=+?8=`+Jj=BW{FPvhziQd6j z{Ryv{7S#X3B|S*xP+Yg*#ng`0^P+o-gwQhsjAsZ&l^YfX*H)@qz4d&q`Wi#jA@iA<7F z!SmX`pzRF~iR89=mz7K_=rUX*Jb<09*N;4LU)M03zm{^mo;nNDAN@C}Hvx2#Au>dL zo6+g*V;8V;PC$*AWL55Rq3F=3$JL!02M zd)2UJ7!KzlzrGGPaL=EmgG`2V91-66VuHl;7QsKp?q;Eh8V-JrGDDSW#q4+{#-F+w z6mck9*)mud9UM%B)$tZS8(2j5;Z;|U$qXg_$f(Py9?7QmFYOU`l)Ji)_Ck1*jkW?W z_*ODYS44L0il6SnM>G0>R5-#!{I*$V{S-(B0qaE zr8I&EoXvCD8uNZIjbbkJG8U~T&v=6D*L`r@#EXOQjwJohmdO1HLNCW&9oDNtClQ=F zL6>0!<;M+EcXNCJ>aN^%r1kWgt>yijUx!T*6N`S`jq4fhoPHDa>vT44AWB8VLER5T z(Ei5W+#{}4VkbiPQG*tH$8|%yVy?BBV={-zDs{24dCX?lJ9M967xhR^@Ow=E%stw0 z`tvU%THx6}*bbk%PT<_)IJ1xR^BNFjjWyUSC8V$5T2F^N|HiJ0OAlF8!g`taF*sW$ z4$gH{r*qHzjthzM2eH|`2Ht{5xx8PU+64Kp`+1XYLJQLn;}|&)`;t1HhEkOIN_XS$ zb@;^PnD1wX(l{9rVFFGyaW^yd>*6Y%T9JjB*6^6PsfDv^LSmW- z%x$lrnW#fZ%s-{3CRN|}cc_1NWoG}FGCN;F0HqTj792!lL#W(OMtVrGcyE&^uxRhP?z!~Px?(pMe&w{<7(h@ zFz%rV_~DjlQM7)(I8JK;^v<{-q#tPQJlPMK;Hu)>+cdJ??|kIM)OAZ?1IMg4Yr>Lx zv+aNV@lX%P8FmFQ=~>cP0!M!eZ@qirRbti$dmDe2OGYz|hIn-rlaBWBtrz;8Z{eL;PmxbWmP7B| zTjIFxD(R|3RH4$<)&3lb)ijmbd&JW^hm?S(#EwHO`Q?R*YAC(>;^%c@^)!Sx4yxXr zKiKA<3|l?RF{24D@);TrnFo-qxkF5cbA&ZMR5<-~4yXlrN#03*E}pZn?)^9-&Hgg& zJ13$uffl?XIY`K}ezo&f5}FJgZ*()7pzz0Ufr(s`%p@8VE=itcP88GrwoW{@A4;)d zh@(_l8~4g+NTbX)^WD>OC!&Ru&}buo zFde$u-@nD4DGd&9gvfe)c`?P&XH6w%kG*&NG7mGn^eAJLc$N~F6*VaIt6Y2C`eDl+ zBWk6AiG4*lE=Slj-rpaFS|>-s#FZVjdCK&y)r%}Lspr8D|X>g??BUL8ugCS}=RxI4y)K)>(+ z{o55oAOGhi)kfJZ?0{1;5gy3(;MVo|JL5ag(mB4 zw8k$1i#+7@=^$WI0@9WX2x?BHldKG(mtpGLPYOfqcF8eJ-(A0UjEVCS-eT*-OwDzK z?YNI|CCl4__{EY@f(1eX(hn_I+%m2XWBSol1G38rO-lYAXxU8TrYixY4u+>)(^QaIm{BICUZZGK%$aqBt77TFy$bYu-%d~;%jsM5^-z`DNi zCRcxxMmlp=p;4}a6otqQ|L&~FqYc|iXtdZ|x%B_E_0>^PZ|mQ5N|y>lDUBc?os!bs zB~nV)&?z7#AvHA83@sqt64EFwT}pSC@5Xb_eb4XSJAcetEC%LVdq1Cg_6EuTkCIst zvnbg5qfu$8p+?J&{TLnZC)YtQp^*dz8q2CB2-@mk5{eP|vv)7d(;%)&>#lSKJ~w?| zTO@H=$B2i?@MrL8xhGxDI1zj$)r%PFRr;Q>~6)Ax&pZZH|Jgf0P1C+Q8qowzC(5 zljxl@= z?|N(w(M%8ZsdN3b&z%E}Z;kyXwkX20bIsGukXp4&GLW4O z^9EJz)RqLu7jhj?#Ty<@5gzxyG3tqxC1W2=pYeGQn>rUw7eyy%JOy`&IC8%e_|Q=W zh~%bf^!VR#+6KX(9v?m-rKX@Li3xjyHAsA4{`B6vB9smT+-tdn%TMOs45=APljHEC z%Wo9qtZMK^ge8v`Pm_f&$1W1w>(l^AqD^Q^@4ergDLnlfE>3GQ`cOVvx zY$ai-)$ZBolOJJy>Q`w1odo7ef<2EEWcV3G>NY%8Qyg@xN((#_*?TjT$bzAhq5X8s z1ITh3^RI^=R$RvSAa0BI>Oi-JDVa??$_D|Oeu z3vL)UNfVcLDi)gfrSRfecABvJSB^w;qm!`rOrtN`Y!Z&UF^O`Uk1GSX-RC#=hKcdzPjkPfRZ#9Qo`vtX zNGE038iqBb{9SMP1^-oV>z_3{LUmZA>Xm~s0noJvkNSfH@`jKAQS=+mo-KDQDaESY zEZj3BuLuV%pWy4Rtt6-Eu6~zar?mMIPjSq#RNhshWx;a-8|_os>^&i-WxbPNu3!t~ z|E&P}FhU&bnE8^;C(_wPyY#DD;Cc5)q1C zHv2@s@5O~eH*JL8y}0%~+BKU5#D@e!bjlg0QQv7cH=NE(?e&D(jhZaS8Pj{swc~ek z9$&YTF4e{h|Etta3+y>|!b;&nE)gHur5QG-C3EU;AQo<49u zrBu_Qmzp(Sp~O*Y`3D*zIdAOnBa8ewbRqL1Wb#w;7~JlgKL#%`wyE>y69*o+QT7+6 zCF?mtF?1x6m)Lz(i3ptCUI(P5w#*7|3S$z%u?HQOGnS*Un7cmw!i5U7PA1adZx?Vi zLe&qX5E>Bx`#Bha2mC5iRNR z=h)B$lzkLq4UUGf|BDehoHs(T>pLU<_lJwp0iyPA%v}MN z9p6eq%LXGbQkq}b_sA^`!@j{mIln-8sFrD<%BSz#fcp+eY<^S?${}f)TZDNvMKR3` z;%vBU7HJeBbt9(wC%QZF+HfW28Pfn(l)g~1W{&GDdH#X95y8)8u}J*JYqfHd)Ru5c zP=`sz6A}^d7m*C8<5+9I3Cq zUGB}H0A-v`HcAX1MOh#I;-f{6m%~MQZEq_|^v<*dEfTRxDT{@hPYm%rKt~FlRvh*c6R3d@V z63JA>NHxSf*)GpgWEhajLb;cyqmuO+Cb4aCYzBfg@q#5814i65&9Yh9pA&9Mp)c&< z`lV9#HO?<BykBDn+NDKWqC^|F&F}{d( ze|14+}#g#52zRLvu z*}IQ2aeKqCDe9WifwIpUWAZ{k=c!+VH!z8Ra^00xjHV*C-=rn+XA>BOD4$RYoRhYyNc8b72<9@K#I)1{@9{cb|jEt@RX}W zFoCfaiA%D6;MPv1Q6ofJo)0w-D+%!)at5J!a^38wmqksBj-m93@~4jrJQH^129 zRJ~(Sd<(Q2r)e^_Ur*U_l-|w7yxvB0`}@$^kk9bNId) zjlpDc2N94r9#N13*yh7VZjI`4!ehcKACu}*VHPc8rRNfk<%TIl%9O{PjM(I)tC@q# zbf+NG_uXsL)Iog)#W-^*U$iKn;4DbLLhUBTmN~1HQendmI zj8(7aF<<|fY&V+t-sd70gCKx*A4f6_2dP;YacpTner`X-fDB_pJjgJRgp)hWoJzyJ zs-69pIW3R6JGetxDWo?=Sn>g`n)zgXM7={=7@c-%H*Gy_J{XEEszE=MsR?!3Z5bCN z`Pg)5hCL~qq{qv~m)Gg_`~y4J)CBB$n#a97yTl@(2*@_!T6cRCJxW}RZ0D+gC3NxF)z(CCJ&OfCxj7EC`hQ( z*}@M~u(lxPhTa0_A%VUZZCgo^vRZ$n5%~&ni_;o|rr=9!3`-Q2Rp2vO-Z45MFdOzP zI+eHiW~ZqdGvNU~Mn9;Rmm`;*mc>?uAB8G{GB5UEuWbx9f$&s7n!OYK*jI9K#dS&2 z>pKbgV<%I=Rune$vUz75(b8g~$*sEYPedXQT;hw)-ORWu?wN1!gjleUU$n;x!`0`q zdmdfuyky=dbdacy*S8s&I=(B2BOj$Grk=_g9e`=ui|`LO4WjyQZko?9PUB+`j~(n1EXeys6Srl7ZFz#;1wy^*1Zx`Yp4WqN4upW1mM90q3h}ZH$E+!ZN_K=Z)Eg(=pV?f&0HjTe zYg&n48w6(-JIqbVTs)_#)>|+7TMU-UVLimOggf9mQ17Q;$!pX@vy3y21tt_Wu2T^v z(QXb+%U2FMw%0sEhkFP=z6csUa%|WK%y~ZPt4W=LHs~JpTZEGAO6dyJ#G`L2C5BEq zrW}7VQ@#YWwULb9Ah#n=>;o1yNtvz=4VagoP<85`u)1WwubRG9Xn-mrz`yXtA9PZN zi`Am2a0qF=FcnE*#g|{UA<4^cQM(-(eKk%ath>mb?OocUmeFe#dZ#Qh^rPq5wUk^JQm(oS=vvijeJ_2;?GE1&vFG25$bV-@i*3qzC1MU*weR*?hXwE{QLuCQeMu|L9+bi5Q}VNTr6i%0ylp*gfULmNKO^Y;#1iG#*XhXzWyr;Hi30RlpKsH0?7IY`354*!a|m z*XyS5Dl=}o>n;9^hz6?uk6LOnM~S6;CnCVqcfR8OTI49YHVFESQo~SYC^e(^hH;gn z@jJZ#<$@xZgyduHo?@*YP~Bf+$PQU&-Y$nn*I@WZYk(nbt@Snx>C~?Fw=q@p0g?UlfC{nj^+2dFn$rY zJmjt(K|+W~6%t!<%x3-wEmUzUyrTuk5-3`Y6?~cbIZ>G!f2qZD+*#ZOx;^~3@||m| z1{p=dA~>`_jXGTj^0O2W`&1^VpTQ;6MQX*ldf}KGD{K@r;;itGp>Hu5 z-y#*Nt+xH}Y^7LxQ-Ml7QWCPXkGyEGh_mQdgL%R;V+e$A<>xwiZw2;Cim&lacvbB_ zYYEfC?vQ_8hql)X1Y2njHW5@HPHD7zS|h#|03hT|P&pE{%f~|TPu{N4bBM&4h24E) z5=e~^hwE?UlGik6^BwL+@ExN0r?w0={&^SQ;i2NKsd0SHBXUz}_YGO<9G$x8+I8FX zI=4(|RxH9OU|&AKe*DT@mibike=y{F-zAYd4g=QBUHX!ZtCS*YC<4daf@ArKKX`Xo z^)m1J`xc*<8qs%_kh*KyZ^Ur{B%Ty(X9#=Y4thSpHv80_h{c9QIgh#&5Q|Wl{R`V9 zu=;aD8#ftx8;yEiSISW5E)dm8XBEP_XfH+@p1{U}pj2cn>~aX9MHLuJMdHdM695Hl zI^f80;G=rCF)-o*u3Xf!^dL@cT;7F`&bt&SA7Zc8eE%ZX2muxI{%XkakL%@#_c5Ca z_8Vg{j%?q(h*L`3?gdj8;K^vgUACnLzzLGw(R&hQ^D3b&42#Ti1)&8zV0sCAUrr-B z*V?E8y0WjS4S6}!OIbqaysrYH1FrB>ymK%HK?VRgEH1@3TiV%ukAN_49-K3)P$C$L z-1O=(Eo2%Yj$J4m*I<@QuJl%TWF;BZ>fIgXSVV=Nw!o> zr!`U@`TJ3Q6GM?CBny(XS9iU4&2;GWQ2ZI{P^>V&nO%fdT?dtF1~g%mOzFcJGL0d^ z09v?;o?!U&*`59zEiqRHJUUyOU$!q@epw?CprV^Q=3DF~fjXTa$u9xc<)^^*#$c7X zE6dJ2HKCh>+Z7p`&X{xp^^D#*cUo*{F~h<0I%Bo_PY^oH+p#Wun!K-Lr*Ou{y~>sf zrhOfWsg$h+`L)adeVcAGK4P0|)QoQ8we6W^mD zLuh6Ad}3L;6uv}htauDnw*wWsk45?_H=2a-xoLcKmZm7@qY%QKo^+IhKctTP^k5|c zBw8Qn4&4H?xHCUch7XAm^@mEvClnRmEsB`>9#oVrso1)e7M^w3UI8bMX&bmU4F8hV zRc}`Xu2WxM^I<`XPyiY)SbNI#<*rHK*xuEzw!b-sGDGPPKK5EU}Ud(M(WXag!t# zI$8V0ssxbUJQ1({oZzSYOSX|G*VrZN0bd>LlZb#E?RMf5AAd{sNeORUznLtO*yV2N z?6oJV`4ifGTpLqoX%;sP7{2ND_8rQN_>#xCfMkSPW^Zfm3uK+oTTam8&+C!4O`9F}18@k} zw(9x(eZ5QS6ouJ7`hP6C)|be;W^?}VAdZ}n&cAcXLGv8~72+`RRsgi9#M*kr(JM4w z(5mCopPAwC;%bv|AF)CnuUJ||Yg@PbUSs~V4WNrqJmbw>F?3fjDfGU*FYV6|NJ6o4 z^3w4Du4l|}pl*#otRbd(?kf>&klDU3V(GPo^B=B&mtHwAEh2mNNh`=J8gfF5T%Jv5 zHj3kE!k%`JX?Q`#xS98xJzHmEHt$~+-`N{cz(F)|QC4D74dTttqewX<*VBaKItRD; zWeJg&#Fw9Zmiuqt04IMO#?g#fz3zjQz%1x3N-O3(!p_wc-hccAWXOx34hPhiegDbG z3wJQIpnrV4rXCxRNm$v7lVUebYE^ds5Yq5GLB>u@Lo&D(y9 zASyJLa|xbVg@2n78=|Q?gqFe%sRFFKB05%zFO*fzSrFtTDdxu+M?o|LuFUr)ii^lSW^`a`4z#`Utpb)t$T4d`|RG7R@tO~e(hzA_qYA=@4NvLO)~+;{&aQ3r*`Jxh_@u)V>XkJOw!pL;+Pvp<%^jN zaFwAQaInwN7F*O8dB!!Lv1h7_DIbk}Ij4MvKojx!(s0pspQUVfXh-zJ>qAk5ez_sLfIza=F_Ze(5=Fq9 zqI3TQECyK^Irqn^Y?%a9TdIROjkD%5t1+6jHG?7*hEGAmxV@smxB>caeUo8*H>WZm zrO3j*c>Ium#mOeO&82~ML-=rH=q{R~Mo{)`%73i|GOsy7W5C|=ES^d1LEpn5dg$v) zcxfaI1ORkQOEDq{1SrSrN_F{o%f(T)`)N__r?{Np% z%>2OYcWbDVOZLRi?mx9*;4Wvg>5!76QS3nbNltiauo{D4a%~a#Ga^;0u8kfS3MlT# z=XN9P{ag@rX3aZGkU&BFg5VPz=nSY6my5?B-zYflIQDFd5~Edh$y-D|1%Z11TcVch z$ug!gG=h@7!+0YriXcnEFq}Y7vmRS#R)q-<$ISSS`@t(-1U)#8MId>tZ64f_DOoq1 zkIpllEl`rM{Qdn1|I|(!QD(Pu6>N(}gi3j|pF6SJ4ow6a)Qio$`r+QYNqZm&$awp! zh7GbFRc<+i)AdI7vH>Hz2O%fSkV-@uhN2SkMLmLL)l?aI=n?mmO9qk_+3n~1`4c?d zi7;o3eI4%)j3YmZ=!eQ<{5;9vOwRx!HTe^YNRH&xhPaZ#7!A=bh(qi4{cr%JkzUb* zKgw2}N0p=TH7%Evs<#R~-12_-vP>YiHr&C^es0s>mQkPB0(g5l8=*P*Qp##e((%Z( z(Q7$%NMvK$ed!xhmdbwu3CbRNLC6g!>bn$iJyN=utcN=t%}3EOQ31QwN-yx-7L5p8 z_i|8GiR)O`Vb%4~<})LkhEN4>n(AccvUGV{7%@ zY($s*UgqkyrFU(^*AJ#NDWJA5UlP!8Pgzf@NkM`7=aJlOgo;z%8 zZ{|^VygBjJjfK14&3x5`<+e=k<<+>up6?LphZncRw z%qtF)be6XQ01h*+xZ4gUQLTe1!vGvXy&n>ZJdcR7~bjmn^rIWCBX>FW@Z{Tlv63lzjLoMOeO` zKa&j7550Nb+u)nN790$rR)S#r>Hm7Jp4Ku*A>l1IAa zf8I}?lSdH)C%8hU@xkKLh-c8O<0I>Sd_NTEorzlxwXY8s9+8XzJ6WFGdGy3A=a2O2 zn1{iQwTy8E4BU4v+r^DQc>Y3Sgm3cVIuEAu&>%#VwIn7IJ|%NP2-%HSEAP|2DQbVE z-n?fuSF6Ai?&fnXs;PAUHB5S?IVHwdX6aXF_t5%}(lM!xrcX?pJgM2Vl4ENFATPvj z+D@NEpX*Hg(BWc1nCh1o6uRsQiQ}L@A$;slk6`@1wOIn`Yhs3;-_}N)~ z6TnnLQVAdl(N%fDQaP|BQI(h8~Ck3;p z_2$i?@y5I*2pVYy<9Cp>_s%BbsKX27sY@c;lEwTo6o?6|!w!S6z@}-4v0rCNJPWs+ z(mRmB`10HMp{yMcGmqm9sWS}f0;yoOgqdi+eEP+HLTl2Q0Dr3{&WHsucm(^>*m1}9 z%i!6RzNGiEVN=vAfPwNcWo`|Ms{$2?yr)V&H{CD-(p}e4hS9jhi56mraymBk-Y{on z?hHXdGD#O?&yJs+vsra`aDOYfRtgx=d?e&Es zeBJ_Gs>N^Tcx}$@>O8m>g}0QKpw!${8h7rrT}EoR;EjFCM#F9nnW4+Kz3z%LYgAFnQ5ylzoW3rl-2By+0#2S9V1iJ^7 zJ!H~;*UN$%jFv@TBO0|t8a>u2?X!rjZTejB-(?X;EY`6-LXf=wR)tjm!?$cc=J>+H zmlAmfA2z2HThOlEX0QNHq(o0q+?wP5an z(GR0)bzPZnN_jb=z87;YnZ$kFSFm8gQ5JUw>O*HeeR-J;h<3!PkgiknB5GRBpz%Yq|JIB@o5M(VS`LP;)7L z?*ZXlW%KxLLD!>@c&N>(i+A>qA3vDc&+MBfulUI5!KMTQ1dpVjn!RXs!tnVKh-Wgz z#x!R^+em;a-Rbw;^62Mab*-1+5WvI{SB*p07e~Wt<5YVsSG%9c`rNjBf{CXhOCL<* zwPn~S>GOO2N_XR1yh-c^-_c#Y-L@*!<7jaYBH*%M^5vZeq>tL{XJd*LmCrFjruShl zi$92O$w2y%I}pWA7HR2;+>M(OXqEED|O;RhVIdfmKT?qW93zQ>V1F)=ZN-)Z&h zuDyA3rCqC+v(f@shF8DF=D=)$zVS|?-)TOZw^2q*3d-=kd^7KJW?25^enq*@jK{7Y0X(pPI}I zu;vh{7}hUFiZOW@VP+f5zk9PnWL>?bs*QaZYWQ;X>j&4Hv|P7&kC1{)-yd5~6-a?8 z^;hpecT#+kUy)6gJod-GOnNn{Vtxz^iY;bk?U0jqr;MWVUH8hsilD=IFRlJ`0f4t$ zF%3Qgn)**)<6ogZ_LgFoF1;O)Ek65~gmSD5Ls=hoqeWh?tl9ijm+0l#dzrZK2R z*~QT>UURET0@K4Vy1Tvi{`~*kVB|gI+L7b|M-RvQP2M-epO`M*%Rc&7ivjqEY=mcP z+79$yH!&@F6$9Qjxayf#y{`56rZrz-t(q;~xTb`?A&2RBneC6ukKFN&>-0T9TU5Bq zr1M50UTG9J{3W21wP*8QN1MgvzPkn1s3r+gc3vmr+HrbiSB^C+c3`m#5R?LEOHT%! zXURKinA%j0EB&io;-2`g;9QRSj=mCbz;VC93|k<;zD&qHy1Vf?qrv~=*l2R+@eeId zr@WbDn5TeiGh}o=%FC~2=Hw=z2^I=*j5SZCq>xk*& zOnoiP!rq-EJ~DIhxxk$0CZouDGvigYz{I_HoRPGZ244B?+uX9Fo859ZpVF(V-WJ&F z=`xPTKkO?xk}~Kn8=;~@!jQ9DyV|SPt0N=7Qu^ARA^w#gkg{H$mBMX1nP`#FAia6-88~AmsfvLBa zbmh5Oey^8mp{!pw`RPTjm&fkT)%SXDcdZaaU10>@w#BW7HIQ0bWT5yJZ`we zTsdkB-mz)aep2v#Yks)(sJUGu$~7SQ!42fRw0O5i;M>-X$8c1AFDkrfh0wPA=*(#RwZoPcyy+uWdu5P%4!9;=O!_g3EX8>$hoB48xXS?zgGznY+6?+K;`; zAOpgx%H?>~W#IPb27-2nzMKPQcSyC5WgI? za4aNxKCCTiQ29t{I|K4GhimWly&$gl{QZ?0)_ylv^t + + + + + + +MakeBlock Drive Updated: src/MeLimitSwitch.h Source File + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + + +
    +
    + +
    +
    +
    + +
    + + + + diff --git a/doc/html/_me_line_follower_8cpp.html b/doc/html/_me_line_follower_8cpp.html new file mode 100644 index 00000000..27381346 --- /dev/null +++ b/doc/html/_me_line_follower_8cpp.html @@ -0,0 +1,189 @@ + + + + + + + +MakeBlock Drive Updated: src/MeLineFollower.cpp File Reference + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeLineFollower.cpp File Reference
    +
    +
    + +

    Driver for Me line follwer device. +More...

    +
    #include "MeLineFollower.h"
    +
    +Include dependency graph for MeLineFollower.cpp:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +

    Detailed Description

    +

    Driver for Me line follwer device.

    +
    Author
    MakeBlock
    +
    Version
    V1.0.0
    +
    Date
    2015/09/07
    +
    Copyright
    This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    This file is a drive for Me line follwer device, It supports line follwer device V2.2 provided by the MakeBlock. The line follwer used Infrared Tube to Use infrared receiver and transmitter to detect the black line.
    +
    Method List:
    +
      +
    1. void MeLineFollower::setpin(uint8_t Sensor1,uint8_t Sensor2)
    2. +
    3. uint8_t MeLineFollower::readSensors(void)
    4. +
    5. bool MeLineFollower::readSensor1(void)
    6. +
    7. bool MeLineFollower::readSensor1(void)
    8. +
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    +Mark Yan         2015/09/07     1.0.0            Rebuild the old lib.
    +
    +
    +
    + + + + diff --git a/doc/html/_me_line_follower_8cpp__incl.map b/doc/html/_me_line_follower_8cpp__incl.map new file mode 100644 index 00000000..24fbfa75 --- /dev/null +++ b/doc/html/_me_line_follower_8cpp__incl.map @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_line_follower_8cpp__incl.md5 b/doc/html/_me_line_follower_8cpp__incl.md5 new file mode 100644 index 00000000..45ee12fd --- /dev/null +++ b/doc/html/_me_line_follower_8cpp__incl.md5 @@ -0,0 +1 @@ +bcc9bac3bf7af28f256ed669c60bdaeb \ No newline at end of file diff --git a/doc/html/_me_line_follower_8cpp__incl.png b/doc/html/_me_line_follower_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..068f0a40be020ba6b02e68fe5246e23633e27119 GIT binary patch literal 47918 zcmeFYbx>9D_byC>bax1%Al)1qkxuC@>F#b3k(RClC?VYq0!I*#I!H?&q@=s+Zouz- z-{1V^{k=2y?|Yol@vvv_wby6Gvz})W@kUt&3!NMt4h{}WPF7M44i3o=4h}vO4F&i{ zgB3gg{DbmVK}Hhp?*7l`w!%a>xTkP(lCLzp!Q1mb{z((lcL&2BD#Vgcn%G&3>ezx6 zi1h30Pro21RMmMtnQ0;9qIE2om@Em{PS~AjnbLZa9_&Z4ookW?f313@Q_tFjTBe!* ztE65J*&x__ck4_Bh1@KdC9yfN@9f5RXkc(qWZi%pjmvnr8T;e^|3}tJXB_$dvY$el znwo7>gQAokR9qa*SD_vr9(NyGu<`IV+TRsn;Ns!o#d~qp;$%)&=2pB$DN_&mP!xrW z7r(3i`xzY_-Kb0ql@Q-1zIm{2^;@a&=N~`H5+kXSJOzIA@R`o5l97D;(8n=u19yA) z^gToO`}eiv;m1zue_zK7=l-|L zvWef{>9V1ASTu9G*2?SLo6nucGie!kxnnQA>3b{b_Nv;P@9nrm4HLQlzt3C0*;K)q zgo)&Go;@3f9pl=z;l{ix!wcRG`!=D=XwTD&h>t%Z zpB)Sy?(jL_ye98TsI{Td_AeAsD1zJ zbn?q>18;H11T!7o#VgY|;C8ave`CsZMT)^$UxYU0ph&b!QzUIJgJiWRuLsn9Mo6xvP>7c>5lCy9yBew$Z3qAVgW60b)Q-<*2^zN-+!F!CH z|F4(&znA}yo?+QU03t(DvL!F~yV+~`BFt^7ph6Ky)?V6yAuOyM=R>U1ocPVPO$s!i z0Ju?e!DAh`EHBBw6L`NoXblhHMCEqIM0GBF8ocUZar#9ziU1TjI)i#QJcV3p$nmMifWD?!{!n>;IwTY>rnn; z2LH4X!Y!PAC5g%mcyUUlj-=t}8xXV$|AO`=(`73*XW`%ouML`H3WS-lxaE8h0te@96gIG`9EY zSM?@IN%N;_kLht^q%$Z2(ckm_^}EjW8Ae_)kh1iG|FJWZAIg`0p#PZ+E>B=>jyEWy zjmp8|-eZN29y^pk^MVmt?h<}*mih7g-XMubgI2=uq*!P_*OS#AT<*V3kv2#G-j4n; zz-5h!$gEh+wT?h@+0E>9bX>5(*EIABfX)5l22 z_j+#%ni~}L+OF=EHk3y?jcN%7`>w>xpmjNme!hQ~N7GhXf%^(=;^(JsOzB8U&Zvc2 z{twOKzZH%DxyHmh43^0Zd#$xVW2WLf`FI3kY@gG-OC5nD`<)-o9eNRlvmo^9i8_4g`SI)m*3a{CBDHc$j_}IASWx` zSW+^dp)N+@-k~i80dRF~;zi8M_Iv9)^Gx+E0X=Ry_pxn^I<&Q|7Iiq-Y&xApev}RT7gY0; zv!$w+v$mcPxTO)7HsAf02}Wd}6--OwP=N==op9 z?Z5r~saY{OJ5#6T?G^1tSZPv{`TQ>*`gy#=3@WZ+TSsm0tk@LAve#;TR#s*0lxM@j zZo3l@BG6xaZ2t#G7BBp1;jSp4H082gb&8gbZe+~nq4CoBKw?FAq82(&4)Qy&g;C3p zGB~t+qrc+eRDJ#0)A@0L5HFtc&0{JhpuSs;m|p5jE$bmgjz+=uV&t`=u?z8F*q62# z)kd!BH!Tn<9n@(yMI0W^vD_%yBEgH_eoXj;b*Sjoc9DX2W9N78CAQ!Cm5z5Ah9ADq zR<2iky|r!(ptX0rxkz50Wa!@!g|#=NDjKhKp*QTe{~|Nv5PZ+MrjhA_i<^}6i_&;y zYfi`J*Gd%^N5*8O)#|m)sV8(1=zqs)Qij3zz2!Kzq@?65V>&#qB99dZ-HcMq4dIIF zLLg{sBKg&3rnZ;6q4y6fQ3x$TJGr0dhUV=`CC%RU`NmD$%v5YfRLEFGG!lN=Ksjk-v$#OH)K21do8sg1drA zf4!@njGp*X%@zEW!+iDgE8){9ms9D=4gmlH@;x@a1cGEa8X8jVR<|Y!eqtp5R?m0k zPCJf>R6rKWO-_m!&1Y68)N0P=H}cs=A8nIg2;cf zx=q`Gn5i-b_3q^0OSgJwH|^VG@bIPu9=$Ni3^n}Q>huzZ50ilD!t5fr6dd<1y+=C` z3=j?C8EX|9g0Mev_QR=aulKBTr1}=mfqz7VsLT+WMl=EE+iY{TnQbCQ}&((eA{+C;Mj6mCxmO zGIpWmRaRHFfbn8{Zn+ezpj8NJaHI3CTVC~3X|o+9{mdbO;d?V+76M77wXDJi!t!CjgpJi^^kjFjuk|?bYAf1izkdvhfS>X(%Z^Fxfen zvzDgJ6I8W55lJ^TRawtUJPc?6Sy(E5Pe;S-*4=@}a3OZDpHk7T6Qdo}S3#ptT6@o7 zg0ascO#rpc!hJzE%KNWv^)iuMm|7YjD|+h4!W&QP=A=ZTurs|}B8CyVwZGAJ?AWlO zLicO2(#j+0Alp}Udts`Gf{kp%ud^*}M$6JKb+p>w8X#Ntv1^Q@Ct4Mh$03b~I^rv# z!(FbAppBrC*~k~Mz`L@Mqf|50W|;F)Ht3%-TUfJ?Mdr?91=h)gaPNGF(aV7GF~J>Bt|4X>zyaZggx@1g=o6wO`Z1F)z z3@Kx%NVg+f((1BIgZ<#k1`kFECoxyCV}b~{yoK=8d@=pyVm;amTvzn+-qyV*Jn$Vy z!HW|rCdii5QVxJu?Sd5j*K$IGiNW;?o{FVLdc^k1Ilt z_pEvCaCHb5M`56&ZFx79%vquy=sly0X}=#FaYC>Ywos&Ls^ShDhx1?mewaE$Cd4wl z00k>kVt3c>yNdqAK-(|lrC-0u95{LqrI(}OvCZtvtgQ^MaII5$REjz4J|0W`bI)tw zT8&vm4wlq+3mSNrI=8I5JnG^D5A2^~y?t@M~S^An4}TsNKnn5+xW$5Ph?xv@RheHRCDT91%L zvJVqoc3rHH^+5%V9V^V+8-76en0~hueWGEH6-b$aa5O#WbfvIArX>|hg2lY_iRy#+ zK7aHJ4BcW}SxHx=$MCUNum2(AlTjK{vwOU1!<>EGXF2F)<OB*?IORR^(}PnWiHTW@p@M4S`6R$&>Kf|voR?}YAsH;K#0 z)04qXzWkIBAwm}C5r>j}{_`>?(haLhY`=E*bk(OfO|Ap!{E4$q?jYNcbe7>4z~s!p z$~_XoH>OZBNciA+p-`jQTn1x(VQvLGiL%pig5g_Ad_glzX`$%8_u{BymsH9?KyH6} z7!Bg#Uo8CX)rq#76ChizaR1qT)bF4ahvLy#(rvH{mBKbIXRo!ZRd<+T-0ovfj=HXb z6W!|}gIonCuMIkd_=wzkHPDn8{dujgM;hZIS;dRQCEa?IJ@}j=MAK3@qP8DgIA>Fm zX@2*y#u2YijB~K6*OA9_arMtCvJtKBDeVcnzUAU~p<6V~jo+5;dR5L=YRRCkv zGpaNDS~K~unigyUB?%UBrmhLr?^K$brcpWW|GN2Hln2x24qFSM95owROJWP}z%-+9 zO{pQ3j@3ZYH|Fv6gtbRtQqP}*G5m+4W4;`9oD|Gu#25(@VHs&~CCxgEM!4wZjt8cO zCA2D;s@!Hy{Oxw?PD2An9KGZo#l{HH4=1T+)EhJD+Rs2?6nK@kaG9_3-`+hY2n~8~T{*g_i$I;+9XM6tKpX}V& zB(%$7dUIe*>)J@{6RCppTce-vFAo|7GndbjI;m~8=EB~r+RT4ct^lj-Zai$MYF&61MP$*82bkYag(~faeshbNP>tJ>xoEI zh5)`23!#$@4suOeNzepF+hqnxT$JG5_jus66IQj=F&x_3w>lg0b%! z=omZVoJ{(2li!%Vf{2jf{AhSHlA1Zsv>jiO*8Ec}?E@3HC=TJ$_2km}$?B>2cs&*p z5f(K?4JxW$2IqN$&Suo7RrYSQY(^K4^ljx~G5jZ_=XFVoFp;A!CKtOy&EdSHuy z8y5avK-!U=Ez9=MMGZh49*<8hh`xfP@7lX8uW_to_^dX(*qlLWaU;3h%`}VVG%NF4 z`{=z)YQixqKz=KNQ(Gc-J^ehv;jzMBR`quWf(x37mnC7R?io?*K#}qFTPVrT*>e`z zACr8!_?JC^oA6Y&0sH_!$RHOGKT7hDt?^&YP8&Z)_9;TFtlgM&;twQ^?K#*Jl>XiJ zb1m_?A3FNE=U4V&ns>n%>xy-~uAE-N8>w(&C~Qhe(?rc_wLQN_6pn94!CJtWIbb0Gh2rf2t7q!-pFGRP9Zs@Ge zi_(++`0|At#mpWSjlIMe8o-tM&5rqZPfXdb29Z9JfA)OZL>2`Z{$zn=LV_sUHH|GB zSIk|#N)->(Loq0!Kqn9oNN+?1C=iTuOrcx9akew0k?f6sCw0n?a5Iv*Xc>( zmic-~>iMq};#f=s>F~N!q|S4=D&`#u3DmNEQl*m|m=AK`D9K~5kC4^O>zG0eL;}NK zFD!Lla`_3T@`BS34WlFiLl0;XzS6&#p>Y!k;?v;s6@f3*-{Olt&ERxYO41Wv59D*fgy+6p%AH`-4CU{gJl^&{sVRTIdi__mF0dnzs!*;i_&@xgYng8d z4mL(pT5#0-1q1Z%MZZH}#TMwk{S*ZIg~Y!S*R3EIx6%iuBnp;|{l3Y&4pC86$FtR% z7i3L;&MrfYAlgF_h&KFdrUpi0BSs%v_%=jlb&2-4IvPkgk@z z?R+R$9g7WdVegmq{*7e%jlkv%J^5JbMU@GGjJ+2Tu5jpxx#`x(z8*6D{Nt>ZPckHX zu@AYRb^ahUfY4M`F_-70{UBPeDpFdZ*X z_>7Pac;;YW3}8hT_8su{&gMDkVZ$Q`qaFNQrGyP(P(4% zj);;5)g1T zC@+K)q9X{xr?!&9)cV#QQs~#}6L5l0qbKxz@@$QAl=Bg_ii|g~$9)fAwP_c0su3ac zFoZkE&v`O#HjW+iQTKi%FjRMnWN3Rrid80`H2t?|3vVNmueU)PksVRHFe+Wd3G5IF zq(;s?B7eJF)G!ONHhjYKaq`9KaE%8=T5YZXY~+5>upgpPxm*RAQ9-BV-2aII`I$2( ztGZD~Lq%7Ibwnzcsli*pIWPLRM~k-l!b*~iH=%JM3IrCOKI11J-DLpVoNg?2VS> zOg4(N9nR+wNW3^+6`nVWj+`Zh&MS<#apn3(xCfR-c;4~nFD!0vTo8k*t;*`|JSNLy z=n2whAD@|BqZM|V6jP9#)_3GTPAh^i3`?+)wyoF6nm@M{6l`hPu{k8r@|-caYA?%V zXSWcV&Rs~mDVTo;3`x)Q^qK~v!sJQE><-h~_gd z9J%6_%RY06%sd*xI%fFiP*Xi;gzy|E&vu`ClH;@ws2Dc83um`iqcZ8!#S;?~d*^!! zuQa+J=v35o)}#3b`#*Hy3NDjy>YM%B3q@PDPWR*zku&O>O?Y(z0tc6hwQK=5%Zjg? zjew|0;PE5@)t2G69&9`P>{8Pd;x&}kx{Jh?mVW3o{IWhwb&3J;wdE=_hl~I7Nf6(* zXwvJ>Pi9>3zc@h*0`^X&TJR_+>)2eP#_7kE9(DCwfAivYyS)-Pnw@UyElAc0T?Q)LpWWal71YiM>Jk@F3sQy zW8nO!d8}$g5d8zC^Mb@asuBpE{ZPMUfF%GJfOhlJ9M)(5(qGW6mEdXnPnu4UDFZvJ zvzdz9T6ZGYF6w%_#ntcaR^ru8qwyY57DEHcse2t*9*`i+#Y^QcdZ)4=&rm#e=cw$~ zs(>yqMG~3~412%7g+0fX0Yzu3XUu+C3$F#h_>uVEOJtcuH1C%q)H4pJ}wfCsgS+K$u!wkm#DGXQP zW8;{n?ij)Hhpb%+ac3LQR#~HY*C_YTOnY&Jju!=HW5B5ojp1i7|HI_BrY6DW>@Dj2 zVk%kRY}{iRSxCXTfrsC1lvRBvM|FyxZlr|0wt$yc)N?)pn0!SrF7!1=E3w`h zr~(yG#xMty(uOos0IP(Iaqjf}5jy!K;`o6(sq%vPt1}OibYx~veKLei~jNugYN8;@lT=Ecx0F0cnn z)zqe&w_XmWB0x2eH3@7AqHytA69bYByv04mF1(6Gs(@vL{aW;mv90k2&MRQh6T_Yh zKQd`aJM={sp{pU_SFWDIUp<|0hv1Qxve0WLA3r}xqQUcUpc{Sc%|C;k0j5eM`#9%4 zXEsEjGe*wCg3ol9UZ2dvAq!9C;^i*S+iS=3r=r{st>Nn~M=iC;;%Q4Ppl|W_68DAq z5bQWbsAaD0yM(tnQqucg6un3!9kBw6zs zD+5sX==Xpxx;QF$(*9IcJzYtfkvlaQ_we}FTFwDtrXr#x+kUzQp?AJfq~Rp+iipo) zud%JYw&CnDcFoRsEVgG$nUyYJXeZGg(fQ!GTaJ}G6GBdc9+ z_`TM0D8ozG^Vcg>2fwnNWe1uq>$1~fFCH1I?Ai3Ji80MbA3FU=Y)5tGbf*19_~CjO zV9bMlSa|3v#h}{7txG?3#I0nmZ&sZm4BJ7LnDz~ry~@J!ZEZv&a_1ix6}c$}$^P{G?& z$+Xe<^)*|DP~R<;M*!Vytp~Eo>=k1ALrQL>J}}wM_-Wf!pAbZK#TK+=47I&9{~y-B z9bo+_J(L1M5UAp<%`d@9F@^pmLi|YZK`{(Btz9&0RA*PaxbH<5z9F;~!mi zbgy6_E-WqrpiVREuxreQ7?DEQ#K0lF4c9}dtvn!jbmB_L?_2HENnPwN(kr8;Eh7j6 z=LaE74@e{cNTz~4Kta9dLRC<(2ep~Qk>%vK8$R}vvp4F8UEqjQ9jVYDZ`micnC&#P zgH|O8)RoM&cR)_#{SJhTCchXI!g%X>>~Ga$A2bBr^-6uTsrG^BawB@PTgAcgm0o`5 zqG+rC1DTu{-wr+1WF6s~!21DUGb7&%x!B3*9`c|BZw&aq`LqV7M@mNe?1{kB_cw^3 zxhy%y=%@Lgt8mdV8j&SRIklF{P>g=~d`Hk~Bs`e==5p#=x2KE}skraG6P4b&s$w0II7HF#L{Z@swvBF^&uj{+V~@MyYbq2Rdu2ea8xR zRY-3*z~o6UXD{V$^eVRA|Lyo%;HfoM05;MGvuI~4NfSj^D^L%I*GGq46OT^^UKqMN z(4!4QZzI!B=CgBZ`lyN#?1$*l#`X(?NkILaO5P-V72huYphg^%{gY8fI=w>phd_I6 zII5{C3>`lbMW;>LyZ$)i77j6McVPH54sJ$xq|ed_wR}Bvq`_yllte=nz{D|WLXCz9 zkgpT+V?)rmOn(Ihuh07|L{DH3_k!1-_}rfG>v9KWIP|SvC0@rfHeP5d+~AmU^TS0g zzs!kqQ_dZ{B>)=Ae{zffkODFS!|Vn@kgTl$ZZX9b-Q}4Qsav1$OqX3sBSip70TW!} zv2l72R4IM7be5gxitVaeW?K|Ymra4&SLDH}aiE6pS`~PhC z&{fy7#|f-23vW8R2BeGNdKk6=X`m3C1D86LI#ZxJHKxu@9^j6f$8*!eZ1p2$T+%Ss zeJneqdh2pnr6;r|(I3HGoo!;VRY=Lv&uatx^-y~u2z zUj1^v&ESk!mGX(3AaQ%7$S$G1yrID}qjmizCw2O*Wuca~HvhNf>Y~W|<+l(s>Cw0t zGGIM}tH-cz|Kx}HmEX9>$%DpD*6#qy`2i{y<9V4i^4AZw=MEIjZ-(v+uql>vdr*nc zFvE>ue3i@axr-LEoSq9m786&8Vvm=v(gQ1L$fBwTVGAu>S8uJ1)YFfH$o$1rE&1Io zD#`(MHcW^FC#@PA8jTI>9Hu|+`RRUmGZ(wId*m_R z10uKhsXx+sl4SEdiH8!^edYW0#UGM&08-~v zMv?%FnX+)0+008)Z>T-9xo2^oz?f0ggJq~Hs8k233`KnGFW-vM6T6D-&k^TsPpbLV zav$}o+w-kQd8~R`X|LJw_jE(z=8BnrXR=!~@SOYv5WGua=aOP{JVf4YjlkK>uvlbq z?BJ?45+x36IuudPjg&TTkTlE%3Cd_hN|xyDi7nEIT$>ibg7rJCc=89~v#cwDW-@`IF!JaH{$CMUO| zxV$8Z22;_QG>#jd^h528Y4P__CFK$!B@bpm(UE;pNM?W;{r%z@d@6&y!z-`N=*2Bm z{N=!Ck^lk%Zkgyk4S*TRP(ErwO`24x>z+^dEA7t@nuJ+~hNJ7JrPx@`nLV&s**FA% zmiiz#cBawTt)0#kpUU&C^^tI^iOxl<<_plFk?xe=1;(Jr12j4kPxA<&xH@SK7v&Fi z!JA^I0ega*=T*iggK6rv7LZjAwb=NYahpP;$j`#_ut#4vqpigc$%Wgbm6kJqK~Jn@iky z>r-j6CMyJ(f3o!dt2p#tIMi9o40AxQg zp9920r{A4>h*oQ4iP45c;A^{2`(cvl^O-R&i@YjZ z5mq?}Oql(_{2_iEYdGw0Rka(xV`)q%_)7{7#e-zh4?=Kb`zgt25EmeTY&)0L`?iN* zLrHjgI@xR#Sbw<{@LGer8$1R@2{V%Pp+4rG3@|3b=U>Ect+rzl&G|oYMCid@z=U%_GSyAZRd6p!QWI@x*u}ZqrPsmDIy>P2A85IjJbi9-;0LoV3^|R)e=GI;fc@D#6((HjkpC^~x zVKo3FkzHOb1h@dF>JvH`JvuJ!U>G-0>F4#OtKVn-b*Rh)hJO_a#|sC4IM57?QP1f$ zJgU~1@8}!>sS2sE=&virRXso;{be?XN7~zT6a(B4C>L}$kBZ9%P$?G+^53%~rowNb z$^(JPRhpgvDba~81|-M;r(s?7&cc@&&@Pg~5BF=QXJ!vQFQ@T{jJ{2)IFxrto%$LXJI zdmhJy^pfYIk;KX#%NTVPZ*(n`Ln#`c_is-xWQ*l!vYjFhl4Wkd^L&_ehz%dRys{C2 zs#90J-QuefC@7t<#7sfD;yZfh&7<3*R~ z!iE^TIO*;~hf#YGc6KbyPDWUT^m{Qn?!;V5%A(&Y-Ay-l@N_^cU`LbnP|k7gi7?&= zf6HC^D=(*^lZs|_QNH)Jg96Eu**eU@`WP`nZf&_N#+nN|uNnVXbN9TZ4ChXnTwX%d z3mPtm=*CtHud!6J){;D96WB8kjGIR5qNHN}U>5@L z8Si;=_#D-2W^GMdr`cBZ-}j0hKyPFDv^!G$H_P3!-;4Fb*nBgZcg|}w+{3OGxl`wc z^%5gkXcry%ynwLfwTeTr$b8}fllm={n=+s^{k z_NsM)LTiK7gTJE;NHlo>+csoqSR-y5-z?f^zbg4dqN}TR8a$AHMPV}|ScRdMRgnf& zP&nO1*1?21o~?EvT8VP>M|&F<&lBB;-Q!-ybn!pwvw=(#V$8DgZsGiJkw)X|wY%FI zIsL*F$GX*)dyZ#st_soz%VnKo=)>~Nd+>TsYVdsUho?h0Yk*kfYu5g_OXp}}54U{3 zc&XA`rnfTH>Y|uCD4G$5?^OgWSP&7rqzd)E1ux8-t@)MYe)oDw)=9_@o%oz zwzF4BX#Q=>hpPl^vA)gJ)4pqR1C#Z_qgrGeMIA7BQM)gH=@jvi?7%kU2X;soqg}cu z$6C-&SLgy_>9QVI&l^es4NaMZD{8V`xKha9?eod1O)1mHx{v`t$bB9OB8DLj|~g z{EWqM4TJ+?b64g7;r%A~jl_aV&Es7K@s^$46|A(4&splRH}Sz#rubMYC)M)$VcPkY z+1j1xkG+g;vKKOwT3GHq$_^ihX^_EK%iO{(%@!-QSElH;Q3+=Zxe)3(skU4@w%nur zX|Kw>gdJW3ArmW{yGx=oHStH%S#rMV!I~2d$|!K-yc3IEC*~K8QO#zo7c+OeF3GQS)=2;s zT5AOyt$rjLp^!*TFF;L9X7o-qz|rL))4iYQ_4&GhP%N3t4WP0}e*xyb;G158VaHdS^gg=Vx39 zckm)Aym1!y2*9^hF#cD~+f-&s#)ZY#%Dh1-%hLI!b5mCv#Nz}2V^&g4`W6Y9WxURy z=c<-{_9}QPmx5ju#q5oxwIZH{YbqCbpfeZ^D7me4P{EYI!^z68La zjZ~8CqhOBd3@my06L>#a4tJwakB;$;>_ z`C6V?;2gBpbdJa@{pYjVLX5*`#rjS*RGakuIr(84$URo;Ni&^B>Cd`n*EA-QXB~8D zIufCJn|{O%&Lqy@?_?epo?aUD+duF7BXf@=7#&tC4yzgm>+{*K?6y}CIeaeB+r0X~ z>OTkzqU^C~SmIs2P7k&~8JMhG|8g<5y;EctBd^)7;!#Mw9+JybD0O00Ci}>4nt#4@ zGS1FH@XK(U5Z@c9ow#33WnAGWrJ*yC2Nu*0?rOc(mt2x35PLh;mH9q>EsGS_wXh38 zK-QJaR})OELw=?HNkY!*D}0g?;aQHf2B9R9WQx0`o<6*iZc;;fdIPTHr*19A-!*-c z?-(`y(kY}gub;`hz%@HvgJz|JhmTgizwp`>Xm%suwpus?Ln|lv?fOc~qxblT+oWKx z!d8u9rD%#~@^{H_p@>jK$uOUtas%L(V7{%%h{h+~5}s#trr(sul9wEjYVOJVv(AEH9Ga#ZuALMbwu(gcRKNN&=Ry2;{0 z=CH6#e!Q3OlS!v{z{cXmeWxD2nqjS!X*3x9@*PLq(`&PA1X34eolo445&THJWtRep zcITH(Z@KUz-Rl+H*TsWdgR67FWTgo&I^4Kk80%E`0_Kyw%2jH~6f}Sb7szvW7DRk1 zI~1z)j}KV-L~N=*wR%NI2?;kFS;X_!F?Er?==#RwGredpMyR~$g0_g8h9F$*tkf4f zx9i0o<*dd|v}7CRhC24!myym!gnBhD9g}9b@WY?lL~{4AMFbUvCxygnsvcU2u~=wh znjnnds5;O3B^r}1BIFKp7cbJWX%w$FbuNy?Vqmkg%?vq#FFwqMDe2u-bPYkK5lDI^ z4w>&Qr}<|&JXCp0rr(gQYiXJ!R{LtJd_9){ZA!>s06xpHl?VRou)AGP~pjC!N!>rs{(&H7&s zdmwJ#j58_1BeKeQLtY=5w{=nG~`Yu>z9p#xLl^zYq3 zZ5VCIc{xfFA`rMk)I-XVG7NQoy_jo$%D8u)m3Q%L+U7=<%wNm!t01Hx0nloBsSkH8Pl;Rn;(-9XDro#n022Z@&a zsy|9NORS%hq(E-=a0%R_(*w1iHo!6RUMf#etZ%fd*k>80^bmE(Q zPvc6sXy~-fFRj$J+Nq{wW1DcdzYs>SCOA(-R|3SoHO2UKe`U9*uteWzv>-Sm79wTp zzPk=9X}*8&V5z0o3+j&xsSUo8Z00d0pIp;h*Krq=&Q*bLK)rp!@>(~^#arz2T*-d# zP-a?o9G1IX>SlYaYY3wUdM4%S3!;j+@D;V(SGbc@F&| z5C+Pn6@gb5wLthJDrjwU_K=#P8w9io+QqH0gfNG=!usRKQwwKxj-S4nUer03l^;gI zN5e9sUhDL?S9v7O55wzn8u8z5Q7>5S^B2DTc1SW%ZTh1!@}Qt*~4JjO+YhRmT79 z0N$J&0%>#SjZ*Ks{%;bTHLHh665%lwf>9CLH&zjr(UQMpV zIm`EAjDPmWGj$5HLUKfPj0#`b3tXSd$&kj1rXFG~0f*wopsr2@uA3{eJ(kp$;vNI; zXNn(a;H@xNoQ9n@zP&t5TJ-UG{>|Vl#q;YEMa^>_D&{m45n_>qQ71UDSLeRMjM{!# zUO}708?otXbdYZMV**=DG;Koppa|T+y_kOH%Qfv({X-{O-TwN?`(lYiXwn-&3; z=#6e)Tu3FNc6X?M>92-COlgN&EhIgGCm@PdLWrggTmQ9E=0%ryU`mWwu99yZ1uQBT zjO~xEeBN|`Svr1*Wfdjq15u~`G7b3 z;iZQb7KNNf)o-zIbLl>XGE-+tBWuu91wy{Tbzb_l0^j~0KYgb49}u%aj+YA zxc=o^@Xv~jkMLHJ9M6c8ggyw|z(?_Hn1cL~&*`eLn<_LvvZD111+MZC)+-#t#P9b` z(_NLb`BfJH1hm~>NkX}r=vK1A9=KLhko)qct}_c#S^@O9&t*qKg$8}f_`*siUpto| zf<(J1m`8sm4x4}mogGlD+i2tPMOuj5H3;1s%QPD$Ei;Xt{W8ngE50r}6kol`;!LKA z(HKL$$NuGGef0s#Vgy15Tu%vCqt4~wKY-;&6=n3j#)rV7E9FO1mE6FhM-vuWNtaDT zUyVDd8V#l96JV-n(h=;T5UX(B*r4Hq{3~-xV)#6&RktuB2zli6OR7To7 zOu*#UC_?T*n=6!m-OigHci;8-Ar6^*cteGA(PV6o73xp}z;@zI2nEt6&FIDvsH;wa z>%1C>T$$`n}%}uX4pLB~caM z$iQf3Bsh#SHl@{kU+ixwWfn1}kT@)f{blTLRx$wwE;G$TiVnBKF4UMTDqBebg5T7u zrtiZ-_#7S5UTob!N3JXHW2nNsq%(EnJm4-DqJ-{tRM4nGUqB0UG+FwpG{}^)NY&$B z^AJOcR_)_uvvuvmQyS-AI~5R&qr%N27Jaa!g3Lw+m}M70s<+&8F3(=hQ(GgP;yxz@ zU}m_Gv{Pr$FI6>V(sS~CRhSo=Hj(QW?58vNt;Jo4ke(V(QNJ+_pV>XIAkawD(MW#0 zt_fdk#w^^8$?O&GY?L`nNyNykyPk(jRJ9Er3&sz#fOIDC?UFtbiA7fh6<-PMTM$9< zzGx&bg2*bexuvp?gc`R?Al(Q`t;yVZxZ3*UV-)`aCRg7$TMc%|xq4ml>Gph^kNCzM zCJv(tvy{=v-^srsj}nD}nCt2qKR`TQ-ZU}iYmy;@lS)S*_aGNP{79pT6s?Fuduj9C zMsqGxy%Od4m_{Q2KGJ5PH?hAa$xZ%T%N;t2sckFK7fd1K0KiG7!|gzVzCabGT{5RW z3Kh^A4{os#Y!T^tDIOz^=8f8fYPtl#jId)rxBPRpTF0@O{^=5bD~kH(5jul%$&a7Y!J}BLts6jT=RPd-|%%ya@0~= zk&JMVK+Q|^y0c?0BX!w?82vQ{>+6O4YV%SCwr^~4MW1)tvCTycbV?=*|Md!7>zJ4- zJ=)|1uQ3^ufbgw7lbF{v}pGb?}KDN(^?2|3gT=@*TID#xoE;aMD!+(xpEA=<3F6G4$qk+X>lRKpfm zY?E`ynkqVELVDk{6I3Sn-TZw1&~Nd*P3%&K?`rh)u77r=Exmm>JIk~o<*jP;WwTe! z#f@fA2-3H@Jmy=7QcUDz#5NlPf5(%s!iO6MjwCEeYvgtXG#-Q6V! zNJyu&G@I_`Ec7|=_nqrp=MTSNGuK>qj4|#p=LWsPB>tImdAVOM5JE@03LSlyy?17U zgMLADOPfAUulJt4I~Ve}b#Y!MQa3p+ zOLN!Z!|uj2XCErh5rLh@OqI~;)Wx5&709MD`B(8mRNOwz8YsgAa$g;Fw&r(g%jw%v z9ngzlAwr3a40H-E_vb3TYJ}BSHBIS06Gf6ERE&*k8D)r_KBk|JzEG9SK-gEag+O<2RvRh({DYdVf3EdMSL#hCo&XELfgOr!9j%y1*5vZHIhUA zFJyW1^r@Nw2HE+|`&*}-xn8=AO~kokrvPN01YV!9m`^fFR%s1Amg~(n#-?Kfx#(;I zwy;d)1sktyHSyOfuJwc+ts86zezw&9s5s&%fGahBwV^EtwsB zFUbqO{5*qcN8OuKF#ad;gd(0GxQ~iCiBo+TMLY_$T22Mg;o~NWM`)znu``|!?=D8~ z&lO-Cjjv(Mx*L;Fy;EB&Gcg!yv`8Ixh?XH!x!pHFYM8cUXYL;T>vsJ&8M^BB{ObTAZqg& z1PiGS;{HMmCFU7Ut86Du|NgBnB;l^M%}Z~p5>b3*DxoA)TRRX9l#@~r2Vm^WoDizt zVgAYK)L)zXOWw!GY?Qa^B|fA&C*A%WHx=8O5p6@fY!i}a)MT*jkrC1k5_n}td*x?X z$gBNV5?N3!eIw&Y*n_*P^JRDb;{^-9mt?uh%}`?JyW|du>nW(FwrX*5N^i978uOw{ zih?0F#3>0r{Q0*xF+Gpb)ju6STyn1u*aOYU1706y=$@DHbG5@r@5t_9pXf3&)35eH zdrU<#-QAqL>oL94uj!Zy5I7Js{HTQItMxlkLg#STX;*-|!&X6KKN6K9CsB(z*`iGn z#5<@eVXu$M^XcxWIkMyS$aK6X8Wk65PHJ-|4n=aN9)8QGP!2W2G_}lu-&w58-~d&P z)2x@!B4kT}Ty%L4v-68B|5UG%D|q3dAsHG3+W+{plpJx-pE{|H>=-!wk?gi*?(}~U zV52B+L7k-K?#8o<-daL;^nu89?vSVDqeWV*a*oc$=MRV7ngHRDgWg`p4g_LnVrnCZOG7v$tM@fm5WPfGQ1@sm^t($vEq-TRGK|>8MM_{ z1tw7bzsl&>B@#x?h3o#P{>KMH2~^CW7IOp-cm>z!SNGS+4#@>84&@`1zG*sT9Dh*$ zo76Y-4tytgtPHqiK0q|d2QgrpX>T~I(f%V*s4AQ#GsqEMx)W29Qt@)eAg4z|W0N%X zQE9woTTn#V*Om4#%M9ZQl|nKiap^!y(2mx{yvdW!&*Ob*RWAl*aU~(sAU7``g(f3QQY&)eJBmRZz86}To+!0`0;EXDN$CS zC^rJQwRE**Q`V)$Po5(^Ob*MaoW6oQ{?em5TdQuH$;~J(v5U}=b-C1&d&tIhUNPS7=~~}j&0^QmI}bno zA73XdwOJi7!pC}l<0eR{xy{&uS=gw}0CVij(X&AA!@`}yAn0qHmnX6c4w`bfm2cM} zxn@jc>+SxlS&Y1s1cV#jatxzI{YE%ftAacp`GDw8znXy1E$up&PP?$cwi_^-gT5$k zA=_~9_3!XT22oaALy^T#+BlZMX)*O&67tj83cj zFhU+gRJEmxF3@bZ*0-$^)2QZNc*lb;x5F+t(QLL3 zj`s`dz`UDK+!*|sV*ZPWRBM&ys!NneZZoI7I}yFzS>e)|Roq^7Qrtrnd>)twV;i|& zHLeE4`$Yb1S+96^@)NSqLIvS5wsnpc4yey_OS!kn_^Yjg@0kLv^5~Sk_SpTWU2(a0XEuVA2&mlpWMA@K_#8MfrruO4$;aX% zoHe(awzj3M3kUnQ`YU8F2RC8p<9aBpxgOql^ajr9CHXftolibks@C^?wvZL6I0t?ff;Z;HD5kXdH*ery@7ZB^(|zd-Ny zaMKaxza3bV+|0Jt#`5-kVQKcAw|E1N$VV-@U6;ab?G3+Z&qsm3e@PC>E+sa}EnV|~OjbO-54l4hnbrEcLfUT6F6Rskv{h6v z2}Yg04i|`(N-J%=&x2#^ef}&M@o(+7wzkgnx>UYT$(W|lTdxTirXeWZdL`n7_r<4K ziJf=UdXd=kXJKs&Y2#|zupNW*D*hgeB7*O#RMK9coj{VylWx$25Vp7M;_AY8$Hk_j zCr{~m*Xt${+oh|=hD>a-aBV$3J!AiYzu<8x;zXaiH{VljGfRIT1qw#2>29 zYv?s%haM`sVVO!}H%b<(n-bnST*kyFu;cHZW_S%aGJ|G5c^|oX>>MAQjIKhPp>0>0 zPjI8%>*NwXiA4eqQ)f?OVPd2^qf3xlOwk zy;)5-R<2d^iO+ePm4`M4?W*QQWT`OJwKZQ99mucJKWslAjU*NE+YQ61_J2ChD%WWk zI_J&0n=YC+OS2V>iL)p1SPM+NURliTv(=R_WLawvv-A^CJ&yB8l#G`^q*~EM&((UqaRH;b z?UZMKrI9NwaAI(LMDh+}-6hfPPyT~bmZ-^rUmDoE>X-~MH9ph&u#LP#j!~tTi{Ont zko^6hrehpQC(rC%q5~k*^R8`$Z$;`ixuOb`zn+02vG6S-06P%sdIYG;?UAMF`9tR-7W|^wDgv{~9TvS~}=IQno>DHAW5N zO=VrNGec#%aV&A=$uM+;#~}{VW0L2B@f7#utN!3|VEiMRk!-;OMl1nWZZE3O9k+dM z`!TWs#=H?jsDT$g15W%Z9hkx)FNq;6axdnu(%>PMfBYTy(YK>$LqH^CDlyZ&`JB!L zxDnJm=GnV>lyCCV%{SC*8RhnOE3xsM?v?%^1OSO+{8<}fewA$ug~z6}clVyhhj*wK zt)7m)=j(iFgz>K3^1*c!bV5_ZT2umOOlvZ~#UiOjc`k?Lu)(D5b9c7LSDgxL-cGu9m6CA+d(3< z2O)TU@kB7>%Ny_G#H2x`6n^$Lo^*z5PguYI?#r-d;ErT-0{|(!fEHW%Z~N5rP~LS^ z><>z!=?gc`-#?;WNJ{w+*aC)yk1L6+;5i=Lf$fL`ltMkaKQ)jJAr?IYT6dOm)WThM z@R;}Y`R4u#!;kw}YhR%q@ecjRW$}*Xh~AXXn%s8V$ZLIWInbc7m6BW2hI(H7Q4FK< zwoH33AiIxb9~8TRF+6mdRf1A$7bMl*KO2|7t+RLSwc7w$cHkeTE72!T`q3o8krRU5 zbDi?B=bpVueufGa1d?z@Q!^sJLr^)N+GdM`Y8OL~5`{u5uRc?ZH}-I{;@>oj!-a3- z@2>)hQS>P{nI;F;K-x@y6JNzfKjYZe6crt+_|@Fk@xI>l{8e;6j^h0J%mUzQIbgm# znd8m|9d1u->uc#2x8;fSaPeHbV87aRM9XvfL^i|4W}vEVitcDs2I82vR-WO@$Ce^i&s1K% zbZ5c&RO{A>05?S3xnl|xA4gDFc(wn%7xOuggoX?+GtSMxqgNSEQWfY|5Zzd%Yv-6C zY{^Gkj{UpPM+dIo2VSFM{_EpeVDRe7r~&7k#sVST3P|W=bXZU@P&Ith|}vk{vFY*xtx{I;EVKSPS6Tk(Zw@dB|43(Vy}1_#<8S0;{53E1KymPuI$0JYNM-`V3Qj&^G5gQ=6~m z)*8C}amiV#><#9Mv??nQ@5wx_J~0}gUhd>~-CM|!2#gcmc^?>(s4-sK`iD4WwBc;Q zJC8C&&1H#sk8<08R5Yd93G3zR#!@o2-A)~n6^?mRRyAh~0ZI&eCVqxyIT#|jOeqN3<2pq&B0_?m0Ee8@s~P=hoZP~FT-{^?#*3OlnEqcI<~ zD~#pYimNoGgM2YEuLW?8rD_4pRhQjpeMy58e-D>f=1`E7HxK>NYA^^SZuTOnD=yd* z@mu~S%Y`UV4_W&+W0GP%x`P^3=QOUcYCqCpM4GU4JvdDW#Z>k-1yGo?T)HvfLJd7b zQ(;4Q?s+nDkpFE>BmO18#CVro2)JWu3SejC>64O2js|=~$L*19@ZCt&q@pry6$fnn zs8zt^7JBKBUZk>0Q^|l~K>Q5nL_EG~7EpFNB2A^J|F%~Ot!46MHnkoPA~cmP!$9%b z23E9UsNaD*5}v9netWCxto=JKQEc#z3+NtgMycg5k1K!bxaQ3)*l>iW2=8}nS`JJb ztn^SO0)~|W$Gq`}BL!d5CmA#QMF6!n^4G*?U>(J#{=&{paqv3etdZ7wdYue`0Gz}{ zb@V0((ET8O9T(ug+)(=I0z<~8k$!r`cvK?ds$T`==XSRaOSJO)ISAd2A z8@rxQ0%++79g*fzI4>Pg{u`fvjosWE!*s;AoVrWeb3Jg`FgXhAo|qaDwW7fZ1ct63 zW7~J#SAa{gFmexQw7P)#LQy4#2WRZ`+YOLYRZ`#|G8swLI~vSRSakptL^A$;0vJ$} zn4GK7y{X}+ZmnQP80q?+(FM#m_9*2lp$W9FqpMpxB4+@F@m@UadUBY>`JCxB;%s%Z zJq&ES6d||G33mdsqeg{JLY&s^cE|O~uuQsnrf10HP#zf#MA;L?OlRaHe4Sh}G-`||teX9Io19#*Bsb~_6P=V6ep&$S2L8=bL znI9r)Q#y+^zpi*(A@I17Ahz`ySZaEJ#c41pQ7q3z7ozp-bt%Tc?BUZ;7O zt-B1OYNGv>5DTHy024xmvIaRL%-Wx`LrP6Pc^P9@c;azuJ3To&GfJJXJ0Km~K zIdw;QqQyw7Qe_Ohu3E${+^un~1i?L5LA8g!`7VqEkTr>v0QN+5%>yDRUQvb zxw=*bbJ_L_o!ev=DA)iehqJ$4$HUZ7CQ;R5WOnZ_-2$=vaSJcJm_m-~mO^r{I-vCY zJ?sH^SAH%H(8p@rpioPfpIgp>gV4&1vHX(`iqv~;16qTK&Rp>Ro^vs+8 zmgyyYay|=XysZ@L?@b^N%C*#>6$I2k{LFrKicf!0qA^Emy;B*~ed`c!5YiuZ=yeQ3 z^{cOQ*c!;?8d`4y6551&rY>m3bx0+qO=*u%@^Uul<~h9 z5N8G8{BW>1QD_Zw1!CcX9Hs76sxST(g54x`6bTye@{`FKbyOSLp z(wYOwUQg;Nq52z2p26DuKtXNm5Zo74==uqwO4Fk)DwVK^X(u1_L#hdHD)fVF)|+M; zoLIn-7Qto)TwChukC~~FoE`yc`Ii5Lx_+UMHgC=A&7S&g;Dz{2g#uhfUm#Yg8Epfz zKaVJO`BQ`R)z_u~Pdp~h+S3ZOb zG2+jAzOk5_%Hh3Iu!Qt#VFEd)&C<_LKp(xXGm9EDzWk+ATN(WP{r1u;{hB`TB4H#+Fy8!xUS#_DHxf=P?7k+3av7a79#r$^Kh;fKl zI6bHVbITsNOj0XvXox#>;5>(Qg3bVVE!%RxS{39NkoYwSeR*&d&=7!+m4vysJ7ixu zMiTjF5_JwZ4`hS6E}3L4{L}`ak!{Or!QUwQJ9~)M$YIa&BPBErUj@)Wxx-B;Vp88H zr?|OOaylWxFD=Y%o?KxwSRya|EL`UXoqwpru*o9rT6_ykZgwKUuYO!dwdW+bSLjri{doO4KLoRv8MkN?Yf^+d($-)*#K5snA&0SSyHh`u$>UJx=#}D+8HR_QS$J zvqc=@@Y|UJ>BSwzIVQgj3Osz33ThS>PU*Y#L&xI)lUwRR*^r_SVZCH~q~N!DMe$o$ z{Ht(4Vi$}_n(PxzQy}FO2mNt}0a~`!vL=LgNGrJ4VS&v1!;V!(@NK(J5sk0S*j<;; zQszuq^pl{0W;4usqXJ>c@O4P9@lf;C3{K~6&#z*|k)r#8936eAPVK4U)iR{W+VZH$-<^1#>}bwLmBY^$b`lvpmry*=)x472I@2 zm%F2L%SnbfU4`9kx^C(foNpgADP13TP1<26IYc(DpIyYSz)qGyCGxd&_ZpFqYifa5V zzC&6+M&=(g{6ci8huXeBk4z1+t6Sj|ZHi;(UQDyU*A`73oYI`QSf`GC?&9=*3y~(1 z0wcS*0>vN(9i1B^-jXJYB@32lh3{%;(7(Cu|5$dZ0TBUC;{gsRQ>86(sKfGj6D!5{ z(ceBdeHm10tR2AHNYU4T5FsBV3*}pAKwLB<7wfzd4#!}@IkGnAX3St-J)K8IYdI4_ zITlPKCq~-ghf(utpk`UjZMlG$bMvxWRf9sJ2(`Z+cf>{Ry$psNi3)#wa{98`f@dt% z_(9e`=Fg9^O%tG@tMSViYD2kMB4Tf+S@es%lql2)03N(bsySPi%|PmY5`~&a6_hr& zC)Qfl@7Xw~8SHu-_PD`5zbapO8Ljr%!q7kghMzZpGi?2h%w9(KdPUFsTfv435dg)~ zpyB5Dpm|6qNP#NTbeXIlMt>y-4k;Ea;Gqwq{!I;=7yr7GLSZ^_hg~|jNnYBVy`9QI zhmq3%gguc?_(e0~p#2N)9KSXb(GQW)MRxpe$L8xzZ^K0RX2FoCn2l zmHfUY0f=4w8Rm%$IpY4d9*Kv))U;5T8$uIK)W1su~UEiE1 zY$lVxm)gz(7K3)Gp=qrI&KGpn544*gWPf?Mtv^IRQp<*pfN9YLM60m*#j+{xTbEe= ztGdkukB0dz*yxjsP4Art&;V6ti+g3`6M*zGdOOCL&WtZ|KAP~YS*VO>;dDR*rZY!Y zd{7ZQ4(Ncl8A+P8!QVuX;v+qSjKg!X)HPidT9x{ZxG~@xaV<2~?`}+RV&c7jZvqJ9 z4u4?X&kL(xEtn#9mcfBfNT2H7gP0+G@*J-6cYWBQ)X?gRnFp}AWK1)uIE_S< zP+l}+J^pY3#87Bm*u!pT#In9a+9Q+Sw{kU=zjx(G7wd3v?}1R8elb25JmB2K)9=uf znq;o>ZHXPe5#q%#EI`B^0NTvztw#<3P3WZ^!x3GPX<%5OYD5W7Lo91ojvq#T;=DL* zrw7DqKfj~^s>%I2lE3O!0AOi?n3jK#6+sd#{pTbABp)nX$bzvvCdBp!-&%34N_jOi&~@5IFxA-NBEU`-8S_Lqh=nICFObOZylf3o+_Ox(h5A1;Wk zxIY${H44tZ9?7Dvy3Lq!7*K$8#*<1+dd1Mc4*SY@%_GP0v4tq;gr^I* z%|2N%jpy9Klxqf&MhE=Pf=fHy3Vps+7hnhwU5pJvdMD(syr}^`jU}|K;5%mo%eA&yB%;hw`jb0<2BCW>0@Y0^ZNle37IZb2D1Z_ z1KtUzgPbSd={N8VXA7>(zJY`X>p%Y#Tfa+qeuGLv#T&AeZO`&}JB)QmO*W?o@h}!T z(8bjZ|Jt75@MzAydz{yFe;36cM}8pILMm4`HI;m&G>=k;z5px+GMTjlaXG+#9{sSw zK%%%O5$OF&k=SxWDbF%vt#vxg0q3jAmRk_vTfmv+ZdcemQ!zd{;>Asuo`yK+({&CI zZN+c#`lvo4Bqj(|t3;9c7mgs+F#6lXBu9D27tO`9^#8}hD?B7+RO}5W+<-!#X;P+U3llpQ!q;f`ECAm-HicR`s# zfFhNdO5OE)XdPLXte!!ThFBqvaN4K<&V!L#=4s1)<#xZT(Y(Q=$(+tQV9~}~J(Otd&rcG7W`}8{2%4PwMACpXDOI6^b$nj|M~&>H+>V>WE=D zSG)*zG~Tb#Sp%~bqdmS)cU!4D)b6EtAv%6x)q-mMk$@NXGmvs= z7P97aKYnbf)mVA{IQDtaXp?Y9gX2ZuCB>s~$fAF3OyAt*ms@|Ikws^-9>4O=!9$R8 z;0^#{{Vuo)kjL&-FH#N#SCmepE!Dl7b*c{@vj9}_ zNh>`Av1tyM0*PQ+CRaPN&E%Oov7Is%447-%sPhFAta@(cX?^wl#>p|gp4f`*B>`yX z+wO{fsXUTTNMPVhfQYU)XO?6!tewGJ58=1?QFOTG8o=fVanCGdMIx#^(d;@05{-lo zy~QDQ&gh2`>`0LdPCcQMI%i)grW zK=wSv={YCu@mu2qYKHCDnFeP;mWBl!w`_o#G0otV-;O#hIo%`4$!n(dwI7t86TmQ5 zMIkQ{6#WMab013)P9N%HAom~rCl#A;amosW9KkJKB5vRm+B(1_@TQh;BV5~N-^>d1 z(7h-JWxRjgVeJ(`#5*sn8hZc>cd_48p5=ugUAdth6<9i@^_)+#{dv#{;wm`Veeo0? zx1#_H8_KZp&m>e<4SX{?%Du`3TW|SRq@sM&#d1eeGy%xCyx^$h} znbRMQpImx;4$1UNW)UI%cyU!El6*bGP=9KnMHegVWAJ$aq=5NCnj1?t-%0bTgV8|i z%9D{}yz0m%>Yn;RAo8Wn9{M0q*x(s@*EzG)3+NYF%-qTVM4XNGF+D`@GI3X*TE8gvL{6M_!7_e3t&QtzP$D z5Wuz}$Rh9ry1@%5)Y?YQ&A_c-6?xL9=0Rf&^%T5NFwof12!7kn;hrpuET#XCiaXn6 z3g=k>NF6sHL_K~SgJ1TNido4tAb=IEc{KtrMI#7`*Q$?%!vSd4uL^+PG;21m$4<=P zT02!8{bS2`L0n%`YmXKMTSK5HmGAwm)_XE{8}CFBz|j3ZIHj~0PD{P%1Nw`(zw5=R z&qxKGj_gB&8O!iE+K?;}=kAZU1Uw2F=wCQAx*;6C0>Rl50p?fY-4R_Ax! zeB|jYVw|ay_v)5-YTuW+-5PKBh9(fx+H}bu>fsc;$B4qf5S-Tt|H!k>A@+8OY|@CIO->q0yPkKRTV) zTEN?ysKD&t+5C8PBd_%MF{Vq{oEixRdT!QN6RV!N_+3LI?N_7-Z(7$JBkCVpv!#b1 z-L`_qhKAp>x(&Yx*uVWzrP3%1G=U#4uJ|O|ZpGkH<_ZlkP+3u`;q1zk(5DRCI|fg*M`TN%m{NjE-AU?DwjR1>|N zFZ%e-&F-hDo@@=EG!smtHz)b8N$evB;mHN7m_rM!9{mth8tlMk4vYtE`0G8Ut>R@d zNaTyHh6*;eQSQBOEWQKc${5OY$>c$_VZ|>84i{|9$Jn0p^?(O++N!1_?UXGF(pB7f zO;_DDwMVJom}q-g_zg}nyV>#*v8GrVZ|7?Szn=ehcG(UbRlbj7P1k3 z5aGal*NS|u{9+M@%oAi@UEbuZc;d$d@3-rGt0?(7adrd?f)oD=i<)fOQ!f-?auOfE zZikiVbV0<+70U1#QM~1UztY@2$~{fw53|#HyJ*N0Ci0lreO_6OyhT9Dd0Z26>1NKt zHXV*1rVPgHL}XMn_T($`Dtvf*qqv~@xSsq`QLJMcm&=MZhH^;XrM0RjTj6516b@ro)U&N3fFe;o&cCRpz5Pw3 zRmqQ{2GT%3_7BdVUavedjn@vt@%T{MIa+@n8_sRIY(lPc6*- zFr)x&LxmbD^o>a7inMl8@^Du{p)Kq__rO4nY(Gm-eZCAzB0~X70A8CkyG8)u_-{RU6erTl)%W z9>sQ*J_qjy%`iUpMA1qDhJf*$a8jeX9=+({jJPzi6hXIid)l~MzbTIef z8N=^^f_znLJ|gtf`dGY=!AC{$uGOkm89-Ws8iAsv-=sDCV59`ph{CTFM4_k5@)${B zRZWid{cVr+uq?nsJ!^l|C@-o>KI#a_JOppcQ`Q&tiLntbY3wn|ej3=UL~v`~Wl3 zif$-HNDx~bGYBn;=kifp4&_?6Ecl|uv()B&10&W}8toj}J7q*}JEhj!MI>_HCPR&r z2nV0?&ouM|E~yPB7y4Vs{e6ZsSrNZd%_0Z6s}K*;!m$}5p$V%7P@{u|w0CoN7BvE+U1&xnd8cUw89+bzK|a^e6JIt z%r$BTK6@@gj`+0A@h!ug)%#1fk98LLpG$utGjG<_O6I?RX;JHH!u%DbZ z|K{o^`U9Ji%7}4(>TEdngTxJ+#C5GPn*2yt5F~uk$Ug--MAgOw7f8zpTy}f-CQ$?y zwO2Bb!fCP-n~MD55aFME=Bp7+(8G9A#hh5+g1(jG-{;IKIH8IkV8Y|-Hz8EfS6gq# zs_@ec^e?bjrk2*8kE0U96tc^6h@+J*d$-)xY~{1IO!xhZet=UvqI9@Jvs*Rscx4a2 zN~X#>ZuFV_0AgkhO7D{LO#V}p?ZXGXN*JObw?H@7(@R!GC3nC0sX*%~2@HDn?9 zq-WJFI?Ti`S*<6Wo{NxH`D3f1!Qq5UFB@rSF1Gaut@${dKdMmRvY{))z8^*9#1ZT` z^CYHNJ#O7!m|2_y*h^cGsQC=F>E<0?PkX1+S|pduU;Yc z;24B(@*Q!ww~mTDKWymDJtpGz;W-fPwCdWmn7Zy9pF><@#6;$b9U6ZeD_;?hBk4ML zY5-I8*^m*0x1=A%(ooc#-xwYt-(o>5jY7{8;2M9wY6vb zpk)RSWQ^dRsEdKr#=>X{xI0oiUE;qi9cT!RLu?^}i2XVdEpm0$!;s536uDGaIzH77E5j zwgLwW^?+bPp%;X78%4mJ`LNFsNAAYu3cg`Z7>;Yvk6RReOVnK1mh>gv^5I$^I$doRHrDvAdvk*W;C(+g`u3 zUjJ6~=^!oh;};p|{hK~~|8cr#v=hl?pOfzh?GH{?G)4@xw7jl68SX3oP0Ma_dv5Fo zga_>m)n(?`?U%EbEUrZ`<(UTioTZaN)%y3_ovf@;e$=do zEKP|^MzCLAH3AeY>H8u*a5S73syEctqP@ss6LraKrC!=uHG<)vA7LXY95h>tY`$ex zRWt-qg+2mqnM0&|^K(}VN>Ts5fs;)R)1xyxI(${mCvRLLlx?@;g$_mZ>UDP)VK2 zZMzl^GslO=s2!t8+pf3Q8c8z9O0duIH%wAcSib`*I)X*Q9KD?`+?rp^=uRm;NfY202G6h-1}tg<~QD6Y4#EC)v~2PxLU?~G8q$hr=GxnUhaxvqh>(z zky%^V-}}fhi*H<;$lFfA3LIlo--0sSh~g;V`uivSz}jAZIrGgrWpHRmWiOs_h&Xr! zq+mBp0=hy_6(I~CdS|&XOev{Z(V8s7Sh@7f&6SWP- zkKGH*+_x4zF8TVSo2MKt674$9tg=6L_zU=7Fuxrog%#3=uVqrI=ODHqRk8TYL15Ao(dSS&!pG=_r&6BdaukcEZpE$h>z|{Q>VLX5;`O*2$S&J(|7x4ZcPh0rtwFt z<<06IO==T}+iof1u3haLUT>dI<{MCxs?m|9N1kQ>EtL*oHYgsklL?StF$)MM6gXGO z-{oZIr*zfUGh1aYXMXr(SIJ!APG>gG=$`KdR63eV{ZJwC1& zoZqYy@xXeL3fY!bZ9jZA9k3gNoSe-cc0T41WpxZDJZ8MU=O?_tf_hEu@-txrsdgh- zRuXTsPq7fU%S=2@=)PTo((lBe>iRf!71 zH8|^f4{M1gGCsHchULok8s*z}7lYl-!<^}f)f(3E4Kv>3yrxxzHn9KkSoHFGS7Fhd z`(sC2;L&*}Gvgun(o)|S{<1Nq^*HM(agh4fLGb-{rbz7fGT+@+`L{QQ!_>2drk{ag zBBmRRjsis*DcgSsHibFyx^!8Hj|ARsEbw+?b0D|{Ps|oxx{Xz?7xf+M(^l|ytoM!1 zx0Pe={*2mO7jCGRO_|?q>ZX)e21NV6;4uogA$44s+|Os(brd0<;I29`rR#EF@@zb!iw2LmKfSbt;976k%0X+lP43vTU} zvSN5MB^|GhW(Izdt0!N24o6^*J=xeOd-&=~IK*pd;WYI&wqs1eZeLKb_35HPe&?9F z>C){9@8@Z(B@iv>KH7R|PRn?4gm&q46{2k)oO(zCk*t7nLyqDN|8B8UaErc*C7{g> ziEuaLJ~NSY_a1M^k!PMj!7JY>i*Sl=dA&&{2E0;4xR?SL>H1PvHWSeS=e|0qB#(8p zrg{KXWj06%)^>ksvDQ~e7_a4_V3^_aLepMpPM5JMZG~-!F~E6^xh_>b53U-XV;z|} zKF1;Ll;rF(LG72h33N_U=*Ec%JiK!AfZllW?fZ z;MWy(wS^7hq0TWZuj+RC(hcYPF6uJr&CSd`5!eyy%`LA!%Ne**-ut2!NC~*r-Om&M zbf z1{nUoJ_;rqo3ail_>WySjTlC^1>Hy`RG8TC_~Wfw28F5XE9 ze8{X|-%2L<2|@5~H|Y^ZtsGyT*`js4eLuuw7Rk2PK!wlbO)1QK9s*EO=QmdDp0w7j zz$pEt$}g?a)&<67ppjg);sBXci_V3_!rRZk;GD5Gv_b7)!Y90}-jx(hXF zA~ptTCUwTh>M5_v%QGoRJzt15rS=H)s)J_ksT~-o1Z2bE)zUL&g@d3*dxgeYV;=wc zPVT|P;{o*r)nzo`;OnVZBpY9ecqkuO767whtcpwrY`tHxjb82~F^(Km{sU+L5eTg} z$!zIxkp~t(GM-qkd8qNJdjcSm7(-1OCSWd#f5Al$2`0XA%rKa!lDmdQYMz;R^pdY$ds1SZ#!%sbB zJW2^ngQdfpq$n@mVE{vpH~7mpOFW@Iw4CRxAusF2htY0?DUm+723h}pvkDCHDlOEf zbF_T~wK)`4uJYZ0J@3TpwOQEc*S*rhW#(Y)2oc)J^7rG1{6v-P8*hE};ZJth6Xx!` z(AVd7RD4#vjVUFOjI4W{ZW*E@JL$8zLsDpB-MB7&*Z@dtjp=Y=jm-kPJqkV>PNUsf zV+iWn`R&J&6)E~rHGVVnFAe0RSJP#b&%0>%N#@X*`5$1zk?ZDOEcpRKC#Fc0)2j4tCkjSXYP%HUT zAE?X>1Xg(|M-)vvN)%~6re9S&f0Ooi&GWg)+61?d`t_T*cd-~qNkhCxw|Pk24Ll#% zb`qrZ4;!Lyp8aKcqn$G#t*#|H{?uv%m_oPr&%tV}lVM<2Th%$=kxy@3$MSZD4D4va!w%6D;)(M<>E6-4(W9-5h(~HFD|C{%MGgj*h3&AACSn9l%86 z-GjPH_8>C8=2d*8aEtSQKKCQ(+#WS47fJcp=DU9GB!64b>UL`HV=t6+hl6&X(cI*H z(bARgdOmzM%Ypur!(HTk`7ecAH*cdX-&>-_n)_CrPHo+0?cEw^%`U6DxmChuyn+)^>QXxQp&L_CSDjqOmIR1! zz{_IjoOZIcD7)EfQn~8Ef;Ax*U=ZOnSNMyuJdJ_WTQ6=;89oSt) zFBl-VyrOjC0ZQ<|vAQrblAvimaYsPY#rj&$xroNKtHKM0_j&C>e4~)2Y`nu7NB{i` z3E4>`g^#03*ag7}sB*f7n3#yUM`HfU8SzxxWK~+b2<;c`FJTMCxm6(WQ6*?|-J$Y& zp!sZRs|@gF=qk^W@A$IaQrpuv&*VvJs*BRX;g{8jNubdS67%7cqlhB1z$Zl#*l?G*dCKb5)o?-{;6N$QwYP7K41GdlsKqoA$? zU93^)PF%E~T>5h+!eurkci|CyB%$moL%^N2uA&|E!&b0@Az!W^E$-JO=ch`@OYd78 zN@%eG<=J1fnR?>&Kyp5knr=Sba-MlN}rr0s9o6j9T9A(glgug=c6dL z7CNk%f_?Ia0#)w(xdD6jCsuIJs2d4KuaS`wIw zcBM6EQ4WVR^h6zwtxc`@;(^wl-tOaG=vz1XCJ^QX3thSTmcNzUR$IwZqD;q2kpLgT zqG1{7D}x@zUyt2xZViTz9mf$=2Q& zN*k6a-Ly1_a>?Y-=g_iHJg|YuHK~jfzTY<_i$(9^Kt)jqv+h&Jcj-czM9MTNOB}1+ zG;_Z*M?bxk3()I@PWiSuDW3_v99&bm86GoK5!gzMEgCLpzw}ZT#Kj}oUQhB7SgE{n zsbXinqjuNA_O$TB?bb7?T?20Bu8ZmgNAJVvROcVPOad@pZmt~Yx8 z$FI2WgVYW`@^GlnLVjwI(a^wTP6eohIhzWd6xrAjryvyiiEJ?=xEQ*<8ban_ z5vY1+$urekUguZ}YwODy5XF9&4z;fkuqwcf;i|^oy55~PkWrJ>P-B`Y^{lzwyJ!p8 zi9A|}W@WL`=5T+5)47NlGOfW>;z#4H{56-gkd;@R#$K5rGw1y;Z!M@WYQ*A8&y9p6 z>9WLoSn;>`4)@lVRaqD3v63w*OW^q9UASrzPl%bc-;DuCrMn}VR47C(?Q zoD-WpoDV$eOBycgxPnJ4ktm2m`Qkf1(+Z0yRy(x5t|n&7*s$H=>CBkhQT9qhy+b(4 z_@{y_Jh0$vgv90_q0kkfg~EwZ##K5wENf!jWZjLq*vF@W-||KRg-pRkkK%P}52a$% znXH2fFoB>hEjrwSIBKx_;Tyk>@=qkg5~Px)pI68toQO66F+Fxl6rGJ(t`BnJ^j`_! zU6`!gJ9=kmTN*8s3y4#?uy~aUh@(g9QUz2=ob~1qA(qn4P481mG^8wEP^xTsh{#)n zh*sPr8uj~-hWD;G8n)ofhQni$>!zzUj=|^(1_zC*Rzn6`A#HF`GWO^z9M3~*D~5!h z?h$LwIG*N5Ji?d#$UKF|TJL{9ur6ZH$=%`Vz;_Pq+|$$TF}2{2Tf|T2;jQ3X`54R` zEHGUTk3S%e68^+-ae)-YiS7^rs_i!pkf&O`?;&Jn%W16tjt;B{K@Xo;(Z8H5uwoeV0S|pD@eJU0 z{=1VDxSv+SY~w0a#o;6waS~1D=N|{0u#ahzZdn?ySekDEL9NbmGTp5(W(0fB7#%mO z-#)S(2;w%{Dx_cYV5R3@ak*sdwJXw9#_3^+IDLP|fj5ui<_J-0-ugHHdBN&5f@jzL zA|7|O>JPWnmyN4vOCp-nC=U3nbzrw5ZZ-_7G*SYn9?4o7qhHSIo9_6?41U!FdEXZx zA`VX&3@VJN#bYMHUq^lHs0D(4#Zd#ngQ?WdN?hEd>y&`|1#DQ&@NG!N;Xd+_&_owa*rNm?N~u$UMSpaCviwzkneAi9IJUvdSjOQ zLCn>@Fj3|${a<~ymxj_F#{nB3yRPy8#P1U%_i;^3O#ciMrvVvw$Kr{>if4qa9`mP_ ztOJsC)6cm}iiyB+BRs*oJ8y<;Nz?fZm(Fa(dky=EwV<$AY=dy72(o1sZ^Cdf_tF_z zzl1^Uk1@4$7i-qt=h5`1Y*8+%h@Bjrnr!VYlWAcR+Qh(DM6FoKeQ_Bd{40Z(eYA6_ z=*TuGZ)TWG9%$qewK^Q1^vVzde4r0anCcUhXl*nB**rj$?!8Q;r?PniK6cSS`_^p_ zI$(^HB@`dg#%rvaV^2Md$V}%YO=d@xZwh^6&7@n0YM2Ejn}QCUW|+^sX@L+;QA?A7 zcdflL^(XhzmUEs)aMKX5!ukh0aOZ){+}c??K>U#w@xig z_F7$lPZHU43WV!ZYfHKW$4>SpV4Ch$RDM~f1Ez`V&KNuH7C=kxc>UvX2FAI56CPlt z%m)V&t5&>jLola!Y72rtL^S;m8Do6Z_#*^?$~+u?#JK)y@ef2D~|kLcnQ zY#-{T<*yNWN<>4#0lmn)`w|Z; zi;2?aBJ^P>t$alLoW+GOs2i!#;Fz^$4XL9m(N9Zp*0gJ$IwesCY?2-DvQ0r-c_deN zHs5}bg@G)A%E=2#XGp;G#+nOo*_0_!yDD8}KS%~?DxntsHQ0q>%d@b#z}Qn_XVd#h zWYXQ0dikg!!x_A`IiJhE8ezNKspib}D)WkZRy_? zpwCnNTU!!GdGJ$uTPoY>PBjMPW@P4FaSw~*G^l*iW4jQ}Zon7Ns??`kQRBXT3}ZO6 z{9-pFaNvmXbuKeYkiijDtflot<;SgFI-F-L*xDrh|&J>WE(l7%eR5{%Mqq}lv2Krqz@|dv;VtWTvBHgfFGuS5P<|nGx z9dRx!PN9CW4c{4tVim@8m7`>uOO6&W%PSrx!=+0(hDX$mzZJ4OJlb3T?hzgTIFs4$ z;d`Nabf6Z{X{HF@5mJ@U17^ntnMnOS+EMEORwNCiAxp;A{DegqV4=e=S*9>RBQbwZ zKzrp{%iR_3L}lUrM1@N!13S3-fWq|q)x+#{17HA^8o7xB!kVe>+*;KBv#{+)txz?< zf(@|9zl#8rUU7R82Ib2T?F!(SJ)PQZl5pLA9O@W+`88^tFm4bPi_WB0N^57;WX8N$ zx8*q)yzFCGO478Ua7iTddEfCC*NW?J+ku|y zm`i&E^ian2p-)swj#7ao7pc4~z+m@esyiSG@kY>STBM*NCD}&Dm{u>h9L3Qy1FpL_ zzwF|mC$_*Vm|yPr-OI3?7XI7C9<^;bm6D9{tQ~lw)q}6|NAi_o!_IFYAe!yvioV8m ztGwGUw2}ybiUvwc3Uo}Cet?^NUF=UoZ1|pG?_Q>ORsEnPFf?7eNM;JJa{T@{sD^f| zNRY+2E-Zap_Cj3Sx(hkhv&}spuW12%eo-dT)Q3|RA+nPo233UCD2#a2x;Rub%Bs@S z$hBgA!$+o_Rj_B_Ujm(`o9^OE_=#(X0`!0EXwW|P8!hKAaPlLWolOW(<>7sCQHn!s zIKzhe;)*xl_B`u)ZhLmP2gY{QO%O&7{~Q2#+OmQf80Ok6IGu2}1E!a|%AFiLWQjxi zfv4yyhdYcEf4vAY^>4}fVgT9~9VP+O<(#bW`F$VlPZI$i<;a;Hg`TRO1z8)9N_%kt zCCnw>9a3rw9x>$H&}TW(g}76hP()S$6G{zymtPbqJ8>_X!G5l@!$?H?(R*NWvM`ug z>scH@V}x)7PK2?cKM0QK%wP6km;(Ri-MMTcF1l(bgU3TIZVAwvZ1rALXfNenzSQHR zEy02pe-cKA0SV`%2C!~-e=Z-mVST+9j?9(p*OV#&Zvv);b zPgbPq$=olkZsj-Uq~+aFkNk&aA7RtQ9;KLXb?3FoOC(>6?)6COZ9&>(oW}X9Gz3sg z*c?w1*1UFyLNVzvd1VxvIz*Op&O1KR&m;17$c}CeaC&AZRKE5QQL3d6gonO9#$=_; zUWes5QWN~|RSnf*J+?FR971#^)8mcDMUs^SBYNn$o(Lk+q@ht~dlY@0i?9r_%E>)g z%WOC>55izF$6Ia;d)~tzRXfe1+~XWTU|#P3SIqzdPks%= zQcsB9zYV&J1DL_w&;W7PAYcr-%2R~OF4&%?l>lcOK<0^PCOq(bbda;{smkx8w$)Ta ziLDQzu+a*mRmLXUjx*sv~6kB3$fY)qv-_SvdDvwU_|EZQ?3MC%bp`gO89?pAI! z**SK02(qGLOErTJV9n2~U#C!GjXL#|_byoiEc9J-i?F(b&1erE!zpeQ51u{NL##)A zacy=OEbQZYS<6=B$CE$|ho)Nm+~|tW@;;fYVcZl?@UwZ@rUjg(4#qXp{WB>Fnzbd} zuF0++^eK$_b4Q$=@%5))PsK0@CXW)nR?}Ch4%A&q>voxwpI?^aO9mr%%)8`wClSje zJ$3bOv9y+e;-6SBPq-CO#PQpEVyC3nVoWVuWhLBv%SR@Ymu9R{rCbkflb>9Nc5x~H zA8GT|T;<5SWSC5(F>rl9#;$wFsfcrx_7c|q(|^hLscdD;R%qq5Qk0jA#=2YGw%}s9 zc@^FjGyZ@z8?sj!O zJe!Bd^WE~wg~=!Zqw+hIGA}@KgzLbb(uVrD#J)H|v;gZ0^FJb>Z}*vwgv z+|DV}0vC0IUb-SfThl&ATTa=d&3kTgcb`nZ0WBvWayG@|Tb)y|cpuv>>n{7y z?)8<_wm|-DxkhXnwi^*kE^@4jC%CxSetRo%^lC~pfJ3nU^8ezJ5Yszjgq5l7NMjD! ziQNzKxP>FF)Ni(I-z{v@YaaoHDcF@%37$ew0Bkh}s;-2c@vlDFwojD?%A}s)F?AH7 zZmRgwtO6~P2l+a2<<+o@>p`EN7w9T4VTFF1(k0nY@qrW`r4ubRPQK<$18i{C*i6_T zk`C)yGA~|4A{Kzaucv7uN_UdoJqX#v0SOt}<}% zCq9%#wpe35rp(Jndk_K;saNV+lr~~ePAKa^7SZ{de(O24be?<7@1r*`nF?Cxuf@ z`ugLG$i^%cuDk~bL|>+^tN`)DPs#je1{BEj9q&5dfOi~$dGMYFD- z+338gaQrGWv4Ul7tR^AKf~W*V(KnNZQV&P(Qykt? zLb*}6QE{Xprsio^i)i%q075n|L#$2z>CC9vX@=H!C6EZ=G+qqWjT#(OzOWKj)0}^| zyrBfKknujX{3vc|pbB7921T@+<4+Pi;_V0Js3HZDlW9GI9L|xjp;POr0pcx+^4xno z9ic3ot-!k%BD5Zcz`$}9ga>Ocy2e=m8V|Ig`J7jX3^Djvsrf5LHS=YQ+X)!By16i6 zZNv(Y-$`tsFC6h{7oIB3CsR4y2FL616Tne?GSXqs+LW13i&~y*csq2^P47@Y`SK&a z4r6xktgkEgc+m@Rdn8QagrQE2oJt)GwYQeOqC%4NJ9ZUp-XY&(>lD8DFtB^77I8Lz*eS z{xR9?=>K4{NUY0b_-PhN33nlFN3xLEAE|80KcqXv*G9{DiOHQ8q^a5j-G9tYv~#d7XpP?5j_VsMpEwY~i&Ftb;N!?ZBxNUL**FRM zjMM5JP>CGVb?XVqe=%Wkqu!bLG88^gym?oVazSq`@?-jcQ{nd0%)2>&T7NIJc5BB9 zpXSny7X5xD;}E5}KI+6XOz~HfO1&6*Y2&Vvis4Jz*ieyjv zRDsbSqS1F#sAO>EsUsGsFbvhxw)*|()irh8)(th<^Y{Avv|J%hAGvfDH1`XIll~x3 znWWdHNPg7Li$lbiF)mT6qyjlNu;V)v#COIpX){N1K-GH?B_WTcD23u&rlhp5JOX5g zJgteAhvubHO;?#p*KE?D7g$@30rcB{{T=kZ)CEdQ#Y`e`py5H#HCUEaD2u>6Z0pdCo>yVkv~UNGsjQwD3&wawS`&y z%=kzk=Ez63K|phM;4Ou8U3oi9d~mGY$NgJ+*SsA0C^l?z@`@?c0_fH_IiE${k}3FP z(>)trt)W!GMIHC^IM`ERj+$;73{}^b-_tQL?SCGH(PU;&Hf(dq{Meqt-nvFvT2P;) zzw;sQCAR>Fu${^`ffVe6u;)}AkVoLC zpWvrme199Z#5cPg#o_{e?F#0ao(7%`}qx8HoU>y$~b+7j-4ZwQ5U3l&-KkdmQB9%oy2!VYEa5YI(xG)mSG_Tey<*zi9av9Tw-~tOq zksA_zPe*N?7&>U#(`$j&4JK#(LuYts#vWb13tAFm^Dh5Jl(4ni%w67=!^EHVLEp4^ z(CYTt^NKiCiyGuQbDk&V%N43irP=r`1#smyL_#@GZqnR3*4=@-6XCe$DHtXOr8wY* zw(6Kjf6Xia`U=Qa1P1JUPqi)`DxFDHPqZSWaD!!V9p~Eksez-FxAhGNtfPwPA?2G+ zFQ{N@YVE_1RpK)+#fj#_brdYt=a(z@-tX6^JYES}R4;kCpF)s;f%-&#BssN9J0WcYov&{AxkKf>?X zNvPtj76GSeDceBIMNq$8I28a)9!i#TPBYie4^#BMyF3N|3EL3=3EM1LvN<2&6$i?o z@D>oB%~;)l(XU^(C4@8XDzLFZQ+vEW%u<#7<_x1(tOWHstm6z;XA9yq3sg2*z^^Q2 z17;(p%vat$f6`>F)g_KmCJC*6a)7Qt=t~_ud5-GFefCVCapgw!QX=2YbqPy^djF5v z{BP0N+cHbUaMXko_xL&&(69g)DI>4%B*wni2^`0orvSW&aYJLBm!xKVWN7bw=Tz3O zD@3w-e^^7iQq&`-eOmT<3Q6qpdJQh^ms|G69gIb`+KIv*@1$HUD~)a`Q-oM zV`7?6&U&WK>u&6Vj{P~hfeIEtbZ&HPBL zdJ@wMI-&uD-ilVN!WPQuO~^JlD1xOqNl@j{(pH!Vgi&^&_U@G)=|<(4^I ziYc0-M+D(rMFpib>W#aYU9C7$5ZZ2sX6}96S{q=yri+`?d|gzTWBQc)oWpA_QV$rb z1xxa|aI?4cL4<=EBG^NGp&dhguZ+6(C9id9I6{p{U}Ac10L(Zv#HvCS^tF&N{2-9Zd{FfMMk_zy=&(WM>u{7QJVX>Fr(yCUW%9MZ-J+!KQT z@S&y5o)YD3!~meS@N8DUH>lSeV!BryT#BcUe-J^iH0LEMI&-D~!BoZ@48K?{9M!@a zyTIRdI9CeJx_m_O13)wTgS92kN|-h9yA8#;JfwqrgA zV8++^?^+Qb0X5QT zx!jc;T-%d7!jIeOCgZFnTlGH_q{ENjA7P3YbOWP`5M=1DBTFioarv#Hs#Do}OyIkIH$nP(Y5+FD4J|{}221{gTG&`U z?AIeuJ<-PxT~M0FKTMaF#g~PkN4c*HTcYrz1EY)CDj!rd(A-g4vY7kBM%D_5O@7;2 z0e;{)Ax>J1Pi@gnAqmYO9nS1jOf)Mc^E;oa6dXgH&O+t8Qfg;kvC)k2d5>@w7mz*r zKC-O;fyY(r$0i3Tiy#5iQXoAi3c4zQ(Y;^`Um;d$qHnPv7m3CZl9(=k5OY8`JsJ1= z@C{d1YH!9O;6$PSwwzre*oUVs`f4>-U&`g39{6TMttCrw_nV;Y%sW^95f_K(B5?xk z+M!26cCX5x0}HLVGWdPIVCt$>j78{71FTB_u+Yr3j@?4exctCk^=2QBV7C%7acg~J zaM98V1>desN`@=nod|fPrwbgxtZQsaIFEMU$XgM)c?eAT`@ZXfpw=48CN6UWhSw}) zK0*EO^ua}=)GVJpLd03u0PU8<0$k~$m-KGK=+#2|){$IuiFsb^in>bVUIiI&$VRdx zKYTJ3MQS-^mvFZY(`PV-YOBS1EzVej^6h}keOAVn!k=6J1Tw4x6fAMQv{4Z2dp8L zKfHI80+kO(w=)BXB6K+}6dw zb+qK_+L*u4nVL%RVvXY6!(&bSWi^xdp&9}|KzYqyakItn3@DtyYV(2P_Erg0o{WC4 zB~cv~S01XCRu!=yh2xnBC=P|2Lb?te#gjd4+}B;cx0XIP5f>~I<=*4hqm=xP?toUz zqkXjdGgh`SH5PFfCfU0^@qnK{Pg!jN5JobG?7wn4%0A+O9)C4g+Q!=hBOyhV;!p*c zLqzv0oFk5KjQV1;d=t(!c=5+&*c#X}ktl$k%cZXA76NxVZNiS8O#RGLvFK}cnLE1NM0m#%ky{ z-2vp?>c3r=TGt55Hqjr@U#oYIo>8?58Wxb*MJwRSfG(nxsx;SO&nKQ~HAG=-D*wzo zzoH!mT>zo)73ZA^eb#00hsp+gWNlBaw{PT?vJ?dlV=A(@?DJ~+ZEm3oO%-qvJm$c_ zSfW#m73jDaxRWA@(bK5p!bqh+L@FoZ%Y>|)thEP0dZDk0?>&B2-2$xh>ZcAU_Ig*& zPdEB32F?zjvn{6_k5XVV64e+BG9`n%zK0e-Z8^DHuAEuCd9?8!eXFKNbrAPa&BF3p z)lBJLIH0{Bn!eQFh?zk<}1>wyT(Z^0(TIJz9+-PvPQbcR|OIapUg5;gT?q zgwghQjc*!B>IaI%qJtlob2I1;zyNe!Oku$x{Lsp;3NVI7LBV_QK|8g-0PN z*ZYOrfj{##)omX7(0r(W3TKN|e6G@l{>WYey_XrmPHd%XV(E7EUiY^OM6DPS?v zcwg%H*oE!{e*Z=zWI8X5cf6>GFZuQT%yGb9ACF40WH@gSW3AMDw6Hzob>=+j!5Tof z>@vHeOrNN(E% zl(5v-YTu>m0!G}{H27HG1uSo#3 zu;Fprx9gh88FdpbUcT(jpf?pIB_-tdLqxa5U!jLm$`s|mc6K&4D=#J$Xtd3Khf)Ps z4QdLOIV>dO+!-lZLX7_)v%g^^1BGaRqb9lo%92hwbGNmi*f@YG;;jPy< zrj3)MqnzJdKac4X`$;$E<2P^Y*#-86H_o1ar4Tx_jjgh@%!DJ@pi9`Zv++Jv%Zv;$^s>*HT%`QI0>UHt|mWNM0av_&6e=8R-*Cd1tk=g!oDB_1FD%>2rHppysbwAA@! z%mYhIByFCnCcuxBX%~@^sWB*fV#lOf3ml?Ldv*WKRbt)D3wtJPqUGLLYDTNO(~FCf zSApE;xph(8XTMbT2e7;ay{5?bHoc6$-MFoXqGis}A>#oXCmorgcO*yq$lx2<{5$(D zc7IBL&7_WRFX-T9XJu8I=P}|%%DgU;RUrTYKjAU-OATS>*^LafrB-c@Q@JT`lcdI7 z$YpBGyMU?(-vs$g!D$@KGath?yce}R+@$61Z6>^10v=ur5Wnn=O;yCvNVGHmdohUk zX7JZz)7gU5tzp&sn^1+Ovf1m1o5x6+B;#1~i{KPeL z@A1{woITWLUhqQDRUM+c%~6e6bH-8R_Pe#UBzmy)tsu;6Ko!t$3_rZP#R@-^-BgF+ zk^TfdW{#BkdpQX2=*(%gEvPbvK?E+}X(@N~a6gX1)-o0SfqQ5l3ztjj7yqaI@Sl>W zGA}yEEkQIYvjO~x!H<(vsP61=wFP$88ddqMTlu|YHKlo4H4)cj;Vxsa4+>W(Iuiux zD(AYCh>XS$7Juf!e3Uy18_HB*qFG)L2t8n}qwe!$^<}A3bSGU4E^l>pketG=xFYb- zNCS^WqhsH{8UB!NGI6eeb z7FgZTx43@Yem7F_>Dm2(XD0In?aP5>9A|$@Y7G{Dg`Nj>qVg#uNJK$fXouJQ+;En#@BVj2Q<|El} zIPA|-_SLr&?eUg^&_(=HsC(|&Jv_fV>fhDo&#<5KRcoI~S*}_- zCesfUG$_oyg%6d0U2lWp3ap-J2j-jZ;!pGq=e@n_d(yfD8UwS>furlizJ_>=1(4Ec zf0IZGj%ylA0u^-cecWF>m#|VX6qq)Es&iD=hu~^IQa)AA^^nJpD^h14;1E^9Cs6Dr z0gd6Fwy$eJ2#4CB$|h9zC2m_y2ikE3{`PfO%a+ePY1s%J&~*5v5c$Z%9_aD9S1SU{ z0*ytt`IHn76Ij^(jKO#4K@m!#3PtTvm;BfQ^*oEVZYgm%>|t(t)Lu zjz{lYYNzF*x_rr&YRRb^>!V)SD@ip=jn86a{_PSFhyyvyT)>t1dit|u)coAc%%Eh{8=#>W2o$;+PoF-;1d7>Nlw_1*)w6D^6Chyu z@9yk;?N)>I$>M#yvol!e`=Q47L$1%Ab_aXYXn`jC#!Mdq`OS;2?hgnAYS7x(w~?%% xymEG*uAK#6z>=I + + + + + + +MakeBlock Drive Updated: src/MeLineFollower.h File Reference + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    + +
    MeLineFollower.h File Reference
    +
    +
    + +

    Header for for MeLineFollower.cpp module. +More...

    +
    #include <stdint.h>
    +#include <stdbool.h>
    +#include <Arduino.h>
    +#include "MeConfig.h"
    +#include "MePort.h"
    +
    +Include dependency graph for MeLineFollower.h:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +
    +This graph shows which files directly or indirectly include this file:
    +
    +
    + + + + + + + + + + + + + + + + + + + +
    +
    +

    Go to the source code of this file.

    + + + + + +

    +Classes

    class  MeLineFollower
     Driver for Me line follwer device. More...
     
    + + + + + + + + + +

    +Macros

    +#define S1_IN_S2_IN   (0x00)
     
    +#define S1_IN_S2_OUT   (0x01)
     
    +#define S1_OUT_S2_IN   (0x02)
     
    +#define S1_OUT_S2_OUT   (0x03)
     
    +

    Detailed Description

    +

    Header for for MeLineFollower.cpp module.

    +
    Author
    MakeBlock
    +
    Version
    V1.0.0
    +
    Date
    2015/09/07
    +
    Copyright
    This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    This file is a drive for Me line follwer device, It supports line follwer device V2.2 provided by the MakeBlock. The line follwer used Infrared Tube to Use infrared receiver and transmitter to detect the black line.
    +
    Method List:
    +
      +
    1. void MeLineFollower::setpin(uint8_t Sensor1,uint8_t Sensor2)
    2. +
    3. uint8_t MeLineFollower::readSensors(void)
    4. +
    5. bool MeLineFollower::readSensor1(void)
    6. +
    7. bool MeLineFollower::readSensor1(void)
    8. +
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    +Mark Yan         2015/09/07     1.0.0            Rebuild the old lib.
    +
    +
    +
    + + + + diff --git a/doc/html/_me_line_follower_8h.js b/doc/html/_me_line_follower_8h.js new file mode 100644 index 00000000..5d529b76 --- /dev/null +++ b/doc/html/_me_line_follower_8h.js @@ -0,0 +1,4 @@ +var _me_line_follower_8h = +[ + [ "MeLineFollower", "class_me_line_follower.html", "class_me_line_follower" ] +]; \ No newline at end of file diff --git a/doc/html/_me_line_follower_8h__dep__incl.map b/doc/html/_me_line_follower_8h__dep__incl.map new file mode 100644 index 00000000..ccffc944 --- /dev/null +++ b/doc/html/_me_line_follower_8h__dep__incl.map @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_line_follower_8h__dep__incl.md5 b/doc/html/_me_line_follower_8h__dep__incl.md5 new file mode 100644 index 00000000..81c29c8e --- /dev/null +++ b/doc/html/_me_line_follower_8h__dep__incl.md5 @@ -0,0 +1 @@ +6a1f2656c8001ed5207a8a8f7d139b17 \ No newline at end of file diff --git a/doc/html/_me_line_follower_8h__dep__incl.png b/doc/html/_me_line_follower_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..c4196f6479d826530b990644bdb8185f28e5d0fe GIT binary patch literal 14050 zcma*O1yCGO*DZ<@Jb~aAJi*;HxCeI$PH=Y%!7aE$aCdhIGQkFi-~^Wm&fxHxeBWR1 z)~k2x-lmGChMpsR_St)_wfBkmq$G`jN`wjn1A`$eBcTcdgAfY*?f41__-$k3gAd%0 zOys2{V4h!oesq;2!oa+Pk(Cfr_ssgc>XW7KmVEL!u{76$fOAZRknmj;u2Agz2BMof z!t^Qy?4b3Km*)^lb|Dp*HI<`guL!g?_H8SRFV;K(=#wIxX1544JmK}QBYE<%9d|pib_aG$mOPU!3W@Y zkf<)jl8g8wPU3oyP*PGROGHorEeuDsx3}lq-Q6vKiqZu+7DKG_qm z_5-z%zjRfnI{4C6QfD8w*h|ywoHU_8SJd3Wig_bkOtzdeRhm`0$u7CU8gF7Oh_tF( z*{>7h9^-hLA?t*Ylgy*_0xzXd{_dAHkQ8ZffF`xg=)Q#BT{|x0(TCPSEIFMl={`x_ zUB92*A{=*NUpc9Wln3U*S^95YkssZ$KbIE%lu5u%*ANd;QjK<7uh6XGKdAWR{KzzP z-a=?EK=TzCkz5@8zk%T`&U9_c(ZBUxQY%xepl|Y&l#np<{m;wz{no_$x2MVb!N)zl zvOxx5I$H&0X21P)>j+LcJXo!+`|IM%tEY~)EVdfTDk5LmAG^ODGyRf`z3Do()t zvb5-UKb}lLI9>Cdg#uOj{;_h{67{_RaM1sba*JNV`OAR?7^t&z2>=v z(caPFbj>hdsWXG?Aqe!EEP?y7yg#Si*Uf5)x9TQ6eIMZj-g+niA5yA%%ArSuhrhBP z>($u@=cb#=x7@H`H1i1_4w-^t&s~@QrbG)U#rH9KO-@vl4=$`(^+XEb0i#vT|7RS= z6!)yvwU?YOTb+|_tI-z0T#Y{Zm}Y9sOBX(5&8eB)Rfhz;Z`H5=7UE4{@UgKt zqx|RCcsY_boHVEO{#h9J8;7{d{qm1P3<}hhP5mtL{0^ z070hhQ6p_Dp_gSTD`$WNe?PZ?U2&Z-pjbgsK%KcD>I#S|kA9xmNe-~9T|gr$2oIMb z{I{_R2b%1!54UU5c422w(g=H9!w!zeSkqwjWw0#GA4Y6?VL32iCg4T5_hE#&20nkx zf-&Ve^_a1_y-r@xGx|f8tWJW3vLx~-d4GD?gAwzL>Kk1uXIHpTQPbk;sfG)wQmns5 zL#rwYoQeeOCx!xb2(Z^ef|aJ>2}p&BE;bk|dhxhK{c+5Aqu+()6x;EYXSkc$tT}qz`Ie zJD*_-1$9KVJ!pqzEoZbm@Ep_?2Q9mgRKCy}7=vBO$1xP>2KEuZ-1oq zN3+|lL+iRrA}$89^bR3`K!Z0lks9K)7%R9wTGuZPIXHpr-c-;@x%gI;VUs$`xL&4LGPCN7-JqN%QY_4L?Mt+3z6F*}D4deOo}z-VP2@tSb-j); z3|?qn$Cd_){8jx(%GixV^@lhig6Hp*e*y}Plpkf)O}SOrubhpYpP^th3y5q_?DX(V z29dk}nYWMKK!7N)FR@Er_N5H$>dVqrSu}^K)FbnXYy}^3ZU`c+#l>xrj3_`0MOtY$ z9Nn1i(Qbp9idK!_z;ZNUSt^EftrtRQHw|tW&`a&up2pQ4i%AHp>sPgzL3d5^B8rkoC^1G6709k&9A6i5|)?OXW*B!1x{ zJa~O^gwlnt$m)t7wIk_?%=*_G#x<-e%e@;n*Zse|<90)QeEHpn6%0RLW7Aj^B1qd?kGZ}Nrrdaa$`j#o^NgDOaJR21 z(or6Fk6~}py1g=-W3*s3Bi(*xkoho{gK(X82HO2*PnF5O3yWWAWE^%3IXy_(Ruk)G zk4yME2ZKqjy>7KE_2ydkcn#82v*6hGZcZu{wxoz#DCoks`b)tnZ^!)l7tjzn@nr=CyVbM95ElYKCWw?Q{aS}_mlY6c*etu^6RGdR*NP8s~ zK;Xw~U^s4f8ot3mdTrQ(pf5yrngx_9w6fYo-P{j3JxaKzj zv(p9q`STh?>!-i=@&Y$%8{}&1vgjAYUA=n?TuXG)KBYTYw{yq7AHI1MPUndmq(Wgk z0+oKuWP{5CQ|~rd;H;cV=nux)YlfjQ+_CXQ#Y_8?ND0=#n#8zUUN2bX#mAS)6mbsP zbOLX>sb^qiGTrhMInf2iE)GpAjA7paG!P8aF1Y=ENXzATY@deO(b7*NLAlD%mSu+l zyo+JTVU8M?;e-)PO|7aHIVL_&;u9nC;rAuIhu+=mC`aL=p&ed=G_l`zbEPdW;L8T4 zcL9&<2$}Joa%6>}SD#rya%4Go?2v2w|2#8_a@k9`O3!$|#gnK;`nC^jrMT#+Z{CTNqB_<|Y=zpH_C zmmZ~ppF>=5=bu}tF!5@Q?Sh5$OSf{dC-9!X_wjH%Q$C_l@+y2vLzn{bKX@qhBDt*f zZzPLjl5kj>zIt|o5c~!9C2@h!Jh}UgbrZ#N9I|g@srP#h!nv)}wyPNE!hu7h;P%W| zx&y_9S_HTS)-bz5f z$|+hdqv$KlH|dpwFn2qRVRQMMzq#EikX5eiYD|#t&3x`P%1q3dnh${B1l2LS<{)HX z5RLC+WS_v!wj#GIb$b*Y#u`h$9$A=vB7L3=)4n16`qpE4jAA&2*RMNJG zeejnCDvf!fUo3Wqk(s1$>AlOy7Zz}z{+yIpZ$pJcJr$cUIuPMLzeG406`lI=iC5lf z)^J3Br4pwom-EP4zATB|NKIm04`U5%2HX3>FNl2y{`)%u+{83IuD#)fc>;kxy~=L<2*XbcF@xbC^c?eNzNlHaJZ?(LDSA z_@F1gw>miOfZw|)3n0VFj;nU4cZfO5LnqzB3+N$UzbXxwbX<_^Nhfg@BN-l|S?*+> z>PPF<>9;+!AfX#Zo@Z{PyC4)F)yyTOzHJsrh1alnxcf=RE20HQZ-6V6M6D~T?gkYP zQ=A*pl1>P0^J!S6k@4npg|A$>mb~-*F9LftEtsZM~l0n7vrCKW%ji&o}^Q$a{(Q+ltRg z;cK%a2I(Fx1)*RLLhWods#)&PQubbFYE%Q^zEZXq3Zf3!3{N3KW6QhEfDK6D3c(GV(DWMqQ`cx z9rmnbl(0x9Axp($p_dfc^KCy1J&=&4^&$(0COXhke5-8oM#JP2!Eh?iwsceo;Dc;Wg`X;`Kf4I3gCZ;t8DXo_KG+fOju!`lZUab`-<$C+aj~xs{r!d+}$IrxDTQ{;5?jbO+ zoR!v%Rcs;LUtZqg>`WV5GWFd%N8NH1FFgmA^_vkBABtmwhSj>ol6fMBVL7}aqpg}v zS1(aZ@AAD2q;~nUrdsDrEm9eF)9-~-Md%7DM?J9LZ-rkItm4nsH()0`Q&R4T0ze=h zb*i%uM@@O_V|m&ESP}`JPyZXoOg>WaOhg8u_-x!J;s#7Dxv2=)AB*?X4vFW^t9ynv zI?22K&#zfozImgi$2sA`lcyjR=ZI<1CToEyfnVKiq{+s()$JB$23TVI z2~9UjCw>V(YdJ^8C!e2bE$w~o1B6tC#fu@3!8>BiYuK8$i*`bm`OC8))vUV)v&;n= zB}cXDv$@obr+d8L$7$ju>Z9<&Aw<>m*JdikV#FrWC})>&u))>&nri)ERfWi?@Fa$p zz&|2!!+`>@qMNkDZ|@`d(p!a^oYC@IDzbQ~=Vy=ukTWkNLWO9Uj`_{!Ki@ z%1ZxB29Kx7h|XA}S<=Hx;aDMnVgJC*+HFHdbGPDUWstZ^;*n)7zx-$;F$3-O zTohl^+PS2G_lJShRGEu?2-pW#%Jkoc_nmx~!wxx}yHafCI3@_Yc!7{xpf-Lgousw| zW7oA`GI+_}o4hlu6{Q9Pz3Ss?C8Z&*VQzwc>sQb(zHy=wh3D@9DM*#_1v;;fW)bu5 zVLA5+1qTgG$nHGClF)`1`=Z0b%B_QI#ITE-F*LBMyL4MmC=a)n!lgJ5>$qo;i%$?|oMi*PvdM(Rr&0ZF zac$^H4$Os_$UIwfbvfR_x?5rGyAHBcCWzVj{=;@{BjSTvYiyu}i$A$1M;Y}S4PU>% zicp0Wwpev&d2pG_Sd%D|QS9;FcQtTOQg z&XP6zn_je+%H(`SHRA1k4a`|#DaYCI)o`dWx4UEgX_A-SzeTR70;^dI0a}n-X=vLM zBLMwqy?EGA6*t(Hl6-=43w=cUYqi3LH&T!JoFx!IM$l4aU8|TbqE|o2QqKP5Z&&c> zuYZPNVIB6|L*WZuLlQ{4eWby%+PGTDl5g!1wZF<8pZ8bYC8P(f9V!hx1=Tpne6P-pj&ND3AkFDpHq#tm zDmBE_N3?`)UpJuOZ-l^c#P_;NUydox)ODClwk29RuhJ}R)L@L4i&9&0DdDW?EJrQt*E^z!@aUiy5AT&=K&kwz@imydu;u56h+H|NDI39Q z^1`3$=X3?AR_C$ z1#oYf+7R2it(rX$nE^5p)sLn)Vmv_};CY74`3h z=9*Hi2K$v%8OU;WA6l^!I;{IIx#YBhKhD493OnxIKdkt}cg2MrFZb^izj~p_aRMAD zX~~=xg!*Qzqn~M~7Q6^Ed*C3-et+SiCJ?M>KMlIyMv)arxKRLGK+0&J$5HGG7k+21 z4oj2uw}SYuV-_38e3-ii&D&G?i_Y!S6Jue?T2deKZk_hhpMY;JH3GTX>t@fdJp@Ch z>j&3Or3An{#UhgOMG7qAGT46KtWc-Lc)BHJmZM8NJN2J1g8{ILq(miM|Gv`n-fv;~ zOglJMth!qY^QtTpIlb!^>90*;CKsjZ@eBEs)oB~AzHG~(VarGfNdB{+W~Vb zbsx1(MEjA|PZ%4$x`+FXuU;1bfJN$RkP0(xpP;V zRhkJJ8=YIdpt8b@D zg;y-7BkbvP6;CC9kQUf^W9W@kC6s#w(}B}Q%n!^|HpVXA2l>+;95fIP=gU=Ojd3d& z6^w=_*gAeODzFb@F8}QUF^8twtkb3Q2KMf=HrjX3o+I`&`M7_Ee$r zo8g-O6;_999u0S1tcFb4q4=x2SD40#A4!Rn)MSK+HuNcqYIy71t{HZpB@aSB0=qgG z_-0UuFDORih!`@l8Ecu(XmhPcx)jJ#ZPO?cCy>+1=x}}a8t)I|kS7nJUlX?FjA3k7 z+O#g&x%IA!hKkh~Pb(&GCdqKVvqQ58(c%KS#EHs9crimx&Jv@gQ9xK( zMdIt77idKqY9g(N6MgQtb>|A7KQgb*>Wu!uGu(9^KcIiN@fWElacR5ug;Ht#q!-+( zyA;cn{fb4z=?T-i914nURKz6Dm{ zj_STA`eV<{=E{D{HW&FJIo}!>ER#l3p^wruoG##aMsGStOuhukE?AMr1tcG#`M{{L z?99g%1pR2I2x6D;1j$qwmvH(<7$sf^Yz~)Y3nBz52Qf#;`5U~q15Uij3vNwH((i&} z#}>iosAWe%pJEX$S`SHmnhd(WhRIM)%94kn3ulfkz#^O6p%Cft$m=378W?1$*!*MA zTS1_=x+sCQt{YH68U@Uv5fGU$Z4t?Yy_1$1uA0`TkIA`O7ovL%myMsPjy)qK`G+&& zsrlh-2Npdkja_JHBH4vT~OovvU9Zc zttWRTvjf3sIopI9W-$uw(sEW0-I78qhH%a5s^lV`V8}?L!n# zZ?xeQxXBqHO1v9kXO)zNgPRgpwNuP^LCgm_U6AK&9IP4SXT(-0M+?z6vx ziG8CevQMjlIIA_Nd`0oul|3~XYoq^I9|q#GC9u<6u9^psZTUcQ7=eT)#>xTQbZ5Y? zKhMTI$6U}IWk8~wKx&nMin6CGilcH;Eydw2zSkkDSERMSBZFtojP9sf|6bv|uv|>q zBD`=47yZF6nG-v{Qw>P9oZAm`i}ZV^W%Ig~FW4F*eZnvvB0h$M?2j6ggAF~P^WPw9 z!Fx9=0K`<1W2G}dOwvWVrAPAS#L&MH2e4iRsud)I=ccf%#HApN@#l^4m&2jn`g27n z5MEO<%rhT9V%<=j+MN6ul6!icJ6iAlEFTu&s9o1RH9tVATzCH;@h&qWK>|Z`y5Jzf zP6LH(QZ9*(E=tgtY;C=ius%U@?lkG{M@(#j6s4*R;4*%d0#tLrS}n~GH!JJLDa}qL zH@87GGqm@jmy9C^En6t40pHRgx8bBa^Ka^z5UMQkw#k!o{&hGNud;w^`cxHd;jIg> zX)h$c60_mKlT+*B-InayqW-Bk%Cxl{qe!V#F9Kn~6)a?5S76E61E|d*NEwdYV8QB{ z%tNrq#JVGQr#Ae(Y$J?gFgd?%Id^yYH&9>)_iefm$|2LCR??GPPfu17qa5_i)BrzP z5%5%W3XT!TV`rteS2Vk0eXZYu)}n+YVro4EAWA&_N(U{X-8w>Nb&! z%N+K*3=6{vtlbg*@4Qx1MzGfcf4_yNW9se~&(+@h1)#2rdt@>luU%C$N+AD!cxn^2o_ zvf|OzMdT5^lmEikG-qJ-lU)6;yJ?s4JrpD-R#SurdNvs0?e!L{u!cxg%f77cCnj>O z1kRxQzDg?`IQdoRpl?PKHT`&mN$eUT#iL{i$G^a-t5pe`8ZmYx8hocdcWRrDD>0)6 zGD6G|I3NOmBj~oxTPQLK3m_6Bzgguwj4&0H?D(zbl(8U_jd`2NI>jeo!C-H+R$7gz zIb_I)zTs~i*Q%Z==m4oln|uxR?hs`@7Vkd_Us+`;Pg8BHZZ%HaX)&VSZR)7_6IctR zT$B7Sj9AGcYpgYUz5bE@u(h}yxe&hLdJ}t zHk=zx|6{RC(Xg*zTN%dSv&?m!scZA9y~6;JXNY#&bnsryR@FB~_bsfzw%#aF0V%yr z+ohNE0$Z3)^FK}@?>n>Mfzsx``tja+g)KQ_7b7Q)Ke+~me85U~!B`|*pxC+YznqO; z))j5)GTYu|=?;4(U>$Cm)FqszUMiDN92{?eaZJ*2inW+x3;KkJ+XJ>2G za8Zk>v~XWfNjj2FqCvowaH?3Lo@UGp4pYe87eQV2w$z1oepGP>@UnlZ^bh)iJkA}E zTH0rR;I0f+1JFe&cce#v6A2t+lK}xafz<8)OVG#W#fMKd^BqT8%c?t|FplfXnfz@ECWC`ge}ukg`{ey!C7ybWCvESO zgCi6CC>W{*`v*{BwTv(ft_>VOThSc}=89N+2VfCc;stJPz+q|PdDvL*jao3GWa-Uw z>PW9pB)7kaoo@8&2y3K2F|N6nls99`^v!8f9q9P4rS}r)ySt&ZKD5UK@){RNHGHP@ zE(xsUQJSj*t$3w~v6~Mchw~#|w!ezo*C-B#6*bvThM=;tac@UM$Aaa2;c)o5zZpm@ zs-J+xQ1}k;A}_JmG`@@*CIILMwG!}hG%cbSlMglEooDIILRcK3o!&`88F=dLF9_>f znLxVA!M)%HYJSvgDe5c!Am(U$`O|_Xo~4@2DDCNKd9@Nv(l2ndCEg*n3P`?cGoqUf zmHi@n;9TS(I~yWfwUx7^s9g+U>yfwI=}zVZ=TAQPx*mWvc8Jlx?g)xGwpFEBxiMdh z9+tr?s&I}~IQ0fF}@ycV?u%HeKI>(%eobw{Dg&m3uX7hH`SDrp! z+F{J9s<8sGi1GWX*Lm>CIRbN+weO7QScOA<#Vc@59!u4_Y3!(6T02 zJq)ls|4A2+cN!#BqZ!fOIen&VpK4r>K~AEkkG?d)(n*$dpwS)XYWUd#NM$owy`i~xwZ(+RnEa|F zT-CV-TfGl1!i(4(6qJXZ@GD#eURMD* zL11qrm}fNze{`kV{6V}GR)9Kx!U>-A%xz+b#t+0haF7IVD^ZXWK| zv-B$rcjc8c^+*Ap`!=y&Dp3vg;rru`MSnsM1!vWSefJIL4H{!KspU(eW~(pWpI_h+ zp;{Z`QSp>-es{c|!~)vmaK0&MU%lp+r}^3gSEEIzRWKJCU4tu)<3p@KyRY+fsso>a?K z&)C^#a-p9t?LKNx>@3r&4wqNx>adcd^HLrm?W+fs6qCiE zM@QD>W*@qivziMV#3~q*0lm0q&6oqcu)yV9g6(zI+R$Hu489Jc;_~y|kdJ~Sx0)uX zF&&-i9IqryvHZo|5Q}auklz1vu^o|0rE{s2f3Po`kF)@+!CGMM7ht~*Ls*DD`h9Qz z6U`R2f8qL)it3W&>KBy@0p@f05`94M%(DD0<7uWt`X0Nl$E%ciQjZX!Z)kk)a72y; zeINurZg12H|IPfamHky3{zpGetUzk8KTkV+TyYSh)HNXgUQsj%`np!+8q9&l|M6s8 za3X;n-Z{B$b|EJ~C|cn4g2Lj+cHFQ0!?lhqdUy#>;f(|An9!0WSnTD=FVm@SjHMFx zU)8Gk&2FYgo;Zqop4?>cFIWH<~Qz zBb7%R4*d?9QM~LF4!#(hDuB%0r@zGkY|IM1eo0FRzCuteR?3O~Po*G3i`QHbH3uUh zO#pj&ATu3*O;_YhvJPUQ^WXE?|0t3iDap!2f`_%k`I-DT8956EPomu zx&G#R{}kfRc}!sbkkWil(~A{II;@LFe`}<#D%)Yln=QALob$4^@g^nIKQCHIIqdu5 zXG=#Z#hOj|ZamD!Da+x7$mVpuFmB6E_Qp$va8@_P%qPaArt`DU@`}6 z_|b34P9F#OR;rOeMIUU4?BTy(THRT^gowu1(r1K)9-E#22CvbtW@KM$1R|_KXEDIY zZ8On5yqHOr@WZB%zBuaL_rH2Cz{#XIBp*RRnD{xxM}f!WsGsk<(w&(_r={SCaMiJT z+ws!2C6u~!q8u&*Yxd1m)KWHI%NmaB0kf>R_5Uj_+f&hZt(^?P^AcOmo`2C>Wt$0U%}0KMZNkZYw7egQ_w7)um$@{V;_mTy#a9asXg;ykC$c%cD+dmom#ks zMS12?J)mg!EC+>vNW9gX4_NZew}fI?EopVHEGa&v+VAJS5H!3I9TL7fpJ;@j{E+0A+r`{rT4vJUHC3hR5s>6aJ zj*TBkZoG^i9wffzmRaY+Fxp*9d8A}aAt=D*IPd9M_}Um02oZbuva{*(+-;k2k@iZ; z?s=Tp)cZMssHs{i`yHJ31T0p1++jzP2bfr15P%zO)Yy&CkEv{;jW-@oc7BPg_%5F8 zs0XmWSOrvxcBY8)~ny^j9TXzx9kas6*_N|KJXKNWUfyd zZ!7e6PM+}G^U^<^M`MBZZB@srqlepnM&idO?kTjY_<*2K3M6A z*{HkoovGeA)vK>`K+)~h?R=P@RIZE8_igs*QK9w-fw-W#6GNWg2et5f)^Is}UU&N{ z(A`5*_4*SnT;_#)6%DA=X96XjhV_o!3>#WzcEXn2hi$rVpMSf9EKV|P^@*f3L{f3G zXZK(m9Lq@(2=39{c?C_tL_F?@6deo9jam3DFQv~w1DQMyWNvP5ZQSvw3v+Y0(1)Au z0ELy)^oH)nUxvfiPva2Rm_Fxbv{=Yj{)@-ZoOo$#vp!{YFBjr~O2Nm|u* zY!7zaOZvFOxB_qvrL>t2cELZjM+UgK3Fa_Bcl}q1z$TuHR%pT#1_uIfUW^Cx;nuf6n@Oyc}-GEaQPWkLv1Bo^$oBff_nF{2IEDVuu-L;*kF z%$@@YEC;t%+GNJ|ARt4Xc4cVa`k8sb(8ta{IMqoHsN)VWv0^Q=xuH`vdVH$wSFYe@ z=7}pVdZQ?-cPxQY;5fDC^R?=F|FQfVI@F)j%0xzPvhVL-{q~KSi0`B|okPM*dhcHf zktuJ#A2Qta&*Hzn3cDbxZtfTHVLVi&*r9GJUxdzT^~5<`@Q|MDu=`j$1ouEU*N1Sj zw-d3&%?EOxhLjhcbozt;mBs@N?KoVS+%uhe+Su5vNcYeT0f}y& zut+TQc6M(dLMwdFpK^_5s6FmuOjy2A^4OT;b=ErhQ8&`^o=nW1hxx-f7cJ7VbYAXy zYb?WU;>3k2^DPk?ks7=1EzxqpqB69ZpByijcSw=~{raiGDODty-@-LUiv*SLDbz>! zN*}~PKJobJo?!SwuiW&EiA}8oXk?^!fB6bQunRSe?6#|lSVyZW74ODtM%_mN1^m7v%=0op;Kg*jS~*tAaTRu1oP**u$R(*B?)xXbS3WDz!6{D zf(YwYzhq};n!6|IXy%4`+hyCdX=g@{Wlq08(d%8zDk8Hv!C-Lmz*vels za>UwpZ%cd2t8<5wd&F8l`l_pHa;rXT2+eA2`{KqlMq{t?oFss1_1P*%S?Id0g-HVa zKwoT0rdkoikA$?mV6{21uwM91D6}4)n0_+;A#Yk)X*YmwNhX$WT8uNtG^yN#1gF32 zy>!FGnZ3X?h;@ZK_)*ZuHr9N-sG0z@Ars@aj&qf@d#4w@XUCs zwYBKL7Z)Q(fM3vcJaQ$hU3z_|TFB;7J{6lDZ(HM{X+OySBxOQbJ#)E|d)E+gmzCyk zuy@fUxKg)uvyzfJFzJaydCUHrob~bX&oQ=wnZi!>Z_t2eKtL-<>(^eFDrnX!d6Xd9 z=lNFi%NbsQ9O1I5Mx_(3Zd*)L-LYlqI>R28rfD7<$HU11t;3(B<(tHKhNeAX(sfVz z5jn9n`cSEaE{4XbHMX2^EZesFnB;t*dB;$nr%-R-5bw%l;bN(ZS&%UsL}Xo#Y0X6A z*wm+U4l%hrYiLlLrTdDEkDrKxh{K7#TkmF zM9zfA*g^#x&d?>TqOPg87ik2_3Z{!%c{%rT#A*c^_NKK2P?01^&!Ef`H_lZCW6Ofv zhnT;ApovF*yt(*hJJ1!ZBA`Q=Yc<)L`;U`pgtrsa&wz66JsipWnK=-=8N8So@ z{81Z5)!^q|dyM6hO}h1IGa-Oj?)a;I2w{sqx&>F?5e~Zu%$~$tw-!WvSP%|tXQkge zL*8LS0(Ct5KHGOsH1yNNNL{p#_}fKaS{9YQ9dZ}GPObsz9q)BH6XBcsk&}%3Y&(wl zbp{TNIf`Vy;WV#0soDff^=MRVqzQN>8wwR<(1l&&WIq*1U@@hqI^N|dn z#9FTGxhP}kqOYvyi0EG3GQJQ+e-JjTP*Q``z;ZcSGt_$aAX^a0#NH)n6=+7FC}j(C1K`? zs8ijY(26guq5^tr2#QcBpM_{@@1Cp8CM>|5e|D+^~b;3 zrk_kSYwP|V+lhMQL0LjHfPdG1x}W2#VLZ^MtfQahL+f321Jj#`z21M6W5 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_line_follower_8h__incl.md5 b/doc/html/_me_line_follower_8h__incl.md5 new file mode 100644 index 00000000..f3a75448 --- /dev/null +++ b/doc/html/_me_line_follower_8h__incl.md5 @@ -0,0 +1 @@ +3cc49dde4d8d68a0df6312c56a555191 \ No newline at end of file diff --git a/doc/html/_me_line_follower_8h__incl.png b/doc/html/_me_line_follower_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..e53a1b0d02c25e0e6f1c8fe165de70ba627d44ed GIT binary patch literal 46646 zcmbTdWmJ@Z)HMu)fV2wIp`ajLN{0#vNOyM(N;7nih$!7XAl=~@PW0)VXj}Cv(G+fZ@(!kN)zBx;-aCU5y;9&s-mIY^Fl*ISH6!0yu%4{ zY65;?naW8^qTQl?zBlK^prJiMla+j)~!-(QvcBTjlyi)#^n|XlHOJJ5LSn zi;JqDT8gPp^vwCn(_1g^Q=30vla~6_jU$O=AsidQ7CE6p z)z!$jtVl9JDaoiYiZpgtlBwxoMiC5-yO+=tf&qfb%)sDAPl zc;UZ^VN?hf`h>4iq*WF!^y%wYbDak+Xb=B;^-{-)qP_w3>iF76``_D9CXyBrs6Pi@ zJzSZU(*Ld3oLps+;qKG)JfZnpsEDeK#L$AsbWXRXAHnP+8 zsMUUHVDC?`z4rE+uw<1m+8Ifi(Tk@Sz4kWWTwWjC?L9Fp8`GqxuY6weZxa+IwQN|m z8YD;A{(pb`V4CifFxvImEU9bRWY_y~seiNzscPO--vLge*6QEM^l;U!Y8K@Of3mR` zr2MFt{6*LB;X?|cyF(8}oBWeJmX0s6f0M*FdJz1z=U0ZU{=YNU_tT6#a>i3dZe*m9 zl6QE-4aKL2q zHvanG=H=rV%v|GGCB;R_7WPsw6-mhp#k*5{@aSIK7cTr=&+VFt%=bySGJ$j) z;=`_&@SUcEQSo!|i1?>g@sr@Xy3f;I23rMPtBY+?%tVRC2opFnmXRwHQ=FWa$l@ln zhJ2GP`aS}mrC;>Q zGsY|@<|@hUN!wWGU1Rb#y|0AjaMn(*m(qI`pwiT)^z3_Vs9QQ*oi0fgZao0UJ*T3~!&jV^Qev`nbet9qsX+z{Pu6e2G(!YK^ z3cE|mUJkbqCV|JxAHSoW&Hats^i?lW4t&VU z{utjpJdF%nsmv=H7K+%e=8XwB3Qqq3-_Mp75Lr{?;o3OuM`rXfkI$teV@vjY?vJcS z2or;r(SjJDqCy-V1nyW?^v&$Wy=KKFqEW|*AB-3g^63sy`*;p$4 zEH*sAoTmo5rtFmYk3QfZ+rQK z%$-Dg9dU4d8-ZP=@*}l*#_dD@s{gMfE3P(^OhIBUvDX*YF`5g^p*5trbpe>~Mm7hp zJl1XGEQBJy_BiC+9rr~^9zcu8x;#nBg z2VJ4*IfNzO!>A0IJ9s~m^9b-84zq@K%oeyHH$^8Ok=XB5aoK_FC{MYNVAJQ{`qFM# z<<6p@DqD&;dn$0~Jce6dY9krhbQMP2YLn;CJhg-IA8wK<48{fddxYqwuZ0nZdhxG? z7!4)g3Ejc?Fw^7H^P2*ac@W~I_GH>pW+(5~x3ng{v^`9?8?@+S@Yb-rh3aIC4$X9F zZX@K8GAI<2)@6Ao(ebo>{Y0CjVU6!1e}<2cK#lr6Tr#!89|sQ2uFKBxKh6e&N;cV` zpESoc1}p0_d)VlCBJVIurYsc|5_W4#;SC}~m|dNCc(xu9hFf;~&*m{W9P9IIdrJGw z`Qk(;)pU^++-3r4{;Ci~^b?FU2-64jezV4?{A3$j70Y7n)dt(!mG9c2IJ8bL))|(F zFbNr&o4KADfJ$8QzWFn;OR0Ut9zOt>I)l^tP>Em<7rJT zS#0&aq4jN78}xdy>!B=OSct37O3rzsVM*|33-jcyu3$m-tI9H_LJPS`-1+WQSpj1I zZ}5A(jP+F#-Oo8GiV4CPQ^$01p3zGr-GRbnY2{}n?t0S11w>{VVs%|z7wI8P=8)3S zyXIZ`mmSfkdfM^swg|+LR{~}~go0-FLrl-ev za~FS2-81j#sH_)N7eGPBSY#63W;15%*^# zNnu(vPE?{}vfn2mp4u{s!xwkZiU?+eAt$|h7?P6vhe`!J@OfBhh)NIsW;XV95D5Jj zu1JjqPW5g_aZzzK*VGX`PwX8SQ7o>N?gf}4>V%O8*>4d>>ZS@l%|=qgL<)ke{+2|E zhQhNqX>Ik>*_GhGNm{#J+Hf$wB}O{hoU68_!)3j9w2zJk-yfLP?s*CZ;T9Y8ty%Pc zX!J7fHT^K>-7&q(uS&S&C=p~s<3LMuT<)(49RHQ>70=`oEldEvsHJ`%FJGg@`=~Yu zxDwk{Rv)D)!Lh}c!x+uCf&09n(;xGu3-b>xrjeV?#zExRfe6U}975u{7tmyAE4l() zHM4!(G!v4~0{#-VFT^Xt9-QQ&EU|&f{`>ke$AbAh4TJ7KY(v&hcbcf>#o!|C*Vxr@r^>9O{N@4V))Y zi5Df&_1mi+4F}tQ{R7EJpTooQpirrmQhdgjml=^to zTV3o)$^D0f0N<&{UG9emzLIkF>Drl9V)4punu}m~*C3pSF1U6@onOkabd#@@M({i? zEbY)c_?o>_G8HFV3rzt;_*C>yGr`$(e0K*YTefUEIO^|zdBoU9dG&zT7j3{nTage6 z_IzOd0oIL+TaTG&)|I;PwvjjHbeA(ubhu#4j!r@>op3=ur~p1caQ=biyQNBo?N_0B zWeosj&F}g=HZOQ6AQX%iR zZsf)Dsu71>p^L7(?`H&RYJXAkT!-GMPBP3gw+;~a!8x$PcGSbDIytkbUx=kT zi_+4XsV>MnoIO|{89_7b7-97vuyO()=c|agj*xgU^v%$B#Qm!UQBMm2H2hM=GX%58 zu(edTn~_mqL>@Q`p*W0?IKKb_mQ>Su5+pCqK&*b!Q=1AvfjtFNlFFh3{oW&o6pA`c zvZ;&wLjq|?{CSJux%^Ay{nT&ppaGz^5Wc=&%q052vxGt^@o=T({7UM1s?69H&Q`T z$-dtdvER~W{QQ&-MCc~K!$s%@o)4EZ#2k0`#Qa4JPu4WswhcV7bS{v>V!8`SiPsYi zBJgD_GEK6{-Kz6}1_CiL%VGza25z4h_%#}n4A&|s{_V=*?_|sr>Ls!=HD&7cV#9`E z5>?Y|*7lwlzr9b)ZvLn%3a&_#(6niFMqcdOoFoo5lPl^`&iGeg%^ws245L6x06YKQ z9M5tvYIlWZ-?woC{Bqw0f9b;ofGipZ03!8Y?KT0N7}97(G`@*d!fxscwYB+&vby|w zZ9ixU=5a+Zi*uLN%M+^#0sbD$QPBhcFBD~5238y9LW$}RCF~ccYnY~Ui^bgnm1-lg zzB7|9XBU2`<(?ke3JKrlw}3Wp-hMcBL^|=7qTS4$hh!|LBo~aiUF6gOX>$+nOtqV| zOv|56uZLjl`N`YS$(3fIh%ZWQ&rmqeZUEYzb(FnOFZUlqFD8&kcAD})^#+eE?4sn= z{`L1fJEqB_+@0f2O=yNuCrav$CZ5Iljsr`NBRzCkj?quT;vf%^TJM$xy1z0AP^y> zFAyo6+8rZ?mxowP5NtdQ%qTZ_p0;;LQ0m$<*=4c4=G_1=Dgom*^FJFREinHOhj0wd z6qOoBhB|^1C-u3K%HI$}E97^s&LFmCgIx(4`(;_bl9{c&Yzn0Zm0czZAytfeOmxBK z(Rca!)g`GPg1MJVp|y4TU<~7&X7vC|ydz8sYwS{Vph04_agru4u=)Nyy~Zwr?muO& zKdybOC%zs@=>()dAV&&%Q=Zkeg_Q`-RGSwzQ@Zf2H&!`WWsQOck2B!g-NWy@6z4X?ABlXUBN)|BEA1opE$twJ?gH#92jhH8 z{wq_{!!v>PjAFg_=&eP}mA90C)On%@bk;7{R-M8-$e`ZelSwAV2g;F|2*xC}+V<0@ zTYo_DX&9p}PmUND%3c$%L+7lgA@1s(>5_M4UgqA?v2S%}{Wwg?cqR__yl=_W%M}iJ z2GkM*H_}nk=~L{B^P~q#o)n6Y^_acz*R;qcGogs*3`2rpEoyRjjtlh0;z6FE(tMa* z5%AQ>-!4yHc4fnp792>*y}F<83X&RD`I|ra50zd6EcNt6go78UA0*AT&@O}3^g~ai zcMN_`2%aFFY)2o8e41W%`bh=746R|;Bky;7-?9&?bHYfMe^(f+k(P2nmfo(7Cg1Mi z@6T$DYpXLlX>M$@s(mIQYcJ??%JSrYLHNf{o|*q1iu|LnwXn#x)6XVBZWh(P;>_#{ZSk#`%9fJS@p?3Ggy(Mz%h75LU+b&du$4q_WaeUHN&4?~KCW=61YoP|#K&R)^I8T;!kZnC75u{VqnhXc|P@T=Hu!^kp@^=N(b3%w7&@ zw1!5Q%}5C+ND7u84`lBqBCj5uaiQ}vOp3)nN8wd*pq4+4u-{-<9lxzPzYjNifUH!r zU%6;k!a#w86=7-$L`~oCP~MAu!-mJ*yJZgVAdCS&+(BSClmXfydrOf3O5<^#fpv>4 zR8S);3hBL=r$%`a?@qe6JoxkO?2dZ!Lu^g#u0TAz?Y0-ZFjTuem_v)iAPlULI&qKn zsLT*quWNu%Muz+*6%g0cHiu*)o)5z+AGati=r162Xj+}+O7{cwaJSQ=uwvd60ev@E zybl|a%0LtTQ}ELf*WYVlj`N@nGpvZDeJk>VKR37C^Dpr|&4H>7%)FwX8XynQ1__Nq zK5{5&J;s?Aei^+(k`2mbPqXt2;ZdrMect@%?FKg-Jc6pKcbsG#Wc$Hkm;Rb~NrncdoRTnRJr*iaumtOEI|W{o7)QD& zOP;pZXoIBZ640{y33rkC+t*h$3X9v>BU9uoCqn=X%|P{27p&Axol$$;XpJD|ROE~m zZt56q`IPBZg=gV4!-(J#4ktGGDOZiI$;> z^u2FSi_r{mC4$M~{4Th~%=uO9F`1K$5@X>+VJ)9&IX01%V>7a?kl7or&~l#<>OYZh_8)hme-~@;^7R z8AMXG691U03>|8`B;(jXu?kP0X(+G#LmMolm3K~Xv-r!3Yq_^hE!7#-lEOYbiG6j3 zV|g_Pic(Cali@_BXB-j zQx_$z(s-t8DYp}DE26MO!B-W0H+ev@i|!i8ts*pcbsAoxS5Wu7tdz zf9?A8;*G-K04@G>FIH${XUtV?Zln@n?mTf+3ropi6E|k8&c#rwfumh;4J4;UJKhHM zZUrXwXam8(TSgOVf>5j}XlryDMm1>`^LU?x-i@$M#ekdAYUOJ1FrP86gARn3pABYP z06lYmM}Nm;L>KM$@8y~5V{Vxs#ZGNFaF@ODOG2T`&}lX179Mh?K4!Ty>Hx~nLPsJ; z!`dJdM7p?NZPKjA0C%_fA$LbRLxjku#`Ic;#r7ZhRXx94Er;C(Abm6~AImWuM%E&C zLt{&ldCmspF6z<3d5|xZ=rH~8xoFXt0v~SfxDYZ2z*Ezs`x6=ozm^sjCU5V!?bJ*d zV(dS~|G?RL#bfEJD<#$0c;nmqjU^J8hxZusgOhesVmkQQvZqwo8m*qttakqz|-X}U>*sI70s^}xZX!!;JMemiC)en*7sp{X;Po(22V_Tn}s*ch_ zjfnDj`+6$#fAOJF`CGtRT~D0mbJ!C+gUsqqgye?qwPRT72{UyQ-yA!h&-^(i=>)dR zlkz(#Fu`c&#!IOU4H(7)6Z<2U`18N+?PM!!2VmY{>a{VF$=EjCqo2er@YGELjsj-N zKbg{!nJTXa`Nl~mS1b4k(d>AUg`YslO9Z|`J5y~>qkeegHm@PD*L&^gnI=q_0<8I} z%X38*>4tpU7nSZ3jma&9-~9ti0^Pt0 z^jG}iLYFNc0Y7l9Xg9UCU%rf zYzr2Vs2TjGo9cQFKmy;)RyU83gekp?kL6CfO${OkF%M7I3Q?t!^71{X zM1-|s?Ntj7eeN2mnDy8xmyY+DnpFyWa#4Oq%->ZXc+L-Dv=FybV70mk~rje1yMniN3@Im1OaYV&xAtWGx7qjV|V z7R>wY=2;YIv`D>-sGeHS&1#Zb5iJbauB)fhYWXze-V+DiN4mF{*}W>=AU|M>ezkmX zKHtae>M<(#j>q;BF`)iLt%^fD#vAr6-j-6*IGriK@La-~ugM9FgG)lhbo7dWV5n^y zD8kz={X-|_jeCXWTW0>{*X4CX?xfD;v<~Q9(1piQk$Mh%hO_X~yHkU8fjJ+VW zwt-EYI7>x*ewD2fFtEg~r~5;E=I&Ba@=ZWBJ<;~kIDWgib<<_G*+PzQmp$56Bc=q9 zOG@qg7X$2ORuN&sWP9E2!{QHJ_@dg3ug>;oZy!)N7r$9`fcaz{Neb7>N|_@(0g*Z zQ$;m_uD&dt-0)V%9Zu`LoPA(CrvfJK&9!;V5|Ctx5=VQ=T~H`N)bKM56ONTS@-YbR zT2i_sE1v2aZP%1I@=kV;&FlGwJUve}(BLbfjR1w$!r>Knav$+c^NDv$t9!6*xKR4n zqjb%?uT#@mf1}fmToF`ia1>J(6k3sxFafB+VYDwB;u>ybwfM8pMD@tI4%9v1aC)jg zJ6ftP4mWJO>e#s>|nh-T@!2e$?c<|KmfDD zdFx;sMRK0b&{L1#?*3?BpUGJ<#tj>KpWh?x*^Qe#Dz!)N_|onu&=){uYBBQ&(859( zLCqW$i#RGj(C{*UNp%lM4|EiE*sKpq5+05yn;qvX1)dWka|y3TsrVYlNKL9HKAMCyF}knQ2g zaY~okmVYxagM~uW3~WOr0E$Z;1)WggF%myDY~>|&D4}qRdv#{;Q=k=S+eA0K>Geh? zY}GrW?t&yzEq;%gD%`B*O_=cM=chrVB$IIxwSOJ!fK0yEvgzM6tjj_Jd)tV6bX^C8F5 zsM%KZ41O%dPvC4-Mw75Y*p;?7`a@xJO=8m+i5(r53T$%fG#|<{a(ixIzf(fYRcxbP z#gCu=7LG81QfZNpI80q(iCddgTr&eV0TZfobh-A>GSIrP@z{>9bxpSwHS-$U<&fsP z!?8EJsqf|sTzJWZ^@9&>j0bc9xfF;&BcLs+gP_+5rrIF3HcT(2Mw2RS`$0K%;`4K5 zr$;|-*8a*pTnQren_Qqm+y89eb>2uZB+ztk-H#9kHrgEFHk|TwV4Bsm_V^}k2GVa`dwSS%$J7Hfk@{)z zq^0dWm>hH)5Dy`gdRCzCyW{YwV*o%~3Kz!S(mw}si1#q3ZHa0KT6qM8R}can>geC` z%x%uT-0XfN-u~xSED;Imr{;)x$FvH6@Z05_sSiz`lfF>)`WG@+GdbS6pX07A>nHWC zsvT~Kw&efZi4aQpdi5Wk#rDPA7*VBK;{$@u|A+>eh&a@2$L1q%KeU6*Tvy?nD76bC z1)8mW?U-T>*dP4Er?pYz*(58zM=RAbb=Si^U&tI?wp^PdxmSIF;Ln(*H|^;dY2EH~ z#sR`ZW+G&G?yl+B?irQC?daF!7Uo=sAM=yF%I0HYIuzc#Hq!~<%#I5|sirF3#1HRK zy=TB+5xX_)02QXpsQ`gEHQxmQFk@~d|cEi6bH)TG{8-K769$1_5xUj>Xo5iYh4wn zCoIsr$?}UR4RAKPfb`9tt%YS*_S0NZ(}ZQpeP zXzBjP8T<0ZusmC(aV>!0qFPn1GO8!UNA0+{3R^L|NwZO%1r?~2PzQlauIoiNeBC;N% zs)$kE!X6a8xHr4wAxlRlcDi>PQesH$Lb4thJ|?7RKyh^L$=QP^@N41q!s{T6K>>UL z95YTgnbk*K#5YZCYR(?K?uG2>d1OizgBU01z2DUgY+AoEUDd%O1{&%_7VB!s$>ue! z>`{mE>~4~XVRzH)>yX${_cyUW2KRg`^N}^sU-A8nxxsP!PpK(QGPRe46>y>i+f+@l z9mR*rUwNY(={}guR_15PV$B+w4#F8|?01I+IeS#)eftO0Tb^1{WQ;QK#zi_PxAu(O>hCBnrwoInM0bRHX!c?tdfyw_vfbD z?25JYyKmKiFG=Z{=-OTHtND2O*mpXO*q2aD<&dl_G}8JvAMnor%#A}|J0XdRhy$g6 zCU!tG93MEypals~zrC=v>9(*Zzk2n#mHcWl6yOA{wOwaLnm+hOfJQb{4*M8jy0Eck z*;3(LTk{SkhgDZtSU9=k3mz5xg3Bvhl9{<=;Me+Zt`SvS1dv-YU1kVU?={+${aq)A zarF2K9>R15ftv;hpY$_{kyt)}B^}W~V9VT=NsvcewC){?b77PEOAG zp#ia}?LkuyD4okxMa!uQQw9 zL11&L$lb%1{!H!I-t(~7EzM(TqGdt2W%mWGj+4e-`$ocrQ-s^BeS2@vr3o(wgN@hN z)SMyZ8rh7ho_WOSX^TWJO38{R3DSYLIg`AOzuCvgcB2$1bO8(LF9qEH}`Mop+k zi|J5z@OZ!tiEUZTv=X{usz>a?M$rVEaeaED+wEycQ&5tqfZxp(+1#*I_=d?I574}MDg-^Q*-RDvQb8$-Rq#je^U)I zG4fi7Rrd!IY>XguVt*Jq_06}#YzhTJ>p`oJAr+d>fBkxSYbY)dTJbZK!GWWIV>1dWdV)I<1<``r{#S34Gt>bX6YP@w;*-ypNhCRc$T*| z-WCN5J<1M=fw`@{aLZj9XctI3s!i%1&{2d}Zmf$8PwbW^05&HX#}>g=xZZ08{L)=H zlhGtMdGtDpR2${d6lf_*%4%q6dO%L6r)@=avUjOn1wFo=eb3Li*nMyP%`{Nl zu}dRrD#|~`ANy1~{xB}!Sw76*&8qF8^g28MB!l*_?peWVPS)Tb#7bxQ3wiKmlO8ZB zFmvN^oG*R9=^gZmd%)Q&{7nYMcADY7gPsllBNmq0GGGunKP@;A)3)dlFa**ljG|-PGPd6FBS~J!pzV>$8$2d*`RCWJp%f{Ov<})Iy81TW>do$A zH|Tj|@(!Ly=cOO!ceq?44@Z27zAKW6@`D@~VgXiNS6BB!?u;a0{^!&mh8UwBw^*4| zv~5x|&EuDP2?bvE%xQZDg92j`YsTIr?t`#K|LKn*?ynCOJWEkBjLl-?FF*z2e#uB7 z4?5YYf7bk%&G;2!1FqdD5zG`cRp8Nq>e9$(LMyr!AY*~GVnB;00sGf>u2%(T(to71CJS__=p(6(X6^A(GWqpDzw7B7^O zMjE>ddBIDZ-#yecbgGnd#>N$Kw5~CPE)D^!rN1yny^~2)$>0hEXmf3Y zFxOIb3~bzv&c$TQ9FTzSKm9!BT<9N`Qq-BIzWIX9Z?Du{@Btj1wqM2n>mJ*;w&)gw zbo8x2+1%m${Y3Hr)HFRQ)RCl|p`5~f#^f=A1y6gdDawVxBxK`tk@i}aTEo>>=eBd$ znkB~sQYYK~-)LDT0+7fKZNCqO_JvUuP<*)M6+1PYXC-Ao-+GjtSnKfR`V}B7A65Jn z)ri__mO!%cBd|^F*l<<7TYvmC>^Z6eWUZu*$FHRnqBKsChWl8zbfNAFQ8bAe?z7@d zi%5(Kw3@-e)JC8xTON8CXlQ!wT~&CK2#kb|Kw%EFmHyA|^Ufw^CdC9F0NOEMt-pjC z7mitUpghXUpx{aPi`Y)Yze)(J==48rk=jf9@65PGSNhbnpwB+Ommn&t?);nUQBfkm z{P+J+kO4D6&uDX_FzM`Ky5-D#y4i29LNlt)PWU>!Xl-UnEO?VtsbZpPzbSlpMVA** z!cm=a>C=jJE7rvX_~riK|D4XP%qB}Y$X@aoS+dvCk+k=kdqbt)f*fxR2ZliYY=8ZVFM4!Ari=yr+h@%4}Vt z0w%_(vFqEm&3(gv%>qajLGKBIp$c%GpyxG#SGobPsyoxf>ixHj*j?ssj4@(3Y}kMN z5B=LDu!tsUMRL!@MJFoaoF6(o+B=5M2r=`F-u0q(gF5SttJ!B?1d*T!3Vm$@^VSF< zEp@7Zj9<-=rls&F>DW>d&f%gf_3w4GEn?A9;04{-~3M25ByCLpr^jSa;D z)Pnc97clvK7ZDL;k0%)b3jz*8{vy2LsdNfA&a#<+n*S`6Zy180EsqrcjIh7dqa^a$ z(QNrt_5*_HpjGs+6(zX|#s7~HZ!QN=XL1b}sfQuzb1#>JuW2(qpABWc_&0Op-@9D1 zd=Ctf>%12{@IvyzhaPqmZ>*p&&D&~UbaHreLaSi zT#$qd!hprbgK?L}eox#TzA^PySUl!*HZ6Rl&#vNVZv~xZrb+aWSnM}URf#C>=E*N} z#4uOFbB6Vmrnc`kIdrdunT+LmkY@1TuhE)5?_;N851e)Q67Bz$xjA&T2FA+t>mxsI z(wxL<>i?vL3B~jn-?5yzhe{W0sn&ykx?yylc=M&AlYCMz*7r2&F+xE`Yg-61&q_?Q z5VPMQvP8dqx-jCG*`~QyPA6yR$6%a{*FM`%k@b$Wk-LcPiby(h>w0ImCD~gNglYg4 z&?B^m&WkT9365Gi)hKhO`-$ygEOZ08F8arEEtbhg^*&_aoUNP+Awe$J5t;tcr5B*r z-dd3GL;q#j1aUenR}de_4}MniX1Oa&gm3uEg1tg_VT}>`@?fHYfmQ1_)F$rCx zw^?jddg}k^2WYNcpdj~Gyv4;$Gxr_o#V1$jk$v_2#46UKHm4fl_JX`ao_~#;1l=BV zYRpEHAT6; zlT<(zyPo?f|0^bDDuKR97Zsde`U0>vEa4cTdDm^qsvK_kM8MCoJJfkCL6^?7Av*}C zfYn!0C%Z2oZiEJ|NY#J{5a6t-FG!lsn!-{YU+7M$Xovj-9+6f;4WaV(9?&MD)>AY0 z8|dQoG()_fXRm|hz=H@7`5cvvS%_*;nvPuY<);uXG2Et=E`!f(8aUL=eea13MZ!B~ z&a|b^c?rm;&ymW=fplmpI%y5yK%@|=!?0!xQo~+;FBFykuK}bm0Vd2+Juc*4=;Fir zX&l4z>@Ac6bVz+X?c+4F->};bZN9{oEMJtcPvMZE+gt6$@ zF@`j*V8G_K?|iA3y?9UN_VT!WTHe(Rw~J)K3~sd`7=XpUVODbW17+%Q94%%6T;W)) z?Ko!WyoI>iL#Qaizl)*=hmU;a2kN^}UJt+^fFI8pj2!^@A0LM<65^dz3;TfxQHjkj z+&e8-EVxk&W7#=`sWGpCjGp=wAHqnN8^=a$461v-H?>7LEb|K#NeeSscs+6HezNVA zoI*jbX!X+Y64 zFWQ78NNEQH_wuK}z!T%q2CM+La49$3*%$oec-7=rb0!w#l{PBhUP-|qa;PYI;E*Bc z_++(f=|r30W$_}<#ln(Uvgz1rgDVS*^%;$ zo$8$pofhC9L!c~2+FJkTiQD69vk^A zf<53E@B2CHRX*1W{X!KS56)geUWaO`A4+>ki!5S;PBDg7k-XQr%qLy1Me0P>jUZq< zfIYo@Fti!czN)htps*+3tPsIQVrYrOt$98QU1gR6i4Dk6%*~L!b1oD43H^IdLfYip^8z zbN;|iL0MnoHFMp2djR%;+jgS^`{P)}E#;j+3&*;k#e?XN|vIDyu443=XFka?6TvOk~q zc;Y{oHs<&hGt{h(52IhOZK2gZkA|jGD8<01F4NrBXzRrWGmtm zrSA8wDbVzvu6b`)vqB~BA}1<*xwZ^b5nj(q>fku`(o1YZAEN-UmXL)bt=w{5sY7mV z{rx$*Gk4R6>~H7VX)~gn^PW8BvMncol>lDA?Xo?c06G5-N7^TV%XXcOF4Rb52<5$6 za}rNVfTYV80W0J2>y)Z5Mo1^9R=4P9Zke8`kBDSd8oKc&metUcktBk%Mq zD1jZIU$f~7%+iJkq&a7y0Qbeht>6HDs8T}}=N|t88T9ZlP^y?R_}14ob<_nL5s(5K zZhL93@SmTG0t@BQ%&wma6)2yA;e8C*&d7%l!~(@F9dqmYcCzvCEPtbDe>ok(l%fu@ zbHR|B4t~qZQk&zdLXw12FT(MiR4S1oGc(_3>Z7&KRCVomNr-sob8`@;mNF}-7ytYE zh=R|vonNFScvinjSwrw-EqBhZxrwRFT-VkR@`%ghrJQHHr>Qdy6qX3@p>vQu!ToGY z6qmhObyMs*B4a%vHw)$VU_1P_l>;a8FTt?jP+~e{QWc#f6|JiJ_1;+Rd!X`hZ)L;0 zpFg3b*5+KbLlkZTsFP)sRPc&^Ld$Z{>Q{!8f=HoqDPi}xVyxd;l=QPwYbdtq)AK00 z{Y#eQU&I;>bc^-{&+;BG?Pw-}+PMYfAFigrcV0v=u;ElYxRqWJCMzWaivu})X-|Sb zh4;fn(HG~uCzrh6HHY87&#D5_9r#v5yz;me!jmhmUC|9JxmPWzB-b8GjJ;2xm#0*Z z%h2@Sun}vshzfBOBFCqb4Ae66&Lv)q^Q_K3V{F%f`+}4(PU{Iz zFEm!R3n*Bf(_j008tr#%fAQa3%l@=0@a;? zgii*mJT$Q^xrU#I1en81(w_O9vL+N_u}}SxjJXdUySIwodhmyWjD2EOH(0xP@70q> zc)g;&$d#Ht4WVaAOX|kKufHBOr7WsFD9QWyO2q(&$O+8Zp|MQ$daX2qMpge&r#BVj^5n&}F`nj$nsO0)XdMLWE5 zOO3%Vms=n>OJ*45*8n+5OmSKfI8r|%Nx`0mBI~rNopGEJ#(Fs2;aw* z-&@so5omVJEItxuGHWvJqy=(;B82%Q(S zm^!>s`W%2~vbQT8kP-;U9s}f7B?`YaJjrDdswR|sIy?a|4FH#;6Rr_M&TP7Q9rqnt zSa|)1SVRJyQuMlf8mdhzoWe-+_^QwZFc!D8m1$2_XB?PQt934GY`Lpj1Fc8uEotQt@s&m-#zX;F4hkKs(VFr@Sd_rsiThDPPdFH@_gJ zS^cR$`IJq+EbrT%abfJ6^Q+6>nlDR@wA>%Kk33dPqKgd!!X?P+ZTAl@gV-wnX6QR( zl?sPlnm6ZpL+eT5`R~o28%a0#9~mQUU)#QKm>p^`wAIiksB)yP1F1Z0Nh;e;?{eK8^8puqt5$ngq>it5Z(>TF}5TzoD^^17&&0>j1ovzV{w~YxfV*<^_|Lf=kDn zYXWta95PrgLH&>I3J7{Xwn8K{GI4whxTIq#UOje7m}jPlQPAAt2EyK{=g8uRpCh+8 zHUiTZDR6b#^zEQ{-sAY4MgVE^?}0?u=}dl{D-{zLt?5j#R0`SN{kV$nqn?lQFnE_e zV=)pikZ4rU6b$x({sg|%zE`?4iy{mf-=5`@nj{y=mlDVZ5Usng=$DC;Jte{G9cLhZ z@;_dHC|_i>?P88lqUz4W#3y}hUJ}Vk6t5Cv)Dt-#kUT9Yr`9I<6Hsr&+aQnRx#hS@ zU?Ick#u3?WKc24J|2}`%M~~A?x{7OT$@VPdYM?XGrqVP5*iQ_`6kx~){M+rfqhHK3 zfQ_hc8m}U1r6w$wYV!I{Y&t_mH&5$qkz{hY?;+D=TCc2rchQVKNzK|DoQf1lEJ=i^ z#yNZ<_V2%^2uf2qJ4Vl$iBW3A3Dnwbi(Z+Fr)OkOeX{F)6y}@(=6Hav7!hb5XfNwZ zAN@<}MPuh%r|9_x_l)a>wM8Wd4RBRn?%0R(*%))ZTg$)cGWu?0i}Ef>;STtFr7T2f zAs;2K3LaRdJWkeOJ-$D&+S;3u>He%#9J3|p!8goRe&1CSc|M(g1!I52Z|z{_{?^kz z&I7>mfIoJdt1Y4+!^Gc9Bk2!aW3jwW z@$-OwLA_ynxOCPPPSB>=8=W-^{W8f%LSz-H-}hA$Q??<#^vbx! z81c--b1h->bw(eS17+T(zZHCh9y|Z@lO*^yTQ)Ij`c7gD+lBTiQpMVun zHL0(|*08M}mmAsv#gM`oSMNC#6*UwnB@Wg%M3vFqomyVazhY8^WQ7hC50p(>VwSpK zvy@_Fl1mq6!_)0#7A>QoCZbr@fq~=rb{YM7iTY}BB=0%%h|}r)@a3RT5` zb~30b+=aSpZMun*Qyl=t#eQmxRHpVxc&)*ckjXz6r(wnslDP~-z!J{2a;#vDlM5wrm)wlad~D>yCw&cZxeri zw}4tI-a|+T#yMBG*Sx^1vju;!*J4Dx|0{bbt_U+4`W9H|6h|8=e}M6@9W)fe1vXT^ znMoIv+&F&sxu1IR$m5O9TzW-VFXO`GaCHFw3i=OkaUZxV3EA|{nGlNYou7X7?m=f5rR$!p>&Bf}0 zwv63QZ$-PKXb1FC|LK$Wkne#eV@&;P5wp35tzR5+;N}kv@7XEDmvc=ZnU6J}l_q?j z30-jB+a`sUfVx*drszJ)NSF3#gAO4-h8yQgX87*qGxbNiqzTdrf-9PSHvdCJ@yzhC>+0TCV-sg;O`nzJZ zZG!@k*$u~O_!IN`C#0@aS$K=n^|fPFWQktU>+TS~!{?3~+W)1)Z&l>Kff`#aM`{w< zl~=v`GQ+##qmC9y(?TzV$AIEaEfjgw`LOB%%%i6#6sSusvtPwj-C||X#nd7hK%sk? zE|WJEC}OdUuuHR^u-3(({N<57v*etu(v$ySvGy$%v)UtTYt2F8LOXQG*a31nydHjsr3{!piY%dX9wQ{y7j zU7nlXuEY0Oa?;dYE8XMxxg>v2`m0)LOcZGg7d7x#NnaTy8J=QT;xMm&iuF?LQ`md- zEOUmm-V3)aOa-wz{iw5Ow&Gj&+0?~(rs_%*ffPvW!qNh>8KbzKMA`q4(4He|U1FKk zuqx!)(S|J6z@~PhJ7TO(B8L6!aa54bAbMpAYtT|iO80_G2-6CcG+tUz2XE&is7H@Z zT1Q@u%oPb6o4cB3)Gr^;ToXJ$jF^ypp9vAlIx0KjW11)l$`A=zkhc9n^mn-rfq8G; zWu=2O|6KmmOKf-P?%wu+^pMuUWAH?Wklr1J5dJU}s- z@?+Q9(hMLfA}TeOW3Ya$sl(_Px&V~H0-}WCAFVr|{KZ5}AS>Cy*HdW&o$3MN_0L1i`^98G`y>cl~w`8XkE!RFyw~Z?<2hZiEKWJ$Y)hrlng} zRp?^sVrpOlOc&ihj(+*6*jhi&Ziy{hl`iF3>x|IgKjq})<&@mR4?uo#Bee_%iRt2l z=Xp4!6n0asF7y+V#IK`3^zh#pNj`rxiLQk zJ=0M>$tV*^n)t#|j`MJBOLcYEc;cP#<#gJBsgS<_vvSru_olM(wu!G^DPc%?C~&6^ zKqC?Ia8(&(gjQ`DC+3I13K$y6$`0SD*1br1nYi0FCpWl{^&iB0^AJ)MQ5rc!N*vC& z;uxNS@mJzjmH6lfM=~N^V$#C|Yrl?xGBuJHM1m=2Wx48NRZ4)b+2{$-6eIqSPq_vi zYSHbS5F_fJ7f6iZQSkuEcJT>l_ZW_$@>(Dp%tzXPy5#5Z>q>cwN_eDL0=zZqtv8|% zjL_ofYq>gp$DT4l2|DVR7g{ocJuk z%kO1OxUbD|RLa^@>}Au}C@uquo7olfX=hRqCoT`_33R!By;LGLTo87trY_D0H#L3# zYWzPv0zVkVFYWhq5=(C6NyK)wm$9M3%-JhTzk&YB0*3_AIeMFQMk?{7=IbW2k;*8^ ziAK>IPo_kqHvOLvr$+T6lb_qSet5lmuI`>F#&jE&-?QaGnxBNd`JJb`y+Ms-2o1 z>Z)<$8!x#bGL;%TMVy=b((SL1^aWn8xi?7bPiZU4>Sv_YQWndPg~5C$orT#ZN;eLX zg9x@i|EU*&VOpLPU-!b;RX|wzGkh70IsO^W5QytEU}dq;x=XbXCJb zn!TyV`r!2T7Rr;M`DBBiqsw^deW{-c@;>TfMHguf-2U1&IE4_Dec(&jL=L@fy?A#wd}0wcViszNT4;*BAi&Y?7s6VnyGl$NVnUwAEtM!t<8O>mZei}288IF_OaBk>FviUw z#km$)cE1k2?>pu6cQwjv`A0h#MFIX^)zXX>SiGzXxQLt0$IQYk6gbd4?jUO zw`54s4B2jeDzuPPPid#286|b(CnK&7wx2nDFl3Db3u$~Q9GTr%csp1v_P-nRcABX% zQCHm1=si8Q*tK$;&tI~kN=M`epC)-wZ$S@>_c$;4PLw8Cv8z zMn`f1g@E`E6*LyO@@3Q`F>F)se-E^?VG$%US>#%v@2<=%-6t?^sq3ARUj`~*qqdyM zLWQ}n6KiM+`g~nQL_U#41PYYCgzer}!<)&>3e zbDv6S)m{=f-a9RBbr!?(=g1_Kc6sm%$qGLk@{vp~@N2GZ8((i>4iM0*-zHdm zq`EU`tmAsZ)n=T0q)Zk}wHf}M;O?b!lm9(QqM-DD`Zj4H?;V{)nNEI-7iHW@GS`l6 zZNsCLyS|2+4!(1Ck1l{64quj~kIt1F9mb_EZQ&M@=8@ounR?5k%ah~?9mu(OG$UOF zT(xdD3F%uXdt`6sRxo5k*~FSMVGZhynL(PNWDAbi*qzpaKuCai=;OYhr)1aDN^$`! zsla%p91Pk4U_@02bMHM??-*Q^kCLs;eGrsyz+U3B%>NT?)7W^>?6pkT;f~`i(xQiK(I`-W)@J^ zQ13B~hmwG@62ahDGd-wxc&Iq+Cuh9RqxzTAhToaO-Ksq`pIKvezQ6xJe=(*s;v;J1 z*k=eR)}8JP{sH`(?zHYY0pfmvG=N}c7M{h`0!UkFnT-j%iT}H>tZBZk}W<;s^gYF%?OO)yW89=FSi2|50ipX>G`Zek)%769$w}wMh@)wFggYy#E zIj)A!vUR%XK-D2u2Xk{Fh6Jn+^!V0z)c=lff~Y?e?z$OdFHK#*&NRw;E|=`;aW?2_`K?m zAvL6?w%Qjwf}FEnNkTXK{GjL8!u&Rr2VecdTKIS_JUIkxB>tnK=I>U3rgVRoog;f* zmA?*67&~0KzPwm*x;byXcM0uI`~oNCHyyow_Od@F>F?(|(}nxiUKiz|ot-bz;`T=3 zly9ALS1#Iid0x1k40D_Q8OX1zOT7S^alcm%Axx66lImFthVpuGZ&v>L1+B9!kAolM zi__wJ`yL0o2c0)TZl}B2fYydFqEwL$G@OuuN*PmA48AD?ad&rd(Ll*+!OhkK31% zy<1=!?@6%JF#D$}u2;5VCyyDPpD7bVmfI$_ z@6OINU--2xWY4^ncUAvBb9IokuoXw+v;TmIYvZN1Lz4P}DC~fcyN9#W7U|&@n)|o& z;^cSdxv5c7faSQ6A6&-){!+y2SnWKv3B8?QGw6ea^v@CFMuH9!1iEr%9)N|YH?L;t zB^Lk|XrFHjjO{?y=SRzjj_Tt^Wkr{M%qkp`H=UE=wt`NWKg@B>cYrlw`cHt<(AqiJqwY1te?alZWkf*QX4`LD zB~Z+3r0eLU3{d<^OD;gYv*#vRfhX--KYezhs<=EHYJbIBWC|nFgPW-iFSrZ=A4>e= zggUrGv|Epm~MgjxVdsMotLu=5UEO^*&P{n!gGh8XdHbgR?T*EdiZvj~v| z#-}SQV&3JlV{Q&Z{Apg*d<6>r!$(rxzb+b&j>20lEFyaHhNr;G2cd&wo}e^jEB8`f z^_Sd;y2QDup_Y2M^%rUT;g@w>TAub^AeB9B!4;FDvEZRO(Lek;q1xQ-zbyMvbF=_AcfqUMGp!=rfWf|51UDuV;1=--k5AxpldW^JbT6tLF}HUx64bzPW272g5@%(Z_^ z2UOnW7AGG&0Bv9V;Z$P<^bhF=?8SWMd;)yAR&nKxqhWUcfR_PK{nc4~0&M|D=DcC} z$?aHqZ{?nHXo6seLiz_ZS6H0%RgDe-7UrB&eUG7g(t2y{Esj4vLK!mjktwBImkNK; zphE*UfMJ|SN~9Su7KtV$7`AZ!yah#bCy@TZa0ltIPV~zZghso#UFDSt4n8K1E_~M0 zn+KR6FB3R<00kUyIGKtUWt+7^B|=kbPKEL*yh_77h`C0H*o zZJvg{=zRFl5eGu$h!qmmP)D8L{RDKszhm5N|6^}x^u1siA(XkI#hu1RilvzK>;-u1 zM+KaTw;~zdO_a&CZlv_XoQH1(`^%;s&(nr~FnMC`UrFo>6YB@Rc#`0grc0o_+T^gs zo{ zr&~X|FPDSv$hb4x>*#ha3t`Mvzb=Cod8q%#VIHG6OsI5H8|7?7kX}wD0p1GEmOqUX zP(4W#k(wB?T>?e2NBa??Hi09kF-}#6a{I{Y4i+b@$#VM=g9k`w6PqB`3=QViE=@5G zs0PKC-F}mn*VpJ*@bys_WB&@1aa8w>DOE_y*zR(H^71`L_x7X{1F3h?ICGA)F}02m zp7a^(MvH7;tLB_+2$RcFXZm)2(Ad#4g87xd7oxrT$LjZAG7Komf{EKpE!XXb(Y|PT zzTbw|N*`^t?Uj_Wk-;rv+!Z#3?mPhOnj7&4lzXg??Zw!9xOFE&88l-3M_2$K3f9}? zVo1?A!5*?sBP=Y@;3v zVEOB&aXWE+;-eFkkptYRI>QP*1V@Y9RpTRTU@VH;`z$?A`3Wk01r3* zxVP`XtnFlhO}|t;$0LEJf`$9+IY#%pZ}6Aoo7y4UHVK^O=_B4cRax&@7LCc%kll%o zG>MXqbw5 zCPs9b8cnlR_x|^-#_E6K-nvqSqWA-UT;s>kJYl&2;he?<8b>I8?ZZ;y*>B54G&bE- zz=TM2Z*9iK1vByTLIywnlb(N9fxLj>fsGj3Tm3T%&Qjwukgl5OFX9CZg`bL=la zvFeIcG>qxeP8aE70tdW?8+{m+F)^mcd+EnrI6Eu9jR-D^Y z+HbY5olsar>&3p%6RQ?seE=D%F)zjaq*nt*u-6+tL^l}pS)tItwa5I1#i(Bz=ugvI zOUtiXzecNHQS5Qo3iW%*JO@8APY{gaZ~l0Elnv(~31sB2lf~j&Xnk+3UIvSX3_Xqd z2lT0S;0LB>_T*2NG~|XT2jheY5UZn_%StBY#P5k~d@N>MRj9~R`gtO_uvPdpc_pp=~xOqzdrl1 z+oeNdNUMX78khyY4y_JcYJcOqb#`fx-cRh+^BXpzh^!6=3&i0Oa$7ATA_my?l6Uy%mH&qz`u}r49ypo6CXnwmo@xj z9)X2`uFWC(RBhEg?HlPJ2*7pkE%tk~eB6BUO>rN8Yk&OE^Aa$J(R{PS(^{>O5qc^N z<|y$N=Im`FKEM$qH7|+0l^U^BF9!eSL9-Z3w`ub@wki zBn+9`uJYmq?X4<+9L~BJ1e0n|-m?Y%o5kY+`Z<}E!H?LJNA>I3(0{e-Re9>1giW|m zA+|rhb#42uVU0mbIh966+wG`09JmznTKG4xze=Q#UarYg)qKFuRxuAnA5CU?aei4< zZ3turvXGudAnQU<^Ilb_2y6A-_n|EFwCwP6lBo3?n^u4oeU2MEcfi|rTY`lHg$h^( z*=s+!S$OL3VU&(}mbvAg%6iWx>1x8s$ox_@B7gSumvJlD zO@`UEU`s4Uz^VOM&=HxrXH}lyWsvf87aYDE^r3ji;ip!XC#hTXdc zskbYZTdo$*b=kq!#+Svz|0gd;FeIk`oUD+GDn%Ml@Ti|213n$Dl|pE+K-!$}nXr`} z532|2S)iJ44Y^7{dU?P}oJ;|rud}u<)N{l*mAl$!ekAjvW=zAfHYkm?LmT0Q(d;BI zv~rXyL9V*MqcBjsK{>@(=!qd!~gsK zdp;u22S1?8cfTc=$>8OrjDQ09vfd^eYOvvlF-SdS#85jEP?BB3+H9&EblY4<_R zwQgqjJI8$UM#)7D(z8*z`sqKPxQ0u^(U59sOc+Mj zdD_+3>vn|hUf}fQCTsekc%4ev;)!PnAZ}ui9@gN)szbJ4C2XhZR@IzJKCl_>+u%~C zM{Mbd;kU0K{fniFAHFyzTd18ni$d|upKNQUIrJnt5G0{Eqj;%jInxXnJ#`sU~HPvXX3U7CJrbMPsvl8YA+`K`aI2CgCjt*-@Niwj9w z-PX(RUbqAgAQ?n`XHbTi`I!HzQ21~kyVVEo(LA8RmMM48m{CM}XGu6KiiuFAt=!}# z0c$yK(5DRQQd+w2185H8Q&v@Estt05o$Rb|f7%fWR#Yb*EQqQWM`Pg@H8XQ>n?x*) zklw5-zT+Z70N@?yW6E;uZG7{R`7>NKK;^v zC^t5hwXCyA*moMTZJi*<^$TB7m$KeyjNKxi2v2E%PZ=ZhOelj>sA!@5Z>z>}Pfx6BRI_yN!iX`+hQ#Pr40oCGB!cV9r)V*#`?btFAYnCN?5e%q^cA zQxU?zsLp_97Rr6@=n&5KAVWe?|D>vf_A`2QAZws|=lw5xi(r^D|)7Cysx1f&JI zF*S4fq4ZHO6>~bJisjC9r7J1CC5rs7oAfwoF{l=v9XAH#q4`(?LyG?bB*h7ff(!{p z4FO``)8`hS&HbDR1WY3vf&E()$Jm8fKu?218~y@JI|B2cIpt;d8h!3EzNhxAD7|X2 zDj7uJ?pjpiyQ_wZ>1|b?w9FF(EFJ|n)mEwHJpjsbq*~fkm|qw+%OW7<8v#MPEEV%{ z%q{E-Tle$HpKHLXqb9F}bK+gLQZ%-~bC@F6CFHEYjSZKmj9VsZsDO2cU5A31PhzV! zX1V3@k~j9QO{!M4+%*cXh@P)!xZL^-8>n7ow=va7S9?9B{XF_=O(dL#Vl_DbP;tGJ zz}n4$WRU74=Lf9)Fz4<63mP%)Ha`waPev{m!eSef>30FzMU5%&kC%v)Xe5EZzkv+K z)l6XGAAjT;qF9U88kC$Fw9`P(HZ0#Pg(6(q#8zheKcvj9ng1&ynXi2u)6njXp2{s> zNV>_I1Q}l1vwOEc`(4l~;O#(25NDeo#y@9A$f9~BXFxVA}+=mS27 zZm1p0VsB%tCNNn%qdHC_nkJ8=e)JXd+0;ahP^YS+MEYXI2ng!dn&p-xV7y3$)Ou0xt{`hc{8b7iK--(?v(Pr>=q2{E^Yu6Zo_ck} ziBYfDDCJY+nX!j4&#__O=GmU=i61bn)Snf}qJ^w}`U8C~LGqzJB;zd6iL{X3x{_WRviU67c`9#sDCDSZ|}W)(NrF)l{kbEs?=V4*)|J zy{KJd1`+SJ7Zcq_BIUIv7&8<9Uzit zl8TQsX=ly6Nw^W$?=>}4B}TF30W`G)cqh%Dk)me$f3+WKwE ztZ?ooc@nG(gVIS9+b`n{m&Lp%x2O#Y>d}KBDDTF#+6T{2QtL1?1Cb^pVS+dFuex?eA)F9Y=^R=sQ#Nqs+qDK1DFs6R_MXLdY3R?c*Z2X=+-M{p;a4(#Bs)_$U z%%q_5psrs1IqHQ%Cqb7|wE&ihNc9wtuyWo*jQSV>*a&smF=`#kRG?g_9O_*zKtphN z$IkR%Kec0+;~o3aJys}<3Z};mbiNtog%waDn86qNVhhXNp?c5i+PHIR91#tBsdmjP zSARJF9~e0SlJ_BB>;Z{27`@Hjk6}Hd1&`G{7`Fa*B?mw@07K^y;cz-+Fcv62dqUiX z%mu%N5;=KL2%ZG4`^h}aYUwEX?CQOJqTVcakrIMUwSMMG7~1*L|7R5FNtR+=7Uw= zKxvb=4vr^OX)P|%>|J&>CaCOrt}kS_Oxh{C#o;`>N|DSQ-JBcNqm=^NOWnlmor2l@ z3yAdMkpn^ftd*;c6q*MT&nEh>`si1m+8W+CFTq&o$lL%-`A0 z=k>(u*E>8}q$JdHu01a+2W$}yCU1#n+1f;!t_IOB9yGLGU_n|qw!bu9@EoBiI;S1F zJAu0o4=em8S8q9{--pxPu_{f_@bld#RDvgA-Jg_8R||6)ohruNK@;$gfL)b0W&Bfj z@$mr)h(Ghm&;9@vWAJn4T;mBFII*(!;drZ3Qok_PuOoLF&r8<1Eif=NHSb5VTqA+h zb^Gp|M6jphiEr9D0rER=Q6Bz-_TYVbr|~_eX2Tt3*RU0gAWn_XqWV4Lcmf>hFKeep z)BBQ8?yIeRLM@J=(SKX!>XRi$bEf|^%`NHvWlsm#=%b2DRrAkL3wu|Ehm~J>?K&gX zb@QZVwghHK3c?q_0=oNMQhUO+{PtBphPWW(EI4Rgi>e4C}%HXeskX!9w$#kgZ z_8%}r+D0GbPxsohov|8q5c-QhT;16tw~JU2-^>BNE3g*HQfzkaa9Nmp72lQ~T$bQV zH`}w2%zI%0Jqfw{UD`n4)T-wow>dlXjxJ}GA{NPFlqD$(qPrWL+Mv=LM+R(Oq;6QC z_)`|2R3$XChiH|eQAxj0^&Q5=Q7P&&v(P!4BSx9)glJXAXFXOBpm2*Ys#Uh13aLhO z6Shae#nS3Bug5$29`n=^1Askaw{_YMYpMF>yfT&x$To9FpHHR%A+z_yv+Pxzq>eN( z>4W;22vxmW7=Ajpcn$5o#F()VSPz(4wi#cP!(&QdSA&CF6FNn=Qbs8Fpr`*n`9OKUFF0hNdw*cppB1~52 z4B{M=iPrdA-}ciLIF754)Q3cS2hDgojn9h%A&Kt4lovhg>#tmFMCExgsde^-znnNY5Ihfw97cv)CS$csaUF2xakj zqn~aGL@@qot%7;O&hzd^tu90tub;gAk9Cf$6L3XsZee-%kMB_=0Q!M|zaMd$L12)V z5j8h($|p$}SI$G)a9oNR>_QJnvd;y6QyWl{@13cYOV>TGK1wmpEZv&9V zeL-3UuvNM+SpgN&bputAaqa?3k5aWqzZ{@sJ;PAafp>F!%!NRMv*Z8HoSuGA%{2wQx4aD(5RPLl9?LOS_ z^vu(zs|4UJ%7X#6X=U~Jl@6*n75RI@c1$}GiTh(kv$)xj`4888A14~?)Jxah^SOAd z7PtErKN19dDIdavBaMhb>zrmvS+XqW*XpE+wfMuv{}$9C(8VXHue7mzi+Rchq7ZnABPVp-4V_D;g^ zh%Mf@7pr*0*@W5MWtfLo;;TJz|C)f)BLo0B%cyRJv&BKP4|jYg*Rc_h>XmEv0|fY- zr9y{A5y&!f=uFcRf1Sb!AvC!0{*l4eTO(Y4&xc?YYyd#dasdLs|6k@kBf_IhQ|fMu z6xrr-#-PQfs+`DDJ4tKFw;dX7XKX3SzRC4#f9PK$df9SOv*-npm&G=~;MyR)7vj+XVh}Rs^+V_+Ptr;#{QMP)Of0xBY`?wz-GtrVQKjYvWF`Sw)xgd* zKwLJq-zOZ;Zw6~~`r>lIort`D^SSvuApKpw^E%HMMH~^z0@4NmvM%|F$s@G>JqgA@ z-AMHwiFSL)dS(2Z?=FF(fCle{+Dm01W**sCl|V+FH$Q4zs8NW$$)d`s79{KT?xq=jq$$B@GSS`3IYG6$;OQgmT3cc>f^ zRnsc}SL{u8A}1fhdR0Z{iaJb>CGp3>aM|eVvFX0O|50i17rOVz|LP32+=OfcYvh?e?x4wBHiR@ zeB8Bgnjy%}gvwed&pkeV!2j1J+oXI*g1DEP>f#IF^^9Kp*0ct8b?l}Bsj9%{*blDu zrHMI=`L}H0+73X&QZ%VcOF1I}l~~wXWSWd*O!BOUx*q>FB*z!1+ETn40hFgd71B;7 z&y8Ofgl*@eqFL<`4ocLO(k7*x!J<@YIoHfB=-eNHeS&pd@?Bt=e}L@#S4B3fMV`b1 z(;RIS?VatH#gOUr_+-7!#rb5OLpYXZTk&~dCP7fYydDsP0F8 zwxT%=m!(x(uaaALiylb+$-s+#tz4^68%bpz=P}E|hif40_@NedqNS-*<-m5P1kPX~ zLdXtGQ+Zr*i8!}fj^^+n!`;SRCzyZ*!>+UZ^#}cPti$(%KJ_1yM-NtbG>r_XIbat5 z#0qKl;{J1=C{hUha=2%dJ@;AGa>Gk)#_B4)?e`wJ_3kBHK|0VUeN28^S*RU)A2AYK zyM6@dlSgAD_KBE7bfRD2Qg!kn7lmeKQ?(AW0r(Tyw`vrlXN!BxP`AeIi2$XUvG$#~ znEAg1y3g~VrZPCn+=*hE@+jh{1gyXpCW+tNFoGVo@xpJ0x(jc`yY+^|_(-~7x-3{a z7>VEDVV2iH%E@zs&KXULd-$ufoWA)*_0*gA zPvGR;l=v3k+Q44k&95>qzEx*iZHI~8jyV;2AjrZgmbzz1l@#0kzh%;hl*skIVzTNILB8G>pv0B$Zn7c2(M^-`drXxj3OwC2U5(d^bHuPfq<`=>10v6# zr*a|VSfs>5JA>DLlnYhr^~fi=o6}NWgd3A5*~Y9EkM^ZVi!(p`$qzEGek*Ydf->d0 zJe#97nd9EcycV~<>w0pl%0iE8+{A%tP(hI?O8SC}=tKTst6pD`f`vh$3IeH{8STJ3 z9k)<6l9T;@9u1UR`1VJNeZsI3U6}Mwp%=wMIEeRYu2UO5_dQyjf69r}Fj;xUsSI*zv&8a+ILMk4-a+_~gfy6&`Z<1_R)`>GXs2;pFZwXG{ zSp+ucLHrSlZML&tOeLB|86-R_(hj8hIq3|ys7N@y;@+io4A^};PR~Ga1OHQ3pXQ|D zI&9Vc(~G3t{WCk*siwy@hMrk7V|{QC41#u?Q+oPwtqBcgX;i+NvH69VtY{i9RtpeL zUm%V=lZ)yV{j=FsxmY*sR^SADRK!r+ccvb^K{R)f2|S&pVq60AXdxPRgjX}C4@cs0 zULszo=`-;1?%%D&4zGHO4^Q=(ntrFaeT!&7d}V+vKy>=Ui-kT{Q2b7R?m@H19aT(r zoL;PC$D+h$x5nKOp>kuTpla4sUQw}g?f9%Sw6nE*%!eGR3&VXvK?g1lYC&{b$iaj9o6fsl{Yrt_Hnq{g*yXY0Il`Nr@C^+ZW#)&- zDrU7jf=s*$4E(Ymf2EkKU^9xb`C8FTA%8CJs86%KaJskVTbxW9tmFu6uB3)Mg45H} zH40>;Yi|VKn00z{BHY{Ssca(bw+o>kV!cxGZhms4Z=;2iQ{)#MWwz-z$pJgm3zhW! z+w8H;EHp>Xkd}%8+z%Fn18R=2-VWEi(W2*W(2F|4ka@4U(4|>;6jGo@p(&-(jLJr8 zi0F%<|EY$1P}_`##Z+{5^BxZvxVHM1CZhS0sb6G;G}&sm&K<+y$UC8;mh?QutB+jZ z=Xr$j;X|Y{IeGFP;o8CBESnK(6k5qFeRYJ7ZGa~WRDi_#@$c(>C)M_ zp&RWq%s3@0LT8lmT0*@QW4u4q*ZsH9($&;UV)vIe_Vh9CXfS^(ORHduJP9A4HG45z zRD3fF{i=Ux5@e^_Vw(iKUPpIQ>b$Ks)&*%;k@LQjiA^VPfyAA!J_h4SQQgnUX*M5z zg?q$2*l`B_mOAy$Tuaga$@J4%;7-|NzXk0zIdHY@f^N8+O}(3(4})IW$k+_$OXfXjK>nhz^xF$H{XyFYj27O&jhWf8@NtU;LxFhJHTuE+h4rqRS?s% zIJ}gg0)F+=rRsT>bOY0C;3h+9v@c>*3ho(qe1qm+Sk{yHuDm%Y*ZFih>wD*SS@74D zn=Wz6N>=&O<$-U9^Pe1l&POm;F3OYNT9=Jl-nm^&M_+lS-V_XHRDa3XMV^}7O*T7M z$foe}5ATlxQ1mv{@Ams)qy~HK2>^&|FMBE!qdW1 zds8Vorm(8VwYfY?<4EX@vt*JT@cyil*Iil?L>FG(4x4TFp0)cQ!%x@f({_ygR*s%$ zs-6X0o3iU(A+@1Hu-(L_mcQROC0?Yf_Q_Hi#ypUDoiO|=@q|&wGlcM)ev2mfLf1~= z-y1``*J;0N25(EScg=YSb--Y*i0@lAOZv_oX?P&TIrFlga#ksz>h8pE)HXQWWKMGm z+286aXP5UkJ0%5(8ePrH?)6gkcPlI1i(U2JNQ-OO=NVWQvdbzG|vKxMw;i5q?NPz^)Z-e^qG(J8>RJ) ze@f69ZAaOJ@~Pl7X;t|wg#tsDXnYxOs5Ze=fn${IHMe<3aS)2=&xo_6P^y6!Z)SY zSvj}AOtd=xp0#RhAF=nI8-%jzLz;fEDx2*3JOo~qAfDqCf3-8^qis^3fB3duBd@+c z&s=IGeUCp(60(BkcR-f0pL(M>!f_*xqjz{sS2CR7&FEz#VJC6rBJ`vn>DA*;mN*x3 z&M+U~0En2DzAHt&wEb}Z5k?!F#||md!y-P1zz9K(l7heNoT!B+x|F@#sjeaV)bhiM z$o36)^={@^)55}UbtMb?YYw`-%J3ad^j~KChF^r97>yWkacW@5c)n;JL>dFx>?j#E zCDFS1QVH5wCEht391xq$#o75YLCOe3VCjtm_viQ~XNgwnfuBBRJq-0<2Pb_N-rQLP z#y^=Zuz4(KI``wCDQ8rMpt25DX0z1c$};@D3rfMU*h=D~&I=o>FaUHCmk+CEHA_Bw3LOU@`GRhENw?8vF@*{MBu65GfduO0HjD z4t&N}>YM%9kLGrEZSJ#;B9-=b1Ywl~PIT-eX8*ZYHt!g{+_${%m3e?6=HoEEsF)vp zb_GkU9R?fv5=JvPrM||tEHl8ih4TCNF{ zmYE;2V93!c509*}W8XX5{86hkV6u|3D0<+|HF3cF!zzH<_0&BB2qvIL0JAKS#N%p$ za*P5|J_*u#{3(ZGCieIf7m^+^d`&QiRw$sEUK&H;ZYg4;v8=};7NLI8E&y5mrlh}_ zXAosaki>@CIf$yb!^%gEg?fBw?Y1q%H)s09l)!N^Vrk?`?HcJR&sEIAL#y0bkH0S_ zC*J?0{i|!lQP)<`M{T3099hvB(KVhit6@G~24dAO4CIMyTl7?CU;l1KfJb(pc`4#N zYc(|U>DSheoTp6%KFFEhGiD;M;^E67HwOv(92VzkEGiklh9L2I1q2ZQqbR=-UmZ-{ ze6m{fhXf7$-c+b5_pU_XYj}1$2s*$Q9J(&}8Qb)X#>Y6iX$%+1gKnEJY*(jlfHT*G zYnMCgFKwSJlezCf?@)s5^s6^(8;kdsDpj`h2jy7a=;V|1WHh-Pdi2-P`~LlKy)3(& z_FlW2`ADh)j46Q*a;fFS*XbR#@8o#F&$pe>1zwQe)TGPukJp zLNb6U;H<2?FuB}FwIDGukzB!*1%aCRf7eer7yRSCC-bLu;^ua?okC$oK1keyS1X7Hi;=}t zzWaBlGgI{^iz%6oZc7;#Z!Vx?Z?0;0dFEd1mu+@DR~bjoxOw6A&UGyeq|s;nwq4_S zg-;QWE{3BQ_r0@(dNE@t1>hZ|KF2DxEkwenE1OBbymNQpS{I5c*J0c{*92E7+?qx* zJ-HPT%MR66vOMYYT#9FTtuu!Hg{Zs2J+pJM#XWA;Adp6Hsdy;9K`j!w$Gvf4KG!-- zEX;ciraZ)ErQOVlFN3Z0Bo3d|)M@3xleUaWwQ#>+??32{J8?)G_{w>b)~PLhO_vyS6R!mgbgID8<++o7)y$z26v{isjl|@(0VK@z&2@t>%gUahkfTcA2wrIiTf(;e9ztX zo2^OC-X9G_gRQn`IF&T6HS@$i(rW8=_e8a-Ra*4ZI=E6VE4G2Z0g_f0leF+iGb624 zM6jR|A1PDU^kOx3#?b!L`mmLz@wnlp7U>s#OJ>p1z?(tI@MJCQL$v%4EMqkVtVe+i zsaM@qFU}t@jVaPsDT`c7pfl zdpX7FX5Y`IRxSLp_V{Mo7_O?facd83N%dDO?6D9NoQod`$BR6B)JMspQCpv!zB`{Z z{1A*E*+KuOh3nkKWwe>&`ExqQ&8LcH?;uu|I+QsV)pTEd^mdQ354d-j2R%dsv z7gh)seZq+Vu@N>$Gfz&cEqfc5=@~P<2o|^PmR0MN0>+Mx6$cq>7$D&ANtnoJepMC# zHY-m@o@?*@WUNW^!fguiF|Jq2o?Xo>(PPNr!kM)xGG$+Lp{C{G?Jcq z{TgjJG$>vq7=5_ebgkAghRo8?IM8FD zt1>(Dk7Od$!2DZweA8IEsO#6H*qt!4(K??lAws(e)-9VhQuC^6vz)H@@?kTWjes0$ z@RjrYnoT%A8tE!_Cu`XJyfNH6!&wtJ?t+@!aq`A}77)vQAAfQRzvR#sIiJ zq(7%^1wS{^U9Lg?P;>k5max+-a(ehtLZbbqb@!wUE=X)B!WJZf{qbCYJ_Ie7up9k$T%<@QkC#>RZxudL+u%yq ziQ972mV0=QQsTw4nd>1+c03KN7aty@8&DvI4SZKb2Pw*cnn1DadaUjf3a_;Q{F{Mb z5N!Witr7j>k3!?7auV?SJvzbMmFi;)-4GK?P9K{2qvR7(4GjC@Q8e=?@N@lW_aqDF zOTG}@fYQFUy}KsX)SLVkHDyX=ff@d472)i! zm-iUmn@E5*hKvp?FbJdK8-lZIOK9*+`SGV}gMf}AJ-+?RPToKQD3=j+&R&rsV5-<^ zr@V%mR>K|;#4nh3fKs(fB??}XckTYhWWu~;es=YO^kZnGw=GwOxz1Gaie3@^AL|Kz zcp#~Qi*YX*m{HD{GIw-NWJ~EHK6I$w$awP5^GnO8k!}ED37N|AHT1<)BZ-YVm>gl3 zGwGE zZM8Z^ao>_|niz?{K~Mz9P6>{hmX@d$=N9obKTO1y!OD2@ti`oRoZ+eFX3EC~EuBrd z)v-d$tw5TQT>HDu^#=L0727JMtli$uY17Y*d6uMI;XQ%l!ndF6w9M<*xhQ`Bo-8Xd z7(jmh(I=EvxiGOENTOLthT(hY&=bTcwpgHwf0aJc+drZumB}E~+{ddt63%xdDClZCAjlGNkfT z&_8I(Dtz!k5we<`sR^Xli9G8KMR$tkmm~QsydQ-K2UA@hJ z^Up&a3f|3jC5{pMdYe58$H^6D^Q!-=v9An^vRm7xQ$S)srBP~-?vavE>1F^)hmdZi zLmC8BV(5~FAtfY7K#&0e=}t$wyT6;~+0XvI{l5Fh$B#Jd;Yc?`AQhsD17Q-G%cpy+70T&kG=V)`T-p6RzHAqlJNIFdWEK9{0ipGWA(# z8(9OR7Wvbfza?K%6RgdHu4fkDH{)4Hknmg%>ekmsA&R)l$9D#st+=l`f#YDxktZ8h zuE0w6n7SUJvtrpKE~ClkTv|R>h({{`cT@}H(?qhB0fOfg=w$n*9G15Z24TYy@U>a6`|6+z(ID!D4PP3Bk~8)s$8k^Q2d2(T#!RHK*eTlCzSt z%?YVW0gYSUjch%c9_wnB-4saRse#(14EOI53~TmBk~ub-B(TvX8EzD3qLr%)hZW3c zg_m3-i4FoObhn-Tj9@+6?G#yMW-Xs}c#0A#$M-xPj&14Jd{N(e9tHZMrq2AmriTM# z_^~Mn)_kzqR-rHq-C~1pfaM8@7`;Ma)r9&v2=R`O)6Ch57334(PN^zXR31fm;D=_u03Zz4Nbtlwc$8} zRtYOh+Q@DS8BkgM&PO2X-3FTOyOE|&a~Yf7LDVf+i}*g}=5Li_({z9gMfB6K#1zc= zM=G?cBz;bUlgx`=+qC3?$BQ!pHcUZHD~$4XaCWg=1N+ND$$oU6A`e@!tASZ4LwK(w zvS}|US@iZ6N`Qd#@Vg3T31EXMN6HcP=0!Bw&wT#YbMkjMkZ6y?Ex-zZo>t`kni0Pt zSlfkw28AKYCGdu484UdPbSHmd9{#_EfBiM1+&#J7LyHAW%R<;gpjTdNw%Ndg-B z1YG-vYY;loEWb|;=2?IQWRCAkrn}QYM4GniTxc?r?u4@b!lO>dKbOdEq#uE5t7b?w zT2^9?-j-z7w){;vDu3JhYZ+TvZHZAuW$rBc(#WPZi5siegV#5mjZby)5jn&N?VrsF zH^lt&PFCsIJxbJ|?T#4!DV(ET9(9^!pQ`%nj#0Kk7IHD`8&S%d$K$j0Pot2{VRdnx z5WDEmLT=dkznK&O}1J>eTONm0BT&G!^KDqMX09 z*VA6Q#*On^HhpELuTV-P(nX4yQ4Uh5Z-+T_RUdNw2G;yRT5WTmc`SjnmL<(X9I26R zQ9zuL-fXTamJdD``b7ndUjwN9JSg#j<*tf>dhr2cY6d0U;$38|QeJA3^E{%L(y-H? zB>s1z#Ta3T$5*gpuxUZz6De(dfWxx_Nc2`(y8H+jj3-@I18W^=|LF`!<*MUxgZ)Is3=T@`QbQ4>!Eeq&)o8_c3PF^76ri z&OBi!WnuWDfN|&n(DHg*w}HlTZ9j^$CC#sx1(*+FODURM@rFP8oKcg z1b7!FROXiu*rqb#qWYYwCfzU!<%IuM&2sNKsmzx^S1nu!pDRy_r#SZP@fhtyQ2fYW zlvZ&B>R3D+*>g*?`<0YD^LNxf76OqKR9BA|m_l%YwV_}Wb=n{~ig3jGH>6q8ah$fR zNm_?1DS7tkX41bz2{rXFB+I-g#CnS{@Pgd>kM}F#(UJ$FqP}93E=3e*6|*}iuJy{t z!-&Ja6@zMaOkKhwaEol$8M``Wq&o`u- zV_2(vW*mc<%>-o+Gcl$Vy;x|vRfX6xu(-WR+Zo@1sMy_%K|6%5Ed$-#$AjZ}sjNN% zj{qeU<1O}cmUOtfI>*NPh}YHY*qC|wOp?uKn>K?E>y-`W)y=}mTLU&@6;DXH0_X9r z_78MA(;aNvAx{(WgPy$eFFt}~rsw{XiCYmdUdM<0w`$0N!?KP?N|I;ix5+MVqp2HH^=_;{gYd{{U8WBik^R$==ynlFZtUBGp0L7 zB_$z+jN^SfnvBO;-VeU;GZ1}QWhH1MIJbmbBvlZuDTQ)BZA(wtp7^U)z|$4B1w04! zKo83RvU4=J0;W{Eg}^r}Ah5>n&}2|}4W{1S+&L_*HNR5Q@xn3Jbr!H*aqA6U|B%T% z$bljQf*_<~xd&IUqftB3m5Wa^hM#^m;>L*C8}p;Rf5>YLFNIxOOw$YWBN}Cox)LAsAZ!&z|EokD$+4+KY^av5fjbQ(?d|P1@Xhp&G5GxyTdL&62OfDi{dm zDYYG8Mn6o(>61?Z`b3ll7LYDxZi8kvM-Bgcace^+zgk?qt|LHM235|zcWrIoBk}i| z+VHH_{2$4*V3cR{*T+`{7`j;Tn9v30P)n^&V-YJ&$0~~fWZ&OK5cTQXgb6RiM;V>K2{Q`BTV5uc2Xz8gL8U7@vbUs-9*8>=%SCvzpcX!dir}~?6ckU~ieccX? z8^$T%On)RBUOGc2#5!!)Z@~+oc{M;6rDYcYopPf1ImnisfoHjQ|LcWQ-QRg|02^2s zeFqSR_}NDGz`)N-FqDF(iMDym=dx&Z{2S*%UPe#)8vY(&J^6{*6YBlwn@ftW*9ah4 zd~X&ylU95RSWPVAx`AkT&uAMop`IWJEDp>H7%I=8)Lln0L2$&9y1fb+j-=&SrcZ9n z)@nEDUJX4BoQosyo#9D;t={-5Sl-co1&Tx?M}5i{3jqz+n;zQuy^udMRtt0!Ymb+d z^LX~ppuOcoX#j|L{KNR*nqWCbB)LYDJV=weO^6S^L}1gh^>6`U+g1G?wajyhG~mP< zhft3U!faB;xET?koxEjp*I^zcFD`oDtWwK=WZHGF%CA*=1g$JmnxP2DdKN*R@O-== z!MnD>AlK4yeyFh0~ zMq>gk?5Cv^zXM+br{iyuHJ1b3x0Sn-_GM;!DE1&~@lr{fidmDr9w#i}(K-!O99rf% z?ZU)d7N5tf(7~RinW1V4E+W%eiuM20pc8WBt4SE(ux=uozUT3{uN2b}xg#S`6r;Cc z86=OL_);OEVibxJOu6%miW-=Y6q)GE;L5wNk3INmG_1fy|8TzB2>rTx*Z(J>`u(!- z`qfb>n9EjXUFurc&Pw9{6|hxO0C-%5zavuR#@m)LJ_35c(IGHirs$xuF zUPMh7ZbMM`9Y4>ASBa8T`Jig_lVU88xeH4)mBZj}vBkTBx>plXcWtWbhYNpTYgcHq|4J zg>kx3s;tbo_+hT*9K|C35lCP@dP4Ppuu#Ut3J9&QFYfeHvrK^J3%ws}Qx}vxTn@z9uZp*1;4EG)HRZKBj~}DVvsCEVk8| z2X-vbPcG6)JWI@q-X%8kS(?)Qf=CRLWvJoGXuR`Bg5)%{m0&ZcGRB>&0If`0$X&IdM-^;1Q(e-Quo_Fu-7hHj}I z>C2V!Mr!@&;;H3fjXB~??skJC5a7{=J&1^guk~*!sL+@{Kv8Aiu_Td=hX|qFxP;=< zQ$I*;x0ADUej@Ox0_BGC?o%G0?V5Men&R#q#j{I<=%mNB~AI zYNt!8OMQL4ljO@Ph@g$)RIkM}Desl(EeYd`6CaquA&3Dr2Mvxe&%|%gY~RM+B?3Dt zsmJRJd1u4u_|(eGl3n%$a}H@@Jyb<=Yz;d=SGq>@@=~hu-`CISUUVhfEhi`hNOwFk zS-Q%9bJN*a5&z<*OMyPS8y@f3d;s_^8DvKlo?c)H`M*2u^yFOdOj*toaF2M!~ zhp>#|r&4*$ETj+7jWLCJ>(9G3Lp{JYLm*_;mds>VHXstCA>F*i#--mss+LiRX)Z3= z(;@5G%AlqDeiQy58|Y3SR_Z4(=50JHsPVw9N^_Fl<#%S3jd!BTIeY%%IpjFa@gKmN zSX$gDHi|IcX#iJLIa}pRX5ws-o9T;d(<2Ffm^3weT1qI;5@=iA4{;U?0%KZ!)A6Ow{Be3XnjU4)1gLMFc&4 zh^i@fJ#XjS_h-r@4xE%BSF(G~e=&EP<6VlTM-gMWF|&;N%wcWXIH?n#$<0mWv&>ti@$Om%8E$UFbT zUZhdlwcAD$|(a|;G`iiyWs`J+nI5o(7Mv; zvbqDL{}n)Y;zMaMfl*mT;Q^E}jL&oA63v25d5%R;1HgL^cmlRfhNyB$FS&>kiLdr8 z*kC2b#jwwsYH{;rjO^`cJTrpHYvrX6Y9DFWD167~YYm?VTDdVKN19^$G1lY@AlQ7DG?-9T|w|P@!pVCqa$@_^__{q~Kst7#YxwvT-`uL~2 z{axCL3HJ2-cJa=0SX)6mg|6e4It6$zw@oghu5N#4O~Ph8>@b=~2pj)IVC?yG#gN(R ze6rn5w0Fe7qSKQvvRX3}FTOOhqDIb@yx8b3GKb4dX%>5D@$q()0T}M2@|(}7pwyY6 zQhK+M=p^?sQ0Zffyo|eF<{4eD`e8vKeFvh?T3N55N?>(W4leu*qa9w88YP5`a* z#<<+Emb#@X25NloVdc|YUr8GL!MHe3eQ`G~)m@#$0K1}un|>pUuHRwugiJ1CMv2VG z=g0%3w^;^wV`|EChJghgn_4Lan6`bdTOq))B%4DWCFBVppCtZ{a!%Do;2FaI2}~jl zgZ4demUI~TLXR14x2L4Ok#EV^xZ>r=0}Nb{2B>vjgL&MVuX$i{&KvtbRe|rBW2L3q z*310OxSM!o+Z?%Ide!5V@ERF#@F0`E=0$2$DQ#S~p|b-C^&Y ziX{O*;*i5$aG#r5dFdB%lq%S0d@`oEKw&_4@y)B6G6fya0UF@!7+N^<-7!i{hRsC> zC{m#zyH)l&`4{qikNJOcBvtp*O>oA@)iJj6BtE`&C0=ex{a~^NzF`}({P1UDbcqca z{>UCQi77$NjUE9sox=NsBUF!+kAEkhW@oAsZ4N2-lIogU$%W2j{#s}x1hN{-r7Wdn z?e-&i=gIfG9cH)zKf==18X+Dg(y6dz(JO08<)t!wNA2+Mv-rvg!Zkvo09={Kh>oTQ zmfp@$5{ak=Tf@WBb?49RRZF>&q#LwB%@T^3D0!j?! zZ>!s1ERN5UspcyvEVCALybu@Fw~~buZDC2TP{=UO8`jL<(cl>3!WRQql`)Dz0KdWN zOk>>NO$0_wep9m9=M#$0i*9eU>qJw4{$K)Z+~Rpd0S8KwX!*kynFK_mPOM##_;NoT z&VTaU;{`9^m>Mv4`B!YR|@%;YOAxcc0 zcp)tmt-S6FOGOi zPuZGud4DZxJtIM#Xts{9_S6{rzI&&qsip=!8PzEz-Kfnqk{>S)g{|z0K*fZIm$&b0 zzqlp&s?#gv0e(a*bZ^h4qg7_p``};u6s%Wb`$|aGXg=>w1}}J)GI0Jei`iAH|NcZ{ zF5y*d587o$W&1YV0a922@||Z`gImc~ro8;ApI@j^X3p*#zCwexZ83=t3y29FM5Upx zFFU-TDx<})H%iJf3X=YiPZh*iskQiM&Gj>$yWU|@b@tZ7*0lB3@xOI2WzhPgq}@s8 zv%*1UXXQcO1Ff&~*92cySzN@_eH2x?6e9h?P}!!k*i$JbIPFH@cHsxKl{57nO(;mn zhC*_f04|4|LGWN6sj5hA?VgsZK8;-&$edp`{PRpLlDDQgw)c+8mLYen;}WNCD+?io zR40YhOI$YGt9{Qd?9IaU57!C_@%5(sT@;c#&-{Ep*YosuB_9_5H%cj8+E{8&XhDL8 zVC_k#H#!EZ660e&neXmjJX z_5)Ez@&%hvWMgfWlxdvC6P!#QBH3Q*gx6{rrIJJNo9I24hCLmRT_rnLmTkPhb`4GZ zL>9*Kc|8r4`1Eb}ocr$3Ndy@mxGKfcv4yf)(UkQYKV$#8Z$Z6+3RKuI+H=)aTIk8k}9J$4H)1Hi$k1D+e zwBA&uh`U0W^6Ig54@FFjRTA{$uWbMgUi#|ek*RN2!_Urgnul0%jvgsV2;+(v{wM31 z7+A4Uaq9OJyi`MvVyk(i=r23g{Oez@^D^8d# zN2B(|v4U+F&?@i&1mg1B5Bxm`56(%zlVRLKB`=1U<5d;_sRPlEqJfaLgftfE@QXm& zKuEXou+L>Gy8$V7%UiAC-uePxL)@cl?}4oRj`yLy@WMCahQ2 z81F-D(E=r$y_2~?7-d}Cpjkv{hiJcvVrjXf$3Us(pB<)siF-{I1zrtv z{>q;oDb3DNheD+}{5F62A8M4|K5WM=8DXKj8{h@|l7KBB{3?JcPaQKnYCn&NW~DtD z2OBVf&AZZXQ>$M4InSQbnYRJkUq8h9c|ZZ;xuKny zUp+T9(PlSBE;Srdfg1A z9NOWyOrMyzZ`_pF$dMr`qA+WvtrHT_m_Dh&d1Co^;?YQmd#o%r&rQ?HvTw!h78sa7 zSDwj#Zu)qf&a!jzmazu9dMyQ~0Wj6dC_2|yF;M3=kfXvm-~c3f7I>?z8!ZzQ@)mut z1jv1&1XiE@iS$YaZk|z=^oP!>EvDCkvlnGHzbZ=Z$~LfwrA$|wgOA(^Lu$#zC|3vK zBUxT?Yi4RJzSm)up-5?xCG#*Y*Y?c*#(TqSe6a?;JJb|Zfn6V6+0ZIGmhXD8H!yYCLtm&yH$@FC(UTWWu=jSA+wYUs2!(~UiwHR>RvPjFGZz8|c z*j07hgHC|VMUA=^Dx;B^57Mga+?y{LWWosqH@JSsW#Y{%sOndAq2te$iVpxkii(wo zDn@aKSi&B%;dC0{wxSlRZa44E)zQ5EjcfY^CD} z2+c!5BuD-Rs~+|R&On*g+m|KX#yL8@nf>FWBBQnW!jZ9UH))~Zh%L9)zVAoQwA5+Q zk1L@qRYBu%zr);Up7R~|okDhi$K4!y$I97J-&*VBbunE?{dH?PiY4ny+*D)Ey!x|q zg%C2-@q?>SM1`Z$hJT<#zgqswu+6>DUyN<1Y7kTkcz>xpalnzGvHK;*_XlYL^daUP z-&w@UdkHYe!sfr^h$Uhzk(kingysRtIKAUnbkYs=N6D60Shf_;lviN}3*(>7 zz?724y>?>W%banS->GRdBlE-CcX%Cmr;5uyzb+gCe(ut-abUE^mTNNK_q6V0SVSsr ze8mN(a`Tr^a>8%&YWc?fnofQ*(={ANL#Un7INTXXl{-{Cpd5<}yhH~AFv{tneg{Z#n3HLbvO$3^BH7MqWK~Jbc+i0tK!U3vpi@%5GQBbE8^oFBS)M0bVJv z*=OF>xWo?>|JfM5%=dKBIfxMKON(BSV#JYcB=^*MB^abD3zsL8k=Xm(9w4@*gKv0P zZIe5$2JFOSx(&kC<7zn6Y}0sn7RQa!;o!u2Bo>x- zc+2@DWaYoYgTjbLSMd3S|8fBUFF=V-SN>r}-$IH1oqB?DZwTDZ@DQsrEJfIg39vK# z^}T>$Lh{w{*SCk&@;DP?=(o6YP|shXlu{hicJAKTLTu6oqCEe6(k925O5<@=h??T1 zu!7gPi>JwA7E(Dw`WJ=CIz({%^6Vf@KzK5O|E%-V?GdPdeg9B<&`HqCRh2&t&0=>< zTK%IY5`4SzKK{#M0DL4*p~bZS7=i~Q`WOSGK48>$2Cgicj3W47{_dRzn@WZANB)*O z>kl6=`!w#=jPE^zXa;Oi3XL0I-ABUpx>I#-(bcriPK(#kC{+4nxb|Hoilx5ge7#hW zd;Cgl+C>zw)x#|YfKiN(hU_E`c^TUu74_)-ZI{5yIglMnHZr#y11`8HAZfElJA=k0 zGS%kf&`{kN>Fr&y@rJ^I>;BiFtv+Q*`lh*98>j9T>FKTWYneIa&e*R#B9SO(rz7Ls zlZz=6)19MZ`c3r=ha*?>7nUiiUosPEU@FY3TbEPA)sg<{qrx8Q{D$;)cqqKr{Vua< ztZxFe#?Smu#+zEluC6TRmA}}J-=o+PoxGl08veKmjORUv)B*Tr?k z-QmX_k2)V&w~T*L(z|I^=YalxFaGDJuOi!9=c1sC+6}8^Ry$xMAx_6nxT-9`g%(`V ztw|f#{sCa-(n>t5?11|IeauMpd&Oc5SKPc^o`^z$$?22)HqoiznEZ;9bHlN9^yMe6 z+Yxbn>f~WtQolC(MrE-&Nz%(Idvbn`LO!_1KJ9W)`~Ir8+pn`G{;zDK9_gcnY_nx_ zz^?S2Mz*%5HplVO0u7+h@6Io2U$>!+Or=e2kGGG;eiD>w6dw!W(dBl3uh`k&3rtG7 z{EAVjpei%qvHRoZU4nyf?emj7f`h$ZR{T~CFg%+$={bZ# zP-Q?H&c?a*#%;t+YG~?{r38BJ0M_d<1q_qb!*&R>>}6{}kxJCo}72&wSXqc)OB)$6scoZrkCM!c-x^ zJ&+yh@;_?KSsf5*oG*LSG#kWY_ab3iOIg#?QT5Do(t;+oV0} zMteh<6D>t1mmP0shwGE%IO(6vqQY@}Lntu)L*E)*?*Fr@x_*<}O~O=yUKIF5{B7Xr zN}jRqVSo{Jnl&cfgAMhz2LH91*b>Wb`}_YB5EuYG^#AL>z8j|%QUq;S4&VEAub}sE z&PFBbH5`*{Bcn2TA#8abLhctbnU?cUzP)|4oAodod++H1>8PPHLih>ngoWkFqQgd` z6+3d#e){+|B5};{4T@8t^I?;@p7rci%3HeAvN@l%7Heyyj>Pe%io8(`trdUQ=}$*b zUHQudt(m>F%oY5bv#1E=H=U8QHP}|}e`d2>x`PI2VKYgVXZ_n4|Lbod`5Ggj?gI;G SU620uO+^JY`EpsacmD^1o}b_V literal 0 HcmV?d00001 diff --git a/doc/html/_me_line_follower_8h_source.html b/doc/html/_me_line_follower_8h_source.html new file mode 100644 index 00000000..89801fa2 --- /dev/null +++ b/doc/html/_me_line_follower_8h_source.html @@ -0,0 +1,165 @@ + + + + + + + +MakeBlock Drive Updated: src/MeLineFollower.h Source File + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + + +
    +
    + +
    +
    +
    + +
    + + + + diff --git a/doc/html/_me_m_core_8h.html b/doc/html/_me_m_core_8h.html new file mode 100644 index 00000000..c484b58f --- /dev/null +++ b/doc/html/_me_m_core_8h.html @@ -0,0 +1,475 @@ + + + + + + + +MakeBlock Drive Updated: src/MeMCore.h File Reference + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    + +
    MeMCore.h File Reference
    +
    +
    + +

    Driver for mCore Board. +More...

    +
    #include <Arduino.h>
    +#include "MeConfig.h"
    +#include "Me7SegmentDisplay.h"
    +#include "MeUltrasonicSensor.h"
    +#include "MeMbotDCMotor.h"
    +#include "MeRGBLed.h"
    +#include "Me4Button.h"
    +#include "MePotentiometer.h"
    +#include "MeJoystick.h"
    +#include "MePIRMotionSensor.h"
    +#include "MeShutter.h"
    +#include "MeLineFollower.h"
    +#include "MeSoundSensor.h"
    +#include "MeLimitSwitch.h"
    +#include "MeLightSensor.h"
    +#include "MeSerial.h"
    +#include "MeBluetooth.h"
    +#include "MeWifi.h"
    +#include "MeTemperature.h"
    +#include "MeGyro.h"
    +#include "MeInfraredReceiver.h"
    +#include "MeCompass.h"
    +#include "MeUSBHost.h"
    +#include "MeTouchSensor.h"
    +#include "MeStepper.h"
    +#include "MeEncoderMotor.h"
    +#include "MeEncoderNew.h"
    +#include "MeIR.h"
    +#include "MeLEDMatrix.h"
    +#include "MeBuzzer.h"
    +#include "MeHumitureSensor.h"
    +#include "MeFlameSensor.h"
    +#include "MeGasSensor.h"
    +#include "MePS2.h"
    +#include "MeColorSensor.h"
    +
    +Include dependency graph for MeMCore.h:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +
    +

    Go to the source code of this file.

    + + + + +

    +Variables

    MePort_Sig mePort [17]
     
    +

    Detailed Description

    +

    Driver for mCore Board.

    +
    Copyright (C), 2012-2016, MakeBlock
    +
    Author
    MakeBlock
    +
    Version
    V1.0.4
    +
    Date
    2016/09/23
    +

    Driver for mCore Board.

    +
    Copyright
    This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    This file is Hardware adaptation layer between Mbot board and all MakeBlock drives
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    +Mark Yan         2015/09/01         1.0.0            Rebuild the old lib.
    +Mark Yan         2015/11/09         1.0.1            fix some comments error.
    +Scott wang       2016/09/18         1.0.2            Add the PORT[15].
    +Scott            2016/09/20         1.0.3            Add the PORT[16].
    +Scott            2016/09/23         1.0.4            Add the MePS2.h .
    +
    +

    Variable Documentation

    + +

    ◆ mePort

    + +
    +
    + + + + +
    MePort_Sig mePort[17]
    +
    +Initial value:
    =
    +
    {
    +
    { NC, NC }, { 11, 12 }, { 9, 10 }, { A2, A3 }, { A0, A1 },
    +
    { NC, NC }, { 8, A6 }, { A7, 13 }, { 8, A6 }, { 6, 7 },
    +
    { 5, 4 }, { NC, NC }, { NC, NC }, { NC, NC }, { NC, NC },
    +
    { NC, NC },{ NC, NC },
    +
    }
    +
    +
    +
    +
    +
    + + + + diff --git a/doc/html/_me_m_core_8h__incl.map b/doc/html/_me_m_core_8h__incl.map new file mode 100644 index 00000000..e91ee584 --- /dev/null +++ b/doc/html/_me_m_core_8h__incl.map @@ -0,0 +1,269 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_m_core_8h__incl.md5 b/doc/html/_me_m_core_8h__incl.md5 new file mode 100644 index 00000000..846d769c --- /dev/null +++ b/doc/html/_me_m_core_8h__incl.md5 @@ -0,0 +1 @@ +3bda152cc7fafdd5e22cbb0fb75f86c7 \ No newline at end of file diff --git a/doc/html/_me_m_core_8h__incl.png b/doc/html/_me_m_core_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..de6e89d3ae4d7e2fa55c1edad9da51228518eaea GIT binary patch literal 871629 zcmdS9hgVZuw?0ghB3%%IAP9Isq)YEAO%%aOkxr!7&_nMvGz&F=2!cv4(joMKkRTwP z&_W0p2qi#(P(IGRy^&peS;4qk$sL8K*{;rZscxO&oQwftQ372tzv{SHZaI#~>g)t;$0W-$%w22S zc_@|OL{UUe)#W+T&7q~B@20cUP3?M(<*nu8$lf(ziIsP5qdO`PBZ^#1@)kgAy`4mN zoT#4=$y+?^-rB!?Wz?H6Q2x^+JpTWo5j?u7C;5Lov8q)E3AK%XD)j#1NKZ0Owb~3u zP=R^l^dzJIIYU(|YQsQst^YVykMCvchxQMjX9~CT>~)^I+~+rE{l@?ovv*(rhxKnm zI(!A8u=rM$S7W0ujpT`&tk`&a4?LE{FYu2sQn*vhdH+8?#eX#Bdt6;k{O4@`56b}X z3rpqy@!x+is~Y{kaB)@t1u!-b37bOUO9-t6xW&s~m@umkl6y7(!DaZkhfV+R`hOYr z%v;5nf?%W5r0fxu?Y16b2eBO!cJ=o^-8+z(_kUl+Nub_v94#6v`p>&q`Tbx19C*2$ z=f7ZjK2>0O9yH-LWy)FDE|w8A5xni7o+%E0%8RpsE$$uu^O6FFNnP(P$^PTAV@(fz zcKCg03Uvq)?ge{ig|HD)572k>e59Yt`WtbP*cJMt5_f()}k+eX}m{QZ{Ied=5 z3Z)Wm33``&-CwvUm+;-4?Z{Xgz0RxR)%-xmwOqR4--G5p z9-B*}GA<~gS1=ggI#03a{q2vb6Ub8UkY3K^i}Ql;lRcUZr|wz|M!3*CwserQ#oXik z0Je-=4EWWmLTruzpOn_+t4AK|!dB0jIE+h20t>2-cG=J0Ulhr(!JBvLp&NV-vC>W) z!?yyLcuba-z=Bd}037iRr6^~jlB<<6ey$9Z!Dg~O|zWy)pj2TEK^`iy|JkaQ!a7r2eb-Z{qu@CXi6== zM`G$?Yl%Aa>DPm`=ZKq4>YtTcyCANhDDIlgb<}hZyDVRH=>-a{{xj|A`Z!d{(+@!j zXiq6o30NA=8L%{7`m^1SP;`@+4msWWR*JEB&(*eiC?zGBMUFi7)p!y&`q2g{Ap>-5 zPxEAwnAB#MWs&mlZXv7wvbp?G+LoE>G*MbW`x;H?pz@Mbt>-at)lSN4{E06>tl+&R zW`dEvy+B7&fP1rccRL3=Q^Drfe(qrF)b6_G#@xmqiQ3k=_&N{2$L&L1`on)K)=RQr zZD z>jD`3O}JrhlcRBF^CTO9*<@a=MKEd;H>9VRzcy)U&IHXP=boRPF*zRz0fUv^v~q^v zR4>S6gHC@YHhEZRh2+I!LMptSbz~KNi{!Dtle2qd6@}M^ozd=0`wQN1#0y7%uJvT7 zqS&5lsp5NBvPB}9PQl>tU=o*E)v=qr1_GYVs3F%JE&D?? zJezOv1|_{8FB=M2V*K0`IwSsb!`Sr);&I?X)cn#P(Y4Xkl7*4YtweCH)$W-v2-VaQ zJne%z39pO7xB-M)o(Fm8mHU%^F%0S4*1)xYa=)r^$Tz-&9BE0=*7^Ly(2DKgz`oVH z^k?d8KVeF3o$;ZNui~23*TWmT7Sb|Zj)Q~37UxLn`O&HwrQs#$n$|x`TO;(2MU6}g zRLg3MKOZ`f>dY~1qeQ^@>P2*>$GI?$nJvK$AB0kM_sY!`8}}uc`kxgskkl6*Rii=b zHO@`X^#ecSWX<`~LpiPk2fcFl%{vggIJ^1z3deQz&5<73PJ__RJbTlf!$tdYf~842 zM+$w@r#9lH3soxKNcrIm zlG3Hyo$MhAC?|J_=C)rxMFom<@&|a7bDUkFUa5k9Harq?AYYzTJNw6rZ0=WbnB^Oe z10L5mdBNXApS;S{rrYQ>cjy$;tvuQ7H0{V=LOmDBbRP$IHW=4U|J%RYJXfCh8?f-W34`j+!xr2QG9>4j2VwEeQx=ARjoP^njUl()6^qI!vd*}bp=&!P zD<&Fm63~hc5}xwt4!4jTm{;=r_i^qYOzYT(5?H zeHqt^%nf238!Jy(FFBZ=tPswB`0Gr^K?XAht20l?UZ`gwDL$z+wK_?=z(Is^tlueGF_>Xz_V5XV`J zV4O+6@#cVe$_8cf#m)?swd-LvNHHD1?*hy>1y%0feE3Fa`wEotaK6bgpQe;stZ|?L zE`T@JnRwYyFTWtq6LZ1)YKX6u8u8#l4$}LrrFOj9f0iESvdF7s^ zBp2b#mG>0*u2p(J9{8$jW`Ic-hvAxm`MEhEGyv1=o>`$LuSWu< zraQ(;PN^7L==(ohD1~gk;{&Un&|03)a7+5LrHV^xB+f0Q>MAYb)(*aQEb8+1`8w>t z&K$x>?Zky3f7Ha{X(#beU}8qdhKwX#+sMTw4#{)eq;lX9M6&?cW|^E}goYk@A;(#M2j@foX6k8I}LT@FkYvE=@~f$Jb{b+r3v66i2#0W)Qcu zJLk0gL35?IblO&GlP`n}^@D6<5%!jtvmxQz@>i@qdQd|{?5vAzhI!-@vfBO?fJP7p zfL@`5Tu3^P3f&7OECsWRsxzkxQuy1h4lh~Kn*T;dccPxjBxxGx%9VopH-cc!ScS0K ze$9Ggy9dg0cdJb-6XGjG`WJG_3n2I0*09ich_x5f;_SBOPg%6G!7^n1?F&VAwzwvcOp(eZKXt7^ z_4;B@xA&bE1@~bU*58Mu>?+rnBD1P;xQcPTEh%ZEDsM&a?P%liO^TOMXgU7rgfB<4 z#r~*XS6}tf?CG3i%2jZ=C00LY$Jrqps;6e+O&WL$Y*0QUcq2oP7+bwIomLVMnCu!X z_ZH@EEw)dd^CfMAxx--vj|?QF?$8T@8Um0$kQ}B{QD+D0n5`h96`LQhj8ScOyHtrybDQXG6W?;7u5Q`J)zyy_w0P%4Z6uMsG)xapGPpSwpmEE3 z4WgsHGhTe&5Sa;@f4=W^fAfKiu2y3L@gLEAQ)IWFBR)ESrgJZq+*;dhEwf2&OMPOI9WkJcAms^T1 zkbD@C4b-QF_U7nGr2tn;yRuA_CDi254MCxdt5B0iRw`ogTQ1_vP!4#RuM}Q9Q_z!_ zP~-Gc>UiA(k$#A#lKf?>5{)Pj}4RmefxGuZFk_7>#AyC_?8(m0y#}4O5rz; zrC**d(|mPcSHJaif2)8iRX`0LtXZa3{yavPDKp~HEvnex8-Z~(+}!;2to=MZ+={L& z-x#PlX7A*wXhIPJw-xRHlX-&(Nw4}2$N?Xot0+8VqZbwUeqxq+P*Qv}^H^CrF71V9 zDaLMp^kw{E6X!RGj<8RV4f4ul^0>UfZ=-(yNvS5zDJ>mt@)CEbm0!Dx`=m~=1jyb` z`*b2ZC}qQ<1sc%`3ej(DKJSJ;K|iqnophz{SJG^A%?7u~eFu7^>jO0@c~lGel=jK z^WAd7%uGZU}jsVFu(+J?R(RW$4}(H)Qhr@0<@ST_jw8 zhd`x(@(>i9Jm9}e*@?8hm-sDW$my6-E9$8(gl-GtJc=p-Zo0Rg)qK`4FjvsohsT{y z|Kj7!kuE&q=nnwRw4~B()~WNJebxWOhRu7X6IS8h?yuQh!^hz#Bz=!rM_YOAn|STO z?pTE8Z5Hnj`2c<@9tSP!C22l*u_Er*!^B0+s~&7z)(nKBrU!3VBhtToT^C~JZSm+B z(Mt*E7KvAg@zJ+7@HAOn3dpPCE-sA#y!hTqhqOHoU~ou>72Ll{Vx)M*#7#}9@EMMg z#wzN<+f6u6aJ^BX9=}e5lj)q=WT4t9J5$B??XI4cRG|bS(xN&=R%Ux`C`HO!^^{}X zx+^u;^UZB;%B(SQf^AGwAyM{rBpCynQ+j9u zx32xx6n`96P0hYDK~b{|(D&#%MK0d;eW*}tM&zfs;)_X`yfl6piiPK6LJY_vRdVe& zmo`6CQFd#bR2_YR?SFpQG?Hc3=>Bvh^xQa9@|4@^q9TTX-p$gusA$~$iC)J}%x#kb zh~YhVy-ZZ%I23Q!ZuCzt{et!Y#$fr9z#%uM_XiRC_9Qh5gZX9`&(zN59%*EZ3V~c7 zcOR3^6_KDV2FL}_jB@4FIHWWBQ}a&KNqIWJlMBCq++1}$r+<<@{iM+JzbnAa;RRK( zaLAK7Ey8s0P!+O$fbH@$h5EEvA-)L(R-G#|e>}vD;Br|pgRdp_K$Ht=8QVNPtv`q& zR%mW$x>b_dEVG==Iha<-vEWd1=zaO+ES2FG+Qa^!E*}+`p;U!w@Ws^T?E9*JOV#lM zgnRj;z@t`ax388}-sHSgD-X@c*4DNz++*DOh_lg~xJ zEp49T{9a2M#WP%yU8>;h-cfzcID4aW)YlXWV@r@n;c4zhBh^WJgicq56Lcz zwFj7Z*MMJFq`isv&%F=tH07TD7JYNIAY)X;wzp#CGn>n|-SaJ;^GMOi5&+f?QZK1U zPhqTM!qMN(B9RKamhC#+GW5D-x<70u!-6yH>|r}ekT2M;-`)Gz^}W<5Zm?y7LKT-` zBxtE-8qYvKnOq4@q{3&6Gw3LB=z|WTUW9+ZxqsdrzQ`yNtHi#wzP1M$4r&C-EG0T@ghNTI^kQwhShEd$6o^_h}I$BC9p1 znFCo%xAg9E?$Md65kGC1J5{#|c>J8)b0bRy$3|)d77x`?L+H&bPPqju!+Qa~DQxqK z3PrU8vJZQ|Y6gbppbN5qb3KokGP;M8pAWE(XLZL?LJ>TxzEMy8b=r4!c$s-OEt3%s zxvxo3bPoko%j~ZCMI?Z)z6}c6l&k6N7M$b#`VB-MkTSpB1k5HgjNDH z{ri<9vLjnIs2G4t+D+;W?o!E~&QgL~f>`(8$4V(2pb^sZCmIF(=|36k_5&ziPz7LP zK}7auSKIc?Ugsq2p8-fxR{o+O(I@w(;u|ehh8cj^H1tN)Peo7c4mCN_*p#mzpA24n zw01>gGB;&vyhYvG{yMK&e9lZBrT@tV*J=F>HR?!}NZ$^;tvVR3UtJyE8Wgd^S0=xh0JA?G7e(=eQmQ*o*k3ASC zb=7&bRL}`ymPQ_b8iw3-ecCi^OyPhC&KWRT#6J#Z8R&u!MMlMC>W8%eyom;z<)@_R z9C@7@hT*l&1hf)|No)p#3|v+Bj@Q1Zg8HThL%K;TNN=L_F$#g)tACO4p_y?N-x@+^DX0XO24=?I*vI?X&N`-Bo)_l{cdB z4yVn|n;WSrm@MxCG~zW7!I4Qt;7h-^lP$qX`eRpK`thXlIl9oM? zxZPX7ccwzXxtXo$|9Jok@hCX|BQLz&VTan;6WrTcB-$K^sBre{Oj{2*xEftYV@^J# zA~J=w2A;o(YFAyr>k3n$JI8BKHa?MDq~ZaTCEHEmn=iNLeP)K6JhOt{I*asc^kkJ5 zbIXj;F(Xmm7}mfStkTXjg!pWXX8A;XUhF`D|S}s>8l^61sS*(mT~r!UUOyJKET;0^AffgPh76!0L^hr+qE!tNx)=%(zZ^ z_qJ!oJZ~&|C0;f)K&*J*q@cQI*UuRgDe$&D%RJ;n)xL9qZ(ldpOn6&~k7~Nzmaap> zk|(eZ@36-;J;KzwO22a@xOI7zYzN@N{zrpPfu)NllZ~N+!{tylY8bG3E3gx=`uzsp%yfffScvaM$`+&LbLZ2T{EzC8z_4ISs{ssWNS; zGCtXUuL>zMR8Px?4yDpWJV~Kjevm>x&Q>2BQt0{b2u#)BguwkT@auRCObV&8oVBge zX!rZx7vLKxXSYP@XY9^QNtoE6rkvD=19B?pl$A8CI0L<6%VB2&FCo<`LBQw=1Ncm} z+%Avd^UuD|^B98>`*`XU=l{_Huv3_bOl8$%YqA<9eH^fo?=xk@bGt=F_^m_)rsv@g5>v!gV7~m6T?D;T7AqRw)rr{W>j*?cu z)`tY(ZA4BJWr!=vG6sXv7E!ZKMKztKYze-?D{k@9R1(e}QPo|FZ;*AI8D^ckhqtw5 z4dRB+7p&@haUa+_ND&@lwkm!{Y0Kr#@M^#}>V-<+sFZEunC##1&1CzM))07=Qxv$> z=ROel7Zp8sw5_VQ&Sk9+w!{S7+_5Z27*YHt`Jlh0zM(?4O`re#Rik3>H18}>+%V_q_7VP)6u|4^`q$N#o}8m|O|SLn52T1`zd3W1LxC+= z1@xJdv=BTjDb&=ypH5W9P|)<0%;)0SnvDwa$mRy{7aJ z7lf!B<5V&_QUxJw0&?V@u^A0<;&Ey(ZWHaIs?1qC+Gv9Rhy)y8!aCHr9b^vBm=LV9 zbU0|C4s)75ti{@aG7D_FxVr*+@)V>NI>D4xR%Pc?u;Z4?nlu0Jnp61w;G*&gGmN;n z#k=#u(~>a24XC25vT1u@9(tBJ2#oLQUjF^!!@OF%@DD5kfEJT-r{sGt*t`}DArxLw zhx7|CUMLq>uVsqons5EhQe_aXQ#%F6BcJf^T!&_QTBh_rnS$_%E}KI}=8v5`)d`)t z*H3+!D@s%XDUppp%Y4C}_UrME|1X1_bePal2y3 za0AvodFfZEm45QYGw5w6QK`m}_*WbE@Y^A+YiF?1yk*6F!@$?rDO%|Z<8kQQAvz{s z^#>2!`gPO~r&rGnjh>CS#VsAng$AmMFZYx<-a+a0Dn>z*^FQD<_1>v8#%$N!HjO(lH zwsEW1GVfRkODq=c?)@+ascw1ZFS^iRdkJ(S50|FLU9=n5sMI$?z6X&>a}aR6#sx8H z3syB(gb#E=+nbi~juBR_XpMj&Wnrpo{}O{)(;a&1b{xe11y(*x1Z?)PPdE=l)E3tb zLE7Nb*{V1#m1xO(#jZ1TFOceZR%gC$!Mx{*hkS+K5 z(|}}U+O{8qIuAXiz+x z9A$m%q2aa9FqVZ|NGV)%?c*7i612_(f#$q6eV(%W(MV2Oh<0-aOS8IqBh}bhUu0by zw~Gsx_RccRc}7nEB)#GOttBmpp8kV&>l79JhpZ)bRe@aLiMb6os%}Wma@||a->w`}|z&|-4C#|9I2&EpD#A#m; zgJVCFG<-hkmap)hrsRz|6qc#lRy9$ZeGbq<{9KJN`4OmZf=}i9A`~Azp4|P$v9au2 zdM@W|@7`6H_O0>qWa^I*pHz$R@^W?#I!U9LIP)YoxELJ&YOG=vV5MpHZ&WuDY~U-7Q`+Eu!-g~D}8n8m$yzD zc#z`aVQMX@}nBQ}mzj9MlUg%H1sBSn_TD)V#tvH(n+C5ex zUKS>0Rl%z?`-hjkVzs5}M4m}x;T0y7lI#oFrUV+5q4*vC4Yf35Qy*neZd!sZM;B+fl+R-OGE)pKDz5|*~l~KJ7g7o{(-%hi1 zfu^ryyk;u!7!Pf*i6qo;@#$bSWz;vLy)FbvM>WCYRxhSvyl-0e2V4)}3W&jz2C<#O ziUqd8&PX_wdQy5S#i{HKzP_B1^Sz59!-D1-qZ+X0P%C3b!WoVFkEnL_rp&J z0f{@oZ@)V%VvDp{$Zz^yo0h7P^!~W{3-MPWsY9^8QjRcGg${z@zBwAavx5w5N2q@$ z0ywLK+vhrrC)JdO+D}_k!J!wfV2WaEt&yrl)ELO=ykq-K=VfjKGqEgLy8Z4lWf=p? z3u|AMQ-_ukxAyZh|COj5z~rB3sQ>Q}osOOQ?8GteaknJzipC-k!Ji@l!fGKYvYS_wn?U zDGF63ee~Ys54kB=$}rx*UJ6ZBi`jB^I9aHgz4w-AcZhH0RVTesaUY?a1ATZ{BK?A~ z4L};&X_T&?#yjvFKD1n%pPPQzv8CR@JWF8R4uo2+Q}PSilMU3~fk z;Eyy5iq3wxf^jUy5&Gt8#4E6Qev8a47BK|yej*Mrzr!*{;JWG3T}mwoSxN^pMKU0E zc*eLf!f&I+3&t78_U*w6Ao=k4nvD#2^nP9N2NLW&)Gg$`vbcxvGw^ttk0t(|5M$<* zFN6>e_KybiH4G=@r-xQp3HvgV1o-Yj(bV6@RD3`-S@#sv$$ zvLEavKWqc_;kvq*lV|sFYH;-{7Uas(xHnxO`sW!a*k{c`=ZJk z$#vP#DGeaTb~OPu3=l_b{_0fc>_==-8p%7QQHdH`RdIWcAz1%2PwAzDS%RWNn*lG7 z(UKrL*@66{hfE1KWKch}pC|0gf!kD4Pmi`QYAc}7C;67J^PrA)83&)|HC9|vj&1iM zIkEjog=-i`o-EK(dZyQHUuK6z>(yhbyY`TI!0J>Lf5Fi}e#Er9_q&8EI=An^v$*vM zxZkGwu)3^()ykfEh$#~a30mVdp%T^+jt&PG-|OL#_geR(5nSQ{n5dW3oVJ#({Rp~H z8^GxoDn@8?C#uP0DM8nWEr#lT$DzUBA^Z7h3q>aRrzOW~(cnP$2s|kbG18StR9U%~Wez`8*9E`(Zh|2y{#&3pe6*fDlV&W-;Iv!KyPU-tyjE>!-IQ7m*|au5ZuUO^SJP*yFGKOl;#G zK>O3zV2FXfq_~gpR~pY6L?81)E#2O$JDL`VfEtDo4xpxt&FuCmZO~NMxKdlE8gl_j#xwX0cg;x)r52N?&KL(dfGSpyu%R{IAPxC ze&$?h)|lV*r{l|f)jm-;FMRWldNC@j9IwC>uphSQd2rHfzFyw}wqBAOx7MEry!**E zzOF^tleMgsqgaQ2TCGA&E8-R2)0xKtX`W(u6fqN{a=jl=+Hhaif#$2ARvmk-lyFO( zW}=N&RJ&c1LSG~`_#2;{XCp(PWY0$v;m%e_fq&#^O|tm@VboJsO8+(f;ztENky#J3 z^FOb_k4b*?ZVYvhcbUtM&pMaEuTy}T$u?&|tQSM8>uDq&;5TzLp}}O?x*aWPyV(*t z-*R^?n2<&|AkC=4%2u)v2zHP2J(I?Y$~l86w}Lz%{j}e-3_yEYdb)p_A7#H(ef80p*8@;i0V!IOd&c91bqZ_0I3!uNH;p7Ebtd84!U+#kKD7Tjb?}iKx5Rs3 z*V=5AS&jmjF>J_<1EY43ZgUBiHG#v6Ea!E@_nB)5562`wnIqoBHx} zS8|j$PT?|4c&5;b>;P;@KXg+7d%J@-L-({{5+Oug^&>(KtoJipQwSxNajEK8ewuwO zflWpof{e2dj{m#hW{^3bIqO}%-W}qHYVmam+?|~|#~yi{orpuNx{u2M9`6jiRu#h{ zcjEw!VtW_b=u`vz?g+1adnhS{Z@Z(@1)=AlLrn(_hVHYlbk-;LTC)>w|12a41Gzc7hDv!16ifi-k z)t$RY9RKB4sE_6CYCEL7)9{UVDFljVn%yw+)ax+!}jPyIk^%Z`r+r8xuF1UrtC>^I#dPw~zyj^cmh4(e4fTl%sy)gCdg6OXS9vn^8``$fn z$CkUlfq`L-iiMcH+mAAUKk-_s2w^ITKWn#jj^BQ`l!a8M+jbxZ<2&?Wt^XT7va%l6 z260@(YyPhmQGT_5*lN@WGQ)<7%)US0qrNNc0V?#UYB`;<@sP;oA`rAiL!RqYo$L?f zA7ZBFU^p!D*I0GvSD(yVLt3uKJPi)ne9O5VBi54M++PGipi;StnQ7#C*4BoYMTI7h z$$&tc)sv_=)T#d5jlr5uLJ&whb+$w7jt zz#-;@(#0Wpg0pQM%E@JALZP1FF$G+a6{jVX8pV3E#H1t7d((hH>cIBKv0vBhF?e&K z(JMu**vayX6TRX>K8uS(poTQmp>Odtef!At1{NE!rTCb1yKFpeq>wW$=91SlRh7Dm z==jAIIO}jp3KQa%LEqc>x*=&%76F@hHno_{8#Dn6%x_5i{w|tcsSqyCh2Z;YG48Xw zN)?<>qw5=Nt(J~^@ML(g9ZcL(RL^f{%oS?609q*9jFg}vR02i=bkDc-JFYb&MV#B5 z-&g-3!{l`F;d91Dz$d0^)|XP=DRnlhCMnYU>^WBezfQ%*q@VeA#y@_sn#l(LYjdF1``{k&D0o5NEI4w>1=E zBRM;|ILUi3cn$wf^LHm#z9s_Gaqr-JCa#@xE*qRkPhoPWVR65G!Pf(ea*dL1n0s?! zGL`)PZd}pOv|aPf$j?ZxW?c6#X790ROi1GN=$`sh>rz^cR_O*=SZ-|UWP;+Bm2^oB z=5a=mA>gHI+@obx-9k>LQhR-r60^uk-A*THfsdC)u`4TZ^$xXx_#P*o$3wCS(9v6Z zfrfdUz5h5Mc=$K03yiX;nmHJdxZcXEGa0HNEJk;&)12VgF-S zi>1B4iObmC8#`X%#!{9&;2BCu?zT1LP%#VIr5^qu*?UQ5>E)9A&LsmN?lreuI(mHD z5O(GtHsh{QD@-5{AyO_Xa_>$&v2BEDkGdQSMjyr*Yw=X5S;-wdB8hcX-ZB9-hCyfybhyWQr z2Qkm{`DBfIO_-fa;9RNwdj|_IO&dzlC}u=N6VcRF(-lGWg&=h%tjD zp)*OVBXaj@f5gNl*xFU(RZEMYOz`mnrmg}UCO8)B&k2x2&Qo~DeN&NT|iO>zqXFk^M>#)<Fw@n#)#LD2#{&vh0v-W#dAPKMqQM-)RkBnm{(Qq{UV&H2wVo$!FWi zUcXgpD3SX1e3aUascB>}Q~tp(1E1NkEQ}PR+p}#&8s$>n@p_gF{-JwqQ##Ist+th{ zEP)?SgD3NVd@Mt|%chL0Aq2|Bxg;kIIg~!B$oXd{%|_2AHMeidfF;L=gDj0(%!;p! zwB9DMpuIxE@u3Pd^*IG+>QA*$%Fp+GmkBgApBPi8WYc@V2BUv7RP*bv)XpYDKtqDys5=|pDo3dGdV&&(kg%c3mtr3_6B8N0^4lJoqAz|JH$eq!GhOI zwy{I4lm{bv@Gkne*%yx*grsh*PzgK(>+goX2p9d-{`=$hC#hsJ&0{IQNkmo&d%;5^Tz&*L3r?)x<>33ppcFo1PEctccb(PMxyDhCmo0j{ch=+=S=TkT%37L zAL6{0Ys=Oq|`7Ep+pG|`fnyFQw)1uRyF|9#%n{~EIw9+09U@NS^ikPQC|Lv7> zQE__YbuUyAUqhYo3D{l1P_=AV=i}Ml120kEM;_aS;(yFu`vvW5`u%Y(z@jCc`7)8G z<>Kb&jQ!itY7bbzn8Z2ab|WmT(LIPLalk}u<-FL~6;(;hUH~ofwi7hBL1AaYVSU*e zR#rNjJm*V`A)FsOzLSzP6r2A9(uDfK@aGA9o>uC67vD{-YM6DlNyq+k*%tvBLsjmD zOwJ`2o3Im55c=cP(E<#1cgplU{bILgvRpxth?qicRCORXkDt;lA~vVr8>%1g2jXrj zRsM8Q@;603AOzn}p^T5}Y^C$fqTaa)VOvuYQCx<+ZwyQJut+|ym{fbn@?FOi-yR?I zb`vD^{Mwt0AE&fy`sT8VjKQ2oC0zxGB#(i*zYDN^(Qp4tLs1d8_T{j;|$51e_+_I8@v8;bJpI8t~zC zk#UQWdDM;ce*Errx6VAKEEosTh&RAbg`6t;hE@mD5;3=d3(>)MNL~&D^roa!D3{P> zQIBP5h)_P7l)Al)2FuyWN@v{mq8}UoE9U$_J4%U%k??zXbl-M?v}2-cZF5Q!Qyi-% z6bDLWvBpLxiKE`$Lt?2w762SN8rOr>x@dPY#vL#tC-5qa(JwnT>2NjAm)KiP@u8 z`7$LIfI-KMv$d-=wcw%uS3i*R_m@4Y4;F4?jyE_eH=?Ns! zCqPHN*;x|q%k4QSsc+%~Nnx9c)IPLqRq{{nH?I36K4iM`iz(x(PXeL4K)J8#+EXnD zmJVqk|I+tq`@xn}iwxt@zal7y`KypX2a9{AGJEr*tboeD>`#J8)AEnd{=C(u*AjZ= zusfpP?Xg_WbnV=)@__Ns@BR$eSJb1fN+c3L>(|rD%SkU4PKjN;cufB7ubK5{?59_h z)+YOc$D{9$fx&-jjb=WY9a%kTn|il?{oN42m0`>4r8@Pu{@OB@k&Gb;mwOZATF1Qh z9@NW5{H~NHdb38fbGOtLT8rISv`cc?8-FyInJrA7K~Q%^pFFGjLMGR?Sne!#eDyk8 zWp>S@C>!A%g8`Kj^nudd)E`>l5BQ>Y)*L{6UKvrn(4hhkvrz0ah7-U2#}zGzk5_R+ z-3tv%YSiBJZAlc5O}`;uyc^1-%B%?acxA6o&A3w2grwfzWiCTca(?LMDNW12;ND%+ zD2V%L(HCeY-jnFt@G9j&<1l#q+QI9lbGsSmd)RjaN~o}eGQ?xz#p7C2$3>zjiZFM_ z4K{Z2*sPxL8z5>fcc{|ba&97^yf9uM6UM8#7|S7gdaQ6FrK`91-uqP z&K6SZi<^(J4wT3bN=~b`VFmu|jf7n3{UApB0Ffp3^W&W)bDxwenKD1J>J%M^7t86m z-Cr}^e0i}0KxaF&IkIH|&27!|EwZI=1E+i4V_>OV5Wzsqdh)f;4{!XqvGC9Y6#CG(|Cy|#sUM6N~ z^6GL0`jsK`Vn@bVWn78~_l@NcrqIVLp)z=y!(N94|10#@S{d;C`{=gY0q5(Q!G5AI zstnbtZrbx?9Qj6)5mE`zu*2WFTN)KVP*okDEEsp$cRno@@PdVe`kKeI!XL5-!( z8%NaMUc5~vq%C1n)m`E8B;HFmj_lCF9Cnz8kNDI{Hlf~TR~+7{oeRLivD;a@tPf%H z{~ujv9o5#~WqsT!4#C|uxKk*_-QC@#xVr^+w^C?vhvE>RI0cGJAxLqz0_9DAGqYx% zdFIU@xhq*KH_1xwIs1I}{@(k_cnQtlem|gSJ9k-Y)Y+Z|-hvV@I5^(`$ZkfEmB{*i zkxQNVFawbVQ49J7bK`W20+*+aPp?TREC=Iyu1@ZETn;*jE?vl;=)Cg)`rG!4Zx^_x zNxJv9*BDI3z{L`eu|ek!MV=OxqL(!z*}cg?Iej)Gj#mX)5bcQh zs{(#^;q!wZhWZM*9Y}I_)tnxN94?Oj43mv(W<+kJBhnc{s^G6v98w-(bNjnClhj#m zz|y!%2kJQaWGR}K+vCl(OC71cdf8p~?g|%~jdx<`USL0B^zcu^2rie;Pm@*Oc<|S1 zUt%4;xACc`s;k?*=8<``Z(@ZKD@R>E(lfUxTd@f??vi_ndJ#!?CtUGP;oMY2Pi_Y# z36-;i3j(&exY3;}(JWBP9cF2NrT$9r*iF0bQATs^|~lAzMU? zu4H4t-~|3k>z83RJS6){uewGbWRTc|!P3ovdcbvrK&>bl)2%(*Z-;!B5WNuW?9z#? z!{wZkZL(D8MF#ID9PV3SNv&%rb6i88WWO!etYtrj&r+8ALnJxKz36aCjtW{%Yn3m_ z^x2m^THj9m2xrs9Y;Z!>b&44AH*u`kv39kabZW}qw>e!9b0q*MD^aeBg7{jN+ zdzEX{*@Y2VZ+oJps05@}I=?qOh@SpVGKAAQsFL^1L^#F8JlOHBIA1fHmNgGxaPW9A z`o`kkRUl(Z>!dqlPw^5tCHm(*=Dm%U!JJKh7N8YFw@$N@Dcx9Bcnx>EUHrbOzca|S zMf{rSQ!R|P!fm6n2H_@Av1g|Xk8=uZ?0LNZdt>qEEh+L!oa{FWICv(U6Z@&v`BQ2LyUdDPcr%f7u4yh?P$2rZ-MDh{iHR!#3^s!T$vC zSAheV*I7TbXd@A%Yv%ytx7E6w@YoN9YB^Ibk+EhjHvl4eTH*sw%+$DIfiiM%yi5Sz zQ9fBEWK(DhI|{m= z%(HEjRWdEGJv)?jwokNVsH2rls`mIa9m@iGr1usYJq3u6pQPAk`+$UjEWj@*U@Jhm z#AZ1>ZV%y6o#U9JfK)n@0)IKhc^qQggw145&TW!nMSw$-7pHy(Pu%ci4qN-B2Kmjn z;0L9bA(3Uph#>mXQ)pd3A9Tf`Ye&#Od86YZK&Y`s)sQH)#x$RYuSBR}_@#i{XeTk` zGWLh=^347W=^ZX&cdwpH@i~WZ{f6}cY60Rj&R$n8Fn7uC^cSO(&10&o(LeR`%~{D< zuMg_JT2Sy)kF$3ba?;WDpoW^x|ze_97_2K>3N6t}2^o@z$%H!&y# zlb1gD@|WxhD{Jk2?!kh{`2&w+GxtD{V_bT@bfn?MA<+lDopziV&iK9%zE!Nhhfy0i z;wo?wq>62|#298vS0whEi_>(X>G2|)??~+YW~XETc0e)$3oc-XC7sFWc$klK#x(d3 zPQbB2A;h*w^V|rl-Bxk^kX!xSvX{I~;^FRJRb) zr7CXM`Xf1~Lx(MWZ?JIRFXm?vll`V*fanJ_LCgYv!9-u}B;9Ls30Q zdCKKml39|jLz;YmdO;*HkpE1q(CGY*-`RBu;-!R3-l;A9)~sy!k-+TP0-sIr(SCSB%3$e_PbEGf&@#yzyT?|h z#dHFgu-c>xF7RxLSR%g`N7)?Q_u7B@5!}P|ZBP?SPm$@b=odiKrKz}0x>QE97hr{7 z&k7w(M8Y$fhtU};dPt`-W<%dY-?o>1c`LbqVzocmyfOMaT;K2mTJ3oyn^TQJMs8No zi}j)XCCHQ`af{4ae$8WmjhB6#P=GdvJ%PBLC8tMlW@kRxKwrEMG&EyJ#p6#JB>CW| zT+mAYRBj?j6qVy~BM7*$z6{155ZV#8xiQ12V=T-B;#U|GED{dZ4*SooFvDj`+)D*g znsR!}1tt0+d!Z&vz0^E(i_qmL+gzFC85euuZf%8=3DNj$M{En5aQPd%W&i~MgX)ME zQIW(f(%Vj#>oC|LD((dpGj&2M5kN-5DLs&I7;W#Vj4hWve4)N&JzPcT4qr-7v45F5 z2Q2l}9~tOWo#VA0Qu|a_;3lP3$?j)zzPQOH&wSlXsO_^m|%@(vx?MOc) zN9RJfn5F~sVTr!9+US?U2es!A_$xF$eNi!K-%l=?)Bd*0KC&BlSwAd=k4j)jaSg%F zg^sTCg#hz=)`cW8;0%G=ubkg8qktJv$orQ~ix*>=5b88GFm;qt(~Vy;9zsY^O)*;) zwtxzB{sPIj|jlZYwXGW8dRj zPOvTJWXF?k_nCWCGJxZNO(#Tb-@8VfwsGU|QKEQhDD0WL?k@VPB}ujKCXmN!7pQxB z^4pvoa0R2>b}!Ry2`yB8HR5>~c#zaC8IUI4F&1F~V7{pSZg&(%;+@cFh)%)=;iiRf{Z`w!}c zteA4}o)1*ERoA|LKDh0Ji}4&y7QZ!rnl^aae1pRgd2c&H38#r$EchGe=`Qocl^xna z_(dmGe+pXd9E6I5o=-f`?BsU&Kh7W1>jm%VCob{45gvubLY}&Y1yO$5AQZQC8zf~U zFSsa5#~d{^s`uX63Xs8j7ZgY}^B78ePZK-~5<$70`eRKBNI)V&tcN_df%<@g5tl&` zJgp?IAFU9Vikqs)!fSe}pL=8Ou6@(ojEfSRuGEr5RM>X|8RU6YTI$Nz~b6JNJ7 z?=OE8KYIWAc8EtO%D5BKHVKfzfUInji(Fug3enR>($R@wk3LFg-X4JPHP#Y)O)1+i zk^CAC!qG$A+!^!bKdi)hYzWgJ6GHT~@wlR-EwnK>TkndAZ&(6DGF={@SX!P^zdlLT zv~(6M3C^22GPt#fGk-b zd)lwu@8z>DOd}%P2&sezs?5^~+%{~WscF=#_{P4n;wC^f z)5uFa*oQ;*hYa9VF6hI*3H5(!I{5D2H9Qy-Tu;7~vcC$uecPKx)+YHQbGIR0qj9H| zXJq$Xaj_)g5@8GhcjjX6ss*=NCE4Qp68AKWf;M*cA^3KRNqp8nx5A!KGBDTAv05 zeE&GN*-MkB-}B9nb@?M}7Ew>R2 zpZr`kgh9&!H1qx#AYoX-mc_2P>JVwR?cGC#MtZp$FEzTeVwzQ?k<}@wOko;4J&`k3 zqL1(vPB5pMqp5`}mY>E~5U4}I+6v|}_M8jXRhJPD$Q)+!tbk-I|-<=+`J^MSeWE^XCA?J3Qlx2bM zn$=6``V}nggAKJ6nJRYwRba0hMye4L{ z9{dmn=+xvGG}Ge2Q_?6o0v#Xzsd=S2lN4d96UvZn~ zk4MyIAVMin@pDNl-lmc4U##)#jf^P9*8=x}60=#+cibbPlC~HubaH^i@E6I5)a4mI zK!}Wf-$@bTKDK9MaJi6K(rhI!0V1(yKd8ip%hqC=bRKE`%|3}mokV5U5v>5jaVzww zF8p3ufCK6gMA{=B%xR#KM1yiEp7NszlrLyn0xUeZ-@<+A85a_>vAsY-aeh4eN|WF8 zQfx^e>_3}4jk0{-5fe2r%tv8YHAS?$WIXZVfD@G=ZR?HmWOxh=-8o!P`T@U895Oz! zv8NG171Ki&VhYER?=HVn2B!Bk;&vbV=|Ouiw@#MbZkY4%-*9`0`hb16O>!~-dBXaA zdcP2ujswL-`O*jbrs#I0v#WRfku@`aORk2tYs1ul4@J}!SAA#upjCkAe!{&k?kV&h z4;Q6q(3kj<-3$g2(I2AnYwb}n?qKS&LL}hfC{r9y;<~{9fK0;mg0w#XhZDY!Pi&}f zqiXVTp7R%Zc!=eNc--rmC)S#4ZS$W9TuzwRpU?+Hi)*jmac;2UF9l~8Ng<9G@E*@S zP|QwL|Dl+4TeoOQGVUEW1>zZfhQy4ys94JNP9l|T$n*QtAznU{1v;5?cojc5VJZ_S2kglz3m#Nz zM;w{Mbao8fc4OBMDJ^w}8z;+n_oO`jx(vcjJ#WCky%QAmgl#U63DEf(-UyT~7Z9k3Pjv^@$mai0Zl2h}{ps zP3fxzI4n98 zE5{M9S`5syD3)0+PI$A4CUY*cH;kl=80VT)s!=A#$c0BZiW*_(^Ag04``hIR*K;}t zcQRM~x(GT9qV2OiJI{?;$LW)45&+jiJA09u<*oc7p7f}Wx_P89tPF(56i+MT9W$BJ zc%jM+4N&!Hq>z{L?{FGg_&PG>Xx9IgXM>ezQfWPi#Fw+03AqJArG6o)Wqp;DKS63? zn835Hcg6vzm#8BgwZN$gf3*03X8FEAkP<6O;Y!ak^6rm6$^iSCvOXHJ8g%ewrB12( z9=wt@#3DChAO#iC(vCDi85sm&)Xs;*&hGk$9ejR)qB3XY9T@#PA76I7=5xH0$od5? zUi`3&VRy^^?2bAY{rzz3T=+9vGL&KzNbFb^%A7I<>Z!IEu4F3{3?(_WNR^bq?|+;GVh<8F1(@14Xq3hjd`TXB%39xyn$d!e7gMxA zn`nLfvb@$;T{#s+$w1dzrjN?Rd}Y3E*vo`lVL!$K@b5I;Cry=8hb>3>7A0cX|AHWnYml6kNh1YOq$7dR z!>QOi8>rHB6az;h?i*;VUKqF4A9}wu7z?a_!S1LUMSKi-3a~e*sU(Pli4Q12Y5S;^ z-Atn&nmqUu;B+XBN3?jUzdnP@6I8T6>_=D}yg(?o{vq%R5%Ue-FZ~Z%HH=x*%F%`D zmqiq8Sv{8q+2$Mw$9U=P7||i^b$+qd*`5{Bq`e!{8W?o^T+C<$HRT0;xXk>s>WdkO z&9!Z+-_H)2sslxcqdgb!!>_S9*d)O)OBL&a&!`jF`-$h??`O)HBL+{TfXsuA zWC>SFHX~MPahtw14ArN-!N1b-GwRCC!75VRv9MCbF7;9Tv;J`u;VkxEX!gzCV*;!qPuS=&P;ERz6wo zA|oylA{QrFmRJ^84d@-@t78u|*{D~|0%6Tat}G~wGo;=2J5KZ0`(h!}`Rzwu!G8&Y z=DK{dq8sZS{Q0MsTy|;`0f<)nNt+I2H*qsK_?iB+a_lAcX|jV-@a->w2SsAeu7Z01 zoHkIgR3QF?xm59B0$^qg3f5yzPrM5zEJMn~2uAD2AH1ZVu3q^s`vUK1@1~S{Di3ZI zkzR2h+9n>OwqC1VrVNfLgJtmiGF=tA18-=(?Py1rRd6^Eh`rjrotr-g{p@>PAG(`q zx9lU`yUcFc$_pfOM}aV+Y7B-TiyGfQUnbHyi~pS+JkFX5B4XkDB?rBpOr(sPU;~jM zk$x&@DuR&RQ&WiHQfqhGN#j9h7uxxBV!)Jd@<0In8T~>8G@XQ~j7KnFr(}g#T6~8q zso;kOop7in9FsJsD0+P=;=bbQj#!TVIPkcuy;@&Z70FeAcmD+GG%wH^iOZb`l#utp zTZ;JGV#L9{pBl4iaHOzzvqH`*c$iZd7YJtHU31(`b^U z7<2C5N?OZ$5`S<@IXb0(b=^nWHYbd-;rfU~D9P}lB~@QGZ|X^uP~-U(^lN?d-pG@8 z3|I1vo2}=i44Hv#4kwPVx1IEJ{|-7NSIQ~KjoF# zB&o(i?aQ)i>}$!PRKIZ?1vgIfD9V%r@?D{}8%{{|y*1w?3Rj1#aN*lMIBN&2~ynVMZ$Q3tA(*0A?7N}N!tAaOZl>_ z1e*{Q=eBVTpHMr2sEfvw4(%)K{;ZgvQ`;Ut4HTWwdKi!ug8V+S=kw(Z+o2r!?oUzIU-Z#b z)vj2L-6B0Yom*6O8T}_yUdc6vj}IL}EML0i{wd8_6qfaIzADeQiry$`&`i=svZ(-7 z#=vVvPj}aeXig z#Ba!Z^J$jVwl{NN-5To-|IQBhw|)L9*MF&S1)josj#InZ6`FNge$Vto3&Ju!_gET! z!24XQ=dQ9)H^f{zu-AmeNoHi)uy<5#bnhwrYlJDN|(6CMSb1AIltJ?>YIG5T&q=471T$vhyI>UQ;n;4S;O z!yJIMID=&8t_O$jsP(`{;`A$MC}uHftm{j6?s!^${@>!#9nr(PY@2kcmz0QSZBj-4T5~?U(;w*ESseq7$#A+FvBGXc<(2I#f0ySB1=KUV%R&6k?(otZ zLDlJes|fxR+1xMm6V9y;d)>n5tr6GE$|{?yNxgWOyw zaFu9}R@9sy2S0c94j$&eM+)5SV5#T46pwoXp1l)&n<6|z-5YjEFrYZ)_oqzwo9g&A zkVjmlLqbKd+b+o#*~4UgTKau)uq0*5gKU3@WD1uA{pf3>{=gZhcx7rZ#K-D6925f7 zgb46^u!kJ^1>yLHsHWdLYu&YM(5#26_LU6bzT#fS=%=e1CtIb)^wo5AADDBByIf$W zkOscLsL_7t6Mv%aa;u%OrzH!1uWh`G+#_h_ruI()CIIC&ivDL;|56xUl<&>2nF|&h z1II1h{Lv)GnkF#Tx8}a%^({;*w5@^npoz#xa|&QQd%6Y(&2*l-LTQbJVTLYofg!I- zrT^_MB+iy^v#QBd9L1x8X%Z9nK+L_>rSrG^KwSQ*UwVhvnOOMnM-*DQdPis6su$+ zeRHQu#+Wq1$B6keHCZy6fP-ECB(hKeUfQorYTKJ}2+9~c ztGknc<({J>BoZM&G4iS_1!l&4Ql4!`&&^_FXm7G{_GZB-gZ7{(S0SpMM6rN;Jon|a zxK+3Qml3W2{rj{nwv8X`barR*&nOmC>8NaOE z1=gzl*`2-9u>HXu@eraQ)t;yjFo8eVM&*Y7gdVaM+V8CFw}xghn$>}6Q1+B?tt9bM zwU;k?UM)jiQHTeh8SHP*eFBOXwcK~R0ugJuUFH$M*PgSZMUrETM+sNQQK(j{h=%@R z?`>vZ&_&<&z(z8}0JFx0CVVXm%$SMpW34+^9PpWcduApq;6cno%!`iW>>gCjc9ns3503zvRW9~Vr-yP{c@B~_pN4Qp~!$3>Wpnk+y zmK<+a?VUsk>wmfxm@5}ti&~vI6sDR zqqB`9-9m(V;uEEGwSvoF>r&7Qar#7E4-*YLcv+Tmcm0-dmA)-|=l8TI#4p29AAiMv z)R+1vOQvg=-k(YKy3bUNr(cU=J=V%Fx{j+0`Y4(@8H;}SHV^jBJ*~4kDvqF}HHsWM zd4A|_Z!%)*U25JGy!Y-A&>_G=S~(T5oB4c}vVo=|43Tb*IX7kc1OM2?k&(0 zhIpjAX&|8y_H*ZeE}cnH?zTiyl84BJSw^wATuMsN5V%>e=<(#;-R-GpJFV>Q^fLk_ z-z63zC0wuh$oZl}pgHSRIW%(9hxkl7(16$Xypp`^NxE`2KXbf<*cSzDd@vX6n01^VZ1=TmU6gQ&7{XJdupd?>~l!KgIS0 z_e?vN|IHh8i3iUnL?9s}AS;vgFH`E~!u28-AoOwwZnHdBl1e@V{L1l{iSfgdOnQ13 z8xeb-HD2cjZV%J7HsVGPdfIHJMbo*5^_eeHgfZq;aLo2QsPgdM=icf|{av}mQFBwn zEf{-gvT7;eEMMn72d(?+<3+v!7k_D7K~UY;X}AdRZde-A2L?JSDOv~=&dsCu3k@8< zF+rXl_nrEAvV)uLU#+FIP7N^zoTqe*O7*<*L!mTrzYaOkWEe5nnmAjj0Qf+Wbe?rQ zvB%#Joji2)%?4SNQko6j@_p9Lcf8FgE!shagd=D&v7Q}h2zuDExT9D)7C;6BV>%Qo zPxO3Y>0uB>n5L4|_&B8Kw9WH`c3tVokLR=~$y@&E8LX3|X>@k%Ug(g!-8#+YDrRjx6c!rJeYZqkm1yGG<(rwZdXLA?$WHG05{v(el>YM(SeOpSlhCT{ml15`}9q>(k&aXO4yNZq`2R`<2Ofi zeO*aI&W&M}$#GZfN*F?G5%_O8qMW<-dIY#-lfD^0P?dktFdheZlo8FmRlH)3#$*AM z$6{Dcg5tq$)OSvCPv8{ER&C@rOMcYXHMmDTqyzALILCF1Uk;{87bdnci4rQ#YgJOX zpl2>V52`}WZ`?IkDU!(o9=}gVaD88(ukiKs}8L5ZHs1YGRZGAkRF!CH+814h%=Wl!1~ zjuB*jn$eg&FFd9(8*}{?HK%!F)fFi2plj}I?I1>IaM6Z(Q3K@#pTG$KPvwN* zBz-WzMA9ulpb&2BJy?HSV~y$LuM1i?w|jCPJjtLdda)KeYPujUimVX6_7eNj-(|BpTyH)-a`q`c&?!@VA z9RmH$3m?}4ksgXM|MWzd`d^ugw5K|UJo>#{ z$P5c%r(s-STyq|JV|c6zKF2QUS@h~#uY-K3f@cRrdfeO1>IXQY5I$BjShY}*7vdUm zL23qHKB$b4#-jT|uaa^7)H@P&_U9|@sJ4*UjI@rq)DAyh7mz_o$=7o5=Nph%EGqa7 znPnAi+f2TCcBQPPn`T4g!AsWI52ZF)`=(i9y3CmzNKx-$4>cw&fK{ z&4NVWsx|cuA2&rOlr4DXI6i1;u;kEuKw1nfln8a}z8j>^$l(u+uyoP>Zui->F@Q~+ zeoWy*^9tQ~HT~`C&w|V;I)?Q*(abBc??6-A#7AbRRVQ>6%2z*f@PEY0q2adXlz)v! zc4G=YgOIqbk?3!%av%od6gvOBBl8I_{A&yEa_J25bf=Ec~^{J8v<)f^Y2p zH8~5;S`}G>)e4PHS|zPBS67)Dv?v`gpCDH5T%V{phLkW2U@T?a^(_d$$DZ2~?r={s zBluHWZX&7^Jy0FP#fEpjhe^QGEv4f?J#OEn@2rw|bZ6ad{|`5~E#6A?8PyUhp9PQ# zEl~h`fN#U0JR=AZNbtBr2m>!LNw9G^=wA8T9V(oXo0?f2b^can@!l{>nB^`OI@Gfr z9O}*9Fv}SwE|N$3qmZB|dQaZkI8B)i{K)6&3-L-HKI&5vxR06P{%tf-M#jI};$Vuc z%i6u*f(ViHeUD%b*LOQN)$l!5yQNHO6)^9Jl7%!cG3R31xVk7ped!0df}-)Q3V zlk3Ab8*}T!7o7=sJw+)@#|azrYnr2u7YFX6j0eU>;;+`^$MQ~wWl2So#X1wx{byj z<{2qlmZ;Y2Y0CrUijs3LQOyK)GRS6VigI)JC5&pnf+41JT~km@!in>{M%;G9HRO&u zz^nR6^x1kN^B@rR!F?bk;D$QbvHV3VnS4o4=YZg6>!Cfx`bn#M>-!Fvzhi1bLf|H- z5B?c4Bj)t_>_G0=9QgMO3I(GRBZBJ^w zZC0m}EPvosv#xSd3k_pYpAEY+TKLoqwU6p0u19`u7C%Ql-Sy<|b#+tONnG~! z8%hw!@Vxsh+tIKXbock8=q$Hegs0G$%h<_o$lpH;f6o9qmSRcba?=hC`X<%V^*T3d-mfT2o41nk=5)bewoF^Z-{N zIqUO7d+ZZb5Th`9OS+g;hbVK=A!t4os3M0g%mx?$i~xpt;w>Y&e5fWVe+Bl|{^=dG z6+o=mviS0gav(|^??BHWeAuMlqW~oCH-h1B*)&H@i7;H=A4>eP$#Z0;Cet?%3!;{m zu+WpVFb%|V{NA6F?1@VPP#*L-?(QEXLyoDE9&|!rfecy{nNAKmpCNENeDvFB^@r zF|fh&syn8A($PP06h7h!jB5+BnC1d?=n@{eI@CQQPA)Z2sSqHe+*UtrTP?U_?)yI%VF~5z&K^$qRL-u|Tinax}r9q(h$IX3u>9#DQ0keCiCY-N;aqiYVQ z#Q4AEq$s;*;iP z(#aM!(dg%3ClNJSyuK~CQ3*Uh-7ENPg9X>XpeZ)h(EUW@JrbpCI;pCin*hJ09{#JPlF;*m&#S-JbacSi@=YMJXgYflB z*&pxJ8=nODW`-BP3{8Tjet?nS^vLcI#F)GP60=C5(y4=vL42pHw&UEZ{^^ZL+{*h=4QtP!B6&o2T#nwv~) zsQX1>mU}{B(6sUpyqLW?l-HymN~fl3v4>hS3xVXi5Vw9;O7z#yKiFkk(7k z%9)}rZ8@{KR^#7~e#C)_C@2d^a=y|bYgC%_Un#<>NDC%GK-`WUY zbKu;1Ekt(mhPI>)=85OnrnR)2JBn5757@tnE3qrbo7T!Hn>3fs$&HNv>S_ML0IPLI zcZrMne&fitSAj5SJ36z!$ZTT!eZiA=p)Jnw5J^m#^$W2#{_;JTGUUws>FkH-`DowA zr>RRU9Eq3*@sV^t&etR8-0kpEt9t;={T$E-V+kIR^<6wswz)d_T8@d|!iAtbTOmpO z-W~FGX&&t(q%kTHTzVyWP{w<;b&fXe#EGo7P9jSUI30bI=MhJGCcEJH$@e#A zYrtm?KcZ7_#RzEoF=2=ukc5^b!qb80-Y#&)?Tg$%+3~Jne)Tle$b5Yz zzsiCfZWYPRL=qeT9Y7d18&dEgUI&7GFt+?OSg*qeymO8x^eqD}Jj<-3&P;6ZT|2LL z4Mrm!vFdn|NhoZ23G#dIitprI{*4GC-ou_7{l zbJT2vG#X8l?n4(naF)=`COUr;jJasSic@Fs9NmSkH=8&PvLW3gDxR0i;#prBa^sLe zpamYDp}dzc@9Jy##d>naW5le|EXS?o_`?6mqEBrqff`YgHkB?)~G41Icd(h1#S(> z@fl1>t2`WDzW7)DDHvGfHZvUopDcry@nUmwl5%p3&g||%^qTk|+YEGgm*<`NnPW4U zEWctZG`-JDV|$BE4+GXfT*%7IY_-|%vJGB;YJ%PfOLSoF6TW?`VL#rR$Uff)I1}2^ z*Cs#dkdn`k2P%EmxKj33=r}FDN!xIL-Bc>amj`zR7rrwa1Sm9`(`cJBeBmPX(1I6u zSH7OH8lBbp$b5_0L^|B4YnM_e=cjAoUKEd)CEyfoycX#!2|xaOxot+>zLtw5av|(3 z6*dY2+`nvGqNxTk|NFWAw#rmr1hdvFoQt_-Vc59E=d&+}bZ-kItv(~{|45@F{5o2V zlL~XI!S?z!&B9-=0z~)NE_a92GxEzG#U)SeWACKnn)^?&edeJ zV0&DnQ)x5R$-&cgqeCMsrHQW!5!bfB;fCAEN0kn)$$=AADeCIj_~!@vQ@g}5t-Ql3 zLRe<<)U?LgRM2^C#XNxfOH0C>1+`-&nG{LIhK93vD!zT&HrhEUf%YQLR3Om8149KJ znhemF&y){iHfl7Ya6fO2Vs6anei#p$;kL)9_>k*vUqOZ-a4Z|N4Vaw4(bW`f%gFE` zcyHCx1OFl3 zVj%@+@~Ld>c0(R<_4$5PZEghnapwk6Iqt)s>wJ2@v&YK;15z~lxkErLKY~IXYb@)} z`s8zbt;Vs3fe=^RQcy=D(pmDlUU=TVBwr)BHd@}GgHq?`lOo2=sog><02)G;W!Ojc zLtF@5>22AF@U}h8`m#J^@Zw8LszD>ONyqju>5(;=!x$snsM_vE&fb2eV~Qu8=VYea z`GLn2BjLEibz+{1v{Y}~HrOF@xLQoyaerp4u`|Qh>d&&44_V!Q$9j^*_x{C;F``z( z9|>s~J#ZpFnlv#*q+gcK)|Zc6(f4O*CabvNKuj3K)?gBuMDB1dIE+!?5Q7D89hXN# zR4N{py!Ex|;ZYS@)3}KZ>&izO67x`-Z^IYsY=lMsi)99x- zH?dKZIjp#=12`fjaJ|G!tkEXuHGuVbI>BE$GuX>w{mEUUtG-0kl)IpJ<=#=m^I2P2 zcVvYVC=2%JBY9I!2D_P*Ae0eWOjCe2;m6ng3FkoN4+&BGR~(sF=BZub4$kN&oHL?{ z7nJjXVN;fVRfqPqk-(>G%B=0ZqGtc3dYrwTsEm%|GqK5;QH6dc#aJd*;@~zNbMF%1 z-@l?Kjx1=qA&OQ;$SA0u%(H*y%eh1W&*0-JjrSV_mnb}2UOu(bdX4Q+LFTjIsF!}R z9TM~t+iemx$;b(ZPCB=-L3;RX3-^0<&fz((0L{VRs0g&D9wvd*y)#=A1Outui%Znu zsTWT+kn3bwaFY2t*}IG|gRqCN*oo>wM=>vhW}b$jPs{9C#$QgjqBp*r$gD)oRyIJd zd{${WK#5+CW@*9v5MArp;n~LW5$x=PKKpr=b#`b+Z;g)Y3l|+%I2X&foKr4Wv^{(? zPzwZG4G7E76Bb~#@%WidC1(x9hLk<20p%nGxQWX@pLwi#B#9sZ(*tN0$VF`h46GFA)6 zeT^h8>zD{QF8`yR z6E8{l}|oGVvG})_o}p zd2k9-OO@GArCSu07^Nzu^25BN__aNd47BYC?3!np>(puyb=}%)c(tfU5}Q9EDtyrb zu^y?1#fKu+Xk+Ut;g?%!t4A`x%Ve@i=|r_KIZqP7)=5)*nOhMm==dO$lP$~8)bXWe z0eugFGpiY&fCY)cf;uT9oWzMHH60C-i}w34SuU9Ue5~->dExiAT;e?XcU{c$grs@z z?PcwWO7$c8qu#J7nDL0(L-8(QaVz|?o$W|QhN(2zI(_`0T}&aDI7*=>Sh z?{Mtp;%xqs__EGMu+a;6K(k7 zJfg8>{P>bBRU<>v7+K@p^AYTrvchq@>MB2(c4Q+c#|M8Kc=i4?DYB42u^!;xcmn55 zXJNSR=MmG#mxh=KFOWmD^5$`^fvKDY6wBp=F*M12b%V#<6UXVQyfAU!aHG%JbsN6c zF6Gso*HHHJ&L&bb%#WFl;0-b7*Y|>v9w>~_PPcu+F&?!h-j0#i0nN`3F6+>14$gZw zJ*TNtNc+CsmRu)uz}{vXXQe6FxMw$Ur91mwNOT(;m0ThkcEQ>&I5_d8o6Ghwfip;t zf&VvO;B$*NFL5yG!)U)r)I8Jc&2G%D;qm2jaiDq#&I9i3=kZFFV7Wh#De+O)zK?xY z8Lt?BPgIcpYKghl^ciZzmYdE$(M*`ah}2ZPLMz~Fi~j4Aj?i5bMH-rF$;}hQLuQ*Z z%vKX;M(iaPU&lXbE!AMGrr$h@wv0^17rid29OfBc5Ub#wAf@iZG!aGiv0?Xyx-F4w z`Cx#SFV@l7u>3VF2U_4LOFhX$68q)q6nN=L)&7&1Y`yxOR@ARCuT^8lGi&iA1QQJA zo%c}7RHqYr;Af57p$aamE1&F)9f$UgNi~`NPKPm*ceJNP$1K@(#4H(u8{^LbEiW8j(D4WNBo^D&V*sj z1tI5TE&nEVMb#i+JOhP*0K)~dCq2qz6VL%`M6jL5l8snb<&hZ6s?!;$8am=v`|fC8)zTsd+j>rTz+8UAU(%q^w-LRR zh*5S!5(1sB%m9G*#OmhKW^$R-kvPiWScOiwj~MLLpdU5s_{R(ue2fxI@B+;tuF;su zxtmtkocT6R?8k*Kl`Wm+5jM)H={ba!_DNAH@U>rf6H12+RzaounRn77%qnv$XOMJf zrb3k3_z8FY9WNbqri2Mq*!$c>oriqsO`+29$iWPtl3A|0`J0IhX)P`0$1TKR=@bpg z+9%-+Dieb((XSCBqfo#g@Nng>`TB?5>5BoLKy95R>D3A@5AD1X!sno$I{F-{A9V_P z*7N=!TW1~A2D@(i77f}44N{7`JB8xz7TjHm7uP_bXrWkvLUDHwPJ=t8SaEl!SfOy! zy}y0Vx%b?^I>Ur!$Rz7s&u^_KucYxM{C8%;4F9(T(2@@OGjD~10RNRD3omf^fW-2EG>@~&G~ULfeEZg-TUYQ%q>xr zNvY$ay+{Z(V2!Awx4_Fzz)%O$$5J&}zw8C8QE&ihp}Am6YOa}y#+5o*deN14NMJO95s%;thb@$xp}G403r#EX9Rs_gJx0M z?epVrcOA&^d0Bh)Y10UFmDM>u8`Xh|iw4(z#PfWNT)7zUj1lyc^+*@WU}4HoIl@wU z*Em?9Z}c6ED`0A;NyiXDlxzc0_4I%i735&+X3o?ei50%-&+aAsLLif-?X66p5q+=& zNJ7%Wqyt{eYT~77_7vzTT7Y!Zenjpok8Zt-m?EY~Jday4Z6+JYo=cS9!e|NlOF;!{LXH%)o0aKwf}rspq4O;yVx_(AyAM~3CjiZ6PIBY z{yCj7dCHZ2b2#wqS(^dVN*rE=xLMm&uws6dO{=0lgY~mkx6L?JvGF6x!8;p(5R_bz zApxJNS(yeZqB^d3b~98-ISeE0$04ZT{>aIm>Nci6IG)&*w2Rd^mpa&b9_aL=wa}_j zf$EN1W;<>x?TWRXh?S73dqY9|*wZ`{ZwoBh~=BVyv+;D+z8i{`<*yITI&n#*@1U?)t=(E=gM9-H`ey|pc zc*}UN{`=*1o!)PcS0HT|J)AH3IfO+A=FDQGVol<=W8PBBSG{+=yGP>0%@v5}fwEn5 zfV6-7c6220q8qh+i~kdG;s$)kbaNxi?~e)FKxa`P-em|W1;O_7wT=*pmJq@HO2+Dd zYc8R=y;FqTPOprkOWy*{4!ai#B2Y{ueZ2CzmA+i1-_-rs><&f;5sGGWKbWeCQGcG> zy!-q3@86yP57kIdL!^(3hMy7w5r-n03G#U0iN;sG5iS@ZwUH~_>PK&v&bC|ls@Ppx zfEUlxlfmurk5(z{*GRunDNrlAO_|zXek(10o%F48r9W=xcCPVBB*Jz21^kCT(eZ-%#qpG{ETEHB*CDs+3>`1i23kO?N zEf9Qu5s-A)>}OK(HGlU;BAe0J6GtA;-nsJ3gXl^{4jY+K;DL0Vm%X32oCqjItXPfN z!TRpk)X0Y3813-O2r95_$hv_WJG=&x8*R;7sLjljA+yhKkTTc`OYo_!h(Y&^61-zQ zIh6GU4Uq?6b9^U!{lefSS=|=fmR3Z7kj;Dd#M-!I=C6YJrC3~9Ds=Ar)WxZpm_ooe zGr#?*7@A0Xj-jYGaa+AZhgtDInNflLmE7!b!GqwPm5ET`g~On(;?`pLgKXqf_M6I| z(S?PX^uz1%L2X&|fD< zCTXX~z)5~-G(hxD5w_E#nA>`?JA0x;tsL3fD6(o+heCi#U&+nFNyQm%PQ+-I)&w{5 zN)6DKV14U)I81eEN* z(9H?6YUcOpIHm<9CTT5IBo?|ibnsp-CkuJR9tyx7$dC%&6OVEo`p8}j9=wBEFi_S; ze)2VEV`t)~2F?z**ARUc_xusbnXigcE-HkV%`5cbGvMw?EJ|J0k+zN#;$vQ^M1f{) zgq<-c+nb}a8{XJ2Xzujx;WCwxU!QqO@lK5*QQ;qobYg)gpBJgH{i|fM zND*C9H3zE@pYAZY8oUInskPIo#dJUc>q@_q7WV|purMa~j>u~$0`M6LR~vF-InxQM zX{QvP>Z3nvjhm9bb(6egO_W3B5N_!AU0Y?^u5Qmai;%r4OSgXO(zB$6Cw!z$v zxbP=2pJ$2x67wX4WzVj0l1bHSW+P@M!_FvHxA0B1`UNa6mIT;8vpk_^y#)Ai5Tv7S zZm^V@t8O@HWyV~^nWRC#v8=o@rdd2gv`*{Joyyo-nqtU~XE?6Jrfb-)Gh*TUQ?u@% z5H+JQk<5j6QA-s}IW~D5@Tjk-!xB-o9bNZ1d1jp0%6rnsbdEdt zmD_#rkmM0~$N}f>T~zufdwPD&akqLA#Q5wHaUuwup9MI{?DZ))`MV}2F5LfiY(SND zb5GQOh^Sf!r;-;(6Q={)JF}fTUvh% zvZjkaCBH#@`K{^_GB(W;CGZ~5qvt#y`DsItra6DUDV4!=vdVoS>KNtPY`;8-ad{*l zOwIK$%d-2~2CaA0FJe%nnX3+rfYh!k>%iYKE4f_t!n0&YH|vOK9C;V-+h?waU;AD$JzY*5DKI=o}85z7Y+)_%5xez*a18}F!s}0MLU z4qbSg2O};?{E84YrgbwE^cmN9xC9s%le~BNdiueS0*0cRSe}|4wH_LG`xAj#KIf?H z2ohl2Ja++)1Oi-;SE7aILh)S?2d7l>2ogTCGEMT#6vk1hklgH7;-sgp0_k?a{x6PE zSXbFo%C=;}n~@!#@UKqlYn05yYLuXXCTnf^I}-#TI3HijL3rm}K-gzT7~erOAxa_H zJmf0RC_Ov4JjR%xX!rM>XPlt7URJVqFCz`Vg?tKG5~^&XQKT%_^udzn{;j+MHu_0(^KKydeE zS?prVh!MIKk;(OqLk887mUGcJ;aQ zFWDABx#=R9IC3Zkwr>cN_$VwH8Ao%K^9Z;`EtqCUN^3`pMq)oqsQeGA^N-9n{a^ae zpCucbV;~VVEidP+Lx6%)K8H&>J%+k)Q8#w ziz=F_RF%fI@5iAwmRQ)J?U4^lma!oF=iAZPwcNYwQOHk<(!Fv@x zbInP6HVwu7NGdu-VMzm4Cx<~018_Y0cOJX$()J32*o3m^Js&EI6Qe!hLN7+NvyQy* zM@NT5IU}l=P(F3_J_|;(C_?&PbqS{5XbedJI#bXN%8Zh{9beIswhi~VMVJ+R&DZ~^ z_VF00Rg+SjoQs08D}o`eo^T!cefp+YXK>iXAz3dumluJ0S+_vWvTI&Ba@%R5zc2=`LOToOHB)a0SsoOKlcP7i2N4Sk=*sSw^kLvT29w=zRw|Pjo$>x5Jy)8sK+IaV6uJVPBY@xBd`% zEGuH!JSx^?fPrzJyY%#lbq@(vMZ110!}kPRH`4{dQtozpxl_30QY)=>#v<5g~-!LyqA^{;wqRO;?j-TP~5O(fo@ABA1O+ zwx$y{UNa@b->WZYwMXv>R^rcs z);eHmE4;&pfa>Urx!U!k-Pb8BWQ|OJig|y0&7WiRFO$5Ht~;&rxXSzUQyL{bRwD7x zB;jaP1o42R!?jM(39(?s$?YE*H+RJnpm2VBQ{jLUWla?M+kBODJao(LoDGzgvL#2T z)B(!WkZ){0$rrHQO70_<6 z)7+}GMq{{KWEmFq3|;Ez7B$ly+er;^q&AZE{Q>{N=tA0KU3zBI5a-`XsNvKX9Y{t4fc2&_Y^UdHo`p6deDK{pK zT(bI2x<~nE2QQy*&S--^_D&fyGe`pn${x)~*Ht9M#90X^NOc3s0x>%kE^-=;XvSQ% z&8ee=gMZT`n(jBUG2rm?`Es-Hhku#KwV!4!``VVrWVANEKJT%>u0NGQ{W*F_k7FE6 zhsezmiKOJ}WW!_n3c*8Bf?O_q!3slkcgldQ(OtEQUP+-wP6iWsCu5o`-}EY%w2vdf zpz0k_P`^z2OyoW$!2yx zzz?OBz@1T8eSxc?bc#t;Hd#V}#wvi?2UB00wSiYvk)*tEW8e#2GB;-!C(agO5zr>K zFh^aSBsnrFg;pll$HD{QcfW8aHGnhrBUxX$DSrVt3353g;5^V^Ch%B#Q1OfSmsZOP za1M^H;AG=ySDm2#ISMC+GKMlE0ZNf}nlw`$!8E6RvH}MWMRTeGvKIfCl|w|7Hd(#5 zVr}<#o`q=<8IPZn4m?)WhrJDY?nq2eqO=yZI?1u(A0&r~JqungIBr=+J*!8iyO4>3 z!{GxdCC_9^K8>~ByffiHjCrG-{;7advFvix9@&Gas8>_7hgMNP+yW&fn$sNH4e?a+ zkuJJi`eu#*_)p4AM853JRd!*xnjKlSv=#w0O7lt z>RQKerUH=ONs9_A1r=^wkC`>1{;FUtuXK|9u44H~@@CIULX zEudUX*_Iyl`8LQ*H(HLzsYL^7Ng@kG;s3BX;aKft@xj2$>}PllmUqBOH^!9L8ZE7V z$j5~)LUY*^^UMbu5JTS8`c;NW|RR|iX9{>qOwEX}r+zp|%FIb)nY0s}IfOgMspht?G%@C!J%UV3j^Vm16ez-miRYNafcRwc_s`39t z+WQ;KiyM#lB9Jlf|J zb;Usx2d1Vp=FUC7j0c6g_Gq}$Myj(3L8q}zV4Ha`&?`DumrWS;y2Sj0o>#PaJhQN? z=IKhSN@lo2rWpXl&llg3b0bTO9lR5U%^{HbcUt{U-l4Mx+~c2BaG%*7ezu(VD{}Hn zz*qo&k^y}P*Xw2wekSJ}sq9$0v^QWxz7%d}+dHT;Y$+gM4K)q%)Cyn&?&jNW@q*{ZM$~S*1|d)=T=0P06d= z5#^RIgz_iOJ08**^vWN*MIUCiV_7?znldI-!WtWe`HCq1w|a*Ej|{SAh&&klafhA7^sZ_tgLa(Qr%K%+Kb6Fyn=yOy$wn-a8nyPvpL6S7enJ#;C zPt=vh(dR!ftyj;5KD~J!i^V9ZksE4lU_RcR`G!f4notv%C_Ni$@QxaQm%RlpRp-_( zvic~Pul(%Y2g&&(Y-l5lToSiXH`g$ykJzvwCb3b~U=cg*%TlafiXJ9v+Vp?A z0MI&dg$|360CGjUuiYR6rgpI-vG1Bn|UP&6P_nKI1sHE?Pl1|KR`f_eg0XL75}hH4!M~| zLXZqvk4TAY%$G7Jn;!44X!9ZtRFXm;NYg7J?Su&QkeyDmdP8bS#>C%>kL3`iKBI)E z^=qE{E%kf3jgRI)znQ7c`0XuN<=ddc)q0S3#YZH|yb}s@Z75f{DvT;Zqdc~ZGnJjI zm8jI1G9f|Ujao_fNMZn)`e9w(!EwU% znFMcsS#ra|Io6xDv^Wmg-BEs~>9Noz;)5KmD6+BL z{JIY#wln;!y~yW!tH<4(#`K3Kd9cQf-nKXR_Jg=ViWvIi-O!7nc!7;4ge`ll!!*^* zRau)yz%OLstAI@39j-g{!^W&d8R%hiA=&l_po{rzizj|)x7qK@Y#1Ut zH~RDJwC@6n*%gIvgNw{TEkbs6W|6Qt`nTF~2ym$%HiytS2p;wAo^~5!MR%)(Ty_gV zFG<~;>nGU$CLfB?rZ3lnpy=w46wY6{!Y_=W^?+)t;mqYJ5pJ;1wdZvjCVFH$t!@^r zu6dWBzB6@7?*Mp}V7m^42>SHb6E)b$wiSaCS-kI;>Vbbxpn~;CV30}j4Q0D-%FWvB zZ;Nn&kU0$#IiHTijVm#KJ=tcTdSr;oZt0JVEIeFNm~OZf(hV~?5^j`hwP_bpnih=l zj7NiAuZJwJ9jLz|&!kltdH-@HH?_IkRd4OM`}vY*9?ApC`iGLX^vKsKKOPwEfBpJ< zMk;(KW2za87wC^tzrAd8oaon=%3-y0df!^M8ngq9hi^ZH*7b|srixQ?L2(YOOMQ`QCc9%{vZ?< z@JBS#o^r@||GH(s>K(qxLF=b2|5EE_Juih`)c{tNTyUlh$fk{rT_Jmuvm+j@!3&U9}>D~+dt-IEOa4WAnR?#KAN`~GuzEp+Nf0Qq zi?46cW#%Q5BAYB#l6w2qdw9}wtIPo8Y$zoN)R!6AbKO4hz+OW!J!Ej`GhDm+m zP25+2$_%hBPsUMZQZ7-KCK2GY$@2LXfl0$Of&#R38`aZXb48F*FUB&A(Ina~xzwuP zy*Fh6{V;zAO!=3sIR-ur+IjbIc*5^3FE><5EKExWOvwXjU4bS;E_v#bxcY_xE)w7y zu$`t-y~Z2P0?4@ZaEtMF18l-6R`ca~*Jg}cg>@pYbtxx>OfMod3b$^ic3s4W)+1yS z@dq~ZTv-}&y~jBEHuX8yKILGZpJZZI2?vj8kTB`IoWt%b$AM~prDHPdtVtNnA!bu$ zp?<)*z2~weiN4bXXs)IJ%loYg=^5KV1i||chpS_s$h%~J=1(@8sp_zxWQlos*ZO?T zMr1$J6D{r71fX~Cmz)P$bk?qS5L1}p$9WPAVM4ERbM#@{WMk?h&G~gy{x-MsGJ_%r z74%Rq0vO?zIBRYO+LnDsf)r6)1nMOFxa?;ROzk`n`Zg4H+Sm6I509x0f5{J`LERQ- z#+kJ}Cgv+o-@I|P zt{03Vtne_w+5*&|ii3i<(#WUNeYvfRF_Ba5i$&WJ>&NBnw^VcdYugpkt3evU-@2ck zJ{IyE)}mI67@Fkz)-&*~WmPyKepNP)C-93 z1Y4t6+7*oA7>D40h;hZ(&g-U&gMswf-)Yx>%(rb|;^{GQ+^dH_XAJ~hN7cQ^ebGGD zmgdr0-i@Z-CVWcLi_04<+&uhiSRa3Av^=FKXN=eZvcRc-!!cV{d~;k`U)x%6N( zz1rrp++ArRl^RFIzS6{Qgk980;>H(|#yeOVAE@=i$gXYsj@JNPuP;bXF<^o7>w$-U z*{Qy<$W@c$)a<|0?G0WbzOC4)!qiMq>r1bnX|DhsjBf$PNLhemMkjGB98v=;J=B;S zle)HFZ=jsz!vu;z;(QA9=sW^oG$v{?lB9+)g%XfaT2TVK?@viTynW1x5|6_ zs3OKZeKsK|eKJuvu4&8^S_2DjZbQr@8t>ghw$9Rxu%kP9tIqi;gX4K zY`!uTq7h9oRbMz}^uOeGjh`mc_1^_%6r{yyKOw~qP@ze*CWmzCajP+l zq&{^^ZupERP*smnxD-E&H8GQQMqiL=qv}(}G?t1am-oM+ZTIqsdmS~n)mcNk;hko? zxJ)=^v`mQ^5JiFuz!cuV8_B>@0?=Z_-$*=QAn2DKLhfOXE!TX8*{@zR40BWHMs;LT zR@HSl%H&8_-9 z1a>IrMC!=o&>-bw(oka?j?@5Ur#Y$Ndc)kU!aaH*bX5Lmx^0feM4KC**Dq2dkK>H2i<1Af5l)m93SUdQjtN|rFF#f@%S~zmbty?;Z%@AA4ojroOBEQ zuy~(4oh3;CB3$~JNc{e@CgDC<&}xUyFY4&}6^tDHEE^ffuD9L}@z7}zkH+fbTEVVM zyh8MUWm|Aps^G|FB7g^G)ip3$=Zp5(GsU9OpN2pq#O%EDQI+EQVzDdUQSpWiikNwi zbiVeeW~zH^Ba5&Pi)s6SZmZy3@>dtzak1Yi{$#8W>p$Y0sfGs!TyWiuW@KxFMep!T z(I{pKx?n3vW5@JxmD_2h-!HUU<^wU-fjFGdzlb#6P+H^=Ni<#DHdG<2jzDB>}nncb=lydO2LJpK;h zwb(Gey>dPkzVU%G%OTFBG6c*&Ro_nN2131gIPNG21Z~4FhiqK}LSM7-aR?z!3uMCI z%!Ig+XGB0;y^-gTu*U$O7nijm`fJp18N|ZAMoJ7O@fT*JCA;rNf9`~%jBf+yK74sS zJu;4tik8?q8K|*!gReX{ z0|?A@LEMq8yBVeE$HbZXCJ`m1pN2mf7{=`m9F*g=_ZlVR_529EB6Ep}is-i{8i z9+DC3n-PG%^)bk4w^VUjBm>R#%o&@ot*K@AtgVDi?mxaQK2FRda}yx+bB)U`7bv~Y zC?u02cD=VG0LdWQbEy3&vS1Rhxio9OM#guNkv*H(0siP!;e4k;5_i&1mv=5g;MUm0 z`u=5>Edsx|$wGr=@2uN^a8yPvIJqPSoqjeaQl42r&rRV$32`*1BWgbu*>67Q{^L1W z(LaKlWHY0b_GQMZNj;O$!tjD9{ss#>V$Zl^;2RBt5F)72Rjp&*^2zJwx{EiOQzHK4 z2;3kpVVrbtpPbi?0_QzBbaOy_X|{r68kGzeUk?iBpTD(G;61}jyWS{#2j}+qai+pT zro189t+KJbaPm}oY_{1crUV(gOZW+W_Q+hBvq}@box~9J`=J1wMR)BGYR;&nM`G9P zIDL+iuVCwbrFL7l?AlOBOIf>N8c`ZI*JcU<5C7QvNVor9H~Gix3V-@<2+OL}u_wo} zMXl6Nx}a|GkQdCLh<2{Pi?|$yji?UIU?xGr9$&s(DK9ESm19Qn&2d$cp{Hb`9?u7E zW5V3-SQzyY6EqQV>4`NoPh7@al2Vq0IIN701MP~N9gCnslS)Rza#+Qhp5aHb^R9I5 zf5<`q-(XCWr$Ik=2DDHyMJM@1Z((|f(*q`b!M`+@RrWq|YDXsh7zX{RLrQnZVI^s< zv*e_>d^>Bw7}dHJ_?%!02G6MwuLm2**g2gAaB<2~GlX+-46)|KBKwAio^u<5 z2AECC>sxY#Fj0T58lAt9i7t9eUExT<9y}5GP2X!5n2_!V##flHEcVn3kqdvsbSAbK z(9o9&m`kRF0`MJ%u#_V?*LMx^XaAUd1KdS(e&SXp=uh*xw&bqw^{AdZjQ2C#lSj$X z%=;m0C2g;^Q^mX`t#EJUIS1;Cag zH_`yl1Z;Lbv&Bop%PmL^pe~U~=Z;8>8~lP-*kH|!*f8;8J!vJw_y_4ix@Rw0zb5D(z2ory;Z~Slf$<_|FB|G^oXQTcQ@1>%d*&Lb8R*n3s9UnGoiUt zZ*01hCCAswj#&=6a`2u(p1vt{g>h6k>O9Mc!|s=h8G+9wE!WOg5?*GW(@NrwqzOmQ ze-rUixUD+!G7KSdU3D67Yp8%$(xvcHkZc`&m-EFn z#0)JejO*j*x*AnTVW28A5^b0R_FRS~8r;|1u_QYA099Kx(mTNyLxBPo;`*FJT@l5H zAvi9^d(+lD|8IPE%y_D~Z61z}O3`f`7K0QVcM(lEzQAhh0w$e7*s5z>3cOpkwK+HH zI2S4rvVS+ut^!m9M*d=A)_^7EV9GOoNSF3{yx2{NNLTKY9{6KN?!fMUWh-Ge-SXU{>OhqqimgY;G<{AGM6iTuEOI;&L^_}DF&MEY2W({94 zFk(k@hqy~%6Hi&QziR-wx49h&ISJ^mSgr@(BBlX z?+ZEL9SefCb)*p7M6Ek9-e4>hpYZ(B+1V`9>Q)2$N@2UCrDYrB+99qfY8mKmV{2Dh zT9pyZT@-?xMqPM!-~8ZOH9Wqv5BL4?c6672Q~=}rvS=&7&h~D|W~(9Kz5K`O{`kwXy3|x67*$fD4jt@9Hq&N2$5lGaeQAz3^@0Aw`4}idcsV#s7o5p7B0jI`xwt%!G+&iiE2!%aQ_tg^0*} zAyuC@%O>OMX!KWK?nx~BeNZPnnmtX@|8(bxW2S8s>ooe?6BjwZ*0U?AjPv&|IZy}w z2FBms^;XO9kS8gdOyqgzJ+f^(DgdZ9 zo;b%LbewZfb--IOFn`YzziMS_VHeHJ%W&_(cWBx?U*fh;9~ZOTgG0tUTjfhQK;nCC zskt!UK>%R2DYYpcBCTUKE-ET5jeb(Tn;7FBQ(d%QDrrpZ-_4k*c=dt4`2XEmG5Z3P zhW+!yX0Cs?f5)ZY7qOA3eE-V&m5f1PI5Ib%9$1J>WqfSlXeVJmpit*dZ8berwo%Yn zVe(6>H!27d-~p=|ucscR9b)9G%T~x?mDEUy2H*?c=}55YU~kUcgUU%Tx#co7=yxob zB^n6-;TL)=e_!3C+)9G)HWsY}27OaD;rxhpV4+Iy^22-!GDD41&s)`kMkn4>Cc4q* zNkN$+5bi>F0c-%(2&scmDwa-`leqwun)R6ZJykKpSV9}OF*^qq66^4ij zhDipD^@sqsOtOg}WyI{=1u-nv$d#p*!Yg!4w}{)OHHe9i%P82D8IUuE$dr9qze=uV zPeJKippGVu(hJ19b=a*IV8Jsq(yoOnv(koFi~R@czJy&0J$fF;T6*c_GF;#phEo7_ zx8f#aSfHoCT)7kqqWD0|a4v`&G!zbHfY+Gi5(4A0j$w8fzzG9)>nF(3n+4~NYo*i!`rg( zqVzO@za5hK;W<|USA=3PjBt=_OF+>HD0<`g(1GK5?bPs}fvX!=jYi&T2=jgS`3?+u zLc6VYbHuKWJlhuBSq*&b;ci#u*iRKgRC8%|n1DgVb7rR#v^%B&*KT)1vQMXK9Tja2 zqqaZ_-SsDSqTB3QC5y{a;;VejCllyu@Qw!J+F}vgw~P8vtTRInN3~XXS09E{eDDd^ z-G+|K51X^U%rn{tw2rZMy1CJYAO@k~9N7;E4?Zyh=S|!HZiZ>#ZdN&dfOv20Ob{lI zFlP!3J7Vs}x(1y#->u7zn*ObC&fuNuY@0(6w`vF+4#;p|wP!~8-l=|q>kJU{X#T%;Ww;Ws^`-B~;8D4_n z)hjLc>lf?~GH^3$Pe)GfeY`DeIv&+WE4js-)@3|O0HwWz&dWO1u%;P)$|$VJ#%oFE zM%|samz$lR@0eN2Yi1(gf2g_LODjg3xBb0^c7;olc99Gjx6#>NN|EY<%qbHOZcvRD zjxJHuUdzj9)F0)f7UrKR&u8%x_N*PbJ%3oZ|Lo(AumAn3t8Zoh-0<(n!k{P5@%4k$ zE+5esX0EcZv&ukj-};fWCAZ42%99j&23Y1?><|h<@AyK2Sc#tzi{8NRpox&yJR{`q zo-)giAnHm8idS+0L% z#&$QwjoxRy!h-hqP`6FnWIQdrvLo=SKFLLNIQRl^og+7M`)qN>vs~B>K{$9Mru22Nyo?k}H zQp+k3FYBLQwQXc_F&v=FJ?Hmq;jNccw-p|V!LBAFc=ckZfzux9OHi(uf>FZ62w_sE zlkDN%m~vLUi0)hMg5KI-q*uNmT^3)881*W(yzHkP&{$>jdPg1v{bqp4(RVZp-!UPy&^aSw9+SMu=-!3{bU0W`<&XSgVFF8H=aH6{&F`BXxdbqe^%^L#^n<=ywQP0h3Ad%8keOWSw%S2$EnWAL>CtTV8xBy$^4`8n@RF3cn8g+0Ix~;ob zgrLvV=q95>ULc`ui)<7$=Vd-FSh{=Bb)I4|ypLzT2j7yb4tlC4e}0$fLJ_1lUft`x z#IE*wZn^)A1M-9li@10~^X>foki^|YwEA>+dgxMiCWja$PupwMf*LflmxDD|4b_A4 z&P-p3(WC1gc#QnqLu_3*EsfMah@Mr4aM;#Ad}-S^sC$Z><>$MsG59Ke+W_Mq7g{S} z9>5LOG%-B2ZvU|_map(?)1>_9qXOOyB4TUw*a>NVIUc>8Noq0|QvX5hn=lL0=L4}a z&pX-|0Fl_Xz?TgE_x@{O=#Mu&FXog0O$+3Lg?vTg9KH9O*!Q<} z6Uj)21&ny)p5R0Z_F}K+Pt^|OvU_4C%haY;yL^(ZYW0`N()>w9w|;n+j1Wx(PdfIK zYq=Ze`K5XIaI<09OfG&ARfXS=u%JCPi1ZS8|VL|5BjE`U*3P`hEWUlF3}fVwhefZcb94%o)Ag zq9+On6_G0RahGvYbJD`?C}V@JG-OW+Bz8P4(>D656wj4Lh}@-=xYsXyn(W@W@{DJT zct|cvQdt{P<;*}gjLQ3NtNEFtJQm^bk51a`?}Bh(^op2+B~*0* z36wd*M4Z;=32quknr@NmO{YYoam(V*uR3XI$gCf!gG8zmK)?KC=3Gi%+BD!)>!Nt@ zJhF>;<9<-Jx9~~qm*k7nJ7AqIFYE(3V6o#i^f7yiXNluW<})`^^P1V?PVjl=(zfH? z7&>&0&#A6&TyX>NyBow+sbV+_Q<;EM%*y8Jn497rMD(cieF^-WLNAi|E|q;G8vjbw zmWeF?f4TtwQ9Oj!)eD_d8~s}bz3Ecu-5@rse3)0%yp*(Hdl?04-e*^3+9bKCR8doQ z%d{?h&PdIecF;W7w%;f+{sz6Pt&BX&=m-2ZEkHeE`dOep;b${8$ytLPl)6toGU1s_ zoW)?Piyx!2SX$w1%D3Ve{|N4c-@iT-&EJ!odFhhr%Ns}wha{6A^x^bey!uM@K!a(z zFTBri7*zmcu%_Sc$A?k#Y{*uG^fKw{gNSwoyg-BgrMr#-nRQ-{GTL)|eo8Rd%)&Xs zUQ5l`{G%8CWbSNKdM^Q;z;QB)fW}%dSxVSo^>d~;q}gx+R}~}mJ3gH3MIiuUA2 zCtnd+G9T!mP71aYFO8#!xv%77y9%VjERadlw5B&|w*MBDM^jn?uy^}2W1q|$LBgs< zngFzxHRI;6l1VR3x7~1Nsza3Y|0C40^eZ|Ttd*pb3STL(7q#sMramTxHbqXBq{ZWDP9}5*`8!lG0Myz00e60sD&Trz0+b+bZkO0w0Po2}0BCQ~zvqAhIYAlA^S=KgKPrNMwyhdt+ zh@9~ds>WDe_KsY-NQFbYo^FM#&8hdok4;i!7ZyCBfU~pkE zqVP75?3QRmV^rgs z+Zv4(e4C(L(aS9ZH{!zT|C%W>*H6I_dv8EH3I_FZ=4@ahjiF-)U7C}aMp+w0hpm2> zEiE!kQRPB_#@t~dV5|BYU@P#(d&v#>T8-sdK6PvvH&Za;lmw zVOkC$S>E}|@;laslChPT5U8x0ab2N?4`UVpZFtReSUn6VIndZB8dGf`JDmLW=~IC` ziae4^x9tJWwA83p7?wOe_pva+F>H1;_HqNiS9D1q-Z?==Wsm)3g{(a!le9HH6soeZ zfeug(To+lRyBtw6)DJkPa~q(j+lT5IJ+L-|CBAn;?tWB8&~SxK zlp%fWq%vg?)feJAaB7so$X0fMVqJMlpvYIUb*174bH5CO(mbx369GKp!{`{}cN)ZM z>K~>eCmGp^>sKT_ZvD%9u6jswDiTg4i$WBV$tBU!w9^QvSQ6rBTNz1`$s-h4wakqU z3m^(#tRycA4q20e&zRDU|5R@MxAXnC=S}VTkNth;LqumXPrP;T^0hSl3(@6G8z8jv54y6-3Ck)E}xMmTu6sZr>*uiN#ceHFemQx0vH?WPD zW1q~DIK>Te6lVV5-2B#j9+f06>-O!#2Bug6N?n;usgo*|WikezatSwtDodUI9V9A% z4WC1lcE50TJsp3+2J?MFPLE_8<13y0mwTFS6JR@HhUVjL1*Z{(=lR`&?B?c1=HxIN z>h#J4Ow0o579Gw46CdTO<%@`$3d{+LAF~0WD|AU1Ip|6pbh%D+`@r5r40VRL(IfHN z^7f3)aaakz6JyE!pw z`y+nq6~yCye^1_e{U|&euIb)I0Smjh1wOp-@JLO^o;jHkaN!6*MaTZ7RAp;O8m}xtoeAN{BTB(*tbt8n~Qi?IxPbb>_u(Tr`)?I?}==FB4_Nxb)MEwEq8I=4@VHAr;fOtv=08wv%lHF%Z z-}yu52u#MTg*v9{<|bavR1VR0h1b1amoO6#cd_){KeNnSVRVW@y!DJ8LGk4m)d&u) z!0>cxlq#mL^l6<~^#EDtu1GQ;@>nfKzp6hpv5Gk7i|9Wh`6t5VI$PCbbuKPPT9Tw; z&(yLfUy$5-n2mQAcU`At8lPGlsCBwZ-jvj>Vs^2enHarZzXxzw^JE&SL|rV8LbMhV z(>9HDeulYrX?Pj>biusXU@d~)9faeh7k(-@!NF}#a}%%UoJh|wlGUEYKhHwMm#(AT zwaO7)?Ta_QwcWBSjZrnf4CY=(Eyx8XFLZmrS}q|z63@aVAkT$+$h-?CRl&bacRG;* z2)6T)UW0wa64d94e><)fGe20(UTASpUivs^{{74EK*GK5E)qW3fK!~l=F>uLc^fpr z_{487&FnEI-txhacwCUGW6m-di+|_`)h0UqETN1hm=CLKtBCiJLe;<(W8Kwt@O8HS znePF6Gvr$>K7ki#%w5(F6{uK z_0CyN9hN244sCY+uW-Ud=6-99rpmlDRt#8O`heBfH&rSMxoqZk&5~^dcKErk?6eq$ zosbt^E_^?$_3scd6>+FH#&S8SbyvaOoJA~rAQ%MJr7}G>{vFB>jKWgQ3S$w|@^{%y z5hFFz0hUZB>?YXtnn%X0FIb|xMhZ#Vv=$EjGMxfV+p_<|)mKJEp+H;15Do)Mx6(0m zm(tw=GIV!$N-G`GCEeXMAOa30A>E*KOCufM;Jx>)_r71V7Hh#UGqBG&d+)PP85fF9 zRZ&XdYlbmqaS1&7Qu!$HkEK2=%)ZOvQCzlNy{NoutytEQp(=&w8|nk$?0I=$^7P*Qk?6CQkr4NmXw(@}8s zaT-6Lr1`%4QXt)O>k~%DpZ{17@j-Msbs#I-U>pGo4HHiu)R_SroHQUxh!?3o9gEHrc%=L`)lASrCb|DrRiPXWMIrev5V+}kMNl`pNFr%BXk2*z79DEOD!|A?_d$1Oms!oh+JjIxrfavJB z6>Ktk(@-f(@e&;v0<7ZakiPR`y||`LLX$MbOFM3bpFIj%;;FuR=&<~%O%Vc43`mM` zW)Ys5jv&uBedC|$h-%!YbMi#BRhrl;cHzj`zwbVHBqJEqBmkNyLNTcZlnlFQmt&XH zp3qDI<%S?UFj$|TQpHzfG*2&LL&_N~E`5D_RD|K(K9nRIf_IhC9VSgZ6vb~ma*3Rb|2`2?g2T-E?ug@sm+=v_c3nDUWZVPwW}Wke!aN`^}t+I=9ntZ^)%~T44Q{B8-+AH)l+~ z%dco*C|);E50Y-|mG1nzky#OjNB6I(*3`!#xNZF~T<}{e!N4dHU#Vo%;nQv5Vy8de zPt!T-Z|qfn2s~>?>?e3;}m`>h(E87ewMeRd$qvVH(Iii){-W=7Q1v;4^lO}y1|asmd*zc z1v-4>wUb1LV)H?@5=JGk7fYv}{lBsStN=pTttS>M$?6B-QRR%@H!k|dAEL3Kub{75 z&D7`lcDTm2{K890*6qW9Zm=dcYM??M_%af#N&8I{@?pr9#q&3uwrP%Zu$}+#M&k|2 z`>C;r2?mGZ8ik+xSQC@f}9Jwgq-hyM~)M(`{ErQ9EL3EY~r7eov27wojb#V39OZ-#iFfkCSY=Ke(n5Ri|U#`+NT^dYJ)bWhlaN z(kp&SH{96H@_McMdDI_N!(BbuOIwl!T*PR856(!sVFrqZzl{!aNs}Zku!Zz4{>Rp8 zqd(OL9{CE?#?m6GV2gFY@6SDBh4N9N4bnBOH1);DGaq~$Qm(G-yoOc)`}I_2(+LSX z9A+r>yzg@;UkxW_h1n(3e!&@dfYV1Y=_OU-xvsIHE{i5u)rl&0DCI-K76edfMH?p8 ztM>>*%&2prLBlvsz33Ud1bmspDj>I`JQoD(q_LG?HW)HH?O-EggT{9xt{`(|BuRYi zQW?0G7Y%Aeh=CqOet?iN`f6t46&X#VK{x@4@O23@@rXHfyvj)P!M4tANu6gORp23^pp?YZnL~=Fvl^R%M7JC1*XJ3uT8$_P49j+Z(WtU<((Y zo{+`3N^vf(5fSbgpa-iPrzjY7c&y`X>aBKw2j42(8q*g!PiZGr1iR>pi)qpjX0sk| z{iGOxCNf0EFnxCzDwJbb5scs9P5PCv;(JI!_*L}1>DjerlP>xl#JABmuZS3e2i0cwpT%V*cPH;piKs=J1oqeKzim?QAEGTy2<7?iUv z5`Oyfc=JGH)$?m^aSzw>~Js5CQ#~yB{`Dm<5~MD8I}J zvZv9O%1#q5%V_pI*4{Hauv$^zZM_Iv*QVZ^apeCy7tEE;PG)RA%>^depSpsjrk=mjY70`%w1Ohh zlN@%*g$|j%aP49*x^7VI5h5Ha1)27-7kc;E7@sRA7ykmGN4E6#H03ug)TZgC*EVPL zI+sgvaOfmp%Y0Y>7jtQh*$;>xwJ=QTR~z{;SX41zxXBIJDi+%&>iL{drfWyocVsUW zYw-#58OW);vh3|?GxW}EJWBND1?32p{rRIJLO4d@%3YyCF8cMk>Fx8Wil}!E(pEif z+tOC5d1AQ+EPqzLD}puyWEk{L!q7s{kkZ*_0>t&-@Y9RyB%=jqmgDY$%&N?((#@#S zXtx6-{)MrBAF^X230MD4d9Kf#R+47amB!*~isZJe2qZq@lk`kbglgDYV>$ELS`%1- z==(^V!~|LR<&<6}SN!RV=;2~m+Bj_lT8GFb?W&~k1ZCWf=525%-CBwEX%%A^D+aj< ze`{3Y{Ie#JU@-mse|knciWGEM%m;~7V3$5C*i9_%80TAVSrI@?vmw04@~w>@kDF?) zE)roHIUTVZRbzo$t{a70=)RWW1vZKi1`+0weq1YOF*_Z5H7pIhj$&R|9a{GTC$lr% zYb&@JMLZSqTJ<%4bEyLR4ql!@u0pa0_}Ad3kt@hr)dh%4rKmF$4Qv2uAfx9-ipde- z%J&0ln-6E&hpCiT5{O+yl_^4?!d1_2o2d%nQ7&hw7FEWmc}B^*!NwgbxuRsUP|S0f zHe2RD9ce>bk9m^<{+}<|mAvnx6H_H4Vq@@h-4*KD(Ku)P>)EM;?^(Nt^EcX$-J1%h zjHJp4N(qXZD5i*ZbX1UOl0K~AxD2J*1_2w}5r7=nR;)j2Q(L?>GEOCTBJ)R!qSEpD zd1>(cL!~$iV0673+i+sO<8fsk?E3&Y7#W=~$Fb|4u*cA?bE_DOQn*)Bpqz zk~GQc@rJu0aa6U2rYQzwg}>$ID0F(?7>;kX3fv^1d4TOS>G|eA)gxVcF%>z_0F>{X zv7yYNLjD4U+^)^-oTNH;9sE%xl_XMK`c{ZO#n+z$&%b*;4PLX3&jtC0zNI#4 zf&@#CYk_coJ|e+Y5n~NyrZV!~@wLpxgbmx!_S?OCEq|GifESJ6_Q>O^&x{=n*xO7m zd<{KOVT3_!fP7fgwLr(+5Bkl$&ur1 z+TNQW92=eiL*h~J8}YCkZEY)v4<1;tnF-UT&Ro2~_4gOrJ$w3l!xyAF4rYv9U${#R zJVIQ4{`v}?jrXhj1^IY+AHnPB30%iTN@Fo>`k3e;^mi*DNG^u#+(=YU$dlMbDz-KG z)V^k3R^VR1F?t_*(&4?*S>dF^T!Z4Rd@UT_?|Q3_x53!?q4pV}X&&@JB9NW!xS3I; z&!tgi2y^zmAYDRRD!yZcVM|wUaMnA1(yaYxCkI=e&LyB}(cgM+{47*odcLSOYT|%Q ze*4gS$=y|Kxji>?)@Gz;x;X&e5X1LhjWU3`b?4+5iD^EX9D4N{9|5akL$t`CW*!VY` z%Vb=KhY1d)by2%5gxC;AfaYVt^|#3{>#_=7hW#i}_4zLOPEL<~=yELKsQ z7eD`;Sk4zRq(in13ItA;n>lk1Mh8VhCi>!36$mI<X}|KT6Tg<=-hb8?yGqWm;qx8)c&^!6gcU_=GNkJQTv? zNec0g;%~Q0C~NPRbUo4rdvU*IOL<+5E=-a4=yyY zb;Qvu1ibaW2o=Q!fE@8;_G8L>YqQ#R;2JX zkTz$;;w({2d3t51HWb2KJiTL@Y2LN5@Wk>u0-^sY0rs#RykUmQ}(x8IR;Vs z^W948rGi=UU)Q>Ypdq~CuRHkQUjZuwzXNiW4^!hIWA$oD7%{s8cxF_>G!D-g@p@47 zl!3!k!-!nvcz6~uoHe-sS4JYpX<%<0)_2n~oYW0Rv?v&ODoQQH2#hj2TgM;2Dm}1% zvw?scybm(#o~1+CQm-S@%MUk~H`c(2Oh8p}{#JlMRfw=wugy_dmEUI{#()6f{M_|f zU@IX-?zmq2A1%&yH0Ha_P@+pM>&e0E`UQ&=<&lU|a0Sa-52nOhwuI@v#9!sxX$B6} z8&49?=Mr=UdT~efE5xE_c}#Znj^COR-)QUo-uMg)?@9v}lw%;mgLfm$)s19>Rh8JA z4|t^SGh-~91l(kQgv5>|vn!8Pj?s=$*Y=9HV84e%nF6xRABAHTl*y)#=XyCK*((QY z!*6x5*puWrZYC_v+U{6=k*z)zk3n@`n9LL4&`3;K@d~f2I6Je&MA>e3))h$XRe1Hz! zxa`f6(DPubrN>)10Q?Fe4SSY`S;W0<51tegU<*BiK<-=`B4`c?;INfj6meO8oXhAF zWQcSF>~-cp`Mq22ZJ=9$d~2y}l>zK58YG1K3_9^P-<}<>Mdc)++ty*g5gqpiF(?4- zj>||fNn~*Ln0!{D?P2)R?HM8)z(?x3lT+Yfbei$k$+hOWpUw(5tYYyoGN3KRuk4LJ z+>A9mbVHHih@_2nbv{cTpHp+mX|H}0YonhR`8N0WGk+w$M>n{6A$s*~&N6+c*0xmp z{ye;0*7@ue`!t%@!S3^aOGBTfzDY#+g*<|2i9Lccn7$3qdX&%c+==^KLB9F$;kYoU zA740_bou%POd-O<;E&o;atZkQV>Zf!Ea}BF0s`?gsa8guL1%_Pm;j zmw_rHX1wYN=~Te0)!ui`yq9TgF3LXe&ZEa_t{AI;X&^0D)hp?JD`Ke&NJpv$XkxLJ zZ$@HQmpTmqQ_WMDNTob}!OO|Dty{UdLatri7=EP77pKm!Qc+XPB97GXN?2f5X;&_O zCiKd+1VpGqmB6k-GIDPV zlc%toJZ`F`^#n4@=Mq|AZ!2%oraX9Zn!R~0g{F-~bm&J9E^aSY*hvpu;HIQaaTAVa zs^%>0<0>?~i5~trc(cSH=&qMhj?1l8`nEI?hiNLR2vMQ{E>Q@i{Q<`q>v?_!KCcrT zM$P;VHBPVjj6w$w>1t*F^w&k}W%B6!JdzU3-&6qq(N!5f`b_44Z1`V39~!t5{)KfksWACpm0}IIa(` zniNk0TTRFs;-m(EhXR9=;K?i%a{#4fa3w<=FJkKnh5)(D%KxbjuAb{s(7#=?x{=tX zVNsKy@fZGq>PE&!61{p4yZWzLy<*RuBa?$7=q=bFLL4b^uYhIZAFP?VTDiOTvE4TR z`)PJ&)tdNU+l34(Lk|~Dv(#B7Rc*R$=NvE>kNOgHDAXfSCI~RfI>@;if5|M{I>Ft@QC7zrF}_QygyKGGXe73G7kTA{tGqaZquJuqNBJ#(TH&ZxPFW6H*!* zoJaTloi4DqfojU&t;QFt7m{US1VG!GuzdxF$rF!7&iV!QI=`(1<6>2dHCO7t#n*Wv zd`I3cXZw@wA8xk=WZj<7flB34Y})z@1byRxvI^Ku3;+pC4Sg7=$XlA}0;U*~vZq*? zPDQB-+V-X@TXzp*=*Enh=k+gQx9$015_vxwjchEb-h+cm(@DqSGUaS5DV<$3vR0C7dHI zaD~rzY1$W5f((O>NI##H9gHCb_|$(cE#$ZqbKaT%W9HPM;y3nORjtfQchZIj!&C$c z^|xFde+^czH^+WIiHZD~k|+a^>1$5amUxQisxvWf-xoC(`5Xo}IPXGK+e+ENgQDt+ z-#{O2Y4h)wDi*St;o)Zn!LbFtM6-N;=vVPDL!C_-Qb^m;$OnS8iXk`1vC@6@&*l>cqq8?}jpPyG^p<8QWUY$9*OqKk&HIEjsl_e3 z<;7#@M#@9VwC=?}y*;ZZcLx#MLSu*;#x!$v+zdsZz9X=owAV>kVDvhMPE^QA-q!5X zNN$$~lN+TQ`Z?H*IB%Bmr<%^_)zZpKb__j4X}oG+bSdd1F^m(7C{#@wF5Hhy!nHON zi=C9f7j%x&37ka&f?fzk#BZ&i}+lCk&!&Jv;Sc5|im%V-> zq?vJ({+AK+nVNUR&=z&*$#7X@-LR)IcIOin-=6miS-ILac}BL7DFro{AUIS7RVQ}r z!$i0(HTN3wclfacNYR{&liE*a`4^NZ8!9etr8cexoImmnyB_FV~m-ti!D zfM*N9>bbd0<-kUrt_b{|9z|Wt#@#<9|F` zc8u@|)FO9&%UaBeAa9-#PRjy*^xA|t0P5Xb6WPblijbS%K|x;yD419SdC<)u-$8I9 zlqVEE3jnk+1ez4%C^Us6%4zoK3t ziawT)N3LlzISR0*h=~)I3xj-r7w+?tAWya;4i=}pA@@T)KD$HueE}*CVJ{hLT4f25 z9p=~7i=A&M`JN3b!fm35l&hvj>>#WtWbzJ#{+P)C^?g9z`+C&GKnsL73Vu{#$y$nH zOSY(ckTL*(gEhTdheT4A5!pBgKLjW|zZI>}h@qhYr{sH1IL7Qex<&7lHa#SbC38Zn;&8j#9EdAozRiT_Z zY1rb#2e5p=Z1VKXHnHI-%|22|W8d&3ftHRbRgZ>7ZYMGZGP@RgVLR4%!wfUS6-GbG z)T_y_(35z62EBT}a`45}u`n;{O04y$w0V#d;62alEkbk$PZd^A4bK;BA{S_*+Yy3D zq)Nih^nXzX@HKu1PoX9xJMEmiBQ~;r(ke$X9~UR{5;plJ5&q)+rcu+%+9 zadL{cDm5Nq27K_m`(x$meEeoXmWP~2`Q{=QW}r85O98V5mq>ZpFB+bB?yG7YKe=H; zMgh-)Jc7uzu4dYg4SCB0pIYuzk-l|s=QB7xYmM=E7$PIkoZXpI5^HOTbu3eUhdLO* zICcD`f}!|lfTV54=WE22>cUl1!=Loj6@T;<>a-=HScAFG1Av0heXm3O?#Lf}eNBIh z!hfQ>0pT-SLCai7y#g)oCxlCcMTQt!3?xT@W5h9mGR;HEzcz=QBF}AC-R>96iz?09 zd81t(6?V8ScYe%xjg~<}U9_2!7a*8a&``qmpzo{HnYOO}n7?kx=5gG_aY9pkQ&+rk zU%gB`<8O6VFXL3OD%pvEWoA5tnmVFwm-L_?J^4jajUt*R9*=R`gVid%IY2dkZ__dF zC);&Gl;-fnxyXdRxMpv)1d6OQ+IzTfxrt!E4F~S5W{D6K3h{aR_ zT&8yXkCakr8sEj{KI<$=X9dF%icm0Ri2xLG(G0`RUx|Mj#(0E5)265s?i`27%Laq zL{^IyD|HE*`HvW5DVS0G8>8!*nMER%SrsjMG!R4n1LA-yk0TN8kk?N^iAjjrU)$5# z>wmRdR){`)yE_k zi1KH2=(l??f#>{RRQs*--6JDed;9V)5H8m)(3n-7`U$T33CUCQ{^%mfIFnHv^^N5_ z^H4ivKBphHkG@v`!JHeNd|5~|>tHKS`oF%$#@}6lnt=ugQX6Ex9G2o#*+P%Eb+O`L zZ~piigu$eTZ!T**2KAUV;x4vALgiKXz3%el#;3{EWy#WNo32GE!Y$Gbc3668&3EYR zH{WULY`R&{vnBOp?*}7Ni)B-SFn-B7H&sZ%O(_MTpW55JEmdD*z3#Gi%$3NKSZent zj55tY?;>KSgQdZMte-s9gH>&bVFyv;k{|M#@H`FKWF|keYq~o7ThQ25^}ufx7PJrR zeXdItrgpV$IwZ}y>WDCT>%bm1)0+YHo08jot)cN-kDC9|( z92wIeAQ60xh(F?bvOM<3Wt{Law2-E>ZkTYBk4i2 z(VO*c1<;s0at(u3T`Hj)$_cP>Ngo z<0YBjE2T3G_7tA$;9W878Q>E3@ID_7r>seNA1s<241{Quaf*K=D8-j(U_5}Y68r!u z_5IY;)anrT!qp43vA)w_0Gdt5slnMoqRq&7_HW9qI;Cr!o$ylX=)CwZiY=Wm(^lY1 z*iK2u&DB_W~F3->WpQj{MPeR?G8(K>^)e?6B$Dl}Y>{>|iDv zVr3erj?ic=VOSMTxyv#Bdw_Wf#DnoS9z2#qB1AYSE2(d@68O=kH4q;2q0r}qHUyt~ z=_*>U!Y~JVURTF#^J+>v8&%8UB#YJEWU_-sAd>^V`Ltxd;rYs}Y77m}n=V511JYE z8@n(Ky!2SBdtUnpX7~P&T{H}ZO!bNfAK)xCP=ZC`jPp9s8RAa|6Dd8#M80EA-TEyp za4D1EN&UP2DKuqTf9O4|WfK|#Nk~V?hSJ2y$xy1%5y~aT)m~AYFUVVxJ+A8eqmPp5u<1D7u zEU(e)WjX2FL({z9by|T;!m&7PICF$fyJHdwhN<|vruhP8T@yOs-hyT|?~Z9g{dT3B zQ7g`X80B}lND|Ld9Bg;MAU7U7{4aC64g}~qmQq9##2Q2dL`}+{-ykb%MH{C9x|`VB z49+NL6BP|)3ct85dC^8V&~ogX#2+48#AZP8Qx@Nzh>x83nLE|=UucphucuQJ{BA)( z$uM<(q*Bx+{HVX+X&k@xM2lgE+>(ucJF=o~;#SM$2rT|EhQVFHZDPd@H`Elgx$04m zfgLJKu#1Qn*oB-{R=wR>DnWmF^aC#T?^2&?;-wmIC9x`6B z!JdTOQ7Slb{S%{+u42h71ze@k-M?x^G)7l6P<_>tT6P@2yF(`~oy;w-^PG5GMUNEC zF1e9tf|nvWZ1|jK!aslFKb+L|e)1w+BY)+?%hbZbh9tzYf)t~lb!&iRm+TPjpLG_* z6o0aB?jk6#gLD(9Hka4aCcT#w>v69O$Uq9kt0pog8p3D7h;T{<%m&&PM~-V7bLOeb zz_bHpUo&x}+tFmj1UDcs(PY^h?XFbr*PTwxANy%^cV-;l4@PqoUCMk*oOV5II(+Xk zgwjk7U%P`ezzNH;{l#Yd+i&8e;`@)IzrKWNx@SM@fQJa{@`>`%h-x}?7+d`=q_M~O z@&n7TYfibuPuhCBP>!QdKJ(M!w)OjTuHD4)NdY0t*IAR^bgpYD2+oNmt~%bIXF|Rk zO~OO0Y%KwDnaBd4!~zck3t7-UI`{+}U9aof9u>tPbE3-W-uRC;bS{9kL+pZ+FJo~{-c zIX1CbU&64UMRd3S@xHiOpf5;_BAx{?X3+lKy4%YulvZxcFI(Dcio0*qTfZv_%wq9{ z9SE7qnYG;e;*`)6&P|t_d#_IwV>IQfo0e(j$vf5SI)7N?QB*1>@6w-qgMZVb&5a;aMPjv5^|c+@D+AxS zTfxbEl+?4bm_ZY~=J0v}1y;@iW{U%kk(=$6A{j|!cM+H$c+trvY6!e6!(Z%lJ^`#@ z##^1NPCfsWwkc=Cr$TwGgl-u1_Eh9Tm{oJj=eAnPH0oDM^a&|yw%Vq>Y6o|GKVj!h zF2?X>Gos+1e1{g8FvZ)I$y<-_=&mQ8If9jj2pw2Jt49ykhb^9FbJa*VsPgCk={t1~ zeh%t%F$#N`<7^ttY_eVV#p>b}`MCyQ9*!$~+80MmYDP5cw0sOZlR!jBT>y zj_Y62qi;%1pj*}=o;v0YT?9OK((@m1S4j{nKIAGgzKlf+$cj9PLBe$Ei+$YU{i4$} zR#=)&WrT4Xo*C^dln%XVtQ}=MFjf@3vh%Z!bDiDCwXvGfvSv7X9-N6uwM5txeoplg zmtQ_I#qUkgKEY92e}kF#O*3P3gpGblFE}A zu5`TTONbUR;iba#?%IxEt}sOj=(&Dqyzk_i$PZd;!M(n2Sb!Doe{Eu1@{8DV14Av z467VvjQ8dVT)?X!75-8}i6THJz*DpENQ42l;Wr6+j-E`+2TaVh+Iw(Wowhfx7oG$quDREtjY`VQ> zR*&wG>8x3i!Xd4#$e<}fET4`&SeYo7LR_S%|NDJ9)U`z~m=iMSbU9|n4E0q91XV*q zC5dp*elbaO(gY!7MbL_>l#z*PJgi=dc1y>4!8hMLAaMrsudz%Z`MXzo)n?NC?6p%r;}fi zguJcFFuA?;ap;F9K;N9m`3OQx;5ia4D_LzT@y#JKj|PJ)&Id^bo{?KoGmqM zsq5Z*h0kag9SN-;1mQEP%ThoA8a5VP42+Fg$`0=7>?iz0Ky`N{g|1vQ)Ku<1BW5WW zCc$4z(-R82O1!J+8#Tz|Bq&j1P6ky3LV(Hn>NqH0@^@P+K{*HUto?nk(ofN%hM zyq*9Cw5n{ta;(M^0IMPq$9S;EwCIy_y#a4e@|hCki}GXAXU#)|+iQ*nQN7GC6nf|I z*fT;<4uWuJK-gXX&ZCI8)+K_W#?@WWtJD6ohUC_P#4z_Fm?@QDXgw}i();-;#c|86 z=l8NFocv;XiLPS@YMo@%MHUV`7NuBrJwX}7&wP0z(}fn2NH>CcDFoi$cKss67aMBv zgUvwhRiYT_?VjbSHadEkwAHBpi*P)!m&%G*NY1lU)dl=dpqD@1I-k$?({Rk*9-c7c zd-zFIn1trM^HK@U63v34U>o2Jd8#Q(Hp#7&VE+n>+JBeC1zMK6B7@?gy-k z>8C_GrvfvkYKfstSYMZezN9Jv9MSG%R|{csN#s>58|O`t$!vHYorOGFyfW1T#*gzq z&DOr_1)w#qUexGg91Qp>v-UXmKf$L#UJC#I*a~f>gmwjNAs0)7U&B^v2Qs9M|5{~) zSRyQ>q0fnzczalUsek`OF^WL%(>vp&J%;;&cl{ju1LyJLlAQ8mEw4TqH0rXsaLM%fatZn<2@ZNwY$d#0r6Uf$lN+>)=EVK(Hmw%Q zZ|#89qE;-Q4%*C9fTCPhaCM^kiQx z(O1(KeCk`iPJ@#s|23U()N29!gP$)~cO`U$Kfg5>lnWtY#AB2!6)nRmt(7kVCR3@G z7NcmQXp<+>U}=Q_7HbO@=E^>LO3Ri~2C?%C%9>EpGX6W#dI?6Qza<;ryq05(F>Zn} zk_v7kRUm6rs70tns6?Qf=%xR`j>IK8N4lpvub7DCZ)ITz?=7G(3%WuI&b1Yy9U05Ph9NFw%xe#*}8{<|a_kO62sQ4E#7* z@J;U>pd9I1L$aAi-{>e>Ot-Jiny8j`?Bi;rvRY|qq;>n*f`e`am8EoFE*kd%6t4AQeyBvNcFIq6VXeyc`KI(>}l5}RWdxE1f z>N`GFxb^#))+^j{rD&ZB^)i)=v)c z-xBzGEe#82EZx0A9Q5!;5a#+#QbS=ya&%YnPwf#kUK+VqxPjq{rGs3QQung6%`!yY z4SjMz32D6Qs6|Im&`)-#-_(vH^oMqT_bX_RGko)QyP!?_ z-5tiDANZ2m7hzWUw-i5}lX{Y7M|)Oth!^JEWWGDlr}DT_w5W>@GOug+eR&h+?s#eZ z(_&@0EOFki9~hu^$!KUOJFxi$bN?gY79SLIdfp+kvG4k)B}XtHE&{*0D!6~Mu{=7x z{FNX|KbZ7%!}wllMTCjFpMJjK(z*3?3j4k`BmkBW#*W=!_v_0$<KOB#Qi(Y<#dD6iiJlE2#|=J4&&q3a!sQj6TrK$$&SC=SI% zRn}3^HKtrPj67{B>Vot#6*o`U%=b}8zk|Q*Vy_A#oMeDM*(PFeEa2!{FV-s=FYTn% zJ&+d03t3)p^Pdh47Q|$*0k7n;|sA)d2 z*xGcj9g=`E`^9?UnD)e)-kT1I^kYSw0rm?ok|47SZ}NmsVlVoKi=#x8(W#%Kkw2au zTKj4%(6i7Mg6X8|N)xwCz#2t8$W;2a3_RlLA!^w2s`64`)!7jPj_!U##L#Jc79vD= z%!x`U(5%gdsBge6Of~c!EWC#}fkuLw8spX^Av;7KUa(UMRmG##NDDB)5IzH~aut&g zm#eL~59AIcej=~rjF8QNa#1BRSkmgm1jfkbMCRcuf{`fOV^=g1Od9OJZ(IJ49%J^8 zi-!x7n{3J)Pc2D}x4g1eCmFK#;Y|g5rFa=$=D9}jpy(Bed9;dM zg&r2v>ZfZ*;-bz-Mc#7p4qN!R;UC6(dcJomt;1-B1tyg$6mWEtSY_rfvjY!O#r1|x zXvZ)U!oTE9fSjOnIj_u*E?L+x1Z|V;wjcB_E zgBbf$DUuLrt;YC@=R`j((8Ii$zs`(BxCmSD_tRLOrZ^8i`_=AKjGSiC!<4=AzUR!yyek!>nOkyzW)qA z?NKS`{At>4I7D>eZ`FBwh?6|sSD84jqYzItSP(*9O-0{LRJ)2co^{Yj7Eh7A%|am6H^KLCY^<{G6h}ihk5195SFPZ1c^Z|^{QZe> zEb@eed;Ow85cZAOp8AG*(tKcWcR0@n)tTtE||(GJSY`D(}^;aQTUa$XK7djL@6=SeRTY=uk5p zK6O&J&Ny`F@QX)z7m@Ek{-L3* zq=RVGnJ>wTSyE};viG^rjg8&SPTa&uD;f(j35`);uUGE7bTT(~GpO3lOkWBd=QfVs z8+Z#UeC+$ElOEadeAT&{vds~W0*P|Js1pd*9cZbOUx{5CtABdK4T~i-A??i5J{yvU zcB5X_hEsUrI$+oU_>)<_>xb7br+dMF^*)RiU2`rmawVtEj<9H`FOdJ$#VkW3@v2!h z9@WBhc?g}<54U@jVHHvTwvGXKO!PFo)w*cWP9!fdFeSETH5L(^0_;1T)KNMjy@HxV z{S*xY{w#MZQFH4tabt7Ovt4)oLAr15-X6G@rj}e^$>H$(JrAx!? zrkh3R`b|C~{Je6AlneHV?kxFi166Mb+hNj)z^|qZaro16AtmW*r8g##UcRbq>{F8Z zss8aAN6~q57o;4!Ql0#<+<|eeSXA72O!oalF7RVPN{}AZa07=cBEH~6XEu(S5MZu& zv<58?^dg${PX-I%gy9b+ltejRdJ*7^yV8@K@n>lXGL3Ku254})zEIU+7w&FNj4&O> ziMe(C->qSGZ`j|BpHU_F2zM4WRN7O|xK;kGT5Wx!8Q!+25d*7dR!}WdE&Y1%SEvT1 zlB0WONciy0yZVUYXb4TcF|Nc|{_8a@{jCK{lbhopHrhoDd%Y^Qxv)0mL`FT*TtHDm zSx_~?dKYalHgf@y^t6k1X1hC%Y?%T(8BZYS#FHW`D+bG!&LU;RMw&Y#WrWeR{M%_L zhbsMdwE^EyV1dTZ$B?12Huo6kGf85FUgBO(4ffToKZeE|IzeMkpGAAZ9s}a+yF~w) zcm_I7L<~`^t8(}WFEV+DcD%Kp<71UlLs8nMxeKy7JME}NY9WIwFSS0Rf2uOGapHuB zwYXqI!_kA?r3_Z6LeFe=V~KC%CPZ4J(MRnQ^XBbl4+$H!PNA>l&>bBKS9w=FAT}R+ zD}i6jGsXDfQs};93&*D2n*HmXN2uab65HTk5FGtr&Rf4g;a#MXL`6CrOAwwWrlC8i zUbo|>$W#HLjQ8InNX5eTp6TeQyx{LvQZjM;*|Mb#999FgrIgwC?8}SRXuW>4DTyBL z7xos!!o&MvX|GoHNnQxP^p*HHwYre5TDEPTi_VYfmX}EncKSG0lya6B$|};aH^7tc zXJlr$UqbjxZyM7gf7W+LZp-z3^F33xt^}OEsM7it>J=TsFlUq$10wDD~$Mty8E@s0q~x;5F|1$&yIKK_r{0s$9D`h{Rux*m4F*A{&6j7d(e zl?%C5ZzaD1Du?r;-68Nt9?L(_^k@4i;+(bBHLSdQ*2K#eYltF@K85D{F8S-9kUM?W z=v!`{vfVqZ*!(-hTF6Q%q{C?i+uOaPg(aip(@t2`=}U)~JC_&ssb5{MFLUh1FO9G0 zj(@~s3wOi?%PYtQqu1`!exmX`Ds4Ui(W?lJLMcSPx9%QgpHH?#p{}fd1GU&@38^eE3REa)|59M0>Gd~gZapM z;yJ*sHD#RSE-;D`+{j`km%qKm6?K&kfBCrU`Fd&+@+_NF8_!zN9~D;EkC#*1GDp{2 zA>7=y{&HyKkWE7DhazZZK3^a_titoQc_?D%G{=4#KM{ASU=V(usbui&diDJ^^x>GC z!uKu9GIsY#yzwus(%Ji;Y*ux6PA!Z_*v4E?YZ`xBA}b{S;4i6J!-W3F+l!m9cKh?^ z$LEwRN)A%UbMTX?=V0lVj!PwC1p%TxOSU=ZlOr{m!W74sC3<-fKDs+T9}$&MQ{hd;PYf zdA}BSMHcv75@#Hya|4pKJMpg$ta#bh;~$2c8R2xGtfIJp<|FDRzq7*>B<_=f3MKZ# zi`Cm>txj&)S(AwIEV<^-EK!-#jct*;>kqh4Q!k5Fo0ONQUELF0C2zh4LuZZ@XtM1> zm-(ZqGd@LQaFcNHP9DA5FbeLxUJzv65Ep@3?&4&>Ap)7oMOygzse?Y=mHxg}_>LD} z4J;t&vv93qPBY>r?CbpB&78LUKLYfyD4eR0j@~PTk6sXh@?JDwjR=*ZJ;@d*MbdA^ zR9q@Ob^4=SshxfoRSd!pdwYaDQUPi^3dF28g$n-zWge2W5F$c6JOwqp!E(Sg9u;25 z1S2(ekR6s?;cB~)fO8N|QPB7DsV-0jGv-#m6j((;SX`0P1NXH$C#*sR=gr%R`4EEd zxE1Ddz1^Mr0&nwixP?*+ zi*#7Wtcoetc9FC`c2S{yi0BT?XHUDbK>2@6ePvu!0kb#KE#2MS(j{Fk-QC^YxpYWK zgLHR;beD8@NH>UpfW8Nx``q__+Hbo2&Yqcn&5XgN&0>G2EO)s}n$BfV>`xq8Nl04c z69^DOHZ15}sY+_AM(@d6mmz$8{*M`Q7=IE{khsJ5hrdAw>=KH(WC0^*$T&+D?b|)Z zfaQ#$ZBOxPmzxuY=8Y5hOF8_-wZf9$g1)WVvI6>NM~H6JZ1V#-er|&QtrvvSmtjgZ z?R=?xSb3pv8>aiV{SMT!p{PM|8YhGRfO0?yF}TGPzdz;(@BV?e2^a8@<@*32GG0Z$ zp@GRlZkmPC?45S0lxB*B3IW_Dj^^G=^E~l9-7gNU02yN-Y(N!`EevR?(>e`Q&OK!_JqCo`9%((d1FZqorDLNxk| zdw1$P!VXryY<*MtZrCtydwP*;?kdm&pN1IACsOYaHfVsdZBt?}JrW#)cp>$~9jg4RXQ`1#C|6tE+9oCYKxn4P5imHs6(D*S7<#Ryw`x1AvqF%=sC#f%-I|dcm z=;F_#Y^6YZjRif>x_kjhmX*qaL|6@BDZLMF+yK#t(Afi;OqgU27Y_xRP@3w<2(wvg z|HjEM*?hmAGkdK=r+-D+V&HTm0CHkdaT|w4o6!NmsyLh>MIEx4t`e=nY2@j)YVp~5 z2*esW7wV*(|2|)F7gA11w*!8in1 z|FVQ>hYPJh-l-uE?dy3C{>ZL+G?EewIgyu8m`hkgE3bjDw_TEUQUi@>@p$aX1RaN? z_h8~QEoRAGaATEiwbZUUw(!_Nr#h8`PrWb>NcmQOVniJOZ*gmH|5x0!T?A(fDivZs zKrU(k!^0S5Ep<|P8ph3S@22)fZ4mW(QEK!hPB7adoo4$b(SI*={A~nhKLqFhcfNb5 zm-)*S|E^skc|)ge4LpjO8VGc7_#LG5f!GugbMLokQjmKfDtcrLQq}jy&#Z|77+^KB zW&(sT%`~TA6mdudr~!I+7}nU`5O)ehu@gHTUZk*s%C_C;_c*Qv>oo|c)eXYPUN{r5 z;CuKpr*~z>y?4+v2yTdOblEWci!;VyQ@hZXxVkfU)kWp9pQhooG36qlPpec=77)~8 zlq$z<^!n1QdUml>gt31^1H<5O^9Ja@t87^xs$`sZHHh{BSCC1#&)y~nk0NQ%6ZcX} zw!lq+Hi8YavmOwPTpC-){)4?1_2e}w<=PR}AZB-7wMT7gu}4YGE2_8!>O|mW0%#l7 z4rF0p?!FyaG*qf1-AR`>hZBH(!U$6M)oq-k;_ur+P@fVPYasM@ioVhvVRx`);~vNM zft8Pc!r%(sedlD>apD7kl`Ejyw-=yQ&G+x2r|2#of2d4TkTZPX0R`!phCY1kcPCcD z&^AXdmJSK?pcq>+0hU2seWR!O(f(941T!Y8w_D>%2xZ+z!x6QC89e!15l}gc<@mY? z!p|7lyxuSq!(U~Jk8w`9Jm2q!w{M2&JQ-4vPt)I?snCl33-?H^{KsjVa_%Qc}|_WO^OLBi?=4-hR$kB~m(mMJb5vr;B39dtKM*)^-18 z4^@Q;sMLL6##ZCrH{pcF8^%tshXPSF6({)}wM!RYEnOx8ayU+<#y}UvIfO9u1_ILn zHc7YwvLfQ~FgB%ds1xczHvCai|LPtUae&^?zW332fb6zo3b1EwqHRx$R{0OXZY>~t zsV?iZ0v?t*wVhm_Mp(7UYV>u$#^Wjc`1?gC$O8#vke_!%c6N-v50BqrWKFKpCHig` z-2)Jk_S_$yrg7SyevcIpbPd(q`R7ZHi?adGZ&>dFNzEbTEG9dQ0|&jnqEBu65ZTE0 zBYl-92XUgGpO@}P)1sc%E(wbPkAWIa8yjDKEgc8yTR_vj*^hICyqr3b569A!pl1{8 zXC6SDYWeJ*Sp+MdLuVUIaAqQ~yf=))Kv@~PKa9a2>?#T;S1MWxf26YS_E?~!`cHYI zEsq;2i;i7iC{qC|#UwW^?d67w(EzszL3x^B7G)oa6W9)>pTo&+zws7VF^6&R-IMl2 zEqI%G>oD;wCSv;Z34Oo{%0_vbP>IgSK529HB9f>X_*sfEmb@d*cLPs=R$JKE@miqEFVAr%^Bv%mD*_QU%f~eN%jp3riTD5Sip!4n_E@lMFKGp zMi;?T)#tluP)=+Hxq0w$!nNxqup4o`3a2Q6@3PIt$I7TUSs98Ef0-(5{w+;wBzWmD zRxp}mIH0IPD;`8FW=J6{>s3LhlF()j|Iqho}a+e>Q;lH$d$b!mzw) zcOiT8cco3#dIAMW_2~=fE)>8|u1B8`FJR z^cGw`c(a=lrJ3c3F(Mt9KkQ)~o;u4)S5j0`N%Gdp!Oawk@uadq0f)D_*?*s7ccjXN zq*@v`R;o{!U@kMb4!aY+N9-lJf>mA8r zxH6nv`Q~WQ-T`}Y6-K`&ZPdVMNNBXnxe#{az7gLw+%R*YX+WL+CaUg1YS9WG7*1F@fw}v4y;c9u(7ndyYtoWT z^z(vK58cDND=1_+fwz_Hok>Uyg&8ZZ60H@tS-m~5ut7&AsjOF<^rc7M^A_J}b()H1 zuA#3TgH5o1Wnulb-UgjyUfE~G0{{k(uoU6ZJ|(azT*z>hCC9ak*jJ|slmqR_D>5bx zoNmK#?LuiZrjK&+>?wO76t6r@xf!lh`dGi=`NoxNTI|a)V;hAbx!~>KpbysJr$_R< zuTW25R$SGVSFpOQ6YG-@xBLVCdi)s_DP$7N6|540@_XlnbpT`$9(qx|UvmOL`x81g z%z(m%)UQ!!r{VQJqy7plhH1j1^DRI3D}P8b`nj1V4v{?2CNl3uP-( zqNpR$g2RHVq_3%)#t(Ca1ctMh`-T0adR+I|(xg-NIoeBvM-zGW1Js*~Ck zfHZ{p^K7?|Pnckv`^(i5v87;xw*R#ak0~@6CYNm-;X`&Ey}<-blpPSz_%_l$!H@;h zqGfDL=JWpfc*CFRGf=0^IKC#g`+R>BH34NX;@S6m!Hrl}aPrcehSul<9ZA&*8U6E?UOjZzE=19}`i73O)Rxjr%*`w7@x=y7-H}ANR)Y zh;uPO*<^1+n=WNctIgn%14v00uOb+pQBn(`ic1W}p);@;5!+_7hnnN7LVgcjn$v4D z6yhr+Q~|Qqen|nc(eX0YYrP<>6f;!!=-o@hGYm6`K+c4n76Qdkw7es|S7pP$2wL9y z$M$ZeUw8rtav&I*D}TI>9l5duCVv2uQUhNs8;h$Lgs8(NwYMsbf4eL_Emr&njaf^% zL_n)lDZ|X>^!W?$=BiU!qBWIDEK0CIh$r{UG)~fB9QAv88-i zAr&ebQ{;n$^!oB963z;la7zJHzy?_a(C+dn=gBgJJ4pZflgT^$R1ijh1S>lKv2 zkOVmgxFYao;u&@TxCF4M1TRvbi}kKuU3P`;a(ZkLcM1qwq0QSip3|=}w-QKhs8^_E z@VY1N^f9FH=gEbwS)1ijw(a5ID*K>K6=sjjP^QLU6iPE4VN&X8O@6F#9jnn`j!|^V z`aWvUlV{gU-EK$b8mkCF+>5V1g*Sk|qkuSt)0-i(&4PPq4(IaOZcL7UW?cnJZ9gEQ zuGSF}S8t_|WsGiLDP5;tPFaMV;P}=eT@tr@IZ{JR4$>lIHeqMft|nJz>$Ccc zE%oBsMw^x~gs0A|iitRHs&?W`Ukrx=9qIkEDsFZ+bWR8cn- zH)yv4x83*~P*oPi%k{EjHh5_B)T$1T1P54KVFr&X4tqYx;hAM=O!P1`HMx=)*lsc|Uyhug%>s zc~IW8N;+@tmsa{bdGi6MvWV*2FUxhBYM`#G*FoO>%@ zDetldH%ErA{x=H{NAWV%9r1MQCkWgK0sx!ZAK9=U60!D%{z|ZiK7lN)4Zj_ zgB$<6kh3FFs$iZoB(K`5zv;fY!bJ!B&Lp_I>?zVg=5)0bL`_OY*=p`KhV>@uR`fEr zF+t8^elvc+s31_;#YewWzBj75f?`?+T& zqt17i$ad?PWwsi_mitb1Cug^^L{^em0#*Q^x!aUPNvJ5zdtxUx;s?)Y!D9almQWMN5LGd4I^nA#8A?bkBK&j!qnTgr3ciNH(w!Ed%X08B#GW8DyDIY zGs<0@r$hCiPsOalKA9wbr|Dw?42o8Iwg_aWohoLEOdWRsOgmu`+4u(mLf4&Bx z{8u>y%oQeye=~lQ0v~4%*0hx3u!=!BD=j2xM%s!}1<;_w`RW;CU=P`4o{B{p)d@j| z!V$m)W>5a4{*N(Z=@2EC&32i=k^)pf?I0z7LPX2HF|+pexm6B_PGUdX;zpVVKeC)p zNS2#$3D^p3{2ke|M=fJ3D3=4Bx2qcZ?1@ENC1o%+vAoWo>6%X~8khGV{~%IS>h~cy zJY#i8gaVVIGv-M@qlzbJS2hT0lFxhC8?5-zQpvnl7%m2_d$>m1i%DL12s1MmvY*kK zi&pSB?bL9Kx=?Z5h+5(X$WpObc5br~i6L`DY5Vyo-Dr~CfCPqK_E(|y%;}cX=o{Hf z>Y*;ghv;jAol>X11=*dEf=-8BchkoJA_GI@;D&* zlDsFGoae`pXPN(oivgW$3gi|?WhjLiN-n<_I|urFod)vo*YY_uH5AOv`q;AKM=*8~ zyZmxO)#?qCt&1poca^G0ys-8n7(jZk>Yp(B{_yuzgnzciDg`t+eZw&jE<<9X@(28` ze=hF@97)Qr_AQ6$>VF|#`lY1F(>srm;T$tWXT?0XPqb5j9sui8g<7r9Ymo(sk&-|-?Hj84M!=#bd>lJ?TOy3?v7>*82 zbs-ThMIfKbu}HO#3o42!`T<}l(W>*9q7{H`Obue;)~65_mHVHN_`UbJ~CTw(abrJEhd zxdH%VBdGkmWNImDU)dB?>@{c*!<$8`98K!)TpGK5ZhynX1pJWP{39RAZ^_2@;Yo3f z0eJ!}UXK^p`apgXS%Y~|nq7i|^J^kvl5U^y)6J4tijk1FmgZ8=@MluXyA1~6^$Nz} z;YUph!FMl2GjM(=kGFq_T~4J$9yq1l+~;lsY#)Q@NFlb~SM?2*yy88!F#ILLG?*yf zJ9v{X_4+q^yLyFSFPohbdQXiKNp|2W{0w)#u^)W%CCwK~8~K%~^I?m9*d7)@oXO5G zCs!IP5@dqd`Gf~3j7?F+-|+(I!joepi5}h>;+?cEk?O`fC zX3HGoNp7ajGt)-LY-{M@1BpP)2S1$=HSHs4maly1aoFT%o>6JD-i&LO?UU-a(w=eU z85%Fge`-_9+o{M;?kE`ikP+Ky`?txNeJ1xqSf`qt+TYPzaSe0mvXO8U;&BOr=2T|L z0yqQ>{Ib(5$vLl%jR^9t{J7Jocwu)b1VyD;|PG$gl4@}VeKRX&5 z(MD6J!o_I*rxeMW$3a7uh~fYll@ASibU7&CMl>0lfp;n>5{>vL=Nu*PMKe(H7sk3Y zrRMv!$x^0Dz>R%^C}s^9qh^$ItFcADh~+GwYn`5+5+(*wE=Q6~bn4~k)HD9H2NL1^ z;KyF@R~oA>y{XgCrR{DfZqwi8=J<~~Y(0$p|fJ!gKKy`M}!b~-nu-6>@+rB@hItKmr@ZiCTN zNEx!R@;`mSOk;62si!)6yQgNko5)=G3Fc!i1y;EVi9M3Ow1zGTeFHiou)hWg3uT>? zVAQG*%xUp24Xu`~%w)=)(5J^7y?ZkWH{E2_hb`Vk=gzPYQ-@PLC6=kHB!EfHl76>!?0rK#1Ds$1)>BC>Qo(1i9@eqivD$7n zFe}=jb{vh6lQMsXslH9D*mTTb`q(#W5HWXB>Q$XG6sU} zLze?SwRC||*Q%m+;X^9$IJBb|st4)tBTO&Tt0S;ikbi3iyPH& zs=41gj@d_7<#AI~X%XsWbrjwg_qWz)?!a$X#OELe@U}o*PEUF*`&uM)s|?d$lQ+Vg zaN$MEM2+qsBi=Y1Ex$t3Uz`7e!BW5Fa{s|zu-MM$5}i-ri14I68VIE>K7j~0=eyv7 zix@(#p8%s5leD&;%^HaD%&7z*JwiH->j(?s&OO%Ug%z!YG-Sk5J+N#ze?aI2JE<_) zBhtprq{`n)Obh%2>8UxqtG_~f5qI2oV3-1X0!#g_e7@ELg7K&5Oxqus5<|=g@V5#f z*~xBw7z5=`X#AG}%7OAb^N^q1w+|g(ZZ6xuaJ3xU%MR2coI~0u$D4S0n5BpE6y~fv zHq?A7c?{}>3wpo%qirI{7`z;Nn~7LEWYU>w3%LkrybQ@BLMGm|bPr{WhusLC?+IbM z;rukgR|Er|5tuJj%j;Xgoqoir-xlk%jgphP6Cy%JTzeCONXxGW(w$taB3p*AFn!_z z`s3P;GT2~$oCb)=ueaTX7ITL$0sZlyxT?{iv)F*iR$U8j0j{>$teXesH`fl5)@6^sQZ1$dSVz)?qp2rg2ASr$UOrzV^*CS`(iDSx!M}xx>sPCB6-mL9ezwvW3r(C>o3HlKw3w>nw3Q`jffJo8ERNU zY~HKLu9YnR81ldpMg9Ykg|`K+SRRa;M@!>YUOYf`vicTX8mM8?CU|dS&M`%U&i&4F zhpILI+Ji3$7}Ee8uf(**@gL!26cpIt?dW6<|`#a1y^~n=5%$f^QBJ61qQW4e_=7H4o z=x9yN&}4%SB!0E=q!xy8BFfO1ZQ(_BS=BEfG#x`vKDn=5#?@@|vH`s)r6nKjgY1rY zUjXtTY*GgV!`MP#dowy#mQt~9{sdk}vTTPxM!F^WKTp$Kji6YkT7LLD1FsvQDkgEQ zwiTCS(l1NWt z|LK~q*$;$#Bf7(z4>-FXqomtAmL*_bNL@AkZCxiKKq9=&te?Kpu#rrmKzIjVTGKJ<9wX@L=4f2}Du;!e(RdDk{JjY9Bw}MBy;gN8U&myby*Bun)`w zao+f+wcKf<*+p623OQ%F)l^1Pd3oh9!Z+zgF4|iGOe^7y2Spd+E3C-yvL8&`V4BM_ z4+YTUK=obLL~9sWRb{5@xEHLR!)GiUmTw8CQW-zA!{CB@W}E}AdRa${+qdF@*mCLX zhV_^4kh%+Xd~~ADJeL_S7}uD2D7;ZKCF~#)FQv63A6=o=RG>Q;aScyb-m>rDIu&%f z_HHwFI$4J~ZpysO#ujWS^eA~ePh%UuUkl8q}E9*S0^?zCXjo4$y~4@z{Ad z>-pqbGx*2LCHXB)lzN>GE`=e1^nw0Gu;R)2%nvv~8XEm2DYlK9fLIu|>{(2_i@g&D zKXPht;M?x85%ExmWfzC#za1U(Jr@G>jy4FhBD)T7oSBAf2k=Jfden_#@B;WFofUzN zrZY57D*4Q?wBb^ZHzqNZ_CQ8|n(i#g*?}`vpvtL~&Qq*oMrXxy9_~dVtX0ihKBYA& zwUx#2a6#pJ=msFGYRL=HYo=%z3DuBY_!to<7BnH^hKVL2St`>`Nb+&gWWTO?vFhY_^S)XK1nHNfs6jH!rKQB@r8+@SQ^uD%f-t9S-@V#DjVYlPX519OLI z#kXb3#SB=7(Mpv{%u2O#*q80R3^v3Aac7=Tn|oWH+WCrkoYX%JND6Gr4GbN^-Yjq$ zZT$bwR%?#^rHsz^P$!)4mYte^I3sIHlxc#)L;<#1PsIjus7jSkkSRirf_g7MO>|Xp zq>mA&opb4hUc5oTlXIA!LC>-{l;5GXAn~idP)y7@Y3BIG^bSvtX*xA`NETq(nVET$ zKa^|eX>(Cc+H(Xo=~cz~>M-2rMR5#Ke|)-291s-~)2?BIN3Q77DInyelE70iAZI6i z&G{ee`RyY^_dmoq6ZrP&JYzKKm;Ek0{hOy1ZQGJ1Nk_aaM&-o3q0n=>^1c<3oUIgI zqyKSp_h@wEq0#;&qM;$R&jw|rC?K`zkim^RVNENdDumiB6iSF+ZKEkDik%GT=QW$M zQSyzJ5G;e6+%z}~R-690Iy}1k&*z26PhpOVG8zS5>11{6Xq6lB0+-@*eM0#XAyo_q za3lrGq=v4FZ!?0RhQ6XU!nO&#%ZBmIy)|3xK9jWIuSMWir}19v6xC;v{Pn*MjirFN zA+J#rgvXBK3M!_!chjpov$p*s30*%7?^H{kbP38q z2;sbasrG~oGlHp}E`#}h^U^Q=#R;8 z5#PO=4Wa@LOp0Y+N|0ZSe7XUN_CelCee@}?_9qkc z8%j*aGyGU?*&+!7=fA#hbg7TqJ`ea9^EdF+ZX%(Y6yI8f}2ds{o0x zIWKEVoP*8Sw;G5@bsGnBPnP>(SfUTyJ4OaYAnh$)NNsUeTY_0ICHn7`=?|%Jx_y^+cBSgiy zU5Cn3b9g%?M<-aOuZgFuH!9{EO14kfs@vAVL+qNTNBQ6f3aRCyK#6Cae(K;q(n4UO zwPAc})r;@({XzLluE*}m`HQ*h#*e}3EiI$#tQ(I63WH%UjQt~h`rO}B#J@ZOQ}RX1 zS1W#Yqt;wdkNCe&?5#uc3Welz;GejwyllaQ(m9rw_^we*=sH=Si9u9dyn7Sy^V+vx8DeN^}Qx2*{S)VEr|Z- zdCVpB7Hp<$k{knw1AiDsPbIZxxy*S#LqRhef@hUS=&Nq&yeiR(>4wzqpRtFS5-Vh9 zCtQ%QaCs@RdqXU}kVM(6a26uggU%2=q?$xyjATdD%R=5N;q&}HAMZ+XDa_R5EvZem z9GzzBtr|bhkx=+oKX2=srmhQ~g~CgB{sv8sw)S|Ft3LR;j^cLXaxA|J)0$cPG;L$I&Qq>B z$aE9JLr+Pe?ZQF^tCm$PdJ$dq-k}aQ^B(TDqnhFFdPj-UCywLDSbn2!j&fVVma#EC zu`}RBqMBQ6+8^XeTPe2nLxi46Eat$iyN2ICI-(3FX+L(!e$*Z7L@&DDjF0RP~`z^3=GU?YUXyZ>%bt9(CdqUi@ za_Dbl5Fvr>v$6|knxG7xFDV29yt}n`T$E=LW>q86hzYOAl43>s?)wM@i0mE;a=Grw zZ$28a-HkD4DlH6&m~8lxe@$z1*vx6UQ%SQWE2~*FW4%ni`5HtK^*7`8W#BYnYr#cW^cbI3-IGBz=Nw}sS);X>h&Qc?pGIJgD{aqSSKk74V$>dhUn zkCcO7jj*tBIax z{7TwOOw-MOf%|fAWUm^1C3%-)nj7&1n#AlxO2=Zw80zG0;aj;B66hde)vNezq@ME! z_J(g~Wa=hk5$R$`zJ9AWL%T)0QDs;feXqpHDpHWAb4#055ORWz@p1M9Rrl>YL$BH}t1 z%Ax$^*?xD!_MXS&kKDajV%3;czPabN>5pb2F)?i-aK8_mURPxef1NyE@}oURnpZ{o zBz0eqO?3UhqKT*BqXlh>XwGq#u##%3uJlw;Ezz78$`8-o6MU%2j!r41z?FB60)W3H zhFa*D^NT8s6HKXGauV;vp%buXOP2~b58~6ve%Kmz6!|hh*JrdzweqekWYB~L?1b|@4V#O5qL|-kW)CGGuE@Ny&2qV!On+TX4q{KzY#)B zHt2g^hsdLmhjHwRWEi~OOO_q|%^&$YKO+zFJ2~D8j5co{W-n;l9sHZbxi8bHkQK(m z8$Vm_wT%-iEm&}zZsmF-?CvC(RWRSsR1sPu|0SIh4gM$V$1pEGBB1+ zI-%N@cKD;b-Qbdl;S4x$2;w!nygub>CJ^s0W9wc%mlY+v-{67Q15x=~e9!#g3)eyP zRz|bEfWF z50^*BYnna!xB=A#U-HgH)0xR^7$sJQO1D0vTu#|~&xSg5U`WArGAUhw=-6ynwpPZ) zcE(C7RHAV3(k*j173UW?=(%s;l~8^5%b`!~89EPq4P|CcG_EzAhe;>uxkRVU@RUM$ zjxoe8*!8cJx?72NPwYch+gPlpyh7aH*ODFTP+W9Yoy@c~9WVd393FL%IR%xMnm&EJ z*1?d2OHvC-NGMWppw$D(K5+h~Q>RN<=Sa1q>GpZF~8b^A!iF7%b*w4jmV35KWXw_ba-N z_-A)AG`b>-%DGRp>2jGF7>z`egX#3_Q0Y=s?aasv*6gOW5{2m0#)(#3vs9*6R*I@J zY*=`9YKu0V5!xlkkHhKqCNylJbh|TyAwvn6)I>JWnaG)fT)eZ#5~}RyC?j4*WvX2t z3%{vMHmIdUPQ>E7eZ}OAg0-eGSzsxU(EEgkGI#{`y_YUry&n{Fch9C;#$J1ZW1nhw z6#O|Ot_Yz!WQ!E>=YV_Jv>t=A6S6ce*OW0?t5NwB?mbrOfhY zA9&EguL3mxiOHaKMdLxUeM*Xz+@p9w+(#hh^4&VKs8G}>84ls+l7P*NbCN0dnZ-&? z#bm5Ctq4L3u7s|D!>Gxk+nR;4q?(0e_SJK1mKMG%@?2}W=`l_ z%1<_sp5(9$9U-SeK2vvRfEsNUBdRZ|NJ$iAH16?8B^MxgAhNP=c>Y0Yy$073o5oZV zKcwUS$DeDGzpkM4OAZpOqrFMsI1bzGzhe-(ut$d~hw19;zoN*_1Fr!>hfM(3n{~^l z`Tkr!0eP~@8hGY`9_=lyCXK>HzXn7kMpN$01R9b^&5n)#n+2#lA47$3Z?;Sn?4HoA zVYHMv<;P!~?f`k*$7J{(9V}_T{+-%v zxw8AJ-|k|53@7sbH@}0a^W7Ch57GuI);kf*m%CWY$G(G9GoWoKn`2L^#Ak$PM`pk_ zMkY;8Q`l_FSwa0mYkt1`B^4T4JL23~>ViXl>Hn|^1kYa0zmYo2vfX_75cAY`V56&DFR7VyU?JJC@*d)fx+Aw0aytEnYOl0Va2jvH^y_ZpG)KRb{`gD810Y4&bcADFWzvmJKKg26SYeQ!6iwBp(`(u}E55kG< zf;R=z5&S%QUE~ug)haIOjDCRCNvKl z{$76B7ISvoe-2py6M+0M*YYR!og(5W5%n#ZAzcDk&3~s=GFN= zf9ldyGS}3-DRovz+B!AyxCj+2Y9vwb)+P0ch*)U53736IMR~o`UB!YvJK=@k00Pz; zLo?#u$sv{;W5PtKLJO5}o7O2lC5gXwREsGO&_JoDHB9ebA*JwVyNYHuo#`Wo10;V$ z`V-u6uSc$ty#wJTa%m_t$pqN73wpPIqi&duL_JRJ9hOz~9TyXl#-@H3Nw2DY!dnHe5ToMw=<{GsD1)9@@=T?BEHGIW4n}JhH>-N zfPpt6C`IP!(VyZE^UnjSqx`5@l4$nmNeV~Mi(Ui;yCVS|IX~_Q1pburir&s3pO_m- z6M7ER2zxxm8ge|n%|1Va6(=u?GxENbT$A~bGi|)(U?St!LVG%zS0rdy&bR)G>{`KN z<;F79ti{yvp$4kv!~R-`)D2W`C7uAbtfQwEuD~)&etqp!%<1WA=HA|3Po_vq6)S{Jz2wGz6y`m8r$F@{0!Z{_i zQzxCaj?A0(CuJUNCK(b!HKi$|*;U*$SCBYqa^B~-S(4gF(oJzKy!*ja;YGx75|c zcAZ?gt2P2l$!~b@VZV}9|V(>Cgv{Vf8r&~I8 zan_`H(K-n!*O5u|ZPyx|=ZSg=Tv!u`iJuGsKOmKTxptDrpuT4q9zs2&r+0MI1f6sv zF;h2lnF8m%5V-BzWfk-HGy(4)H+ji=Q0iA>NA#j;HT+iyrhh(tVbq-BX*B$v#gmYf zgmilb7ml#r>i9rROl)Y-Y@_~NG>saq4Q-05@=KW$&Y0CFHM+4BUk~jIue?Vh?rl|# zN-Zg*3n`{T_olB2RUQhdt>QD*WN2+Ef^D)x(({u}!b!v?lWv1h1C*<~Y8~bg#G-{C zLnCNt352+cjT|+&%vHJkJQH)+=RL^S(EMzYX|yvlK#A87?DK?;)z7?&kj)ZQ+bgEC zz2h{YH286c)^y{uSZm5q1HsQc6%<*<7AzykaE(|f9Jz@baL1qqq*=1huzAYEBr(%S zp(XJk0*2Q5zit=WjG8qsZ5glYaXedI?cEwXkY0bDjuL-Hm8)v{2VOltQQ{lED?yr^ zV*fK43oi0{a=Wl2hdr3olR1}iucomaGR!O_nC|d>!pS!3 zdPzBuV}wv#cFw(AyV+*ZPqrtM%@|Trvh;x#CLEX8?6?jCv_{8Y71pZg(_B*Pw|iVh z@2KrI-Gxym`jXJ>xz-TOas{p{03lIzL-=8NNe*w9(AEXe$+2oIoD5(XzH{h*>>kuy zW^PG??a(`tW6FBPxmE@y3qXwrs}zOv-ok=d)NO3Ml5JoA{4DkS zl+9c3a{FV<(va6_b+so@Bm$MV;_p&xxBLCUhJ(9%GXo&X0owZ602}XPi>+3i5kS-M9I_br_F^6<=ZFVc-t* zyFk|;@PE0rFjQIBD=?O)Cb1@y&QcFBhAz}GguZ=6QS=m4F^D8w8-m0Yn*+7_+@CfI z2iBC$L-u{86o%~#yBTVZu^TX_vv_aQ!qC;4>?!NlJNTVLSO$x96;+V&5#f5CW&b39 zE3nP3(V}=)3ZDlODd+)xD9#PR06G^Y_Y>iCjn3%QE*+5`KqsS#mXT^6_FzLj(TB`S zB8LS!&7$`>y1Z^y&;vdI=f)o#)g&!5`8W>K(;3tEcXayP2X6!Wbf>)3uQLa2>2GXs z&;88UQ3h_j+Lco6)n!YPwQnbXvLWG8pEVzE>B)Nj{W58ldONo4;av!9B4aEF;2nW^ z;CZl9Ik6gXBaPB5)n=M>SKd}m;^K_Tn0WV$jsolZ!)kDzOuEp83+rH|@zen+N|S~C z?Tc`KPsui|h#K=MnP?j~>geN=WETccH{?jjetOVRn_jDwNnhU~dX}l@$>w~W?s6wc z9^;ths~P2^$xM%AM`wT67IOTXoBfY3Ok!{SXC^1M)T3?~qR-Bw^Z{4AWYhUx8KEDu z1zu$L3RH8W<;iDZK!fZP%xH?UX9E^Zky-_3);BXr9!T)KH-K$-GOm1MVBxVuQ}7|b8?g)+1RqlWg&_LfcSW#F?so$+WS zr%(QXiukU>RcQn6%<#x=hmS|u$ zbG=Ge_)R2}+e14YWkZxk&>r5U>sP&$kYbZ!8|LG{IIzHyjm3=pfEUV6Q-c{tj$xiK zL`UnhedIOcrEsJiLxeW#`n8Z*Hap1bgEV8VM&5U#>Q$oZ)RJcTCY1Z`&!Rgjm=bNl zy=X^U{Bg2J>DJ{|WF`2Vlbqt4+GV8}IcNI44v{}(VFhkFb$+aRlgE)SE-rpZrupNMDt*^#Q6AZhCX;F-$UeAtLBIUIK}A;iX^51Sa|=ZqK7+i9*I) zAk2GYpYCfgs~eG^*R?Hx8je{J&(i2g$E=XfzW9&X?C(szypXt$lx^`QHZJ2URuldr zuXN8%Z6jGBu?$H#4a`j?xffRS^$~;=;m87&7c@=z?;oO_@~+M#i2-tl0Psy`uu#OGMWuUJ&XdE5VC_bBk(w!>q0 zQ^G#$C@uo#J!{L6;zJKwsEfrEt;ha9=i$+nQ<&K)l0w442Z0)Qep~A`JG!A-K`|HG zSD&?p`ZNJ-FdYS6j&9-h5d7^d;2r)w7T8IA$=tfpzfx~H{U^A$ZogFI)p}$snYPCR z_)iz9?npL@_G+-q#jB_HRI|9I@eK#sbg$(HHJ6wz29(aPeyindT@7jmucNdWy$oea zw%F%QxKGKn?6GUey$CspDs?&3+Y=v~yi;2~>B#mX;yo6MA$b!DI}~uojj(rFbehU; zFTY)p90M`gfp8SUvdT(AH1x~yFO1$-zT3WhJcMn~Z~WJ8z2zcXvJK+vMqat3q#blk z%D(3kbJNl9`pC4L(<8Ma@yUCW+&(|PL-Iq+Az@yM;Q3nLksYP}j{;JJrTEh3pRtMH zx_P_O9dl~_U`-Xe9*M=TA7r^#;{)do$(0EgG%=0s{(kwnr&TY@Gja2?orU#tFu6h6 zji#i?W0UM^Aj*YF@ZE0r^QC|#x=ir0nq zOm}9yMy0U+8N(6akW0&+i-+pc64ExSi`JUCKkSt~s603!yJ0eQ*C;J);)v?z{T%vZ zD<>2N4{5RyVt-SDBbe!$zYb+3zMgV%Y#wk>!~q9oV)Ax`3uao-Qq3p*YOu2n#e;jc zQU1>ptTOA$ZtO)(vSz60Pc@$r;h#3s0dPNt1pHepBmV5f95KCq{_+#cs|D?02=@}H zFCf|q_2%d6z})?KETd%sX7au>lWNe|AiMa@nYP3|Q)G>#Bh+`Q8_a@sCqpnhbK2L= zpS-Er1b_%mjShU^D3J3X)fD*#(lntBK{Sn8edH2YsnxPUr{6+;_Wa?5 zjU9b!qw{PD$-7W^}Cl+BWWzlfo$3E_lEq z2^KuSI{>9j(9vQXrRq}663cT98&^rP;}lNU{WgVBC3J!YC_$KnE=Pd=>N$Hm^x6w`Xn$!Pu6^fGS|Z#O+mf7!(IJhx_FI z4P2+JtBKPas}T&nCArK7t*^yY$b9XLM>IkqTZL%Wlsalf9+P0!6oP7kZ$HkP@3o$K zU{%Ar<&nCifO8OiQz>j`kNflrPz`vR#PeJQWeu~~n?$wN1z_inDY9JsF&|nXQQ_ns zG-AC1PX@@d`T|l1#xcu_aQ`A?8IBz_!)raJRX?+JKDTw-VgI6U!;t`94;lAa6ayam zcNEZIlg3;m(<~ceIGgbmemQ}o@L@TjIngkk(GJ4$uxIJ4*t`sednOtgFTB1WoFj^X z0c!~l|0m8gB-QPzEBe2W7_{kl^6@%o38BrycchYKLl4YM2(&m)GbWVVUW@U(<&Za3 zPmniEPp~yOr1Ib?hFqB2+f~j;OIJWN+~9!r;bc6~-B)YHVYT_Bfs5ZW67-2*cz=7nF2FG%^=;~#GsPii?LWBsCEug$ab zxZiaxjiJgOa1l$2r}oJ|(^AYx$0!f5C*9g`Q2l==E&e~A-ZLET?)x6rdnbB}F1pcc zB5JgV65T}ao#-_Q!ytMeLiA2BI>G2f5M3}z^xi^vKJM@T_q_6ETo-4~S$plZ*4Zbk z5REC;q44=Y()U)oy!r({qjlacwSU58CX~N;@b{8EE|-$G3TLr635_W*-{oaj{+fKV zG&J;*Q$qO7;S-=O_w#bgMSQK-EB-kuJmIWlxtJN9Ne$BO{<@*XI~g+x{;?XzVCyWb z9jQH8%1ijt=ruX@ir%cFr@^Qv!1ow_M;LW$fNXtYbUbdowQ7mytSl2&RZfJu1~%>O zC6#rl6-lXya+1PE3c`y|P^MaP1^IUxbXY>;i}||Wla6hbULCYEVkuzEo%E)=9DaY; zTvNst4?qTE9kG-*_~(PPBs}rz{%q2&eq&kc?$_0?IN`Y0O~0;ruKX+-U*t`kq%BGA z@8J6XNh#KVRVJXcjtLoFdTMK&L-AtQzeCVUUv+^B$26d`rB5pCDQizv^~?r+5UwFn zJB!s&t5TCcfbmbylN4pG)|*7%FC<_CZO2Rfs_HNC`Vqe|?w`KZ7-MZVx_zFG4_3;h z+~~6fi@R_4s(h;y-E+V-F zJcAy40dGNKc(`iPtrpEp^iUcm1CpyGaTN{cXSDDtohE~fVWUwVoxR$Isukd0kzZTu zSKS*Q`$skw72VyOj{W`K+JASOPmxE{K*}hs#5R*nziQPJmcEu-Cn$b(iPhY2C`=(D z_|vFkt_hvVLZ<|i%;LLYSAmwi5c0veZ+L(rm>~9&xL|``u44^?SMFO!Nu9KP(Zstwin@ zA^~;y<8yRR1nl-#srrKHyhn%=M#y{g_bePh0%*qe0O5yv!h-NJa|pS~mEJ!HzhnHT z*5mOr5@=)#So?jtWwzl4usuOJ+hZe$UUjsoe$^$8xeuaZrC|#CHYRpnD9LIZ>D%~~ zunk*O)N`y^kS`nQIL$ZQs5*XkOHIx`s5qM+d~*?PMt!j|x7kP6`(k?echD`r)6*o= zJh8gz`l@Hz&7hb3yHny51W+2=c6>OURXwWpm-2Y4>2lOU)Jd>1D-4S`u-)#;{R!ks z+(Sdr^Pl8Fh;gfV;qZWL4>xHxL=pP2zX}t6#YC59p(uVPkQERn^d1sa{jkyx|@<%BIlCMFQ zUm1tQm6M|vlwQ^OiQO+rG)RoUvgV~6N9=J8oc_c6C`X7bJ1m@btvA9DVH!Th2N|32 z3H-7Sbs+7`pH=YAa|=_cQxucRi|-q;&fV;61?~#%JN+$&#^1qZ%MEH z(lwEn{;CezbbNPF_D6C`YS4zlMV?bi;SCHhmdK(9B=g?p-g+;YlnDJ&^9O{@6`lAJ zdajo#(pC{rTxxO+jWmyr9=1M=9tqHE{?@qxpTb^6wHPAY6)_36lVTb-GIrMA*!14< z;xBJ)z+9w{y@k9kz&Kl13QQe_V?9$wlsK;7ll;Q)SkD5iHJ&iFZVD;t^g*WQBkYvzQ%5! zZpD^ASr9+7bsx~~Xlc4#y5w$&jXfS(_m}?123Tl?&!bT3=OSIWfAqJ4@uF=~dCX4s z0iGQq-w*My`!D4Nv#LQqc$0o7*+?POj{Fy(QDc4!k}w7bpKWc|AJYW{q0#WSli(Uz zYT|9r%1|IVGyFVVfCRhU!Gb=q43< zk2sE?N>^2iRY%d@SaSxCI5J#dLbQxeFEk1_Q~EgSDldn(?eS3?09(+VcI{nHH(#Ig z8$;&;C)8cc+wg6|&V*8NmEix^K{UAVkWk}1a(5(6aT1?IQ{1rPZl*d~NIt$tv}%M! z!ZmS$m0Z$!kv)NnVEC8uM>0q^A<}Bu;&QatDO3nbf`?5)=A10$<81>VJX4z@A6pGq zoimPxt2(F5vCOd;!&MCgeR*e#p>&wy!+xQ>0}SM`V5x9Ra^Zm-RNnhqn;T-$@fd%U zYcyq{b9#!TRZmmG>AVyFy2yF&ga&(|LUU!=<5F-Gs42>>|2Z=-jkD^NxX$?@eC$lsCD>)iG`#es@x1Y?UuidF1+TkzFXF-C7`5^M*k!o;qqAgXvvy zcClA7z#~d3D)lLxz!vzMt=)$yJCqHOV z9f=q|z3!DOD$;QoL~VGQr1)&W?iYU@)!*igaD`v|O%~`Q>2AMf$F9{uon7tmE(Rq6 zHD=aySgk>_?s_b(su+07-osqN?;@Ht@4m05dpeJJpIGyjTW$`gG93}^6Jh+#gS)!V z0@VlwA->^XU9RQyCO7Ea%(AaN^9ZH-^9NB_=}JDNg`hd>I)61X8oP?xLchY!+F7j! zsSA>krnn8T+*uVs;znD4u8zGjiobfgVu#q)&=_S{SJbZxdFm(39s=9jDEq>NF2?{w zRw_=;yOM5r#2m7U{F)Q`;715UqM#NoeEn?wgcJ2hi{Wb7t0KUn>s+8q~9e z^0XmTeo^FwPX!_>6K)Ik#!9bX3_Bt<&~Fl(`0R&H_Uyawr9Mtwehhe)E2Od>N!>u8 zT=M3%eg#pV9B4PVT|S9ABUy3e(38NiSZ(4!G$_^BhFf{0$xfA)(t{DG8`Btgs*Fkz_{NR#U5aZQdfw7NqM zp)4!3F&A;&KUhMjdF}Nh^V>M%aI8OSJb4)@ z*#gP3(>K?7J5&|I)9tdT9GYOctD(GyBWInZsgtvNdiu8$M_#Tt17!uXom5BM0kU41 z(0VV`KdF_?)BQvBXJ_lkud@X;df7CtY{Yl={iE`Iq@!Sg&S@qVn*EmYP??t zwS8qAP`mQ5zVXmN@k~n}D~Ld9yDO|e?K`A~VA@d_c?zj>~hw0|c> zR#&N*{j*L`O5KTruFNA@4EbO5Oun;iFrIwb=`wd>8_0MR7o^}yT1EJC1X!U74$+Wr zWRj?R*9iKFCpNn$c`eILmK*z^V29fR(x=3#5(x3)EKz3GKTBGr&aIa1Eiu$I0_Xi_ zcYr`c4_Kyj6h4yo`za%7wsoy}Rg7M2K~ko3jlSpWEkB7?EPbzR$}*3xk@$S|9G?E{ZL*U*$=yq8`p_VYp-= zxz1CaPYEngVa2*0d!secghJbOf4n7!UT*zw^!|( zeI`c8F~F%%Kz9X~>Hy{z!Z&Rd9=yzQJArNn>pm_JoYG~Gr{lv^w0$EU{lw>Mk>qcSiL6`J>4J5SvKqzk2QWYyEQ0O<9l&kkkyGSoO(&1up{nxhT%f z--JyQJ+(9w(&mghk_;OJ0F2ZRy0z@-YeR{1C~bgWm>Q4dr^ypB)R=~}y*Re`#kUS2 zp{J%M0OA8Ip`Y72PEZhTtk$3QWQM7k2lXWM4YJ9fs7co;D!q$HZ2)d<;O#a*YQ@Uo zFe8J-2np`Osk?8pJ5Vh`J$s$huDA z^DXrcFoKb$2Hk{&Faqn1Nad~I?aRRD`SQ^8aMWL+QH$yM!%X|NOTE@C{=pq) z#^@VI8mK@v1(aU?%E~D>5ualha5bc+nPGG9WnE{BcZaZz&0S_6RoFkg@`>WT1 zA;v96;-Wsa3(%H`t}NJE9@Z4|!DjY_H1)%?iG+B@O_fb^IW8Fb9HIy#og%>#`P5FT`%u@!w5^K_1XE-}L8X;Vk`^>tZ72_q0Wn1-K> z_Ibsfjh-M($-Tl7)JBC_b4On2R}qn@z5FeRBwU>}Z%;g2j}uhBUV=oZQIGO8K4zxTpl;UZ;1CfUZKE&U3t1M=b6*7cHJeh?(`<_7O%js zq?*X~FV{-wCvb7!s9)%EoJVSS;>U6+t=AQ@)PW>~&m$qqULqS%*)K=8r=)pNV>yMR z-a7#{%5j!&TB9M{9{S^e$ua~kpm~eSfon@X)4qQ|*P>wf;`bH-Y|InUAW z()N_bifGTgn1Y3rBAHZ0_>0Vh{xYrQYPJ_;UMEfo?^38}wejiYF+to{oq^numb|Y_ zJ@72QHF%{XIQ+OkwmG%tt|gtSIZw9hE6JmR1W?`Y=3y5u z9=vH3RHFrBM$LVO-v_jcA_#L>DvN$V5(OHzsg-1B^FB5S9W3unnDy7`A2l+L02VvY zchE=gZQLSv_5p<$xB7Lw8dfrUwJ=;kupi39W=q}9B!r8^3*V&wDh2khS`nU$nu{$Q z%Ab$r$j6-wI_HXeDa0Wt=#9g&6ta3BS3X#rndGG*DnvugWcQQWEzuq*BmhHt0c^}EUUfK!@rpIgzGay%yZFfM_`I+PY zh@W(fv2IQ)Xyj4hVgH6;mwaVaHcVU8r+x{Fs~Gt?66bxi7svm~h2e>F$jzUI z67q?y{>`DW2`$b;H3@wg{JNmaoW2GW$|0KxH5odWhUFIfo0au>An?F9cnmBY_)qO4 z#vtM2fUK6`76*&vuj!=Nv*dt#LAqnMt_LWy^XBBz+f-R%J_88u`@4yYL4 zY=UtSOgIM4KgU*dT#j*>U22E=IF%txm>x>t+FHxx;vo<1Lz28iBwlO;EflUa?jw}- zl;ykT?(oNpjZW)Ej%P_yb^RmfufD(Gs>ppVd|jVEo?UaKJi)AL_j!hrO%H;8aC$Kh z8gfi%^0a5OP)0O|HcKM-c zup7MDqxnn@_U_sIp_O!=b!og4x25xv-4f8Tygqu@)`O+kA-Su)<%a}<;VFuh;oYwb zfM8$XLS|Zge-q@`KrmZ1NIF$DAJu&tDoYl)F=u<+wK>mP_%yxvDP=1LT4cmE&Ble_ z-&yOB3oK3gS_MMZ$EZnlbZWN+s!fi`UEb&%&xsOtn`gWkv4FK3H5)w+27d}5!LCbP z$57?Ha2_hUj#QysphGvS#((EuZ8;QNh zCVwE1*^`;5HvdldrJ8|SIKzQY=5M!w%i*7mvuJ_Tw9^5geb~%mzZ`u|RU=+UeKqN4 zxtSm`D}DI+uNVg1I11R#yJZ7U;r;9ySe`me99Z)eEwZ|Kvcjx0kk3{x(t<35#!{0)P3h2w=( z9sPUwJ%^p;vV!`Dk0wd}qQI=+QK4SX(PpmjWtqNZth|fQ&-jWe$_?DW&f*h9J-&AP zh8@uiYb(DrmtcuG*$GeX1#aT-Z@V$iPJ(c(ieEfSli~1Slny&kdw7rCPKjX5VLG|D zhnD1>-#^f-lO1Ag4RWz#78QBxyBO$_d08pT7MR!Ov1B3lJXTq5(iiusYh__t?*Q~h z#M#lBX$WONl{|FEGg#|X5d@HLxaGTltQ#)TZaqZEkDA$R9hGAcJt@r2Y@`EBN3kUh zzh?hy!W}ri$~=+G&|upxV-DfVaCT?4i~$35`Coy4W5nQQEz@K~p;7Jco5R`DZ?6^4 zCVTe@>n2$vQIr0dhpRq$<*lwRU|JvzSS$2u6V>5s{mn=9X%WqQ!Ti)fcpAV}68L$B z10g+gmX=z+f$HN`n>IL0s#Q6ZTiBMlcs(NqZeBZB;6cD{*ctCN2Ms2RBfHHhB-NI+ z6sPg6!5w;mPW6Ih4aQ0A`sPFkzEG4wCtjeH4#%^i)wwL=&P_ZfJ|l@eCCc_NOzgg_ zWf{5jwL1yaj-_|m+7VH45>qeX+4AEUsJkS{?KQ}HHvdn)p#5r}e}Fnq(kbmgJth*V zbdacfvO%py)cAbsIXJ(?F8Ng~L!Nu>8%b9d&lHYrj}sJ17gaB*FIpA=ZB~?9G?B@^ zBL=i#u@m0c%z0z#lec6O3feRiM*R(wb_@6$GP3;*hZHBySEt+DFj?;i)_1Fl0F?r+ zt6X?J8*UO__8e6iMc+a{3){o&#{%of5}lwSt}qq>5Mhn}_z62nUmnre!j(L88=mcT zti>GXM{bq9`kUT)gl0m%eJ~5Fb&xgO@XxVH^hav^@EdB*lRJWIyX|X;=4v{ttkbq^ zww~0pep#}s{>UbC#k;rAP_wovEb{Y43zFug%!4|Xr_g%sVV@8DO zy36+7uSfH_!!AYg86J5{j+#MsJC-sjyZFd#y7Z2b_91(P=5F;t%tFN3kYW4Zv>80( zQy&X$_0I7Pa3;L=VM7hmLg1T&24)TUB)DW#-!xMSnb$lYyDMOf>Y`W5WzbmHBzN{{vn?xo*P z(qkE5eUh?E$`AK=~~@YaYj&g1%7D$*j}Sx2$mfH^8?FRkWmW z^_d#Wpn7NuYB)4}Um`0DxCKi%u3Ue{Q(vU#bKwPYVDI<)y*S1@=7BPlLH0G)-;`HW zJXq%sGltE??sKoc8Ybr4KJrW}z=UH+<^CMJLflp&%SHN@yjHNWB59f+?JsMSJNMDBD55hWw) zApI)ZaB;yE!3nLrbsNHQ?HWnjR3y@z*1oVOI1GhSj*@J z-7U!ATkA0wquJO#zog)HXaINh*M$FzvG~tXu0QPEC!SqS96(X?u2F<5KwPKBsQ4!d z2V5V|`+w*sLABmA`c-a)Gt{_*#}h#zP)w(hoZ%?QfOLfXMr1&AD4M_IGP}wrTQx%h zAj>Naf#>$V1OIfwyB%;@mgF8K+8iVU#}*!t-ij33#u#<~tS~5<#ZEhR!U3aduQRf& z0bOR>YuPz4I^iCXSEs35RF*TlY4c7@43+F>?CwEXByepzfmohlvdS z=RrFG1K@pB_g|y}znlGh2{5~i+#UgL-u}sQM6SXK@1#^fj9pwZ8DC7ll--jFH2)iC zw-a9A_W(E5`D^Upf0Wq|Sg=eXE4Wy$EsW}na0_>9o5&+h=>o}H8*9(pYa7|sd$!9} z2O_G)As|1T|N7Gsi3I{~usQlH*CQ;&&;`zR~YU!mkB zdVKtVo%3OD59Hu?6k}}mQHMp_{|!|-7iTL66zdfxyDd}+%KGZN?lWquNnxAMHFf~( zsdX$szslu;B+zo0lV+OGICJf<3TB|bim{UBGmo!O4;cBRz5o4tZzWKR1nW}{N-|0^ zd4wdjj3T*c85@aZ zyt#5z+E?q74Yfl=Mss+H+)y?}iJ61HP38XJLx@C{b?=$HGyQpQ&wk12a9S|bV?`a< zVULH~4D1982$7g8L)hwKJ?bJp(5>F?(_;0P^};=$ zrcFt@W2`^|7>SI_xUU%-a(O4B4qaF`qkd-4mpoolTWY9;*jcxeKGc_w}%V)4aUaTvR=H3cZoE4 zD?WSzcC^#XR#i3N&qt2mAUfsJySG0?QmQWICCwOVqDkbRzlcx2*ut zgbp+)N#XBiON6d!KRp0ON4mp-zX>j&?AGP3ENdf*VU3exIGWqOR+K^*zk!H|E?w)-eR9+pch8!KAAMD*ReU&cQlq2 z)tbK6_zE_-~0M}Ke3c3@L6z}``QP9+MRXC@|Qzf;uczd^X-B{BlQQe ze(DJflPh}SQpb-HZ@q!xdjm2W(<^NJd&6s%q~xF@9X~PHGFlGT6PV^Nw@an(4F@)T z>kTDrGJ&fS0}9w){}rfQBVdtkUYgpIdXY4QOa8bw;!YH=Q%6unVq==*)Xg`ZYOMdD zqJH_fjbkPG6TtlIQlM&Vb8XX#MLR@c^n;0Ia*Z`ISloC-Fgr-O?$1+AwIVn!(zZ`? zL-Kd;2-cpETqfCG+A>*R7v6N$8+{*9rY5+oZyb#_dY)#{^dIJ(~uzPtsW8_U#GP!s2f- z4+Afc2)3PANE%!6jZPnra8_(myGV0$9iJK+E0E~&O4(BUqWQ1NMADlBOYpHKgI7yU zicWEpTf$@-`AOv|MumiK;X=95dT$u)v9biSNaVS`z0_8ex$XGqYwef7Lh>iGh%RL% zFk(lT|HNI$9l}fc{!?bv>vv&&@7BYrbDy&w6N01O@0%Zvs^!H2-~(f4H*W0M1wi z`+zWn7&SC>11B^UhcND0nuwzTn*qxf+7j>C^)BCB}a~}G_YUW(ig{$O zf`C^mXFd-(=JnVLWR1?T%xPp5rygy!)Ezt1@h2IM*(I0Z=ZprBv z(TMalO5&Qa%=-e=?~m}*o_F(Ti`e_m>aYJ~yLedQH}ow0OmJLDLsWt);~AXeCIklk26Fcww4Qmzi}#JH zj>)PEoYylF5gh$buK!+jUz3am1MPtAVkV+iuL~Yn^(;On%Ue=(tLy|5)l3Iz#tYjc z6Ecg;?6#&6?JHaD3FHTNfIm1Yh|WsFN&RBM{4iSPq!TDa6YGkrzc}UO+@72i7eiU9LlSoR zagq!eh^d_XuMAgrc(0*#8C)lG7AB@BiN#6UgUK~v-I#9Z{R@>mmg@4Q-=%1zn81QY zpTY*>9Sx(znk6cIf``QXp?y+a<e=RXLT2RyJPk01o`By_%P!YtU5P-NogBFPk9 zX@g%1PW&uPSmpmU3DlCn+B^RAASBDSL0&Zzj z=9v~%Odr1AG>nTP52&dM;YtE8IsSUTUNN*r^u8z+d;C^dKd$t-3Kb_OeC#J1_{{;z z(g=DRlk9|5x7e*(^7(b?HSIvD()6K&O%uKTQ2D{E#CnfHw>C}zKGb&?pmRU{Y_BOA zZAW=AI!Lj@r_soh&0}!p;{1sG7_VDa{nK%lwH`19KHWpV*yR63|D+({1XoH&2uDr| zOefE|2(k9RXU9zo;>`>*^!t(Sp*eiQu{svfj7o);s!p3(&r5_t1SJh1vpCRFywn?} z=6^SvXg`%Xnxs4im=@h&yju5uE(#H|))za=lJ{(6q1ZC9+Y3+d4j&BD)pIXO{zGWkr|7F#jUJ2`v{k^8IH~>KndXSD>FX zF-`>n4`*f2G0KS}9!}{atIaG!-)x45KLH)$x!XEtcYh8W1GeqSKgmBKdpLR;`arDz zpcG2pdfqf<&r*iZcdJ_1`Ii5l;@Y{0HF;>4DV~0w;1qusiczQ; z)-;ja8;G&DBMa-~&g^XRj{MnX><2=`ak!EM=?n7X3jSX0|Ky#O$J;jKOW3dz`HGCE zT`toQSRykQ(>Oo6W3fo$r*g|#9K+U)^Q+s8A!`g>@FQF4vd=4qoN5KNREB05&5xM4 z-SS=1Hqa{Ge`_7y3oX}+58|je=$l=$h4R@PkGM@Vhs1W|Lf9huKHgr3f4^H73W=07 zAN5tPin^l7QDFoaDMtkZwdR&p_!4uslzU1}wifR~zS@of{~=4$vn_VDw|t}~F3LkK z++@Z8^)_KyrJ)7~NV^T)uF7y0U-}+avPiyXz@5yF`DYi;xbbl^L-A09(?Pm3LxZ!( zHMN{W!}ghr1}Gy&XiPCKs;pZiQk)}i``y)YCtO>P!t%X;rEcTXXbJ;|%>HEbVGKc+%lCocm6q_Y3X1a%|m&5O8TFJT|c zA>~vDc@XOWFL0m8G#>tQ)wfUbEBHi8i>ty#nfJ33;^-8S3R?QnOBp}2{?q*^)E_#u{Uvr2gwI=&dZ51vPOecCynp+` z-9V1AP*h?o&Vch&A|7ocj&+=L4Y2Tzma3NX|fHQVK-z~CO zkWn#Mu?&nFUioiX^UqLPCHc|$6Sv=h_)+5ejkYo%WYJ6x~nAIfgh>z;@hI4IuM{QImh?rV4 zCK4Lrf*{62jfx^}VD~`aVW3$>-=EJy(?W6;mv$c5$VsrxN{lnqVWgaCfDEoI7E5;? zl?bQ0)-<8RS4Lj*UR}f&lBAk@23yMUAEQlVdDS*0U_;OFWpHG^S%x#vo5uo! zbHt4qua$)VE&n8Zb>y&F&bHzU^9lmRln#rOs@1N5gY|}btz?UNZY;z&re;woWxsNl ziMWYPm_qk*PK3_%Z0Z*Tt{Zy_$r6etHq#4lLa4dOJl0f_aifC;jjupF2k=+!sWfl# zDVfJz&;d4v7Q%xR$LdO~<0hRaJP+S!fNgJ__P#p=&2VeS#R%KTD zKFxBMiSi?w{4h6(Cfyq>CZ-ysf;X{d-r^PKcVGE`P_Hqped?(|=M^|cr| z(J;_P*B;bb(i#FdkPpl|#bkh?-tAsP)ZA_TV>qu7#0XpZd@WerP zQ|#q~!kS?IeqVx3NmZDeJYzir)+gw8UMP$PWP5yfHqku6a|aW$QZDg{4W+92Z89G` z-&ykSy`8$Y&1FAKw{FM!R(3`>u%WqYK;(^4tDftuNs9`ig!JL|`zyId@9@p2#p?Uo zN5q05_eZ^*cnR`hi#fT2t0KIsW#7p>1iu&Tey)=!?u#OnG>5nL%nM!UI^(ZB9%KTaT#qJ2U5o|6x`dGr6>b{>W`%NI zM?tqk?u+8D3C?|d>Ls$1Wr^E(y1GsTN&>4cu7X4BZDcPla(3&kY|m7?x;h(vn4_+k znb&pu5;VJ%jQj+0V-}oKRPvn$+gV7;{Bf}4=W&rg9?%*7b(Imf zM*g0;!c4{E8s_QiR3$pSOvg1TXg2*4n_#%C0=r!JT{iQUV2~A zfl;Yd>_u{_3lvL>2O!%MEyO4iU znlDW^SD*EWa>$|aiUR#wx?l+U9oAfm=bi1mW|Na&Jor3`4Ze)+%muS(ex;wx;nC8! z$!MFIQDlg7>zXf2YPQ7ghX8|)p?$U%L!fsAKC7xpG;)a=xq$vreu8Z2ljILqn<@wR|{r;U^vHSfy(J+`fnw*)8t&ZT62}wa>fBms#udAdl&+66TaZ z$yyX78dQ({^U&@SXl^&r*-1%M?q+=MZoA{NpLdSua1Hu1#*Y1q1anbUjq6{m9DP$hY>++jt9ORj0 z-9NK#%E+VPxvv!2Z#%QMBmA~9A5YR*jb~Bc1@-LH6;0Ss#4G`$%FiWqWkxh9jlq8EHW!r%`5e7*>L zy&OlTo}ppd%FA2u52o9{w{6YAgd267sCL9C#Q&iWgE-3yemheJ+P7h@moIR{AOGwU zmE~ut+8LvmltS1-CI!F1LcYPjTz?UkX0;;fRWt2--?ssZ#909?X23 z9<$^2donYK2(5PnYToCluH@B5?tb8Md%xe-eAG|yK{I&XEi}#Ns;y=~YN0grHM#Fw z_pTm3>e#ouwW$DY3NM5*T;vkjXQy`_UR5AE*D<%gpC}=Pe6HU~91Xaxl{%QikDH+b1uW z+eu`_f`@AE-+SxEq28--O@L#b1iIBdP`kEaB`Ka?0Xeis&Hvf<@^gk`n!NRq%*rN| z3ie->rrlOnRm)x$OIvpy!ojvfj=AJTEjoe|&;ZF!L$fib*oFYp+7;-<)p)aJuk+>S zk5C_-8Ku!=xcRYK-$P|}F<Py zj*mzza8fa=m?RQ(&34tRo`Uo3IX!u@eBZ|+NU%*ic7}~$Cm$uo#8dPALwZKpLHxq1 z1nD30Np{`%L(@DL#Exj2b>Qkg3dv%W?IAw~_v)TK!eW+jkctsoE#9ED54~UFwehma zwccrFL~x6U0K42ncy|~mpQTmsiPeG{hBqhcvr5(H&8@V;MvWw~f5fg-6t4<|&9%s4 z{tund!rw7F=sIf@`^Jbmk$8>4aj!wdfV@XPBJ!vCOM<^OsQjaQvPN?A&~>Rl<)D4) zHSTNec&3k|is9XZU%SRb(L0V-Lauy_EUtt;5BN&i5F$czBqS@b3ovoh*Ge0d zzv`LeZN@dBK{mjdSng-zErl~4=9H~mO{4?_}fq2W2%BQW&U&|FE)-Rhk2j9 zf=t|r#iRF`8|^2Cla*&gpqSm-=As;Xjd5PXAa5LB)|GSU^JD5Va?%cDF!2KH2h6Ub z428X-!Nf!RhR(jeknZ{FqZ{`3;?8R6&o=P}Ym1hYRZ~S<{v;XJFgoRI>XrZ4((!h8 zItJYof-ZfmxvJOYZKz?p0oCBi`)(BsCzgq-t7Xdx;$|~hoi44Z_}EaD(Ik((7|dVp zr&VaInO|s|cljliEbao;U3MLEry3mue=$`NT#5?)2>Hd?-~%5&Q|&Z27~OUQ#hLOT z1DVV##6NYWhTAb87IsEQUTw}Bw+FFZ6A_4wP|ew{UXDtcl|3uGrciS2qYH6d@SW|r-z*MSeP*T5Kc0XZtaSwFhfbyB&ToC&9-dB#eHlVYqO`twn z4venfy~q*U?43CdugT-1*cmUM++Ays1)E7uWQExbDFQU8A$pH&ZFP|(@73lp0AXq} zjgpZY}URHlxqi`!lvae zw#&R$t=Deul>UPvp3#-Q99H|95q#rw`zCXY-qcumHg5G|QsWj>c-uc>C2dF3bh2}L zm9SK@!ii4!!7-67v2;G> z@BRhB4Boz=dQtgpu*B1wMn+nQF;|U<^gp@=wFO)tc#~(f;E8e{9bxr+E|Rd!kXqiZ z*65g`-~~eWRE8$!@3<)-6qg5}xea)ruYbZ>iQvM9^e?LOzYWvRn@G3DRg&ftSmZjl+_&j?+PfhR;OEXc8Lj7TaW7|D`d?IHo2 zZCb4Sn01@P!Q1D=Ea?a~|5g$293Aex+M2#y7W)pDg z$`zBvqZgev^vC>06O>ESKB=SV27knnp#I?(lX)c7$Bnmknfk>E9s5%xpd{n2;;yO# zh)L@j_#YB`4qA&Et$W&yo~{dn09^{3zh?k4$7YV&BnhPZNTCN?bH4D*+^0RSz-+pY z2Z+N9^~P|+V3)*~V?ZPP-M6Q{Z4#f^aip-7WtkkNukj}O8TrKq`Z@Tq_(@Ia8CDh4 zgACcsF@0a{WBkfG@$vU9j>~=O?zvG1sKNRSdw-lH-|4|)#)H}W)%@E_WH4t|`hm2< zFZWd0e|eFP$k!J9_|Z$V%OQ z1dg3Ou=sx4Y}vVA-0xp&DwF3muW%|vzr%MIIxdT4+}gB~yBc`Y4>*qmJe+ zDpR+FN<=9Xh^q2O<_i0wNpH;WfJ;UiSfe*!^K7$kLA5Q-7ylnqXBp5|w6ts7-5m!?Ie4zwf4-s&pQLz#PpIJ$(1Y`#!`0^QkNONRo&!pQox& zjwR1A52)!nVn|GX>9FKL5RS~4qkhXB7+jr?)W1{F>8OrBmIQoq%C5oqrpuqH>-b#6 z^5)!7ztJ~mHv}WZPZjbX@b=&SbB#&{TtIZ&42iu$`a0;Xa4>;H7l5s~Tn!>N&;=im z_jne(d-SpS`Ex%}BzVijV_nXbxp!;>1F+x8+prrx@5SM4qnF5q^{!Y}{^G_w6qP4; zLKt}R`8oT?L2VMiM)f;6Q+|n2KMkkhXR2WBb?IJV72YO_ptShHWG*AV&FHD!(XbVH z0M}g5RsoC&Z)B`2cU?sWR>H$zL~wqNT?x_qholIK-shBt70OI3UaW;bv;gQAT22_{Yo$K*ncawOtF3lw{Xj_=`le>i6k4f z!tu<`&4f|?1rWp~pDW?C|H_b-=j#=tO0yJ-IJ+^}E1p=(mkD~G!H2#3XY7JnhD39b z(S(}xIyAqmyk`w2mDk=U%;D(nDmQJ@Lu8sDD?<4wt!2=q)=5ODzrXhKt}B<(bz!ymm%;ZI;h7 zHOxyCHu{V{1Z_sHTLw}+RqKp{VFQ=HQ}JU6%zA*PIr^l*tH~UqzjRfB)IdF^%ZFQR z{HdX37k6?UnD10qMjgI+16ea};^fQOJ1l|j@x-8s<~STJeHIwBCqtCBmcn<59wKH5 zT^mVpJ!5qfUy?*#DIMIb<3?R8piQx_9#8+?*M;{w7|;mmype*LmbVXhmV{;!5nw z=!*SxkDU%-Nwk69rtyG_lbDP7AHE;p2;gN%ed^Sd42YX=7E)q_TH}P{h&c^6lFIaE zB4;CYtz=Rk9Kq?rBKkO%5X@mw03`Sv0Ofw5xhr^BcB45eSPv4>!kcVN38sm8Ny)Q- zDc}tKPH7kTf+Cac2V}O(CH>xIVVGixB1Q5gTdm-nIemidv!=OpmA@1`!4-XR9!3at zG&?b4Z#He0lv|IUp$vw89MHEz=~83iT@&e#?Um{8KZgVedPqJaz@=f|+>j>RDU}_? z3i`g~gvY<19pz)-ZA%ToYKn`dCC%3Em)SeH zjU(mJ*z3aaA}Xw`D;G#z{7i&NCZGt?RocjTRK$mS>2`B52K&7`<)$CMv&|1Ftrz!|k$L?1fmC1A`oyCxXXk$puqOfFV9h`oLFKX}&ZtaG2 zn?Wy^vWnF$fuJjnK!RAMrkj1;+GunkYkh={m;k?7?gzkdLhlaB(ge8~%L(OIFUxQ3;1 zTwsi&)tsRGVlZ~N^ezyMsR?K{G0!E=hZ-_tM3Ps0wk7Wi$35jOUJ zGjS{=Pr4ICzmM5akCvrV4!AA||6)>tm+M7HDI+4gh64Mq=5^z8!nI`#J*BWrC*<|> zPf^?b+z~%bWsOR~*>=!BtVc*<64rZM){_uYaq8(MIHeDJfyE1Xw21SJlg6tF_b#uf zLM}_r5h!G!H9~(TE6veLcTtSFKcd)@Fkd+2qZs_F z_CCvrSdx)TQs9dc7z_bCC4Op9cmTimzlkVvuSp9}Ny@#BSB86YB)fk*O&?-AGN-?u zi)-zA(@KNy*GwUkkiNrT)f{Ma zG!@saKbAPDFA4016Z*~Np9$fAnmNo$v=H5+BgT&z=AdAo?%D2`xo0OxI-iObtSfHe zq-cnK^^ywAs|iN7Z?XrW7qS^Vl)^fWab??-fqx(;q+CB1887~ z?Q99Fyi_%vrDUabXD;t8iuS2_&${!m!iEVK4Te6TEXTS7BD~2tmY#oU}Ay45M$m@{y;oC6@ndU|mD+-FB z%+c~F_JW&3j$0)b*~ja;O7c~u0IrG>Z#$gM`Ptx4c1QZNT`2kMlT3Dv8FbUw`)Q{u znbU5a^5j=hwkY-Sw#AShaqLW05R_AH(U1vr*L#4|h;EI{>hcwg@TGGP@QJepg+e~o zX3caRVDgK(i364<`(Hg&-mSf?ZDN4sc7hYc*>|9}u!SIE`}30>rb|-8W~|L^x+7+6 z1Po37o~2~19hwD6!Sc9UL!UGe;chmDqRUt0L1gQj@J#mmCw}BPK|tn&2b_i2*Fjz& ze`6cwh=6q}2qHMpWn|54slbJnrZ6~9Gdr`T8L)^NuqL~^^;0XXom5FqQ4U>P+`~y) zXKAJp(J?B>;Sfch5|MuYUlu^mPpvZrbwEukf-wbIft zb?V|r$;}N?;ko2DX*85-DZE#i{RU+VTLGzRfxw#r(YiLV;>jV43h?g)ZQ)O&ZB#g- z_^n^p479>C<<{83g$qhE;N@ojzHpeHN18 z%>!t5$WYVNZt|!?c!rZ@5fZ)NIG!cG(=)nmNF7WJo!Sg`{7YM6zXux~F`~(RvP@9D z;a|pUz3L)})-OgO(61w#YJ2ddt?t|S<<)b99YotK9Q)P%clxt`$P@4R$lI`HP&eK~ z{;;T%sxv!=S=+rXc??L6?vJ{;9iE58eQEDZz!UCs*`=RmYM~)N}I*L1LLG zSJE(^n11bLNQhr~&&A@W(9^b9=;KHvvJ@m)fu5u@W{GzK)4r9?C`~BpP|gYCJ&_P6 z<3IiM|Da)0Os99msj>IdaQKVN7XO}M^1B+u#2qC2{uTxz6IyNLz;-c8SKLTmB*VON zV^;w_s0$dw2`w%bYTzkUrnFnlfEU6QVc?Q5YwDtCA00jKXv3(iu;|>2xeV^8*PAV8 zb0dWDc4OQ!1>##zB>U1_%Ub72!$Tq>;XOMtmE0qr-opXeRl%H7tJ3)I${V#i2mfBa z)RT}T6W#aFS2vUul@%EWd&3pql)R`AzKQT+*=f5cjT;aq0_ii4yh09_ z2NCN3VJyD1+0W9OOj=4=Qc7bQxUnQ23ttw979em}0!fh!`~1#DFSj}L=C^yIe8^Ij zLY+}0dst^FU5ydTuOJ>a?i2OP(U9@jw-xn|fi1=$_@CE4f9e+;QIRx7sD*l++PEzG zEStT0v~K6#OzZ|4li!fRvY0U}?Y!(fi>bVkX;9R&sX;wSKPV zO2GIglC_>+Q*#MZ^!zJvj#HjI@V5ulWxZ1wFIpS!Bv?mIb zH##C=jKM+4D`r9kKliCXNidm4pS@^h~VeuUWM$$U3Fa|es z7W@}>T2wl`b^cXMxFiyfb~dxjawgXvG}>gmVq)^EwvcE#mWl`)(zWgX z^Ib&n?PjO2u=0nBPz}?St#rB<+~t6I*xMlVEhHbRoJiM@W_grgQb`BMUs;$yzTa$<9;bA-LAc#8*QlSB(oATYa}(Jt zqLzn?#|G7?Rxlfuic|BF3RRJwP;-!^3Z5mpPJp+FD?^*8$7*&nIU{!PPW7u1 zNUWsA{!7` zVq;`So>+(!2S3Da39ic5wA4pAJ2qf&8u!i=u4uc+kxxhRB|n}s7EuJ3Ht7EC;#O0X zyCI#GQx!@Sgx@D?4(HGCBJf}%c)lypKJ%3+!HWhrh_Dh|+7sS+VMpH_$ZdE{Bzp0k&tw<&E)5*tZ>jTK^sV0;Qv<{ zkg7FJh=mk0U|n(ia62Y!nYz2>=JB3YfEWtAKUnV6WrKbVCAZupaQxV7VHbBZB1{3N z%x%}%0;>6EQH<7xD?J04^(g0j=~6zHrX{CvG%!4wXIC*4f2WBT1Qz4zP%>-osmxV% zXEnvIe_r`*r~Pr=#MD*7P4e6Q)o4Y^&b{PjD|_yqWwINk_^``1xH^c&>n}n6(xs#E zXkcHgq&{sNu0vCsrK5tIPzO3KGJ8BOT_>6g*3;gOM`>9bh2vhNVa4|^!}|h@myx1v^Ec@Lal?k&F!_PeVi;mV zcT-izdO4fbosU?MUB^RfVhMeCo01K}ufp=3+o*9JX9= z3UU4ZZaU|1_o1~hvD0)|?~Vr6*r&J6`Cr{N^O+Yf4jLvIcZ=n3=MS3WWT@f4@AM{b zfkD3RF|GB6wkl|?NBV*3 zi<5xw7=d`3-kGA)V+iJDakK>)jhxb`zLD8Ik6d8tkUk`pWFjcP#(8o3K%{oL@b`1o z%39%XpGuR5sgtG-e+P@ZrdRRjsE5PlP0}u8@x;TkgJUyM4WmiPTNc%{$B-`6|;ex1x&H7Q~wv{+=*LUT(BYe^MsH3xT}kGO>+L0lq#a}Vy_UgXZvkg zY_q#%{wXACkx#at;_WQtx6jj!R)xM)-w|HX$`zhqpb9j~Tg8mPR{2f@$@=GXGA)EF zI0C8`0WfZu&MdEtx-(gp`oR}C7u4V?FqH(pv|JwQTNOd8#1A>3h%)KyHw8E+&`Rdg zij+R;n;0EglFEHNKs!=p&t~nrw-}Me-nx0iv??k1UE9jFrLR2}Y7=dcndrr;6A&}O zkBO}(izC1_+;l&Xn7WaU`y!9OXU?RW%+8)x&9F3bENq=NaTdu&q5=ISR(UGruxQci zFRMI(@eY6fW`sgeu!m?YhkT1aOeH&qG_Wume4Y2d#!7ylovQS`_D?(D)lhvCQmczCmsmk&=N=gDqfb zY>|U$=$F7SW9oLu`CUKHE!>EHXgVRi!2$|_f=K=QToG2u;SWe#2!}LhVi>BE0&rsyX?^Ub zpbrhEWrTPVfE8xHVn+x2+fwu0ymy6wmT^5Mmaff!#@OXrZUsYdV8F{2k}H-k&y!=} zM~obh7Gk|jfsRIjjt73H|9gi3Kf&|dzasoUnG!nmdfN%WgeT+sBt z*~-F-b*I7)uR#tvcSYK*3pt2bG6>M>!h@j^7MHYnp|p@>cS|b4!~GoAUiJJ@aMX)z zomjc#BOgd)TA;y$LdYyBHh))U@Q5Fw)VX)*PK2MAV<+?z$0`grjC~bP^Y7~Fd;cp+ zhl?LZi-RF3SMgXZPdq-Dh3R5YuC;;vUXs= z*}8pJ-f3?q(nouuG$_0Fzq>miREW%_Z2Jg~N~pplsoVq#oIH5GpsKpN|s@av49KpcXE!!GcT3C^!Ys`xpd!b}aH(g^pg5tu1h3!s6nz>Hdbtk>* zj=D2YK8-@xSnzD4w6C-P7w5FMt*eMe=nRiapH7#mMe#9nxlb2a^u3*CMm^tX#4#@n zrO)*~cOkPmJdb4E2`ZoD$|aodz?jHn)(9}8&a*{!1By4=@AJv-tW+b}u3KWdfRY^t z;FpJc=-`UGY=_yfCXM;70csDQ&Pq<72K77SoNldW(ld@L(~q0D`$a@Hw-}%s75P!| z`EX+?q_Uy*93ISNB6|>Neq=d8KW1+Von4EPP`$Y&{pHvb;aL+5TG5W6oDBt#abBx) z7eoatNqk+7$|urjdnb#(5{e|cVTH0yH=>L}+nY=BCQ|v^xpk@Dj{VO5_Kal?G zr@Fz*mb6lB^oNG&&E7uq@Y}&Z^1T-PqVs-TA(>a}eJq105q#>q!u`oNC4)=PU8*%o zIHEJl^|4eVNqsiVyKjb5n^u96UE4`En@!$u=9EQMg>)u}B#9}}A7rx{e)YuD*uy{D zi0{v2=Hn3EJO^;IeY$l6Br@f(^`y7lp1^ESdj0?+DenhW*yrs^;hH2oG;1_tDqC)H zi9}&3IT8Q#yiQ*dNfo516plQr7AD`Xubrt{a&Q0%Zp6;+dT?-pDO}hagO%dfsi1<_ zLEiLeWh9zE>8zHgKm6LqksXqfR*fA}1iES}X?9kG(=-ziW|i)VWR=o={Z4_Zx`lRa z;I&Zyt_4^K5X`GYVTyqp5BrMW?a?(_Oq3KidBtfF9HhmOi?GrevGIb}`?SiNgR;6` z->t;Kl+=P(Ich$fk%gUu>mh948#u|qvS?AWVEYl$L!hs_jD$w+(_pMLna;7}%y;pb zG*sk~evVipoOLt`yuk7=&J5h-X|#d5V@!AnS6RMySvy zXGbBzK9AMMFZZ2m61mgyMrm`0N8i)B#_uQrzn(IVCST(YB@x^lX_q5^{TaLB%Q11$ zryR4KM(3J6BsVHw(Ez7`bbW2#sJ^#@?GTk{`kr*#-u$a?*q3HhYAgp1Io@i4VxMr# zH6-VF>dLAaTm@_$OH@A=KY{d*3~uUMJFP*4Rt{w_E>W38Ts$buOcSY^NJHq%x?k|oB*m+{xlk& z9p!zy$Q$7wIh*BUPp3!&fy44nx5c{%i@sk-4#M*T@u-ODX6YCNsFWv5!osj*_pJRLrfb1gwnkN8dl7hC*( ztl!!H+m9lRD^y_Q2)1}%=Xh~|WQBy@UdY~wl61X*KdnEyztSIn+4??nVFh-7WQ&vA zDzzIqq_R2M%qy|kX%UT}YK^;R=2{QI=j$WM_upDJ)R%(U+fSBj-b~Ne^~=8Jmk+BW zlMg2ZM=QVTOs>}3fW};wZi03fbY9-mW*m!11{@h!#mv;kK4!5LtG<%!BB>z4`j)L& zW1ot7w}4;I{a!7Uj|r?3)FTvg3 zf>#gp9j_-Fi6dcNrhyn!4vU5NPD}cLj!q6;`NyaAy4KJ2Z!Ne*^t0$B zc+fXs@r42~o{q&vCnd56pc_xOa#ceGb2&~BVylvAlArW{{Uu~P z?9u(Bp&uCX7^^@O7d8Ysbfoj+>`P9Di9Y*8@YyS=o+k{_cRI9w`cO|QtLvL60ddBy z+0q1uqI@=7Hl~LliiWOeor#+p%bXvR`$DKU?Cz;CQC|PUUGcH0tcIw@gal_6Jtz>7 z5DDVeD(fpUo$15+hGoQaB!=ygm~p&4YQ z!jC@Te@n~#YX1r^TT32wG)C7#-oG^v=vAFu_uqKV{W(`kD05>u1(!#CBEM2J4n0@ z2KvZ*_zJ^#qvlIG1!i7+5Z^it-9R_cTuc5np{||XMrJ{~Clj%Kz2omsbQV{nb?cZ4 zQloX;d`uPAnRqP-J_v543wkuZ(;jDeFi(f@G6JrpeZ#aVNOcq6%3b&@a=(?#X_Whl ztx!-Zg`OsERotr$OB>e=>Rt}H+puJ|VOX>y`ukTxp6?Xd$JVz1)_|BJ6ULqr)ne_T zjhyqfn`6tff7f4Hw#>ee4z8E9=s#mkd>Wv)$M;2fom<9U%xd zCinvJo*Bkd>3kSMz`a#bxMcN9Vi|CjX4`WSBTNrzpg)S+ZbsXQHW746&}Cq$fhZwc73aNL`Udf_R7N{b`cw zxRZokLj04eEs0AdTPo0r<~?7Zu-ViXbd$k!fhFIkV!Ad~z1X{`TbFTA8&#+H3CL>8 z;d8L0amHIbdam_eX+5u_(E$w7W~Tbky6IN945K(AT0Kg%^oXN$4aeWOxTB(ZMmfW2 z0zwg}6E}o5Ot8UFO>J1*QR8|`9W1pIQc;xE1x0;g>f%;>h?%`y%T6|ug)_o&QvQR4 zL)@su4_LKM`}iAqbkAt&Se2i$gN0=rs;Lp_=hfiXj{AVDGGv zx~|(U&e{jVVzsM^JL>7<2F+Yr_94S^+&cf7VdxnAj%estel3m`p5uO7nljkZb%Db# z6N9cXdNZ1Mg*hB0SP$_ZqB!P|f`;}))A<#T8`1oHXC$>Uu!3~1L?vroX5 z_HeYtcF!A%PomwfYvb zw-5^EHeUvRa@$j<{1#!z)V8pLV@k|JwmbLIDNvB{*uvGFR4%+(aJ_F*+X7-5^!b6Z zW;IREY^!5pGP&+RzCMxYV0|^6Xw$7OX}8kb=C+tLqTrFj(0u4N;pRJz{H3lIw$P2G ziLR8OQSXy8Q$WEWM+Tm2#s`OiQoO5*)r`~)qsFw3<&4p&?ORj*@h}T|+x2ROGZ2

    `rj|HB+v)M)o<0z4cDq|KlDL@5G4BU) zjTaLuU=#ZLMi9G5A0M1CqIQkDKi;=$gHztqXAD;1#Gls|x^; zn5x-1ZW8X>^yRhCVQ7&c0?hc_Ydol$@%KphGiQ{lZvoNgjGt#|u!@kw*HZ>^ce}>bMG+@> zzYGR!{ z@Gr(=p+g`4YH79;O1z!C;=(G7c%SW7M0Za=9Rwon1h2Jg{AotTXX2i`dwN*mdw%wc z?z0hnEb1osP&}{x@5iy472mSlB}n^bFuYNQwZ={8QqRi8vy}Y63FPVs%OpF$0n)^X zc<;2Y?@Veu#+PS$PP+W{-F^>V|4g(Vb`=0h&Sp&fd!UE1&~xFx4*hqo_VpRS7mNwM zGkCr$5-x1J6}jJpL{Y_(^AbMY>zCbr;zD_k?m0J;1_+)Y^6HCrjeBV8XT!!;8~rEr zC9#rU2zt9iDrSGVf$P}O6DxZ|uly8llG%JnIY%fS6d#a0Ohi^&Xsr!s63f?Ll2Xn3 zAkn9Y(1kTi{CX{6Jhv@K*f`s+4A5#Oo7R2Y+KCk}Q{49TriwBhwwR6Fkn4~E-@F%WL$cjOBU zd%IY(AD)?1JRGMQ@>;VQX(fo-o(44Af*hIa!!uv|J1YfP!qd3C2K@{^x)R*vuyi&| z?p+bwCi+uJrj~BEUE==&Zd50B*Jap^!9fhgv@s^Gt1d||A~m!jADOAP=5c}H9-{T< zO7XWNl}WklX(TT?A6jksS?iA|vOiZQH(CNEszi_c24T3{?I^gOH)TQ3cjkN9VracO z;CwsSn*c!+L!iKWJrEH~7>YC?kxDFx!y!&cc$Ucw-a0!Or%^FW6 zG;t25;qP&fy%@Fj#{`8ii1ua;Jm~G=%aViAx|9{RN~nNSL2mJ%PW7qX{n}sQdWi3_ z+X9qLeSYQ{CMBdVi0f*AfvDu`p@n=|(&*k@5y=KHO|N?Y)H?P8WhUXE^>|+2@*b7q z<-|QN>loyONku*aOcv%1ZLqdz^<>9JJ(^k1_*YA$~ce{_P8 zFDY=>t`ia_Ju=8g_gE+t_%v^nT};+!qg-i3pQ|ivS9`AaJhLo5{og3-k6?PXDCRm+ z;9vHtf_eRD_eb28Ohz4x?Z>LxMWxdUvf6 zP9^5XIWPmJBtJG%KQlB|&JTms2+Eb%z5r7)oZ*3*|78Ili*RSLq3O|&C0v&$pw@;t zpaUD*>AcV@>k(zv+}S9|r*W@A5|Gvj*yC?gusW}U?1d{^a?G~FL1_{}GPYsQUjQVN zs)fH-E8(+Fv&b&Fd;$OBbsz_&veX%+nt)#ewC_|}y{(DM0};909Gox4q&_<)WF~C3>MLG->OrpaV&JZhwwC zCfiIL)ny-MeV7jPm>6tCvQW#J`x@pK#a@sKR*K!UK9>Pl^=ff#>63tJThS_!y^Y>s zkfX1;m52l!x@C^SYM_wQG|L9klj3LVA}_iB0%>D;4IjH`{b}$#3E)btyf-YDE6Jpq z=p|J+*)MAH@r&>ZR2`tdrf})um^r$tLag^lrH4CTte3brjt6*5i7aZI3-A!Fd~p%+ zi=DEu*&+h1u-3jBk;O*U*j3*>*viySB$65;8tUM?417VSKzx(9HnpSJ&Z?OUdRybs zw=SnmtBq>BCZ#F;+#TGNV+Gx>(+`j3xFw9Tt8X@Q=>errhKwzU`Dqz5E1n&|OG3Ak zEiPbk$c>pbG;}78F_DT$#+)}0juef)4PsDjChKg2cMqI-F~#x{u#G>MK0@jO+lxE@ zvS8`1mqaM_A-g5$efqF1lOnc2LZ!?^7%rJXT(rA zCi6n`jK z`;`wt|C>BFt+*Unyla0s9I4+AIh+?Cfg&;S7hBu$FN9V=MMl zE7oivXX<~V>*_-#QX%=P(szMT;I37`qImjMSxN&sY6zn2M`zJneAqSS9hRh~CqNA$ zLZe}_7OrwNB1r%rOGbRf5!)rp*HV$)K72O)%uM7>*UrIYi!jJLRKT5RFnG0GlL4(0 z@nag8*bm;Jk zV0aFQ3yT9>iiB?&CE-+1o3T8=e z7%}DexnkPTza1Ca{^VDJbmc!A+ZEnLw2gP(d_>_7+dONM|BFqta>jFZh5d3@h@$=V zo-&uc-Q|^rX&HlEEJB5pB|}&F&82j_2D*=SZ~<|WpNS(}jZ-(_5nEu5)>@Z;_%q@M zCwVCpIa%C~ABfMvz%3d?zZ1(NSxB(sX}|EGWfTfh0e4b@6x{!g-f?e#$`ft#r_eNf(M1hig4b`J9_O&03c&IZrv0g90~UHP5=iK+5&DoKr2A! zCCfyG)@jz}SCIRl5Om&YXq+bdxoM9n9}pA0rTn_m3!ERXQ@HoEf~y(1)>VHM+@--7 z5(P@`h7OWLE?o1?cPboffkcSpf1VcauP0&sJ8(^sAD1Ry{ilzXS1cg+tx=-Eq%iE@ z?fX^r@6gD?5 zC?U0~*Rz<};1n3DR=h5T_|A+hA>3DH5p|2d^Lv98L+vPp^v-AV&2kFvUPxP~9;tJK z(v|7s231EjkwAbvz}F3Hd{RuAUB$2eYlW;?RHF7Fj%*?wi_e~XtWOSz9xDzBs`?6* z!UyQnO~sUwLeD zt}B5Xbq&+R5B#951+Mj-z&@1Q4F(VmMM`%tc@ns5@X=TwgnYJdAU|MZO+gd-HPN*a z$}7LqJb2e~V@^z{VCV=Wi7-j7;QI90qzA)Pm9>M_n3hyR=xhkb;NLi>paOwgx3XlPiug>^LSligro9zE!6bDq*L5Vv^& ztfQu^o@p=d*tXGQeRG@UtKa-?dC79PMCL(z$Y52+bvTyAJZ;EzC;%B+2v4_#P+at} zBroy8+gKVBhQ1UVGr0E_)h6aW3&LCo?T@}D}^e+pX4(R(W{ z+El00|H+opeR4q}F)DI@?M!+K(i>L$x{jI~tbY4aPJb^ai|nW~ap8CjH*FX0(aD)M z+3*XG>VlNS^4peP8-Jhd<7B!w_|&jBNV+!kefyDxPj8x-4Xzn%M0gk+9H~&?DX`jU zeaAeUeqYcGNt~x`p1b-_HI18*ZwIxWX6A|+`jav94q;ATr&q7beNL%HcLVu&4?@?J zu3^X)+6+?qI4MSsG9%)6=qfS4IT?2|eActPYhledZ%t;hX5z6tpUch&|+xxa>*U0t+u)y0%9W3MIEH= zPt|xCZbU>7Gylpiixboj&TI}`hp0lTu^cF}8mMY}dmW1V)nA)S-sx6(Hs*E2n=z|6 z`3)*ML;O+vfCfT-67+~hWYroi>>uhGS;WjU2AjUtps*2Ky$1ab6^xwgc47%yr4NPX z`F+y2GQ4Cd*VZE}oQcx*s<@9aj>#|z<@S9W41>V{HPoXlxGG{}Xm8$c*Kl09eEjDk zN(e+;7>8l(*irNBZO9)xJw{+gYL}s|vLpCw&PBA6O7$7tJZ0gRhCF(Z&2xgRnZ@C+ z@e{nh(a{X=a70}N7dD5d%5if*mOf1fF_RU03cMf$#x>-Y#^SQkPI${16bDHJT|;!uN}X zK>Y3OC~tr#2TnZpyo>`MV>VA*2>mo01y?Y_EV^*yqvk4DC8W8W-5?L8HblxwY~)$~ z>$_#K;GaUTrrYdkV+Yxa-%kIQ@gMy~oazEMNOaKR$8|g=-dWa!vF|i+>|UZYLo1s* zzVj2hXg%Z3LD*9dZr28x2%8!Li$HA=EiXcM`u${8R4*ulShllfvFW_D&% zli|wGqi%ziuF<)Zr2gZACjo=P!soBZlz+bB9B!xo9&Tu1Q5)urGxW@Y9Y;YTc;>NR z^l49mAowLPJigsfY*C2}M4w*%D5@bkRmhJ0gR$Et&~Y1YUIoTMcvq@Y4l4faav4XM z8C_d$Hw4fMV}u>pxold^N8x_Gyww=bK_PZPbu0;Lx-4AWEQows-^DPDB}3~dJ5I(7 zy@5OJox6OFGW3|GVH~vC9c>Gj@fzU`ZQsa>u;n8G;h-QpuEu13Zf{6(omyPCk&zY7 z96m`4HG^#mBr*dFD}REj8;{&$LZ$}G7$Cs$$)>9!*(&a-lF?TU?tLTx$q1*RS(7x4 zG8lY;N(1O`WYBN08j|IXbgQes8|-$)Zw{d81A`!Qd^5tlVFv?P=+F{iXxhQqOWy; z6%#=Td-sQiali%6HV4QB&VaGu^>4Iq_m^KRf8-&mR{o}kt|H_b0NVX9&cUM+KGOMk z)yoesXda2CY<(lmI@oF1y<1KF38T+Aty}(QFYL_XZIDyx`(BWjN}#adtRQ50ofJ$; z#@^yitM3SZg?ppzed_hYQ3$>FH>?q~-LvXTUMVDLn0YwCo8W3lajnftWI$$LJd%wL z?TYze*ru!q_uLq1)N14sO=s@|3DAu@L<8&ntF3}H_DXwM0foOknm4%?FZ_9G&z23y z0u>7$P%%vZDz5>L%Et|jOnMH90>7*8F7K6y$^ZDXTVr;DBdP5YDwP_xEX9fk*;+5iRxmKxKsv{^62+dWPpuvysdox1khhKmjSM;WCJ zefiwV!Yxk_LnlG9lppcuVr-Y*-(+ZKKI7>v;d4_+F>mq`(*4W|!R3CBFs}^~aVvn$ z3=Q{aBb>r3;7r^OMLm8$44lb1@3d03z22`c|4YwrW%Zo%4G%a zsWFNu(TfcG^G+oIU3A91z68@trws4@yC7j7$e`t`z|0`rlaQ0MqoYuopyQ z+1p(p!GIIrmIjDmlLQhrF;CtJ6h_T=>mH;Al)a58lg>QOGNZZ^`FI`K;|X$u=u zrgdVwUlS%QJ`Fut#CbgXQF^h8l`-;_EjaGGyOB2@t8rk!`-oJd)nW0|;6=h?WHk&A ze9-S=>a`5U=ep;8(h9T)5{oq%%FKOb!u6{cV=t=9hA0vv@4S%W64lofD~gy5VRYig ze5-+F^ldnxBHqzlyz=%nVY7wT_U8_+jNz;O5kF2v^!i8ug;Yw^tFXpGYwknmG>2O} z;c^x%Q~dIcpOjF&{S7fWt>v33kmD(fE$M-fSWDy2h^&~}-{XO;)SS-@cnH&evrtjB zYMOtOgtw^f2vAdwf|;)b#&1wH+o3iiQcgc0i`S7i`j+ zs58_-jf~*_G6YEah$dfN~0cqF+is3kLvlD4{rLNrF__UE;Ih0W1YXvgvG z=u6CQGX$zb33!j+q5(aK*yw<9ThX8)A%C!E)-2;O&+(*$y+1Nt=a!>?c{&$v`fElX z_faJkMlR7E`zauT^M^PSza_9z7@tc9s{o3G{7zKd1}ae3d!eae(V#>LbxiIAdhBm9XoW*poR-}bJ>M~ac+Yncy{v=SjabaN zZMr~n4?`O#K<#>snJugEY#Lm;LNA!zQ8aJZos1SrKH2SKY|vYd+e$lD{qm0LvaM-R z@FfC9cZwgokWS;#og|gG9ons&#raT?$RuGF_U2L+rP2h?x1N2_e;b#gx^Po;%(Bp!X%vj!?Y&ZM1I+YyF`OJZY7cuE7j1V=~Sg2qR>_nXC; z3%9EASyz#fuEUSUurO5Z>-YW?VhbXCngp*tR-U3ois;3M`d;@?BjOAD^U^`7Xsd?G zQic8@bABs21{7{(8Dx&?6NgrS*MYZ!7SNUT9(}pe75aWDba@OA(LR4pBtr|lrI;>0 zr)LLMl317#V~GTSuss&`+Ksgo)nQ%X9{v7yRGB6y2St;mNKeSkON1Ustlt*+Nu*qHUQF8sjUuHMp*rA?Kz zgxPQ)X6GW+_z2i0r^4kY- zFS4E&H@LdjkdmN(zo5x%-M8DcJNl^yiM(f8!>ew?(0}Q9w!Zrl_$BF`XkuK^^_2>L zfG5m$<*h<{;eQ%QJ@(XaeB&C=i6c*g(dbDZnu7=}{;c$e=pVfB$czc=hUr?=_Vk+z zkRjs)-CZ5IdOaYS){yw3`SNvP9m{lBKpj-PZ5jqnd8(VXl&GWu=@2pQ!=wG&CcO%C z?m-vRR03B|fUi-Pbiv}OvR@6UM_a(tJ#yFs<*Tzysi=f*nwPfK^-*td)!1iZM?pmM zt)FaNs<5|L`)q|{dMxyl}Wqw_?c3dD@q`J3x>bN}wr zvO7OJ7_S_D_8@drQ#qiB1Bf3~=ZqV=&?+NO*U$R1!(5pOV~#cg@*pRyY)Rzyh^s3Z z;N;5jKTbY2cb`5itw;vfNra>#x^61yb~EdXTmF*ktei)1-TyQKKay^990?uCQEk|J zsw3o-_F5OT3EALVK%kM7&X!kqG(pLBvj3CMr}JjX-IvxQbYJK46`vBfAzNSk7Q7ZN zSt1=qhgW`mqR$P8JdE*_=<(uL%6+eWYcX>qkh+ys>i#B1(gQid4N+B)=+cHP5;O%AiCxf) zLjy~YPRF0tK7G;0wc0d(L*_Fc(}w=uiKHQ&pD{!!R#oH2f8hWz5|mM~-Hu=#-2`l7 zZfNH8X1gk+8E`_(h%RpNRT!RPn(jI+Rj^4Fo9*EBK|V48cERK#Wp4-qu2+ts;dxSwChX8+b0Hbi(U9*@XW9dHcYrLX23?|YaocU_r@j~V#$T65x zNaON1g~iO{v&esOZu}Mmkwy!;L^I+43~R==$(D8az|KBo@P(a>aT#ScHl*so+PxiL z+p7*6=EACt9WZ2S+)5^$6Y@@=#TGe%`$XPSnF!m=>avb~*EJ4kdx>VEfN4qfP)bYtrx!ZFq|!>^vJ zgDn5W7?CPtSD*LNs9ihjdV2jF$6WJT`SmFPQd_PRQcs_qNg=C^SW^F|fK) zWhg?`am{g&AO58HGY^>xTE0+O@#=aV{O9`okJQ25C6!oN5?P4osyRd^4v6>wgmZ{< z9G@L6_=oU(H5^}<*aa25LE2jP%im*-?pXBVo= z|EEenh}?gd6Mv&b^yEc>TiCTuRzl63SCB!?0T)Wup1y&iPa%EdZ0x(Ny9d z_KGQ|8=tx+{x(&rur>wsm>OWkl1UMZ1^D6pLA7eVnx)JU=Su_j4u?M7nCTl`)L!&r zMU*xU5!J9vLWWO(yO9;?NKhlDhC_Pk4mBHP25LsB+>}kc`oPy{V@RfzTgjW~enN<(e&~^x8L8wpUCIy4GQ)C%32|M zO5sV$ZVOwv6r6KtUZpo#{2NuGGu}msld@9DU{$8 z5v_8*q*>`Oo4?r#xY-bxcD{&Ufxpr!xCX zj6<J`7ByAEHn()D^S0 zjh&HVat6r-m<+?3JOC$T(u&NYZL^D$ON(mlZ!iuUS#BLJPQS#j{Chaf7(^|?jG>tz ztcn>{L;Z5XVC{w50US491(w2 z@4;v+dki4-#fbMv1abA{@ne66|M&z_L5<}ac#R-8HqGl27dNQ;Wcl;SZ^RdmXdcw4KlSm2v0BFW znv3qelb*NauSVJfk4?5E(4hN2QHBFXKcnunt!}VfXVmfVU6T%uV&|&pBfuq*TS91H zipW=Je%ueg>&ozVDjuT%9h`t*>~6wN6ca_mzfXsNWY_wA-->N0`(w(*P&aS8$cl=Kd-Z=vx- zP(6%ba#ZmgID}lo-JAAl6zhJNgfzAMBmprP7t+hjFIk z82EJLCg=N~ll03A!^z0c&^}Qa1aVFfrR{(jfjm0k!xh242{_By7e(2WJtm@JyRK)& z_;)AnQ1cAbRjP%!t_upjce{e*neo`0#>fri^n!{rw+77Sv$hZ~pqdN7I66?kOEx}} zWzUrJZ42@cB}oME@;rw^V-&&IdQ^<4R!9o^<)*{JH7 zaunzcuE7@F-yB7etI(OoX$x1+TvIB&ocGk~ST>%c26OT`F?zx}5(azCREcD_5IeqnifSh8m7uMWtXf9gQu zZb2XHhrru&2iOI~FrU^L284RGW6@sc)SYaa<;4_aB90do@fd0C9?4?Xp3Ys$Is1d& z6Cx(&KL_s67XT_)(&}G&@)1cN4m<=xLoAN#;WHVp--k0OqK$xPtGxocY`-0J{2z!a z`NM5Fc^wcO9c_GeAUI8h^M;dQ=gp*Nd=e`}394(JLO6q`r|q{6bjd69gWnARm1*Qg zpTo&<@?8-^=YK@jRBMsAV=Z|QV!L0Lr8K$nV@fYZFvdOlVlmQ_C&<&$uwQsmP->b2 zV{3i2rdjk>OBJ_sFJADv#<~qJ99zw^s{7r=A7aOE@DdT;7b|pKrS~yuy%!->QNGk5 zq^}ZgVWly{DgW0it6+KG;j_jRqHgso1XhuVkJq0nqm*YX>N9qbQW|M`Zj)R}^N##G zPTgWb|Im#tV6h>S?ahD*5@rg@g>L_+-9r3AK9tcK5=uAO_5xu^dI9sn6J4v{*y_hV zpD!^dCiaBB8*l+)Z;7}<3wu($6fMv1Hl zov{n)ic${3F0IJ#wNU1=!W(;3f&YWXogw-T|pImLfN;|2$q(FwSN46 zuO=IL`iT@te)^!YUQUXJJl{K>ym(GBVmC@R3nf-bs499cEty!6Tsdo=oBn(Dzi$tE zWEoIV{1o}B!UI&7ao6nCsreL%FG@8f5woxs5Xf5HRUPL)xRf}#to;$z5_RD~!} zZ2!3pJl8iX8sRF{WkeF)-xYeZ%-uv2(hMvv$9j+#w5#{!^kXgaGHJXalO+27wXU0+ zje(Q4f_vd~sp^5Tdy-PzF@&%)e4fhWh7iXVGXZ%~dz0(YSP%zI*cKa0>?g&X*O)KL znZ!FRG)WMY*BtUe1O|*(R&6O48L9=PzCFGP#kak3Et)RV+~0N-kvYb8`X2p}wE~ep zXWAO3MaYM%jJM$G{x!o7^2Rp@g)g$eH%Nw()Bf#DY3A`Hkzwba{Fj8)x3vO?uz9pa zTI8LuYRz$dh%&(P+Z3A=1$4I!!g+to{*CRg+tp-;d<~B`L5PtmU!jW}-Ac^mp85fj z@hhSpnecFA@&`Z$P~jNq+Whz%9B)*bs+KjlbI!vb<# zEQyHsUC~UgUq?7?-5>bD9K9ph>Pz2d=PJm+WoOimp7qum;Prb5X7+PPDN(+NUxqlW z)yG5Wmpg$|E6LdmK#E5f-Opq@VTBq29Bs}~HI+3~^x=gVFt6L!uJzY=cy~Fmzz&n= zFz9AiwNj;oVA{PpcybMNiZ|q0bB4am`R`?iwq)y(HzWP=a$3&AxT4GP^k5NC;VB$E6a`_*;f0^eYs zybb7{fYEOYcG8MVDM4Mk+DGH;86^p6cX8Gx8FArzt>DX zO#Sh3uCe^{TJ9(I3XZ>FKi-3WbL%RVDiCikE)ti$F2L)JrbelY>!n{w`o=kYJ(qh% zaeZ@1x6wSgw7=?FQysx!H2k2~HBWK9^sw@9d=WSK;9G+c@Oisg_+%5X(%3(cZj@WI zTG!)c@w2y+RV9D97)cH7MQM55bWN7iA3YfDJZ9Y~vi_~t-0r~$v-iVFYu3Ycj$T#EH=4TnQd4QiXmr|eIUdFZ3 zCC;4apU-lsDfdQnO}Mh{U)I`GBsxF#+DRE$^(39=w!RGzeq(uN?iZA`V8FXW9j&91 zBP0A4boV5Q?3G(5YYMa^H_c-6Sp#(NMX?P6^GM+jWzZ*gDnoq43X<%&gNqvBZt|eQ zLa1kQBs`wM@ABig?0a0A1S$1%oX5`r7PR-A zqW;Tqfz0FI27$S_i7Owd=x?xlQ(4wIZWRRDI7l08+VjxzP-!vp&d&#SL^cf4E)HvW z6}rcY;5CKg?VqdZ_K2+wPX~|2ymEUPnBWNBfDmd%m*mq0pl(X(XQHm`DMSu4`d>o~K~-KKR3DvCynb~v&+`{gsc%Tt z4;NMhB`mC$hSTc2p=hK1e>=51Thi15< zKy}1ze!SB4D)Rr$Hj2F& z$*vUoI`cK{n}(tWyU)0JK`LU$;2BT`!X`Nc1~_lM0Cy)im)%NobY=e|Dp7SJi)LYQ3RirIx8 zkNkTpsr8mj5UKxN?QLp#Ch6(`q!sXV`5jwTLGI&W9DK~ws@i5#W&1z>>^;os@Lb@B+65D6?ql~NykdcX&+Z;Mr^5-}xFw_Wue{3}?l>sb z+0}qLRgv6uYN^F3+yrMR0s7my=t*$FO^%;ltAds8o3A!q<7lWX>$P=x%?a%$2r@Ob ztfszx?UP1l9Bm4ow-5R}k+m`aYwC&VoOYc41RRC&My$|x`|n5(5|VkYjI4gcS;t4O zZkxYxW$9NHELal7_oI*g(9Lu>2qC=soUsf~T}`=4i0<$Gzv)?cTu?&dk6uc^=F~pU z%>+ab{J2j%D4AR|8H+_wJaE9r_qT9G_D{MVwg0~itsQg1c!HHTY0khcRA#>e@$6mG zk-ROZp9c5i3;=efa6Ps6fTWDw`?(XCjbPq3?CJ0F9v3H5TVjC~?;8R=Q`N^RYQ7JR z@-*P@*k66#$4QpBLf))0#+l~gO4B6pvm{JH#|V4!$Z9Ot`n;CrfalwO`-rYgJ4V7w zHJgz`OrnYTjyzsiFz30)(SvshW*Aq)s{0Xl729X;IPxRB>VX#2x;&?RR(P`)z)N;p z+{%xyeTc_!Wb>cws4`X48w$f-%1sc79rJ{+t{wD_cpsS@u#aqKE`L^!fnJMsxIZ@*Ovwk^5(*`g<{9-^Lom zK4}IS?R3U-itauCgzse=Bu@&aJ1>*y>_-vK?;_!Bcoid4Uetg_w|_N^@m7liL%ONR&JdMpmI043XByLXDOtuv?KnlGfd4_jX*9zAkj8LW-!{jZJH%CD|L%4X zq%#VXF$Cad5+yZv0F&gboSZ3&qMo>Kbe#$S++<>FZSLtlhT(_>Sukp06{aX2?B}QX zqq{>Fs(1EF#edfI*5kpUC!6_5w1p2e|UNwFFw({T+Fn{=1Eo#--;(mm8-FnyL*fVZW*o0(`voBcCL`HJ0t&8Ja zT`d|Y9J}aYBC_x%Rnu~-|~JNZPS4yQmantjqCe280oKB z*igjuM|_Zf!-+$$fR3+OhSPw8@E-)OBjT~5yE@elYsIwbF0_K$*`+aXsNx+n`?>fI)Bj(TyAlnr2RdAKe@wnY0TBP!K3w?B~B+Pr@$PIm7x87-qRJG ztsW@NJr2lZ(WgkluWi()yzxqZMGlwjB^;x1nOYc`3ini%{p;FgVpljE?c#CQNO*I2RQ38@Unm8-;?mn{xe-2&TFm3&E zrRzIK8Qhq;V|bG$%tKhCUhi|QhzfKwiHQgFfwQYSG#xuTU z=hdhhbG}E>9~v6NDecS0!gbqe$?a9tS!&B$U3-#}(8WNWbiz=^hLvB_ulvFo@Jsc| ztJmyK{_u*{_(;O>R|;ZI&awkvB!BaJ*1$y$VtaQj-QjYrTyDogXGyr|L}!v&*}Htblr3cCLav`_(ZLEhu;AH zVI3P?;xw}EsZUz|`^3s%2uRGntl3PGuN-nkgC1d-o|`yNNxYRuXq`MHT467(?R?xk z>g>&*0(IP=l~-p)XG7g&{{N8T#?riVqeoq$%cab>7f_8-vA-@?clO+omfP!5{tD!?6V$bahWRmFKO7HGYLHTNwuLTTvX1u@UuTHDb=MCe&fnMJDokbc*Sx}Gb2ZFbUp!Weh{4T{9WFNNZW;HPW5w7f_D|23J_!Fu*deo!FtbHBZ~TVrIP*>*D1 z;}GJ$l_E5lp?wysCe2OFVjZ~LIclQ0$BW(|emre+gdYu>TNcW?Ho_(G%Et_dhY*L+ z7`XPPU{EF;9K9B`<^nn-euh`u*-xXuVAFdwUv%?4y(fJwI)*mck)#e6A4O@jPiRU#O#hLzId9Hi!cLXc_AFogAh(vsLBbPs(t-w+vqmB?B4 zP#>@X_urc~E~~qE+!9c&jR@sXBA@BoAkEGxfMjmjKZ>qwy>>a#`mtmAO+;ITXiK7Z zxun&VM}!W3gbkDk3u{6UZVTbS1Y=p7CqNukj>$k)idmD$_?yWky)|$9y@{b-9yPq&=eZ}*RIDyRF2(#Adz5N4Uwl8P2ae9T^GQCTt4cdPo|`Z$4^et0Sd8#>GS;~6z_r-H@y`EdJ( zW2do4$?=6kJ)np4oZkURJZl<*9`t{v*t)TDk_^sNMb@*6gZ+Hz0ptjoN(q>PLbU8UfBq94lhdOfB>}T}Lv$8~|va z$rac&hqvDR>T``OH89Igf;e0-og_ZrS$u#qI2Dn3cW9|LZQ&Aa{!+9^Bd)ez3QL|Q zm9V8qxv{9)5QI|nh+scGKDwi_RC=qi)?tp0Bi(_ezOd(6mxDG_v(df# zy1O>|4M&M@J_X9R#9pBQ?VZFl}=e(QiL@DPE(c>g6^!4My zIqyCr_c>GyXLA{cklYOJT+bE3TjD4Ae1dZQ`kLZc0M@GRe)K<*sW*zm4sBnd1za{- zKjcKKw#jHeL=~=^J~Y&WG&qDsEkZd3N8B*FJb&RN-R9vFPEVyKkAo(w{2STXO?Ji6 z*&x3~2vv}AbdA|#Yp)46TG*+41DwGq0wy-#j(*16BSL!t-OwG`SoKeq@Ms%t(Oqkj ztGUig$bb`V()7rL`tqK(9r^g~xuu`!x*vtMF*`q6hmLl@7ovEmE-kUbsGb&aZE@_r zOpsV*eSFy^Mr#i0|2T9oK!l%HCEcR7!rVL5v~Ieh?y1M`|1UZJQ6{S-o!b^x9pHpD z#=VwQuPgx!x#y>#On)fw(EmpvoWe9blmB#VZL;uuUrINNmJDqlYoTnJ?G+0T+BZX{ zFMVo0!0QmUWno7butkn!F*+|B^8z+n(>;gHRp^RQS=U(iENFJdR7}2I@V0Zt=B^T) z|5{~iQ(ZW3?Q&T(Q}AQeyXxj^qA1%{!4Dh+Rxn3U9hSuHw{h4FD^GX{7L7oCiX!FL z7O9i%eVKh0o^84*r-&>jWYQpGBEVqA&kWyJ>cc52qK*f|M>wn$ZhX59*PFCcFL}2+ zLs0HJ57+0Zeyhtflp3WHv@jEvM$7BfN2MX=)fX#a1oeCo5iS9JUheR|$h1c14NXn& zQIQhcjZC{F|L=7W0egBxTy;vr-tw=N^Y5LA_m=xyw^t1+6d71FqNCL)FC1$(s4(Ku zS2rHrtFB17>r+(F5OZu_;v0!8!2CfnAp~`mtxrrAzx&z>6YQ)7<+-Z+vCM$XhorFL zQk^Xc?uz^wcIBhO>I*Yh_Kz9n5{8+8;tWu^YV)mKnYx+1Gpnl~NQDirI{cnfsGd_V z)H;>P|9C?D47BxZ%_#GYpa*U!;U}t=AS0Q%n;gQb{)2YCL9Us;2`SLsOjxRW*I!%e zFcN#bB97oMKO}+bk@MVkvmKbPF_7Q&C)lC+^iPaM8iDC5vR}rOl+T|5a;Mcm7Uo^i z)cXPatMoxZ^abQ*fDZCU^g!0dzY;eauE`SKS+U;phcE)$vK2UqddCcv4pm3;RCm6# zA34kn;)uXd*!PhIYLr>?vEOzs=lZcvU0TS^R3zP)dj3P4?yJPTKi``==T&>VeG=i6 z?yvZ6_}XpZvPix=Msyj{_J3Iba$M0NnV|f-%4Dq5q3%L?&vifj3YJCqk@z#tQS9d^K22ytsPZ~SO3V_cjb}R@ zq5)gnp{__B)qb(W!ikyO5=$@WYU;Kbqm1!-#Ou!{R&Vlz*Z1{7lJJc$-gcwhsn;cy zMYInc+sf94uf0&rPN_mB|3w0Q$A-FUz#8x;GO^?ox(zeDnm^3WkOj#=Vq$Vi-;TxP z@m#OENMhf4=3_3XEds|1_|G}4hK>vfBwaAaX8>)+zOmoyh6I*W*puVj>v1x1ubm-k z%`f!-Yh3u>bTYFH;nS&`Y+He-_#9B7Xg4XK{7x8)_*LwSN@X#|mU7eI(MN`D@?ewJ z2lR)2W+|&eS?eI7Gwr4B0V?KoEJKo)) z>!9*-<(wo5smZ*}O1--`T3GH~aqRY&Fe83}e5<~j#nXR)=DR06Ep_i_)|^SK?dm}; z^GsHHMpPX3es>vN&&sWco-Zc#CG3CH(3rfQ^xG4t!E8Z9wTSPpuWuRrBifpYlyMIj z-HT{(E+}tBDrR&;{uYA`{TfE6hRH%|N-|^B+d^NK^g&QlM|qgSIG#AsG%7>1b)1s~ z!mpM*1`qnc5z>alqU_?vz$t4p#0w?lAx6f5?gcj^7F4((*^3s7QF>wS^$8~oE~eVg z46mm8mmo1>qnFI}@ItZWDZXKs6O|h>Qp4mS#wR18!+TlXvb}qhJ(R4q1w@r-hNx3; z;lz~%>L^W-gRh=~AjxF2uI7_jN)s5&>Jjv)YHEhPHtKMkZ?Zr22 zaC@?>&(YzjR*m|^RpsY@SIPJbGIk*;H-6$Lwx6@;nm4%jt3v2&sGC059i&3E^dbEX zwm(kp5?^hx*ffq>83%A##esh(aqlPLvd0VS2&M0k%~e@c&z5C}Io8hI}6*H-zJ+iQK^jUdL?y|BaX;>~nSATSk)p)jo3tf56 zy7b>c&rbaOSuU}Qkp<9u$K>qy95@YJ#!#ZpIJN@{-LwSy( zd&Ec4I+TgUQ~y3%-J)j@`xmcIk&oOg;I_@^l8Xt-)Y-e6f5(-!%a~RDkr+9g#g~JY zuY%i(890KwMR;#dmJHh2`ZkaHF%Nflt3)77+7nX=|DUTbjEw$MLojpaazXw4s!6yh z3xT633w&$Uk2jrhI=pC4!iJck<7b&=0$Lh#eh*tV<@u~J%3#n`(RK8GuxsCA&;(Le zGhe4%0F*1EhD3Oz>Lt(-#uyacNnsiOQ28}12nE@~Q{D6!RE}L9rBq-Z zZxgK~V8zRV$I@xN3<3j5LY()3{Q_HNWZ*t;ma2iThrl!C%$)a`{>4n6*c#s6@1Rir zWUBOx=a8uMG?zF>58sg*XicE=f#;xYuDM2qGIcxQ9tpj$c`>92XL z*pp{0iK}~xriJe0{Dp2jCyc3s&bsbRP8q7WbxX?}Ej6@GRRFfd&kjBhBTAF+^V=dL zXV(@~yiI#X);e9*I<-$}dy;->C_haoTQVyVq`AS8i1&Pg1`M^xw2Ak|TD1;lmcJ7V zW@z3No=~IUtEe)?I}^yElW*(AO>1yavoJU0WBeTN7}zOf%n~_=_-?^V-8bQK)sp_o zC>3tIk;aq73+p93FJ~_k;~gTdml`=fr0a1L|9Mg)GnF5saXMOhdJ*pnQ|Mioj}J{1 zeXXV`-L@!&FWz<5Vrf{X_I_)f68_i%c{a~f)UB?3ki{3q<=$_4iPL3+(u@>Ei1w+! zm*3`Qq}qN6=Te_k#l>HbQv+4b6}q=mOId{+*H`(Q+nh_e3nwCRB~d$K6W<^?`S&bV${&A3e@)ws{t= z&Np4K01j}|1`O$mE0Y{Xug{T9otjb%iuD0s(Hrdv!Z@pT&ds-|Yf!n~5uTnjZv;rV zF5FZ8DIYblOz%3Y3fS4sFYw&K?rhjE+^Oh(x?_GbhURFHZF~hcaTVb4pY(X9^W+}p ziwUm@YF)DhKRhhl5OQ5lm#6V^u6>#ThION|8b>v=M%8jKz8tL{Ewcc5B0)(V5ClQghrMU zC}p0rN^l``R6?SBTsxHsf5bAATy}z^_>=PQ`IcOjFj0Z@L^rgW4_c?rX-vSlMn~6T z?y*!fMXmT6W~0r%VPk;csVrbnz=`E*!{D#c1A@uhnsw?WEKNW6#m)-lv}?s~nd~s;wVd$3%^BR!z@| zAfJJe=c-wJWwpjj$>MZG_t%8%HWw4PJ!!ut@+z#J>`Ta|ymf~N52dAUx@g&MmYUFY zu?(AcDmJbAxzEk=|NSo2{mLr_@fc4moc9b%|2cj3mcg&>+)wY;vDa6cenxX>m3F3Y zDsm;|sIK>}OyPamL9Diq_eDO1=5W_4AeflB6k{ zN(9p7kVu9NPR|rCZ4_4Z%C0L`b@~s;-H#;|dbp2981vXit+axMOjR+> z%Qn3kyEIJPqL_oY6BFX(Oz;$AKc`o*z>BL!lhLT1YqL0%M4>eUQto{y(($iG#%QbL zw;x-52u19T-0DZc1u_k!+ma!?GcT<0{R!C+w|ss}{NnFvElyP*GhFHtz*{$xrB&R~ zOrh|SJfzfGVmIG|_#1`2v%d+^C+&u^1br4}-~~*|$80Cj$+#Z4@#Ee=ex=5k^%8{6gt zxDb>;X$5Fqw=tq`-_3d7#~U0Eg4s+E1Da@i9Na9B4cjPxt799c12{;JXoIUGJ$&M= z{c}vj$H{PfMAZ#j%M|FyBJS$);tR`dH4=iw5cSRz^df_a5=?4sxBkJtCOwi5$L5kk zC`yi1PCLvxXhkl}@C^v63wBb6dE52bV0J%{2lq#jJ5lq)%~gNggiu7nsZ&IFg@y|S z1ht$0BmMuAn211h??gX4#(*yXs|5gV_kKPIdAAtQG{D347x^xY%jIExf(}KB2QFaX z*ucZR3rFa>rljL*8pF&!@gO_gb#y}+-4Fg)@G^?_&PA@F(~p+7>$Pgb=e&+-E%TfD zz3su=1GK&Bp}9)AM%MRX4{1j1Cl%+uJv=Dgt~XbY?cw}hJgokYGI&=a0Z6x`rn$Wv zBe$XLHLzfTUF!c8!AqrhD=D}&7O6LeU-AV1qbXzR^MdCs}{86L2>l^)%hfbdAxke&&Y)?Pm5Q@~MQ9(m22=KeSDh?+5M<`qKnj=(k9R z*i8`uWi1rc8RV!@xh+hqAB4Y?QPLV^VyUZ;yeS3_EWQv^Dz>8otIf=@_YY{)ZVh7Z zG*sUg#=AfpLMX6ZK8S>hLFFGSIe|FQL&H5vaXzS7?pV?{oJBw1|KVQ8dQ=(E81#RM z+jKRk*$;dL3o2eH!EjGyM$C$}^F6=5dc5xxUal`~Hw@1jS+JhMW{%XJV&=qU#YlwH zTCcJ!+ClRNHhghFTm)8-e4C|6QErI)zjWS`i$ui?6x%RRWnEpeXirnJ9>zo|XcYvS zL>a0&@o(%KClAZD9+8Lh*O$ z@_6q;O1~=3mAZ+)d#yPLq^}T=rO(14ptv3%l50^+oHTtK(+u!sxDk;qZ$sTH&|%$Q zF3}4dM)vYt#br&DJr@H00<|o-I2rS;W0JT*sOoC=GU>5`1&QP{kwr9^?eq2PAKRA_o7qoF!(3ak3izq#(J9%K7synS{0chUnmM3$k`)vXPf~z5 zywJTwt7eSY5xtSRQW-!?p0;sd6ycf!c~=Fue6yjS>LOG=UEZ^UylwkN&@>ja_5-Fz zM#EHd6)}A~X*m3z=|i*(S+cIzF=Rl{jDTEZX+%yQhpXyP@i1ii zPKzWRn;Xs8F{WoF@v}#bK%VyPLm_d1X&$q|(Ld4>-#K71&1akFylQrd`p(NTMUCNu z;pKw1(jnru@tJHi1*OaFgZP3|LN?1wFAV}L2`?XW(@$S8NVi^pw^KKmTUMuWd~tBd zo-LHHMGPY@7pf0ilcoA$QTkUTf$s%`m%i6LxGa>?eY&ZHH5wb*)EdWg5Tz3m2U~3{ zA%(JbEP|m3n?m_~z$GM(R7{eK*vS{EYH9!*=`~3YrFr*gzXRi|uSf1pFK=`HEO87= z-WBip!9udr-smLHqsnF)im~<*-0c9lR`&Mf<%ka0MSUd3{Z%gYLzFHVMnbr)ooNLj zpMUw5W)tGBFj5X3YBw3b9!ZP)CJXqI0O2;B>T82?_I>6fmDKdp$JVrYzpq%-nP_VUB zy3%adIe<<bP`MvSwfJUHly72T@&|p(@v<)rjGj&s z@OtSgaB6fa8B* z7McW-+pEoZTdTAA0Z27?g{XQ1GiWr6j`ews@aBM+A&N;L3TBctq*l^pywcUhezJV& zQ`OX0lk+Z{1CJ=KY|#B0;6vugD<*~*{BH3c;_Rb|U~heXLkfY*WAs16FL^&3-Kzi~+nIpNGe9^WE^s=TOCF zD}!kE)sPbUPaVcn?!hwgjHC>{vQbT8&4d$hxK;L_D9_A&WG>V(+T=43?Z-agMMruR z-#CmW1^Dsjg|9pCDF5VfJ!=h;%if~0{xM9jLtcltg>b3ug$>*IwZJuD@)t*csmWJ) zSF+aM5k@~hs7F7w<+s-Sn@SUtFlVA|^AK{e_7@2Tnd$m4_tO0!>v6A%L(l>kq*EzD z%HHrew{7h_J+m!3xlap*Oc_>8*pY?HTVg9E>35`r=NJD!Wwc}0FT^a@ziPgnj&_C- zU;#agk8?gFm$V&fY^pPCa7)ffvS03{L&|0n`r0}DY&9JJxonDmhSj62d*woiTIwfZ zk1L*8kTBXK%K1&y+TNo7!qxTIPfi0|_WK|TI{6MdT`cN>+qPbHN05^c+P;04NyQ(2 z6Tmt<+|`;r(RY-r)qlaMK01(w>U(MMi?-nD{o~ae_ zWN#aDql5zV_A^^3;mJ{+<{ha{5+;Pl9^0CZAQ0b#@Wdq&xNx_SGwRhOS8LD$MW`b- zVmGkKx_h!jVB4rSdjsL)KV36F92xEe6ez|8%3Z|oU;%Y$RvPF6Rv4;1;Rq;*A0z)5 zRRLM|P|WMim86>kxGXQCsq>3Dy-&Gu!_i_svZaqUy6U_=fhE zS_Ag2QOY?|6#bna?Sr<r?ig4pcMxG4A9SeIIAm6s{#<;^LllEe;L&agP%jLu#0G z?eT_7$Lko=aGSo{HrWFbbpe7~*elzSz0lNGhn!oyBSe@R_GFvqdw;bLd_6O#Id-M5 zgTn9rQpnF0yne@wKCWGO=T(Q)N8@IAu0^4AJhwOL927pJJ}!BvNf7kW;JhL_jOEAN z9(DK0#m+ZeLC}lf*SP&R9cj7Xuyp)^YR6@a8E)0Uwoh8m80#$J1N5HT}Nt z!*rKSV1%TAba%HX(%lWxNR4h086`+FK)Or1Ye<812m@pw4Wsk7_vbmj&wp^gj$`+| z^SaJj5Myo`q8e|%nK3#irDqnI+C(v<#;eFa*9cQhmjjU&D1h4?~F?zm~o zb^W(A+#AmPi3Dnq>{LhR?mTijy3YHVf=plkmqP4VgbauD=Vpj3qE06Xo1hewn&q_a zq5O{%z`XcBPTwPNaQ8yQGrqw zHv`RWA1pSlOsYc|N3fow)B!w04Mr!YLZ+1y8?x;RH4ZgH(?LAY4_I_*qIs4i&m1SW zTkR^Kzl!Jw$eSa#G1g{RFMe5trY|wv_C=3hpY3UZOWK}$$u|e41e$><2@t*C6oXm; zc>G0m)j`Qd=AGN*&M1UPJn;^;7#@m#sPqui;SS^ZO8<~jxkJ$JitcRj;qCDm^WdZ2 zaO8Wqlxt1jV@a$GT{i5h_+rWh$;Iedyk`X1lYTZ6TRf@O^5w>E;am8H$iqy}_Dmn7 z7#K@+WI-!A%W@8muY>>oq!!&&oVG|3yJFs$6lC4%D&bJA8rgW8op#yezp%CfAW{H| z5P9zF*>K-fe0A(vwB|>waj2a4);1RnOva27E^Cpm-cq+K-wZw*lyO+TqR_sjXW zSEB<3dX5)AnYRh`HXprTSP1zQ<6KCjS<&p%pVngQwTP<$zuQ!uljm(*R_Dn|a#_c4 zhTInPl^gBa;O;9sBxUD2Aryi*)+3G7B2w;2yg#4d{;fi^6|h_^!Ad(ldk2}~`Kc;j zJkxB~#@mxhL^mzpj#_xO-5QF$i;$CVm~aEj`G3ygdjljTV9?KKTJ!RWw%yqlHE*7- zrA*J@1rBG>zoxVRg1^206teRA?icec+5#iD<}3xDtA}iz3|hNw}l~=a)C{|iCJ{A~|%Oz>SF>|oiPfN~o=lwD- z4l{AH-yArzQT~`wYKk5Q(QDeHFuH(W+$-G?aaPs;WJNh)0ma;r^?rH8%hv+@QmVC9 z+ZT=G1FV)WQmNrx0e|gYxeCI?cX{HJ44=2u8;Wc?S>pa&k^RseMhR%DJN|tuv}W05=){S5u;UTX`_}cTI_V zpfsgQHXys+|E^;Cl$E=aoT)^Rf-yIvo_&%o4?QPtCPquZ69r@rH6Og*n>)$E4$B<6 z8ef(^;h5^-+;5#cYSR$6pw`RW`-h?oL5e4ks=Us{eV1A2z2I94_fP*Z4I)$XaL{|O zPuYvDFLao+-$CBi5h{t!5N2p@6Ke|AFVc4oBSom=vmAvM304#-Zv!FAs%cYaGL>O$?o{S#oI1uvj!i5~O2=>bYOByl$l< zxyTfP`jXLg;`-#jOM75C82-u~-d1JC`)(#^HtW}gBdIj41|EcZ$X0@XXt9c~cKY;6 z5j`pGUr=w5aTzV0L-*AjuvEcf(8cXl8Og3_@w6XM9+`OY?qYX%V8-N}-vj5YA-e5> zBG?d-r!zH{;p=+YcwOX4@W*^T_A2Ddgn<1q4$b7yqixndmC}BE&AmfS8!4&xg0!TQ z_6PrJ3w)$Il0m|V0{W{An<=%?+2QSfZ;%4*f3wvcbK6c;F7M&(`sDkOG=kSb@ERko z42%`a9uXonnoY}1hyP#HZ=546T{M<+#sQS!;bYrQOg-N?ZW~E(?z-}J9*KB|eA1o? zA4pH9kT!zupSr_rx{hLwh(}{Ro-=NNbtX_upB@JK3Zhp;EohcC$jdC#o$h_oz{vD} z6Z6mQ;0R(WWb!(mnpMz;Espb`TS)fdh>lT-PVp-3Z)&?Wm0xbxI(`=JiFwETxdg63 zZ__t#Qe#)cvcS*BQayer@mGicxJ~|t`LZgJQYDGjh!-?cltuNgG%HEMB;|1)j`et7 zTx<;pN4&t665F#5;}VvOJ0hu%PL)T0ZMCpmq>IfS@eimd`O#XQmmBB>eP0foAh!W{ z@Ygmv{ zoVQwT@ZI@A1K5H>hoMXoh#@g?CTlU89(P#g06C}Mct_E7o^t>jz@m#s^$le91tC)_ z2jaqSAoRU{`6I%L|EC3z2A%K@yR(lSfWxk9mL~?+TfDOSo>h6f9#<9)ZW@26%XD0p zn^BeN-{uT*_4aiA$8H0bH;~>Gu2Vrs%m0KlKXy8N()BOYo32hOnAM7#d-dtdHMKvg zpB~ZByOjj}`Ier)(bg7@6u`Nv=V|r*TwKS_r4FJ_FzSb=B@2hSjhR66cg7!`V!luX z!w2s1c5v!g(IwTDMP9h=m}2nGD2gfpS4PSX(sCO{$Idkn&n-|8N;>|6V;H>O;@#v+ z_EXAvAu6kpE{hhFM0{*QiFehwNv;e^hB#k6%TSNM^M`SM2;SgSs-wGXRYZc zkML6EZe{uy`6B(Qp2{O383NO8Y+lojX{EnncHC1;2>yw(2uMo3Unl3V=`}?M znX+JASrfd7z{jS(uFKHpRZL`pVs6Lsl{Z_K?Yt&d-F`^uK7)1Qbf8d=hfF1~c&`rK zetzAZXIVfiqBYusb=Jtp$E0=RIwdn~RUblH4iMcNTag#ySfcV=I~VU0VrkZ&@Mc1ZWX(chN|g zgVZ+yj4bT6F*K5X01AOmTeIS~ou~k!+2WaM{c{*qij-6@_rn&5_dAX6s#q(arF1kGE$-a>t=3e0z-wMAl%17u>p`kxoi@<^7= z!&_f?#!-rpz*V1TVA8~)jh9&WlmEDxFf?6^Ol>^4Hcy<;{vKpUmi1#<@!P~E${uK_kO%2?3b^cvp>8l9i$l($XOP6SVYnO?y^ zo6y%zV+FV#yQ{gPaO}dnS%59VvMLu|O)k4bFLVz0=CJJf8N8}dh>AfzP2qMNMP^RX z?z-ChCNeIpn8vL@q%@E&LAWsH$=s)q&ithe zeJUHIo=~bLxg)i~Q!KgJ@ivIxZ+)tQz=Yq=e5lgvx2^!z>8s72SBuTK&b{bf=GeA< z*~|Z=0Kt$14@+Jw*KU8_sk#XPjUpKKQ4z)jdIiy?-SBy~((~SV8gI$#&YfL@NbNb) zEp$hQY1c^u!E3IP4B}r)1?rd{pD7Swj`3Ok+U`|+qA^MNwuGCIsUSkHuoh4V{Wdbt z!S&^EzP~if&6hrgJ}Lh0tZ^M8IVDy6x(=g|4E8Bs>0O}?N{N}*L~-*auiA%Tjd;D+ z&vyS=MRYvZ%E&|~+KI&wUv2Wj>3>oVru&=dU#?9~rGl`}^oXBfq1XGKuD;*=^P?I(s<*Rzwj}_+ zX7G&T4`z4v(ElxkWLe$#e|sZZ!Lq-98ceC{7*HH=ex0FF-Wp`VO1uJL^$({E-p5E| z24#Gy#<5(d(nOT^<*!$L=E@%mx z$5`Zt#%D479?TQUI+Xk4uO8Y(9w*{^>4kBctb~Kt`ic~ubU!2lXd5G)t=Wt zo>cXB{H^$BhiUA(yL`D3Fe>v#PU!$mPKHRkhI<%)^E2W>Fl(XWOF zqTCRTlu~KO*y>FHGH0KE4e$QFPCl|AmpWr$7{uduH_urF({5)q+!x=v^LX9ADYbcO zG}9UXKqVOd$tS;Q5FgbGwfjePf=jK*!1W*PmTXVOYDAV!8ufGFhIpbS(QUJ@EL8DZ zkH&euqBrD3^85CFqaJm0xt|BKbNR5)g}$a+;MTHMKj>7}v~oSAx_GhUMhn%ETX%0< zuNeZ7^Agak@k52gxxX&y4r^1jRzVgPy1bHlzvo82u-N5k`A5XRpsewKhQ$ANmauf+ zy_~EYJD5%s#&Z#FdH;%d!>jAa1f=oaP};K*jrTyjU-8ifxXRqk|KEPkR|ioN z^AmNO7N&J_`%mDzes>bm4n?LKornG807L7G>^*Vs>hp!bfBerX*|2~V+ZxZSJg4q) zT>j1leSS?!$Di~a$1?t1!*!n3nCb$OP*UJ2O<;ukeU z?Vj9(`3T>2qy0P^6Q3HK|B|POtZa9R7&*l3b7Q5wgboz1JWs7>$Bg+b_(AeE0-f68 zjv3v*aT*DuMb!5@pN#=bY1{xes-42ImV z1!~NT`8Y|OTs?+_1nodps|$@PDr+Wn>DH?+`Q5I!d?Q6(fQc;9K)h#?(}d@yufH8m z#(+vG{HQwfG%4?-Pj2TX<0aeYCa@uTQ#3Zjar2sVIFz#0(++{W2(;#y{ud#cfj-UY76Tg!6@gHCSWXr z1{I=G-Y0l{@FP>-bK}n0p74#4J!#Y_P2>oDL}f$A;y^FqQr6J614bhjz0k1%c6siO z&ZJ|FSlCC==Tji*i>EXVPHG=#v&UNzm=R{$ulwbBG*#WdRLVC*;b+j@KB~O(y9qHI z!-t%4#p(3YTf;4a{Bl;pXh<~1`UC|^SF0U=z?XazeAo9f%c84gj4Zgk)ycqxS3_x7 zG#5GVb&C_MzIh=$e!xiIfkuI<81iZ1ihX4k4QtP`VpQh-Z~A?*3jK8n1edR%9eyEV8AzEjoYwdxRAr5`(^c z7?`rPruim7kdbfnpFBgyz7y(eEf3`grsPtRfn-%*YVwE__&*8)W1KUtloBU>qDA|&*OO0k!`o};U=fan0d6J3MNmQMhT~`2_dq6|$CLZ$j>%6~w zL2oOQ6yS74d*LdWohBF03cAcV##yi@rOJRlt$6x@7A zK(>5(GoG1zvpL}f7~qxxxbEyz zKM?Tc`-e{KRF`@>iq<(pT?<9n0G(gg)R6?azN$3{!|n3~#O#PVZbkA-yKQY8E;+K2 zZ+`Uld9hc6{j<~9HdpeXE&#+zcWk0+6U3h#eb*_v2NR=-=@NY#9_b8#n16{lD1FI~ zXY<+FF@_dQ(jVg^>p;7Z84YGp77JjYP?55@J5>m%=GVvrF)^GzFgpY#q?%o?JH?RS z)3ms!OI)OMs&CmxW@E}IIc^}cZOIOgt{;w~(X?Y6udX`HJQ}^$$iv?c^LE?T88ilI zb*besF8K-_72J9eHB0Hawrdpkp-S5(JS$kgg`Qld-t;{E&GlV}dvn{`g)oLWX#iZ% z=Yi@CWZ!5w`Q-Dv!;nqpm4@hFGA!uya!Si(3=iK!ZBlWkasN`&6FZ_USt_ee9BABL z&glGehs2hA#Of9dqur#zi06xzM;$!itU3zG*37rUN{>YG$#D3oFIvgRAS7p(MgQg1 zCLh9ZsgGHO8gOa*!=lV`jUv~Jj7Dq zlpBUQXki$xv3~D%f4l|x^Lr-7&$%lmkLjV4N|flK2@q;$a6W|KqwDd{3kWDxhp2vh z)#KX@P}&tAxDpuIOU~P^w{|Ppc156mi$^W)TmVz^no|z{V#Sd0hF*7yE?@ze$=`qE zX(c7f+yRN_T2FedZDu@ol?3*Uune zR~;?d)hU0n*1Pz9AIU!#@gdz6F(V z|GVN;OpDx04gYmcoZCp;Xg_{)3YlQ}p`n>#W&TE0mJRo_h)pJeJH-4%)oY_%n*WrW z0O~ySDVlGYKHlf@@CiL9Ao;?h8o)H;ERY-=(s+<2$@C&$JUU~rY*1d`3sl0#vUOzh zRY_IX>W5)bgXZ$6E3xyhKy&y|KqN9aeKPTpO$y)Ap-@KA$2 zhs8D(sxDwe=7JU)=nQ@6&nj;NwksnCNQ84V%Q8}e!@YufjbIHtYb`=@LAT~N4$=L3sJ=Aabr z!*Mj)pqU49`u=l=8QJsl0Xm6vt>Xtj)U+EDxULp+I4Om!fLoZ>Q9Hk(aNLxDdyow` zzez(oGUlV359h@zJv;gWF;D1qS%MT#!$hPT4K>#h+#}7$n5nZ|q%8p&-3&8@hd8nPD zoZgB}4VW=q3>CU|G_glZgb@SQ4~8dNOLezo{02(#3vc_&Z!1pMv6-qUB4f`uB322B zGH&o`SW!M{0)FYuPEyk$!gUqJ(2FbD?tFFDW02m32_ogP;*HRA8wSTC!oOV&U^!ktz}B@IupaH9NcBqNv(oL0=1Ca-itM zFLWD-F0koETcF%Z=Fh*VOZlq&2E7*H$Gxk+DOFaseB(%2Hjfsx!1S78-JlHJB_5@K zP;{1lmGQv5`RJ309qc^d}h!;>D$o zkJAwB3xKroz+2mAq$M9|+`m}|(Q&AWCeB3;3l!ia*M{bd|AxGK=v*&>d97Sv)xO(?hB;= zsm>Qqv>Z=7n=DI12pBbyO+Z;njZ$qhlXv(H8vveB7Zq!p5S!Sus0RauZ_CDzpFt;vJT+E$o;2*PW-f#O)j#_mC2UUXSkUrgdM#w*?WmMQuEXN;=b{#!u;dho7vb4L$1k$VEPHWeCpZe+u8` zBv=%+eE)_W8!OJ~VS|Pr*(P9G3CFQ&BXM$isg~8i8}f=3Jfdu45y**8w0OS)`FA6g z&C3^O(_aj}BTeyQOJOw`TlUU-7pZV4`|u5RoJ)NKaJZ4={)l`ar2|00S)U4HsUj<1pWX7R$s3;gQc9N>2$S#Nwi*4CF&m!uY{eADtvA{Wtw`~hz3t9F09`UhF zz{OE7LMRoLR|T5~@JtY@^R>U0`GzuDmZSHQn4;MEVEc_`G z!BkgFCvTx;lw5=}QqS9>GoCmsDQ2m$V9`|Kfh?eXa!Dl{`0VTG5(04;W#m-W9QdSZ zumk_(h0zb&@4BT>b{F^ChJGS_sliuBq z2egl=gOB7j_a{BmLBgxF3oFK>rG)0;$OL}jB?pT8oOY+ZfxruM9$){~GYydy5%T*W zZr!E`1B?Tc@RpzB%-P$P?xTL^HhB`)dp4wWG<3V|+^HU(-n-`2r$YKr&m(rqN}KSw zO0MyO?i?7|uiAUML`VWHWgfZY$E`0gO|+?E+$nQ#@TJR#X)(9cy7g$Wa03$*Rupjl zjepDOYH84}PRnv~v~>D7lbKJadcp=;$mrlkQ9`IIu7>Xlt3_F-oG)h%hyHxKJx47aL6xq7R66Onms z7OD04!@E31ZKWw}7D@Gb0?NzZC2H{<5RAEQ2RK|Vj=!=Nmy?=qwi=FZg*sv1OZK`{#&3nfF%DLZ z@e7+@qC2^iOf1gU^UAt)v!-~dAs5}rWrE?6T;u=#O7;i=1lIRyuXL>-j$9DuiTZDK zS3X8-q1qn5`mDqtK5VRW#=O06*sslvYjAWsyN)}+iDEha;I1sI>{obVO;M#>zOn>4W&L>}=>{8SCbho>(;=pXr3F>Ag7+n{z!W>QG2ka_1 zf4n(l#?SyIVm@o;33SRs=T0whM#--zN2Pk?`hDz^bg;|qgO5G?cb#c6_%ifvz@dd%G2Lgb1U#YDmpWpw7 zin+;M*GnO`2@+gYZD#PHJmAA*LcFha{nU}Iu_nneeCj|?wSO^8<9NyO*@YqTkDkG< zPA2XjG~EmP2qWFz7F$Uth{`**Kn>=wpqih-9cu+5UMV6W>w{A$i?|RGknC1?#dg7a zSAGQ3{m&}x&8gRJDL20+OLf8JPL_O#TPe ze=|z4^H$+Wsmk;4{w;8U*m+u&R%v?HC!St^S}ZdcFG5MCs^D?SGisWA(J#NQ7?Xbn z)I%GI1|xnz6(6 z>EZQObuTq;-s1L`T5CzCQ!;~{vuL7t-+8?f*N(aLG*G(aiO_a%FW#V>7_ID~u?hUW znZn#XtmF6s&cdM(iYDb8cn5KQV{v{nhX5%%)v_e2cD9^xB}f}EGK0Kix1Mz!M=EX-t>G1B09nZ(V74F=}i4D>lOYeQp^2(JQKUfexp=p zXpbeKgRm>v50=A6e;dNae<9raXhC1w^B1QO5>3X`v}i(V?DnrhqNK zlXvhux@=7Q*YF%ZW-W9uiaT8@9}PNBIhctBA`JRH;P>hw*eR&6boB4AyUkCD(z$u< zS$Hs&dPS8;y)=3X{sI85iCRL~y}L=LM#DRNtrq0xokM5pk`&LGs>No>9wl9^2W-Gd zkEU*vj-+9xxa(KVNr_SJkb09Wie%HGN?EUnzmkqM-1>W^l6~#UacX6q#juj(QwMU4 z-|({3P^G?%aFdF9@~4{!KCk*RgoDa*B~PFweF9d1i@qh+Sb7OijbDa*w0H1&Rfok^6^AC)&7C}=F+97 zf$(~KbTAZUT_qf%=%4gTDOXGBrEr|EU z!MLZ?7IQ?U4XiQG*N{8Pnn8y}9Vg)zXhBlL`aue+BfTT)ai}JDWM&re&1Gz$igCvn z>`Y_29pA)K!whz)E%fgUQA5Q*ynOM^`LxI%@(B|no*p*oU(kk{8t6mdUDMzC`N}fz zRZyOsvV@%1Vn{R-#mXhO{D^SInfV}Bl;tz3W%?kxgvj}xbqmiK&4$}45v&xqVE-d* z3`i_?Hq9!s@-!ql+$nsblUVu5Xv+wqe4-=_PsnRQo}jOlJz>D)K2Q&{>^7DHeN}%< z^1j^9n0nf}+-WwLosi)CJxd6_P5fYK&W*@_du8L3z(sUpBHk3VjG0M!6@;DA+I}oE`M0v zKG{fp$&K-~%l{gbFCouv9QN}PMObzM=vPD3^lOTmJ<~?SOhhGgjczhD`QcCW-{)rS|SnMI>%`14+XN6$PIY0J9Db;5_$p>BIW zvY(gu0gBLHlkvXy)_G&m`5m;==T6B!ufke*7^>W-P-T7;gI4xLHzde#_Fr}UY&ZN% z4{d%$eJBG#uzKVE`w!c*BlE{A{~E;%$-gXkZhY4l*`5X$_96GoFjV`B(sWk`4ow8T z3E%xK23fzA&i-=p=Q{k^by)enXX;r%($Dx^@2bvx+Mo7i*amtn){_p}^A;rjYRx)# zDrlv_q?WHWCaL_6I2f|go`jE%9GJQX;i!blJ?~3bO;`LU#iAq15t2Tvc_tw%Rpl_nN^*P;khoKB?WFU|nROADmyCx+ z`boNGu3j7Q)Z*yKSc(@S6S2D*@5f;)EiIGvi^L}x<+3REKny%$QcUS zdI3SLP;cC({*6Z)#Q*hMl4)Ia@qO_}Poei}7SJPXR* zMJVK`89lpwhVe|?Ih6N-E*dppZ(y0IRS=snrT=hwiIu zi;x|ZVv9FY?Wn2aZCjU21hQ;w*v^tSVW^=O>-uiF7T3&kox&$Wmh95nNb0 z(&@voN_z)SKO)MQy{ta4k$F+$L!#Hg2lF)hb%hY3nvr2N&vmH)qc@*g zdB+7P#vYWBxNctWKXB)H@ZZ&YxAghOz*8E&5ub>NdEbPy6~V{V9Hfq(dMobn!vphV z&v(7OJ?VdtGViYssR;F2Rh{8%r0AO^=Q@$2%}pf{vG>iFR_hTCDU>oi^;Dvkr$&+; z3qiTH7LM@e=-+8w#tuT#*j0k{|JF?o-^T^3$CdwYS7|}^P|^3PuN1JIDBafA-LSN~ zfIL<%wH?E4Md60rGAn@tGCUY~rRh7J2t3tHh$FPBp9M}vEYN;7U8Qpu*mBLsT9{hb!$-Bi5xdf4Q{ znj&wu*q|I(C46`SWIJJS3ol-Y+24O~JlOTACR>6H9buiYaQ+P$8$^G3Q+wUL+TF3V zyENawuMp@R4|oQ);v2@@d=+~dpE^&cd_!uvpjD?miDFQ^XF33$c9L}z8g7w47w@$Y zXwfL$fLHT}HYY=SX%VucvZ-hXU* zShWPM9f^sQVbz(*8sk=|=T6E)CIfZ5gHcrTah2-2#U7kqZBCDG1a>81<5)=7 zgsH^fa_}PmEL=4_0};V%GhGNk0et%WI(?NDJ6nh^n>=F#dofW%AcUP^3Q0q}e!Xm# z=bl070B+!jk(K>#hv#X6HG$ImCd>W8*_NQgBi?<#(GVqZ@m>K-L7IyDV8|z*izFZZ zL!6V)_?Iw3dD!?ceU?Cwpy6i)!wi|& zdqLS9`H~#eKSF3|=ej9HGwvR2g-zO`tjH0)wqFd1s@vi4;%b5_6V6$S?45wT^Y+1d zbLe}*n&ehA4-C!6R!i*yV)?_xYXDj~E4uL{DL8=XOL71;J`*Lzo95ESh!+CNe*vl3|&h%C6~5a z&CF`n{87ihn8Pc0r5C?BSoa{QP$R3vwC3>g>?P(HUrn7Rf%`AmCwaNAPomO$Os3A~ zM^(H|SmiH=Yph(HJ#(>13!i{CZNu#&7-uB(@T zh_|eqW4a1&(}Jf;n2-0!oef3*w5ia2Z*?A4?(prtcR@1f;i%?lYcQ|@T5S@j9GQtc zmc#dYLT8QsWlR=7Pzxnp`d~0c6p}8=eipPPYA%#;sV~}{5#82de7Dl6A;rDp}~x)SBx+7uTM#!yR%fp+$^T}Fa_fM z(bt z0_JeU)B-kwSnNRfVa0Y)ml1_u(6JH&hc{ZOHq<4D(~M8OS8do?R1DKDmmg^!qtTfA z*9;h^c$N9k(D{L`J#r(878lPKBWLd-sjc&G$|!~>PWc@3NIIomW#e_GX;8tYa%#yO zBr#d=b(IMQgl`KXOQ2e3cnFO9qWDWwn3-s07B3F zju&ciLoBwuqN#cs=4zPIvziYVBnZ3rz}fAzd-gtPq0lE-J1CtG7K8ETIb=}IfyVGr zs5`LPysbL$V)x79@ltOk&*ziJ+v(iErhdsv66a0_pNoPT29Q>5Y!A=Wk+#5g8H_S= z_mrmJ({Rg30OI4(s=1}f`aHbwM;v@c=j&3p;Vh9Tb(b*+|9bWfzaZCjJ{qS}Dzn)= zJrMrkfd+a)+KV45dT^Wj>|Hs5Jum5g_e+{9JA1n&+yc8h3%Gi`Y`I}_h}hrXnrn^` zN*#}G1HVgd$-dzMhH9zaP+*GphE`U2BrJ|1Sip-^rnNA#46G1(WWoS;I2}-O`R9o$ ztOqVW5W2%QXsX1TTczpOGe`O43?<18ANDylN5EMU70uDTvr>NgpM3#uU$KA&5R2L3FautSu5dYP-DMvM?8@{{Ny{i2HOiu{u^1YoRf;1t{27-&z}V@$ ztb57B?ioLO2%K~3JkFq8kKB%n@85P zJL&1Lu)(dx?X2_9%sx-H0e_iM$6F14CyktJ<+RVaJ0lo8(YVSzi*mM!Pa5HmZf1{v zx@zPSe)_REn6R92b+Gx6nUV6>DnUcQ=b6Va+pikASae!w!+@*jz%;J|m;OV1|G_>k zOeO9^8Ic={FaZD4&gAuJUV7G)O<#nPiQmC&?+4t@5H|e+QU^lH7vwp`zc@<*^pj<^S5?Avw4NkLS zmpk1{lRT&~FVWoUusUCyPkgcvKzyRKmT*RHsmzek z7#B6ghMgS>>N4jkDxYRlMq z%bjd3ODr98;$+i|1S%qoZXLn6wKiC1xxTn5=DIn2v0AD_wtd((j#<2)9kzyK8!66# zKajs*;~=|j86G!Y!;^Sw!gblOLRnt&qiZPY;5M!#gxJT=NvF{!?`txtdY@WmhlO*X zNl&#`2mWm{h4JP#B6@yOm+%yH^{krzcR3dxouZJ^7ApN#?5|p;XP$c9`5}-JgLxy( zl=JgGav-UIgTBWaWP`{~w<9j2y7dWfy8HYv?#W~^H;h&X63qz|v*mmMQ|Ak}Dv>+4 zZ7P5jO1eKG%`# zQ{v_e-tpuje=S|eU@^e^32dA``96`f2;{QyH(Bt7gBOrHD($Y}htK8JAm*D+`LlLX za{NUg`uWR!FTiq6lve6~*e!{pTUa&haM+Pl*M^UVLaxcbI7%!5??(imot5+td0;4A zU%%*DR1nd+TMglPmRwT;VGA+m}nlb@f=BO|*7yOhKL`qsG6gaazjVj5YlUb^!~W*PXf=Cm>I!JyUF$2PVZf=tC~i!$=c%?J)u_UVrxPawOS|5wsB;o zl&PI{T}V8k7oU(g#n~y4>B}|-&R(pc=06M%dAv}L%_zy?>Rw0xv}CeGK3~3{tc8PxQ@l1dArEk3m+TG{|u(66I(5$2yAiqm_R3|{Q>!*@8w26HL;VWf+ z1J-a+aRPiS6&4n!^3hB2iYLMdD8a&rlW{SdHW)KT#&5aUXE&%Q>Vi(pguSz)IXEk+ z|Dh|LFIkq$glP$5v4VB60uy20*&VOf}JRcLlHR17W^m5>= z{={a>quX(4C8~7lKU&-^SZfPg;{Va~l~HYWUDLQb6nCdM!CeZp#f!VUYlFLMi@UXW zao1p>6bTe98c1<3#qCS)_j~^EBWpp{l^ph&y=V4}dsFDofK{46U;idBG5Je3G5g2r zeJkXR{+xdY9!mcaaTW7OVPI+RE^?Gof2~Uy?jiReTMR9i5b-$sfUV%?>*)+<*txbt zpdUZFw1!?;-E3axBrL#se?XH#RJb8XKo(1CKa^YX^Qsa3ApBI{G3k?gP$VVw-xKFy zKuU)=j1C5*gI*jD-8x@Bfit{z3oS=!PTgZHPhcMY zlfKKR(SRcaGdySelhw!uQS%uw#P@jb#e2&BV1H8z&tE(_Yz%&8OsEzbW(rp-EvP`Q zMgA_j$1+}R_LlADmUFU`6yj`Cmnc0($M}p6F8_mz(da$-rHQ~d_@gr~UNuR>hX?PP zL4y|;0JIYuH{bl@=>pc*UP4deWHDv3hsHpDTHhkxjlfzOqu<&mhk}1U1se%VOgK+< z5+2Gd5!YKoFlj$-dy3I&I6tP29=q>Jg=$N6N^;5QyCjidRZxSZ(FYsIFsH94cHY<^ zrWtK=FSQHaJsUwmSYs2Q8`M9k>o^sVKm>@=oL~Y>oiKw>mV+%{# zzM5O{`NSSEB3s&QjOWx}MaNe^difNq9;~O)X7XPN7fnc>+aqI=c*a3@zpBX#gJTw;Hp$46&w>WI1<5CzG&(r?^$`$Sz#V{hZKWt@cG zHzYC)1?Ik=FZgty#zr3@N5eR{b>4}gFI`QN@CHH{0)`z4CG)3{kLJW3y<#IEj&O|R zpkRvUFHGRTQk}PO*+rQ%-H_AYGg_t9ZW8_>q&8}o?0YMky~NIgX4!wm5n1`$|0k9t zF9fgwY)|7WB`M~8>po?6VN0%vZ%Z6J8=Kum70Ew9)@z?}-Qzc4xS2e** z9`G2h9Jl@otr^v}ojfY}-2`{tAzsoNKVjZZxN8 z1(|nWZ*4v4hy0uBSVKKl%-S8pgApe&y*vZ%CV>uC5C4gJuZ zR^~==)_w~M^3D%_UG^K3RH|!-$;RBOKlH@rx$Tl)M4)#pk;QB| z#r>(C#r~%QH>3{_aBTOrOyb5Ne}v95NVvN3u4vWue)OhW(07k^eP3#|0G7@2THv`n zQl|4`q*T*?!#tIDhN5ivq?biza0hYHVlHxr0M)2?;f91^9**s;j)+_5tgIlf@O+b%ZD(bnslMMD) zrh@pgk!HsU)f@r=5`a1jCxjv^SI zi!c>^UL9dKH{!Bh`@hu%?DB6FblJkWGE`{uy<6z_g^4o;LKGf9G#lv6(3^j&z5W(6 zOB#1fkL79|rDjL}xh1;ew~$<4qxbNBdbA?!GT+-DL50tJp3Ha^Cl~RjkvHQ-8GCsc z?26S)&EWw*ugM&o9!FGUNWnr@B7~SmMc?{_v7p9iMS+)Sxy-1URY^Ui`(!7IA4!VC zK3wozFfD4y5cpc&S$=?t$3g{YA{bz&`vc}Z6>B%1`$kGNw;{h$sV|LK$b_$Ax74sMqQBexhTGjSBj1_B{?^3xh0o`wh(* zZq87fC*x3~Q(OWP$Z?TmP=7FI*&WY)D^L=uI11v5O5NRlW{EelD~mrHPNU#)Ulu9P z2$UkFY!-cwHkZIkQ5T}-Mvep%>JYR7W&BSIfSHwv&TjM+Fwa*N$ciEqeWcAdl*qAH z^;_-eKLKR#HQhk+tQ$N0KZHlsHPAqzjk4i~eEn|MEL;Y;bo%-n8R}`(*n{!%^nqP9 z9lzApgA}2*4W&gAdBch@a;Dzq>Eomj7|EBw`nED|Vd{4p_Ltm=s|7_XTm&YkqK88U zXLI8rb1unA5qupNETDPiz{ZE>C=-G_8RXMDK?qd*RRa!xPy`Dp_{^GwKF>TBDGO)mN`ttV{lRmRRjT zfm{mj{uOw$kH1lneZL8zi!x60z%~lvr}0>bzg>{f>^XvC)$S&M&+sY1;#&zEI$~?10eSThmANz`zCNsbyl!clWz^$dLX&UNg1Q%95pATA1d~5ZqKZMllCSDvBYukM>2BZY4k~m%p4( zuQT9QRZURHG2d`NOx9M2N1fn{!w# z@T*Xzt5X;MPM1kX812a`e4tJ6{`}Pl!*;jWwguYMSI}TfxHor{I&$8s(LNJ$gPmCz z;cnz^{}`V8X5~;RR>PooPtpxiLkDyZsMENV)OX|7I0m`7gb3o_l0pM1*xNIjZ(wI_ zpVFx-)c&!wES{N?`jmBlJTeD$<1#_I2Dht8uV{9EX%Ix1j^U)xr&v*6{@VOUV+0Zv zy`+CM3hsRlM;BVQevC>Iu|;5#M}$#8k2oG(2XAAN&J3eg?S*GQ_jHeCZvxmPi0U>S3H{@S3pyDr=xnW=_gxZv zE9}fXX-tN$=0@bwVs*xT`bNl@;f0AHyq!j}s*OlSe5pT|yQgi=VhVmXiqtzc;S=Wc zPNwQ+x2C;iULoj7BK&Pl(H>dPWe_!(o)=P*gYJWpXFH^-vMW+#P=t{}wFIA+R4h;0 zYQI+J=&oZ1`M}BP<%83gfA9@3oNU)SngM~4GA6Y& zOM?Tcp#14tf}56oKiTuz+_MiYzGd}je~3M)3J&Dj|AmK1I=r~;ud7GiYKZIp4u(Q` z=FjGxarLn>8(7%na zFro&>a9IE6^FFr-nAvNyKJQX>f7CGbTvUe`F25h#vdHy$>ul(@lY3-nI6N)T2hLuyz-z7AzHVzbMedfbPFt(4mI~QkG z*Rj^>v8r6!6Ktlb#4eLMVVvZqNNJa!q_yF2v;tzKReV8?>h7eL~U@S!l6l zzl|s(CbA{i5MD@*wSxs%FC#VOZqG~D9lb)4)c<(iP*>6wramTw%8SQ(ZX!N5C$VWy zOhecDKR9@JDA=~c&^IUd|oLbyyDIU5`%B@L^#5= z|L^}(77QkNvYZQo$$tAc9^SrWeVB2EA9p)2L}d-NmlXIOym!7fa7h|y(*$wnaQrtn z%Z1&9n!Fi# zd(;zQ4Dn`fip8=X5U%$Vw|?8o7E?@|<5>PBWVOuRW3||;r7YAZ)uf0I>vfFQyr2eu z8Tk?^HkiYu+MdVHm@^DGu`uC_wH_MO83nB73kc6aCck3TNKv_N^4$D2HaKvqW3fyo zgR6gzMk&4PZ%rxLtC!A`s&Q?k!&Y+t1MRyBYLBv{RHzaiB85Lf zrXruE-T}akNhg74>>39U!zkHiGy8Vm@;j(43>ds z(OJjna2wm?z*ntcGhEyxFJK|2V7}-E-ZQC8C89KbkJ< zcug}^hW2cB+{l=PKFuGCXndu!^Y7E`aqmJvH;lsx+Z_p4RC^;?b`aebPn z{x{X*>@*DiJnniaOO*lq7|tL&4ZT7d=dh-hr4?#hAy8oD&$H7n_d@98sY*S)gTQ%N zryMH1d|)}Wb8rviOaVr2xG!n{H#0GfgTedi##Q|tFo`RwDC^>;cXcHR1i$I&z~OL_ z(bDv}7?0TcRalln%T|B2Yhqdz@P+~V>>~|uxjL8$U1N-#uRJZ5}m7hP1zsEY6EVDt0^8^9;U4SocaDf zT^gS$Iyg=`VbcydUT}Lv7tecvUE?7ln6*~P^@ciIM!IYUct)Owwd}mVeeoHifFqW( z9R-}*48&r-<57Am1hTL$(p|q;i6P(NYfJf;vN>ndXpA4YB^`vkN`=_;reuTe8$+Ab z_N|&0b$J3S`2v3R$zx>Q>WDz9lHc5*)mhK}jx=ZWe@MumH?qwP&Gd&CFPdr216?bI zogRh`9>;(b$reRYaVf2tWYVW-b};7V_&a%XPf}}nD}e}%F<39yglhvzXpL4a0zUF4 z_bfPlt&>nx?LX$i%R1hEVrh%Dlw-gIqqN{|q-;X7#vNqN#}7jTaZ6f*EhS@nFX{%j z1a}TT?{x*bb-*fvc}xr2+odY3yrOLXN%ar3ql=hJJ2vV^yQ=EQGjF(BH0PP~6R|W+ ztwqs-vv*di5#KOGjA@|v=F6>uF|D(;C`UgJ^+x5yDe5UXBvsloHHst^D_DNXYiWG` z8s&(tJ!<%xlh)d$X>f_G$IABF6y!@JvwD?LP}qLDC^y&#SHqogU3aZD>1UH^>k&db z;dVOT4IDjiEuXw`8A!Cws7A$p6SIOzK<#r8ua%~v{NEO6=^>Qa2iGz8~>*&s7?eSe4X z=@ZK;Jq8+8V>k+PK^TkiXO`8^YYJCuZA*bK2G05?ZoVBx)*WA-q%~@t4^35sj{C0f z`)_Vei`*MY1?7FdfurpZ_YbMb7n;bPW~_ zOR)!hpzISPwmq9gs>%mb_ut*1KaniETrZ#e?WcGe1W zIJ)nlsoeTwTlT16T6}@L3v&Au2?vgGJv|l zWqksEb)9=hJJ7bDhL1J0IllJgmF+KKKrorcg$SB zIJX~4f!KCBU0`bMq5WgtTzNKc@x3=#ep_}}h5#wj0~=VUq6vE9z&?YBKaPvfO5#+V zI}QghH##i8nhLEy9SJ*Y8QF=Pn~T)7%E-`IzYgmdtH5`e`*8WF4_HJ>^@q5x2PX#a z=tynWsMYxR{hr%a&Bd>>o ztSjRKoiU3!wXtsO!OiLwy_3C#tT^)6hp$@5pdkw7Rr`(m{dl01cY z+f;${mm)Soy^pTx_l#7j`6TS?z-A=`-=_+$4DUZm$gM7aHg_L9VQO9dKgK_*E)94| zN}aJ8OD~c*U3{b?v@=}#ZFYFv{w{opz#yTC4A}g~Ec(6}5XFxfm38;Xx-RG&*cCE+ zE210`Ihy93>>8+5KEiD9X3^b*PJ@d0PPP%C*5RsUpYFMC0_~LEneB0Jio6tu%8%8R z|8=`Y)_}*}UC@D2KP+ouNdYX)^FCbv>KFbSktuM7C)Y+!mB!^oeaDf)MC4ixfF}_R(B-ZC1i2O=%CT}CE0Qr3K9?d) zib(Y&cHn?AW^jzcv?#N+CP(Z}#7C2&cxFovCk+Ea)!=LA?t6c{oIr|X|7CWo7oUW_lD2Y{-psQd2h81Ce@kskX=XV&4~t6m z-lTH{%%^Gc01YN|9#yBwYZy80Sy zh0f7Ijns5&z;r3TVry}J0=KuNo2&*#G*I1W$AKC78T59CCNVcOJ&LtAqD@cr@edv@ zW)2>$y7?JCK7UvNiwqlbe4ig%pxRXW=cCbri_vAvL2a0~p7A&Cy}zVIHm${p+d}%* zHkK~*i0NMSQUHlM6B$2s%)DEyQFC$>OI;-L>B3ymR!)q^V-pY8qy9!D#cJfy8la)C zO6?}(kZSQwPrlm*UzvBrezb}K34V)Lfl((I-V`ShN)Fro9VcfEqq{%EP9LNf-JQU3 zDmWBP3f?7^VEooGQ?2b%V`2wyR=CJaPA#hCwV)rMM3jj@S|F))s^mjK6J&U9dRh60 zw7C_ex#7}fHqFn@@gy=JSEFkXiW^ltff=(tb|J}i>r@S1!ZsN0s`bUM;iMSep;|Pd zOt4Rfz8$O+dzFx}u7~bm*U`nbAn?-h8yX1qkJF1+r=F@H#>=TDqU@oZG9rcNb^NOR z1StrKksT|bmYA*J+&!|08 z#M$;nRg>h!5@}S*YjvrW<`jhI6ML7+0Ur7Z!nr6^xzLIINEvc2f(0p9xvFIk`1EmDOmpR#&GLx2FpL+bOL!Y>uSR1LSODST6mBNPhc-Z3$UHYQif_?#tMxhN%;%*lDXgq&nla#ON(!;XGRPP|CTevX*! zM|>M$M$tDNyBT2y2-rDLOWK&9J(}qC5SHy)lB#IN^IQ-Ft!5KQ8xzO%3HXU$++HBK z>xY`r=xs|DdxTgO;1{sbh1kpN?(0<1_z;)2F9KgG=Bkh~{K7o?H|@b;L7i$_03D%n zk$n8za^5^i`I$od)?*5B!AVdMs#1OMTe1ov9)3@blnGT6r|r*c0k=e~#Y<9&%dt(6 zp@%<7@%CZCaAQr8k&UvCu(gGg)rB>IHxmxIek$xe8AT-TS;apCi!ySZS-M~0I20PP z>#sZP91vx2q3q~vhX_gR<<<_;vjoYoeH-OCK4P0B|BholJxjNAP$LjSljJ{Z4+ffa zP<-aMW4U)?N@}AR9&0u8$T|#Oo!7f~qyZaGc0Sd=y8Z=+9Jy8GBa#uo&6xa?m;AGf zNnPI@+YOvg;qOPihAv?8tmt7^L}~pEwHTf>jj=t27#wv}wG_)*$&Eh#c?&qgwFj~?tz4tZ@mlSy8;K>kjWxIR9wVb(E)mT>nZD_WEM z#Iu;d$*)W*Z+10TA$Vx$Zo82TIc|7&nTo+%VZ;L~8k){PtgtZ@v^i463ov*`QCE>v zq!ujYe759EEA0Y)2oE6+<%aPl6!k|}cSU&UyMFjNJ9y+#SA(23!XtJ%?0p8#402_l zGnQ^vR2xo7MRX2(Y5J=b@?cWUFd}^>BXFxW^3t|t_YnCHN0tb!{>2-S+3pG%=Dsex zqlGlRM&2;`Arw~|?i^N&Nsx;(?*+1m74Z{a-Wuicf4)*hL>qk?k_J5gg`bPqOQ|B& zxgt(AJU;{Z9J-yQgg^$$@1r5v$S+jKA5-WG-$BpXZjSl{gt>wBO!++WNKEQ6@ z*4@RuyJR+}K`Td>QsSDt)pE@N9$zCot zy0@p zl5RU3%cNGaHM~FP!kqxbEIeE|kvcK?A^_`o#O)9_a;)Z=Cn<;{-tf6;%Bcd&iRko& z`6yT-+&Q)0k5YdPO6|peK5+wxtF`)71e%=Z0@Oy$_yK40~*!n5B@?`gZZ;%oO!q7&#Mz zhKD#sk!?-i5&Y&jl!6I}q_l9}j&F&h5v*2mxlX;+m3!C`-v9}MhZ$oTwY|$sx$MkX zVHS1MlYk&(=dvzL11xx0{B+Hs2ituGrrO8`mqn%3A*I!33>4g?K{Z#wn}i!BF}&>9 zjm3#6{V(|nZ=IhWPWB5M(iY{hRql*p0a-A^5BQ>Z51C~Acao=Z7S`GrSH=#OA^!t` z(WM5fFA9J~%eBPYg}Xxy$U$8W=?V22SrEvAaGTIO$O%W`XLwKLL1Gxe0~(+(mU zJtb4rQX6wcBE6PA2JAK+VbnTH&WvL7e=9H06iOy z9rL%ARnirTF(pG#3$1f57XO)<&y_O>%`DnqnM%%a9fa=mm6RrL* z$!ta5U^W5p%}f7H@ki;j_-0vKV*i$Q4$lWP(e zxn_#Z$Dr_2hFK$?IV&aoyq~Ak+;Mo+G^|E%3h-r7%O&L1B${v34L|V?Ib-fFb|E1G z(w=~N%jn=gnm87!h&D19syVZ+2j56B>Gv4C z6rYzf$U`sUGuvUn_H4()8}yVYk!hVcRMD6-0_r;{Cwnh}-zGv7KSfa!#Hk8A!C)Lw zq#vR*X`W8V6FPk#Tg+y4c0-YuCT>+!y4ajS1@{5+$Z1lm&REJ3e5rrB<=Gk4ogO8@ zOIb{2o3{b9!_Jc?W_!1x(z{CmrHB6}7}C>~%xQi)YyKONL4-&Pf{e|ww#o23)|-@(@@$~@of}}{g|w`Gr_+q z#;Fm-c$8=)2AXVNV2*uExVn(XR?|i--RRsHSuo&p=UZqEjtS06Mazoi2nWnj_cXhz zeZ-ld6giYGTiYmZHA!z@lI32>~F81BoqocT`6$ENnLq*1uW`5lTp zz5m+o(SIdGiy;C-P)asx)ZU9r+yS7&tRZ{#`L0hvsRyds$6^6Qz^Rzb>nZqcJU*}7 zURCX6Qow8?|ARS$h7{3t9l5#1c_ zB}b61z@VNPE=5N~c=$?|CkY>8E6@^{e2#u+A^kCi%s1U1x5^HD=@J^vPrcWKOzWgq zrollxMU2B!)lGa}yXqr%*rl2>p?OPaqK@!n4z>YIw}9qA+C)9LMIVOT@OxtKf%iI7 zcZ&_#tCs<0wjAz*K{lV^=r(^DuLB_%ELm(|P8PGoJr?p9Q7%y%K6#8p$zlYO+9l>m{s>Wa zSmQ`oyj=8U2EV;3@DowL2#c-95rNXDC!26aK;gq*qP>$pI3u8R2LFJmA@44Nx2D(N zZSwQR$#_mwDcLDh=;qSSUB!q9?*pp_iEL@f!p#v{(#st58wfvqKsEn%6Z_!7bpP!X z+E8C`PhPs`1|wv3@>WcqcM^^$Dy-(#JC>*CWVWrB4$)gjBt!8{I4>sPtrTSHCTCZ{ zx!sBTTpv`KC49jdt@U@_@xQUb&MJ|N$v(puKwXFJK#T9xILH_>y=&JWC|q|@w^1P@ z0$I%pi6kpNgx&o+&TiI@Q=OvxSw9RIVMN-ZWAS^!Wc>a#0{Px2EgnTJOBCqaS5Iw} zkTq{?NTI82_`fFr^g9)O{kU%RP!X)U+;Il(v>wJ<1=c}4B|)o1$Lu9OW0ecWzU6~- z$V-UDpI`$nz2n!#Gs466Q2g*4%u`O5pxfz=<)U-}sC=|~g*^K`TX+X{$e~U^!J@mq zBLt7%M;a{ z%dD13h=qMe3gjQB%y+7$Ep3djovL<3J1=l%crf}6&7ENqeZYEKnmYf?$TAgjLyjFC zeBAG8#^6~FMT;zEtW%a|yUiLLwv+TZU<$HlsDHH^=q#`k=wjhjtX2^;fU63RND(wX zQ+qlS^k1C|kGOmi{pGioaiV%K6&@6dr+P9w?jybhx-(nw2*#TK_~Goe>Y@3RVD*x; zwB2iJ(Ie+??tWgO&QEujtGV#_oYm(pZBkj?VDQ`T+*DbW=|JH9Q2RDE70nKC+ZLH>P)L5B{4=9Mp8vivA@cGg9SH>@o46)`&$ zfO6hN)mW1Iv@sHJ+LO#Zs`WJgz9l=h)pUQckadYw5{tEtO3GG{>P=ZFJnSe=lzg;xwG$?439LyFn4F0Uo(CsUtz2USX>FJx987H6Z>)tj2yvH22Q1n zW($fmEWJZICrz8~I=VhNZ0FCSGO+}|0=*JTJ=_uO?Jirb)-5i+vvp|kEOr>j>R`Cki>WaNW>N=W

    1Kh& z7gba9OV&-o=Evuf%b6mViRj^uRAI}MJ^}m9ji3#6zT#;;(eDVpk)RTb8PrHUU91j5 z)vw5)Mz}#0JWqhqZ*Wb9eazz$C6W!P9RBG0*C$SX94dBin|l&sxWEm(MFh5q_q5wQm(2xNVQ+M21{wY2}4b>%$z02HL9r{xOzeBUJ>OwpS~R) zsDfEs+_1fM2&pZfe-nu1YUeYGvb|UhGKy4>o^ZX8a^ZJKRyrq@hbiEzuGR_aDnxDH zAQ)OB;Lx*r{LQytQ=Y*Gi3@2q}H0EWgZ@meBUb9H{_^ zLRi+AArPWT0Szknde6|G`0MW!f2J(Q<_LrVQ63dwlpH*1(O_>RYD}6WT&$K? zV(zPD)9M-m%tk8Qf?~5#l|rj82nJDj^Ok5>jmSe9wMepJ%&tAR2D1nB7r$w14Su_Z zVekIAD|}~Z{&_Gve3_s;U{0M!jtbQx+|Z#cKDFWfd?N+}#$oo@p1Hm~qD`3fGL^Nk zl9AT3QUGD(XxHNSEPA`6BjfYC#>tVI9=CSh;!}Qjb$>y>s88lRv8{aQ!hV&PC~%7d z>YS}+C1PclP?nI*`{|Y-> z4$vBvV7nJ^Bcwcj5=(&I=0GZW(mhy`=*Qd;lORjbKZXhh2LiwC^qd zD?}1`5`jc52>07&{ZD{(uMH79iJ2N7wZio8WT0gD7_WZ@9f`9-G-+P5(h~(jDKQGh z6byuyRQP^btIo7A#CDGX!I79o2wS$gZk9w=8tJFkm{24UPeCBip&6LMKgu`HsuiDl zHZtnnfni9jWAitMosf1($zi48d)1pxw_IW&L`>dtJ9+>sGZ^QC&@`@d6xs{nyn%lF z%Z(YbvO|sgXM^9=d;SoAJCnBv9{$9<7}rRFeAm{;Hyp8^J~^`q4kAt8;SS*E5!j6M zM@T8hfbX(qeR1&79w`Gc3g}G(Mc<#ltV-^O`=)xkcK{l40P*jvx=$o#BR1bx*{uc) zOT~l~pr~d+#>#u)P))Z@#L)n64W^fcV8H0J>i- zm14A2W6cOHd4F~|rDUn|OeLOXis8=tN}Y6P!Ajn0@t%Ud?o~2TM1Krn`R@KOf0BKx zq}=AXuwebK8guk#wnj@wVmk4;o2E)_Le|TY8xxNkZaH+qrdhlse=0sK*%f`pDa_OKToNt*J4{_kfXx^vMU*_ty|_{Oh=c)Qoq=qS@A zeZPDg*1AJNPNK$HuM9e>A#9mXYEgH2mb1$!SiarBP{Rag&R+qY3rl*im>W7_u`3v0hq9_9ghR=JTAfVcHxJlSOz z4g9fxq9F5b6G!8z-3mtb}2(?PGBfLE*LVA-+I*R-e z?zi=S4AWL2dFY!kvd0GIE&P-#@BWaU_km-#eCIDn@N4fo_?6#FHMw`GJex|baP`k$ z?r;W1X17M!ZDF5 zhOrb`1~P0T44%15g(+v0E~)r+6mCD#Vn+VsvG#6NiKyG8tEr;!4&zVi#rAtZ{gC&o z6taBaI~=vhM(Ms)iidDIe`|ddJ@uN|l6~*Ix`0spFmK#5`O~u%ZnCVh8Q!@;8{ZO> zv_h?zfIil_gD6D%{#w=KXM+;62S@fZYf&O3>Od>1P+BROUssd(gt}*6r|QRKl@Sc3 zz6fg{)}7Wm+;C(Y53vyGGt_5xt|XCSZ*6NJNvH;Cq>LpN^=MaK9qkka`rh`dW*l5& zDkbCDXApdoMi~_O6bzyM=8Nz#Oe_mCq;-T^DtCZSe*!1;$l)`l+} zkp?R&fat*%$D>pq_Ax00%QdVtt!Bi~!k>*$)KV76Cl71SRx8>oqWl)%D5{_5%yCSy z)9w8FBcr&D55Zv&g+T|?vyb<0X-otFxXj)W#ai&XHfgLx?`+6+xawU-0h8|j&JEEw zyf5dEzoZxW0}Xb4eq0*{cWnwqIHF~6~}eW;pb%Dbet+n7-p#wk3x z?2tIshP=t$`7;>GtM&(Gt^^~W$3AAfKLf}}v-oib=2RvWJpwe2Xmzqh@}yd|%9-wc z#I34)TExWr9FjqQPrG9mX4Cx*rF_K74U2@6)FU8XD^E)56udSh{8mcEv0CWE5h29o zvz(H$2p4$W1Zk_O@EvD*4qe@S-ekU+3{7rP1Z@2dcYSZ$D3xC8c#*8p?uoBa&y8^V z$MnO#om@PkL*77|kudJ~od6uv=YCS?Y((g?mN*IkRLq8VoTkcYJ zK6YyYE#H)o_(6k_nt<885sTL`pQGf8XN=!bP)C$%G&GhP7FEuO)!fK@xl|!G*-6R{ zfGbq80y~Ey#9XybOCJb(`2FPGmZmSO4b@N3ZskS?;PCo*wccMImc%c0E`KRQ=yyf? zC%(ANqrm5#|GP`P;A%YoE9*mb+e~h*-OhoqLqgimYlF9^KR}#lrqU!f3XD|_j3mS= z7t3iv7OG2e{Q1p{(V9^bO0w2b=_NoZX9K=k5uU$b?!UPTW`7Oe(wtl(;wAV2eLiFBd_B^V+*Z1`%ST68(p8JQOGfY16&sjSOkmU%8MM*ccgKsxIKClLok z{o8tt2=F#A61f^UCMB|}eJPOQ+O4qt5iZ8L+=Ja=zY^TscLm5IU!hHw9N&`A+Uqnn_EG2b;SL4=Y2xoeG<3JWzFSnKWJT~{tMlx|3cH#? z5#-4M4Fz9y`4uRzFC`UB4YXKW3fq6*-9Xp?yv>cT8+ZSLyMD=fB$47tm%S)eRd1A> zZ6Bk5Y2u!uKYFu`q3J-;uSM>S#VxqrZ@TW5;e1&Pqpm_n`hIkQV~_@d1tUxH(=pIS zPY2n`aUoR0dhDIOSmTIhUva zBW5cuJnr5se*HI@I9jSb7krQ}-j?TxYo79+RP>PgReX^{-Vb@@e71* zz=4G8LY-H?r(u!Vk7HinmX3XF@elvX{x#-n zCQQ?KErD{*+HVGelD2IK@w9;VSkA8vSvp zT{yrI7jKFLOMijzMbTUrUSHbPpld)M*-O&JaC}rp@S&1~BwQSm-|Ce9IYqtS{rnp) z=gCv$!`;6&FDr^{q9q9H{Q4^j`3Q>DnGV!7R7L`#yZn&n8t}&I2Ap|aRDJW!oVVkp z&4k^vnk%R7f{PzUB+q_D1jtgytf4@HQyaKNgvW}sLrJ&l>@)nZM#Zu_1t0vxJ_Qw#{?u_-96e%tNk)m|K+*&&2PW;X#fk+mwulH z6fh*VO4kwa?84KR3b5t)8LuipM-b<0WZI)KlO zyCs0SSa8SK{4f!M!wGc0e)i>>40KWx`guu?7^gZ^w-yBT2MK(-fxxf9f&F9cnr&_^ zM$Wbyc7q~;*iaPwoZCs+Oh|F<m%R3{E$Aa&GHEjY>8xsH|F&xKT^|w;UE& zS>R|^XVBe;Y1=;RGF&cFnb7>n7 zwDcmGGa9j1L|alC;qw-nd{LUz5ZPW{?c(SG%)0q~8N@h``G8Isi41-o5{?}fU+1YQ zBF+c*WLJim0_<~WuQDp7^sBH|%+PwYKQ{0im)lgz?zf4Fm5^5bgPt zA})&(qBnY)@du2pA%y%J9pb_?RIUXxYa! zmiu{yNm4gX-Qc`~CeQB4{h|FogkSO_kNp%y?Z_;XOi2SyBrN|(b5@p$E`}flmK1}i z$-R_b@t=;CsJvx*Tp~0Z_)HurT^gT3fTe;HuDf5$ugtk6bmUW7+!PzbE8N>Kw%D<$ zv7dfi8#rq*Vj+lppw!?J#;JVXoMcJXYmdBJVnC5 zUeLxQ#kwn=6VvySv-Eim=PK=tE!;GYZ3_6|+~yGIRh3!^@yqcjWx6UoacaQ*Y2sWu zmpZHGCs;XHDS=tRS+4lQf4wvv>h4Yk@4YDl-#5c^ES|u`Q6;8VBc?>t=)oNBbTO2ld)zROQ2j^zB52QH+|>@varoFdR)$1RZO{3V0`7 z#v8dziKA$-UNV?AQX+O=r{p^cm|vTOcA1HC`26|%kF!arH5t-ng*(Aw0Wk+HvgG=e z!e97c@8Z`%ZrHoc>up3miAv+%DipWE_Uw=RAO=56!~o}Q=VAj#iCzCH`d>8WC4nOj zUTUqZMe1kOZ|ME`dW{XfqpvhtxZOze+*3_O$y=tA;9OiZt*binJ+S_?+zgZUQL1va=c4aWzIDR)W_K~>G9u1v4R}Rw zABpv@J(v_rLV?tx^a&3wXs9Hzbe>-m4r}Rbe*?qOD3a{!aBgA z{VW&AFyz3!RuoRVyX=vMSdglS3vzdm&G~;con=51?)UabcMFVePi*KtD3tPp2{1%VE^c@0u38Ru8%>m@M#VoU6T`Z|g*OFzc-_SZT2b$?2Xo zY-M$4FG%vF-xQ=I+uRz6jUApY9JB^jE<1U+ z*TWml0PtuQJ0Q4BZW*Tydha@_+~D*Zq~PlPjoJAz;ab{8XsWdE z+imJqjP$|o#)@K7>M_Nhs-*eD#5hwkyU%Q$lodPuS zx?n@Upu;aoTchcZAtF#fF`Ir8et0OP&ue-FC^{}hyl=_CPObQnpen6S#-v?`_)@mm z9P7lenGiYq6V?5T@ScAPV9+AAFzsD6{3NiFigJr+Ao2}^y>+BLJlaFhowm`$Z<(b4 zYFIG0ikD#N&CHIvMV=xZ>QPEcqnl5BthI^y0E}hd4=QL~d}E07%(I6~D5J`wkkF{wIa%Xaif!b z&`id@j}ulJ3_i56;{yTTvR~hXpv^Jb*LdX8WQ^Hx*UX2KRQOFi-M z>8VCWuQxiwpG5ZYl0%uX$#XpCgUGWl7G#OSOgyX> zu0DgMnFVKU!|1PsR>LsR)`~EqA+_lyv=a@lM(JgHZOFMdIs8LT5;1Hj0dD@=R(lN4 za#Xe#FzY%KKyCaP&>oUi-shGv5J$=c;ehfX^Q1!GGRnr@%o{SFMq(fkOr58S-)+0z zLiJa*Hq%v@x`5OGM@&thP~-~%10gx^;Bp|M*TK`P(Z2GYj=z-s&k zyx8O~Tl)3Bxh6H!*ELv5MzHYAdv0sWdbIzgh_Ro`u9ivmsJi!EmG1f5>4}$*9J8Xm z3<$FxAmC}vU}o#`j*;{HPVlmPf@tq9$5*3mq!^WKCMU4X6y5sIKU2H*giH1#ubBwL z%LYg1w^r}FLc2U`##xF)j^(J?@N2j_2D=>RI&a) z3sB6E-*raSWszIV^4YE1DkFngGQe|xnv&`Cw(n)jeAhKAv@rHx1b)d_bB>VA#v!ds4nzZD31X|X*ng4Walk+W3Ja{(Q6|t*{hYLH z6j^C|UB|q;?Q*t_JzrwUBXw`Nv>>hx@QmenMDVNWM+g?cyjx^{v)YQHFiokg;G}%{ z$EJpdmB@{@ug9@T@R+M?h_Jua>>RFM)P1u)1ZACdf-xf?idU_^7*m%)t93xS=E5T> zpk}ZYp>}0wlI#KbWgT~UkXx4w4pcIDH*K~f_+hOfv$WAXfmdsH_}pi14FP01@dEUH z{PowB_sq+mN?z7`x4&Gi_7{5(O*VBwWkrn48gAjU@+)@+lAd$>G}@c7oNzjDw%*36 zT+(x8xeD?*32YUys9m$2?O#0g__@%DM0o~7f+y4ErPc5@B8&B14OQJU<%?IHN4$X@ z#e*uzgx%1Wt#J!j=;D*MAgWH{w=4f+fTw2UD?^xvtuwq&9&Zf}lXj^ojSE_K9Q*~* zkM2OzCW9V~FO?Vgt9{BVZgI+e_s<<8o!^H0o(eiP7g}1=*V4>K%-bPej-3=os_O5U zG&!f5$+YhdUGQBWRrKGfU)<%^>khHc%i%s&wR>OYbYT8_rMoq3DCCIoPv!_8^Ch@z zge0bH^XJE|@u9g0-nnSuVo+H&yJ+)8>P!Us-u3TB5)RW!Z$!)piNFg?yMc1dm?5T; z>V#-q2~G%|j3r4fa+TdkCzC{f4$Qg#f&LhQRU=48LXt<^-}~(~N<^cBd7k2jz{x_A zK!6X2u04hx{m>BAvVmbjT@vuVo5kqT@@f9p-t$f6Hq|;S!O(xn)e4ExLSNf4kb@Sq z!~EE0HE>nd{?_+H?+TL0z6Il!+H1=7?bN^Znx&#|mW6VZL;;i!xJw@SiGoMm;I%M0 zN~IXX7+bCMx52Y~y}nUcr!P7|;l;^m&O^Y568ds9mS2?}KK;h~aHHJP8Vl$gr9)z_ zfn(bYhR>pY{5I<6cu4uVoW?P`>V=P|qM^hmQ~ z7M<50(u^u6Y&Lw_qTj!0YzJ^uXBLCC+Vaxm>8+V`@Lv{nJw=LWJ`=JSFOgT)_acN+ zg51=s@DXA_z1D6`!52A``ytwJiI4VhoI9uCctc>dQdm&0N!^NqgjtJeb@9a1i_%5e zb|JFeQcl*XBn*DyG+!L zglBW`h&K)%U%+Qs=2b|_4$O@+PBsbJduSSicm+?<^eNG+7mSe3bo^@H$TiG)i_pue zR|&cg<+8|dlq{ykBBEu?|C3d4JLMGlwgzIu5dh*YGi$8@j54TbqhEdZv@SMcu3@EXXXhq{edqq49Nn!H$_my@(`t`%C2-X<8Y{|E`lrV;MZhulD@75qvQN?@R|FcUhFKx2CGHhD0l1wyX{pd^4K|tqkv>hR8t%dwp+XcqXbq!AL0HS`cA}CpNLLNkj^5!l@dy2Bk%Xl zv^9B1;=7Hq-ev>u#f`P|@-`f2`IOY|!r01s#YYYGPuJ|M@{L?Etm>d#i1wL3kDPq^ z4T;fDZ++-+RmtSet(FVgE2N`Wq%N>kGZ42J7ld-oCja3kXN2ei+Q^2yA91Xah9HAbf+-0`7pZ_W>fx?HJ7Uz!5hgJwGQGj&hQ}wMarf;% zfUy_Vi&d&k)cFz{681kr=ZOFO!65L;GnnF0Duy7!D81ElBdOV?YtW~3|6h@OaD{c; zk8zKp_@FuevW?4*FNrRsHFOqW9>Le7u=*}PQrXOBTq^EkM)HO40R2D*6QqFbhpX#w3mcqJ=J4srBo>fOHo zAU^hi93U%n7Tw7L)e#$0U~^A)D7?mqG^dJy`$`5E+!ep|7O|Dl|ER$$TKEdiN8bBn z3_lQ-yFx|J?_>LBYw;83ua(-AOTiMefA~sudVt(OHE$?gYi@1+T|M}5naAHY*2sFl zoSKX)-_@7ISZV&Lzm1ueopr}A=jrPINjUr4NXXIPl?E7ja!f&;-|;{H$e;H=4@#qz z;p8+jhse9c9XsFqQT`va`JuvAKzvN;cfG+8YaSCFEo~%mWvG7j6spihEjc3w{90r{P|xUSCyVyW_npC=^@nR0bb+&CsKaPQI?Fjw#Dm*d zH9{AE&~ay$$-YXiB+nP{Ck?r0z-H8W@*Vg~@@M5f<~5gZC-T41 zJb?revUcoRPvJzfwplXD@pML7(&sN0%*ozZXnv9m6hK&p$#)J0b>xpGI-bbo)=((? zz2EwCOPqzR#)SrvnSEmib7b@_~y;&Q<0 zh0`&wn(*=~>sEz#Kwig0#SG?J5UQ9|%0i^6$%@-lE2yYUoM>p~2|D=gkzuy)+~y{{M4%#KYcj#O0^7;$1ai4quJI zb?~68wPlMTeb9ymI;_j(L&)t5(vK5u6_`f8hW?XhaI5!MkCdI~I#CW8^1Xc|cihsC zhwrlK*(7$TZad)$-9a%S(5^v0Ugtxj&Yr#%Cg!L8vcK9EkeGH4T4%>Yx=tem1y*Ia zCnm>txjn}eI7fLOw=FIU+QVy3Jlk^<+07ZddD=nkM2d?wgcAEjCsUv$zfs^2onXBx zX%B!HWd?WdSdP>89Z(ed@TS%)->{2ih-S@i$mLzN^B>Mc(Eu#5 z;#W-2TBxmTDoDr%m7x2R6v4u=))kStpPEZ5dAYS*oSL5cie)7zMau7hODhtX|5HV( zIpGyqxIVrpE9Ja3T98utbmG*cseAkW1ha3*xv7NCxnjEduFA0TW4oVmh+&fp#mb+K zZay66SK0h#?W#?WN3f$>WLt+5F*C8KTT}E~S2$LAdPv4#Lx~xqusY$bP1l#>xU~mL z63_c|d3Mhwu`u&T%NOyI+3$sFHr3xbhzgw<(nY3l8nqFMKkM^#!Sng8GUVm~kKN}Y z_8b(rcp+|?tYe((cKoHHq;4pj56eN?Ub#%^k!QyiVUpkF}doznVmVt1PY-wZ}dl*Oz_slR?S z2p8`(RjY=8i$HphDJ1B^XLh$YzNy$d5S8#=SAFC3z(cisi#{;|G&-667PSQwt2mxz z+KFndT`!|x40YzV=$=~Tbx)$57~*)iNZ8iha&J8lXLozsHcbS-b)*L?Q0&Rf&x#F= z&5fvA;bXpdHsbf6OkG8cf-JJeI%H;@jB*`>j#(3Qt4&>3sxC6wGhM6EmCG=z$82ej z3`!eJ{oVEZJl?tREGM;&MJfejagY}29>aT*N3Zlr6~>Z}4~7?A3!r&>oW-To^5xV* z?`$*??*v9WwjwK@>Louc8H@xxhgG?LCrh5=8?+Z1(tGkHs#vWE!Nn$P`XP2M6dmt6 z?dUQD)$C)XZY_{j!6sALWRJI|i^eRnXr;tos|v0{B=?@C7kmySWE(FOajDI;@U1d< znY(>x-=T$BH|PRd?kV5>BZ1Z(fzfSbNo_4?*&jc*SNZDGyo(^qel6{mwtYusA+Vu& zI`S?F+l(dv&)|=I)HYFuT>R43{I4XrGTC^WqEm4-fD6@@1481He{>crJ-}>GY%-Z( zLMTc~vnMynp(c)mAO8Imh$lry)Fb)Xpuul*TQW;+2oX2KOt$f@mP?9ynnXNkZMaY! zj(vdDQMN$pp!SS5xvcijZ)Q#Bj|Ae*>(x)D;aTd^3H82lagH7?AJDNU(LX9Hp==@G8Sr9jBcY7SQRktVrJ z4?YAgftt3+t;_$N~K!>tnm z!WW`^L{D7n0hN$Ib8gfzom=}Gh2%^rIFx?f7u>AX5$&+w4~AXLP&xlz@8n%h##Bs6 z(Q|t^T@;XCXnz7U%}gw`wC9Vxg$NIa*uZBX*^hbXaW33gLzycC_LmHW#|>Ee2@4Ze zAD{H0Ml^gKyn5g3W#f+PpUKTwm1F8`ul63 zEyMHKk&-7gUr%m_DHfSh@8rk)mYOW9KQMc542J|~8juV^xd)-ejQHfKBcGC%##5o6 zX|K89OhzL0`yY?rkC|4_7yV!YoeJ7>*hZjlp)A|i6N;?X2NzNv>eiuId00jw~e zbI#A7&5n4cD)y&x8bxEfMO$Z9sTlq$hU-}3+-}C7@Ljf;|4l&h8I)EO$V%?hb3ew; zH}Cv%-}-$+`n}BK{XHPvhH3N(I680=jN(l=KkXX#A2&?C`R4BO?7>M6%7Ji@D|z_p zb}z>?>~T-hxSFr)?9B3MrC2BqjHz}MjlNK_L^4#&m zvQ_vy=F%UINqjNk*jK9>{0jE8NFLxhE>4MD5v_1m z4ybAL7ZH>!5FL-D!DG|McIGN>Cj9WQbXh56sP^eJ2P5eBvZF_j)so6iU!|_~a1w5p zGR`28rzEI+LS2>{^VbEK!=Yk99wX^RR3Ht5sK{+x9?^2xh(!l#&`(t3@@JhbvltQ2 z>HwOh^^5QyOaX(;@*K}`*=*Nkoiy&^nL`-HUB0RBDOH8<@=`90iF4CSt@d+lOHVHi z7J@gQm}A~j@J*J!&-5Q`Jf^}0hPHXfXPp;zD+P`ZesY_UdJ+2`GBW!rcJjzoy%$VH z)ib$1n3bhE2i+{Cr^p+C->Qr;<0UZm-b{~_Z`b1bWMj|+dXCi#+M@s#STpZ>fj_B3 z!LatsY(2qDW@VugC~0_dN44^U;>%*CB8{ScLDNAR;iQG%ysaJ0R*ASoX_@XD4swU>RP{Y1*~eWGk2R{$LN1pV8Q$CzVT5(EF+Ry; zHjSL0>{x5Gv&8I%({|4s`-$7~jy80||I(cNt+qt7<<>xRQt{V>7puA-pVY~WZ!Wyj zD>ayTL+j;!`#^y#_#51c;CE!4POwDwXiKTG_Z171xUAQ$dXGB}FnCh73s#fW%xB>5 zW)z2}7ww`=suh<#kqSx&6ojd+hw%Z`TC(fDB^@^nAHCkCn-Npgs!B@ zPTB1;sIBT%#}tEm#tC_XKhQ$ysWTJ4C9dTFOaqyb3sXX5V9tKu3`?8h50dcok zYR2CNqEBfy%HW8yVNPppDY{2I`{$wq0Qmwq9Vz%C$)nW$213$#Lz2Wpg5C61|n54cUazk0k)`mNEz@l>Es!>Chqqpe=o?LV%=1_nX_4~wy83Xz7+dQ z*g}+ZRl*lCMv0nO8G*GFl;E*=AQyd7WV>2Kc!lYNvXqvcVw4gM;$aNQ8?SJ@65hqh z)7Vrw;n>OWSPnG1(c_r`x-suGV6mc)7EBQ6{FS{&e7c|DtvfN5IEVLI*h_8Wig2%} zGZnR9kMR2n2toS+$Ea%07h$~P*ZsGc@htGGI&X+9G+479#1iyisM?hlvhf)vc}B~{vR1RbO|TOcn8{`$_V?ORx(mhPxNae zEPsiIk21CVH4a2!G|)H(-9PchK@<&8{)5G5W$&vD#Vdsmrq&r5wbT%t0o&Le%K{^D zrecz~?8W^&6H9Lf(gF3l+o_~+Ny`2-Qz3T823(vO*+;3}c_Tj-O+HxvQ9@J3vM=~6 zclSJ%e)vXzM_6q#MeRKr&1QhrPtd-3vKySrliaWTo@6}#m$5e@VuUZ%iT_bnQJ*T*dQ&U;7Vbsht%Tyjh({nr@#;U)F73F&!#j zNX6|J`R~7}UdvY-n}+{n#L5;Z9#wNOs!6?oeaR!Y7@O&)f^!bdh5Zkoy}G z2Pug=f@BkITg9_MYAaU{W>T8onC%7RjGrbxYYeKR1m$>;7L|mY!S0QzoOPbW3p2!x z&d0&}m_Df=Ycij@KC)HkA$4}$QU2xuw&I^-X5zPEXFyTfW~koI2i>#Oc`jcDTx-vP zWRNeqru+NTumRQBFmndhsf2mnK_i0kfbr(Z__fza z514)fvZ}n=@pGO3zKLy~>>zbMNBq&@De@)xg*p0{?Yqv5`?q%nP2@h~_%ozHOzYcM zcs@ZhG?<}|w^HL7OGscUou=Tsx@byHKg#*|6GdIg9D(h{_wFgBIE4P!YIpnt&fw6@ zsN}G=r3>RAZ39*RYUBNi2v{sQo0 ztau$3TN063;t6w&Pm{bD`6C>pd$z!%*n6ZhAR(}L7&CQ6H?HwvFyPVg`_%<2YfRpI znhxlYXqJXOTX%@SqlusqS*co4x*dAE-CH#vcJ4c^jis0|`+#Ixrm>)mF`<&zp$esZk+%~yAW z_YFDLlSnGQH(rIc&Ky`0DU=AafL90^rB|BYtaPhPunL%YVp@WqTg$PJv%)1sZ3AS4 zuwK#f0|~Oe}tCY!J#Zmz7v*P?F%$U3$yqfX65h z(IKDtNMjst#1ZwyING2Di#8wuf4lb@JDlh5e&IqSNF0wSRxz=%`!we*7M{13FR-iw?$Bf_TsmsJq zCOSNf2xrpU==Jj~Rbf)c8BWC2o8(}Us5~+Tkh6(PrDe|wt)q?!3BX_avJ7SN@kK4H z@e$w4#lOE;4{@Zcd$X0&$Y9r@mexpQ*MXnr$)t;Lm2uj7s<@~k?&eLjG1`W;+rfn3 zzzq;#|1&%J6 zPp_(%GbK3IQe_Y6I}|-b(t#N}CasaNxIdO~#Z5B(-P0U3wtjqin(d14hs$A~Q3X?W z#>+E=*q^btCwZ_%CBh$xu( zwQB`wnCs@#FD4(UD~$2mNdr^VGFW2({j5>Ql7-4!lUHYHaO8K093P30++w3`qL*xY z8@ptbOQ(tTIx!w>i8*qx9E&S?;G`w?=A4q_;pe#zNj?ahUL=TO$=!o9=NtHX~!>G4-dr&6@xRx7?I?b_{zv$cHT{Z0f6DlvY0^aOkT zIyfQ!MPE+9Twv3CuaTraf7!WScdpJ5CG5={t*gTqA5%ryYRzj2sGsJi{0Z>eHpBGi zi^~Zwmbif4XI^(#e!UX5Ils19U zuORPz`R{+A`Ad8CBq6ajKTaN{xB)k8U^7gPDgqX{HGvywp>lwuNWR$X$*TzxIW zf1Zmp^8s#_H1Cc0kM~|lJpW|E(Q+En;WR*R+_V^$2j7O!H@&JR7SgeJS99ql$R1t! zfg^(l%_P>$0C5=bJ6bUEfym94H3c_>Qh1Kz=D zO8!2dmbcOAYlyq~L-W{%1^clzM34SdkFFr#!WmPJzdYJtWH{1AwMx=B_XdIPmsY7( z*9;FY%+lkscf}tPc?Hb@**38OXg~O1L^ZYfem_OS%I~v@`Z)2q2dLJB%VW9dQw|`G zDgvD?IuCSmOC@wzD1dWaq}iq7*PbsTVQb=X|m=ULU)6kk{SXOo!@ z#BVJKGOhsQoe#0L#%z2(f1@}+!IscWKw0i(R9&&u$o^?dy@Sjw9T-#pVp4#i>H0XI zhJbsbjg=y*_f;LE_`Ijrx_c_(IyXt2!o$R?SBEOczeT$m0^hO7bFpcbYD{6wE|ZUC zZ=>w_oR6p1oEqbK1BBH^1~PdvKL9k{o`_qEQ}T{GJe|%=N<}$2{@9wTqqbDbPry>v zuTaPX6#0&E04XQetbc^K?RMg8=%CsyMN;m1m0k8HUmpC)g%a>n{Gy32HlObZMim1txR8y8~!uBOEIsO^vCx;nnefU?OMsD-2 zECs;5w(ZQqkMPgIsm<0Mt?f&pmEWO5X^*DPX7x*#xV8xpqKEwJZ4#0T7az%`rko6j zsj9>WN-29V-5@v{kvM}$f*COJWmY`@cvP%wHL!uO z_Qz>BCeT1&jk9owiaQi9`*c~cH{Jx{=iiI4Jjk@658Ytwc}TKdFFF%l%E zx9rnRtnp;{>d&mE=+V&5mo~N4=+h(=(Kd6c9ipWh?+YVVDdN|U^5mgbtK*|SWU|Bg zjs8-bDNf{Pqn5=Lp&-4aHbzD@X0kR)pSgpO@a^o$w*Xxx$|QSn!t7&lKEF#5K>ajxSl+rZx)H@!G3Z=K3YhUi~R-uwv2WKO&!$ zS$9e=?yo5NweOf-#zQ3iI^9tdAzynuyxbX6y(|@h#_bI@^0(tc7HiZXf?C zGhO%0S0C|J9p1uK!6?%tzGHO0uOP6HpDs6cwV>EI6Q(tHGR zEZ!C}Y$i_~{XRi>S?cu6A>jn@o1gPd36wR*Vzo2yL2XDVXY2C(Tw3N)iVIw;z`~zJ z`9L1qmbW<-8gyji*ElxVPtc|^KnttEs_{Zpa?=4CQn!KZC^xIL4Lkyo%oAHBl{Oa3Bze?GYZ?(axzwnkj1K+*;GrMA1>g;rFzZ81~5nV+8m3?x1 zz4F7hPiyw$#E+5Z2?{(_=9t!~TSNStVe!`wAa)c0HqmjiO1C=6O1YAjB1D|Tco1EH zXO5CAB@=|#gl+J4BZRH4bB1*z>&3N&`K|gYBYFd6Wo7YIvf+Ay#s#A@T5a6?kB3Ua zE^E;WSeKZPIN2~L*uazl73l0TWTrYg+M%`18e~JiKI?u<_kA7B_1j3=&yw<>X*)gp<#z8PXj6eOMX$!8Iec70=n4%zqB5 zugs{V9r22Sd^8z|7#%8$)oxmYg*|TL`V}yw?o!0D4cNfT!{KI4v@b9M2?3LUNssrG zYWQy5m*I>`Ny^Fg%f07A_&ID=oIHZ*gr`;5u{7P=irBhjYgGsnew-{~AUPFP2RmMG zyEx9U=v*D69^t?tE;&y~{htoJFrTryueRhrnPoL!AIO;pl{{1X_vuQdCO%}*=h6)+ zHU<;_VOBfPbopuTIynFC^dO!k=q3D=N(f(~uH3swLr+xQU~eYX5md~ceh0yGXndiV zpF_A}Kr?uc;Fr)Y@AfB&CB5Nk9|hr_F`dCcuO=MSK3$T^sIwt0DV_j3$ELPfqJHiO zq0i0-NbR@WP{DSE*?oG#V)`>`yHcV$28c|gz$Qmj$+D}QCZ(+_a$b<7@Sr%RaSg$>Nc z6=?H+MuhO*6w^7YyDK2{$5h|z)Ls2NDMHBy1Xci6v(7KSvZ}CNW#5~1nYv5r#=&)| z$#J`#28InK8|?UX@I^33#GB@l@Se~kemqG^KA)u)*^apy{fA+cYo5VA7#E`ilbPmV zgl(oq0=GaCS_y4*0kqj*HR-C!FcPt<)vpcFq&=8weDMl{*vm3Gh^>1PlVpvO0 zdN>%Whx|9)_KIi#EIimy=~f>y!+P0P-WV_$M}*EoX@|YypVNlZCD29LYq^2Hqoj~G zBRfV<3-%uu3q&OO)42KPOzx^0bGK_Dgin0}bp3m#yg3#BVj`nO)eZ{GT14JenO@xO z#OI=(uT~eQK7DQ}FPv6??S!vGtBSHuz%Bv_-2~`@)s_n?NcF;b;gL$IkyvF|lg?^N zSi@$k+~F$NrjD5`@AZ9b^$I|g?VS#v5`n0xedee-;2RZ5s{Z-OQ~?k$ z9Vqixquqc8^-u1_dJa#n%jrK8r%Js<;72j4ykx+1CB|bDSvTiu?m4PTsgM-v`w6Qt z=_#UtJjxNLu+hzQeymOuVNo|}JmHbQ$wZvK_|6GZiU@FQk2T>^*wgxOk`Filti>gK z7a2$b3Nb1Hju*PiJm4Pp`!HC5av+n(?jWw>PcymxU|!uY-1k*n>Ay6Z>(+|*9(Yoo zuxT(;g4~_<#l$$I6sP{EL)1}~n_LC}~HYohXjLHxsZAoaU~N7V0_GXNP}HCS7Ltq(y~47Mf{ zyUcM9A_H%j(Zq!UI*QSboY4)@e+H3S47!{nAp)Scv41#j%e2_x!Zg2&zFL?(8`_|( z>3qwR92B!TI!Q}niV&tR4t`hD6X>%tZa!BM`X%e*M+9Gb3(gNcF?r4nwNp&4cKuP* znB)!q9|(kvVZ|^(UERwyZ}$AjkbD!e?V3?Iz4d`7(K{PmlnqAjcg6*rYU4=r|L+5tD1|hPg0<9g5==F%+lCHL31cTsqYvliQRPn}aqtO7 zrP$|1>Q)k>#4w%749p$_SoWTxIc&o|oW78%Ek~g7zx*~vd{uC%n>SG+$0IUu`ys3x zq#x&@aZ0$G`!Om|nm9gEsgr&z#V&m7XV~+GFh^18fOD!5l+&^Ccc7^4L_U6zMjB=3 zR*FkJo*ebEbUP2EFhWs&TE#<+FFd)oDSd}OO>gsucPXaJ5*avw5lNo=|2TyiR)eM{ z3}CHXFplw1QcACQm?zfI$iuxhEo%% z!ybk-)ytFF%JYLn#;-T$YtQuy0v)do1>-7tIk+`Y&SlC`mI_6a(!%GqNU*(@g(BgS ztFK;}XD=6-=FsDA0w{{~i8%3C%LMwW6dv~OswMa2=)c(D%=7)W>4Vb-DL3&Ga=03U zn10GTu#No#9?SRhu_qk~uf>p`E<28m3ibcp`_pI$SUA<8i@}(XjXs%2&Bs(@j$N~7fKlysT~{6)u-`^R7D z9q9j4ELt?iFuW_Y{^~g8m%Ce&)z`)pB9LRx#7epQmXACx62*1z0`Tc|D7|EHJF+bN z%)+aVE^N!Z5BSsPeOH7IWSK4{{oSU=hvsdmNQ^?}k)JMLWB4C9h%5!gP1sE`qs=YV zq@FR*pFtS*?|$pt5Z21`KM&(nc!a7?YM+E31-9NVt6of3boiBm%Ql&OSP4AY}omD7ex2@5{Ey+9=mCY*~ysloCfIvxb)vqXurzwf4u(>)EYRn zzoqWk$j4!&4X$pEb=MYG^pbJZ*8M&heupwnRK4G-Y+0yrPIl)n->?}?gocutsO_i* zE~Cxzw<}ExE-H2rqwP|W{TRWr_bP7BpzoO5<$I=c3K9OxhGk+1Fn!T*)q zH>xjRt5hdDYS@e=baP$_sU*S~=z4#dA5X8BbDhEFs5^XhO5~P`?=LngFmvHopombm zz~s-V_lHUeZVseZlz}UD3C2&5V~zfcG2bura-p^M@ncaqXU0=OIlBiF|7V!>kNhqi z4{c5`wQmf7zCVqSML(4Cr&Is)M9zay%6b4Rp_BIl%FK@CpW}(Lz1Xy`b(a~{VQJFQ zyyL}M4v|g^X{Nm8UDUv8v-NL(%})!H*yq5MsRpIm+i$3!{VYZqc#^fOT%JA_XBd~Y zq5SoqU-4LVAacq{d`w*KzbG`i*F`;r^_sty-~ERyEgxp(C8naga!29ehZ%lc^InM9 z`RRDACe+hP594>g{r$p1;hAbeMLAh!R<6pJkGzHPz0QPvkq}m=MDpni9F$G3#+FS2 zW*N**y5j4?DU}TPGY6lW_-6u>P3?JOU>ob3X_=Rq}0?b=@wu6QeHdr$6h1AZ1)0M*gSCve?~v0s(twbznxdMI+$~HQF(-mf!izi zLw~(^lbC#c?c^TZEP3DD9L={H@9J!+1AYQm4Rzj}Os zP^yRZQ==;aV;5~elQ4$^n6jSd;6HX+?<4JpusE+Vx zxB8Pq)-tn(OHw=MA~fcauu0~1?Fc_VNDu(_k&pade7d;-S??xl$S@OrlLS z@V6OLRhj*lr8w<5{lh%SybYPR@Rh-WKL{JC6eC5bwg{1Z^RX}piRh3|^TQY*+9O2O z8`T8oO=81(ZG`rAZ>n>~ltB%9jxwy_b9~!HTfI#xsqFQD2Z^{kV?2sVG2My8tG|8% zU~)yWpu!8HSQgR}(MJ!)0>}bux%!MdDAok*;a7lcMlXaCGtM$_mawx4`5YfB7lPqg z^Tz9*A{KQl_%^6jXo}CzsB2deGngTd28;3LWnS)^X|OFLae)`5CKUpd>XDEU+H>ZN}AEC5DR>&&{oILm~l~@5TKS5%v$&ovF zn(!`t3XHMS-dt@F^(U8*+M|@910+21kkkzi-Fm7#3GCkTg80&m%*$z*n2Bfr%&=b` z^gT2>@c#o+BRrkxbJ|c0uv`FfgLYC@!9BH{_}^kFD$As1Mt^7=hRS(#F}Hle;O>|= z?qdalEYSP_){mhen-*uCleb|qO5Vl{vCc*3u_q3I%eK6@vbG*$=p~6N`r6_5qj)Wm}Ha;?j=KrS3Zct>{$< zoAcWFvuPMt{YH>ZI<66U4v^BvhFOtW^jOTEDpG$-<0oz$3xsFGDrBU48yX6eVSJh) zSJD>mlIlHu2{_VNF2)tfJ}C(Zbwu!eZV$MLNM5ual$oJDwK!aLj*5w_#3LbHR=XnW z#|)=ZxH#VU0xQK;=xSN=LrBK*xX?%5R23H+Oh38TW-vWWLAcyqakb>+b{PCGeB(jPwevz)!!fWJ#*9&w+J! zPECW}yuKJ`k6c~Q2Z6^*CsS7dDPx>|Vsg}CjP0)LP}`H2bEeeOZHkcoSH00(=VNS3 z&h^Dg`o$w80%VsB5n3t961#6mSfPW&TpeWhU!W82k1&t^JS5C@z^lgq#a3hb%6ts< z7HlU|ZFcjvCLW@IGU;w#k~cj((SHA4u3XLds}OZJz99Y^-Y%XE7dbgdu<&`RV35jb z^_Q2xui=3-R_ehvGeQ@g&dIMo?u?DLFZY#Eb~}rboZt@N^fOz1Rm?BL*s0g^r>GoCHWUWscyEfoG0+6bJx|kh{}8UtaD;K) z3%gGldjsxRdyJw6xmk}6?e=llT6*>nQd6&-AV z!8ubu2QkPy!(FK#LsSA>H zroeJ6^Feq%6kEeiFH!ue+LX165&9^$-?i+&v&oek;zaC}FPpeesR1;+J&>rx&1UVc zJ%gTPTKA5_`DcyDHo*+fWfg{3ceH~Y&sjE7L~1%WBP2{^G}b{o(4`nDJqneKYmU+; zS%#w)sDl!x0?*qMOh*Eq9)3iaTB0jO+JX)Q{8j|o1~ez$e9aN5Or2lFf}-Lera{3h z80iCXjLao?pbiLlv8%`8(xE>DQ_a%qp-U$@q*@Ets> znSPSmEMnmmleG-ZGN9E_A!9wtHdbz%GJwBuEBJQS`9J#9`O}}-_x`e%sVjAX;L1>M^HL{jF+IFJ(tXt9`Ipfxz($Cq`c2s^A?fV znZ_9I%Rd!Vmj2d$Sn>p~t3dP9w~x!N)j|lN(R<<+ z_h@hKyl;;dj@|FOBRNQOdVXr>t1SD>ihDVI-rg>M{$KGjsKLiF*Q)brRQj)9i$t>H zH!+iYQPg?u_X}J82+bOHH?nVukqK24Zg*O;3uS8xU*?~EHi6RT&@CnK{~rsGodKOs zkp9Ww?m(_2DzXKs=bXo1ST|9|S};2!&l&8InESS{2{=qwhe&F{WuGP*nMzCaZPkcO z4Zh-2%#KjWB8poLQ6|YT*c3@f@co-ki;OIp?k9LPjVHB_Gj$0kPf8y#(A#v~+zvf6 zJEKUFY^Mv2!BR@YdJh-YG~Cn2kX#Z4S?K&?eUU0dc82rHy;3P%xz2@Vt?j)?^OL)% zUK;xARx};I3#B5ARjHG@$%N8P&u;LM8F{mWlV33}yI{fXM#2r@U7xu5mo1TdQ zDn}Qc-m(wD1SgixBUD7RZK8tegp$5npH$1Qqs)@wxJ07jEwjUj`^##15RXH_<4{By zx+XzIHh6UQWB)uou`M3>YKJ?kw7o)T*7cN+cj&ump;Ig0zkk-fe%nnO3Ct$7`(YPc zHV^w|EWgyO$$WbFGFrawvj1M8{=qb*>bu1iYJ517L!VP7LkD2^I_0JxoP&tP#Kd*s zs5u?SubDt(x$N6xApSQ))rF*3T|DBnVHmo8?kg7>-g;*0*_U3Dj(hkmz1N8YNxnO| z0>L|bK~0_ll1`+7zEjo44Uv@3DyWc=#yzYqj48jcz&I#dus*or^;zTy$g;_2yb8P^ z@KbqPB6cm(c86B z)mWcm`{|#(T=V6Nr71fUNSy8)55erNU2@U-!$8|@7-{N&4Q9;V*UYq>>b)@_#u zSDt5=B~ONWgbN7bjhOUgPwbKOPGP;e^>`dbY>4j)MZjaAPUovF1RBQ62dP;84EVM_ zXNW)k1AqUfmQ!+!FBvc=5S;v4R%(nHm~dBCh+(%=f0j-#Q#=g80{GC)ZMLoltw+?M z`3iC>;_Sqm5bSWDWRikOyyr!LCTAOf{D*rB0T5n~Mo-;oAARwqW~GDlbplVcEbZ;1 z^;pH65}?z@*rQ1^vPHA1>hlDgU-SNRy4c5gb$5^N;uw7=Ym7C~t`+tC60vk=hkzTYvrC?TUS`rht--^^8HnNOHiVR2* zLeZ=%4-i=tLbA=6&IJ|hy{K2zcqcB22)L0i(D#(?Ki z+aF7}#V+_pWNgJnxn#x+d1-4yW=C6#x2|hb(>*#n%aC@sc?&vsCcFnU2#~e?xs5+QLrXq396)o_mUgKbPP<^_v;ZKsIXRcF!9q1IjcHF0 zmLOG)7|o2Vd%NYFzx;}yHE3E3U#kTAUf4{R1Z)Z+Z6j4DZ@d;xkuK5K~Yb+Tivft zxdafaLc|{80e!s(Rp$1J3c9_cZ+8$t=)bP*Q%C%?Uh)XP&mI~wJq(i>HvRAlbb{(+ zI6FueJK+HMzkig+d(U8DqxR`Ku@{{V-^O>2j;t}4z0hCF{(jGpN_@t@d=GBKqPwjJ zUs#*j82J%)i)Kin9@?a8i`78+nBQAG=;o* z7du@VS^w?szqbCMk22#r<(7TU zKD4MFOfy-A<5f!k(Md0V@ciw9Y!CWPiLM!6^x|kAaL_kdYZf)!D&ithmmFlJe~{^{X;lMWwHGt1 zs2jDp{d>3WjI+%h@F9po8h6{PJ4)jdD!%JnopP{-rD0|3ch79>?3TQ23FM}#kJJp`~#@J60ywu0D%X-L-TApcN->`k0zTa+l1yx=inD8U^B2hoVZw%J@{^{f|HPiU%^#|tFDddYG zn|r2w2ujG0ZTqUV9(g!yzuesVpQK@=>+d$LFMY(ga$qX-In^k%gCNrDzgAtjKlO4K z|Ktu3=SxQ&D8F|&3|QTmZ(jW+w6CLlY{V0l`R@I4@f(Qpj&r#0)z_H`>G*T%po}T3 z^3v3eTAx%BvF=1S?y`rRtfaH%EPj3imA};LOkDE<4}LNq_`k2?A86Hh(^;^aqYa%z zZ01dDx5|y(E&7XLOdu}Pub=N*kDhD7P|SRi+t{LiUyT>e5#1W)AEnf}xPe1A|1lhz zBdVAbE>Oqph1;RK3_@ws*=Dt}=7 zc%XB&q<0nVOwJLLa`#0A`1yl3VU5J6C&NC{_9FQemFcoxj8r$1IyzE z!;6TGDZ7Stb>?1vIM{M5>BcXDR~>WH7)_c!&M1whaQp67fuZ%zkj>D;pc)alYjD*5 zYMhuiNicht+cnDm4cM-%Xe;R1<0_q{MBz ztf+HRG^n`?wT}dFzl=ZZTpV-fIZndp)!Xf&gpR`oN^kPHOKoiK|rHf|HSb;Vy z4OutvP4{EQB|S>zuGWnoyrs6)B9!Yr@|&|kU}iTlF%itTI8!nCH>~>5&M#=w zhjuNn+YjpZ*o}{(6LAqMQWA+kF7P3j)zy^`Y@G^Q&1*+&T5UA28b)S&l4-S5Zj@h9 z2s1tCA7Ue1#3+?I9z@>YDpg`X)PuM28UA7MCQb35N=T&wACQ99fekd+ggpn#JYMBQ zB8B7Z;Kv->-;jUG3gwr^y5>lU9Ec_;h(?;!?L>rgSq;H7Q7KkNIo59qS?iKDOz*m9 zsiso;+S4jrSkeNIyIHhlP{OVfDp9-ZPqry!N9v%81zGD6@kGN(DLJo%xyt3J7% z!1;uFi03rFSm%%_Um2`6%JWvapojWT)*N1L?2R_Hbny*1_K{&`kyBG>P%l$rIU5?_Q+nkZqZ+%k{<}Bn(biqP8;yybGV$%8s83wd;oBAG*DV}2Xmk8(mgb8 zn@XbB0uI-{-=F&ck_Xs<#@Aj5^J*_0b0z%JPrm97zHR1U5(Q(k?Og{!_Ol*Q`5FnO zTnZA4Sg%0|p?OgiGaAJE1@iq+>@U0p4RyvUa?Ia9Jq>%xTi+(a=Z+R%w*;B40h2IA zS3SinW_}TbPT6b{v_@nxx;0`pd}>)bZ~Ni1JXd%e#WB+&HZ$DB)Rb8m>x38P0R%&C z5W<@H-;Mq5XVHaOH=|920$;tnJnF49F&!;-DdJOjMihm+wb+*#ektFNWoUNiMwjV_ zhE_c~KIjY>ldz;{SFWqDwe7Y%IhGm~R{SBI?gYyzmGfBmEXLTow2sit%b&?=AfkGm z7eX)|mX{cH{_kPoKZp5Bl=Ow^D?%+Ed=T@;5C{E;DQag<|D_R#EjP1;w9DrOK}*(8 z&1r~z9kq1WolHanRtlBs`@$f)30#SHg10~SwPi>VPxJPjV9q5EsoED2-m$dmUHoCQYeci=m@=Yq$fpz$OQWOrt+-X3 zN=MI142G9aJ7ss{B-%FQM2mAE^E7&D9yFpaYlZ7kS<{fR6__YeK9oe#Lb1*qG3*eM zXZ82kEp0W+^Sdr-2TuSkifk%>EG?t(Hxl{Utj;i;@b)WWVTQksq}gih%C2ACl51U$ z>R+PQawqmtp6Z)}>XxgjUFr42V2Pa|vI3P5YCy~XmuV)>q{1^wtIhBPaqQ6e7n z0Zg;}vleSt=AW)wrOf^!%W};S0g7uNpElXwU_5~e7=v9dG^`;gvHkV#8S340(eUsS z{?yaA$plO|uNcwz3wd?xkuD4Q!@v)N|F{_h8b;xQbpxp1o(jfYtBima+UwZoY21Xg zPL$iynwkcY)91+_hH!i+e8{H=&bGD5sc<&9v?6*Q56iwAzaYIX^o#DL6oBsy9ML;l z9eX9nPci~K$ugmD$BuKR4`_&v{V7oqw$u6oJN6qK=qt}Tc=Hr?PMq)EEnXD<9+ug+r zj)hZ6zCYx_*j7~S;5-v0MR}u!$*`gzV(^l_CsXMruV3nuC})pETmkjii?`2^`$At2 z^J#(&_YmKl{&dC&3t8K$d!I_mP_S)Brc#PM%$wL3q_TYBt2SS#mss5$7^abX0l*HX zqMD}5816<|+Yr7EGFrZ`yW-v~-S$~FY)N7d?Bc*izoHYRipWf}&xA37g)XlX&sY(m z34pdjl^V@EE6ZK5S$7H`LzTCm3D6w<5Gb5TPz_xtJS>cd>>rnq!rjC3!v+>`p=UXd z;-G%b+Ov{0BT+Cr;6X_O>4XGW5%jmXW4^;zqI36c>JL+o@1or^cyDz6P3xX-&dJ%L zFYg2I@Ng6MdRpWK#bi>4XluklN@?`K>SDbn^U<1X4Atir^XHc?{5rD!{0r~R365Ub zG$iKyXq@k~PS~oltV!&6rK!-**~PJiD!R*AuWJFpZP$wD^cq2wU3zD0@ zZKroe1r)#GWSEm_%p`EsaQyv)WsP0I05@&{Xqjm5)zR7e_2-oy4d)g$LR_1^AC@Yd zoxN2|d~RHNBBt~Z+>!2-3&76AezOOS1$?QRg$%ry4@KGVxV%FMmkZ|txNsi^I|-!Y zWQfooxUH|W=$lptX-eDfEl zRLd|sf-;uvC731$%P_JP!qZr^@Bj#fZ?>Ok(y52=rO&*&<&qJZFWFtf>3v&5^9Bz} z;N1@Y!b|LW0W4mbhZWOmNJboR7I3tW8s_L3xo8sd>#CK3*W@37aOp~;CbxssrVWBh zr3ruWQoJ>HdYIAPe;uC=dg3(h)ySa1S41Ap6C|KPoJx58fc^=uYHOiT5ZZ8S+uwP9 zk}X3>X0q5*j{YhCQlT~#ikl$%!W1LeUXJ5v1g~;G8zLkG7h{<_)?LKEE$Y^Y*uwe8 zC;j?hK<&0}_;|oKIgknG30K%ZZHd4W3Iql)N)>W-1~ytIpB zWv}pP!k}Yhx!8$48aigdFS-#G7}H5+pKVF7EDYm5j0^O8mLzGiHzwy=OlmXesy5!ALUk7yTMrY<-l`=7wdlTp=)9jh;PMf!Ztd%{ zpwk(CY|aij1glQ{s~^$C=Jj(x8*LsR1QV zQ4|MK$5jl{qVw3fuG1eY+_0t|lf*L6p)*9t#vr&$Q{K-E!19~YF?BNt%PwuMe2LjG znYdTtt{D~lTi?W37q{pHaKvD8kpYtkZn#2!{Z{d`ca&FVx2;{YNjD#z5M~V+!Zt#| z$s@uXS{C(J=*D%UcA@trKDn~uwLQ*V$!o{r2*hhId{%cuI=iLhx~W7{owiqdzna6Z zV_yFF^tAY66fV;;Zvgk9UZN{oJrP-(+o86nTYvpmfIb~92VZC^iwZgnax_1f)kLvK zilRA(M#UwMQBMC9r5S)DB0MoRl0d)WkH1x)h7BywWX?~W^BZ}#k@Zw`BGH*`vLm33 zY^n#nHQQaS6s@M#TS}Vaz1pCZE}1j4Xs5e%{4x#C#O*sy?6P-Cx4qRy%mx@me)uc4mmQ+jLoaOAB}UF7BxF|w&u|^G6U%eDQ7=IT)uc}XDOELT-F|p ze5A70r3;C(U3D6rU0xndh0dj^ZK7*fI;_Jh@3MRVIWB!+@rfyS4t-ghbVS-g}He!ZOw_3)439#%N>^3QysFnkuj1COk>-AQ- z6FC3%LBZonUEaC2vSa>_T)}R#^h@AVIM9VhS5U|)zfrXCN#B=q)MuGXN(q5nK93^k zHl4z~-ESUe9_X|1ib9>Xg0v$pewZ$}Hd{?z!SBlpFUd83fCswG?faOj7bcbu=Uz^l zPs!QrXC7=S5U#JC?xuxJHBZ4DqT%1XxxL7WJnBd;{p=zRPl~wLUdT$ z93>73Ye%KS4!Z=-Ej&!=d|E!ajq4m-zDgvs4S97aDNlHdwyBRFam_reoUp=6ke2-J z@iad?z4BKe^Pv^uf>Nx6bQbRxD`37)=$L4Z9`8w-;-65}r=bKiBvT~TnwP|1SQ`df zR*&@k+%pcrX83J+g*C+V7O>Vpzri{I)`t8Vj80^ohGpJjk!!Z3jYZhyH;C*=z+v z^rh_vT-PwE6uu}VLa=Td_;)7f`ThrsntiwbY5{6%(GnV%B~!@euJ)cm^^ADFS+im1 z>M9;+#QA8!F`dS;-sI{*sg4AUUXX)A4L4)xg^oCqpCo5q@7HDIZwcjzvi?F`r`K%h z&rA9fX}|*SrDqG?Z}|4@i8zja1_^w@3AeG6e${6tROd268Ad7j*G`=e_^U;s3LKXt zeV*i$0oSP+h zTm6t_BeonPWiLoQjT=vnmnX%cp)I4P{g-;VZ5DK}dmkysWH~)Vn=}vqVO+gl39Ikk zL>#%F7y9-XWzam$#&pJ=TJ2tSI;i-(y+x@uakdw^t&Ly&he|{YgQSW_>jM$)>9noN zSQT4~`)RO#r?%bifyZyo^TT{z7ZFmg@R$fs3%ml6yd)BS2<=@Y?B9zTd@Ff-J8N4< zHK9+Q?Mq4gR0c;Lj#TYbdSYNxJdO}eB5?-Ha0k03a?7~ z_VDsK)dlR9B|Jj0i7qwEPETh)NLOd8?!JR)$n{YsFYxB3};~4TTh*~o4+B$#_tEgscMl9V^@S~YqSD*3B1ZvOfrCxueY_W znQRqJy0xt@D-*)Jq*i?3Hv01Odz?R{e}bdLJau!FU93R=qydRU`V4!W1Tz%U zuOARw9j6MJ<-Av-)W{~gd$XoAWyz!V%bf1BH`hn%bBzu7uVJG%4lU1no?m2t9y)!O z%62UxLxA;1Lg^cV)JS;xr63_SwPlwf^m@a2B!>7Ku!`(DLqAwlO`lEe;BD2HG%=l~ zkP-#=!SAVEkW(5_F7CdANWQ^s-Jt=3l%52r7!aE&^u{8@@Ywvcl}d4deVGu z;d24Ee4}$@8+El$$s#aI{7IWD;4_u+e|`HZo#a*~;6;a}4#+49PCQ#k>CWI*rC8z}keMgMAO;H8iDU+JNHFKd$(=esn*%3hK!D`mLtI<^wR|^dE!u!}Hr-Q_uR2le2fgs~w&5_2EOIbwy#V zAo-bmXLtKg6nA9*GW$Zi@Cdk`|9dyO)t%fwd)=X)0Sv4R?`0Ed1$$uol&Hw0 zO>CeL>?B&-&9iz2?6YbH$UcKxdFH4JN%AkH(RUcoeBmQ|wtrZ#uW1%u4%5qPk!db-&3+SSE=toR=E>e|k(k}(+s8?_0oko&i@Va&^p#q#rM*GV zvP;>c!n%uiKGo0p*9*071thhP?7U+k7AtY*gjwy(?m%iRw>zvP06k`VQiuD&kJSF2 zPx)88J3jiH2Iqf458li5XM6en9PFZ4`#%;yLsL{!Az##!Baerc!`?W@i!LK7Mh)IV zSsD$!$o4vA)inXLB^oMirx4GC<$ID)`Rm9Z0ekc{mYa5@((YUDVP6Aug#q)vYxK*Ir;1DmO4aIYf)9W zV;?JD^b)-0xSuB{zYOZoH+wGu5bQN$YqLe&3O$cZD=9#pY_RXJcrVER43~E2=YVeQ zkYT*aqjPTf=0)2K>4Z_WN2^V zdP<)CLq@-{SWHTZFaHa)4Irs5Rk*cFe&0oBsEzQ7=x=kI)nrNk}RZ3BBQGMzpoh597K8 z5lf&}j`P7fp}%eUjC>LI7*9`|a!R1w@$ip}BHX|G$@q{dgbU zgHy9;d@}jNb!L!TvR%gDe}N;EHy+h9)alPnJjS1jGN}hZ{J#s;(Y|OetGC?%g=(NU zfe7YWJwr)F<@4u%0`h?bOk|BdO6uzK_P|XhYckZ zV!;T0ybpBMyKU>9OdTx48GEBk?5Ts8f4jh`S4(nCOd`HNekrJNDWhCfiD;}Ia*%3} zkTgE{EzE9fP-uf?p~Zz9s(2JFUP)skgz}K{91NJ~))wrpdBF=x1&9BqwQ34_6JouL zb`B`JsgSfOPV$m}zDL52d?BsBTc|`U7FZHEG9ot6n=2wxl2)N`fUwYCFqmV8XR%;JXJ6NL~&it{?ur{I{f(3$F|w%Rg9);f4Op9Vv*!Mwn#cBSnQRo*yu;&O3@J@PjD!#D9+=>%5hFR6mZ;6Gb# zZ8Lb&{J9}BJjkCNX~H~fk+is-UML#5=kv02VP(-2FH^MsXhLO!6VQNEFN+_o@k)By z-)$KACohTB?LJ4DM{ak#oe^(`ERq<*gL056+@F&*}DlZ`+K0pbuLD z{4nE(xAIf@52KX+;3RjzEkDLB2}=LT0%L=iUUPfVEdQhFwt`w6=R2a0KFSFwC=EYK zil*&Ba|c&&4NG}22^SQxqA>fGSGk%uXXny4e@xiR_|9-;PNbW*3YFtc1wb~keUCGl4km1;F#o@ zEegBq01%KGg}$E%x*I!uF1WJd|MrohGjH`}gU#P&m0HXEt+7VEi~N*lzgEqm3iUyW zRZ+Ey7oMU^d!3zrub0SQQX%i5$a>T+kU`>=? zH_Z=-%jUtes2UZ#D&1uYToK^x`vih#eMF62HAhemBY5-2Kf9+mF6y%!@=v;35R zVqn2XfEnwru*^mHgUj+h46=7s1Y`Z`Vha}wuQ&gx_YjXaPNiOZF51;>28FK2Qs{X5 z4+ls|^fNB-|NImvIHDVsOa22V`g2|q!uw>(O(EA{16eopSvMym;zHAcyJ>o531?}7 z0wKWFVB@xbI(43B#p#P|?`-E}~5NcjSgk<5LSmq`{WleH$nK5Edbn5kH7TYEm zZBX&mQH;=86<=ADaBvzs?%=@D?D3X}tq;Mu{Y+J+;-}B{tk5>ckCO0QqyW;PJKTnJ z057tG09b>EoD~>gif#u5-(1hhdoqkPS70 zerYMpBsjLH{#Lp~6jtGCK)*BdjbJ{LDz?X8qoxsif}%ZDqTVLI5|JqAi*z!I^2;h_ zCt)Pm2K=;7X2(+_2z8%r{kf$8N@s3*94nevQQ?W zIrV05FDD(~LC@XGzAcRUtdop+ZU1zz{PkU8T3^L-cm-Omy~ zaMNYJ8>x%#836N8qCIjS#68ZT9G5fb`kTyIbZ%$=pQ5;gW3(vR4dd$gF)@_3#ukQ- zWtle(!Dz~6Sq7>fy0b5ck$^DK)>i_sA5C?BmB+WNWdX2EBDIw4*GHGWQLjRtad3<= z_5EgdOS{0nA<1c<-7Pdvy(5tNUN9D!?6435+&&yn-fk!b%A~!J%Xk!<{H70QW0U71 zKdFM{SzOP>`|h5t=cS)W$e;8+i;z6>U2)R*f|-|;ROqa4t$eyhhat=gENbI=2f3om z;7W3!)-=v30VF2_rUwqmvFToRYSaFdMq`KIa%1C`;P7W;LAK*g0RBv(w5*B8_gKWT)v^Q1j;_r@lUzZJsKEiDGQ}GvO-~|fC#dkp)z~>) z(bS%p1YJK1IY?E7W5=vkyLSQg+y6{r>bXqMfP*|uw%{Goo9S-?knBJ=3)Bc_by^aDugj#z2t`>sjj6&@(; zqnuA97&L`LMe#sN3kq+fbcTZP#hoT zQe`R6n$$?jP^vc;j&VE5(|&D19_a(I@Js^Q%rfMAp!{#fCZ~8;v`hxp(r2GaGO^2b z8k!4qnQ%dZNpkG>w9DthzoeHn!GT0*)%@PZ-5ThEB&Jn2|HvOa%hAi)TNzS)h+GKP ze=Yq{bn`-x4{hkhj$&JRO@ThBB#)(2d#5=LGZ8KY%QFSl_wwqVnwj9+!xOMIYUHW} zV~o$s(oa`*_T5T2mnAkcOH&^DV(UB(`1sbr<-WG4A3>%#<{&hqw20cLL*hWZal$c= zF`c34KLZkMBn}8dqnZ##NQOeH|(*9<=b%Yyv{U=em&id{Bs)7hcZqcRZ*A-=(((u3m z;uBi~QX~O734K)#Jyp0+7H;N5F8xVFc>H|KH8(Z??XSgd3IIHGzK5iyTGAFlQ za;G0f2R5$=;Jn?&V)mH~B!MF=w?E%H$bZTrKm0)rek_qadth4w(S`5ryRF*@{TwcRo{&NiSY;H?`OcsMXq!9WAI7tXj2xv zM8z|i*(oY!b;=q!YWJ>n+kAlSy6tzl+W(lNwA=mY;;N9f8^D(-?nIetE=auek5NhG zf|(9V(0eeqigA|^N_SIocNGS{Iok6}z576Yv%ZYp<`kWfgSaz<2ULguJ01{YWOn&R zNt7ot*83EcUefvnvnKtjEje#=Rs=>QWTo?Uv{m8*hvN5e#kOk`SE;;#>e&j%2mv6| z{~7qq3Qb^Er`gEfL5$A4jO(+`_w+fYs{5=2Z9g)Fe|jXxw|?UKu}Xy2H8D||3V7$^ zIhdg9z+SJv{ir;WheE{lW)~DXLHUnv5BfO5ntszW3?3Z|;txyy&P%v?w=S3{Xp<7y zA;IK=Nt+YQ^kd^ih!*OAs;9jnyYAb?@twH8nPX~}q{pCW{~dKvK7H<5D)znoIW_zh z9)i=9NNy(>wYmZC-lQBG>j=s{+wd(Cp?#+_*p9f+UVJqEK@jKBUSGhQ+V)VpO(VHr zk-RA@9eV{lXEV8|KhT(K`yB;Y*(sR-q)eh*z2eRMa4rS0ynI_{^x^O{&z6l*9dZL{veaYU+>ga47YlZsw?)8P7%GG#VJJBmN(EhGpfHq-_4GbX3lzuiRy zM(x1SBiD+uqmY2{pM3w>i|Q8X2>=(D7|2)r3RM;L)b-=OzTU+VpdMJ(8IrNleE;bp z`EHI9hI+_H?<-F57joon)4Fm1r#)=1b2*iKw~;G8R%*tLOlvCtYw|p6S3E@xL>7_= zV(29ZYVtrUTd4aT>lbDic)3!FX<#d`;_|$U5eMqH07Lf8HTZonY+v+HuUb)u=5TbV zYxx)#+1N9HdrWMM)jv3Z zr{+af1C71-w=VB2;sm42HOdQnm4f|(vf|~UKhXIUch^2tRZNvXZcBwVCiXu104|Ms zA@_i;{}Dy;L;5xWc!h8n+co|smU~Q(V$FCh9ESB4@Fe)`y#SE=>n)W)|} z%w4MGhG=^zW5OGVLpv-!nlGB;aT9PsMAR_~_4p(-m^U0&;scdjR%dqQyvQXK0g^WE zUUbb{$#g0_ggq)!Dv9@;8t6n7HzHU0e-<*JkIef9idTQtoHA4ns2B-x(HrX?$ww8f z6#Nic|KTQ{jkdEAOXRvF9 zEQl6&-%AgAv=Az6AiFEw-Pq^8T=ZiJ6Bv-dTWELGNW65A`n7XihbY8VP=s_LFcU%0=_@OGb?p>e;G4B%Hbpi;nuym$qbgov zvc?d1VFyRf2wSle^R;dERbu0|g%z_*Zje>#1X6dDnu*b!W|05R!ZmzkDq=vM$V)`9 zYWe`D&dJ$V`ZZEi1^+i;mX-2I{c~V6KVEUVfuo#@Izzq(cqze8y5((|?CV19Rlmlu zk{de$!{o$QZX5bYG=@NGYv-%H4BOD9c-N(bfO9bv|{?m*LI&t8YSe*bH!eAFTWFKb6cZSd&afr zY8~F=dOoucaY5xqsU*-SB~uA3A90~p-+NamYHC<9LqFp=iY%)Lm$+-Rc}a+;A>inH z(6HnJMxnA*j-Ajh>PP1$2`j(YD=Yxufz>Q=r#I2r96--y11)q!gi0jdW=%T!lNWwB zE8Y#xjm};sEUk|T+?ru`5g^vj@X0#Sb>t{FiXlQv^_e=ASC=ZDx+1H6NO3pE${X8G zEn@IigPAZ|9_jFIAtou8LfV@0JVG1)JNO91+unw|+LMJ4fRDxL)AYSMet3dRY zI$`^rkL{aQyAm#Z1!a80X7FQm)`z>4wdcz8imCTR%y?<`=%aBmTXeeGjQkYA&(^mv zlD6lp^e-rN0kA9{_)uTKBA+1h+sAr`^UiJv zyOE=hn^DyMROV11|xN~D`IOdu+xfTLbtx(7^zxJf5KnSkF z6KnUh{83nz=VZ9J;q%Uz?7D`np4!h!GvAIlR{+3+r@J5}bLSEBgc}7S%AxB zC%3nHz-(cszZK*TO98}s`I%$Z=+?-em=IJ@;!}W6NWYw2U8Dd4y7hlZzz`m;WVSc7 z+xNr5%2w1!GjU|z|7E{LkR(IkFsVX;7~X?kKtIoaaXs`dpJ7%B16##+vMr)I!ztqZt zKAY3ZMJ2A;2$N$H6fcrWe#)2hMVLy;glJZOeB_VPp2%#*&I$MA9+(HN-{4nTZ8)@a zrvn{>5S2C63&XY162%KjuIWW1QqyiGs9laZY1!_4qWv^q<@KR)$srs%NwYbHRt4AhB&9f z0%n6z2ByUiVP%zr!cst)zWUV>?W<4oTj5KX+AaiM#^=Q7@jkc?^tC{hR-)k0$`OC_ zG}}G3PKBUhEG)_rHWI$Uu~6w|bi9su0Yxn@J6ZW8i*Fpiycg~J5Tqve03mkQ8DLT+ zPX+FMpj(w7=x8XL|GSAWrGu84btp;N+qc)6FuFeJbnyQoNfz|FJtk)xAEg;6}~1=y9A`ey7JI zcG=^JDj8*z1|yx2=&rhjw+OmWZYG zuNfQLf6z&ONJ|);0eVW8VOUfnYINCKp=wM)sP{C6wR829a=9{fds4z_nF=eu$|jq=iM9nKwINTKUDllg&XtHdC@Dq3Jn%01MKkCiV?{9u$6s|KSc z=jbDCjm(itFn3M$P0ZOZmwj3&0EF@It;?(kLKQTHtpW*Qc^4rE-3xnO)iZR^mU~ex zn2}liR@#fPR`)Ptl(d6^Ogx1d_!1eT#2-OX2h;yk=#h(*`&*p^w={H0)DO^r$2W4-3T4NZ2 zNhVa#^T7~!d^Qz78~&dsIME*&X_Te>Ic%Ok#}gt^#DhQzp)M5u7*@4lv#i~Syhh>M zZ}{j{GpabHI#cF0vH6%y;KswNDO#)G(W5b3nKTAdzgMfH+IWPSDtf>x&eK(q5R=hQ z_aNa3G>KD-pl5t-`^i(TU)i_ml}D&zt^mJKtWe zo%*NF0xv~6bCvZ|Kv^(ylRqSFyna+-bVtpwupl|gRE;W$*!S2eX~f6QPOl*6tJd4B zlbNn9-P?;Fjn6CrueZajPRSbOZFxu8DmddBX&||)W%MeB@XQGL*x;9njU#5Uj)9#4 z!jL9506>Kyv7zwuZq`{Sv8Vm{n5THtYms(O?!8=SWRAvz{Yny<;!vMPhw~rf`zfU0 zJgtd+LaCgn^L%#Sv>ysfntgX!qNfU^r0f)lH%5nXR4?*(q^fD!7@Bep8|hdev>xeO zU`n~4xob1!cH3cq0IS8Bt>Cuekb~G6Aa3c>LF^zPFIEUtq^s!gBC~YcWI`%9=RN-n zPZI;K%~YOa2OHFgdvi#Hxh{e={Re6HFsW5vz(lZ>UO>YF^>Sfs;xdwHf5DNkEEicN zjFgBLes6;OIxQJ_7bOo0W@ntYB8qFdnZ(^o9?2z8!p?1elD|uSfLHBMVRHBxtpE5{ z?Da}{RTV@qw@VC!40|&+E{4d4)D%hm2^bE1hL_e}+;uZWU_2UAiV%BbkLm&5SoKTm z6FW!BhBSNo)=x@AdF$*rOS@2hAMjD1W>~)HDq(uTQi--z^lvkO4@Blp*H@{ zLQWYP=c_GhcsI@NDYiS!227!m`5q0uFZ*cHOnMW?U|A)92`8z8zJ}HACtI+kxvkyk zg+H%#zub`DB%U)uTzwY=kHUd%eRq^MV_QLaA|>&Fe{UKUyqhJ=K2?A3Wb+qXa6OUB z5RvEv(5?2=VRd2u(dw^pk#;Z*E{t0J+lQo&gIrwz{Il(y2jb^PYr9?jt-AaA7BnV( zw2bHR)jGdM9Hk1S(Cmn~Y*H;j{JZFO3FZQNz!D!Y_?CdJDcgwF2BK3Q^otbeoj zqNdg4PW>0djG-_E*0H6Dt6Qs;V6D$CU+7xWXg}+Cho_OF8#GWVb-aHrZLZ)WKF%JL zi!n_UNEW~!*C&xEx9$D^27Wq&Xk3NpvXD1+HwN?+TbX4&U3D{SNK=k+%p}cP&n}fg zc^l@lm>hR+BJevZZJw<3DaS7RmW40y&u;cLbk}~lyyV}6dZj zv9KS65swd=7ZA~ud7~2tYLlv9lvvaU5AW$3d5k@f)xa$8*zRaRdw4`1`;{zzxS2yD z7QCEYF}Aw{8l9E2UCrB`wq7GnP>7)xcI-)G6qXr9RKQ?9%5^Z&HtZyE0=uRk0bc&Ov5mr`XA=F?|H zcQ7c;$lr=m=HYmzNF++A=7Ou1o$6OYC*Z{+8Z%U>(~-a=(MbubmteqMok}v3{y!EV z3hc9y?U*{uSA z61V6gk7UN!?)sSz1r_i>iHA(w?9#zTOPu@)dH;{8_l}11{lb3r-bXOH5TYBs48FSP zLi93>8ohTCEy^H?-djR~U_$gZj1irP-g`tRN+RSue(!nDI?r1EVzHLFpMCFrU7x+T z?6f80y3lF~|48s4boNu%Xj8$h7F=D7pLOcyG#vXHYvT#CE!28)*bLUM9>IED>;%mj z+7+WOmyZ11$LIHZL}I}GIF~vx(^-R{S&TS_;DI?MahYoQlTzM!hx%E>ErBlYTz(KS zp(s;vX8tdqL@%uIEihZ!s26;U9=MNeZBR68Lg;}PeLYg3B0`g8r@GzX5J-8!eI|Fj z8Okidtw5oZMo=!5zxifEJS`=oK7+JOe0=!j@Rm82l@rDhPi5lZ`{%xdWrp^b%iMuC zh;_!4Q!By&7pU#B%=va%*BoaA{zPo=WjV`3o82v&0OLp=&1)JFw8s8(M z^E!b*RZOMyeF6#M>_^}_(Rez*a zfGJrEWW@kwKP>5Lq73EA@hEe;_;h&;G&%hSK9f$I@b0dKyZ>3`en?-OsYN#;+znt_ z=fF-W1lSJ&TuZvJ)c58NMg1#gWF50GU;k`)?8iOY?!TBBG*q+lIz*1KP3T$|4b#( z|I_`zA`a*Zl)r<8f3`yOkH9cv%awJ+zv51@w1%HT$Nz4AugEcpFuBbU&lAPsshEIt z%NgQT7cJzTGo^^U{tb4kYI-hpz#_Pe`}TRlxCx{ME|tNI_WE?r&(ZbIShK`tz!dB z;?gXTuV=h^AzD;14@1$><(%ozLe9bM%%pXSItdSk|qez|7b2v zz(jUx@Z3OEq*s`SIe*pjq>||38!VjdXQc<#$kDcI;3?8#o$=~gQj|AbVIfb{Cx--3YWgn4+ndhWkuHva0(UH7;z zUVT(2clC0P2TKuoinnALw2x5%6SJ6fO@BF_8&5yg4YVFP!H|K(HqK8@v7)64kb3n` ziVm}!vPFYov3`ix45B5YTIf-tZHS0IT^11(cx@FUTtcW9v)95CDg zAptQFS%^j*KBkZwT8c-?NDhRN!^Mhb0p2;^az4Bw?=dCbQK;&+HE(V9W++;>M(T2ly*3gX+4oBbGR)>jTypbV!7esH?I zAaeWC*vo-TkR#e(LC}Cg4Q5^hZqai z)OY`^yZ)2>^OeL>f*p*j|%LzO}(~&G90Qn`?`^`8{V_X&V zKDMj;4 z_wx^-#&8`w%dcSROqPoIXtVU`F*&%dAv$?b^3BBT76tnlI8rjVUeGDUtKknYYnz4O zCgDdfL=T0&jK0n~-18#Lqq?uJr1A=OpY6KvCCmlCJG_1z^O{nk;DOtNcqS>1yaHs? z`;=_`tDcOX+e5>RB6pf!d|@QZU-Br>`!ezAZuoARQ;p72`RPi+w<@|ROZldT3$7W# z@OnQo>I`YajTDYCh8htv`M+c__>Y3MUZNOOh}0*|mwzqpeZC~V%$-Y~Bm*Ei{>h&u z&nBL$liK~~SS_}|WkLN3?82YqGCH%jajcd5a7aK+rbtv~Xp47P;`@V)#dYpBmC(ex z+!7|Y(nW)2naB>Nxx;=TP&-w-QOJQ-<$OfNj>C@N43U@+wh%|@C2_eQJ|fQX>Pik@1`#g8BN&cxRsq^A0+y4H_43QLF|E-%P)3!5QOhp-H6H}|3*iAPg zYQ_k*{d4Ia*3`ZE(~WOGgO7K6Kj9zlUvrPRTa~B*|Edo)Mv36Q?fH@vKES zm41=Z{q-CSQ=O#i`2Z;+Y;P3hwJ#yz>t!{5f`Bs^x)iC9rRA5!gUL)&6F-3+zoFCz ziyVj&YfWHvaok^VMJd)?r8FFRxpYz+m0pIBbVBBUHd|`c;~=hO;=Llg1}h(|a+dz| zXyCPOZ%-#D^<8LYHj@$Jjfp|CNVUmi5IkN>-NCOVI*NX)X2f8|P$4MM00afp9) zd~rb_tW}drN?1LhsAA+bN=om z32I*+Txu298B+uan<%w!DzoX(bA!&F8Oa#?hkclsHmjy}TN(S#x&HkvOHF*aNM`9{ zIV*DgQp7{j)^%l&+B}CFLmZ9T{DA-NYf>5iH7os8nKS{Hrt2WW^RKBp(Rvi&`;r!K z&(o$f91D{OvLQn6W8z!k5N=H!Z;UE_-_jDQezb=UO@|nzu_SAf9mx7RC%(?RqSN$Yprso7%0Q zV3Kdh^*AVY*O#D#j^^iv24i&I`!I&8w*8ibK=A0;6my&tg|k5_q#$AaoirtcfpzG4P~5 zB;$R&fBJ1Xmb+L=(1kWA=d=y>3KmAvWJ&LJ3Egp+B|cSJi-_ibfrAi&eys8F`+LWv z(}B~m!NP=BM;nM#fLKF2N9tw`dM_bL7zUn|_4QEY^H~^foyx1iMrr~xcY>yk5M2x% zPm?tA3zp6Pas0t=?O!|$QDNWlQ|R5C7k_nKkK{47dPi-!y=_h5)A`~@i5ZX{{xaz- z>&Nsg>j)-`aZE@fUU98AUDhqLd`bUun%hLXCNU{^&w<=4Ogt23_T~M_($a3x;^@9%?e&q}G9@pq zPa$?V;YVZsha*3wiX(f{f&iF*>OB>1{oMTF4Ul zUtXZ1>UQyXf2p&0$G@LpYcXUce8)HA9`%TC%`L+5ThZ%@S>x$_rTo%6T<)S!XHidOZ{mV-u4&mwxJ(tSwx4kzx9c#NUsaO z!o3WQ8VKZm+G!OM$1;hO>5t#=^rf#pqm*T3bDlnNdibZeQLCfr(Q<-T|}- zNI$lI!lxM(%qmbaNyCF^-a{Bj1y6-*Xv1z-W#n<@Q14_qW%(kBlPPBM97h2r!~qkTyUO^5Gm8eW`rd|3Q%mU;WB$TzhN>R%4? z#jkMsUX(H)h0H#g2s=nR4k8WA?;YQn+s-^MK+4snTjNTkJp&S;-&EX=Pp#ZV@O^kO z{%FV8KlMC0y8l^2_E+&}Ahx!tO^z1PuKR>3v1*? zCmC?FE$|V-jwEr3y2l$WVh+$iOB5V*`%GW1?e6=8n-Iva^ZtB1|FsPv@%uo@bcG_GV{-JY@11sH{^GMg*TRC z(NlD5QM%A0#6XyKR`DS^B{w@C0@{qfJ{IGPl$AqzdCagojjP4NOKT35%Jya|0Ki8yW!f>k#qu+b=cia z-l@~fd%vqfBLK8r$p~{gdE*7(xDq|FcN}B`zirXBY`opHluLgIF#57~EAuwcwAm}$ zr+vKocooFN5!%8P&E`rgb`{O=;`R6FMuAer!A^xS>Nid)c~?05FTS9AH@5yrmv*;A zAhnX7T5a`<$9#--o$;U`wd1>~c4#&=+x%9e@OE+r`4spx+zyTH!xhHF#O?pOS@I{} zSo8$k*k_Vy`Q%>dNab+DNt7C8Ic(mgzs`;rgcYti%GhjR?bF@HAMOpC(GYN(b9QG` zTB(;_(e~SqoN+aqqU#&AIRUbXe*ZhB?S%S!xV%|P-}}9lmP=KuM%kqh`SOzJIs?zRnv)LacNsaV?zg8IV0~3^ z(O$Bw#)a>8K-XYK+eWL2r;cA~Pbtye}jPFEC_58ei!?KoldmVR1WlEbce&Ee#qBIBz1Lxy3 z#h?-DRsI4(52FwCQXsO#X8y>6=)*m-MVf|hU6r5pe)soVZ8A#@o_ivgh;Tzzup(bx zI}V+8UyU_o-~4GfwyBAZaE+INScq^d46uGW2>b~KMWyjfcn}aPDK=P^BKdk5_@u{G z)$3{CKD4LBtBGma&(fZg6@8T1^)pW&P$4Y*&*-v1uYLyXc6M$a)PZYFlbXV;lC}DX z40lyvv$Td|c&XUvwY)Hov*He7kmTlV(W07|9ouKY#g1HweJ}5) zY=+lMIblMY+>HX6l$fNI%V^=Atk8gmy5X(6I0IoG{Bxcp13`Y`A@G|w1USF&GXsW% zdF>w6zi;Z@DM%XEl#ci=&e!?KK3YvjMdz9H%8CUJoao8|eY2YQ`B^Er|rMk&%XEh9QX0`oqiM;X2-}zYQ-$$*# zBD#QAkA&s?g)q$@`@6-kySv5ag@s6pL&PK2GJm-;l9my~bTHkH8uaznzduDG7j55w zMK0aCUrD{xp)RRx0tFuYf8@GiyX=5^#v4;d?38P$^tJF%B3QltJL3J|KRIms(XvfO z9?xGG9bmfU2C>^~Eek0$L3~aO<9%(q}vYhw6p-CcL$IiI)qY+TYI!k16V*28KwlQ^GQ(txB z-RS|hDJM(fS@~YMV9qS7E>pzyf9GbDhv6-XAL1^><>K#SzN`cPxa%h!)`!v92D6p3H~m0ucf3Dfe7&YvH`S3 z5dv2@q1h028*6M4?D2U zEge=4V%na2JYHd(lwuv?-uBPQZLd0~>gO{ryQeps9v&lOB=NfvF5y~#RYg#$+d%4i z-t}iBHa6YvXx!h1ub=0I95H<)|456JV(~w%Jo>T7omsaJsN>*k)q>d7=u_+L^_MrE z4HuPv&VgUkfpX-o*wxw1)pF?=#?nm)U|^z6QmZpV$DfWPFN|sND6|bwE(i$s5akn{ z0IB!nnWl$*v<2*+9)qnh{ zbd;as$|Qu#zI3Oftc&vT8VWWg6Olc7C@}*4g6guDL$VJtGtW{rtw2$$wHyh~>bHc7UZr43EAj72wnO=^aYn(MnD6aY&5ujkw4Rx$W0i}`9NTy zyR`Z3?|$cT!^~Z(;5s^?4mmrN1KYp_O45b{KOklQA^V#U)Gh3D3_HC^#M)W1Q|jCy zro;B&9nUmZ$(UO@uyqJ$ydJuCzMk?^!fIH9SXU){S!p?1Y&e|1OXcBM*V)#rXx?cN z6>>RNgBItkaFcP}Yn?2-73Lz&V=EO@h$ssxx3?aWrQIKEj3!^x2nC3wz(%0*bgp_y z^z)=O67Vmu6jZWa$6R(_QB^j-a6|fUf+(F2A-4vpQ5OEmf{OE3wKYanEjgs*LIXZB z_OjkGcDIPv$yVA_&9&*l^OeD_Pg$AVJex)aBO{f20pVl;J4vwEp5BmEjqFL~_hZ~`S=efeU1s;|3NTv?DsmKzy=56ymMD&wQD+Zausrc|4jQA z+gMHkSt45tdU55w&(t?#SQ5-auY61a)=B;IDEeZoVWo2Zt+1$d85;4l#MmI(Ud7rl z+VJ`5@uPTiktC)kB9FA#WXfV1L5#HvL<4J*CFIFbJeO2?G7BdMZ^|VeT?Q&8CK`UE zg-4+KcXGHPaT6lb_%$jWL>*Kp%wO7ev4@WKHHkh7TRQ{x2u|iSiX-7i6zD$qqK|5V z_;SUq{OoSYn=K{WLDu-jtc@?}A9wFH`wt1!dpPR(&KW38%5rjb5_MTP0+KnV@4lI^`6$XdWA1Dg}vjtrw4ev|8k0 zsqbtxP3acQ-JdDFgC)f-Bv!78!3GgJywiPE5EFn?H_$BT)RDR?L20=?=Y*O0rM@y` z)pKo3Pp_7mOr5<&_Nhqo>taIvCl9O{xVy->EO>u_zMi+$1{(OkRDM{_$5{5-pr(5M z@#cEX@59sQWcPFa2dhs*uMzT#{TTh;DycIgOiy`>#UO6C9 z`JPP8_OTF7=~QfKP!~kZDh_|8f101{WIi<*Y14a}F0tP9+AaTyv~4TGJAy`s3n8&% z&TqDf_;NMsBhf-g5RLIGHqF}`Yzo~mxXsZjPtX<-%5+ZhvnqS7U8Ex& zb&;SeZKLi^72ew$(zL%V*oj~h&hyBu^b#Di-kIH3hQ++fU9GLRWjWs8Rj5jST68hi zvfed+`JI>Ow4k)grh)7Z++w`3xN^ST;1T>cx}R}3MKLYxyGib8e_X?1RN7@5aF3s< zHjT%|f=VmYJ@*3yaGj`Xu^U?7>aAH0EF^?Afox;GV@)SyzPolm6ufi*RC-w;Ohoz+ zv!%Gr8{sM9b~SzI&AJS7cNQgO6rT#K8og#=XWOi#xf047-FzafyebxjTv1BWg0dyP zV)LT<`(F_o*Up$T{W+c6^C4iXZrrI`Y-v#bOAUPTt``G0pSz*!Bkw=!eMH6N=IQx$ z($9jeG$te%%Ldn6!Q)>~M`EESk7Q08ifu-GoT;9tCCVJh3{jsgw=({a?+J~*1hk?g z|9IO%*M;m@u~&dpr^2m%pKpQ;#v|b=+4rVfbY{js}oihW6 zt=ld7Wy7~|8$4{iPJb~|XX$Z&W&ZH)l`QFff|Ct$h@@(Mjjx zkW*+O;lNyYc8v8KXVamE>hc%Xs}aKOkSR!51vBG-W?S>c5<}k0otj83^#)$n6BefH zw*yV`?IDN8l;nt6x4gt*T^)KIo`b7+Z0qP}1mifvR_KPS<)QcnnM&UrL(jkx-?<>i ztKAdHn_44zO_}>DyfkP>c=8|WI+RPO^p!K6ZpXep@L zLgoLm0Jb^JW}Ht`yJ-ceI_x+86^#JFG0D!#Ul0p$GuwadG!(z7cmxEYHvRQMN{Z_oQ+Oj z&K}yBGJ98iMS^o?2-%BbJT_l6CB6f^pbq|iO+SPvgCIjz0lF(c z+!ayXIbDb1E}$aJpIX~=`YUAMF!5vkr9Zu*PEy7$chH><{f+qS>{!z=v&THXwtp*P z9JgD=rSXr2aZgl%>%hy{KJ$r^I(CI!4##>^S0{lyN8M@iJetIR1l%N5^v}$!qXzQ4 z|0KLJ=qQ7I&%lbW&4+N(5gcmNWWeJRw^thMH$-g|W^4Ot2 zIV+Khoe4HS#KZzU)FsjdB$BK^9-uGRI>%3xzMYelLtv#$<;yaeu$jRquHCd|sK9k9 z)x(8~7`xt$Yw*}i>{wn>&uk48@=N{5T5&IP_wXi+=<$EyxjSjso#HXJIAmu`)<3s6s1tuA?VGe>mAAjoYoGHG9wRZA-v zR~BH(FF3&WV?;vs(3kA;w;fioqc@V511lQ!6k0I8E+G3$X1CYRM!Nh)Mww;PY*b&L zwGR}39XE$~_%L2tg9Fv$g_mk~MkWQZQa9{yaj4fuA>7*0OhOF49i^sp$sj+;|696;%ep7lFV+%P{<27id(YM+*+a4Yf7*yPPHbnw|!ZF+-K zZeX8)auHM4%pf^CJmF}>Uf=#90uZIWSe%p$vC&G>SnBFU6oiGMv2W5CMoRyT2hx&x z_>}VYh2%A)kv9QlaS`1Lv&+MOL$cf16n5{x&NpSKKmPX?{RG6>=mHV;&uZji11cdK&ZIkRz>-WGWU20guxM z< zC9+e&1JkXgA)-saf^eoYnIn%tdIAo4F%4U)Zi$?ZRl9d;XZ`;`j{m+lC#OXmo4CpS zX@68e)~Y)t6Y_!oN7vDcXFZ0=jhepz$(=r)SMJJnWL4I>V#am7e;uyS{L%}jmB3>| zVq-JBDN#5Kp-6?aEAb>mX2CMo(g4lV^acpLeIFxrKpnd@(Cnd{hdzmMO0?yhYO*6{ z!ogrO=b|q(!p(=<+k}elgrAR%rb}eF>8>tiXbK5z>k8qv(*4yLJxYf&=QKt@xC!7n zV?E#hGK~lW5~1$B{p&G&I&qf@v?7ialR)Nat5Jl__tg>0nvX(im;^9d-9h{t5~w zj?e&p#B!l^O!;`xeT@$b)j&YL;xe~5boSDOP4kCh73)*TZ!0?tc{CGwEl-YnzyiuMhK;ZdSSF?2ZtPr-*{KGgds^NdgMfE-)ufdf9X*>onoRM z-!R)*n@9c@*bnKvPah-bvxi!6Hc3zq=$dxz*=gMC>jmr1PQoo}WG$BKLtD?<0=?ge zRpdfcFl1=CA7gc1YBjxPyvU)%U4p0jfCF-toGi17!e8-u2}*w?ltB30>c3_wHMx`L zR>h&yOuA#|Rj*75lXVl#Lwgr}xRx`cG5#OGfV03I9|nQmh2((yHf%mysZOLF(j15) zN#XRUO@~UbSI(&k!HO?8WcROHE05Ozrn1PJfcbE-aSPCQN#b!<+e zNL%?YHiA9*355(^PYy%|DA0Oqf+z~MQ>VzJLNaG(+r6l2)@cTi7_}5ty!AL&xYQz5 zHKeE~_?rgQuQoXJm-uz6+kQH+N~SRP!R)$sr@m2Of-iTmX*vo*3_O*odFt<*1M8JA z`t+ks&h6ZB>z#)2w=f0d}0Pct}5kBTVjPn<&b+4cvQFEBXFeyFnVE9TwWn#86HWoB6T2G!AGGwvKdsn!XTl(bDzJjROrZB4JNgrn z6X70He77g(lUu>wM-TwSMn5T$KOja@nwaRT2^RNa~#L)so6o6*n^ zJoJIwF@j7XAiQ4_gKEE{3BJuz-1?(Lg*Ac7ba<8MVAEPDnf|%?C zAkQq1n|C5pW!IU@?vH>VqB+4e;bV_@w5!3)iDb;&L-;2^kF;>E;Y|uY^(Ud+mHM%q zP)Bunr6{tgJ@EX+;?(z9CNaV9i`)arv33si7{nJE{y)zd%$0j{?~QC->i2Pl8NX>A z&oTxX;+->O)QN{i7}Q1f_$A8m^pW`I-;{nXKNf#TR)i37C{?$^Yk+7_y=b$s3F~OY zZEgKPr^;~Y_DVjeYEVUfBrZi+TE}}ao1oJ=HjjcKY*S*Kihy1gbm;qzT7i!Boq+MV zQS3h@t%s}N5E94(@9Puv%GbLHO7?|Oq<$G_4*r_D5wp`HNO+8`lpp7T2O{)t#0}PW zC@ms*@w9Q{6l+HsMlzgBtyUY>O4dl>x$8l`v%oz0Q8eO@ae2IpZ7SGN*nit_$4Keb zw*1FNd-&RkU!*$;vw;X$;ku!G&i7{sa)Jp3BPGbgw;}UQ&1fTkHB6?1VwX!Z80Skm z7weBbb^s3~f(f}6)I?VMsg%&v;11@W#AYi?b4hFk_Tt=h%3YC#P_fF~&u&@4c zvB~Tc=OSm@1!NSvxRSBN54W9MbGZS}gJZL?2UTn{?C*1TQurNoq#%VQ%M2ti%>KQm z`&;Du+O}rR9%<b zwnU1bs7tW_SIu08cdP@1q_}RJWKm>)2E+d1c0 zWSy`)RDYvW7qEJfFw}mQBftO`VH{_mEH8{(#opZWba}x_fJ)%D7c)i$p3O;8{R+WN z;mn!pit$cGk^qi&TV;wZ>;8*at0TZ7x#g{Wu;jiWAG-r=9^(^c?GN^^-~E^_qvw!s zV-=5F$${C|AduYL6P<-yjQkos`3#m+b+~mhb4T*jbcj0YKJp4XEA=bycz_0*cRO-F z*I}Gt{=|ExbFY@o%C?%9(Ok2OEUlT+DEb$%EeGX)IzDFbyMKi%Ik_uRPN@-oA~qQG zoInr_CRjRnY_@iec@_r3IE4VzX$E!vNJ0Tzj=3gxhlV4v4(Qe&7{oxmkeTO@{ zsOxd{Ia61$yF~B6cj6HEktJ{w+M4vLQICiNoO56!)EFRfLZ`m7Kt1s{j|Mxz%Otd3 zes!UfTN|5M^t#TUPXpbHPGeP{>od*r3@qN2JF}YG`-WS!7aaLjI+Y}rytIyS@x?4; zN!lpP{9FD@a7(#ik_sg%8%FQak0I->2DKh_2%a6*oI`ez&xqz2;+u+Wuc&9m93DzREwqDi{G)D^xsBj9f<4;r7!+wS0&^b|9QC z&_?g<6k|uyBf*>d9v(}J)md#eQLZPuPJcH6FR6cu`3T$>J>dWGp#t^@;Sf3FqazmE zum6~nkHUcjkrRFvTlsq_H@MTk?c>Kci@t)#XhYWx&e)|n3lQbT^;jaANUcQ~6a6TX z=a0fdY}eZVEbqb5vyN2+iL&sGCt`p+OI9Po_dxsWdqCVdm(cM^4Z@M4^1aHYdX6iM zt*-^mJcCM1oOJ{D;{OLxL^~Zn7jr^m{KH;m_V{sU4F}gY_1f(1z6R;x0u@4Lw(lFo z@61;u%H$NvNimvqRvh&HWHw1N;TyCPSMY+B@ zYC7eMa`x?js{^9Z|D&A6=0Wt(pVF)mW|rIO7_hvE&tG7+p2G9Z8Y*FMF{bg+&yjFg zxvA^5L@r`~=bfw8A03ch29Vl)tz`Jg(q|>|m4$;Xe~Vyr)*$*WghAHDUanO6|$K^d!PySD!dYx^E)R66!o12u;WKqhMUOKqBp(>5ePGbBStfB zfKwWJ)nZxS2LnM5~P|4Tf}V^(n$a1pPs6J_o`)#1ee2GCQI zTCq(F)R$OHk+O37g(!Hu0^z98_j6&<{d{u8>mFAGmpdY|r6~ub&kO1%3?LZgx8>~| z5(jQ_n>%)#2{BV4asyfbkm@$u z09zMa3KAVCy|>%4cezmlyDhr*0w;8saq=wn`mMzV4>z`Wg|$SctlFM)Y%tKy#U=h7 zN-5AEEV_NY-I|BR^g{r!Xc>|nt$xbGQ)d{gEYIAI0>6r04x~o>6|x z39tRZv6aiH*vYa<9t8u6{I+iuQdHzN@6w)!e)v#lxnq8UnbHF%n@Z^Emk$5mPTJcX{+-+6!_AXE* zMZ5s}S~+?L6jbLZw@~bHeV;WMHuE?M=kEJ?le>GH)^BiYRc+plfjIshBQphbop&juO8E7fDmHZBaajF4O20!y^-(D)g4e|)10Edssv6G+i|(C5#fZq zO4wx+%yA^@#r?8R;jKS1ChaHUPb=_!u7p%c%ckX;WabJj7tQ>WJ@%&*f4ElsGq=J5{`Fkz8d0x~BRuXpZdTzB)+u19!&XG`y+q zs#EED(OAK3W$7Y1$SGJcy&%Dj_kqfRQX}KRd1*+=sFLM*nuZO1KtZ&qYLZ2O`FALrivF^CB+pGF5JTF>Wo^ znZ(2IRUWAsDsjiw_;xTBkAnXy^UdC1IHpza|3H4%l6~)GiB;@Ou>b&&uRpJ7v~8ea zncZew@{ZNspZ_u!X|_?M=69g4w`#loT`Vf`4sUbV5Iudh>QoJ=CVnpuB=`EoIVF84 zbZ_Q8m|*QFMz*}kS(2Gw&%{ClI@O(FF)S-C%x6rglrv*Z#RUhuT+D@XOur(9S&ziy z3tR-Nt8Aj48(3S~rT>v^Ye)}CmgtqadtKtXnsnW;KoS`|_H*}tjS%p^EOtbw`$mY> zsD>}bf|G>gk<7(U)EL6HT90%Ti**=+N1}|S9&gak_?=9wtM>4?@w>0@B^~NKJevRQ zwl>u>o|qFQ&?)B3Ih`D!#NB@^*J5N}ml$ z>W7p6-FGr31-d6B6aOL5@>kDFiglz=L}LHGpM;HhTDIGm?kIM23j z{9Rj%FoZ<5{hs(DVV;%t;lz;RHGF!g{OM8#oxT!mug|1k^!E0J!|s8^G#0m8SKtKm ztQcsMPdVZpInpBaLBa!Gvp1gxxC?H7+5eS^E1`5z>&R*MU>?V+jg8%0A1mJ5c-$Yh zQCcSj@&|e0q`{$j@dIgr)?u@pe8-w%Q>Y8kS`{n$ZhblXIE3?yN*`!MO&dmE;<=`? zoauUt-ui7V{ut-?e?|0A_y+NC`Kj61;7vXN^ZHZ6zxvN&d4C=+S((rcq$`0N+pd$yZnB}&oQB*_pPWql7YW2Bkmh# zGRFgKmUQN>ba@Uei?Fj~;d^u8S&uqbm-|%wuB?6J14Nb1)2n&*m$z;@-F0f8-S=VA5_Q*z9{h0x7HzWT2bf^8s`t`s1mO{$CmtN7X3is%dAj&Hd(x>C8QzYfL;p`gV(4(hSXyH&e`8Yp=41VBVlYg=Vm)rC z>CDP={$aI?kBm2b4rA@A|IpjD;MaQ3gV3JeEy3AN>et$noz8>bhHHO) zdYi+oO07?mniz6A>E>+71giM-9=?CE6n`x$G6nm{Eb*mzF8!7%p!XxYr{`~N>E17; z9MGWYG2}n#+c%GX@!V(J8TCW3A?lQr|F}JEr3bpA7GjvN1Y9P5)97-0+DH#XuB@H{ z_x!ti@40YEH=gavF-GgcciWYR{whZ({{fPvz(#N&sg_p1u-a*!cmNX}+R5)x)9!pZ z2-aXu{C^YwIKO#-xFk5{+VY_g>(q6=e&%ak;4Ld{*ta-iGDFdbDXStFg`BdHsD~EU z0*3jHf-Qh#TK2f<*txJAmCi-Uz?qga@1(_m3)W)b5{o5!40_4*ESJKMn1ZcOZ+6AXY@LeS+F*920Gr<2oH1SNnDxvfNF0NV}|FvXW(Gl3a3kr z$VqUFz??Aqte$jU!7&tT)`=;2cB|@%DLZp6r^g+0E+5%XwZkM+hjy38j->dUc%MNL z)Jf79C?^ydJ`smCZw7^uL5wjIW?ItXkq4bZT*@U|+^BZCyI1)yf=1`~G&gyB4DraM zd}?~zrjW6xUwCLG!^k%S&~BnOVyA!RaI%i~=QgPDpU0$9~4lTah@1rAku-WJC`x9p_e0IPN!pS?T}Ob`F-mo#d~ zB*^PBNH16@_*F+*)U&9%p>wynhl1W`bfy2o)9pLVgVW2DL&d0FlYf*79Ct=00v9QQ z`jKVwq{MaiKm5UQ_HGpNojrx2?BqsS`Kc!({IQ+F^RFD@At0rnonTHCX|^={B(*;nIK(&hLd=h{+5-%(uKRBz>>rO1xSv?efXV=?s3T@M^(v$rhjedroeBDOKu;k zW<_Mi0ydzDe#G#02;O{O{!Xyrh9gRQ<@8%Dk69qsK5};4(6ET%2MNOmvPawmZ|zIe zXgT9y1#k?ZV?n$o=q+ewEo7FN?rK)$>*XTLXvA^i22K;zpS8}LU!w`+(lZZdv}?o$ zWY24|kxKPri2-9~wiZ2qYMEzEruj{ic+`U3lCVbb2mlfRP$(nUQ*dz*M#2S9eWfZIglob)$|9CtQmsRuCma( z5n4i}-w~UBTgRUgp5f(Q1i~tN18Tk^;1AyBGTZ&V#q8mkSN>!SNp)?Z+j<)o)LdC-C}a9Qm|F&3_G(a1 zXQA)|m`KzaZYUsWaez>3Uz;wsUaM=-n5Y96c*bBi}EyhZG_cEVR<%-G+)(uN{fXWLEe-PHsTMRGqnyTdojN2ye{%H z#;9c}E7~=3tUN*e4$4~0^YrvpW-D(~nhh~@GR92a8-SSWK5ta^4ZaN=sI75Y^9z4wsMIB96B%W%%ZbHb_+Q zPl#by8@zr?`^?=7rYjcD3KjS_cM0AkJ`x(84zls&Z)>_Bex83Ka_ej?i$n zLirIcdiASu%-9QLpXM&`yQ3!MqhpWkL(9KaTgdS9NM85FUSzPJh_Px2=u}>-IR7Hf z3<&L!*%@t#ZhyP)GS1B;$BL3kNFKdrKSXYh(%ECNWy4F~2Uj%Ur#-unW!s!9-==*c z9sXH?ZZ~Jk&R0NB;T08WzU6DrQgpANrCD&}CaiLLzs2FM^q)vX+fq_;aCeB1M2mpN z&pQH)RSe;>_no(hUr46kv**6cgD~00MUQ9`(J>?(8{V4lyMZV~Po_cd&;uz?u zHax!dJOp)LO}Jp#!WKKnuvOD}CRv^5;>~icZ5wLbzfEohomm`yX?o8@$yr**IWOoZ z!%Z`w$&Aaqn*x6c(L+3?+D?6l?j|1z*%5*X+GlP^*nz5bYeWVt-yoru*WtFpg(?3J zQC}I?zs=_1li%a<*HPrLJ+2lQs1aT@9!bF4otoaT0UZVKT>7cB;eE` zVMAo|B)n;#c9Xon+cb59=kkP^dgP%&Ycfil$BBvc(ss$RxnA@+Bl|@SA!Jq~7wS^* z#{D6qzRp1PKh@`(*%A2?KSiovwaG`uE*?AM(&`NuONnWk5lzrL4a54&S}KQcJl_HXlOX@8L{m0?r#+_=LZZ)XeSZnWaQ~j&Gysv{`N1RT*@~DWbW0 zl0_-!PT$A$`p_2EywDjYqqaDY*KI(DZ_LAGI%)i3R19$}+${|@&d_j6AK>s2(h>?p za4d}Hltq!NdbQzQE8TzG)Pmlu7_a&ryRX2zBg<52!CJ)O7>Ez9)C#*lA3Wx|N>vdfE3&&g0JY+(&n>R*3r!qM3Ljba zWXCD&WsII0_mmw=I(G5&Z`z)(S==`1Ry?EfP=U4AI2D{Gk$_1+JPdjTaaTNK^r|Y} z8|!MwG~6^Yt^PnR8&z%1c&2y`dS@;1GIj|(LOl6OcsO3ym0QZ|Cg1kw?Z2&PhT~>A zE`+N*m+r)#owRN)LZ8#NcAThg9HhHyw7^{hq^vapq_U=xZhCnG^{@5 z;g%C+pm|5hOmEfpjT13oo)r-ofB91G76VP}<6KPr`jXdJu5YMXOOXA!!mUuSK=J@) zR?}MI=JiQ{(CL~5n56Ab;|wRq5i4)8oEd@;kCy_T4A-=Oh3&)t7-NHjhDJ1lQJg*- ze_Lnk^K&inmqRAc5g3V4^;}V%jXl}g9T~2DN12{R%cba>&b7piDw>6M1 zZr+#Q2LF07o{*_2^gcuIq*3DsU!p_n*H1;>U&CCIr}Gz{lhC2S3+AC z%lYUEABL-&3cfa665s@Lqzn0&lP7ICM`~SeQf~A$;TZ0@&WtbtQ80s$UrwcXfR>jh$Ivfb|=N;9CYi z{HLktK1f6Ig8VX}#OiXB;Thc+!_|P1xb7d#;XF)PHWk8p{3D&vqt9ngtj*18>>VO< z4kAOd>iS4+)-CobKF6h6F+4S$bV<0p17pO6_G2gF-YQ(4*;##*=V|DFYz6t-t{YM3 zntIpJwOsCdWvW^So^0GU2ebWd3zW7ILR4KI>r{)DabBM=}Q zo282KD{;T2ZsgJ%WxBK)zoaDk3wi3I;XSXG5JQn4AS~M@$@05bPC3*oElZDJx9f#R zBqt2))!~!~B&V{ff66iWD>;-kHb+#}<6qaTCX8l<-a8xvF3J4;OZ{EROL6u-OX_z6 zh-g!lx9lXF*akK{ez*g=-|&>!3zNV{9lVgErw!5V(l1V?%~hPsGM#Lw+Gj}YPMjK; z$TOmI+`?~qb})&I3@Vfj{W9gC2MWyY#V%TeajZ>y*V5Ia(A=%Go46hvg>J-uk6IuQ(gNHh>sX@x-sxj54X5H- z2!B^M>n0vWK!BP6mpi-q^u@}XA~%!irYz+uCsjf_ZfYYQKQc~?fDdUlt^Twb?Dru) zAwlHw(DES@i{Br7n0^s$SlMh~GWE_y^_yohHe|~}a{TbjcD6Yoq2cvswLM73SNQou z9dp`_szm%8woeT;0Q%O6D9>WMWc>q*>gdz_o-t}JG~9uJ^Tsq0rR<1;gsAKNv|hvc z6Hvur*X5gQFMUbhs!D zZ*+4Ev=i)i)V8Dv8E~2Q%ZEQ#SHEE;VM(tzI+CznVjlUr26W`QcgYik65kCU%T*Yh zlwjlXa{Ycfc(DXhc8VOD7 z-(YJ?`CZ}IbLZEwo6W`kij`d}IawHDUTs<$?!CJ7j9RV)=v>gwg)IKr?RckvbYhI8 z4-D)pE|y2pc$NblX~7!m8n=Yu6mT&K%+m6SE|1!C_8Jgi`O*J1H*vLBUW`0=6n3K$ z_jFtNo3;IDT+yq==}P~HgoNS%9#3^MHaCARCcoF6z_jIMKKOMPa^EYl($;r(p;0|G z+rfuabAZ7&iYOgz^d1KmY7iLM2tWp*e^ijQAFQp4x%#+%;{b@VpD)um#b{c5JZTf2 zoxDZQ`82DcSlmVp{;Xp`gkwO<9FLkeK3frqhw%`b6%NLEKLr!o(6p__@ zZpO|_JW>X>REalyxSH8U2T&@t>^QOZMH=G3bSDkMr(Aq8d@_}9vH8IT`u(nP3H3#6 zGhPVfG3w*4J0kHoGF89eb?AYK6mR*8a>@?Abbk$Hw5{au{rj$!z(yd6a!e6zX5x(^ zyO4j-BIN*oNVLKPM8Ezx(<7m+O574cF2F@!)5;+3X)$u#YRCcIv_(?z1Vo%~Fk5}w z%D~|>9Hag&jFaB^1>KP&iKAhYsrZe^v!LJN9N$Gw*RY%T*IgCa7gd|r-#RVQm!R0lQA4NVx-(;%1+^x6Y6{>q$*4>d1xQ@j*kHBcBy2F1{aCbK|}`G>j_ILAMlHEbePx zGeoBU!n=EhWbn^fA|j&ynvL^f8EdC0!w)oqo|e-o%M~-=fzD>uL^22WXv8Ll7hv1Y zT2FO6*D4Y|s0aVj*ZVM=kcT3Pm!xzP_^ruHrJ}kLYcUD2YP3Nz({WvLcIgI&iviCT zm29u*r{*In@yzO@4}HX#X18bxzr5IzMVBPrHvwpLGfH{n)&uqVUa*v@SnJ+XmTEOFD&kr< z7`E%M$y-aaaa4<|5=I5|9p8Nsb3U3G$Z=12)(>UnF9B8@Z*+cm{--4-d>p?L@EdsB z(~d?YhP+yuwcYra@h0?%o9UB0tW1#2+n!XB!mm7EowTf?dn}Ih0AKilQM3Ljm|*832OO-Y#_Fz*0h%U=N4n zhEJ>yuZI%#|B+YkRNfvldg)MD}m+=+YMx=vD&Y+PD($CcQt`o*f78G?mpCsKX zotask&cIi3e`bbim&32c?BQqQMZ#oBh7Y z!aVAk)%EC|`n#NJcbn7)I)C%CfQ>DHf@-|E1-yITdfR@A{kTCaF_gX<5lA7QGidsw z{UMRCbnv@^{$tQz+&t{d_NqT6_b;M9*3V+Q+7Q5i!gkDZa0a|}(I*Zn4jH^*>YJmw)PGQ^4h2RT>J}fO#ofa#P;=@I?~}8GWtc0 zr6!%U=xfH>hJ}wfT$qA^I9YFC__$Hd`nPk9ctC!}dJz7;=Lv)|ZX<4rugB~mzs=kb(lZlpi@@J7cjCMnQW#9IM|$K2g%NAMNtzQN{hD|w>Eyz5ISv0eXv<66RQ5+@ z96m+%CUg8)!agERf<<=bR%wJacTlOPoYBqWchAD&%Gz2+ydyx2cJ{<24(Wd~15=+! z{(Nv=3OLqyklsy79;r4c{k#;k|CX&y+ER4!u~578;`6ffA}Pi(@ZCLCV3@=#WB!q_ zS^)6jy*%Dj8-aKW=W~EUjUb3|dY7%gmP8~g`?V_s!>994JTc}+#+LRet;M=iNU{d` zG@uWeH~~INqc$%~MBlp*wSaw0urAX?JMsb;OhK&dTIw>sHy&yJTr)~jqw>bc6^2~( z7C)*@=)Hyvt{Mt9;xxgTK0;=k%8~hAQ&Q*iaw#i&?<#~f{qkPpXg4u&pXL>U-(5CY zF7SyPHVqa#5^9OF|7b6y__0E1JxUb#+Um;z+|@^lQA$^>+T+a<)6}lJx9(RPJ{g}? zy?}BOnvApy%#8vxO1R|D%DV5m={&Ia=y)#A+ApMi=eeX;?5VNGWyky>^+M{3(Wty! zgD+y3>X>shVgmtLWlER0mqYnm`}29dE3CrA#uF1#o$_@klzmx3|GE)RNr<+99RDT% zJ)@YXXeezA&HS0|(RCq|dDqGfq1Z3rBNR|3`_0M7qgXb)SmRS)!2S?Jv5pBt%4@t4 z$2=-{MHR=rZASy^M41OoNer+6&C@u>fwZw$O8+O7`9*?<&#=(WD-tL5yj>h>UT4it z`Wg&s!W;rjLBaqpT~fRAMyXQdCq>cr2Ww0BLcqhbYf2mI$0rftn51Sg%(CkHk^U!n zMAA!X{j0KigA}G8DFUB>aI_07f8A2(47@RBdnUgCH=zW_1-em6@qj9~Ipt}#LrLri zeQQ^tJN=Bv5M(WaV!OC<>{IjhLqcTA?ZxQ3`h^-XmSmS<5OrUf_^?XAyPKl*cfV7U z{hSL4BGxyn?^M{|j)e7Z6Z4iSbM&E*|SA3zgK zIPx(1`=(B<1p_$Jv)ZlYVaj;jPffhrL!JzUi38w!#%G&n)1K?)cwsjA-{SgECZ)Nc zViDBD0k_EHFdHXI7F@pFGNv3c__ZP|LnIG{2?d92Sl~V*?Uk-v?OpOp-*;J+v#vb* zrj+d04Jt1)a_u`lk_qB{(2^%0-~`&T>qRN)ZB2E!O`4eUMy|d#5!bEFajJ%(nc=m} zlZ^4nV#_i6fUA(*;N!BfU4WN9nM^d`7Mq5vD3t8Kex{nmzV~NmSJ?C%aZ{LZ>2F<$ zcl=_9DzrhSl7ybz^TF)^sAaaS(+d%R^VMC%3(t!_TC#HT=-|45_czTyuwe|ZCGyB% z#hGTOG0BXnGNwQQ>Z9#W8{bX$c-WfbiS0#!w_*WD^?crnq-~@Sp>|TwP7NL%#cs4@ zzXy{BiLY6YOtV}4(*$(eX2G(=`~4hj9XWyRGFE@RRN~}PE&71tj1f&Cy@5f1(sZkS zeeTlJyS2%RgPS0&%R9nqf)ow7sYtljIas>J0&eMk_UZ9SxfdcbiF!}@oU(Mw*amze zzZtkGoMI1|nE~3qD60V@P%k8nGdyBF2nTIyV=a{s1Za{Z7jkN9$G6g8PAB@8YnEX+jk{6*=sV4HHMGsi>~W{KOAyrFUe!?N`k*~KAL1i#UQZ8Aq|6+ZVg+&zN?9MG_V zAHtFwi7UsTuQ<_pDX)Z)=S?%s5`-c@qy8bG!;Fs;S4kb?>)~}Du^n33zx7YVh05)E zyYDt}`Euy>)|_4O#@9aN0=o(f86JHex7$Bz<7NV(rGGlAtHV{W<72&yFgacAoD{p> zxfAvj{?ZPrmzW%(@3Y7{W`UnxN!L>9{U98J18*9@jf2Xn-hk!f)E)C$6F;8ew0!fr zof$Bp8m-sgx_LP}!3lmrVIX{ZN*aCkc6t5T?;8NJr z{=-br7Y64d9uQj^Ibv(_#0~P9G;Bv}d|TiRAf|#&bI#K2a~{l&{#*!71&~G@9+^Moc0jBcS+zwOdR@J^ofpl zlm>73NDWfmzXod%GUm`A%c6hm6y?A6LlKTj^>Kh1nYdDSwFm<~G8=zJ+Bay98;w@& zz+?V`wKm<^3~o0&dD@No2lajkMJgX)xs6lMI6A{2U3MNi0k-wY9%2#s#~eHa?SGf0 zF7pQ)gtYJds|Z(?-uv{4^k7Grf&winh-+{KqaN2B(*svf_%_;N44pC2D6?a=VRiQu zXdLAHjtSHwgilB_hD?5eL(5ZMCmfHo?1dr16C(NU@KIZXX=-ahDuTWaKMqlKn3^2TSyB_PE;n zXE>n40Qtxa_B1|cN=Ii9!~A05xCx~N=G55rht#R^Yl{noHG4MO(9ku zu?X*P(g_mR@Td<5_G2DQIusa7&L9L9NpLbk|sgFgy!5mP%l_?1RM;?X@a|T>jaJCSFxH9yA-^} zx2kW;Gyg9OAc@ovV4c^n=rv z&1=Jg%LM)_Jn_|6H#>L}!c*4Dnt|bL!6So1Nq}$-GGV^{QMp z$5V#^rj4_HNW05L>Zw8+IyClTg45RzUlW=v`Dy3u#!Di9DtEnBizkZvvMZ-fnWhRj zsk(rZdY4!iCQNbrx^4CTDEYz!5V&c8hQzDz-m51a0L*k=+jwvbf}C^3%H(MMQ#`VC zYX+(22L;yQ_8qDm1Gb-bg7=MlEYwX$w*?sPS^wREZrq9i&Z_JMf8F&B?6)Ij>Zvp(5kXM5PO{&tO;G^f z*Vry}+z$YX{yrR>>}NT$*9F9iQzUG1yBe~-$ac7A@O09+P`ONBHD1W}QjfAz_qppz z90Bw zknMEPQEIfaN8!>Ii*LYDMlYEQT&?iC2yu6y^3EN?ojm8v|B?Ic-#w=+%^rk6?P@`9 zPg}NzN{YIH34wJ@ynHJj%+|}?XQw>P+G5T)E)~EP7 zdD=GvFs0?y9b+w=SFH+X){?@7-T<6R4l=1#{141wvNsRgtEc7pc#Sgv0!b(}AvYAl#bA{=l zo;Y%FM5l|S>L|~*^=}o~9}r8sp{&RQOEEu=B`&$92b|=56s?6dW{9Vf#tAR1W{T0x zDHhJ%QWyNipKo4@yaszWEI5lsxx6m^de2o3lDy9w^Noxyg&iilw@7o0qsk{c%$!Q0 z$1S-u=4K1W*=Uh`%fbF0%>iIzWS24lC4o1Y?SG}(iu-(#9JIqdeXyZ68*I>-K(1aWqid;KNeBLg}5p zbWC*I_eR+~Z~ka(TO;Wb!Q4U14q~u)xb^iJZ}+()sh6(!JQJ$hjY)*I6nAU(ah#_^ z<{RO-AiRC2u^-PUC%lIh{ku!!f>t=pc`y0ZIGA<<7?Bh7!vvpN#WtVgmYM;!zOQ)I zE+`Y+ogyyr1f7RC{rt6`uYzsQeTCrk^QX9c$h=eic&c+L>QGMwuvXC@fr``~K*~Am zj&Ou(LdC%_5GsP=HiMffprEv$$N|)-*Ek7v*@b|CT*=x4V*h_SEvTlbP>RRwq?WDLMDzA@XCLP} z&;2r`7yO$IRDU};fU?A;6+;+^;C=P{!qFt}(mL7_ir>ogK?PlnXS)fH@5hr=k*SS?k#g?NH;;x3CNtLl0R>;41#*;14j)B9C}_2t(1$t(_U z$txl?rxWb>a-K6OwlLHbyPMn<7W(ChdH-9h%Hm*KeN#YEMT;-EXAI8da~u4sMg`P&Tn;>^SMIK! zZN43FjZH4~>=x>nTgdEVwTFd_jM#P#{w<9 z3OCZ9bL$kQ;8y_-y1K-i8QZ;eb!yUhvV0+4=3T@|z;=;62+O-tr!)4)Kk-SC@KzMp z0KdevSTJ4dDDP-~ff^I`ef-RSmu2P{h$a}G9m~K!{Lq6o`%b221JLXGkUccyY z)NCaG<&;YNxVq}a|!$hl?-kd1^-ZBl0TkZFpaY|I=PHxo_K3W)4MSp!Uepuy8eec?Z@&0%nk=%m^M!E}A=Y2cb)FD(MA zNKbg~y<)C{qc56%yZkfZPvwb6ZuDUK6rSZ|+rxXKx_C3XHiqG`Jw0O%o-$W^;)W8O zDY}L+kUN#BDSCUHRMLA+ll~BLMa1Lgx=@>h4opAn*O}MHri>dsXACR89f$P|vqcX- zK}9hhQK+UlTu<`1-TGcGEdc-0E&C9C%gFL)@$5!K6w#shSQmwl8(2q3uq05b)4YJ` z5P5EPe$9TO3BMcrD~35}*(qEuX+w`)S|dg_PPDneMmq`-;NDG-Do!l*yZcR{0^dU6q!#cu@1DzuZG9GkC_zT*H?OMGIX%xhhB_!r3t!10s)&ef_~ZI-G<_yRPBc6O&yIT# z>ql+ax^fV8iX(f+2wA(v)$)4&iC@M3jFFpD*ZBX^X;*zQF~^#?x7vmeu(+5M=14yq zAn#%Q6L(Ho=%@D9-V1@6H&kJ~UECe)?2tYxn^+1j5iWRNXDD$^U@+1{{nEs&X2$83 z<6eBwH`yGTL>l$;SyApPLwMOTO*5{)8w)v-pOAGis>u;-mU?cB(${ zE6pcL3rlZ+);;!JTWTD%A*Rhu!G4OnF#nGLOyB!g;j-{3itDgH4b$izD;u=7GtO%2vt(o|6i(yf8B{<;Hk5@6xBszX3?cl9TT&{COenTs};L!|M9lL^oj2fW4 zR3og@SHXa??hf{R1~uzil}Yw?w7DJ4U+vYkB)4=#5WyAuU%1t$Lq8SS*7GZ61cj7& zcxeYV-o^Z{3#POo0saA8@yQDaZ;VMT8~-d~MbI%5iVH!Ekf;ABHY1h6_IavI(JR4W z#0<~Fx!cQ0x^WrW?pKdqv6^E|5CbUBfCxP*y=fhJsRzS=CHrysdUn^wnBm0EF~(`~ z*i8p?M@VV7;17AFGpx4d&N{;y>e*y*K4qlIT7Bqvj)^$q9|;(X7|8YmG}q6Zntlwa zN;E}Ao^M7OhdVjeU>iG60(Ftv+Tu=F#j#W9N?b5;qj14bZ(xiJ>grGeC!6pFd&(~E zauiFt2VW_*?eT>Ee|axuKkP+LfLYHpei@IGx)1G=>EyQpikuJVP_jiDY#|WF_VhuZt_#p>@1pi67d^w&CzlsC_M5-;uE~gKgi&2N5>F zaHa;?PyfVkStG@Wm~^`vz)>9W0RMH>s)c77^Y@k#=una6|I2f=De;UaIb*nIZpZkw zW~R^63oQ#<{uVNDgEVw4XjB7%UMPxWPyP|R`x%M4lMZ_$Gg=9OMNJF?tNqOFF1YzK z&J$hiM|KbeQ!jkA#0lc=OaJrt^2N&cxe?2?3RLVwPY0rc#5cJ{%(W|dV>KwhXMWD> z*AyJ>S)PA|g>;g{!?33C>UR)I*2G;F9wqgNJtinX;Jz!991*N6cN*K`sWF}VS!3CC zGPyZ6uOx8P)9M5Fb*Z|Rc=2MQ{<`tfq=vj0%{%y)g9G+gF$O>8=2_cGQhaH^KPlN- zQEmy83zk3P+7yaoS|X4*aib)TaeKyWc*u_Vsy>XxK6~$dD_ym{t>n%LvRPoS?mJxG z6(&4`i{};!4iuV9Apn2#WEGM$$M%7I-G;iH0!g(Ox-AC)8AENgzHT?Ntr2ulLT>)< z8uu~+q!ou0)Laxd8a-56bLb8aWvnTbTVmox$?N+PA^2PAbi*x9>Ld#wGsXeksg~cq z4VH}AxK}jWwU9Q*pwB@jo?$>9Uey=nnLa%M&L8-X6l*ts{7+RSm)ywGh2&&T~RC)bxdI6k3 z`=t9X#tY}71ifUK(<4UM8k)w*9n94FUmp1&}Y(0!r4)*-`BxdO=nz5JsWwwoMk zg-0cfLcRdxP{q{#-OdqTc-|0D>?V!xH#rPs(JGSDc+;7zH(Vl<@dIggtLBQsWe3Ic zJih}4T;2P#*dx9||6)5JGe9N>_nb>^fc;n`K9$xd&ZiL(QgL;Z4b26JuGrkT8-+b4 zg7E0cP~W-^vFd_iY5HiEs?zvUO$u9!?BAzrGU6dJ6$)sO87maB; zSIaG;zy{TvJ_`xaZ+bbs7^1GOeq3E=M~($_(h=t`gQ!5|0Z4(872_ptYZLP&ct5gC-rrfSH*46rs{Z!sPKfYK+A zFrXGO%X~wku7Ek-^~n)vo(ccbMTWS()a)@4guaF}euk&=3Sx7l*U(Ls&0)EsyGIE) zQ~Ajw;$^a^KS0#$pMhFl@_{n`^a}UHC^on0D_lsPMQ9S0^54A9J|;JlgjweEZsXNV zKQyKw&T%5V_O9n)KLE8Tcl=m=aZgZjSiLzBWY-jGRCi_$pZm!UvDNeT`1EPdsTGjb z@(Ku0=5UGvhFw-u*445Ix8%BJJQf{AK*}_3A_8L8%W=Qx!v}2@T`TjsMQsm5zv9hf{IxUj{=2?*sPkh* z&*MvN_LUEal>^6-d9qQQb7sclW2>s_FH*f9mvGE+RlIRZmLX>NY%u1=d;a#1Ol$Mp zzw!Pj^t2KiEzarFo@dfJeii1`c^7>X9;H2KP4313h02Czp3GN;h9X=prj1luS#$xm zJTg!ct)FG3!guvg7DoL_15s-#;VYFf3*n!ghQZB$>Oe1Nia+aEROgla*4A@SkG3ESw9FNw)_bnhguftpw0bR!?vAq zJCc0_R`>g~)kU?JdUKTiJ1mY&?b_U-eA03vWH}`mT_1lcQoe7Q+h(pGXj)F=`6iXF z+vIf3T_FDge>%Z{~JrsCYYllD;-agg6|kH4Rfr~&}eEkNj~YWS!B}O<-b5U zNaCUR5%kZ+p1#2WQ;1~+FU|HYYEejdi;u{_=_@Q7>A@+X&y+ofnr7oxy%ZZK90avW zl!PBTXSjxT%NO^IX1VGVN*(tab!N6W#fFF?$VYGg<{vR>4=DJJ#Zye_$=zdDX2p`_w1G;ZWPG&i9~=Zet$zv~#n~sJ#hNLC zkfA4`f?j4JEZV?z?;i9>W2i?=CgpX*aKC3tlE*}-Qc5YX8#b*ojmUppmYQ77&)z$> zc2$Eu9=KUa3T5g*6RtBVG>Rh=4$cp?8@BwBK9V;Rfd2$mSGO>GP-^Nq3f<_iUH!6_ z^OLjce-N}6V$Usa>6qM&^*`fslY5|+-V5?;%FlT(6VRadOd#5aERV?E!I5Fg;md2K+nb^#amH+MSaGWYPu14b& zSGH}$Qw<|1fxzZVHr?X4RS)uLSqi>6R|_XFYm6H#O&ABKdF6a_Es`(aV0FW);&T5s z>C7{B_qm~ys7TVSH&2pV-dl;MpTTo^?(HP!rpE)7Bc%na z{mN#%`{{Pjns7Q{0_a9cMGx#@cLo~k1O^f%D7&Oql7;c;t{AsCG3*Tx{ejua&b^Sd zo$-CjGAqkx(|3oPOP#w)zg&F#I*PpFJ;rLnh|jJ;(|Urad}J$HSrM1o^auqC zf5N)fk_JvVL6c@Q6umeH2`_@a3DDKDl?~aG2#7U&5N&Nk%g7w3U9_s|TxkDEb+Au~R7O2bVV+uK zLpMUhyK$O|Yi}nGUw!j%tvn4_UL2;Q{!B2oR+Ra%>OA~!&=b9tU>uN9DOGY7RGVV& zyZ)z}Su}`w1jIDX@S9q4xM&;J6W#{R>Q;*CyxylSNt+k*x_A%~+@t=&V{a}wgTHwT`)o?R zqH-+siB0f``=jAbuf`ChVN!EpT?{dXUMog=zeGxvZDL8m-2R@cP4ZR|`YHbH!Dpwg z5Qq1{#0L%gv&ZcgYbf7@(&^c=>{;`FQ*`+ z=;lr76j`NA*@$x4+Xy?u9X3VYF3mS}JOo(Q6*9D)8RZ5wk4@J;uXY}C%%m*R= zknH7;9UM6c=f?WBMg4U-Sftd|B1$y*@7C->5>*^-5ch@c4}}x+Mp;&T-zb5TdBYQE z$>c$<0Ii3tD*P`c$yF}`D(I1VX!h8^bZI&=+2}PHS>Qr<(#v(6O&)Hsd$lh=gPEM% z9GD_FHhCNoUA>UCxQZ1sy!T>uBM?cF_p5L9f94-dMqnY^T|LWTHt*k~d{!mzIm$LBT*P^ocQH7>NF6w zWZw)nPnJKYAQvsmfxXFW`lhcMfm_>s<@b{XfUlGmz>B?+6qGD8V_CzN)uI1pj4eZ( zx)B@s5bCP&o%n*4w&A%7p7NJa$N$` zc4HM^l&2P17mL{Ff8%a?50s+CLS}#;%hYTv9OYmjMzBD;67;kFV_>X$Vq(OA11nUN z{eu1KxHLDdp7)1`xN(*kA2a?q#MpMs@|=blwe1oVS($kH;) zVa(TCHIOpOnn1}LNv4_<8kFnhV!yBi%Gtj;I1D`~IayjE=ILL=qhIQTVHkR5p;=Qb zlr!lf%C(6`{6}{1ak1kj-dy*8CiWu7qqH}+o)pDD+pK;ZA2q)^SY^%dj3(umP29lq zg}uN=U$(z8f|bkbblO)e8{%?ALE+38#4WZ{&f%h+$MXG38I2WQXxtQL0<3FUU}J1aoBkc0KSi#yMuOb85=7{E%I3Y@a+NT+31E6?XF{ADy3AI~n{= z3+ecOKnF!6*~i@%O|%ePaMho&{Sg+yp5U^81=Sl~s@Y7gvIfB>m!bw2Ilj!FrYRfq z1&fPO9|h|^5+CVvEk?atf8>YRvE<@fiGX}Ka72{#v*6uaomhb+CFN7HC6)3t&zZ@i zj;=$_4MR<%X<>0A+d%f?VfFr4>$rCQEE;nq(a}cT)91uWGML6Qb8#5nCUM00N;`2s zbE)Oj<(gG>pm#Sq@UP=rhqr2!TI^9Le_1?H;WWkc?oN3XkG0AMh(ejnWQW(Mf4hO| zT}9^CUsD)*{oKbTf4OBzw<;BwC;I~jBpY}R12GfvXvA$cSU_^0&YEv_FFV~U6n-RC z_-Qm>;V}g^H(U@@bqeGOI8P*cvk5t8Bd83KIRowBb z@<<{j&&IpMy5iP4a-}6>**ueCQT2sE~RkybSc`~n3brtfNlXFur58QK8 ztfIROzIz!``mY&%LI=c`JFXgMZNA-#@KI(KU^O#{5Jn|ObJ+MRIVm+VvTnq`(C%IW ziMW?K=CTL|1cYwY>9jS}Jz1}dcR#Eq{f>Dh(J+;mX8YHphBx2Ht6VHY8%7vGiy}w) zcUGu+m2Gnk>|xLqS&FG^TsNzxXq@9hAL%pk$mLaJUhgL-68VAGXu<<^Jp$VF1TO6{ zvJ1&HS6hDG(8F;ZC67`^5cd`YiP!&MsohT@m!fpn6(Yg6U}_l>EP~_ zQu^wislrEyIhN*|H}ekn#7pLTZ`SVe}~%+ zMfTavy*nxKT4m?Mv!jE}ew%#bt>}x7iB2O>*yt-eDeCRaElo{LRi3ix2$`P%Q8K0Z z6F-IEY|}n8z+C>ZS6~w3Pt4{E&{WZyS5tmnl3>On3a^Gi9A zP+59V7pagxcDw0&^Tz3A(OO|f5V^c7UtZF1i@)cyb}nYw@QVZ7pO)>4t~{aa1Uoz* z8J&{?Sv-tCC{_DBUi~>>*P?r{6dPtAGRdUXEe2g>NMB_jYE#Fx#{HYIOsnP13^U>8 zFQl}@iS5Kw`|^Ad?0KF&|9zo7cyHC0V9Mt**=kgqAdv?j$#dL2&g zdz!owonwK^+am~x)Ujk2mJ}Vey5PioAa7zHtoK~&qqc#Fpr~$e#IkD48Rg8GUB_;* zM{rU)mhTovJhN=eae_n6hw0;6YRS*o$876lYavT6^^pN?cuVJTub-oi!@yOr+xy%Z;=q-i1q&c^k8S#GK6=ZOuaB~Fl?--^2qrj5 z61s@r>zBp16E06Z*TwrSV@+Ya@DYkKH?q)5{~PD<7vFdpHhKOfxVOr zx?YVWMKSJcC%4V*yRX}n$2a3mNmY_{)OQxyyM`A&d#l#h-|@x4(Ew&5Lr3sq`VbcQ z^Jsl&a(H?AOb$bC5$c0+gXxM$i~B&aLO=PQzv;N9uE6B@%c6N^q!3(%=Ylq3Dei0o zD{jou?sSu%wM+^kk?j!b_SDM7bma!|I_?o=5>>ZBe_w1^==TNYu~Ril8MdW*dV9i@ zO7Uvq3vL2=doDi{UE;4>6pivNMt@!hXXw4$V0lC#^p^rLm_g=UEV~xQeAJ73tgOX+ z00OpaIoJ=-Q7Sq?w@@fiJU`ZXONz1;PPG;{(|MX`e|weZ4UC2Or?P!EA^zHGH=n=H z&Bp5=fA|N^4!ul?Gu#4lDU;{$I95HWk1wBG_1*~sD_uiuTbvZWP?O&v3<6TU%mjW-&{h%W zSxXfkvqx!(Ee%H`c0zP{sOSwO=C#h$H_7+e=^_gnqRbxkWlVU#NV0q& zmtH3j>ccXrPn9%^ni%2_Y_*SOb*(t)lgf2& zs|(jM%}>m0|Gi-Q`PjGOvU<=KV40_27cr^KcMlKapldb_X$2!c<1`nPagdZVT!dLKa}j(8=V33?aQZ{8uAp64ZZ{xKVRG+8l0Ma|`&%N@t{iZ0c7o zl}1=CO6#n4v+dnkNJ&Xa9JL5=1lOlQS>|MQla(nh9_F`nrm5T2-Y#XEX8&_2w#ilr zj3yW*BYBoBk7vWE5F)Ee=bjBMs4JAx?k5m(9!jy;I-g%@s$xLClU>>8=V@pz8&I% z$OPbDI)@^meCtr_`ShL?nH`@y0m;_mL{(3g1fW7esWQV@2!j*pttk7M$?*=_l$f8? zZJI{2-euC2iZqYMA^4!~eW$BoH%BIv5wDcQi{~<6uY#585VT{@Cu)n%oL`;gd|cAF z{jKsqoZK{b5#O+xTGch6m)}41XjVAHsxykYEzjIcMnrn?Pa5Db|Kv99*wb8?Yjyt> zmH^iIV70g2VW)*$@ZE0N`Bw0?J>p@ihWD;EWxAl%_>_)9UP`Xt$#?LF5SKdEekP{H z11?EcRhF5_QQc*9?);Fu-QLx}g6?JC?00#q-bOI?-cHWsgx;U3DSx%ZZwTCNS)ymu zA}Nr?n%S4qD(X7zB$ru-Fi&*D&e6ciB0V1<6MgOUKVy|Ig-?h!-U)&uoo3H2+zTAN zgetjPXh-%hr5Re;NR|{D6{jTd7oKCXY6v3Qkppu33jdYU@$af+&t7_{uz`)wsdxc1 z)>R~b%IEDg@ayKmt8>lSsgz2Us8#138c-H6*HX{f=z8n& zXlY!%B>zZ`4Hf8y>8jdbqN{xow|Z;iOKQC~;5%F#z?Kiaq$QMH$UXXbzwi|nXdS}= z7U_di&1&!+pZIl^^$qQj1V-ESvWKN)y#L{j8J!K7j(Z&xLJvA+&|Qvit8b6$Y<%}T z%`P$)4#i?HK#*h(C;X()Y!5wMV#f4W-qD<{A3l70#}%~^!t&5^NV?ui`CaD0$9CxO zHhdFKI$mWo5e-@A=-CcLblsK<5TX2`m;_cBDe3@U-^?s=Un%c+9(5>wa1L;*uGC#` zUAXZ#qwTeZ3x(xVMWLm=jm>N)>l(Us#WfMat=487jcrDwhQX1)Ca z0W?f%y9^TqZxs6u{UQ>tvHK_&-=!kI6`D_==G7X_@SBk}6c?*!Nr7U{0==0YAI(Q^ zc-|Bwr-2BNa4*mN09dI4zhiz*q~_cJY-B{X@0mmPQQQMz%@YlaFD`$43|9VJKutQ=L~E=~Ek?h&+?SW56^$oK89$KVSKx7OMxE*?5^g`+lj2c3?BeziqsdK4~Y zX;Am9PGdq(6#@faopv5CV4Uq(Yt?@%4+e7yk0O7x%R{A?P=U0m){r`PN<@>>K+?>T9+5Bq4T1hZkhXMWS* z*We!^GPN`Gw*1T0#SIOUUt6hI#3jUa>lCg)>d3*Q$2XAkzH+*3Uvyg!-Bb;C%QY|ME-i>IJ&Tyvtf=-XP?$<&x*s-dYZ~1qOfuEkJm}-p zJA?fPL1c}j|5ZDGA6L6=T3FS)?-jr~-@9qi(bgMcTCCFCD!dYHA#2+OewUNgK^CFD z_=P;Q#zX`CH1@sj1m_ty>DTn6jA@U1!vvA6 z5;L>u5+?KLaPPJl9EwCqrme*BFMJNqM%}4H$6sUyrgqbUJ~V^T3VjvZ`V8{}7}VCj z>wI(w{Tg?i-PTYMRX|We&|dL}IbOWDdbzE!OVL0$gdJWhBL_}E?ELBjjl6isgCB=> zZf4EfJbBZeApcSg_uMA6arw9S`l=L84oY-xD%5YNL3>i9xUzuWfNcC*LmRfzmvEbJ zplX2YqB)kUf44j@B5}|c_q4RRF}ER+a%fsd)BDVAWak|ig)WZGOHuJ^Au3!6&gh(Q zZ-0*-e{V)5cVtK$HGDxq+Z0b3lXf{Jzfiw`RI3yF>&}q zij8z_*_#M`PpBqlgze!EL4LP<3ug<0^cwTZ2}Yj_j^x6?qufRH=r+RMhsUkMAD%vK z+)rDReu%fkhn$Ts9XgLTUo8MQM+eU&=aqM^85WlI@kh^ZJiY7X3dW_QQAglzeKXj$ z&ovAD^zsV*#+0r*4NpB8PEHQvdDrr4KX;4~Ls(~Q;>dp~W42@onGZBFz3DZRIjD=g zcg6fAbKEsB#cSDQaA+PciEPXF6Z*F>qaT7H<05b{8eEojJuY*6axtZI9dNq|IQ3r} z*0Wh?Va>F@VT-d*q7o!Ez!&O7q};{x>`6f>zs;e|Vu}c4*Ud9_ksc07aNO#Rd;vGl z#(-L6ej@badHX7*FDwiAJoFdSJ)i`bEf;jgqBT0UepOc=WEeSq0zUu5rA(HMm~wr1 z9|z$Q1>h7D*^0^|nw_7;DS?!%z0TIxQRQ#grh23BW>B2$MY9|+vW2pVYT>7%MMH67 zFH*odqkb@O``P;iq%m5;4Te!|%hGDTag?>5ZH|zv-GG3%J~=q6j<(Q+`yWNhW&*da$^ULMI6*;TROOGyy-y2#j? zaom?8mKA=t-%8Y>wFnYkytPL&8xcdpc*A&kDBth<5ln@>rIv_i&{8$g_eH@yKfmey z!7<-4YPjet7qvQU`>q%BZRs3&|LOVFX5<-09y|POrDw%@ClLm>*X2)v`L>r#T1cpU z8xM5ax|DV`keNja*03iLoYibboqUr$g&%2VpKD~mURxWyfvGfTbGSVqOKLQu-R!^X zm(akzfLwr`4_JwolS5ZTOk#(jex3+7wuii4_3MlLU{%F7I_!+!xKO+An9! z0_C)AL+XQ#8K$sfqFDgiwNboNCT1-jp^U+^8HY|9TU%S~i2E#A72&=b5@;*S zM;&9^buW;|pEP{FWM{qGPy1Z;AA^wR0S;Htp1+rjRMlC`z?`^3TjYF+(V9u?1`xdv z756|$3hxmkgEL+-2yz5jet5q=9VJrLU3&~~N&8k^3vEKkBTt+5+4-b9$mi`9XS(z) z?_Pj`BMFenMcNsHd7n*DrFWD}`_&SHXnc)!@9`1@&$_#?RwIZ&>h6 z9fS;)9r|7P;&i!g4DvlxO!O%|?z5PEL&SqFwjSzA=h8Ev7xbVzwYaV3iylVR)_vS7 z&R7<}vXz;$_oImwf?y)^^8yw>%{tkBrgj+d<06^%?DKB-s7#U4(oUcAdPaXkVW1Cj z2qbP?@`s&5zZq)tC+z+7V+e&aD!3n>;dvmUDUvCBy{(Z>P~~ZgENJBXotoEQMrR(| zh3@LFIrh%BN*gaGaO5T)T-8C6le61F2lWUjzTyg`Z$oSQE?fE- zBuOpF{_cT?Wcs6Z&#~t~B5fPD2^+*DW(3bvDBsO>`%}KaD#?;qQEgNR2 z1~qWI#)((vESXI8y`5oj$#}#sWqCvD&lb2{$S4=-k6i}?blw<2$fWMl(3SDNBUIXd zW<6HmwXBr#RWU>ll-ylE_B_b&^t??0$J2U;#Y}Y)SbT|-5e|Z-0BSS5vnf$J)&WvL?acWHLM-GPZdVO2<_U( zfou!uron;p2oT5dD-4@eJR|@_MVuI#z}}HyAhI^kwX_%Dcf75z*w@l%qWmd>ta$5VLyY zPHwP=a6IOCobn}Gku=%%opbMJW4UER)blWZ5lW}dL}=@nBt^NC6WlGS+!bIOqDSg$ ze=cAD4~0_z#=!MWr&@)5arZjjyIQs0%c_wZ?%lB~+n)=hi(ab_VxsgJ(Zf*E8G}2_?is{hO?7@-9TTB2?cFxi7^PqDmui$RkvIkf=ZzMNh@N2ztO!%ME z40q;Ryla=7=k=$*ZPJ`w$J09JSj24HyL5rUtxl&O2=07Wzw3FDI*^l}l8aCvFzk~V z$x>HEc7-8AIJE&Oj8)Fcd6v$9(f_me{j>i83uCV*%CahB0CR5fDhPs^w zZ7Mj{dk+y@9LTkrDGbeQEA`2iTUovKm>eJt1m#~@tM}Wrsu2CPV3TBB8Xo_IaagT} zxb*5L=_Z1a?&pi#dq`{z9aDR6^k)i-No^QT8rUVReTWkOUi4i{^_?RnIS94;R4!-i zW+P%ni}FXN*|TBQOE?%al}TF^?wb!~Pb#NDdv<&eocKxI!aUV{rHa@iZE!hie7dn6 zM1mBX;CR>bl?~7N;4}uKTG#ZR$m1Q^=;tlTNDGrl0*c%yT|=V{>CaOCq6XZq(?8`f zQcY8WSsRMJE{*t`c1Bm3Yk6{s&nF&ybH;Lnwn^EAdpujGn z>pz+;*TN>g9Qp!pk>3z8DiV9(yoCJv#3clvNI;210kK4~6!uY~Zv!ZFtsz{>-@sIS zSdA9bD)R5@{Lb(nHha_YN`y^`_QNPdOzos z#A_PQEF;{CJc1IxCl7RuP=w=1!&qe{9eqHL5>uC62+jGU=b#o<=dFBnr=qyFI3m|E zWAw5*()u0|zg*^X1<_fe%PM2m;jmKH^Pcc*BzFbX^nQ2?yb4~<3Qq0Ddce5R^6w@% zlj9j{<4anbJj0k?Ki$c;2^5?1b{$_TKCoEhS*t`qMR9@G_CY#`H#`$v1`Jd9r;_J8 z4E8z>9fn~d`)RH6U@~Ry6Mk#96QUDbf4(aEDrOgkz)N9wF@h?Uu87k%ww{| zHCb{Z+#|6mfvAgjkdSU_KMRC5LW}LgGVTYXIv&W+&tw9~C#{`_v14{s3)_~s$*w6j z3mV>G=c^yh(nELgJ%~UKz^})LN(6l~@xAoebufVQ;o6cSd-HoAcL;?G!Mc~JnEu8uwyWFzc z%nvSkxJLT=nx9=n-n5Ar2VF6TwC*vLjIBiVui)L%>C25-4tZ%IR^`!v9<56Ng(AF5Eq~z6z6GSsxVniQ$guLxBqxE2Se3dVa%L% z(1Wd!D)c4a4}Jip^u~W{Eu!{ohew2gFJW(AjNMg<6Y4<+-PQi6^0zgtg!Wms!B{2- znokv|u9*n!;qXB{3p0v%d3@!lo%ossqE46hoa_QQ2BM)Bjh zEstW-2QUDw&gU2lP)QgTkz7B{@?|^-6sXH@zaWy9EKL-=t?P{gVPM|1AKuCXv<4-mnKPV zSnD8A1wNNi?vh%hAx`=`S*BtS?fU9ryX71ni$Y>n`Im}RDx_sZx?zAx5y(wZpNPt9 zGR2cztb9G9WFw@Zorq@!?6||x^4$lDVD_moJR(M%8CFv}QC4|TTe&)ln*>42mra@V zGjTu!$l$+e%7mK6PT4S(AI-P0c^>zYTSjyimO7nY!lT<9AQnKI9Wva~4YqIxoOmZA zx9t@jAC{tJ3^`biw{-oPhdLPQ-_tzI#5paPN+H%LBp0t>Oj>N};N9B#aLJu6OTQ+y zf>JKc``=oA=H_P3FuM-Oiduf}6aI}ELLD}Yfro#26H}mEWQshB+ux-hHF#kSIRM%LKDn8Z_lV5yq0ib3|jzd}V=aZ{LUNaFjw=9_pe-$vFWlb9+nvgN2gy*bD+^T4kTxeVRpQJ? zvLze$R(U8lSts8tFCZG?vngaL568bsg`$CPBo?!*ZP3^_C&T_1hsfCuE&%g&EC<}_ z${5j7@Q<|SaY&u<6KQE=XYm~bCTf^Hw4*aYr{UlzdWP9?K@Zd-dZ-76=`>qx#-LXZ z=ms@-7>CaI4vIP3KwkOm~6mU{(Enp#h+qL z=zvI}26t`IiQrDEguoNY4eWkBe*Uh5J56CeX)X6D?qXTe?^EyXL8R1LiaUe8Q} zS{Ee-2`qwsu3Fyu4$WCnDt&=zZIH6i&Ad{oVMZH~In?8G{w7mzd*70pegSdN6e%Y* z1-oIRILS0U72@JdCLW^djuc4`t_f0IbCBdZGH}ww#YA@&1S1NT_Lx;v0}O|ewuTn) z5kp%gJ!fFrt6K_4hJ6tGRP+BXWVeyT^uP6~1q+64XwLq(vXNScx>wSQe}Ta}u*%BK z?qH;XYq_hl!M~#h5^ZS$Z)(6CiI!=W_%ke3P3|j0^>)ACw~skbAABA=j*zU;bz}LNU8eLNcwK z8Bs=(35Q+vm~ZK9+%u`8nTIt$vFgfUF7elk(rwq+Im|N{$XDk6?u`2|_AWKh9^&=|GJa6CrU1~I8WP&vHmZ9{Y)j6mek zQhev4Cz8Ro=xD;}pWD?{sT*oG4Z(}^B-T+Wx^wth{Nac!kb6q(%J7WJ6MM2Gi9Kj} z%??z+zP6#JuR-iR#=n$ab6oVFYl$vSwE{#MRF7YWa#Jn4J*!pUI(6DZ4cB$scoi3z zo!!Q1)_S@wAoct2^d|iC*8-VFOMe&06L$HatrIRs@kflrH9#bFR!y;KCoCbXpu{H6^UI-CQYH=2PI7M8$`DS5 z--Z-r!2WkV7m(arhUvVX)0cPDpKyOq{`~stmH7$*RB`V}$GZeUM4&22UJ~TZGHlyL zHYzdmu1m=v zyw5qzGU!=Zbsx!Y@<5ID2S`oPi+Y|O;~t+;VDM;?*4ebStK$DI?zpurub7Yx;*Dh0QQ@{5>)OhOmUA9uAySkz>-;o~mhPXv-7bU7ipwKZg zX=h7!trakdn}XYfeFSl6r?lZ^ykhIO6prtQrz)eQy}AqsJ+IZT6l$?BQsHlsUKI1Z zuHs0=isXEuNWl_@&aA^UgKJ9cgl`&-AJa@#-4_sPKvLZo9RU;(rwZaK5Tn{B|1>9V zmYXhKK&VQyAFbi=`=4LbuAYDie28M<E?YP;$-MbK#G1p0)L@%AV|fZ zNbM3MEB{64ITJbNbh*0I^$UN+hd&lS77%?UXJ5UdGpbi!&5;{yxC-KxQoqJmd*+JO z#d(n4Y%Jodbb`MNnYLgotgJEQV^LV zE$La-Mt&%rANUu({{MZPe0N0_h`8M@z+9~_5$-?A77_N!8n9$zrEah0ytj@A`Wu7_ zS&$<$ZK*LNoflHUTkoG$(@)L7_5rXx_CL_cC3L3Q{j*Dq^0ecI&?McbMeh09tFuZT zi+TibM=Db@H_!)1+2d!!{q+$<)DKkMSkg=j8yE@<*g=4>mgTrL`AT5lmqoar4)rsU zvGB_9;E^X`q}hz7w234^ukRLxs03JIn>|?+SyfWNTNs``#@bG$`yc6`)M^N$2D!VG z`)yT#78bS0s3bDHN-b`de99%=+VxO0P&UOozf03>@Oc15gh0r{c})LaAuKDlSwcur ze#@d;fMm*zNCC=qt+bS@b|QVUxVO8lbVrZLWmbCn#j`xF7~v`Y?;^%e`HBs;h)xz_ zlJskKO^I0i4{bsawk88yGWth~yJocr$xsssThg`-BUU$eC3C(UuhqHX0VuyD&_{kzg%_A(Kmyn@0B7OEF+p*}ea1|^^jOGXW-=5P+2HbUMzBz` zO%3KX$6-DP`%0`VlNjj{HZHDwoPGJOfjR?ft~X=1d5VNR(m67NrxL%&`m_^3gxH!kLw{$Ij{}~lSlqoDz z>{o+J>N7Y?SWCt&$}*WSbt(m+8xOY1EuelNqPL~sW4bs&uLV1h$~gnCw_BQF24`+hD*JZ;D;I;eeP4+EyZolv%rf>6?9eWzt+YGra;i$o;K#+_492ti^xfMM z1lxccD;Ywb8$GuiJ=mAj%-+H`)%=g`DKIp1zE&v;7?uDc3t-Lu|64~rT!X&HsvG>R z1#GE3h%*Kc07tpCh+rFMfARj@vONy|F!Oocajmw(xC|~C`I4o;vHa_s^1Oj?GrhWD zXc(zpUB0}!_9zW{(bnZ1pGv!bszxp?h-TX1j4<^v2R> z;;Z#KDZRt`@trQAXx5pd3&E%6-F*baVDN~KOWFT&h=?vB;Yn|3jR@@?6FY)~bw)~T ztlD=0-}S7VM$#XBTK*)BbxG=>@BcIdtkL`E-TF?XeYNV`y_(P1y4N$Sw49v|5KkLh zynAzRHo6@g;Pzor-)hx?spa`w%h(Ga7l}tXC|WCw+HqGFc-185-KyCUpYjMG>%Eo- zggCgX&XZ_W<=7+uJ94#A=T}BP^>-~J=FWE}e{rd9-NBZVQ^>s7Zv4I{{jxGt)%E@` zq`k(=_pztU{;kK#lG$$0%$D7sZ+!>(6hgM55m%DbIcp;HE{j@LDb+4nTKLVq?fN0D zIWn$5_^|-3(_U@(O`uk*mwBi9mcw5>V-fg$lSeWW-w9rw9oA7P8QQP6x8)y|j)i%M zITRRxpJw~HWIt|-KqBiHOMY4BQD?9zmmHruvz0F5Tb>82@n7(*ygictSI9QwYvU~?+s-5rKFmS7~gB<+~=hu*nbTn>P$WlHXC6@t|MV<;*IbQ zlKbQIP$zAjnryrM#Mi8Vak0~k28=`UmCquToTgBuuE*khfCthFXEj1do&|GL8QJeE zHzH0K=cx{<1VVuu5jIfmI7YUEci+@}Z}^(#GI<+V%iUrWZWNA=q-IEAFCoi;a*v9M zdXH3ae0ld>J&DR8%i}#8M1th&-O7@Bdc9}uirQ6RwOqX=?z!AJlYy#r8A2J{&+GspHEsotqKu=rV7Oic$7@}c`8McFL#^x= zS8Xco;31_7lk=)*ldbf4%Fip|sk?`-H;#e1W(FmC7B^rh#sJmyN{^ek+p`%9{cK|E zcfpAJ<*Tmz8oTpjr}E$eRR3Cb1B^Wx_rp)4wB^BCr8OE}Mmpj&9~Nh=KlHY{u%9<< zWvhjTw7Sadb#4RGDah*~V9~c^LS}l-wTQq)>>1A`LWRmm7PrjWk_hd&55 z^3?Rt$99G{g~y4KsvjeTnQ0dk;-_dy+NoSDHaiy+wSoP@Ktpy4-!5jrL@1JD;ZE(L$$#Kqznj z@crXa-?n6=5u##1k$r1W;<+LjGa#GEd^(WWhL9ggW6-H^^~3`8eG#z?eF;f6%{J&C zxf=@K(F&rzxh~B!LcCT(mz)I;HM9E!*9nzioPS8DPxqQx%F{pG?@Xx-u37XY6eNkZ zUXpnc8KS^$5K0-`%`}&@rKh`Cy07M-me^S?RM+5Lurei{Tj|2N7-`vH(&8#Xt1;^X zzp(0v&+2ZE|DEB4|0ty`ZC2Bgd8d}D%HKcu!lQJ5-neuj(5%7SY8H<10+{jS>SWd+ zc(A)OU;0B@;yMd+V26eWYdG*m#Wj zu9<2d-30?-XXYO@W&iu@*n0VMl5?iakm=NA=iZNwp%#*Ij7kkkF3|u{tMp7~Arr{u z3&bwKIga{lb;rmU2KZzoQu~KBo88r4X~OQ@gKfk}hckBPvWKoLO;?R%c_e!fFCMH3 z-f_`sac?{~`fi_kq+LFRhQc((7rx`)n|_OE*fsD#zSwDgt!`Syl)0CNo32TNFhPx^ z?WQm@sHtE8`d!K6t0Z$M;PHY*}LV4FE@iBNf38SxRd@agk707o%19N){b^W(S8z-U+A}UhkNE|k zRMYfTYw{I4(U3Uy{rIN*R#A^X)LruIGXQ^1WZ_#V(NC=#{Y=G2XB+`O=`52b%jxxy z5FSa|)Bbq>t45o9eF4$xH@|q=u_cW?v@KSwWstB=MdiPJ?UX|Et1Qfi6mH;qUG{>)db!c4>a4-6H@c@8YC?3;h&}U%X zU6PJK)q`q&g;4_w)_kc!C*ltX{z-W)?z=B%aegpv)4Ay`IZT+bsuO~sX4c&CRI%gH zPJ+e1(vCYwFuYOZU!%y7L3{#Go_oYj67(mIBblWQ`z=cw=>{{H5pC9w<%qVM;llP{ z(6-j?BKmqlMkw#*Osc}4dcYA>VX#313J%_|(kt>!Nl(M&N0v>!>$I5&7`wRh&*%@L zreqaJ0M8YTW-a(WoD_GSGA?r1v)$?a z1!NYEncaE$t;XNS?1TXW)}XTZd#1G2Rq87R==kVT^14XOG-x@fvuv(sODV8e4mF5$ z*K7>1Vt=Ab`kdt#E|*k}5j@8T$ENn(Xl!uGUp8|tppOr7f23}yma0@h_HyRYU~YM;ag8!z-9+414%fsvYX;i;^$E>IK5y@b zzBr84ozeYmvxz7ndIIQN<^)fDscnx7_T0q~16hgu!VHJo`TN|cHf8K_q$l9UdD^ts zqhI`?z-OKKjg4(JDY~sO#J@uXs)Vj-Nir|>d7Nv|5k&vn`e9t7P*1yveNt`(HU@Hw2sag}>o_jz_FuUkvF97c8D zf?6CjW>4DM#G%+luptNWT|io9Je7CuGvgn>&AOzgLedFSW0ch1~$<>3HqNIpX730AFFj1A0DN~K2B`V zP#>SH3WJ>Z3g`(`->HE%R&bXVo0JMFtG7gDv%?5^!CQ);4NIb_rY~G0fN_Aw`yE+Y z&uAXS>i$?9^6Vi6#fvg!_@@A_l`63hX z9=oZO#cBNT!QTq%F8X*^@y`_&8aN;>E`S?r62-0EHIAt_l8%xUws{d+U$0L@+`?*Y~=LP~09 zs!_&AxBuWZ+%j>e=BdTHJ2$l1p@Pe(d~eS}Ya7f6OV{Y_za?VZ?ZM5O%f^ERRIZhA z01WiwRk3Zm=I^GRd_*)blPCDdZ6q+NcEi8&AT{!ImDqjnBd0zTzafU5|@Y(>_@tWis4tB z&pWzyI<8`tWb$2Inx^WpNGxFV+}OnB0jS$LZYdAT{{=CWN+!YV5xazLlxv@@FXwxF zUYmKX_}#1*YHZJZbdc#}&s%EB!>2I9(Bq!BqEEcDLvq~&ZYnSCcO6nS?+m_?1bj5T6@IV2?Oagnez5jktE-xzLA2&qC0 zooD>Y6oj?W!D04Txvv>`mn;?l?IBV?aeWV}tS%0(eP?(^nUr1jr>ES^H+qdTA9}Z) zS(Bf>w)(n+P}YnBDyh5SBCHKQL9$Z$+Rt=?WRphP&ySBY-=ZmzFf7(f&p&Rn>BMo= z?`PD{ns38rTAQ_wY{^|P&*sM;2A)*YkH&w&j}jTOcHD>?Ta<7OeHp1M-f`oJw-4b;cgec-+v% z;P4vyJ<&{0f4b=do~nbfWA4MQua7n;EATn#?A0o!Cq6UM)^_LC26;5u7VGldY7&tZ zY2tnywHEEHsbwR2nvEv?LhQkva(vCYe9b)7Gdz*0c}tNBc_>V}TJ9dJsTNtdPCCVF zRamJ%4dO}Zl6>=e%LHf!qa7Pp_OQ!Q?Fdj>=T?ztP!43H4K=^x;ft#3)v_BXNt-Mq zyHi$4-WU0}%Y`4usYOR!H)esxZkqKo`jdn0sF;@~HI79Y%&1`B4>3e4p)4okyRBee z5A^M5?Pz(DpE#D8Je}={9Z}1f;)kBe*VbFFbi4b(gTNqS$5`cNl7eI3@m2-$c`a26 zvZ8!3)8~G_E6B)x!x-jB=@Z;tQ?r^+i`krdh|K~c1vnBu)0~~AR!2ZglDjhPm_WW* z_7TBPa)u>rc!ofO?w3z&#jx{N_5oay6kH&5lH#QI>|*pXyFN9TiUJ;AeQO5RxnwJb zLa$M-TdHTvB=FC)&)+AX0;1Zwq$)9qc;ynzq-hRLy$;1!s|Ut*1makQR;B?-Yn{x> zScUdqS=pA&0*s=0uj3+bIaK;eO8imAZ;1|`- zX=^I?>~pmXrMr=OBiSXlM29lWn+O{^d=PJ$!p|7LMr=gMPKMiATG_xH{o+fg%2U4f z!qBHv>5IwRqsh@Zv?Ny*4G}m!Bk$@*f9+e{5B5Ngt?z+H?Y0|@!VJs%hMU2FN5Q5z&hzqy4+B_ow-fMpy9k4KyRfzM2 zO&;nDU96x#I!B(o7fu?x&pwpNSErZHxe>mU%Wzos{_KKQgHqGMRa&eh1f$&X6EY%F zx-tH!Nq|J0tg2<0RMO_!vrO8q;l=_!%s;&!1a$kFL_UgB=4=fk^4W{GUVC3=45WpK zfdmkgHDUG}!|!Ia==-C#-pATDyp#(sk}L!?Y7_=qnyZcA+aWz1^@zQ1O}L{k(81=% zfDA{86M^=SVSY01!HF%ngO&+WFI>1Zed~j7G1*v$oBbZ%&yJt%p+>GP_}He2DP9ch zbTTr{hNPbcx!V#Jr8QHn5t zxc4RUr9hhwYn}Q>_f*XJnced&&N#!~VeqQv z0`{%rJ*7zR*}B@=6O%J_7dB33g-wh3tYavefPCmzc{9=t)IR9uDO63LFl*un-`(~e zWzo!8fxbUkBiNxSh zdIkQJbl(*QRn+1oONNfc*)b#TZ?#V42GF@5OvWt(hS8(E_{4|-_no+s>6{B27KdnGTLRhxU7Ygb74 z*9DN7;}_l4k*J_K{7OC;`?zL82CHI8bN%>8vnJi{j&Vz4bIyo=J0wNBi?rE8*xyIs zF~U(dY+P>6(?UzOHw}CW{J~NKPml#(Zl|d`(j=DPm9J*7t=tzcRXz%7eU_n0hC`? zjt@@xEhMD-uRvbo17BdvTu6zAL$SB=(WGgVvFphTjnMV5>L=p7 zW4`8}{))F`$dig}Ra@Gj%_vz2_UD|eCPdP(Z}Jv1*1bofS3d(VaxDsFeWLXrSBB$~ z4z6#@#A)yI98yNd%GQhil}=y710SEYx9gbYbd_n_BJA z`&IAr$Lk9hs<)D1XzJYG!$H5qzqa)xi=NKMLKO$Si$t;S9;uu{hLlfJJ#)mY5HSRA z5RgQek`&bJ{lx;JIk=MrbI3Zpy={Zdrw`TSzcI&|u1(f%E1azOSNb#WyJg*o&iG~+ ze$kL>ijH>QE@CVP2rLG|=^@^o@n-gLxevMztbg><)Z`u| zq=8v-KpUE~VlASJ6RAcK4X`KTrI?pwCprupNjyT(FFqqigLhA80mnY!+GKCXZpB#n zh`JAEA`b>rdE)#vHMDzcBJk>d5Ya5eo$T`;Ff=ec(2Vhq!-GrLOZWUW8}L?A`IC)1 zEky8h>_!XtLK|d;p704%s#9b+iWZU*qX!&a69!4-_? zd^~R*^+Sdy+Q=jkz)K=EX{T6ah=$t%@|*XLGN*R7PB;ErK~}FpZ^s58uVvyV3zsIp zj(EO~eXFGq|Ff~3)iSH1(ET?IBDY_mHHa*mGxxezHa>C!Gc8&O&H(1jG33%8{`u- z`t>|Thr(b<`vLc#?h&JB6>hovag{{^b3*ggCMB`v=27yl*|_U$9d9C!rQg<04ksdr9Jpk1mU3aoMQVv(dmIg;rBgbASjAL8%$C6Iw{ z@wLU-Lz6bh!-=K;IH%LwXI3_lkLzB(N~A4lVp-btHtQ->ah{)S`xIl9u~)zdFTKj} zG3+Kij?sIpHJ1}c8T&Rf$KZAFh3mn$Ixo=$Hx}JI4r6kHb88JvhlJJ&?}`ckbh-JN zQeT$<+ycl=LWlIYc~AxgKZ2$)bzc4aFN+Xu&?%>Y&BCiAT>E!`kMUL|dQf$_lvuOk z4;oY%SOV($C-Z9h3R-?ay>uh#6)$RBMw~~Y-+oZAi;(z*8-mq^hPm;{-O6t0!}N8u zG$Db6%0OnXI6--C`XDa{?eb zgu&VuDleqSi*2mK0wYhV*D@kAxL) zs4kC?Ad;byba3}n1xSzx=cgP@7T;ZR5ZXS#=QBpuVt$QKA^a83AYu4j;wcOc3jNgv zTZ1Q+U+M5~^QfOKp9t6u^b~r~2Pp-!RZ74`%3u3Ht|t`6=5i!cmk-^V`Xi(^+%=is z9?zIsyO`z3H*ASoCcsdr8I^La&H!*4Vw^bqF zgu@?emD*zw)qFJ%@@>+Hz z_N~960E}Db%!6_HoSV^5pedLi@QAzdq!yRp^ApiQhuea~sX)JU(^l09Ix^%{bgK-V ztfyxi3^-~}UmPUD&yTZfaPkI>xMe74x%}gblU(JTPdL^-pZ*MR4@BuPk%(+XdH#P) zon=^5@fPlBq`SLQx*0$ur8}fUIz(C;BnF1=?(XiAZjmmDp*y4n@AjN~?sK2{#0MDm z>^p~-n%tgZbzPax0~`wJEKaOLdQViGPo`Ni`gi@qHMkkQ7p&QBS9kzS&y7D zEv_6+TLf2m`wjpDqW1L4OXBi^CO2vWF8yZ_@yo>C`UR=rSI|33-l#Lhe0|`mLI@^P za&bFC69e&rbTQsl!{Yk&$(q8~VcMj6(Ub3QSFL^6LD;H)zneV8J(bu-(pJ+LqD;)?_gr?6gjm0XQ+wvLhXTej9#6Iff_brebV%$SW7LSCk; z{|>4-cWC;H!AdFjn0V6W(KA+jcD~wsq>gz%1UTs7Tg)Iz<`$~GNy`stiSZ6O%Jm1R z$!L#V5-ZaZZZqtnjB9>ui|Y$xA61zJB-cl%pZ$#h9lrY&tI;u}qe&wt>0@q$qMWd4 z7WF#KRGy@OV8{hjfJEt)Zj`+d{gzh`~%@Z>6m@(NCR*JO1 zqnweF*%(op^+52y&}lAK=gKunk{#Vry)2$g_EtUnt&J?ZL$374KBeusyeJg zsnY?CO_^K>W#hbcJyxvvOsQN7y7REO$?x=8I)(vn%4enD4Bt-&N}WGuIqJ@|zIGYq z4XE!F5#|GqwY>rP!Uu)@Rw6QTR>dCPeAs<~YBh(w_hj-THADx-64LyarG@7Q74_dq zK(Lc2TN+;&0lSe3-vFN>yTL&yu?D_lH0=sz2Mtj9tc$^1%-#3qLWySY)jD2NpWO*V zG*miQ;*@(pl*RttLj^yMN`6F98093I1gl6KH9a$B_#WkaI+~p|#gZv_V!X^AQm-~y zv>}T;(_~3aFU|^6yv<4GDNb5Mt+#iMdp)2<$SS8Q+<@0D*_C+Nw?L<%D0yX(FM@92PiQ3?x!~10_n+p@A zKeKB!QU4i=P6oAt&gTbneM=`+mpv)XcIRpK0W8vg-rBnrfu^PS7;v*NPy6(uU1Sbn z3d%7C;c56UE}vQiHrgKfrmqJ_5bXiT^223_zV`a*_|qQ^2=^}sLgrLFZ5jtPYO3Dl zp4||c6aG1}T|Hp!2FVEQ$ha55jy8Oq1RTUaA(QbBfgV%+Jnt*10A*)Oe-73vQ;4P| zh`ebdUb?_edfjR`n!@@Ew^hw&4sM0=UUsS$UL38@wC7tlm2ExH=?^|l$>e&@A= zwM|$4=0gq&AYSE96)czv?9lLv@BcTECHvMHbDgiXwuLt&W}N0Wb(l5w7bpMGQ1PQ}-vV}@hs-fJp^g6noH*-?!ljtye|~GFJwMb*0IKMn?c3;&V<)kXf#}_onZm%^$5S8DUeLy z{-!&{sd?hT?7uaHPs($s3zN&aA}7|e1;HYUTp?>5)2qhyH?>N~wly`oX%&NPUeT~U z+!Y?dc;7MNlHQ!x2Icf~xz0zpoD=BABq4 z*Lc2DH-{raL@w4w6l(?rAI}D|7qkccK_ecqpX4a1cq5)KZ4?|lA%P&U3wlEG)8H}q zdZ&KSJh*}CcYAxv+w`mpQqy$2;By4u+Ln~LK%c0y8NJ=km;^;8Q;~~P8;{2Bl6nzP zcrI1anS*18=M}?scB$&1P4WL*o0leccuDrGVMr$F(w$l226VJ}GXBM{q|8xV0p(D&7i}s% z#q%DeQckF}-1il4rjGu8j9pw*_C%-27CF!}<0(IgZX$YU>$9JJE|qWci+yy63SS|- zUfE{^<0J7p!E+e+wi>sdDm~vInAIk?eHpX!V`MngP1wyqj0_u9uCLxE(V zYS}-TXW~GQst!|c>HpS}LK-oqVa0pea}R*da}Jj%yrCDll$m<*A}kqm2bi8;KdYBc z*N1kJ(Hu=UJf7Jn^u`&%A{m)(I%3eie()@V_* z*y>e0L{|W^L^vbYE~K-Lw}SN(S@157ge8AbwOQI7tFEgiM$^FD?ii3nfMM8CG~UEU zDAz1PQ$yEJMW^0;d-vs&xB$G9Q8E0B!gTUXD31!V2e7Cs{Nc=|XkWG(PN#X$Epm_v z9bh|dl7STB@T^#D>3SlbqB!n?pyT4L?j5F@x;pGOwzr@2^#}Tjmmmw1KZ+>7Xk&_V z;bFOu5LMv<@c#6Nka53~-aqyh2F#SW9DtBU3vMf{0$axq=pG@Z#RfNsy)aIPLWzqS zxs^x6*-8f#5CRU(wUro71mO`Hyw1dOPG=xD!6METxO$24?vE*yE?C`!xcXj!tD@zB z)n!IjO|;Xncc}j7Ol?+=`YE14&T>}l`qfXbcE{Zaw>@Qo>dut6xVLeCoQZSAgLBBYL=V3pfQIU-81DiIZYy6%Yvtw*P-+91-Fc?q<u>6f=<0yZLM06oAFdW<)=OVaL^MDd^UOV?_Mo|=F%pBZSDKQ%nK zfdvZU^`HA?I)m_O4u@TtP0O_p-44&i>SF{QF3=nm_ej3wbLy;yb&53!Q*w0W!$xdm zz=7Rhn;T6Cd~%`Z_hc7;3{R64{Qm`Z)GkD5X8US~O|%Mv@g9li?zz70PvC5aCE_?< zOdS|zvh+oL&?+*ZKy~@Flz!({@5jyuyrrgS;#W|Gl#3niz;F^|S1;j0Jyx}ugkRw$ zjA0~8BVZviXhyGy_B8T7Fl^QpegEm`KxHXq+=UsIZFZ8;{jbE@Fb~w!^nIq($?$RooWC-~^N{PY3bB^M4-;oCQl3Ec zJ(Wde=Rdej#x^ex6IEkVaW|B|t%R$ZEWkXcn$F8oubG@<|$GZxMeu{N2u)?&O}Pw2?F<&TA_ zN4^(5u@w|-c*qqze!_H&FkSkhG(APXslw!-wijw2_(FGvac85bgauDk(1+KLdSwhD zWQ^d;s&;-9=iF@B=u9h0y7}#JvU#*R!w{o%s?@>Dou?R~by+9Lg%jt*de0&Z-Y>HpR*}ZK1YMHX8P!b< z3Xm9x)xV`_@uq1B9c;-lZb|Ma^DUoU>4T3aHt@~8hl8SSKl!cOX#2Y71<%0cazesC zT&r7IWqLIF2{wo=?bWuos=793*IH+SvG%07pL7~--x}pAY;W9R3AF%yWzO;`;WIFt zX;)PjH|&?eSTm<9L#{*Enw?HP-9K84Z-BF&KLqGZ{Oan=N#*(72`>@%rBm?seq~5K zn;uFIz9%v4YR|0(CM4VszV*QF9d9)?Surh9X)7o;=uNFJsEK(tF#qbzVIKDjrdM9; zvXIqF@bU(xdy36CIONms)SrxqQ5QceeWAW2Q3~}=lx{0oPTtA3ezXxHYHBZ7?M-4g z>aCfPx0Ty~eM14jR0|LThF72v6g({(MYvWA6yt5kRu@lxPx%4EZ`s`4`S?9g5&$YB zpr(b>uoV8g%QRdD?vIG&5ErIlf^JbT0h-y**UDltCGCu)5s@k0 zkQ$XMV%ec?mguj=@L5Fke!a_q3MEUZhms7{-%~RF>xWN0I}vUt@I3yg>t6F0ZE3QC zBW+2{^Iji0T5ep}mrgLv{}huSXTY2Fyd{1U`shzN8K7it;!f~4{Rmub|65_R?HxA< zLX70PeSxs?)Z239Ao9m|4f2quI8{H8l9)K}2ti}$*RZ!DlrZd=wC#(;@L)=5EZJD= z-w)!VT$HUrMvZ2@=o@T?WWHU{mBGxIYV#(SiRkymLFTC+LK}=)_ELq2mVeHU7U4^q z0OJ2O#FO&u<>eeQ&E`g#e$=kXzZv{zUMhrHcfC9N;ofav?VP?z6s?kH3JQ z%gTcus$bM&gZ{ZK9%|~6W#+Hz1tMN`;?$lmrNplUeEfoaN6uO5UTyUdGH-qwJ3@mSoFHNgyTiv#VD~*8YojaBGNY3dcfwXlZ2&fqS-5cazPCKMiSB&Sh8?mC&+7pwjw^E z`@%%!{h2CJt8c`iiUV7g8?u9fp~% z^l`xz1HLtfY0d_bXHaPX04uABAwlJxLrUA0$|m6jmEq09@^V?3P9`Oc$iJkP(UFu; z!bm(Gz*_}gVtBxbTK>*hW+@~(YA6PK3z!FTL0ETZ=j=*D2$dsTNxfN ziNTlt#kY7-oRBL-PICQmSikb{+h_Q^e-|!pk1dL~Fli(*;(-s8!HYgstEdG>KvHTN z9d$bnrYbDY_WfHPhJo7n!K};(Jw3m^J5}7$(7ORdPbu+Ro(jL*jQHSAS%q)9^P^=c za?vc!nXvOd!)6NEOod^)MMZWYA0b={I=IOWO+56RBG_T_=n)m1?%jTzsOPKqJTdWn}jZ?@!4|;vn6E*j#193speSrWj)Ufjl0LAh`y!OHA-4b2lNP-2dD*OzyaD0KBxEM_#)AlUyNh@e=(aJx* zrl&0p?DT?O*nTVN=Libw{&xfDOPq;)UkcJvjF(I^(T*yB|5fP|`!7zsfP|6!hyYyj zZ$gt0lDMoJLtW(fGLJ;|n;hgEB9O%;Xh)bg=XU5OXQc5L%uF+99eSxmtg;>aNLi3R`&aM(S#5$ss3H5l?OJG*`K_dgw=ap8 z+u}<)8j~=2%sTY~IRn=1kAoR0W&RraL)HO6`a-nU>h@uQqGzQ+r!{daocLa* zphKN9)jiu*)!Lkm-}=ZeIF#@pH>jKbfGt~4c~GHz@>FC%08UYyd~VMrH+J;l-Y%9? zV8qQx&$qIBHixAp7IVage$Wi*lt1Tf3nw&UBL@T%UXt_&2`5v`qL5P{qaL$*TWyRM8WN0ry>P#XJBJIlw>0EE@#n~Hcq#DSFW?tpK6R=4Tbdb*BId7Jzu}^U z`_cSssq`Q(VarT&w&ZFLP!EcTHTxs9@pbRfUP~94rFNB%(1qcp@;TABqbAci7U5{q zveY)z&d!<<(GhRpn?rO_V6}wO=wcYk3NDnII_q+4XdTpEQWU$ptQRX8n~s`7X6)4$!Mv!=Q<%+BVTEpP`^{Y zYs(G5nfDqV&vQ^g3cH^fPTYw@&UE?ai#Z@foSRPkY&KuAC@@c|gr@~#CYdZLLmRYR z42d~K{19UXH#$fy+uJX`Y5fD#qIe4DLF^z{FGuNv1MCLi#Z`SYPYhiNQr#SN$BH82 zG#+Cq?J9t29asOwho*y6@0~yBgK?gw0G%v%X=elK-r>#ezI}sx*EZ48w>NP!x~qVr zaYJzLWg#Co&qC%-{y{5oo=Ftpk{#0vGFf6wuKHcoDIsE+v0g?tH}zvIzpv7fOgDFI zj*+OB)82c<-7kLC)z$4;=bwcXaszlCru2}rv7KUykal$7kmI&~@2MaN+9z#w_Jsik zT$s|dJz(Ibl-0z!?1fgk4gJ%8p!UPhmQ!!~Hz15hr4w?C_8oU>vnI-7AzEIPb2!hB zYKW6u>SmPgQU#sF&F?}Jc3_jOl;BH>S=)JW2!cQ6Apz=@_f3B4+3y#g{*C#9asLD~ z6pus)-+NQ^jODk>QM0kjDCltA?xzV+405>%xw zK5TV$j@>K&IAaxM5XoM(7^jd%jv2HH8DOFRX zItwaiod8zx3yCh!vQ^MHd(PUTiaDY+m^=mLb#q?#b3ur{KXKk@b69C0pbK#Rn4huw zA`Fql6cj>-ewOa8O%;a^hq}-gz`+zo?w%jr(m&@ygTEz+7F`^WEZ~|o&Z`WHJBSm| zs^8`(={YHYbY)fTply`JPmfZUO5Y2ax+FLuOr!=XX>AI_OgjdTL|ac+-|x?&qJZ0?%x|Ji%5ZAP}tB1BV5Sv!FrzFE-#TU)CMMp3|DJDz5=mCIco95 z5x~J|XDPtPXxSLPqGalb{iq@K(0uk3pGf9+)6 zES1%)LLDGj*w!4wdB~MGXrAW9T|N`M!VG1yLNn1b~T%yweBQpPhmb7*Su9pp~;)(>cw>+UyuAO}{l zDm73&%jf+>cDwe;{f@FN0=E^MRx)NyGMr6;;i35Bj%}zkh*hE=YXofxz?8UL)~UM?+KelYR7`gXRqIM9eC$mG7Qm^cOs+y4j9|2Oy! z4U?JHliXgni7;pOTp{N9tfb!^Z1N^TMY9Wm5Uz7hX4QM{e`T5fd{HFc1R;Na)GBL&yObC-6QO3Y<}Tt@*#457g7 zoU+Iq)HJ(#$Qwb^hCem$+UPvwHJ-1#x7q~Q`m(W<<=`JMh4A+y(769p zLhz*TNI}K*pz$3F?8Nd%@@;OMeHFm>V2=G>D1u*VRaH;tTQOBe^65_*Wf>B&JvvIg zs_Z5)RQ@@zXLdN@4{8fCP2?$XvCvuHaJ!&@gf{akE&%N&qF0pG4|AzFxVrlkeP>y3 z#HyQ7m;pbDH#ubmD;=#0P_}=KarWo>N`vozY%}|Xopt0a?hI7LIgA-il2?`d47c@{ znEP(Vn!Mg!0;kSaILupt=+4p~M8a6%Tc1lZ7lay8$jwS$0?!{|XWEemXTd0Sd#<%d zmSElqhxDBjOb#m=C}d6~OZB0CTMP+aA(Dy#uv#sCn6`q&NuJR?EYRUZ{cw;y#;v*V z%{^)R#VdE<`C5%0mBh84IZip_P%#GaL5J`TA z6k>bAbt23OW{-Pv7?wI0NxPZIzGufE$zA4o$NPhFGFg~Wv_fKE&o?G%n})jBDPdd` zm)I|214%5n8dsIff!m@GMAUA2g5h z8BdWS27S2|Z3b#+l10zGhF2Ts5@Aiw?9#M_z}Fa%;+$Q;4#7*lq%uNW>=yKgE!?bqsx>0h7)0T2YEmTxmd+G@tWI+GVGDzsTy z96K8_;?i*C4sahc#L%{rtbazr@!?_(ltRbk!GUAFDoaqUX7H5qR|g5!1A+LAng!H? zVL@h|*)L$)IVfcZZ+b&_VZ^o!TuFV5!vtw8PH#W1cb&&N$ZJ^ zei95Hf#wl%U~FMkr6GW|e~4TX$8aF#JoPGQM+!$f#!yju@qe@RNIzmbM=+)A_1i7W z)*xT5YfzJ*G9;fXP2pcY&gY6+ ztQ6tvTTkNp)Bdg*d@J7cW5zMtdaY*1NYcZN!LR2yI8B6ACW<6ig}$wfq2%NRdo#@j zdi@0oNX$_*m*D=ZYhmMIFjB2b9~%rFI;n$}ve>9{I139z6B`TB_Dj+7+t0XTccU)w zW5Q*0Lr#LkRrn6nlfz#KJ1JsW>*cX2-`q4(pS3iPt+|nI%K2)22JBe_!lIWiR{soF z9Tyw(xDYWYS4apq=G6zkFsUgatsUyT1fem+8Cnj2{qe?ArOO# zHZ+4`3XF>^G}KTwhttf=I51Z|?6txfwi>N`UpgM|zL%Mqi~PEO?6ZPOA<4mG!J53m z_@em?$Ci%q@e2bo_gYAh8Vh(uMf!%KqBwHJikw%Al57&m$~ml1Og$7ixH}?RM^m?u zh1wNF@SFy8#JET*%_$jj)OVd!?NoIe0R{3auJGq!7o^%mpOW0P|B1oZ1AtJz zATq&cKeMYV4XInfofBnv%^m!U_MNhC$BF;p^5YCtN^)f~sf3`Syw>bvSC|Nc&?pgd z*r4RTOI|;0Pnxaxt=HtcN&0eiUV1}==rW!{S_Ud^dezK7Tk)rf&03aHj=m9O=6#aMwC3y;U?gIh%t2sh?t4}KmX8GfH;i4 znp$jrlC-;uEu5^+c&Yp+1b~#Ub-71KBhA)UJk%q67QnHP&*j_$82F_`4MxlE{Os79 zGl#flH%JqrNE6H;qn=RxBRn=k+^%S&+VK;>S60xrGK#)d9l*{r~FifH>>NE{n;MycDEW~pizCr1TNw@;A5-^{{7hv7sh}=rGIYB z+YLLSCLl3YPUp~YQ&N8K8F18bcX!t!bD~W_xy1$6waB98j@m6aqeDPWQ+GBe9JYNY z450ryt;dpIk!m?k%=EH=>J zR1mOeK|3G%p~L~@W!tK2xfY5Fahwuqw!QoxyGEeNj5>m~bD~UZ?>+zfoXboXwC{Z0 zG{*g*{pIR92$$D53m=*IHyevbXX5TbcMh@EmoJLloW=(v&n)dW=P-HS5gxE3rFM(` z4=58lxq6!}R}M)Ww|NObXW?EVx!*kqcN8`cV&gl#J(;RVIZvxLU7-7|pTW3>OD)FE z6Zhs0|K1ltim{*_C^qPeCc^U)Oz}%FWRUr&GvC9Swt#cx3Z60`nK<{D;C+v5lF8k_ z<llMUvCT$9G-`Iqg2A{E8!=6?Mjuy{|B}6MC-8HKr=QeeBKvjKtgNviE#Vd3cI@p4b9l#8Iy&hR+Gl-6xg8tuTZmwAUFB`lpL}bnL`@etl zf*)qwLgMVdotSRuMLLsHONvZ8tDyktI?Ue1f4{+P1R@K>0!9%m^&5taTY%O{HF<(8 zeB2_iw3VZKLB)RoXQ+!Zd_dh;E0Pm_j!mp53G2Dqo?i+jM(LZ-FJF~+UE>ga+;Dhg z*k*WaIQeFoL@F7HVa%-yMuBI_*fDFV(T7|vhn|+%oLsIiV;|3VywJE+hqJ!rdPyC& zN=%M?68W-4cf#+tbVjE?dwYfbY!EyU7=nI0nZ_XmlV(!48#t7>(@cr(D4s?tK>mcY36Yc}xA-wA-j9}3k7j`^?lZX@UB5uYiM^vQF)bh= zsj8iJp!w2hu9R8#3(YsBHd|wWXQOiOS`3o^ahf9_jUKrmYal!4R+Y z5Ft{pPDz5Dl5Zn3?@?Mb`lo}$zYd6Z8+~dUYX!cRmQf^s*{@Qs_Jx4L0_}rm z$Y_H%AzO>Yo)UdYE1e1oSn$By`hcURx)M5ol3U!T58HmgO#6EBch6G0jtO^x7wJFn zw_F%wt4DX#$i_KBV(NTB*zS3|cadZF_nEVNk6iUV?fTr!nWoQa3MTX3z@{T!jPG9a znBa@?G%Gb*E-BejNO}Y+07=;WHXl(!91BxfHbvr8{symzdJ$>Kgwbb=MXNp(Wb{tL zoO9SXZxgZ+Aqg=G7BVmW<}5q&*ZN{=psHfp_wP*ST{$=-U78U`3tuU#5NySzPBO3L zk?w{RqWzAqb#9~m!@>U2(K_Rta%pG4#)rwgH^s98V?$|8k!qo&e6vE*JJ^!2Z?l>T8<*~1>pdic&=K+R2OdGHVx<++;y$&FGa~lgCq@^~e%zpfm0-M5g7|nF#RNnV zcARzhA34#7I)c@qIj1R@A3ccl1RISHSV}Ox$|qbGjOMEMOfMS2y)x@_c$Y%Xk=;mt zY;>|I?=IPgtFMbDAG!ux?T=TKx+&xJY`7(K1|hyz7+dzpYboR-SYYUG^KPk=^N7D$ zxkATU`XNOrl=x!H(iy@BMeq*OdlM`&7Ug-Xh0Ke^t)>%WcbqKaM%<*(G`bvSohU2- zdy;h(MuhPehwY+gJ>wbrvcb3UlRwHGemLP+WU39|OM?uqCpR(6KUfgZX&7i*bVC=u|^5r!Bg>dSOA!AFb z;WwB^HlxgK>>>g$NTJcV-z&dwRfNO+u z_#i{d_TZ!uOqZk4KN%u^3na07dpF-zIh$L8oHS#kq{lAjt3;G3Z|ONHFlox@-*l-K zv|}$Wui(>p5==2f?3Zx!AV{tUgh?w6UhuWvzCpcxbLgZr7%t#IG}WCI-7XZA-43-g zz*y#fz|FSXtvF;J8r^;o^wC4iyKS3IA=P=8k^MKOx=)8T$iTbKJ9j~ z+?kq~Tv+(;kjH9q&OSElF7t*rRKEnV`(`6`P{1JKlzjSPzb zjG-fH9phx;L$j22b+%kzQDS^QdK0~B+wvuEZCPpoZZ8$ns%c0`R*CksSqV;ML=&BQ z*2X+Ee9sE>t^PgEM6968Tw!*G2nLc0;U90$nfo`V-rOsuxWf<9r*}e#)X)0TI-Th4|MAFQixwLi9hR*U&e)$MA3<)U{9#M!&*5T!#`i1}klS0LlAG{Q z2Ep3!FLz%6cmZaD~GA*uT<;dhm7Uqr3*7U;M$KSNc z1TspA4^(~aM|?wF7ZW)nJ@uR1S;8JOr^wnlQ`eXWUcJWpUy;b`n{mGU@9X*$`x7U` z=Hz}=OE?C{YViaQmlsjn_4$KTUPsJ~Sr@X`y?^hWaq>Qq#ym^do=+I7dD?xFs8=fl zO97;&S!zO}^+0VdDsLW#7vj5|JA-_U;EhyMD5pz9HmKPZw8o(EAyB%@s7=QWO=QXj z$Bnd!j1TQ2c@rurLyL$-)OX{lO#Kl?Z=M;hsfpf_22LO?Uj;Jtds6XWMUco72KvFeS&gKhpH*wEC3c$qn3< z$eRb+;iYV^T+ct6XP?&7qx`1h=|-+1h^V-h?Xxsg-rU2KmCtEyS@ZM=2SjcN{5TU{ zjX#L80=b;wT*S4ImXAsM`Gaz5f%`>hBwj=Oe{ zSi|RXF*Bj@-}0%K0<(yb*tm5%*x6(;3TTJ|(+X?p{r2J_&+fRMN%mwinLiw8ek=U( ziMcM*EKF4t0tIwB4tMU z!r4&zPAkraBAaNQtfOtChSsR%Um^=Bx=TlLj5Vo3-5wc!{yN!=K5gTJpZY*l+t?>u zJs*u~Z<}>5q3dv*asi15&K!#VcjJ)a3g$^JVLVsV9W8Q;w{MD~VOV#8ZO6gF*9jLa z;z#wLxV4rP8OHnO-j~M=jo-j_DFplr`mZ_vrpw zMx~{|?An_b56v&TLd1rV86q1&P<~LY(AAezi=k}ID!;tU6zHf-sVbFVqtp2fCImPeVi&-^v6Y1GSOfnNQeek&cbV26zURU0B%@DqYpPyNP5%>0>##pjzoF6wgPH^;S57&3HHL}wBNGMWby zi=eF1&!zMi*@$l8wAYg!5$H9__v+G1S4H61hqu1YI@wN96w$zu5w_92vxN!Sq zV)bWaQl=tPa3klm)F20{=DOHCm{0wQs18LB1BBC07yTBL{`-+!4&};rjy3SYM^XfX z|JH7x5$TGEHb;R3&AI)%4wjp!D>*2Au0-3*%jHa_$o}{@&+r8{mK;e=hEKC2$>H7Y zM~e$>K2M$QnnuL&wdD)M&h7Cr1tvMXW^KbY*(q<{D@Og@Y zna{C;sHXkZETCzzG!=o*i|&m*9me-t?VTR1u~aAb`zW^lg2y{n{X4)p?e~iR z+RSPPq#Vu3tIyb0leB`CrCp^*pzpmjMtWh0Q=@&%pwIh4+5)!S8 zZx~<1-rO;D-j?3s)2!*Qd*G|}M722*)%648M|N6-W3;U{Yx7+O-*4@iU$wsYy^<)p zvF7B``a2Da+7q6v5no91k*&vGouybEW4W1}Qx7_*!mMA>T6J<-EgeZ?l|EqSf+Wp@ z`@Kv-wqXq6;4LQmzPUh`TrgEyAx&cO_8pt!+}({>*>#oB!cbP^!Ep_rNsWG$Cb!BN z<|7LBHIfc&CC2fmbxTgpCw!*lY`2GtcQFG~r`AbJ-RX_lz}mzpdKG?RN-40|YhjR+ zaZF+0F$3w*pb_ppFmNwB(#r2^{J4T<7abv9kfu5JG(;VDfC8N`2}Xun4`D5oEg`Lo zj|S;N8Dc%9$E0U_*|4>zG&md*9a`}*udE4jk5VGiHo7(6%(YIf@pWTrrK}k2xXgU4`lQtTDGR6-2 z9)qy|aJpC6AU6wd+&esRYU3G{ZA#_!Hnrr9N2Lb#ixDBY;c_d;<#kBm5OT3u65WWT zX16rm)D7%`SM9wL(lDIVju2ky`Ag=1E;OwIalDq@+IR7RJqIhDTczNqbkAQX7IKHT za11pdH)JGxeLiO@)TOxs44F@2rgLgajHDN&K>qlPF*2j%?;rnbzHrc{HGey4yj}sgxJ{AQEZ1rd8%eb%`*6XR4#w`;HH~@ES~Sc8 z>P6C{gv6F=34e^}Rk>xoX?u+3l_OBXwk!gvn=q(t_-9qH%N z9Xm%IrCsS)cWrOHn+V)yiDUB|&mTROqv#l1^fzmb3q-+>*1UF=Cy!)=CjpBpjfTzr z=0*&kw-l19}|%9fN- zHT^I{I|tJsN|=e%TUm~0<)+{UdxpTI*C}1@3KDEoVe6WWxcpH3$RCk!1;HC+^w(F0}$PwP(MhDAlQ8Z zT{bPaP(SPz!9MhQ7i`mfX=Mp2Qg-_-eDGlS@E)#&g0#Zyx9g=}L!Ar_jSHonCi`LP~>e3dh ziq=WRY&h#)WbND+#6z^ZlW&G-88hj=e0xoNttS&r{q zxk^;fno^&Sk1sF3)O46?2h_lOa+@%iJLxq{7GUSN6Z%Rh+x4PxLQ8*N1^4RXJTk3U z0gQVZ8_e1kE8P+r>z5xy>BBZfh)F~t_!9CC+=oDcX?M)<{<{}xp;(NqvcSo8K}4zb z;t3|+jFrV=y0xRoPIKp1@WHu))AS@P*uL~a{(me$?b&={IL_i#A`TTlviFKw6?{B* z;ldyz)(Lsn{x-qjagv^RLxkX6GI^GP>w%C~(cIB!m`c{JSyTI#D^GB?P@{@ISOsEb zidILdN9Uz|8Oc*ctoz;m`M9^;TU;)nQKF!oH>KjoCt`AMRtuqc>IdBqv8&nbiY9Cvli_=e7%p(i0A5F8-G8&H#khbEx$g<% zaQA-0;f8rB-tB=RP&MCI)_TFxkjS3UOErdDn*>UQ_Yx6)rttthAxudpHl;Bv74 z{4LL4Z?)e#ibm5;SLO!BFU4`mzNd|A@|<1gb6=I^oHY!ESw4g77-_IMU!QQq00hZx z6dwyu4L>xIIKV)2hIHYi_iEjb9eI&aJe!37_AAa6C%=2vhEZ+0AImz^LwY}!Q`ypz zQ;xYaMc6(i7w!fJ{v?H()!Rix%4va_Xn2>Gbx<#~zBp!5^;LeBSQgJB=Bbf~1JU-1w6@w<;Df^UW~#PUEyOYN(sc96bP!^ zhe*aW_~LCQmwwjlo*P|m%m^v2{vogVwLUV9x$2b8+ya^A!FYJ|DzLyyMk#5V777ct z`cC|66@VdF6rDk^es{Z~YJ&#$lT64QX0)wtJ=qPOg5=t&KZMjkgFa%}F_ zTbBQ>D&y>85W+Etq^UOmJCTi>zh=DCQjWTaDZR7PA4fL#<&-nGTGs{r9tviUja_%s z|NHdSYX0PRl9wK~nIW?8B*X`C)82NwKW90r0+F=>xE^8dH7U6TIGMdY$gO!WgL!Ko z3oc$D3b)zCFoa{U5~-FHv>n~4#HS}MB`{RG^))Kh6ZGlp2PpBkWro8f8=esn(-0zOy}=2EMi84$H0Soz zD~A)1efRT}q(4x9&gmC&PD=mY6e>Tl37e$8_x0mLLtXu*4FeZS)zF8C>vL+ID}*}EU9!v1#} z7-#1@lcQ}vAiNBWrjYNNwzBb%GJ|}C*00IB`0{C`mNwJV6E5;;ymC$(!st;qLSme` zH-3{VW2=_f&`B(-^5{8Jon0J$5Um|_Y}&}1(HuPDr!r57z6ri$dNUpf z`l+|*LEh`9@9>5tN~Zp{}+ zk}U9XztJF@?PiV=?ZUJ0($-Szbe=T(?mV9EB?zxUJaN}6U2w@V_zMkkRPwU1Yk%4O z*p^aJL;Il+apROyI!o?61lXD*_e#EX0C+)O>AwigUVnYM>OXf#rF6`nj<^P?_Gl#0 zB6%}k8a&n!(G^6L91lGqlZPnbe;E6yj^7T*C}!GaH3p=RH;9#L0wkI1m|`^j0V0K( zKfpFTh46&~l2LgWhnG8VLkO|5t(xdEKyDd_NwdTx6yhbCk9?vw_h)YN{+1U{xN>+v zu7|XBv$S-SGWvkke*xrWCckd>diE{JRd-LXgYs*|2g!vo5pwqirsd^GC|B29oOvOY zCvMgKf3qbPe%-BKsr*x(saI*#kvv@oY6y;$&hzspf2pmSnz(9u5fo}nip-|3a4$0- zH61-njCpX zAV{e8s{nQfIm<*TA3@@U8DtB#ALu}_k~C~Zpux_F##}{5ZT(KLYDP?UxtBS~u*oU2ZpC zA(g-A=>vKb)zsx9mbh{fuY&t;BE9nOq`Ewc82EMHs;OUbsf?fOTMi!TLEMJlgzld8 ze|YbiE?J)^uVzZqH+Z(!)IUanoAC2pxVu2|+=7Ne3*Gv_xkptcMn`6TBVtEJULnrU z>NJUpYs45^z8wlKn>SU@c#9jY>-gD^E;h!oj`}Fs&YseT-^SFqky?5p`Fmhp{vIMt zXNxZVyIJ0kS>^0_pCGB$+msFfDty z9O>>5v^bSNvws+%foSsw*>p-%&*a=ilI1m9`*I(3eLpq75k=yTmc5sFtpPP-akkQ9 zSLJuhU+eXf_kzK$T+{q%5N=pv25$Bh^hvqrCd985YAufrt5uFSpC{bjWd%9trdjw2 zOdh!iM)K;F!21$5Y;5svFSm)3FS#nMW4H(`V~V$KwlV>0gtb8E2EFJLcaG)7U`^PN zR^#s(iwJ8~2kmpU(&?BECzX0P9oaeXalgR^&fV^?eW^guElg^(fUXPCAF5zOJciZI z{tr`U9n@C)ynWm$ZiV7rptuHiiWVsD?gV!&9vq4XEmAbawFC*pt;Ib>iU*1nO5Z%+ zncvL&Uow+9$;mnAzIU(dv%CHOaE?CC{{oy*YsFBC3cYkT~Yl&Y4wpre6KYU@| z+i}OTcWzB|`@58`cTD-{m0`>C?8?U@Mu0c5-9YR z3fY8)0SWA*_+qu?U$0xrP79u8c*dT;Z>Xo~DTLg5WVk49mSmhAU*8FjMZ7aeVz}np zppE?S8+>Oia=c*;_XwkRlk)44%!-gc*7yDQ=Z1hoRe%9QhS9D9-|Y^H)0w_1!p_Rt z!Ih}y0b42SXe^nZ7!_*x%X{Ri@@q+E{jE z?u$RQB&{6edKL8&p>7w4PV#OScjxPw09Cm6N(9*%VI-tS359wpIBhGN#x&?IN>XX; zNz>F`YaL>EXQ>=DCSzvCkCaEQzo<%QAo1D}ZzifBF}A1evKU1Va@?xh`i0gLX-L~4)#hJbzGnRare2sDjBJ{$RH_BwA0Lj_BcBDoRz4w5aJhiPAl z&h7=RYr}*IqzT=OLk8_2$e-jVYU|Z>v>3iH;$ov6|rOZ^vz5H;rUB8|8aSrH==ojxbnk)qudphX9B9w6>zgmr`b`xYA2PJlA?C-&ry zuPYhkGWxMbnt(TB`q~YiuI0O3_nOn?5GotD((`qIk!~{b_jY`KZh1^7_I>R&@Nlrm zgkzF1YvO3m(=`RUCZXtmaW@!}R5JxxvHpd0h}LX8ycz0{A`&7D^Pc~b^748`;NR`* zfKtr?u>g)jw~B?krvbYrI@k>6$Rex4#be>?vFA*!B*sm>@u`p!j#&>i;wYmVNo$ix>%UO(=HRY5-0a~9*pkuhMcjTR0=}It@5tWpCZTywtN!g{HS+PU$4mGAtqk zjLvff874UGVBO%WkubOC+*=hZOIf4@?@&Z-Cy=fF!82QWwN))EA4lc`mNjMzon0LB z$MkT}GEu@SgLb(Gir0s-N_wNA9zU|4CF*Ei{^jG8A~74NJSdmlS6o>#Qs^5&E!!(M z?(rWSTN~gHJU8z}x}!qD$Q2g=3ra#z-onSw?N)49#JCgbzbf3P{nd$$OqG_MVzYns z()HMn&HF1&q_o!rbX8Q0&%l9wbUKC`8t7VcIs2D{Wm*4wJ<(nV2Wgl_|1S+Z2W+4j z1PXLdT)&OmTx)n3t@WXM878>Y_k1~)^f7Hvr;9uk(b@fX54G$~hvPJJNvz#~wE_9{ zRxHKWX4A5YE7EwiKB6%Lx(j8{a7I!ty(J{0*u29`V7;?7d>i$Kv{mHg9lK*_+oR!& zczP)i58OhKhz#!q2z!R{)L)^ilaP9ngwRnqXkIQkzT{M3yvb_F*%qdnhB%fm3M!Vn zjFiWDZQ|C#&E?*;26*kz@KS&9q+glM2^omVq+erPh{BnZQgGlQl=mt9f7Av-pYyVb z7J1PLQp2g-Ljb?LnHV?S2cBjBO{a#{(H!fb)pPUfSKpavM!yLb`_H z6xzrf2v~4PZiKrCk@F{7sfhw>y1XKjai$AJ+`bg_cl90`$Y8~nrZq-fmTgZ8Oo^#J z-|%j)&W)=>;0mBSnm$!9kb3mgHl1^Y-vxSd&^`NQ18_0iyNz8W9ePW5R2svAt*M7e zP8jczpf|@dp{h)AFVtKxTHE@XxTYYV)s6sWJp@Lq!y5>0{%8jlKr{rt8YN>-U#~pX zbu=E%nY21?dN@Y<=WorUmLnLVszp|I`|keAe@3}_JGAA8;HMVGAbd#x-;QiX3au=~ zddJerGit%!p*U$o3h8s10I{ZZ-=N zCb$}2cpp4YD%R}$2xJ|@9llB)x)U@+p=6uwy*y$jr?9RI^M0tU?IX-nP=TCD<++cA z;@v95?_30-!+|4z?eK%DoOr{gTtL6kUtaUo0&qij&!asxw!OIwB+({RDwxPVx;MX z2rT_c-X?;ZQ~qIe+*}0b3UAn$oZ`cFC4k2eM^DBWZ=WI_$e|JE-_m^|N0*PD%+U3Sm-R=0ZxKkQSdZkTx0OPlP=>44yVS3DLMHZO?&-ds9c|r_6ilw7E zw5d-q{XgGvP9zvGb&XK^1anTr8Zc3QLSCJep?}B=WzG$#z8Z#%Dt3~do_z@yVKSi= zB{{9ojtxk11icWF+;I83FTWX(NP{{^3OiWCvv4cY@N4$qH_VvHsIjU0 zr9Q3zgVVwHZ|2ni*&%507};8yL*hxVXaiCcDe%-S2@|oL8k}8s_sx}y=*9$vsN8x$ z+bDrkr9+30zU2n`&2N|nNT~RItZWy5r1*EzQ27OK1uy%#t!@galTKYkt6YbzNNHnN zzcg3CQBh}FvH=kG{T%fm4oCd0{b4GJXc7I?(lz5%yGNvES+LSYFF@8Q7LWB4yA*#`EXPYV^O5wD+ zRw_DK`)B$OF*i~5Wz#l{|~Lu z0J}gkvD_uk<%ga0Rf6DCkzs;|wVyalPI(pn(%t0*ilwNGywYMsUTk zSh(9+CXr{v9Y0)N-woJCoy7;_k8)^13^A zSlbhOP;ZX2JHFIWou%^{e@d$yrv3GlFFKilL{shyL&7l;9tz$I(lP5WneocdxAt`= z4gUu3S(&WsNQ{$%R)XoTxCUaoKpEDHj+d-^Kn8@WWUy^y{ZqJWIX5;1|9mKW{-HfS za|TBt5KUgK9e^A(ym|gsW|=xsfR5SrLg6yWT-6mf(7umc;e!0h6>@(Gh7B{PWh%x*fOghFlT7>j#BIsX_|7YIq z^^+_C7y8Q=gDhZ7dT3D9ld~oY}ALuu;_phUmqSto)qiVT8`jf&TpHL zmfX|AJ5K?)WZC=61lDpt3?>r?9DV}37A|saIdbc8<6)fA-($iyr=D!?-kyr?K$UEO z8PNTtq@e?O^Ehh~I$lHa^FzuEmfZ@IdT~Ujyf8bzYwu=SEN>zo^nW&CnA8Lf!f+Yr z&__pl*#V=J?~3m*(dSa-;w<1@Y$3WCqN*ts!TBipUL-R2l1Z2<~j z&fk+2O&PYzu;ppd~`@oo; zHOZX_j&l!JWT!RPb-M9WZJdnFl!Np4ICCIJO!-lgLAMypK|K8NQ`$ZVq&-P2^q{^l zq@M`E$iEDohSUnHI;2M~l`SZJ3f$Ej-|o-)73iT#B*nJqbys)GRQ{~iq2svZ)-j?J z9a@=q+?{83{S2<`(Y~WamVb_QNhf!QpZkUS>x?abcSE(6gvtbC1`*q-|1|FDJVDA9 z>dI_XV**rCWA*?z?q6q|URD@xkCyvr&@0G<1UPN__n z8^3YyRC){_8FF+JZxFI#Bk*;PH@T2+rphGZ3(a*xQc>|9NH1W9+u}bm^@m$D4!(Usk4SsOatJ<9yV|x2{Hn6QkD%GP9vmMO6gsHh zZBm2;`qnD>hR)`ywsoc0|L`|=ht)*6MQaE>???y!Q8<^N3_n6*Xl=~rDw?8|AzS2+ zHnPIY7HzsFKT;wkdtbbEc)s+oH)c4lg7f)reDhS6&TQ8R9#7qAv zg<&Bsu4`6hPiIe%@|&BrZC2N%xmC(I1GgjJg0jyBYB4k9J5)!7%4fTL>soD(j0%m4 z1i9plT#JK09_o z;;=b|ZYuPH+2;?xa_3HKHXU~6`uwn_H|Cj~P1sa^ylVz{y zKY=ic=B;7ov13daaZj!tsjZ;RMTZk_=e%{d*n4r~bLH6dV8rd~vzFKL-@m)GfLyf0 zjQMk0jPA_M2YZP+tlqy_Qrf9;43oQTUE>NP5%REFOrky1X*GM%vPl|N5%Bqyz|d+h z5_3>@_rjLH6i>=K#vr0F8E*;Lz%i1Fzfm{RaQowa^jCucRW0%M5MNH~XNVz}lNm}5)3nXxmw+SbuW|h^VED)bb?)pw2M;hLA&>pNc_F z2!NUKx8}R=HGfj<`+e)6H{vqjk#<;mn>TCX2=O9kRw|`AHq? zL;y>|8`Z_O%VA1h4Yid2h;(FZR4S>=G~Gq)O2n2>m-C$}CgF;mmX48<1YSUnkfk93 z^V5+>es(5UOXVg02k|+T9m6E2cO>aq2hrU|W?w&_Od}1{+7z7vJr;4JOF@?{|EaNp z)3{Zl&wy+j19E|hv0~4(z(R4u4vWEX9mG0mn@u0ztYWO>!?}*kR$%5HOEi+}p|~G< zsuMl8o?O!gkc)iSUtByiDk~!c2}#Cz28*-L(bm zcuYQ#UML9v8V?I@5P@GDXhFIY9{-eDR(;t6aDPGeEc7avarTWRK5fI z(8Timd~@DJ{WOCyzo(g%-a=@cZXAcO#j@w!Eox=eEN~z(76&{r_bo2^`4Y9y z6E=KZy)yMz`a(`Wyji0$3Ulz${>ku++zc@1AxZcDlM}s(6~+WUDsf7g@&!sXD&1@k zWHEyH>HAo**<-eU7C5%G3H(q}w^nv`D1_cSvUfy}4mQfJy;v zwJS}LR?nSzX_p0;k#}(l;7YdTCC&w%EBZb66#KFa@tHh}C9UoYly2n0>pX zA7pP8bkf2!-*t_GKrt2@ym0^>B`TGAdHl41i(f4*^e)4#yvZx4c5D5JPip2>3Vfx3 zb<*9X9;>`aSDabn8tt;?LI14qS)4;otK>P4=3nuR=7fvGzW5qa%(^H*#A(K>H+{I} zoMxvHY1cn(dhSs{dLe|blx!qRE57M-Rn9$@iP))RD(yE(ipY#-9yRJ^pH7~B))C4d z*suR;kzO6RrIb#om8gH#b{YE3i2bR#6HCip7{(>J-#r%`VV2HC_J1tE?rz^RXO^^6 z-8;8Mce1edfX|y@Er(L{|08`R2k^sCgH~uokh^C)`eqYLF72@h0RBJ?6B+#UK}7j4 z<19y7&i&o7~(`JV$q;YBdeI8Bwx#@%G~f5xXSqR6sgf zGv{=!v^--ggF!HzZxYQ#UXUzPffQz+{Uzrf!hJ-))5@m)5#E0j;QTva=$Z>#|y4P3&)mRUh>cnsA8#mM@H99>BJf+?lYibe50O2laqI5l+n;bs)22I4@hSkpO z;Brw$E1YT^6sGIZOG>Ohv@pk5_PD_>grsiFL9YXZJ47M-K{|;?<*w1m6B^wbFn`Ld zuWM0{m`FHjcXu=V92rlPxzk?=bn%d2hEdtT&mEG+2mVY1o!#3C1%_rfw&y2_cP=>t%>QR-2J>L=M5!}>1Vql%AXv}-OCeU4ujoz z%#f3;i+@QUf*Ut?a7W-HQfJwrDvnC6{K#478zQ22qg}8;;+Z zlnUG7z4uL*;)RHj7)oDzGLj{F#O6ww@(>yKb*4cewrV!n#7o{8lKP@01)W3mw-%$the20zZ_^ zFis+SEMn!OH1GohDLuE>VIepD+@GTGLsJEiN!9N|dw?f+Y)^q62_m`u$2cOL13U5N zyv=1Yp5>VP$$9FwqQvUI)Ova2@IO*~>w&s~I*duznv8qo48F|#Q%U7p)V3;Y6`+=1 zrYh7$x2(k7s=c#HHRi>wjE3fSYV5>8L!p_dXFa_Dk^SKBvd|GB2bv>3jZ`e|t_ z&~tI>fi5-7SFnWX{1Q-Hee}bYe(1X2`i8Ih|2T`{)I(PqBNDtI_u(L8+wwO%1JR@# z!9{YOIFe`m5w4;^iY;2qgi4O&wgxD%xF?BcMYn?X3a8bPY$tJ!arTqbgQ8S3y}69v zR*q8H@vnWduZ2Ge3Fqd_h1F&^qy;$g&aVQeQXS1XoCUhHbW3p%(SF7Mp1>p;22HeWGeR&az#gV}-Lx~Sx>p$TXudtI1QLqMo}zYuaR$e8{OtmTlc$sT zb?f4k{4Al|44n!(~?$o7uJC z)XqGvOOj;Z7x~i+%^ex=qHpqaTJciU=QOS#4|S;9u~?mYR@zI)-5EoaUH$5Too^6g zyk`_jI=x92uD*AHs5@6t3%vJS!|KKPb*ugJVxMT!Lom{6EsURa5Be2DaO-{~IGMc;olR#)O2f_zzr zB_I6PjBop@e-Sry>h7F=+8Y1cxE=&|=Fu)-<&Cg{6|ZsKPKVQfRic7FytqV-P2e98 z^-AWI`pruS^~FpJ?B4m;YYc6+RNF(x0P`E;Gs440R$piv5|4;xuJ|MwH_5-Zt)zJ! zNMUpYG6@%^kjyt}ZbtpLu3EgBr<8x3AiO2Gk;(cT?mLzJw4TZRtoJtqM&?W79sCY( zPz9dlM{xBgAvi|DgJI!fI*?ARuJQkTmxE1B0RghE!j{s@w@Fstwf7OxEuU_=3hR}~ zC#WZ9ZtcWuQhk+D4%lrs^IjrpA38N$dSRgI+t+vWZ$pKx%&TH<6C*_s$~0o1;xBWh zaSu6g*_(?HUg0DY^qk08z5p8gV1o7Ul-rFC*;K{8Yuix}ByFxtnQoYc#w?5aCFTv1 zHx9i$ycrKU!F)5Y11d#bJk)9LQCwX6EBEC%M8+OD=VAxmaCoAXspC&(HX+1Jgr+*Kp*`W{45|Yuhycd#lnVVXJ=^k zZAYia%a-B~Z0dxpK*kPx%?%8)k1IB~0a4WGu*aBoll7_M?Z5ComQ+|4&v+Ia?LQfY zaN&;>Z}Z!e2_<~$omS-HNz`9+=% zD@O3iUS4b*;77v(+_7!haQ&w8wqgsKY&XLZ-NXk^-i>(U_P+Kz#Z_L+tWDUm>QgXt zDj}MuRLNHN*Wn=#7Pwq>cH@P8)begls`TE|?|nSNPbo?LsXp%fvyyMGvMV7B1J>OY zUwoP{2NJt-Py+9lk+P6DnH7ITpFBGIj1LjnFS9-M(bzeoZ{HDYy{ncn*B(f*#+=KqFhvFWa&VyCf73VbG z8Hhxu#HLMJAf9yhO~h_@tcz*Dp=qw4pLe+lKs1TSdo^I5%w zPy{h+G0*N@isr^ z2E~KIQ%ArqS&2<0H;EgXL-+MxR78R?jneD6M7w5dDwG?>(yLA~z4g?FD^S~9zYPhC~x{u}DF)fJ!C6|DJyY@ceLc5I$ zEQ_DgDbrmviTw1LUA?lU{}5%p?>}E!$8c%eG}`c^&uT)sAPi3Is4F4H&25Z!F#2mi zd7`R*T5c>tH7)SR(ur7<*Hmy}#fE?geurTpxBMp}t%279pINyv^$DwOrsNEKYPSK~ zvjzRIFOerXD^9Qop}r9Uh3pRmmv}bCn~ae1PjOD^HDSaUJ5-l77O;lhhECbXT6TXL z2O7?lEL7^_G9GM4vvT)rXT9h>6>^w8n)&aH?sWwV3cBM`@(dMYfo^)ptuHrrZjof&W z1sU4>P>1}V(qzSUF#rnjWIJb%ZtIF9+!#S2jj8-7&Ro5iArH{I80@~E{5tDNM^PxF zY5youF)6KU`>icv_=MhJ&7?4=jL~4q-itc*A$zIOy$OY|ksv+`<~Z&!$9Bi~5^kwd z$1*n9h&jNuo!m94S`f}l)oE4d=JlknSc7%RIoNfNl$gM_f~@_O7zwSKwI+g8dlVO3 zV#6ddU#pUAiQ=&0#FI(XV@dZFoG8X5q3f;$U$?r*=2eVk+elpBt~qE9iz^N>fmQpg z(>i%kSc=&Ce1(IV@Nc*hzOztNIiDofdZ*zAeV*dX%imH}+V zs_ptaM)eDdD$^_l!`YnNB@5j?1}3}G{tg~7(&RCh+&*WhgYy|T;j*z6yQW=7wep^Z zYjOxH*Rq-~j?QtQnBWlE@2PRfhy9&A@}H6AKd z&Ooq>PmZavnbvO_4IW$WJ!b0)nj*Gj9O6B+p+iHtOB&^Xd&%qQpYT!w8%;G5#`d%S zFnW?(nRU!FM>_I0WbfCq9}-));C`%W-1!{Q+ll#)`BPh&6Y7eAid&CSMa95r>Fd)P z7XQ<=kZ|mKYi{TROZ$tSn}kAo+|iF` zJs2o+e81cHTcuy@vxBtt8Y*LZHg%Xq;I~l_W0mNnbDgQqqVuR=%JB{L;DT#!2y2>A zt0`5{q0@_*(3*#O71NaW$L}ugL+BW`4UIhRQg0+usdyul^cU5e*n*}H3Nml^fICp_ z*}E~baD{2^@M+NE$>+1rEYeFc`-QruGus7S`0(-=@~G<eUoTat zbR)fc)fY0f6RZHYXutW4HQ)vN+gfUiP)pCoUv}0IoaQ4dHI>{Rkjfw9`Mj(Zb1~lK zSvFIM*mx3e8KYgk!vr*&l)p>vLYvK{HZtXRra*hd&?ySS3i_=0}}WS*W??YX|obk&QMVM6f6 zs2`+N(xCH3XzmyAala!mOd{}QwsV9DNS||BFjY=jXUUrs+t0@M;ZuXgwSyEE0Bn`` z3}xYt!s>MV5FHr(h$ptxB20$Ev~?#7PGW0{TtTK=2d&G|P@Z^q%=m`CMB@!1pW>`E zZNBNa98yxHH^k^V1QC1!Vs0TSPcQi?oD~6iyx$TR8l)+wKAFt5vWZX9)i?n-3Iry@ zih2BVm^E;LmXSN=I4$WfKp%OgOkgsxoy6-?kVQdv*vdyBopC_wnYd{)!r2+v?`Xf1 zEl21r!$cD1wQ&DOj+VHy(cqJi3{Tet$aRNRsYn9JEHXHeYU+C=9`Y~YF5N3Ez2aq= zWQ^`^{k7SSJEU^fuv&zF@w|I^dWw-yH4ohgyO24K!>GbeYW5OIc(}$BKD4 zX7|H>$6ttE2qKBDMLB!1DzW81pZl9`ihQsCkRYj^pouh$KZ4iHwqRbFtY7 z!G+m*BUHy2tlZy0oEq0$J_yf3%@jSsW>JHO@fr*d!01(nkkO%W^7^y zHA+MV_3bI07X6Do7hfcR_dYfj`O?`BChtH0p0V(*eID?Bv^a%+u{UQ|EP6dUiCXrk z`CGYTs&=ce*l)up2AbC@m5>$PA4H6IVIc>3*6#@2YM1$M)rC#?rKWQP7K61%^C_t0 zG=G%0)CS0}g_Nb3#ClkrBnaCyH)ZmRioldtQyqm#m;8_uKr_xOL_RZ*IypSOU}86> zSAMdSRLq4c2+5!_2KjXu zz;Dq={LxRi327-@Wh8c`)-}Pm)~7;{ZK+$SSsA*=sg)wiN3)_8F}jsg=h|vZBZ+&} zBzyruJpNM~bRg59X^)Z!w8~qgJac3bD6n#uH{EHZa%)&T=k0f5O2O81kDerpd21bJ z0;YOIMV(2#=BB}lI&g$rABK8P`bM!zVR2W`sl}rHD$LJ8pPv@xq`^}vqpdm#yWgCw z`iQ>pYAWQiBlolLSU45~)^k_W+OtD#Gp()j&re~jSSg$2rFVGH{>jfCT9N5yT`Kxn zTr#B1tA`}kJ=lccW2{0V^o5XR4T=EqnM>QIkzR`t<*VZCPSFV*^A4oljOk9*=Xxo* z=MO!}43g&E`sTsPzlCHFqzIm0-H-LSK4#0y9B`9GrT{Z{5(e|q0tEi;-Dv#zTii?y zO1Z~jf_W+TWmwQY5a@8wEed*PN*r(xD?3i5;`62Qclv86Q7+Y(oMCn3uk5ArI`-LI z#-|6d=t0d`T=-?*jYc&bMm75X5RK$dPrAN}M0sM^`Kr(5DMg7i=KUdJGVB7|&|anH zq09I9Wo;ZeJI_7om#q-cCS{{ut`1}l6gL<=SVX!VaC!FW`fL;;*&Hp5;q3VwK{DdI zzgyN_iR(5i+QmHLbd7s*g-Uz%D#f%-qcjsCVja#tTr&VHIXga#cxxZVm%9T(n7WsG zrx&vA~tkrFi-%{&hxZ;{_w+W_i~o@JEL7u%)> zWF6A*5}$jcgg(giIWX+su%vFf9{Wc_ePi6x4#fXz&o{amlK4aL1f+8J7NVDOOj-f)?XtHP)EYJ``MgYHm`k!_wLFP&G7zT%c5p#Gy_s5{e7r6No(G%sXUwW)JG zI!Y+XQ8|Z$doQ98cFBI3zXS1$8N2A8xc%=e`aljbI_hCQt6`5&y`bJS_5X!4xHH0I zCW%7PLVKl)zg#f#(6$&+3@yp}C~1laMX4Nvq}T5Qp*|Ej+KvIT#E%1B|!B zbvkt>m5XY=$}@$Bq(hblV&A7|PfQDgeE>h1-Dv&jFAozj6FH{u7m-2Qh;iw%ZaZ?> z{nc65CT!?9l~GA5uxTw>u`o;^^cfj1PV^->NsFj#Pctw@P28%x3#~8*3H%CTFR}H# zmhadfdrm+(54j4;!0(Dpommm4B>ri({F(E3C%$X^HwgE|(+@@c2NxZ=J|&Efbl_5RWa( zpj2vE-^(ihtHsKFU^-OcD=rW76cugMW7K1O>zJ73e=D2`Rj&3_M*cZSLa>^}5#KRC zpLdK$znQ&`*}Q1R2PQ~nDXlxl)As{?oeeBd35Dw0;o8ZP@|rMr!kO78M>CG;oJIIe zEa>@fkcb|p%$bkEB)bsaHk8_Rgo_9uDnttO9<9hHAU zJ~H9A`&a-|$&fP;FvACtSQjr)%K~e-AfHoDe)g`MY{ll%G=jibckngKzS}8!$YaEi z2=!7EOywF?qcHjYSI~44pTR8HdR&8mT8c}^Vrd+-kX`eDC5i66TI1`n^D zO+4|Wuzh|X7ByR_I5KCVFdZ+3e?t>wis90IZ@gFL>n9v@V|L~C@%&a{kbr7=;x}qnV})38C$6(_rPh#HQ1ffz#Vgp5 z0a!Jx6d)@!mSPex3?X%kb%$W(&ttOw*t0FLNgIU;eWq3rF=*Wz_L$`_51% z8kh#ulF`^a_e+A59>WQtsCk{d?Xgj2W~C|-&STy z26*&)q7DR$!(jYrk0{>CIeQjkJ_Ao5U^Rbi!S;Lkft(p@bTi{smY{6!QfO^ppXQ5v z(R3%$L-UYUO%Qs5whHHY0!zpH-4ly`lj(JOx6mK*F?y=hkqJ8(0)3)$Ch zzk$DZYOfwYXdgM(by(J8{BrmaFuZ#niuNItdNir42Gb&`&RhnJ2TAk)(X`+u{_G~a zJA@S8GDmdSp8b%EX3cyE7*V?xB26TW-1!*NZ+(A!KS2|E=E2$g|IDz zg47PtoaS4{3-KS1wB<@xoTbYVWz;c`(mQ6p;Dg(FWBVo1S|ojPY`>;UNzq>a+XM7E zI*`cz-uOPzku4j5rWv?bJ?sykq7>Mde|Lyx&r}D>T&1=~Xq12h0LP$rLQM?m)s6FL zmuLhiyJz?nA{ilyL5iyH5;$4&l_zk=M{`E#ecct^Sy&}r%uz)x+hMg%=f{bgz$7rl zJq5}uf4-+F`Vyakm?LTFuv|tZQU|Op3=JWybzgycrgyojKiLH2SXYnu#q73%P-2Qd zaE@^r9x)nYkZX{y>@?-J#j%FeBm}Vd{bd=HenEYjx8lWz;@@xAOZFH(60IaPjlJeV z?-f^JvT51u%SQRFD;I@l6=fq&cp$v%1y`W3v+2Y&6Ny|lWW0TPrzVl3AHpY)%TPmG zu;>ALF*kTeJYZ)hla|&-DO>I1uNMb5@G9n-b*B=TOwqu{`Z@j~CfZgBHQet63vF<9 zUYR=2l&ugmv>4g@S*&Gv*o*{;iO*!7^Gg((elJS_@CYMl$~LSUM>h4?wq-ZmzQtBr zC?09|kAbYl7tiUO)Qgo+*7{Kzpg~_)hSSG-j$HExH?(&=UZ77+Q`Ue+-6l%ls49eQ zMBi##GISa6oEa3bM_vq?@xwGx@G!rijBIeMq>3Mb-qGk23*ibVbH~qkb|mJhx9Y(L zB5WSzDChqCIB}-SoK^l}X7nysQ*blX5mm^3%Ez{c{P~rYj^S@nMG;bhG^wap1BZWB zQ&)CJ!4=FMM9W9{f1lP_CX&?Hl}wsF2P#lhU2cUq)`5U9FP5Rh0=XQR1+im}=e zXQ{QbfQ3+e%Gm=MZu}uT**b<9uuUCWyHBUJl`T*?&!`oZ6Udw;ey}59<{b@P#oD4R z;u%h_z|gU6nBlEDuM~&W)G2^b#gF&u5NOd>Px%w!@x7R(8ODV^PtVS17+96a?e^QJ z{0%Rt72ofgnw91(K#R*pW4B1!vLrzd4>i)jbGcBLP>fN)x6>kLU~wZT@%uJ@v&2+A zXNh~hWnugnzdi~p`lxbC$fhzyd5Kaw+*PcL@_1tq^C`R_;eR5bvUwa3-5VYH)Tx}N zN|Ih|@GUaECZ6aa%G{}#y(7HCP*z^Pzb7!CHeCG**X)Z}-m1SC>ewbIfm*N2gW3HO8fF z6{Pa!C1GL7{Asy_k8mKH^9)*NI_75kyEyDurGocliG+(H|HlIC(8Z29Jh_DmoFuOs zGtLg(|JlF-pzyp(!wo|Ql4p5Wd^CAuknJBIX063wIs{AkL03V)FaUB5;$zk?b|srC zYVt+u`4px&WmrbCutVEC0)x;H7|KDyr8ah4*7DsCx>|FEY7yDibk( zrU!$ubwc7x=}%6k?JNXZjxQXZur66IvBN0@VeB=Lq))!=`hQ%9ITX1iaFVfc!- znT#<_v;2uUNF&$uMTTygTs6$u)kCTV-}ItuhG-~Av#ZY6DFoR^eKpQ!nMP}VMz0CH zuoj;1WsH9mD{%fzGJWt+8|SDh>qGMOWPL@{d{~=c(u5IVqOh1?g|-baXQ4d`o!0K4 zQ8zA?jbI%u#Q*rZ&|rv*W=sO>kaOhZaDjHDK-4*JuieUXK6b?uMmegb#6AES=q+t*f+m)R`n9JHT(ZlPZ64aYWtsy z(9MNKY@ys2N%N_e*4Ycd_otWLaxoH=K^qd%qIIF7D00(-0<7`fs6fGaa2!J9_BMAk zsy>=y)w_du8RR;FWQU75C)Mse{fpMf5|%lje#4v`L&m^)S@I9WVBvXO9Lv zwbn=JD|0VcDh7)29etoJw=DfQT`&Q|AM71UXk}93_DsY9{>S>VwjAuKF3S6x9@l!= zg+p3CoIB(h0gMM5BBFv0=g^0KS>hiK>q_qK&(Gi^Jqc8yt^VIH`NYA}P`mQA5Ur2% z*0$A2>;3b}UR`IJBp2m3gc(P2ZQnTCP(E(kUMeOn`|Ng5LOiNa7CFdoJGdvrYf7u@ z`>!Sn(7@F78}p6zej4^0s85s`8IY-kC;d(T+XLg`*`OaJgYHhheZQglO3=TU$Uhz$ zm{cC*N^}HKP!oxY&GWDH`QFKRUMfZ=qC_yXKv(xv4T{x$7Hr0IUN8znh$JNgQb6ry4_jMrtQvjio7<^K&3MNHfd?&O@mrnfM%J4V6}}E z0vk)tS~47%iE{V&=V}8lYaDsdmhhk5`%v#gMFu8j14pM@Y`1q{rR#{@p;e>J zCrZV}AD@)vzAp|af=I=qgX02Y!&IFNXw+WY=Zv)-?NjB?E8g;9t>JN~4goNc zju4rEMsInZ^fAgU=@oF=(oa$`QGtkzu$uUI_RDh%`Cj95*b5fIqe(Bc!x3|6DDJXp zA&TY}ihIUNh7Uk&X#k$NVDZ{8|CT(El?#$sHOWteAR_g8`BYLSgw;nmvOJ4nB9>HYz7yny#~B(fj6 zj5+(#yj;Xx!|!!A%Cc86n5eztkJX(OM%RnebAa(AxqJw(G#4RpB?>T0L|^Y$lR){mRr3CmGZxuC8(JZ}Tju%0j z!JRFC*` zp};9zbMd=A)rcPZIfdzhTU*YJc_JePgC0TQ0u4qVPTaY5U0`*!QeZc-wnC;blt5DY zIcM8SI$ApS-(an=#TCDXV`Rp!(I#XF3-{?`m<>PR6wYUv^@}@rMTQGewc>XsxuR{P z<|PfCUU`cm+lfjeUmjd-SFAcKzT{y025Pn{pTGDTcbb~OnOztP;2vC$c0CS7bq!5- z`6O5kFL2&{)FoAP$MNGu*KyJE?ym>ekoi#E8%IP`S#GO?VlsL-E9i`GJ z4};BY23$p)Z*0=m(rO6jGtJ)UuPBFx##}SstCIt-f@a#&s{b=8W?s<4x-j6?yTUnV zI>5y>D#C&8wlx{qcVmqfjgts~fPw5!+*h(M$?c_TT!u3k+igngFM9rLz2vL9wN27N zk7QhN2IKmK5g}BS!fIMlZa*irfoei}5Y@<{n8}@uo?vtFch~kvu@8&X|3|>08r{W* z7+0fTl?V6LN)t&s^l2r2ea;9wNv`Z&yF^TC29!d6`s^UTHrmGYD%TVLX6prO>r%z} z{}gz-I~1{r`$#gOr}?1ux6P{jDZTanbF zj}=kb<7y^87w%Z64eMT5SikID~2>NxQ68Hgaa4Ou8ON7@%NN@$o(D(bRz$n zu1n?E5h;t*`xVf<#_+l)5Q~6Iu8Ww?`Zu^%G4}E0lW=1S5pYw8t|r54er0{jXNs9; zpTEG}e|^69b~fH3UR>QHP2~+TeH!}qlS3|{=&1o|NXl(*D--@n92rhb)hqlbU}^19 zSx0@TS582|7e(n9RH>oslE!uK8LOx4-owovC5&f>zO*CR5w zbu}hd$q-*<-b8L-`P|#!q`bth|4tx{AKB|emB3z@TlWTZfZa$=6XVUztEu_+Y*oD)twc$r^-ntE~wCl58S_Jl%m9?gkVr)lMT z3BLzhRBkY7Y!}fla2uQ7#XNQYa>)gM;b>_aH--5pRj<2=cfnF*rb_kX@!%BFiBhz> z4udE&fGX8-&MQ>-)ULpSrqc6tPqIgAVQf8gR+QizFiKJE?j~C-r~Vw!xJ~;SNE3^p z@Z_aIF~beul+EW24TMCHBU5l;4cr0d-s4NhX?lT6uZ}dC1ifS(G)-4VSYsnGgS1x# zi@eX(FCWyEwR5KiL-35UNsUAS4)PYIJoEWvFPiw~@>xaV?O-Kj|Bl9Wj7I+6pP(%| z`j9Nez{}-q7+*PkD9Iva$1T&zD(4p@6Xdkkro^u~av19b_h7yieiN@UVX9n9fc;A% z_L&fE|71Mct4kmCA~_>WCTs;4l7oAZLj~vp+KAV)3v9Ans&_y;!8GYU)5{(Ti)qn za^(WDuH)f0dF_~V#LYp$9)DhWr;mm4nphVz#|CKM=$0Pchr=Hxn?F@ZFBVp{MT4`f z4&<>+Np)oq+zFTZO!W<|4A{ena)^lZb~_yUp;@d_sQ*o3TNr-D2FN>tMfd`a-^bkr za-o*X#a$Q9yl1;5)z8G!HNK)yMDpxeR$WSAx+*OPDyn~UA9ZH40udHbS#5SHib;p) zQudmq|nQ5es6<_;HGm%KoO5DX|0`={>q{R|y0D~$%apD4+Ja6P|Lz}rH6ddm64y&uL< zl6ZW6!GuemvCs1YZ==5em5it=`Ia2liPk++K$};4$FA>OJ|)2%Q(!H&8t}@s0ZA`M ze;@#V*!1v9S}h#m^N9DSaf^Xvp#h!Edtk@LO55IH#J;RQem%`asqTFKZ!=7(vEX-h z)8>*k80OY3G&FDr=(i+3VL=uOnhU6TB6t}RsEvAfw&WL{HihQLi}i`GLz!B?LjG_I zMiA{K1HThZTnTotVk@Lc+=G{RzY4))ZD2bUvp|AecNJIZNasUANFx3#l)6j6j<(Uu zeX)3|hg824ebt#$-q$A)m7Sw+Q<#`*JA(==^xY}(mzm?3w-`_5Z!E?M{U0`>t`EOBJh1{2gNdAT{TW7R8G&8i<(-fbMULL+j z0g0H!O?t-`EZ&;o9{-UtFG~lpa&A+-DPB_-w^DW=fE@TeWF!Se3fMI6V&%+3XwUFrsyf$!2KRe4a|&_HnC z?Q*C%`xNxSKM=sr#O&#w_-__KCMsmmgA+GW(^(Nkwr z0VfSsyT@}limnAc zn?H>SkYDO!jIN7mC%w5=+9&ra7N5=omoWOo7jpF`-Py9X&u~8fVN~&0YDk_0V-h-b zx>P%b!6OR{U!W2FLsS_?{x`g9@#Uw~F4L^Y=>SD2LA;gtb*jc>Bf2Y69i;xWQc+7P zX!g};K<-yj-`;1zO@yx%#6l5BZk*TOgZ2Xn<_KR0Q_;f2CECCFgsh|bqE&_Yvmxv; z#;5qWa3st5T16w9x)lM_Qln$`0$L~L_n(~myQ58vrgnT7xUG1I*9`S%d|jyOk77`Lsi}qqdT2XMGXo;=w5G z)6rD^F(piBG(egc-qys+xLrebn26#AYop&LIr(=SXiocJYciEr8GWCg;~VnMfplOA zd2`6`=2DTndcT_h*)~AipOt2UUaU?SY4GK>-iy3(FuYXL$>J8?A@`ucvr0g?Ab}HC9|8)I zANSwvQ{H%dPWmcXN$5MY|8|6<4IzlK+}Wquw}^FimY);KShpSfj|N&-*Q79XQ15;I z#sb_#!+{TSksP6_vaaOE-pnoEUrF7o8j>To5GP~q5{OyfEZXu|JgeZqPU(`anqg+q zU@0wvgA}}kl@DY^Vuv;`-eydU=4DZ^>%1cwvRb)ui?=8I@nz9l=bAAFA+Cmob$n&- zE%i!q!^Z^GkDVq{u$Rl7vn)7ri)buE*`@L6btrUHDWIi=j^P4tqU+vJDXfT=<4*Xy z=f6OCC*D<4mGk}ekd2lAT9Vdpg5IS>N6merenp_`)B$$|YE<2I$ZGUwNM*iU*)@6j zXmI>}+w`O8L4GbycS(AFI*P`PMT;v|M+{a`jLLS?fw&xqTWw%oHy0eNv314?7F51u zKD?zlZN+lKODWF8=_O7VrU|H@((Z!e#VV1)4F!gYFNA(zdsLt4kon-v2Z324nkl68 zGrg@oh))=}lSUY7Ir}TQgNZm$Dt7HZWt}afo8e*L0)PCu8)u~!EWmlzIEm7)rIRz} zAMZ&2_%;-znKX}3(>yJmW;xVuo@A8Ve$i{jy=g%<4h!C!H#%pFS!P<3dXGt5_A{H&n;P$-X7NfYAo8dv0tus@dN+Hz*=K1xoTomnYd({BJJ_Zcj`;&A*Xn) zrcCwNjA8QVkG^d4??(bodV<({)&6S*19{w|J{~&>GS)AMddajiZd#dnZa|eC-_LnB@y|DoHb5;VO1ICh~O=&15nh@^9Qpcg>$}-))JTVA&JW>4dLi z(X(5XInbl^9a8tKmCvNAl7 z6BpxURj=i|qd$f9*WRY{&$fBliVOFy(NHquy(il>H!OC7#x!H2cwOnEO|^GXmCvc% z)_y@giQ@2b2UhF-b^V5(pATUb3XtlQZuye%&o61|!KK zUr@r9xi*C|xTbi+Pb}cyaxX?;dWM8~*U2wl}hIwg;}(-E3m`DQCrB*BHr(=s(rW4)UH2||7^Mt<{7`ElX1O;5Ub&2-iTo5$`ZlmGqs4QPD2XY*&F)k#%%%Jh27gjS zE5jLLP}`B-LCj=#Y7J~nKag727z_mPjM{O;uv}P>pU<@owI!dZI{@2)-c#kni z4}pkxA#QT@8LWR(ag(<=lZmpB?H$PC=R%Zd7y$5F?lYOKeTvvqRtZ%Vl~L%X8z5+n zl519;RT&}p;UQsqy#6&e6QCmm5JmIvQhqy~Vg#k&jGeSX+BW}4OQSXsby5@F3geWn zT7D5v^Cl^UdO%X-%7;p%^`WLa&PO8DrC8G!1wINehw+$$T2j7c22)Q!d^SHW?UmiROM(BHM2fhQ_z{OgFH;4Y)du2>s&>jypeM)4aA~Zr+4Q}n#gc*tBE?D z2hQ}{iDu;s=2I1E)sW5xJsdZxqknM7FheUX#IkF)BX-b0|3&ZOw4elsf|o9DWj4kI zVzvouXrElT(GZQlX8BMGR$hHlBa#>XQ&G1dSo0#9=Z>;l4F*tq_nT0guo*B^BBl^2 zMxY8)!Jw$d{x5LupGP3#wEtu&X54unGzC zNLt{K#ePTbrO$qWN92;7qI}Abgkb^qBpf}5vV_!_qoL2MGH<%U7D`Tdya#BC{AG)) zY$~Va7&I3~-+GE=BuZBbDK+nZ{TUEM%!#xQ@ES%ntFMFwWETz#>hHVb9|9AkouHsF zQyWa?KN3(c$Ys)3vhBIecxR2H&A{@4-1-Ujc92elJq6Nw$=TO+fM!cw>T!M;LqBpziCJ|(#jkWL+In_=bJ295Fxl4lUpsnQ;F-=# z5!IWtMWr*U?uWvKd9c&i8 zA08|03=`9B#LKW?IeSlQ2u;cebhsD>SFO-AW7!wWgbWG8HdW*tq z$y#o)yz}#&BAW}o&v){kUL0;5_3lC%@J7~SvGsYj-4*nHPqa_L5Oh^EP@)9J9l-S@?klv$ww zbcT7C;_0(pUitghJq~&5ThVX8C;}=2cFAHxQ z-H@Riz{mTy`$AE#3){ZGgx7)RepX`H-RkUn7Znvqn5tcln-KC3rlIkdfUen+`-`mZ zufUr#G1ROzUUf=dE8lFD29Rh@G(2mK2K9W0D?j+5J@jC5P*E}vUU{m^$p}TxAqhXc zZneg$e)FV{Q)VE06@10TR0A5Jq-LN&c0ZF)Zv|#KO&&Zw z3vM>ibmkf+eqyP>y%n-7>~$WP&6@1{-!FI)p3E1OdRW$rwl#pYJ+(XY|5^YzNz|}o z@{U!WZ%Oi=$@P|;(ESP2cu1Z~*Dvv-Av)&Ag6QRpx^G3h|;25Kwsm@T9PZW!ET zd@zdcWRc*H6V>>E)avF0P5f0O8{jEp!p*;IB12F&RjBYc>O6WITw^58^QfhetY7megG zxWI}d7vqjWvmL>f|AJS#g9UIj$3*Rk;_p5jDUZ!&W#-$dE4mYx5Z0GYucXlfj})iM$(#8M-<4jC-4}u3SZv7MIYG z#z{Nq!oIC)c`zBaE2wpdl>-#6l2xCQ@FL#0o&MPf=qK66-FvX1estgtLK{k<6IuQ_ zOY`=MzyjI@IYB2!kPi?e6++SewqPu1$q~pEy}Y>@{oU9O=S;8Uo{Q_Tt(k)0k>z}1 zbTzu(hKY;jVCMMAb@VdE^AK7qt^k{t;UPe&%-gA7DGTjGn>&RC&#tjl1z)V$)ABA< z1dp#Z2C+%poe*iNz%(fC30J-+1Dt7Rg+X5FEv-5GOmdFi&UOBeKAkA20!6a}i9?H; zB4yb*skL6jSq}%k-q7$GC;cJ!6G>l$=$s$aOQDX_msqcec-S{PzijLB89e&k(7ut$ zDkCt?CF~`FRQee8kKv6=#`%Hz9I)T6m-F2_pN}XjuewYT4H*B;EHgBda(%_6Vk3;D z>Z>ZB2;oxVdD9BLy{^yz;4B&~k2OUk1$Q5Y85=8f{E<$T@1;e4PMUBnMIpCoo#s!a zRA_|%MH+njQYy&unxPYeu!~dVz(tm-LLIL8-++WvsNtYr835&uc6bnxRpNtc#`c{2 zxOd(%wbE^>QPu3g-|rqTUuXrkO}-bEmTXy?{7pM1-jQa2LqqDucg##bnmAY>7j?Q;n0^MWmLK{D`mnmX&DdVbsz&A+frmaf6F6)a(kP@4|DC;xnPGf6b-h0 z4Y`u2sxQwZuGT(9$<`CaYSnxaBn4Fm2z+@*w~K9n!=9}xiO4Y>iYY@kXd9i~L2r?; z<+sy-^mmw2^p$a~L3~8PY4TdJhIPdF4aD~5!x4XMMVGEvF3~T#b9|b*X*>9$R;)-a z{RSAqF0Duf@IhdpdQtgG{C$lPsb_Lf;Y#T|vXFo_#qIo-kLFIO$T?DE{lrhKvrhTB zrX1l1wuON#YYY@|cAgPE4E1;Y+WBiIi6Qv?74+UY`R0E+9cMk0{n&JLcbyTmMyqeXT59C(W^uheB(MkeJPcPOb13h@>b_dNkm zYceIft$!EO_QwE3gh{tDnI|Ld{K<(Xf4es}ZM?uPs9yV5HW-|dan8H&XBhDXNV}cQ z@xb~TG>PY{B8ce+P$3fp#C*#%;O)Z ze)jG~@usPR4~yO*y98#olr?J4?Nd{~hpSV|$y3{}T=h@v+FeIhKf@Jr3?1iYOA9(T zLhnM$?jFB9YMhBvZJeSfdt+>%Ydd@HYddRQ{;N}8%R?PpdLQ}4%}O+XmmI<55lk5I@tyRCbL|COrB#?DD}?HnpgPhZ0b?8Qw75O@EH zw~ufP_xwfvboxCWR#2fpcN>a+d*lvAk7uM(-I8ncu#6!0z`g{P-FT@iNf1q%W%m_(!fc z?7d%;!4*BFrp7rQnaO;ikaNA4#y-7nA zjZSPxtllagdo75@jCKHp8jadL#Bv`Gc@L~eJp1*Hs?osMaMYb*WJ!|wm^2$6CbCY~ zD1dEJ9bX?{GR#;npYA&NX+M*%j(MBP`m)z(%Cnpw^&#T1LT z7$JqzZBBnsjZQB0JwG-69T8)2C(p77zocIx!+Bu_{kss za)ou04$E5-uC5{i0^D=7nzpW=nD4#Lni_jwSTyGo8$3YOL+guWkelzM5UN%p&RJJ#g%2%aVm8y z{M}Qr42;^b&`heZrrcr)^@Tr9%)7vH?kp^AxJvL00->@miSw2pR!<60s}n#@vSuV_ zAxPyn@a*^7-~GEzO1Q^0*!#j-R|l;YcMFw|C!0(A42i>kB%a+#{Gcr25cPR+@qp%& zO7o)><-B+{7QBdMraP(aCU$r5)I65|!5~U_(|=IkU)B5jS$P_1dcr}{-Xq}1R`0IU zm>W|HpycI!i>7+ZYl|?E6CK=mq3@Pv(`W4UuhaOb-8j_ns(gp;%`s1op{sg9vZ%7f zt40xphkvh7nGo<#sAbCce*@mNHjCSfkwXwDQA(1!Dqp&Us{5_m8q%C)A!GP$(WS!HhD=_EUAz{| zOf-a~&EYj%N+3!m$=6&xHF-bDQZvyR-$gvi%H?Snp*WhZqB&5nwfdO`}` zET#{y{DF~Ww6Cs0Up{|KV#4RtI867R@9r}S34alF{0nOiLB#7C^}$8>K{{sefxaKn zKTVr>o}brjio(L{yhO!)rIJD zWIT}6A@eFaSbQ?3n*^WeW~5~qTb)|5xv6XXt$c)8bT6+D7K}13A7O$y<)+G=xkcz9 z0k@zJBmCm9K%ET>2-tI48I%Y_m!;UJlGXXT=S<%Q3Xf*^bEzTtapf!LkOygtbe8zH zd6SPRtV1kFFPhf^X%DNteRm;~mb$#iaHUc!ytIduB6)ffZp^o{sZ5Rpax%+AEYBMa z#3JOpN7_c9=yoy=sr1B$y^$f}8EI6e3=I(#y%TEC1ItsnP)bxtZ@?m_A-?fv7a)=z z#x`PPv!Q13te7ZjXQJVjie?XkmSLb<>N$ABZE&4VpL(aW@ynHbTH;o%o9VeWwRcNX zSA*Vzd&^P~`5j7vpsj!FUY3SJOB;Mv3z1sM3*wSD-wv){tu-#)MW?!*_?qZ4C@Nnx zlz21IC%jM)uteSd$-n{1`?yhAywZB_V<5lmil3ru`=Tvc%m&%0X>_<}lMpGDb&t3*`OFY#{qDEQ zQBR{jq6~cz%DjrcP;{NgFfR> z+X}VXid@vZX5LMfIFl;TNPL#{?e6tzl$jMf^KQD)X=-tX^!@*7ff>C z1TUF*CoFZ1_*iP?Eqd|-sUP~kle!av+E2+Vy>)8D?geOKd3}-jqa|D5Bb*#N662}o z!${(M7dCuCX5RLizVGfs3cOiR$-;7iExkrAl-`uV7UUYau`-_hX{L^FvO{lb@Q z8o__x&*|SNSxG7NVNnV}0#k;vpa*nQ9t<87g9hZP@$M0nF}-nt!<*VAlSu+cTK&p7 zm810AL=h(wrZI{xR{UL^U7v1M<;4g#>X#Y5;kOGiKZ=j=;lcaykk-C8?+-l6MaV3z zYu)8`><@|Yh-M=W4`c=Ac3xY?!vbDKtkz8>`7zN3o0Owt@n5sI!{E>}54#QdwL=kPh* zk5=IH_N*ufXA9WN_8&5=s1L8AA+i-abP?09N_B;ZiZQxXwzY@@Z?~mH2Jicr&fPvK z{<1$Jg7JjgzDe>WdxQOr8lD~5pyPK3!t;0H!N71=i^AyE?!cIH>d@*SU!UhB z*Kq8}8B12`&wh00hmnJ5;WVo7s8VY@lq9W6oQQ9 z4II?f>h8RNB<(hts4b_3;QJ% zLmK13_AcUfXrtY4IIZVi|6wU6d{ z@2NIilc8ob6@S(W69X|y1F_32Og$rIJy60Ya=bLM+zr$1+Qjn^{XD8>qc@s-1!Lx) zOQsHJxVTM{qWOxmST6Y9V7+nmNEERx)j3R@VTN&)p8BfYhEitAMfjYtLnk$|E&o!X zZ+}oWc7|5^6dlSjG=dd*_3h>o z@ZBN76T_>asVh+rL0bBtMT><|VUQ1f6-ZE2L%By8Z|m1HVtr~JGe)VGueHFIyc^w!&QZ(bJ= zH7!JDp|)pAjc)sDwSya1XFYOlIK3<-_Ws@kFwTr6{`|;2UdFadFkpAsQeZ)g57CTQUqccCMw8Z*-r#As>xJl_Cu`c|o_c z4qW7#g*30;>P5Ft2~3s215KuKdPgdspn!P8Rm+wi=NRxWe+HSyw!|VEFH?9@i0Kw8 z4}iSGiO@jv^%MoYH6ma5S&I1IC*$0iN5OUm2fhp`>`Y31JXjlBD!ejS0f6an)o7wH(*Y=$U(+_l5BQlZ z|B4zLZ|a2uReAL% zghnx_v@FQ!!PS!FlVdfEQq?tG!k#pXv{wC9OG zB60=aZ~MxdSb(sp`Mj#$r3;yXaO5@LVfW6< zk&9Z?Xw8b{zoU3EE)Lqq|fC0oknjK$2SZ&w{w#4mBOm4#}1XNlvI=CxxVr z>S9K%(5pPPjY9Q(pJoF;*_ZdUWVk1s<4#Co#Uw|PCnqZ!?VoU=qiZePDu5&=F&(Jv z1}0;WKe@;jsE_o@S3KOn42{@K4YzR(&!qKa*PN=N@uheKQ?4uqq?3nqk0u3np}wp8 zCS*6{{!c)sCx4vqJ23M=zZp;PDp;Ey4HLmy%yl~g$JP%)7RN$VAg>ds5g4k&#dhIL zv4%_H63eWs!s@7)K#;J_8XfM5r>r`8#kmiidg^lxQUNEtItwu#>P49W)W*3{rMQ-C z)uh-ln~b*XREO+w55Ip{fsl}nZ95(~%O36M*ZO53FN2X?4J%5(-Hv8hoZZ-M#2-ab zOM1Ay>+T`nTD17VfyrJG5%oNb|4_-;j!7g;ADhrLT;5DhZ^gZ*V^gXGXE_GWc=B&V zZL)s(X28x)(_SrkKXX)DwA8nBP<}QxH=sx_Ef!Ds0qoR@f{mIpzlG+Zouj-fw7Ai? zSBQ)CEllQ_aK8aqru%o$E5xv?&~_tH|QHUr79#?Ov4Pz{y89 zh!jc>S~V$``fwPennMt8s_P_HGoc-yKcAh%_bmkILnqux0Om5CpGTHCV+34U8#omH z7Q4o?lRaE;KiU41NpX5~pD>C;IAoX&&tYo|4*R6FkY#Ik+T6Jts^Xt&pCSCx#p}Yw zJOUVo(=LdbTx6rY@y_PV7wL}uKWQB}U6F`h*8;5J;M$EcxBQw@tCRaw$E zU8pqW{724Ga`$dbA2V1Lb8lBA z>3)LDB~N2>H+2WVZy2}V1FFclFC{s9%eVP*QLhE4u$rhrL)S|vq1Qc-q?-*7JWp@ns_5qO z6jg$pt5WRJBC+L;9j<88YeY##M9K8E2PBR5m!xKFfeJkyrEeppO8*7$xi+`qnyX9+ z?IGwRgDcYt^y9r+j9l0KO@zRP&j++xr;~Me&C8~5?q7}{>KiAU9sY@lr#fsc5sgSX ziBL>PTQc+lf|BSZI^*X+wd9TOdi!i6`~;7ucVgYwOoM+ECg%D>FLmcx zpmiZoJ(?l`KugGilgz`n0!(Gg4oh$0dotK9^`03tlF4J9&r{D4)|BLiZVdvqzB(K= z+5)3;vb$M^a_PrUoILj%2K}*_EUSNrq$frfWSt1y?KlYCMwDhW8(DK{P{|+X`!cMlk)qgRRS*|s%V^Fu`zlX0mTkY&T-&u!Z zmi^sP-0?7Y_)&3j`9TXm`!D`|2UNa*S3!YVX!&cyJ9kMcho@jW+C%pT{?~Hk6^+h) z3LRSCq~Tfwy$L8I5AW(lX2}@cz2eDZU~ls0#B;Ig{f9b82Kld4Q}Dub#NdQP+3ZcJ zSH5Q-)Ax3IMmMASEYoF@@aEVCa`4u9lsjJUPflnKHJy$e4`^H|q~YkX-xSuF?Yr*esLQDb7q_yYfJE2xj34NGG1+Y}KO_$}lGz}TE z<9)B>eN9>`*J~lE?@(oglq1jPy6;pfh8}&2+NiQ#y5@Wj$pRtq3X!cnj9XGA7-P)+S|FOTEjfLZG_x|r`xL6^eq ziEd_o)JeF%wYU9zu}VJI9mX7900LYZH`>IcsaL~a)nKScMB))sCi*>M|9e8(#U;;P(*sGuJ;vW8z}qJK_ho(D=^ zj}=&-cm4N1F@(Q_*(8|}bXiV4$n#{}rsp`y7vk5>ZG<7RPBiVi4uUozFYrmmW7&PI zgr4;hCJH~xQ|(|#EAZ0+Aso}SBT8S~?QBJFmMF>Hp@-3Xq*gGno!eES))l`|{i=U; zeZT^3@f8CI0`wPHtz|9zo?TJV`z#(+e2v)~U8!Us7Wq@I zV)xpo<uej5`@^%QtZ{g{mmVou+}S)Js#K%85Gr?qqikMd(r!l4h(j&W_H zMT7uoHM?e{>l>aULBKASF6J)Ynf1}*8igO_oKRL?NVOcf(P2eL-TFsDeX1&SQhVdV zEJHMn;{oct&>%ejH|sbq8`L2mg<;&qFSg+8{sDaYF6cfKzEFD4SEQ}$E~8w3wKd2q zq(g!A85=8yX?o?;$~fx%cOBUrWwKha@3Wb-=3VPvISYTHh$J4H@x@$ns+2~KOOVknFjXqat5>B;?aM!6f7DO?Ww`DPZ!$2- zpVtn7&Uf%=v~V&N;iPChZ(hm&j+=MbgWeOf=D*Nm zH=TWHpx;D|!8P)Mjb`l`Qi0`fKX*(QJ

    {UXZz85~>cH^Lp8wiW0BC$`=8^<&t~j z&aazy63J0PEwUj0i-J?uA$}CR7{;L>Yl*YjP1U#vO~KQ-#X3IhfkJiSk7Ix+^Dqbw zj9h8^ZHU0Dc+U6s`an)_+klc&&j(xQ#hVJ%3&;Y*y39-y?j0;ADv@*(*?U^e1 zV&h`@aTJZl?~hD0@vEisDD3DTPg_sd7eT47lcLLgD7NV`y#*jX@~^Zr`k%-SNH}`! zFFm+9h_RdKWN4vs?RNqVLguX3k-dob*Dl+c&@b)vVE|}|9kFQEXg0ln2#0Tc%3AIC zIZFTCUGR)y;XRd<*m9cP>np7RlVQvV6Dv=IZshBB%d*k?_G71-40Q91mcq5){IGwu z&*qu*TD0cez9x$FcYWEFv0jk=__y<#Wso-ojKa9eBQ`#9;ql?YkwdpNX|I!M0qUwPrPubHscL!ZRq6+1yIC%f){UN3c$P4r0{HG}GM-Nl(<)>HhAEYg5th>xeZ1j77UY6va{DAbw57MQUzk(v< zH;KM?v??aJ6AEhUsJB#y*%I&jgZ$kv-93&sV#U`vz8(x=85j11p;mahD~2CQGaZ>i zl0MH9))2l&6MTke%>*%)s(QtkV|YqQ!|#NM~csR};m@(xfRT%zBSC zj{8DVCIH=&6-}v4aQx+Hd3A$P5tp8hxyWe8Y0ifd{t*>qinIL9#FnKd_{gOQ$IB%#@>ftBL$hz$7KNR(0CgGZEz ziC#yARnucY^ExQD8(_w{Fl=alAvOivqTj%1VaXS^#asu;o#8h!HM8Edo5+t)Vmt@v zRd6}>(IFki`;N{OX{0+VEk|Lvhr!#KHOZBnGanf;=jJmy#9!l{6SrstuSN zdSdRMs!czJj@gyaD<*UPSe4(fj5v5vc+Bc0?2C~u$=uA@$o3db6sPimt5Q#*w0`1j zyea-%ETKxrU-&DH5t+}`yAM&0GB64|PWuarmfjM~@w4a;b{)#2B;b6sK@VX=X0%&_ zI8vErC*0Qg#$;bcKedF#VwyLvHo&?SZ!f7;j%dOU`_1Q+_`eI29!!xrJQYXZB?C58 z+U8P|2I6l8yGSGhvSV!IOXdw(QB^>W-e1?6HD8JQ<5miiKyH|u0{l6z^#EMHGU{?L zURad;piRSsSqi*QeRBi0tHVyNK7Y5h2Lr#E4pM&?7`RA;z0;QDi!H5O@Ba?0UqE9K z>!<8!a1h^4l4_1Fkb%2rl7MzE!~%7Z{w)c;t9BZbS&6%j3wh}z7Me8YVk%lA{6n2= z2CFV?SK5*^B-zxuCy$Fst%C|bppV|OIcL7Hwn<$3BspA&%TVk~KN{D2T=j34F*dP0 z)Z(CzAzoQvuIs)dV3@Ik$x+C)>c%*6)2oO3B#{!*H-h>FF*N-<%JqrG1lI$rQKA)7 zi#7m=2)C}oFOejq=76n=lrv6Mf|znFmg(4^fbYs1i-mD<>@AGUiF| zOV|V^sJY!BbF*NeJGu`PO!iBUR>TskiE4h5GuA2Dbga`X75zwx6HQYP+ZF_~1|;p_ zF-o?{FpjfT)m$7H4rjJkisiKq*3 zh%sB}U3!VnnTAJ&_LXumP*xp}{~xXrdN`wYlqUksRv7*~DO5FwUYC=WRQHG21l)y| zL3X_A!};&mfJpYXd1zVn^&}?#gT7M39lzXK@7TfWf6w8JaJ{07*Q*Qgz{AkOm}SZc zZ!T9uQe>yk+~aGF&vn^Kpnpn-<0B?9ujzIq-#M|TMtndDYR9wkmVjy;c8^|M_*P@N zgag``ChaFWW_+md+4w35y7sJGFLHJZv#tDpx2xv(i%qYTCvlpU7x3%aihWZvdM&bZ z*je~7U;C)Q9cCS~b#{29@bz4Z@M#|Me9oWw*<(x_!3K7YT=5CyhGV|USy@ZAm0^=Z z$^n4iMF3w>IPQ*5x_ptw=ZzYplJBLiT~**&EsUg*lG&W!4pvbk0SEC08;X~fKcpS| z(#8NclshkJix7@~`fsAiPSR$uPCt2t&bOyZSLvnuVU-` zA!`*yjfm2yFg8xq>yWmIQCs@3flZYJfmoiT#*mjMRtesk*4~E%x&q;UznSt6yEF+J z&o*&-wPot_q~G1dZ9X}ZWn@q}O{?+1-yOBiFNLhEn zGK&4 zI)#UB$=)CP%m=1!d?!^7xs+?RdJ+x>{96Q=jJHjKIbD}B#CFpTVn-%9Y}H&0!u2cS zyvtl$JBB)rNKGj42Y9ir0WIx5O(f)pdCk~vYO&KO(Xkornv5JE03Wjb*K$^f^2b)^x1>E4Sj?UKh z7V{yeG? zAw;9+?{G?SBpl=ppg9;1TPWba`h4Hg*_zK+V3a_Hj@bev5!$vyLswY1B}H$i`~4%{ zqhj37ePn%!vm#yk34@+Ms5$W38r|CA&;epb_RINXaWHRa1G0xMr1dlpMbOhv$qwAi zUSL5Amm2U)pX0Vlit!dX&mao})8C;aN17H`X41Y4*9k`wMQF`is8v6vV2={5|ER(C z|MV*AFm|#L(BWkXu1<&7cTng#vELWGi*7V?lx$-W%7TzOf-3U>c4=`+P7Lh%|Bt4# z{%i6L+yCg!NsR80?gl|Zx=T8wk%p1dIfisM5{iU~bdPQk868t5p)gQ7zWY4S_xS_% z!~NQQU)Oma=leVkyrr%hJ|D{+6(f5S_ZyAV&_X;ak)ob_P+staWc_|FR*A&Mp z$Go`eq`})E^@p1V#ea^Jc|7vi#<|kKhpI&|GP6-nHA3zK&%PH99FdKndr5U{M^$Vv z0}1$I62699Ths`E<*AcmLKwA8B^^`QYFXbin1rG|y0us(i}bGU!lZcfDikqznG8;Y z7=^31!Y>LD(WBpJAd#Fnq`lS=QE`TZn%QK!oIvUG1ndP@>5kZOp)6Vir2KXVqa?l) z--&Jac6$rwMSxc-k$hyg=gNOd#5>EUL?S@z&cp(HH4%zR_Xti$wlRK4Ate=8BXfrX z{U%8zz2+W=_E@lgpWj5vb3Yg>bHGB7f4x+o^CbIwgPBmpK?7HO7t0BmIgaDP`5M=U zR;*Tfr;Zdx>5H9JwE`)6M|NoJ%B`rFV2&&4_n+GkfDQv{;jqFu5tM^J#??O%bBIfa z|Bqt!OdR1h91`al9^+LkFp20c7?T&zS3ZAnoFACJz86%9q+48?b`+m#Tfzi)VpMOz zl*t%zODR5&j+xj)QyQ3RIns^!@T0~81yTrPj+0{)8kpQz2didP$LxED&%s0nyZ6-g zM?$n-=Vf1Dacg@D8db?=DYX%0?C;cX8m>#@BXJF3EsBr?onNsv~E-pkpc}{VG>M25R4}Sf6u%xDx<;eip z``zQ%Y~=9k($-KH=r%DImo8$)d8RI%s)@xKfsENU{ALXY70>5*rngx>KQ%3zC%B4B z%ECI?Kn#lHQ$^u=`%NMR_zslig|3Kle$*e_^Mm|hITD%nX`x*9;MG|4Oa9b2`%Ze{7t&;uE7l+Hm$btw8nI^*EMtj&;5%j8pD@o> zL9C;n@#zYa;He!7AU(>9PNJdw{;3wzc64Vee&R;#RW3vEOq=4-mAf5|^mzDdd9*w6 z^A(N`@kzL5v}|IPG`RomF3r7n#2fS&Ojh<<)G=iT{f0XIC;ygyD^^Mi3NO`~KFj%> z;#b)E<3`)MRw;a`XEx{3)eD5~t@~g_P5&L9+?Qd-|-xbbyOE zm*$KMQFOl~M9&xw4_RQXR!HdOeAe$G)GzeuS(L8P4eyKqDNjS!Z6_0GQ`7hi)Ax60^_y@|vrE7Fa#8re+4E^&W_3!1> zm15a#{(Q&3I0->zz^{LLf3UJ6g;Qrmon#%eRFH?k!1P!%kOs-8KFa%7eOuf1Pk=Mp z8rA@n)c)?TwJDGNa!av>4!+q*E8OZ=CzEY?in8DKWk;O!Iw)A~%f3p_{^T9W92MK5 z2hrF+8m{puJ7OMsl#n99X-c&wlsj z?1b^`bI7R6&gf&yj2zBX~!x<#*{J5Pz-$0w_A>yx%v5LSiCZ=?-WTb z!Bd8uph#qJ1j4S$N$zgr|pO22)=SY8J5dsTZk3HaIGZ33m_ zPpHv*Vnj?Tc9Biq;0(8YP9YC4$I*ms47fihsv0UfHZIzEE>Yflp*$4xq^bBxVh8=_ zr`E3Ra@Ct@X#Mrg?`PR@k_^8M@dUVu)S@h3d>U19Np*amRh8|IYm6->TuVMf+{^*_ zxwVq?8{7C&F@WLJQQrvCIUjx@7I1Lf}6m;#ass6+djnDl5Wp z-#k4|eL+)tghh3Ul$G)CPOY0)W&(&UTa) z9$O%>Ko_AgL+=h{@R)wv*q2jFskKNIJB8b=O#Ii<<{_#FUGa}L^NWkG$9H3$OP&f? zHuxnFo7a&`6Rj-g#^2A?k!OTDMK&N8hvvwL%<5}Cm2}xU2q{cvpb=}^FpSn}4J^a? z{aysk=ye+opLnne4str6U+MvGxBF3fSVp$k09*o%lSgm%C`aGCmVzHRxN-!44iApH zr1rFJQ884*DbKlLI4xj!V?x{z+U34DQnX9hYd9AEvvW(Ok)`oyz}v+Oc3$r9btXa& z#rRZO^WS>Mj*HN1u>w447%n7Na6d`ta^G^K;lJ5IJ|Z$!E{1*<&hBUTqpL$&Y1yaM zesTUU*{nh;{5j@_KQ4mp#jLZzkf37AR0^Vt***O(xEF_f*n%4P?1+d~9sJ zk0=K$JiXidLZt1GI!owD@gl<;2v~|$vPUTOsxJKX7xdK#PpsM!uBqy*Cqe0~1%}p~ zlSp`q8~T2TTgUO?giY{?{3$mbJ{ZlDdPoJJEz{90VUKh5r-Ts`8Iitv_@m>_C2&CfB`vAiieq0T_--tn^)K1npg;qx2*LsmlmNG)(xCu@#rXMe2i7;`3EWAC>vD{;E+^}qF>mujB^*v} zWPm+=B2iCV!u`=@j3wibJ=&%r6&-aqLK)~2+HY-^L$wbVyNcaprQKp2jZNnw<6y(5L&FW+~Epo8#&uXh8W+ zPaUg_G)*|I5bB3f30h?s?zip^i85&+L0czF%CD1rxdyyl59_W>Ye3UcAi;fEAGF*d zJA6fp#V`i9cZ^HomX+5}7ngTtF_0YXN*%(`zb!S_IUa&@`@I`tE)X$2ZFatzUh7!B za4OUMl<=XzgF>uCWNAlUsMZReuawau^oB{z-X^YBRnd=mpC|EwHc99B$#Dzd#|F-E z7JS#iT$8FtqpHE^{gbgRPuoxu))hNI)HKWeR%FBFrNwb+i(&;*!JZTARo|tF<3>H;OgwBwC|S4fTwvrK zXGT3{{jcL1HedpSBQe!}!;7LO(-*Aezbe@ZS5kc1@hZ6#_ekLm zK4eQq0@8@faC4K@8A07iX|M3My~}Mt7Ye;jMMI&nAh1iJh_Ud}PQ<^z{ek52S-P|W zvBBK3F|lN)V%me>eh#Xp5Hh^_P7nIQUsy zth2qla zn96e-t^8+UW=AHv>*o z6FMxNvF87TpRIV>m|DY{GTc@GA<8``ROHi_G9r3mbxQb+oir@T=)_;?w6%Yy_u$?@ zVh4#KjPK(=KaVrW`DQ&s>iPw*22|>Trf~sI0IW}Ss-+n7$OReWi>OesmKEmRS&z1^ z45bf7sUQ-<;v$(2mu_&_ujbjSAC68c9-J>i!$)2p&_7#CfiF8LeT6qBBdti=B3pbn zIkp44Kr1{b)hDBc3!7K22B%*Q8PQX$A~y=-pAExexd4r3t%$cvR8eKhv~Na{HZibq z?PPPZf>tZv!6Dm|RV4exxZ`}vm=^jralTWXYb%(h$Pbc8FkFGhv9)}HNrJ*>e{n>A ztV4u9%L>18{VHP2vwID+DgTcinLF2HD9@^=L8FJ`cHr| ziFi&D9Nh8UgH%D>E8wCRtDq>ZezvW@T&*u zxh=l5al^4a8wnO2sA>t?YP$CxOy5bsQMmk#AHSUZy}1t~ zTPg9nKb=-4C`R&8SPPfvrqd|axEsQ3hi0EUJU|YAw4=pMmjjc>8kj^?_nu|7Y;W+AJiy=mWMe=<*u#@v+cRUe-K!_{mcG zYc$h9e2+Z7-#Gq17QlEznX&9-Q?sSD(2nd~z;3->Gg=+~Aw4~huX!$oZbNsCQQiMh zQ9|f=)T*E7$2}vck~FiUD6yu?vK8X?g@1FVVQm3-K;KMAv#ad&-2tFdsA&m@(vw5W z1}62RP+Py+lYQ^n*c2xIKGU2`th#duLQjBWtR4~@+6QxrBBoC&;yLyn4#qe<^H5=9 z4&!WPhnsA)2Q7M_{RowcQG`R=OzGEOyEYO|be2;B$vHI(Xt+gje|?s+cA;?yeDS#e zfB%a0*_C|sbLhg*ntYq{j08d+WLd-prmX5$}7+{(*z{?MLjFtnTm_|wZ4ZQ21Hj0z;vJlXWZq{WF$IB8!sEDEn zD?~XC@QV(IHyW3KpsV05>;ng_h8zLG@IM!?%4c&L)+u1IA=>3cFqc4lDuYrF(#4Z* za(>Tx2@NX>P%QcBv==lG`qq8J7AG-O`-Ll?{`xr%z=a{Rp1aWrBl_t@F(NwjFcOAA z(>4$K=chwJ!ORj}D9GlO_hvmjj|`9D75c@05ksFHbVnV#*o9Yf(93QCDm#ekA6UybH&xM;*bR@uKePuVb+emizrmxIq&1C8 zBsG6Ww`giIuDesBe;F-;JHxXOA72x2aeMawzRZJ?(kZJ%|Fg~)oK}%VDxkkqQcr~= zTYeROwkPf0|RhE6nP%y9Udm>6 zeK?L>Y3uZe9(S<)aaOB#*~nZc&J}w~+#t<(_`|h{fFl})Gz{XTc`7d0O?O3tdHjh4 zrAk-FJ9lv9!UPLM*6}r< zeP|t9O4Ax{`a&qRbpboJ*Tt-mA%o03;@uZL;4A*XJsZMVhNm%gF|x`wE}~@RuRYJ* z+)-GvLcoAD$S8L5q`KH2erzY=nkM+C;jPy4t3}Wg7_$tn+n-NC-NMwDl;1b4%mrJz z*MhpocNm+pr}b;O&?oUti0a~0!bKAh6+ysrQUNM|Y3Q^qO)($(l-Hg5Q9=c>3pFJ= z-cGue$rH+7zjk4Ie*Cg)VXGY+_r99+0;8kZ+J2k<4^j@)-l!+$*f|T4=f5PQw3OTES3IXWCQfORD@c3E6(5z-sF$RQc{!M+v8 zXQqwz1OHw)UsGG;_&NN!AtC#zBYM|WzInqk9_&WiIs);&z8xY(1ujcRgyX%jKQ&Z| zxe~&$^KswbTJk2l-2GRyo{4y*yQ3y|V3`NH$b&_nyyv&9PMAYc4SB^S^@2xnc($w| zGJ)j?S$tHLmU7|H3dN%n)Vs^kmM*39-vRFMN1G35izL33X>)JEtk^48eiR&tq zOVSOyU*b%D>j!dC@WpsWzj1rL-+WVSp1J>0zA! zmcvL~!l4mIH~=$#g#Xn0e1oM&JywT{(?-Qqox<@)%A(-6n^d2CVc;~KDKw)Kp2ml5 zZZUB*&%F_l6vO>W9*QKu%P2RT+V4M;*1!miGvD!#B^#I~@+wPWN9^wMi~sSI@4~uk z1-(&=mW^~)OIMK2nlEgQ@&L|NA)}67G0Q98iWCuRQTpy~*scVkJP6bLCuO$Myq)2a zNQW=wUY^Q_pt&?ZTg?gcSa>38!goeL!7o!8ZPGm2moe2xBHm1#gRnNLJ0gB41I*r4 zvh}OyHO8$nxkx(&Q<5ne3y<4posGLVXUoh}MW6I4_a)ij_C%Y{f|vPVa{(01MzA>` z!Rf;UZf;1he+nM%!u_G72lwjc#+Dg9cX@JSi={5mnE;XI9 zd6D5eK+IDw(%kpi3xJkFK$NF=wPls2dca=3cb=Q*Vm*&L@h`WFs)o-Yz?P`6WR)8g&|jPoC9=@A7D`*j&HE&IOIb1 z*o@D_=;gh-NAh$QW@3qFsu%;GG8Q1(#xkw{K;dHQ-)FA8GJoR{TWEWkJ}I&FORYLU zoVReqnov`ct`EISv-nnwZjM1?WQbkWd#opmYo3UJMC?s8>Ys|z^cl(2vFAHBrg4~c zo($=n(ZtCttiW+hJS8QWK>F!v&Ocw7WH>*@nk++ALH~U?aVd^XCmWfYQMf+*xahC%}Pr+?z;=6}MT@H^tx)rYt9}6KG8O6k;0Ijzqx;*`Cw>+ph!S>6lUjfZ zge}Ft0$YShn{J70l!&*N!OQ?F3u{gIB}vh#co?EW?69w1%8z`ccyULeRk;mRy2{X{ zlPE3E?+S{*8fPv><;-W&r=9>4u`3fOPJayVuzm*gDNlr*|Gwy_7I=Xve2@!|%={rP#oCFU&V7Y(hyXS@6A=k9?f(^|Qn@+MK^CRyF zEbxt3-Z?qZO*8S*-ZwOTj(Le~>?DFEGCK5xOpHOtP?{SpvcHEt3A+j6kbVo+BjZ56 zyN{QN${2c(-e1-sxHY$)e%MVe722+tffmU8=w|KcD`{pOxY%xGTy!KI70I3J#P5y} zdG{Bi*W1G}APVZV=%JQ9ZVXD}k%DTSq=;61l^2wJ?<<|wAew~r{)fnL)ZCK`|ARMv zV>&|ng$S<{Y8aCkDb_Ofi%3}?(x3+~njie)IT<3K2wle+b~iIPODtDHzcN_xYt2&Z z@=8pA*|BV98F4?>yk2DAb1wf5b>lo{C&RoICdKF}m4;N8%D?!?dHzY&_{kzDXhD=# z8eDm^dSa(jptS1-xZJ0;ZE=J;`m=f?N_cDcb5^ z73eW?KE%5~GCnr8npP{6A(jO^O)L*m&`qiuMca?-PeVt&C~ul`c8HO3VZf7c{aocl z-#mdV9{tO7bi5SRh3G+`CONbicZ~l~CQS{ ziJjVF-XdsdFS`nuw}Ptsz-;3IpBldCDM_JVsRB$C(nPhc6)UFJSOrL&5N95Uq#g!28rT*^0BO*G8#{c(Z_rzYDU-(<{$m& zBpXc9&S&jlPUD9^*4bMC{peOKJw9N7*6zV&U{3ETavwz`kM^CaH$C$3mV zf40sn(4FJvs3XN^3PFcEk}^GhS6Po@8S43cC_{wL))p6Z0SS`?nl#{r>l(< zs?5cmzDt>o*zqSCIvoJP-S*Jdn#((HFj{xcUzPbl3b*a#=!k#mmYvUl>BrW|v!8T- zRn(0Je`drw7Lbr7v8}?YMkBE`Ry~+k-o2_R2{m7@I4FK|%FZmNkPk(_72(mM)VeSH z5S#m+xxPuY4)i-V7?>pTl04~^IQPy5ARd@hT1}vzmSl#MCKk7Z=5;2IfU1Lto5DUT zTGU-Ly{6iDExfujAit44c^3D?E7OiYN36CBpjOB$GLG5#nyre?FvXCIXl3V_I!+9_ z<7rHQ_Nftap~HNWo%r?$fEi)%vZ7o4ABsnT-xxhjz7{zcnWN102aO#>oLR~7jeHXp zF?9wDGHKtG=U){{{Sk^SZLQt~6R{Do=&n!_E|A*a5hpn2Qc0bHyQ74{b<`eM^7pAa zdP$_y9IP+xj$ZaEzZ0B>O^C7T>GW!V!m>{Ya0i(-d#JwWK6mM@us=KOD+o@m7`FOe z{|SatCt8_WruD&2JtHd4aoU`s|D8Le=+ZqdHlM3lP`6#+>T$dzy_x^ouG*6gu_W3w z3QxH*M_SO2!>()XqAM}&Fm6`yh^YySn#*eKXer;?@z!(*(fYip-KKY!H@w{U!vu3X z^y=+V5+xXs4C;v;{^UJCw9y7?gtO4jrqQp2r0N&K0hw4b>Wa0Q-; zQ9}+jcQ=#+82&2Ks@uS}Navwwk8Z(m15?FmwXK2-zs!VyWi{*oSo*<2N|u z9q65-(7Zh_isdciV}_rxqA89*;18Z)11=uzR2wexB9)v%LqWr16;^Em2O%3h3$hOf z50(R>?8wRyRl(~V|JtTLzZ`4&%>m}YC=Fpc^7Qz@0*AFfLprRG{|~8Gl_(aCOTwZT_|I5nXhouN837(D6OPoC?xW z)@ilhC?&K}%eg)`psweZsG`R^Wf+9>wU!fm|0wVrqmMo!P#@ve**Mv?!y~%3=v7`e zq&MBKAFj_b^v3vX{j+ikwCq0QfocEe>6&)x)!0AOg6^|yOCD7!aoI%UN}$LZag+7Y366+i#jJM|8U)O6#sqT7 ztQ2y&ILy?!LaK=_OzAH@}a%DHZ&j2{7k7_9kz5+UY{FbhTnffKk25C%9)yJVUa_6-f#*rMwO@Y>{-_v>>R5E< zD#ecu@GjlLzx&Fz|FLtcjQ#*AXZraE#%$o;2f~%hkZ2{QhOyE1pl+(p^`TcG0xi1j zM}IM3Qq{@s&F%8vs+ONNHSTO`0+WuS(c98FIW1?-^6VsPeLv`Lusva;cfAAm+n>fw zYT~}Z_U>^{xQ+#mX0FPPe)MOq1)wP z{=44*+hMqK*=(#X0YlJ|{T^>e^P)s1f}IeDF)7B!3MQq$eC>1X-(};o8w7rx=Lht~ z@m1Y36w`|Cz?_#u7>6vw@7Wc~p75|T_ojYw-lRr4%$&qlfGi`VS{lexI}TrdS^3^d zi0JrnHESvbcVbt#SR#lo76*VauO7_=TZC$qm`OVYMiyF-CJR-|sZaT?g-=6On)b2y zJiMIj1_lB@3g)7?2X6^ZmRDk$q2IQ4O_mI!uK@HUx|-+T2Qxih$Q=u>D~lV9Eb5&; z^x+k-)U)rMnAs@xy1rYoBO=5!0_F#zj-1j>89(GTF89n_S&7YMU9ES<3qe$ycoIb3c}i>!<`Cgu zYvZTO*x`_J+Ct3UEhx@g(z zsQX1hq$JO+2ZV8NB!_w^g{B>1#_K1N)(ISmM7Ef2afm8TuwuQFZ3YF!F2d$Ns2<}6 zqXQ-?`QDT`qz3snz>a1+VUTl$8F2?(M#>~-4C%CAd>}R=gTB->ZM(XVpXFHlvpQbQ(WbS%>2Ego^dL`H{+5lfkkhqq3 zkg_)r+!jjLSJ%*S#L@Eof^BM6Y)fW}0KwZPtYKHP@M2eYP#V-jA!H?u#5-v< zEW2tQ<5t|;DoPDeU?<076kXH(3_{yii7)P`^?`2jcdE=F)S+~a8a<&?X%J1B0uSMl zkwVga$~#SW!BaHnh&dQc)M83uB{r5P*W6KSE1%#aQji1K{lZ=b?1i8{0p)rPZGXuf zt=xWH@|2{tunFIroGJ8E9pO4uXhW=$nuIT=NcN=6S%Jgol>$wt07 zz1;G{fEon}kERwRy4FH8agAriFvdCJo}Luiv-(&nN6%7As_V0!`JF{!zHNMtQ6&#< zCqMItA}l0M`Td`Iym_?#I5wGm-l>dv4-d#^!phvT}FQ2LAh;6IfaYH z-j;Vkn$J+)URMh|dk|!)_IT;$bI7PdKPFwlOf^WqM7~twl&C)l$K`V4jOLZX(4U5@ z&Jd}7&I$B)UUL#JJr3U(I=ql5qNEZ*r-|VjQ!J4i_lk7UD6Q1QD$QpNs!`nf9!udo z>j#Cu`erqQ!FCZe_|P9wgI2txPdV+Ek0})+8c7b&XR?Xeke6$T_5@Cu=k5TKV*lsg zeou@qj$R3Wgg{mq@5*XUj}M=3I5CZ_#$SH{!BvbNx#8lp&BF&xiga-^29(td6~Ps8 zzLK(Z?>F?9zU_WbI$4Q_CST9tloJwIubvgjaEGJUKzmNTLR$EO@kO>&viIB6jFdQ2 ziRFi!z{xwjUVdoDyq*d$-1F`i=1?%@p93$-o(vKHXC?CE{IN>ig$v&}xJPuPRU04^ zn8KoQhB_8j(;(~`vzVZ_BX5Jk*AggLMe&pV^{aCjtiv&NE|V*kRr_QvCIX&874i@u zQF#HxLW<%D@nF~sWbz-bjO%A_=FKBbOZPI&%ly5cbGVb}xL?qTEz6AK zl$Q4L4!A_=)OC2E^9oM4`Dozfq?b<2+PdkyVEK&7u~44yN!$B}$lr|Tk&hb7!l5&e z+(F|mwg=%<8By!-QBKdG7?8eWgv+b+NEDdKQ^!em@#V`pAAIUj5gOzQjlj!~e!02F zV^_yhbhl@2P?X8S*Y+C$kWx$X^~mp64Ih`xv3*{)4{k}9WXRPHc`kZTnVX%l?~rT- z%x<21o@Kv|=xAO##-|SRYf~nvbl9E8xzuP0tD%o6(|Z4L=@F0tfjzkKyfms?C+>F{ zo9<%hh&WOYcM%^Kt6eEWKh!|X0RNodcZ2hM4IE6{X*9|ibn|H^k7uuUrHJBA_5ByU z3@oxHYx_5nMF@*edgyI0(Xnvz@9@ZKnY>IR!s@^=Q}m@&jqYA!asm%52=91VcTx8f zSH-Qd$VGGSQm!IogqpSeUWCw`6hdBXZl3R(4-1DmdL0KR)Haa9sxgknPCKEHJB}J% z7pQSQy89-;)^UlvX$3h;H<)K!3hsU%9q$M${&|I)K?&I!|D3q--(kK7B;5HuBKqK? z4dlBKA102=Yg+Qrx--~oB}HwW^e+|R-4rW!W7$1>(J#STHY>FYjakz376^SNCb0ih zrb$mnq?wx|uZTFRw8$|`Y=qQ|d9~tfPEYWK+%VUC04RmmtYt;DEkUJ)ORT@Uz2Nb@ z%}E>+a`5-t*-wADEtpk|)$COyCOG&xYfWH_7SI@=kYy~q7~Uj4UM$jNBJ5U_66VwU z3zE-i%lS;XnuEQMS1F;Uhr^Q~s!0+wuW(9mHruWDmF@Q*I{JdhC%HftFJ#b6-Mn0m-scpVhMZ@IRxG?-dSy$8fA-Bk+2%e--m2gF&$3iN zrV8tHP%^rb-tMDSlCmI^@2ncLoqOz&x4$>Ves-7}kA0&!)U5I8#Yub9UDKZ}vFVX@ z_D(Zj-W?87%g&56AlUTbnK@dyp)Rg;sRoD~^5|&|}~V z=DK)JE3s(;E>$#ZtX&UF-*fQ~g9~yK&+Yb+D(8d?#n)Z>z_jkiS}9r|`O=Z+B1RXO zl(PJYGMyQv&1=1Icj0oi2jotrs6Tod_%9{&4er8IwAp@sw7D~FnNb{yHa9j^zWzvB zY)mtUoDh^MoO)1q@Jxtu2d6cq1Y}9ZNR9U8mEKdqc*R$xrrst-hZ6sH+kc5FyL4sI zlBKlG8C(?1>MSr2_cJ@=^G==}2Z7C7?3>hBIOlaBwHeJrer`*&SM8`Q` ztAlEUBz(3o6j7)okGrJ9B+^OdVFf!KO>b+<;$q$aFKZ5`})r1cYz4s&i_v zDYDGl0h@>@iqiiA_DIblF=e2MC9@ojc-MzIkj2sXs!v>EW#?sf4qgnJJmb%V6TVff z;u%!>Zf7;Wu2)fX4vijOjp+1uVZ%#Y|2A-}s5?h>4gxY$dIg*|P!S!EYp)ziIY)px zEgVg`#_hI3+m_M2!wZuy~K&Tas*7u~4@l{4CcF z#(-r!E6sh~VW)Y=BDmL|^)#5_Bq&?_Hv9ul^lA|HU`jOi0giK&===Qea8chcj%apl zTRn$swAXZU18Y~ph2)!gb&M)njgDiFZ5+O{^m43H!EoMXX5tzQ4j~Mt^O8cCrkLv< z2g(GO6JD-={Z~|5AhloGu!OnP)Rvo~k;v|9gl{N@xWvD$5jXo5ouy()^vLLeSXc{s z$%gt_Q*j$kP3SuZ*ncY?RTU1s@c%zLT?d{O!8E86eTn0D??Rm ziyLLAQsN?Z>V0AvbSd|HFoi*Tpmp52GzY;SSJ+qL-BZzZ-GaXS7&FWp^zjizxe^x( zXv6-M^W_75oN{Z+5lCx<1k37IysHXKj?e+nwAnZKoAhr>oI5K>;ixbEG0T|WnwH-< zcIFZt*Jg%o87p_J91sHExQ#KB(>+8ys=^fXYtD*JZBzWHF!n^#0lnZDY-*v_R-L<> z7cle(aS@Wey^g#uvK#y=s}x+;XUgpj?+^xA%rww14UAOk&K1Sen^~&hD)9 z2ms~}EO^+kZug}}<*Ah8(tFR)Q0e{m?~WvNWvJQnIGx~bW2H^mCnd*SrLQjCBdllI z&o-PfqU3;ZK~%KNA7iZR*lu2A=l<(Udv&I6`?E@7+%-uX$a+vxHOt^2H6UK90bL zB?ufGY5Q>Qp~Bxmg>nwt3K*Lw3P433NZWtO{>4Zq!7}qj%D}-A8h1bXDGxnNc2s;_ zMVI$I}b>c6(wa`F{tQ`&_ds$YMWD%ps+6a^!pwsy70&GFEpErDL};hZa72 z{o~I|{Tg=AyH;WdqZG@@W(Hxf)}ChEcmPF4YXc(e$?gnU)s*$c!*FYe#p`6cwZuWL`N3B;zV; z?}erU-@GUsjxc={c^gg&w09Bs@!acqQ`d)9zR+}A&LaL=5hi`(D6H~`ZKG~GZ3RI} z;MtIRoR^tA%ft&7qL%rEUk9hRroj2z+_O*F@bGtm0vO~vUCf{xlv1q%1GLmCnh z6ahB%1hU#tv9r5Lfd*y@v>n+{nhQ}GSyrDX0W@W@-?=Jb#Y!D>rhVrl9r0iT=-0E) z1=Xfyq+)dEgSxteWsM`rBeA4Nw^TJr(NxL`Z_cV=`CLVadsf@dHh09kLu^va9?j@W zu3&DNJO$0(-fgj{_lgd_3iK>NY{Bo+XN`GEGD5!$;BNMXA|1zN_Cu>7p6i=L*%*}HBUJhml=0#gJ(pvVe0HgbA?uupF5I{-96+J?_^r))hJ0s> zFkM|1TSMoweIWUrs%4xWGn105dSieu1OGQv}rxuWA~MLMA6=GK`0{inyB4kR*p~ir~n=a_`-5A4aMLcl925 zZ|sSOD5C4N$mDz+D+VtmOOGx>Ct=C}oO2+{g=L@}kwSniMrZ#=tl+%C<5(BK`DD2j zY%b7;1AYwAjq}D9wpjk|&UUKwEFkA68saMR(s{o03D1-&Xy=ofNe?ZO{XHk!5R!z8 z4xtiH-P5i>j*iyD z#W$Y5aweRpvq#)1m;BQ)CvQsOT9NcbkCnrh5Imd#^MU|?@}h5 zi;vd!CyX)UQIuB)ZgGlsM_Qd;L4z9>*8e^xe2J81elr<1+s+`xPVLZ}Yw+RJZm^HB zjF}`c_wUPZUuC^b?0KU+K97HL?%RKv=TnRzOi{A498u~s+aq$Kvk};;_*x(5P5JoA zqw@aR;4z9gzSwP*t`sOIN$>z(#=J!?GR+?}uE|Oiq9&;%f|2zZuSy?4erYKm%=kao zX@tv<2u^ye7z#OEzo)yMawBtX(PAkZz`N@jx{j5=Ew}0#jFMP$qBoA=u=-NA+Es9_ zTaw|Y$Z8PAguzBZ5j!DAVw;1i3bhpmD?@4KuW*_n!Gl+U#+bZ!QesUZ(CyA6-0(Bi zjLP7T59A0UJ{k)L$Aivx=hD|Aei@*FfvT~G-xkcs=SSiad=JBrSCq4qkI%Rtdk;6i zi#8%YF8R<$jKc<`+FO2rQ|Xo*%VGtG(M@4j5ykuunv1y`<}&)80Xv{l|9+c8v2uxjr*5C~fm8AUhm5YF4l0om(^=ow&vkP6Q1i%H}b9x}vYe zES?GfeW=@6|KM?T;ESu8cV|JBb6SgeN-%hC1hBTh`z+OI_mX8~ad46=B|Q^$RDz19 znO6rviKzy;ok|?1s*|;bz`)ETLZZ_S6!rcuN+4$}B?yH1>j*x-9$7qQeEow@PiI0y zSeBfz(;gaFH4FJtLpu-y@cFI!tta{359*R%>1Uni&5dQ?Vp-|}JCz%x#Khl~*|Fmv z=}2s={)bjz-@os)-jj_xdP4YKD<+>aDy0IWyURK{VURjzJ!n!6mYg~Lb&~o z*=jMzbFiZ$0%Oz-;_S;gZIC$O)__Ka7c-4`C4MZ_x5dToQv*@>2||d8I25eqOUsLo z`9Y7~@ogrgV8cBJh=$&)xF3^EugKm%r8$3XpE;xwtNf@qdM6D9Z-sJcP%J6vNE8%3 zx!1#~WvO-0;dB>#TSqE($a!eknTY00{07tR=iG3)!u+7XW^=$*jwtbIZRMa}8%0L# ztajGrZg5-%CK8`18PYuWwDwP6X#lRLK|EmNx2MnoeKJi2Gp&zIBo@)_*H+p=c6nrx zUm@fvP>7XDa=f|Mjgj~X^$xw%*8%;S-KuXj*GwrvR~1O6sG zKei}!M4htafyuNd@~<>wp5Z8Bv?n^o7=hkV6KC}OeybWi{O;(ybpUxkuwDAB0ms)} z0-BQCKnu+Fdll0cn~&;srkIx=-`5-e{y8q>;Wk1PEySc3+v1`71Ch%;MB6e#2FAr zV2FJ$M-i1tuR8LlN!15h^C4ul3hhM@rLNXqCWVGjS|9aLqlhPjo@ayI>X-=57*t|x zt`V*z1)&>9m(W*79z5?@F5qvbmm)9uBLoF-llss;&5~|Zfd$nfP#MS3&-tI147Sy8 z|N2J|!g57MRWdh4u>A0<(LHpH0Xr{sF|S{t%pBg_3&PBA)A9jNj;mXSRGh_OjA(1? z0;kH?=t=rs@>4w1>xAC9`irus5JC;}R#P>j3L|AH=dRf5H0-lwRXBS)x#D!*5BXIU zBkKe=%``d%@w(C8IXA(nuW&2n#ZPz=-1!KhS+qPvhj=3;g?eF1)ovRx$D(p)DxT1z z{vQ7-a3QNbtQi!7WtF=d0;LIj+pJ7oq$BC1XS)P5VT@N-SFn#hxC|XlkBh|+?9tCg z5TB6SxHffhumlX^K1x5kgtb{HT5tPzvaG=5BDs`xnk*zmC^ zG$ey;5nEG$xfG~&p||=>ilpO&>;5&=v~a$8eNM?ZDQ}yx2w>16ObFKMwaEH^G@W%= z6O8xv>FyrgB{8~2DWP;2bW3-)q!I%}YSbu^lrCv-Y&0TBNskf`7>(4s=lfp2zZn3&Es`Z_@Od9)hAdk%`efQ)Oor zX>Fj7p;=H5ij8|nnst3wD&Z5}KIY!m{~-3b7KW)e&hr?C)CoNbU}6_wpN#bmZ4{1C zGsr_{1tj3;&CCbKzgZip<>U2u|S1Zn*A2kvjtBZ$mQdsTB;{&ven!!7YGY)kfT zCendxTp(ew|C- z=W&9IRp9uAbUCi%jq_1sU4~{#y`FjWF&bMeQaYknh(eDZJ&rX0RW!h#UHQc<$%4-0 zkLK4OI^wpuNJp)jUKat8XRET0M~uI7B}W&%PSVli_ECEHk+J$1>&sWn%?zl<&z1L- z>ugRrr{8D9juy4Uum8q1Tj$w=a6p;SUXji31Ik#^v@Ye7x4sDrKo_`>_`yfQiHn)S zc6De30w?r$bCk@71zWhZmwRBtNV3Nee1?zc@VB;o)9b`vJJ+M5jA55*U|XPB_iLxO z%re0~%>x&4QkRJX@PG`wb!%SOR4C{t zW(>zoIGzd>3HKF9=1`E?9kp&yYM-=y6>N(8Xz#Ck!xo~t!OnB&njbi2(<9T{vX8f~ z5vIpVx`Gxd)uHpb0XN8hXTyrdhPsQ+-`&j_tJsdkNG6~Z+1K4yvUp| z@BS3im^hSF{R0uFJP|EZc+-cl$&itzwi(Iy9dh4y)9*c0eYNdtvB`V}8rQ$;sORcW z^G#q8m#+90pzh8%xp07T{$pk-h^U}Mhs2bFikMxEQQ<&qR-v~d@H?D2jZHbXMvTM+ zg4@w>FBpdn{s~coWy#H4pq{QzR(%a~yZO6NJBbBmey?5W)h(0LhDCFj1# z&YhIihleCci0$yQRwu?ybsk(?*u4Rh=JDiZbl=n1@IfCxqSojdl}8(MAc~0DbMcY2 z@`n^v>5n9<;D_CZmx^;365ZrVAE~e?f&?`H7#d|TI?$9EOkyWwP_tW>Duw%Y2HkDD zd)fPD+BSvo5`P&J8$utQ8A;4>AsTqhevq*ii{o8WQMB{gfBSUS-1#mtDj{@!5>snr z$8PoS`s;yK$HVMvvIe_ttly!fR#$)OXbw%i-*>7&{Vay5GnH zTc1FIdB=q+QMFkY*bNg@j0`d(vg>MPSg>z^vLURGhgiEN#TeB8IzevClDoy<7WVjE z%g&z5@${@z-27M?3~MEK_Tag{4GI1CR1I50h{Ml+lseZ?Eh?0b8sl3Q&R)PP4u0JM z%_i&xy9Vo%>VZhG<>}#>+a%XYQ$GIf!c7ocO5fQ@EDv+wjW!`}~< zMfQ7W_8j4O?^AnQWM2O?w)Q2)L^)O=D$ra_VH8z^zc ztu5XSumeLD6gN%4{D~Y&tDbp@seLr@{f)-sfqF^P$QzxLciODG{Q$L9!?;we??h$T z`uM4V;6M=8Bo)ZB1m#izu2q|hd0fK*;PZsoSLC4B((uK?*)GFOpF$Tt75Jsc^VXFo zphnEdqf{rqbI`BeVzXXuEZS3cZ9-Vmo!Z|z^K>UbC;p5%%Tb0E@&x=Nj@8f31cved zXlnVRO7ezroO)a)nAp~ulFMpDnau=N|GxRXZAU9wEBpc(k(+Yx)6vkO)A_rk(C;v? zwY3T*8Ck6`H!bcR!)MtU59Ql`JDZOtmaIkS?=HT6WtKHGxZ_cN9iMd?0h6L?uQPL2 z)_L?m8}uu0d^8G>puuGyDDLA>2u^W;e3~?8+voy1M0&vvDlFo7fRa8$$Ju+zc71Wu z<;UPxu%GFGIO*d(4tZDOTYRe!^}+)-W7LA;%LbN6`y-1fk?h_W`dt8gF|%-;uH?NF zv9FH)dBnPNpGAsva6gKPt>O;{iD7FP(enwaO z;9Pp(nQWa^NUWlGL0Vz|@s)kI*V~kPXIZu|oo8=+*FZRGf1x$0^m?}g@)J2G-1d|l z*4E^;Lme`GC6|zY=%lMqvlAp*3eBBnCH9x1{AaxG*FUvo5-whp5BCqPY}0#(a~FZ* zcWhx3hUV$**_YMOE-a?^^dXf9lf+(1L3Z7|Z{fOGx9@=Z~dNZf6+$Af3QqAv5ZzYe4R8w)BA2^l(EaJ1tI+r8Ckq{5K%bAO)n z|7Gw}TJ5)M5{baN26F5@>JQ2Fo~Gp2+A_dzeAczad*yfO??#@}tc#-4XZ!$YRZwey zcFqHDiUNZ+jSJnnctTT}BPZsJadCiOpjx)j5L~x6l%FWSCh!>(G)YAEq8%e8=x*oR z6hZBE$K-2j7%g5Q(e8UYJ>QHgh=%41)$Lo#b}IJr-(tO7Q$er)+djCzNyP?tg~y6_ z$$xV<=pV7wOSq+xW*q#rbS|h(Lk+2mQBIxQzI3@ zMne|RD@kZg&ou)kQ6vWPHhotiNVvtC{6?3>xJYoB7=wg%lpOP?La{(1@B?N!-JIWi zML>hs1&}`%eblKiJ70`Lpw0RFLh=Gnuz~4;rhinMDN9fuyymy-UgrQ8@!CVz&vvxIBUFClsaOJzgkq`R z>1@JvV*+DSKQnA4*mX;E2SxF*s;O$5y_Dh~`Ix9jJQYFV<19PT$M^d|sHey%!=ZpC zjgBsmmahIn9A9@hY>H398&gkyN;X!!=&-dQo!UJsm})wvOc9fknWMIl^q$s_#Y;@r zb^io@OFH@8Sq)^HI+5h^v8>7FYthiO!Qw0k`t;e)!CFPF-ZUHiLubetf0*Wz$obz+ zMao5=YE^Fx60L~nZl8!KRT~&;#1gx$4LR!YVR#>9HBNx$H-gDGivep`M?#}NWtkg) z&*-wC zgTe2mrzU4BThS0*3#0~TUJj8$)l6_QN1832&9JdBi9-K9RVVq~slh|i%f8gZ-=inl zrMGhPc9T*FIYI)dd->R-<{{Pfa*>40ioygp-ENlPQRXM%BldYgWO&2z_$l2ZZ%tgCN#E6!!46V2346s*)DP z4gVfoFcw7boHTARivp!24J2 zP#XCvwvac_{;(;*vL|{%&+&gf{-$uem_07Tm?!b=KbJU-D2^`wuNNzSFj!ehd5RC#r0fAF8tZZcg?MX9rYiD@xz~E@ z5pgjsiIm-SGH0tQKAK#21xORVGu3(R{qtA&UVy6bh+Z_ek+hzV-jiGdpZgWonq5MY zHba##@1#x&0NQV67vPldRxyGjUToIABK|vtiIy?1fJY;akX7@;o7P$^n?GKdw>rzT z$@MGudJ4cLB$M7sn^i`VeWXJ4m{nGkCG?ZCmfgI|WJ%3NQwVDtCo3cAu>%pF_X!=j zjGRy6>E<)4LPt&d6KSc&83Z+(@Y`Nis=F?(4yrE*G z@$iO6d}DsR`O4&RY{2S=?w{V&ZDQ}-ggw1GQ#x~}D#+T!*GaD9Aos8N*u0#w;F#*c za&o6AHMfLVK)iZ&;v}ww3))Q~U$M0BV;*P7sr$t?eBB0MvqW#{F^nE4Sfxl3w0nzA zlP_PAPeJC0uB8(1IYh#R~->x8i)!OE- z==f8JJ@NNAAI545hRPB*LIXd)+v%(kPN-q_0`sg0QwFOq6E$Ds>h6ICG11kozD;c2 z3F72kvi>wtn~LIPr_~nsl8_|7P~5=9H|TCs$RCF&De_FNBWy_Cq;StoBzqK_I*}cf zhwLR**Z3JIHHRnlT&#~|WK68!f3`OmknY0)SBDiOB6X;nw;&Ff1g}cUFpX8QnE%Gf zdS%E3YP;jNVRZ?OH+J~|NS#t20!^Do3Mkh@c5;Sq0gBO(d#RuU z=-J5F6z^H25~%#3`Ne7TpIu`!HNUo43HuHzq!!-}VIBLpsNA|bSa)YJyqmNY@2BCs zXUSBhQ+H+kL96C?CGZjQm`nO4eZb~Ez+T=Ad&{H(TY|D#%#naM&rsO#Ek_P3cQ?ra zKF(a0lWsUM3l4vfKk0!x${4c2i-=A~*9}6&W{1Zx(4Crl2qafnY5Udo`fARs2S`mj>)Iel^$9=#^Q0aiDt*qG#2u|NZ2M_kAS2h* zO>u3FZR&QiR&I*hk7zu?^1v)(JTIu{z;f!g;OO}NrZ@dZU~v(uXXwlT)ac+HU42RgB(W({(~SOOH9!miIwQVk+jptp~U!_Ql^=mzK~SBRaPn zqWQ^)Q(fa)OGXjb_C2Ao#&lrXU9$JVC8V+tw?JQXwmqW(x~QtmRflpOt7)qi#5Csh z8^grwBsv>)_$v3y!==S%mzQ=MR31XPt@V^G{n*h~W1QE{M`^qW4OmJw(?*>%M+s7w zuU0lh-pYzS?|L%%JBSNhJfsVF&MC~5^yoR;IVr0KCf=u%R0Uc_ z=i0Ee{d}n2XEkHUn-1f0m~unR>2m~wj39E#{H<-hVE{x`25|-M3Eh5E zCxviK+pz4GIM+_jhXgMJXVC$XOeXdF;Zc+g6!TW*OqkS8e+IA6p0= zMD|%K57{L5l#%+&{9`e@N+3Tk0}YA165|%l4xo@h0L=)I!N_ryF)s7$o!XKWvnX|E zbd42^xFcf1ZTOx?S4E-BLJ>Sr=)~AO$<=2ar^FKNriM4$(q2$NtjK zmzS&z+q%d`IA&dZAZG^dlJV9+-jl=B^1oGn!omA*fg|?ej^amUOB4SZ0Bk|D1juFSj4+tgJG~<2m8>w6xtuCp%tVc~_>E)pdA_kI$o0`4MKJDoiBys;;K-_RBuA zepaQ2L9D7vM2e-Lkq4)2k9`{2WgTB;cKAg*Vaf!7I?jj7wo@l>LbGU#L4_E3}P*9Jx72&ErL z&liG5<){QSwpp8}Qq#FDZ{ zxQI7p3Bx%kR2@eVOa2TUE5-1F!gFYYaeQy*j)?ztX^}sZ&FVES%wb>>uOpZiZrCBPvzy&Qwvr8!$2AWs2<&?_D;hw?#Lp8 z+AMf*9H?tcwyP*?3q!R-bO$x!n_7_ghZ?s|zYo9Q#h%wu>iQA2k0(I4fP{fwgS^1q z?d@&VPwTqn;>ymD_-)!@dNE_ygwHmTI%C;S{A7Mu zbgZIL3Q5jpMo4UBQeVBe>2qIluDGKV_Q0bg>Ul&Il7S^|FzWk`T!N3vCaxc|h|q$`J7LkH zeYXZF@+$G1T}v`0{_7NzmV4S9r+a$O2J6&IS+{n<*81cStMM~2Ukh-kN=)sc^yYU&jmsc#@35r(6(33$$9N&b7(vb(T zaj~dpe&qYh((ElehX1h)Ea(IowBVr1vDcf-y6j_q4ZuchuC-#B+{v7_V1>vn5e^z3tMSsMzXgt3 zLP=6N$z=_HX-clPvwLAI$fx!W&6oa?L(5@DaWtzngIJ$~p}4ju%UfPNWK7Jj`T1S4 zb|C;$jop4IC{0=q9v|`YOvpNJdgvnN7oHOn2)+Cl3xIxIF8-9HwYmj59#dHL7)QbQ@gbe(5FNQ0-|LZ33z&!z(g@T4{raT7@h?4^FaJ}JfeSge4{7M^LYmzKw z9vwFI07Wk*wx75u9hJYp9?5LmBaL9{Sd3i} zp4ty>gl&+XWT-V@`Q*l;nBbb7o z1`Y`B<7?ZeOn&7FnX-zz?i>((AG-t9f&D<_P|nZRH+;~)46d-7_4vsnyFVdoy?JbA zegkv3NNLT#5R-^xljR$csr8&~-x8>?wjJX`GVA>^X@23f%hHZn6K%?{Hgw&0F~4|O zrPNNHlEw7W$Z#@6+*7QQ zZU#-Jp#NDz{RD>^rx1cZfM&U=Be9xPNdwx4$rSh;t8Et`p8QkIS;KA_>EO%Soe8q^ zn$n%Uos)7-P25I-KEKD{3Z`qEW@cKk=vDs7=(COYR#4C+2}?2scx+9lJjo4KRtzhl zLKLDpU`V{Mtp(DUS+y@e*wr3KH2H9{ zFWVySrXeC1`Ss*@?UszFLFXNw)~l-Jq+sS?^j4Hx#R2G@{Lm;VdVQ`#9WzcD|9XDz zwUSi_e*QUrKO0~n)WSNS6V9lZLhpk4q<0UdIx zjicOueft#SXp~g2s(KT29P;&pjCqu3;j>|TjUU)7NmQ1GBy3B3jr8=`p7y|(IHKm+ zD;b8y#tRkP#UD9H_3?LHK8V{g(?RmKqQikLrkfii)b&IB2xr8ZvCy7(6Qwd_A2eQ# z-@?9)zH4-*Sm4s2)1U%e8w`M`50jE-8>izk*eH~UdYnQdcF@XR{l{2EPYoH)C;Z01 z08u}UTrBnmBK~LNoLg;^JPiH2<-7}nJ$`-LGdPtMmesE6P z2`nx9Ea`m~Mwfh@SGe^8vp>o4JG8g2QHgCgSxhvqCQFulU+%_;d9^0aj6)8D=RU5iQP;rj!i8#1*~n($@H8c~8;qBlSLn7wm$M~3@_ zwO?_O#yWTZQrVEQKEhEzomOsiLX22nuGB&!3(#!G|L)t>OU9SO5L)cj(P%-{kh|lb z)7=$=5B_|m6UDe?FE)Xj7^%-DXX1xP(WVj zzVVQULCl!^{JmV+?6Y|4EFz6{zi|n2dyyWbV~&kz!@NyBxy{N+^KQI9RI%*uGrZ}; zooiwAZHSY_6F2EZlbYgoxKi;b+TP{n&N7is*e2D6<&+K zpUTELj&BrqX>lEL!W}z3;^N*02>s#%U3F@;?pYN))7R%$Yy`JfMm!~G2f@FvCvQ7I} z*A?CFF50sUzrrC1`l(MEr;5P8BCQY) z5e_+P7dTQ5ldJ?{oc~q48BQO=SFD%$K(V?jAWnaEi}}*+^s|mE?%8|)4X0Pu_E!Vv zt*^kWjzeAKYv6szy?urexzHzYyb#5sh8sjQQw{Zy~c(YNp@$knae->N6GkItfKO(qKFp5`ARdGJb=xj zZ@E`~@mTrgqnyba;JAu}xSR#i>o6{V|CHs-#FaxotRQ>j2MjK?i&n+v0_K0)Q{P7- zX=`Nu_{u2}cH>@GmtUVa0ESlEOvidqQ3INDzZUw?bE3U2k{lPYWcJOKcS?r3!U$ao zTd7iFvJTu1m2V$=+YBFxeKf1{hK$P-m0y+Cse0i>@^=Jso~8znc4~W1|6}a3>rPXo z=41VD&ZBh4eemG^s$)?Tlme2m>sD9|S|D5&ZS;vC{aq2udi64;6HoEU^`^fh)XJ|< z%MYOBxJe!zHao-y{ty|=>sShOWjaUTu}Mt1%~^VhLWjlhgc__;*q1x;A`mtso!i|$ zUyPv(m2R`T3CC@1M)E94bs3c_wdlMM8hh>gfbQe0S+dtM`w>*uDNQfCso47h$oGjt z9)7OlNkA_*skM`@m%#b`PxwA@m-$&#Vl2HNdP+>)Aj))@AQKy8d-xKTTK;?COiR#$ zO}lorwtdXGfGpJo-6%B3LBCpivgK7?namW&hoDQOYb_bicXgq|dY%N0DJ;gVYvqIb z?UHFQDSGfTwi?JGSxq*1)i>Cy#JU^M^q)k+qKz`+6Uhq3hVvxMQ>w9>J{`Px0p=^b z9`Tvd?+fi|)kC>V!5EM`y4C#Bs}8AS+abj8e8R!Xf&uhhyNv6S6pzjt;*_uJK9 zt9=WX9pQy>o7Y|n`VnvP5XPn=KqR`Fl8OjYB;%nv8o!5oH%;tbPv>|x+*A7#I@&R+ zTbw_Vg?Pe)$qjfHu)YV*1kXpCj zyY(=W!s21|2&PcQD6q-l`8^7Q14=Z_W;fe+(oZX!_K(5S0WO5gFv?8*RyK)8u+UI| zluL*7DT5c5-*emZR+CwULnU>gK{a;bsHM7V`Y#xN0&r}%Os*90bmgBU$Y>EzYS$svk=uU%;rvS-FPJB2>Eh*rUwOJ_`0Y=~;~j zimB1Z6ff8)X|$5tZED5(4sG(_iIM<7G3=MJa51$Swd4UxFfXxP=Y32LzJQtnaOG1~ z4ckxL(X%keJI_P2tIGAGQsy-Xfzx0l?$>%%i&US)#510qv5&avA@r&aa!wz=Gviui z?*S9+&7;jDqat2pr41`f0J zVje^mAkVvHpZHpQ#)t$_V<3Uh%Z{&E&q2172R}D|R}>_l>EP^664j;Jk{sibVO*(E zK0*`v^?6;{W;xF+yxO-$Frv{<`J{e zqoAkV7K&OmQW}5O4cJj6`{2jPlb)U4Xs~DLP&)gpiqz<%v&P&r>DBn>l(9&X&TiR# za72uvBZv=0owy>R-b^oSI_*2*W4ux_ZHy_4aBqQ`tnz$t z2%~E_G#WuW8Sg~%V7(EJy)1=s6ZW`5yu>6&!ZFUyHw~V~k|geqr6a%TSQjJDv@Li> zk?e@mCyqo+21^!IuuQw8QjyD|`TQjQ9IjZ%2Q;g>P*G5#VpxW;t6}RoQ<@+c+fG== z(Q+)fjsbs^Sg^ATD`_-3wRA`x3FdDGmHXK0mCG1qSNtp{(5!k&>4H~ArEg}Cen-YH zk)DXSrzss|RyVq4;fl4%aOOM2ZKar#6~;;M599ojiDfV^XV%SUO|YU1%Z&fAQjp$G zGeM2Hk}?2om%Dx>pfKHV5kn$H#&$o2=;^;R8g~ycW>(J}HjXz0^V6d5^qBbg*pZkC zrx70{AulZ*4QQ;9pZg$+Kjo_F7pgn>Yev>X65DW!%?)(sV~C%=3o-L4seH2ig4!@o zLQ6; zQmb#++Mt)+okU5cUqnz|0AR{4WIu{28Y#}2zKfVN6g1o@W-hb9tVT!HW{e_tONa~< zH>{jXicgk`e|_k!nurfWLi}1_Yl~uufljun&qPB76P{117LUcSLgvq~_Br8((TeZEP&pG*MC{jO|{thqXwMx;4z6yHyeH)q zW#AB^QnC=%mzd*yc!oLLst=9$BPmLXZw9SJPp&)P62=I>#6*zPk+2%`>(n#_*T4Uv z_nT5#H_4hS*iHy9&qpjQC2>2(jnE@FO*NLDoNoJORqar@=Tq7LWc)~c)NPD5?i53~ zK)&6|%V%=vvL;@%tK=tybyQ#97^DloDMx@fRa5_{d|3c{?oLZ zW6W3ubXP#ncVMBnov>?*CTjWmnFxUAT^2IdaDGHxv`#3zz2>f`8l#?j zt$t48LZzi?R09~O~kUswK`~T*=f{ENw#K+$_flnqAl3VD1b~%NTEKn;4G99WOPBMih z`5hi5LA+A+IqT@%&o?LkQvgCSN{Y0iJ_NF*!#)mD!{Gr z^B%t(3ju(3tad6Dcna@>2a4PUB690n7QdKEDZl7wTQ6=jJeG-2)KY-gZ!Ovm6m0cz z$wGpdbtg7{)Ra3*;h9E0R}FhZw9Eu}44(H5bF7~7;Iv22`=h%J!4wP+xaUWdEb5p< zKk>b6n+PrX9~LLFNzT$`i-;*l=8Murfab(Z zL5g!5^TeMU$*bcx|IPQW25v$+NPOY}Z>W}%dBS1}ip72={!h;e8b1@D`wSY3@;gnH zKnY3PD*^c?X|wG<1Fly_)vSJ`AUj|_vG!D7W#vgaf$}IDgZ)^ITCi1=6VG>SvV6iD zm_5p`8QhKAuxd&aHnQdi^+>|%e+@STcx<_FmFfbPc>RiOCZ1J~ZwGrQ_ggmMxv1ai zr1DvqXdW|r>SD)&GZITo1{fAaWyFf2Lmn}|M2_-aJ%IdijjpE{Wq z$bkr>E{o>e9?vpCT5d_lpMOuMIiUrsLwZD+UgETepy!i`&{lUU<$9|w9y;-Q#OE^x z`#iz~m@}kFmR2T_G<*%(N%5qf1XG=kXCT|hJ9r-o$g%rAU0Aha-RtJsygvQ*md5nQ z1(+z4k2r$fwilw#%%xH&PY|K|ql9sS*NPD%yotfioFL4XSvO=7E$AliV#hsr*1#+m zCDR;W;hh({O8P-3sVz3f@8`aFe%9 z98|A9L#J5%J1mLbe*?t0_z7S>H*w`c?|;PS#2>hqG7W3_Q=WQR#&nZ-vF2_lnve*O zGeJl+e~_zFRhdv{rm_Jj51@KDPnp)?rZo8_On(!kRVU?6iLMfbTKJz~x<4PLq!Z{x zh>h+A9TPO+c{uuGu0C6e@noOQlFAQW0;N6K{E+SR`{mA$H=YJB)NxrDj+w_*x`F?; zLQ|SU$NdI7me;mU`Nd}E=v6$UBR(%&Xw|oaue6GMRq<~Xy)5YFOQE!VTW<%b>0EaM zHBMmk+0ADTl2{QfB(Yz=67Nvp9_)vZ;Dlc}&kI2nXm-94`$>l&rr&(}<7dkx)A2l& z7A34X33)M!kB&DYrFN^vdkz!RWK5B4PwGXjntexWv#~bKhcWdz^8wTcrAnY4Q$P8>fOvQQ!CYkVw%T2X(#{T~aUW>UYkIrUqeK_6Wp@&}Le zgjJTzpR*qjIy7C~3bX_HOt?+rWF>l~VaF&7wtKLXQ%>-H&AhprMZKS1U!XYze}waL zbRqX#ZgOE7cd8&EdfA}SH&$y@+tgVAO+hUZ8Qk5_U4GdW7*83LH^^LnPHvpWGicGq z@&w~|C>hLtu8 z8gFGcdb=EnK&TZ=bk54-8@IKzjzV-VI4=DPrk7s%yH+17=y~^yI_Q8)N3OaQqp|Lj ztx7p=Lr6Jb^7h1{(l{q!ypns|u!g{|UoiCIK;UUn#`)K>l-Exmnt7mQthy}+G0YlF zoKL2YinU9Mjx&8MG(N=Ev8G71?4*Qqn{AyaZB|ZgYM-{W$e-44{kv;*+rG5YtAVk7 zwYI%L`;uHk)%X{A!)IdaGPo&}cZ(*HHhfHCh&{0w=w3ET>0w{vz8S_6g5a_4oP@F* zBd1_GIxlONs;euLi!jacyJY4(U%7hGcTucWTHCTgV~j!NrERKLOyf26jbnV9*8!wU zZ#R#sb{HmL{pcC@m1C`p53-ZCt?DGG-ScPnuus|gilaqM!+e|NiHB&fU#WaiE&~Jl zySPw`7f%kY(f;WBq@{__G(ZsMU%d8$+86UW<7)p?Wa~sCal^m$!j*hW5r764lq>ee z+<*EwS`Jd^L;J^i7dPEM?E_*xX~Vzt!W~oY_D51o3OW|o-__SNrlG$Ielshz$GmRp zW$`eyefhmgsR)(yEB`{?>#lsjiwlale%X#1LM@X(6aUcO&}q3k~K zKPL+KAP5OAS0g$37d?RX5zZc}-iORf?eXD}*VZ)l<*i?ZNHqLfKMIfvybWemcyGBv zaF-4^#)$MhS+tKGB~SS(ILoH$!Fmt@RZ+kZ_nu#-aD*u z%kxdaX8%)_Q#-%WU84=3s5cmDD=SOz2FrJGO(?efv;o(?Yx|~t zW7*IRJ%Ek*#WTOj+Z6}PP<|>;ELHjNP{#+nqw z+H#|V*P1LFzlZP`+QOM_vSC8atmzLQZ|Uil%v0HMvT?n$lT}}(Yfz93JzXjQtOTbb zhx5o|bjVqw0Wa1}-3f3qJ&5 zns|v||JK7FFudb0VM`K<`uoI?gh2u;0@UySE|cE6JkzUC3pY+;x;ZGAsf0bO4REEs z+`1*k%1l0RUYP&VAG9eL@_N{W^2!TAkp{6x6VU~N)2kEtFAX;mn^MJ#I5PSr&OVA8 z9@$N^sBpGvtCTl&^ke-*b;CA8h_7Sj-^{8x9dqO8K)|_Q#M!G)|7e=$xa;th`X4oZhOIlK%2+ja8s>ydS{P;>6+|lCLZhi-Ta1QKtuD;B<-+9q=Oy3|pAlUQ~QN{je`ApW+TYO1Hl~gV$tn%PQeF+p4UPe5-=weAIkSoBl861)I zJn?mRI0v7BGW=Tdrip4*yX8iGEv4;_g`8RH8za%rG^n*fG7G6s=@u1BC7SEQ+5^WH z?ym<1=B5$5F?aD|?=}5b#j8!+<>=JmRBY_uD(r;@n+cHqgZFQOzbZu0N8c+>!IOin zq>(%WV_&~^OXg~fwvxM2Zo1;X(e5t9*gwj=j!q6<7-+s}I1Z@74L)KbK)Mtyn@Vru zmti*i2d$JQjZsPky8=acAai#MVBuiaN&4mpM@7Yddoo`>C(Jh;xVewLES$;v@bZrz zh#g6^zQL2`v+|OTv)*%7K5>3-e!<+v+4+dwrgt$;PHjW0lDwM-^K8UN0NPHpN)6By z-W>Xa(FfhDbTc453Bg+U!*x)HB+mFcUFr6tJvv!Sv0fKmyg;!bVq+VT!je0F7Q&;Z z+UHCBLjdV{d^77$bBF#xZ&^K6yVr{I2*o{_)bvlK2hF72Y?ZES(NV=A;&lH~-s0LM zdJcxa)dYQ5{sU&I%P%V8cj#DqxCRvNI-D&STp~LY1iwcq4p-TO=}8W-@CMnF^@Cn zdi-;h{&zM%e!aDjqFkCbOf8uwNL}o=I}nKdoht3h6i|_;k6He2_r5Y~JW+qnwDV^3_L@`l$p3x!>B_A5yj?La#QEdgnD=icW&Ka0Um`9kEr7}3a)L08J zV|A87M!~Ekps0|@Jx=Jz+h9*_g8xW|agmak1T8j0^`b%n21MzL=zIN4Lcq z=#w1R#M4|rI%vT;u#mV&`|b7jxcBhqL?rQ_P}4R=GFH&Z;;V;{ zJT-SjTr}7NxED z)clj3;gEFJ0q-!$^-btU3NosMuK+oLJqX9qfv^f8VN^Xv;a}nkY7|68lxC4DNuzxJ zFVlC|kAz<0m1J_P%0`ZuUqm3HQy{1DoJNX^mXz1A5x$2q({awPgV)HwS|K}Fe&d6F zcMR?#(|G8k0z%W=$c6!1>JL4{Qy2^txhB=c&%&^Kq~aq^Wzn3+mofoc%UJoW-L%Bu zS#UYZ$&_<&3dj5GY3OYU8kb=ZH6d}6{x4sops{_MKa5vmO8OU?5~?oswBifyiJjN( z#zdLLI6lEYgas2_SHbjs1)$6>q=El+nr|!Hn13bxt~wjf5_H47tL|uMih0c zSImWO|5J2v$?{R9^j#4PWsCNy_xJPB##EnvNu4Nx-*Gs{K8n1WaN_f|l+s!ASL(SB zV>3o^&u5LCBy*D+5lmcorzd~I=h_~FGl4-SwJX)L(e{}^@;Cnz{zc{>4B>U41#>mw zeO=9vDa!@QC<$&9CU3Mtr7c9e>B_i@c01ngom={6Ce+nhiGP$Q_y1@w zD~uyVo~f^3%YQezOMx9@q8BB0?I+Zs?zO9>GyjjLw~T7D>$*mRyB81cZp8z|Tims{ zyGwAl5}*`!EA9n~I|N!>iWLv;lp;mH+|L>B`JIeC$d$0yT2t0cvl4f2T=2R9FA>2h zT5(3|F9u%hQt@zEFJ@`Iv>93mS1N30U_YQn_@sxwH`^~y7|EYnawljv84am8Y5a<2 zrbBXvRHVMPZ|ZyU-Id+WE_}Z0j--Z1>QU~^=+RU+b#0fWpTMsT+*pDgx z5<*#yGk;h7H%cb_`skfA-85y6Qmk;|W_A>)Ex>oB`MdJfW=H)S+ms|Z*F@ODXbo=E z@1j@asY$7;Hyzj{tvC;#2l|klj-8y>;d1BpC~KcYAm9Co zkKpY}m1O=^l3=d4ujGz8K@B=(OJVbyLQ!IQX915Lz6t0x$_xy;)O=-}Wo++YaZr_a znJ90YjQFT5v7~}_Z)y^0`Weo`>MygfJoLCaEhL%-p}}}gGJmr$??~vmEuOeP6%Rjh ziHxnEjF7^cHkThxi=eMRg9;M+qc_@LbWoE?!?bz6>a&W}ez;8EVSaRsL)OZT9dFcV zQQ(SpF0z;i7_LyH@^9d4^Sf6AK ziO0&h8E~{N2?RdCCr9N#Zax@4gaconC`#3Ei;es@fjR_vIY0g?UhuBwEv2R{`OkE? zCzPKC`NWN-r8$AGGyDL#YjW1P1Y7eQhKLhyxSu5-CWpgjkQhxDPy34_tb!IjTm>27 z?+4!R28XNCVRSwW*7UGMEwr+$%>x`GKHTy72v}H@a0*%;w!pTv9C!O_`CeoD{Rka< zxQymN)^NKAqvF@$v+wz|kmI+ocA4A@S}A}yAHUk}8@ZiqvTu5bX~Xp2O70Kny}qh` z6tjP zE?Q@Sf}hnyBo`|G8G^A8zI);ngJ+QXKFgS;t6qQD&gz0wk1uUn>**D%@;b`KhY(?U z?#~9cN&cAU=LH&-l0|h;6h&3kSY$LTl;P+Il|6?~b3n;+(I-d2uZA7cOvHO@tT2+u zJ=B zm~re1S|i`6t0l6>HGrI{H1@hnNkV%O_UsW{SbPu({%$3L;H9O)z&hk5I1tCmG;4oJ zYCF;LijE@awH)|e0*Kg)+F!v^)m=<<5&%$;1uUAUl8u20dqB{-u^DfR2_sAzD4gMK7;9=Fp;LLLRaZG@}4 zJbI*0ejWI(4)Q(alhnKA%5T`+45-)LxwMdwxnTvo*Ay}g>BB&;f;rdHLFp8&GzKM! zH`!TS@1ZCFzYaOn(r;T2x`g}d&1qq6vf(}{5eTCnW)|^Fay5`Y?O2LaX1$yG$lC%> zpyIP9XxVlU8Xeydkt#syr~3rn=v?`zBX0*G*`*F3|sohGv|1{{YJ$IfucqAFzV&yxxi1n#bRvhnc#5jhhT=COl^61&4 z{cFj}pzoT%lGgNvc-|FDT&_(}d0jM~I%$g1t4}8RBV#Y2f3N$}&Fz|8U+7sddqrFu z*&3@y9XTof!(pZ+>w!l+HMo5`k&Jj zEBIPfKf7hG67y+lu-wH1V_3O4U4eYR45aMuvnwi!;H^|Sea_hIwx{aFP`oPIkBSB|Gk~3K$d841??X9UL~i1TCiTDP$0giQvnGWVuK1f|5E={v|SwB3$+I zTXqc-xwwG%w9Y$T$Q-%?*CL-cJ-Hx0owTXH1>`tcW;+ASd)3XH zucn8ezisVl6X#GKh`n=#xd>3MOw8rHv0`kK8zNAF$DlU`f&)l@5kJfA0c}S;kJsQ-#?&Pvn>imt5j0Kc2 zamHayyg#m3VpJ5CBUf3hD#$nWGu&$XJa#4;&X=nV*YnpHVbA@4?)xai-S!jOL&Yw{ z8ysc^L2EK$I|Vo(3#dspwi%@}RS(=D66Vy?{v+Or*wba25)^6wN5i`KQgWgx0LD6e zT}cK`Shh(rIpXYsdIfz-lsE^x2wQAC>YrqKO}pQz7{}fCZ)uSia!g(7Tdlu0=#bWw z7tQ76j@#n0;=7|hGkDKKTgQvq?=oo+dCz|-#qXET?p53*XHr@(1G2unJ8?WMg=5?E zg2zH9!n`je?MgcYqAzwOIFQLWJ%rYNh?{%q{6_0kEFD~m9osc?~}u~2 ztx?62ElG*!7ixv_1oPp961qkmAGxp5Os)-z3F;(jY!LiV#wGujt<^FITs7o0p?cMO z-b*y($>nz~-&9SB8cd3C3ly6X}(VlCT2EqKIWYiFP$BMq0o{l^b&Hw^uBazs#z zBE=nAcl6R9@#WnxcVsjHa$MC6wp+OouDg@J-Z`60y9-kYzKDK-(+_Yg>oGUnC~xz) z@Idt;P5Qd)?~z#y?krR3uXtBCYgORTVOok8Z9H(GU#OBc@|?}(^Oba=A)&04b_6EY zh45*h(yo<@jPR$WCc3t)_*bEoYf^BFI8gZYlb<<+^RW925}* z@>C!unMgYlRH^T0B}vOhJ@Z3LD2;l45rS|>NM2{5m`m44PoaGVgA>Pox|3k1Cs==- z&}L__f>U9YpZS*JQ82|;UJmBq!Nj-(n^+`^d9f1_)boFUf5>rduYv7$9aL~JGJ7ev zahql_J-ug|I79lhz&P-TEGTb4(@|rWxB%nEM4seeBz`*tZoXtb+q=5qU?Ov3?u3T~ zf5iSKDb>E{okRRU|nKIBbXs2ky zTrrZwR;kv9FNFSr&h7}<_J zGkZK5jhPP(c&|vYZ#S~TI+3|Q<0PaNuSvZWk~a6zY1S{%0-ZqNVRo7YYHe!Pj!N#) z?E&OE-Ut7j<NtPcUetgE*`I(z>d-7`ceT`T3zfx#G>)eeAO0|1uG>p z>2P&bx3fQQaG@SI_F*o!gR@$$MV-CS`od$cBN{l(20FMGh&aCwBYzbk-dFq2A3=O2 zAzfD1ZrOd;Y~?bPO7AzJeI$=VZAnXQpD8EN?7goU%n$8Yu@}K z(i|e1sX83w?i2YUb=g#z(=qSA{^$tzmAui_`-29oxzxVprNu5vi z^mRIQD~_1?C0uL!*j6Q(Ng(^}7oKPCFbj$}0S#v@U3Ppnnewpz-U0G!OE2{0$~sBV zeE#GY@?hP1Ni*jt&m{P@bMJN%&e7@1!apCZUl49(gTfCgw!E>eOTSu*+pIFPxciUQ zdk=qI+B`Hkah?Cy0ly}JEUP{NW=T!Bo5+0y&%$z2l|*xP)-kKME@czzTSh@&OyAFz z`W9MNV*ejw21YjcEW};N-9OfeN;TA88uIUTdLuXXhfn%JZ=c)QamTOq9JFzU0u)=` zQZ8C^E5)z@>6$AKN4CYrff$vr5JseLilY? z`P)3wrm?Bc|J-o>xW2k)<8jpJmx+mlvcw19(CPW)ajlx$dXvD0tKiUvU+#Rxceujd~Oeyvn);EiR4- z%ohlWX%lIke0Qt@UhuUWB3!nsL)$p_5^^^j-{n_dvqr3%I=KhGJ=Z~akNl3WeHubl z8o#}CJ|n+tnB>ul;=VV|7LbH}p4uK-o|yOWDQ4~tfrc)Kr;q>YCS_uvOrt@Y(4X>G zoG3D#^z(-Udy-fS%m32?3?lV-O1rD_N?1>@GLSK2B4!RM4BI;i4JBmCZIGYEbp!oD zCi@?HKA@~H_OB4er%thsj`?fu%OwGR@t1s9iNNomNHGXYD}H&iX&8r15;Y#>Av=kG zAm$lgi!Ja01JSdV)|tAn2&@ca3y->!m@k_(Ri5$Ae&Nq>FDB^swPuBC0!+7w_93d(p- z+(T-vE1T^xt?=RJihYrh5WPV*v!aWJIrFBko!o#`zG-_@SbJG+1^&#AJ(Ys+X{b&bsYFfV zplA_|&Q*{>x=EgzK^?xS=pJFw=G2;u6T?&HC3#4@#>x26J~8kQ^JEd1;XS(W2eQ@WJYfcw6pl{c zEZz=D4F^G(01Eb->VlFFKAVDg;C<2ci zw#JIQXEbt8a_;Y->NeiYpYJg07L|>-#cE^LU&_DuAwXjD_zrrc&|LptRXiF@h*Ebi5isrPq! z>6-2zgm`rXecE%hm!{Ix*9&KZckIt0b0USDLBdv9fm7UsP04R`@b~kf9??yqG%8DR zmun$X-hEX}Nkg9|IrCkBg&&$9S6w%rnHN_LX5Yu zg9o?5dpl+wCN|AjTV1>AZwqcnXj3rUyJAD{2bBW7tEbDF6wOA#h4EIV-4!C{KGlvx zYBskw-|+6A%F}N%Q#~M1W(m%A($UR~7`Qlq_!JF;+j0wJt1`1DK&MjWk*jC*Bw+FU zM3k$)DqH~r>A7k8n@}Yqsl&gc3$~|!qvvy{&M`y$i>{^?uaZ;;w?Q>zT9psk8XoY*Gh{Q37IMLmL~ zGc=a-)PEgkjiFKyoVrzp?A1MbiJj;4H?djw4Xt^Soq9P)f{HogM%5^flybtr4%%b- zw6ULlYjAZD1nzSDIZ{Y4=n}HKWmQpq;p{wThVW{Vw3qAF82heCm)L}SKZ(Fqyj`6g zo_JZZ6fMbiW^&*U-#FeiKD{goA|ow zL(lHbh@@choe*GQwrkN#yVAFh=eAYX|C1JEVsayK)7dj)-kpYQIY27H%tWW_fltQ? z94i8Ab|%f*>DkoWBOYw-*;{|;7I|*z3XltE?KKN8(?O!^*WoFS&qM6vZM>WDBY%ve zZt9YwHL7Or-rR{-VHJNNM|I@U8f<>WZp_6`+K;gpS3p$7rK;DPi%F}0C0R`=-tw|D z8u{F+FAh#6ZFoECgnvWG!UajV%>mB?~I=i44uI zy_I|j-OuzV*(a+1bIE_uu}pbD&WXa#7sWz)!(t;Fq%RQ_oNOCuMV-{qs2>DGsjL{_ z6HTh{PcqY(ysC;RP|-=FV}RpJ?oQ%DIVcns2VF!*31bnpjZ zC#FVM3|WAY2{tkS!RijryT8lw0}JFC)$v0jSlPSi0X;w@6WYQY1-UUB=1sr z0$PP0Q9q^%dYcy5B*ltGh*Iz8WE~(u0uhAJ|8{?_{LRU(J|pXE?kzSJz_$b`L;Z5V z1{qb!>;GW$pu5_7>D2Z@2?Su1KEV>0{6J`Gb;#2E`66(9k4K`8<{(NT$F^YY~kU*qF}W){_ez zAG`@}j%2Sd%cfZ#xI6U2TJa-f*Wm$Jg0_4aOPqbCU_iNM0{-inX9X3pjLICY|PRdt8>Cj2C9f<{(w8|;pHtdUEJ+4 zH>?=R?Pkptby+?V(5&-!BcRl$aPVJVlkPEAve%hSRO_d~ya4>L1>p4ew&ofzw}1-z zw3La<>?3-}83dP!G2=jfL!>Y*+IAwr>o4kX?O{6Gy-iFP4YD;Cq@oMm0`<%Q{fKv& zWz>uLR^vy53EKMtx6M89amJb0QhXnCZQq7`%qHd3ogn6$e~3!=2vv4&mfHc3{Jxp_ zUq|d%?<~~#;1g#^$^Z&k0{#IRXPgxio_CJOcA}b{H=BLzx45s~rz%;=6PBkG%2~Ae z7Y2g8EKVY#hA+_M5dF-DD70|#!fEGJQcpplqfh|NYRepV{<#<1!UHqc)X;@E3`RH^ z*Qd1K>@QZ7ctWFR_#)y*(LGqk*>~o0yCB#58iV8cXsS%)uKC6NW+KnBe5xGY$&U1w z_V>XnRU!4U-{N{HN7|n#NLxNG*=w{$oAa;qsVlEYKR06sKNTn+MebjhFjbDT@*m*W zY>H4pAqU(YF$iTiWjHDkTDKL(&c$@i*1X+`>DY=D)F#>|e<~2iNXMTp+?}%Rq>!LSOssv^nO9bl zrn*V74UrW72MVj)bwG4Za{h)Q)A;RBwbgw)n-7+(_z3Tku(sNS>ROb`AB~y2K1D?p zqH+u07eJ<6jV%1s?m8wHvULlWt3TCyPO&jIDGtnpUs*m#+w}Ac7_1@l72Fh<^z2+Y zsP~}n@4m_zvv^Eqe`&n@uf*VD?Ov>P|Lhge9d&V@JD9NlTW})O@Qp_O_DXW~s|~dz z_LGo84+`(l>)7Cdx}Ur6cO8r7cD%17{bD>U&Kr9eMO*K~-oGLArIFCaQ4kPpmu%Pd zA%^NQV8nCENC@~-b2&HG_r1TVI*^F-BbuPbxI~I{v+)Xg92Z^sdb$oB|w-$Ui`f$xyzxG6ZztPsY& zfd=({Vrq~;9`g?#OIvwpHmg<(s7>`24tQ8vhG+{$+G)UYJ1G=bsnb2b0ur_>B55^- zC`C!}Jnkil?D+5J^Tw9ri?bAGA9Mb{TMEbtQpjWB2s{~Pm(RP&u?JADbLGKMGExW zY4>~H*}V_pl2YDrn9`dC3Fv`Zje6wwe44=(kX#%+0&{IMA=su+ed7W10~iI}WGyb3 z(gOSY#~s&5D#e(t=@{QFl{$;4ZXPBwpCZ6pK3`GrV4!cxUej#Uv#c~QR^R~-DT0z< zjWs1_wjKZyw{V}6bwlhi-JK}u;0_bw_+Q!<|fdfkd2z|k5c6@+Tp%^`FAi}CJ3RLZxu7~a0Ti&2!JC|ESl~x zUNf$qChIuPX25;RT0{7%x>3GcFC}Lu1l1?5H`Cq87R+$u> znkxT+g-t3Dg-v?ob(>G@KM;|K8f#eIC6ek&z}0 zH$-0~TM04^N*pwBL6qlT3AbmZ-isDi%sDUPMWC zizILDABj*WpBTL|DLbXh`bvRrn}10Jm~Af6bYPU#Y1@j5C$eo}BOC4HRU4akoGCL; z!VRVAjU+-f*|%>7<@0xrgG>rTyIN(UqqdIiOGkF+wd5%*B1u^K`mcB-92d&}HPph?^vEioYNr-p2`?Qyu+dhqHaryr>|EN5eqUoA1FE z(P!f8PLDx#=-xqn!xx0NndQK5)Q_!QVJDoBf3J>5kxzR%Nc$9RM;Cmqt1S_vs@`T4 zs)AHxg=;N?LdkoZ*hs8E+#KwwbW(~CG+n_o-wjW<-GY+F%YVG9f6q}6aZguIJ0tJ_Z$7H@jL2lnQLV)wlYcq=R2(w_5xAGRa?`&GeUNp=X^0SJP5;C)h}BXSb*DJ(<_eNZTPn6^_k@A&e=uiFIPi~Pwl*3t6pT@*HIgvek$V6CV<^xb{ghb@ts1eu(nv%b-nER}kH6*vb z*&5-5?gb@^8{GvDgYFE;->rdrsIsfC#eN@W)a6_NoiMh>{QE=8*+L&j+E%73{w>7R z35x&v{NqoFOd&ESgFO;Y84X}wVMhHOr4M=+JaOt`yDH^2$+cJeAT862+&%kESR2X4 zT@dCBeiJ2(4Ml1)RSmTL6Z}VI4UIDcBoUu?$#sT~)Kt7wwxoyi{cpKwA~l7&KJ8ypKE0pB{!A!A za&&ZZvl2^Ji;POR&uMf5HL11>1o`(VIi)7P7okv?&M$=eG$UR_fwH_9=cMw}50St! zRn*enRxS90EqAoHJIgF0#~`#Z_hG;0*R(BrJNsbxV-5`bXAO+I4NKhnxP(!RnwmnCJ5BA&K4^>u24dJt_u8B^*N+pko?{zRQ7FVsA^7b@Qgcje(hc`(sQrU9p z0zZ-WJV3gJ-&jm$h!cD04@nLa1FKo$&Z@~>sBdw)k{$WpdXkCg9EDgk-A05Y2GfCx zh`^XvwWMhI9>YKvLZ5zT^5%R#^#Xs?R>IccO}|$`*5}h`iG^NYNg@Be3im`${y%YV zzeg6l+b_%4VC^AG3 zbMx7uh0c3|_D4#8HnV6C%qA{*c$fSx**5<^VgwYm)t+(W2jsjnNY((_)AZh@lDw@O z?Ow)$M>9FFgs_czkaP7yGJYVI;vn_(M7ZPOhHX5gq4i$si3^b*@af!~u|b2?K*}Ia zUlM3kRL{cB%!MAhw7dsR6K{y5964GnW*Hn+L5d3$uKV^bt9n|{q}3vFZJ;KbVKgr& zW`*Rf`T?STR=cr#IC%n!4>RXRO+j(%26e*qX;GkyV5w|@jR*-`^}Q2?_e{b);S%_v zM1kozcqfp!KZ+RzTt~iVU?#3%_33hTMwn6_uu8aYNG02V18EJwc+3HuHT7`YN5?(V zp?6|z&zo9=grVds02X5;(d8;c|7@hT^47~>oPmQpejlY?_GW`vQb7_9D3V7b#0_S1 z@ASK)LM{VHnl>SJkKQpJp`q>gi#t76vwsb6xijwFFeyqJ2>!C@;_m;<;+hV^Iy23e zb6IdVEbfah+HOi>2q3NxouXx7NDR&}oZ;@cH?@&Ow%5T!=$$0k`a`8f=0}S=+T_$M zoMZz*a!^vXY_a_V zXtG@FfMR&w_Krct9A)~|3e9cycl?}eCQvDhwYP|UiU_xe^G+Br@CuYW-MsW`4rKUz zv|?1+iUA-Al4(F*%xOXgj}4`A*ABrGQbz8MJ`ddycN_GO^&Hb&Fh{5udy!3p^`gGh zfun%%V1)RbwRqIIf@h@`X2MeXLZ%=2Sx5ZBD72532KcDZunh}!!LQZopXeaURaea_UjWc zhlXJ;Nv)o${`KSUuc7<~{^v->0p;hxd2GLyzrsagl6MI8IS{AT|GNJGQP<1YiN6Q) zAD#RT;a;-Rf!`=@$i@qD>ugtNlQpOMnmnC)NgTqP=4cgPOy=XTEj(S0)#RBI&uI^M;f{V`qU> z@I5AqDEOP|D6j6OD6f2}#=P34x)w+y2{x$uBoiHcKZ+WU_^gf0d-GVzEj^q~QeRXq zD>l4_Na37T)+sEp)si9zYv<8lykr`@A5XM zs%Z&6TB{}Mlk|SX(wP327Lm-r+Q9L?qh_}*&W}T?*)cqJ;@+42T=EqmM5w^-D_O6z zds#%KW&g8om=GPc;#SIc+z?SBu!rw2c)u2CHY6ybmwV4;j=M8T)^@-jbThv6@mi;F z9uAFD9Jd=oTM5U*H)+uuI|<&6Agg|1R{#(~C<(Bk?&(JGud(e!wj*`eK$ zR^Ux94F3;Q|8-T4Xg&(jaVNb@pBE%7bi7%o*)bB(!&i|CzBA;ruej*-enKr+LgLZq z#q~F*xvUlSWw;HP-It5RV@^>Ls77v10N9~iIWbugz)-?J2qQG+5*B&Npg)8}e3n4} z&4Kab4>7XEi~;hpf6+X|)jxo56+`Ar68-Fl3Y2RlaZO}MrztB9i?%w0tiVEuL-V=2iFz^mdp{LLDv(SheO9DRpmwq)_PDjfDdtf zu^JyjuQ1}XnijS+mRnwe1}p#)5Mi)j(UJ>RYy1f1QElN9Q*rGTHQgO4i{qFCGf5w2 zBT;91gcdjSxS(`F>32-w)sTBM&jKNSM5;1nAZ{o}Ay%Nr`@4sAClpD(=nfBohdyG% zCdg-A>G8%pPrDfPuNy+`HD#2OWKpQ{c*mXhHr?#o8-=aOejhUZAFxSyvP``Ft$~ug zxETJsOjrtHT(j8r%6Xb$yp`*5_5q}Wf1iGzXyU6E!8Px`)TTO{1}D>?hkV#x=in>p zfY;<~-Y474xmpm{G|TnsksfxA_S0G2dzw$>THT4NYiT~dxsZn#XlkSY}@h)oQRry4axIg z#c14CD?%!zQvZm|2Smp0j4Gv0(mPl#yxYA?*eD~J(6-`dgKQfmA`E^Ux}OYkcq{5F zfPufECG82Fl^`j4g8vVonT=CkLsj?vS)l(2V{u**qR{fd(7@^vgzmvW$4OR!O6~Rv zN_^bXfs$E;?bQW*NQv$&uc0*Ac*bqQknVsnQGH6OGQBc-%ny#NQ*9dTIJWJOA9QNy z0Vce&F(*eN;e%uwkcG0Af5>JTrCe~_GoXqwX^8mI({6$oA&(5Ov6vYrr zV{}-KvH(d$jDSspd(@Ih8Ni90*aDr_)%SLRT9({IiH<7D;VHz@9u)O}T?rdxDXp?{ z@1yj}cGQK$ArNCQBQ2Oc^mAUROcuTknVa zzfR$XfU9|rBt>cx+yT>H&{4s4Te{4v=ra&QrdN=Zm%I}~+DXvs3F2Gf`TpLfq@~4o zwcnmRB+YlG`7)G(_^g~oh#T)e5F_xBVsi7gl!v|I zt)~0x8%v4&P4Ne5kDUxZGv`?qM5Dr&H0%!36AaWGBQ@NT$4`!NWPMltJAkx`T>u3G zr|-0`3=DtHespVrRd~9dv>n%xFqQnD7C_#AbP1bV`06)&8d{18R6`>xRxX$oxx+oH z)wC(d**20TGL5>$o8=rOh_t2u91Q5MI?U$GNu?=NYM%O!EDMTZDg_8-;y;A#Q2YfE zFOtW(PcF=M{zDaSe^HxM7U-_}sw!e}8D<_!E{-WJ0*5-Yldkyj8W2rY(fK|CJZpWRUEFW<2|cqLUV2I(h!iGnj{ z7yr?UBcV&nU#SS|a`jh^9mIM_<$~R7j;jenv@KM6Ao!S1D-)nzU$GM__zl`!UqBr9 z3mNRB;Ev}W$UG{HS=?gvzapLMN&U~B?85A%)ky6PHlxX=0yk%RcQ@?{+27640%cTHY`|8#<|uJaAn&^mRo zW5}=-e`JeP<6~+gO(Yf-76y(I#aI5ZMA1mP&w!{NNc7)Lv*T!?gZs#@`gp4e9x-Mh z4f~!?9_5Jnj+8uyZ~4$*_>HN{P;KP4{A2f#W{fCGi`z{^(^SUphsCyKcy~|{Uo8#j zwLtv+XOP?e2a6zK7&u{_E<>dZqzk!QDq2od!-3q~kTWCdW1 zA}YqieP^EsxTAe;tm25IvLPcRx5Le3c$Ch{BSK!lsfq1n?;-k6PVFaxbDg|;gfT09 zeFB-YcfOe6YG;zj#`}7sxF6{|PFmOtXYH@Y_6wm#7raOL_o_gR zWiOD_4>Ec}`BHvD)?Wh`e9>T1kCcusQqVYn{H!F+Eo;0J;y}gI zBU=cpObVpKiEzZa3w&mcg$};Beo9GjYLEeYf&C|BX1Wj*qa5^;6s<@Qr=_g1zhU;T z!fd?>Zoj0A5nVn6&v z?3B9#b|h;ZN*!qMwIL>~IRI612!Y)eD0j+dl{{>Eu~LJL#%5(EjU{3`wqbDlAZveS z47x_Ah@tRj|MU>^avKUPLx%~SbfF=G*m<8K0pM+PC<0rkc*+EK^HqJIHrvxpO3Y9-O|3p4=4a@glkc;(Kz?qC1t(1r&F4w zS|1SwwrvGAY5+ss+B=KIhyqx_>DmT&$*`A^PcG>=*lR|{p6%4pJ)^gk@3@5RHPBsz z5k;;Yl)*EBAwgmxQS(`)*lle_26v}%4cDmq#cL6+-XWWP0-oTctgAfX0{$zn0U{zQ zInj)VExlj5WcrCH0UuHE)SxeB#c)>dUoGlBjzQlM9(!k8(G};0>@nS-OAmN)fDVY( z0~QLG&46`W)vgo6nGZjtF5$YC8={*P<`T>^*1t~S0L(K7Ok!@Cua5;1nvt`#rBl&i zk%n?(ZHT))pDg+#F^!Jjr0k3l{AFV+Hu=+JHeq0&3ax;8l0;T$Yn!OJG3574m{zI6tI2e(}RsRea(&M{Lr^S+$}S2m_`OJVyvN zb%|+}3z4qVI^M11S8tW6^sO7<#PcDMX;pHXd70BFRzOAT@vyJH8=T%Zg12urJ>6qy zGtct!C+Ixop}=+JtcEjwaLLTA?N+=qN*(to(4T|}%H;5KB;KP#n47nW>?C(opZE4E z+p>!YT15gC0UNmkQ$lkiDMyY(5M-Clr?uYe43USbG3aYeg#-#5B zF8s%{ho!Ts=KmWEYr3yAb~^4C+g1hUJ#kfy_P3M6@BokDp@)ZCi$}M+^}p+1xvtn) zT)SP;T?!BHlGlp5uq8#2%JQn3>lOu%UeOmj(rVlSb0q{9F68ib5aRomyMMlfR8L(7D(v# z53^UhnlkB8vQG-s=#U<49x(M3ZJ4NfOi;VoJ=Y6bKk#I4b*(Yw7}ZBdNTgYBpF7Vw z_sXdf=vx%3`Z4fShId&VpY&JBNtj|)K~;7{cnpD^@vcR70=*gp3**_bk5>oe1g(!SH)pgs1Us(#_Q+f2k{2$w z4@!nU6guxX2B(r#xNGd(z>93KcEG7Qv-3CFx!`9g@$H&56$kg{jYN^GT|=LfMBgCz zTMtIiN>cvp^_#}Oe)f38lF+PKUU-u#nmNm3>L7pm1>XK^xRgLt1qA;IMp>L0MQG5W zfw)k@a<)kKprZaBM3+JlhDTZEv5|q7YhKmNVV3qp(qukNmxK|^Oju7jh+jzyJ|8rZ zD)IKOnEppdo<~uZ99>I9F)nKJ2djCf1C%p~&bvUDS&+v`FSB~cMKbC+mHAuDqIF>- zUcCc= z5JKG24S%@CNsiY#xthuFAY69kD$)g!_vv!^GONMqh_v5HD&JP7Y9>_5OlaXlbos~@ z1&Zi(P8b#ZqS9{^EK>CGo8tjR$FD31rwVV@>{P6GE15qzL&4dz{@D zxiYNu_g~@LyeDS;W%@FQK9oxJBFeirloDE886CiGYOT9RaW|9E2W1jU{-s_~e9!h+ zKx=xWEdpYbgyEv4Bf0y3`^V3&qQg+VS4m&iOBO*z=si2Q4{>*yZZIMDBY zHed#8F>m*&Exj>8#5q2Bk8}IgvQWUYKd*#02Pkd7NZS3`>&g48;JRiavg}ai0pD9z zca@z*%hc=tVA+4GZkheNnUu*icE|JZ$I!+Ldy@Hm*k-SD)l5dTT1fMw#!_-z-TD_Mi)nM5=C;EVZ|uMQ^r zgmzNmJP56b*A&T9&D!QKJDHI>p~^-NVZKPG(kLneg{%T#$`-^vt+k>lE5yLAgae89 zh`#GqPjWIrM#2hVzY0cMuR!0XlHj#8$9X%G1^`KH(M>(Z&N{mYoO0oII zjggN7j`@C~-zjbzEf7G7t%xt%2=z z!R^2rmI<~RCP!GFH=R3Ok{3RCgs5QaHemDlmu!}7n|!5Ln{v8Q0Oiq&r8 z^UT`4Sdz=M#bwV@Bt2lpULNQz-+&U!3NyFEdUOjdw9$tvh=L`Y7+-*unN3x|mjM36 ziVHJ1sKL(jS1w^{PZ8x%Lzu!PnkoNUQ!cO8*71MKe9}6mW zIxN8^L4CxM%9~HTlKK);2481Lx{)hKM530%+lgR-xq3#*+c=9G#fE9ubF*98(K7>D zjdu^?y7@dX3M`BMC8AqK6!>y@%}!ep?c&AFD*s+cGWsG?rX>jQW>2Btv$g zX&?^5&>6oU+b90+@-4{_u2%_ob9G;?``wm)^RD#wjW17cD&s_f(#)2I;OvYs5sOW? zp?mRwFzCq*-cl&VU1_v_SA4bD5p-Z0|8(&iJ?ou46b;VRyQv(A_I`Fe6XFscWl2~X zow!zqtz2^(3A_O4Xm{bTAB*Tq@LTs6mhaUiqaIDkPC}Zo9t0NC-2f#FC*iWyvXiqF z?dLTj!{BhDq`m!)RbWG$*R0ww3+{9Jt9%M?y|``j4Q+~vE`pME^!_YhAK$HITq z++gTO_VPI8g?d!e8<;^6A_M$0vae8Oa=oL9Bs#SXb3WZMEuQMw%niY}P?EyU!_x5$ ze`)g6^@)57pwy%;W0Wq$vbHE_xuB171J6Mp1L39?Q6LaGi-lRu7 z0indQ9uaLvPU%TckX8Y#H~TsLN_SRdYdubatZKaLjaUeBV>eN5yMT6TmA*z=gRzDG|~AukqHx;-wG05gj2273Ofg?ImuN z3Ev=SHsA@m;B6-mNiM4D9fw?adtW}sBlD?{wq(3qc2J|#$#0&>JpSYjwSs6ev)NrMQO{f_sZwaf-Xc&HJr;?^^kN*36vA?DN>( z=AVQIcxOsS>C+$x-s~WkM=PWM#>W3Fk`r?J>xK3A(g^uJ*Vl<5jZr=mu#x12LN;fK zE$xE&+}8s7CIlspyp>t7#rS-r{krCY(cX0T-m19z)nCTarjjnDj4LAe-@b>@58I+T zaM|M-Ci|g%WB*sq3mB6*r>`|8>|UYK50u)UqTzYASsj_68KF&h{&qt*SOYCe>yLTeeZw3U29H($sHUN zG&{n_*o!)K!K0QBvPTi7>S1BLmfY5u`07n=7yd2I(lis-MVDhD_?|s*m-_@0c$94V zHTah3YV#2X-tp48Ve(gx+>yAM)XSiMwZ7Sx$pf~sx%9JlCs|>0KYL#6$6_Rf%g8LQ z-Z>DkqOc(McVF=#Ouu&A-4Zr?jzuSg7Qd_u^HW+Q^aVU-NRxgkUyGz+bpKKxiO|Gd z78X2@-NY_cm4eubevp`?G0-y)Zn?W}L^J!lHM=9rizKpCn7YwQ_`MN!I10{|fF4l@ z2-s_r{#r>KyaD~W%ycTj*#(7of0Y?h6y3siqHUWD>iD}Q9|WySaH%T@#N$4L#o)OS zb)}aWX>dYUQdFpcW%5=vsVw`ul$POcT|U7%Oir-Jrp?VZ{^X!(mt;Hi@o$x)=K{C- zQ)2n2_7w{CT1bHpA@f!*o}B;uH3HJSQiSqDoP!_O`&$EQ{4KKQVj^Zs+Z{@AfL{7Dvgerpi>fq^F*U@F?bq(=j3z3c9> zH>eK?{=@^6CygY2B|b-U@A`+$;j->iJfo(rChw=t(cmV<22^k>3+5?z5Y&yVmxf3&$owC8*U>CNBx(APZp+>V;6*dFA&Avp7w zWfkULAmNtWn_*~N(^>ef?@ybVg|unN336A!k2cQ#?2JGC{rYUWUe$1G@ZAm6MZ1iO zS_{rKEa^9mL{DT^^701p6|m<`JJnBlx0ZL??Y2ygBiPxAfSBqFcVY4uS<{?~Tu5O21o$BRZZ4ceo!j?A_`fpBY>>Ohhf_ zGn7?AU(ft$-`h6gr+N8p{P$%^f;uyf8go}d=$XO$Gw0G&-G)(s<{eEDt!y>&!IGhFk_@8?>sSs?Ucf4cB@R? zIQvsl);bC|LJ?w*73|nPgD#ZMd0a!VjmF%R!K)qIAi5ZF*G`>6B9!}y?{VUHp27E4 zR>!KX3z9l+K5Y^ya9>0ASzJ7b2p7!&u|6g2^{q!Mzu)#qd%Zx6gIM#6Rn~z>PKAfB z6(ezgFA7+Ou;CkBjrgCYo4ovdp(x`2>f&43kD_T@`Hoeh=ibM>z{q`)ndKI)7VB=56w zukFwHBcl9cILevCV8J}r7jM35#sD`mtFam0WYsCyI6hnLurU5{vImo>4p-bvuf_d`H&8u>lAkhnY2jaE(Rvt84c12YrLnO1o2 zz>p{-%Mb-;>K--!E;2SLUFndBV;{n-20_*CrXY??wa1uF%!qVvE_)X@p)O%`9ja9= z8$vk8_K--LG+`lGzo#D7t)B0JG($kc8;6YPgv!M}PrzUV8LESR_DkeTb|3zcr0V6&zNnlR{XW()|CGX8O9fW6gD(NCvV3b%x=sCtfh(7wc1_}^jd)2&S`i1BN9fhmP(9C-juCO} zakwM6Kk%Yb)t1w35m6hw^K9O*?T1hkdd)5N;r|B(G;f#43?S`40oM|?TJVIHI=ojS z!bf6UsifHZiCknv5~nYkwN_^oT*p+g@}MuMjZAAwyhPZa3eNLMtVF&DhC>h_P3}_L zi&5t#V8%+Mt?{7D%oxvnFWvN1{wk3-m+@t^`d}@`sS?YD+UEE!nk|7+upbwiQ~+&7 zNR^O3R$nKGRwv=-Y97OdT{+gJe{5NekLjDiXz|Ds2dJyEd?K-{$WoVs@04{i@|riD z&M3b!)n|aB|G6>TJNk9ArNZM)a5O0nF9&Js`{#K}5#k+>TgC4&z=tQ1(?A87&evOc z&rX4K(Qh6+zqcKW#;%uppl|PZ5ryX1JcDR@a+Mc!T%vhU#XtC{$0CT6v~Gdgvr$v+ z1A64XQ+IPi1$T!HE&m3MG58U~8dF3ECucIVtsCs+vok=5<2B0_>#1;8K}G_W8)afi z70HFsyNYH@3Uiq|w$ICCvfl5*KN9l{4AJFN2h)JUTJ6_;#w`A$x`L_p()WV<@A0?^ zOyQj($qA&OsAVQR4V7mgn44IT*pZ*L|05>e=ac+1xCP+fzW{>$wWdg6JV9Z&5m@g} zV;eJQh0f4z)0W~77Q&7lm^<)-Eb`NYmB-_{a4V~n7||pW;55~9LHngY=Q2YL`B8yb zq)4N-S8*?J(v~R4$~2-49vedlkKxr=L_QJ%^@ozU%jmhE8$!Kl6pAQoP!F-w)fYQQ7M$x16}GMc=u` z(Cr9;lV~I)jXr&Mcv*}vj63H&gO9d6blJma{>Uk*TkAS=O7RqRTlhXrI_*Ex<%U0; z{=Q`XCtg|oDX31JQxCz@+)aT-GcpPHchz0T>0;4FYWe>tPFj_frogO_%DYoIL+X!O zJWPpQiQID|Q~zJAPSuEKYYT;U_zh7j+0P)A!|d7)KHypz;~u1%1l?ioBkGw3CB@i4{b%^gBjLT z_Xqv4UpRm?*O-q(jhVbK(c*?yKg2KNth$xYuSf8aUS`*Ur;mYQ&hF#c+nD$PmNaT; z7y!DdjCf0A`h#r&;{Ju?f+=R#Q%B99r6Bj!wY{4wA#qp7pn@+g%3oZKSz5a@Ep0qN z=?f7!cChGSODeJDd|Tz9`t{qV^Exiq(R8N8bX%#@%Ol0*i#cQG`oF?my{EUAl=X6u z*$q@$3+aCH8tLxG}Ak za*-I2d?`)*N|NxjEJx-Ig>epIY}2qKlT87k>oVxh%1!< ze~yP$GJFYnIoH}h!=e#i)&zxGM9*~Ru#;w~{s;=%gjoQ}T zPnn%*+$L)uA~u^ny1pSqQs!zK+mA$L;UaMhnm^4GyQuqh94%A6QsZE%Fk;vALZP-- zDY73U$j@JH0pMemfC`icvkr4*S>&A2`Pq7DPMG)HazqeQPoo>ANshRj?Tl=amjH~$ z$y>n{=l9?6VoEt&1;#;gtnX>E0aQa$Qj3#+v1WY#=9dbA{eDpUSA^{Uq{g#R2qO91 zml!Ju^12>o`7^II|kFQC| zhD!KaTIGVgj5b$M>Np*}cN!q%YF*Ubtk?AMyNC@-fZdXbcO`^nXjLNu@_KO}Kk;nj z~=O+%oV}@p@?=-zX%Q<6EtH;R5Wmi&_5bW2oe(+V1>dx#S zs3HwH)~%J+LpvB}Bxz9SU<5j74 z<{IFbmOz8O+sE*c;G@=5zIGKLgbo3!A;`lg{_J_On`*)#`r}yu8 zcH7wPP3tmMNkrEB7X!ZJ&s<+_60NOe!S-d75BaM65>k500O_~0q;2$c*3?)at}`M9HNH8y24fOn*s0Bn0ZC=L5WxB!4wMK@7^SVA4rpXLu~|}kUn{% zx^Lw?o=hx9a$Vu)VrPX&lj!F^yJ8oOUU2HyYF6qpQAtGcc}#Br-ewN?&+qCb)^(FjG=hIl_6}rG0uhAY`x_y_rru@VDG- zKGhLF%frz~(nq4Z^TQZrAuWhg)PyFoWCp}V47&W)aJrlpNweO}`a8^-*8Rq?U26}C zHhI%7>M#NY9{%bEdYyh2Ub>lf^S*z6(B!Y4=ibfd|5_X@8*9TML^N*LVFw8bD#hQ^ z1qEh=4x7r(Dr{so&o9r#OH>StG+G~g)cZYu*%VKUKVP51oUEGH3y^BdGjici^RMZi zrYYFp3gjPvUmR;frG+NKrXGGZeUgB!bs>JYxqLXhEU@r~9TRoBm8RI1Zp~8ZT9CHk z-mQlRM&d%>$mS6+gZMNA_1&h#h`19rOA*NJk){(pyk#PJ#7>0Z!vK(A*kplqxo1B` z1I@Yhz8H6y|G~X>A$+SGaa$CxT)lI9Xw4s*UD0(+CA_FZ?1|IrIyFXcN0UnC)fL96 zPP<64DT%V~?7p?dsN4~D656dA@zo1?yglv>#k&56$)Utp%kVHLjMJ<>0rrublbkNE z0QbA6)eCl8NkBn=i_8W@nSVWxc93EY%)zg;zZ38{&v0JV=bV>&jTB7(^M}3dcYukS z%bP^t!UeiO&Jct5`HB>Rce_JK!3IFSh(cB8%m%E!(xP?Ab%E&}wZ9y02JOXo30x%# zvW~>ZAF8H7U32w# zNCfoKk?*V^uZZ`iC)vwnO(9yY9G*jVfR-zU!`WVcVRR)s5>>WnHOmZ;=I+n5#dsLM z3avXNk1o$Tuc#zn}knGC(;sz z&v<-g+D!9uagxb1lhlI676K!97nFg7J01|4VDK~-d5Le{J}WV<|0gL~67qaxrZVd7 zMY*(bdd+1eb>d1!xAmHi6E|+*Ey}1v-n!wsU!i@Puxi})kj8%>g92L_PMJIeH=Ujq zkC2K8#K^%n6yF4LV?9xy2_iuVg;COxuy^|P`U~Dnvn09MXcYy>^p%LS+f!?fPywBr zwcNC4w+8!;QNE!cztIDn6aXZ%#Z2V+l>&-oMw>%Fo$^_JxEpsHTg~eQPl5FSxplJE zA>gOugCX3N9wT4z?qIs_0UwdMGsU7Ii+BsW$9zHTg2d|raq1KYe!W)+qL4+3Se`9y{SSWFK>5hwkebIRnXOF^T<&!sEHDp9qrB^;d zU2e=(HI|^Y9lk;bE9jGz6GiB-ERB^CPAfw*<9ip57i_wamFJ`JFSuV!@g2T3^0?uS zci9%SAn z7b~)&0tQgTjgo#u{+nSDo3tnZ>vlK*9UIo?kr~3sH6v1I14;R1e^D9VvjWs-CvjnFqsGJJA%0=Oh6-yJBJh;!v9R;@$&+D!T1|!XBz$b z8(#?S))q;h?$n0dHGFDT%8l56;M@sr97(JWS-*JKTw;7b`2!Y!Pj@4@5SD(5w|p-u z0XccM49tF{v{@H)EHYqv8SJ1s8U;14?x-8vZyv!B#3p2ER}Pkd+Yt#h=I2hkD{B#Y zc`~7Gy^`ZSB1WPcU7{R)P}U&IFQ_$ekv*b43a)pUxs6zL&RM7&Jc?F>Rc$3w=`Pv^ zlicA_?_O}8HJgKyu4i&5FGu6PF1~iNZ>_(5`8&aM${Bkt z=LQfE1$j;~KWgS=F*COe)Vf&@0=Ce>hbuU{+b@5hEc$ww^;?j4o&kGYx(53#866oG zHzsWH-CV#L;{p}9l7QzMN~ijwvgO_qlb=n)b4`bVAaL-Jv<=gfvB%FJqbzPa{R_QV+?9r2xWNfT~m-0^q5Y2#48kJX6~NV3N%rEgCU-IxNpZrS|3 z*GbvAbx6?rQRvm(ewX1ZyzmRuUJS=xKwHX7v}E)jg)q@8NrUmbjz{2!l!ft2mi)c- z7HR%*_=FpBL~??5gi&Z~(Jk^ma3Q|EMcTR^z@^nx@aso1n~>hkQ;sv&Ck~I}0NqKh#O)iMl2wu#%!70VG_gfc!+CAryj8-*d^Z;B1X=-WALfcvJI8z*8R@XOr4o z<8@qes3Y!w-UUxmHq3rp)WH$Ryr?0pVA_0QU9*NUbRAcXU0^G!HPOF2kA!^{8}P7P zpSc(9K}fysm8`>&N$jYm=c6M=}THG32Zodmb3 z>a-Os)bf2A3+GwF211&+vZaML75dr`$kZc@2-U89@ttv89aAc>yBx@Szm)$lKm8AF zQJ14=T?~g>$nz~4UV(^<2Zd)ewYbUwRs??kkgJ#YZ{#@lSg2MBeL}vaE}It_ycr|q zm;)5v!HeuUz==>Vy65NSuUI8aj5lTV0Jh&v;c1jta%( zaZDPb7m4MaG`D}H`J%>t=Q|SmXMPV%GGai3df(xi61dh#H|?k}EmjXG^Be-lIpkPK z8euN6f~Q*Rw22wx1E=rUr9TJuv=_ZlhXwkilM3XBxJ3L4kiKRYEf1(}&)#-<3gxuy zVihg-W*xs%y7&`SOPZCGQpxXgKAW~z&2`8l@6TH?Y6!jyw8XRizA<5%=AK;H>+nZ2 zi-*R_PAQL&*pAVT!455#EjK9z*>2N&*a*j=m2bg^@Zn;+Q%wv_tOkmhNUfF>;u!I) z=PknP5mFJHtW9zm>Ddl$Wtb2ITJ+#$PT{w6+dPCjp@j*-Q0(5D;^>_|_g`dQ6HfL8-2Yg_`f7}U-@5Jr2Tee-Df zd^+07R>tA+w8!=sto_m&QAcqPN*vSQZk3T~W=JCXlU=5f2D|V>3lp>xEtu&|aW)te zS*jE!;gVgQjSn<&^mq$RTO_3huvcati0~wD@+G6IRmOehYspD4VEdZ~F}*Z|pD$kD zJ1WU**HlOx&{tCHXrJy?=AL`@*G8`6D1blYMI3OPL%uop*J_gMIG4(-74L?Bq$XR5 zyA49d9x7s0xs^gM4JXf4k03*~ojPHic8XvqHJfr?v$$_#=(NCjS2oR2ChqCs@ZGC_ z#4SHXpO>+GthARx<^H=nckHho3j}k4tpQf^xXl6Y(Ed7|^X&f)Hvaq;9l2|$F_`n>Qo|Ehxkx@TMK(BCpeQ9evn>SDv|63Tr$ z4dA30|Af8`9*mQi|LpMna=(Cdh*16bRt(ms0_<|;kBy#Q_H&9&A1KS>X;35On0Uv< zghRN$?oAH1*P|=|tWreVUc%*KQQ2c>e?^d&(JBxdTnK}i(TaKQfW?K}coZ5`{#A(+ z{ByI6i>~;*JaXLW*Q9zKLo57Y+*f_O_!MHAH+<)jfJr@hbL!mIF5irbJuFicQZrl?LqF=?L=gd{I2DE$1xmSEfG?#k0jrurr2IB7)|*Ato#j0n8v5YxxWs zL>i;c{!s6(8?B1tdm>)sEgIGPL_y&t#;xYbjQAb(2lc34lu-X;qQ^$a+RMK`SoP-P ztxRiFN&ZO&kkjE@@Ohk`q@IL$|7|!M9M}}HhUr=N<(*FmCb}*=ijB>i!I7l#M#v>c zyG>V937icA9{i=-)Y&p}xE&`mDhNeQgSQ_?v8X>HalwOizg^K`hlc!slq#R1(E#sa z1XYiUfTCx^6nuQF4k>+;y;>9gLTDz~oM7h^D7SZ z$$$J(RNr;OfgVTxl_nGwUUGw&9}L%A;H#!!wA7eb_li#s^5y@xpEH?{5tqDmCY=jK zMf)I1S5EhtJ=~X?+N5t8nBpmazLWY{jH?sDGwQ{(Ngj%BXzPVX;VfG|{WI6q4!I-u zkRc{JQyW+e5&2)tSEI#2Ea)f{JI>pd6KC_1e(<(8^iAiaK%A4^O^8^z>C>(7;w7;! zHHWZ65t1YV-doK1u;*WMAFG#5AzH$WbJ#E9!cmh&YVXh6na!9Xy4*#*tR`cNap$%9 zndr(1pvzn9vK@Sfx^J2v{L~k3mIySn z=rCfUX_J`rlsol32(~PEPt5(hpM6SG>PbRUP1@>EV1ip!3@Lml6s^=w zY;AKJPNu=D@d2h0u4IepB#UBXykF*ZGEp)=mogVuE`iacYo)(3Bwa=MQQ@+qHdE;Q zxaDpm_l@)h+T}`?5t5%L_4`aI*qJs+RWgX%H4S~~9AJHiQO=wY=N8R21wv$eccowI z5TPQU&=&FY?FB^^g&va?#4wu?>uzva<9=cPmZbXLyo)~4= z)74VwX;Bn!Q1CKloFd4gCUkw$%T^Pbe#^a6d}l6_H*$iY@-3&}nG%WV_D<>Tlacr3^{O z25tZ?Gc0xBZ+pSm^XDQFM7mq9wvCVvQf|H@vy86227-Vg)0S4w)h*bLiJJC)B+#L?_IHL(v?uD zxGsp1_&r26s6~05dGDsrrfLY05H;D}n!M0?6M1To?9q`C8Rm*(V~>llI1fUX=jOvd zLpdT12;KwzV9*IRdA}?e=V-yz9vTO!p%0%t#eZ)z{Z0pt&6R}*vL|8y(SpG56{j8M zaqaC`y_SI(KZtZBoPPeBH#|}sQr>6Xe^%sG7L3LkkaF)E z+FBwL8YXV;+G{Qh>*L>EfSky71y>wIF|+H#zYtDc zvkV5=hl<;%h!*1;A&La3a>zXz{KYSY|2zi>SV_H<_8~)G(dIGNQYOE*V)W>+o*j3( zwalZ@Xs(M)3_c2P+%oVU2 zadzh@J1>`ss#wkx>q?}P3A$Fau;fY4F!xoWPUnUcxGDmh8l}y<6TFP9?-eq&+Qwmj zE$^R$gT|TZqWbe>e$wb=VP@_N)#*D9{ue=+jP7Ks78c^s)9K6)11ya{of6-MI-Lnb zj1uN-okhE=thAq?1-a#pf4-q8UpUUXGyVE!gC(vO%SH8L;N5sjg=7)rDD-m%Me*Q# zrx)LxQChEIP{y&?qU+iZt>!?{h9MC=O97t8T=-Mwk$L4%Fh4rl9`Hh#sxD?PJ}RrL zO!)Ri>T@48lW9rjra)4r1@SQP2guqf?iATc2i zQtswq^)y&Xj)ILLjc`0=Ru_pfIrz9TbIZ@6&~~cLrB;?n>PwVvBK;IQ;rWUw{If2t z#U{>7;$7Z1X`;zs?Sw)aN3Y0D0j$u)YlksaQ2aJ7(N{>)c50+9JB)jJuZNVy#~xYr zJAU3F_MxXoDAO!X&00`9&OML>rF-`}IP$5>-y;UbNjNy2DDhGF)DY<4!pt=ux?EGW%yx=#4}#fQBr zV*)z1msuF&?NZ)q4s|DAZFNOGhkHCMBCP>FHLr*5Y z`p^bit=nN!gF`J^HxH3w&wZ`$>mE+u^Z#q$EY>o1zs27jnnVBL@D`bP+8SJ%&O#obvLfl8oo45m)cT&a+%j*Z!7Oyj|41 z%@Kpw+qYd#X`iv=kj#Klb1<5Y>YY>Xh`L$GiRX;Gji~{z;rlRSgz+f2Ui3~_Va@4G zsBd|^jhctsC7|Gz1lC9~IS9oDUN|X;)Wm-P1b^-LZo5DF$-FHdc-%Z_Ja*V)LaU08jsrx1AWei||%^0#*@+MQ^WdnG*+NFXPs2 zxIJ!9lU@9?WufMV6r4D9WBYZ3eSESPv~x0m4b|GWU2gCN>Gq4RmBIurjWS3pXL z8q5Z407tIt2&0^TSDhtXCh;y8U-5Gr{o=cCuc%iK`Sr!CP#s6GiF!NWWfB$uugK32 z@_=;}tg(F4Sczss-+HGREQ#_V#j!TP{8<<0c?oLI?A!*EmkdIO(O=|z_mtq_`QtD{K&#T6OHdhDbheL7R|bj8x8>V@14xb1OH;iOB(t| zJr5YVJ+?JXQ@x1}dbImO z2LA?sC#=0P036GA8Arxsk_oWPpfo-qcF!_M0=K&04{~R=`}G2@<6@5mD5Z5%B*OUx zMwZUn9ja?b;&om_{!_wGS57+V|2BkG!p?)=L$nC&O0=S*wf#~b+@G)MOY6Qp1nxA* z#s0%R7&bBf5+uConfI&CD{Zhh6#4y{1JaVP@k)pC?4|sg?HPBxzf~8p=C&NzfFL%! zt1r;YN|mr4qXTz=8B*K**%idZY4j4lOY{b+CRuZ99X#DjE=+mX^Eb~lVvvP6keKSf z>%eHuzY}rWT)A(oh8TfxP7p#Jm-!oX7u2~lc*Y0&ojXcUe|7kZd?!| zYSYD}$} z#R)z!Vp(#O88{v6-cW9CiGoNfrhmx46{^NIwD52*@1L{`Uo5|+FEjDwH-bGDn|y%VvCJ^rX94#@T{4wdx+MoHf6dtL+Cq{mU*4j26uh< zdB(Kl{FzTUZ0boE?LLK#k?tZ&?gc)Xe=C1Ar<_9(RHA0&7Lffp?nCe( zEcR0WX&(b(rvq(^{fZIZ;doJsC;{DRnee1LonZAHy{zlH&W&i1~ zOTkwwSZlR5jaUYv6*82A_9uNnEN`gwSuTJ_UKnGpAd2+4vX%B4<)5cvCGz`jb@8-= z&f3$R-4r3D+Bp4{vlZ^?v_3tP_$H1iX_ZcP2QC?BS)MnQA2l>f)eGrC5x8!5??9F` zOcd_Jat3%?xR`q!7ZOi2-3YYvVt|3hzJPe89%@)Y(&P%Y4j-`*8eL3v&HBXF=2bex zLDy>c(-9v?Yq%UN=WNI8$4_|0I%BJlur6z(pl@Us%~3&esQ^Z#XJ9atQF&YL7Wz}0 zU8aO0sbfRoES;_4>QW~D`&h0s>_xXLQ!3|SaEuAVnageD+nb**Lb{o-KWwGAhfy+8 zb|=J5c3Tj?_)@?dDMT%3RcaL$W;~pcNv_S-vMR-+Ef`M)u39?zbthxq-`#k$taH~) zlB^dXTI$ec(KE> z)!6c;fs}FEWx3fDdmJ8^)?^a%j@i?0Y2{;AqM43?mYLx*Z{i{WT#=E|L5sKSX7js5 z9<8UHa!Z^az@-B!%+FE=S|k~ns29Og@5du5uc78(uDDt|7b9=+6uj)oiT*@<1X6t) z$Nar;c_*0?Jap~f<)zFNNkDD;4^d&aX!rNkOf#vgmx59tyGX9_WetHh#8cJ^1|+Ca z>`{%s*WD#u6=JFTXW3%;%G)9!#tO~S^5JMJzfEIh+w6cybaa)3`R`d%ztV1eL>#2# zDTsJ;@iTTFfrs(Mz0dsONObycM-EuBG2MI@z=leb1Np;Xf)&_fVmvxA2kA*T_aVB= zst;T6!(G`W7q0rjKX}z6(TE~XwX!0Tv-KE797Wmqk|q}9m2@PbW$yi-xY5E}%&-SA zWrna)?Ah);m_C_v()krY7%7*L#b#UaKIUI|z-vNvbUeS_NY-!)N^ z9e_@H@imd{uG_2B{yTEqZcLVn_n&9GBQV>f;ZLi?TmZeVk{c?XUj6XcU;eY3AUit> zNjpg+lRpfgRtBCtPXr}Kfqaqo{J=?T1d7(~q*G0w^W69ZQYxPq@MOW>Spv~3k=N57 z4~C~S1%0tyL`#))FK^(W3b6&!i3V11Xjg&c&XHqz=4W{`01j>&11~+kGYNESNQgSY3a>lF8-{P4y|JXRcPfmK)P6mK5Tkjq94R@+ z_g4$41bz`C&;FEf(S)Vl@$M9K6?xDVd>-)NeS1(Ua7N0%#sjHPe40?g0K{i^t5F#J^6kb}1jAWZCh3=GS9iJG?K}db<*R~B$Kgvh zf3WVTC;=XW=NjFm8Lu(C#QGI@QUp#L@F!P{TtwleI`!}6_%4qAjga7>?r5uxvm@Ci znA70LLqxZs#(>K-)i~y=SHTifDkU+Qend;6Dvu5@=Kl^B2Uh0b!p{_!wuP?dza1s4 zY49qFmBW_HU21-(N8lKrKP^vVh@)XDuxsTtyMHy^^%!s-Va%7Mf3N!Z!6pS24>!9W zte~3CmlYio=^e*OR9Jl7_!tq3+fv>T_?J;Ew4ya}5Q=M61eQl6gAIwI?B>c2Rt#MR zhtSLJ4)k}7Co*LtB^My0Bz!==!WMQK8^pfpSPAHq9oRe$UR`p zJm$&SdBna8*50*TN<|#KKu!tUkMazsE;Gef`a)sana-Y?&VW5sVnW!s;Y^fZC?I29 z?x-Ta>3v;&WNN^n?HoZF@8s>_%yc2M-uL=BML`~I?R&$tj18{x*H)I8y?=eZ_B=@L4B50udtUSxae-F) zDboZSH9y+51I@pL)op8y*q<^XXIoRtQKwD2U~)l}+)81E$6VCxJ52vkPp(|EV^64R z{JBmM-ft%q3t5V(#(9hVsh(5qK>G}5sMPxlpISXbHjGh?$Lr<4OPlDsbO@3-GHN=z z3%mOIHYMAh*ANdRJT^@cg&M(l7}uh1*I(;~Bv%5F*J(w_Ok0ff+RMh`A`bfCl6FPl z`NRPQKZ)q5Sfv>8Luj@|F9vmg#1C}BM;yEnk?3F1@54{}PZzCq(W(U~fs|wO#grZ; z2lqtSe8+}k#$WqRNQWO&xJx)@FLuU;>_sop9v+`G`a}6|uy2&Q$cWyNH13I;Q1Q5m z%t~E7TU40H4c5ob-_{Z?10ULF9_|h0$=CG5AEECWL$d3EQ7J|-LwJuaztOx z%8y5ZWiL)O%TO>UFV9#5K`u|Odk>jmf<~9p2DfEv-wDS1s0Gr?BPYq9-z%MytnbD1 zOW7%rd(bjbD0Lh#Bs82*D7ObxD)Y%*X)vy7IE~MQ8c;5|`??GGr<}ai+NY7o6}B4N z8OG(y0<8qc%ObeA;WRuzQ1@E*gL+A|nvS-s5&ck~)akSXFUSu(CIs^1Mb9;nZ0HGZ z-Eyqh!`IWnKaB@2DBd&|Oa>z;-kVNu@S&2~wvQ+7 zqnq5)nNzvA`t*^R2kwOE>R#~*G7Dr241RlfR2srcy6qha6ZQz!A)yBL8l>O^4+|0; zBRXaAWkIR6cZo%4(XV#TZ=OlP_TxVopqmH5q?35_26X{a^91+)8-j@|!OTdLkH@lExuJ7#^Mv$d^W&c@2Rsr2jn7KE>aC747QPK#W=~~bYvFxHv)+8x zB{X*Kj6ZOBr?B}oAFPw|-}&EvBT|Akh^=@he{FGb@F8La`I;)~ZlU+=jry^28z%}` zR_%eQLN5<7tjgh{I;o?a^<`w^<3<7I(@owkeIfY8aIJh@_>Pg7*4#TvTwr>TA5i%p zCyTEh>;*@6Hk>W~|EmpmHGuCPle_r1J;uaFVHN*w4FnG6BYLy%R^hB<4jhhh2s>r< z8$?XjnOXa%3`)SQrZ5hbr+0v2BRJqah%WXGS@t7_>z$UbejUl@*AyHDSEPMOuCAsc zMWUIcRM&d({&1!9l%_tUD-E>x{Eo$b zd{O?%zH7T}(SP7Lw6j#X6~Q?J$=ia*GD=t*4xT}1RCAmV$=rRAXx@<22o(x>@0w-X zf3b=By*NN`Biy%042 z1~JK`MmY|e5qQ$LkP55P*K%nN0VqFXj`BXe_U~(KbYvLy8}?{f2za8yij&EQLIy&N ztEg#lH_N=jW0Zp>DX3O+Ya?h~GyA%s-os$%?{+#va zX_>&3I2sm_h7%0l>ZXoq9A%zg+X1#{49(CUwQxgvAiBi{4}vE0G7gQR*lfYxHwe-) zT>bjbf~)pdB}zVWbVQA1gYJ_n+9XB`OT+PzV!(|Wd3WzL+>6YlQ{f>9H^LS}`-Jef zvIbuc)C$qz|Jia#k?M$4%PIQq*6mdWQ=7cD&81RG*kVZj=j{N4#Y-K&H$HSlA1n*x zTjb8C;C|>n&qpu!jXTo}?nIBo4WY}H11szmUx6J91?v;B)&DuHiPvHSB%f~$@z03C zv>2gN89#hCAoU#v{4-c}`rF-hUE~2Q+*M9!p*EX}z`IHQ>41;S3V^o9S&^xK@Wu4B z`Xp1bKJ=Jw=gUNq~_d4NWyS z$&d~LRbdDK6*JW5K@>}k8ieC0i7wy3GtCIec!<^qDzSGQ30T?Hoyyd&pw@&_ZTiQ9assNC2dFAT5Z#^ zm2A*Eiy{!Q!CU#3szuI-i}r_ps!A!uj+r&SPL=mpU#Z}-eWLVx1r7!B($#(~fMUGQ zFs_Ojo8=T6BRN3@9gSadchDw%@q)R7C-tl`4m#9yXQIFYDkVXQs+Y!&FJKrxFC}V# zz2`9r-*7a(l@G8*syhF@qpnDm7{dAxe8>lGMcCVL^{%A0e$MRYr$5sbC^GWzK0a8E zgIn}2=r@FM+>rhcO=rOs)%$i~a_FuZngQwV4(TqXySuw#1cnAdT0l@hK{}-d7`nS# zLILR#gm-@bwcZafv(8zk?q~07?_o)KSl^(Z`*+}kupZfJyv6>EXn#R9<2^TCc(cY{A zEs#B#5L&+HBRiuAK)N&fe2Nw~8BPC957+gG33W1Sys%jjzxa1}7TNLrK*M7b)t>bB zpZZGNaPZX|VFN$?KZMNR+}xrXrg9&)RNoLp)yJesRE^@sF|u9q@~Z9WM4s8sp!IkN z9kdrz)Qo4Br=)~Yxw)Qcov6|8zgRd7O zl_02JW2ff~J217$13l!(rEe!bp6(@%q7-$k}&^ohz|v!~}5U|wB@1@tB}5@Yb) z5{i|;hZb?WC9*xI^Mm z^UJ;2So(6sOKnF%B6S&25>@aWCy$REgDD1Ezy&%_ZJQmS?K91$aw9`3y18{J~1-z1fWexgwdQqgS42kM;sB2g1r)`@-v zy6HPgOtPrxYN4?M3e8hF`%L z(E@U0hbrdYN$X}{>B}Uc){z6l40n&qxSIHk!geI`S2On{VCdw=;5}-A#a;L1+G=w* z?X-bFAP|uuA>egIeED6HTb4Y|zaW67$$CW1X!3Z_Lxn?_mX~Ec?C|WziUlHyLdj_$ z_-hMqGrw<0bAI`Pemre&%8duH-%1*4Zkj*cgF_PHVf7%)85maPm3A5&$U^?bk2!)v z%tJ*zV1(9*8iamtqGxrQ*X9xY!xoWz(a0O@#GMv)j2a2y#@GDH^_bc19c5LUAO)o% zU(VpE+vA|CKhPtZA+3S8&4%Ini)~JwlDTonnIW2WX#a>;hw0=DX1xW9U2y-jwPhs(nh-|B7J_bE4Ah=L(;kDK-;Le2xL?LEnKxX#9FxP&C#gWeM%_1S8J-;m$;F3LHp4q?;=ob1v2`!$4u!Zy5 zIPykbWM=47Y*)WMgPU`9s=XeaXXO^y>tmh7>5h=V@g~QwfWsaZ1txA$dsHAP_ z7k8x;ZyH$;5d#(yb#WedQ^JMCSL zhu{aY;CHO+3zq*>;1stalWSJ|hBcoZ?No)wUIxkH(0Id|PV&ZtsrRo{2;-Al%@!Yq z!^iOj)?M2J;?7!nQ5Or*I)OE1$CfxRPUx*&qNwr@j?jON72l|gXFfZ_Dx&ORA7TtS zy|hV9V{#sH)d4Nd5zD7xsp!N3sE^(y?nz>>nl&&wmhrA)<10#xWD)JAY(8dm1#N3i zNy1$T-VkrD69(#UEo;e!jmKg~^>1%|u9FuYRBmG*oiwh@NTnR_uYjHy;-tZXuq54+ zq25A)z89ObiT>jsRiS57e^1MLvpGi^_uzT*%&+OA-wA$dl|^*sn{9J>IM1QkN&sH7 zbrH1Ag*w-Ip3Sv;hB}X_tGmUkJN-JAHN{NWhi|JN%cAhv!6u=ZqFROUOu*RtNwLSf z@E4;{^`X%WM3VZIgvnIdP{U+hWa!z}GoI`BGsirNQjvJyslh{d|Jj!zqaWTc7Yqs` zC|?z36m*LO$R_Bz@-h7n{(U1)y9nxurnDV)G_gyUdV0XKl`3+mUzffr3yPjyzXX5w z_{w*l4@hi!O^u`lp>Tdh7br>aB{!TI%RyUH+Q_$ie&rl;a-QzWaghgFSzfT_qY%Dw|jnbIEiYP@)yMzsNUuJZhu!e3vc5qHE?Rs_}lwRq8Ry zkg15EF6rH^;H>+!BN5w0`;XC1(fPvg@v9rnyKl}WeZdgHZy)ML`E3rj`#iqDv{RY6 zI~p|UGAYjg2)o89g4dR{r88j-!SbvTj;DO3Yxwq6jYgy!>#sUKCOa-XxOqV0a*L4EoXG1e!-nW7|R8;(vM=+k5BxuAL^{ zc^!QXQvbaryJGMM3_dCxE_=QdwDkg+)Oz;#MxgaN(`{er+4$T-V3Q97MAHwr&L;D) zTv{2qE{oWtF86OnmrlLsE$V-KoAlI=$l5M1w*;1ApCQab?V&wHK<5Ym z+9G|r^Z$N3wCA17R?u+KpwV$7Phx4&2#>IByQ_7YGui&FNZ>PLcTu6CWa{6erLA8i zyeBgFf$AXi>?7>d)%28L=v0&?W1o^6EHWA-Q^dH)c<;gchdbwCF=xxMmU>F~yVD#q z>UZbn9uumr%Zx!&KMd9+XHG!`rZ;siyR^>*$y3O8EOlYukVdGc5FWA* z{FJ;sWCHJY+bHtonA*`3iSSQXjGuYchUkoYFym?hejj>Ua2ch`Kx?%6tLLj9uUhO& z*97%UXUfm8i!7I1##nxEWo~3g>I+n-?!#(P54TbJdd#m;|KzQTYOY)~+21+Iy+60z z{?wfG&=ZGqPoT@iL%{S?Zpxb^zGl60>=ms+wC|$1t3>L4$KYrK-alsgY_-lnL2wIV zU2o}KKX6v#-Yi4cV}QThFyX>>-M~aCl5Yqu#OsWjaj=nhr`Zy-_yE@iRH5bAn9;%& zFBR51^=_huv0Bh=A5W83q}ejp%Q*uJKiUrN!}j@n+Ce$UTt1?I)Q#VJeutw_seD^a zLG_^19wGuwD#jRbJd94&s}3qFKBV z_7k`$D_F+MaO8f_?j87NOBiI5U~tOXjAmfrAY2VbLQG&KsRNZf|3Y=*$oSAb$~1^g zv=G~7Sz?(>U*BAnL|1e|52b~ga6+y6Kb4 zNWZE_-$Mo!oB^4HDZUlE=Dqi;-H*n*iBT1JwC{t4Q3yU7jFk<&`g(!Zti4tB zLmq1hRfJL6Ny+%!eNZ)B(jeeUNr+UhoWi9|Bf}mF*!h1JAduY$U0P&n$hus@UeYmx zLNy3kSN^loG^vkQmi&cF6uE#4nKR4@mU$45&SY;udYzBcqaHNyKnvOA^zO=%yV8e1 zp)-|O`0+S=@3#~F&haB_^(GSz;6gwSO$vM@x}Hjm@+<@uF}cW|`eto*3=;9UHXm|T z1Pi@JGRf@mXD6P~fV~Q(Gp~3FS}Y`k9Hx1kSPNK`$T=w(DTP3FY$Mwuh-I__jeHWR zI&cFDf&Rg@ScsmX1wWR}*bho4bUA;n9dt_Y!j8Vu?8M2HM}MNJ7s|euWBA0fs7Iwh zlkw})b$g^@w8SSG1c*JNPZ#gc)cG3Z$!lUKNSqfxV>5`W=#Z;x>8<$++MC&xb|8Kz zyD1I-q~VthNs+*trEZ94Ri#Gb9V;2a59Gx98{@442ETL?i$mdXQKlnCy+onshaVO% zPZw%n%b9XxRXc}v*f_m|5}vHDZ#^+cM+C@4%w^0UaC5jym_ge)Jiu{4*d0KvvqZ}g zk>edD+o8CcNqmY!cf4*+B=Iem8h^SOUT{M- zi@qnBTa^&)v3j2EpyT+xPzls1vyY;?6JA8;PUX>VTCq5PZp~iO2HOAzYHGK8Hr!<{ z6ue!2`*Sw&IRa0|5^IVh=YBG%zZif+^A(BXz-CBIHZr!Ze?W@+B)5O3Z?ZQaceso$ zHMniM48u}@S_S2l&xc`fh{zFnIEb03bwgTVf3J+xt?0FX<$W$x#k!;zJA#emdo#}S zgjG0y{F%mL*NB%ea1e(VI4of#3DCiE6yoE;Gqc&HM48i&q}q8%k7h}w2ahdPmNox| z8AQoV8vuHPq8k!?{3<;tlPjbBOG{bfqJx{cP5b}mlMoBMekTsTL8c^i()&Duf(He_ z{ZMY8;y#~xlAe@10BYVy&fM&G{^>X)1Yorp(Kn~m7&wOrn7EX)|L5)u6H}Jz*CZu2 z;EjS_=d`@)H0yCs>s%ukm;w|c)?^^@bv#}|mn9jzE+d?xi*hq}$clo*bR)&HF9vM* zFofsGtt1DC9etKk(o^u{<;2S(rU%w@x@e-|4C`Ur_Y-?|B$dHIXp?$Bo2&}+6NtuO zatR(+#~u!xP#srB3iXsWE7j&l(ylWD^gqnJ5?mMF0@B!$jQ4YMbU&*;@GWGJx_uR< z(7`LmMK~}Tg0zZTTzmhT<7F%03*sz{lEiSz#V1Jj(SD6bUWuWwD^sj;DfrIT}Msvn0sbR`glC z1>e?Pk#&YYjd|Ep5LT$i%IB448(KDB@HkGLEbp2buk?^t3Ac34)XvS`F@qHkH~m)T zzdtauAUxYzy}wb$34Ah?R}G?0UkFJMl735XU-ew;`BMV%Vb6b`h#jfK&Mm~fJNFai zr>5L`@!|#KvkHS{JZ?nXWizIdl#MvPauG(8oy~7XIq0m0taD6Xx^1#9cs8}(&;s~H z3UYXod|uj{gmt2YilJo(J3s_*B(_FEfp45pwa=x0ms*KKGciHuNyS|!tShF=~&{dfALM;62e(_9K3NQU;Ae}3)@3fC^)eVQg~&& zR4g^GiZK7slsC@qf0&9nUV6JyP`zH+$P@usuWMOYg4?BIKmY0R{ab1=qf}n{UOdR$W8ZWy_KY%ee-d`* zEG=xN5Q7J2FA4Ca)1yB8z-TR;Gk__Q@Vv*)jki9K6sflC5-X*NhjXi>YJ3@Uy|pqm zO=Gcb&&Zhhvsql*LJY+~?;YKZouaBOkEQ7y@^OBpumL&hP#YyrmSjqGTd2kOvdjIQ z(9&uZ$--pj0DJL@8lA#`uPL2^?MfRzj11~v<=H}qXV;C#=FlqgAskb7Ry9X`wsaDN66a5ij$Hfuf^|zSdDd)m z``wM?aKGfgoJt~GS6!{wkmiPewier1cl8?mI0KrF?;>=fV}^b|@`n5*T-Bn^y~#(Z zRlHE!jc9-bom`d3Ip)uj{66BAR}LqTf2N-ZCidQS@2RdT-Hy9 zWa;0NKR5g(Mjdi2vpEV2sli0V1QIX22nklqXvHj^uMzzrmZlCC`3>~IE2aZAPF`DD z3sy(ucnUD(d2Dd%>!Pi<1wG6d$bS?&S%XsFu|Sry`>y=Y*SC0Dmf~EdzI6z7nQiko zx>XaOIp|1kflXadwj^fn-n@2sTmA)*KUNxx;`{nq`djpC+eWN;DnSKZx)SL=TwlxZ zaP+8pK>Q%BK$Ah#gTRS)8!GkNix6P!)&P*Spe6RTNdyW;7R0y@LHFrqLRCKq(^mEAX4?x1z!Ns!BsQAGho%`(Y6=tEyG$ zJ6%Cmr6U21)7#zd!&1qL3W>*YhAW$J41u1IDeDp`E74^OZB!}Ch}N6bD^Tj!jRw_5 zSM|btv`NH>Lc|EthcvrB16(U{!jP5ICq z!S>^Gfc>!+$!V`>y3*>^jl-w3+fPw`2x)9Haa_~N0zUK=$(Qdyef$+f+wf_e36&ea z0e_tU0nA5Hw~?K{UTU29J0wYH4$vNaM+dktN_OMPdhp&Hl)OdK0ja->4g$;CXJ`Xi zudytq1>SUK4*`*@OV1sjH=lgPni?*BqZ38#2V9K{UBruIgt<_MF(j9oBF5?7(qUZA zxF6NSwha4hSzfIx&vRU@^GlX*vgqPQb0_&Z)FPU~WnP!{BDO~x7Ubb?F&Yiz`+>>i zFrJ$6z&y$1MZ2pR^n$buxez?BP992lYSY=hfUC@*Q&Xos+>=lV)dIy>U}Ah;slDyc zt0-U4bWT>(A#afo5BZ%NuB80-iVI=eh(i^vLCWoA`7?@KH%2fOz85F*RQfR`d=YV? zIecSq5VM>8yEQTY|rV1{?C|8Una&nY>x8laSfZ#~GHt=A$ zG4;G{TZRYv527v~m5`C-O($dIUKL)}(c)iDHS+b6GP=BTmo{yS1cN6ScB#{9_ibhh zetWUy1!$(I)Rcu1>Cr2p7t6+Uv=APpqZSq2-n|R{AH=Lf{7QW*$deyrY!6Mg8{8z1 z<8zBR^S_c&`7`bo06jsqyD{=Bqn<7i)%&CAUSIVl$HEFKkSqAl3qN0m&2DlAwx>^E z;k~i64ak^SGM4QAm?+jE6FBQ+_%jN9RUJ`=bX^xIsOSrTgm7G*`5=`a7mdr6i&Zz6 zjkVMp`Er@p4wfrDzk^jUJqv%|_l!eP?uR{9Ghhq!!^|X^WGO3$UqHbb4!Xe=b|pp^ zIYg&qovcb|qku0*Iz6;W)LApm5i)m_)X?Z0$TG+(kZosy{&s=v7aJP>zE}by8rR)! z$d0>R{pEVA1($`cGvsEN?BAY7*fCh+p zuU=k0b*I*9hD5};uD_7pb0xg|@JRT#5Jc_p05H!S`1|baUbP`kJCxhNM#Y0zd*;t& z#Yg@7`0=UF%j8A_wO)R=#b4d+)Z66%%NfLbFZJl-XMq$6O6F@GqG(ypiCwZ^9qn_l*&siDv-cDcc%z z&wljz_iwa0>GV&6$6OW--B{F=HZaUzv+7^Yh3MchwFip;=3TaCzPY}GNS&K|)xSA~ z*25Gh7F0|MYJ)kF`^0V37}Le()xU_JtGL-0Jgc04YW^NDqtLpqP``v#0QUu2vXdEI zeQ;vdzWUjs$`WU+v|FGupW7oy=nWEVwx($M5%Dmfq zKLq*cCteWOVPsGWVrdPLw1bPnZUhJQ$%EAf=dv%ySE-hRtEUzS2@ljqG6gW;ersrJ zB+DVcA(9tL#HqBN|6Q;#Haeti%BKAOgKoU_yzz4P2GnT&`dzZ#Uh)s6m4@gtqp^8- zyUL7sD25S^w2|q2IGFyE4W<>I+X#u`7JRVCu$S7h9ppEncn+e$__o z?GMmtN5KG}!h&GQT+Fm>T?;LE&u#&mXO*)#_^77Lbautc26hDh%qdmE+h~p+JPHQ9wfJu<$5D>>0<0Bw{H zDE@CVsRXPU8MR%;ksHDfR0m!uP^6DiD>)FB_16%ijmoygh_{~)6AHx)S_!HvOM0jl zA*~gBq(ajpu_r;#lXoi3b>QA)#l^UO&v1qI3qj57VSfg>HA8RuAM26tjWiK=dV+Yn zD7d%wi~Uj^J?~ZX!i*_%-{_6~&qsYmMeaJ-vS+D$sok{Pwhr?b4@KIm8 z;Z(bG;!kgrnUP6eP(iaZ>-nbNH=LNb#(reS2=6CPNN;Eatuopi@^#V#0BfS*I5c7gXKa?S9@Qj?tj+X7c3Bm1p8u|k?!oWKXTvsqPOJbVwmBL^Y57|JRdmiXmgw` zI3t7$7FJS<21g%2PJwqbg3mjQUey?`8?n-NA1&wU-on@LGp$;&%H7SN_xjNH{9JEu z)k)(L=1rojRM9*3Pxd{wj-B)*H2^w3l<(#y*%i0s)8isdo^SS)*AFktbspqQ&Qow0 z;UB(_lJztAu=vHUgxxE>El(akfzCSv7h4gyVD6QJoDttEnd7~P{~}Qw8p*CPbk`>- zMl;xpSnMgJeX#78YBj!q6R3r;0+&V=nbtJIcmNSmL1X}h#y$FB=NQJ6)U?U{swG6ENYy zpOS05N!%?6>f0ElQOI^do~%z8IvSxqh zbxAuv<&aRT?nZzhEkE*qGc#KAXr9J4 z+J^9pl^^!sEH75sKuw+jp6;~U(VOLOkBDNHznFLipT(Fo)CaDu@SosL23ESs<9IeL z$?X8V%PaT3N};We1%AD@*t4`B3D*v=xGtYa6M|^kBr~49;BC_bSW`FkLDW&RY$zv# zOCC30qZKDKBM-XbP?(1m2SCMsOftg`Cg;j(5KZ^>QQxu|crA^HKe%Mo$VfT#rr9W(sCeiuvoQBc;#O^q+Uf&Kif(4j!e$ zYk&Vpsf~j@qV;rEX5)2)JQOBx<=p2OO?^jrWmJWK5&Uo z*4O&o_M{8CBy$xW1Gop+7NzmiefO1IF}lgmh&aR2d-mN_36HwdGOqR@!*vWmDE zWfR3sXiuGnW<40Z|EfB~NNE4xINoj+12$6O(2nmt@-Tg?F+Jf-<6p9Mnz?Q`8l+2h?F_3*SB&_l( zxiZ+E{0x^#ZHYR&L;#H7$i$)7Jv88AGhfIlWmOBe=Ug+u61KzeLbCT7exuqKYx!eR zJnr$yDe?*dmaoW2mv#v2X7&N;B#A{eC7{Ob6na-djX~_H2U+ zJCbDaO39Z|*6q>%8^3A=N!@A9@Z zBnNyVSlnO42Gie{rj;f(3f>nHl9~6`W#`WFZs|1!II0vT@)dVhew(qS-TK2X%7iga zKCxGiRZ2Va4uXFSqHQ6I#`nE;N7JO7SI4-T=~n4wmBdkk`*#k z9+RIB>ll3GwnoCVmTtRT%-qPEh&*1=`>roE^(ioIA{imu(EQ7LFBswt;v}ciMkq?R z_d3Ze%3In?={EZxaT-vPeUE5+rjNQM&41EJdJD}v(aKtQsj$=y&-#ArtMt(ID9-oW z+(R}M-iZ=ENL}!Y@GVI&_Va);v_RL;%)2fz+}87NuL&dvqQh+45btsuV+Sc*?-|d(=8j151FT^Ar|%*4RU$o zpp%MU`G@g#s56x87vm>=+LsjL>LCr%i7tvSPV-E%ztP{J{#oN<)f;|-TFrA1^Oj@C zmdX(}c)vox%pBPLq>SPLW3oAyyQ3crIS0ajVwA}%+-;+u{NPPQ7B7wL?pH`F=||b9 z9m6@ldlNhTM@r#NA+eRE05PUJ3*-msLklZlVjx17PrYUdVla(l2f#kgNUuxAr^A{u zuFCe-)qfz|6wUIPTw1$;s5~_zs1g0v@i?C?cPV;tsDlZ>gzoyoD}Kx3k`8d~H$>5G zFg4hLkD6pYuaadtCO3A*E`vGvNpa;c^gOI&6sRwgn>{mRu4MCpPw3@kJFH+`!85zy z4Wu=Xvsr)H_C9E4E8-WsQ#aPa@Z-aXbGP9A&3%}?!CY@Vie|64fuROoy=n;nuA(@{+da$q9~{k{w=@JcX=}mAxUcxFH3WcMzC9 zb5ZgjK1nU1GmCYGUN*BD)-{>W`r>+w7b38y8=azXSm)eH~-uVE>Lt^LDK*EDHg`XCqD7u{|pUJUr78JA1L&85>KLs_B_!DtoL zFwxid+9L18e1i)j=C)fGTUNi8Ir-ka-aW^cOa-6@>zSguC1sqll;OJ!0Ni_>EZ1Dl zWb&udU^0G`_%TJQ;|H(Hbafo%YxUGcrvqem7i>Q^rVX%1mlJX0pF6bIu019k5qAQU zb8LSqqIA68emi>dfry1vHna^dLQ9=Lkz5t+D`?;CpA~T|Tt)BdHSuM0s0HxHe+;@c zqh;}9n?CL|Nmtt+Imjd?O|_*j6u?$JI6Xo5|)j(O*k@>)~%d zu5Pu83f(SXWbWdI=YfDFRLhi%Df~mj{DwVOQl_<%B_~t-s{r81^C9Tb(4#3Q?s5E5_}`aaO=lX%k4^(qsTCU`X`7@Z zEy!a_Evp~*f~%7?1Ljr@Bzz^)d`njlifKp9t~>D(*aLnqwjSTCST{o4-FzS(YE!yq z>^!!1{jPTqA(s}AY-DFHG;~%|aQZADYHNEFJf?!y{`;s;-s1=uAP17CXm7SJ|6uuH zt}oo(VpF!rxcOC@o3Xq4(*s7(4m!|v^!NW(`?db9JC-^t9OxW?zicwR?-9C79>1lc`cfAJD?GxLCO8rXVqO{3I|w7T#MC4bMz43~L}&IC91}M8 z96^1Ce6!5)w)!ocR7Cwg`(ftI{_KdW^1D6p&OOBBg+-ja5>&e87R8Bt<(yn`5gDi= zNipENVcr?UiM)zCeu@=wjbkwxAAz*d`19?ewdp4~V;Nbo=E`}%81qDp=EDH4=!0)i z`U`EZ;Ud?81PjW#+l>QR09pGRF`(fS%H|LOLqsXeAjyqw;d~>5+zU}1wlh%Grn1Wp z3EY)whusCkA^fyz$#mH+4;OEAc7|^e>v>XmEy`H52(osrk@j|ETFdM&1tWaa@tv_4 z*K?-q4WMZ{L^B=*g?sCBBb%?LqR*+s`R9g>nD26KZ>?NS#v+r2rgs!t-%|O@C5I_^ z`7*0);)lJ`eAr@{UA5(fnR1_3+v?DXn|L20`q)hJ+pM5Wf4JecV$%}Q-&=VcLYuqu zS(=F}wMUEUK#X(j)*+BgagI+R!TgTQ&>DciN3lMAc5F3(y|0cgHvZ}anynsFt}YTb zsIVoQk;wrYKX0Z&r5F?*gkra1`C7D-VT8UF{prri4uz{sF2jUM{MXZYKj>6pRJIk- zbvp|D*lQ_8%9tTbtYED45t#_vVV*=4bKY*Lb21EXGYUuIJp;`G_X+zBI2TGJFf5CV znuIU+K1m`LwS7>7aIUt8if~tT+L0UjOSnw_JpbXJ!gRcM1ZYfYn+xG4u=HpC#?w=n%h%&<&fAblgqPQg&)x_kySrtbb z-+(0S3skGO%0ZeOdliokgG_8%hL#cov&rwjxq};_t;X~jM<3>01NYAdSMBtD4F!AQH3tL=ty>9)9vGW(!*IEv^${g}3@h^K{6*INPq8Hky)eJYgK9%7ld{QnQVck@)ko<~J{m~0EIV+<}W3!bM z_yZpohsMtF#dZ{yS(r3I{H}1u28A4Dn3OmrkugQYxK^k8X`azZ)TK~2l$gfhbBsJP zbcIqF_zJARC{!kliiKfSv~AAJ4GSXMV}Y9A|8;MZnpasW>fgfP(Gj$piI0E=Gi$x2 zCr1&O%{pNEWNhQ1k*96dl7J3H2WmQue+A#4^&c_l2{RInE1a!TTY;qKMjoL>1DO=1E+|BHSS zEF*7VlecWvD#80-7};W3e*{Hw4^TI^#)9ao-qGFJbe0cK5(Y_Y1~W(72i7_MKMQcG z8m;`YBVP1T<9W9l>E4D!WY{Pf5>wp2Y?Toz{$n{z5DaJM`!M?2a7x9k7l(!hiJT#V z_8#4;yYo!OCb}3ttgpIluXpg?D}1bJyE=EQ=Lkr=$NH(f>+!PBIQAFmm z+np*=ULkBVlH~YB?iTIjz)&UR33K@IQgSACe!(MdjCX*d?njY5B>qam3{$%fu(rOH z^e$zmmmb0SM13;be@sgw-#(*H+at~AFmHa+uVx4=fLTj_I~n)c>jyZ=uF%7aIb!3| zyOUr!?_a0WE_yNrQ$RVEgk#o<*i6LxFULaegPdBQ;IES(kZUr6Fa~4qJ9F|`*>wtf zlm2SP#T;cE(Vv%sr|i7CbFR9n^;XBc@UhMWE|95zv=Z!f016Tn|9}#PT|3=wTw*^O zUi!i&9G=+!MD}dK4dV)i5YOSxfV4FF6GI&fRC}WvE}W_?AwYEEX}s-A><{}NZZl>{ zr<{8V-M0B83p&ynt!lR4;-bJg5izpRKiFdL35q~9A6koV2!qt{?a{*T#5?ZK6Ph;Z z5)fm&osz&3V>U9~cvQMBt;D1BpgH!szhwAbZIW?F?{w>~y9ArC(@kc%#N8?Wm za^Aa2)LzSAjL2sC-xHNI37&%`JmOAG@zFLa7~dWQ8|sJUio9S7X~d%kCGCT`{5-B{ z6jl)ZR2@6V*4{DQ6U@4T^zUQa`-DLOoF#h@_kE?0WQ;lQV6S4-i9C@f2hJWD-~pgC z3?9i_{RDUA(daIOC;l6J$m%7G@6iRLE{s6_V~B!rCy6eJED1_>w-35b9k|_{DH>v3 zgfBc1bwP7R7W*Im%IVZ)IWzF)zzQ*OGzz~UNB&_5)B4Tpn_h*YNMgU9Ai~Icbr<5j zV?zAn}qBX*aD{L_S z>^oT||DX>ju}DIR^9~k`lwmx(Qzg2#V4`{IF9bnM*)Ao#Mk6Imy2J_si4NB;NG>ZJ zqVHyGXRJSA`!U8tDgBgYJf@|9$a5Gioqc8$iomu@a%ObMIdYY50PSR z*AT#Xy@XAP=io%&^93V5^DJYT;H34PA=D2-VVCU<%oR@SxQ4L!R-t(O@l?YvL-V1x ze_nlx|Fs-IB;1j=V$Xvltj^X5;WHg{Q*25lB!ZKyD`E zbP<3crbY5)tW&3(QoN$edGoO`5C>%BOEH17L!%NNzN}m_1y&^|nY^mc&!UhQa?zZ} zap84g!WRAuu8B8pfs5LKDgCfZlmD$y?nDKTH=<4sLOIw&VWu42+`o)EYui50u-bzMw?VT)RvF6ekAEHg$DrW|d`olE!t9HK7t$*1A zOQsO|ns;a|yY<%wV5|9^<>&E6yQ=`~3G(pgL8t6oP%?S1hMam!t!wW~xcQ3^>zGbU z-1y>+$ZB{Hh=hw?GGSTues884mou#v zuY7OHJ-Z=v9%tvbchJi$V_)e`U2vy}tYz{z`^#xbfDJY3U)aY5Q1UJ2;{?vepNtC^-T)5!K$&52ukGuztI;4bu2Ji< zMEp;0x53|fJqFbITTB7eG;Aj=m%z8!FZ(})yewfYy_7q9=G7jfaV?|WF*m5rJiF)J zvq}9P7_i}t(^!-=!>fz1zZMHOfXS502tG92hnu?n;ebTR5U`IifB7KAx$CVAxzzAh z_e|1zO=i=2Id#6pg0|oZ;>X_#t&XFqlLk#+HRD2Vm1OjL2Xe`lmxkAyu-zCF^y)_VlyiNG@3 z?i>gDEYt7H{MAo*QkAK+-cz>mmr?k=v#f`&kSsD=U^3Pv0S}U`kr3^I_9_;rXu{v4Uu7(wU zVr#zpzFtY7{)Ad8h33&6ULPKbKtk>JY&nFF7=bTn|AS}-k3~H>3I8a4XPNB`NZ=|u zYU$KHwL{rCXere!Mt(LK+^Xp)LMW!Gn;Od<%DeIlXq@`O{HD*E6PPzoiEvLO3c92^ z=h1RE*0FcoTNn|M2m|mzp&3y=(oC9In2DjujzaC}K+h0F4`aTy;Uo#mLNWahBW3<} zx^VKJNpfr}b$$iosdaA-1@t%~PM+#se_I40WNgu#38&7pa|{B_)(9#{B+v?Qg%`@* z#5WVP{wGA)4RTJ_&G)v=pyN>3%PENBkC^BS2egD`PPXVVOGc0FW623bH-NMiF7yQ~ z_-05L{mDgf;th)?WcAEsfRgG8;rKz5@T+>*WSMFR&@4rY#LOa59)X$-0^La5w5^W6 z5?sRHocp_RRyAESKumv*)3;^Q?i#{63Kf-vtNE4Nky$ z{$Y7+iMcVeV>TP1OARX3sG!IcBWu>8Pzu2I$hWs9mVHdP(hSxpHad0jgfd#+GVOHZ zP^eb4AvyoITZ$yF&|v!wOS**BF|$>9Zy@8kvE@+Do2o&nJokl-d<$-`JbNp9NYzDf z+t@Y(9Cc=y_;}f;Df%x0I1Kulc7@UF?ThJ)a6TV?oCf_d{DwR>i~IKt7JC(`E8`$HF<_9UhB%$&6e8#iSV2qbJ*3*!Dmx5~mf+6JtG;XlcXZRSHX`Azb+$YPn1UKf>-wd z6%*z=&qhlKdvV7V7c>~}wJr!R!_HOQcempZXb z7iAs2p`qD-m--d{dCwK106u$dmcWOB)RWTzmL&ffs~S@uE_nPt6Fm{<4{Aj!hdWYo zC`dY63fqm?O*~udQK7z?b)guk2QW`bO@A5hntlF|fpp7Z&G`xCDHqjPlp2sHZybmE zivUxLUv|ve3oTx4zitTiQn(^pM^-`aKxbPmfdhB4@35_yD5$rD5wh^M#gTiV7cXAU z2GIJ6l9f4rhRmV_f7@vyvI)hT|tdA9xmKetwW?8?;5Js`}{+4P2N@sxESS>MvA|M-6#Xsu0sZ!M!qv^nerXIrwK5biUU+ukxU(MZptLezr=lHX*(r^+;v01GCiq(ry zk|!zW3}8WPrtlcFY8}pPXZ2&a&*&nwWyl=9^ZXVj_bx^XhTppd&;tIqxnqddpxI##vkM?a!?)#3u`%ZArRN59GW*tJy|B5%`Q3rlR1am+g`ZLGcho_TjI&mk2~k2CK#LW$ zmYQr__)fRFBXy%JyxXAVS44Y{n<&T7aNnpj-)4&sBtmX*13ED`FiSE*Csz2q(~^RH zpAp7xg&eG_kS4ID%YL!2hn{Z{kVejgzNxFL08R@IV5H518vXPV&f01)N%m3M+K-~M zVvV%+Xy0lOUvEx)X^8B}lPO-YX!Q9fbx-|wbi9hqi*gX;P^fA5iTaHQovm=N+YpX3 z`Gm^P=lnONPD&t43TkhI?P8Fw{VP9|j?k3Dp*8Ki{ly+O1QvR^ zwTW#^U9R?Q8p@(=V7kQBp^WpMa+1NPCBc_elx56Z8iQx^!hJByZFx`cq2S(&;Ah-V*v-;tO2VcQTdO!TmP&~`3V(hRnI9;`|OUP$ZsK1OS-R?&OT5MKatTw;|0n~(S$ z+}Ve2^);fB$(Fnz890M$kFGN0!$}hCws5!z#t-DNAw_7I3`f}0AgPz{5Jqs z;y=UkC%$B2sYvLy_>>u_KCP@86tw>b3GjI0M<;=6jCap%wpc!-+96&D1uF_TO1=rW zvcSbD1LKne?(m31^LB8Bgu@tQebk{xXSoa(@l(0!l2c-ZcD9D8H>^_ zk*KU)BrgK?uy0jZNk%!4R!k^IO87sTzQU`?_y3z5-O}AE%}8l!X+gTXJBBof)Bq8s z8w8c^8ZdMWknV=bC?y9-$FtA(Jik9+=iKMscD=9nEAQwFgH0o=`l@WPCs3{eLbfY$ zdjpp>R!ezZcvFe(og%kxJRA9pJu24J5C&Tpv0z-Jv}!P8#nc{-hDrjKh+>FzDP8gt z4~{iA=0?#rGwG@w6Y++q*521klB9fue>}c6pNMSG;ZP74r6ib#hmJk=!uSvo^ouo40h)(+&))^gKuJ zKj{v4E6W2Hw+Z+6);%Oh6A^i=0)T8RidyTcimEaC=it%YD)|*Hf+Oh?9ap13myY~z z{3s)23?TZVb;WtjRR=1~+l=Szz+TK6^A&dwwbR_sjQ=*c&^(0HJ!spiC=q=SuX7-I zDOu5mgohy6^wz)Dg_(e&LU5?t;K=`1+>D=G>vip5 z)XmN71%~MYEP4&}@}+zhC6lpd2A=UY3yJO9>__iw-x;XWKAx%YDM~u2x9NG#Ldrm^ z2u8F|u?;0VzaQ(*%ZDE__w&2v7DPr%S-WZA8*F zmmZyK_xHeY+p5n|?q{THEEENM}NToM?TuL(L{%w$!++9n=OY4>H6=UdUUJ747o%YlE!miI`L7pg;L*L4C|R;hY3seF&RF7`esg6X2_ZM(C(( z!RLPa@s|bS8eh$@tO3@r%)^l3Mb#}_`tFZdLbahn^{KG_RuNlbHd##;M+Z+NrYF>vmsmuj$w32u^CdL$<;NiUmml+gqvRp0DxsmFlAXi5>s#DH zzZpgVOz#shFymI6a0%7m(E|CyqD5ZA4E!S>-x`IO6yAqL)kJiCw^*yqntiR+G`~9& z-1@z1yv}gp4>>9sd{0!4NW+ z2tKw^Iul&K&rHjw&t(O>NE!`dQt3TMQxnMW$bp~RHU)J?!0#jIy&Pvh!z_U`umW_& zB0Oc1mBJGSqM#+3b7NCs*H!}(2JCXdzs6gkEd3r-R6 z|3oM(`hK`02Q$Ed>2wkvqQsEc4n zm-Y>gx{~7zvqKVJh>EKIjr*D+F}rHd6&_+wqC_ejoYapIH}y0DrrXM$N};S9!0(rp6d%jS-DYk}TQ+CwEN1QzQ-)RJszLEBMmYxyh z_-4`X(9#FqySFe|G{x3U5_cez7dt>!XW-$%Sw&{lku#){H5WA|yPF?k>61^o zdv79J@#1jvjd)`LAG%r0>LIuvj*+gu2Xvs>Oa(#ophDc~w7*QF2C-KBr5v8AbSM=F zN;%L;3HcJ*TVq*{LKk9!)sFU=jkYlO@lv+XVaDp(jN4%Xo_+h4q!>~<_PwFE*~RuX z)Uu7NvwRJ_^NnF#ioyh#54ar)K8T3o2)@FR`O|Lb21ZD>7C*C)S{tafDe0J z@h-prk>oCosYo9W(&1j3N=R$DUYa@uI@G{GX=H*XG6Y+S6S<>q$f6bSSbz@bo*7T1 zQMw05+opBvwzL9XWP^KYPgKo2RDq2;jd)E zhMR$RMfHTC9g)!7mdY>a#2Kd?6-P@gSMgoG6oBmRLEd3RXr^;FMnK8) zTcW^c@NRnLkoT6X0_o}nzq^vD_nVR?R2h>gy0{Q@7g%BgClf{TeLtyPscWYt4Gu3C zi(2*35nE*Qi~9ECXZyNq1mDqg%PVFdU5?z4{J7jOoJR_9_mEk@Q-@q)i$=9GzL>`` zgfqgkKMr6sgzXV~#Z1MDca)xyPV)f6RB9urkbYHQ3jru9H)36z%Pt@o{TqfXPI7K{ ziRVe;mRPnS<4vvRuN>#DsyQee*1qGm*@~w3v?%-VeZHQml{DWN+RfUi-FFJ7MjZz* zcDgk=@EY1_%~$t$M_=x4IyhSx>qI#RJOx)RqSe+{UZ+8C ztHHH9>Fv)>ew2!NDOgt5wpV{+j1-Sd5B}YnnXe)4)v6Dn4skR0+&Xx=lP5L8aaJZW z;Ty$G=duu84#1gUkR|cVl4J{grgE_r6qxTSoZzHGJNjb-Ig7Y1lIRaa*I}uJ5~E}E zkc`aZ=3@@5W@iO&VV9-U;cG)Nt17B$Vm^}$PDcD#JBRkv!?BXQ0(Op4i_N+ZQbcOc z25Jw`>O$p~#EcQ(9`zXnWDUb@d@^`i%(Q3XSd4qYe)HrH5xpE2zSp}Lwk`ot4fv7l zv?Ps~j}7oPEn$a;suk<4E^UHSSA+97`4JeoiM?X@iO zxar-H@ZW6`xcf%AMZ*eAi%#hGK9Urz46x2Zz1*1`ybsvVc(@rdlZL3n@wj$=r~dXy zy$}C$5n>_fu;{AebRxb<95+MN;=Z-s!P-c&DBqMzOz>`)?gHu>l7d8Sf)f#;N1j^!>t< z#tj_1Zc5X43k%ej*BB=`;9D$N2F`qYPBP{rh-I~U8O?(P(<~sKXZSuvonpcik(=cH zQO(0%fr9SPb?iWM;&@>)5=82;#UxEJk}33hGz?F?iVzUjs8?pP{-hVLoN+3tQBu)` zG)%Zl=YYLQi`%+kX#GWbwP4j5sM&Bu!8;H-_d9ce_z3sILitu$SF6r+q zy#msdN+&yW9PWe`yX|;5$$YEC$D1A3zCEFV1b5)(WQ{ukk-4|_0}G;mnLhUpa@C8GI#RbyV36fnz`Ov`$davN+Du&DN-3Uxzgvp3nN?(D+xgd-U{@KMAu zLgt8+LEs)}xIM@%3#G%Bo)NUqRKr=T_J#S!OegwtvWB(^tAl`q-QzhfF< zAKGYx`6iyKhVd-Pb7bMKCE^v#V_W~v0%ib)@7K$p05S(zdu|qKKIFDQM8P+xC2$AR z<%{5f3$nkiIoi;j)Sy2;SIFK|{Xh&4)kBxcjM=8%n5op3x=K!?D%eS@U_%cZh#m1* zf7}X^&}<8@tpocuCq2H4dSr}|IV*^g%d=lV`#x$6lx>o#$$eg0Vq2z$5VF8Pi!d_o zNZZYrI12MR%lhegOhG2HX#GUF?(QWJza*)2UYldj@=uIoLf=fp0=itx2KNXOk>Qo| z7scG789ZVxm_`5r$7N3p5CufW`t{K>KBtxd2a$c@c)!5&^oWt%2SX5A|7DC)0T9WL zLRRufun013fm)rI^W5NJ)SdK524I`o)%Wf2;JJSnLq_SxzMg;NUi|d0GeDT1h5l{r z7~0LXYhHv`+N2cw>>eHf(1P(udW%r_J2opeQUlae1$MWq+s@* z=f+>`^+Oia`@YbBFZUL9=-Sridsj{KEhS!m&h=#r{wo#d=j9ng&uG3%x@M-}SMtVq zurqzlHb{>f;NjP&AK;=Cf0Gl9(C>>lwMWW12mZn=!&VG=7a34$wPeX8LpM;86gekS zqGTUU`R|=+=@^z5&oXW;rN9oynsdL{U9;pXu^a;z!5920MtGOGYE3Y@p+z-l8s)p=O

    <=~HZYrdgv;GjQIABI4)=rKcTS zd=N;2meGH#Vt2A0T1$_+gbpPA$m}eXYOxjD*Sg$|sfS- zT47D?N2o#f%ey{K?wYCIA z1ts=AU&Y|Qcyeure}Jc+NFN5jdCE}HEt2+N7W{82O6=~iRD6X!z|7cJNVy!s9*PmYG z5v5;Xg^^sSIn*ch^p`RfP7PES>PQzN`=4Y7@4X0ETy=udie7D%!uNcvtIUF&){BlZ zLw?^LyKod)G|5#IV*2O5g6Ensq&npM+s5MR-K-i>q1MS zU4^H}Q{OV;Itn%ljdfZ9tV9SZ%lAa~#=u2S|2`Rt9l{x-A^7F`(NzcQ^v@qliPweu zgBBLh{%2Os=fn54J^xANdN2WHw;WbE$N$id-#y7a!kCE8y$KZ;Z{pWwGNh9W=x%wM zCJX#I{$0wgP<^1FaE{Ofo+-nzHCUJ9*3pQ#tYkcVLX_%aBO5V^T)Pqn;{3u5&i}G8 z;2pO%^?f3JzM|c=B+0KlX+TN}X+|Hye)N27CoB_F{1L&>DnXZR)=FWKL0gTXXM0Dy zm@4_T6AE6y4r*;=p}J)C4ByoEpt+lCx91=J}_PROXSa_bMZ$F^yFpl z7PPsS-h*lu_$|s8C{3N<)!Yw|>XbgYBE`lLnRDs>vKL5kq&S1+e5npJ#8{w3k7?ky zPOdwudXOd19P})uPMeC7K=?jB(3(r1TS&)4R#*MH4cui9EAW zK9t4X4yAJ8feL>f{+p6dI9Wv+i4!SpnxG1^*-Pfn{M1OR@Q@HJHcQT;qQR3LlCWr( ztzEnPH~D5hRcT)8%H#?F*j=C*bzuGu0=N`axJq_nbjIv$;z$oI)&9}`J07~<1S<()q?m&_7a*=U!#!ks!qRu-- z>X8=F3&XqjPZ!FzWxwbU*6O4dCmVKMoiu7t)WGC3wm~;Z#R^8GlxWndYJM} z##LDZ8=ECL^|SrQU>Uu-x#>Dx`4F!8=>NbD2U}WXZ3-#CtjWD}P5Rs580b|7NxRTi zyL-f<(PdN>eMr$i48FA8oYl>_UwIax>cS6;FbhYV6goH(P&}MEm#|`FC(D>s4JLTC zcl%j44v*rJuc5I36*pnyA|zynj>xdi12E*;Nzc5jcqWGWg@JaVl=nL+YF`;VLK(yWws56txPsq7xhW-_nmsze*&R z+@Zf`yq<+f_6#9a@xX6AfBcpvajOydgHpK+M4Ty41%4&E482Y6q2y>*EawpThB>Uy zG!5B7sM6Z8P3{ zQ3I2r;AsI*O#Z~|!-th-VO?MjpGd;*{WELZYNn&EF(y#=8~f@cfzlssSS&Jc{<}43 z-CMFF{egmSw)}}KKl-~$pA^7ma#68ZGC0&pJTN90J>U?>`Qz!gL^Toxydp^~GeY;L zyg4zkE;$E7+e7aLU)#e1ELHr0Wp~Z&KBrH(-wkHHL=$5H$w73vB}UEllxjvbJJn>I z$8tL*yuL3vA~%RDWa08>mGf3O7f+{iaf5d^o#L{o7OQ~?>*Pz44DW(XSbGM|fiM(0 zz(pb<{x^wzEdWc#+F?=Ii%&wp(l7u2C&B zMxuBt&eJ*aCp53UFpCU74K%nD{mk*#iRD=11*0ijeS(KN_cfa2NOH+p`l-fF3T&zt)GySL`^S zn(Uk4O8@!8i%L%2VJup{Q}^(rLS7$Ye*nWTkzk?=K)JQkh{72<2(A=N1X}uv z-pxpH2Maf>WRP4xMUD2u))MBmkP!TA9FjkN69WrPqV^-gU%efv;_l8hlr?mhW4uuA zbL}m@b@aPc1y{IecY>^UXIwHDU7M-tu$4fR^Zq`TZQnB`VWz^>W_3N1yn8TFyg!gTxmyrr1wwV zTS_{ixCJ?89JqJR6zK|Ywxc=DalKz`>i#DJe$43a9Aq@ybzN=>3na-PafY0=;RYX5 zC|D;Pp_K=%liu>vgL%&_Am&Tw5_O`ct_|dJWFdP&{rgaOE8F@>uIdG1if*RSwmop~BmN`Ss3bDo+rqXz?V@WtWM58H z(57|r;ovD5s)D&f;27;zZ66p~Iqq2R4XH?Pw-Mb{!TpV9Gx`+6ZRcLfM13DTebwd^ z;(-lUM(?V}djCw*-qo6xUyC63DP3|o`31+;sHx^CS zsdmwq^mp>42cg7QHY6l9FV=C!c)i^DYk%6nL6_fggBOg_cWu1}7{(^B^>Y2@(D<~% zZjZ(R1}y*?`_$S=;?truUk|^!tPoN&j#o#PK-MXv%9C_Lw-V(2XU*ImUPWOcyb}u*zCr0zR`x?6f zTsPEiUl$k*8%kpfe%`?6Q}P5LYRJ`oC$p_jz`C~POS~keWG*Vw_QfV9 zxE?k{i+;J*d4EM%(o#9L-pW~bND$jHGKTKic0Huwu+c#%@Fd8R8=Xm(28o4*--OQ2}IP3Z&K9uegIbi!Q4uC$i^+YFDjw# zDQzD85uv&k-_n*6vy8xU%9Gy0I{v5zurZ830Q5tQ{@;$TW$s4}IArLO9P78p{T7JA zj$S13rz769UOmSxf5QZam7)(ZF}_jqR_sUOpQ_Bx@S4>eW)7g=lt}=kGo92dA?fP_ zwrEmVUVuMgGL~mZALK=6DJ@-sQ zeMQ7R6ULb#jIdIYAb1X0NykL;Yja}@Y2v@Pr-NQhJYRJ^*(V5}%0Y1K6VLxkX-#-t zaz5qb2JZ#8*|y-iikH`N=nmUfDplJWzsq%QVRvR*7S0=UO`i0$XK=7o27EqeHahW; zc}@LE^-c+&9EUwA3>Xk&@78k3G(r5lDNy!0q!`Y&6@Mk_&yQ)NnkJ0^9V z@XJl7dUFoc+F?2Iwyy#39WhOFxB7{qP*bsI<@;H5AK5uVf5?v%ZtZq}0?<~Z3$cm) z>cH?n$mWWHcPRTUUQL2<`#xSIR4zkfx+)a&Y>@$zK*9VDfS)g3)h!>)d*ET%= zt9&tnW#$_eaGB1=wb`U>fpC%ge0U(9RQ)7u_E_B@-L*l{@X6Q?l762hh$4tm_%-&P zNTUf_p0_eXcic)D0vEL)d&6%5qls(-%O**S+7uY+gI#TR~tk;wC-szIJd`>~`{LfAk7DYh<}ifSk^j93K6w4i@) zUzJRA)Q8k-9s7XhfPjF|>8h1JRqhL6*mHPM5lisGj{-G9=Gq@&BoD6}1e5!KoI>x? z2o5F%JM=TOh{v(VVfb`~iC!HYpnA)25E~{c21BmgOrdwDd(Y&2ljP@HU$*^{?~$6$ zXyv@1axT%ur#nkNm9SS>>SyDBN!h+hEPVxjr6qW}|EOSE;w5r~b-tF4t%c`4SRikb zHl!JexA_We48F}wcj&w|BB?-8KC_$sf}%M=sDW=xc7W z&PNy>h@XqP!W9Eg&PqCu=bRbLH;5Vxtg)?fuP%>o6Lrr#qF4o2Ym&{F$1T&;^iG%~ zSyElqoHY$u%Hn)K8H#e!eZnVbVgEZCql3%efzd+UI~?OlHyZH?MWVE-P5SN`8Y4@K1Jx+Xl88R279LBJP17?&!tXX0yLuv#`*71{AyUxa6QTs57%lY*(F}Or$;7id2#Zw zDm|SFK|z!S$2g+l>5?=Ua+{l5fD-i+Ae9`>3yQ)-Z+f{cF>`nj)MKXCO@Vb3w&HE! z_$YF^fd)eS12Ha_2?ZAN z=*}{~3U~k)8WLVhysAvv=<>>l@In)%J?bWATm7z<5gg*X)~FAEpNHkj5Q~v!gQE|L zecC)dU&G5e2evr-7qZx@MdWmCyUyq`vT=nM%Nt8Oe@0jHZ8(=pe3Q1kg)xYq&j;{q zc^$v1Cw_d!wT}Xhs!Aq43O~6h|UgirG}d(e4*@FxDex z4WrKl2&%@)erR}c`3xSrM04h$%%H5``zpCwf#i-Yt3ya7crI4Zp1GThCtJ1%J%enp zwQf1j)ZzNs|IwLuRFlqdUY{`DV){S83LeQzj3~bf6{?XJ=Ok1MBk*$|-YsX9cBMwp z62m<+Ju5Gz*p(V`bW^M%=P`Zi&E0LtlGJH%IgX&pZ2XwI$4rc7SV@o z-+&!Hljjf+wbwSn&;PS4J6ZzE&FKjH~X!CD7EVJ9O|gF3~5cl_l_PG#WA78_TwsVCS#wI9&w zo=Bmp-CaK|hxNgR6a# z%m&P}!;{XQvfMIAQf|seOA0P!-6eb3;doAoTIcXftq(2gTgB7#kM4z*8^b)~+VFvK zBFyO|;(4x_gS?d#-v(cMzgC{C2A9u%ZFJ3Z7RSVEd2D>+g;nu{FOf%Bd0>n83r{BL zU(qyT&)EQ%vX2+RPDBSO_LH)MSwv;=I0Mx5F_il1731Kpy^}$=^3(}iHip7}hrqCC zs~w#z1} z#IP$_R&RNkW}SrqQ@2QrQ~y_>R%FljRP~wR0s~;n{HFv?@iD$l`yiuB+)Sqkqln_) z*NsoAwbMt8GjB7L=k0Ht=)~q_S%6mSmM%1KCfI6eV;J$pHHMxV8nLKSwsol)?sh6O zjKPP*3=L9un3A49bl-?7r_Pbl=tBH^UI|@Hi%t%K`KP~YXx$u{3rs$rN_+E2GWF4Z zxHfj)wnam^6WTbMj~CkWU3nIgVM$vi^RnH{yUvd%V;{RQ4^1%Rm&&A(1bsBS)JC1WtThUatl+E+)D2de)oB0E2qPaF($A|y{I6em)W?RQ{j*{NLoK$BqOSmBQ!!(} z*JF598Z-Z=1u&i}I5mP_aI4*n7oK{^M&eLC&Xd>GVs@4KPWZHL%5d| zDW-`loQI?1EC!TNiL}%TI9a?b+ZFvKH5t&*af}nuzo_o07*jVZ+&mLL0U1O%adg{% zKdxRQ+xZe0#dCE~;M_HsTqStjraSUCr+z3r?wV(ZPncDNb%Etd=9=Y>7a9khahCOh z8wLf*21(_uVHsJFis88?(jTIE3b!A}8vtPC;GT}dYb)?^|Gi&ae_*JUHug7bvYhvi zD;;OHHn#FqUUL&E9eEn@|HJt9|*#%pK6y*FF;#m?e zcTp3i9*cJE!+#g|XGkm#bjPA9rr;-!Ucn028cdluba=5WsjMzSM3m(iP1X+P)uUcD z4^+QVC{I1Z*;QXqD%RTyM}$L$RU7B~G-B8CP>xUZ04PTnNxjJJh&G>=%Q{?kt^XoN zU;|fquU8-IECLq~dHT!oh%DvZ-dObN1{nSJIeE{sL70)wqI;H*8GMCiRV6V(H2Hhb zX7XS(Avq0i{}QtQgB(;33yb0NW!*_*dpI0b>kX(l-BVx53fjAjM%Q7j&kYQwf3oJr z6zqG3%JfHA@h)NU9)i#hJ2$%w4@oLu7?`7)TMPp5>3j8br7G@ACt4$m2!)#T;h@q}+|wy4)}pW!xWxcCIe$_2RF_byUl{tR*qz zYmHU4Yx4J^AM-!nlw+}pR4!doo_-DNVj|FRmbRXlMxqte8%262a&l~z`)Ijxce&FY z=xoKDAN>d5(}RA1s9%7vX?W|lM^GJ%6A-f6Hu*3zCAAZ&G)qPEZl&}XyU!B6u;>15 zgnSf`HchWJcV*50+sO3ncJZyw@$oJxFcSMJ)1lU5En#8r6FF!KR$qKz6y%8Jkge!B z`9`nE*Gn%(L{8Ju3aUu?IR_cH!Afq8Uz~|=s%e&3wf})g2jn5f0db4`sGSwsC2YL2 zcFEc|0p)&5qn(OyTpsIq)N`gbeXe@G#4)HLjvgD9o*Cj>rRW3`;gu(v)e-N&U95%1 zu57rGF&~66rT?d3t^Ncmq+g)3Oz_irZoC|Wx_8iYeao@DIrrViXFHY&Z6Xy-Ovzjf zF@8IYR=cq!WC0vzH1)R{UHFdPSbX{M#R22&MP^ADeon{^S*Rxm!A^Rl7VtUu_)w-k zIg;32_4tp7wXmH3hH>IrJG(W`sS){Hat=E(usWDEQuCytUk@jr)EQmhjRrV$1ZvS6 zS+TFL4*6;v%IW5MCuvgWy0X>1E(J0_ikq9*zPay9f0fI$+&Jam+x{02_F%gn_GItq zGiXYec5|1GQTQlbT0wRl^JjwRM}h8aNsBGz*a48;H2_8{+>1uV4~zb?v!u;g+TgNX zn_FJ3I-NMc?xz;X85f0%Oxuj5m{R%1;(r2B`{$a&^gr!A$Do5zeqbW(l@`XkYkt;5axU_T2DXq z9noL~cB63 z_M?*KLuM*aYB;{U6W3q$m*}tly=>)t09DOkX`7mvJro=n_a6TgWI2Ofs@(`0sA#|9kkQ>s!f72ci=a)`;Y9=Y^+NNd9g z6N9Kv}L z;m77TW@%do%Y~Xb&+<|%2Ls#eJ+~D%&#;^&kF?%LlOlWI_1UOVQv6z}S&swLHl+(Z zhV&K|rq>Jnu9{f+N>n`@Nzm$(Q;~EBJSpASsIAx=#QsYjyk2VIA#Hm$0svzTVW;PZ zuaXID@3}g>>Z;x}z--_pTkp>=tY^&^O`nHxdFA#HB-CoglgLMZ=RJY{&mI3#r=B{ z+WZEdtC_fz5ErlIRwM-N#B=x&|L6pv(D)?DPM~Oo|EY{M#5Gca0yoZ|{m_=&$t)=C zg4RyuuhVQ*k1-$B29TJx95t_!lyxbYUzd3bT?5jb_|e zAL~uriVd#@sN!DA5O)wOmu$TNzt8I%%ft_&%_z)5mBC2kcFRDG7+Tv-M&HZFAu(}g zXcCM8yM@J8S2|+WXQKWOO90{$2u-t>&uCP~ZRiFBhuq36%1_Y^{ddu{2o1`h0{W2% zz8mHW#+b;9(gWhqa&0(N^#c&{9G5}=PMVQQtDWbJ?gXi%lpE&zvBH;PwvJ|9J_#+V_2RU1ph zFS;Kc@?nCtFj0;`ZCapw5G;t!YT8}Be;nOyV|=sOI4$4BAlk*-ZTBCb4Y$<{{5oed zA4`%QEN}(Y zEMKYj|yv0)NKde0`MynHI!ba&BJlKK*K<05X9m|pym?=9fXLl(2?@hD%zNA zQ*ZA2IOxcH?7DPHdY=qd0Ia`%zZsoRef=si{MmeSPn%{L_ujs%@S=hJ5~orFa+eK) zGN0DB7v`lL%dv+3fHTY-;&3rc(9|18jA)OSy~ch|y-PirM$wRFhX~ecuppA9!qQ89_v1e? zRhB$D?{|rE7e|T_iRSHMoBa&T;-Vsy^{XNg2K1L4EI?!@{=`LKlUK_?dOfwYhEtFi|+SqkGinxqCXHV=PHZd{Z@qz*xUmr#|CZHbnHj zAsgI_cD=zD0FfN;n=*raeu&?2WFrgk7lG7V>fmzNNsgZa3-1vwN6fm|uA}J9bk7P4 zN7axN2_97u>8M6ny*JqEnfj8)WV%7sUs(oy5~f)-MQ2_z;#D1Ye|NRwP5qf!ENdxZ zHb!>IY6)$AhVNMK6swZ2jplfgjb~uKj@HJd%Mkqx|ExDkt<>dwIR4SUNjbe6#3WDw5-Bm8r$51xaQ3va#}JlkUd z#=&9)ol;LCV0IO#xk+#J81ZHGXJx5kI_30O$P5iSkj-gzL=T0m=LL+MyQYpsx!6T9 z0VmQA#NS(SoNO5z=t1MQT9{qp$m=dZk-|sm%u+d~0y{YMFEd31Aw)C48dF(fEE|EIl8+yciI z`hUklBkLN2*Nn*`T>x1eD)?o3{Un;BN|fe<#I|AOGf^3+_J1wrbMR=y1}|QxAX&oH z+j}+b=70KiG_J30mnZ*iwX%jiS#-)Mq**Kq^Ry)*{l+pc#V*uXAMJSbm$R*9#7uiV=dx2 z941_hO%9lA2j%!^3)JId!3{$5Achogl{=W>?vis;!T4<%nq4vzgGAx`B)j zgXj|%*JvWBHPYX zChZY~_F>;=p^jG8?b3Dr^yB5NnZS_7ShH%njhdV=IeWGJ{9+97kSUalmDi$MZ=m-L9uwZ%UFT zFzc;bCyQRhmdn-&%nhtDgFTWN(m37F`X#%51&?UMv=Hkb|4senj@Y48(MaZr-&={S zcB@YCE)z<17qf)kbkL1rYZ6*ujb5LlaPKg|WwmGKA0OY=pa5w2#-_SmE1c#l8T=GI zjeOXbnp(s0kmelpG0dTI+2I#nZI_D2A=7DfwdhlN2ea2@a(-@LKRqkG%SQ2^3eNA! zAA@V6S!=z}Ug0@pDECTJcPov<837qrmglux_^ZvwA6NEKtpGNoK9#p}59b5+8LiYH55K1V5KcpFn^Lhw{Ujls_H#5|5u2-SQKT04^by&>DX>l zz4$WBaEr1pHZ6Z|jr>Q~=Pnr72cR8?IKtmQJyO1VDsejGs5qdzyk|^wQB84g_3rji z*>(;i9X?cfjc~pJR1VMx`1=t#px-^Z$N?fnb)ZctYo#&* z4GaDk^OB7r&rA6Xz5Yi9z(_>BB|yB9EDM-6Zk`Aa-sw(yKtqs5zX!_0Sq2V(-BU7l zcVDCW1Kas=F#YLnTcvE9a?aX_Bp5tDbSOxiPV#x(n?cOYwD^309rRZ^CBwE6?_@^c zCVKBki{laPI}9KqL1#KFAqz+4&a~smhZkX?kW2F}-Ccv<%M8CygeRM@7zLWx)59NC zged>V7dSzv8tD=?onymv!h5UpeVD!pwiw!_nDBY{>`q(Wy&_-u_4}6#!nXvEipvrE z1nL-5p{F8sga!`tH-_>F_;tw>4Skj73+ZcmgG#-MH`!Sz(DDbn{W;4|Kl8_8mVJK2 zFn;{$%PNfGq*pjN+N4duS~Wv+98JvHtYYTWuEa5a3|asr)Yip<$vp>5ylWc@+%r>PFqX9{U_X#@UK71W!{1idz}A&PCIjvk>T z+Ay6!)$$eF1Xz*n!C0!C+19|*w^)JkP+Jy?m?K1Vm0Gl{OILiU%I{7k2riO2)-Yz5 zBvKI}q6#3Q(0{?Me4=}HW}dC9OYlaChk(PN0BJX2_p_)PiSc1PPW*c5NaAt?^Q{5( zdw00?n?4hAv>SsF#qtxUfQPn|?4E^O9I@dT!Idb~kt2rlo_b4duho<}<<5L4Nh|@p z!;}}tT2J7>Fv*XnmOUB|5=eAD3s{V$J#G_j!x+BgA+`Mr=)&!BMx)9kZ?|kKi*RuE zGxkJE`6mtiP#%H~Y-f#S8r{S|+Q&J1G4dQ5Rbg5Q+sWrcgd)VG>0YV@=uF!Z9YLc= z0$LqO9zO^6Us6UCC^q6XkD#mjX5I*sl`*ARCr|v$3Wb^Y==q z31FWLU%l6pO6Nk>nJVI8uUJ za^wWVY2BtX*fclUA3;3{r+PHbfUZ9@3a&|n3crp3>X_F|)#a{`+dPzTY`57<>aN|=U6zemx3TT@KTz%fxfpbe$39_jM7dVjMw2bzMmP``my27IW2`g zfE7vlpzfv>L+AQLZptCYRBi?SxInbG)p`Qmy&!f{L&xx}>8ILbnO#q1RQ%9A(FphJtYrg2yz(L`5Nvh6Kl*!bQvntK<)L5EfW2ejlj z&Ur@mqcEEePy*)&zW7Hl57?HpRRlm4pH3xH33(VNv3tv|KG`8}3@{jg*uIGk_!z>k zL`^0C)1m0G7AK(SYgWOPi1}+$m&9)huZnCo@mi;>4rDzCkkVZAj#0cv0@%En`i50~ z0e*!^t>21nPSsmaO+%w_5oH(W3@!woO2gw{B}6pnmE51OV}Lp z$@h|Ja^!q2S_J8*gpDm2tIrOT@JEps5En0nVAj5o!^}4jZLw9D)oTi}-IRBZ#4Bb_ zG#=Q&AB~{$v9>1=`jw|15&2#8+_$nXgb-tX_gD!~b5DH#J7|(oiaZ1(8G_KLf0uV+ zANp4;u%4khv*HQJOw9c%bp`Rmv|!!+H*-!1szw#b) z3_QBZqI!8LpyQawB!qHy3NiC>|32mocfOZo_Biltdy2bkcV zol{dMC!6k>TN%1ZE5IOB$2pND&U>1N#X1yXt=6O-7?}{1mU&W(;~qJSEhko=)nig) z>8dxrVTuW(XgZP9EgUPqiQHsOPA)f?0cku|%NEQNgW!D48w^xk)2B){;?TIkPJU8< z@Tli`h~QPpfY@yH59wX&oPJN@RBi*C@Tt|Gi9I`yR)1dE_Y$WEhWW6ylNsOJ_QRjc zK0EeAbdtNBt zbN4j7E|AEWlbFrjE&aLug2PA5rzEa>n{E9>B=pNp-ZeKOEpYsj0m1gTX2Q0yp{c2P z@A#Lbw0n2^JM$*OKx^~$N5FZtdas0KyGVC%*vH}g3$o)Y%=GkmKz;>m)~3K>6B2#M z=KiztJ80aBap>6xv{sJsyaesKgB8K?3#ubSRuN%l;CAHg%JSRjP+x^{F|yH{FoCKH zq5_QzEQ83VQ52xT@!Od)BbS=bitSUNRfG0fP-&mtuNHZ85m;O-l3SNpko6@l&*SqC zJq-}Lk-1`ky>hmn4}v;nW_|uh9#lP#smksEb%4`6fpF0tW3HE;fT&03^#R~F9Y&XG zQjxZ$M+;SW5n}{x)uL$S&SZn=?eUO(k<5K!s@SE+E$@c|U#ZN~1PRqC`mmwoCR{d; zB<^#Kj-{lTHug(6OPyg?PPtBN4!t9>RA60)-RDoz==?cbdTf3 zpO!d6Y{KLOEtn@OdfIZ8B?sAFKKBh%ZOzp_Ydy^~Sz(P-eBSIfUY-uF3T|TfOkYk; zF9CJ}@!4k%vq#GI%5v7?Zh!A#RiQH?VL(zd#L?gzezT!T-iYS>WPRb51bo;hl_$n6 zQ?w?IKOLT(I_SL^X;N<_&=pS(2u}Ltl1JIByLYOZ&o(hzfcw$m(D!qeHUd2R_>IWN zA%xkmil0S`^RNvYspETnDQ)Al)_fafokX~?eJ-JF&J{3g>@2#+CF3~8n2VoLCAw(H zROzGU#z+flnhkSUU%BzA!%R33JA3OJR$UN@x14R4;D`W+BoC6tu?!MjOe(s1K$9|f zFz)P_MLLF}WhlUe0Vq3X3$=sBRr!Z*c4DFNQn{Wb%n8J4&-ZKSCWuKMn;sX0bYr@< za8fG*cOvkv`CwR%_&J<7K;jZZVl6V5l(KF$w(22WMqYxea(x14`|h9$?cc}d;Y_9F zJyMT)_Ao~z(Tmw9L-B;S(hqrvdq^M*pm%Y8^7bI?Fmb^s#5Hq#60pQw{G#pBz=Yg# za+^T4UD@Q9UNe%t`|vdPL7**btoCSvZX^>LXBJ@0^M2>FQK8L_6NM5(7P;~BXW>#Qw9mk1)J zKk#@%*mO1aZ=RaHngL_rt3U0fl}52?xev>VSn(Wx0_bVTP(ha{g#AqSzEd6z6rxvD zLONgB1#{RpdO|l-DW5R$yCZVG8cgxffhgMrP!`Y*3*Nd3Woz69bu~uh`#;WyDHb1? zk7ijmC(a%#M36d>BLEWs7NY4 z_u^E4*&9eW-^I>6l)-!8Ej&*q+pBthK)uVUzodm4*Xdan`r?%O2wY^q`SyIcw?E zzUeoP|8j~(JIV8ryTvn|{gCSEL1ta!ZsV+H`~ITH`YclllclPu?D$+EqzocNWE?o2 zCYe7HHc2Lv6bS7>#;O&gU9_^)=w5YfWWtv*sqXFpPx8~yKu9qB60Y;?;7P(#&1}(k zi_3tBG#Doxo32F$=3_SOp&!B3BZPohPS}Sit+_|xgdCMv*L&P~zORKI7_YCp3pIS9 zZT(j}KjS^6LivE(7?|Y}^Z!|Z9CVz!$$S9mOzVu-bm^lSSc`u_{)!YOZeQ|0aAos5 z^E0`K6%qSsi^DGi)Bjw3CYmbu(}4AHYCo^6BHJm1Jlp!hR$u16SuzgA;q@|eWP47% zW$yCdK2M4#D1lUpy+E$1wc`fRFM@e~b{dC5F;|pA1V~h`|DAQ~^5!_0YTj9MxhssA~{HfC!Yy;HTe zIKEQpAV<>Sb^9&x-6#^JKY&qE2-v1m*o_N>etcTo%LJVz>@ALNh`m7AEF#f~bQd^s z!oJBWVWM==CHCS0Hv_cq#F)IRa4Ng-R&HNmvkuO=rpD0Br5at%7PFuNzWvKSaC@5Q zYx|*@Xc-ge7DbF!KBr%MLVv-2e!SJbCsdwi8tIdm}h;2ur5fgs+FUk60WLE?B~0|2rQY z+uAhsYKrjbhupY)(1if=4OhQH0tlC*(YhVoB-j_4i!9LgXABo(?_@M9vgopXH6RY1 zRQch2J;kp8EX*7}Bhf#mbEfB~M`9=ggJ?jJzR!G+J35R0qMottSXN=rWQh*?T1KJL zI*acLj>6&oP1I^ZBCrLT7J9TlB1DGv96FF3fvL@y^ZTr%;*V!mSO2TY1C0wIkW(~) ztD|rTQ;qpZb22R0MKv&BSE+|oCn1NXVbmAT-SY7fYMtG$vL1R`BDrk7*Cq~ zf@v|v_o3vojBkt8&2xeaHJ`vGGO!mP!viY%^ZBt|GumeUW6ryfnSu6*0FGt6jz>Z* z^ngRW!`_y5_QTg6@+fDo$xqBE8sQ96)fl4O(qSToEqqC?z8y&tI0~|aoj~%sfIk*j zS(QmOq2M1h35Ry){i^mLRGV}#As&~I7*AUhOF;{<7%hCE_PIwtOZ_ECh-A1|O5wNT zp|pdf_J$gSh4x=D;Kn0Yw&};0Vbc@bV&c~NkOPV7e-=Iuuemj;q8Zh_1m=W`sr%O- z02b^>_~!2RXe8|kBrco^Gnyc7ThFJiX5O!Y6y&N3rs zm5H4a#LncYmhheEX2<-j%@mO!iJC>Vz_)ZCI38|%1blKTr>}^+W9e|05`7H{$4qLk z>JBXT#RVIym#b#RjjiaiFOMkMu)`{b>8g7SD79Xptue6__TQob0z8<8QLxZow?R|R z?~3x$?4k<_bPYHz1Tm4?SoTEPxH0}vb!ax-*hLndqY-7gKYyYvl1Fvw&eE=g(}2yL zu|GDEHR@s&F&%?iJGu>>+N@bDB5*QNS6SkyH)LLztMcXerbEjiRPxy%)$-jfWx4?H z(`>d;g7A}SiuL8--czs+$t<<;H3trjAr21h6Z_jYd_>E3A4djh%ydLo<@d$oej1vt zWDw~yolmYm1nu34Jab(fl|B?%RaT5 zpF2YqZMb~02QVYty4hUo53_7KD8u6dLrFXclJdODW6+QUqOl(ltR-}l0U!~2`|ga} zynE5vFW_Iw!hYlxO8(ARql$bjba4Eyl%9kLGsxp}M82o&9?r!o&qQX_#|XX;Jfn9K zQW4_W;Jo-Bqp=V?J7{AzTOm!1@(~@Qwfma~=ds(14+F|=E59VyB`AA1X+-$1n}{MD zsN-zHWVK|?vAdnPb8z08q~OJH0bAuY!_^b^WN<@cBKx?7s^^0b10@IPj zEf3*IxHfrLd17Wyrh3?$j2RaioTA#-MDiL%4y1?W4<3CScu__#6ShUR6G61MZOp)2 z$j#zc2tR!-uWh>8HN4sjpt1{1b3vCB3Z((tR(rCJ1=2pW0Y_#Uy0b zY_#$v&_sRZN10;kE^+ssiCz{%aPg%XpnSb&uz{kK6`{+lv|koIy=h|~Ma6wz*L%Z# zDFz7GM5*l}0?uA8Ws7g1qPQhby^PsY-X0}u;R3RH{RfnQklk@0X%H_zjYOzI-4BYM z#+ezK2&gTSz8Cb*z|LieDVx{p%^m?9slI;n_HY0>~B5>w*_A z7WU3|s?9j+&0tR=8&Eg5ANi5b8qmnur4lwkEf;DMb5080Yu@pQ8;a1wZ0!=`C6Aa6 zjh-&_Z-MTGY$Vn?+FC21Xk_23<<8%I-1*BDOq{ojQ=zETs;uwCVp~;96_ubaizB@! z-60@l<1r`ekOQ;tleu4Obr^e4l@lT~B+?=SL4S^e*q zLRuf#?L_Ax{XGkKOFYj}O>WxtME#+gQLk^;Zc0c-?EQm^6elBFg(- z(cnr*c@uCf*52_#K~{ES#ah)Sy^8Ob2oG=eq?c+#9O-oR3gx%=hIYRdA?5MDGUxQ% zblrq6<2A@j7>TP!RI(<&W!fbeEflh~s6o9G5? zD*H(lf{SdNbH1jvRQ=P}l=s=3J=`CaP;(|U4v#(%@@P(SG~h(;SF+VbiZ$=9E2bt; zd|?+HY@xR%Gr}98d#~3I&iVSk7co+*pC_<=U;&hob95*9s9Oz2Av8MY3`@CsA&mWY z7M}J5B+}x!Yq1Wd&0v?DI+O4j6AE)I9qtD|DjSl1hAdz+dY7z zGDpX<|NglK2xzpmp$+m7%$0OfjaFxGsbdjrnFS4fsmiS}w}udtW%auSbAN=;$CLK% zE0O#fjEF&ZlH*{1w1>S+qc?Q{ugtd<<0E_bGNI0&DJEK@ z-MWN>cRN;a{%)mUIdSb0Or5BMEaxa}7*iPBdK)~)c-Vf=9S4oE&Bh-qh|RwC^OjF! zj}7XGryi}YX~ru0^Pu!T^!*WaAvycXi4h5O9i6PoDL`xbDVe3I{;SLbk8d_Zsrp;I zVkK23Ao z5VAGxXB(u|H)5d7rCeHIibt0K`E=w(x-Derm-;ut#qy=_ijcUwsjpc0R@W3Rh~54# z^a}-&zMmG{TSi0R;Bb7U_cY%qoq{BuQYEU{UX&_mOlD%{smtf>;ngvbxmcTF=9DFK zX&#ly7%;ue7jbF}XeTw-l4Q$;A=Q%+q_=YkQit7tG;q$Ql%d^jebpC@aHlCsLl}hv zLUdsd(sL8xGN!%{^Ow=RM0gpc=o=ZHt?$BX|320yfLXt~R|UiU�eBN+f3?{LpVo z#u@Abt1F_slFt(Q`*vrs-a!(Z&^6a)NQ}4MBsb?7%AW|kvy-V7;2BC_Zo55^32K=k z@0jt#$i!lRwX(%yXztXoy6k?rk~r3{HPWHopnI#QoFj2HMx1akqI7>m@7`%?{fd#o3{%`s#L_iIPt9ri`r1!zPot2_em5QYG_to&37tY25kW zf3K-q2Uh0yYU+f9UY#Vp{#w0Kkx%0xfo#C&yGpW+)>3YCk}COO+rlZ3zPriw^VcAR z30p&y>)y}ZJ;>yq@xNLje{<5$p>7Gf1d)4@pLy=Tg{M3?*VDYlXzp6g+pjPwFR*we zo5)<9QK^HK4_dm%6@MkQr37O}m~QLL4(+3w^;Rlo%ZG9FZ_$`ra)ObsCibrNlDHu* zQ+)03>K8%XtKUNg&J+)voq% ztTm3Y)em6g;hvmLFl~FMT7&0e&6*#w!)h&2c=>T)LvIcWARe(535;aJS{>t*`P;eibd-Wh>Zvf?TTLMZStE5TZ19FbhtYXA9Sp_el}w0m(N z2PF8(mz8svzG*l?*ow3cIGNw`^Z>#t(#HLMOwNE#Bnl6PDuQ5JOm>+3uC-W_@${lT z<+>L5{iRo)@cJ1{UMnuLpU@&~n#Ihl3e}5c@=F1P(*viMpvm}g=5l%_?qwLbYiCTI z(4j^8C`1~CAA($%>RF<{z-=jA90>JWij~82+X0~xQ1Hy!k*lo=>Bh#VNc(t;XtY-c z=*nH$tL>1e-LHP3`S;INCl>3c$6g|sk=~B5g-;LlbZ8|+jQ(vwI=Xf?WKQ)wph|3E zn(9}_i`aw>o5cil;v#?*&);UzeQmkK=};~gmJwZ7={4i}ow6HhnrJ<-Bz*sR?OAQf z<%3VNo`=4PAL2m4f-y0{Z3Yk(3p@ei`p%XZ{q!yzzgbwA28+XT;6qgjKI}(KsG>CN z4&J*k=#9XeaLLGgRxiJS|HQmDDr~?F@g;(GV2QTHRusu*O`IcY;%!`5njqnDc`Jff zLn1`rk6X{h7(hzuGpo~WR}7R~=V-<}AAhF?uk`sPOeyaC_=hB!Cdf{4l94G87Rc8@ z;bdB9ZwI@Tsur|yhL(W2j8|4(i`vtPUu=>Rr&{6d#LI6+-VCHTXKPF8Ln%1^iKYT} zaN-;dL`+alM}$6g-Ocu$hE7$KTA#z34Pg)i_Z2g z(ti5E_4kr12(dVpQ1ZOAla+|JB#OG2z}Ucs8|W>TGs!rJ?&VdPbSQeg84W2XXn*XI zp)aa0tp929BV8yRm7xc0Eh8K9=sTx!e?lva1jaRB=#!U4C+|$DQQ>b%(_@zWzl{hHW?*1a_salnMEma*{tJJ(zb3lS2bqCIxt z_xJkqK75>SE^RYO_hl44`>=u()-`%$5#T7Pt@(BGfm>N2$~$i=6&+b?tn5c-VuT-g z|Bj_)7UB|G$D$S29Ji$_DLi0xDr3`IedF4p(3wm=>Gk- zLY>Ao@XckJL*rj>6xiEY>$>I%vb|_&SEgVaF>>wqnPglO=bzOHU^8|SqJu}8P4_}K zzn!ew2qiAQO7nok7t*`hhf&LE7Rk{hZauJ38`MmvgL!HG&cI4xk#5=?LfR7#Nu(dD zYr^>p%AQO576|=?9?{sde;B!E`t_C`aHUK&;UM@Z-!*!(nnv?HNL-!!<=s{Cy_$g68RQL}C~ z1n_3xBw=d`$H(%-6-mX;&FX*TH?H0Eh!#-&Gna2GTFQB)$hUYXk^k`VF+rG4cG{6S zNWLg@*rvugIH$S&99FnJH@>Z_aSNTWXt{B^w`q=?5nW1B{QN!$hxM75&?f)_5#Te7jTf`P|w)-@04p zNG*gb-pT#e(xJx$HTTcA$JdE}a8TNbk7ojvyKZH}275NFkgR`-x6S>#6l(SCw~1>} z08bBGRNi`>ggAt|$@J-;Nlas#H^)lxKGcl z_moo!fuBA+sgB?`jFBQb{QZ$8QuHO_;$RXPfxsC|(%oxl zY1}?(s`IF)jL3rQr>N%;$>`xM;c?=%F@B%;Ue{Qvu~pKgeX{pQz8?vdwIh;A(7dn! z(BUhGfZlDEIGJEcnE&i@p`Rkm5i&}C1bkmIFc7~e%cS4mkLR>twfZ?a*YCKaQ$YCP0{XfKqs?GK{XCt~QxtF6x~+k4@^?O~Ip zgQ?{Y)S8QM|25*HBuq|pKEEw2A!86Qfk;ntL9v0yX+us=oyK$amNUef_u$dPOP4QR z$vHbwhJ$l_{RMw|RT^`6Ri2psqL=V8bKSFo*Pnz{375ujnnxbKf1qbyI_lg+T52TP zo(M3Tu2-=ROXSTMMiFY}JOxoIGjPGS)reU;$y@~(QIeG$n!S=bYb0d=tu4DCY34FR zX=|oXg`TSKC$F{gnUWlMI%wepE z{{ngKaGH}DODgqyj~9qTbLttlqH7$u=@e_SCASMU1xrXP6bmy94U8w;tXy zE4G>&hNCj;{$a1Z#Rs<)4C89tPRfYuXVmt?#$>*b+i+!wd>}{KBDg z^XAtZ>q-W;n~XJg>i|m1_yWJ3K^8S2b(=b|;)h+bKVNPf-J5rX zslwxZQxP*Z9v%MQ4 zMWy5A34RIOwSjo~b(g36IyvRC4gPb@lkP`2Fg#fUybLlAWgZ>W5ADFr_hbXkkAjl6 zqEu0VO?9Ff?U&ZFbhNKL_<;iB)CLT~#nwf7zr7DfPjiNNu3tfmK7GJSN|Stq)E>Cf z-W(1f_RkKC?a?C%`?E69f3wj31M^5~d7oUEoZPh5)w(2vy!@{V0wkE9|K zI`{Fcz=7i!K^vs}+dZ;tn|-&7{qbZiXT9Vv`QBmLSB631=l@lL1bo7%pOIvYssw#O zz7#{%Z)(IX(FR(jZejB9UVn4={c$pKGRg&K{ts(jnonW<;a@hgbtXc38j`G|(mk6Hl)zq_P2y>fizda)Z~b*Bv@7kHZymdMqVHylF+ zB?<23g6kdZjD0JD4;`bZ!^U_cq{ITKJwm5UeU2dI#KZ|IfJ0u3jm*&{#~m{HkLzM@QHG zLalvz!=<+8Ztq5CQ86{V?fmY1>aO#l!ThhxTG*VBb#V0ENuldm-@H+Pi)(qGSdSVx zlU{es1Y4EwfA)u~P6!S14ziN_Oy)F`rJ;WiQz`^T))L?Ew;7$UY#uK^_P-&31&CMw z&|~|?!-~!*_(w(*7E*TU;qE;pl!-nA@Jk!sbZ)vaN$|;BkP7~SUgY$9uOtrTvMDYK z+Anwv7F)aj^lguyNNUhSg|j{_K=v z!(-n6BzDJ~r_?u|e{Bm_mIL_!IVj9%wzkoku2Ra~YkDLaFah)({8CfrnJ}GXZ){n1 z$63dU6h?4I?b)a5{O3K>wucVwBNqP0qNRmnKPMhKIq!cIB5JaLsq6o<;&~jl)AnqC z4;BI3z0pAe3$RKEir}?9M7UOh`I^9Zpt05=`&5#dMr4I zZ7mmdlZjCs^ovh@O*~eYqj~XVoNk&Y7K^x%c*dE&sg&FC8a56Lfl$UXUz)ifk1nZ> zDq5KYy5yN39gaxU=Xrzw<{}*r2bJ@#V8NcGsl(0E zj+nY<#q9)36~7J0EluaE#9MniwCv(Gn0`;WqaN8>Yeq-w|Ogn-}Bre7KPW{he>@S}UGx#cs<`EI> z+lsrO&yA%UdqK1hLh4clgt~H*O>ooyShf1x_+=I@`e3sd*P>-NG%5Q~)vDu61GUDR z!QLWfC0xtr!|S@<7(J*T^jhhy!@nQ;9*Ff;Gxa65e~9bn1DW4wMru-PC>>GMT(mD; zosykeeP1ZhzRHy3=G3@4#Z;h0*fTeLZa}Ag;E`IpcS@8F6O@DEQo?HR@-6%5P%WR~ z^y;#AuS7yiExxpRs24Z^y(?f6fM25=f*T9L%)v3szS=5&#M~(-{hL|Bk=YC(+nDmx zsr`K)J>7?%V}fU&^e%Wp8l={l+Hj-+`_R-FIydGj;KCSPkqm@CVGeBVVK{y^~K@)c#U35={T5AoX($kdT z37q@085ZHzt7%!U8Ct06FRY~Yo_W`1L6pE?H>%vmH?Eg*08Q_miq@slLUZmfO@?29 z{t1y8rVBqhOu;ySl+~M9^%%-a2QvrxI}h#z@RDM!hTkVS`_h+*T1=*yv+rr*(@ERt zt8TgU9d^;MaC|s-kgqmAoJf?WP)gBn%td#ve->yj<&y_ZgRi~`hTq-M#qIZlq_k@Y zg@#YzIQJIrd?11EI(R|m*{>AL{BU?TJgRcTZtHn-^fSCYYE6BHiX?yz$3-Yp1#B zlg-wjzE+YSNVRQ>c5e+@36b^@jxw|B5ZP}R5jZhm9VxX!e-ANW1*UP5 z_#{_i(+-mg72(dgVYrxOo^d-sQeiV&czT_Qs59vC`4p8<5iV`o%P}jf_h@TN8$7?# z6V2cC0d3GLS&vUnLgPWn`xVh|FwQ`nmSU&#`xOLjTBPAy2Es-FZ1 z!R$A|{YwwOqS$J89Z_|b}CarxNQgrd~*N5a!YiBpzy1mg; z!WUzM0cD1FIqDf$+Z6gxQlq!Lf`;o|d$_8DoH{#QPg7yNuk-XE3L>1TU_4>vf0WQA zlJw1D+^a{i{#s#{&u1-q-L76xPu+o%j8+ekv4kSmB4B1f)Mo3)dzTIeyz>F*>TY&r zP2Kx0_v*9e9Zc5<*`=f)$)zSA>T9!}pc4MkQsbX4lbhRY^LMs|JqMEPZu98so@3Q$ z?f=Np_JmquK`!g$SZ$d9N#M*YN*TI}mm?Ou^{E@=^RhvQ-;!}ZL5pe;s4pu6*z6)p za!9@(9r`j2lkaQ94{ZpkO_}^Mu~`E{iuVldZ=!cgAh-H9+V5UkQuR}}^bQ0*U>$iG zrdzucs@^Ce>m)4Ho89X#j2m0aRE8W z&%UhIUsFV}ISAJHI*-hWsAV2#v+wr*<{}@Am=of>B9GTS1P+}R*`fuXnEK@QLq`g^$_472jhD~}=ZLi&NA@OBfrGTVNbNS{i5Hhl5O!l4ObMn_}TGNk| z1Ix4G!FY1~xIZ23T*AW)x$6FWtbWcdvTU3-3da+Qp&)%Lh^>I8R=KYYb-sFO$W&3=^%R zU*1O|3jRaB$X)Yzf2SreV=L2}D$vE-FX8mc1|ZGX1N^^LR5etDIhT4>*!ipBZQRdG#&Xi!$L}_x_c)F^odyU5 z@Zp$jI4TX_aE4HxJW!w^3i%QdsV(ysB)=O&h1JZ#ANoe_jzRl83OsOfb$`W7U}DK; z={3Q&ZGi!vOI>qkG*gX@wh1GR2Y16Fj8Bf5fi5D&V(+b8^xQ86xijk(zCc;2JmfvJIFjLRdZkD&GRy!n z|MArP^mT!d!)c<}qzSWAQL8+dPPhT;sK7sgIO_@8gz!5nQKpK0jO$RhAxkykm;7c( z(a=hmCDrKfCC-v$1zgL;UnNOPfin_p8Dcpvg?%jI)s_#QmtL$M{&RY17y=Jr>^htn z>L!_JJp|;5+GAQgU)#_zwAVaD9AqK4a=&0;s*D+1vr+E%kgbjdnjMbcPGOzx_TTz# z;uxF>#^rNkaTeP(?6X?)sRps{(n%&BK}QPn5LODr;sPt8wx}ZJmz_+3uOf%4`|RD; z@G5_Q5fc&4ziVRhGB)Q}Vv>5$*A-*{$jeBWG%VF<-S}1|Rb4J;j<4?59XgXpv>}WG(o>d_x zjuh%er4^yeaPTQ=4}H|VTA?7-I86_xqh#sFP}-4To-$reVra@1pfFb%I|tXZ*OU{; z7?8QG5v&S&5QLH2ueY+xc>&Y>ek~5NmM(zu!u=we^DD`ELIn9nXCJ(AyzKF@P{ zH&Ip$>*$T;>|r*d(vUdhg>idC7@XIeAk&?xLGXeFT)P0)J#l*zsEmvts|>Ts0I7tz zU;DU_a#!4hBimBrudufT7gftuios7XIqM$GvLQd!yIF+a+rdYzl?mSv>kS8TI>_kr z*X)r!n zFXjUaM}X5aD<#&S(9JEpOP_&MVVzz%g7P77Xp+nA8V0WD1nyZ3?Ps!R-~1Kt(iyQ2P&bb2_N{=Pur6ly9lF$AdcFh|ub!XnV4^j-Qq$5W9Cg0j@Xw8{TSFf!0HxxQ ziTrC8Dlnn(K~tJH{ezMZ;2f|2*kes@OsWw{SMMs2wxzH;pXs9XSIAhBhk3Kn1NP-8 z!BI=t=cVSkgVzL@ZziG1*6n}pUF#QKd1GwO+K6!PwF>vzy70`McNn6k{6~x*0S3X% z$F+hLnm&2_ZrEby9rKEO)98R8gPzTPJcC}@XG=AaKyRM^<5)$Jl)c~ak9rg|)u^d= zUH&6M|4t6#^|riRQ#{cT@qVmuzwWk4M#P#Ps1A#A+gzQsdw5~t+28!vvfO7i40}jQ zl+2%Tu^A(@r2ih|Vz1rchxpC0lL`lB;$FDBu0~#Y%vB2fD2pzcrZf9Xn>tNn{+I95 z>;nB-&@1e14!oiM$L(3?EcP7Guq-%c+u`YB&iftGI_nSZuA@3`Vm0KuHqmt3m z5lq#?a#q1vosDIQ(!(`-pwcfIHIjAwQa$cU}?S z1`nu3zTl}Lq`99JWBb|3)LeP_2lSOn)kJi@TAe9159=US9PkzVN2dU;oU{IrHtF>{ z^@GwpDxcMfS8*K9{>#=XDi)jJ25@RmLdg&Z@=(p^r^)KUN>vzpP%99k@6WdRra>YK zdCAOo^OyE3IrM_hr#wz8qIoUsUvi{0Za@d)^ro3SZDhvN!S%@mWw=W<-a92omtw+* zb?qr*L!m=g9MlB%i`~jVwM70IRz$NiedbCN;Ys%Re%7=rOHNBW>RS@M782O?nIC2V3 z|GC8+7NE4=eiyYUvhr>eb5atY(R8P1LrNY*V-jL&unxd~JR{TaFoAUJKSUXyFm%w^ z#|>Cfafzwy;iYA~O&}H^>RdjquU4XS8Y}6!t z`29tAMRe2uc#4sju{m~(p~cORLkv5!Zd+u{+(Wx1#5@0}QrG%!3b)nM7hpuk7!%4B=tz&?5JT{Vus>mC;=17h4ec=-?M3@ zJ2aXVXr(5=hr+QZ)c3(cW}X^@OL!fK)@pno$?9Yc2V5TQbTq*5!Bd;w;aKq`&QO#| zy~j_c8>~>1k4QoCy?o5WHU_0EdbBIw9{EYRlDTV2@iBoaJQUuK56KPD5vl0fR#*{9 zk5A$N`XKQh%6UT+tt6$rNMABNGCqqLD!}hpv)7StyaX0F{AN!46vq>U?Qd`$wp$zI zWM^RiN*I7M(R(Z-}#!W0=APr}YbJ>|>8tVs7ukDGrUkaKW za2E8DM^JovN~l!KzNnQnPh`=&TM}MFm&3euwC0 zNEK+&ZIu71MZ9}P*nwtz`BWkJefXoSCo+2^=VW^@^-e`4{aHUc%{3| zgo3#Dwv-NY4W*3d`!{x+S%?EfB zdYs`kHm7EhOS2s-*IA|iv3-Z685KQl15d!qy!8`MHS%Cz-+b=!#522Z25(9pyLjE3 zqWU5WS`!aLWdtt-IiES?y0Q*24iqwE$>aqv6B9JB?Asr?JEq-Y4=4}$=F1@NM=v6C ziY~wG)gnrP_Fwb1DBTXHt>S92C9=^H5aPW%|0p%PRI+hAn->4duyMqK7&^n%iPV{) zu;)g=zAh}kH}b)3`>cp2s#F>-wt~vN|#t3&y-0VBC1wAHE`9? zNs4JwKB`>(`>{*Lm|Dd;0=@mRuorQ^AHfWID~K|eWcDFmd!U6HIDmS5zV`&asPkPi zW^qP6Metp*rUC?=P@uK8d+d9E!Hbp83xBQRI|gNjK0WXQO9(SbNso)8+nO=Z$Lav* z3wykb0jIVqb%{xZMvdHJ%c4;`qy5%?01JLK#6LlFG<4;YMO~$O!G}L)M!3Wu80GxB zAny~LI5(bISn%K9(6(6DaXZJ1@L@UL@i^v@4iV5a;`JZR`+n~P>vb%MFP z#S8}nDFR%xEU1-WWdNLB-ZZeoeEk1l}(~0!TW<}<>~@-rsaQO#_L5~ z2Aer=1&-+rvDuvW!jC&-d`Jv^w%2@NMv| z*Xl`o^RzwT)fOD2_^XsrW1Y`3d<+S9WI(!h$~rA~KTh4SCn7iK06mb3tb_4*qSJR7 z)iMftrgU;~En;sdgy{Fv(GLw5%agvATb<`8haw`|(JGw=gR~nwBXQr=lkBy`HNIT( zSZ`CS5UKouvJACKynd?dml@oB#N)eWSUU1}=@0Ej;J;KA$R}o4oP*X6hu6{R#ftCr zqpA56utc06y5yEaBd`flZ18wjn`vV?oHobu{LcSv2uw(Shnu~5x%^g7`}hQ!9QO*q zl`y`3bEy3G*HAGj%)^9Y1=s~R{l(#bH!_Q0?^4G}F)zr4^{OgJ-FcCC?RlioUGgJO z>~UmyScX-_p~(}$4kW949Q~eMc#Yi@iL7cpbqrCHvr`1#Ymq z4_S1}Z&KK0V$j+E!K8sV0XSMjt@R9KfLmokJbl<4O0YcTKmult)I zk-Q(nNp7&D7cXSQmd+3k_lP(ZAF_JWlea_~>z9&7no;Rvwa#o-jTmW`_a!h1;oon8 zsS3OteQheNo8rs4Mh%PTIZX4vc`wmLn)BuP%v5j76S|cj0KQ7_L$iX~X&=2~gZ_ef zLXiGT`!U(yFE6D*z~3eLPhMY`t449^Y}yCrEN(7))zx{u z5F_Y-qJ>lcA5C8w7S;DgOAOsT0|-cWcOw#tl!QnQ4Bbd~iPQih-6+y6-5@Z4l7e&$ z3@JHubLaQJ_kQO&=Q(FMd+!zRT06WaR+QQxSv`VtTPY5(X^dn))N@+CF=7eMsJyHk z*HxR=dJKlN&(;|DA*=6he_hfNeYIR`n$gFKDq;_>rL{rDcd9-6(K*p7JwBHnS5Okt z$ut(phGlH^U8HqFoS=KviLxjP7-!Z0d?7*P-_8`5{`_(L#i)L*3?bE>DPxc2l zGwO~OOLOp+ud9TnXo9(;2>GRtC&ujii-8z){GQLdEuSwXJqV9#q2^ZHmvp;$FWNq* z(L2&r4wNk4xmhq3@YB29sM_SY+y{xu6Lr?dxM+O79&aphgV{GwHc+d03QDtxvSd?m zc2e~S7$g0I9Sc4!u}}te0^`AFfn|&>ZCy~mDGV7h?Uy~Z*h059=an$9J$PbWv5~~E zvSs&e>@fhLrqD6aEswmRGWq+ScHMN)dY_mVhF%%J|KYJ6ncMT;VPBr1sX{{|JQQ{v z!X9$}skphp&y}&x-b|?-Z_WmY%+)lsw~SFEZgPM3urqgsNAF_-EkAlvFDTbPId+%# z)rzi(h5wUQM>4}PV9wYS;f+PXB`q0;dV?>`d~>K%or>V5PeS8EhcyJMNkrPX0;^6i zh^{Q{AjEEMaN4tOX|CDOW%dK8Kq!glX3+ch0guQ^$y{8zoBr%9jL$YV&Bio9Qhr*h z@7Gcz=cehiK^(%>gk!E|ObI+!9=^>S9Fr6OWn_n!#7O~NIw}CST%6H`P5qHEyB-^% zI-r(lEANA0{77_Sh86NbI;wbEv~-~?wdcMdMrPc8bBIK|$NEN9tf}P;7uHj4VZ|t8 zd?>rxWK~JqVA)Nw+#XUMd<_iQCSaFubIp3#s=ppB_d29*N*&xXd}k!H&~r?>YzuSQ zU+wp`(7fRsdR^I$!m<<97PdR%UMA*LUz}}dCUT0cxLw`u|J<@QJKEBT2R62AxZylP zzRV|k2p3Vag#NJ1de|0nT+C&+|4aQKyrIXw+J(B=(3?g}#+{#)L?1i0+4)9)cM|fN z^vtx|w#(IeS0DVrj!c;oXu3k(#`ZN&b49)A0EhK`37kPi{=V&MF*Wv+ng)-={;|+% zon^V1N0maL*4^A<6TY?utYg$D@|v-iAvOX1FRJtbs`T4v`q5|ZAFtJv%R|{J+&8HDRVOBzvX#c;*cp?v zYtg`BO8lqF-r@mfEB+~3E!bJ%P>Uhob7P#idZprzXMZPuv<4A10sjvndj{5P2>O^F ztU2-(wai=NZr!wTpYaJ~phC=GM9UlJ(!b#|i7E;vo+;T})5%{_w@aCR-jtu--vcx4 z1PjhX*}`03gY$T&zM7nT^HcZ0-InvjCVU)_H0x2&`T|UkZF+=NpHTj9hcc z)@?h0EZ9CEKH2!(P2C?gymC6yl{(ti^p4GhjATaV46`p}oA{X>p-nT2dSuCF6+&@H z*QnsGeZD`quR62A1taUBQts6t1tL*8=Y*4D7kf0x0T?VG|qSKO}G9yw!N++HXsk!eWyz$txApM_9ax z9A(moon#ZrCNyI`KBO6!j)Fz{g~yHr))W6}E7+9F#2?OC^{p!GVSVVb^wN5) z@3lUPXafBEJ{Ja_2fPUr6@%7YfuDD%sMz)Wwe7@_q>BawX}ISMJS(PXb!r}0a&k3L z%Rf^f>&aHc0G-qglsX08IBG=sHGb`!-}TPV3^OT+39QSeugJ5Wsl1yVUA&$Kd!bghBCcmze zikcF!WXtRbo~Gd>;ch0IizD3CG~g;+J|ZasC-(q;X$??bT(12je}S?L79Uq%6Caz1 zI9kH?nbye5SJMEdjmb1_W^Ja#E)37Q0R#1)FpB$8guRD5BZYFf{>xNLwBsjmv;b0Z23Hi6B@m|JLNF` zS>A98R$0}wLf%&s`2$nk1X0f`5gT^^e? zD4H|b>R0s=j)H*~evGt)WN_!!O9(fgb z{Ca2&qPO^KSLsv~%fpt^cbfMKa69Q{wZW%&OqFOPgR@7<1J{P<_?YcEt|NAEgyq&S z^eGC-9>>fhXyvY44CCP732=X4&m+YUfa^5SBk1VT=fAMbo1+;=~Id| zxFmVz;TK*XJxsbf_X|K9E1EO)9*1C04Cy7BuOjORT7twL?<7Y{s{%9kBHp3a&9+N? z4ge}_*0Tti*qG?wl~i~zxN~gv%m~Xz2yfF6Z#jS|@Gs}GA)d7pUP*_*^5shy4NEq; zYvs9QWZqxw{2bgbvWB-OW9>|~Re%tN0yj6xpn(3j9X&=eSRQfknMPM>m5otSNiq-P zk9woQe0&tdc`TniIKNHMbz^5a%A&@Sw{1Y$Mi>XYDRv}|BkpA3(*pCpcXdeTop$Ty{*jI*@b%8(_ zCV?eC!-cJ0ew)K!Wcom^ci>HNUcn0Cka~JKo^gA1I@t#^Wy^utvChss+$>yZ970FT zdjjIe(L=P73t*Cr7ArHOerU+3_1@d^OK*y%Q*pj;+k;qqAGpF974->yMy}md^2ece zRxpAJW?|{nX?kI4LgS(-+hl5Bl!O>abU57KCNi$Ar{QDr`hJ_f3?^b1Et}W`%jCnK z9sFMXMMmA!c)?Ts;z6{AFcksg@G&vwiz5H^q?~^h0b5pP#|8Cr(K~2@bT!%wr$H+lJ|DYqt zZEvs;gZRp8Hv_j^5Za>vCKJ?sQ54wb@fxk0`%zD%j2-P*{z)R*=2#3Ed*nGklz!W=e!D3L!RwI5ovv>xmD&eKhb$Y@N z*zG$|PZBrvpQkkE4ppv&uN+52l~AR!l@|L0G2H~6rrwyBgkhYjb zut|Dxr>lqh^Yt=4xxyF4GUZlA2xke9?B!o!Yy-p=1~VOmR^ZF#5RlIE-~B^5-_e;i z_uu)Pzx4m|C9Z>jEGQFhGF2P7l@RRPdAd1V2*0+Zeylus8k;f!d2e!k2BOdX6MJ!k$G8@ohD|w^rk< zN6g6h`G~_V{yN!Yw1?d^2`d;@e6SRxR%zvo8Kn4drAj(MT_10I5R-h^zY(4lv*0J@ zv}OAchb3P;ETIg0M=2F4WWU!26=?O*KjoTR{vOptz5~g1BYrJ60T1fCfhy_YgsZVJ zH1!s-GZ?^=jS$HY6guOW8lRke zxCqV~HN=(5kKFIgb}(~{+L>_DWzSDNPyZ^<#RB%9!jSQyZP*t`5tYRLCNDxBp0l5^ zs6FNtn8;Dx_G%3EEFY2R6pRCBMm~`Hjy@L_mgW0Fl6gSmBU&n@Sxku&91W6jq)KOaeRS}T z@Al)sv9P)X7@|@+d0Z-IBzX!2in8D|>fM@=jOHyfk4~R*#CRI5 zDy18qGo*SfdfnFwQ^NmwYaFa4soZUgmi*1}%ECb93S7-s6~B zi(Nfm0TUb;v^C{!9SGv@#3gyL$kNK#O5#xfy~Dos+x_d6G-}I-x{!;!-TNc(vOfA1 zGyKA@_dVkYCxf6@E!d>|*Oj>@+6cnzzax1?=K{0^-n$@y80Q8EfR^20S240^vZPw@ z^{g;VDtCnetNX{E)cTOwBxSa)g4jShx|>z!aNnBy?8Vn(sL`*2A>FW}7toXw))u`J z#UB*Yh}e-~%wDYl4Qjtv@{GB>M$V7QkSO*j*iDDb&_O5=O-gz{FSx>`f`GY_UMh49>vvo zy1cI>3VCWCx^!B=ysCom7bG>+BLLk{4YT?j#%eXlrs^$%jKJ4FO}-|H`(4NR3?UC`oi4C7^T@ zWpy`xxBP0ay*=lsVtA&-+`t$?^0g-xY6RAGB^sqKJ%qyJ*-$M5rU0McUrnz-K@-qB zjODeJ-$g^hl5Q95c{ROHkw%F~Wj~#bvD&Q=z1si2xT*o0xXv-??~@Dd98e(DO$}&G zY5Cc}ibUreL&4sqmfCNLit?h!L7`I^sSz&{o4)zKjvFRg4RJxF4pDPx2$%NQr=Nn1 zYu`U9A=Ji_RE|VOOnB#)Ri$bSP$J1D{I0?Bw$esg6Gg>&7WMO9$P^jmht0-J z#YOti=|#8%y2BlLx=9=d=2WNK*dHVnn;6fAupd4!ZJEF9kva#fqvmHw2R|z@hKu*z zu=DrM1#qxj;vNYj(ie=8Qdkl-)c1y@1Y5m(a=msM$vt^{ZD153#phgtR9E&V(n^&i zK@iF+I*>vnD?&?4xXl#(uK zVHeze61)TxGGi097h!_NzqIzs3f(C|HDju&ck5{%$UgCWa}&m0Uw1q-Ov`_^e#}~f zRb$aJ^SGzZ5NhmVRC#i+Yti;LnTbFZZ2^TvPq}s2ApywCTHC@E?~*5QM&q&vJk8 zhH|K!z_p89z{^WaUZRt?^*7u{#8u{DX}QHks5oj2@m2M&qDB=IhpAlE&JZX3m#6XA zu|I(C{dbnWkMy+UnIxh(9xu+tG)t9o=$Yrjrc}R!1gwSRbS!K-|Ci8oMd18b#mDJK7&#@r0!euNzJ3@My*SnITlCaDj0K?> zGRlwcb#EU$lJ1+tD+Z=2N&kfqbKZoM*;*;WVn7_FVvI2|V}8T?H=PJ4) zQ_6+hLf~@FPk(nO=*q+hr(F2-_g#?xV?~f%fa-Y*I;V04+ur7GdHyU(I}|nYdMIdn zkULLlRIhM)Ko%oUca%W2bU-#%ON0@@CJn;e(<+fK9D)#lpGH;a_M+SO3(` zIR!}v6x&zj42u*5LS3L9!XEwSht{%?=<9@G@acx%eC>_{__ZtZ8A zJ{8tmMMN!Qm@7llc$;8R53@)Q?(kyj_xQQYej`vdGC61u4z;j;?D+klx z5m&Y2Ugq%|0uXYR-UildzKt85E2BCQk@hpo{M8es{esPg9WT=MBlbK)Zsd;bJph(q zb3NE&VkPkRMrM^8Nleg5m0+Tg0F>oMP=lVlwp*@`7MrM(4~itF-_PUg7d2RmZhr&q z_SzGg4}6zXN?HU|7h&}mst|wlXIbqj>5(UG3kp?8y)5)IT2dM#y;sGBRSL~BnI2-+x zAof=1v1%A6J|Uuu#7(FmTNO;zO`ZZdnlfMO_L)@0gp!J3`QRWxDgid4S&{fTf&%H` z_PC%eTpJ2D5#cRB6rR)YLP>oHYcY}OEtcTxKUE3qw`P{8K{Xj|Bm`IxJ8IbREL*wvGqfN)!HoptaB^Gs zBFJTFc~`)#@!3QG&0X3RQQpEw$?`H$8J?d2gFHX|+-c#3({kKNUg<>wTG3-mo~@m- z7KN#&u=yFI8;IO^{+Rm4n1H|!gD!ld7L)?Co8v^3ADZks#4$%t=S?Iw{zph)BQ$M` z24`syS9(}$DY8sB1uhw_Eh<4fI!kS*PL58)oQGs%#q6}AFCghtlq^)x^f%U11a0pH z*YpOh-&u_cTm~?|1M{XL$xl-K86A6vz7Y!0Q@Ml9Q9jD)W`Q^5^~|!w9ipF9*MGY@ zfy5z3#N7-+KtmX*SOi9(ND+DP2AADY&#y4-cu|!iF2xl3m)Th~yk&5m-BU7$(5_T? z8nGq)0DXQoJWlM!7bGl1U)2ANLNuVvkN+ljLiHZ4j`N23IPF^8N^KZOENB{O84tC_ zTQ>5XynnnLWo6u3=zR~g!}3U%-6=hBIu=4!!9kIBHnNZt@{K`{Av~O8ij)$pEoU@t z@-$L=X!1?p^937Ei@+>Ei;C#4uM1eq%|ddn>Pc4@SGT4L%mw?;O7^g-@p-a~o3q=V zjp;0=RZ0GJrBE;&&pa-Y;ef!C{J_lMr3EiMYFYr z{so$ld=D%`yRzN8TbiFP>V4XfO=PXR6J&^dexL6wfddmqbfb#wRwPL;bslgY#PN0? z-3@l)t22)&;xFE<=Q!B}eZ{a~iCd+do3vB4F!oHSx%*;K9jS<8g>D{m!5VZ=_ISI} zO8^vLV(8mlaf3Y2AJg2DKFF8R7KQELt9sJ5I047rMoiva@su_W4K7NCI^Z(HN2@GwyqpZO`#_wu#~v$s|lIsF__Av;ME z4XVOSXyg$@CZ_pm3gmaj4NwMf9yAzZSt3lWryp>Fq|2r zK-fvah=>aue4eFZK`Ikb-&LA)JfXy!1Vu@-^B!EKsjqV(Fezbbta|kgQxX1IBY9Ro z>Od(-P_E6a~;g(JbT3<*PYs(wMC^(hoXDzZ2(Ld1&v zr%mk7C?e}08nGYmni%@!OZ(@3@fq809G}cTX;+z8NsM~sm=hRxsT`;83LAB~mIu3* zEQ#c#wTk^dxv%9p3Eq`s7iVb?z_}iuG8U;m`cp8{>ij_7ac@umr0y_A-6ikKdHA=t z{p)ZogC;H*BQBWCD6HNJ^%r~g!LzyBUX4vCfv+mhN?`f4ltGo+o)>C zXCTY+0dkbZ_LZMUGj!xW);!gHP93%(VD8e9o)H4^9Flk4)+8R>cg}RwAU87I+&xVW!55Sg5V;F{7^_8(H7)GX2ZMt3u_G_L>QnaW-5V z8j>X^weml3Tbv;BI$T9J_jjhqrRj3tJAmfQNny(nmNsra;YKX3Hf)%pAhe*%U2+W~ z{=b7N-L|)sX`Dy73jd%|KHv3?AD}hkJ?>x-pZ(U{3^i>VQ(U|tKao{EeVsJ^xX?Ux z!eLBcWPLRkD#!n0(5S=U=bfj#@)R@ze#m}IB(P{BVYf#9HQO9Ygq zUJIWT6KS+Tn%6Ycj8U?S2-IC_<3s-)^`s@tJT?%^7Ym{F;mGvLJkY0o$jm>7S{L!F z{bF?RJKR$i=<6lt*?C^xh;5$OuURXI>O^~by$LIiQ|_expML&fl@=poJ$TpUI@27J zLAX^9mIqq)?hm{^F7i%7J@>faL2M*7Dvp*~cE0W75;4P<>-@e4>*d-mS$AGEjLLSe ze2@YcQqS*XuOWs`=+WkZy!*_U&a>nXD?}CD=%_#3z6G*u3G%J&STskCi`vG^cfTT1 z4nMn0DHM!|9Bz4kj<)&#)aG)uP5r!UyRalQyOcOx1Md52WakzAA!GwzBz--sO%8hv zcCBiT`1*-ldpmskbohmc7K`v22FGh&R$<0n(IVyiH#5cslQuf>#4;mDu?~x#RMYfA z=|1QOug`~HS+~_>7Zlzl-?LS4EqDMR!1^H!7Tt4>U2u>8j|oLVM`0foZGHMGz$evj z96!}`e`5#%g|>;8HJRpgNq1gmmS$lp_JtROp9egdP`t+5gWw4t(l1^yker@FZr9i& zWFK-#{$fh1D&?EkA!I4yZFrf5nb-7!=a^T3963wh`N7W5?lEAIO3OvPzRKgl61uORT{5@vKRV1lG%F_E^SWB(t>(~=h@ z(!ZY0Z;-xlj)x@dxCJ1J-L7VdmmC6?qz%TZac9NX;6>pG6Bz|6 zc*>NKwH2wo@U?F&-Rt%2(kIk>EV46%^rex{U-)F zg(#ndpnqqYEVIwN{}cyG-Ba_J3X=0J_lBy7VAS3b=!n&67EOIp3sks_R&h$(b@ zYA^ds~ms ze|6H#&>Bf-5mrHxMJ}-&aiURIO6;9yBAwVn80H;djOUj>Ld2n2DE8$?VdQwHs@>?W zeqoCG4yXInuBb=CGO-88B>$9y{H&L-6r3GHE{1`=eJwH)7^rF)KS@(45%9v@O|acb z)q-pC-S1r#{&Lv`cMtsE#D9ars0Xs~UU?C+1koqhKZH-u{W)2!MUrnwu>v-I^`dY)i^nQ<6Vg*S|3EY>z zQv5J2&#o#O^Wi#-eDcNKjnGGz0bGF8_m-eKM7PpRGB%7}{bzD_bU?^GPzasn8!Rz9 zE4&2XIM0+N=555cHwQBH*MZ#ar;U9@}RUIoVHY6 zx=@n3-2i$!nKU_Pbw4x_Ap5U3T>tR;)=@Z&Ge-8JTx~Nj)m$CC0GOsa$DXPL{H40D z0x5t7xIuR6yu`3?n;J4g&)R5OS`L7AZds}y+#a$!h|?GCRrTa>yBU76Wxi|SsEKYo zB%w?e5hsTprV()of1HZFX^bw3bvL0nvqJh2x&~q( z!lnE7{8rM@THau_$iY6hKJ0yFdcX-=*jV!gPH{t&1V6DhvpiBD%13(rALI_Qar4Yk zYjIR=<@9|gzBri_NGl(v&W-O$zEi&0I(KccO zS(av@mt%0Pg3)8ML4{EeCv~O$aXxKlO{yI8vhcTasPCe zX*4FXUbui?3Q2nSQBdr=I6JAD%!Vk`RxjdK8&F9XchUj!dWQeq=NpQ$CJA4Ye2d37 z=lnJh0{7^Pu;P0j?f8kw=cPvrRx>8iuRR^rK=wr|jMwimct?~pHK~WmdwEkhK_9I` z#ATp2PfeBd1sZ6A!1SfsNa$yLiBv!_z_$`dPZip=9e5=l`wkFkdw@qguwRPy5mf_{ z#n?$|-qF@&Det|{-B$g?7VAnd(1<-om~Gw2KChR;9!V~ZR^#Yu$0)c9o7ddLg6@p? zu@avJW0{X~AIQr=u981RRsH+pFD&nBC8m>xj9SDkxZS`xXp61wvQ1f}hIg6Anb!(zCR2m&vycI?gVeING*|JtV?bFSpan%Y zArvh7>%q1ZadqwrjgFBe#UN4h`@>v)8u4xnuf#BHCfh@>f(HIULA67QsWuBU@-My5 zP88-HAQBzh#*5-vP;@`~UC}%RIWCDnh!7AeUpXZJsiR*wYdJ2mYp!x2QT^|JwEN7LGKv=MmFhJ+x0pf(BEaun-w`4mKK- zTpQSm@y*ix+4^o{_RTUGs&o6zk}B!T!0MPA3F_z6pxoMxd>`;FMTFhkslrmie8TQh zTAXPyPBQjuNj(d?2d(s5y3~_zrjR<*DO+L$@4azC47I0wNNLc9$MET+HL+6yS(Zh0 zW|e@eTEo;gy-y{072X=}J+>118$Gjt=}Cd8q5H4I?f-}t3TlZ;PFl7EQ&psew8Rjm zD&yi4NJ)~GN>z|{_Ry(w%kZVqc9h`HFsMjb^tr!B0kb?dzB>fH?2UUfX80`%0YQM< z!Ps*czfZcKY9j>l{W;ch`NDdF!}3BxO+R{&L9j9_V(i$Xyc17OtOu_RSHJ1S@`~fE zPIjp=J=fwXRcF`0^k%btxGG<_vsRq(;fU> z*WL^LA0tMG3FQ7Rqy_$qN8?nQ5}7hdAf$RUs1){MwGw!@@=cpr-s(gnqJeE(96|r* zc*@F)tCrC3?aBAPlwJyQZ2)q!-A2~8v-%<~P-dY;0N)Dv(W4>GPgONKwu|~&LFh-9 z{ze}H??5I;Y@yZ6POs;4eNZ|E_pRy2xvV?6$7Lv;6BWY~YWF38%XTk-55Tf}n zHbI-8e3zz0R%+gLpvY`SNRa-`oEJP3x zl!&^30)fPa|M{?#H|I9%zmRAI-P>>ftZq}=3X&*z8HCZQ8E(+fR(FKLn@qvy``PdK zJaP(ICfZJQ7BDM2&g~+cJ~8i%4f?&QHZVE^IH2191@6JiQyo(EgH87M&?I*v* zVG-4ekKpcPvgv{6C@sH^HJL;80n5`C$dyXJYIY>3g*$ijWbJKt(xw`@%dlys*8BWl zH|eyq0T~21_#}vM>@q}*iB&cNL&vHOR%DW!Cqr;Wp z`^1k@3ixyOnn&?aucCmwHK_TWm(;AWcf&X{A}Ndn{mFIX-7H@NPU7v3&t4B(_y4T4 zQ;$_r&!o(HUU685?*rx#S`X3T6Lu%XD0}cY$aOWhoxx|!(-Mt z7Eal$!_Gp)(oThFk5ulJya*;n9K&Os8QWl37~66L(A}Ta^7+bPZJu=uN-(l)c{Kv&OCj}wNV}?i+qk;YW(@k3zlB4F|b1e#1f8-n)a7WPf$K* zCrM^kPeBI<`#l2*3iF?Z6}(cY?MJVEat1w}8v6j>V0^z<3VIN$u}G^3a{2+^A8GWd ze2p4Svozcw?_*=yU%yNBy=4=flJ7iSwI5)IFh*7Ha<+W_TDDEi^!(I<(!r@y}o7`Q$lZ)U76 z+})RO@URV1hiR`v#;1k5QJ8X$IVLcayC$#m*mNXhyEPINZyW!`^ZuTb|HlY=Tkv&m zeX|_F!6TL#*-E>KH%!!rdkW}e!o?xTef?{U;@(l18AeKGdC+G` zi^=Y2OZZXLE$;^{YJXp11(0m=KObl< z9z!#|z%EeM-$Qg=7r-lL*T_}ET5xXqT2!&Sn{z$(y{6=55hwY3Szq~OazRB4*G;7v-1E|&!*Y}|N}pDFj&?w6ZC~-Q z`>VEG(}uSC1)bR9TPu6IZ`GUNUj&<%aRg*L2=RC&I8~o31tyTKFk%->7_!(Go+1*} zPa%8rXSbgs{SGTqvaAh9!8ec;Gh&@|mv1~$I6!$^9RqCowRb4Ylg(Tl0T`eFN?04r zuAQJSd8^a7r#t=6ijNEd&4G9aDIT6QPX-r6FCS5`&XHuxktGe6ub7P2Hor4#2Q~6Y z|B@}i(g>UnIy)W4AzEdxpN97c=KuVfk)?#$mlE?Pzc+W);wyif6x+FtIQF$1>Siwti9|g?-%mtz7zbn$7A&=_+Rz|kTFUs+tXD?9^E1Oa~X~H$srs$*n>m?I8 z^}h?D_DRGO_Kkws^X8UMh*ZEd(QSZ67!Xgm8mSYCxcl8;bCCI(OCGKS z7eF~h*2+U&2Mxv2KS*2sU6(H2?b&*Do#)56_tJ}-iciribBcdzd}gGF#qWl{=*QeLG!ZA#<&7*zXtcI^GY?bYHlwX;t8|5#bSBVqn3Ohh*U4nu;;+PLc7 z%KtXRSS&pyPc|)4NoCjw@C=5&L%+-J%;=ZPF%eI*H4>_=hN{N&jL1v%4`KiE^xtJ} zao$^j=AN&{M;7{^*OKlkIvj&%Vh&hOf}ow&;dxxhPVEhqo7--)&sdC4+n9hNUJXGk z-SmkpChizpPj^RUN+Muip%B$S&aD5kh?9yz%qcxErRH@(c$-LJ1aAPRaLg&@N3W{o zKj@l9qP%@kBo{375#*#0cPcB^%)aLb>wwJ|p_tlQhY|vVs$b8QS$cIMh%d4uIWC#8 zF%NXVYl8y!;}X1*FpFoX*vbkp=~U-CoIcAJ3X}0Wg|DSwlTn1)3JR0)5{#0#f9Xup z?n*kV2Xlt|_)zR7?~3oHPvvbN9O-^`2$sQIu}k;g)3NkHA^AVEBR`pNGHG*}wO=v> zI_FA#J$#UaS8EezErrc-w6vf-3EkM_gt@HG~= z8!U1{lX5unA59M2$fGuj@FQWE{^JDe;rTI$(Sl;LwdoITxC&2I)}+xyudHELsQ5w2 z=uNa7tVrq_4{pzC(><{Dp!O{LukN;BS zHg?auPbpd0Du(!#NHpD+plv09lS#GcN#eFaANmt2>x(OcR!ke%kR6Hqp}qrVA>iGi zrw`fz0}JlPqZ=Q+5-`RAGMcF5C0+4+T7Dt0fi$_%wwEmbCgn}8Kes!rw~8*SIrGUk zm4MCWIY;+iq->DpVb4&cPyDg8mEh;aGje(UBU~85AEum8oW&>qSv1Z#&(;=Y1w@OVuodtZ>gxC5h$~7p1+M_sEVb{D2 zWzxQjW5iLw@Zv}BJ$V%zbAoJEt^K#KIMz;FStf+#Z-0K;iA89%NU~ zfbm(``1c-tiek@GUiA}!gf-=1FImgFTKRrN z)opC&n&a$NwgeNd%jX3%)%Kq}M8;vII$u!Nr1raIAReCRfKP%}K{h2D_*a-E9brNR zFVWvD;~4tc!lsjwCMS)H-||g^SkmB8nK?yMj_zbw;6=&!T`a9X9(Tz34)o<{8;2kl zEe}fb+z(IO_qSLt+ZYU&oUAz8yD9|Ghj2(A0H0#Y>s-OOyKI8$)@7!}c5VcLs9-U1 zJ#J_6KoRL-&Wx8G^rB0YFJ;1oC&`|{%)=gjljqs$3mV4>$sFqbl9X*d@zib^cGh&A z-p9Ip-Dw32>rM zG9Gs~Xzns~VlmaFD}!AkLRu(fNA>(fVn5yJEZidaAocV`$Sj=X#P93c-r?4#B8Nbu zrdKo+*Hxf+wvZ>N%nhQg%}HyhVRpG9(RjQXnWxI@mT(+6Do1e7!V{$NZiT4XQ8|+UCW`Il+o=hX|kjFT#6w9+~L!sS< zI~Q3q75onweaa}rq=xdO)>5OA1$t7E@!TG(ril;d|0z29aI@aG%#7;dl@+ozOQekN zdqy8aN|tUM=l+cu^B^ejP21Mxd?wzs*fEy=Z>I5wh8erL5y~Aj>SeMGK+R36^%|gX ztO@G+4Z4-CQ&e&HSvSnCk!jZ}Meh%T3^E?^aa1PEk`VfgM}JhNBIyk=2nZkLerCKj z=$4&MT$0kPHZZ$Yga4}f6;%t{Z>-SJw!Hs~dQc9Lg~YU+rk~J@h_#ivnaAT~`Nz|Q zibmfPjhHndh@zEC^JjrKSn*Qi*;S{Gd1uGGK+U5Z;X-ZzgUl+=dd=!L&lps$9m*j> zMk7LfeM{-i2va5};Xa*wuPOUM7CVf-mK$y+goUGpQ)gU(TzQA^^ONOfaEx zi`A!sE{UWsr?L~Bp;u>y2FC>PfEQL|i@qa^^skzEO~i+NtYq-CoYllJUglcMu1RCabG~*)awr^UevW3fHbz+QNJ^}fv(+`Pt_AOb< zUukC0I_jxcrgz#;XhfVqHUJhW>-$Y0yZSNQ_?Hd85RSz%*jyPoX_vQ9QpW4>yztRS*1;oq3ftHiN%|1YObfX_N0YXuGKEC zziw{25DUhPcS^piNfz%gqfBgN!5e+Z{3}a*f7Oo<94ZXiK9eG-gU&_(K@fI5;o6m2 zm>ZY-)vFfccg1M#tYus<%ov;`aq)zA2K5IouoDQ!hf-e2kZKe7WY&vB25UvI)<2FX%~MdcRa2-GEER6kBK}xfOj$>3ejRQ2{JST_;@88ITk=zEkbXqiowB!MM=ddpty)7)*PIdr+IMm=@`)2%l zRQoM8?ly%H5F7%{b$~6j?g!Zr{WG|~?~WNNC?$aDQCObnpnvBc+Iy9SO|GRRYB@?h z0}xXC1`elI`FHZ7Qo3-JH}ZWPE03{e7)Ezl_HZHtw@mJv0o(^bz?*aMclLJcR5s~1 zse+5hh+A=$+cfvdmyDAxsvciPRGEc^vR3yr`_ zgVICMj!qG)4#Qj@#8Qs+miZz=rB711j&wN7FS<9Lyd(8A2I~@MmlKr!^7Q#vUR}ZA z5kaW&F93a~A;&OiM!hi`Gn;PIK9v(tWI(7$k=<~-DmsfOBn`|*y!oKDiGpiT){Lr5O**4yBzKxVNtmL|CdLLhhgtjUdS~GJ z7PC z`0!c@Tl5CXEC}q4lAfV{9`h~Ht&O^BT~*x^XV1^|&#X^5Rk%$px8|xKXMV{be#}1x zx0R9LS;A&BqEdoBi-PSRPd1<1_q-mI(}RNf=FnTRk?%Xh&T-hgvvPm-5Vq9*Rcu;^ zzmJh(w@sPE5GBpR8>L6%!O_Y8Xd-q`RxVUDB%88}27vv43!3BrDh? z&l#XFOrqohdbhKIo(s7#&YjE*TT(@+e~gGAHDpvs=-me8f?_9wIWze(DH>AzL?pH= z{Uk`xXK>g_Xlral`1pOZ`71pU2~ZHjHR~$lqOE)A#~ofw`$Qcy8D}LMVxRv*(^*DE z`F~xXZiepe&Y`5!K025E3WxJ=p&P zVjT8~MEA2&alooYgeOx>a^_$_H=D#wSl1h>g3++xu=Nb-O#ZNoEws{OZxMh2EUQwIl2K(oRZ8PHoYX(B`tx|Fy69^&U| zckvvLZ`nNHtJ@TmQgTXZu8Kr(_HFTB-qv7kh*S4*NBQt0g`6AjYq*S;rwlf`jQ6iA zzHcpqc=590I7kwhwOU2(v&y`Oy7W(kTRN;2ju-)JMMKY2g7f}(mzIltN1C8PN|WVu zsdddz5?=CCj@9OwOk>Rk6BX*XC|Oujf*vnekqSUu<5c| zXG;U&%BctmtU~7E#>Wua%C>F4cHq$ZZtq+Cz3k`?@x}MD(Pf)q78nLZ0Uh#Ck(ZoA zFVY$7GGUF7gDdEq^XM*|{A{uP*rkfxWgze%)+{ZB8!Gj7urEtc|3Fdo;aRCQw5E-8(TwFVdZG?xo)JapD`$Bo&3$0&BHh z=>RE6$1gP1D`gCPGdgpLU>vNf6=ilDkC~Y2jFsGZ=nB+wn9s8Rw5rAfAoZNw@h?_t zdXNfI^y3l6rkp6;ErxmpylY!hGL1(0Xd0A@K1z6=*+8~yKXetlWS_;MQoy4Us8}Fc z(oAs3Pi@=WXwzT+%mU{c(k)7Oh0P+I(gf&siHUsoRCE?>(_;nOxijMi$Q?L~ zak2=Sq8kK_R3i|cV803jS(M`)uJQS$WVsPOv4#haGk0X!18MJE8Z9ohrS|7D%afCb z)l|B*o5ZQ$6T*IL%f(s%;8F6SV6m1;l3`d_@+1ym*&W=9u+DN=%QGYFNcH!e)%ap@ z!exYtEVI3wv-gie@Wk}R{X=!!H)L_v`r_h{f(-mqN1?0gr^)b}nlqBYm+=-8HruEpHUcb?HCJpC) zEuP8d8U1^*Ta7?Q&`v+5+JP{YQu#A6=hoCZX)UwLI3!B;Uh(FvU^Zj+>fz~M9(#wpp6N~Bp*!2!sWsC?+BegOk1JM+whA&Il0f(-{xIz%1_;M3^QR8nPGxdON>E=ce^o21Y42YV*?Nf@1p0xAVUby5Lw|@*R zC@cdkO)iRL?BDEr1f$GYa??Azu_8?;nq=_-qfRR4#tg4?tc?AG!3KQMrZD{wr&utj z5*PEWI!y5x0JY{Wbl;vleV&dmK1MAR+#<>a*iVL3_vwcjQr%D>oiK-_E?#6MTdR$= zm5XrrhtzvhgEVdpZ{+`NMok#3y5$UA_GLO7o z@>I51k;V+wq1rD+K74HW(tmPAv&CYNE{es+XobVUr~M;4E=8h(pgB0fMUn2Ez^*@- zM}44DQpWAEG_Y6uZOvLq6L>hRuEyM@S9Iagm%BMIMO))1Zg|ebJ-=5eMR&YZG%ReZ z=jbbPi%*IST5z3{kaik)jNz->UUx7OET#{Y+*JefU7luBE6Jvw0sF^=Uv!k(B)#73lOlrT zdmuZWHvAR6-Y4ZuxY+eC;p1NMGsOPHaA|)0rr-6vu5Oa&E3817_K+y2EFs`#s>#T0 z*0QhbNBZyCij52+=}M1~7=xU5Sw=;j-)O5d#V4L5N~PO@ENCs6#%wG^_P_wD$T zq#k@GF@yld7rxoyTJe1I_8jktI?T)1WA-Z6v-Zc&7pKa*y%OsM*5`(;V)&Dhz@Kc+ z=xfc|P@T;a-qu?RSKpmp9TnJQeBwVAV9z&E?Hmj^aHaLFr&(TD8j}vuLphl6Fx>?2 z>91wmGO|He5S!t55~`086td~}f8Y=Kmj#BhDsqV)vtX}v_{BZnaljiJ5no5 zW-p&6aK&peE@=Dh2{Y`lzl%!|c(Fl&v5uNjG(J+kKHf*ml{;v%tbLsSMQY5^?XM8g zYy?P^?{v9xkl`Xw;i0CqF!+^Y<%$}5?ULNN&Bb{*Zsa0_lOa zCcVaZc7BKt-^5`D2%0&CXJD|^ci0IbkmZD)YkzOeYPk25z4p(incPN8XoC zqI(CV&0M#FAz0D-f)V4LJJXo{;#hQ&Wve&$MrZ(l-Bk;(co)xz4^}oLrqvxIY2)xs7c)@ z#D#@_&^lp=h6(ZLvj*H+Cd#nmh0!5wBn_86J3M8M;1$D)QSq*>f6$Z}vh^W5a`^zf zZogbTvR^yml+3*AmAVV~5fh3d=%)nwq_v3c zh)L98NUM$KlzIS$E^@wtv)i(Yj2QK$qmfNT(lQb87?pjtLOD?Sxi1Lgmq0fX1NPIIVr^>EBuG$$ybw~q<1m?oo z@t?8g;3*_W`quYPmXN1GJH&si=53yfAN8Ivy`-VC3@=xm-*0!`o-ZZC5kTr+TZI-o zS0Hp%*jn$_eVmPi`0JpN2kxnS!r0BnrRBM9D5}d7 zGA`w1ZDu^SEtu3dL&0T$7j2LkwGzb4ERyy`WS&?Rq!zLHhK+&(rik9++pcSO?YK@LS31Zf_Rg`x6?6dkfPoi7<`1hrZI!1De3-xUb1%+9V;Io(*Tma%L z?wYFNRw%ChEgcM`?)T`x3)xWtdZgZY9_;*G)#16Yjo>LG16?Z#8c5+}bCD8?;qrA^ z#pY*F_?Yb1-(|`}ie!H0uKFkpY4wG`j-_ef*knl7K_UASU?Aqt-&4<3TNy^!9b zllZ;jbyrq%{~fpTh}TPEPjOL_jENK|c8*sp$4)BMmltQ{_@6+4lGds*E@64Fdg0n= z@4X^r!AO%;?blNNfEd#QK9o!W#mIf1MlD5G)3;wjhiUw|-%q~{7pfTZCv_0MBXO8G z#QVszS5o*rcYc!HwD4iR_MlCObo2MC${dUF-M(Y4^pCsmbo=ZiV}G#GUG^<4-car@ zWdP1n-!uM7t1117p`QJRibO%)q|mN|!bIOye}+EJMB7B(p`V+%T|kYY$%UUDgIdxq zGv?~_I6Khkyqy{S1vj{f(`;h7SM`>H5Wla>p6cqc3hJLWk#y4y81`O%pFvH&>Nw4& zCsa&a=!RLYDI=E%`G>P(%I4YTT0^;fDrPl&`57r`6pH;EON>64%^hJRk1S#*W%GgI zx8UKs1SM=}$WRiqNMs+;49K=$=V8UJnuyQ5uCp{yn`wB!!rCv}2MauhQbs7wLars4 z&1^Pa$kReDY#QnyrCTC|Omd?OHV)YQBNyiHMU;UY{!B8$4){RfbnX&=-D4iMFyr#` zlbIU_SJ+emSa_SZUnd+kCBFu=Tuh7}SgO=Qh@I!0&PB{Hj~j<(=2-eq?9=B3#&zP4 zaDAmR{zFJm%uEo0yo&a(35(pL(pTv|yJJNyU#U0FBY0eZR_*T|IhU8$;u2CY*TjrD zg=6qv+h!V`)FWT2`88_wH{fXEY-|;cm0&meOadfF^FN&!j;NV6Z>WFKH<5A>z_WM! z;^b?fGCBg?Ld*O(P#4TE?HsQ1Qb6*R|-~4>RpR@Uz{&@BMWuwG`o8(`o zr0;i|&{_-b{h%L#2-%&tZRg^5*<6&8cjvNq6?8ILd^hO_r$L1^tz|zf*l$W4|AH>8 z3zsD~K=p&x!;Lp@vd!+9hNGad(>2m7W8st z0#w%Zyaa`{d0ml@?MparH>ji4SxZHM-qgdFFG}xp{30(ivT^a`T@aOnNTs-_zko7*EaCIF@c-q`3g#YNriMq3))KFB~wfbDML zo(h9_2B;iP*=E_s79}C2*7J(c#kW%dENG64juflT=|GZGY4WDJ zsZ@%$yLSO}D$QzjYwRUs5RWb+n?5lu53|Eh0!(O3D#=qj-u)1yWV46@IfW9i+*b+) z5yTpb=7!HRT18#2`*>F%bA7?s1{Zf7l{V##WEk+u?@BmW`)P&w;&WWjo8H&;>!s*p zH80ch?7F+FKr1iZ6-FSbT5fckYV>BtIRd(77fm8B(KkVfiMo8n#VyVx^u_Jy{J|K- z?J(71{aXVt%|WC1o(xFEC~EWFZnt*QGX6H_#QGatJpu`U}0kK0)J1U#D^mel20`@hMdoy1~bsprR z_&{LNswv$hZfIfQXmgA8GTY&IZ9b=Gb^1zGW;UwExYk@pQzDY(11) z0#_dbuP)rYR4#sxMBz{lc14I2154bdP+Jd}bhO((5|XcEekj+Q^l~T}tnoJ*rz#&B z>AzndS)NcuUlMx${a4zKCuO|k;zD>Fu_@=cJ(V0?HAmG1e!@qiO=4q`q14f}BkUrH zUpI$Msdk}AMZobFivG`bq*F9?Fn0vffJ5@eMj7uzlX}h&yIuIuMvEyt-R^loYf`(Bn8yMCtNhZ?F1zBDm&N|YR<=Ui<++01}^vh%wh>zyc{KT&5MR=FNm zDr`kP?WSd=$x&F`#DIfINFHfU9f|S3-DjMEj(5&#m8>5I&L# zWY0L;IacpwCHIZ8ebgT=h8LK^eWGD=6Zd$ovIF1PMlH5K%#BW%f!pUG-(547@k-%( z!fdR!u0wt66UF^4T9-&Oj+DBCHl-`by85AQSijA4eqjbQ5BX_eDVrrA)q}N0e;x1R_2n*Y%*3?or7PqszoY~aRv?R9tNjp%6G zwN5HIEjWDA-3b|*IPqwBOj_{kg@3^GA=lU`xOh6FJ$d|3CCm=&5sK#IxNL^i;hvGM zIl^70XIVUIxPs*pIpJcJY4WJ}CcE&cUsD*+IGm!d0CI;4XYh&LU)aLcmTJZALY1*+ z9t5xFYEp9Q%ZGK)hQXWTOV3t|K>5&ePwA6yJhFL^=WML36&=ss=Ud~lKv@JMxA_1E zsqp)Zk8R7B6&v~S01YR}8M*c-^ON-DP0gF0T;l5G5?TKH`OfctzuumYeONjU zdYeyruO;=+OaN;M-qK+sq;J}hbZMl#MIKw?X$j3NpOUVqSUA>_;EB>fZrlEqF_mpX z=d<>a@Sj+VS(9>y@xK*b(5{l-h)IX~6vK;OCH?ivz@04O>v_WmfAb!_1j601KC-ax zaM|&Ree*e%0Na(o1z`~%2b&&zUVH4Fp3DH&yk)bQu#@_s9{gohyE=-XE8$ZbUJ6@@ zN+hRPiVq*jL5}EW{9QzX_b#8y%CO&_9mxNuq_TevU|Ac2u?ffoOvHSb#YfXXJ0*iB z*VCg~*&OZT)a`*BJNnobsVu_cVmeZ&Qp*3$C@+RYN)HDzIHsD^iv|6X|Krt*AZcTF z@D?0AT>QQ-rRi5eyTFv_dFP5>-9~Bf144%Bae)-13igP- zzdNIOd*9GPpKy2;>_jw)jLK8kwkpnDskQF8JkeFb8HIoPeN-5hTM`GJj-%IH-wi6< zM>x69yk>y>NOC-!w>#9JdOPRdg}!S>v}E&y1R#m)By22-{{#sIG;Is zKsqPr8XgMrTHd2r>3!F4nMj8XwS88meck8#?Mn3U46Q;;A#K39C)RbWXBpU>ooY)` z9gMOqB)M}Iut(=|r2p-DvHU^pR4rcW1NXoGeRo;?9h|-tfS=vmkK#N*zfSs62z8?S zh@3~~uuniQ>%ckLJs5D{^T&BB+-fbQaEy7!A-M@#UE?p1Ix)Oh2=mg4y zEjvJ4*;_g4|DI@^rg5xq`&TU7Ir)uyH%N87*lZ#7N9{+|ZRtWSS^aFJTX#yd@ogc|3NMP{g6ENu6Rj791+ffYbSAS`xTE)qCn&SM+a zXvevG5$!|lz?e;zV~nMatcnLb8cqxF%kyq~%&8OZdeM368cb%I}xVYCC6V^78cE^bBP=| zM93mfrrZZYg6)gO(LSgBcP6KAnGLo4SM5AatUTX=&<0jYM_Qwj8eQ4DTz__VjxxR? zG}}~Lv<;nQjXYD;E{6(@_C#vh2Qyf;3KQw-ou`oI?%^4Rg@e{{uw;)FX4cys6SVLN_D&$b- zOgx{Z2%>7-)s@|+@lrFz8sc6w+zLm9lD7Q=#wyU&=Qog$&;cZ4sjJZ#(7h}5&rn}n z*7YBCcBQI^;hm}Wj7?D(Nk83s%Y4YInr8(sz78W$Utkak$f?WH81$FFewO~Uob)^b z;QtxGb4`mhS0jUmJYAgX5aG+SO{g4#Xv-@Ta!=qDivQZ_$D#AuMa=Y8(bwDhEI?_p zFVhq13>tS%Lnc(|)EO09ZlKz=M)MCqg>hb3$V+AIF9!|B)O;#=CP$EIe^`A4Blm5_ z^ognOBj9^#<;V9HC_Fi`U4{(DZJq+oZ1c@is8AG?|)bpvmvI36294@Z6sMnl=x?jV%uRT2sc_pF|GYz==vlsli z-q8o)LzdX|MyXh4j~kb?C8RDX{NVSqAxtcU*&BSzictm?<{~%mtO*o-Y3Q%%BQ>IEEG_+yoV_lhlR`RdsvaqkIF)s~{bU1W+s56yI zHjtXq^trqXA$*zMyvdGx(fT*xEAWJQr}58*G7*e>7Y)6`YB5pb&^26^(z-@5HhEp4 zl=@5?J$Og$Yr1^0MMY9cu0H#X{^2=`@o8Dl2}0D1O!n$VN$Zbq3KdBdkMEc^mlSOe z5V4*uBlWYg9^auCH0-*&1STakmp2^t*8c11(H`gq(K&a$f!)tDH1Lq)slwDCQW6Vr z>9ojIQDy7V6Rlh_PBt#;s|L4e%)*jbI0LB~$ZY9s_%8g^4wF2zNw{YTx0|g25(B%| z1`CfGAnvoDNeLIQH@Go_Pk^2MYjjLxx#gw3lMr=&ZB+{#3jn;$|BnnM33ZuvyTM|> zw)mz{brudx@LUUOK*xpNM}LPC!bpzU0vi0-=y8)u;{#Wk(GdiGySAIiXy@#W`Erht zJzKVGMLww{0zl0#*hNMm4yNF4GqX zk%>4xZn!nz5RFSJA!^Lh#-PW3*FDdH)r# zt=cL>3~^DWt%XN@K78V7?t5hH;zL%p2)i@zr$^r;1bH>e<1qDK;@=3&lKYG+%#S@* z;>xAS+lt8Q6Dhe9YdH|(92b${l7&z8AApfm6iVbq3i3QmY)n^WJTR5eZijJcM%!nU z^>jsi@p%Abe}ToaDxKjo8S(^=D7fkTibX83rk7&bgHz93eO8Qo*~@AB%ir*bZQ~7b z@C7bWvT#Xhcdocc3t_OI|Zd|~Yz$O_Iz`AKAa(CAlCrw_5{d?k`Vn^#r+@=U4o#ZS# zIi>Md8M*!qj>|<$v0`E4%WM35_1!*cmzdy#1 z%frAiv_bY;n{F?RY{d&oeNHs7-KJ|T^1yYps{_vA4&l{<#nbarJwN;M-}FGzR!*R4 z<43o587B&<<4b=HfWK{+alwA_S%>HShZUK)!)jy!Z{XcXLZ)x0%O6f0gy;Jnlz2xb z_fYSp{a8aZNBca0ej~oN{wAZ7&7U31m>{mqHSmfP=B}+HI9=Y)*pD<6?k3goMc%|t zXct%cmYqt+XvxSlE+eUQ!+MYPnQvr@HMq&?5WQ!CfywhJ5h}p?VSHtO&8SW=DpI=dO?; z*O<&(6svr0;K-i&eD<~Xchnb6uO3EO%%0kw%zjEKabx862LYd|t$$cXTvyjEsTGyG^b^KOy(18Vm9impA?I?S zBpZ-FudW5;*(~~9k}uqMj&+s-XI%5DWG!1Jhg9A%*=or^X7ute!AEwwAcY7ofSk*DaUi;D{i+d)GD} z@@V2oCsk+!eszOlt;s)y9vHj?ce4Hb z6XBzcb^hq-w_}?aCg&Txc|s;fRc``ln!E)&`pNh&D<5*=CSuT&XNJk$+q1i=6qz>p ziI12EIO3`qyQt&{p5&*oQ0<{x>r*GsgQH}uJMH6T=aoPfpqW@1H!rT2X`}`&FLW16 zjxF!{k~r`FQj=Im3-zt<18GaN3@-qT&6F1zH~2z%5joT?=!a%s;AVSpgm-oNf!&Fs z(*7h(NZ2<8en!6=NYU^^+T>2V|KY;F@A*jw_>X9V43hIFWg-KqAL1DM#6R$fc;)iy zYwUmSv2VA!Gt#Y~BS&jk?1SmTG&sIrz!T`v$Nw`2^ac=#bq zsY!k7GjJZ5Q*8?CaA~TATm%sH#*qn5|V0|(u%llLfD$+YJ>|Fcc_qHgns9uzBk0(v&h9 z{EK!6eCi=jl6^#74O11M9YqZZ6bcJFDuG+!P98f%eXmj8(iiO%p)~PN>vpaA|JBo_ z%;HXkN-`*v_S{B)B#1;ay#vs`2AV>z^rYwt&g;V))Ucsa{Yb#t z#f4V+(0jFYNuL6X+w`l`KTYbHx6UkblWxjlYdK+QlX2Ftv!-|ED=#vB}!sY+-_ zG9#>b=(w}=F-gwKFhYMY;e3C3;Slx}(kSogC;f4E^(b8rddM)#bJ!$@o;*+OW7sVB zgVCPo5qDPKIuyS9bO{(%V|Gkk+}rQRo>z5ae!N}vq=U(=|L0)9Ji|7J1yf?=KYqC| zm9IgHD$z{ouORd-c4C>fu}SZTVDRiO1!_5j>#es+lsEiS$<*ZkD>TE8^BwcSB#TIc zi|7z}rP@}kl;V&bHU6@-2jfH54B!Li?+6eOw~J)UJ?`1T)ZAQPWu(B(w{=El4j z!Mm8mNk41RTF9(KfHJXv`<<3RkhYyWjZpRs`%J9jU(Wh6sGf)+O6SD;h^^-vl{Ghd z#@{>_F2q3-%Z?tADJXRLG3=z~TY}a-)U{1~CvAV|sbVC`TQSis7hK$Sed(@@`>Ji* zOa469=2;W(JdE7&_#mlrP;H|4JD`^h@w1O3bs z!j&Q7df=uDZG_y3;05JH{1%CCW`Jl>$$0Z91XXGO{rF&J{)BQ5r4Wt0! z@0AF1?=loU-r-%SpwZqPTz2KT?xn>GxO^w)kI%suMOs2E%gh103&W!&tUJ>4jT9q{ zJPl-81%M^vx@ZkrKQ(==|BhGYZ@1K4N%$$K4Tl6$w4uynq~7* zs=iy-zk1P*ulsoWi#_Y^C|%$AJJ)=)whP?VF{i{aR+F4bHOH{gSlix>#_F z>U7N1iT{{vnVpI!1RtW`ic6pdj8IN_uk>$%e=WBjLJ(c+|CV-lO9|)%P2|K93l>d6 z8>ic>0puH_l0$I_EBB3?4p;(7bk&Xw3Rq8k34+gN{uJy`DvQ=O%ke5Gl>D@=wHASD z7A(MT&U7K&*CSJ=vK|)t0**NRr4KVMH(Q@BtdusVJ9e>_31)cosKaF9{o?d7J{Ur6 z$iIdA@B>uzSXJ3RePQmBrEEhyA8Wlsx)AY_h!8i3`GcI}$%5ptZhDGn19@d0jU}Vw-&z(UaK;7FYoy zl$|_$05^Ie_=1WCqUrAC@dUX04ZV%6g1O*6HJ4%AfAWGUGSrh28egot>@R|e;bJ+z zd!Js#WtxCVIpU0SZs`o4Jw5R=zM7)wy30Osd~RI3u1!O~a{G#xZ!6w&pN1H5h(C*J zsqR)saR*!D+HS&lyPyg$E;zx?!lj7UJO~~+y&m7CwzYr{0;+7Fxx_>vC0Q$ok4h|o zmfE2XqY~*KGdOqG3r~#SJ(9c6VUi1w8ZOOdBIl6$viE@$uBtw_{71p9qiUB0vs*X2 zBw8azd^uwDIK4vyFa27?Dq8;5N2QA0Dg70W>AYi_gr^L6I7H{x;|Qy*!S`vZ8fi94Z=i zD#g8BLw%7b9GkqQ=n8KzwxPqUBOdDMwX*Tlx|aED|Ewv8U-w>0^22jAouAgQSqzbK z%s09#@@QnIsom+0P;^4$$tf}0B{*1#%Wtsr_OVQ- zlA+7bS#haH-Hj<6i5OPQ4=NXQauB_M!PV>Iu-lK-RGrQ3CAhiggFG-n7#h69bK6(q z;omf=vyF#8Hom>|dImb}&6`)pEyMYIXSr2`AlglZ!P_^Q_)iPcJJi1O=aXO~e4&U- zTrUm>8J#QI%;-em$k3H*#&5F9{5rHv%3uWa#HqfCx1mnZXQTZWqO7bBMaQkUodPH! znSEVHZ#4o1b^Kg}(z{mui?J~Le|=?1fx(6oMLaj8c;wnmd&d27YB|%|UAo3oe=TC- z4s<_TS<*5kY2=2&-|O1j^C|WI%87rCLu7EBrp^G)AE`v}R@~au81KLL3w!-|K=^p{ z<6-SI_bKP2My7ukPfyxomI78A&shnT7HA01aC;)?*ia>JA0HygtvfK!x~Qysm@a< zCWtb|Uxtd%ucZaHre1&FFbALONILwLD0Y3WKppZnf(*SE!42Kd`c!kM^+*Ww>Z;nM z9fpuPKJ}i(dlYd#kGjFYMp8LXY7wE~KcO{YSNI(Oo%rfhmGZbYvBuD}iYn>Dl9#FN zk@)U+L3Unb($@6sJEUxUy!UH0ed~(g$p4CXj!T(8M6(nhBv5G;o)C67J_A~HKK=;g zzF9S&UtSvCvjsy~>pyj2OZ<27wXY$*sM7A6h$?ULAS|hv;fBA2tF}C=r71xt|5=** z_ae*keR??#bi8h1!0%;giD==l z<3p_*$Y3=xizj6Zh3_CDms+6;xHLg(4LJ$Qp2^=O1KXo%z>rGMZPvbx+ZcSOzb;W( z{LdK`u5BDiGd*o56+_ht3CQF2%Y?}VN$OBnwOfK~jIeZzyzS9wrHS%`Zre>4ph+zw zP7{<-pO$=R!1nupe>>ahu3`L#ZAymF6edz3G;`HU<0WaT2;RK?pFv0_7Nk}o@5{S|W>#g5%vwy1p(Drm?S@6{ z@ZrNhQ>8W`M{uy8y$_w_p`9WhVV~ZQ>q2@+x?|CawRUKd58sen(hyw%FC|K#$OqX>Y@mTr_LX0#TRXw5_M{cztMx59p|hS;fO||`a0n6(`b%WPU?8Hx z7V!{jY}AUlvnWX8<IkH$?MPXF&ee9<0L^^-Q7`^-7DKTTI7yb{6&C`bXM;=kAtn zSi{8u#`Si=2_I2_So~%KwfkK6R?vUGe~Tbf+_+kkubs*_>O(;$C5KV5gg#S3Y+UW+ zx}dbCd?_Zf6*@CrKEUXLb=~L@q5~;>mAWWCR4E0OPE(0Hc$lH7u3-$A6|ieETt% z$gv?%n{G*)@=@R9GLfbA#4h}NS;$P`?AU#D_<4=>-UW@A>efmGmIDXUB{@%$`%S2~ zi^l7lDAD-2l}ft5eN$XY1Qzrk%%+|k4^@4aQxsRV)E2^~bDugYh6>xabX)$h;=Jcfm>DhV$7ZVR&3c$yLO`4Ivxnc&~odK}id( zBU=cQ`1IBBd}8oVb*=B_=I?ig{#EAdl$lXz4iWYIlnALdk|x5Mu$_&;3ZT zU+Ny(c{wTUqJ!NOr@72`%)=&M8$P)W`%uS(DPt4axz*#!lj9Jk;5#8O$f-%=8MbU* z4gY@kvBFuMrvhF5`cWz|`?&JozI1i>;`w(%Wg)#*ISv)H@j`bRfob(9T8MTqZ`)h} zkTNKI#sE8q18>^k9dkM&lCrNHjey|9kUFs#%gs5PsdcA#NnkbvEkRSDm^?8&4oO80 z1r7XzdFyfprqup`Cp;B`s;@aPJn|{L76rPB+^o?RK4YIuLoTV9OjZm^rnUOEK2Qro zBe7^xVT!pi~1wMwP z3?p_4VvBu8Yu$d8EteSr09#d;?PX$;m6XBJ^x5D5!ZMqnEbF(G(T0G)iPIK(sLT*{ z3AJcHV64COLIF*Z6TDuvG4(kavQTGU{J?NwwIvJ5-F4r{b33gf~ry4AdOQ zf8mRmUP%G*1UKkR6BGdBX(2LAC?g-31QQt1(2bXJGHp~0kW%P|d-^NHxBTxA4+IqD zT06E!FZZxkd3QO9dO6yWKqeP$QM(WO$@OT#bCe7IR2h_A5xP;O+CZly8)rwZC-i_lGwW8w5jpf*Y9JeUD#;!H>*mNy+G) zKUP5Ou44g^3dY7u;v~csggI^|ddlMbsv_mm(fTb1U;1oRR0>=MpVlplesKq(vdkfE z;O~jYRs~`$Oc6<@8WK(QhA)c8y}tQT5tJGUSPY5COf1wxzui^xZ5EcxBM|R?lf+ijp6{UH&aAjb3W}(i;%&ovym#l4A|(@& zn-zg#uc^~e83+lSeda8llwu9#-!jh9(<=!#v}F^h`A&|n$xfN|aARaFd8!Z+3CtW#Q z{u2j2mM%H!78A7_j-e9jI2u#zvr=ampi4URCj=0UE_=2)erhD-3{6uOrSkr3oqXg~dlgsx3 zV~>teE9zf>gNqe>YO{(ZN(H8vV;L>GGKk{@h&CVljA8am{^Ox*sdzzGLnqYM`L880 zZfU9T0ueXes~CRI3;wPy&HY*nk*MC$5W|M$$m5()*+*SJK_(W&)+;~w?VoryQ+>J) zlBbZhQLVYDJMws9`OxJ`t_YK=^F&yNFTpQc+WekU&M&F5Z!-=QoA~M-zb3YKpWW7$ z(;ytrgEpn^h6}EFyG)2=?qM~OK-9oH_q&wOHn-iU&{8;i^T(+?$yiWk%2F_Von4*f z>xEPY<%l!C$l1|WTwEoY8h#TlE3HYxvWzgnqZhrQEroEHy}mmQ?UGnxzwcVUk6(06 z1=nJeeYM>4U`+&z$-jp$`}QrNI|c@ntz(f92;p(wSpS7EW`Qri(t z_(#H}Iy1L6&FdGOvh3`{Hf&zecIxvON!&BlwX(i{4WkYD7%i<8t6QQ*+>LxmH?6fD z8p9-97BTIZnf5#8eeY^a++^v-{_=JkG;udln_x+~?f4sWx6(oOMA(EYU~gS>9FY7G ze7Q(uyv7V~54VFi9X*#IU?d%+cjg@iI9{+2Ru(a{T_k5VO zd7O&d$hSxdXe26D$3MG2R72cutzF1x4B6cJ#6`N2#Om`ddQJd$z_QaQL91F%mS-1N zH+%lV#eMD^xwpqB`J2GZqfav@&nY*-lMxcDG{Tdm?H|dQ#_7zyWW2YW7GCWs$?7yT z@ar{!GDRc8s&lGrKK_-!m3xh&8xv zU=ISE8oKFPvQH#nsPQ)ZB+Pj|if9e8`E2J2|4pkqvYHgE5tBtZ5q-eGi=u;A5MWom zUnPPKL&^$E3bw%IwlsA1e4@BiYoPc(?23R4W5dZyJ`x*8ThlXu07MLng{bmeIx)FP zef=G`)Z~&P#01Fyxt-Wy?oFZ=ZPHt(u+y+OYra5DDaICmCBUn#JVhp$$=$XT;!q#L zn9}cq3*LDlw7T!qVdn+G-aA+@>>@jKz00%f!fqcMswwQtwzW^bv2MOL5;hplxkUtg z_;U3=OfzGn!jv@ziKTCEH7sjhu4kfsY3NhgOX_e^t!o4%x`FqoD4A$B>#sgs6}Jf%iZ1iz?f0#e4DG&rNbt!*#(pQKu&**_GxU@#*0}%ND~cjx_n-+!ig8ya zVa?olyS5?wD%7Dyo4bECw#yQ_I$kF)EyLG^=j~70{SZfNSp1M-8}qmIwl{O`v}@J!zUPA!rM)=Onm zL|xKB*HJ+{pR0BCASs8Ut<_ri6mFRf#tdF6p>bt$1m7|5FLHi8mDKUrnb(>v?{X|O zF*iX3pj~q&S-2l2r_UEf)=%4ut^^RPN z7lE#ws9acx_%b3;f@Rc4O;u9PN(id};>W0$te-xUCbMZd`6PMr_$2wr_5Wx(3$C`> zu3M83+}+)wxVu~NLV@D$?hb+C!CTylOIx6Lu>>z#3dJP_in~+nTxnqba@w5-Q1qjK-#Sye~rc749sk}E__>=%cZyu2S@)#P#N zZ($6^pr#E%XAM8m#@~xFy%4m3Y(sz*+j9M+)cnQin_F^@fSH}Xo1HG zQ+ucTLVJx+T24Qc(pdosM7fssLAWi$>4%F}-u%Q8iMNGAVLi0=V)Hs{lBm{{5W7kY zds{92gsWU*lO(3-&g@29usFM^wr@h8N%+0VHxvI!!Mq}}M5E-~Aqt0y=@s%DeSC>q zi{kOEb`8UN4->2&39($=>pN_ZPP>()z#{29c&HpsK|0qvS1LN#ookFZ;UA>(dZTmx zFkI>of}mBn`rsCb77xs(D$v*GoN^Ef?8AHH&*)<~1B$~v8`*p3ok*!Sd$DFP{NSuq zIqFjOWug?Z6E^rlC9a}pgk?na3fli({bVRNnqi2Ni?t(W;Ah(QrRFy;n}ImQ>?6Eb zz?6$iFZSCLi#kBcU+Bz2CL+@qeSh(F|NihjA||jkHI{Kb;%0PDc#q{5Z@F~P#w?R4 z8NwPx19^jjI?;&!4pocar%<`72I>cg&}(N5oQy?hDuammH1Q|U-(26N<{xsSbu)l5 zex%>8N)cu{%U9TeBjhc;bgkPV((-x*jWzc4vo+Ikqp{W913fjG1yVisJ zYTq!@JiYVWfmgmr%kRjIHq(Cw_}Uh3Ej@@&g0pciHT$;0w>)qG2ja`$PjH_c_?}Pj zWlZ?bt0SLWn_t}jX-vyXVf5305#3AQ;m6eJNRMkS7-Yl#RL0Rx;5k5>=4Al}%&H$o zXA(5!weC&|BAM3M1E#a*&VVL}sXcoGWELat%*rw?>g%5hf(y5lDW=hEs|PQ4qAtk3 zLA7D2PDi<>+m#vAE4unPSQDc-!e_nrK#1?zYEnqdUdlhdr<$-w7ci~zKf{@JEkZBe;i1E&EZtsLhlKE4p-#jTsM<<}35s^u z1oj`??R-todcBa)l5?W81-}#Tv;Fj_i$1#GNb?4}^aWNUin+mv%|%$+MJm`{x1Bj*xBkwRLV z21ccRcHMzbDN=B$oLWhbg(t*BW74Wlq(p?Aw=u_4-u$)A4aAzD6lQplej99w7<-gR0+$(^CL6zTw_pMNfq~}MweinhhzDzT2GB<9}T*uA1 zxs5`kLOUKpG1RJE!e@1G}s<)PG0f6JAK`Cw4@>xb@U#s7-P+&~*-*CGn$Vhq6&%qdSJP{RI@l0R4 zoCbYs*VxW`lW<(8W@tf$iv>o|Mw{L+B^+SyR+G}B>7rX=R-T=$mfaBi_sQw_GPA+| zEsm+e)tnVd?yu9|Me4sqNtP+b8WOUB$CtrRJOyTtq=YU z?4QvaSvOytc>hTi)%H2iDaIB)2Lh-*01mU5-P!Y8h!p$mZx33saD~wKIAj zAMGu>NfKunirbMli9tAmQm&j)+h`PNn$gbiy74*Yn9KqhkS%K|6M5U)Lm<^#^sgB6 ztPUnZG0m2{mqqHGa0-xH8c8}|nJN9$dB-vGloAv{b0;y+N#AU7-G;=VJAhTK%kEv1n=;S0GbXX6)Rn?vIrV;)2?Tbm~y3#HI2 zboL1IGn~{RGQe>tf$hc=*gc057krmox;aiWvA>rfX}i93gq~`wnu&ooawlG7g}A%4 zQkuZQdJ~`e3z2;7CI(8zXU~k4dsSBP+|*^K^O|Buv(cwf&R37nf~=X3FIx}ibVZ@g zB;HjJLCwO%>DZ}3SK7<#uQKqwma2PAA(8k|L59Z8-u`CQi*D;TSrYmF113G(NxaBx z`R5N@q|1{;Jvt+qCM#FLRuo<{W6EvLWw+J&vUD9`PVVHxJqZsJ9k<4DXl-r#@8Bhd zJm2~#>)l`VDCVHuK_F@H&e3+`Jl@aUV{MS%B8X^MgFCY*sx#xEm)Z5Hu^-*@>NFbP zZ$c%+$BnTx>p|<0<7h|w15Z=)B2O{!@>qzkMcVZq(_7bqXY4!PN}yv3TaF##F&*ce zw-YYpH5qP7YesuolKtDJY!wPRp4$AF{Mo(imTiFA5OSXWvOdY~@ z)QU=IXX#fDPk&b1eKzYHz4-_dsr5EIG+c+(Rm3<>WFuqXR*qT;9*#Xe; z2vOh6es%G8Vf-@S$y`F+ekYG#RAq-S*U^Udq+1G4XLRDNza?&?`DQSMX-t!}O7ZED z-Co+&s8Z1!iVH9lEg&=|>y>ubJSDZQr0$ZE;hgk!EI1{)9L{f=+MQYD~ z|B@6=&iz_|{LzQ+9kQ;9+sCFR(seO{>3Nx(%aoupeG)57H|U}<$7M;onLTgnuFQ@E zF*}dkp-B%xP+uY!%4vUA`w9P67c%nW!{JiijhvTR%=I?UmrYm!*-~oEzvtyxFJ8kC zUm&-p7~H4kt7Z8T<|Af|)vS7RilT1Hq35x*uwdSZhMHP@l}s>AWvUkSP?bP8X1GCb)t-E7}{T|mmFkqPCn z_}MuEhjp8C_CLM2e(Dige=tTqoqV`SJ`YlgBg^tAt2(9r`a}&JdLs8C#7N@WiloE% zp{d%Hy;ilwrOYF57VVu#k;5$3dv-nkQi9fKp{TQhbZP|ZBFF`c{=LJA0w~llc8fK1i&v{}3>DLp< zLf&H20wTzV@DwxX8any|QipCD%&X%*4-VCxi9iDL(;N%DkwzocR?XSHZf8Io7T-+X zjSGDhIxmRkimHx^{M_L9*NN-!UH3s6f$sBg3MXY%7%XZawLCW$X8Cgbo%a zMI`$j`kC0Kjv>#cW$F$8mT=&HhfU%wEB=*&)O@SPFrH%UsnJ2lNGb2ltO2`j&Oji4 z5^0_b14$~d7COgQ#h4_lobFGqB}Vz}tCydp6iQz}=% zEhpDr6Vq(t5v!;nLfiDOy8KNGVMk-~t1J(o-&#l64Q`UyK{;Rd*hOh=H2M^wrrfqK zU1@xE+7`j-Uxr-Tj z3485%{hWF8f!+2hZ$l@1W=|v`)xoRg8%5?GrU78Gh~My21q;>t{n5`MU-;v-43T`$ z*`iz;xD2BErUTg#W$z495l)7H9O6B<6^^7#th2ShYoREC0&o#SPQS%*!fvhL%7~); zYh`Q$kdDx-*(F1(2Klwal!RR%x}Dga}(ykhn(TAwP_ks z?qEkSjS{CK!vT_F@)E!WCcuDp%X)`BoT#*8)jej#GcANm;>Y+;pFcD*z1>z|EGVqi z4a}~W@d>p0@qHfhx`2G#C?952o*pmzC__?gOcdI+q)!6jbD<45p$_pkn98pKjU}LI z5byScmMUfl;07fDmg|qhqMMAPo3SJ&9$KWyNf7D7Z-DTtSUFEz^XZb~ZsV6(*WU)j zIeBTYuh1=WlEEkPc7#5a6x$Y2k>kj&nGE_n4K`tQ*uG6mq`CyNUyCwk+N1jB5 zp<+N-(6DYdS zv}G?UE+kHz4day|<4>lh5o-FoGOGeuv;Fydis{uyjjjbDEDyWNqT6dAl$^yKj*o@^pdBvb$v_(GYV-qoUI1iA|o zA}#I7tACgoCx4mbbbF=qCoy~t>pvZ-hA;Vzz%bvGt_N-beY=46bi1=Iso&T_UuYHp zjE{rrpOClcI>GsG;xv}R;W6~RJHxjExR-`AUpQE*;#$#W>kCA{y!WW7 zhEna#qy`TY`056EL71JRyeLUAk|p5BqOfMkVloxE7@q(vjP<*v=8i&%z+E&&xL%mY zZ^j4h=iBM^uM~fQ&2e(RIsgX@2jhQ53o?gqqpDcEc(#xx-Q8!8JJf&4kC*Na?v|L` z?|$*@a3*{&2{iZ9dzsbp?Y+y1^qqc+p2fe6zJ2FNztiaH8&}6XkI-Fn=6Xdw>xHc2 zNz~kHdIg!hk!>6w{EFV=O#2I6sNfb)u%=T~OJ;%Wcd)|O1Y~tf)HX&7Xpr8S4Zb8v zkW5U@cdqWn2I1s|tB>nx(-LyB!HBL}g0-BJXH*cyheV^^#@gAhx!Y+wrEVU(vSypp;qXSuA0-t#`pVKgiV)#D&@ zx>6PM*9z4(X@ZghrQ-y2gi@N^6u)2+(8!zKet9oWgXuB8^1v#Q(>F4vcC&PP|Fmjk zS7%Smp@$6vq$J^@x4?oU9jx&u@{p?hU*j{fK&wzFy`6jj_hPy+BkM>)n^owuXD43? zXzuc8I9UWgn67Rpx1=3}FX?qdqP3NrH_cwLADDR=CAeX98JefnK1{3qh`64VzXzOt?-DbUh;88&KC#IzKA1d%r?UcQ z5ZFL88(535K*0*i_{pX>&U$zbWc?~XMlccML!Rud!+Ubqbx&dfe~~*W&07L-{Wp@j z=1ky&!awQu5i)4#SDBkKpn!aGU60LbVxo)i)tC|7f5bspXWHEB)c?I@P;GlxM-iT}M$%>F$|+rNb)W zx>Kyej|D+oe6lGN7iPL|BA>rOoKc(q@*PGd4{t;SXGjY*sd`xQHfwE+d_C5Yz7yk) z7g?aRKHI09}z7$7yh z33GB|{nn{2B}$!eyzHMZQ%Q9we4yAf0yl67ama{gK=zseVaN8n%RAe;W*^G7*oR2_G70jIbfWft*Vrc&V^wn z6x0Gm#>5GgiPYg$B;T@JcU+1htWem`74R{+De)353%Q0eP9ZEE)V zrRwW$hgPs`Cs6Mz?OTorDf}A zuSE8UpO7n}6|-O$tT%J`Do!0N64SU%{UOW@ak;Yx$7C3(i(EU(R%Zd(#irWUmy#ZH z!Pm-DHN$^ea`JYav8NnW?KZ`0)wNv0TJ2h^T3XIVpr?QhZj!s}bI>Zy`0L>oJbDR9 ziQt8xd1PM8>i!$RIrt%s6;{D2O!~UDXoJkaE(|`7<-TGa z=~%E1d?YXT|EusY#(uQJUu%%{R52K7*}B-vm%U=rYxd{9-KQARj`dZpn@kM1+-|d2 z{S1*9@WuTA?JELf^&+rQrYqvi=g$ZINljy=d>=YM^W6X(T4vnplJPXGbTpvmry1jw z^Yyn@f~;BVsCNEdc-{wB=YoiF_${JC)MrBsNU^ZU{c5l_!zx5ZK(z5#sB9X@<=1jm zq{@VG=c2`i^vI!^uve<<8S`BV)QF3uS3nQiW~-2C-j|Jr!u!R{E}1PPa9B}e#m_Pd z4MFQRXb;`P|6>e^bigNn`}HRsx|TJxM+C!n^_Z<4Vk`m5B%^hT=HH2c8$KI5O>3W> zXytmCRo7NV?5Iy98=BJ>$K)onkxw{yMvd@Tby=C7G3Ol5U>&sClN4{vPPQeYbK)J= z6|t3cP@mc3j!Y71FRv_#QGn=7xe<>n+hVE-N(B~WMS`P<9nr&2Zm3YGqDJhbOwiqe zq`4(%e*6czkR`=Mu?ltIz`^?>gnRK#Z=$q!;E|Dsf83$E%02z!Bpr)Z zz3{Nh*h&3grU6VM^9rnZXimZG-vf#$zX8^#`E*yY4NtKa|1GTu+tP1gLh5ICO~{W1 zJS53~4m8!-Z!EO<#EKSp^IN>~!6^1~fMO+FV}544XjTBn^7JdD@gs z82;mOd;8_yCsv~fpA?fS&^mKa76sXBvr+oRP^1z%nOA6Jh>d}xW6C!Nd(@SOaUw;$ zO-i_~5>!E}g9qpvX040G)RXQ##aH{SE}SYnlt5z{JkOi}^!fNXks(akr;Cp_7eS|6 znZNS|+$j+xPwf?-ErR5|Az+4T$Ec#niXxUB*$$!7zKq-&FJ%56%P;7JKnVvMs;1q9 z&X4JP11>+_Oa#$QBkqN}M5RrPmsz65uY1yBr6>HebT~syyh>M!*c-n!lgS@&v&4Jy zU52TFl3Jo)rvIYY_=|zXN{D^+yPx~tfwIY8p)RvLqioR`aeq@~JuqffD0x>;gf=M2 zx9+@Y9%PvX(7}wLhN~L>>1`6gM(FeZ(JFTDSQtt4xHtZ^0|X(D1X@L%(r`QAiLTaS zA<(evaP?XAdSv!p7q6u=6`N1rSM%!qcXY|vGVHbl#d|N*!}&;oi%5YRVXfB)tIQ?$ zSv)Eo@=5#X>F17L5fT{>GWp*9f;<*@Xpt%vxjxUD6kHw1=qTDz+ zi1fS^-OVnW&yVsJz@`7D$updDTlJ@%c;n!op7^&>mgURF0g|urF?mh6w@~10o8c4n zP+M}z*$4xMZVb$9wySLQpO%oMU~g`{Q3K=%oTEexa_gVg+4PMWJW06Y*gwsWeAN^X z9ai<)0CY-&S}C2($1#I6@$(z&I+Ub+nYxC4>Q6(A`uvzai|Tr1;s7j1BvyWwo&~}Q zQ9;|fL2t3bS2|VWVoH2@a;PL=2F@Kcr+abHcz%s2CF}R4-5E85^z=)~qcroR{L7z0 z+}3t3c^I$qkUP@Z%l)JQ&9KnnQqz4wLjLzIV2R(1PJQhggphF%8B6YOiNsSoaCK=F zdwvgW5-C=0TK1JgsXuola@Z84!0=T|BxR+quaXl&u5#~#HdsBP@EL8A3Ow6&M8oad z_k(_)&!hK6bzqm2w8OXhN&tApD_PG|aO3tGY%#%cpO35v zqNrmA?iDDgiC!(pVdA6}B9~LQ#J8>wwm!Zg*R+pde|7{@y)$H;OGr z(KSSUI)FI56~CU-trpSyvDE-`RBEVqK5h`To{c~LTZrzd3I2k5@*DaL{_s|p7Fz+? zS1sp9S~=zcB`WQrfy06qezM|Qt)?GrQEZ?{;r3$B?cI}Me~He9lFRL;rDiSXq8Tv` zXbXslf;1ls0W75Fl)8$4mLG=@N1LZ$w=AXkStf3H`$7d zA(Jby*yXhGE4XjzUZ<O1BA~`Mb{5c_)W2f~sQz&H&-fKD;|n0}yL?zV$8l4%;BsP9mv#U1$Y% zNTxu!V4lE1c<&k|KfSOPkfc*o5;)YO;Qcsi|ch*em!2j-LFQ|P3ss{1$Yzr z(wiTP%VrLT82OklN;K6p&R(Mf) z!VJ?n<}fKy7w8x^l6HI%9MZM@g6fI3+)NlM7JD-jw>aMx(|S2Xo@WE55HD>DNY!;+ zedD_PEe9}SwIY_4QQ&dBraeE!aM30(ne4Jl*y_tlL2$}OEMPFT*9-un{A14`5dV>6 zR)FvpgZjP%i#5-kL&Q8>f6}Em(b|4N zlHQs2Co5y#6WvSVv&xWxeD$Lp2UxseHnB<@^V2KUSJA=m;v@ko~n2$$R4CMb+*iBH+(YwMDh3DF@6PBrg+9AJ%Xe`GE zeN)Gw`h>SOtE%8oU&RI{^j3&O#1S%Fg*= zIOTY%kP7CH^v_i<$eu6a=tRv2jyH5%G#rEBH8*kJ7q0T|DdqiptnPZ7DSbhUTqk10 zR~Bct+vg)slZr0W-mT%Bde}B9ue{2Xrv^R=RwFl0h-u5*)VIN$H7!L-@cc0)G`lrR z$>OO^^EZqZ$ZOpXKQG7638IHc8UOxTb$y0F^13o1B5&XBDTZXu;2^Dz`dhrP^kz%`#m}R zCcyq;tp>dm}K>{7#TSOpQ zUVFD(wVLJs4yxj*bKxouT3_<_?Nj}`S@(Qj>CUA%WRj@p5b(68GF@%w%_b+FtA2Hr>&1}ReQy;A_1@&prD=Z88HC0y65!}DD-*DmRE;L5KOgu!01EgTeJzXg z+E+3(Sl|C>o0Bu$YCQg_8@gGrZ7rG?DYD;u1FJM{&29iRY&|p$hG(B|z0SB+t=AiH zs%h0~r#doe8jU#i>T^YCu~o%*$R&KDT&JkL_QPZ&ApUNR{%CD=f-NX>{X*VFF^E5cm)7Yv1@lF-4WxA^-cO#bJM>-#wadz=w5d)KQS zyZg|=j>@CjO%;UJ+x89XE~9gQ+_SE~vi|EgG*#b~EQt%mN673S@9Sc3@DL=bll9V$ zO(lzd^?XJt+Uq|XnY9IDqJgiz6sQi(BtR;CB~hjtb(*@_^oaGqM(;> zLT#yl?-5^kQZwuw!l<2WKyvl-ttLr#B{Vb>g=Wy=x&KP$>dRjI`wI8~lo-yF==s~I zHZ3(DACkD-A3&#@1l0u0oY?-+5n5#m&s{LAt^I)2<*GcG zm}t^{f+&8j&h~0PbF4rkMG$q6!lpBplsU)c9CLb@8=_G@sA~5L(EJfM(;>$4r#N*w zPvQ(zmI6hEq35f3&`#a`>s)(=G!lTAPoQ#(uv`elh*e2i2K1@osd(U$jbaW#D7 z-s&s~j&^ppsYh8aB>X&%$a=TMKSZI5ZaUY%S`wQFKQrjA;_>&34}A@QK+nJv0sGmfA1a^a`#EY)y@BT0mM~!wCTqXu@K3qM*?>g!_x_m5FlRr z=}v9N_nDn24T#1>2e~(Y@g1cY5Z)ndHLJ5ZB84GBgMy=8(E;kfk59%yN_+j84oB?d z!k^Ra3*Q1~F)>|A@?@5X&(DEea8JCT3;+4C@piqcjr{aX6{23e^P$N>^-e_n)6qOz zQo?V{Yn*0m>1_3c0A~l<)iC+()YYW2zZJS06^t6FvAR0*qc7FZ zOxzHmJy<{3n=yN%Y`Q?kqX03XD1k$x?jTBmEiA%QQ13gThzBRg<+08e_x!{lIuFhZ zc`H<#W?(y$2N(6UbU8-f-G3k$B!l(XM!~IQ$bJ!QU+6w8Fc=?2o9GF!q|zBknn4op zw*vb---g3pm6453DHPgSdNg30qXVT8nzvWT`2bBae!` zkYUU3QvB@d>bMI$i7LtH#sS4j>LyRI$ri^KQ>kKU^lpt>wleuJP{_|Km+iz~BUr9o zhC#p=uaT>l5EDD572u?Nf~(9whT-?C!~(*s#!t&Tg+Bw-E6YXV#Ai3y_)DK2!kGK1 zWx5>2ZC%5MsmY>SthM?dT6qk$1g5<$KAdZB7(AKVE!X|8)1bq$865B#(~cunj^u(x zJOLz^4eh_*(U*^We&MI;-W}_?5?zA#;u>w2OvHahepbUpHqpcSw3?H>UMa}#E52iE zBXu$xMK&*+BwkpCew)_f*@dunOWb56wLotXh z2W?((T52H9J+w_a?1FcL1fl`j-3;ITLw}-yv24hnLEt3U;OuDu+im0p@PZ;eWH}e* zw@LIrJ)gT0;1Sm@P8nb6n~BB3~}k?;oPdkni{hOxi|WQ-x&Kh5@qerO@e|6F`~ z6(q9=b`p$_J6^9(n=ZMZYfl5&NE7}ixy=)@Ie6J97ut9+ZZZ%4KxG>P!`U#jg+x7T zdu;zjo0%Jozd<;;r-X|vN*5@qE6DS@wE5E)74fxkNtOU>DXKxzV9VK*N;&<{p0|h4$j2X_=~bk@HY@1a`zB|aB`aHH&Fq>nq?c1b&%+BHhVR>k$A$A zPx)Xos4M1t7E_A&@gIqn8u*(sCK{kP_7k6cJ$Q!pvyw6&J|yYU7#X)TWxqFpH5!GJ zqc_vR>#ctF_bch^_@8Ju4`(p|>RiiyTV{biS=%IkP+}$pid5?EtO^>hYK($rAF{s> zyl>(mN3rM+#g@=faVD(dAW;jB0}Gcq?_IVFrSX~%a(XpR%eTFx^l z)GljG!ScB3S9$L$tD-Y0ZPLF7{715n@!b9_RqVvUQ#pDe zj7e23$F@&?6jJpZbjnctp=A>V9cQ%wwb{C{UI?7I04F8Fh&X4a*#sm6*>lFR--o0D zO!K7u?G4bcAXQ5^*k4;!yk&-m(Mrd=a z&yJno7k&$I!v7r8e+5q4piFni#xj5!D$XMfX+FhK%;XS+rckBU+Rt2zSXW7}Bd_V}$O< zUghZX(~UpiDcRnkq?u&)qNSPV3*rhT z!LqB0+^g+7W()a%6SlT@($jCDynI4ac~b)xP1;d0!jzK6zqb{iDZMB?{&h`396`R( zxw3jcl>W2=Be|EH{@l z{JNEQJ`rpF-?)kN#HVgDxJbNW$v|oC6_QP8#2R-W9AjqesO*~dR5AhI%y-=6>t!9LD-Op`c!LEaww3`0x_no|n^^tHd z)|h*q`?mO4+UcI0T~=3LM59t}$}xRQ7p0>fR!e+W6eE0*H|OgAWb!1M_&3_pxOJ3P zeD%~cq}oC64NWtJWdg7JqmiU3tN0L%!AoW z`u-ci_-FhX8jmBxE(+^GKEF=Y_Mmfpp8SuM`G*0w7Qo5OC#+k%M&ZyCL=*vHIEtv2 zYW~1oZxvH2!#?b6=hpNAAS(pq?osS>94>Jfjuqu?VN=Zipsx7Q@2yx3uI;;>K!kJgQbZt4JK3itr zGOZ_FF44T|-9}&{Z3wG;$5weF@XtD;Xn%OPTGAu{Hni+Lh3^4q-|sVzWq(KjD&1P?}aOYv&oKE+7^g+jdsn z@BdE<`qDvb--U!D|OIzv=Vk+U!OFF@KJtwAI~o0*jWB+ zdcH~X@jnui#4`0U2sz`DZz>C!ddlJFWbZ8888%CV4;&JxAi5Q8IuQ! zrDrXmca~u29^DNKgWW44jXVYYT0~8bpowWZpDVez3t~ycj@6t;+Md#QSWFH2d_zk$ z&OFRgFI?Ff%Y~B-_o_lo42?c-;6Gb?OV>yiC!GpvXY^@>q*Xmd$`AM9-`~_JuZr%k zwzp@m*Et*n=@$=5fU*UU+{#F8Om{vNG_(~zML7RTITUJbNW&uX6MYFrwz%57HSmJk zqaKbRcR=h!SAW>g?2>4l1^D$0wlju3WDnh}=6byNmzt2<1Lu2jbUN6Pb@Y5?X?Q-1 z4B?X^ky*Wh%5U%fiOpewa}1V4rxoEdZ?>BhdxkX(xe$Ws8tGlfAnz6m&n@L=9;3Ud zChXtTp8s`IigcdTzXGtageFn%eki5NUv7KFT>5rM4J%`(76l?v+53USSX4-Jktap+ z@7f?QJw6%k`87|n^Q~#29CRy3_@6}==@)Zh|9H8-;ShZvu>Bm?ttt-iX$`bioHRx0 zMt@9)O1xb>3n?^xq`O&{nyNdPxP6v!Ezu`30AuR04si^>Q__M|5S0_~zrx@uAgX&N^c*x#~1X5cXoU(U7s+L&$~Wl}E-THkYcoV8(T~wtMJ%bF!k_ zd`FmTW;QbYU~6$PUrCuwW@I`_8!63~h%^^WZQDdKo~punU+glhpv=wGL2+&hYCP3| zz9cgC&KRYt_xwKA5L%|7Dm5J(g~jj| zaa$NjM{ruM-#+yECLY|1d+^^8dZC_~C*K{u0n_LWayv{IHvXMQ3RG1#Nm~i7;$yvU zB(p?{zzOQ7h`evD4Y2&K!M%sYDL-0-LLW%BXZ)-Ul-Oh5>u8SJI#JNXt$ZEjjfsRi zg1&;hS7!x?*t8Q1mM}wNQ+g9sWTo^Yq8Q1Dn;F_v7(0!XAVDpD%E5A0AOXn)=GNm9 z6fijg1PDTzJatQ;atCkV?@PaCx$31k9kAgW-B7-@tUhXe{ShOn0dt-eVE7LNa^2=n z8YCX0C&AB-GJY?}4hI_O;a8X9@KO?DIu`Z^Xl)aX<_$O*M1=^mmRfK?x%q00D%U>9 z_w{__ERE_;{J#Aikpj5(aB-hQ7=`tI!~9zhy^e*I12Hnw2MH`MB!URMZixYWoYw^Y z0FZgk2d4h(Jwz@u)knY-65&JEP0$>tfvxLmrZ{U4AGxU2ew^TyTn{_L8mh zEEsD%?u^7rmZ$4td8z9jnO8QWi&?93L9}`Z)AKFD^l|9jws#s`GaGEK$V%1Gi zJtk-}tcG>nP<>lENqCl9dc0OZIw8LMInfbU{EpV7R`Db3sSYXI#$|y(D3q4Ob+h-JJ-&tV6Eb z{c0eyJbV^j#<8H*Lt|yYqw0$W2~cS!VzPCDIRyY{=iJH&M!bfEMp<;vt(t|^wqMEZ zF+yqYta-a~!+yn90j#K6?u_Gjd-2GF-1V_{p zCaA_Tl^8ycljkkRnTD~fj&wl5u2%@%mOJ{Oiy4`OlS3v$n!@v%kod#sJEihlA=ceF zW*tPhme_&jc6UvniUx3lI=cm&8P*7xgrZT2=k{|X+@4JzMAevaE85?A)HE159j_;5 z0_FVrl#T|UGiR*5punR5yfSuGKpLZJe5rXcb*kXG*(W3}i}=NNw32U5TyfFnr4cK` zyUMW(U;it@wmV3-TARJ>o}sBxTvBC|iypCp2zzJhMB>RMHoXt-Jz+cMONyp0;}&>6 zaMeGaVZc8jaQan|N)wv=au(YqdYpBxT+i&cp9ie*!8>b%b3+!2cHOC0i0CVIpldjw zu07&Y3YY-U~b0DmJnosWM?86^fUE!E`OB&FR{yRCxK($0*#GLe5(uRb!po_uKE3!#Y@hh%+~k`+(B-o%$aY6n7|A zRdboV_NDUQ{B*f{Q5z|HK$qcU*w4@-Jo5jUEe5*QrX4 zTv=%Om4uv{*N3UgN?W+kCY$}PQyB0s&clg%2}ZM(s(R2a&}%jnGkc<0d;~0}ey}YS zs_xF!q#@p&tk+9kT0p~JxqRKvlld`w!4}6b)OJ$u8tb5Hhug?Q18rB`jB!f9)0LzkvTJ}OlVPLLr zG%jA{sNSx^ua=ta(JV(Do+>b5t{!_ZWth^B*yld%Zc=Pto+}be5p{DPnz-tl#G1$A z<1A(qvkP4Pj_myhHxTDQzpCzj%&hB*X=Ql28qq{-;M!CL&);Y?c-Y~{^8ZyQt@Ocoz0=WO(8IKK!?^>wl^Z0DZu z2%{;HTLl!REykRSFo0KT?AnhVKEFBRc&Uu}eNWhTz-{I=tnfRuGtn^ z50$a1@u_)A6DuLtX}&|l^+84a9NTM#TvA^Kj6IQa->&zVNP=>Bv!U!FVz!f0Yf_Oy zgmlx!HN!hu6#6I$nj;s*P4C?ub&J?N(3rhNh55y{7aJWV8?gO;?Ua9+vT6s7{=GMt zcWZ83Nwa#DdAE~@)b-`}>X1vOZTGZy{-C8q2l}}?#i<-*Bv&q1XDqeW60MCcmUm;Q((+7M;x?5T6 zy5F*WdiV6`gTwnF7j8S8$B#P=f;8m?2+@w6x}dwtG|-FW*=EIS1zGSfZc7y;X>~7W zF%y?`>9CPp7P6E;zt*q7lsE%6<&Wu6gin`;^1)66ij=?7Q+pj`ODV`LNxH#X^C+T= zW8kl|O`j>SNLpLYO5`-McI%kb*FOwj({M%%!wC{eR0(GT%Uq`3JbjT`Xwz=z>Ut>Z z#M{3T+hIbbBk87t!v72!K1Uo1t*l21hr9_oA9FM|vSMXy^1v*(>fdf4nIz8g)>U3%mU zT41cJ=Hf--Y!M7%3er-%kWbHD5IXQIjMl_(Cv12YdA!V%?Fv=cYBc8@@F$XBRV}@c z?|rYJ1pdK=#L0E2sv-mWi$rxiW<&27ytKB1r_Du||CRe66(5ui{ocZOFIlbi!YS6^ zpC9g3dMHp)`p*6P0Q}UXdTDgvRJx+~7vkx1{>>{!`r^U-D!13_EGke6e);(708zJR z&hOvE0=}N4qt@>580wpi_$N?6N5H5+kWI#ISan0uL@L^(^QsQH(1CL;B6aj!wJf&4@SZ8;pw0aB@+}JDfyss0gHl>Xom}d3wy7(>Z;_ zE&$5ZF9|rzQan7xkWqf?Gj=Sowkbd-K*0ogRN6#47OCW2S@v*(uRgl3qx)x4#)XCJf-YmN z-c%}&l2@Q;c#+Y;A+$3P=u7Y~Q z#oy&RFY~0~D~adAI|NBNDfy%EUWXChkux~msza1N82i<<30E-9&b;5E1s*-|L?c_y z?>}?ET!M=wGrhMVv30H<4*3-ANTNj4?;{yt#q*JBMO>}HsVHJ6kl3Vr zogIjfR}?;WB$$GXnU6`w%f?+T+I)fP6%WaMyXUIZ2kW*z;ai3j_KzJMRosh!W!tZL?{^9bE-PWbTu6a{sgT#Zvq(Fsf zHmO-&H2|a_`EL4IEmJ74N#&lJ4q*;sP+#PLhEUwvuF8HM98ld93KkN+lrN$Rc0hhf zK{7XHzAHie_v>wt)I^6>gjCOiGN<2Xny%AbAGq^j9$;@V=> z%?la7^73Seaij0SVdd9~?Sy%4cVzN($Q^P_AW$}QtAT9Qip#Z7?2=p-^<=3hnPnsd zs$rDhtaO^Ol?+vlV%xr(h2=B*%=fr_O&e{M^f6Rz{^)fPHb?!EM#01qar9@S=+F4i zHBc_fZ}7Q8u2MjFn=+=n5f8u{@WGl#4#=p^Q2%?Q0r%iUX7TSCr!JsjIAM)Ecu*4E z-LD?*P82#@PDQO76(x?s=h;>I|9E-}zoy?e?0byvlI{+X?(Pl==}zeZ0z+zm5;8)R zPC-GD6bZ=@ZuCIu9E?ypr0d@IcR%;@7wq%eKD(~tJdXEyo|CVyervxjJAH@qL|d*c zx>Ql2xKRThcDmO$$5ru1YenrnGLV4J0isb246Ri9N@Q4=!ycTjN4_L{2Dy5J(PZ z+{>{JOwZCZt%l8xQpp;~I+_PZnLw6o%>v%34Ida{wW^cs(&lY}sBm$eMF=6>(N1)x z!4A+YHOhXThN3&1%es6WdOicF-Y|F>DkJ#Q9I!)Erv44oO$srGs6;T3Ci7E(2i?AN zBfU!iraxch5@+HQi{`TS#hF2Vw^&B~&?HO)VR?;H2Uf*O?8*fgFZzFY zAV)ny2y0F{t6&{`TaDzT$J10p|pw73gtxJvL zuH=}<@tHRBF8=NrQlT{|lmZ7HDpxN8EZY12s*2{f*Yx1sXM$z$qG6d1bTii(MZty zK;GNluiwd{voygGv(*3isL3EU=pp>@wyE%bQ&+W3I+%N5K6Ly;e{{)my+r7ChmvXd z?(`>Kqn*nco$kxu4@Ju1MEQ+>-ad<;8%Skkd;;r8vH=9M-Y(%o{Bun*Qn1Cz==aVV z7M=OvWNfE743V6OZdq>gzsXQ_@f9Ho{G(#c;*m8TV=7JB>kpj+AUY}=Nzd!{@2iY@ zkj!)tXBAh%ZKyRMs)Y|}8z=fXjRyXNY?v@mJvbNe-by@UEsH27i|PNd0QVo&`m(~K zUJP=DMI7_NtG?{-V)VD=B~d zQH6&ju-sJmd$ap!n*m%pK?Zl9N&z=GlWxyw*!zffOWvM-F&snd^084#VtszOv`p}R zbntPf&YRC9BO<&fd;>f4~ zY;=jVCeT-qnd&dNVWVhNo6iVkRd~5&tGWHled-!SwlB;gpm~7KB|XUg8$iA=Z}uOM z3n|^}ASWHO4ka@NK_;rkr&tPE`4YMacR=u-QMwLy*w7jc`dKc7)9nrEPr!DRugX3m zUc`wnhRw=M4`$lz$(9Qa7QIRxx37B}1~K45n=$9=+G|@Q$dSx7xF!9UpH6E8lq2{_2E?M2b0FhA`RQHJ2C}MQE^f ztG+Irk^Jj$h=Vwq056iVVndFhV&3^XisjYSyNT7;5zG6u#|5Y-)Pc4~g)vHGhi86f z={rAy+_+u8ql)pidGC-+C!IU$zeF=$hs)t4*GFYBkDH2Qe~63D{`aKtvTiBR*~5;m zZ|*Sw+>|nrC8lSF3}(~*)Bk(*BF|ukFluwfeOvK&451*(7x1{TsqWFrxzg*(afdHa z-U=1P^dS@w(s8w-lEyVx;?w>J8wT4RWIS?Da6rG;C)m###3E8k(9P6baFeP1NYQF@ zpz0CTpY*CC>epG$*(jTV`XaY%8B3A2-j?&Nyk^)U^w41kZG$soik^)sznmor8^in# zKY(5%e0tx=yJIuqw6Cl)q&Bx}*wCZxZ*o6mecuuqtno-x1}QXTKN`=24|8WOF6m0M z5Qq3h*9LRGK+4gEkb%;nn5{*);~&4BH)tGX;X2Ld8rEoZT6}g}UY=cCe45xyGuq~H zZ*g-EC^qYPexSd3$5ga~4f!X@j3$L!Cnqr#4tS>}>WGP#JUzx)C=JqG`PR zc0hjmrTrySKjp^1Qv|-KyeP__v+<&GCI5Z=57U&@JM!wXJC~)?{>}Wv)WC?2!rT4K zM9Gi6U-K_^zw^6d9dS@Qtu!a~FdN1QBMLm9{I;=NmqW4HRn3>aXhAMz5AQx%5kNDh z2v{J*EyfyYxLEi9DxfuIYViNzO2m8(EhwIxRwg{$>Y{}&%u>7Zk`u%b37wqXUNX(v zJ_vPsNQV4iEDsBib_)K%i5WQE;JEYc-mFr}W zWr4sMvt{q~`b8zT8+kQUW;*Fu!0&$El0uc`n8>o-tQ}poHixSM)_|LV6l#Sh_4Rk| z8I>=0!y|>_K{q4hKll*4>3G0b3O88MxabfnHha-!Rs~zcei~V@yh5F7n}L*531RK; z{Q3>YNGV#=f*m5DRCf`a8ro_K$ZPOZ7;j~&Op zUX|SfBT0!X7rE|&puHa>PB)~Tem+xn6}bgWa4$VE8NJ&VSz%R>BiNzgr#k%O7;j5Nqd@#@ryH@WuaiglNS}36euYGX z$mb#Y$JS`*G`{N$sgdzn*Dt>nTILq>r}jIY4xF+UHH|T^a>>4I5BGW1GG;2gZD^1~ zL6#)j;)qZp#1f=u#Lgqr^u9vtDOa+AQnbd8mpdxM zNGUoijObpr(X^$ZWPjkbDa3aql^rab^Qk?t0#xx}no-&wyM~6-sVMi@_Y<=io`}vv zhmwbI_$_fd_3*NMN~&(KpDMV0DBtp|gNtDw4^_AD9LUj%8?yMy7l7<#>Gz5OB_g=m zd>za<86wk-*O<5O=EJbj%_n!mYcVtH)<*vHs}*OW1NjxnRwFle!<_9mA4!dP{~ZEn z2up%-%D#*okE&*vf6Mgji@f6;$W9KSa>iE0YNSNF^m2_`FVmlX?Imhebd>zBl=*3Y zfC}bOpTUc)6PF!Gn>#*?7OA2)~uk}M|_q1kRTC`IgwomO}x$+*sss6=C6VEQD;POVZEo> zlkYT*>Y!4Ym^{2~GTt#v`CS)hqPIk7uL=0|aJa;OAKg%kwbX4v&6y`Gwme{A!{FY{ z8GQSU1BoQ_;$q${_+iiG5J!%_%EPsGA^Ct zxamFK#XhNC%U?aeZqqu`f}|Qu;WEi>+hC&;>C+eo=FLkg4y;i$eeAOQG%fjyuJ(!_ zsnd_Pe^6g?x)`4v7AQXWiq4A&Bonj04#LvpVWe?p2AgmV9ePSuiaG%p(uA)Jv0A3x z*AwD*Nu+@Wos_v)FiU~QcgDbe{hreJ_(E!S<6 zguj8qvh^H)RMW9s6_U6;d|qQJ`avAb0gJ2{6FeYW|_NdSA21~VMHi13B?|Ho_?-48uBfa2%Swv%{zkg)$2mETzn2j z&GQt1nJ*wF^dYsmkQlZ!dciz>gjT!*&`=F{=C_~)a@IuGPQ!p*M)7kD_!}esA1(02 z0eCEqsziWbW>BBY1`R3!m%ZE%Heg4RS(M%kdR~o*_sO1Uq;Cr%YKd>7n5IAGanMuPo$KP z$Ko!DCkH9Y?XY|wG|zBr>$_t!253w1>?u|@JnI# zCEu9K-%mAm7^h#}9>}f)Yw!HY&;#IFYo7Mb!p4RJ-)2 zPSG%ZJ{1+RfZN zeHX&t$R()Sx6;@6Ei9sex|$l-J??)I0rihNWtQ606)j^6-9gDpwf1gK6}5 z^oqC`+n4;z#_J~RnYIa}IU4uRzJ7aDFhV0YY6G8G@#lVV{U% z<8Fwa3u@|iZbMJ^p5n^g{@0&Au)tyeoPrk?uvCX6cdaJmGK%h5nI_o(r#|A#S}jkA zwfIU%{yE*`>9&4;>Ay>}f?pp_0_mL?FJILB{TrSa26Uo!8D%sWAPTD^xU+FaT#RjKACMnhW$cN>iepvE?Iz{{TqEXf+H+oC~PaYq6n=E7bZ5O?9)vFWu{0W&3b& zy-4V$+#VfIF-h`&?=E`36vDL~^=HImN)IYJNO|D0`Y#!)hKX;Jh5)H*20oa4h)6O*1d!tvb@u>6wJ7$-}5XifH;1z>TRVa{<7GdcUc`gucqolSCk_@|1IY zu3kUBteRVn6C&|}k=K_Z@+&uDC|$?s`@0GO+T0MQp%PH1*>|Sd>m> z0539TL2);Zt_aL|;wM7?q`LmQ7R~eI@?r3_qHrBv+q!1z=K>WWKAi-dYg=r-3ff@( z(5!kK_Q=GtpPIy2l?6a!1EQf3vqC{`O#*a=pX+O(r!68DSUHKl7>heLjnKJ=1qZwr zK%K?q1yXhCp5{3>0!XFWPcJbOPB7`Bn#R?|GnW z@IBRBZ5#V3NlEse<+%hB?*9UIdSTeSAeGGOiwOv%GTbfjVw7@FJu)-ShGtcS7WHGz zTrIZ1Hry5})Rx^?V=q&E@jd^d@kT_aLhk1nCl)mSv$Oi7G^ChY0v%I3v2@9D<-536 z%Gp-q*3y5wdS@TLIeYwS$x+Xa{)Lw&@!64YS?!2&#dh%kr#}DKBZac+A$|n^+x~xQ z=~L!!AQ|rp;6^B7rD#!lGFDb`&tpMB7eN%iv898ZR(MszUy&4dyUQ(q!q#!$0ue< z)-qs*_~t1x9V>M?du3j$D06nT$+)u88(EYWkH)65qJ|6fXexe8PD;!MUp~L=8n^!Z ze1Jfi|JWNy$CGg!O&vZ~>Zx*gh{jm^32OgKE?_ELTY#QL`LX*SA|s_u79l+MTI=WrW5)ZO&S78X|F>M%D}~udD^&R0UPrK|=nEYZ&U%LxmS9=77&j@r zjN;Uguav4XA|J9|m7l)9QJv*^<^%y@0vN8Vny)A6G{wp6OBJ)oJD=S8GNpckDej1aY z6Ibe@=va*&s(7pBrHiN>ern%Fb4&^7)qs`T4|E|EqADI^6nQR=(;(A!RA_aV*#GqO z9V7-DX(%7*LfTD8F7 ziM%5#5gtAB^(a-dr0mM;Aj%TVaAxj*U0xLNC~{pz5%5Z{E!#KMZq#nX+H=(cPa%ut zLE7;&mtY1Iu@$h2w_{KBgMScC=8y(+J&CZ?F(EKBl(fNmy}OS64CD0sunvXNo_a%_ z_;AebG~unOaPsS4L#LV(MLdl4$$GrP{dwGCgn4;Ux9upKgl)qbV9a0brWOUVuu`YG zwf%j}PEmLMhmQ@L4#`fR`~~8x;7a2Q-NAF!-gc#&5VNGRw!51DRV4ip@AHJvM14v< zP>M_ofF(9^5ImFOMGh|6CCZKN z=5+`+E^9O5PO%k2gx>%Ols{^GrG^C)AzlkLD8voM`WMu)4qmID+%pg1294^7Des}E zJQ8-GoUTt?(-?fYOEQ#@hl>be4IA$pllhBGOd#Qb)A6`;&i*TRNocxP*Y2$b)5%}IpL{48}_+D6cWnDv`1T%Bug$!j#gBEYQd^{l$a7K?kL$f&b-@co%{IP zL0zH$0|!~8p%2E!Pu~Ft`q{gQzIG-i#}6Z94POsRKnNkw(Q+mcH)ckl5~etEH+vmG zqayy&;Xs#DA$+)3y0Y*LQkjQtrR*W=B#q*FbD7(r>|RgyV%bN^?ZZw%Qb@7f7Ga&F zDDd*wWguY-+z?uQ=To*jUy4!eq;&}b^fI{!N7n@Ai#40?&Ww*={)T%hl?l+tJ_k`B zK~b^$^JA@a(S7TSxqpBmqvDrB95z3RdY8LPv=C_9$$f*f0P0v*5Vh-TsK}E%&k_7~ z$7NG0?hAa++m?Ys&!~u5VcU#t)w#voon_-FVtNiSuU^b>&%lw+|HvwN%<8nk0S`Pn z;+5B8%JZ1J=KjFrHKZjsDy21Lj?CGHg3g&thm@Z)j{5zb2$XRShvc20=x5sok@6LB z0Co@s3ig3f_VqKicN9g_r4vpBW$|WPhtbJz?wFk^{}x%eV|{K{xf-?<7!ggJqCLOU~^@bctYj*q+ zf1;}O#6HQoPjn~CcM_7^g;`TB{+W7;5|w-=`xJ1tMF2W#-*_W4EK0||N{Q9-ERe9& z(EG7*uSdd?#5n4&L2FF-6s}h%`X2^W`OqA5_p&55V)rr9@Ulj)XyufVl|>+~{w?sl zhNPYt6v@F5Nex+y+vsXFpWtv~a?MD{<#h9Hgz+*)2)ssy4ZNp~nmT7*KXMQ>D&aWh zNq9WOjr`N}PNi3B*HOwG*+E*zcWZBabOENd=Cy9|l6joYXZ?Ha#iDE4*O8zk=qiq_ z=s|XyZ?B}?%x`f8gVCV2kIeWyXb7J9rou4yq3-@!9Tf@?ppFzS-#CHS@DS(pTA1n zak$wO!HB9(leDVsM+;mz`RBqWQhHrQTxL@AgekPScgAqbr{J&x!=kKF@+m$Q0XJn! z-52g=4}7`e`~vaDs^$&JV_+wD3bY=u6FnzNG>x)sPN`$j$krMyK)( zdvNzg|EX(wQPdIn5Ho&O%ovH@ngZ?2oqm3?YoERMdv4R@ckME78(ZB;_~u+mRUKjr z6sYh=T`aQPQvjSwnE*&r5Dw3X`WN3Uk$hQ{#9gWl%>>;*-N`L&{=Ko}P*9euaieI) z6`8Z5D|2@E#3Jtub|J0^v86czPefWroo7y}M(KUDGyTp%!9=lvMbGMGGIWuo5-XC2 z7I;AdkMVEVA;1hGa>j=%zs`9YxE51&r*%a4dfM~<2E}~xdHxtJ*-Wyn9%8?hHo}ZS z%>_iWoZa>+f3c|?{!|*jY@P9L>8e67&G-Fqw08!%@O7iL26!2KNi3^iQy&JFvFo|z zP9u0%QjU$G;T$V^M@Xa6ej`}w5Rw>1+z5_Y7XdfRAm=e=3{(9E%Udx#tGGqMf17Sk zARGv)C|~pJQH;Sx*!T?YNo{B7myMpD1N*NUOPA_~7$spC1;%GJXg|JjX<55e16oSyvYq=z{(pNU7)mF`0ZL9b6+)Hxx+Ct@;^2^ zZ%%BDm&xZF(Y&|d7*b^jW9s$2dg&-IjpV!wIrP; zkdlJu!DJv%=b6r zYLAbeTPPbHee7*bmFt#z zq@nVWTJL`VP4F$C?H5Do^@2r5{r|MAm%d`sF|yWtKjZq_9@?lW*N0>Mq^%_N7ySbR z@$}r%sC!6fQUh%`smr}reJ^?iJkX1Dh(km&QA>NJtZ*URU>z8*8`BnC!NHPR&}DI9 z(An)=Fvf_1RpiYmgqimO7ijic6qFk=htz+E@e83ikeA5xSn>nlzAd!i&M20xUL@2$ z0fh1W6vm(DsZ1*?PlPg#3r3Q_M4*Mq_+vfuA6E?(@a)8FPKh@l zc-J2Yd>qGDeC*yhF#KWf1$I?1o;w1wKbiz?P^1mgl^=s1Q&j~Y#ot>F(4wTEV;IzB zjBJJfWy>#E3s;;Crp9Q0rwy_s*|r4@%j%AnSbX>rr1C4 zBt_rgyxBcn>O#F-oG3g=dhs0danCP7QbPO+J|OM=q9cuJnoMw}lM z`Wvt@w_+xVU{t+$5Fu82BxSEQ)?6x>)jF*)k)olImw2$a@o5@{hc5yAybD!txI)vX zp1^xbpX=%4nf*uEUCZ-EutAn_Ko>So6JIE&9zz+BU}O`fgbl@J0GS_zb1Hj_wK_x9 zJ6|75Vq|Ahjy zb03gR;J~OM=sfH+ zSp}27q~f(Z-hDy}nHqE*hkK6V9thBv?q*1h{8uA>8NdKmjY-7E_OF6W@!0=KH@wM| zb;)M%EeHA@w9l{X?6&_)`o9h%jk6ySfx*Lg?sH)VHpw6^_zkY(I-RHD$2>leWZ|Va zT()<$0PG0Y&F$4Evi+863tfBGFv0jdSxu=9cxy!TrD+E?{IBDg2hVCNj=X&>fWcew z`ORb;cDPPtT)Ft{cm%hsGbpQU64P$5M-7~+;=;;m;X@Vg6KYO=mg8e{W||5xd1M2r zv8a_u26!1gNb?J-$_H=x3{#G4cCian%i06}*aCi(>g$qS<~(!$cJ?Z|8lp!?vEVa; z5S&2ayxh$~ej_v*4o;*>bMKe^e=NZB9kIiUsj6>`$R$JoN2$leVMRGbAyb%`QY#luIZNk z=#@gy`oPJd4d2Rw|NMTlG0X;mS~z5`?(ApT1+g#HrHAv^I`xzwS~geaWOrt@^^}qt zQvkLy6@Rcb*8wGAsdJkeWlM!8oo^+iN1Buq<%~O3&ZE?ggm(So2jmPS9n;fv6vU4H zQxnLb)Lu5~nT%Ze+s&sijl=)vqtpPqi#7i|Damf^Q_RqmV^uVL2ldL1^SZ0+jg0de zy{vwGREzdl5uC={iYaL-8cSG;RQ;GKd3Jzy;JG^P0`c@j_oF4dl|xa$>WiNK_$Use z_@`H+643Dv@j6c@17_VjUNGuFN9DI9gRG~qtC1euDT-+9HJmAG%iR5M?LeqFs z3(|t0z{^&m77_lnudNIN-M~*qt(!Q9Qf;(t`V=m=Krnw|=}c;<=@)U~G%X#IoBRL% z4XG-();$$*#x7r1c!2g~^4MKh6%z0X5-EdvCfY)CJC*70u zNNE~89U<3yDKIg z<+!|=5=e#o&~H^iW7UryHoB-R7Atq^Embh9FJf{tlwIQFmDjj|EOE%AG#s#BF_rbF zxQn%`C+u(NS$JKa9rWlzs`TqBJlYKs@XmOiKMX$Ow9mC(i*lpxcpB=I^G}OKYVnQb zZzO-wp_+(d!t#n$?qBF#wSc(=V9FEv?otYBVCW}-#)`=C>Onh)`(+0gH&#R$a-}gv!nNg=Q9B8u#Vdq z0$)CF1+@F0tXm|!8@YLP!#s1FM!M3J2t=Mq%8eg?M2gHFsmGmm#v^MmMpBelDy)5@ z%5mLQ0#3QU+07Es9X*@Y(%pgBp*^CV$&L8zoY|?^Rv(JqkNZ*&(9&$&RQS@I zmb)9lC(%tj;s3JaOZ=hzOQb~EqS9i-COD!bYh&@jRh0U2kuc*_r|bCbSKtz_KLOIZ z^!pQo1zL`IgD|0HY^sI^L5N*Dq2WOt*|(-&@~@>qtkdXU!i%Z_+=b~fPM$_Z z2lnOHcj-NVdwe+gy8IT|Pafu)|GB1)Ae%T)|8x@Ta_;Y(v;Ya`L_U z8#rcDeoPybPiN(7&vEQXd>%$pBYqsh{Fn%r^=~S;iK}{1L%x)%b@1{L$8oPVDw4{{ zNp#s!wjh+@S0-M9Cnge3IK(z$4LI2SDD+?K+Fekp4^7|AU$R^Mg0^W|c+u6XK`%kN zz*EONfN(IjR#@4H--JS>3SKQ zw)O|3Vq5^`PQou@oi(<6{&0rBw9F z72CIFYzM^suRZ*KG*FZ2*^mGyp+Oekf-?whz6M6QQ%67B+LMl^zkHh_f-DU4o|T#nzoU#wTmMjO|pbN^ijs z>$Wd!z#}avdG^L88x@1!a+j*@80yVAj8>CvG#_ ztG=6vBR34$P3QBUH0M*A$hn=>In>zxBYezUIj2@{D7sb^_pY7VFmIviueAt^7q?q? zibWC9Ny56A^aunm2s-PWm>s9qvHQy$?%HIZ5M)H9+qQ@z93YY_seXK-8<-%)KKGL~ zKz#{%?1+M(s$iT>$PD~cj0=q6)4jJUJV&2Fjynm2K0gk!ay1H_XC%V+=G)xuOXwYqZ_jzidfC7X@vuq+9-kl08=K@`72Y%cdl zhT^?o3h=!(xsNdr;W;(FswuWAEO$QzEu?H^B?oL_`aaTp1d(gm*|@lcUQpK`&LzueIW zVg>4VdK^_c_k?J!qfWobSu#LovK67CWP~}Rlk;-;&43EgbF8GMA)VkN_1bGS9_aYZ z`#ScrnX8{hf7~4$!zG^1mfn2)qp@!;%oj3Rml6IsxF%{Mp!Hq#$+uPcQC$ZI`}zt2 zwYARHm~VG)#KLTyWG};Jet#YTXFhSS%(C2s zttkF5vN|;yK;X*!=Tc{E$U1n>nBC>4Ahjy;K$7vb|HDzdXpit;N&Pw0i;CdC{JLF$ zX^Hrxco>Q?4y58Qu&;3PzKyE?N-M>b+WVN|p|?iPKx#g6OCC{6g`0A?$@~DSfsVDm zcW=rG{@S}r4as$~7acob{o`|{*>vzMB>E9bF(^IJOjxypEMEI%K{Rk&>NDMK7cRR+ z>!+ip6^4h^!>GSo&2%b3s}+j(;2sF5W1*@E+1_Nb?*(%i8Hu^jJy+3v#~XS(7P!(B zwyZU4uOB#8P`AgcP^1<5RBmTa!4sd)LH2W0_Cxlo)&-=Hw_q=AIwVTGY5gW0a^* zkv#IHI#MSy#IQ;j$IjSbc5jV#O6JqP5bM<2GT?4Q37?`Ye2T%nS)Ug5xp?1gW~iBF zP~N*9n1liFEvaR>qHB&Uva*>&viMQ5gC;y(WS)Duhvj$JI7cD5yKZ>JwG~s?{hfn_ zlj_N>y4xN^REuIOS>Tc0!Xf+d1LI-2Hor!MeP}c{S=r8pw(Of~tWkBTjpisap7Vh- zy?iZW9)#AGT>pSv{0KoNLH}Gz{W(5E4f|Ug^5;ZwHd|fCD}!FE^S!ObXfYAHru%Ry ztj?QcXB+pW#oQJjq7(f)cPfwoAXXH1qG8ShV8#u4PuE9l^9HN? z#n&H-?g^Oi(Gs#0?HI~ZhcZ{s-dI;zB85U`jez~5*C=>qK;jK}K0^3>y=h4PJ}iX| za3PcjfAcW1l8>-@wsQ4wr?kzBO>TKn_nLM?)}*~;cnZ$nq@#f9;}%Hn|E z-k$A-xvRI8BZhQ5&qHmidfTx$T)eBNt7!y%tsm+3@g{SYspmv0_o$SFyerJi#0khM z1gX?pIdUw8AR`XskkK>9i#w(1a6Z-|pE2yf!n69&?XC|cWkocM#xTr^1pSPkO0Dvm z*;25li_0Z5{n}`(iWxx4fEuUHB)Iql$Cd3EV)`02NkPW&#m(v4m2{R?t*Qy%?@Z?= z#>Uxom)6FxsjBL)olhe^wcEOCNhZYYpOG)y)j)S76Q`!d`XulSpfLLQR5?aZ*Uu3o zzC_QY(QO;+Zxqpx0mp;{@pD_4FRUaP;oDQ-g-?AORQN35i*hReK%R{(Qo4Cl=?QSt z@nqeHyP9co}4p+-2 z0-xTS`J@Kx|1(8`tvP)_i+zSSAy&Cx9>0Ia-E$ZLP02{;KQ?l0Y`($uRcf?k_1$ce zqeT{V*q8QSe&JIFJw!!**;Up;nliZ-FQ1B@>upejyw`w{Kbl77q4h6Ip*n=tOAAFR zpWeUx7HsfB;pnk*8hPtduJ?^yq)BA9Re9{A+YW}@@SKbe1p(p8hkkHWDMS()0zw`6 zQz2ayxBC}vwoO+)?B0y?wIETx#1i{G3On)wJU#O9_@R~h(iFnq_uTydM(rQ3mi&z@ z%;~B{NIx^dT2miU-Zt-=u|yr^FS-3;rU(c~5eD9Kf`eY*$%G=L8s0$#ln5;f?5a5- z?ml2-*xASHY3gkA@($Ab{(6t6shONZ!Il!^Up;t5HOMZ52t|bz*KrygTstBX7qb)-7^{kouCO7wRQ= zyY)EN_HJ3vT%{*gS5C$JOfa(*eJ1UmCo}Bk{L80tt(Cau2Q2B;=f9Qi1O&c~G0i+> z90AzJ?_~LxcU1}Dt`AZA1;nWIk+ytNXm2kC8y>6i7!TD~+L8zoce|v|S*8am&0^+Z zzDxo(S||Ab+=96##O>3uziGz#pJ@kXG{=x4Tj>T@ao$8?Pw?UX+_!C}^DEE=M@9mE zB=3VYlf`k-g6jNr5sDiTxA)y&_jNgk-<#b`1FaSCa%-_$5Ung~@9E^JU75*$o}oNb zCoKoyMKqp&cY!W&i*C#nT7)6WYV-0n z$&w>^NO!pdMuEO#n4>Jj%ZGQ!>C5CKKV|_6MPHyO*!Jk-;ptSgmEALSP#U(qu!W3Od zKHhBA-fqwG0rM*E+z0{dq>sC}5SPYQXGRe}85zKaWFL&pxq0)&aOv3bj)WVG8m1GT zP}x;r+1)TMc2IXJ1l(;k!K_ny7?=^5dDjMB@8rZIf52ZJg-Qg+)h5S28QqxFWHJr0 z{Hy-ejpb+rb9DGr%$8U<{rd57=-xy~O|t@)Aqj450$LXe?)AqeG(Mj?jXHRdz625aZU}XaJ zax27}W3^H7_x|{teNz~f#c z@`#pBqt|{~xVR@_PH^L*`h%~v-D@Q8o7DT2jxVTUlQdi&`l4dmLFp`i26xXjY2FKb zt4cKB-oo^EoT#yL;dTE6*VW}rlRJ1tcC^a`jF27scx?GGBWf5yPeig{5AE z1MMTC%9U)x z0flphrdUJGjN4iMrPKPmd`81;^`~5h zOFnjqRA8mgzz%_Ly}-v&APF0sTf^NWaMo!@q}MG_`x^Zi2_=U2S2(hBwK(NG`?wN~ zbfa%3k;#Z_d`a8(k~Sfl43S2;PW|e;_4cT&UxSF~xk!7#-4O7e=!1e?93SR>4nfVp z!^b_XZM6yB(qWP^M(Dd#D^{ca@O=m8T<2WAupu|P1_M{CP*`14P}dX3@a&xhRYeku zJfsrN)SJYXule#)^o+Gl-xtz9c|6V6MS9#bewywaPfixoKlqVB1O53k3;HQYJ&v(# zxC~ffrgphF{d%}Hqd{bvt?Ip*{<6cB!3#CXK29huZ}(!hW83(|{wH}EuHhF^p14>N zVxAFj$&{70uviI95Efcu9j@qnCvX!v6l@@XtF0~3CQ0*kGHesmB_4;=I?3}4Pzfk- zW+e43Ns2SVE98;Ja}BA7kTzb8IgCh(9nE{LXT3i4*U-t8q1|?a8^Me)bGQSjO#m5b zQE$D>^j?|C7lsBlimx1By-kVqxK#{Rb~;FYwG=TTr2$X%j0#^R~^H&hU)$baOA|l)qN|z5UTe7(8x)5u5mz8Q*QSKh9K*2k>xZ9KTS-*c7)d zKOO>&{m-VP?`~dnecP8a@!j6xU-jpla-Daw@C3;n8R#nY6U0?E9RO6Ht*>-;)(ehpCaLnn;z1kDH5ihDXQg>%yngkV_ zx?leso*!N3PO9K)g}99jy}5oT5z)r}k0Ki!dpdmWNNj#>p`kxNPY#GUum+z@l0)_? zbQoGM--UI49r;b8@BYB#$pU6QzWwYNrHDIWSfu{^^u+)ahS@%gjz2+S0gLh@xZu1g zX=?AEEI(ma`NUh9m*=fUqR3(nr31CCj8YW1YCpW5B_a|UbgKCNhXW3F?d-&}7M^_as-?-hL;qvyzukGQfs>(z?EJNv_AOih-Xk-opz;iEq?#(o|dCLrLr}(*6 zwY-m;uqU&&VXwdIIK0OnJfxSAV5UrJ*inE2@E z&%~wk=KiFdd3VhP4>xv5P(tbK-{g6Kya|?AUJ;kgryR>9oZ;>6I^SWR`i0vKM+)-S zk!vk;P*hdzthjnGU*z+O8HoNKFoZJ5s>YItwi&w?Z#UM}rKe#uNY$WnzzF|X=U84%4GHS02YUcyF6H>!4{7g;C~2W<`VRU2 z8W#MQJv4NprX1)mTjE-)HZ^LnN60)s_y$0j?8Ebllq9Ks+5~?NoLJwN@{8@K?YiIo zVjiktPixuKe1!-Nti6-w=_8Wc@}! zUP1`t?J>Wh}}e%A1$R?-uVI|3l0NdJXD>T5*RFgn{AdusO;vZiu55i?FKDqFXA` zRK`O!`?xl7vht__6wg3N74d1t-*dC#LNcq@=-l17`{d#i>jI&nzP_>*6TK)xe0;~p zmo^(fR=u1cu;UlF-YxB{OjIq1RV6hr_CH}GGR)k|JTTpM-Oh%#NqA;zy)q-_6>fem zPI{&k0BfUcBSI{IZP$ZT`hJ~5au0=O*jFz*F{AXo#c8Lfk18sUDmz^rcuN;4TTusR zzvFdC?kA|J3LZTg{MwE|c8DNr;xTE*{RdgExV(M@h@&H6TJ#q>yO+kCh!s69nTuP_ zBMnqw3~c}6Ndt?6Lrq>^%NZvw$3z*2Y$O$_n#UQ|0;?a{fU!s)+&yt}nlBBqICe== zw+bc5!N0k>Ob9Pgio=O`9NGxHr#U8c=34K-99BV`^>3T(e|Ro=!KaD0=h;j`{fLJs zO%l;9Vppc+@9nC0K@ce7mUz%Or%@~1{J+zeWxc-*=lkp$P|gwi4erlrtjFfQO#Yef za*r>eDQsBV&bNiJ$`8|&XX34z{x>lxZd9+|@~@_rh7_gr%2bYv{^gY*ka3jz**>ip zW2C_e)AkudT0X5DEb$@2Ed>S$jegIPrfDD@eqzeouoP7()Va{Yz4L#V`s%nQzp!t5 zfOL-TuF*)NbeD9GP(V^jYJeb&IQK^QfpRk}w@cPNPO&F^{M&-?znf3|z) z+}HWmb*^>*N>?P&ZVaKG$`y?o8RFdtPWpVd2RO&|rH4E7)rIbYTzS;ec33*M-fCXq zdq1CG+9RGoicbZozm1f1%2NGHzgAZZOszF`7CXfpGmfPfzAP@r=UhzJh+0|-G@A=` zpXZ{f$b1<~n330Uux07y!vzNRg|wPkoNrByUX9Q8GgF?9wa$I8Zm67X+y$-V65M_H z#R}c&mAs25lXzV}vE)a`-IqZf2UhPXUrT)=Q6{n@0D>yen5$)|mVjQE3#NuPmjUkv z*YDm@Dco`L!||zlQ=UOP%DP3`Z3|z9u87*LZx$mx3>4fSFs2^qpZ8TsR|UGb`cq7P zPEe2Md}%X}^IG}qAI^5zhy7xwUvz{Azy0nrOdjt6x(l~M`a~mYx!_`qs>CXwkAJx4 zl8swV;F*>{ruyf2?%CwD#O}>6gkpTxGlCBP0oqY%s%42#F`!v>9@q=#+l7*4>RF-a z2zIko;{4im4X2z#lZbzIw$n?2GVz`+c8M(%AgTdEas@>9hcEs*I$A1v8kSLqC%V!K zFa`Yx0=Y2^5?hhEV&lhkO+$#SlA7$#f4UaLYkaz2MHJasKoS3Pj9eDKW6`jb{UM!)(k zah*{v1qKiSDD)mw=solFl&?<0;l^yGl`UhEQR+e=6Iv?&A7}yWjYI_8n;$Q|emd*6 zv(Y(35k_)}=)xvB?KMVl1RT>m905|k*=X2&2wod0S?-L8T;f&~)854j#(!qfK5nS( z!QK8UBVXfGrq^`N$4A_Q8lm;pM)&`379d`w-ZeHTQ4qlbR-mox=?P1F?pDW@qZDkd zp?kQPr?$OK^2lmTA3?}IF6oZH>K1rA`Hq8vuhd48Owg$lF+Gf}eaS_ZT`x-k;-b88 zp9px{Hrz}+NK+x#rA-Z0EQ+RzNQd#kINT8{uHUzP?AlF~j_B%>o(1!q-iCSbx9NZV zxeK?a%p3xj#U-sr~|+(e>S>fitu)U$bCbc} zEMn&r{^g66$9n*JSH4FymD?7-Ivtbl<$p!GGN;|zJNK5}%Mj$s^c*3Jr6Mx?Ioj~d zV|&!o$A^~J{S|0Q#t>_*-a!h0_0_)#g(w z`BNWl2 zcq>htI{VrbKJB&ikH^DoghGg4ga^m@_4GpBR6E%*uQqQ0=~{roN4KD|(7f|`C7`8Q z#s$UaWELf!(gJlpRHay{2u=qvfy^>9hj98758^`BLfJvRlI0Rv$+d%TyH6{aS)Cm% zA7YvAfETT+1qvrYTb=ZBKAIIy6^J(nRK{fQ-bw579Q_3dwuxm{Syg)Zt!%UU7IrlD zQjNHBzC^;al-w9r!*}&7Cm&!pgx-c-n_rp_L@YFe7$3SM5F%FaNQj)Q2*0zCAW&{M z2FP$PX+H|67>7^ZG9eSg`Sj1x^3JqVyBHy%Dp8*;F`YpqDQvE~yh63+r1$(hbBL z>|5SNC~@9f!$nadGN|;tl2xSk4;zN0P%2$zeyA>?7+Jhdt(#yIUa=1{{0a`o#wLha zXQyEv)uN+RG&Bx&VuQ>wk`5jcn)-%np+Q>nx?^WyL3^^6)2%$}Sdr(2^|v3J`BgGn zMS=I?hOx#_%|Fc&sEdNis8E$beMNT;cO1zlkB7)sVBeT<>xqiaUwaNxGsp#c)&D8E zw)3v>Z3pj2(jpNoT=c^AY-<{bvIwioDO+y^+q8V{ypvbbrpgWa!|7EjS(rDXU_br3 zABbdv-8fkCYeJ^Owz-sN=3%RETZ+13)P&p=XPIea9qK!zjKS-4qiw_4R34rxh`9Ud zxOtQcBhanaT#Wh9I2Kx*ii@xRYFG*Yx*aG;7}a6|VWa17QhN`!3f=>cHM@~w0^N4Z z>Pu(N!eyMb;j6*!uwX|Z)?z*g z(1|b2U^kOe&eC4|ee_ss8Wrrj`CVDB6`OX6z?HSARa4}?8hQWw!rL;dwgG@hPf(pN zR2S%nuePS%Htw4^z@w1<@x6$PZuDu^uh_=`3>_xk+Q|9|DSFOw|1k{X8`D2T?l4lt zQh$)y@E}kG<1eX;WM0Xvd4YXS<0dx#Y#HdpWkd}55vdgR@yj6HSn$X91O^@72gVZq zd(p3=v!@mz`GbAeLbZjD=1AQs;&0b)iysTvWnM?gmf^#BN-Qs!YJo*LIg=_h75+_C zMzFF3I1(XBQAtdW%lX=bqN<|-A~H}v=h8^I*IW3_4ivnKze&j0k4}rVTE!YiC%&wr znt_-`Om-4(b$i0GN8BUSVEn1KB|ZIlwaEps!4YmiOvGE+x|!3f=rUZM-NzdlJA!aW z%mqhB;2HnFOYddmn9vWZuEzRK{5PRfhdTC0?&4%q-u*umwTH600IB|Q`sD8 zB7QLMRs5C!U(=5^&^aD@-|_9BC&E~thR^$bagBaFz*%ZAeY25%BF>0fVH&wQ{PK)d zp2bNua8T4ttTtDuXPvnSHOY}BXDST0LyddHHCMs4R@_lY?2Gcv;~E?C5$ks=bQ{EB zc2CGw!vuT^TMSmM5nIB8V_1aOlHNF5TVNvA+{tj+&gl>@Lh7SG!l zd5Qi=9R&eSnv3Jj{NL04l8Zv2%wALM>0De)3J#fbIzx43)mlXpcUDrDUHQGVchaFZ zx$%kY!Nh|~(7;bTgCk-;>dJ9PmWk{*XLjJr;gobi9!|SJ2p!teRY#$#h@JTIA6o)N z2QSF+;oe#DLz8b5Bq=W$Wp~dZ!8Q~%`{8?Mo-=Pq_BA8~eKQj9u(PaC`qYx^7uvil z7tf3^7g|%4b=YegYuLMadcVwy+Q+ztddp%?@x?;Xl4__bcRSUGcD;Ra{Bob`$j7aT zTFpF-gL9sjJd#x2EPI73(RW?qMcD>5R+k(s)@)^4N%X9^==)wS-s@Bj{5&!S+EFB$dkR@l(%DdzLyg6 z^+dwo-GMO$)@QHa55c>pZ^sEHr-kB!zJU#GcQbJ3FF=2EZUzvv_2Iicx1UJ_6+GK> zIyIkkF(GIW4-n#2M#2!{tp+B8xJ&GX1=r@cx|+1u8HHMpXoAb&mDiicHkJPj{;j2)#dzh4dG@1xY11O6w+ssRoAl5ZM)?No$=(Fn z{doO1%7Y)j+n~a1GHu7w=#fK3hk*ZKIX!sk2X?yuJ;7p1=n)v|;@!eOEmaIa3r-L;1%iVE>;_3TplfV-9zX#y zh_GLM%j|t%A4iD&b+}meeXSz8aL|>}H~5Xha);+ku0&pAb?C3$u8EetoHVSWZ0An+ ztURkruIUMXG+eYi34)!y&Oq&|ud0uV^l*84DjsLa-82;1M?GK6T6 z?XGW$;*op1z@6{^an7k>9V;HpbTo^BBOa&cJ>Wmsa5o3JNQ>YRY|wgrQ1l^CzBi0h z3De?cwUSzH;yF3}@XQlHlJl3!XnfXj?$U4BKBMeW;yxs77_5{$l0nKmoZ_1qlcvu! zuuuS|xPc`VkpkGFLt<#*{OxwK8ACfw>(k%6-S>mvZinUKB@IFEz~MhP5e(&FR!t@i+{ z$;tcFNvKW)(iB|QE28vh1bc1+RvOp+kP&-M;XRq!--IJRm=Q+*K?aJAoAs$s%h$L1 zufHA!I8Q)7h3Tv7_nz-kKOt1F#TA4!QP&xugQ;urSm)WYhYHh)u7+tGi%3cdOLO(+ zq_`D(@m0gBle?CUWalHagziuqwH@DD3I(B`Igpokq!q2pQaG7|6T0e5z5TQ&L3&gf zhUBXuLCg|lt-y4GP#0Ddt>j)>?WoL)>e{X9pYay`K?Kvp$|RwQ^pMOeblT-e!$+3$ zR-17aJt}P2>0^h-9cVMaKB7gaupjsU<5(DI^bqR|^aK!T<}EbnkG$k_??PsR z@#&I=)~bHq5V~En!v46H+j=9CbXdRdD4nXEL%rxd#f~R_BCGcmJ51!p3h$4fE;X3r zdT~~RZf&xk6v>UBZYWlCdaqo@f|pm>PALr2D{}~9I4wby1aP594oYy~gWvw|Yt&N|Td~RQSlsjsT0LK( z*<3pDbIZR3phx>8fluE%czLzjj^{8299n&(e9g#eBekqNwXl2V zqdq&9J91F0F?gnmS}b9-6AH!+1LPb(&QWV)cHhelJ0nzoexH|J6bw#&0d- zU$v&z@}@1g`K_iC6{LxFw4rJ77n$jjAgPInY+gSfk1}EVQx_d9jjdNdCnCE4(?r*f z1>&M{N)rNqu+fdWJ>mRQHDiY>JJv#(^{i^4*F`Z?IN!r-?2K_y?UGJtjRnez7TKJ# z4(G7QJMIi(P+VdhZsRgn@u9TDVZ%eOPPtAEg^uDB_E{~?{jvJh&;mLpWskjj?bvS= zF7a7>(?lF917QMb=BFgt`t5T1hsSQc%6ju|1TeX8gM##Zf7o(Wx~7M_d{mqo^f-Ng zzp0^WsDSV;*s`WvlySxDGqM&Pxpuw3_|WSU-zCSw^WQ@#L3l~Au;Ln@8Zcqi**P0q zmNUT2l*{jy^+feUit`T}f@`!NLmUri2Mq?u{%=FZKKmShyHzZXa;6!+H5h(7-O|wX z|Hw#~mN6-~mjC5HYB+0~8*N1haIp|w_(j0-;R-=dZrFu1iV4-R>GCy2D~xCIuoQ6C z1R5Rh@O!h03glP=F|Ncg?1-}%{cGFzql=FK zP-V7beit$_1Dw9`$RbiYzu(>X7Z0-NG(Y8Mkev2e;Uiv)&-D@lu6U2QCgziC|Bl%N zVtU=F^%}Ma4yU;0uEd!+9TmT5#B)Kj!L(uZ0H{;&ce1dwWSP7o)rv(>Hp=2F8sn|8c zci1%Mq(HJsa;B7mdGp$P*K=G~m!&I#)zn8_>NCMqhtSsH;uzUWfYEvN;fLL)@@2{9|Y(kuY3Pw z@vPLDp0u1K+QvyzGwgFp78TL`4rs4OJL$8hF0M9@FOFCO0z&!HSR!a z`=-z7S(6|ESwq4fN&M^tCO!G9Xwc-lHeIPloO)L=xylpWA^F(UfS>$N*lz zS14TbLy13AD##8m9hV#*J1IA%Uf$+TM-FG@V#-;|W2-7u-Se_3g4dk_xhCE;j`}AS z9{F7*^nNt;uOU@|jO|xdVZn7GTkXIz8P&Qeql03@v}D`|;} zRw8v;@OVB~_+T`^-~{1?TaQAJui|(X%0d~i`|e53&X_XMb$_l=i(tx54kfz^UWu?> zTsXetfjflL*wzF&s-$QM%*yyaeVUpxDl(;a8upGLDV9*>fJ`;!NZ~XL!{pA4d;8Q? zKIys5`+f;b@vHx{RW6STKGLjD1 z4y3(84k)2}^fQH{f*vi)c8GFxC}Z;Gssyg(A=j>=) zCBn(q-i+H}wLd|RW2gUKMP7~-D^9xe)&^wm>YiS4u4*#xZK^GA(HHCs3Gt^kZv~ui zMnoCksWE+{W}jwumR}Gz$0L(PAQK^yx++% zZT)GI2!_0%b@Y427mo^psjFck4%9SmWSbzRuUZagxMz#{sxCr^!g58`&X=hj7AguU zd}{Qm8Ei#!MGudWpc5PnQ3(H6UQF9L4LVn$Uz-|Vdf=TBLvO@4>#W6pCsa1tF@w#- zMF~oCgie1QrOI+og`)|a9@0!*63r}7e~q|rR9WkmiW@;IXS6E&nsC``*Qz#3Y>bC2 z7kOIA+RZO%wE^cjzTOtEr3&KMvk-N*{@YPHJ`jG2y)jYOp`b>4`YMQlwTL!?_!p>} zLJ{nGWNyiql_(IM{Bvi?HI*+R-fs?kCDGKcn2$bIPsW6^?)5_*ZyY2s{TJ0n#|S{2 zVTv(JQ>^g%RQ^_VspC>ybVm|@t2P@)Kkany!&-#n1_2XJJuCF#hs>Z$dykifK}&#I z3*>tclj4-fAzDcP0;5BO#LEzW_-M1X_i?WUr}r_z$<8d6ojzUP^@H5sDakx9l!%w4 zX2j%T%cXl@4&X@29vHTPVI&yTpoG|hHPOXB9brC``JYfw#o=R@iC6s|ipfPLNdt9l zI0QuiyXnAfL6L*OK~ZZfn{Vt%d%{NTg_Cx*5-30%_=YcvJRAv+6!i(sEUtXnF0_=$ z#B#l^=WLr6sJ_Ck^j0FSUrPSXhnoVzRG3LZ5l*mtWT7yD%fj8jz1D?6?C!C55H!rjfd<)9&UP#S15> z*r~JwUR~#aL3lk_qie#QI$owz-{R!w&&^XH8vSfh<)_aEF-k@#T3- zW1&5j&;XAyskSDtz5N})}Fj! zs~Ii9^u30NEkdORHLa6(T9N0SuN`SINCjf+ zg*xBD+N}Pc3kGDp&xp~hfMS+hBdX_hC(d^UGH5b#!6kGd3zC`xfT!BM@P5?TuE_@r z8$=NfxyX%!>`T{MvObDR|0?};HqVAaM|lIF>kjGnWA7*G=f8VarkKf@na^~zRU>t@ zk-77ay@Lr4vHyhk`^Ap_^>X`$VCu0!nB91RY|B{if3R>weFf))lG-2pH}zvH?`YDQ zSM>%iRUY2FgP9F|{6(hFJJ|f3^dYV|AvCeq*vXhAxaw%RCF-kDu`H7>?n}bZ{s>PR zEY2Q;a_ng?bF^-;mn&AAS%Ov>1$$V%3&jJFLtd;c>fGJAQ?$5%?l4KR+aI7c4SYp9O5|cQD)`wF zi_Z45XWW;c3sq3oe=5{y(bTpJ2&bs=sqasqfs3FH$}@J~CJQ zFt`WKS{Me_RZcf&3i1q27z^myG*{K176eooPHBCO;neJuAvtASFb(S`a=W*05u_dU zt(GjdqaVoPvFh?*$hEmj*_bkJR+V5x1{|i;hjm5VjYX9;fqAfSBa{hwZ;cfNWQIlw zu&jZaoBY$03^IF}Lv|kYM1HiF?7-R=QcsCAP*V-lOdsiNpCSu+l+%UX9}A0+R3>#L zw8#$q#@0)1uarP8*@7hN4W(WifwnWodZ5Q47S(7THdIRCPQ-7obh`E~5KoQxnkW2;9M)+PuLZRF zLKG7}8WrUqv@P@2a224$9+w_-o1?;7?Z5&0d~A)LY8$mo?>=`p7oMV^C#_$7ruKic z0E0Nn?&wFTem^xMEm#@8Tdc>D^5CCBnihXxF$`W-(fEC2m|j&r-HoLuEtG~%cDLSq zY(3U9gl}T~^E|@t4Gg`h^ApvxW!zoQdTfPpI&Q|w!uEAh)J3hDd=34g5Np-&Dt)O_ zWtPgZf5b5>r+H%6AYtW*_8l1t}y;7DMuLx z#Ew4yrPWEYgz7O&~Bz&xQmt03|6#mGv@iAuX zi2=f|*_5=xeQNbd;iheK`2o68{k@&gVLIW{UfD5jB3B=H6ppJ_-!N#)R%2Cnt{n(3 z%-Z+3!u6D7M{{_@sp+r4_)R&X_hIK()#RSD-!tWdJm8||PVo$RKgU~}s`~wv?C%Rn z<@28^L2EFA%-p*{7-a0Ey44~J?4aNs#Z9!rs;yk-K%Dw-hZSjyF!?RO|JC+|fDA*1 zqj(9H8+2IQz5$U&Aj;o|YBfQ&-X-Iy!lDRw7u?#36& z)V}#F8OPoh_X(hK+xR zBokM~UJ5zMqNH^%E%cT+n`bSn@hF+5y1{KD^A}(2rRd;ip}BwvKoQ~?{8r&*5rJ9q zb-b4RH>=Xj@FIN5bEKuE)3H{Qq<5Yz~ zQ3sV)u<>*_%rx@vGi8cUJNQ*9!y##!)Iopf6i%UZk;l^Wq~v{j+dB>E2Y<-D+pdME z)!Jf{sD&J-tKQMf1Z~|&!=v9qlbteyp+<;HMP7|Q8cAM$Cj;{5{3z>6N21aewV{{!FlVXcvfs!LDeh zUgI#5Pq3~{aeWsEnRmEDT5~6EJMY$|Vj^xTYwwzB^^$cuZhxf1?yvLwcGG>en=K%I zf=p>Q)W55WN+`cDL^l)xD#j82+4~srqa`vmrhaYXz=-EPRiFw1?GJfD&*Z`J9Qr#I z%uz)KD-Y09sNvVo;3gKYpOZ6xdpienrUY|~YrF8HDS9aoE3sXhH&O;GO}?wEt3b{w z>G;b+`Pb2;e@{Qw5@%_B_7B+~p>++VTQuQ0ac=P|xgN+H0;&yXfbLY0>@*(O88 zZP0|h+6&+?ep1+)r;}_QlZl%#CCVovSWA6!h0DBj%KZ++rGIgl9g?2948;>?X(@w@ zvl_1dhMv}IqHO8)JV^HoP{HN*CO5pGdEp&8w1Judt=-oE8%z~4585KT#N-sZ%tK5@``gPs&25EN3u>hNAo185o)F6SZf|2cRT4)9wuNHb)-G&snb>fIe106}`I zpwBSk-A*5z(&3bHP9xe2?&daoO0jX9GJb+E-5gtH;_*cJ3GY z%-+AibvDMY_-z5pD##-2WSU>(d7>p{w03EAwS9@?b~Ml(ONUs_IsP4gx|anPv)8r% z_+MB=oGjZFVtsI}Km_V(V^`cGMAHQx^@((22PiDM=9vDx0~hT!qh8R=gDxqoZ7hm> zNO>kik~7i4D%*L9V$~o{3H%6EVvAWO`M#}_zb+!>?(Bdbn` zJEbHf39Cm^js}&K*dOO`Bhz$Mcn8oNMafqT*!mf!tGIQCp%u}}JocoadKL99=cDiS z8)35}pZOXS7Y*jqJnP?8Z`lftj7!4QG%OjVDcLl@qnGolg~202 z1eB>QY%jH3xSy|(Y6{F+F(s|O$niw)xzDG7Q>XYZodPM0m#XM@4LuxyNF4SpQ4Jb@ zbqOy&E|eAO|5OBdae4pQLN<4{D=Rfoixq?jN=159(F30MgCZ>b+}{FT^O$R(RLQty zV9+-p;b5R{qV8s9e7TKU3CwyzqAZ)>UVzLtVM?4tttO78)x)aQ|5FXF8TNnce}=(% zc?rl)Y^YW)@X`aZhsrdZfh=eWo;c&^A}Ox}4QuXXz3#iD7gq#;5?@plxQ0S$i9d zOvf!6t7a&D3~85H$FbE@`Km8@1A=&)_R!TN=e9qB#^4dmbipFJ+48Rck98TsHH`?s zk0|r&5INWh;4!_=0}OKPj3K6OE+m3|R@k9YTcd`9Mv}fJZ!SBp)=BDY`rmCA_z^dR zbPWv*Vf=*{|9FOQ+^dHY$cI!VcZ~5$+$aC)W%=>QIJV$_;ja-rlx?xZ)#I$Q zhi^8-wz|vx1y~y>8vJ%4Jze{a;dLCaa}>ccw8z%hWNG4x8E4G`YlDHoE^RLEP*Gav zfkM{5v8B9zOY5bue}{*WhEx>R@7XEXUqp_7!6baQq2+m8AUgh8vQa*}SHICszF;e7 zKWBN|U4DEcCoD=5s?fxO|9Q@^V8-A_Dk0PkMQf*H)kDROjg71RntN-ZXbZWkJfNe^ zu6nUhG`-tyh~v>}c(7|XbonP@*%2fY4B@dF|BjN}!uhd7E-0Mdyv2A+v3A|^0@F`h zQrDJN{3ofaxoVO&VPWA>t_S*XIJ8KvIhgkGPN8Wen%*eP-(C4x-czNttxXyM32(V( z&P<$pF}j##qbo&4W7VKCGvm-L2{=CZlu~wOlyry0fx7y&6+KIz*9wE_KNG{(rY}i1 z8r1f@IO_1Pp4c!BDTIH0O_OvbfAk4-dExr*ZO8j|sz}_cgA)xqtGWc|SCS4coDONV zl9I4@$^DDux{8_W$5NWer&(Glh+J|+UYMWr2 z_h+Qo(c+b>(}y+1`^A19)dTV|rxX*Mo^BJ2U0>rYC$mk2islkcm@dmdDs;!3b$#eF zYZc%hJ+pR_a(Sr;>KxHu`+Z9lxU0WW^AqRvO0t(8hyMqX5#i>6>nSK~_IU?yn&9?T zJc_m@uzot1YGhs@b&@T}2)=oB#L&ABp2qIScSBJ}F&YJFA;d0qNO_XIhWE$mob2Lp z(bD^q`qkl&DQP{z?K7)QEher?*~u*xSNN#@og94(t}|27m*p?heofhvopV%+|9#%; z$;I0yZ41Mg>8Pe}ONSK~bk$RS%O0Lg?5}lN@%EV`-+u(=2oST zALZ*O@nN?WY^gBlhrf~CHIG^;>C;tUbG+TMJnWK`D5{)Y&t_gmRvc3AqS z@kl@vjH*uIyXJgcT>ER(lvF1v5FTd73(f4MSy=K0F1gmmC3I^3_=ubty|KoEwUo8X zb(mLf@dEdXIZ?_qvUI7+*rPO`la#g4FmqL(#+3u~MH)0W*sTVkwmiyaXxnHQvh&|r z?3kg1*Nr0z3iiG3&1K1lLW+O>1aDj;IIvQ4#TmCM7-$#J+2Vpkgqg-HKBIDp{uF^& zZeqUz7m1qp%VX^-pLbbWxZ0Mfl6P2CCb?jnFGWa1a!J0H-DRNWL4Q}|lfk<7TOL~^ z2*1IC)XKG~+@u!RV=IgZP5zU*5`}ooa?a1r)-GofTX=p@Ni;cOnV6!A9PE19PpFx* z>j=Hi@bfR_Dh%;=^Ut`l9>NVBwcHh3HHJLBMfx`WIk-|ZDDnbso>A@;7pFdsjI%$< z#WYc~f6MS8YCZR7{iB38?f8E1wER_1A&to-liKrl58{bwE1%M43VbOmjK;eqzS8*c zy0&28%a=N1he@1I?V9ccte+SXt<{`M)ej~q7iMkl*Y!!#SJ?#LYx`rHBbZvmM^oF|&!q~b)7bBKZk2PN%YkCxN;deANqTY-qOc%k4Eq2;N zi66P&?0(X?_*&?xRlZcR^bNXKr93-zG(quV-t;TOi}`}-8cDU5))E`f)u_03x7iCn zkI%Ku{CFz~I~M0PrR@5M4#A|JA91IV4MXzr-Y4UtoUC-V_!}X$>b@h&$_yB ztuA&@2;Z9w6tt>Mp8+9Wp)@+iz|>rk&<|bOl4xy&I-(aG*FxwOtAfRzx`N3ouXqs2 zESI9-JqOxL$9e4YA_TTW+iVro96iHoA;C@$m55oHM9k`JN_vC_y$qy{JsHI+PuQ_p zw65fcLp+Jff6~=hfMak;{aEH(By1+e1YZBJqYbH9K5W&$)Sxr`*!jans}=g3!16}~ zN;Hm3Lhwiccj+AQimQJ{F+whjNcrUzGuf->;N#DTj3?rS_g135THe=SjJSok=ZFvW z3d0%P0ic&W9{X}19|%jSc}qZ(w(3jHpSQDU@3=|v0asNAGk##ur~3f9ZZA6ubJ395 z{gZ3WmCmGafzD1?#;I1)b0HA5Hg4&brFA#wekGQFG`sLa{lB+eCO<) z|Ec^!VDrzqxnAt6)y)fa&TCMtZX63ihJ@f>xeUs3yQb{Om8%*5MoG5FSXb?)g+Frj zhM8jui?2f?LMnJeSA`N|ojx{WhYJ7vCU!kI)9~5q30sMTsL2EegxCE&1JVYQZN+p>| zQsqH=a=k?z+6ekIS|?XT*zB1juI06|>?)?^)DM%hPc_Dno@14lII>aulh5_W2!r$| zlDcG5K*yEor2}#s<$drej5>A;#;9WFil)Xbm!p*k3j{PzzEMcqj69|E6EAEK zc$IGUp{wWRsUEy9wzlS5(=zvM?OSun$Rd?D{`6!A4%mu2*VVt0urgEliK>4iTgGl$ z7?$ske;DH#`}O8=`ZV`#SXfhJnU_uYrj2PSVr+k&UxM#LtwVqWq%B&uH(*I+4er(0HfPzVe)0DW`HWlzM&FL9`;HFQ!Y zkLO+azpI)%=e!SRYB6_t=M>Y0LKC1f8r5BaRT^DFvcYT)0d2~zIK7Ut@~Q1z0=7H`6ChzcH)D(R&x|J`tm z5R~|OQ!*WTK1uN+Ts{cvMYs&{tF+Q)QM*OFG1_h7sDArXf2pFwCSy$hect*p#7Bur z#bvc;_>G%yzf5+Rn1#G}h)eq{6R+c+0)XG+Fj_(VR~tFQ*YR$z4t$(yen$) zION`{!4W?n*-;lOQJ^a4hRi@K*aWVd1vY^DFnf3d%eW0s+KB&BiTEPM0dmsA{ zr2-Xe!|fO3pxC4x+kwRKBc~R%9CAR*T!RP3FWgnlC#*TIUUNY6LDXr)46X#tu3`r! zZ{CK3!+9zriUjrC#!?9`8u8!gg@TOaK^AE$(!iv-J_f({-;VqJo6a-pYszTz9gUKI9wzQi|m1VI8(g4OA{j<%d%C<`ly5=5zh zzX1lpb_geWl{`W3qdUqbN-cSb6j|5RcvZ6vuJ=(rhogV(y3TS(zxaH-wl?;2t45IM z-Rw+Pnct~%vRY%&I{ZCLc|^!BuaYn2Cf@i5Dp`^vz|vjw55`j#orQkS zBK(t4bS8PQbu3rp_sNjGGKP_%G0{_O+e6Kuw>%kLelTzoo6lK7#?qy2gdjzQjV#If zi@Ol8CfN9K7+UMI%f~7?0~HWJIy=#W_9ZHiHA*Mh)CR@*Ccb~sK#}iFfpC~is0ZLr z*lw6M&LEx5`5*jlr7<{6Ccf$2g()ad(}Zc&Clq)LYxm;lEF@J(ooc(Zw3lq&u+R7? z&x07++L$VrCkKUoFUzk+S~N5Qw<@nSc`q_<>WuAc?|{va@@#c=b!pKx6&^i- z3?coO!?_?jLfKmL)ZAE<=cJaEesmg50 z_*1*73{I`+SW~-U*obmXLr(Omt`u#k!D{R9^i@E%AB~_joH!Kj8qviZ_;#eXB^=L0 z6iEu#JqZf(ChVU#_NWRkvUo16t7-RvFXt~WMjX4S-W}2Nh)#tK>LWA^R$ zR!-jZT1cE3FNL4r*^W)TwX1UwxaIK4Xu-9DiPI%=ae|#95@#NKFB>jDcYgCbf@*CJ z<2D7YCa};FUC+3^wcisPjI?058oodbC=VZ}yQYU!_G3REOrvIcV{i$8(+j&HSL&iv ze{pmlRaUm-ftEk|FL=~EnkKX_Zds=E*eW_Em(;w##n5x?yBP=n<@@$#?{_SZ4}-FR z<>W#d5lq565t2_VvqN!^8AEil31*E#t&Yu%T4`yY=3W?4x@kpAGM&3OVtr1U#luAB zQdj4q3^(7H3n>=gm><8r`{y3MhzB?07J)_|w#U{>930PU`P4sMyuiM{zfkC1=&QQ- z)XPWZ(R;JleAr ze?)vl>|#I1?r=Rodf{vtnG)+_01sclUB`VWUYH*0r_uCryYkZ8Ow{N45hfhP&p@u( zN3K9EQ`n}N2Cv5wUq;x%ge8?T$MT3EK8xa0=UL!K62^m0@9g%JGA#a@iF*on7vY59 zyyUt4=y0Q@MfKxAbc+Af3K7>QhO-(gU05$c+<7>xyKDb3c9M}5*?@P&s{gwd=cX8v3ilmBeb*cZWcM{%c^YTVKl^3}9sDV3O8exk@?xvj3+Y=EGzItG;yIyVO-Kj7M&H5i|pJ&3}LNr6JNG$AC zFe8^bL2xCrLOF*#HZ@*%-v4A9Dv5YU=1qI2ENl&RTxE6*KXHgf{8mr|9rw>_3|2**>4Qc2ZDr z8t8lX&9ZY+tsfo{xB{?%{hLm22*?W4oNrQ0kSOyk^?_ zR|Fp-xeuj&hkOpX+|syG7O>ZP{fyFyKuhP|dfPb~f3)+H0K*0M{s!y)7B z058AV&(H*xzA^NBuX&=J{4IfKX5pb}zhXbc?k8rVzFSH04Exx#sx)9`pTmbmgnm1> z9)_-61emO*G3HTs4^D)T8XW>?$b~8@CZ7(w#Z4aMmR@Tc(Vf_gqhMTjNIJijYq$;qh*+5qv~9jjhi{UDijMu!nc zAt#!5yb+Qk4{3W^GO@pt`wK5_Cp`bwx1(=iWa21WcKZ4<-HDWO^W^>dmrr0DrPo+J zZzuJGA9+|7o)AufJ2G_3kxyU9l1r_65AsQs5rudr4M8|@7~}UmA5hf3G$*IA1_#du zD3u_al!pMBkIrK77M)Kt^8k~-`j#Y3_5+iZ?c(ug#nhHmKDj>WquY&pEuusj_*;CR zPSna@l^!j0L3&VKT0_-PekfSH2 zWI+ozi>ofzn~7vab95yliwGEyDcG~>-ULbU5Q-{3@=Qsh+dzgju=l*ZseX7l+fP(M z;upI1m8=gb0(d600TNv}Z}nqe8hY|1=r;`27IUb-B74rlBE!>9;LH{@jB*PvwalFO z1d@?gzzuijnK)jh?s6_WrN~+Wq4$Hm=AU|oTwuKWoeeHn5U21+3!qt0atN}z*UL2)l`F{YFqRw!rkz;3U4ii+G~^{mg8i*MME4f<&I~nfr zT?7XCCB)8*LI?9bkT&o)c>Xb&I3p+YjL}lus|KkjK`&2D3^F-5HGGr9x5rfccCe{q zx&So&mPY`e{HYt2jTP24_w$m)i#M_&rJpULo3QhKW_^!hNIR)NT%HpaGG82GxsDwG zqEwUZA-@0A7R*-{j-DEQ;O`%*;c6V}Vwua>i;)s7rRzPYIn{{*;2%Anz9!}EGC@kX z*l_xh3KNc;1IyCz=r(|?l-XBxNB&WoD1Y3?5@NJlZQCcf2vr!xbC?e!SboKp=3wgS z|A0-TgWf&XYXS5SxP6V}>5l~-=AibMx*xx;mqqIWBf-aW3U0`Ky%p2<`{89nqOS=1 zJ2;jir>DL4bRTy2U$}ZuaWQ?Q*;>B069d^*ruu6wA;_9Ty+e_!*+!chi$%dzwZmY% z_@UQhevuljIJ5=>5<3(d#@pj6#bB{+nV${Xas5q3^T8q|D!+%j9~=6*MUbX{&UiWs zJ*SUvvp~Pqs!6x_v(d|IN1*8mUA|udf*Zz5(wM1>1TKH_Xj@l^3yw~6F%#@bu>Hx> zdHb~4WM{C##t~@)y-s5E_4uAa;RF6K$i&v!cEQ#6EV-Ncsv7RqCH+T)lQQyUM`@fX zzxY*v<2VZq*I}~0Jupa82EbfkLbvY zg-;~-yAQ%(ilD>a6S#zvPxY0#>6dVp-3V33s<^f42=#bsfieVz<*y#Sx2A(nSih5U z?nPhk{%_wT6WEqPM&!}HO9BkIOj3|%%}A((D;AHBEkYJ!qpC>jGOl9w%9#u9ulb!e zppHg<&iAs^P{;P5j<}?^O>%xl z5%12%_An-4;=n_lfauMhCGobg0ypzWOcpjmCmsM_D#*V1D-=B??n466M9Q8$TUzkq zvuya;B3<^b`|G@4^1svdm{rRI0Y6&r#sMC0kRL`eXVPi8^!h6TPx?!NqEFcAv*tg) za=`|l6yxJ&Z7ZI|ea>}#MiI`ocSvRX6A%@5RRLf`vHX+eL%zbxc)aCb34cRx8bhE_ z87>dH?96-o!A#qTjk)CuNFbdFe5Sn2%kA`DJHgbQJMwpk{QM_h|9uG-ML?ue-_9fi zIc;;rl7;cAfxYv0!`b5WGdg=}xjSh_wSSkpfrX!kMxu6tA~d{gr{q#31ZTkR>oEmH zhpupvxYXE035=zQd5#tuaD8}(j;EVX)0+XSwxpBi0DE`|&{NEq3q^u>VPMR@D z52n=M&;Z!P)BlzuKj1^W011D-_SeY7Nf77ckxqYsD5)p=T-Yc>pSabw1oi4SR7cG7 zRJHHW8y zH*7W~d^6SQcT?+e{xKSR`VwRq^B|L|{RA6kbeRz6m2p(J`n?%`6ex_1XaIi1Nu(9S zZJ0I7$jTrCH;`u!$lld~iXmY|GCE_SqKUIhO)}7FPg755SZ1yc-e}TP$YONZB z)Et9t{`cWD`cCj2CC58{vZIqfEtNTnC)^&tc7t9K&E)+jvz&lI)mnG8@TBl-LsK47Y^Zq06QkKR0DfUPY%5A}(1<7+~Yt?h%a}5^ouk7Cd^fP_*+m-c;YJd508+?kio`H(L$(a<{~J9Snb^Pp#o|u1yG@xLfyJpoZ&iK;`;mh z{$2P!k6i{bq^~B<>MdUGVYrzZ-g8m8*)o`u^P~u`r!Bmr>7U5wOFVOXAF3N<*93HmjTXPD?c2JS z%=A1TG?mgn`Yn7~5eDc@#OuU!z($_I9<%H99SJxdcXnYD>P+6n_z_MdGorsvOn_w6 zy6BeNUSB67XCLMFmp)Ha4D$;)tc#G-JxwLV2;Qk`#FB7|-_}sgs~B86X?oZ;3JZ35 z8~;|_mwy5_m7T2?F7RT#WW4k0#gV-5(9T6wRhj@`U}z_Kd=7GLLv{XO3P|JEGce0D zU{G`YN^?^-bpjA=b?kEwFlu%%F$ybYuSH7Fvu3M;6Y04kzdi)7->ntvJXg!4yxoOU@99^s zj`qi^1H3u*AJA&21WzNW(~-a5T4pHr=5}l#Oi5p>@?$05`hTRwpOK8KhaMjzj1dJu zj1o4r_RC=q?7T-?y16EH&iYTD#}#239y1*mS#l2cksdOd#SUO!h1rCkD+!L0%bGM- zch)<+n@oLoicPKSXSAV2ibCu(qWQktRrH4!#cpENgw+N4w2z*Qa$!(uJ7|=^iDMh^ zrMXKSGbDb$pUeX`B77IlPbd_kT4h)ySNa%JWLUYN0~g9C7BNU^H!uPcV?`o?MgF z)0l5n16#RzYH}9*x+W3f(0yMZ`5N?PvJ?fQUT?@Bwbk7zb)z$#z?O9uYWu;4`Z6Gj z4y|hFxkem*U0(v0)U#hcykFs{*qjz(@OS_vOY=qABy?dcTk}5$@mwQASajxG;d;u z#<2Hvy}>+0`1jspBIF;B=z71~oUs_K=JZfP2tU=&ghoEQOd~X(y4VoZv+C3nM}e<< z3;5Vxa!e8r^v@j+h-T1;xmg;e9R)uMWkj^(5^f zjWDmVaD3a#><=i)(x6qOo)~`QT#(OExN)3(vd`AcTxrtGjFzwK{%m;qJXZ45F3^Ca z>9s>Z2j)m|^q3iDPa5`9oF-oMTn{&ctB0lnp}t>KW*i#1MkwClmGRzyfxXUrRUDYT zv*Z|6ER~xMo#1hLejt&S*EyADOdJ(!fpNx9;tHP0Y~Zq$Vh!fJ(7fZJIe(=XOQqOM zjaa;WVABK1)M6;0qTafzrjFJFiEV)}!SWMxlTwvPx*mNq!XQVo(EX4DS*x+ei;al~ z9-x!+jo-;^*|jPJ>bVC-Y7wxFBGp}>Is!PPXjV10#oWufO!gC*flYN(BqQp^_4)6j z71_lOBuX>TzF^WP38(@TbB3Nl31dkRkYyHsChw?X%egC9BwUgFJB}$=zgM$na~?s@ z17q^}BPYl|O>l%$DfC(E46vJ;Svo|I(CThq(jvGiIujywKc`aEz}~Qhs$F6Jn4R}g z#3v;qa+gOrXfWW1aVj_dXFU;{loyL8nX;k8q(-3+gt0vWevH3i!M`Xp<}^-dp)(dT z-U>NL9h{%bJoofY_7=S|T(^{;q`L*5+&qX-L^B^~OCM(dlHBm7H|1-neLaX-@yFJ9 zf|vG^8%pOnGRDF!)8}1S?Du^7-%lFB^!Yg^YZT^>!fY_dNu5T})0Pq#L(vm3jpPZI zoT2iKOwXXpKzno7-BR>??@tgOF>V>2axWgqAPRP>9;BNgDQZ?5SrJw`^Ss}X{rK5B zKj?37&(I~>;^&C8g4Y+gh4(+c^h&>@Z_^eJNySohJ3v-J?rWB^ily>`Y#M zp8A^(jVeORCY}GH>6enWphOvC?uvU;P{h6}saZsW8Qq{w#ofEB@xd-U{2z~+X&?%I zazW6}+n1kBYWtheB4Tw7h)0-*f|rx***0)c*DU-J02XHFE&TJ*(iikZhbkZVHk9dC z8*Mj&=}9}j#E7=+X&raM9y{rQE(ULCHqq>3?x3%jf5-iC@q7s{Kris@q_E^Dt(`s3 zp$%7_>Yny!adHc!Y;dS_eXxi`9Jr8x1uPz2|26g_WAKu^JV(IE>f=ZJ$IH}`+@yC?y+dz8Y zo9)eYwXXYR+GTLimBw?O_|X_F@`I*Pky!`;I+K`xSDc{C`MRDy5%`oPo4a*9KYohqY&dJUTt+zj5qgG9Y(8P0KcnP? zzGqS{qof2^nPkR9MqP&)2z8?ZZO#Hgz7bBcuUX_jkhS1~>*3p783mfT$%amPxbM+^ zanvqh-G{w2jbmqSl2Cp>p4-<6bmP0;c4hI_W861enlRy51lcvbuf-Y|l$e~xyT4lV z#*Wo7eMjcF*}>qovOM8su-B6VH_V93x>~xUpa6yJhs*D{Od<#`a8tfpU2mxj%qbOm z(Wz8Rm{Wv93Rf`}i*BKR_VuG?z2*Tn8nyEfGC3Lj4)Ihfl2EN6&j->KdV_qE(*wKa zHF0B3co|R=58&~E=N#(7!k* zt}3y&c<_u0&g-Y0G~$_pO*!f?sTgbDu&tq(Av6fyx4oXlt(TCe-4QSpgym-dl|)^c zB_P->lTx#@%wXFnZMMe`J{(TETffFkKW3yp4-%6t+y?8=1E#TVd$s`ih^!oETHgb{|@F67I$n`IqRPk`sWW_A32HzI`D=b^DYdW z6BQZomichEqon@u**o?A7OW(~T(pC)wba`*%G?B)q3&|m5Y8ZvKf#pu(K`l1u#7}C ziFggvm~++JUA1B{jxzp-GayS%ujVuN&^!zDW8O)yQ7iqmyc?^V^~B6+AUSazqgyik z)YNWU8CLo&Kt063$)4-8&_jiM#5davr>y2Cf`4pTRd@xGwZPa)#^Q9$Oglt}Y^RwQ zhg^*hHE1`%FbADn&~b8XD1FeXCxy?YB=t?VJG#(S-@C^09thwRuD%MR&Iqftj1cx% z`L7yFWtSQ-!=+NfvdbN^=&AQL`zsLf6!|4B%~>I|=l7Ux<;d)C9)Pv$CUAqXvXfRG=gs417XRkJ{6Mfp_6qbJ&-D|-W&vfzDu!ONC z^H0j>U?Lm*Bw1H6fJ=-)zmqgg+NH))uamkNGw4Sk-*&)D$C?LqwMLvq*uyqQ97}@V z?cgw_Ew(2$uy5xi9Fafs%}JY`;F9D=0h`UpA-_wZeB(u$hrSIpg2FT!8|FbT!fsdm z8d=nL-&@iCU-1=ErCU`b*90JT{usMcjiTDHzI{n`ygYsLl0(C5xw7Ms0RI)~jyZJ{ z58ZyK^>Ne4$@g-KWgIX=)ro@vk9=JN_$xp zt{CShL_zL^jn3q|Yve^$%BZK1^hGDrx*Aabp>2HI{nazgA&ysa7#yb#>1%76M%zSm zWDKe+^hnnI3pCbcUUvG4-yZJ8D0HdD^%$>{Q!Y*8wRy3H*L*TTQwJEd2&E_mLFa}j z4&-bO<$vSzqo3zTk)A#CV3BjG%eka|?Qi(79757;){|S{&o-G5`u&X9i9cswrqSPM~FAs^7PckO-lv;yJb9ZQhJw1p& zGmP@{Nxt3Q-9`e;-L= zb=b$|HbEa<>wz;w;Wu@BqQyQ*pstlSMepBDwyQm*w0no3lS^u?Jj4zncV5#7uAjN& z|4FJ18(2A-a5ol}579%Lvwsm>aLxWpzSnkI_6hdcSQPUoK>;zI~wf@HFEkG3+96g2Y zgY|Fi)bsJ~VbCU;xSl=3?_G0Po_`iO@Si8WVi}%~B#na9L_% zyOU}HT{DCvDDAqzLMgZA9+>~5ReTEoA6M!ZRlW;8w{Fsc7p{camvV_?NpGoqxzH8?Pp}V?TUQD3}f&Mf2 z{SgL1Ha8FBIJ^tT^#<<++I=#mM;}XhlWQR6(y6yztaA1fU%3Hc07@?eqUWxF3|GoV z?#QNe=68RRMV_gldz|;U&gvWE7lWQ4MRq^jNweioR`-4~kWClpc|Tvtm4MIXrNeh+ zqy4`Laz;gIx}(}GrtYGOIIlMJGVpr2`6SVEmWvM6BGvfXtSC1YA9Bn$vCJ-Jqcz__ z0udRbhp|HOd*NusL+5~iI;q>4l64#6E+)Xun|3fH9V5*OCaIW|pS?nIsyXEZalclq z(W+AuaR^V9crvz`D_EGFZN;U@&D(XwJHJ>KZQ7@PmX7f*m%Y_e>Y~NK!7Ld5USP%iZ8EAP~O}FEL;ztyOWAU4DfL5ka$% z={Vwo{z5&A*3(>6GxA-gzSPb3NNOsjDCwougHpq}V06{^<1HtBL5}>l(BHCea+9fR z^kPS$Ml+etFq{B677VI!Oe*0ozyCQU2>@u4uU^U{8414zpwXEqkPcY1{eBVTccz9- zW@nW?&t7{BJq2lp3kv2~1PVzN8b^cFS@2krQ_BK*^{O4vLj->PM9Xf6XHPjwvs%PJ zX?dSycUznFzV)F2OAE%O)Za(KgahiHqjVw{LBo>;|GA#ivqZ{#HfHBo*KcNCEL-jJ zHBuyi0BYUgt8U~0Z_p+mA>?noGD;hANRkE6+$z2%bWv-TvOV@z7;&D6!V}>w2dIVH z?d{4uT=XxAZBI7jx+1<|pNNa>Y4!cD7a;O#m^7%0cPX&(Q;%gO2jyS24SyiGUf%kwpION%sCryr`-!%K&1Whq^a!`L2( z*Ws<67xwF-XjSehes;FbqBoYN9hizKoI$)z>XiHF0uEncWqZ;HL!d{iNPDRwU zk`_azQ{+Zm*zHhyLumYW@ews-sVKlki=u3V9+j-!B0nTL`hAeU`92qX6_nwaq3Oy~!T^6-;S zN8Ptv5ChrC>{+b8e6PD9^O|^J;eId@?C-wEZ;3^P5enPo>&#O-H0lsej#;IAFNu}= z?jGxrTXcpD+2nX}nbffn@Ru ztucC`Dt^uXW8UoyBm0^1$BQlLjG=b{5H`U5oFTx3sgAo=Fm=28ILB4^XSdVNFGfSR z??e28k{KZ|vt(@;?nj18Q3DL?am)SNUiySQyw8@ixrc%?ui>KXWOVFEFjNC7g`RJg zUM?7sE>zGF&Q_ssY`(Pv_=G7Q-5~##mmTE|t$yNUlFo}Jpt)LW8wtd6BQJt2g;05>2V0l*o+Ma%(UW&y_(M?**L zXEW2Tb|das_8oXjq3|R0X??hqSxuD1pIu8x67*sq@;Zf1PGAvrk3;>) zprqjERo^==doS8kNq}kif z4`{s&)xy4&l?}pgt|D6hn~n^Z)kW{s7sffn*(n6jLEcJ2^VPe{7Ye0wR4~u%`=pWR zB~ah0Yvq6C-%q-2r>&?5q33Ayk{IohsWq~#e4vuodYM3d#p&^UyhA%D-{WS^Sg-9A zMIT_xL`HLiB68N0W=yf<;jW0EP{S>rhX)S|g$I`-j;+y+Z+B_F(9RdV8X5C$8kFSq z-G|2Xfy4KZmr+J&Pd291?M6^sk)Ov%r*F$~jfHbtW8fOvUpqk9xL5a?{H^MF;EL^s zh0>ul40~Xus^Y(9`6ByEgmfg@rb~JX!KBY}61-aA2>YjJU&(C#-KLOuoNEX8lwh>Sy}C#lyqHp0Ev34zffsM3c6pY6z*P;j>B}6Vzi|%JU?=Dd3y@@6 zMjuL)KIHF`lV-T3d%vPf@=!8J)hnGh#gz9xy)lLUV>ASt5nLZA5Ru`CXxgOv$@t2U zjp8=5qV(69+%(@S}#*H`k?{SI_2|F}dB0mZ772z*W#S}?;$$Dd2BFnj`9#NBP>aB^_2ct5y_5lT#tiM z1Xd9iKTaR6O&h9h=hMWiF}clVJowUhC--2L)6)aGB1&=e#K2ikXocS9uokwMD)xw8 zj7qO}BMKN0F-VOIQiieHh_|6Oe8DRbWyw$S>23Ct>8Z8v4yb&xXo#s))&?yfw+LZ{ zP0Zh}b6kL{dvqn>&}WElvV2#TX;KZ|0!qrklekFVX@}Z8K!)=YRr%xUSGrEd5Ru43}_0 zT;vO|)JC*T)N)2kCs1{wlK8i;RMa1%o!SR=S!guitblABhM83}2Jgups*-jRVc7?o zb4p4`8eRYT-O(hsSb!cQ*(saingVC3pikHxTA?EJAe_PI!Qz9EBJIv>mC`~E3>(mq zTa^1uXh-Jx-B|$x&}9Q?>x75YOI~O|mUf}j4jEzY;j7v6t1R-(O|=evCU;+;L#`F% z&sdxZTSa*`w$D$*i_RIN1<-j5__eBLVJx>BPKNJ|{UtS^f2%%=sbBuc-U5J7if!Zh z>G=sjYJ72wJjlRcq7dGav!_H0>3nH%mCb*OO%%x{Y8yecZk&2LjDD}+wVvt(#5lwP z3V6h}U`o`!$&v+K_tqSl0d)I$amA&5DK;85Y70INcX@I;QwdxFV#d!@GW5 zc8}Yr-n_$k#R0k?Tvh4iMfD{aM{W|(7>189JV>6bQldltJXHm!1<62SDXAyX(v4V` zE^%J5I@EIEwM-mA?RgZ`h@K;yeljQsVz2=R2i|qap*~!G`2Mv2BoX#o+95!w!VKx3 zDJ>%Z=ihwT*|9*=+4Ak>hdyo~F+02R_&kXu{g5e@XH7C=5nSy%k8z>toUn#vd$w$e zfnj5*LGgvI;jM(%z;y96k0ghTw&pTPBdHcWBX0}!5FW3Km;)z}h>$QIQRR3P7!~y) zSl3$B0dL~q_S34a*1`Q@`(@8X&ur-I{aq=(r;q(d@bd(hjc(m^^`stxHqPbHzLiV9U^SX zmh8&&!4AEgEpj}oZgC20Hls1n-OgZ|G`~(lZ*Gh%Z*DI8u!O40G8u3YJY8}s9d1Wb z?p#v+c#^mH>Iu$))Vii}x4&ojw&H5!fa2viXzG9w=!E!ST&ZDu;5gT7P^LJs(B>+# z@VckM=8`^~+LxX@PpF0U!kbvmtkqz8>nav7zzRPyz*@^jt<^j~IW>~}pxA2%el>LU zI#F)IpBKrYn%Rv)(+{OquBK0_9WECeVta-P{RaM7>0)tmz)1{FQoG!f%jc;fZ>4sK z^9Yw>#IN$#Yx$#};b@LjgqBam=#HLC!Fb1VMQ=?M=Yl8>MgDR?SypaInZ`p;)Tb8O zq9TD5-n*%z`dnRv;F!1~nvHlVYNE`KSW7XTI6i=0iO**j%2>Ii8gD*K2c(`XQE}6M ziTM)SMn=R%Bw8GE={pIH4{3eQY!@#cNc?!uYW_wiTK)drn!?owGf6%=3GDI;~Kqdpf!gk;#C6l-KpOicP!^1@ny-kcC7Rm{Fef6P7mOho-2 zg%vYgFIPW_{>p*)^Ma|^z;(*1FJb-!6M+ejgkp2ae9fJJLz^mg{xD8?1aYKhFf8++ zG?I78kYV&JDt)HWN7KrrzGOfePP&r_k-t}rmrIR*Bk20-H`+%hnbqHBfWFC7lMpHB ziSa#p#PBeWQL*@hG~GSKT@Z>%JaJV^2SlXe{R`d`?GJAE7~-`zveSiL zPqxzq8PIU=Te02w1~>m0<9{vlw?nQOb>u`0^u#A*-;bxv{mSy%uxjo+xJz1TOkTQ@H!f{0)}?sFy5 z{N_vcN8|2oKx%8&xghe2X(Ky6WNVD--*=AwFbUBb-5E|A2ASo|GKz$x6CNU*Yg(t* z2`~uas`l3(oXJa-&O&2eu~K zMZxG9cJx`2bpcn;Cb6Ezz9%TO+A1e94m3D8N}c*;HAhV&p!ceK@X=8L6HR^ro*u1U zAo5RuQuBH~{4IfU}a)Ngx@W-ytgAg3uVJHUD3h|JpUqhHYutqJFbfuL`gCwyM6Pvd6X4+dlSC zYxwnIm-ab#MvF4CVY`c_i>BpuGnp5yXK?e(7wbt#eM{zVe#1cRguhHD)?QxAUoEa> z;#4x{_BfL=2y^Mju^E7pSo^IGUv9VTb3DJ=k6ryLe0KrwcMH@2kYZ|I%;QDE2d}U; zreQ(Qr|7+;aUdK@neEUAXnV8X*ouDu8)W(Su=R&*^N+~y0EG#S>!}_V%ucF&~B0}FJC2=~|XABKt6TtpFQEMoXb2Hao&WCyb z8eU^A(!O)kqX4kAG(O!CinX3N!vsiC$LjfkCP&()nS4+Sc%EZArx!|!FG%l~4^--( z7SSjzj~+ozEL`Lh^Yt<41_`%wn4gF`iL824E;VwSj^3sXyxS_=Oq1%H_j{j=-x%oY ztATB8*kCa!)0IGw{uo6T`)zt$n&YGzU_IV8$mmo3C0cCsh3Kx>dwW9+n?+N`m{1Ty z?+z5OgQFdnuQHzM32Kc2xeJjQgkF^6+V?+jiHaJcwren3_;y;!oHM5N51J zS|x+AkRJkW?8D>-biaE>W>3b)Q~7r~B~9R^_BJ0fQL7baNY#N!r-v??7J3;Sf%hgh zLhNFY>Od~!)qMob*GNbol0?ddBFoK%0wZZUM%zWtSnHSe(ODV}r=Nt;Z}q_UWk_hH zB0Q5)V?x;w#ylMA*@x_*mtvzWuoN7cfSgWiim7B16V{fbKgkLnxQ?FrV>lLOfZi>} z#=xzHVz!P3QrO^6@}`xD){%IetsE-~P0@6W#EK^;YA$b^1V-TeU+Ms(#|6Z7e?n-u zHpW3<7AIj*IxyMKo>FFo18HOr&xKB}M|yDfhOH}SF82ss$c}YH=S1*fz~jDHCXpqw{e)Y6s+`9~l~zq);juzx|A}Ea*p! z8PpO@VL!?9VeW$A;Pt%lJb-Q~WwqRWM&RsWDe?n(w^av>A$CNkWjdlKFvs%m(1_Cm zkmft7i-MX~&$<#myZQrQ<#iR{U2F#S8yIM{t-8r^m3!-x-3GObAnqX-7bh!CuhRy; zw4I0hW=VgNMZ?e>fPvcPlfdX ziks1YbRMXJ8rIgfF{u|Cx!@Rw7=(V341HVj;l6R}aSyDgE-XtvOcPP-X&|O~jPcV- zm~H%RRD8=fc}5G7=eG_REQ$|B3sBJ=DMAtL*ha8czXIEb8H(DK-B1UeKWDwVb4hb| z+vbPbbKiuM+MPRr1(B(FSeJ}1QZSCzxM2E!dCXy~uCtqc^)<7PcRqkgj{$I$NA6;$ z@Fi1**$d~~9TXW$=7}Gh;a6wh^w)?|YK4yludnO@@I`F;K|f_eGLp>=N<*{SX8k+i zV{7FGKopR>NMiSF=FPr@dU_e7d{1bd!a`KTZ<&Vq@@^MT4YO?$@a_!Kiq*R5WZQC` zL)2T`r#nV8Ber>}2fqa$#hh?^z*6?5^esj?Yi&w-IlB!1xF#LN1__2f8o_!>wJ7W^ z0LRSaK zLX1`+bzuiVu|+ZI9)x@^M3&7xm4Qm!I{$#taRk z_#6`}9xY&*A6VAx-5_=X_UUDaV^wI2w~g~!&Hwh*?8J(6ig_Z>`7Q=dMr~LuKWGhp z*}aCKtAq@ODFcqjw{Fx@=G?D-`RVC!Yt&qzN`ShKhMzpxr|?vlTV-)sOff#1QP;e* zg2u%uM0SUlc&7|P7`y&CB>+uK<{#hota{I_;tss->G<(lsQKSn0&_0a+5oq5)Otx zBtASy65->ud@kpkq4xb-^R{C8#UJ_=8pz|t zY)4bYG*o=-GdYq~$*C!WQYTFxy3WulRn9g92k#-WOV?Kl^EmVo>M6p*rT0@P(C2*9 zwbi|C1K&E|=cAg>5nH$t3P*aeDAodue2gCEj5zPJ>3;^c1rZBIdz%i)f3|6)Y*9;Z zNNNDihqflK>akMs_W$FBV*#CUvgsCLQP5MzxVS>oS z8E*&r5R-rY+zyzxqkmE}YuqHZ2Par-`NdnlT?l|vaHWSL+>Deq-1G>;2hze{x(*Rb zrCRSKoO|i@{bXm&#`Eani}fC*(Ao#b*-=P29}8?C0g|#w&k8r-rF00O{$*oEj|KZ= zu91d2|1-0;`Nr`{gFlm-MdLeJ9qMcj}p89(IsHj7(45sU-%W zhAm?vY45OHzQ(|J-Rj~>sohS-b?^zDYpXnUAGnp8nww`VpFSq72kVjzqV2(zUUf^s zmClvT^hd^QV69yceGNb^8VNsLsxjY~{4IWDc1~hE&IpZWQxyoBNm2CX4eelO~Cx^W1 zN6zw@4y_=f7=9L>DwVBNg0;Rz#e!+d^$Ys9$6CBfmRMxZw@jyt&i20VNK^Di89CD6#w4+~@F9`SHAM zt8wtp5L)Tq>v?6*+~scTg)AyH1;oX8NAwZsTs!kPYZ|B81)Q>}rP$7Kh^~`IZ?r94 z(GgA4%rUTX0khY*WBjkKeP2dQ6}rJ<0i|3cEMJr^`GyNFj^U#dYPi4=z0npTu7@@z zZwHhGA6vV3{xL!4xxN^Fv6cEMhO3NHUeDpjo!Rl6NAB^;Uz;WM$kik4V6N=tvk81p zxhL0FmH9u@y6L6(KFVzM=?!X5(H~GANP>IdWbnzE)CDDq+4{b^H;jMO0ro(@+r8%< z4FgN2CXG=Thd%C3lSb!N&jSJ(lH`$4!;XIe{QXOhXXg4Z+SMn!?PM+;vM>MoltDI< z%L4Ah&`p^}np2}cx}6L;5yx+}Ec z-YTk-yK>C*#Oiql!xt=SVp3WsK`vzylhlzobg8tI<$>hY0Eaq0c5I-< z6P^Xv^;$@SQ>A7b0m|Pc{MBm$ezYW;`7LNkvggJ5bDE>4^_v%KDvsm%n@)PPkAAAzr`_y6l7;@- z1%8(O+}F4owm0qvtsRj4|8=_Bu>LNS`yqIZC~X+M%SI9u?@U_tyVH9;7vha1z?;?i zEr%Ut;Lr1_Mg3&2Z@n{%Lub$2z_$UiyotfF`dvT5C2xxSdoTY)%+8DW)Utkbs!Ta9 z885Dj@41ebA&I}fiWJmY6m7(wWVd^5+~GnfLK?`a8zmr+FIm4IDnwfQQt^@OIH%l% zBd#X6LNZgW?QHWIBkOCFM(j7>n}byyt*T`m4C(_DXo<&R`{<96=?Pd}BxkV8Sk;wARS6e&@^f zm8cUXyP`}M#@}!?WYPA*#)fCejiTH=F*!0gxDv{CoyEN{gT9L(< zGg+Qn8Z3ENat=MZr@uht^Q(WoXJ6+!KOVa_1w=V*Oqq*pMcGV*J3deFK0B^Ww#P+k zdrDlzKqCzF%-qTRBV%u#eU4nkjKikKKV}jgim7TDkit;TtN%_XA(XjJK4JM*l zThp0goy_eh=}ivwDF38;M)zRtwyifhfXR3xRiV6B4>Nx(`O6zLO9A7vx9UTb9yZKbwd))n zb9lqgUPGrSw`&8HyFmgtQ^RL+&&Lk-`(|GCo8wdu3__PG+NXyIZe6`#l7J@m4y!EI z90dpbo6dH?^MHPqrmt~!;cuFG?`!n+?~WS3)}kv{x}hEY4;Zhn=10ao(?(etuhCBIspbA-L@1jNG6!^CfOk_5XaV;!z_tgpQJH~VW1Y5H`BGPp^ zk@XFT-&xfa+URUmZ6XND6>1Ur^O9QR{r_ceF3Y)CY1M=2R7r7SK{72*o2LOiJOh(* zYR_5Am2wJuf}R(<^=laZw&LO+^F1~h9I|0Ii*qkmXa&)0zpsM$I>On;wbU(sK%eKg z++$R6vVW2}R5F&1ZwN}cf|1QWZn#gF@HT@poslU|+B+R}nwhB2*x-h$#V^O8CToWhmt*61y2duHhH-{OBv^p2|7ay>xTG@k*quGQ)4mCwePSmy z*X==>XK)F568Oo&5Upj^vJefvHTmz6B~}M3xowP@Mvj&}M`l9BM)@lHr*A*hkY+#a)ZLTX87vPLLM2;8wi2773w(7k3C++?~GRIdkT` zpZIXk+!K<&>|WPzcS&vd(um&BJfiXjf7TGakSmls&CjyB;!QZ(eOi`Lf`2j8yIlm- zyzmNDx-HBVg?5sP^PLD+PPUqiMOc?E%<}VhZ}!vlZ)MjNPb=VIHolp-PouY%uKq9{ zvgKc=0N!7fCoO?Z(L;nII$sQUY=y?1N!t*pX|}$%(6w50NA9luK5i?x@=Sd&CdG4+ z3;J3#{k`r@ZRLbEQ}6OLB+@C4Ks>Dlep`&7v()t`Y7V7$cmZtH2*1`I4$WJE#a8EY zxvs6v4W%@-76baEZInN*3{e@~7nd`N2`VpJbE$KUo8wYOkI9)Q_q)Wc@LWU9Z@9(- zBHUqQ@5G-ooF@di#SsG=oU3}~b`#+Nu;~2LQindtf(f2!^DCvpY^r>5S4f*{H@brSaF)vO$jR} z_xckFL82NU&wjLs)~e>vpmwq5w%=A9R5A~#z&M2>6TI2+l^X3HaFY|^u3C9a;o0{F z6fsZXhwO)LM_)AOAd4;l`~Zabe=y_JSV9XNt@9c*-ZZL4Z^e;=XaOw4lR*V)Qlr8& z9VWqo?i9eVfg%*<*}y5atFek~O{L^ar(T&x&^Q6Xk0j&+)bXLjd`#}LT!xs1zO3dy z#?2mHqjXp~getKj<-fS`TO#C{5mCdD;I-{YV{@2=YHrKn9bKlI07L>^SGQ&ID{f#$ zzUoTLm)MmxwjfjbFAISbnmB>sr#)+^f$B+ur+G)^i@w4Wo_!z4IpL{W2ne%}XlU_a z-xq}Bhm~*DJ-w=qz31#7%_T>zjW9Nce1)RmW`b3iph+T_G^z4r9=>te{33&786PL! zk4r}aCf=cs|8A64H05x~$rX-i95iwI-J?M=PxmIfjJ z306@xOR}mKU=J=$L?xg`5od8nr^O{gcEoqJdNhU#6qp-bqxjtTJXZW?Otde2DN+Sc zGeF8HHdZgAA?n<%&AzR;(GQbW2mIo;fl^Ry$yN}5c)c-!!iR6e0z8apO>agJn^Z^o zv!wT`7ZA{1g=+(ZB86g*uPwSu8P=`_?>5X0tSauy)IBOlsR@?V(4DulNR1d;>00ru zewQ(=nYjnRlm1&SYB#q6h$Zha9VFyB`wR=LhgXktIRJty(}~=}ZQL#?w-MhMAA>@q zHDWrI*qV{f_#xl<@{2DWu}A*fiB=p*JN*S{dFH8cu0zm^rwZ4$);%iWUTtUQ^m!y% z+YuGzSQl9erdJbF4j*S?6f@znW^{xES4pHsVDFc-jdJjiVZ;+EDk}IROWtnp-hG`CUPw;`5m6joB{k4_mCmpn zR(jm$f#qYiQ{tGn!E<}M&qMiWHv~yWZ;43!R2zPRRI5oYbZsd* zd1~R(?Aw^{NMJ75LmW!MNn-dAJl@N4+He8IaDc>8@zOoILw6S(B({gEb+gS3iX_r* zdvvY-nqRMby`7lEO~yX0s70$+>fVWIv}qWr=Is=CbGP?Q;45<)ej&QxT|2dsH@Qyr zI)MYCxx}?u86?qw>K^IR7rawRffF|w1W$;)zJt7(TuggLTCePk;6XuyJ~k&ZVb8Ag zTKn4HcUK*7Q%sPi+PNyI^Tu$#sJY|s$Is|qy-~iBSUmow8==}2^Eqb-W*u4@D4aWO zAv;CudRVa&Slty3;s9GWUM|!#LW+M)&fJ_hmv_r$efyoP_G0_pgrrIg>KT%x4LW6a^^Pb8vtNt*7^#})4`6R4X;l>Y1weW|*7l_rYFRD3x zwhXbhii+m&s=;T7HK-~wIORC#EAy=-E-MjC)Y9#T3_o+S#;~K>qrE~g($uy)B!k}4`omaA6Xpiq>zBkgMuBc1Bw&BAd(`+c)@L+^`&ChFCK z@+Xnu?7c|(3rVt}0%FYGE1H08z3ZSQ#BeLsGyyMSQ6PWCZvpT}It7m;{LLy6AT8OM z#!NDG;!YU;Rz;al}>K9{I zsB;wX;Z>gw0`HjOA=)bbp-eX+$r9L9&PE+NuPm@9!M&4sy3Cg)28XKj#;SmSzI_=v z|E#AAb$&1Y!>bsH*Oub*Jkwcg|B|V5u6SOLSO+oNLZQTfZ>e+D=us7%$D1_&pu@67 z-zOFxfaAglDQ&|v^*CKloAayvemuO7`j*jFk;4rtKhs$5Bu&9nGDY5{^)UL@(#STX zLi**vuZ)@t)vpPaMGhm?dXcxN>>Vwy%?k#trvv^cB8y>MIKNW)@yoLK_1%wDYZV{M z40Ga*ESceFFG>r}zq?pbBW<>C8iHs*^iNed7=k6@Ga7%*=HfHz|3LIXgMb27Bg?gu zlWX`3<3ZpHhMk-& z4l1!a;xnowwm3FXZyqvBur@LC{tRYoU}H)3;vT}T0DzB<%$<)8E;Iya+1cMf( zI$M0yw~AQCAfyW--;xO#M7gjyBv&GtpRTC3M5Uy`T8>N%-zb>@x(8Zu80UOIY&o-n zQmIXuWqbR$Nv0RRiF6>SR0(?F3pQy=o8!`cffUqu(q$^FbBK)n za4n1@urIU2GIUaT%04L?cWEGvT6e}o3gUgy8RIRkV4f_^orL?&g3nYEvBXuFmIbjDm1AQ;e*Bu}TipHl*lq)4{hHL-&+?2y0$H!T zO=iIQ#K*Fqltp9VeK^QJ_bSh@;xfHRcG=e7o;Cd~MHJ($RnW?1FpIS@t;Vg*^&e6p zq*6Ved4w3;#$2nyvu_g#M8YUpD_awq;HHo6k_q|$2u#8hO)AFB?eyV(DtM)?JW=i= z?ilWUgNP9kY7|;|5p~(fJz^PRT1B6QHg!3Vx%6Y*d1?EZb5o|92pivi4eV8RU)?{N zSASu$nA%OCF(8Z-^16c1o<3dBTc%d)-P5Kp!{zmhT>h_RQ3UHZ7zgDco~L@_94+~J z9=&klp>MpXvtX@8 zv-a&W9n1%E6nQf4JdodJc$z`F#29>R>Fnxk?&>;(0uPCOUEU>h-)8lTMLuV#W=X#| z$+egQAqTV~Q{?p_{DyE#Z*cVSGYH;2eLBN@NYZ&%1FqMtFrQHq7(H@{uV|acZRhgO zwwz*;AlOl(t0{?M2a2>rcTRY&*@=OBTf<$huZ!=@ynO@${O^Mw=KWXpENkd$Uaj@r zdT7(^*eKU*c_8YT7b*B3d z?y=;UG+9e~^T|$(AR(i$d_b3_gVX6r9QfCPMMW{CT1Wb&{~%LYH1wh$Tz zn+|c-TQ;s`2#FqNQ^?WJ3wRby(Le;t#QTkLP#`#Z3ywIE=z;iDNQkpxXkk7oFK9hz zskfF1z9a$9Ky1ciroivPVJUo>2yjLq{>%`k)pXxjtORs#sQG@1BvfL!QvUHR6fr_k z^E0^kI^LwZ)Qu4pIvFi z!`$^22$tN1)Xg-D{zbJ1jcRpOGv|Kj)?J{N=MkjZmFo|;?`=xK8+MBbl}I9Po{DE?!IVHp4v0987wFCx~YmRE1QM*yqy!4kA+JYo^Bgs@9zf^_iUu z5%xg!yhE;hSn+ff?60-&MDzM09|-Yxg?D5k+g3=og@#Y$% zLLvw8!ny!o680~;hINXH?rjvGj6&B|l@Q90KKss?YjgDPz|n#G>L=$;WbHqwTnT4v zoBVOLL5O9h|6>KK4t&%{Sd()<(3J56npejuSxz&4q40)Q`q=M1kc?qJM_}m2VxL06 z2z)8|#cj4y*?(td^ojzt3i{Cksc8*cnRAZdV2S2`rZuBlE1UmP)cqPe)nV~ab zt$HM#+%kydSy_^p$@_Dc6C>&0i<-$>(RW4j0P8OO5^12Nk=(45b@r5|pNZB5IFB5V z97|ws591mW*9udWag6ZM=T$vZ!Ar-Ofg$Q@b3luSmfwyg=hW2A(d>`*{wgm_$~dFM z#*Z7!^ZXYK4IH@JZVEOk=`Nm(bZ3yd7k7_ILcWUi=kWbGl~6CDS>Q!+@^kax=oxl- z;I?sP{BXmvEvPm=9+$j5p%GVc6Qe6yG5IcGIr2xs(9a8vJ##j26%Uh$e9;Y24!5pl zTAT&Iz$V<4!I)RWM6tNGUo4%*7PKW8i#8?*!ze8_*7qq&rl*T9jbcRx2OkrcPbk-#~7QPza z9XV4E|ECaBoEFGnNLk26$r+CN`TxCnuY=HmcHl!&A4K8jUK59=8BvlV5vVyg<2V4o_XC zdr!C>cX|R>>NiW?;kVzv$7o4^E%6a}Z({%#WZk4&N{wrf%&;Q}7PUj`> zQr1c{yeao^;nZ@j;7uK9VyChTFoS$o`gO&)F8C{Bv1T>67H*O%ytu_PycNH}BS(^I zU*Yapc`JwM@o%wZ9W{$z+RWVSY{DUgln1w|1nFZeDcp)+PLW~kIA@>hHVIFz%F_2C zVYhGNjOI9+#Qs0oZ1XSUwO2?Rb4ge=T+lB8y;FVpB7R$hLwr5M+CnuMxbd^Xx$(K9 zG<4qPhj|*h&6`Wem9Z`+@US@)@iZk*_VCawgYI>tt3pha*;waZhYs2(A8kClD9Z)a zzX%7@+`maLLJ!17_^g;5>w`0R8k>>O@jd{*;=zf|tV*TWCus+5I6x_)(%tQ!9n@Gc z-t(f}hApFCAUh7gVRP<7TR_k&B$L?)92w_6@Gdwn~kP-Re8aGwsVV; z%RfpYBv=!LtfCc?WjLy~XHj^E3le@!<`;v6G%tykqF2kR;efbN9;2zKbps%l))YPtm3*xy4`mLX@rOH?GeY14 zJ?YDpRRo5KAbjDP&B&b`hBkT42sC`*tiVhb4W>y);&|QCaO+sM1WgCI4-aUq*2%pP z;4Z11WuAA~mN54$A!5-Ww}7zL_X_l#sTs*Vi48bdh#%UaIbjb~m{RpN}pO-{r{S5e?D$MoeeSrs2H?U#yw(62aOASgQHsPYw!f||G{I+#J1?VnDoQAig5VT1(QO9_%_r>YU+ZE=l z8_arxxUMDd$Z^$2`vMpKoKLRw(1@yV{6((wdKwA$B{&&X#4=%zA}*n!#G?wk9{wpC za1}ple}Ec@Oco{?g;k!m8q$5nPD~>OpHK&~lV@0% zr%btu!+OKCabLQ~-e`tyOnp^EWW7R2@QaOBY3E#ri87s`ibBb~IAPxsla}s&=}se1 zL77;A(W;yvPMfBsKaWGBTeor2svTW_V_h4|YFZ?`Wb8-$mp|oG79-VzNL~wpxBC`m ztyXJu8S{<7{^X>SLX9ap#eeQ(shLvHqL^w-j33rOwh+y@puTs!t@^mRdTUlOT>+z0 zB zeU>vsUKbF;R@MBtOTUZV;ics#9G|xBhWa*;6}!OKA4E7ltL>xfxC2*V@3^90{JyEY zYTw##^2r;XXmEfGuZDNnECZep`=5Jjog%D9tX?DliD_*0^-DgjcO?ou-YNb*8e)dq zx?pEL^{PwRZKf~F@$D<1*LZzG7Z?`>wn)I;kLJ1Nx&2G<^F&6yt;DxBI+<$pqwTVd zTm3qHq_6C5Fc4gTn-&QhX1kVx_QuUBdosEQ=WW-wVd5 z>Elr)1a8SrL-5QvjcmV%Fz!;s`UjSXuZ!j48Kn;1Zb|YPy`V{>Ne4lpn`276DV(Lq z!IK!>b1fK=uC}hw)A*!zCr{R0jo^Nti|B%outuk5_poY^R8_eVi^Uz zjKOeUFzNeEz?pj%u?lEHZ_;(v`RoT*)lgsy9JixjLy0;#H@M^bV_gchGAC4TZVJ$|LGlnbOU_b7=O_sEkO6+2B-S^k7_MV3!Zqnu`BgH zKUjYuT?_1Uyf1kLm*xo9)kD=Y-nMvWK0LnJzCS@@hhI}ydgu3LMrkuXpoOt4S9oDY zAny(#!C(_c(3MGCKF|j^4xe9K-mA7Pxl%#;15W%{)uwka?FeU8H+&b!TwnQxsB!wa zn|}Ty*aWyr`%|R)l2%E=e2#n_4fqN~$VPn4?{O-ZK z$-yLKk;J49K5ie=%JqdPuOg(Za@@)fnL%lRoi`nkbXjh=v6ym(zK6g_^y}Ye#NdK< zAh|KsiHUo+;EHA`LK;b8cz5ASNF1{jd}1wpcz7tVCTpT{1f43AZF#%@LlY-t?8Y#+Rv|(;h?;RjwUfA6=ud2hW4#)Ku?>`$O+q)Ox%aBHvrn zYJF3x)Sz$!0PhU`MZO}75*O{!2EW(n{;7_wjpm0-vY3bS#W(dId{zPHsdByQUka2) z_~pYy?`*fQ&$-X>?@&TCOa&_(xh3h)OJ2E4CKcq)gYSEPYEyrjW>*V>Vg3ym?3yUk zFu|G%ZoCbs5Zl0hlRUl`Shi!wt!|1XnPis*+E^L+gH`dhPc%Gd3RAfTgdNkm8I1<$(+BQ2n2 znOI2QzL)QRQdJ%4)%AGf?c}lX1(BL0yclVLAa~5qc2FQMRA|`O59`k@28^32OOr-Z z5`FD$8E<6I&l1gzA+qB4d3_eUm2q~Sz^3PJp8vzzGKfBqJ|>hiFaF?W>w84*QzuQKc06nfm;oS1eC@-8@BwO>N4S}h6k-4dhCt}?JB2Hf4&)8gM>;qyVjEQ()ggY59YBF@UG%gkR z7cY@2XT<(JpCz29qfBrY-nWl0D5>%$sz9gvvH9Nr9Cf<|+D-zaT_=nj_aiy&hG08o zoG;FhJy2Cm{Gb@-6V=Ak?&cnSUsn0EuX)d|vvCP~Oh|!cKCZn>9chOabEV6>{33f+Mg>GKWc_cf zju#Gbe{A{mr(GG;DndtAJr@JihGBVQjxg&dgB-Mj=Bk#|{vOC2XZsAA=5N=WvS{pPNb1@HO_#t}#NAbe*R-luz-Bfqx}-Q8Hc}|3;iOTKf?(*RVJDaW zWty<06*cJ{84DqES@rtCeK)Rhi(VQFeJx<@elpb=sYbZG53syE1b|Vl* zJm`IA;)Ge+(pz>_dlK+{x1(U~>{kaTLRc*V&?CMDa&WaS5PYg0r2TNktP{w}y=EVN%z7iLC+-u4a!_#~_ zYzeU}B-5lXfdY*G!TaKE0Np4iL)~%Qr-amQiI}yD_p8u>V)%o?1&c*r!eedD5#yPM zJs?;}_Vi*Dz{SUdg@X&fpyI@@gUw}cE(_SwZZ~qhSB-mp=u`6tE3f^qeqX$ z0GThfAz*a)=%oGtD6hQ)Rc(N#AhRg7lArkd(AEr$F(V8b0L}Cf&m0mZ#1`H|BLZeh z@u^r!&Z=nlR)ut6?e?q3^gyjChoC;b^p}wIBBw|MOfPtQbRQ@)Lg>?tQ^; z6M`G8RVz0^3-eawvv>*#o^fTryGLtbRoa#%9S!4O1-ZTyu%%dayP}BH3V``72iF=X z+1b>liy7v(=~NjL8iN^87!X$RwqKj@gOk~JWzSO%CahhC2uA&OPW=%)6$~CUVrxEq zj6P?E&32Mk37!s}^Za+6`JGGfUJSQ|r2pv7h(XC84QxUr@at`u>{l-CKU{PpJkqf3 z!se#99-}D@WgxYtv<%$Qif^rcc;Q;8df)+Bfc6a%=iQABp;iX-6A=5sgs+#1tBz2k zSGvAu0ukGhPB`iqo_8euRH6aKkmptbT$Kl5mRaZ#8@wEmD&oOXaz8)Pdn-6D6UP)p zAS$uYP@DY~cxe{_$qeK55N*8*4tRE?YVye~-n2XxfJwpgfv0T_=nW(I$}jN5V{ZT8 z)BYP!boQ3bvQ9lDPTVEcJsHx2Vt(mCBMS&$_y|>IGJRfTySAl8GZh$^3zAQW;R4}Z z>Rm=*Vf~>nMnD^#3w@-l?R!>q>BY^P4pMka-#MY+ z4Y7dzU6Rx{b*cC|H?Ekcr<9-1?97a8B>V$o&c~RuMCOf>BcxPEu1RlTV1IsTS}BKD z$bSt23rR;g|TFTyV2^?q(+LJZ@yq%nE! zEZM({4mLd7-MfCJOP9S)fuV{cB#|uQdAUmAcw`H1>WvewKKwb;OO(N&n%u|p&y-&k7%I<;$<$j&KZHB-Ix;w7^cC<$@+u;<3L?mJCn@sD z6iZ=}Esnci%9(N2*XkKet5(td+G0(hu%S}QM{-NMoh{TU9wD_MusQ4Xq@~^sB@H52 zl@zbxJqJ+nh)aepwqmHs$d#9!nSvgCni zc6FbZ6sRK-39&-&2*YjBfZ4h0fvz&@e3Ankw^4r{bnknku6!N3(OCFdwC~sC1EhEg z+Qgn1?URdIKUyJv)K(m01bGJG@74{G{l3o^MiK3>NqmyfyYGsSQb*?CBdPBY#SVf# z-8OZ{PS}l4XIUKXKRD?7?i!H6kza#0%abO#A>g#=5eS4~MswJjX;mEwo1>@yK9m$;;`H(T3HPiC- z7~;LC* zH@I5W!iBbh6AB1o0(kB`=Xra|Zh!Y5YP`uze-#Q$?<*5fFMW%*;oT_a({?&YA4izM z)T~AD(Z|{7MMd7QjIP*dC0NHD=1$6XSDM%pt>7XP<4d%Q6}foqa!6f1`_x1TYqbwG z3)-Zg<)P&isIGC56#FLqW(+lzqtQa(ozAKZ0!{g7@Jb|_7Bb3&oWHra0|j#oY>vQ~ zr@E&6eZ6BCK zSe0yufb?q*fKn%-I6x`6WH~DCc@GP334&%gH~jhF9GR684f4>=bK^+UKJ_Kw2`va~ z^vsmEGYFvoOcK%d7C-L>-)_XybYe?8PZ?;42Du9-I?~3JS<$JNk>>ogQOSSCJrMkd zrtvq$xKFdTph2AfK4L0PM6iNzbQIH9>**hr-)J#tLj@(JZHZ{(-(aP{|0)vk-g^qM@cJ`! zYJ~FSqWZoo)}Gj)I3h4{plON|0I5;rpL=~S{PU$*cH2vhM8E96wcnu*MjyRp(TD?b z3^)0LvoR(-js&)e$1Ns*Se$`2l0MH746Zv{N9L(`?LlE8X>+W$%pTbv!3(B?7Nuuy z!+Crvg2?U018zXCa%lM5Hu}X^!du}Ti-po)&v^Sx`(z4A)8^N)*G~N^Jw6o~GEn(f zR7BltAVkjI6VMUn?L&Rtx1BTbYgB1N^CD6~6D*$`0gdrUhLgA{s9rj32~I9rSs=7c z`~B+H%;6T*ibj)K&(=8Qfkul<&r2+g*z0lKx8T+zWu2`eFx*FvSp z-bedQuDajiJm6`Bb<78Q8*Z~>z)%vt5%G{sMsqlf40ywXr9we4t>~-{NURbklfx}^ z3H%_`n=V^L#J{8OT#QyCr$IQURShuhI!0GxN1(~E&f{_)7`QSoi7A))0)ss*L;5m} z^7a2(R0(C|=znccpX0Koa6!aHj3IJa;~S>+>=x3*i=W@?o)TrZV)<(lY4w{Xb|`Me z|cfW?Uwbgt(O1(1975K^DoqL1uI{R!%vPh~Y zrha$#EdM73gKv$gEOHRXbpuKx0DCy;c3DTY{hj*j^okMS_7FFEBG%J18uofQ6eCFj zzUK~n+>=So5LTU_l59VR!H*4MA_nyqU#}GMSC1greHWCJj|bUUQXR%+8-fg08ol~p z_k2E_34UVd!KE&e z^st2peuG9a%`piRhaTTS+!e;*WcTH+?ce}E(ItNT#nWQ8^i8#k8c2H#Lf=~iVVvN2 zUxTETD&yd+9+xpk;SXJ^9YZ#0$$$M`p)$T@K>IiJ-D9%Pjm|~$%RdaFoU`HFlU=7& z6RTx-h`HJ{30gx$W9Z!`c&r$u{uY#a*FE=D;BeZ`I*>cQ{V49W!C;!0YiRbfBy^{? z`mhNWoR{w}3HAJ2!eA0(c+*Y1DSe6~U3ew}_>0a*dPs_Mdw!_OaJPH7c>F7E;nNQc zFd69>i9c@9PB*&yJZV5Zk#XnCJwhC~(L(^O#oT(o?>X=8PsZmAfR!15sgr76)z#|tlADjAB6AI{ZDs&|0CVwt(|_-g z<`PXrxf4^P6>#A8HUp^mc}~CW$mew~hwZjp{i?{k6H1CYAGtwHa>G6)<|Q5qiyOk3 ziKFcc?!pXkfnrTPpQ+^Kefrlo`5_~X64!y8LYoQ_($%Q2n@ z+g*&pB`e}_yq|D!DvM&cb5Y2zb}o#wT)trDFt~&Pm2ph-Z}>^Ajz&1@JPRZks7deu zn_6w>fv)OJJ^17nu1Eac=H0^{bO;Y=VJ(M9L*k#XL(ifjgJ_!6kTyJLC<1K84G+`#_pZRfBpW^Gc3TPa z6$cT?Bs|w0+-V)I28%JI4|91XD+vN5{{j{hSSMXr7qz0A*X+HA;j1F~evjv@UZB45 zq;$^Mm#r9qy)LB$N%LpQu2XPe2-VI;j_d@9SX>lmKde7z=9>6 zMqX=hCKVEx2R7Ciz9`Wm&Dc~p5W~M@4Duk{Hcd0CT+;oKbpncVKb28~)_)?jRZ+L# zW0m}v+YKa*`?KmkPyu|}LiVwZH$5(Od{PsOKBI1}X^mI@=cQ|)`dz?9&*Hn41KpRl4CET- z5oj6yzJidWx%v*13-pD(eLdl}@PzzxcIHeEjhs=u*E=!Dwb*R@s^-f3Uf437(f7bB zI@Z>4@LiDXsiZvmZzd-nvFZbP11c-sKSg{?rJR}J*mr`~Tf@9z^Z~X_m||tz0kj~D zNRs3xIQeDBBJEf`LRHq@* zw=*bN14!6IvnpJMp%0|YVT2JW=;KvsKro?uCwh|I`$C@a?{MW|JZwD2{X}1Oz2@65 zM@yY9Rn4Cq#Mv+=P%a-IS3$J%bczK)hpUeooy?}6FSg=yEDQ%eaS&X77-ghukXWmJ zq@f6I3^nJec1yYgPqfSEZQ3d=Kmf#nP9AQ16g3ZPV6ZM?L< zm|e3Iz@H+WeY0hX(af$H9UF>85e2_U<0zW)SO$KiS3oE*MWc8KP?*0DZ z-(sh)TI=vl;>Qz%jxoqijYJTu#|0(@tS_mDK-5&WE=-VoIQpR7|8%Owz!ux{_+A|)|Uu9;huwN-h`JJ=O05wM$Zs75epH{ ztUyQahC===#vHB7bU!C@R`T)pje2a%^B|>kWzkyclSsS$8SKNiqquV8Y(N@wLXrLQvMRkt0W_VW{TG=cZfzT~9}MHmSlts)WA{|? z&@>r|zgXn)1B*|+r~C0C_yiP+OhAvfxW%U9{-tU&w#)cszRJIRMcm{cpU2`t7^3!| zT!o>Nb2t&SOc5oD{&db7396?nFmcXFU(U z#XWx8HZr7RxEV*3f%~5xY@7D56OzOG!CLgc9Q-qcC4F}wvX{3GpX)~ zB9uE=?3{IX^lgV{cdK7ICFz`JqV&PRB{AeXqBvr6&aF}AI%l~fC4L3g+8fgENw6n^ z6Q=2nB)VtC)8wtwh}xTljaQsszYry$%PCVvqcPT7+nZ(KRgUQU`*wXL5L&i6by-&%xbmjm=yVo5 zB_xzMQa?|PGhIq5Yq?@mzC1Ux4%FIoLQWbt!L}fsD~7*oa(>thGkAQxDOYdFO#Rvu z9;^gUkHfWDyzdTjTBjVRS1+0o`m+5g8GBQvaCd!YjRM(``*x~{##|TQQY_wR?meIiZU53}p=G84O+X;8nrK+ze* zCEJPrN_B(Il4Gffe1nA-HW0O|Zuvv-Zz&^A2+y+5B$)(f_pgcIeF+L7Vv*p1*C^vm zqDuw7eYhs0K6PtV|7@YP@PGAJwO=0lBs{B275%-Gzq`V7Ja7SSAKS!qYNb|wWZCfD zj(ZSt>!DI^%E|5=xEe)3MEmrGZ&{#sR$$n|mCwXJsL4GhgNZWaqnpI(KUw5Jm#<-= zXLpaE!Xy|_P9Gy6gp~P#yZ&fGCRGA(sZIy`0YzfIb8%L6$g>Wv5ar)ik<`y^ovr)M z-oG6D_wA#kP7KdDzDZmh!Q@5ac%k>S8n($1VysrKdgu@3U*)~T>|s7{m^=pz=ShEe zx6iEmtm~S)JX)>vNkv3Z;Q|gbVKibC?S>~qR#$9)Pj*uY{;^w#^&;Pn8|f`2=v@sk zN$&Uk;hwE=wZhO4a^TPXIZ^JYiWatgl+rt{U@+#XX4_7{3?Rn6TZ zJGQ}Ob@8<97}&k=8KCj>d$cm?L(~RXqTxcqcz@!o&o}hV&TBV@YA}Nb-6UmFCY?5M zitO^z=%d_->;7DfX1$5&CVutMgCOUPKp+N4WLoVz8-F*Htc4joxd7eIzI|R%=uC-u z4=x*PH<4byAnLb^kP(+I+OR`$6&~hfz|GkW1x3vGQRG+N|A8y;3bFdhG?y4lS|!8e3*U4wY9|y;EYa5pn(dH6H%2BpC}5 zYU3U%*Y1DMD1V6*D1W#Y8*G{w4F7#q4w@Uj)X2Ae1Kd#>`J6>RZcOTlxf?FjM}gfo z_?$SIvhGFMHUrX)(}mAKY4)9TOwvWKWmR|Da=5~O3p>8DVWIq?Rv8kKhM*gQ=)2<~ zy}@&nuNm^tu%^RHktTL~qyBG&H$u72CS(G>Or;6Sej+Iu$1jK@YdPVpWU_e5Wg|HY z9I3Ng{3sB}_#%m3JPHy(RX0SRs9RS&;F>Hu^|VbgCPXb|xlYpJ+z~GMG8xJp+Y`hB zYZ58`B(6K}tV>w(68(mW?)=uK<)$w2(8p-yem#yvk!}y*A{*$u5-lbvF`77$GzIc{ zV9XWa_gnENV+Yg@qanvqQS@ZH9eoaaEgsXf&^u@kSHvvpXo@M+8HtfUCVE6H!Tg`_ zq0xFb!{$r2>uLDM!-dVZ6cwpI8*q)zd2=d$1q3Lfaw<|bu%r)*G(8O2e_XCR*TGds ztX2uMm{h-g1o{2@_KU5$rcUdiw|bK$nT!=TptaxNiZODD%|6OF^nY1^=)g5aB%J1c z2>0vZS4krB5iuoyxAlFF{JhDWIw^zAID&30dwku;r|DnN~t@erX{$kuAaI_t)+l6Vw5*L1OTYQfv<@wm= zq#F-qiP-@os#)KEc18I(U$#c__%mZh;ABc7|AVe}Nz1rHuv&O-k3JjBmQWe9Ww0#L zU(t}6@jBN^0xY&OU!d~sQ*qeZelOKe;JP-)c%|Jti#;GE(g*pG1x8P1Cg-<1-ydCV z1065e9%g66R})LUyDp8;#(^-w-qv5>{NtlAE;|^6+&0kmf-S(ZvyHhryPhMNyPExr zb+Wj;fx3(XUF1!aP@pD{v)r1dWiZ#eE7v?H*x;?rZHq$rB8FJ9kDstxGi*Qhfo2!) z$aW(j&WB`;E%UnDbWBxl-d6Wd2?vH?HS5e(bI6K)ytZ%eyz9s~u7@rEj3L~iGdA|U zvJ7i7&*)D^!m}2*3y72Ih)>kr5sHA7M%Z%Z^h}l-j~O4M{)^7{{|@p;cfDJ5T;e6I z_hz!6$lI#qX_PGf6?X?DRvcmGqhliltIWzOY`8G>$@((}TSA#fZ`tEqvv#c!^E$xM zf4}|uYd9sF7*nKRIOyg!OVj5vahmOCJi4)^^ZxMVq0WmuNTl(ZkXs%90{_js($IHY znpCd|bnwQiw{c>a5iheR=_bR0`O({Sh9i?4_8Aq78}>y78C6t^d6-Jb$nIP6idfcL zuYG^zl`O-nUFJbTfD0TfMqAo=cOu$zczakHgS*J0(nzT!89Fq3lgb8x)<|ZYcYfhv z0SJJ;N#sjflr35%_Yo<88y0Y#LP9mZ1atDQv{g6yWNtLx=KknGMTG}(zBZz9)k^vD zCeN>Y{q;g&)K6LZOpP*7By8I!p6Gham}gw5pHx?Wc6-rxvrY5&kHxjAb9U$EyPYRr zfuH3yzn8GkDs3T4&JE+4L}*12xDwe&`Y3bYaK9l44c~ZPd>s6ckH{ zLyaSRIJAM0;~Yv)f~=z6A^?wr5!K@&w5A5J#L;%hY}_q+y=02S#Tqn-*GzxtfEoI_ z7Dx8Zi~q=wB>7+u;^bpBY`?>PkgcFFAut)+b7Nf$d}k8G+WD@{w8^~-OS>ZwPZK+k zZ?(6F2~6AH21Ul|AeeE{KCa;*W`+=OWJPZ_N?~uZB+;YEhtd1OWqA(f zWUIMzniXsNk3GMNU6kGoh1zL?SOnzbAkKyQh4g=s>sg~t%Kfb6E=t$ zS_)j-%pArd-K;RPt%Zn5hhkOyqtZPP2sdF5bieobE5?ERwGLc(E;bm_VWtoa7+0mI z=@7)9)p2N{Ny17pR1gv00hPqk_dq9|KVA&@SE@D9sYeO1<+EhIzeScSi@+k?zUA_= zk{gQUV#L_3(xtDluxU07)oS%8amlw=C9^Y*pY48c$ay7Hw^APd|CsvfuqeN1Yr4CK zMoL1uyO9P#q`Q&Mp`=3wP&$W_25F_cJ0zrGfC0$?q~ngi``qvO{^cQtbKduywbxpE zuVgFQR9IavrCk37VC%?uX<6;VJthC7e8j`7`^cDvO{iyB|F=nbSnFq$m|7B>?1kM! z_?2_yv$ivMahq8e&STRNzWsN{wJ-GAP(r7}jDy)EDS`5yDpFeBi+X7BI6>DgcPwll zPGQ?2Fd4T;jE%s@Hdc0&v48)--IwX6{iZ&Yp#TZRVBN9ctG1V@YoT2*pJ(onR~z@} z=p(9tIp3~KgEH7&XV>r#GQ|yu`UI_DQ^_3 zd90anLe`ZGZoKKAnbG=A(w0vyfj)fb`Tvv~%;7TIM+OT%uxhOIC#z;bjYY4-5*+Q} zV6+>{HDWsM93C@1|Ji|YbK}8{`l&c_oPzU+n+zWBnrzJW4h#3K#fOt!o34F0E}mlr zatzV1oPL4FP>WMgCY~`PIN;G=V_vt%KDoG1Q=Bz#!*Prz&N*5B&N_u3(N>Ee!dCz* zlP_|u<)g$N@T5Y}*ZY;((c7BM3L{W0QrVur|IyR+9~%iR{ko8{XD!e)vibLrC~0tI z+ts~kw)N2P9*_be8EFyf1_9bhIDZ{|XGdcXLde+*-^&V94iC`{qWxSu9+$+pFOtjO zv+dkV@#7S@?gl=~^0&IAe3}Zuu@qhips}6Zo#fqZoHx{oA5s zZPYCfXvk8Kj`0du0-KVExn5IuC7GKj(h1rp~F z`bO9)-;c9qvqTHYoV>&9$mwCwMr!GwYl8Wf6=YZ;vEfx={S04W2xwIoERN$k+=A?( zJk-Xag2C`uxMd3p7P-cY4PM#-`ijA63DibA54Aq{xcxT+3--z)y4WY=#3!vy`x@Q0&JX1)F6^(l>`DMP7^i~%+=cc&M(6wy858~^YV6*dC2VDQEro(bT`8L=zVB%5&+; zXm!+Rh$NOUq*(Wku<(`hRBgARQ2Zt1>y1+4E=oEFa@vg0&6H|WNydseBnqeQSbQ4j zh2_#kqgL7VsBsg7i<0#;C2es4A~#Bo#x~r;+jC)N1Hi2chfwKuvqd)Ib;cmL1EG!a zlofCO6~gasR{ww__Aco++ajy)549ImZ1R3z|EVX0MZrg!a zE^~h=ccOI-N)Fg_1u~^u&jjqwYVgyN6mAtw$)dsQ*TY zWy1I4Iq=q`q}xcNze_sjH%CVC;LRLg+LyB4C&AmuXI8me7{|W<3S12`WNg71al!2m zW?o|2{Q;NsK7W4QVDdTb+eArlm=d8!X23BqCt>Q_RFPu!A{=alRSHk>IetW(@UL z__d*p$aJP(2<82xNjzRVi`v6dL&$2CE_HwrVQ)vO!56T~FYRST!R-*z{>}zy7+M?) zzot!(OH!Z%AH?6zf3i)ih8Lz0k26p(t*LhL{v)H{Sk+S!b3n=(CyM5kud#?`aEvK`05-5ax={wYEJ%-9#6 z$f@grPSkqi2Gr9P>l50a%9D7EyH8wb_rHa+hO=?ouTXpG5b@m%T|NmLPJ2oI**>Wp8{N*J*j#HE3;6_xr#0~J zA?-z`q2X-LC76Yiju#ZQZt!bg7RYcH+)APV{#`L64$qC2vHHP(!HhM>&~tnHV)29V zkq$l}pvM`pu*|)EEzod#MXxYcoTw@GpJ#EO8Y90o+Hq?d zg{tIgmMz@J?nln9K^!OXkZjTxemUxP5+z7Z+$c3;=N~F!C5%N8y|?3}7Z~A7Dh!Ua zwza0L+qRMc0qo~yU_~U8h8Vv3hNedUNC33V6fRD~q0n%@ULN~8dRL=qJ8w!38w#kE z*RiM-zjK>*D%v*FzB`MvLuZTAPqv>OUkroqCNxVj^B@(eyi5ONX`95~Y+5S2naoU-vyZIza|TJT zIhKd>{lMV-^c=la3@XHOEk;KfO^ z_k3Wp#`=oOSe~hZ&zuf1YY2CJT`eaIj><0{0nVK;-SA=-N*+oZfj0MU-mKjLg|bS` zAMhi>!j*0CiBOSi@L2D2k%B_~4M|q7KZn%-ZjFc;$wmlt~Y4w7B+K&V#* zrJ(i!zq+?PrQn2jb7*9BG}WE$ZlG3}s2xYOq8;)b3sz8Q+oqE{M-dhyxwTBurYx9i zZ8w}Sfr~#t;)>E^UhT?Y?TTnSkh=4*aO3KZ-DQBvtGjhz%ZkN-(S>p}yx_Y!{(_@E z?F6G@i6UYyhc#Ex8pt!QmFJK1ZpbWpQ}!(TtSZ7Gn6QcHB}cXjXw>~lSi9#8VYB=f<8mA`;KYvEB5#q#(0?laZr)Md%weO9_Ue(NV(w4@|?`Q*c=0L#ZV zSLU9Xc}nU;>gm?zfBdVeL3(%^1;=C~5rihP`556Gt&R#FK%b(1ei?`6A@NwWzt40R zj1fxIn}RuQE&&Ur$sU2Wn*7@a$wcw68|)4AHC&Qx52R`79e=~~{y%h$H=c=9@YgGU zUL(N-fh*9!LMct*{Ua^+tK;^ph-IiX!UY@L0?QId9Gjw$YZE#o2l=J2bOtYf-kr57 zf^%^7N9rY{z;@x4IXKq?536Rqv_#Y!0r@mtb5P?OQ_^-5{jrvLi;}Gm7&2Jsxhc1; zfLcOi&nmCq(u6}N&Bk_J5{AOh#`Xf9++10Mg%ov|W*x3l+)dr7L+_A3;zmlE5#Q6eHAxqWwec6Nv( zMMrI=PR;zht`}PGU$g=JM~$RzneH1NCZwVH5jq8`Y|+=Pf-=-QBo+|%tG~P1E^1Pk zeNr>GPpr;2alZvNgu~!x`io+s2%YHYhoZgxSp|_B?IFCC8@;`mbf?g0hmwUTeotx0&tDO1_(Qb~* zju%gYK6L`qf&&|VJQ*#$#n_JRh7l=6i-IT~k0YLRw^<)Mp?^8xL%_F)dkl%qPo}qP zS*TvO!=;JjU427@jqG}yJ{L5b8X6c{;uFzBC^F%(+tF4+mTz_Y7uw4CYHE+4#5Y9! zZkWwQET9Ymc<0>Q{=*&gYw#G{X`6d&Sr0O{vbcDIRj{i5+C91O2^u;OB6`i1flS^$ z1?LJJd@(O~%df!f*n+EyV=c|v{WOMwM~o=>d9iL(kgdk~DMHNsS7eN*Jj3FU8_#lm z_G?Q4c9oR9$n8eix{CNtd2kfKV!j@2QVBm3_wSmVgFc#s@SaEpW_ycHGh8r)2&JNC1dt5(q_$Oq2Jc6 zd8pQ_M9W88Wpu5H-OwX!N0e{SeZoT7tiNA)3oGD-RL*!yvJOzU%e z+Ac6$vP#k62(*cjb7#{Np+alU(>lk~r)TG72ZW1#TTnTO%kLGjmVc_=+DvjtOwN6! zIPd-IP6^EcbTFP6$!=OVoIkM_N!5cJz{THzo7FW=*wYt<6N6IXGdMh-^{2NQZt-c! zZ1?z8dh=n+-tO1<t&f9f%J(a2xjUB1NZ3!p!drZA2sctYv^NIv6Ov>xMrc;#VBU>1*B=fboyIh%#LtO@!Dh|5zw z6`}xXWayE`A~B^)#-u%u*pU%_L{la9oSn~nnmJG$ceG(g*+#`&M`<;+eWSpC()Lb` z@#1o)?%x1bV`o1n6`MyQNcTrW+m~T@H4A!I?iP%8%U4J2Z&P|>@{gCLQailUi7$tN z*#YnCYa6iYF^Z$>lr(Cy&@qmt(LmNLltJf(G=A<)t6maE?Oj2VdS!;9glRb1hae#B zzG!Arc~3b=vg$BkW{t3WL(L#YfN+s{IB#}$&|~YH1nWbghs4=1oI=b2oyc?#M8M0= zu&SVnj1tRje%R<^}Z zqe%*GJ%~zl!dF9Cz^f#kGE{q;-yXexlso|C!1g({=EKW^x{rA{z>-9HXS=c{2>yar z_OZf+rGsf{_$Mw%}C9sq*P?Igq_iE?_rT{p1#*pZl{+gYE~XMmazJk5ZG*^kf4_a`4G;uhBOZ+W^`1zD zSm-Y$HPEkBm+CFeKl?B`1?Pd~9pJ~D`#%#w^>?Mi0k5;HGZ2s>ZO$UhAJNg;fG3$G z>GrSGR%XFqxMLkEM4%q1t%N<46*(JJTpCzYJO5K7NXETo#!Jf{aUU%cLNXz$D*tFz zXCCcn&(LdroH=sgJUeGAhUEPo!APM(}Ju@x%lfBhL#D+{?7U9UBASvZIt)i4E z$qkeCP)#}>_zwfKYZZxo;BJi=xco(J^!lbqPTP`ay4|0k@3nG-bGD~!YgAb5*YgSe zUVtt_0^%FHCai3Yrhr)|!Wz}tVpBGA1JkNev%A7QtOO5w`P!3H=iN3sH|O0tz1iIdVnfVkjtt_$gKjWQK8WLcLBT zNj9;${#iB(fY47HAqAr5-p?*i)o~m$DS0idT#p*+&P7Qr0$4NQ4=`8r&x0YjAwUpyt5PC(Eb{QPFJK+-epgf&!_>Da>)^eDUr|h= z0%7Oj{>hN35s$?$5ju<3jdI@lNFE0rMUm2y1!aeK!r2aAJYM0B|4k$g2_16AO%G&l zL()DhxU)BSW&X$yJ3(ds5=Z;-JZRP{%%+RB0DgDRrN>e9&|p?j3uO{dAPeHq;6D&1 z47j86g@&N9mW@leOFGT7v<|fc(ZNY0w;y_Fu;@=e4cwvwLjd@psYVk1-*{vMbKFm~ znRIqR4K0Kp1_&P8QIzr+`4*HYWd1ZDAh_v<%K90GO8*=txW(Wd7yV3N%Uc&LWaWy3 zI}z?#Ci9@}H5)$gs0$54vljK72UBQnkoWKQuY zGm~mI-iA^`VZS=<>G~>BwiwM}{!0eW7a%&~H6{#ZUyW$wCg9S!scCld!^UUtb4)88 zs+4W?=p|z>gV%)8+Q*>_(9nx03Dp#QC|h9gXZfjFZr)8k1QaR8fk=1hOA{1%!KoCO zsDpt8raNCaOT5Fe){I}TkrSmq4~jUA<1URC0^g-5+Jy)&(e*jJr9^FLU*_`Hhyh3k zS8tes9GgN+>6$^4$J-TGK0WfmOrRn(C2Lv-?x8Wn{25rkW)UTdRp@?N49M*!++F7KMB0(SKP44FkI#n+2~MtAdZKbpGiVKXUJuR^aQaiIRzDS4^ZNXHjh9|Bc3}F8Vm#5ofH`gB-R{ctnQWi>@UCT~~ZUZA& z+=6yT-}?rM{b0oHkO_Jv1wKLRqQyN=V3o3ZGheTfF&8c7l73sGfar&J<^D5Hy4QdS zmU{CD@3{Vt;^w7ac1oP|(XdA5nk(95f z(j$Bwh&{e{&8DIa1lIRi0Eadoedp@FYeQC?VU)iDuM=<9yjzVPa`%-J%~K#|#5V|M zOp$MBzW9%B4Zc=+QWyQu})|J(}`-FSL4Y+SYMZ#_9Dd)p)?34>?@xRRY`96u$fefta z<7l$kj^|4Ni~NBQQ1I7fsN};>37P(=`#rdq3)EXWS#?s&YTaH->H_y;j|x@tFXaHX z5sKvjNd%81WOQR-W@JLU1J$(Wi2hTN%Hrp&^^ z{l=c09>f8u2xO*ZsNJPqX^c08`ziaMHpfjTF;1xy!=;IZ~4R`>E<|(ImA~`@P}n+EQ9~XU}(~NoR}ND&LKj})hvtHi4{+r=*%x6XL|qa zwMFm9vh8^j2gw2nNcvqdALa;-b#ezqIA-0HP)H0gLe+0@?nC7r3GNM+MlvqDY;H@q zQ3Yv_S-)+jTyuP`uC)xdFpPyoqWHAUsvt>(m=OuM%u)tY9F4^ngD}R5TWbvg3#fRp zsg7;?W8EjdLR;c4lz#m`9?d2^;e2=e^;KiXKUfOpYP%kjD8mCX^E(^yTmd9vq8E*MAq^cRY{RWJbVZJQ(;V=o09m3g=Q_P}SWQ*UvuB7KpXComd8cU8r3Ad^ zw#t<~MxRPwtL}l)8t3D2NN_Hdp&@~*enypL7fSRaEMm!X+aJi^pOi(8v&G!IJ&J+x zPc$rI5@vnns(*0!rn$~kEi8wklC25BjUF!>g3G?(=t3M*nHfA=yz~YHmmi*>i?q zv(r$}FL|>4Ac;Z)UZjqGbq2rc<&2O3@ySVd5foE=jo10ix(PyxYiLo{eS027;sIOn z7Hg{2opC8#x|IHx)Z8}JzHxIIxU`Y2tac&6C#|Z(>$!ur^NTJUhEQws%u8Hdb>ET6%bRmfGz4R{Mzw^OQ=ppjlq^7H^6IR)o(B z;+2c;op_DhGmFb}qtj$&~toN_q(H)mjN$rQmgZBN8t5NNR(xe_C*SKODgCnN)7z;?F6$L#?<{+# z6cNEEi<_Pqq*x4SmZBJ?A{lCICbP&glud}jTxbRDR#+ipT48!cqeNT!zdE+<^|J<9 zu#?m0_MMrF6w>#^VjkvM6Upx%$a@ogriF+=S+G0Zq{ZV%`xy_slMLlsu z@(?^8P)O~FqcSRYTf+eRx$&tiD0o&l>LgaxzXj?aR0yx^uL}IoYldLDG$GwE{9s;c(CL*%z)uR4@)Mmz^g=Ai zL!I%ew@fTLvxHk&FeWSc1=BRgM$~qbX+-%(Nc#7gl_n{84)pn6=pm`S@%17n1&tI) zrltjDsW_i(v-_D^RqLhzwdwvP7C@v&I!1v34QV>l@1hsURO5Ex6ePWapBeCVCk%9_ zB(15<)l17t%27swq|arye0#eA5)_IOCOp}%QEnqszcuyS{ma`FY{yO%h5SAYO>E7k zQM~9>A#j9=0F_$gJdpVfr)()jG^qZLHT1=&p;bw64jZ@(VG(nX?iMp5F2q6{9QSw%lV0apt`UMADHkGioo(ki& zH%~3V9+G*jj#^6n(;p(pVusuiJ@ZH%TD`N$+x7YOW(0QD`IOs|>#+)!^eo#PSq*!M z_D9}f+kzZDr*#|R;7+o=HW!7jiHm+ zRSd|_W_4N)npkKkbi$t&mdhFH$z3wkQ1(8n5wb?sPeV3^2=C06$wUuxbl-33={9v5 z89J3;ArYrVGDAOxd!~Q7?mi^kz2jR9A}POd-;_5#;lOU@#9Rx2w^1?PGW1M{><-!o ziRPQDC*-dhzb8z%RFn;I4{b;IbM%`FCXG?rCjFY@{D@q9DQK%a9csPU5)1DFM6>n@ zfV&U(E3AkEz%wE~D}90|oM3*u6)O)h#+CbM(cqGTpLxnxgj+YNN+%rir)6oAc~BNs zS6=1X?HhuH37xl^5Zm^-N_vG8(mOxeKgBZN+&(9-Ez?zYx> zgxZeHEkDjk(dUVcH`hzpod(<=+7tia#pR=g$jvyP6Y%Dn9P@16%}g=gJ8vcC!v2h- z^{M^1BshB0&p}Wtv$mh`0ipH{78KT_*7K9ZqIy#)sPW5QPKH;=I#A(-;r95s=K7QA zBA>bPy>^w;(9rMQ0TxlA?B#DN+J^xw)66b*)ac+85eEOMIO6X;UhyTPEMbc;Exp5` zld)y)kM~{ez$?#b4>tEcDdEBZI8&9|b40o!P*{;EE|ey6w}24Y342VfTA@QP&&(=6|2%3s z2a|AVOMH-Y4xL^QNpf|2uP87S%m*JPK}wMV!zu!_c*t2ZK_E}!&QRQEJ%b9=uDUsk$(Miwm-MidmD8`CJ)0?QSLbZj{ zh)N{*5B*XEiz%cP7=h7bn*oAkkJY#o&5kWUWbMI@!n{MX-dV6sGa$s$+V_`&9|oE z;ZBz2>}Kwv)l9ZlZ69wwP}=Rv4(o~xw1Jy;#kIROoXB|pJ_0>dLwHVdbzu&EEW~bQ z+_*K9Vs~;fzXAQA(Y6hixVt z!uJm&O{Rs}RQFBE(~;6I_#^na(VIRbWK;4wF3JoH$D!#f9tPcZLrL(1{^#W1E>T@u zZguw@%x4UK1bTa9&o6r>K8cO-sO1fpu^V_2SV6!|{lKT@+njmg%ef|z&%Hz``)gU* z*JVt1Q??TtGKTi5aU#rV-agGIq3l#tjxeA;M-gg$ID&^^V!d1)A0lPVmK^dbPoZdG zKT=TfB*}y-OMrWCogRVYZ)(Z-lCP!TlE0IeXdh)I8)n@Z1sXzfNDjP3>*`Cs=jAV< zjn@svKj56Ay&A~i!5d2KeuA{03^W_1(c?>fOaT2_%@P~AJ;g7=rTIAK%(Ru8GVG~ULZSa#w90-?#}n5uDR_z@Eq$Q z(lJ&TS5oCX$P7gNm=0!};}sz)3+D-X^=fhR^=OFMiqN&xfK&8j1250j-9r}lDOCkUJS0uIFyXh`v5K+lJ`;i zh4^<40ZduRe*jB+}($6O(j6m53WO?%uFPVfFRUT_8Q#Jw- zP)ueq8_cJq0UA3<01?vhSMuG{;5=9=sTTagPU|uGF?wkR636rsf3Y~nX9)~|PwRJX)w=LBqWF-mA{g26oLlKE1s3~!*5$+f}$zJ`1P|<&S*YC2W2Ng5F`IZW09SG*=1HkezLqssCwCPx{NdlL z{yZ?Y-1rJr{%v&=LeyJiol;Uam<(~@xz*O?=F+biXt$C;o{x^ zwWJ_CRMLksbUB=VBR8j@-p#rzFYG@1Vw4Nx^$Id56ul(B-k97ZNqRYzuKZK&U)*aP z_7J)nW+_|6k2mCgTlmKJ-idp)#0g3mjC;ERzqU8BLb@QlH9{WfJDLNg`?ue1KJrK2 z8u2QeB>h-vT=G3sYXb`qjv!T;%v~L)EH#=0LO+IdnaS)G&0rD+C=4~6$ z$seE0IErImaDpPW<0Vmof?mj;Lv%u8YQvI!&NV<j;kE>kx@D&fXeT}pLD41u=1 z3P_4npF|IE>p|kt+U9XbBQ$iBOWu-*QubHMm*Ii=p}H(g;4>CP_}Zo3&1CHCOsc#x z*E+>(&1$Hor^arrlE+R>z8Nc$avqbI)rQ({MbaGyZB8j7E~@LVB>G<(9SsE?@$3XgPnLaNp1u0OPq9bQH1kq3%k zjrO+?sA6OQ^s^0>mfoT9xxm3W%W$Q@$BFP5=QoLIirQbA)obt*iKpc4ZE*ks7($dy zuTh3x_yNy+pYImOBbUqq>du=^LrQMKsASqXb6_Jrq~wEHf1JvcFBzmiXXE6>ePeQ(uOt5R#X{PP~uT191d zGFC$&+!FwZ;NxfSEN`44*AqOslzUx$z$Z+&|9h|R+NuAbZ@%7Ox>rrHJzrmFNme(t z&~W?Kh-=oW=r`4*9p}%j4-V0B$^s|W_ZX`+t8Wp09R3x=Bz2zw$V0WI*DnQyTHZ1D zDr*H!@5h`rTVr=he5f2yzW3=p+rW^O$tZF`Cs|m!80QNC+?tq7O&uXdzJI5}{D$`A zH>2MvZuLlv=oi6TO!Gxb&_ZNj!(rF}B({;lUL&{918*AcBHe?d%R{0O=_~0wzU+pX zodgzu##D^GY)Tx40+^ED}Dw1U3Ms21<4T|UQeqf8eDRMqZ@iwjc+tv9V z*B14Ur|6$zP9HLKo|*!@V%efzYM*`9t`A!0*9*i$bGQ@7pU8(qiu(HekB!3-S?_Ie z-d^R*#vG`1oW*0=1v39vS(d#xLKNZVW*|2En%Y)@+1iEir$$44Tx zuFo@<`O(ChXSkADd>M)@tkUuaUq!5WPg*nQshkfor@e+uHmtWuBf$!x)H@UEA;Qu_ zu%q7*b(gWei1?U~Hrhu-O+-loPQX7j_3^C7B1wRdw1 zvq6^>|1M=O(gly`&vMbK(waUj@&K@rn+-gPFUm_PLL!Tax`ywBfjpJ;5+m8erBz~q z&nbDM=y0MuYZvo!l8w~@fkK#q1jJ;$AtgIyF%k|HurKW5O|(a`o&izMAza$ z*L*H-wiR8nQcE0SA#J_9@=mdLggxldvhQkJh85OfX`u&?Yu8x5-W z-%EkkaH1&OoM-W<{)9RJfrk@4$q z8!*i7Sf=$}prp5dK5zTo2lV>P#_ou9iWY#=MheoF)btJ{pUTs`A_0B>sBlwW26YmW zg8znug7HYGrrW!4$EDRByOQ7Eo7L8Al4|x!oQN>gj;Y>T-1h8hglZWL# zmNOx8Gze7>@-;<$@sXGG~&p)vU?uf(3l5o^hI=n;ZUNCN%Hj37XD=%n) zPbxu}XNIJe$r+Zp4Zq@X_COx_xXR5J5dU+XbyIUwj_kD`&72YS89@iJKX&2ktDBz9 zfN4hjb!XEL4{jTu^cJ!***S`ZE`9;a)A1*X4}ISwEeh(e%^rNFZ-0fz%KCtUSR|1H zbe1FPx7$s5nI)cL2J}HSK>VbMtF+WmjjK!#eXx)$72&jP1NAhN;`<1HQ&D#B(ILD! zdnH(V(gPqJ360_1P%{MAwZ0EIE?)b63#??s;#g*obS(gmX%u0IjnD!M<5z zu(kK#{1tZ;?AJq*Lu1TCm>=>{s6EQ3eZI%Rjh{xtCfyJ4&7}}eC*?y-JR$*imdbg( z2|G|Fwq7|*a5rdC%FketZ41978)|^26aj1Fx?Woab;!7o=x|Sa@-OmWj&;UWxR1JS z2^3a5C`QZ^!OiV){*Dz%@lbh8fjv_qe1uvwFfXLn<95R266qhkTbO9f>`J^A?Sbu% zji{Zz0rl^@4#30a`Eo^=0b45(3i!A3U+Y%}5!b*-UMWM%B>P=+p!8R-9V(?{+oOWZ zbZ7Pz{E+5dZsOQhKg{Tef=DB9-+k%j^eUT=&@PQkoJ7fcy-UGXMK6ySL@}%t#TY$p zHZ36k4P;4d9ga~f5oTe*Q-nYw$_1&4EyL+*aI4D8cQJMSr2bP3Mo8R_S(>UfdfV9= zV$aZggjqvBok!tD)Q=cmp>ExDL-S6J1V$ORgtUp-!4A|TI3+hn>T(Ly^Lj3zY*2WFXDe<~oSODwWYC>;CcFICuy5J|~y&Si0<&9KfX+tKR2Evou zD-ilK+U@)uPGKv_iCA@hD$J2s`o|6J!|K(83jc6Sm^r;b){9*#^ae`YV~%rd&CcZK z!?)C(U9pr+UD$hIf_37BxjPb{LfAA|H@<~9@M*;_Nm9am+-y!j<+^LwfC?yNxpus5 z$L~6%g(6dJ!rKii8POFnWg$Iy=*kE`8Hkro;HG1b1f*G|+`i&DUBbT@dE z#Nx|VCO^1yZXYCBGnP9FgOl`@YizJ|l*kVVT`Ul`ONqllX|qx4*}!~lU6$$TEEu8O z+u2%Nob%C`P21Lgx9NgMOfP&&Pm3^urX|j&Ujx?8<99n&nV)`pD7Xpwul3X5yENB+ zbbB8`1#Qo3;XthD1aB$7Mi>sW$9Ne|aqb@Zpk^JD{0@G5Ma3Ixge6P_O>(-msE=lE_SD_;9^%!il2(LhI0fxUlO6 zQ_%J@2mm?mL2%2%4-MR@saf?)dYV~yKE9iQ6Z0BNM|(mc>1nW&BV5|%%UIX1u+TVD z8MC2$63@q>va`m<`AuVq)3(>uIt(op{!bIEWHt4YvzU6{K4MW2p3DzQ)EfRA& zwDvLOCb`yW^IjFSFabjp&%To5*l7RyK}-KcFlK7y0u6tKCdsG#?sW@I}oe)QV%K`H+=OdgP> z%3kqpumpa<#Sf@vSk|cZaoJQWR5RZ`F21d{_|tiSz#vjNxmCR-utS|VKae}Bl>79H z?8qec#h$^Z{;u?!IX%du|JDY#F{*ijhehSgxoizxBwz{7=4bmr;b(_8j&9EMTxi)M zwP3xDH4LTt$D#tRQbONtt508E$!nnEr z_hy#l*l`=7yg?i9EC$S4ZFdEssy}`tCFj#X!$54$qd3`*fG)**?H?$3`xn=+lwKOG z^P7AF{|p=5sKxGEnhUsihgHY9_?#-h>ZMKu{d8;U)DfN+5| z8QmEfci;6ZGWuZfAf;@H@ZIl;d2*^wTR;F^P|ja+?)gIxBTS`KH_HLFz590iB$Ed! zM=p`XvdDIV8ES8ktdZ!|HZDQprBw>o%sxS&wq#pqCexdCE#|g`f?p!nl%e z$@}sdCI`76EA!caA^Nv}y)WMz9jv_wt*Bxe!T+&CxW^&wub=>se9n8`9U(as!6K^< z*2)R|R$FH7?1gghPV0i&EdFx;0ET%i_GI{7X8PbYv{w1@2suU%9@3ug*Fg-Ek7OxK z;gdSr`udF6RY!vD{-IJp!_`2~mYwY<_21vILmu_BakzX!h|V}hM2)UKR@YNguzEQM zq;w|{F5FC`9*X`HEtwqA9u9$&0R9dnfyvNi5J+IQgI>ULf-Pg4lVXn1j`n7{>)0}g zow!&gjTLb?+OC1C*D<28rw(aZ(2XZ@oA7D0>?%v%AC2_6maw-a!UIIejb%gO%{#V# zh-`3NFnCf^89QX?Y*hpDiG&L7xBjMfPC<*?v6~1lDUet0?k%@imVodnky2{$jrvx5 zYcuGG)?^igkG`526yOj6s(Q&HwR5`iv>>z?%wHW_0fS+0_ z;)~TzV?Cr1-=%(@+ilX^_+Lf1$CGx)iR+;!d!rEDMT>PHl7lv!5ZEzXb97A9aqY^BCrIiven>`nZNq0%EjDzsGxiaV?>V95mAxL*w5__ePz{kES^oHzw9xqdTW>?arw~B~ zTzu+xcLfdt)>-2-u`KkhDd%f-dFhth(8x1ko=XEp)`LbHE|o%24{CW$o3OXqu1d&7 zztNX%oPLcFXZKE(*u5b#$Q9KT8}=IX3S`z;fYb8*fxhCyPej1D?t$9@xY*pBaVh%m zuebx8?ZTSY6nI}FYa$JY+Se+D2Z_<`kWh--Hw+vdmI0;hRH8@3!yL)kW zcXug4THLj`TXAo2D^8IVr5tOc;xF z9VEtTZ3SU+-yj`gTESxE8jFStI}^^RJ?Q)3he!!U-S3z>pWpKqhPhXd{~NyY)y) zI88oYmhVA#XLMskAax!1f?_HmLVxiU+w|Z)30dYZKj}8znOOOv4Te7hhxg8UD(RO& zoY3Hb@8~z-IFL|&zoGcZ*Dh`Cnccsxs$REM+XO*I(fN`%!9q5X0QW#{1A$pAoJ(c< z?LK$7ls4f&X6IwEG?K*^O-p~MRF0~cL_L%3u30?jw9_`&IiE#P*tvpAe9+&?zwWPn zM;%f)r`%+_nR);6)ocKw*j?{LJpojyKV5dSPDL%;fVd=Kk^`4i0Mx@$tO#18yvRK>gmY%?PMT92A< zS|=sbgdqFj-M@fmr3@?$kaMSu8fQl>`ep>XOc8t3zEwMMF|;#z%uW_^au>3cmEX-}q&`V8?NndASW{8JlXX zH7+K2!xTW@tV0~g3jWVu{xIb6=bRB9|4}_9>YthQ@JrqcswvH{GC-^$iTCj=-xMMB|Y-dP|uW{f-D3KnlYl#F1`psd!7U~XLv zrL#@aFG(;A3OHsDzRp>MVWda^6Tu@bK)J9`mAj8YLbfCm{k?F3#8ZlQZ^C{G$~!g> zlM3!Ir>R`9cE~YP{L-q z>7HPR_G7};D%wQcyuza@ER9gJbQ!1f5>V5WWN-0Ik*t{V&h<%v^J!z$vL71bN*hzQ;BU0P})>t+pDajxf0whd|)?oS^6c=IlJX1m!vIAfR zaH$hz;d$yd_HSFjZ&w+Uc&=h>f4lHH7* zsPg&`E<*^jkg1Zkd+*5K9 zOk8hl5=75(zsm&2d7kjmj2-U)>b8GQCu?47Ncrl5lj7qnnyCHE!d~J5a>$}`NB!c| zxrXR5ZD))ZW`OdwnU}(~U}H~{!{R0c|k2i>BE=lxspAn zV7xLN4GUfWvg8A|$r`Dxd+SrCUnIbvygH%3yR7E(Q*w3JxB0YWd!NP)=@z(Mwr9iq zcQvRqnya6eqKtyzxnnb`s6+J~%X7QI^@jOHPfl z5TKTZ=e?yBqd@^8+R|dK^hx5DlsAzr8N|vIvE_2WvqoLAFKjM)i_TDEiLV}51?i`j z?ClY+>bym4iU#zHKHUM*%6U^>2zOcJ ztiN>p+|43(<&~)_o`g?81M#98PT6rpB+VkvQoIV7I{FCzwIlzOMC|q%^jjw*IhqFc z?&9@+hQ@zV4Df%1l{!pW+g-}0(x(_5GKP1uL>w`QyBZ)=7>!lq>83^J!ZXTn zRjbLx*@pW8kuQQfw@T1#tcVKC0OSFFvK$*hD;DJX#A}XHR$Ka^>>MT~C55Vy{E>P< zb22N6%~*K|h%AEO_g-Qzyhlic<_w$XBTpRHc>yuzs8S-xB!f2|#j*z;y~yHLWHy0U zl9WA6b)acTr9hn^6lwm623-OX^{d%Hpao{kQ(p94vf^I8rF>4*RZi(F<~R^i6lOU> zwrgL#?Wg=hk<43Dzy7Y)J?X}#_M(v``T`f`#F~X6Kn|Dz<{{0D3$oe`d!pL;?sye{ zDxNTBEBri&VU=FI{G<-?D8Z2C7*IaGraQnrb zdO45+qP>Jz7Tcxs${^!9avAQkLmblpPA+miZxO!bziTxdv5a#Kn8h`?+_$_oNpx<^ zYU|dS?!;T}VmqlDV0Eu$;N7legwSSYH#r$1Y3G<^r!wgSoF=JgOQ+%?HhoDddP#2N z*bIe20Eqr4zhg5Idn1q+SG`#r*;lacvnME$gQ0@^kq1S#6w&f(i3vUhIQ_LSoDeFE zr(`4-9u14cPv&4)7znBYW+~v|PJqY=w0@~5N9W&3T14dA#L*9r-{4i)C~>L`o|od? zFjSYsDN^FUugNRLuT-01*THX7aPPq=B~=rZB|>=K$dV|k>A3I9{+;=PJoZ~2AD>s% zu9g%RLW_zWgCf+jcUXXz`DX*1Rj@EQdX)I}{xkouE4(~N+jSmziSy0E!+eAC$IBQL zOTv8$AD=L!fk#vslzk;XJ%#)YyXZwf2bg8Wl;hew$Gi5rl`&<`lVe94Ynykrzo7y4 zKqiXd8(2fiEwn{{p<%{@!1h=)d10%EVV;E(dDXaPkEqL!j=+RCn5|}Jos_Ca=9HG? zZAl-tQTA@Wd(Uz9r&Zzm$!O+j%Q#Ou?6M5tZ8$%D1Fc;GMXxqE3uNX$sPB?wQ-m^$ z0a9Vev8MjT-l@xBd*C_gFG*|s<@1~o@SN*61gI7bVnuNz5-VL}ASmZdiN3H3ybSm( zjj~h5^X3Mshqrlf>^`S6w$Q0R%GsT4r{fgli}<@k>zrZe!5{a+8^Q=K_}~$AG5Ay) zSe$vcZ}%NRW@)Jv!2Z!v2#PU89)O8}vm8+x4Hz;SjQ&9-73FDMfimn;F|^wKJwb!y zBQ+%TBslBty;|7Pw)VBb7KGp5gx3#mm;N>9j$eFMW)KSJ%f;RIRkpB=Gdg>xkJJR5 ziXtw=Nypr~Cxz=4`B%MfGP``pmxZVAd0E2VsRK@1!b8c9bKuly&Mup{EmSV`;q-53JLDz7J*d$(d81RHu>__s zHRZswoZCd;*EYgqqpiTkm`D3zNeK~K8TyS`xsk%X9%jc$cK9o3FjFyS5#D9dk+qaL z*9d3{^B8yYcuDQiua2Lo-6>B2Ns?;fUR=kdSVq{I{_fhmh;v{*yiwiYb2j3Ry3Zk> z%{o+=yqpc(cA!X+upE8hI=>3byNE@(SETz*xPiS<5Cx|kL2~(izy7%!u3EcH+CRa% z&f*eq!|-2QXtKFTUUc$?o#io{bleIIG1{>W)1xjx6zi*xnB{=FuX{NQ z7d1lz_%U2A+*sW(3*Lvl|8OXUoX?x#|E1qE4U$o%QV!o>%(EXEl^J7mA$E8(k1y7QIKVoN$!8_BngxWkYseY zJ)Z6!6x`W)VCGioEJ{^j zJu{$q{Ir7wT`H$GG5X@_t<84K;is^;Mhb!~i=S09evem4OQ_-&(C+YBm^(pXlHvVE z(EYmjVs*|uc_PakuC-lSAz+!GC43b>OwiuX1}XJjP8&~98QSRAtXRo!=|n?36>r`v zE-U21Aegv2yWFavyd>ClD&NJ4C=MF^A2$FKYLd zEHo9|ikwwUWw%(9-J&V|I88m6px(4>(EKPaI%SFD+a!C(C-yN6_DU_vU-c++<72 zKkm)@<{3UOB_j3`ibS6r0yjcX^uqm2Mk5&U>G82HCYL5ft}^iIZRS@B;FYV4(^MJ@GKjnj#ssVm6??- zxKrA>$h>^`BBmsdo~ixP!2Z_^$<&eWI3K5g++Ze>0JkY%3XmpjCzI{0*ydo*zvyC2ndX3XsDD z#{!hu@gMJ0Ij{dV>$jd%hA8iFB2#YnFNL@iXC4MDKH(g*&s;=}%%1g+hS-CZcQb8fG>9)I}^fu`3;H)5jTr*7G*tM70=kvU4jEP5rJqg zdRE3HU8ouU^w5owBL)30lUas@IXER@DMy=f`iH^DEsJ4@ zbWSwb>Vr%x;-c6oA}^mAwm&K6yoZ-sbu~o>CG;xNdY@8U<{{Vr~3)Y0Fw%mHd){;LDzoX>it+=;U4iIh|$1Jq-E^`qn!7lo@Q+8@aO0&$f z%;}yn=3NuC-2QTHoTU)NHjV+0lW=)4iT){#*f9(TtKwCQk_jn)i^W;R#m+gZ1+j)n3?`WMuBukfbpA$9Gn^ zfwYb(U=4;bLnf?rBBID@w8R8XJrd$*d_nm16l$}X9d%8SPr$FK(^i!iB?eLD4Dk#k zP*iq&)`~$Km?Usk`briPw8xW?~_=87@psnm@5*3?FqpU#x zlWlNDo~^CvnZ;CRWAL}~;;*_{-{B}C`l?m1NwFYt75TXY7^ShHjP@hvssy4s;t%nZ z=4;z9{w+}uo`5uA2Ptzza}Wz3BmoXA;XXF$DL&oVSn;H++=syph^)uGoH(~ zg5GV3N_Uhx-VEgv6P2IUk!Pa=7+Ku4nWvn!cPcLn9<$*&)HynEpQ+`&r@ZKY0 zdlcL2BBX3ll@6jTxFD4%5P#cp=Y>@b9`v|CZT9v+{H3OIa%dmyw1BDb>bb$HU_9`V z78qA^Wa@AZF_!a=9Z^FP$AKt5r$_#UZ@o{COMl)kP_8exNEvifo5lX z9fA>)^<@xgypz)3WRwDE_$;G~z9L5XthJg_B6T63qUKAGl#t2A2BG0y%K9SbTU&b( zIe=!p=LoIsZow)Cc0N!K{~WFyg@^<~voDkA<}!Q>e{9%}+~*j_7@dw-Fb{JGQ%+Jn zzq$bnG&z|B&bzpds9$*@ZQ^gD<^wmmyYi28!>)Ypvs^Mi+cqZucEr99o2w1<$@^{r z&vAtd40tdO)K+tmct6FR?7??^J-CyCrvJK0GHutK5*Il!bEvwe@sQlV{VGV;h_sWf zg_eh*F(fIx%Z>L$28<-^8bDjXWGX@W=SXqyhJxP{g@J70IkS0Oqi`o^oZ!~>Dh8#DT4zPjGD57+9HRA%N zP@&^e@ts{w@c?W9wb^Tdr)_B{9s+?nP>>&XA6 zxJ#es2^A!HigW{utm1{1?+n7WwiquMVAxT7Ujc5wd$PzUtBt0|$)0vpyS`wZ5aVnF zLS28AY#S$SF*RdMwqHwS`LSt2AhWf<2!gKA3Loc2Tao}H%&L6hebt^s-`pmo3u;8c z+xdSI#oO2VIHrXO9nfW@N14dK!$MoPYp+fnSKbylzq%oa8=bnZ=;mLgoSL7k{nL+g zWI15#>sn-9zf7Kc$Fj0ML5c}`yovDkTi(@|19S>j0^89o?0+iFPiK>al>bM(A1f>{yt@|41Kw)0}|G z_eUtxO1R*M_nW@$(G7d3BX}9)#SG+YX9ld>)bEqfsdycNO^Ac0VOG|W*NF$Lhnla& z>u#Ik0vEguJ-Tyow^^zB=ts>*exTtr1Qob)W;AgUzbqEoz4(c`CW-oHS+?EPdd{&o zA&=rmfPXu|2iBpWyh4FP(z}Fs)OW19#G^z_5Usc~iykW|D-Jw6yR)H?_6qE)5((AG z8CGck8NRzA|EW{#PW&@&#&6e2D}HM`U<`Wjc=Kz6+4nMJ%XX&%53|K9CS4=*oNMLW& zBgAt{&~+zIC~4wKQI*{ImPmDK-`i?b>nEGFKiaBOW4yZKg)M{F3ez7ev4iB!Ioc;} zUr<+2418#%!(3w1kkprlb3W>d4#;ugJZ>?=Pm#fq^V&fao*DmHAy`Rl%Wz~KXRJ~B zim;5>BDc=++i7G`;?~S}XzP;zP?bnB`f zzJmJok1mWFe14}1Kk(xqJcJ``HLtD!ud393Er`xsJPp8o`s*!&aCIKMq^+f*w{pYRR+v}*0 zK7Ufu>sJ=7)*nMWj0+3lTqeWQz^9Pt__l>bzF^b+fRGQ_<1`-=c*b^}b)Yr=c!&ZUsmW$_uUijM|0}!0=;PYjO&q|6S;Zc!J&Wd?O@4YX{G3B- z@%hRLKUJT`GCmr(gD=^8lh!#2nZ)pZ>c#J!Il{ZP_z@UsLeLwh^ck!7EB+zLu9)aF zWw&7X_YZ9Y0f>7(>{{=>&_=z9wj2QaCxOU$Mn7sM>A8IQ6ZJ56`|_9q5eI~L-pM|# zMZcM?t5kcV?W^%jv2*@AF~|+PMCKw?)@}!Zr+PcBpgwiNFEO&4q+SxhTEMlfUUDk&(tY@WG+wOzvz9k+D}c91p(lbicXTA*8>$ zU?K``hycH$RZzQb^oIr?WwVhgsPSQ0jG!WI#Rh`j90^c+5?WACs*lBK@y!Labwimk@6I)6Y44ArK zGbZ~r55HrJg`|o_knIENIf;F$Q`^az2qA)Gx@5_vMItxVk{4jpInPPH_^XFk8LlzG zso;884==)&10QWNqid3GyhyQ`2g8v@JaSsXyqvuH4H-fPt6aYb6350JbIEo(kV@(A zJrmOO^!4A{*K2bs0b~x<#~Jh3Q^`wVd2adYGvD3CYOBgSm*F3p0Mq*PksD|oj{<$M zi)VEI0PwNE{DYV)06#(%G*@UAlrVjJH*j zs#+dIGV*QdrWrPW{&V{CE4f!U53`Y>&hzDLj-0; zQd>s?9bp}INeh>G$TNgILA`y6uG?r)4?ilF#4>)opi=TSX%tuOo#C2}T*&wbR3m72 zewZ|;mu|yy2&8{?>X3t>|jZW^dSyEWe|6$@%%43wn*w(EM9I08(5yJ1<2cB zC9B3ZlO^cNG0<%jF@!i(F+VmVHDUCNR(yTrHKI78lQi2`!Q}f7FqA_fRq0-mL{#sH za^%%@8Z~GUkzAA=Pa}r9r}XNmRW?p<_otXJ8m>4d^J{{fd<ZrtE5ieZi91Lchq3tb9} zI|cK+%<{$u3DFeZ?4=dcKN$Vov(IJXh|-OG8&51R(S^`sU^|y3vC|wCY!j2BuX-50 zR#^!6)`zud$xATP_H>a-+ZrQpxv@~0+HfJsJs{5ux z+dr#daU2D*tqq$NIoB5Wq}wH!@$GO3Ez@SO^0N9+zh%oi*~bn$e&*MjsVD@Do@Lqs zhmpKsgJ1M=YT$Kg;euxRs^&6V@G3-ZQ?Rff&0SP+tc znb6KUPWxdiZ!B~9vlYtqj`BFg%FJISIB`vB-ElYMSG7+h%R;1Z#jI84* z#51HRriVsTVeV+Fk{NRBIEF~#*UrQya@OXH0A?bQ*yQ>x*vYhe1_5772y;B}DoL`;-Pdw)YDwnYqv_2Vzhat%o>qK%5vXuw`#`}-F(%UEt5WJxvN-VsYouL&g!B6(PdqFvLTlI<%dod|M)t?pAi$W4s zfJ1Q_(CRm!9S;_vrYO>7TPiAG`uD2zY0>bt?*!Zsoe%dZbZ8-z^yQ2PUl_pXVb*CQ zj3blY*gd@8NlQkgcMNzkebP)4N{1oou7{B**xE zZHd2UDdhv`le?Wd;ZX;I+}luj%sTklduE}lj3j_+8Rg*@iVozSXNwK%AG{Kux*!st zxVsISLnZkovr+Wzk%loNunA}M?bU`el;YBhK_$=`HL<#&0unw?*RcAUFusaMj%0Am zlkfsQhXeE~m?E?dsElT#*<8>wD{|+*+lSm9EO&WsFlf$*gW0zaAtCWl>BMCbH$i5_ zPaR4}J=xQDnWIv z$^-A_jo6Q5@4blTN4KyR96nEf*bIIaVjoZQqb#m>Esf487vErrw^yKhw9sfEI1d#~&$rd{RPx_&n46-v74=9cp1zkmG9vksuA(e*eowCl~5ndc& z+n8I;wxz+r#iK3i>j4s!0{0X!vWfHATM;uk;s9m7rE7;3Y1Mu#8nuTv!Iy^b*FptY zX*a$GIM)%EG6_Uw6_Ydt8E>lG@ZIP<;fZ2NTksOgkbq;DpkV|;k+Pnx_zn|fC@Kn5 z&GB=zb1Zh?QjL(ECfRx?c{~D-(MXKIVe_F7c&qH>wkuR!lTj>+iO&0lR-*sv2e{C> z68VM0!Vf$uLedR4HNHBhb9ma{7 z*}!4RxA&o&+*mhhJ&?r{DzVC&-wt8hHq zZ(|KFrleX#?zO*@?S|hF%S!vpBatNbnd6~_ll@;J`PfC}qezcYfoNl1F z}R*59pcGv2*83T^dN)|VMV`PHxu0^9y0+o^RVjF8L#$=CCzNrTeX;XD{q7PIU z_#VZf%)xyEmVmemEDS~c4z)l@3am^TC_GvV+k$Nu*h%4-<{$#ifx}sFHR@2^arsZ5 zw|yq3a9P20^#1ZU_U(A|8zmLK>56u-(pS@-10s$NDUJUezoE!ILLct?TC+mx8~W4h zH}_@A>TBnY-xBbue=N(^Jkmx_s`WbayyifPjT+(&Qn$h>xNoB3eT(i-+9N7%3W zSfPnqUztzcR*1@`ap1vW`qRG!vjE3Q`@#`V4&w{IvqU&61d&wV)@O7#=thnZ$!O|R zl5aoBr?MiT37E+aCP>mfS^`s!k}V${i%xPJy1K-=)andMX)z9MVmr|#ej_WBRB!1y zmIIMEG*G{_!5~JB>Kz(f(N{#JW(5&4gv~M-QU*}Z^WVs|m+vIa?-Ljb1}+xsv3>mh zY$xWpNEeD!{?_;MpQVuQfsT-ZSn-qyNLF#8tu&CR6-3zo(8PhEDp;0SS@0Uu4qghY z`j5I>BpoydJ@xmGs?PFeOb0H_?b z#U9$+mVvNlhJ73W>&-`7EG5!}BCBFQWjcj-grCA}#?PYKo~`kHC-%;6SS4bR=ycQE zun?t7YV4f2FL2LELA?yO<|26PKL!%{wY4LyGbnlN5!=a^jkdJ4&>ad;XYw#a3)n>n zSl&&?KQStjI!wIF8Q*HbDi>W zMW9e8RPAz^nYE2n>blE2_N+$bN703c3&pQsbfL(+5{-yJ5m*Xf zAS7&Jk6(K2a zzcXIwo6#Uzk0V{=Q|KfxXVTMuv}IznUc zAJ;}Z&^Th^`MeDO`ldVogtp8lk)*K`>5C%a?wK%PM%zS{?|B6IQs3P#VBDmhtVxS- zN53`!(Q(yLr(ncMtT(3c*M5Pq5T8> zsZ|LWIbaPb8OmYir>2DcRw4dPmb&xz(qCW+GL2GRc2V-}h-os~5dqn0tERFlK9C#q z`))fL605VFq%#Y8q6`_Y9TOG29$Kz&^$GBKg*-`D|v5GSlg)@SDoV&jT#4H&JUE&qd8c zOtUvK&qig#J>wRDhv7V^BqDh{yKsP-#4`;hak=rnwV3-?wzW4yAvY$qJeH!VMH_8V zFCNu+Frb^{PE@q$oI7N<=}@{pVSx{Kq->%XK00s0U9I^x2s`zn?eat?83ifgj4_YQ z25LR%iK@m3j>iGH67?*>5~G5HU!NmFF&RvNoR>p~TjHJ@mjT|rbKf08S?$jQtTyyp z)aPTBh0t6T&}6+fUaE_YZW`k7GR^EV|c<~Dw7z@FLo>Gt(&C421R0rbI_Aq3;z z!b;@%2=!@3GT9M)@-euY3@jFQ!87oJ8k%sCeZqbA(dj8f7wTra2Tz`^kT3f3V`gQ(=<(r7xIGE|YZ#h}mSe55|{_S`ANb`*jA4yxCCe*goVb%O%S zPM>aqx%*u3?#ld|DL9!<0u7>V>jakdR~PD3Tu#uSvi9VGX^oWPEbfaCOME$FkN(x1 zUk94P1)8PJ=7|Si-)3>~$)7C<8ANr=Y8b6O5n{0mDE3eufiJS1rd-)>^=0X6rJ#x; zHEy+B`uP$EnwC%14>*yZ)DXgVN+3LO3kUZ}o;^nt+r{$B5ML#DBQgnszNpi=^+;yV zg`P@5zY*jqc{-4&&8uRcP!NfVux(93{}=5$~z z*KR5O>MPA+J{F$CPyqVbu04Fh+PJ)h# z4!v@-A+`&Ox<~o?cicOiKmv0%qS}!$((50f!6UQkH6u#5D7sfLQBjSNFrG(6`p4-p zwfO#7oC#kQs%_pq+|bNxV-kbrwPj2b?8(~Ruw}s=7dMig5z+-;mV{(?nfXh6Ux!$2j;6y zZO>{&w{xQDs=Z^{$?UHdfNtFL@5$m7^fzE*lffd*M&%@q$j=PAXc>5B2TIx(*<^l$ zjch@xQ4eDLrDXt4F3f|E*n%E$Z!15MWY;5_H;7uu4h~mF;zfI2G>g!pm%+G?XTMes zHqtz@KXh4PSt%OL1jGc&0`;d>a#qzh`SbzUq$@M9&x1Wf@<(8zSsn|fgx}c_-~5Sm1Gy;6yw-}mYaPem z+qvbJM~G0L>m6!$Xz{2=@A@NT%c+1<;rUyE$}KCVXhHPce<-`vNca&~qrq5MKV8SS z#2flJBIa!kA4gyu<*g|&m;MW{D^>KGTe87zzYiv2ZtR7y+X{=obS!Im!yyf>c#7?4 zRB!7M_MONN<#}idSa;6riPhz~w1HbNiK8sz>5#ELRl?cizf6%&mW|fLE53i5LE6sXQUSTF8DK zN55GJa(H_8(ka~}KuR0?HyhHtC7{d1ZW)vsD!% z9GnjR#+seK$x+ocu9qCa#Jk%O0e9*lTFiG9Uhh+4h%`8FVUZ2nMtH(C{c4BG2EHAJ6KZK$xQontemQ6t-_<8c zmi;&$9+Y2%d6-e=B@v70kJ(k8&NMsN!h#S#^PyrZT7wU+J1zZWr+{}{Y-->Sz#*+` zgBb1-!bGqjEY3AY2v#G__r_9%Z>bfigY;wBOUqlB!nDE1S-hx_DCjLq^Ny~2YE@PF ziAJ-*3!H5Bxsyz`ZnFRW?giN*8FaSUHu$IZ*I~ltI8^vV^F8^;NrU4p0^g|$3xVs;sow9~JlMpb80x5eE3nIYd zB}{Mo4~BNe^+fhWE(>-t((SD);JexEUF@aKQWr{$t(()NXjZ{y2tIjA0i_sX2r<-S z!>Qrzs~BHVsjjFI8XiF8LTKhbyRG|`%tR9I%1GH zt->^a`??+MY2Ly}m~(4>oePgm8#g){3J%?=UTOf$og_mL{2zlq{xS5lQ{hw53+M|t zV)BPG!}6az3 zR1>1JSXP9^$wa=3M2H4M(0Y^(*zvzi69OG|Gvrk$-Y%3gGyRZ4Tp~x|i~{;3UGRc2 z)CEXC)vRD9)S_-DrZO}MiOGJmX<4hjyl0}Zke~4xW~LkS9JgJSxHn=C zkmL&{yOWQCUNcS$8iELWkyMbnpjIwXw5X(qxR&j*I zwHDm;ZG;8n_$gv1J<4JyKDZke5nb{lHI9c_e{Ik}NR^OwCgeB5N$-5qCfh%B>sWw| ze*Pkdt`anxeQ&h*^>5d5=MJ32%87hCIlnV%=V9>kycM)aO`4jeZLBH3fwoA0QT>)Y z5x;I+WNTut=ew%lEosAbKLIuY#w5mZTLhPHk~tPW;Ni!`902a@3%i4mVU-mfE*`JS zT{D;Kn_3-t5M)kT8vfgtXIh3t9N7um>lh?5SM&jawRF6ppL3$vU*Q_LBL1Z0x71Fe z0cU+wA@j6l66skd7h>h9Wj-`CjLOQhbo`U!xpdIQZaUY@w8Iz{`Yz0qoPT%zPe{mF zeDdnPL6F#0JsepGhs1lYWeHnY_I@1LmZZH67&1bo;+c^rM@cf&U!Xuq3J~nNoy_Z7 zyLwsTMFDD3AZu)OY=6COTTVkg&Ngdl8nzat%(y@&_(&ew;KsHYe>j6|M@mqi`+~d> z4;D&^Lp$lg!94Tc2UG1&+0T(gvT_4-%O_j!j zN9g?njFcM`jaZV$o#3L?FDBRY3*y0G_{@922p<0Zd-#O=z*CX3sV2O)rC9j~$Jer7 zA~{^W-ugu%*0yaWD9w!hbl?h=8yDG)xUl*yD~n1WwqFE}%mnvU0Ez>~15Idl#w+CI}h~in$2+f{_YR1UpM*P zssG%})WJ%~W!Ucx{dKXu;u-&(n#yTEUQNu-E*jxZxJ^ZZ&6({4E=H+I;b20ya@uNNREYS)IG^Z5?j$Gm;F8{^ss zaFMts>B{_QFOr`65JR;L~p=B*r>R?s~AQK2M=SvWzB^&gq5; z?!RM;`_FqsqsNs%{`EsRDfK0%opLdFt7TY7i~-EC``7#Y1nyUuzZN1`8Tc9V)|Y^^ zut>4RBH)xP@@#_*cK2W5QZmTujv;VIaaM)2=`Z4#9G+|bEcqcEI_N|6ZSfqjf6F|7 z81z(N^Jg~~{g`8wh&ZYNIK@l?A$a71lSI4bXJ%FeNeuT! z$@`}^`-`9PTr5Pq3Tr?QVP6hLwG z-uda?rn-{{$0bBLF5rPU{YSs>KNhz)mchL_Kxnq1O2+3}9-+ zh8j|3qhAW2H%XZuc7_leJ{;i+dOocK#BDv68EUJ&Uw1nD^p@Rp-tVd2$mJKmk3qdT==<>A*k{jnP{=dB%O^C5NvPj=2p)^JBmKi37t1WBkk9q36 zQKN^1NF%u8jVi!sN=Bs{e6M8-3O>1m$>u%R76L_AUKC--*5#EgVX8*VcRU~Oz`%4n z{!xs08yNYIuJg=+D#h~=v+#nN>2QM1Si1fclkSNfl=K6TW!yp0BCW1L04C8jzdY=B9UL@#=f4*zb6}4T=7K7#u6v@02Q;04_LBIUW&~1 z7&dhO3QsEPF$LlEa8&vApD`eFyarq_PU|2~2j)A66k%`){+cwCk-@3JzZXJyVhdH% za+5{2btOs}Ye)Kt`^<$9(me>##OSYU*bSXQ?#ZiKrcN5SZT3QBRfhNKS|{m>P;h7H zbFJ0uW%ZL)3jQU!47cAOTjFiWKJi+eBr+ehmK{nU)fXmn4%TF^FHnu=04e3E0je5D z5VZyQ)Qv2lpOCW*g$mQmhUTvh+1!B8qw{I&1Spf z>;~ls+!ZWnWMF>Aveg>?^zbdoHvLY<&`7#PguO`x;E;>Qo{szewZGD%oh?EWg;Icp zmc*}0$!RwYnhXtYYM!aUfib}`vyN7V{FL3P;gLJNZ-T`IUSW;xAR2&^92k{8hV40M zz-%?va6jbra6H~@QMA~gIf!p1-)4Of8{xxv^T?efMmfL2rD_h&L7z$IKhu#4 zENFZ4k0XM#p`K*%)*2031=#}y83Y~Nuy#8J!LH<5@w>^QRwN_`Iz3%&FGX+*@>SgS zdhf?V<6jrwq8CSTs;fHXT^2t!86oCUFuLO5_{EMiWMAZ7KJ$fvrhx{$8ru|R%|o9> zZGi?nIs0H+1jXFiSNTQb(lg}V_=!>aS|{FE!N4&?eWU`q5n{%oR)xYt^=|^eM|KK& z>2+G%9W9GF^3Sb|*m4>cV^LEY045O944yD>CW-q^LKCUhuiI}H`|tkwT^d}LBs%yu zwKr8qS89y^F{34dC{F)2;!(-uit?NTrSCXLxNcT=vftb1EDe;``_yXo?gK~8es5X* zZGLY0{_^;~4!4{of>Ih2XV9WyQSPc-30e@MC7|wC=msiiFS&zhuql(cRd5Q(t5E?j!#M zjsms<0?0nmhZ$?6V7eLm$E211^+5)$XfLFv%|z~}e98WRsFn3z#vF!kYcZd#VnaFQlQBl=wqP|7Z|1`$3=${2=4eQKiA3R>DmDT44|J$ zrOmpk!*veP2fowU$%h%N{M=)Pd=jDOfl@K|5DeR3-2(HzPWWBVoEvz2Hf)y)Gz)^-;KWi&*9 ziTW+7D;jkgL9$c_fx*~R%g>$easOP`f~&qXEdkU_^YwCQT#bD3CmO&1MMxxeRR2>R zPr<~%-!5X{%#GbB=7j8_-5cV>Y}B7LYK~YS5ogssWR(tdy-i(_wX%C^Mmuf+1TkkB ztLd@akEs>txq>ma+>k2mkBy_)(ddIJU##XBneef!Ii9YY0ETSxg!z_sh|OdR*?5h?I3=j9@qa6^%e|mbxqhV?i4NV?$RKE0>x?37I*jH zQrsPa6e(IX<$&`@KmTyz0=pkRugJGTR5)Y$hE-2){mGts9nLnQ@ z?ApjXNPOAt<1LT%AkIa$+k*jtYXenaN+69Tu;BpleS=Hw_VIGN#`&N3M-7BOnAL2E zXPDK5N%EPZRlz0J9vs1nr9*B52NG|Z$Sf_X01u!TY)Kin98aYxw>s67-c|`nT&VLF z&;n}bY=|OXL`c0z+$$F){jZqO4oS^|V|E_&Y1Ml=jz9^aBU+a(T@r@sNkT#W8|`s4 za)N;!D2(8PO&0L|^s_^aI%zzu!WWUb-Q-@!t-H?Vo*WSYv z3r*j{fNhRiyf9!lN;i3|j_Iq1H3V*OHmn<_YbKwLHzXey;psXT&?U(dZdTk(-_HsP zz7CyzGnug?OLa{x^6POC?Zt`TaAhCf6=D1SVg)T|^+WIXK_s>wZO5n3dBV$`URI3j zE7#4}6mN$qmZ$Uhm*;A=pAn)jXlCYb63zLR# z=SQzN$z8}Z<^#NVTsuD~CZw(A*Kv2_QcHBt1Uu1ZS>Vv1YqzGl%ys{SV;j+zjWPYQ zkkacqw!kd0|M(vn3qY6)grAxn^oNduj^g=w0uR+d>oxNqAScf>U$Wp1@JJB4k`zZ30ad!uz*QoyzNTYtxXv^N5O;o(I!j(W6~F&* zm(=ae_}X}!<6hz^8C@GR>-Wo$T)6$mK{i~w%A+<@p{j?11xd0j7dQomYi#Vp96q>! zo20a!hPD0;wMq; zTbNKiGf+3HOAiVavFd&DgcM5gGQOzWigs-d>H!i&P>K3I&WuMdM;*4K|I4^QdrsuA zkG-uh7DyTz?yo`w>lgLXxLPh0I&YT$La^P3z=O7-f$q0Zl%3wO;%Ng{Z;W;zdjn2~wXA$f-y1hNSur(5BJ>>`VeLooQ)G|tc!*rs9=OxlMX8Hr-=3xFo zlVNvFLCg|=;*;v&7+?0AS}Gk|k8|`$e8$jvCe{-IPeu0;dh0dm#WExEbJB!aGe)v@ zOhp#4;PA#IlLQwc)4Ueqe<^>kCQ~=4G;~vle?RS#@iK|*5Kpf-Cxprdv6m)|&3rH{ zzIc#0)euo5O2(z?=15V5vM)z}$YLN1l*(j7A)JVbfmHF=eD(^oebZg&Umd_%k*eZ0njpW!}!kPj%BZ zNo9#XC z58E2-NA@+hV3FU694in^KtXNl3X z_#S{X-`%(RS;S!H4aqvqv2GYV1ddv0=7phS<}ESDC|PfvTxCc2ysD4Po;2J{ripl} z)V^VMtx4y5xrEp72H|Artu0({q%oI4f%`0M%LvQ7$76T5Pc=!twA)M!p>7Q&fY;d9 zxJpFMhG&giXfZ$~N0FpyrjJdL9_DJF?Q|t{e9qLU)!psD-(3~l<(o!lBZ~&bCV=`Z z2(h1>IppJ{D%FlLsCS9nV=|?zuvq5bK_@f>igpWjaU!Cm7%Y}KU5>X z3DzeQuwYwy#ifhn{&RMpa;lahx*7Ab(|SXs%16==yQ|FHD?vQ zok@leUx)j6mHvVf?}|s0@fGD44=sYFmz}wa@D%7{kFMoS_+>Wsl!%SvpDzAuL6Deq zv#F}j5PYYNTuA`JG^u6yqgY145bTtw=XULaGjuslHe}Bt9;dc)cQV8usCGdK&+2>h z4=*)2&Jw9=hOGKUu@#$uj45}0h`=Hh8l|V2V75#E-LAm9Pl?Km!R?T8RiXfWa+Y{> zeS$CK{z7M&oz|JIdVPF6@|fO2M>B+A5wc7CZ05w6(9oDZ{LjjM*xVUJZ+z)B4u81w z;ZwR=(wAv)@Sh)(-O2gOD1VUb2wVyL3`_HdlEYq4(ft1U8pBtzq+`wJv*4WOY<0!| z#}NO-Y@wb`ksLUWzk>_#CGb#F2F|w$ofiaO4xi(;*uWVY-6l96KGJ$gRp($D{KSC` z1}$tpMnXTTl5FStRD=D>q3OYag_U;;`lYL|C0svO{&>Jgl)isv z!WT7NNZX`r4dd9+OAG!QbCsLq=f1bQTpz(98Ei+$|0aUi-Fb0SXuh=6pM2&^hOn(a`Ir%~fM5n3AX&5-FqSO#eH5Y~m0rxVdFU~aBh`*Rar&spL67rhhW2Q{V~`8B=yDYzSH4K66| zb;9{V=xy^c7ehflSJeFv(f*nJQ&%#%94Zl56oEYbGDmnPoSb*-(GR@y?(a5X0C|x! zS0U_PXz}7Ukf*iie{@x&Qs3fcil5LD?bP3N<`vf@D`wX+k#n~TikSD^^;k1$RCqo$ zIZ7F+^s+Oix`^^K7EqDRR39GA^EJ{=#L0PN-`-95@6_8-aPri>R->8jrjbDN&zTmx zW4LI?knmzuDL43)AA~O_#{2N&ggyFYB+S?E^byaxYh_ae_7EYCw~W2;KKF6@JFl%C z@ugh{<3SrFAW4TH_F*kCGw(JJ=zi^q5J2>*Ir7FWK1tfspgmDqtCBR*(Fsc z;Im#XrD~S=KJ=lKYHI53&DSjHfeqn_hpQUgmVn8Z^U9BK{;{AWY)=Q6$3d@1RLVX# zF6w0SaC27tUwBErcVP8T?1K8*-)%wW?w@qxiT3o}L6bm&-hmh#=9%=Hr>s)itO8{^ zl+pr<6wFLoQD(yGO}1wWcVJFw&r9EBetKE>6WEepcimn_Ipkl7z?F|6^cQC$*hcfn zozW5Ozq-u-$~h4IKDccM6AKdvbK$}bV@YHa2*nf|s&|P~q8i%+ULN{Y2dyCfAozEc z8-I7={_vaB5N=jBATkee9Y*)X?lpi=^w+mkogNK@w;g@y<0l<|lZcrh3jEr=nQ=B{ z$1X?n{Zbw52J?!vh=oEi?tq){aZ8F8*>&Z z77`w%FA*CLd%<<-0#g$OP*?;>YWn3wIAZ3O6# zfmIqbUQ{D0KDEctktbL#14Ss4Tt#dJ<2SI*1zpwTsJyHf&lrT?8#E<53<0`o4j-c? zUCa7J@hZ6`wclg<%#H*U5av6k1@b`1pv=;$UARSZE`6J|1SY97e$8#G|A9He)B5)L zbAwHO%=wtM&BQ>0<4aLju6k3P1t1T(ch}ErAOX3g$AD(Rf)EsP7So>O<@-A%8%_Ccvy&jTp)E8YN5)!AH z8x+aK|6N8_Q#h>V4>xLMHwk>5%e&K@csp>u`xUL^uMD__IYHFHZ?Q^!*539=Aizzk zLm_ry*jOU#@FEI9PBX)SGYQ*{?^V|NjKrA#U*&}eJH_Os9g?e~zHz=B9rFJAjI?j{ zrbz}h#J+;zWJ#`lF@W_M&~{Ty3iFO836CD6!a#gdB>g8iQ@eA1rFcpA{oE6ub(J$$ zV!=Arc%yx5edqE6WTw8yk{$1zN{$-sZsu}N~M${nqta9vu#(7@@R^?G17np?^@flFB7ZDD!;Ew8 zOqETWO?ZfYqO3}5Y_i}~P|Cxec=jnNiLcmo!T)&sAZ~9M{Iyw?PPCEGl6WnxPaOsN z`WQV_ooKQO2D}RWaK}F;oRvslHa`FPQ{WcT*smt|P-V}gtZrb|*LL*LzD?(3t*g1| zEWd?80t9_+28BHvj?N-{e2PbK$mx;;nm4RRH0NOR9ow2$zx8cjMnF-)?E1hNaghCO z$i)t44m&-=A5nm@flQBOA=XiIEX2_0s6+7+Eylid5S`hxPzIR)jG9VI*FZ&#mS48q zkylhp8%_)QWwx8!L$>@X8v3RYbJs#*zk}G1h>a&MKJl+=J%hD0e>p> zwkLtlN`RM2BInmrmM8nY9e7XL#KJu5+%`Z!j$i_gBs2}%zAGXhCX&=rk(@<26@1La z|EMTccXSWOF_hmR4Mdv(u*kx&RB#5Ok<33rlK}GS`5y_1kK-(O3=(EKzWnu-C+jB9 zPiUXN4F;p0S>>m@Np8*|`RJgMr-xMkt zDfJhHW^1W|Q68{-j=^sFD_dv3}!lYt{DciF;*E~qKgLz(Ky-S=GMU?^y289HaDyAG0In`Jb z6W=L?p_MeX<9lK&}zios^OxWcJ3bt=CZK3Z(3VBztny9SfTL~6K`3;aZ=4qKiCM*{W21G?iohAV%R^ z#W1C?Q;y$vnEwW>I$e2_Jmm{oEJ-ZTfZ33%#-abPcQ!#KlSY|!A-W-d0o)jRt(tSe zXNxJWZN-MWk5;tKpNrysj&s2&g1{=@DJGn`V-0yj9wXPr1f@fq&O-0)UqxfP72w49 zT9CB8gfMtZ_alz|jZyShS}h&BaB0uC)T#nob|bOKMh_B7)=g%_Z>dxGMF~{Rn^8AC zSsC~bd!-4L&yB|s5FbH3_#^2Cftn^z5%Vn!@pNKyW)7$ z+uU#tRzmVslD|Wen$_FM>Hz2kPa;T%TkM;&>(`ly8+P4s56Zaw;!)$0Q>2{A%)zz` zR&uSOZ-{=>zdE$wC$e)f#M`S5UxS}~_r=%pdh(3EF;!m>0@lO5aTCn0{q?pvCCumu z9Ldg>M1@!qn&096o-p@zzg^R#6<2N}l{Y+0rt`+GI`c-;6z{!a8KrIZ#e8A!c&aQfp!1*c={f7(q@Ab zQCVW{YnN7I&;Mlsm?uf8pZ8e)^0tojo-25|Z~Ksa(+z2*@-BMb+4Jw=EWr7P2oGS( zF!-m7dToBH_%UhhAo`E6Kk=#JO(MBPbL zomBM_^#bMyJHL-@ZYzRdX4RLuDlzp^1iGP%WDCc7ecSR#5GLBhOeSKMI}Be;Q1fgS zkD=I(#w0>_QPGWYn#JSW>6d4>skPC4bD{-<(KqBPZ%uO-M0P|`gAD_JE#P@DcHsVk zZMC_3P*UkA-nVGw7$>;8yncDBn(7k)IYVp34#Z)j&n5C-7YnLpp!Sw z;$MVcc*uBc9^#$?CZ#v#*hxbZR&uDzv{s6}e&CO28|2s)6av!2UGHj@{09aWKDb5& z1hG$E=E`(vKnGZiT{qu6&8t&g>;EPe=pfu$Gkep(Jelasgphdsh@~MiYmaoPGpYblEsrmtszJ&9B1z zbb0SE{etsYA=)(f|2FQ=8k~(U@!BxX{FLASPGz0&{@0uBt?=vNG6)Yf z-J0L}FJ#a;(%;QC-b|574)6GH63h9X`yo&9T7B7kqM47IMWS`PkU%Z!RAWx~(5EqC zPW4?lVtAX9z*{N6be^d%$$nKf;^G;5CcH>Qnn7ppl}?&%3R-{EvKw&E zSAZ(%Ppa2N14jq?1@8@ufF85wGI6pf;nPmphCD z)vBe97vn<3l=T#o7NAu)gWcTNAq#8kc&=zx8C%c@#mkWtqMo^Y#DaENs+fIIhp3#pbiWZQ6J z!Q7c($GFV1HT8wcCK65#yV^g9m60T4|B|L_COt>qFMtY)EK6#cPP$aMu;@>G>7ND9 znDup8y`Qf5IDR1Ac)@PLfeM(SAacqGjtuR7=tsOSiw zLBR;<78`h4w-nd8OELb@5$>}TQA!jyj!8|ksmvHTJ*_w=u5goXOblDGayB}5*DJph zFU(dST0ptyfr?$*&*u*O)eB2R*l=Zs{kosHTicT;i=@y82W}Av#t-;%)=l~eW$GTl z$D7PsIHce`r9x5QvitaD1zPJ>*u`wk1I{B>zFcB)El6mt{}GHw`|YGS^J9)2tU zeA3GkT_z%Rd%W<#2Xz)MDMk1A=<{U-TZ64-W0u@In0qnpXjoX#w8)7FEyz+(Wd8Dp znStqJ8l-EE!ed-fHJ%#!K7a27C4>l+DOWYsLG*(`^&?CQVt$M-1g4;2q{W&Vju6h^I%7QOJ*Nd zfY$rf^=GyP!ChP{B%sdsX%Lrji!+}KiU|m5Y;MLwu&x?i5JTKOrW>};BQ_Df6>eYH ze<0Rdo8W->f^U_FL|4k483bsphA^hCn~8dnKt-l4f6KkAd_G3mevRS(RNgN zL2u3*Y-$dlreypQ4_onR-%W9&pEnVW1xVl;J=nrB{zI1CBte7Cre08$MDJ#y={Xuzp%d0X?)xoCq_g(nEv!fE<+RnuCxls?nw?|hAJYq)gIt+vVdW{SP$)#gk?AiBsG5Y;ME>}fB4n+i@ zUEmPp&m$8+M4QQ-`E~~-8PGJyILKsnpr0A-?2d@B(>9zgNcuhq7i|xc2BZ5Ez3vcw zFhllQtJQM+0q?IV(puUl`U;%-+NX`3^u0Nhhlsl2kyLz7vSc8-4`coKZH{N5P0Q{h zwaNBPb4Es^p)cG`xjel8C%3l{xkKz`wTdiTVg$-qrZqJ^eZ4eU7!kI`Nh{wA+Kxdq zz&MAS7}%X;-t;er4$lN-nAB)4tfoI=1pN`IN-z1%)y3Q(3)MJYFV;8`i0VF9z*Q5K zSwvmk@(sE2u*E)pWXjO4?K?GdME$6IyPD!SpTIk967@P=#tc>!*Og*mdwyWJk*Pt){x=&Mt z3wQA9t#0|rC37nx3C7kLrG-ZY_9I~8E3K-?Xqm@n(-b1gJ-tK=?p#5XgCmkcf}|zX z;Ltx(Z@0RUvE`z$Ltw_IqH6lV^-eMlq(Gvn(Fe2wN8HK#zfS(ieNf%To8|j_eYX06 z0TSL8#1*Emz#-hw2^JxOc@H#=q@n-F>D}?IhvyPS_H0Hi7ku7HK8dWQ9?#D~s`{1i z)7n3{^Ro(gi&&kM@NbIdun3bHQNKvkNXn*pl`1jnh^Fh-KkSgQm1qBjdOgaieYN%$ zqfd)GL-D=1`|W*{!epzqP~3K1ZSuqKheAaw5PmK(rVazKAsyd$r+#=RT5kd|y@j{_ zz4BGKzy?i8p6d7cu=^J`0*o8oBPs zncWn@+SaBq>h!-~VeilSI3Hi0Xf)%fR#NK->bV75-g{T{-Aas?%oF}?_s!qo*b2{z1D%OTyKDo~L7h~H=$$O#%A?%)N{_IVl!i5Z3(ALj?FwPQP0SbzL zxEBw1EbB8LFQz^<`2FgQJZ7Ra{5G-ANX(1?nI9V3U%lQ2_q-WQ>b6WGE?N-lem9wq zpv)fKxPw_n>DrRH9H2SDW2J;93TYf1*r&R2K?gjo1xBNC66AzpM{r^0a0t0N6riCu zcRWSwE9KJmJ@5nI*1Uq@?dJeO6UalTn1WXRm`~ukX)8H*w3;^c>m!kK1I%dj>EQOi zTa`}JVKBCX;vv?e7%OK8=b-0aZD&sc(Qu&RvwCLVX1E3|1n9@Xu0FW~m&Ia1dsIOm zfWsTS9?zZkbrN`*@D2a{_v1zrm8`dghh@1YQ#Y$Fgs#bpUkRoNRvJZeIkmlO%$&R& zLH7g8sZ9TPTv|5^r2C^J?&MF5&#yavFZ=0&E({g=J)=)>YFH(IJ0sNCh)VDPe3^2i zF8CfKwjVkCU;kRGa(SpW9=O|kP5c8xco9Beh%rA5^ozdSxMjN-{k)_4?Kt^R2%#PE zhL8)7x&xr-7?JO~!%r5HpBl+6Y#g@^)X8s7#j9j`kHR`nyVHHEN`7m8J3VEQU&+i} zuu6){71Pwyn>j_!)0U_m=R7egXktp(jf?0MT|3oMtfY4)&depr$D}xUcx6W0hH5KZM7;BB0t-}~ zkdZypceC!yy5-e~2qk?iBS-4L|S>g#8=E-fI;0@MIe+Q>YTQD2nkUJK0?_g+^jXVY@Hk50x8br}6*A zN9OsX4*rz7mm#1whvPF~MYo)R+&K#2aIb>5_kYJg%ba+J#ouZp(e6sBXyzDQWL~J4 zv7x4jlWDQ)2j!Rl!G9X&`jAA#*o=0om#gncV+~4k=M-TrFNmy>I}<5>9Rxpxs5!sB z`w&z;XbyjKK@$(joAK%9DF6D3>^aMtd~H41D;qlkq$)+UvGp&T%$o*RAGE`?WjpaC zFRQG3!r~6t@Q{lx;f~VL+f!FJlsIM@%_K_dGOhP@FQG}imo+W@NGK&OiUG1i;|?~;gf5c``37{4b=N*ks^pQ4%5 z4yzqEvGjQ-o@*dioD>pp85heKI5yrOXhdo~eG~yGN?O6TZRSH~I475U$=LElm9A0h z_MY?CVqQ&0C<+U@=-eU|G-B3Qs3Pi58UFdcwUp(i!va?2|#m^C1(YJ?Yx! zr&c!K%Fwm~Iu;&tK4{qitvh1ArR9>kFndhVpQT@dtWQPjW`DJ<9%xi%oc#6NG@)L# z3TlD}%G1pSXm~#h;0aHReXt8j=DXNyxipR zTXD-9Q=EP&;_y(rVn$A{+G%b?6{gs6mbp!3{$xd$Ex>XCWq^>!{37RLQ@WZ6G(paB zuy%@;F2$KAkYs3{PH4L%PpO24#OS*W{fR6u`XC)t(^d3GnrR80rWB;vq%88Yv`J*> zCkEFZ1?N)n*Rr{PoLM8{)`|7Jd-&^z{0{+r_q^pq@GqIO_;B&;leV*To~p^hE2L{ zolTg0{8XQlawhQ6i!b!MGy?*T2$^C$JtyDih`xQEND9gbz*{L2XSDNo-i)6m;p0jX zMQC(CHawvYHX#0PdRspNA;HVefzJ{r#Eq@^|;B&s8F? z945{1`uJz&gP3H{0MPU@t2$bVzJBMe^{Q+z#XRMER!qKBayi4&i`D-7KRfXn1IRgg z=RSerI-B|mo9(N?Hpq3>weaS_A810VQURppe}g|~tlciC3|Olu7t`Az1E7`t%!sye zq_nA;vFO@G}3YCIhCqq_hSmJ7PI`vZi#h5=T*RM(?ZxDl|eMf)k3b(4*U-{(8tMAZDbR^fHB30Ccg}7RCO<)RPKn+V>vLjfm#VnO|{Tf zNlkPP1c{{e@m&1bU3S_?*nm)qPa9HCxtjI9xwonX!MwXjhVWFqJzy>G0h2Q0nYbqB&fi!#`O1vw9)Caap7{cu zcEzfU#BUtFyC149ee1jA+AIC@KyTBfS)k^QA6xrlrwcDqo1Nj?jAbFWw2b}J(@*o) zC?MXYSq>okMK4zZ@>o3FE*)}>4evlaAnZe_2<@V10zf1^xU)A}#2>{+IMa3t(b+o8d#bZ;d7zx=mEuyKsKq@Af!mlhM@CBPiLQr7*fJeK@XW^N{)8lF(dhSy{h^L}jspbC5dgy~%FP`~7 zx#TOD#Md(M&O-~HZ|i=twXS_h2LN=hrC)mzd6im?l4C++i|XhJbupQsnvTu1e_2Mk zfw4El9l#fOd&Jp?pVDe++!c#X=GmrkG1Tu`6djroqE{f}o(jPoF+{)w${X*9P%?D! z)T7CP`aAK`Nr62fB!{!1U>%}u?kUC>`3s#0B$I!Ol+}J4DI9;@yKpbBLxmC6tXH#3 z{ZDti^kF6b^J`Ha-48h=}bhoXdDeJJI z8JaGWn{DK;OqX*4TXA`9KZ43hpVpu2jB}a%H4=>OyGLk@{=L=B{M##|Z^T{4Jb|2b z4Jy+!ov^%+g^x@7Plo*}HhEv$j5Hj%U-ta8*AWyRWOwn3V8J5c4_BVY_9SY@7)I`> z%~BHc4I&B$Pnf=vtx6ttUO#;)<4Yiz@0z0YH^H1@efw*}fvPiyKSw;uBU>bp;PNXH z%5BQ}!|;&T^5xiVuDcyvmhW3M&!u)Xu2+G2qOFKIxNnK>t7uH}ci%l|0CET2Lrv@4 z&0UgGbg+yY;90{P2eG!X^DaV|7kojRz3L}pCazJwsaevQ^5%{W+^}D)CWN04Qpj1# zf3U9lL?9`i)@} zF{;NCf^vB6x<9Z@yN=p^xY{%K5?pT@gst!!ldjy`fqUe{%%D4Cn7`J7G$T?{{z+oB zny(&1D&OwgafdJd#oQz-cqO~yJCs(oZZ;L1>F{LVGd+W{C#9?Y}-LkC1_WB`QcFh5DtJubuj-4;~|| zH0qkf#|*?}($J1Z6D^5@$n%#kb2zUP7er6L!nLP_c=YIM>@(Z=+K?rRs=K8r#JY^Z zZ^wO)&|u7%pQy7eWpzEv)_SxI>Qs!bQ#}im0p2V)KY{8om|?|l%0`sqcl7>Y zF-mnIU8+lSJ=W%2<_r4*id4xH~Dv0q#-RCwVoOh&LzMhHaX zC|GJTCN_z*`{yv4Sf!)038Y5{ytxyma%&7&`n`RQ4|oj@VVaN2Dt)` z0uV%AWWM#@l~457#{7LDeh3Gu^?BxGi9@0{A^&$NdrZH*J&KQK2=XF$74eV# zdt$}&aHWoLl)U&WzkAD4{@>lcUI1)i!t;$rYy5b$h8CF@b0ESLC2D7IXx|sSJRTa4IZ0k!B-Qx*LGZTqB~4zSfr~}bO3F{4Xw&12Sa(zf6XrcbJH`X! z!^^&|SZrcZ2%w2Ye^uEcov=A`g-t zX8gCL6tW`tXWBpQtUYzGl)>R6^@&QAyLnu{F-Qko)(pTE%SrAv7)~SDL~XF8Hjn%S z%$l0jo%(7(e3Mdzk$_+ws0`#*T<{ zP6sSLr-SNA_VH^1HvjoD1xs*M0w!Ih)hN031j6KGV=iXHgJ9BFoU>V=>*yN) z+neB`u3cvs|4c0-Xr=8M_*M6RwC0NLs5#_+FMURLonrw!oKk)Xhr-JLek%Fwbvw7f zCht0+4=dAYf6!@uA2&(5H}`U+%eNKhsqRh)y|pC3N|W*`Lrm3caOMubGN%Y{vjgE^ zL8-x*X#CJUasXNXml(bx{KFfZCj?K5@l6SBD_vBMK`i8o48sx3V{Al<1EMN-$$Wj& zF^8C;=AYOIqX>CE4^vg2cQBquoR0<4$enw?QtDSMUyC%8X4z^ec49S+&05K4=g)zK zU`LP{b41g%J-A_q5?U9UK89)GoS{E5Td=s9E}!+x8Q{*&y=6pDQ6%Y1Kz%iVq6Ve-jd+kL;f7rx3$h&%${y{qBQ=+QU(&IZtvOS^N1`oo7 zIqQ%nv#~d;?MH*(lChQHyaahIPpb#+gTBDWE4uiH(hgl}cn4xxq=XJ!YVbc=EIwh! z8nn8bz5DV3(Q?tGmQNJ|Kd^LBG`8*Fz~4=A?C=4Ei^v9klZmkSqgNXJ6dDMY4&3cx{8_NQ-YEoGzf_X zH=veZ%UTmj$SrfR8jSqsqA|9Fh^_H+IbR8eMd_ zkc&xlblz{grUv~NH(?fi4pwE&x@b~v<}6am4HXe3raCcjf7Ym!HaPD62GP}%ZbOen zaj~C=Hna%Rs&MpvV#WDst?X;YLp;W~WwCLB%XK#)7XuN=k;N`}&F;pHvhWVk`}K;^ zL#yG^3G>>fB0+FjckTDdz1%jW!CKSbTipxA?7k*Z2VUetQ~14~Y3jgVjn*ZPcC2hM`#KJ#5mSzcy+TBLv1* z)QFalx=`E?{PMMM8~I=V(1}(shB@w;Ym3MzsLi2MXgrDjyf!EtzjeuP zgXg{I3P|TC{0RH57?W-=iU%Bu6JK>Ok1`D-H=0Q;Js14`k(+EL2YqrBcqCRvjDrU4 z`o_YZ6nx*Lr>%(q5-=M6(f9S(u75Ke3CI~{oRf#-(x2~+>+x*$(S{;NBFCNldw* zB{BDR7rFVx=o?3xH~8=Y@4U&xWYXP--WFcBG|0TQb`Y472YW`xqZGy7hT@VSSfA`L zejrWCU&tpt)XLDg%_<|^X@cnGr!&}au-iy<&&t>SV>KlI8Ifk)%WJbrRsdNUks{sc zk^nd!MS~vPds}g7ShxC+Td&g`{;gk^w`3eRZOZh{500AvtRw|_jjdhcgq@mAiR&eP z?WS(Bv*sr6RLF|?utSkZ;r+}i;=DrM+!s^hZQrIPvKukAxL9ZgfMMR++mtbv#r?~$ zQsnpTd-ed@oKQ3^n|??4Gi!7}pWw6Q$p(fcQ4W$X&)dSq>E`Nt@t?F;+eOg^R{l-x zkRFrh5vZajuH}1!D90GS7TV2zzXOqX(Pr8Z4Dk}e4L!^S^QofcZS}j62Rbv=0E~yQ zr>|ELC5J2UL+j*`K!_vQvDMoGJ(rur)O#g_+uEU4ZzvvNEt+T_c)ry}v_{5?PfOS( zb#Z_OySnH|gf-L}9s3x^!euk(?D}iCsxwzYb5ir9b$n{cX`U_oHDfVLDg?6>n0cgA z`p$(AXjW(d{Y1`sL8V04(Ovem$@Bh0-u?Q0hG<0{kLRo;K&~w_j!p&@L;vpeq`dJw z*0tVUGEXW`I1&?oB5IdZMAdkS3vt@f$@uu6Rm$rOt$4J-J(-n z2)>sqL1gmiM`hCa{5pi9EdMUsUr+0>4~4jI7wIgpb5&fQ>zJhlTlpMA(_wyce9=J4 zr}#$x$e`suc9@7G^r%>RO8uby|A@i$&2LWcNRUp2;vx+BB$WFqY6-4`{mwv#CZ(Cb!fpd>qodDIutT_+5sDK0RdnK*It6U}+C; zPj&B${_jZjBc>3~I#5A<5wbR+~<`jmFUsv33Kslx@`p zS5RSsx={~#`wyBG5E~Lvg`W%SrNN7ht|tDDKfeQ7 zR6_Yz(M-9`aiM6TB3{|#j)aw5rv*ZDr+U1ajpy0(Aks!8@JS{Jdbbsq^9oU0gfQpq zbP4P{jgd1SJYi+qbv1=x-)Ej=@mg6B5IAMW%eW67!a7VUMMc}i_xYZQ5rpDOc|`||^F-FGvE}H%5o$96YHoOSWkfY-h4cQ>KA_m8K_qJ$4-7& zA7oZX=r3n($X#k9Z2$mSXXQm(1|GIw-K;Cz>`Y$LZP)5UjC2^ZU*S@8Wx}+fkz7<> zar2?AYW$?G2AuGeZt%aIgZSTNcr8-7*T2UAy|iG^JJauSPnK2%ngxFj6S1dnb)JT^ zie56I1-eBdio;)#c^QZuCc7m)v#LfDfI>ou}#Wr@&Ko{@5jyWdkrb zpm2k>k~t_i^exIqfBU-sVwr5(tNhf^$8xqV*l zlFDMd7jCXwI_kjHHC$6QZd|D7C3cuUKxnu%ZEPoFhAgOtSnr(Jn>A|iE79R)2NaB3 zor@IWee{QbP2ll-pnLn&f&D!E{uQZ$ICnM!-k%M?SK^kqU??d3APR5Y&cx*W+U{`q zOBnjxXBpgTSwYD*T%#{WN@tY?c7wf;82EjZ!S4eeZdbswpEbJ69LNc*bASf^F+HcV z_l4=j+mxX}@Wbrsx!rh$EQqp$r0Jbc7if!1%C3_dPRcFf9zgV^!mP0 z&4|*42iY)6i}J08xoO2|qkB%h1!;w4_#8(PJUDQ(Wg8=zt_rgQ*!J1R^=6Rp>gUXq z)P<}NJ~bgM<0iKMaYmFBkViQqq+>23&=e*S_Kw1l_h<9Q&hARUH03+#$znN#Uwu2o zYxyAuwm2O-{q*L91kYKj>+OyLX8ywv6ODQDR85oXp$xkdfWkAV{ljBkH6|d-C^Y>t`qzJDUdzje-wyknnm?}Rk|*( zMRkm4XfsJ{@Pd+qN1asN_s`(Z*ltP|-;81r8R#W9tvQ{tn22c&Ka0JiG(6FdVwozr zr=I5~^csP?bPBl`ZYPP*WQB@tpgAG1?Eng#tw%m zW&f;1A7$~0^BQgzzEPGOVGiq50?9+u={+WsBCeYL6a@pgs4Th}FLf62REQOr<4<~x#U;L73=(C34ri|x$?UBFQ(M}`NRAQETLyIn_4VxnJq#?<+-DZ3g; zv&z#875{RDIjEXvU+^Xp+7EGyr~)V+i(|%gXOt&JKU2uRvrY7lZ@g{04WXM0re6D) zLGr8{7xd_F^*Svz_I!vQfQjT8&t%C=hTR*lUSJ4mESlUR*`VN`A%H=|m_GodaYF$| zpG1ic@m(h?aCPNMR!Tog?RSMriq#*RLxFN2m&+Au- z?cd?Apym{fDAOvBXcxZ`ag~BQ+U}ZZJO+}{2wkZ6%MnK{;Ih1apUTB zQDDnwi{xECr90{$16gp6p@HsYS|@o!1Hl8mpE7Av$*dwmvmZ^Yrs}@tafc&cBbZ^o z>&CtNWnGv5pbJrp^j*BmUfSJq^mtLaDHK)~BAf%+pbT@e818W+SN{0>X3C`Yoc zH@)85ZeIZbqx42u)9O);9OVsj&JcgR%zH${iSk0ci-HlbD$RWtWUk&rx5#Q}mw)A^ zXqI4`4>drh4#p@+1g4;A0LCIcwkUQeV8EF3o>*H`>}xZP$fKS!!|Jln9l1?fNb?U` z=n-bZuOYyS7XY)@azAA^M35!VakE`=bHceSo#PM zZpO%8mKaOP&WU!jlQtpxeFBMO`hWM2;tsIal~%dYdaS|Pz5a^9@iRVk!qWB@#Vwc^ zlcyRDW&N@`h~{TLTtNCU(ZXc%4Whl$Z9=I?cC5I)K2m-Fyd-4aeq) zcZJFRn^_5Q)$@hC5T853HZsY^$tX`ttwdsO>`=tlRuvaN(vRYO_gfX*;H0^nG#5AL zT&PKD4m>X-K4RQ6vX{2h{zW|mEwoyUr+h~@xj93hwksNc&x_;+I--uLj&7=aM=9F* z@p+VlLW@!iDkkOKf8JF!WZxc;M>&5Z|AuK|R2RpbdZ6Inmz&6=77G1^xOK9vHN)WW zPIi^ssD$5nZVqiJk^Rd>zAAP8WL9BK5xbqg#qQ1@L0G7xFZKEY>L7L9IFE&h8i^|%nxsTBsB5-81=EjCMa%M zza@%GvZMX&M0cocHa!&l zW0-~ENmrlvBSneF{)%n4=KMVJ+jtA?8IJOLd+kRw;IiFJ7;fgxW z9+xa7N&QE^@&D}=&EI#>*PS-sl-n$y?r9{uKUF*odT6@d5p(iEcE3896N~iPL^*H0 z%zm8YGJcS9BHX&`I^6U*L=%2LiqKSOF6Y*gju({}{wo8PXFj=&8xabxId@*8NBonk z!cP;*jIe=CFh8#keSX}=LCW(Ja%J#ZeGHX03~8S(UXZU%xe7~iz-bFFcbcC!VO#pA z%Ob~Hz*a}xGL{GiUg3V9I}VLy7N54ot+Zi=UmMVbO$!#z{PUa~`5&s=@ISX2A4Lln z51xjx;k+9nRq0Ra+)i|g6SV*fhB+W6Gkuw@s^C7jSJe7^GBVGcN>mA$_&OPW#Kb!+bF%FdMOhVZ^%;W>|uk{{_PJ zL^jmKimTjMwt+jp6N93@{bU&_u)btq8>UXftj?|^SR+Db0sAZ9e1(nV8F}`^Te&RY zwg%5|<{MwJ$n}b`>~T4IpFYgD&Qx$uD1UJVJrmcnC{hRUajGZI*PQZN8r>ZxMkA zib2Qf2GdYF)^h)QAC(FAsaPH2rqofwuxfcU*oKJb(gxxOhS(7`9cAQdoSxtTJRx82 z1=ijLWOiL>};5>c9e+?P0_udBu16H;6Kaj?#4#Msry83qz*nF@v}qT z0BzEAf)F*xr4mR);&K2=e9p*1^h#m!(B(ic{=E{HG$atIrQH{8dr-ANQ&aYKHieV> zQCtZ==*vP`>8Q}0E&aX?H#*Sk<-A5L&ho2fbqHvxj|hCB(EC?DdeQ+Iq*=+l$W@gi;8$@k z`8?m5SV$l@#E~JnR~H#^hcOPg-x7)>al5uKrMZES3UF&H|NE|OjQ`e~MY}~f8&QF; zk-RS7z$`N_bGX)5E+x~e%19Rti59ysrxfc1af{S1 zC^7T+S2g?)!wHfN8~`tTy3|cSQYv{Xs7da42J2Dp_LTW)DX8|og&x+0;Jc=>xMex^ z4LRVy#ucU)CVDnc&>-~*Sa=LVI}$A8!=LuUmd2Sz?n6`FRFFGYMegg>&d$ZWkIm5^ z)tZ2#$IvlHF7*E_~zy5(P@ET3wVFbrQ?l zR|=e(Jl5XPqtxOtAc!ux68a{3YDJ&y(94hZTRIgMjhNm{f)*;0qhAIolyrbW6Yn@4 zknP!2qiY1~@_wAim3Y_sWVsN*#8JP`|Ha`ak4#z#Uczw{_TyRoMvwiIfA}G9YVzeT zCV692%GGy$q#7|s9WNxPtKO^yJLG~{w45X|x_E_JBhi36Qj!$AP5wu3rGn%|my!DK zlY+=?%8UK3&+}}&M#nP;#kA``4^>_AYwxWZqHQ}xzXg*yxd>XHwGbrUsEhnvX)x_Y zZ;`1zw(Kx&Fz&kvk+f<^%HaTDd$L05In5{{j@ZaD9g8U%`1iI|ouu5I8$_uJ9ei5p z4Y&YiBHx@+v1(Xk2}h;`BJwl@w5yB;-qMlquMh*BTivW_@)fL1Uh}(MNDg%X<83WN zE%>trA4sP2|HIkp2W3je1G|#onA`UehT98eG0I0aI_&-elp>45#}1uF(Qx3qUzd6M7ZlAOK?BtT%137=X}Zso(Bx4wA<+1J(-m0-gS<_}derywt4HdDrYaz4E&Vy+7?e60_Z!Ux$Z z@g+NubM(Cm=HjKF1Ga0_Vulu?XmoM?;=;~<@@br)L{t(azRr7A_oqN_`e2y%{&?9F7tC~%UH3BCq1@06^$ws0`g|pEy_dsn>xd^ zYK$ajg4u*E0XpCd6^H0jHbS-}FHWcr)Gt=7u=Z16J7J5bQ+3;2;zsg4licP%y7q|N zmu8}a{Qtbnk2d*9?hYpz%Pwi|iN^${z;*$jSBOua`OH7ZLr%XWkXAk3w2%7F(xdP0 ztA+iAbxZ(N;LzsxdosqR*#Xbg^i=gb5e_eOQ4ghb{HJvlV#)WuOu;``HO*XJ1`u1I zf+#o7^;eY)JZQ1R-EOVwc*beY#S1zi8Bji)JQR@%`!ZXW#80x`T{a(i;8E4d;ioSpR^$;bzuAg&b0|Ys0$-d#9IBa(V6(guWMkSd=|m?n~*g6?FfUH zu>My&ITAR$#nnH&`(~~O@YcjZsXfoDaUn%z3QJW`i&VKsp_1~L#e=^yt#>73mjkMY z1@b%BEVP&`5Xmnx%1%{Xe$$r2D!gsvX+sQCO2UgZQh9F4!U}P4#C-B-ggS!-$<{uC z91C`@v)`0FB48NFT(16p*|+;}BqV>h*T-DXh>f!*qL z2K;`f$=(QAO)#(MaY?4iMLg{lKPW7!G0!Yr){cnuE^|F^8@<*;d-SF7|!)GX;&j!0?#4= z0)_h#Ti$q0Mmz65f^RDDZVvKCD5XsM@kCkoDS;zn?&2d}fti@YoIrQ%mFc+MKg`yR z-Ux^n%53usEPzgyrUzy%I^M~ve_p0;d~nN9dmk?~@gYC|hJlhli1sRjXI>@{r8n z2O(QaT+}b91ewZArgoSVp5LI{WLC5E&bPT1H8o2n8;2n;frTC2-96ovA@hRkf(_?l zel^|QpE@@7jl*Z|?jGEAxZglr`T-?VV>xTn!Ti#Q!=hKF=JbstnVG?4B0&PW1QAt+i0mh%w&ntciK- zyz|-N83;{(CmfvLkjpG_Z5%GMQ;9mmC>46*@h>HHqwci|rEkO8(G41Qzp5v%vg|CE zju*WDH#r#5@}}sE%<-|={hGputyDgn>%61PvK(#S@UGHP9D7VfPZ@4M#%*dy1ITjH zZTU2dRJo94aF{ac@!@A;&xc&`yE7y>r)4BaB-y^2 z`9iH13mQs}`JLz3AW6C0Eum3IEBM;0TgS)gMdlg! zao;C(vhto&DwZBuzC(n)kVkfHd&QNHyQpAfLSW-0${0#wQqQa?XL4-gY*Hy#@#l?d z?in1#LAMmT&0-s+KZ-GC-)t}5Idqd2x4quaKR$xZMzP&Qr3sgb)Bj3qsP(A0sx1pT z4N+J}K`B5B-#N1Qmz26um?mz5PXj86zzE%(>%0Avy74J>aftXY`$bW~?wYiBW!PzQ za9_4W~^HxvqbQDX6gK{5UJp;2*w zWm*HnY+e*Ljj_RqIDii%<3e;iu^XBdQxgpgN3U{-ijaHPHJ?J1Azt>wN!v%ULNH_U z2>0h}wDl>npdZxcsnqKRwzF&`>eoG=o_@!u^k5t*laLO^=IVqD4%>Vu$dJG8plDyR zndc>x>CPtmw$Li8VJ$7pJnk@66Db%QyQJdtW-nJ8Af@gwOM9NnsI^X&bpT4uUtOM` ztI&1eoR(2eK@zOb_%NDL$MQ8dNOaLaPNF^2;PZ7eDs7A0u$l)>j;AkRA^7OIvQ21d z%fhN?=(9{F3*I;Q(T%Fby@NrmwKPg%o8W1Og;omqU#_#gSew?@)*yhM>4h#T%--SI zCUqs7j3}M@LkOI`H23lUvH%kIugL~05R$dqA_GoQsC*Zi%jXua@b_jGMawBrLuD$> zysEydOw(!8B{q4`Ipw#Y*4r)Y$jjS2Rxq0?&t0}?J9}>281?};Sr(1GCrg)xGfaC0 z7mF&P@W%wp^D7%V*e3mB8XH0S67|>;adQ9tGUcymM??Q#;0$`$rOE^`D#7O~d8rUhpD$0yGe!FCmr#GWSorAPj|b+#H6!r@%M3uGD0!6IPgYgu;lODf zRXvv^NahG121Oj;Q#slztgqB|tq*?RcM>}zNA;hGi8{DU(rkgC_@}8M@(l6=zuTQ711q<$m^mC^2TOPcZCjqAJLMzr9 z0N1GdF2gd2)iG%Ve!M(0H=28efQ#ll$?CPqNq`>mWCt%(8$Vk|pju>flnRMGvje6U zAroJjQz-?Gah?CG)f&H;apXEOZk!98J6#tv0W+T1fGL25Qy;H^X@*n%zuFppvXC}J zHIw!Y%*WwT$eMe>v2+GesVqBW;3|oMM`^|?vt*gLbt6bN=;656b+r9>%}hS9k}@QD z5gUITbVl&Y;lgBSg4qJetpzZ<<_xDW1%&1h>WMnwj_aydc~fNU{3a!tL`;14FSJo# z{!VP;a@?kwr#jCKouwKC$5EK_$obV${0w9TvH}lKbJQoXU>aFOwj{O{)&;zakaalj zK9lk!om7eGpF%^4vD!$(TzE~Vmc`IxkO5jDhNdiFZ~O`|yYbyPD4^|d;lsyq^Qxxu z1NrC<+wc=L^~c3WkUb9YyC_+}T3=Xg&qJf4q0?0I!qLLvnQ$NXrNqp6oFl!kkrbLtk~e zA!P=Az?@`87SsTL2j(R<1&=SET3U0jVWgz&n)A)-^eFswDEb3gzCz%bT>)$IZQuwvpe{6T{gO*@J}u&5 zcDg;b@R2O=^@Ru26lmdW6L3<=AXD?J^ur9hm#o(!^85*|mn_nBuxy&3o;|NeyiI=X z0^%g^{IrV(j)=JC{Wn7px%+BkkJ?kASLFgd#&GPxfRkc`{q;O1aP{;@wA~rjmOd($ zrmcEjB`3Sd+h^Kjg7!7zKo3noCBLTqS56YzkB7esXRaQnh(u1Eu8wE*g1fd32?9_C z_9UerzlWS$-rS!#m^BR1Om{N9CKkupRY2}-BTe4m7Tz7@ATRN>C{W!B?f-@&;%YM& zH8y`9+__MB;%n29U^=;++JrO1D=_Hqs_P61fE3$ZR3$xO<7ngcN*EYIa}$TgOvkCTOr1Mitg zBP@{Ls&$TrYOM?G!o|F|qD&=#_$HjCf)#Ew+$hOB7u0kceq&q+Jc)7}c5z7SF^n*1bY+ zd+f^j`}H6LCS>Qyfc^oX8LxNIS5NZuI`)<|iwxJxqyu|dTaVD!RHTXnIzEBzeeE5C zg`Y#Mo?=Aunrd3-R*EEF1ahmyLuk)O#i{Kvse3Bq@Z+<(d#vN(;Lq-utn@t5w?=CZ zS!xgI_?xzl4Yz{n1^Q=Z+3xR8w8wdoje|_duU95iktFS zEA$&z1*KSV!GShhL#`rnAr!Z7kiLkMd6rSw64}Nc`%gkCY_&Bj>o-ySF$@Pbs9Y7QZ+IV&OM^^1Y~KX~wJ)x-^7%I^-eg661lp zquDsK$Gqlj$q)JzSKTV(x-`+)b180MkRf)g!;2|K$l^W2U!FwS^*b2|!k`Oi{~7@u&sekXTHTE|7gz}kqU`&iby+%f;hu-D+9XP@6i zY(KzE9H9cg<}Epn;nPdR19Cek>90gaK4`2b3g#uI(Y+Ricg&{FD8 z5Zbsq*k#}uXT!k%zM$Jest6$#|GTojpgnei(`kDq!u`uS4&y)BC1_qaQ{Dy5NJs^x zOZLp=&udCwd^x*>VLAS~OX@lKpU(7<@(a|a@tdD>(8q{foAXYs zNyH5x9$RmZY8_Wp2m144u0AFXFi9|;-~n?O3&%uh0MrG6eoh&)p>38JX!PMWn>AK> zX9WXO2GvlIDvW?Li_?JFr;cD19F;|4GKQWN8@(P>)Y?okh4Q=~qPGF=mw6|XY5mm; zZvei)Ix2G&xekzgY|E~q)Vza@X&n?%D?hLK)tr19I+SI|lbeM-?Q{ODi8BytANt=$QSrg~S0l{xr z$)eo^>)8DL9;>yg6pim9bz_gvof_D=NHnS-Xv+=h+Uu>FEK#bm`ip`<&gp=GwXLV< zJA!14N3E^7nnRIB$DZJO%Kg{7Zay4L8_TpqW^4RPdn+C=f4S%t;o%puI|)2Ffxq@i zIzwoc8DI~X{dw0Gcy3X3_msv9a&3pIzaV3+7`=7* z#sS5k=EkwNR4KX8EU0V;cl^Y3RE~X!5N;P%W{Q?`hM_krI6G~Pyku#^c6stV`?*os&nfkM0Nk}|*^bTbE;LJZ;r zyN~?ss~)h(VQ)?2-7e4B3(83$nNNo=Y`t>Z1;!+q>r?Ez9K?VUTXg#v90AsgNjo^P zV<4mGkMb-kw5(C>_i4FPfRTvm)w{&*1dOge>l5$7^^IlQ9Rn*7B#-9&PYM?h86PT9 zS1&42CU3GaXU77MH==9%&R-be=DoTcnJ1WF1MFN?7?AS^d*Vfk0oD_1t zxn&YkmVoXZp?9c6vO|=tTF;yf;iLI%V8LcnQiOXs4@jckn$!WG`q5pfs0v1_O^fo( z;C#Ap987V!xM|HFu)rD)Xfr9;JJ}MZ_Pi`yqUZ$!SXakE*F7bGyKhY-pjZ4VsQa0+ zrrgm!wwA{`n;VdCLJ$a-b{@uOKUAKUn*)uJoTXSLjDhl-woo4=-d|`;N?eN$bcE;~a z!3w<@eZ$YyH)&(xh*Qab#2wE&1;^``d9>uKjq?#9^Y&ROk&hs|NfStsCNW^%0wInV zgKfcn-gK;tm~w=V^tSVeMzr=jwtO(Nw5HZ+CoWJxlY#0^2y>8e7=L_n6POQ|Kv;pViq#s(Fn*Rky z8d8MiPT$yBJD)|z`I*zt<8Lbag+*9b?{oNVY%pMnNrYnU-&@wj+Eu{pk=M#b*wYkx zk({Q z#w;-da1>!w@Dv^kmt;-Zl>r#Vb7aj$)OO~E*ls+5;cwr0SpM#$30HdX1tSi$>;+Gv z2(l;ZwPf1tvj*}8y;fv%hn6r7ysMe=Fbwcb@(|ouUO2!wRxOFexA9hHD9wZSe;a3| z1EiIlUQ4}qYn1G>DB8sCVj+`G92~CG2qMK?z1CkWv`fdEeh};T7Hm*+oK>wP zFl-%FWE}1fM#Cv_5E{N0YHe#0H6`<$l*#_c!h4H8;q0of=1n_f4|W-{r$E`KSyn4!DJa6wB_hu$iwSmz(PWs zM?V>$>Ya8Y6;m0;Zn6*uq#naCbvmDbFhmOr1QrM?MR_+KTAp!g__B-9vE?S<|mE`D3U8xd+0bF{z5{E#c$a#%4= zTtz%)(~|5JE{yp})@cL3`Eu2Pslhr;96_`1cajNzs1H-g(#XovR?6Zj-#gA~Y^NEA zIdLG6zk1DHiwpNyA0D)4C)}vvV%O|%Q zY`gZE8;xF*IQg~Nn@&3~hUiQ_rs14s3mIZ$xeGiGD6{^HB^2(z zBrxC{ANO&`=1r>wwm7J70GLQtP1DU%(XCTE;~jYs)1s!F*du-Vk`zi4=j<7jR%UkE z^0#<;6ppl}Cqz@=$aofBJ1fEXeBpn3+&pO71N4p%3$$9Oa#RFrFJ@?+1E_%1Uh)xq z`5o=ALux74k1{HAX53N874Oxr=ux3{Lw^lA1{Up*N4;|FcB;^h&7a5Sdw8TR!mh2Z}g$pG1UJP+;ed!8=uzD8ymgA zb`~tl7yp@JkV5~+uo=Eg5Zi>{7DVmFNW$~+$feMIMZ0U-$sEKc~h|IG* z=C67Y;(pZ#;a@gVhQhb|ZU>b-CtR*kw0=KXfE-{b_?!0l?$@_wTr{F3_>_-^#f;uB zO+BYq#}5xn^-gz)){q+EVuF8&{Njvc|3qsc$ALIGrs>M=1{2Y;3*@Y`xFV4JmY!<=BvWl}`wP%f43#jqvJsBM{?!VIN0)n|GBSLJaVY-%ARP;B-ARlj}5`?YW!K;iNC9`m_nqu9C0RVVSG;R~d?GkZ{`lb|ny8!I zx(qeLZ>H`Xx)$Jl&b(6Rxm=6Gy9SnEKh zdN5w7<|^qG?%^%kkg=m#mS{>RyXfwg?ubwKmRN-3lAy$&qjJueEh^Ccg~dO<*L{*A z-8S$%Iw5!fZU0)D=k;yt&+Qp!evJp)trX?E)jPNATVG$Fn*Sf4I!^prtWT3;279A} z5Pbo$?C?Y!V`<=heZt-9z{-*P%3GRH-GMmxpVn_34Z=q2zau36`@t9cm9xOt{KcRL z6FE!tMuqEp0M(Jmx9=1J+l&^S<0;wkj8O75;9p81o>21$gI9y{STz4S{<;E+r6Q^d{afT z3X2qcB$^btB9%AYMl{l{{v=oZ2~bU@PcQ|{=NVk*jx0Jr=5Hj7+(H8nko{v3<1AJ|;OD6RhHBpIgEPj@2QimptYWj?^GvGqkB3hbbcuuUj!|PQg+`tu z*2?*6^-r4USKt2@;2!;4UE;>@V!Y;)=f;1Sz?B+8t=0}&9Wir=cKako4ew!DwM zt$)jpbTew({llmPYi_v8PR2Zlm3!ESiN0%RIlQyC$RYP* zhh^(MD!V1U41|}7x1vxjE_N;n+x8eqxMwl=qBA*_|F(3Ml;~Gz_J&!S9JUzo6F?JJ z!O4nfH;T*%Kt~bHbSo^I9h)4G0`I<$jnyqSp0%$Z|I3bfHK|Z)1p{o~ zPZ6fgTv3o?zDBeL5!tN84D~a%@!_96uvrtYx-c$DH%O;}7vqK1Qx`cnb0!Tv_5Iz~$s+bX=Txb=RnJKyW}a&-XhH^021u} z@u1`ujfk=U9bg{NwWxZ5aJIvTJN)|HQ1%$7njvjoYjz=}Nx{T9e7B*akCii&F&jT$ z%l16Q+NdG@qTX?#^b%2yJUifNjWFzaUW+}Wnn!zw^Ibqv>_6~_zoNwc4_HK;iyVD+sU=_f3O5@-^^kc)xR{=`O zPSTE+d6C(lH{CP8=3TuSgBF5v3{V=^5T>_BS`q&)KdkH~79$+qC)~b>@|EIicb=H> zFN|F82-n^zc~*hz@yE^TI2)N83br;(mw-vciXoL;iQtsPhNuizoeOHv()7|A=kvu) zX_SjKP{tVcCFNyiiKAR1*Tlmuga1r9kr5=DJqvnQmYZU2-*Wl~sKSy3zzS7!JIqy7B}Y>bgcw||efu!7c$HI~oZPZ}uy3&wd-=@5zsAK1S) z0nX6Xx6x19AhO1|X9lGPfLkx8)mdBY@R@XV!C={!)hU$Lp+3=$Ji~WWdN*mzggroyoMn_>syHXoXDQ@BL;{j8 z%C)PgJH1CdjUbNL2>uz9bvgB%4v|z z2wn3olgRz=2~ZQb&xS(?ff}(hYaeh1Szt0Cv|HRo=xxMrN;J*g$+!=90x6M1* z_HB5^oY1X$EmmJBPbbBmo4^=Y$9n?>K97e9XU)=<$Bu2LT9XHY^&8pQ$wOZsA89_t zRK<$n0X^FFcJ>841R1vY>_a!oL#N9hZ`(8r{=2ZsqaemVZR8!+AKbS?>MSudks_>N zS5o_>Vii%cDWg>U{sNZ1-m&FZy>&(-?AA|PAn&O`Fph;8eRjS3yIL-IqdZiE%(z^nxoLZv*Sza!$>W5Cz8jXz_N5A3h> zZPbIYA^vG<)s7W@;Tu$jex*mR5v|w0tdKY2qIsr$?-R|Ioku(jK2Xm5p0ZdDGB19& z9XNm<$iz==Yh;UFt&q-LfDe^(sNLw)Hv3AO?ww5#lluuGTt>ZXi(~T#`0D3|V22!c zm@?l-KEJd7PbOr6?6t46^%JoQo}mj@3R0r1E(dqU5<0pmg9B}$LG2D#_JZwdQ^Kym zWq<1sd$Tt)_LOCbDN-^yeB{JR(&215OD%(oZ9hn{t=5rGT!?cl=1>U!wImBx^i{fS z@su#kX{%0CqERcJ|8D>K+(rF%;Kru~8H+0#wpbguXwr5Pe(g2}7vAC-r19?Sv_U%C z#cY~g7`@MVIIV|=6*)dSM29r~r$M-K1f1TX{{*1~#uosykldz}A@1z#B2N4iDFk+L z=;+3@1aIt>j7y1@zN*FAgp^};yh>*>S_ZLrsx$kk_WWh{!$$L)*HK>5Gxn$->Y>|k z9q2%S2rQ>Bbr#uy{m7tj-^TR;1VKV;0%|wRcIVx;1kjOyKKp>ODy|56kMX`JHqE}h zkXVSCmmiTMe4l<{0cp|xVlYfeAV~#K3hFaIr&5ACBF8AnV+JmOCxaw6tGoVkKJ&T=XcL9r~-G;11U$aRo1byVr46 zjA#hJ=sBcJ3G$gG-)hs-i|@#Vhg(tarbH^w6{%j>3R>D#6xA8k@m$z7X0f%Jyu*6NP7JCB7;jQ^gmJ>Q zoycObBT#4B<$23bXfW_Jal(b%IPv6$0-JwRd!o&8GW6|F2^c9FC8ppWQc@h#H$DxqD%G7HiqbK^_N;hBSV@LgImP z(%6rfI~eI3?$U@O>Qi<+`|)prKseU@5rPu&K}h?F--u^eJbMw5VAJmDpCgn1Kis5T z+)HlYd~0$f+*U9U<%SQHnC}^IfCT{r+wu)=fuB zhUhwZWRhJT$qkxxX&~UXWg!DSa7?C!(-FN5oKmV`l}VBLmYchOpWundYNE{`z>R>O zn!|;+;vMRStntvjg)jr3>Hz_x=`1eR51`I!0_TK)@^>7TQtpHtcCG}^|18f49`e~& zpo(W3xrWtIFI|>O>ZdPzePuKDfL+Y0@k}fePPbbnetpYWWmJmG-drbs6lubPKG!HN zp-2_kb*MhN7@0oJq@8x*^ASj4=F58~ymi32N{ zd=lO5!CP2(OFis?M^jrKQp{p|Ol}=)!~O}A-_)*6W8?FIPDsg%n>ODj=(kXWJ&$@a z|DeV^fI$mr3(?l-WvcvR3yh$8?8$EsZ|zY*4kt*N!dpfjM}QZ|r;D>K9W5eH&fK$ef$a=oQQfvn!~2iz?JqMe-6P99?yRh~;}I5?ciPtEz4_Hh1P zCKTxXeMp_NU1IDs@YV`4WErxnHVrr4+?r2CSCT@wcs}pi%V7pZ%?oC4sSxNr8PV@t zt%ez*;(u$Q^X&Yr6oM4*)GNr%1jZnsvQPY<5`ivYsq1ik3j?H%c>hwUZvgh9uYeIvF{h1P*fb!j)y7 z{3~eAE0_&0lJGM6r0ZAn3)Z1p?rROwB*E#pTUSCSe@ts0AI;8SQO{3ir#e?p9^YS3 zCi!JFMmjxpZD3**k#LB1n6c7#@CxqHAL~_+kk8xgFsxEu^3-MyyrK-B*~BXkJ4iWF zw=*w=Lto_#I8@z;Ch=bb{s&L0%$Vj$pkdW21r^bl;fHVTcJkd ziq7y-hF}uJ@C*_tHGxk44cXf5CN8k0)mz{h1KxIKxCyiAWa|V(f|*(0T))L_ zZEf>OOc9tC7yUSVl@zF%ruqg>j@*-0D$;EZu(}SO(*k7SD^|%IyLUkovE&34u;ds6 zz`wJ4rbPeQdG4TjsNj3G-K^2~>ab{i&rYjr9~5k2%n{DI4L&7LOGd z^%rY2@-GRD^@*n=J5#X+DEpPysWXGx=@qkelQ|D3>t?Qj8{6tM7B}-&1cuH05MPLG zmiA*E546oOZO83{MNs@sTVKjz)8gd?Oe}6UKm~@%@zDXPSs|H?`Qx63FNYZ)SL(u8 zG1eB1$dt5&m)?C*5G)`p8@|v=_n)uDiWmu)VE?NYApe4bKM=F4MMSsLLTEQjx2qci z7sZzWZ5Z+f3n1Fg;|sz?f7NIY9^fO|G7?8O$Ju>Uxl*rC8hxMjzD1wap}JT98w_D4 z{rq+%7PHn1pVr#2uOuIE*kn?rT~By%$Upb>b#Fseebwll77z$$jmaTwh-l#tZy59b zksT>wj0_js>K*QFu!ePvUm?oQAl`E$bmHENBbqTHgqg{R>bvJ}lo8y!u0)m-sTU_o zWaG|pl$q0Pin3Rq+PdU@93NB>&UGmc_5=pjlQ#+m(jfggfM9Hd(d_b> z#Yn5A>P+agWSt7!TAh4Y-bLmP5Wz_?nL=`$6y<_5!g616ca;4fY9{Y6F^Mkgo@R@w zUgm*`En7lpH0{e^ebO@4uRkNpM+P`Dho;7Pv!Yl9=oW8w>k@vVSK1fo#0ajh_ulI= z{K{ASN2?&;cy!6Vt&J`e(@_qj{8TRz)VTo0V0r$5yd1t<%qK^5XtbI3|c*D z#r~14zSuQW%#2>W=t{i8hQo&Y^jg~=En6?>uBL`kI5^MijN0K5<8JL8w^qGIGUWs7% z%T6#me+-3?t!f(ZNb>F{Tzo;L)$c8-ZN3HzRy^BIoVsWmu2MXp&!VyO;1pmefv1Q8-INGD=X4pyE zA;UnqhzB*X@Hma;5RDGDC%IJr-0%6I<<`#BxJ;(Y#OM12=4yjxvIWBiIf zjLrKjm~Viy(J_ThD9#&4^342_A}6CPJ8$ZY$@*Fu*j7PRxBDCa|fcR`|9^)&l+leVG`(iiPadND5&;ms24y z&Umm`l!%UCo&`HYFGk#7QTBrh3aF47zk*?bwEw6(Cw;K{@4p%n_KGcnFXJQ(9zrFU zKPN8V*%Xw?;!rmk?=eC}sSenM{%2iU+EHoUI%0)Iq!=jM!{(k;2QCu@kaXG9AaRF4LFS`}V&T&CcZOquNB5#Rp`0ImW(r%mX z_DPbrhL{;V3|S*b)MERKW7$&a=ey%XuW?H{ohfxhs_gn@DL*EP7j_klBnvq>gus*G z<8{)g-)zhP#syq!RookB8Kb=bllL4t6CozIc)6R+4;H5US~x(U)rXhMKTo4LLgy;w zzu77lYF#qE1)>xZ!3@7*elg#h0}qH?Im@LKwftT}T@4a$xvS{9554w4ejM)0TKu`| zbD{D?M?t5ywU2+=c6EHyB~oJpI{bgw`l_(FnqXVpAvl9;a2uQ;Aqnp85Zr?XcelZU z4Nf3PaDqDo7~FyfXK;6yGx^UwZ}(}QcJKMV?%lO&tyNXnJNJlvT_}+4-w%vET&>fj zZ44eY+%KZo*>4H2MC~Er;9Yn4ffl~)kXGSa_23B@nx{Wl*LZjn75LU=59apx3G;lD z8^La{HmqDiQ9p<3=XIF>$@SgU4{>H_7ve4DihUjoneXrIXhovV{>zx8-6fhSjdWHN zcXebG+}FcS1n(p>T^~zM8Zcpb0PF<~!(}xXo!1M-kA<+s<0dx-_`mIVr%hVDZ%(`Q z_z%>V7B(E}gYT;0KzeLpB-)sQu_r6D{B&r0}6PyQ`~Ffj4s_(ue-RZ)Le zLPJ>}mdw2&nt?I@qdi*i1PNDxHDiSXtrv$x?&#nQjiz@c0r4;|no}tj8Oa|5+5xND zvQp$TM*<#<>D5w8qEB_thjud;x%+nV&;{6dTlb|d$`!tcRVbM(#+Dm*=|7u|U~WL3 zYE4QHmg=#X|F~KrfG$)=X4;gmg9J_P)5_FdIw{V)SsF7U_-qvc3#ZW0O!K?Xi7h70 znRHlUag?jo#mL{RBOh7G7SkVTg((DaKZY$>%d&*k>I<)@|BtY)CQ?Qh%~bGm5a#x_ z|E4r2*u?0E`v_%Uv{K_SVoP)<$5bMZhYjy%$4{sWsc+^Ie&ShYj*Cza1BWDt0 z;>?z%*2A08lQgFG3ne*?d$E+KVew(ds{dFjTA3ZCbeu_u1Ld}dCwgw=gXZm4OMON% z$$Y`TFu*_HkHmcPh!zg)3_G{Uys*#W5Ab=N{;Q9>CCF;F&tDY#nt?kZ*VU?ZUKw(t2>YkfKm zszV)6ZPfnfvCf-GLf|&cJNb)9=rMx%mti<`gV8#zcvA!iPYLdIgg)*pHuwI={^MdW zs)0N_vvY&JltNtH7r1ITosf1;fzifHOG__IDVst3zyAi>6ib=wt90hzwdA0;O$fjx{C48O9FP*H;zh*jr3WGPX2_c12YR%T6%mUQArm}=xb=l4 zaBqQ|_rgB9yc@y% zZWH>e*rKd7yf(GQKNia7jwwTvWQ{aHb?Fc{IiZL7*u~#diUS&I2JNmSDxzL4*6^ zR?jBOhfcNxjSyYps6Br`8+BPLOs87uHydc4yt^Vl9t<>}1CgHoY;y*c(^>qHs;Sx- zgboeu@eI=YIDeJ965i7iaZdgY7UIT9!D94-t3q+E!n_qnaDO|zs=-OfjJQ3f+Pojk z#FtIHuOr_D^9@Z|n*m7j%dDrydri(*zEHmcrd58}l>S_fTMmi+53 zMFOJj_ntO`-T8ma+0XM>{4QsQ>Kwzd)8o=YwtsxexVCp3$Wz{r>5OyTGR$R3kU>1* z{L%R7q~xS=x9-;e)CK#iaHCB3c$5j7Szma8;L_Ma8C>2P&QXlqmO>j4URtYQb3J6; z8%9lQidt`e1F11VaG~2Qu#~ny`CtC0H55CbfU1qlrZ zz#2B6^N4Z@HWOhwYyUkGB%NmD9B90}aLph5_(?g2 zTS_>5%-tk<3DygY#67DGm)|}s%9!>ZOMXF=*tk1^$W`Lvt?#5J@xJToAr=;^PJS6S z`5P<8B;VY8lFCEe10}FBJj?wl9s0A1v$)FB!LsMBiOAJ{IoL_uF|N9YZt#nC1-wxD z)rA?)r=OX0Y?FE36{Apf^T}|)aw3+SUhsRVC@tnhbCgi=KAp_|Esn5`2>L`; z4brYljLpL(;-#pL1Cw?vh6WNdmU$ zr9{p7+<;4VO8*u_eE>{g9*$z3wQ@M642yoZ>)c$I*v8?tnC47ok(B->G2OXTZO+5jrJBawdj6MFoUrzd5X3eCPY- zJGbro?<$`${cz!;W5N+u>cS{u$l^2eO$&l$UHDY9%SnIfQV`V$QMTE zGnsJ{2jn)~9~;K~5{-B01V)!;sm0``v54|wNGY=l!92^v7vjG**X5ZB{9rZlTIjqu z#g}d~RVa|AQ#_)F2Y_b$cfa98icc=a0(}_V233anO&^&@4bnmq;0lpa>cCjsoYW_E zodF#fz_0&UeHB=W7zm_I|6t33eeAPCuJlVZ8qAe)e<(Q!wGA0IFcTZy9e*1JmPcWJ zLsdD;250jf-<)3qPgy*)6kQ$j{KXEm;@txZl~m>J^;J`$Xqn-SO%jq|p^{;pvMf*z zNzc0#wN~|ji-spLx8^u=M>DSDcKT%{&N$k;F#n1F_g`EK@9>RB!doS`_j>F=YT6Fl zekgSE$4K9RvPP$h1j$4Rf)lNp*=HxXa;n!o7C{1XM z3P*hAs2L=dwraOLrj?gw>=0i(C>F*oy5TU9kXs$080^w_Pqjc*IZFn-&h))Ro;H5| zyQkDT<-RA^AqP3dh(Eo@Uu)76Q~p;{vU6_^`Yhs;{+#@;z|zt2|7U#H{CAkU;YzT@ zZ(wGbH~$Yw!*I__ZeO)F>(v^XoZw+@;Qvn{eM-Mu#FOoCr0!#WkK2} zlkn1sP+_07qXB-QZLi74-;1GHJ!&|_hWh^_n_a=KSbB)okbDFQn{EUw4hb*Bc6!7} ztJoL#Vn7_y6yGFCus`BhUt*2QFXX!hZHwzLWJtL4N{x^)P__;UudiOR($Z9vJ;ngD zW}cT6UdHmiymuqQkBSFb0N6`p5nh!+28=C7%$koSaATuBev_5?l)O1 z03mME$hp2~HJk@)wl6_Qt&M|ARDc^{5#yDWaNUd97_PYaH?+Cy#8#6nOi2F%1Pnx0 zf|`+4XGkNd=@f2QjSE}-=U`8_=g#5-j|f`{*z+6;CZ7cA8@OSgyzOQ=WdK)K31?rN z?eZ<)cF5(3Z||X^ylur31L74efld}0Z!@Q0?C2?Pp-e%-WP;UDz7E1BKN`)P+{e%F zir~z1;&yG(!O^?!auBRs($E+Rjd9*s^FL&Y!{8y`Vpw+SUB~{=sL<`Gv@`VWykNtM zgpa^GE%a@JO7l3r*YCRx4^R`@s>6m?PU1QcL1Mbf2rqBb3#dz@DvV3>3hbqj; zPWiaRV}?QUdZP$XEHQg02X= z!&Vat(AxQ=I{iPa`TZIE$ATfbH+jXwP7cJSH{Zhc zv4pN)>uyifzLi+!?CyF8;(2#z&lPcfMGVJY2*L>|2;m$qDkt|PY_Jf;TKJmEAImFr zC@f+(!0;g!8<+_>ZIIHf}PPzvx{`e zNQ`DH9&4M+Q`T)ZI>eF4WMhvlfHF=zp>tpU5=??9_+=K^Uw45jUogr>HRf&EmPJS^ zJ7P2yZyB&e5Cw((f{ehauNm28m`9xcJOfGY2hn&eusDh+fCUZ*%xv#ot4=L1w+xAD z=PnE5WX%vkJs3x)5tQlGEdXT-g9J}g##a3e5 zsy<{r(vL(LOIe{~;p)b_4;KY}bILBdBxhHrgDa?zh(?Qh?DVFL7-Od8;*$-U4z|Et zWdQWp;%PmJuf)8*F{Vk(Djg!&OHanG1Cgv%^WiVe27MZZ(pYv0n!W|ZhQG0Z@Biu; zBY6kNC{e6D3*8yf6vP}bRC!D&wRQ&WruShMczp;Wp~>a)f`?$b7!)?ESOu2^l~{;c zo~6*KWO$V^UCc=12HzB%-vBcDyzKq3Y9qTne{7xPbbCD*r<_s7Trg5#sQ$64${>>h zV2o`dlj??<7*G~Ua&q}a?aa^IQ_z7cyHrrF!9g=aI7X1~L3JS*!bAwWV_2wjZj^!y74rU&^>la{}*3le}_zz|kcZ6>uV3ld-v&em_X;AG|iC zK*lMgXA8!Va5G|Y0WF|5t~;o;=yo{E_gWHY(`fa%427sCCAtn^jbv@U^)-Y`XKc_? zQcAvOF33$s?1wa-iUtB^wvyX|Nr=5s%-7@|@HYk^6SArj-c4f|C zj$|~laQ!$JE%`BuWodg#wzB3to`^dIkdy9K{W^PaGWtmb zW#@HYT~o0+)J_;%1m{UE=j2CDnE0_R#u3Dzch|P!sWNTfJuKls4CRp4*R^-p=f6)c=dd7 zQLFVE9pt$HJWC2+lf0FN>$+C=hU&cfhx)AgMO++4ais;NaNwlALQ4()KdMECOj6O}d*bhm>WnsxiUJEPDpDitC({A&T`%29B< z&mPhLc>&@-GO|i_s^PjLxJla8j`~eq`Le~uFU_+ziCB}oC^7Fip~|hALf+7KB0m|c z+Ocq`_@4T)b4gET+rDJ5I^3GXv4b@K|lzQyIueNlo zIq?mOJvoQdZ<5g1>WLu6uM?LB2yBene;!=MoS7>{-|!F2cYNBhU;j=12^=g{SRsox zXA_f+$Fkv)?W#Y)j_A+hGX~$0HRh?C6Itg%DVIlDJ@BC>58)+7nV%tPe?87YXEt7u z^Ov*maoCr|(y_zkA!Dxbi5+rm_nvDbclX&@;{nf~c6a%2x&8oTTLSt;funO5qjnq# ztskhQIC^Z|D72~0f7cORR)}iQ2u{dgpf~E%B@UT;ZLg2jhS7d-vZLc@G)8Soit+Bv zYua^2pu7~Ceid{T{+={}UT#P5eOoN<{%uF+`HONx%uDb{$Lx-^18RJL*x_ozp}Q4@ z)YCpk-uCLDH}?Iy+H-Zt=Y!+zxkL25zoyt;?m04bi?+U?iW*_RFTDMV#sknQq8o{1#DCIM&9d#Qd->_HMXv1o>-}pzLO0G;nV+Hs)rJ98Tje|cl3QNZ+9mY+@r2a8is8jR+ zhhR!!hZ*ghCZN=)Xz&VrA2^s1UlR&)T_XclhoMD3%AxUWck5(On9tj{ib+84i%almY&`=c1jzV4(3~S79vx~mGi~UO;qnJ0Pe^nLz1=k) z)f%F(Fo=aO-|2JBSF`{Cvv157K(xFOW)_6z3x4q&aD$)t0;x~y-*aU4?=B%P?||uh zM*qBwK~1*2CHqZie)f918&vyR z^g5tm6kk(8VP8V9tV9P4OW+>KOKhWON^JA1TJokbFuI^k3-|mGMsk*i{D@{jNVdu@ zkNtU1$|&;T=SiE&#%TGyU%XZ3D8RV=3?6fgo4p!$<$g1&VtDk>~u z@7K9x&r~2}3PJBf$IOm`{8WI?`4{b~Qy0nmN3a|RKKS|ur++|{6bto|-^{Yg*0O-C ze?=RWK}EURz)tn~=D*j^>PUS=fglI(^-qn9^M)%tr;sW6BfKJvumQIzxJ= zVt@_TeuhfQgPJ-|aQ7qPbGbgkA*Y_*0WJnJ_UK?K7|aB1r&Gwu)Hh=3@`QZ|Akdld zx)I~c?c-_vqy9@HWwRswNuone0ELHGCwjAEZYIL)pS=^WFJ0nd#6uWCe~44bD+t%k z+vO%JK$ncL#wyO>u@IBD1hiJm_Rg4_uhG(y%eWvCHdjoD$=~YhlXQem)uhLSX{!?v z7M?G`F?7@Lk$Vx@@+;tgfcMiAGc8KOuf$$$qzP;n_K~Oc2@X&&`MWFd@I6B>E6_?y zdI*5ST`=ezmJU953bI!6(+AjN6?%MYV6 zy4*0GfWC$Xm=H*^BX8EpNc`Yt#YmFz?BR&!0t*K!c3kepk>{)g)kVmS5$DWj-n`<^ z?GtC=m4rSW&!%x#*2~2GBizQ8NvDF)wppYJG$Bks>7>_8WbxNW&$B-5r-H{5jk}#& zpeZDtof~fjXYKpmt2H;R+Y;sNJSKHOe(z3ku$&D%#&95+qMYK;z{^k~@2p7oj5hw` zsc=l#;Z#5`EK`atZy;=e6G(W(h``A9O?d z(;!|CuKfcTuvT9kC|nxrHx^m#DLZ#s@GnWf1$dPE1_{_U6=3X{l|fSz>~@HZY~e?8 zjNkNTbmWKb?5WNexPTWVmxR6MK-Neq^vaoD0%Q|b5Ee{PUa_(L!=cEI+y;!TOgNh# zr&zV;PsG{-QCV<0P%Ow;ln(ra^xYUfMH9%nO1k3M40ieWJUlL@rYs@BIn!#q5u>;6XaEu{&mjhr}~-MofDL&s75Xn9Jjv~gY?(Cn#?ZrjIo z<8_jAua!KLC&-4#(TIVtr_RU2ASd{j51Z3bUE_~;W-3Jbm|cQ4tzJFS@Wety^lVmG zn`22#K_u|KfEL$W$Xyxi6M$07yLaLvDgghi9q1UNeVuBYoByeHtqq5-wIMD-rvm)> z4h26$xN44&#ejzSTL!r99P?JOU zGMc8J@K<5Dw~S6PnXVoYvh!+_<^}bZ)N5J$?C`N9Ie|55>?ma2@oeY^LRa~)@dF;| zeb~bb$VWWQY8ShAx1LQ;ub#C&CqLErVDrHr4a3~vm8J691hebbE^B;95S)1L1iMG@ z5)fYJk0_`+@B@4{(o=aEUCloV6Z9;TXjsr8eg3SZ#KNSG<;`T@l~w1ZF)SA?7b@os z-LFI0EdUQAB+q29N4p^}-*!F{c3wX}m3oIl^7`Bc#7#Ft7dc;!T$hAM!ouAn9!~Ok zQ``+CmJW;5daSzb$R)Hy#+;MfWGlV}0206Zskdw$rg5VLDrP=R>O`|%Cvq@7%_o53Ng1^y; zp@^UzNo5b1BO_C|unE5zyAH^!=OT#>1^$?TSWY9M*-8s z-l?pu-wKnQpRzTva<+xV+H>`^to+L%EPXiq+?_Upr6(<1#jVRa^~pdi%Y*^YdttRh zpD{%pyDXkCV8xPc&$j?ovRTS}e%3?dxNRmStWrH!_)4f>H(Gvn=} zh27cOcS-gwrkBBm5A)ql(opx)u3mB9hTD?z-Og6g(yG>j1AR@Bu%%g|S-1U{gR(jt z|Bp>O!ml=v_op7D`v*R=uqV0A?#^;g=p|7Z+*y++0Y?N7%>fV^C&(7=+G4$2AJ(sdIn+P zdMm{J3Vg#fMoEF+AyTI^xhBMb(aas zJrf}ky^g%3xyvkxP~yHQ8v6QfcPW)5S({1n{vc8@q4m-*04JQw--1*tYs|fAO;&?G++TxHRo|`A@~B8x3Nt}hm@ISF0Tb`a0&hP=Bfqnj1yfWOyip1n{Csn!nM%4jUcXG-3H zg+4ZyyNzrRFS?(BpN=5He${$S5{4?CCcYoPLa2{UTl3y01H#%w@=94~vM%F?e z6kY&Gyb(k=FKwpCZGodmt|&K;Geh(VV1DQR*GAl^=Yu~H$Qxf%kSKyacL$Bt_yz%(c{Vb zQ^JwtBYukVXqE9^cT$@l_{jb8gW<)`EH0iwo@lE<2`q2W#k~&KF48BYvfO5MYjA!P zV9U<_EUh>HfG)IN;*V8&eQ`AFP^QMP$wk`neSTNFoX3uoR{Ay%4kK?QKa8X&u$rRv z=A()F<~iKwZ;#Dl=oT9R2CSP1%txxcK7<5&^MGGF-tD-F&mS}Uk7pvf+E`6H7lRn_ znS+frxZ8f2>ogiA(4X;h+N z+)+K2O;X5jSdv$QOAGttqcpk;;eljJ5o1}IoAhkuEAytriYDhB+Fbpx*WsxtIE$Cy z1QIS!oCxAcLJh5$dk!;Q(vAskn4DKxM)kISEJHGqMbk_m z>Y%N(P2ez?7T=}WzQMSJ%tsGRn6>94$L@~FQ9MN9t>YUd*|k-(HQb3oSVQ4+gz)8cMv<4vc>UlisY7mX_0qqJJ_b1{H5NmqTGqZ%bG~A_+6Xe$Y8G8A*K3bl; z_)@kXAr*~xHalaL45Op{^2PrqPtZ*?97nWZo=$ubfVu6K|3PU}=gpe!E3D(ivwjAU zqCn)Mb15hH-@jXuW`hV&!cOojg^Jq|F8SlcNb`i2#K_LMw5eMZ>E(Sn9GMOlF(Eiz z(BfxGpC2~ygWafSY!7Dwj##m4_Ga5we&;-$al)ey|C6}?3|(IQCT!S5dd||3$Em-h zV1`$!lyNFeF;_2bF?<(S8gd~De~&qyIQQfTwG%RfFN+o*-2qF>E6S1Xc5hF-_In(B zMVDjGE)2!DZGHlAyTDeXMB0Z6^bgA)+(zv_iXbv!*4QIx={WK&HLfUlg57Kr4BguTdQT2rQQSY zov-gstZ|vpaYm7qGrU>}g*xgdcvR>G+TI#b`L9N^Oxkk+!U zNCBqx+C+h*%=!9n24t}}n1dQuO?m@A51_~a?=y=S$wJgGwjY+*VVPx?BHj217=xR9 zWv)VQkjDexI~w^$J_yWb{^4a&aB}g6eH|={H~LLxSVA-x@5+id|yOK9bgwIrZMXpIZz}_hR60WOi6B*f*NG za}?vi*ijmV9wJ|=jTU+JSG3#qgGlRaS9}C2Unjz{<*}_IO*}dvv@pbA%hsKOD05B8 zvueIcqndnk};^b=0Gk8HX0b1OIBD+-zV81lLDOPFshx2bGmV!fjtVnJApZjSmV zu9>^+S+_(W{o6gfY+fOA=XYcirQ<^teLrt@B<9_wQ?zar6bk#?X=Vf)JN#2Ar&+23 zYu#?X7q$Xp0%@V2H=x&e1YO>*IX6YeRBnfvIxKwiZR|A~wNQPXbDMdD9}S!?%8--| z8W=kp$5<#t?#B2j<7W#-vVl>u|9o$&7}6^G6NR`+Al02}WgoR8va~-8=-FG7vPGZ! zM4zi$uz#ELq&K(C@l-Th9z7P|H*GAW6wvG6xS2*@_YmLiCBoJqpC|-!K>a2#rUm_T zFXu1x7p>OI$b)7dYhCL}{5=M)kjWn56#EfZBbz1u{13liglalXOW#N z70o}8DM;IKF8?w%R2Fs&F3zc0rD#st32G&cjj1q+qgZV1$@U9x|8`@$Dq7+x7qOxA z9+^1?0K#<}MTiWV7&b5UekaX;fkqeFGp`WoOl^+k1QyJkE0a0X?VtR+Vx)6Y{?Mw% zQAxgy&)X9m$TY>Fy6@G?6ukg^n7Pch4eH zPhS#wb%UsRplf5JXVia>UwvNM>;9^>6BUgXz zRg$)aP9S%9(VtR%Pze%8DBMahmtLf!2Z%`wN$M4>A?Oi`?YMnHr%&F)WVw~;EdGqZ zL-0Xb?uTL77lE&T|Ja`0WeCQ(fRAI)SrQ5KXnuGl?dr*d8gkQ@qEZjAp+_mpx|2zjmsQ+>5vHApCft;3mz(cRYa3Tr3dD5oXXISvJO%7Lxw)?3rX@@)w3Aj^dAKV35f$+BH}g-OgYhg`S`W{bOGnR0NK8gpX#9{r%Bt&P#` zCU_gmKp1%}0MCxYQ-m%EiKVs=Ni|`YS4z}`-$1Vk2~~>D=&IJVW+|`BzQyM%K6}-l zYNP%G>sJ>C@I-tc{CR{6>@`Ric=hO1TWz#$)Xv_jDHUkIe0PY1xg?7`S^=m0c$)Jr z*ojCwCBOX`Indcvo{bwrRJG5ZbC3q5}FUqF@vQRd$tMr4bfze-IyAOyx2eW%9aIL}cKyQvYxuDj#@j zv1Li1Fbr19No6+|m)`l5uV1B>VQA6P(RMvSJv+j1GjgZ5-rwD1@kF}WW8iyVJ}{x? zh}L5XOnxM#<*=L&iOpHAkTBJ(>vnxhnHd?L}t#>ZZpVBH+$UxRua1hu*OM z8D{Sx_QBQ`ekp@8RL#@k{tY*W`jbucqD@*H;fJWfraknG;zA+=GF-%IstZ5h!i_Lg z7mDGIZ&)Nu3qwA6+16^rc2%R6+O!Xl;U;;s5jCE^5)T6lB)KDL$i7@=3d32xU94pL zVOEFq#|X~qJc307T{dyrYz=>iw~!(f){}V&o4H$F%xou|npX1l2$0zFdQXY(X}YXz zL3S4c;xbDi7wDXr$S~o4#z_h$?*18SK{>Z%?&ws%c1u!-;^whrz-{-_tGZZrwq3P4 zqE^uYS@#zfi@KoOf-K=ItWUUb4SNzn6v|sEyR`3Uy75H?U|Kg_C9Yt2x?W-cK9<}S ziPR|qsb+E>=Tj>(h1sv1OYJ)aEsAIxpZD~7 z7D&LvSa<^HzBsj_^BmqXHM!z?UScc8p1I!=usHFeSA+3F{cKVk`c zjq2m}L8r;*Wb3JSqCV=IPTW+f=NT7Bfv=r92FD>wB2~42Fsc*1!q?k4&WxgT)-Szr z{Cd~-(e#20kbTdapF;5i$sWD7eAqSrCC2{=DVSKs7MuN33-->T(MITL2Fn9@Y6AoK z&XWd@VyjbD?B*rb|K|nh!rj`P>)N=o>Xt=~KS)Mt4b1D5U@j@hadM zdGBE5$6obZ2IV57X!+cjK8r0>)*RT0vP{+=jisyy;hhM-#%Y#FGIvS11HX!9+6S!% z40#K{ElWdZ5S=z>tTss^;}0MdFZ8Q^yR@WTXD=d0`y*~MISt`%F7)Z1$>13)ro9=_Q(%6nCck#S`z&!@^%qcnD-Z^#uML3^{K#Sdv+P|pS(^|HafH1 z{v0gS4R+zV(KSh+BS2}hJW}pop+}eGjY{zEZf4WU4?WI!~<)NN!8x+2R9(_OZ&^Vl8WW;Ens<^ zUqhM6VjmqOdzmW})2`cRTp^od-7l@KLL%Y5C3mnt7q?mM>?2)MQl?8$c48ey_BSEK zZ2q+!VN7<|F8`)J2ju)GY|?^w&>e_OY5H5W`)?~+8awp(FWD(X7i{=eHVa7-lNJF( za$}7#*_aft>7`_f$wBnUxU8{PGdvzib@TvpNe?M=>-m6l@RaNLiK=Cj}-N;Y@EXPI+1SM-9Ptj#~Z4rjOAght&ZH2{dyj} z24esh$!kjoZ9ht!h?Az>!lLQ;2~xmkex1gp+vCoW?e@ddi0|Y5Sz4Z-AkGSrmFaX?AWZ`aT!5V)_(+_9=3d{K?~W>k$0#Px^mP_Q-L@i&71_Tt?qU>}`)03}Tx*d;^g#^ifes4=uYj5SiqW9M=4f_^1pb}i(%uzi$>>lI>qOOj zUp@>B9+Vj!ZpZ!p+i)K@w=KBHhcH();M8Qhf8eKXBQSbAxy&PNM_XuBKoz%4*Mck$ zr1M(=xa~Rchge2PMb4v0{W7uOk?)%UnLTHR-awc1tAfdd|59FBh-?oQ-CtTycoMF53exx>zZ+iI*=CVlvyz(e|4goUqUdqlaae2s5+4U%E z23u7~)lIfv{Mw%>LacV8vV$R6oen^^~v-=v)xCX(eIHZV`14~>z>px2r~ zVxHQlHQGJI$+URWloSnq$mgf|R*cLdBv+Ex(cZlf);RC|wrD%B6M>;&r{udD&}ZLu zoJUU>cy25V&71UO-E~2}5j(T;{Q-?-@SPu6L_fk<<#tUVZBvV3V|zYn8E*SCF(;&k zqqtc+E!Sro>c+!}Y<+%yU^ptotGY8Y`%49OIA0N-VtXGQPG|3)s#;r(uj9?hj)(#o zy&C$AVD6W^mcNf*I}Txpcb>_6a^3gi_+izy{$_o3LS~Hv$@}Jv<=?QU2oEmu|55z* zYDTz@Iy#yYMUUm>*Y0QF0L@JetM*pR2$)DP0}}}%)`MXPzWSfb<{QigL=o+8u=|AR2|tOPSCk5lU# z3m<{f^S#wZkpyZGOGWyReG(h@f?_AHC5haRFuQ7?MT#Kng}GHbkqX9Mh$2_gs*7Ui zCw?EYmA{8rs4B!%@zOuxFL8d_)aq5N&;!^ZAY8u+wZ4!dmjd()DkX`Zbl<(|Ca1ND zxC`_otJ6>wVZ)MkyMIZ;sCLX@J4Cr~oDII|7u? zF`KoxU?;-nCZ;OXVv)C%Ymd8RIF{0>zzCq7aG`A{RsYlLAMpfL!r5rGK3P`LG84SCVrSw(q2ZM+%{3olliRQ2BAPca*xnv0fC=b=7CgJ@AcI@h@T zVnJbu07krh7z4-$)gx>+5p_E%4*W{2ny4VXys+ns1QW1lgko5a>B_r3gG{8%j3I_Y zx%~t|-5)V1H2`e%kU0OW5IgnWAOnMrF)euno@X#*vEL^MGSam~J`S7IhYf*BaLd za*KUU7~9SG{Ce4ubeY~-b8htJ@MiRml++2eGt}bEEU)-eu;9`>*S58oj{AD4M_6`_ zx5;k=5uywAZi-4HM+n1w(C*--e0ZxQoBXST$) zZ+tnI!Hy#@4*IGIL@xS0!){09n%P=AMV>cDX$LNDBhEqUlv5J={lZ#8FQ;^}ia;2U z2AG%++D4ML9j>;C7kuACW8?ec{JlU}DdO=M@n?;>zB4|s2@-hutUDWoke~b}JysXr z-TBTj1ac+MY*EpdZA_X*R*mEu!BImFWNd}1%&r>$d-NDPlBv6fv_lfbB95*Y;m&{%?z-k0x@1hTZe|WQ^tv{f zV22t~HGkK?j?!a;a1D|)2M;=!5>U@ zt+^ApM~fnrsYza%Rp_@`hYX$CzTH#9-To@(>--qNHt*EC!%Oae+qC3o^)upOWI;aT zRPbDljym;x6=5z7)dShZ%~`}&QC#pudO7>)8y1)3^{=glphb5TA6R=f^`5MtR&T^| zD#^5b2j}40*(aZV8dv0Y&A)4P{D8E(ko9t;af2;CwCu4Bznw81D_q`~(W|J%a&+oN zc3r{ZS2n+GoXIAHsoRk%d+D?nDk&12xgLv>mwMg=yx2oM zsV@=uJNH6=KuWbC0yK8qBmz`Rv{N+mclwKEXj5U`TiS1ofVg&g1CegCF2_%eM-C2+p? zuNKBpTCL0`iv9;PGm>DVC@~=mhnnN#%Wm5qy-S1^m|va!oec7k7)G0N;H$+MxRey$U9piIQ|c=wgLhzE;)}j zq{4gk@PR~3YOQ(0+3oyL10BS5{|T44YfTtMwt_Ecas73n=!y{Bd~Y!CMdv&Y zs>3eTcfJo;4iNum5eu7bFOFK|9xe$_$vK>vDTF zy20uWPB=t^90CLWn$W)cv5_8>#|PbD7RT$;g-0*8ny?Q;lxc$8_f`K$u%*v#|I7l`_ZcQn-#|L(oemJ{ zaFEIlzmEuf>bvfg_H$_qO-R^1*#?{$4gVoa=DEdwEz#%F{WYe~M%>ixcvH5044v^w z2KgwGBWhS%I{||D@-N_`iIXody7E&uSjuB$nOfzRfCqKb*z3)TOdpi;}9bT`r^HAqSb0uln!jWjY0prlfg11Ly$ zNS^U|-gB<^%Y2#-` zX)4Hr{uZd}kxN2pwhOPEC#=TL&L>lM5ps?4Ulc{G(L>2MkA4v{BGT&7bHV9zKn}C~ zRAWbf-yv?1kG}$D%1}E>X!&208JCaD%n%rxe!a4qG{N2 zZJyVdYp2@lPsDD_s_rzS!gb0)*~1J(Th$Pz2zFIHWJ61z&T=*Rh2h9`KMq1~au-eF zdNv4+b@i=Hc^7PKT2g7Ipwd1Hb{VMT9_DH!$n}8;l>k0!tf=6!@<341`6>eIR{N6HWoegr4o@4Ql{xUa^)EtBgt?_I!uQ7dQTo*(Sorr~`Det>>^*tgNJ3=Un^a@&l>s zEd(WS-t~J$>Rr%Pw@qglXSqnD2!*L9vX>4YXnYl?1WP$V8s|RFPoBqoU`dZV81m}| zw?+(q3iACx*$gba=+Jv(D8?wUeL_8%UrAO8NCr0*h@I(7JbCupYmq(X1>l5m73s><@7xzDWWw6%d z<|O8t=Fk4}i;4GGzcXT#`M75AOC4nntf5Gqa+GMM?zv@7G1U$wSm5p0L}}_rtAnu4 zL-wChrQM91oUGjs_qY2;^_K$fWf;TfdkHqchtapkvnc-R|9tq}Xs@o$l2-yNHdgL6 zF~jHViIeoJj;QPD^_!hFLCJY4%pUl|Q8e~GoL`y&o)uZApv)$43p*{6uwo)=( zvy}kb{J10~EG{%QGz3A_nIHPhP%imQ;;&PnPINiY$kdQ-4w&5!V`=0%2jHX!3%h(x z-1W}&w6trqso~kTBEcvRe^sj|gw39@P4J@Fjh_iRpuvU4qB;<&)gR};;(i;P;^ILK zQp#GI*b5*t#t%NNZLA!@n~Qt`+0v|5&G>XA&C zrIl>RJDu~AZ5lWo!cypC?L@)LvA3`CmRvYb_2T^A*XdROZ~W0l$e+;J-1_IO{&|NS zf@KH^yKIST|LkWu-wBt!XNpt83Dw?0346`5byvc+)95*#8`Gs@&{c z?)gef-9K~fF{=*^YF`m=#*X?-G!AKTi~$_f5l{X!d{!m1O(aBq4q_huyPR8>c=nHo z6>KR&y`i3yt~zhH2MvsDM-l&)ia3pGU)V{OA+&0(M7yz%O2i>gBCMR$3l+%iANVX? zi)(sl&wDFo`mI&}N<}MNw*EZC+VQE{#MQw0zh?gU;a(5py!Kd74$^At_AH0&=v%;v zu=PC8ZRmh4SpW~z6(|* zN*7CfswNdBr0pD`rGn)ZX)IsuUj8(^n{t3Iy~_3(%a}RhGZ)o(u7Em+YYE+$yMSVm z>S^wDz7){EvDFLr$|C;zHZhNpFi6LMfrSA0C-WAk2O0M+>HMovGb8rgWdlv|_R9Qbf9vE9e?&ww>NRFKM!i$95&EiCY<0Fx z9VnQow*DnW67CL#?ZL|`>4Jaf<%)3y;Sr1 z^TT9Qe5jSXVox^lL^pCqh?PgIA|usGECy3$T$lqWs2VD9$SC_Vz0WXFuu4xBsD?|x z<;aQZ4M>mCiAGCIfe-_mu1SC=X&l&ZD9_BCMTR-ju?72+MWZZpOnPme|MjokY+H+l zD;>YK)aIaislzUPT!3_=%7uwdkmcsT|2Pz z!1lMx70GenwL-y5QzO#)0<`hK`W2xTGb@DY-o7YQJqnk6b#lPec)Y^fRjLiNQ=1lGX#$-ty zArmynWqi5epW3)zLna4z-^Zs5!{B4kVjl}k0%G+2|zy(TzjKG+aVI&|CC`%{5CpE4e|-r56Kn>hQ1;PQW3l{?2}gm7CWKgz=Bbi?mv*NVr60% zCP8nWfkgA?nb&VomEmK{iaYh1b7w$s$^CAKL2gnBn z$0sryCoomIfTx1FB9EWlAOZuqTbTG%m6_!B%WfOuNL7%;NdGcp0em~_h4Em$pxd~d z`1bY;S+_EJ0Pq=Ba!C>W!GCigo5+!C5cAZ`XgBK$& zh89Rx<(0)8SNuX}L=&trdc=4cN6PXO^%Z&k@HRM_CbX_dSkg7>2iYVW7e&5Dfe)cL zK^W?`SaE?#;VCYyFOs)CSY=XY168J68@FSbi9o$-r7Tt5ka_jz4lOweYXi7V6>*h@N@TcMrossh!)*auy=Knjt;G_u~ zhBYGR-7OJjPYc0L*IQ7Z$8yPu3tE_ocaW9F@IUyg=n0PtgKzoq%db(7MLmJUP5Yg@ zqJ6ECJ%7XJyUxYcKuh%9utvM(l}NX@LRcaO;w{6mmKn2cv>$gk95~)Nv4{?m$c_>C z>4?@hJby`i?iVvNwVBPA!>9Opz!rl{R@4k3o?UCI`TXtk;IsEv-j|*aX1B{BXItZr zvQ3}-B1mcSf{SkVnwD(f9bE3m_Ags|(>)=^9gAB-;d2x>KS|QoFq>Yr_J>Qn zwP$=_Bjp)zbWVuq|q6d*^({SQ_cob3xJ)`TD&pi<2UO^d{y9OaV)B5gf}hU7{SO01_i~ zwKc|Xlp~|*dF`ChO5Q~h(KJ-_-*ai~w~#AAaS-;U)Zk6Po2A6eWhK}zHOytfio-Ca zwVDFQv7q6Yz(sP?o7?shDCdO;Rv*FL)Cue5=!NzCVW63@%m?UEg)6wEmin37;?Frl z9dFs(uv=?=r(3Bf1O-?f5fA`yrQrU zbLF;-sB&Pl-=3jkbMvU7em@|;4tvGd2=&`#A>VVpS;*{KDNH#Z(BGMGlHs_XN@Ts9 zUh&Y^uNSxoGLXHP`7v9`fYV;V`)SWP^rEHl&HI`7=o8*nSbq2(k#yhE!A@00Ezk4G z&t77lN;X90!0bK}I%#is_+E)zb>QPcRYl>eUDQV%b-8VX89lNbi#!iIS$w@a!BE?P z5WkR#lAK9=AS?;^fl6Zzq|a2+RIY;d0x
    >Z~$jWV*BUgP-Z`>G_)l_<`LEfAr` z@dAKrk2{no?=5!b$8FvqVSD_oz0rgezivwMrYXSm6jnC7QR;7C>5HfjS$IFWO3m}8 z_?_x3S}!Kb#y39m1G$uW%>wzJTU_<7exAeP!5Bwc9hJ_ackh5(qjZ)s?B5m568Ibv zZ0Q~mf1tdxKnqFkU$qumeEDpt+dxpnE@}xH!^nJm3G~ZVy`u(1aBSw0S4Qpca({1tnrkgS{gY{|c# zW&Q0Rp(B72nsv%WfjCy^eVQQ{JM{O z$Rc^GNz5Db(Kzn)4;qU}F9r5R(a$OvjU!lvTMEDo#qvP41Q_kPdb||@yKR5$*kqy< z6BG>!ivLE8R?5xYAWwf}Qol}f*V_YY#QCMN3#3(fZLjk#Mig7aOQqOF$){oW`l;fq zYi7Wb!dKUu7XIKs>Hf;XwhBG7iO$57YI60Q~_U>QK9P32S{+9(vf>HY3eqaRaBI`*b-VEN(ja_iA+EvWE{ z0knj_a(q1v*hesg=>h*k6G<)cBvd+9H`s5@qn-|+6<{;oz05tK{< z2vtb33Z$|YpX{_NL^K_|jwz~G#~BoUO@NirBc%}N75;(C37C$LU7SZgsI?R7iHo-M zk<#{sftU?8ic!ycx}};x)-9GZ@fN^STq z?RMxUKuE#VXi4pN+A$52zHJ3J-CQ@He%kW>rf+DNg*NVQSNupP{Gz4_N6rS5LbM;z z93;y^!sHwcgy;dT%FhpgP;xNP9io# zFdp^?$ZK4=hHATh*1N409r~OsV9oq9UT(bCazAr{Q_`tHo;GBBsmrEe(l){+f^)`+ zR5IE7^`Ftu>%a1x&_#GKiz5Va{)NxC)Oi2HfNS*0JD_g3F0KAr|L)#Avn8TA!EroD zJjs#!WPiNq_nvfIvH1G9KM_=yWOcxn?u}PJsolHt%K^e3$M*X=>K zjm=xHrP@EeoT7#5;fW*Im=W$#sTzEKaoqL9qcH-mMo3YsIo9lx4L!U7`Qykhc@ki2 zK@rj+Gp^!REwnHw0NRbVxFNJO-Bw})-KpqX+UAso5XJwTpc$*Y2#gaic4v5j$6g|a z0~Vr!tGEfiVY~bqwTPPG5sjUWS9WiQRMey)>$XVlF;O0VJ+N=pq4Nup{)_mE`(!1( zxpvI7UmraYLM4lu6MQA|hN({-3(E2_#CKO+p6XF{0t>k~Q=~2F=F8BCGIPeFTGejW zQZF1-58)j{F#LqInzz?0QCQoMUn{`yR>F*YR)$Ghx&y4Ho^9hBZ&*aTru??U-8bx` zmPhwY-|79X0H)gCy_~S?Bh1GHy}tL?^O7^c3*XI6O9cBHq8~kL#e5ir-WA8jMMMnt z9vC#fsbZ$WkLdf{CzT@^=^Zj0!gkU^gOPyYu%Bq_ENeUWQubvDmEAz7uGP>HHt#j9 z{&k@-Mb_B7ey`jyfcGG7=cCy+?LLc*DeWvy@>V4ASTf+HHR)h->qr;{doXz6A`Cm5 zi9=OA$Sx(pCeS6Mrs$v^s|_pSRPY66=)s#OKODBd^08CgJ6Kawl(Fez+p z7q`Rvyk#TGn5V}G%JXWvf!mg6evu`%1vYe65~a3`sm+hD7T>qIxjUSh_;lF%yQGL{TNpU3cexV}=Ez_ykNhdF z*w%7eHvcs_H97B>h>fV3j>4?!-$(qQ2x{?N8KL~d7x-iKGr5x@ThjOFj51Xc8gwa$ z5R{IjW@l*bFO|4Bsj7B=?Tz#CRB-&Y+7ZPPQc?>~mB za~;u4zQWAZq^gaKM)7ZdNwHFKf@QcdU1c4ItV^jix!3oq znCS$}mM4?9+sZw_KA`4~_kC^+WMPDo+xlSYu%qz<&#Udp^2v9~=j2st%)F!&FYuxi z;VkLvG6s{dCYFy0aj+%=<#U?e3GKZMLlFYk!%V&0BV5=<22 zfUZ2(YE8mf(DqLnoPwIJmf79~R;3}YI#sn) z$^pgn=T*P`vhZ2th;GsLC2vn#CrZLXQa(T;hTtSL%Gn}%UN))7CBj3syDH2FlPV@s z1lM5&t*-o&p^t(Mv<^pd!r;_$MnN<&S8F!kRhBd078Eg79{qFeUXy-IIGp^NIWct( z<1w`7i&c(!VA1z}B*azrIqFyuX&;Z7B-efPdS=o6(XeeHfIr@$4m~OBdoWt@xMwU4 zGeR^KKxG~bOfqYjTjb2RGpgHKF6ixBsc13oxOkNmv~H4Vw-wisv@-Lw_d(!}C&e$# z!5T+GO|V1zRUPa$aMyufK0QN!7{Cr`){p=0c-T?tyl7h2cw-GtZ7)o(@ZkiCE?#K$f4*q>`qk6-dk)nR0Y)y~+T%@ze1n0uF6tbW@ zVfpVb30ZRZPuqeg45h;Ilcqq%e}&DR>N#Aj7Ru>QCK3_d9@=mGAVA|_*R6W)EAN?=)fBIi6 zie#R=vPI&=I;^u0VXFUR@4=Y1$|M;5+H^Q|;j#C>MZj+1@P!)OW_aX@+$F~4m`D3| z(g^)f5&GBRqhBEcZFn9>4@;)XFv(ItD#Y$OJF zix>t7zUjW|NXB;MSK8mkUaA#dkq2f>h4XVo39ZHr>h?XUL`!91sKR9Enn6!ijRv*Y zu3#E;MrvYEDD3FviYlOIt+MEJqG`5c!#z0vc3Q1uM%eMoyn=e2-%S1S=>G%U8Ygb@ znodj8E<-H=38U)3mvr&sEHpS_JNDY&mbXe$S^6hP63*v^)s)_+=T58Jv$&?bJppdf z3T6oD5UBnc28oqsWt1faJEJj5V;Y3A7Q1)hUBB{PrS{^wWqF-v_C}4Z#Fk0l#1oiK zO6SCZJ?5B{g-gJ!b^`BBiGJ6fvEM;Z)57T;hlKJIk1bnn?U(Dc?dcr5^?69I4|7CV zZ$)G>=+AF6(1lA9osXtDCy!pUm=RMHVD#rTjy4>g*Za1GyxqD7EeCvTM#G=7llGi-FxSs;gttY!9*paL-)ax#-$-_e8x|g6h*6_hxzzkr{Mf&Gl^LzD&#+%>t|3(Jp4{gDIwq(P|tb z%OA!g(`-k=fH!7q)-aI2s*A(SOHn>bL!;Bl+|+h7l{08G6^Tnd%t*^@dBUt{VEDAg zc8U%n?eSoX8T1pL=fsy^Pt8IE5{E4#{SCXP2@(o&PFkcwtBE&B5Kp{7bMM5hS!9}AFf}S^$rHOYaU!7AmcBq zDs?<`fG2AB%da~yJ1}if3FQsISVZNI(^9uB4DO5&MfeOgzR%LmOO}e!O40dZHC@Pe zmiEjOtQgOXn7}?Aq$X^wuWBr!w*Z+#EdOcrRo;982f@sTGBCPFipA2K&sYW6demrQ zbY8)WfJwE@-=;CLK}VYRuaOh^H=n~QwzpXDY%QNDX6fCARZQ)b5<7eOWP}Az4A|~Z zvWB314VGKneby%VpVlEi^tZ#pNpn$CsJU3!HKVy4!bNYn)WItD8rHT|Xo3+UwLLJN zjdH+-Bj$`CYSU2v?+`tgPmzN!ybLUbF17bX8YKoIh|2h<+0EDq{q>>ltXu6tmL!B@tlS7qdC+d)RD6JP)jGp zoXcMmX*-`C$u|6~uG=iECY}ffYn2Ud{BHdcj*~8|$A09K+0`Qt<9m0Z2k)kwTVJsK zhBP=ls+KZ-gfzld&7j)WZo7A+EsELsA*dWGX#dlUP)_&K7~R@DOId;fu%bO4wo>XS2<+aJy60LFc|r$GpV$}JA^sLK&UK-6x`$;3D`HN0mt{%G2kIJU4?WRHz)d~v84`XhTsI_+2aq- zf4~t`>MbSIfp8H*YXx3+%|eC5PPX%a> zFs$)qI5){v805TTg%^Z+waM~4ig75=d#_eUCDt}MZ3$Zcr{zZiTj2`~YjNzegM3l$Dr z1#Xd2+O94tv?YxJb6JIKJSE`)LXMXbtC}ynuKwIIOdDj|erzTCXjEN$aP~yu**9uu zOp30H{touXRCpkBINg=veY~wswSNRp1xx%xTU(HO=$d;?kX|i|3KBEK+?B^-^XexK zQMWOFI;5^gYOGw6pQ4iW69?ar)&vwt&dkx^mcPa}jQ@l(T6@r1 zHJLO|WqZV8x zHhrk0U;_|xqqWc6V48mKu&=4G)FXU}+IDbze7_=F!*9LVe^oYFQRK`=2^5)N72M~6 znzMg=@oQNxNrq0k>Tw9Etel>2T{{Fl46}TEew=73LV%LpZ6)x=U^+=x_BS#?@$Y{g zh+7eNZkIhcBDXOgui>P(e>~b9Sy#feFn;1ixJ5k}Z1S7#^{VO5x4)99{HNJno)O0` z{h*w^5bb@nXn9pIBZ#5i+!LzosoYxOs>*nmbqGU@@xm#_qvVPntjIA7y_Pir+Id)9g&MV|op{hC-I~atT@gpcSDi8j zk}>(Ve(IPr1+ed(DVT}nju4O&d|Ow3natqkHh>WewTHue(5*3bR9OO|>!}iP=!HD6 z_1h74Y8DNr;xi0f7Qn?<#f^p%QpZwBNm57`a1@^l+p#z0l$iDDM*bgXS>Z{!Y|1}?5Z8dW8N)K zZcd%!2a#=+Bw`Mruy8}ZjnwBtTZB};W-Vltv$=xXeAaJlw zXmnZsdD+yRC7e4E-FREE(!mc~o8^N-TQ^34E z##FFJwXo`5OHiHpAkO0!W%wo?qrcY{#zItfCdvoWZ}UelWDir5t&O9_oiLMdC3_+= zkOdo4iAlCtL!Tkz5^G#cGWehQ|Eyi)e2zS7eAP zfQhPdRI&YH!~QEdlZYY%Q<;fgrFI`~?IKjNT6H1-bpRXruLvv6Yt)Cc2bQ9ctrYYh){o9LPxEmWw zf7?Pt9vpUj)y4<&xQBr2gLcX<8TC*ZnO38($A7sVS!$!t4eLfrI(Nn`((moeF~vOz2tB|EIA?^k2Upk&5#Jcscp(_ed(0ay5j?X~-Xj0|=GX#sC> zH<=^97ZsQu{$k);%E-?l)rs1`?kl+}j1->RX4n%UA`+>Z{sG{LERYU(Q@e*B8A+q^nQ_7V21k6slvO+VC^G4;-6$s}m*Xgp$4 z*qm+|_D>hK0eO>WMJr?pPV_kGzwe?GOHWHchUt?ATQQ%&3J8^vpUQ}a(8GM3C{*}V z-dtejskfAi5EoQP1q=9+=0#4h+bnvGK9QOIH=1TU%iFu5sh~SuG z)aXL=xn5NR_S1dxPU^rHEPs=`?h3F4au*rMsg)+;l7CuAU*e{`Mh|C6itzC28ra4x zGC(G)aLmP|1uV?uF9}+lq<;(<{*9$9hw5)=dv3W;Uq`}9w?azvF(uhIJ+qivodvy~ z2{|AnvyrVr(V*e0Kk8;{5p1CmPH$S`-$hzc!b4xVF$gM{pgTaL7q|Skgmd@EeYPV;>qPB^JH{BBi-Q)JtLn`5W@K0*g zdH^f6H%Eyk-uWR_2cPRgrqZ?)1Vyvf!{a(3i;VccR6aR}CxK=uHqFUq-hN>E3WhL` z&z$!BK|_URGT)GVRvd-(a($)x-kW@7_%lEKQZ#Py#&u~ZyVGfNVQ(BVzupA579?&C zZN0Yq4+HV4^J$B-VK&5y`_is^JT%N;;3`GB)#GHsBd))#vm&hV>7_G$+sHhreDIyX z?fY-{VWy>rQdQ0(;o$ombwnTqmXdfeiAHh<21WyE9wGK>P{iJa^L0Vys{Ksrt*N)EA1+_oVKqVHS#c z?+5B}4C6MAM4H z&hk>k1@GK~O{B6soYV#L%ae2Ua+PzS+H-g`C&4rWlORaE+}18)wWEXSuTt|Wy{J(M zRaxxz`CWn340t241MRsgahn))K;=bt#`B>A?&1p?k%ww{5%WaZ{2T;O!(%kr#4(^g zvH8C&Ktih`H|D14=rbb}vg^12gU4Cgc9`uujD#F%Nxk z!Ye6MCVHVgHCs2z)38gs5^n2*r-ju)%UpUCVL8a^f0HeO5Gl1s1VtATvc4v`!GvP5 z!*Eq-pk={&KSDDy8k2${X!7-g!Z*6G#@1NYbtK0NK-9XB&<{kv^{83nNK#%Av9@Lk zE{-&Bk*@%WnQ*ZuSSb0n3n(~pK2u%eQaGz z(Q-zQ{CR`EWL)Ltw)fMOK-`7Wp3lFIvB;6Gk6#Pod~0gKvZXIq^5pBwaK4n%Bk*Q9 zPG9_W1ayM>R!c{eC6g^d0P+QpnWST@V++gAg$a2OITQ%#Z&?Vgw*zqBSw#BAVED!; zS2&JWatW7?F$&)9IXG@r%G@znSa17=bgJBps{1K_hGPpIqI*!H`acY0ceqj*u7E6h zbMK&JG=T*GUvcnwfI^3dfbV70Q7eLSH_6rdU!g*B%?%6jPWa_%fqZ;*d~i9WyB1<( z%H+is66Je0!_iHac(tPy zV`viP3629*tYJ~A0LL15uxr||h7F(hh>x|a7nh{L2^Jik2D?TBf@RN#Egyk-2VqvC z1Q*d=Q{cI(}rF;rJI~OOA$mPe$q%P+w9yIAz zd;N1Ls%`Q4TcNXHkJ6Y7710y+ZXqq8max)sYb+a9MjwO`;uOyh>(C`1Pp;A+q7b6P zF;P+|<|7?TMr0X9>-Uq}qsHSbOR{Ytq=th|Akh+x724}vr{U0OZE9Vc+fn5b5@kJ&iOJ=a z>~NAp1b@S)Zv8&&TZXSuA+2Y7K}FE7vsv6*4qHJEmUA@n=GnGP`rpALZymVnepK zJ1)#EBiw+~<+WzhPp9fVyv!FA4P&#s7ATwkuB(gv6!J)9_aO8l_p+dn__mP0DCWR_ z91+|T%s#;98zZAj7Znik-jLG=3!5jLaPwO~et$CfG?aDo^EdSLE|j3574vYjUv~2M z815JXNNCc*lZEyNqIw5gR*2t9Ztl@}QeGKOA`RAlMDH+tgd#&xB=M#t##YmaQg)*o zgiC+wIWM@RfU$YRkgn|_7T_p>wxHM4%Rd)=?Dqz@y^2MO7igj}G(uL!im&$K^^3By z{)VdG@>-YcIJHGz9{bdM{y4}=CNPTVu#_g(vMDR_eO-6+<)9)5MXZu>0R(>meU9sl z3~K=(^=hyATpDGv!5S-aKNnKLRk75FH8O-zQw}vaLNDB!8dIBt$D~_OXiaDf<@MM> zoe4$tnusI5FB#C=Ha#1JAXG$QBPv2V>9~1Ets~xjH+`rBktlMC)R6w^`Ak0El#}+-Ss|2!_QypP}x&;z~CcQU=k@@{P)j!zjHG1SiDneqSI5 zKqn=97-4zj6ZCECL-^b-+@VSxoA@K8P+~9akPOfVd4I_V4rFdc$dC2OU*GV zfe_;z>a8$5#JAx|5k!09hox`2b-lC##8^e~nFgEUH0^+PyJZKje55$i!ThQ+*a_W3 zm#BwOYSM)2@6D{6`EW8_l#2>yX8d!Y7}Y`M z2!E4l89>XUV*l;!;N`k1*45Xj_Ubuv2R?1wUSh|5lBIL$gl0UQ;ewr-)U#&l+}9o4%*xx-dO)ebK*`8FwG*;CGK8t3F<(XW#g*s*6m^4cdf7}V)61v zJ;qd@CDU5%r?B_N`^Eu)-9JVJ{wcLfi$`n2h>&hqH*4OcrxmRRPc+=d3)OsyePaBl zTkB9&@e}&rwZJ#;f{3j_zi5!8iR${xFN;=wb6onx`JFQpz9I6iEbuNSl`QV>Wx9MZ zK?oKqA1T8`oG9r*)6l-tKdk>+vK+vF6*MiMipzyp9YwuLbp2}F{eIS4hPtc1f!i=WFpQbaTQJ|Ap${iAd^o5&2|HAW+{h7ZC+6tgHh zoR9vYCNM9HAZH9IyrkL-vdf``Xr4j}xdX=Vzku>oh5r`5qtkOC7WJ$t3c3 zi_K<8^~TUl_T^riv}oHCF3LGL8(AfJ7=JYqa~B-~jDZk}#2OB-HxDYv`hS|#bszSy zKIYp9sVu!_ct*1s0P}3uc!s1Q7jX|6JuC(AO$mzOTN5@*`313xUBNK@wGG@lhX_KJ zZP|OOai@q78Oxs9rzeylpWe>sxBl9TX`6pX4IA-g=0#29rkG3JxN1k0e`|dB^Z$t8 z+TBBA+5~(Q<;*Se80Db2D%%3Vl#b}6{D>;WKn2v}xdZrB*NEFF-{_*|e%`Nn0%DSn z>HpRdOHRDsT^+u-B@0PqZ0ze>a{v6j^FIwFZ7lgyB>Vv`&2B9#TVk`sVUm@DW+@-@OL(?;g!@yKlj@SzMCMk2@vs1CF!&rAW=V;#kuQGne^Ue zATe4~RtJDx#5y&I-wU6iMi#pOOnh$s5!38X1!kH6Vr@w2L-n;;Bo$YUVsy-UWVMTn zFPJD_!3h@Zn`?IV^Z=w!dFI-M8$*`2DU!p{f z_h2YPEs9lBQS8Hf&5j@}p%EM&$N8 zj`*`a+u?lN-LM6GI3m|UUNv*a*wK(v(HPn0ju=FT5N`Nhyc*>my5{b8&DWCK+QY)9 zI414m*u{N)xGBdTIUVIGx%6XdxnvYI4AS%!gcubF{Efp z;s>%vI2_PHfBp2hi+LNazUFMRI^p=QsZn0wT`jC&~>26>8J(yG^F^asnm=uMu`oj`>W7awaTZf8M))@T>aQf18Yu2+ZxE zJ{b&Znp7s^)I*)9OZ)dv*iS6br>z+K#rki=9RqPp+sp3xqdV#XS0c1nTWKFFaRFoz zO30iyeKG2S7lo@l$L7&RZtI~(j_!(S^aFDO?Dhey|Gt~@l89?F5{`PsCt#HI{nmWE z{oZ)66cg!!J?S zpXo;4*#Q&3tM+%-!SJR&rHwsm!)M>OE>*VGw&r9Aeq>N3h?LP>oQ#eL)SSYxHc$_W zFkfFA!0$3!9=I7m2}bjyu)-F87vWv>Pv9mp!1F|&@ca4^^0zsq)W8?wNAD@mSSxv% z5^YN+i^~+&K9vX;UdsS=JC4zWic>zQtgstsq*=swyX$Aa>g|G{mueSvKL@Gk5=kTO zLbJ)zd>OonHrdGqRm|L)_1`tb{~7&#LGs7A%pPG4M+X>_g#eawBh}&;d;f>4w+?FS zjk-p0DeehgyhVe%Ln%k*#TTMS)=7`>gz&8{s`;&vLxL{VatMq-FP9^&Ee8Gq&wnzaE3NhF(Gdcuf-LkUL3v+@!id$#1N1plIyjK3ZAo{JxWBs4uX!*hgT-nM75 zCF#Yk&NzZ`@G(^#t^DK-_YpfEqIy-NZ7<5Z6^jY}Is zcxk_|Qqk@rM8`zl6Nzn=^TeeFizq0$t5@4fT`YwslRPbWNPgmLw8wrQRGepSfe^Gr zxbjA9s*(X&>EW>|9$4EE5r9n-pq!W;XSRk!=)Sjjz&g3++llHzhC32lOgPX=W=cRJ z>;8nbW4y4ci^mDu7Jp-d_0_Tvi&7IKe8wmZ(bXl$G({8t=7>uZpk7z98-?v7-Z>Q#Hb3LinXF!-6Y>=jF0Zu3^lbdsOnN=u>F>7nkPE$tP-@i+hK z@kvqebzh(mG*^K0>f%R5z>k4I(=8clh};GVe1CRUkf=}`ou-pZT==kCAnRAQnRyhV zyh+*mTdLIzWt_CK&_ddiywK6{0fM>d<`mk^^fqrk=)zTd!y4HfNPfUZzQyh4Fgypf8E%3atTba)M|F9rUP-Wn!1f!FZdJ@51co!4DsQ1;~eU zMwL0e9K_sG{Hp}@!m&=mK2l)6k`u8WRU6cNU9I%HeA2L;+6{WC@a>l!;F}}#OP?xU z|LF!^>6==xBqS8h(^DbFmckEsH6&5^!2A#R*rgdTLC;ldwSpJ z$&_RDNP}99lbip+Ui4ljTlk~o=K@z2xB2>du( zf0`h9)KWx-ON|FduR)3OG=2fkze8`8yHh(SjbevrFThoaaqfe)3$F(A@iakF3(%cW z{=r|vL|4B*x4qwbti2jDqn=AYs;}#FqDdGu7ifBtr8gkdgblDs9*n6~YaW7OZE@n! zbM}T~Di=^FS3$I1FRz7IFy{3_=EbJ+MP?Mne;7u%xp|S8`*@FEs$YCo*1+7&QK^f$ z?iq|!?JZLl7!jnL*>RZRj2mQ2xqo(tkB+7~>;4pfdj>Y|uSMN@OC5Gf>prKBZ=*P| z(!cuvBvK2t+)FX4uWnn_$4)iyVSVfrR8#@Z6Wr(OfA|wtHg`$#g%T*VYhwF!>yMX< zDm#u_j5VE~{gx-L=P0VR2EsjBmm71@M_O?<{V02V@8a*r{ztFu`Tx=@d;EX&$`-Tr88@^skGjVfXk+Ba zf4`RVCUc(S2a=yK!S|61C!lw3p$XLd(wrX5#cE1K>Mfd zq70xsIA1}1iP8Ed+T`3SPdV+lexw<=-O%u)Q{Zv%MZLh^f=7qqM~%~Ez-KBi6t@pC zC!U?GkyV^axDpw!aSQ{ERYH?4-2s39+Wa7fta&K@)>SBf7=)vJ6OJ3*kd1?u?c)Db zN=KkmIGh0wXBqAQ2 z)bEALtNw)gMyEJZd?#i6C&hXuRiP0(I=<7?0mWrCaX>I88tEe%)SURD?%DW0ej%U- zoF&dRLf@;$nD08*M>_4?52SRhI!U~l%zh2MMBj5k!mop=3KvEKA)4fFi0uxmWqu>Iqe5v*!0Ub7yJ=S8NEv$;<({m{EJrK-tmW!n~}uSp;>B;^-}fbBif zjKXDC8*4K3uF0h-w#I()6tx^Fh{@7O$r5o)D&yDQgLX~E36Ph2dK>W+li^-DGoa!g z=*KLgS}kjWQJC*{*1un3KF*;E;Om&Z#v;sj2QnT$8Lc+rOlXfwq0faXOcUNvX=xSn zw<7WxRfy2V6jOAaa!7F)1FC-}=+&7kCjgxvAnJ;Q(u+K9<5veueK_i=cG5|%TrGfl1lZh0lB+o*T~yW(~5 zr%?sW2NRJVFSY~YYwN>{fj#ha)F{WF|EFBanF3ZX!JVh^PRwA~ zr#vRosc~8_{L8nEgP7utLrIHXeg&Z?P5`4ZMI>L zGhd0eE!wP%;#f+98%7cQvF9kY%&z9xTj%)LgD>%M@xt_gcC|f#Q7DNCZZ=L5=5{yH zmya-$V!JfF)EDfriV4G})c8nAjd4wa*dNwNTM>1@K7SHz|O zzO3?&fE~Xh;6?Clir0bPMR&l^SBn6x)A0SuokE|Y=1c34gXW&*p7kntqMF2_M%WBZ zX#P|Nh<93r?_#Lap0Jb`My8&5>Bc6+qM8D?2dVQQTACHz8beSF%nJh$gdR5-%Dg!; z>?{j+adqY@1-t}*tCSxG30XxNQc^n*fT9_$CFlG?#?uiGPDnLV66?5?eAO@%{CS;A zU8Z6d5rBW-EAIAbK8;)5Qq1*|aKVA19yjxJVD3qaXENR6-r^6W&g49iQU&vz22zq7 z8$ZTJFD<5_4~&ZJB6|zRdzprBCh>vRAB%KPvkqZI@3%r;z~DimjY&O2xx&TRY%j(%0mdeJM+5-g7x+B8n! z7#{EG)kr!c+uB(534d%DSsGnRTCRTrUvENwijcD3Ndt*51h_5&)>*3tMo0K-IBA5Ii; z`zPgSW-&lya$-;%7Xvq@SJ|My_G+~!hRE}6iX{Mlk|&!}-|`iuUYQs3mt92;MQ^jDz_=-qTwc_6d89gFy=;8}GC!K^iC2xVrJRg`Hhl->B!%&Jc?p*gk(9euejT zY3LHQxj(V;rnmW_CL?865^)c)TCXGXJZ6ZVL?|`Op;Vmi&@!k7`s@A!?JuKK%PuRJ zp-NbPl%m)0PGDFmW{Af?F|e*9Q-osj3HFL+%5scP=fDA=m1_3tM_c#56Ep8N{*4m{ zy<FWg~Tr)+vd?RI)(F5vfgzIo5fi8xcK9e@dgTNjN(UCjH10qEL$@VYB)|f zB3w>&ePAM_hNWIGqo07Nh``Dfw`Ch2MvQ}3kf7ng)AD)nbCL3R?PrpAG)D@$xF8z2 zHKW*{o(mGLxeP|unFfzM=V_5izkiqv=O)WLwOwu4Iki@0Sd77Ltbi&FSMKDRaZ#Oc?n;6q8cNIa2_AjUahr4EE>*VIUKz z!7kBEL+}+2_9Nrv-~~W7f%YRC2tR5IdbLhtE-N>D|L`1X5hMf!E$B2U(Lf z1lb3l#DpIxr9Yje?cfmarAU2Dm(~|Hcy@E6YP`6ZtZDLMe?cbpkB|0PMsw%EXy?Km4>kc=_`<>?a!&*6Q4vA#^#>)aWl|oSy>St)uzfNbyDo-muyN z19LUY>$p#Ryn||No6|!LIQ`W4ZY0z$?`FCdq#?qRTfL?d>6J}7AZk3x`(zSr#`{0? zKU|oy>?_1wbko22kIy4cuRng!)wTsNC5>oIMbzd!;E`?GZZA60CL`~Joz%G#2Um8Ttm>pil>T){l|C6j!S^4e zgk8A&xJM5Hf@)l)NevV4O&{9YgF0|GVJrD4K`|lpteNZ6>-f_)*Up|z&)3!|dk0dA zwxa`?C@*iGRbjzJQ)^+zOd>Cs0l99$bPDfgu4icS8*32#Np zQt#T)sijr{MAgO#!SdXD%o_0B=<7e_nFPP!s)VAnlQU=Q!N<3&HGyG;ds}8<+{YsD z%OZIvh5Gg1KXtrtxM7Zk>IKM#j(0AG)ZxrRtYh~D-x@S^Wu)k$? z->Z2057g<`J7!Qh^H$nNN5O5wPnV^!_Qz3!rAL8m6$?&Jg=grVAXBsRrF-Z6eXBv4 z=KozXcftpSV)xK|K`!qV+4fDYfz2nfs#{jhA5LD(bNoKj%8N>{1xr#8D}EZ>c}w(6 za~aSN0c{vFvKjSfoC$7_ud?a8iI`3U@;I1n%Ej?!Z;q_7Dw2C#dKvh#W_J-ysXtlS zQ>or?YbXx5faem1i>XBRbdJiZH2Sg5alD8DBvf)zF2zy9{CcyjN?#}_uXvPKt9z#+ z8o|x-K-;5~*?GJxTA>9E)?;A2px9;+MjVAM`Bhj#Tu8u!i~k^9@%pjSc5UE`e-d(E zKmBslePTKSBMwkrC@=rWP5;?pR$Z#z;gtav+D7$Sj0WxwqD;bxO-)x-o!yOaX6#*S zz%ex|67uCFB#dZcm8hlrXl#m+)ql5Y|R1fTaN*2Y!coxdDa)?3JUYQHn|W z1Cr`0Q`(E>t5E1chMC}t)l7{=^(MkJHfkH*C4M!a)`=JJAGDEe{(^=bx1e(PfKDWm+C)dBd1MK~Ni0ujd0Zgm@F1 za?&%nno82&F*EC4Q(gYN^W$H2E?0XtIx3*HDy$AwSBj%lNUp7+jRSrz4eueITm2h) zaqLhn1r4$VS@jb=qi_}P)6G_~eMt(nHnttHm2yIg`(|g`1t~oJ+-XFZ9!e+Vc>HCc z`=?#_t@(Gs7DIDy*)n=VTz58gt|UK3#!>NSz4(%mSmg$69`%6G(hwB}8*=#+!6!DU zpgc+&Iv>EfG653%Of`c4JC+!2UKP@sjIaic%*F^p;}SZ(r><+~uoQxh7MB$MI=8{vQnWF0inlNLE@YfhTi$rnOP*tN44`@dK)3RCpEi?~EK4 zT=_B#$}tEsjsf=(Ddd)R?Q!{mfrZc#%fz7I|^Q#123BaPB{T~t?+QtOZ# zv5U)F{SUm;p78Fvx9<6f!P@jI+P+R=`KCqGnlQjlFzd!j7X@C_iKYuyZmoA^Q;qwm z&MMKC06&PQ-*^K>XB+~R(xlb-F)`gv>;1AZVzODul?pkS$=}YiddsYY{UV&&-Xt>6 z&wn9RH4yC@3+9^ z6_3kMc6(v6G^5UnsDW!a?$VYmYUzz)bs0e)TW8HNGGcg^^+P>{Mr-_C{S*{ z!|_Fgf%U}8N-tJ#RvfP1VV9r*o;;w_lD)dH06rI$5!s-6i^iMg9x#=PQG zQ7r-Lm(Vc|?3}N--G5aTa^cpBA-E4GQ%p5jpMdE(jC6(1Yl}9$_-$Dsz82f;jj~S0 zxzGu#=R_%tx_B(E)usf}I0bXFOh;e~6!y%1uzr8)Rk=y#0tt;?$FgpIvn~vz!8yVX zhOV4H%ntn>OG+t#6nVDf-$t5@O=X7}oxH<3Y8k#|km_v(?rs;pFbZiHAM zF2~a~h;b7Oui)1z)xO}!yl5ZQ4cZuX3QtYYJNB!#I|8>&7ABNgpCMP_;rgPS@o^@! zBJwQBPu8zFLpVjD_!kEw~A z*iv@2!HQ_BkD?;RsPt_|dwGZJ)uF{jz?p zUL;Fkon8zP98*%&BCdP~QlUfR$vxScn=!t5PO8pxrCU6RTQf(EnzCti%^XF#15??G`;>tBN zY))bWK^_r(^35~n@n4mVv##}FOKXyvCsiEdl8eX0ThQ>qM#|st4*}icEY5I*+e>lN z7Y0zNk}voYE#?%W)aZOYT!%V(zmGTs>J~zurs@L0$mH7jjqX!1qUCRu7LBXE zOb1?WrEb85TDq7jT&Pt@_wAX-!V-;FP38KZd#xqRQXsxMa@AI}WKv|n)C`>E5w~vrXb5xpo}XX_HIvoZar-{A8J-UUF9ahC z>!Hi|ZDGBOc$Qk6;Zrhnv@XWpLz-FX z9G&}o3LKmGQ7jO7xOtJFw2yHh!<_;;Q|LBjDdiwAsKs#90zzba z^8W##%>O?C+KmU%IF@q$@UsYg-gBcRP43A(`92Tyf%Rx#p@L2P@^8bR+e@oggIG41fO|JEH+q7*C8RTx?GHCk(;V3I~7%e@kBJ5`;2vH zB~ytm%yziL0Y<+)rH?W2I*p*FIYH@FCY(xKV@-F7A7(3)m7$(Zx$AU*6)?=1t$bqz z)OtrPm{QH=3q=;k?T-HX+Mu{x!V>55#!jA`op$ClSdE@~inY`(jb5D&l%uhod@U-8R?Hr`AM~wF>Jl6umhfA*q7y&8aNn7RaKW#q|lNr0e^kTcR7mCe!f6 z{TjdbL$)T;50Uh7>UT@SdC*Jf$8!Qg-wv)%+yKKrHlTKsEioRT(ikqe9m#}XPjrEgJRMk2iCp+r~bbAuV*ILWtet!VP?mA7kIPxrk{?y}Ssg`)&w(nEWD*$-op8ocI)ZEG${5!7(TQ#4YJa06{JV z)<0=`S;@a4-&Hwodd8@BlT;6t(pNoMC1M;7#KXVQ68ICTkh;PII)izPQzh|AEG{P!@lM%1!bDxw8 zekmvZSqt&$E_qP&^?k83-#bO-<)&CQ8M=dz-U;(gp3T^f9p?AW@zs|kUT|20nl!N65m{Yozi)PZ zCO)kzFCX$-U006Y#Q493xOsP=jo_vQ$stZ*#))Ele$S)M?OE0R?V_?5#FVNupj?`X z%PqH`pHKSlcj!yC@^{#oVi;P`&HG9$NWEQNcJU7)IGa!r24xZ;Nzyimg3@-;RMb@C z=-SzhZ^Fjmm*!-Erl<_&9T5r-x=wm5a>>-J(35^(ee^tL!57pG^mmNe+QDjQO>4oa zbH_^xnPxfrm&F&aaIQ2TLMO%OOFCkg{K6iUnxF#l-6px}-bzKKO5r$!b?2wmyQVSB zbpO4ly%I?v0?=tARY6p)$T>CznFuZdZ`{62XklD=EpcS{ zisQ>9x}w97kAh%r5)K4m6$wce?a02dlJ{v&=g}>kufXahSz(3T=YlVG=dTL(&CsAc z<>SdJd=Xv8I$!!PJD-cku-H163r)+!u4tjcR6WHvIk`MlRshL#xr^Oc*%0fE9*n;P zAAg0F>Gn(7ALm4WB7p3Q6R&WccV;xxTzDyIo)j`M%Rl#sv*us5cD zrQa(>$sa~esv;>YF#XVhPj5{auB0P7>om2tl{oaavdesIKh=cwfQbDoWC&1^xYdzI={jlWQKK@kl(5~A zPaReXZwab5il=BqvP)cYLG1NSyyRteN?(>aO0}GTy#D~rY)&+Q92bE0C}3~h2K75$ zupcs4C7bc)PIdyW?OdTQ?HBzafs@GdUB(SA6XQTvCaTI$@^gLGO&HUFY?M*Vy#F-W zHA}28hzl$kY`>)xgB>5kL4|QA-%Byo@?Pb)Glu})X0$CH7_W^7lmVnW8`h@Htsfo? zu^B^Jb1R1rmC{?7+c%gwKgWw3p}}aUF3Q(d=ZlMsfhZuOa_!wS#Q8T49Cb;56GU=K zx{!SFqGFGiyrKcxC87Ud$luTGr6!?zX~?eHnN)^FhXx$d^%_Rv!cFiNGh5E^IQYYN z%za_XmDdjFjg_DyA7=l(sNzbKWAI(#KK=QT$kRch3oO}&G7uRWAup*h6f3%`zSf?B znI>b75%b!ISYS4bN1uNFvF@@*1jR}D1w}3Hke4Jd0L2VtRvo-HQ5MgJNXk04L0JOf zul%E0fK|~(YQ_fDW$#^nr^!0t5UDCT;cYpTHISLvYNVA*NmeAp4CVca=!bU5Ziks& z(!^N*>sTf6eBStc7Z=PHja2FYs;?FcC`<&1E3}|TU(a{m?HbnsG{C>0=-7ryQ24_? z(CyE$pZJkfDZ32gS50mObC3-=`c|%9>`=$+0Kc}Wd>|d0>>GrkYGETBol%H{e8Zo7 zc8ZiaY)WDOX?3*enNWnF6n(?+QZ{&7=l1KV+xp2Dgfx>i?cf+t(d!6an?Xui<-c14 zara3Z`lf#8$}n}11Q;+|j^`eSgv#xyqzl={cny0^i< z&TU(IfI7foW7!smcYb1u1r~!Q3z=aa?v7xUq5u%hz;!BdxBy*Guhm@zG3jb?{tGm> z49pCWWAx7hOl>gIB?i@ghbQOz2qVz84Ey9v)|Rp#o06LKJ4^%2ClBlPHwr03g}0N2 z+Tne&E%GdOPqiZ0k&DWPBY+9~DwWLYs`MZj5wUqNN0DrN{FA>gMs@-~vOmmn^Uv);;w_G@Q{8LU^83K3HS`)fQhBA2ki z=mgin0M-kYi0^-Ml=KR44e4l$}4HBhVGp8Gv{fLOFEtA^cYntd2Zjekdl~Bxn zBp(CTi(1E9bBp-(6WTmd+%0h)niOm9cIcSXQYB*EA3Ne$+J{Hcgy@PPOF6Ps5i#bU?|W z*}m%hQ&j(OsJ6Fjo(A78JWFBHaKlHsd~R1d_HmbUty{xjQ6R23qCS8W@M{|f7N0Jq zyl=uQe<3Z<2GV3uT(AMp8vBD+=Zr6)Gan<<`@E?AM)azvX6uR5IE6b#6I`!Wf`V#> z&TT3E%bwpjQFw}g3h>L3QD+jSwv>|9!^yNTW$n)oOE*0#`j6QZV~WdIHM{Dsd9$ap zO*2giNBGPhf<|6JZ^O=do;F2%@hp>WB;|QBV!6}{8R@9u%F89RYTw?CBf#I+G>}@T zwJ{f!7_uE-qK0o2f4ep@L)1FvtZ#yYMRfgM!tva)Lcgt&tcCIaC@y08gOCo3NwQB? zI+3M2K)P&;#nLmyX6G?}n$Y8S){s+Y*N#(E5u#>~8wZGMx!HE{yAQhni1RK9)sbI# z%f-ahgenfyfRWyuULgy`kv2?~Wc8Prvo@t|H|p z!#4+ukjf0_06OoYzTUP+*!}nL9A^nMJL)BLBBH1j)j8QUy4Jexh$epjL!vFS;-IOg zRQ(p!BFm$xyA2DuRz&QL_frXtH$gF8{Z|{aFAfARJ7t&ujFat)D5Lthtb-m4F7R)y z3f;;woX-pXhq{$G3N%AAw9NjKrC;Tyf8}uWkZgWKpJ{T@sVzudAX()l0g;(xZ#y3G zyP+5ee6h(Je*NWs@m@f;OjGZq7>%&~!}iiEQ|TzbG`T`*75<0gwbE$F*tsG?^%lrG zd9597y#Cshg~s-^d7#io{gBo0oZqf{-x_cJ5UeZb>8|eMtnWQo{4ctGT}inTW-OQ^ zDX`fLXM(Gty5sR>qT(VBzVLfBCTOCIWgqN2!vu@S-i#C0w7>!>1dCM)=}O2abgh0h z70>O^#6V1S=d-}TL6Y^WG&NFnUlBJoT}IQkA-Nd${-_q4o@U)FhgGCBRR+G=p8^fNn&?!?En(66W?V^p>}@x@$Ab zI5T3hX}Y=bXFwz2N@>)I8P_3smnErKn85~^_NuLfJI?)WcjmXO@oyQzthbtT+0zIr z92rR@yCPQK=PhO>eoUkT=|CNiFck@Iw9>e$)v{tPvHib}IW2OSXS7)Y&Khp2jYzJl)`)sDT1A=(w-;j|#3bg-x_@BlY0 zL>3v^8)M33Pd^!SuEjuDSTpj2dDLTD%~=c5f5%BgaZKGb6{Ks2oYHA^?oYH-b>QjimqW4hBu~)&%l@ zm_JkdkE2NzpIsgH|ALNI@PExxEbMr7jx>iHQe&qM1_$6aZWDg@gUcc;rC*%sBXMCV z2ur-PAO`{UZ3dF6APs$2d~DrZH!i5y^6m zRhzm0m{MG;SGP?fYw;iE|9~$xa~cbFYC;R(Kva?X)u@fU6U$Q7t0Kv&UJ=NMW9a$n zIM@2c&xo+2W#r$MQwAot1(T0)>K5mf_3G|{qymozjh#P_HN#wSY};g7JtzZm%**vA zF?_2WK~?w|X6*YE!jS;_T;=g`6J`D+hx^H~8E`|N^KgS{m!}!m*&<;x-;l5wf0C(i zOr>McmmwYT3u**`{V+O54?3M%XDdoIaQO8N$>hSPBntK?r<6RxtPKYCJ=~{cC?*Q@ zi;GCTX#%d9k>TFWz&WD7i(#D8+TzEl-GrMz&fE9a-gi8sAl!;K#bV#O@=5B`%Y4C% zoYYWf<)Mt$U-n#S+Rjm>wvBSxJL+JGwO^sAn@Q_vu;NAabgmb2boAYxdnA0j?(R?4 z#^O&ffvua!E80#lTFX!ke#LbvNllQdqRO1*68;ROwa-~M>+`T|CLUn)PG0+gF?2E?8W;+Ab$dB2`6|2N~7k4WKpOZh87px&{l0n zX1!n8#Q}d3dhWW#XO?p)*c02HY@f!E>?q`!>cbJ=AJ0H78GU2hQi%a3>=Et2Brork zk=!z>Wcp!0^r!qvJ5TY29PNmycpU0^x;+7AhKd9K6{OjTGzzE#`i4hb>|nv-zEpWX z;<&XfWZsAqX9TB=Uzl8<_X@dCX6pMY1>Kc zUH(yb)UHur7S4__O|^-sqD)e%{`|v2TX9o%kZ(EK$-A@?iz_F$43ari{_zU-=alu| zn$FkwYmWD-;p-jp-;6#C(RL*IBZuBtL9?1zw6@8AbFx`s(NS1YiQsfp9wir7phJ1B z3o{&Zhl&mIgq_kpx@wcZ`H0;ehaLtS<@8Sf44`Lt+QNB1X~2m15yW7#BI7H|wYa}X z80W&j5#ZEks~^Sr8)<4=IE;%b!P4r39h~pJ;~Hyb=9SwF)OH{u3Y~t-qWkCj`d{~aYAnW^re}rsyEKZrnz z5Szt^ziITprK ztP|Lva*`E*Jdw0f^r}3$%B|f#`Zn0Ld;{_VO(Z{!@&HG#(zn*PFu85|P2eKm(o+64 zelT}JZhJh~)!KWxMUoQQcglMia{I2&02aWHh4gS3$maS49McG%EtekI$Fg`iX)8!({u!y6OM zCeB8}k_a8N9Q1)_xu&Bb{=-+o=z*PAp)q7?S3jqRy|OPoc)QQ-#6r^2=B2^s`RYj6 z^X-Xf5KVUqC=rk{CAwarANsAr%NAfK3{XjgZm@1_lV0>n;#I}Bm(*sVnmnMKjHEwk zo3K{6Hfgx5X_IN#BCurHPE51wsoAwCmind6&@!!xq2if&eW~r<)umYb4{saANb+Dp z?h+D2|8Dz3T#=a@^j4wyLOB}}%M2#*9ghCPX3dHs^aU6PJj#)8MN>9mDT{kfuuyAJ zUg?Tyo19RnO#Tg*m0ItbGOMA_L3{i7?#(9K5gDD+fMdosrsBWT=J=HNs+iy=2lq{L zp<(u|>}}G75mbhl-v?~l&!$bNa)CkmcyiN`*`@dLyY)Exe24?yQWpjI{l1ZPBZk}J z9el|RyT$qz+imd?KCy^#-r9WFX;FTPT;mrF{=W#N)EX@s`^*zgz25%VfEs#WJ+8| z@7p0e3(!y)KT1I+45@P%X!h+tWITys<9!1Q8wt-TGbp<^HW$3XIHrM1pyBh;>XC4_ zp8sin5B>>NbVR^5?0y(s7H~@k>2Q-@YUNA%Rdj=U#|$eCJ|*HCp>KI#pN61yMr@v_ zGTdmXKu5MD!|AR>&9nD${$e0Jr^29Y-2b#Xd~D$K9xVasSa)nUm%g^{hCx%XU(bvd%50}skWj|KH)Pna%2hMJ%>Aoc}Ei3p_7()HN&^0o0hvYU2zi0`u6E<#!6$}Kw(XKaN^{*nA^2Tl}xWeI#fW^4sl@? zH!}OFZC;;NpOSM3nG&T3R#n-Km7fdHmq5j2st?XKt$|^V5C4axT8+kPX6+y}HpjOQ zu8qYG@=M4^jfiX$Du2>QeTn*Lzs_D*XRcK=zOe+BZ&5p){>}3pqbZ4-;;n&MaHe9< zX9p>T*Mw7M8pvmy^`9Ne<{uth4lc$uS=S|hgk!C3VLTlo2>k#x!LlKRemrren23dk z?0LvP@s=VC_>V26n$CD{EX<{{n&Lbx_iKvnsV<>b?y!9t+*H%|IZCPSLRtt!NmY%2 zf@Y+$VFc*uBld}yroqx-E#*ql;RWM#Rfm?@sd6%@ca819cC}RQOxgfeuDTD%Pe$#m za$v9y$szY+OTIL-?OzK_8!&W-(}?`c<6*ykiP#RZm@&tD=K zI03b~0s@rmtuLSVu-*r0>8dHckf%A-a>n)SR#1~HR=U}pM|KZ$2wQ_81 zhyWs!%@B|QFytyP-f+w*n`?jSMT)5$`YlZqw6gsL2ACGCrbKJ(jiJEkx_KB7{!WE8c<@K>!z@@ zrNG~ocP4}}V2dbOro!q`PNYtjqMP}mX^06`gb$8&3Ew$k-b(7yu{mf0SYnz|b?>EUlu{dDZsFlAi^lZ?s zZXN$Fe&9YSsVkt?R(BG=;HG%5n@HB>I4B6EwSMyaHjj68dnE3>9p@X)*V|u{;d=_Y zjP6Zd3=9m*53_=b{QUgWuFcH7w}+iJ9rHVD5S`NT;mgshoU3yx4DD)vhOUxnM;D^v zG0cP)EbAWE$7s7od6;TEBcn3leJ-{+)AJx2rH0CNe#Ufq z5H(cR)i(BN9Y(e`H!-&d9`v;~@wpu#*V&{cHo;MLC*D8I?)xD~+#`KoP|}YqO-CNs zaCqihZzz&PQ}u=+lrE7U(Uhb_+Fn=UW|^O|dlI>?FJ;}^foF9MDNep@HzB6o0%hVt zjgpYV$sWIkF>jk!+LnhySCQ62=VAY_Lfvw_}~d1AbTRQ9rSMM2w;ycW*ycl|+S(oKStQt$$MJlk zwJr=xGB#dVF+x7(=}Ct>G1m?gH@JuzSjaaCEVSjxC2K<5d0k-=9W5^o3flIQuGO z+}ffXTt0fI0Cg@fLE6tXz{}sbjLWhMGoVtBIySIb8Vyu!z&A1pXWI|f%8a%p%x;D5 z3eUQG|7zcXc-~*x)}nX$9x{jpG;~d{cS*isbw{^AIzYGa=iQ=U#P!&vu>9@I+WC1S z`O~ysw(xPX2N;)UIIqz2qqu-)8(}hwK`33&!|OCO;+hRydBf71e)=Ec%3)Y(Al$tu z6N+^C#X36#VtyfOjkhXby>(P;Y!yCRO5Z>l7t{6(@Pdu;sc&N+1+J&+%DWUTFS`SX zA-s{$;4u@ZOH`;+_rn>yHBvp%*iEl%^)|gXMXMqT8yAh86I=g0yK{`S@mKS%)#PTYPdqKZF*v5WEPy5HW}mE3q9W88si62*BGAjt-fpgJo5Q1v z%OLW8h2e?Adbi8&&_m5w-~G+Aya}t%U_BYQ-(`4DfW+-|6EjLHQsUzYe;WvKt9`fk zo$ct_A(5NrIeZYKDgeQ!9tD@IvPa3bajbDL*4oANRPy<%A+u>0~K z-xO;FFN@Ej3SrAL3XWJTM)J@^sIG_)PEmy{nJkGcrv%IDv(Ug0aN0q@pOxI4pyL~L z^0j|Aw0>{&ZvN8mIs>oTDgHL%Tz4^E{j*>;=$+srqj2T)4n>O;mu%%HigVqBOu|NP zC;%j%<_Z&hvW`*^9N5^ewHBj}oPf-K*K3yHq8KE^8bry(eb?G&3BTK?ge@VpM&IyZ z)6bzH_qf@S;hoPxEbg{WB{=jK+^RKVCWoKI_Ju|lIn+X|Wd-v%E7q;4iHX^<{hq3I z`aZ3iK6*6G>w0?QSIht`|Gp%q9+dn^b`yc|;xvDRTrz*#ij~X4jepQR7-dsME~S!TB7j0aEW`Qxi+w=ntOI&*ZVCoVuWf^ z?{`OEEp&*-_cx!ktvu;be=`rw*BHa%1u!LKtC^qnC~|m%wyT|hW8L}I1W0Gn)+2!B z-v!O{{U^&Q=N*@8AvS`4B)qy#5WGK;XU4h;_o7Z0uh3OwFv|S#;sihQmGA{(Jz>#dX*5KWvP>@fU=uP>6qT(tm(XGwYidTATm# z69rdCKzTg$1&sA7xXo63WXBFsBjkU&WB6Ijk9a}VvqjxAi*i65-UT%ig%mCfTszO~ z8-pi;k*gP&+h1irRF!sy>q?}a!Pr==O}FMvcoDrO(m}@SgkAjmzO(A!Ub+&U{P`Fs zv_8YtYvrf`&Ds_P&xQnmvrov6(``fV!(JSuT>cL&EL(*(cfH;SLE8=#{ztiS7_4gZ zY%?D;7gwa93R;LEdaT=^a<^GSYh-W~37iy%{jTYPEe$&tZ#;-wupa zN*2=CPP88wCG`2d#aHtR@kGsF9~Fn-=X}cvd!_J(*u_ATa+wvhubDwDkO54=2Ja9B^LlSP>- z!rmgt>%0oW>Xm1VYxUCU@zY?hiM$^pXT@H>gRBCGS_MFe4Et(6%@?&|xk*eFW5`}x?22-OcT zV2oM;Ylai{)G8B;pQ08!vAF!3=e2HAHwky;{7~jZx|)3Hx5nd)&vE&9Z}z8QW6(jK zY{QL>L|=g~eWANkmA5->cA0}A)^EB`$ym@%6BTx7c7|!v=fASfNUU@Dc!?RzZ#|#bm9-rBQWE(Y2#aYFenKb*cRNn$B;+6b%l*)$^DT9+ z7}pi$L5tAnU>1f-lMXV7=x0o;GX78sF@)1FKItNK_(Yt@!wS!fqO~tbLN_pLJkL6d z=7PsmK2GF8d7UlOPE5hyeYt!v+*s;(H?uK{csI-9Q}@Pwqj8~iwDOHK@nwrfyM zn#sZZKHuOT7lbnPSf7g;h>lH5uAcEDpG8W0+VE)>S5gnT{~abt%KyXETSm3jhF!uC z+_ktnMT5H(cXubaI}{I4G*BFhdufYP+=4@KDK05ap#_Tj)iX= zcBSyGRs(;27&ogsw#g^zRM%dzVQv>8*PFufM?{N z{CT$shIdi1`i8ambC9nI|I5jp6SJDq&oGFXFDKK5(+n@Gvl{Nu@^w)>DCG$Tfz z``(JY4dnuf@U`3_^tosB^b2*t7HNzoJmyk5PK(ZRGLrK&uM={k+G@1nDja>^k&_&@41p^GaczM>gTA`4Ui_{>0(N@J-tw56s}3LQvrO(d%7$Sm#iLK zLI`0RA6?$o{QKmvf%yFTN`~exffKq2GeO{IL2moyt^$2@ib%S!NeY!e|79JzmyLIB zWX7EMhPME&ERVMfe(V;BCuMvg@FLqq6~zzPA=Gw^vd+t|^TT%^N<_&cB#0wf;>|mV z#p?nSkc16xL}2QBkyG(9uG5?Qq9sm`4q@stiGvk_oo#I@2nmODVmWP*_js<_e#R~2 z$*PM?e*;|qA>yn<%7SPRqT`zY{9Hh6Ul91E!)4hX=!tNh-m+0IPtbVqNYnDgy#vuB z#uKqosQN2~DJR-1#!D69m}8&|QBS<69QB1>r<9_Ctkth{!)B)HZJ1@gFhgezmoL7; zqi6;Y?lLYXG}>)HJ#(j@C0qn=j+ped#F^rM2lHnm7gK9^*V$}bRgG^U=q*zror@I| zkt&%#cUldd286K8_vRgaLfQ}JBViKj-yma^-6!6krE9(-4aV?M8Y4>()ga%Mg^WOh zBE1t-1~ZEP=qlTyH9{(bWDvU=kz1+1mwy=7Vtl6UA6+d!B}UGp`_0fo9?s?V{`=%q zvf+h@HS2&b{<=&(VY%t$7T+)m&v((mp`OeNHgu{5a``SDA!qC~W){4C6bT#KOyxO?m*(UO1C zLZ+23Voee0UY;v-Ir`-_TxR5Zs*=};XYaSP^&LBX*6>Q7g!j>+PZz4Zh9FJh z#dw`DKoboZ8vi6bIv+YJGEy-lA1oD1rgf1DZ0(JhuKLG`n1qV;uQfn!R8C8vd zB-%J}1R$7w;@`JDO#U~;w59$u& zK;k&h4a91UY>b)XYh=nDHP)%H4^J^8W1q~XOsEA-NliIV(Uf-=MZ|})77Vv^_y=B24^(Gw$-$B@?)1YM-G{+^Db2wmTV{snW2C7<5pRU}> zT`Hf0U>xGEp8MKLCJ`-ejFJ#D}{4jZ+EL422F1_U%JhYyUd_6Hm-DRZg@0( zgchWi7Y$va_t%#f_R4HB;f!jxTe4?dXBOhy`ri$nHLC8HUoOWomlWMt+!2s1`2(#a zlw3z{TqjGDI@Vr*Y~bb$RCh9bleUA(r?4}voJUzB6cRJ@9QFW0?}dso>0$=SMf=65 z(Qhs_--_WZqop6?r}%nA?aseAR%pAWe2i+1Wwsve-~gM3Kkk?B68WYo-MN{NPTxmM zkT=}mC-v{5Zr!Rl#E~4qk1C0j=2V&Q6Yr-J1&!VRM>WEswR`yhVBwHySNce^c~*9s zG+ij(=1I5lp9kSQAi=1hV?iny4pn>ph8Ih*D$)q<&Y4kmzue7E+~;2^7&N{yGV;SUcAN#xMiVy zGD)K1I*sr9Z)KSwO~G0U`JlWWoR`Ea&2(@gdinFA`NRw^*z)MY@FHp9h&kK|PSa*> zJvHFQK{KHFaKs$=H}HMk2RL;a2Y&VIDb9zZDvEyKJCB1 z0&XZaW!E`20$WMGH$+3O9}eQ$*>)h8e*cdk3}IImCJnb5Ms&>#*ZNVP^nz||V1rP} z&(p^XAv^x4^>R4SYOjau zWTlGKc4dk(eZON8MQB)T3V?gllL1GbEetm7rg`ZvCMSMNV4=&PsuJWZM$OmXV z1IaKxcn;xJI>eL4ecb=2bNJ&B_12SRRVIaG8s7?vpFbEex(n;z_p0W~Ejon1` zcxsS(=jq{N*v?k_Z4Xt}Cm!Zu&)UhrxOM_o%>og};xOBYE)riweox_DWEUWxiy|XR zwMK3lJ0A&kuQeLEOsk~0o}Zw6E%ID^0k`&nK<4k> zlxU*-{_Wd$v>Lg=ISAT2n-ymZH$6C+Qs3*8URv~2`j(&e?l}-YpJmVob?N%?y8A)T(jytPX_4$FF^=lyD1;5g zMU(NzmX+qn`-9vWAx49|mZ1D6nm!8EbH{R)Ty^)KND69n{MSI2&${9k@J0jz@F#B* zjVC7Vm-L-Oel)V26waUL3YI~1PogJ*^JLWG ztc#P!`u(lIu#}4xhnhlQDL4NoG^CFTxrFKjWNPOzpV;C+xj@A3cedDQp&HD*Bkfd} zk?+cqD^EHptZy1Hb1xafBWjt@6}`i9rgC!{U2yp<^zC#iZo&5m@Iv2a617nyllQ&M zS;{vr6kbaS2AH{;B&*p;?j$RQ2rgiP=($|$7AT_#+i5<-lWpf_Q|`!DiR9m3A~q0O zvw@Cj9l0efcbyx-0x5Zeb%#+vQY7CgAy?W^qRX>8P;1;+0MWV{UGY}m)haXUHXBFS zL0JCnH6rIc4*ARh#yR7Kn{qu4Jj$4TRLnk$A=)B=KMD3VVrxKZ9E5O0PDD;1=a|u| z&J6{9fK?uhUJs>8{HmXstD802aXJeMnYXhFdCW{4x*dm zVo-W5xavm!T#urBB$r?h8X4Lrt4FS*L-gE-u6OxUK-VP$o&9{ojpprHMTlz=%4!D; zkS$TwQ%UX6mZttpsgF1{-5X-}Vus3|e@+awdH;#0n0@1D>ANLS~+AVVK%vw6WGi@5hp7%TKkj}H3ybTueYucu2%Ip1ybh|wP z{`vt^Bt1vXjv2q9^4Syfo1}ZzS_E+axbP9 z@OOUE8pC<#x2+W&NqF^ECosLf(rOa??$cZ{gXyoND4mXECsf3<%i!k?=W18n1^JK;7L~=s{qHkN&!m}s0nctN#?rx?(mhV2AMGv~L!3sl zzI`F9$i8HwOhvpwD=_Ia>+UF4K2Y7l-o?l6tphFn*nd<{bN&I-G&-KRmYRg+wlp4Y zYWp30;Dw37U%^p?)7J+Z=l&41noPDT2hLW;Kf%coXLJB+ewN9MeRWm!N{~9eC9~F7 z{trNMU#-@RWyvp;2%qrOKkQl0qik47(%MMH|3p{v&Tq+w+80&}Xnag1>=o4eH;9pt z0CQy$#~0_41rhKos&eC>Ly!)Z#AgDe8EO4mhxOq0xLn30$A zdS_*mLSssh*geNGFWmD`PPp>ZnBl&aiGpCc__0pLqZc_G#M>q`H~eZe>v(hA}jV)+Vv@X7qITH&tNiJ{?=SA zNw_23{kB(+4ho9vfXm~qN`^+0NCg*sUrX0>q5f|uuW#7NKbzZf4g|RtH*wk903uQ(>Da(G-#rqaz5SID<9&QG~*poA^U0~Tua1B zC}dy(q^MwO=H1npw7yX8;M_BHxbEROqFZJty$oR*-B#o3gxa>s+$8 z&9rf=jI%U}LDVDS6wxP7`40@J>%)nQo-Pi~$qjw7%G4(9k6|E5l%E~(BW_|K$OUE{ zT!odKIka}WS9bvfcs4vHklo=mJQhTP_c^^ZRG(TiMbx8j?UiiFFKQr;UTn|rc#G0< zjbQ9P2d*P?9?>AR(f3F9tu%q$Er;C6QnYUQs$u^f^I)sgi+-f8Hkzoe+f>Uer4+KK zeW&Sl?f~?^?zdlVT1Z|wyu{C$`FlgQxgWpPavS|`NNsNaTDc)DWGbOVoX%5r4$4la zebYNhAaNo0Yk}$*J#i6xILa)zQB&2YFf_z<{I3+tZju6n8~;)n>&+4KAU7cr_tfQe zt+Jc`@qo+r^$lrr+|>+Fs{OX%%TDIMhELu6yqKV?s!Ln;jyMEqsS)jd$(~<(Z;cdS>}MJ#0bSyY+W_ ze!#G^+JBTg1mR8rM(TOb*u$w9pyVA*9;l(Uuo_|e_x)I3XbqjX=vqD088^tEe`U3&F5Q`|at&cnOq2Jn^414SYF`H4a6@oytjc7M! zP%Zg3ySE7@{$m*|9HKNCT^|hYl;lmw0(d2bts$tdAhG?7;6WQFrZ70ZWsh&$=LwND zDxayX(yWFMAAJIJ=3%mHYx#LAtG&&RHq(cm0g&)Ee`vGqGR0*5dWX5_#vAF$6wLd1 z5>c%ua)d^pN@fMNr$5+_kUFNL5D8)%hGes891oJ&G{($3(;tMOXw1HoQ05slR%^)P z3~P-gz^5MmsP&XUU*67Wmy?ig}F;o|>#yK&z!tC`rZI(XI7m{6`sUTh4PNi6#+ZO59Vnd_{RK=MXc2)!M|}jHJR|ClLp1*8 zQG}IAw=k%Sa8g`r*E-5&(#(z~4s%K&ZYg|qs2id{WC6&nCSOFE!q1IQW5;r98{3bX zK*_1FzMWX;Tds&KrlM7QhmPO5MY0b%r8*ZlkAZxCw^!;!CCD?;=p^CYh;|!#7aS6N z(@=->QbR8lupahMdPtZVvJe)ma@6EEO6mTKisVwEwx@W>fd23`@f>6vaVnl>cM3>h zAmPRK{xI|tS{cQIc&kRmaLzom&BgssyCZokSbHi<%t-pd)KWM^*~s=ZQ}mRik*FOt zw{%-|3H%x7K))i@%WFFR>AtP5Uydvy?oON`B7ZRAe#|4}&U|r3$|?z2t3N5d2`C-W?R-u%|*?h^6# zc`KAqEj2h!bYa0YZ?LgHmzQAbPf`Kk>30K1@n?!Z*58S&Yv7ja`)+r*<69_=oHPGO z5hR|riC8yu=O*wXg4|nI;GH1I&%#-*F`XMa{kx=_xCWvl3}CPZAE#% zpCR2@IPek+v#Pdfj{Ad3sQ$-cgvt)z`m%$J)`-PHD^~I|CmASRj-}p8R9Gdw}XKn9_f^1m$nOA4xQ=G{H5CuW zydZR$LR38Z_yT22|6p zUQKc&Au>vhnSYl*?46k7q}lU{0YRFgg=x4Ghi_F@#Q)CyOr{X#IE)xspJ9!@AZihc zK*AsWwDm}Cfl(sFXtJaxB1+PeqMXpSAxs-elli+6O-=&=q*kBgU)0;zf$X8~J2n1Y z18(hb0aqhO8yh z#xW(WCmPZ)@0U{hT?5N_@a$D+B)F-^Ct9f2a9I<7*&fm=dfJ4$^-(5okU7XhKr9%H6jCvrK7qb7(u>2OHrr}5FD%lRS zD5pLd@^JUk5ZQ~q7VBQ3#@0KvO43hQNBwR199B`mz7=s*KkRn}tTqgR)(vH(D5hwt;mvvjQM8G{mX))`3qJZp&-*pn;F$D9cPsTus@XQT`}JW#8d5R)oIk!f)Au#FnoB z5vv*_`17iHYHc-TH=o%EGHhDtUDxXt^{A2Laq13@@XW+~FXx+()qm!eL&dgG+3QmkmbH;g03$sw z!LYsqBxw)Nmv&Kv-KOJx*+1`S?|z}m<-4bV*nya2<_OE}I8m+O5seYTG!$Q}Ab^CqZrez(9FTYw))T zpStUmnWOaJ93{J_4Y0)x<>86Q&%6I8B{}cA@ZS|-gz}8wuxw$PgGIhVd*uI0HRMZ& z&`Zo(96y~<7tb-baC-u7$jp<_OrKFkHpw^qM?FGpzfBk)@95!8a@`mrkE+Hb`Z83B$j9-!4Mg}Xo^zWv9Iwq(f#TB*1s#*ztHBATbq~qO#+_G zx&x0Uf{t$m^)ZXCWqvrL{*1uCml%h%$Wu38dHEXAIFPG0c2GZfm+?}~{E6JyIwWkd zCLYnik-nuvYfvCEL{2H<8SfuZt>@B_ny%*7;{>sOfClIxABlx)h@tY$smj8DC_I5_ z{203DHIqj_kZMCpOXf~0VPwlhF<(-6iTtto8TFWm><(mx-4>!e3~v~m+9K?^@5G8k zLro5r0nF%mR8AWM_lUUWLNRkfPM;%JNy<3T`28kj5hi}~qZv-pS1Q*ifCMkaEVANB zQf0-(o`OusEr^oyN>^^e_5_>sOEY{BEQo+9Kz7iEL{O^@FJUr462zn=#VUhk>u`}k z5P&F3oR{1<=J*xxIW=R=0$_TDI6D%&R)ug^I}uG-_A8QrN~R~)So<7y2$nG^A?3s( zMr=mdFInvjvKMa3fqtw&_>DwzKNYsT4x0HRFw=9hQ8`ixg0v~FkeERn$;&Ykfw4eB z2)Qo4UldSS?|f7rGpHzaa6l1X4?~>~AlHAH?@I33h9x4?YmbX-td+Wn@?=_@8=Y=; zV7;7$P%avtGZu%*B`k}osI5cax7M-H|Lhr$|2@(cvL+leHc|Wr%1r?=|n8H6@ z8EPd9#xErpr>>&R}GsyWhg3C^cOi4+f7)+u)iP2Ag2x1zmyUj2J~<9FleTa3VV}m@~j@1CYTO<49?mhJilu+nu6| zp<6@V62?#7{4_a10(cv=W)eNEBMWA4^aVnUw^2e#?v7qI113z)4pXHd-sM9PI6JI2 z7M>B_EPZ{K)8e!n9lnRtu5}#;Zb|3eOVM~zV{_$7AGbm;rJLcYTd!-ryEO?w_O4_QN0V`CynUcl9d)6nK`Wv=7fAcy7vtSb z!+Vflf<_TM085%{r@b)hzuOrA+_F{&Rvwn{1rTVKORUdT3+NP!}qi0IZ=8kfmm>WzqRju_h4QA1C$tbpmKJtam zD%0g?(=l`Uc)-%>8-wpZ;r zK3_hXd35ZzQi}&XorY{bZe^@KXH9F5rcm#~4M$4zZCmdT3$30;;oML%*B1Hk3{rh6 z4qvxsDOC_Qyv9lUybq5^ z7=Levc-67)pA9yYI>!FNt6bgmtXUpIk4xyet3CWC!2nW+D8E!2J4`irlxu@Qyd`jp z=@{R*w_7lT*is&38;gp~;v@pbJhG&0jB12@r1WK99Zc*mqe5TS@Uq|pB^R*W(ksf3 zMzMOS^*XDKpDNlxa_8?DC{Xo~`H0rb&<~)CVzy;|wIf%qk5P(N87;0iq%Kbm7}29FzI(RycOLN-<8#}fOrRxtalZbdYK z`u8a(X3EiwQ}R!;nQStD-a?bX;UhR$#=q1)GT>zsq9sz5gIT!}#@qbK!|Q)e8fO@5 zEVoS4Dc^3?T*kL<@L-33Bn~eTDx%}Pk`j*E5IU_0PHMFK#`4-xUo7t<(QHkPR(0Uu zLArB85oKC}Mw3EztxuayFg4R=xiaV=Ac#!lfQ}nNqrVaNeEYVit@JGGsZ~W%+T%DR zD}q)v{Mt4L#jewD5*+4oBy8hUY-<5F4%8N6S?cPYArN#nPHIiK&I3ll3oLpSb|Pd# zrMHwMqwa|MBfdlRhQrp@!#dkS&RPimnfERyZDXH}YG&Sj59P%1K#CsM3sa&@v5M^H ziQ#s76d`plH?C*D$yrw2W`#Ll+}yq8I2;f*ujxBvI7xXRqmj?Zb*td3-pEbcy&6r| zNUv-W!mip=;m+5Ae8Q>eA|2Qkm7HBpPy?26o3Iun#6M37I_twd}m# z>@yKYuOZB6v|4+TO*8CAwgD;N9(in4BKW_L;a0OaagSPy%d30bCWUuQl7B{Y>zuQ^aCyEhf;Fbq3 zAS*=uMC%MO9QCd_)%UW{v#H+AzvI95V&`xA5_ozw{kYOZM5;4T;skP`Fd;=qh3JBi z(DdiH{Z>8cxq%HCz?gU{e!wMd?BjfO- z?dIo%fTWLDmW&rw@Q)UI`hU_?YTK+jU%5ShB;3wH>;0VA_013XZATVA zve)litg@yx+n&;@E(_wOg0|tjuiAg&SyrrIi191=1?yvdb424$d(mY$#JdGZ&k0$E zclIMW`WLu7{r@#``o{&wt?R@zVO;h6yHij+q!(E%sIy zIoumnwKs&3>Jf_&acwtx+M#K+QT08!S0FS&!8eb*i<;IFLJ$3S`y~Mg(GGP|(EeCh z7X~&jzA_mjkwYbnA5Vg6cQl%p86rA6opd#tzSqN-2mHk=GeWBCcRpWi-|~Nf41k#< zqZ91*bn%v4neGyv1TfM6B}7tDX8z{7&6&ngmRSRYQuWO9Qqk$CRi6BiRaUrv_m-a+ zX1>j<9a+7Lioe#O-;a-qCa3TuqoY7htvsj6N(1b?LezU7b$w8}QcQ)4k3jxOp%XbC zmn6QwlnN}<5c4Bl4(VOz=O|gOhx;X*NqG&$1EV^loI@+sROdc!Y9g$I$ZP{D%-{Xc zGR7kk@DPdfC^3FPWRb!%7YtTMmRJIEA~4}EzUL<%wua$oaX`mEc&B5jF1B4^%;RMuDt|okzG#*ZU@} ziIX0!%+069zdzI~cP0@c=$mV)OqZqu@E>2#fG9=+3u`=Yq`n|@bLB+`7Xw97F33h0 z8z<&C&yQU8T>CHFxMtsTM=gBCFp){N zgOIB;R82ls%xT~rtDp@@j4&JseIj?2H~km>MHnwj4x2J6?|oB}JK_4p9tntSH{M&* za$&fDr=U6NsMra~khu63J2K&2Agl z@f`HYTFEqy%;Ss;<{bSQ*-AJ_Y+wPgXv~HltA^t7G5P~jX z#-!I#FeQ`kvCfI0CQ|M56XH+qK5l;PEb%d;3X`t3 zqu!0hqHVy@r;2W_Y!bde<)NWd@bdnSPZ6z=j$q2hwWB*_9hC!^?wC3X$4xWmET%S)DQ*%l2m69-S+e6^jm#*wW3EYmCuQ zI<30T@TSuvf-s9;1?_84&}Mjk^&aJw6g|+TOKPvMP7Q1mKvL7u3f11I3`3vW3vFw1 z+7bqCPZP$dV)5u@eZ#`_t_q3nB=tYzty;0y66_uHZU&pm#ovW3EBhO)*grER94e7g z6B{z1UOye7n_6gRFO?&60ZxAN<^8Nid+kNBBl#5XVby~0ZaPRn>uYL2jtLpECtkfj zGut6l$fwW7lak-X8P{UVX@G1+3*L|7#CLzZkW$?YEFEHUY&iHwWe_QYwI44lZ5@@8 z({>D&$_Ng#zp!L(aB9p?emow43B@yGJ-cclqSA8Cq_eerL`LTEoEIdKJF53*|I9y6 zzH#uMbhPeH(t+;J0{w@@SB0Iz>IjI~R^OMZ?2An!Tz(VQAKQX$?Ia0G*4=Jg?HqBy zpic5H!|P4Be~a;aDL05g>@K1*qA32VDrBW5{%4PWQB-K_;Nnu$vq-W=8XBZ#0h?)rJrgVoXaE`nbce-IO&W*0W1vVNri6T9V~|HyXHMJ=*q_ z^Yi>EK^X0hCXA2&eW=y6ao>X2Z}@0A%99!K1>-x*jwRsU$PO z0^2K)WIT7dHRK-Fd|=_QFg6a!{`oe+t&;TX)_Zv#oSk~`YePiaX7|s1(KH9V6CxS+ zSC5cO!<_w4mz($(_8mE%XRHw(LuoZQUuGKeS64`Msy?s%C#1MOSLIN%Ij)6T1igD> zs4i@Ib=wV&VT|C<=d;KNMHtRweT($^Z+INbkIz7&8g5OsfP9r{&*HAORQ~gAe%1Ai z{<+v;W6|v&4sB2mSMdWW{2d~2S-Cj(?gajAU2UD5hq}@M+Ioy&rOCVfu&&eXq8X6E z?*ALgI@DsWhS9+C*=12ieWZE}z!Oi^G`kKf|2 zfVKkapOLf0RtK)H=@uCjA6j!&)3s;b?k{{xzFcM84DU zUT!0EtT^LFV4@Bo(`YvQvMnZ6$55P$;1xwIB3d-m!KY&S@Pzr86BeY7sPR`WUJGxf za;s6d@U7VFl#Bzh=Tn5|EqN=(_k+n6;N99x#p}I;?8@=wFB!KL1iuxs)WX)Y=YVFY zo3t^HNJxifNSRzY5gFbrgq&Xi8p7+qAb0y@kJ}S! zwKmett4`F#eeLAfp7*=#cBRNVu~ zo!bd*Z4Gv=!rFK}*7_!J3x11XyWXT?jy-v869T0? zy>{Vvdp0553hYI@_fju;d1PhPd-#p4-jV-q`PdaVXaHtRtTZK(7{nK6$VDfLefkD< z+4@x8T#hz?58*hpS^hhe_-BiezUrIPq&AxSBOjj0NaC#=sVUk zTnto0TJTM@w6}AAtF&v_`cPJgJVt&5oBVFpP$WTkgMrnZ8fG@$*1uEo{8#|*-2-6e zf4ws=cm_@#$(Q1f?UzU?%wgb99jWd)_%Q+godNl%tbg*>k5XU&9C2UJ81-D5Wd;0i zmK*fc#nmNKt-WuIn{>*H)s~vsu*jOPw~S^4EfFe{7&x|}$Np&|2LiX{)_&#M`0tzi znJQiX)=CZ{rswxdtUJ^wb58upe}BS?VT_b*_g&8JgNzY;gCHEsF!S0I=j3^R8B*tE zVXo3meXQOfp#sJ!6>3PfXneP;A+KRrBXQzr!u9j2Hp`sp;%fOLhB7P6mw+THj6_>U z0yDR!VLsA|I?9%n8Gh8v?;ywx;nsfWiCd&m{wlx(-zK?}V<|Q;Dy)WV0`{8um_jW+ z^5^v?Y{)g@*Dl4UaQ-cae*$gNf5PFn0LmzQl^z;y=^CQ>4@K)WZ`hZs+jeVus7uUs zrT{%AXFNU<0)cP#pJqVE6y45^eSl zqc$e`K55l9--kQWSwcw_zk=#Rju>}hJKG{7uGoZsq*zYmLxJh1({xtistB=N1Xv`= zSj*#5|7CVj!=E20mUxF~Bi)8CGv8>)hCMcxr~3oIjwpf1+)%Nxdz8?Q>MF=e$jf)R z{qQ8kER0no!m8H09DBWPmlk=tp|WQzjX`!5iVtfr&pvG;pSfm~unuR9 z(Ic=={hFPJH#ucS=Zg(21=I4k)$+8*7moAN7mx+wH zFx=hc8>@+)!N+eh?W80zAq(^tJiB^)bN6CJ;jT5{N->H`X;`~WNsSkM#1mZv!xJC zP@=Nr{m`>XimiAqNzb7$i#KKH+B`q)XPr#TD9VjM(YShcZq`>#v$T%+4bSNzQ-P() z;v5r&8u&63s7u?#n$z^ag@Iu!VUy*T`AdTkykjnhCp03@?ZCq4EyEl~erB0d&srsJ z@tpBd9w9hF_yaA1Thj93009me(0fj#G`^cYaW`PCbVam<`F)$XdN-$`bcLfsB`~L5 zC`=O+O}+V>udogdZ>#`)b|dRIf0{nJ|HsRSWxb`*hgi7J^ zzy7o(33@gBue6B1<+sOR7nOWif&heFZB`oR}(CFB2v!=9Uq=O@PR=&2GP8)Ls- ze48IPXpO*R<388o-I5G3{*Qw}ekm3YSVhWzmXhR@dV=0JUk~p&*Bt4I4K`1QKd&H{3=Fwa|BQu3|%_34?6!2#7hW zKMj&;@TLrggvdT(>=+^pyO5DkBZMw_eFe1ZcL!o}p)~w_pasY^;Ihk7{1DSoiREHD zdF6U#+F`YNVxeHTir4~WTLjS=kyB@v4ps88b}C1kWn($g3`v?Vf7W}UiC3?*!jbv= zBSf?f)emB) zEa{6&uFj?Q2|4*wV>4paz}IJ`|8fC5A$(`fo?O?@XE5G0PTavjK9I?+^t&@}K&K;+ z8+n@+9Q9jSQJI%)GF5)CTe$^x>p~Rw{9MaWKXj)_ByD?c@Say2hs=PMfj=Eam+&v$ z2{PyT5P&mgbK_Ot_+~aCxnu{q}1mP9LCl7l0yPhM>fR?u{o?5Ou{v>v-I{ zyiVa3saufc(V+w?gm}C1e&Oct&utis8G4g_!Ozz_2a(RY`#OX@QjvhsOea<7_{b$|8p%TeTwUK%<#UhCPP}NrPlS6RYVI~$$hyqyj4h6Xc%)? z=>7=xx04e^c{A)f2zV)*Y|3k(q+&{RHbRh8Zgu9Q2U4AFdNiJDah`AV-y;4&6_TdJ zn5T# zzg?Z@jNrnr8X<9ZE%CNbT-JchuME^Dc0jjMCrVe9@nHYS7#RiY^V4B5Cm31f*8le0Sbz7*(-%j0i0kO_X5G}%*sZl)zQ`QhcG)ta z{qyT<)2IPWrZuuOD%#Q8)iAdGBsLj*?1`1to5dcHzd|M{cYutM@dI(y@v9Z!8m;0n z301BhZov>tWnYH07)f4Kq6yrH1QO3qZ;Bk2*?jVk&DHcJ|LyO2Iy_U_3>IG6iF81AR?-q%Nzm*TC3Hl5u zcl6Ox?MB%Jl5?;uc|-qX99$ly(#@B*7YZ<5_()th&a?t$5I-3U#+3z}Hwu`lN-&k% z{G~O`uEt{dp^~&0<~)Pi5H4M4_FHl zVb*`zWk$MHR*|RlC-Q8HGbhIH{`++dKF@ye75OaY*7Ns^@R4U+07~9L$p(R}!-&(k zl#C*glWBd~aoWqmv68jms^ho0K1;Rr)^wbvSiCA~s+(;g+CXuFwSMD~F$TW{!5@)i z`;l6gzz$jUgl+)i0fNOOnObC%28Gf1ON-?*4sq|;d5N-zqES&do$&u+>a7CW0GOpw z+@0cD+})kx?(SZsxOc1ve!AsCjcLDNE3zLCD{!HaAiH`5WE4`5eoS+Zc zM641X!&xG775YQI_+8E&7g+?*fqb(OCtlu_anscy%cjdlcFv^xUN_Ut1^YA+goA>} z+|RF{p?K`+Pk!_O=;eD(`cmTB_j~H{w|90{%_}cRXhqR{Y+*crr!w z4L5Ew%zmzQsTCeJMT=8%yARi#9-_;EK)8dfw`QUig-C&@4`E^7ETLX;iDXKmCU4hO zjnkz{fL6(R^aoXerJK*mFYnyMx_)K!PY6s(5&y_oo@%9Ri`goe5>tU*Cx${A(y`a)tXP zh?ia)(7bYDL_UTp!BE?VyTa^kKic*_&AY0je4lA>IjigVR=o4b0)=pC(>D6K)errw zYH9ENNdUa>q;*=Pd-31i_PMsjA7rynk`cohvnWc#(Sx^bH8o0bvp;7FWhU{NvG{%naY>SB8$;QbFXqscw4o{&mTiN;-g`mdbgg<(j2c)x`LXS;OO^-% z5TT#Uh`MGAcP?73k-MPRI&lF7cEVAl{Bf=qt5_t9Fz=?jZV$~}@ zexH|70f-3R-s)KoeDEi$Aq@JTt(^ZRtlO{K4}RR$@(=K`Qa{GwMj2e%3K zFFylc%-=ZB5C2;1T00k29M%)srd?QcOniw70% zf#AUw?&9KA*f+jCW;jNy+@DW$s2?I{9OW=#F$uF!->rw~5-Tn9{DK2claGPpTUCY%_J&eL}`QOd}N1kWAc2h@EADKW2{jB2Dn($}@6&u?nCe zd~$qRg(_mM(Aqvqwk*v$EP&7_kVX4G57(M25i~<`3@b~XtGpI8Xx5Y>7QieXkAO&? zk{Jo}O%IBSu+XMIuuoT}Q8naRK-UwN5}nUE zSfn$rXw=TRboYzEauJM>1FQu%QhFNeUly?nxGJLYOrukw@5&aEv*aGU@d=erFeD?+HRKbK1Kw1aSYMQLmiBl*SKrO7WR0GH}pnux) z4VD42fB#k3k+`k!=s)}E?Piom86n7ud>9I9+@T*_S5aF6xFU-P2oI^et(_73yB=kG ziL`>FJK4*IZc_y3hv)avI-MaAWP#oTXKqb1oQwaWJlkXePx*fzsr`ahW3TW!Ay)!Z zr1W4(;YjpyvV@J55N(L0^CBu~!wQpC!xR2NIAVG!!wa z38e==o5f+}JDwBcG=xJ_k@(vqB9}w14=9E~9m$?C}irE9swmbL=@FLQ6M8f*}|_?U)?JIf&^ zg)`g!M&OahLuv~+eeg}t^ZaS`vHP*B1XZBr*BH>DXWQY`cz1fo>&UOi#+TFz94d+h zZ!OAx>)5`>HhkaSif?_Z^yH$8V2u$Hcb@DtDJ2kwxG1itNRUC?LoAWq+KnFgt7z%U zNTEPEdeWlMR+X5SC$GA=$JZsveYY_kaoshwZjI;)`&o4Fl#bGi0FSwb9Nt`-8WNgKdA=dHa@K zDr8-S!J$+XF}ED0TfwKeB^IJM`tbckP6fRe%|H>V!vlTJ?IJAX>_vZ3JRhwfXhrVr zx>4e9$u?yxT{jDf_PA8Qqa^AaNFn~@ZZyO|+u<6F9_lvF+EI=k-hyK02whDdYaB$s zbnCQcAb9#x6I&}jkt&q#hY{mz*C0#kLsQ7-%Jz8w`suK%!j! zo?}I4d=Jl!P97Gq2LbiU8?oriCD4H0{93z0eLNOxxqUsX80te^^J_k#ACK|WG%1n$ zP6A8%UtFCA`qW8BE+9piNA72Of;MBQ1IoI(-oJJhAu4(V0G(_6h)=i^`})Ku&$*3^ zjEK-RJr||9nT-e2NsUAKQn^5Y$1GoWhoY2p2+fe?9m$uCG0L z4OVaZd7l*DGK*a6b1EDKUvdCjx=0?@q(@vE=|0_4#(r#h`k543Ai~7cWJ|qAiHp_> z;@V8fLp~B)P30M*I{bVZjy&S#Wo~&nqiaa%&)bST<^;YAUp&-Fk67QpLBm&(^^}0mQ)H z4gOL%u*P`~Y06yt&@Xs@Y#4>p%MfKhvis5>+#OnH3qBR@q-)#r)wva*C-2qbvtw}5 z^Z4taxc9jiXI;jpRaNt6CLB#|^}r?MC1ktc)k0F$pnPJ$QFAkoCoY^v$>3p%b+_;P ziMFU3w=?m4!v?8k;x=ojhs)#|w^V>e?W*g>M#Dnj{EjnpLu`&`2T^NBhk;Yj4)~;# zMe>e%C^~L*JKhTU$dL_DGOsrwDPH0Q@G&iT=PiV1TFDNK`_;NU@EsJHgQ{?m@Ew+Z zwWy_`^^MEX+KfIMriNX=fDThuR+55qmjqYO$F<#OD!yCM#*TNdul%5EA&8jcfNBPv^iiB z&QwF=jX1kxU2=z;7XfbAbrG)#spD^A=@T&GbSdN+5=KddqTHP{hxyD+7#4{*y;q1I zzfi1kD!^ciSP$|SG?J~*sx%NNk$yLnjPc1xj!Zcu;+lw5WU967H#9Do;@97|9r#Ll zqJt|tStI+0>HY8iYqAPzs}(>sN3xg~-Mg_b32pu?nX}dT(UC=$Gmk8u2(Py5sFook zS|YtwSR<(qJ#1iN$C$t-NwI(VV}CFypFPC@d;1%S#jGqNGu98@Ct>U#I)n3?doK2H z?oiis1k8N61(sMv1WMjF_0hpgdJH?*iyut|9a$l>^=RY0~qBlQzH5loY! zbts<)ieXq*p2F3^BMmcUOLG*uA`;K7QUtr(Xo6Hq9_O-PN8-dRD9xa0`7JFP#2;xT zN~Dw{k(x>VeO5vCvSCxt@&@LR(lLqbh8)IL>$d zaKsZHlxW7GnLFf)WZeSJL|s$0cg8_+*hJ$xz&! zSh(>ej%^OIDmMn@%0o;}D1q_DQC~{o{}_$}3Ct zomM+U`Jn{y@u4_(xr{?uX+ldxLPJZM4lpsS zar>TlG%MDU|jHB`{o8Gf1 z%R2vNluraS+x@jR&k;$i%dZ&JOGecvjG>id%F`S@lbeqDE&6`amdV8|!2ti=vQj^O zDal{*z)iIdi=P5Pk3!w6oJPJkkzJa_ty&>{C4=n-yICr+_Q3fH(Q$mKL=w$J;ysXk zx1w_V1Rx(0I>|u!6#dqH13p-6iD3JFJ4z)LT#nz8NdCDa$SR52ax8vz9F$7U*>pv@ zu6-b^4a4Q(VZH7;tkI=wCfA?rvV+FijqsKmmB7ab>6yQ&rwWI^@p36+M*t{0aAjpCA$$?{9cxrzlA@*w&Gs?oCIA!a#A-&Dv4;J zI|dqP#rCT^Z6X{b9gM%*=tUUog7sssbtTB90XGdJ=8`!eI{E6E=SY%3;%&kPMk)tH z7%0xM;@fZD_ZPlKpFmyBJRew3-h~$BBeCEkat2*W%ncWYNA7>Rl-e!|g%*Y26*({w zCanbE-K+cXf`j5HwC}%5>d#B(m$u0J%MX`4o*$AlsM(3&*u&l1MHyoUt7iqN?GZ~uonrnGJayLompLB=j#$NSO)bqrhU##&_^WBv6xdAVlyy=OlaLwYg z2DDlB7gMWu`1~9lh%H}Gk~Ux%aEX+nIUMt5xMtd^>tz`X2)QU*u`_Pt&l{6ujG|*n zAdiFWbyAD)m5Uu3FNgCB=c#QaME-)F%ev`5U?AuS&o+>&B z|C~kb#Hm8@>XuSYuK{xU6>UFv7zMT&e10{r{))Ei%=;BxXO}E?a5Vn(JU;iklKiXo z>1eR;UnMOjoAeTyFB%V5mK_)?3{tcTiHIKa_N4mQo?fEmQT`>OfbUj? zdF>T4KOWGVZ?5D3iSJl2ccv+6At$PC@J;U&W;H4e`;58A*vIvgT((=v_iFuwTvyR=b0<6oHoUE5?Mdq2lN*W*VH~ z2_U=kFhW!@XX-Coh72tmsmd8s&@K$J67l%u z+ctfroc;{+@p47=aQv({2WefA*_5K<)l_Rtl$$gsj7K)j*FY_t#Fm2bmoZ&x#uQGL zTzBZ@@gatHs)aaYQ!=X)#=$`?`k%4FeDYN4bLJiiw zYxR|8qp|F)mhv$5A!@M!2M-i<>6jxdWt2MRd<@hcqKB{N86cM%l=*=6NI;|U9GL*QF<|9tT;v5ig@J2^f| zurOL}FO;k|Z{^9VG<3whJ>ozjJ(Wf+cv;q&Te-k?>)RFyeWgXxV~U`XRW^`XG3ign zoSf@7@k>r3mQI0^(@E;P!Yhr_*b|+63tmW;!a8nQ+D5Hr`#IZhSEmbxt2Q%AtBQxZ zg|}?u9NfRFnYb>GwDIx>@a7zPRliq1*Jb0zwt9RteB($s-qqqgVB`jNNr)v;UzDAp zqosm3!IZ_LCoDdEK5$Wcfp#ozrz1Wnq?&k8YJm7r*FmGJ#dB1Blg4a>@*60mrj)36 zc|KUGFf58QhYgdX*~qtBh}rQwx~53KC{dDGOzJczK3hg^UDXO4idfjREE{fWxbgWN z_j?SD#yAs8Vp=T;LX+KC341~SfBeTn%H~C+lfGle*#s$T{gh&`3Smd2^FqG!@7J;Xe38Xz7dyaJDl#7MunZ zKFTcP3R8P-Afh~{6*XKKr^YlN7l8&gAcV#SX+1A?3vD@oVx~|BK%ro8zb}^rFHNnV zYzRZd8^Orc;gL9eG>`Tl9F{2nT%`G^Z+X{D%yLAg@AJ22lyCzga-N)2-je36iLEsJS6l_|0S%1~`qGPG zVU#RNx|m1!EVOB3{0~Mg8`9uH3jl`QGoH(UiwOd7e6hve^d0F{t}_WuAe$*YRO|RO#DwRqQ%D2IFFEJXr~MN z78PEBVu^gVQa7sZug*p@9A}R1LjNte$S|0WXP5y_d4$w(ihjCi+L$k#EA2t!?4m$>K?qf#>3fkcn}}M&Q!QSLlW)cPLOx zu#-`@l+Jk!Uy}QFR6)7ws^7=S@Bz>3feb)mKvDR5rdPBlFlKA+oNt5xPj=&e2l+`V zzm#<_e(T<5?Jt+WLYt(oVnQ;MkbC1AgTritRp(eNFTRk}-eDGyEZ!69M|G9{r#NjX zYzcGY>Lv#Ci6JhZG?Tzf)PaVTN?&2QD6qGM6k`_1a=Rhnrfryj)W0^~uj95)eW+y_ z90jvt*2vduWr<@fSUpTa{sw+-#6s*LMDzSfoEbPV}2;m@0X&|HD$TA(`I1+C{{Q z`P%_r;-dlQ^LiddN8#I(Ec;DiTR1=8onco=maF^$=>2iqq~ZLRhH@Fx1j`Id1*=Y= zp^0a?z$4x~V0`g56EeUM?AzGVrTuhysuwhKo%Fmma@;8+zeCd{HZO)l$@CfJ< z3KwM)72no0aL|f4LdOp3hSRK;Qf=U`rDO5rKe0XhW*wU5@c6ZY%}eV6J|uI~tv`aw zxT5!rg9;NL%nj{Z4EKz3ZNpK$j1aWx)qGLL$U~dtKpeTazAz`C$rxLa@ByXF1!NrK zz=|D_O%8)hvjJ4Dp=UTpdpADI2gUr*`O0`W}&mb&k3fbLOf*_ zD7mqmr$HB}(k`*q=>3qL_-<_af8RAZjMM3;h)*-0v! zn@xRzPg1hMWy`5y-iBI;Q9WB4Q#1J+$VM4K^5t2g(qxQ%R6NzD`~_R?{EPHgO8${L zbYN<)1(gWy(euiubt`p9`}8t_mp91bRQsUUto0z?V(2>;IN%mLRIGx~=FW-j9CX>emn%epo zV;a6~;v-7jq^!_s39Cs#dXcrii^a`6B8WnOG@LlTqYmqek5Rv7ia?UM`Pq&+(wr0g zVsmi6MrC0Jp()0H(ewIk6ewSI8r+HvTl z?Rhu&*IML^%Y`|3X0=oGA3(QahVI_^57NnB8L&%hDao>1vsuc?2*ekSNSYg(v(`$) zW0|Yy+uZ9;X(gS>djF!i9V7mm_OosOi4nKn@Lsplhl-z+Fy}|V@I1K4{NYpnVA1&& zBr;JLIpYyvQZiM1t4gH3#)>2rpt6@t978)>w&%9ZgeyDlc?Ew(ibN>2u)LEyO0{=SEUgvwpgV#?H(J z9u_ipAWt&at3QHa1}n}5E^6hjs}5-K-;Q+v?=@vrg^1{zDUZvhD-rdk7YqKv8_kS- z>@t)N|AT8pv$dcxEbDux)6!({H zNnAs>nHck%R!Lp$gg?ra6Nnj8G|d{rv=lo_V>Dw(4897X+J+ni&T}N3wv|#I6lDVJ zztcG`EMXFjqZH#L`G6YvatHSg3Rnp=KKX_vN;F-X*;&no=@yPi-so@=(a%2X*Q}Jf zuCf)%JeY4EuU9pZ4zzw%Z%?LYn86B!sd3JBZODQu$y^p;NTbvRPT<4(Iv(?>cO68Uscc>`)kh?DFJ zgiz9RH<+#Bvqc(`v*~v2z@s(Ndxlk#au(;dpr(r=MCC&mysa{sBZWK2pv{&^M_Vut z1141mPTlfvQ3JaouZD6&je7b67mi!46TyZQ0ygzew_?_GW<$2pXXIhpc#jd+G}oqr zXi%Du68ke<0isqo@z(5VS!56%MhT*zWQE(91v)Bz`-z;A zK2|Eg1j&1@u!qXP%VRYw66Z$0g|VGdmELo#Db{85;6&W@Ip(}a1}9gwvZP1|0NBI- z;9wEN(#&!VX+$IwH@B~m9}bFdaml65&sd==iqPbU%^i}uJ0Hx$purmjF$ip1z!Rx_ z;Z7I;?8%J_=Y_`R4n&R+`%%dwL;z1B@yxQQp0Wu-qo2Fm#$B}Tb#1X8yc8+utgti` zv3NSpsF%_`WN;R#?#hi?2B(YX_D!00pHVt6bM|*wEjuB-k(^m;`&=up^z3@l%eTaK zR9jn1HK?`6_>jHPY9)rVvBK46s!p2X{-Fo)1pW_svLUMFE@={fY&weO2lwm3lWtPq z#%d?U#bH3T4)ItMYA}3C)Tx zjqyiG=NsHaBOHHHnWnok8Q={#(hw|X=u*rmT%RY@2|Mn+^zWFRqsfn4&4(f04r^qC z-tOE7ye9E!MrhF(yUSz~rKUuk`(75&(#{Kuvaaps?&Dya|Gpp9Ci;l^y7)z_P?#r@ zlwW2nSjq{;BIaJEucpon&L&S6XvFsJTlpjFbS5}&n8R&d7faj6Y4JG!tX1|6 z$6+W=V+{DfrSb@*{0HU#AvRmbvB;);uhB_QizV$k-^lvf+LKX! z={n~76f;WLJ~yCDR;q>DRUtDLQhpLp7lP^?L=dy~=^}QH$v%)^XPVc6h7UZQLI+SM zDMYp%C3>fNr;H4m=pM2{T|^3Kii#_~+_f!}s#>yC8s=JDjwf{a-mWY3?VUsLjT{P~_eJE86_9Xf?Mpf?7+w()t(SKt(g$H8rMiffsBUXtD)evlgvNc zJ)U4+7sY?3PkV4l8+5@nb`{HRw9JcEGA+R@NT9L-+9VTMxS3QL@-dD9Ne{YVTAb4& zTBGiP9Y)j}{9$uqWW`R@Rs%VX+;ah+zL0kB(;`7El_J4rrj$=2h?L@VhYcg>EN0Arj zBmdGvO>aVjXOXZW-KqXgcFlGHQGa;4SRrV*29%L`MpotJR3~O8SKV z9_T;taR^sNd`_CzajPu6DqksC+288p5IZ|va7i(`3k9EN?072e}I{M!%fCt*?L}Yh2+UpPL5kgs6(T2dhzk7mrm3)WloFW1O z}zwR3@xo#o(9XJk<9?VI~l-qyMs%~}7ICv(6B&mZuL8kQk{ ze$Tg_X~?Qe1M3zpf$G9OFp*r&gj-~%=}wq%k;yMjz4z3OtF7uVaD464v_4O=0hW57 zxowD&J=~V5asKq7IoiNMR0ReK+UU`LAukMLyZo+z^E!D{Hsim3cd*{)C^Cb15Fiv65tT+tRJXkqfPM@U&#kHpQAh^+% zAdVr0c53Vu_NIDW9TtF}rjHhs1#2jj=ZS6t3zxGp8NTVpCvHg&5fw8_)6wz|@d!sH zFR3w7+T2JG7Exr;!X!y#;WMTTNj)!HX;$dqa)z zq6Jdx*867at7A@VNOGX6v+4GD7LmBpEKu4J28MfIDmD}R-)Fn{$N!ppQU>k?{3!{e zyGvFF&Oo3)KMo!&6t?V-GJBY0>nt!V$1);?IxGjng=}#Br0${tRo!hHu(F(LQmbD! zU>Jc0-l|m>E+RkJM^a{5*256Hz&!oDdw#R3Mbw#)Rq-`Trzl{0hP!k<J?yLE%n+TkK3}t}hP)5T|T{iXncUNvnTb^fEYvn=oKGl+jCiwgJ&00?X^zn`3 z6>Dt!nOb;lr}n12Knto}N`{ny{^BzR)Gw&$Eaw{5A4i)X}0b7Ub^?cg=Oj62f76&RFU{h-A9 zyRi3s43@E%If)J=e@h59ay3X8+wklKe$+fQ)4I1O{XPGXGvTe=f3~17W>A4=tLcs< z*!J2pl3^UiKQ!C7P*JelM{gk&j}dp9;+VCJ&@G`hFG`sV5fTt1`3|j5l|@jcfpaU} zfM|oU*r;ZpLzSTN4n89n^{vEpxA>G{e=72H0?}38oRM`j(^>b$X%8u(7tyttuZpyJnU=c^_L4BZ_tOn%G&@oE!+|lt3ouh3(EwMIr)NN)7bjS zK^RL}8)qqF?mpQ!6WfZ_8iA5k?ZPK9o7_C{Lg+*fyt1slsx1DRLkjORi&~UIF(1n| zvSrQlrL-1&J%QkavID?NGrTthOPlhYB-zHqdef{_J{ve6|1Ly`_$Y; z`vif?z4NdLpYSGnpyl-=Rtx>e00jD=P+djoZmH%sMzBOR&~)Al&~1>S^%>EFvl$r^ z!IgW92}K`wGq^%}^(nMK`N!KqQ+56Ul<(PHNUe5Lc{xB~C$16L5UIncx;6egM{o0- z_zOz^jo2fg4=7f_8Q!BUszT`vD7U@)tzmb~#7vbDn0AJG2tHROYx&=@Y1-Uy;vXXz z!+`JK;|z~?{{Cz5;f>XCMu~D}1=GfWYp%f{ZZJ#Vk<|n1UIs*DkXskK zYr-8qBZgj8Q@8?7^IxLx%(9?6ds?!8%rsd{Ohb0f5t(p+l9TjxNiI`Sh>_D0l4xj@ zP{A)lnnOH{afC1AnKtpLcdW&Rn?o8P!z&OkhJ#JXp<5rOo%XXy$T_S2!+pK2xHL%Y z%__h2%vbQ-D=wbi`3;Mx$Fsj6KnO0afj8S@OC0_h9!?nb>&IUmfsooF`+O#*VLwF0`t5{@Ybwn z0_UVV|3@UKR=v6xP$;vdHenrZru>;L4bgtd(S|9WyX`cUeR>o}{Tjp1le;k})=EIF zO2asGak|{u8l?kK5&Xlls5J$6m{T;*x`fOX@4H<;x(AgPp^ZLUyWRu0)#0p)DVYigc zKP!rsk{l*ic_%?gfJv!K3~@5?1bfeh^(>b(e2OH0gHi&z{99ZUqhE^NV{DT!YPDinQUM-8b*v{-?oG z?*5A&`$w^6fXszz&Ms1tP((V-yS+F^NRv!x6R=N!&il=COJ7_27-NAzmny*V4$Vnf_2C!hydk zs?r&$wh%j8W4Lbh}FYlsC`4$92ufxDp}YgqD%lh_iG%)w?LFA$Y5f zU1VNw!D#w;rmrg3wk3k_pEmrbW#JOK8nU|WYm7422#0BMU;Ecz-Sv6u@k(X2^cWC! zuUWpBj}L03^q-nwE#@zcP#guezd-dsK-lZ7iR6(TU!5*z)~g#PhkSYjM@8n0o79}_ z4Mz2*j}t*fPiBGh{H1ZY4c%Tev^}uJRPUXMS0{NNwJ@m}Pshh}I-Y39)~UeL9M1ER zxOh(IuXkX}*4=3yx#h==^^Q}ansJl0YARR?Sdt#$$vi%*Ma9FpH$m%$daG4ksPGd! z-zFkicAsyV4D~4^`=rM_`Ti=%0(|lS3_- z(Aj;yn^@J5fW7!n+y?MMJF$S}0nX~{y=7EH8jLjQjKNHRw$9%CKeln+;G2ot!7dVZ z#2n%zIs9xdcuxC|Zt&?Fa+S_w1jU2q&TnKZH)w~uoj+mY6C+x!etUR!?+&B_Ei4OP zU~R$D_RG!aIYD4b7UF<_2({2FfR)b{5pgs@06)~rWDr%9%@9B7CGnpaN(-6u70{p% zdbp$|0K72onFl2b|E^W0Uct%6#dFp>XGmn++gO3gT|1kRDvedks?M6}I%g@XPHc~h zfE7NF%v*O@82_(X4%V%QzkkF_NJ z)GDb%$bwGUHjhDR^+dysIwecTIDiiaaRg0~%GEp!kM2U6RyG_RmH@d7HBfGCnC?3U zZPJtb$o!+37~(EFaX$=j`X{*!96ogvv0UdC?Vd$y^H0iTCJV0Q)R@Ub*TsuMgmGb~ zEEOoom5(>V{43Jlq{tMn641D5Dmkuq>hwJbBa=GGj9NZY*p>+>P4SEqTZE+xQ^=D1 z?yGgsJ6m&wUhb>3Ce*CR-4nC?!$ERzWe_pY!L56^*RA4_R9ZDkyS$n z{*e!GoPyIOz@q$x$m1KOlF+@@PDOYDDR{^Y0}nC?S1S24Ryeb7bL#!|e%ZZ(6w(UE{zmn)2*rCN@JvFf2cC=LdZ}ScnA)&!ZhEH;^ zI1R$gtC$5rjJl-yh-kNlYWVH;5R%NeV?-Sxc?$3Py*d5MMxdpFT^d71kX53_1?!2P zwHG)EVG-V+H!WT%^Oj06ofdQ3fdt)-;zDvAwT0%VQV2wZDaJ_{VXvs}g9THmu(z3T z$Sx@0G>DkiLD%jF7e(nw0b8DmnNUy5fbj|#x)8$)a^U?_(=>c_Rt?LuFCE+9m4V^bS+H5iLZ~Y&?56Qk;!OB_y6rC>U+8CCvD!`usFGf= zX7i31cm35&IaoF;sVy)SG}s^cd;NFdX?O%jrtH^4RjJtc?VC@3Xzpp@A3@H*1x6h6 z0#l4S+9J@)mo zRDvnAh z*o`lW23ws1+A%Rfp{hfP%0&gQPCd68z*`i*C;4K~H`ith6`^%lCPkd@&1Xe6<_WP9 zqwbSkH}Q)JPsp6Sk1qwm7gLbhk}V9p1V6sKCS8K``y}Ug3&Rt8mV_>#=~u%^PVb!1 zR3BaIv2GXEKdg29R8eUES`Wnr@QUNx|BPyN&E|83{Xg?rHt%25f}CABAH8xNi;!RM z!~AocC<8nF&?k7aoj?G4K3DKRb%@j61lEjn)^f+>Wk!@ItyFzKxf6s4Tw}(uNLl!q zgnH(Gi?Lh!w0PInARNE)nczH_LU@A}goUMHiQeQc5>F+t-iU@IwTY0mv2LaSR;$UK z`P^|m@;OB)K}HjxwVa}dOz9DKrvJ9I{`lUhgYCk8t^O?2w9KFG9e1v%w!r3`$ShcX z0Gt%7E-a%4uFaeMkN-f&DIT`YpNE$TQsU2H!>fAHLkfKy1M13yMX%s-G@8t#g8x@T!vjEkprep9DA^$K~s_gDeXXHD#?;{Tz>&$V+r zWCsVN{D`n5)UKemL`9}Kc`6%CxG28=9|8G;&jOYx&}}|zn|C6t09;B2t)<(Ft{m3q zkMW@!a=}JoOs2OK1EEl+`;6it zjYe7|ep>Xj;JxLrPcp#~R0$+yZ*Y`>06s)>$$U+XHb( z;E<%-;fLNbHI#WDuhrgh(A*P@LsN~>3H4->$Lo05kgt;K_X(~E3uJ5h`8q$TXTW1~ z^AOA!9LyG_rDAYzAPLAI9M`%s72>7x|GG~&ha&JsIzt1d#f=>IfS5u)-y+`2|1mQq z?d|*$>71bdkE^#1YwCaFhiRl6MoUU}m#B0INQW@GW3+@4A~iszVT3f&A&edhLuyEa zq)Z$gBB6xO!O!>i)PG!;Tp&B=zF+x1hnq2d6|cLl{nPXL^+w>V8Y&N4*%(O?eS4uV z1Lq>U6a97v+ciyJUcRH?*iM_TvksZ~HrMk1K3-U@7LwRcO{3ebdm|8;I*HSYqZ>6O z)&cf^saDa2+w=%Y9?MGoNlpW1kVO=n)AXp2^-U93@ZM+Tq_z6U`V{tqOW2AG>}Aeg@?~aS1K!e=?}y!(SH|AKd~p?;DtZePEGaVPfT=}vl0zZJ z()4)~(vibk#J!7W@jWh}M0?X2$tekocQF*?g1H^g^hCOwJ;L!PDjt+g&}Iax%Vc&p{aldee!0u5DA?Nz zf0^O#&RDRCp@b1NX+B54?cLx;(MWF#sz-N@u4IVbJar)@L6W}05~4fQ*;9w+i~pFO zA9-SXxTsqQkwsdpN=hlQ#|5ka`0N)!tp?ZR{U{u;?IO%LdMwI4b;B?*Bj1&rtT3D0 zU~j<^aQ27ptTfjxL;|q=<$v159^272(W$~W)g!GuIt$$y6+b8W712)m|h{&*u` z^xrr&q*!Iu@G8=jxIz;+t(aMLz-LX{5zK<5TMgnqomEwyzI%;-=eKfjhJ^bhLTyT8 z<-DM#pmtfE7!t9GfbrMpl8C|y99L<9)c<>I#ZLYOf#Fd#x49@}pd%C|j@HQQcxO1n z8e^>^?{nWOeF7(-2x$4Tf1&u*05o8(K)U#tJ0bx{LO`-7GPd9K+4shTw|pZgS4CR_ zr)^#z$gV8?`aw8!5zybkiyDNNh<%>$R<)y9rZ4#1_mb!+S|U<+UuB&JaqoXz0Zgai zE2U!s`Vt~0lah9_`T7^XAurw0Deg5Lzep|4jZD&oiM{F?a)GuVd3R1Bc+0)LD_R$D z8LdmH%)-zQC3_dUM*`xEeG%b_1Ump)l2i(LZ;ZRXTT zp0z6hkH_~aWB};aA&_POJ)a|FIO+45B~+Hiki`6(m$|b_MdM|TzwF5aZu;LP1Qs02 zJ+pEa!Un3tpo!e_kB=yhKN<1~Bn09PDObb#8Yzeo)D*Y~#>o9;X@-U-+l7XE-%q-k zLQCUaaqkn(X%+@~W-m>o24A{AZ1sQA%BtDb6YC7bJU*-+U!}Or!#+by9Ux9Q4+3C1 zfdx$#Z0VB@Uy^Y7sdmk>utCW^L$FEC(pjv22i;K)tMr{G&qReDf*Kb{1r)Ppuc}oH zH@Df|uBFCP@<4kKa*Y!&vmLcQ=8Go{<%^4mi)aqNq;#a`c$QJ`DpDP~94q-L7o_=p zEP=8~*8jq(Fqg58x(;>B_pI>caX8{(>|5%0`?jtb+&{Nv+^GKE4?kyPH-CzGadr9| z^?j9FnBEZ2Z1S}JzELopSqMHy?rK#{{(GBFZ{C!I;)AfYOdfdcLD*Au>}kC!;l{TD z#M@;EyWh!4jW;Ra4vr&l1ztKqDd@>SRIw`fGchzC;ncs?zVV!m&pQN9TsUU{B*{TS z5$SEH4J6QWdX%i;gt5JTxdEt-!Ln*yQ)6u(8OOMvSL!a~R~hRSEjsE)z>6^NXxsJ( zJNM-d$cb%ToAE*3a(J%1RO6FrJ z)QccHK7%{5kk_re7eTa)!G#WlP|EcA0Sfkdds3mP#nqC|MQMuDZ#Y*fftN{QX%OSz zD52Et*c#e;bXN1x0{v?^n4sF`T{Pj$sXET}Y#KWU3O zH7Xsj9N3##;afcu-QlA?kuphe zg_uJrOyI24Rczm1(Ge-D^NN)}CuJ8AI0tU4bpZ;@ULngJ_Tno;y!wM|L(~?}q)~-!b9+X);^|<$NzDFkZze zK)+8=`ecxLRmXVy`MZmtmW}=LhpTj|nTa|&=jJ9?2}Z83DWi0pne1vh;?U`c zF*0f=^O1W@WW-IsR?;N!=^%b1yNMv`3ErchV@#KW5ni$dv(`~*IZfVfuSs;11;=Wpa3Boy z>yg;6xE5gU;P}4mU|8Xv#u}mU!y0(=BKQmNu z-Z99hVdo&XY;=7S)G#b%6|$TQ%Xg%sK6&mlB99^eo|fe29fK_p)p$YTq<_VP&S{gu z?}PVpwH_pv=vU)bCkriR^hz3I{A{nxb)h@BdF1 zKrAn+T6-&5QP*|ktfD2XZ+&{Z_IakZrObie?W_Yk?_x}ZUa8$Yh%VYBss;a0AmN3+ z>nScYp9{Wi(2JD4jwoEpo;umEF2C<>9lRSSkhM`iB-daAt!Nn`@%URo`SgVOvZX7C46k4G*K(dd~~}(xGVW*?dwolB5GU+FmrYc9%{t_H2zJ1In{^&uXVs^mE_|I zors{@#>tGKqlZk{&~KAd9I3KwYWYC&En7+8cjU<7WXE68f)@|nsfN`{f&E#S?Z@QT z%ZS0+MEDHIKl-%%{XRR%QtiAGUoSZ-`6S@IrHuaXs;b9kM)vsc$pmyZyM}N?B}0k) znxVur=efs@j3FEZI3^iMuA}2s4>Fi*8&z`$B#QMKp&K^cR*BptG6Hl+mB4bb5(_zI zx_nR9s?a`c8fsD;d@z=yLIPFhh}|Qwg#-14epEM@FJ>4FRTuN1GA1T{rOF24cCd1W za-Tr&{nTTz{&eK4Q5_eboFHr?i$*|&x>SNQ8N_LL*8%G@4X7BN7Eh{y|A?5B3ChdK#)qhS zt3+9mBajSYZLsfd)hYpQWcByex`}_RRJbN785_D?*y#II?pNj|B^Z#{#viAqYFsYZ z_y*YJwJ5Y4VX@1itEr3lL@_@F4cgzxHOt+O!gzjyuJ#f7Y}pbPF6AAb*&ULk%XLhFaJ}~~NHaDCS+J}1Wx3Lo0BF=KBGy9c zo7090wvXMmXOD>imPl}%RL6hmay#gRr$9SRr=}o4Q)X#CWxKW_NHUdk?tS(ruv7Sy?}7Wtduv z4Evi0WsX{SDn%yUi8{=i$X?pg+mhu)f4^)mN2G5UzB_LLNLG(o3ZM;^ap^IPAJ6J^AP@v%(MiqfYCH)rC?zVmF?2*5^MEkCO zCUsog=*|L%o+g~LpS~)?c&~Jx5<)PRwd9>z^HmvD0@r_u!T5fpFBUT8&=g65TQWa1|!lr}} zXq3(#G>T6Ys}P%{WkOhGR18Z9gW@%^@I4axRD~lDZI$H6L9TIsFlNCXN|dxYP)cB2 z&bit>P)s-KsHuDDN-gdc-Oc%jNKY4fSHoG)>TUFuT)H%J0oRd~bH>mvWst4mJZBwnuNLRN>ZP!D}v8sMPbF~h-bE79EV^IGG zcMLh~@kXf5KxZpAYSa>3zMN0M?_1Lyw8Z43$H7kvv2}m0)75xyQ3fbrQVsX__nEm@zAP+&LNYAA`^%5*eE=>~nmcyk zoT3T6GU7w|vHh+h(|(qG(#7i^D$3K)32XzC^<@;nlJfjgM452cFDPHXX0&unp_a{F zobxRnTI=Km{DCJ{3`iOH+POM5xeV{byF`dgyJZjLq7BP0f3bs3b2I8v6_W!9r0s^t7ZmI_y^J+4s=-0FBoi~eua9Wws{^bJ0X2DU7sQuOhRR8`Bj}!%7B5@$@0C&k}MUFW1anR#>FM%XunOSX0hA;Ew;$ zT^>W9I#rg_ka5%9^(^giv(hf5K1fziUwjfaTi3sZ!gM@aV!8~vrQxPlq~3~+Js+%R z9{8)cFZZ*vceOd4+R&w0ds5ZK5r&Etn2MH!3w*h>NM2lilgB^&w zLXo*aKe5@{Pzz0~xcpuY*L*#N?x9&&?6w}VR7+>fkDmKc`wwe-j zPcoOy6kfcr$V73SXRAc6`@Q%Z3GDXS5f6cTqt%>-^2P$p>L!+8e5y=|_c2ENNj#ku zQ;~b`9-ir}%avM8+5YJ!c8pWw(I6{X#v&!XOX2K1h@78lA_%Q=3i$z-OwGxOTxO(0 zXNXgA{t>q8Zh#(Z=~)!B)BPonzQLlwFYR;4J05z{7G8BJX1Ts~$Ah!!i6ISillFdt zKGSGPf(PS={;CAEI;g+kK|3*&Sl#5MYTSU4>PM)AS_0==mz=v9!91X2i#Vnm{Piw{o`W7|1vgTR7Z=KjyaQEtki*lU6MqTH5~ofij0F(^ zm1J=vEs4hiYJ;?Bv@~>La3Uc9H3-PF&B@pZvoERxonr!BLG|s6Z)d~$W!6O`Z|S~nK9(<<3!0%_V!mi z8|jcCzXR2&$guLCHYB8Ri0WHT32{}R_WD}0nMhQRV=IVG`o^)^WYNIW_WhSEbrDs> zvl7Is-MNd8PCnYzBo1N+lqh-G{QX_v9u3KXSZkK{1oYyvJ}##@yMA8s+}?e7TQ`Q? ziD@60X9$V4LXF_KoTA<_6mD+mudD0X{+`5{l)1Z;%UO1?00WlB1U4nUU}V}@m@3}E zFa3}A@S^n*;SwnkcO;c}>;nH|_rmV^;X$qVX4v`!uGr3q5WQcozrRXt*^3v~3`|x9 zP~^i0m2%@Mzz*JHdL) zMdvs}7q@E6d_rMB9l?k&aEcIMTsUZ0Be4elzEbYPjAOR-aF_0PrIWpMA@y^pbsyWqD` z;A*q;=+rW{&#(t-N1EU%=&$Is+gh4pnsqk{@EL4uZ~)$J6-Clku?Il6zle{p{I%%O z8f(g&g!z)2x3{0fYCpyyAe&_R!U*wE8P?$*_J%~!ZEGB5t8_y4B!OB=n_ z!{i2s06IU}k_1_h7D^{Zuq?E&y7;+H1-ZalOX9EKqEl822Rjp2;UD02@`NcEFCR=) z4jpdTnttbcPeM2II5DZLD!IhL-A61-H^aJ#JJ|A0hOSVhNv)@$Yc#Q%H{L7(9l}3} z-80IWb_iQJ?*W(?0CuB9{@CYqy5J$oPY7w9}f5ze@z-XB<8VTQ_JN{#d!<*K(HAjkf;;u zkK>#`d>5R-g)`_F2EHGlL6Iab{0_@FMr-gP`VL5#?q}-f92ro`0KET>!$Tm=e3?jC zg1|cpPtN%WqS3PgFAu1_L%=g7jcmaK6}c*BLW(()TNxwc8txpnGc8G>tG439GLrNFH$)1q_|BcF5GtH z83B7)C^T~I3uV!-LAwHg4!38N2ZY@(;SnD<-q;g#NA1)R{LRr`oP;>bnQYe(gmueL*Hv01^pWdG z+fczEU3p6QOKxEDXr@S8fxv%@hL#o8a=6uUr@2 zt|O>K#nGFL$1~4?2X6S3HTblyAq$581O9fo*5H~>LzEz0(;V~^(Ubtl><58G7X8^* z8>Nb%G`?!3S?I9VG86RRZs(HmSq)sWGwxoG?h6NPCaxw_F}Bv--qa>Qx_4Jh9;7Ii zT89Fozlw!7AS)KkTRdv#yUg{B|6uC)i{m~I1<71iZ6Pxw0~ZSSC8R*zX0d7HM)ttV z=WpBI97$Wbr;AdtRtcOFP%zoovC>exX)uk!aw;^k|R}H+D zFT~QG0oUAs`+8exz`Aj4uM%K&6A6m(0Vn(`mA=#$mKBpSw}Qxa8#c$GqTbZF-AvPq zqO+Ytvq+t9JG(?!M&IA{YE=B;p?FK%5#<4=*Vzi9AD@0@tJ5;qD2EEr2%Z_0g-g9& z9%?`3T=~RZFgvXeyI0B>+T8C=y`Nb6+u@R5hBc%&me(>Mt4|E=8_k=fo+B?A{C%|J zmb_2}JZ#tU8s6!ks#UN3BsUHv8rY91+;&%Kk1V*BIDj6kw|?Ni`a!!xqAhTu{oX6- z58s21#IIP=)SKmwPvi&Zp;nS3r3qmz4jiIXr}R~?EeK|?GmpOfJ*?S^Y~$#EnMeiY z055}0#M~S>VwW0$A68 zCV&Y6kNqzHDbx-;46_)86ZE}W+A(*4W~{1hL!}`Vy7SUV&?wR9ff~MsyrHmGo|Xf5 z^v_SZ^LIsaa4M*bLFtH>18_z(HJal{Q5`BE<|aVDI|3r)9RsBeykxw7a@?bt!@s8g zKioC1vqv-xb_{w{+>t$Cfha6+F3hg*Q9owZ#SM`QKty@+eX{?4f0$-RDpP*V3m{=Bc@!?zEvgE-BZX z^(^rv9R}N!@RIik;`=WS>GQ_r3n)2nKH-SI4K?6(X1}%1!PB;;yp^Fv1508mb}Hk{ z^t*?7`cDNKYRXyBN{lZUFyj3kaH+#N2>r3H=!X!Lu+*i{NAKLBg|T}_Z5D^qNUql`yN65pny?0S7SF7SOovT*arga)c@qSpoK5+R4(jd zipi%&+C>dtcgT^zTfZ4SscND;))jffh)Z_!W`kXq8CO1@Ald42bo_Xc3NCb}x6-?S z-{)N0_~6ZyC2L$0`SHAqR0gl-bN!7UY6JTJ36CxMtlV=&yga?`LWkS|z(pT{%cM8| zO;#*bRJygX(uq)XUO0t>S9tKp+V%TN(+8=t1&V+LXi8*z4|niEr_-}UQCEoLPq{6yQ# z`~EbW(wFO{r6p$m-ZZ-r0&8pQ07$%_Pj6X^74EMbh>m7yq#zJV90RPUI>sOi#bL{= z-o2kUd)5VL?{>qomd?jVl?D8lCmqYEEMe;?Q-MpZ|Xsn7XFKU8A*YU*1KXRUUL7Pgj4{wcZAQk{2o95JGE~@C5}iEVf}^Gs)wl>%qfbM)}dC1 zhL#)iLirLq)Y|Vks}j|oQkupvLBo;;JETFUyze=Uya$(RNZ)f+$yPlyaTF3=>HDL) zB%Imy`0gKZKpS+B-$9b{a*BhI3E&wptvFbWsh9s-Hah9w&BaPOO`ffv|{Q zf=yQ7A^z<5YW;+tF-ApV0;LH8jH9s@vTMQ1_CvBh&RY|d)CE4YZB0*G+F~eAo zsJ;t}y`GSy695T|ib)uuX4B>+;YMcVb0DK@y@w-krD zt*+^CuwYxOk*9K+a}t}y_b4kh<0(x@#ZZmO%`@D=K~LNK|7`5RcboLe*7yfPw4u>` zW(pYkw~_SUWX`u)U2I_5i;4dM?ddbPP&3l%GK?%H2fc4RCQV`ZbN6JPFjzzN1W;%Wd*ZuB-|-3$5w zL4$W+0?rSTz5m-YqNi@W1Rl^C2k`&Rpdc9j6VZxBZR+i`F^>;+g;2>m#}BN2)U5$N?%Li6|oA6k+kE_qb$p{M7|_Ld-+01~^f?3;nNQW_2g{g$eXq9)!_C#hv9=8JtLv< z{dPpvKn`89B_WvxektNLs@SvKN*dg;610=Grq5I%`I_@wtEjKZJ z0xbtLcRn8r4;obkQ0M@5dmNDKj~*f@*Dd~nKPC-*hTzcfBK7q?Z^=3;Jvo-ap-I}J zcz1F7@GXRs_Z49%VyH~+Jbp^Phq#IC!j|@Ur^99pu*FS3oLRAA1p z*&okB?eMJ^AgrUiVvkXEDRYwSOSicf%-Tx^6Znww@4e$!DAP9KdX{aK6&|kX+~)J4 z%x}PI{*#+H5m?*Y25*rg91PGjjTXei;F?pA9k&4^u5@6N{M0!6{mu@YHna4`O zQHD=MX@O?uoHs%(BR4=!mZq+2wu{eRDra%t-1yd@wa8%_5PSd77$t05XQ|9DF-J7V zg({YN_N@ja%K*)9lU^`DqqgXKD@1s9cIEUpya4iCMEu*}|5} z<|W#L{?iQDjxjy|kB@c>*i$p*YLUvK+ztg$GDJ%>VYIDUh&oSX^0ifgVmGh@Y^^5* zsr1c+29=2~$TyH$%c0{QU6KH4{PN)g|MCg-V_cLhnx%LI?2D)Pb~*yJ7C%t)&k2tk zWWXL`T;@g7+RWyfv1&p~v?rdWiOSrc~9!YA( zeCCvVG)&E#exok90&04d+3$U1EOG=eGp`~~7ooh34^V_;Q95vqXNNDQma4*U6O=GJMd2*oWf$3ll4tFkDu_B50|>0mrn6&`%D!jv@Bfy-E8QLIQnnj`*1V1~8aq{RA9 z1V}teTu3}doCV5}*#9v4&BM3fSW{#aLc)KDrSGM5S*QrS7o;)KAj;CDGNnxpHve3e zXIf=_{W&tlh^$<~v2-r!vXh*Oym8jOzm<+8EsTjJ+~ms5j0r5ArVSdp(z2VeKdeV(Y9Ycn;UGn{cn7z%>;5Nb;!r#@tFOB zl;xc?NW|@Inved;jiFxu8%5eEo!-1Q#4<5HHCN#`p({VJ&V|TW2iW%#TSz?|z)vs9 zHtaq=JQ)`L@}}+D)Q<~sp-FdVbDRGr0)$`0cDwe5CTFaymg5!=Lmku1^s**hHaMZR z{px@}-|~;=mbd(2JKEG65rHa>KHLCiOjzVna7s9H-89$YSS~5hzCtbJg?gu9>M>6L zC|MR`1g_%}w@rHvF@FB#uQ9BK>?SJU@xH=fO^3YQuk(wz;zI!>3%})OGd?lC5Uap_ z&I?Jt>tPT6KV1O)u=gZ;XB}K9);u6w)~2s&^Y`#h3S*S!u4=jJPyt?`0mSdNNjxb&i6;yft+(I{|OgxH1<=7eNcVA_8rzqIg4U4cF0 zf|v+(=+$_M@d|G#3$Tj6$YC7Pj&R`IxSp?Td-r>x?H_-0$Uc}I#_LTvHqX_#Y><;^ zbpn`P3ovqY5U;<6W3(8a3d?UKj-7J1q;XYymEcO!p@G_~uwiXD)v2z%N`?Jcg@%DB z>}1-e@t+f5lQ!Sc^S*{O5N9{~+=c0Paawx_5CrtlggWv%8>9e~7d75C(I2G$RA**Z zT)^$=UiypwER#cSsB63I*EAsKO-dg-h~&qOX%DLK@?3tlykTg?v!&@`vpVVamnnp; zT?&v(Lr{Ydsjq#2H>7IS67~f9K(-XHQGF5>C(yG1CtZ~K8`Fe+Q3Sr4p3~U9EiU}S zz=O|U0I+(h{36-{w-&z;mz3!{=R$cxFOa|{Td+#DdlNRvz znAm=JD#}`L{K)Z%cHcJ(dIvMl;)T@Xr{X^6cq6%BY^1#g0Jzq&Jb;8>>ws5fnB_Oo zHzjR+Z$Hf0;!mjmFWn6!(fl7YR7YL1tQ$m!J4I0aiIFs|_R}F}du`XC45+TY4c?V`RPuj@Zj$k? zutF0h1b3q&VQx&|(rY=FJf7s-V{wMtjFs)f_0)!2kq&?5efwag@!wa2tk9&JtZuB`QL<6&Y^K`i;soy_~=iO>WRXd`&$^vH1 z4BbqyQrjQ%rniW;&}i}svaB{~@BQ_=KXd0}LVqLld9_6|^FRXF?L~Q~GxCd?{G+AE z?TNn^L<7nJAu&zlQ49O3rnaINU0>o5UH?E@Ls&z(y!mNT+9wIg_dHn~W}hwSp;n3S zalL#%j-(($q&`$v&*6J?On)FZCn+iS8!549{8F6~QZCCds9>}}(qLbjS+gR6-dzGQ zUY#ZOVv7UCSD>TQ!r{^1cWnHRE4n|yKS$R9dE$GO_! zop~Km-@bbbE+J*wuBSoknB0sWk*s~pui)7BV5zUiw=>)Nedb+)tFzhS=mu&dt3J@o zfUsT~jh_$_DCJ+CozK>prBas#`B01#I^@89&v+;I62_P*VVm#XxO7{$eE0^nvxfg- zF1NYwR-XdHy4D{AY<9w}(XzdjlN?MV(8M!+${L%HqB-)ifa^i0fnEQ_+P{sSY^?+Y zMxw}YYNEoG=UFQ>A#5SvJyAPhv2;L!oTNA!U3M#@S@XVEp-yF3LJA*!aL+C*(mGNB zDkk-1YxhU#^w55#bBStWB5r&$&}Ni0rtI7coNZSIJb>s zc((|^9^GOn@;xS~Q;jCo5VJQ2#596pW>|tz_Zt6l_J6V}TLQ5DP}lvnR(=yXA9$JX zIG3gm<*kC6-yf~$c`uZ|-as5Z%WH;fK==pWGM4RbJ|L$ZQ@3Hs!+R3X7&DF3X7%26 z)1?Ju^1gRrC&V2r`E5D$ab#-f`ZpT=PCPYd0V8fS*f7q*kgj>$#kKu)XH4auVeV(+ zQ#YQQu}(5a{F1j0xqrn~9q#An^0yWMl~=Son90$`K`8-(aLNIXkaBT?@TfDYqwKjU zM|B1}rD;hr1atY#L{iTcU+1#K#t_9CB|eZuiX&+!*`eZeMHI1SLbhz_AfuRmO1eV^ zo~<-qMnO^FjIt23QmZC{RixY@|FL8tow|*J(wHX3|M<_X;h{k&1{#pJHeZy*cvwqX zg#|@8**IvB9F2podPHxwZinvtLfZAiWU*sdUZsznYai@<|9rb){Nm~hrF61~SC*4- zR|muKc523Tz%pc++9ZP9=M6Bt0W_FDF%j|gtqY?=Q2}E01&@#B_FccmLNE%n<@3L5 z#x7h`CUzr~dIDbX6&N$9{%6_9V_cRF*E_RnRd8A6-!!-U5TAf)0V5Cfb^b3fRo||y zN67I^yHz3qvzG0)VJJR)PPH~x+dL0=I;_8^B0DM3xQ`yONM|#AqA*pcG~jqVT(-vp zag~SZq`zK@nvG${Wls@UXj(Ae{3nA0P{K+;V;hwXVL~dhvazvIvl7V>rGV-8x@<{q!H$^Z<)c>A$PX)YAr+5iZ{ePm6(JuJpkRFV8!jo2`2kSt{|^9uoB65U$(m{jOHOSU!8%jlUw(ld3nMw{}3J}sf9a%`#kE6wq8?dWP!3DyiKx8 ztl{_cOyThf%y3~p?aq_GBIaMDcSCK&}4ayb6RT3 zPpPc>7cw|OEexS7Y#V*R?x=>}R()7*eSC$auiP{DICnUW7>et$PO*2mclg-Ocl2h6 zc7!r~7*0W>(P3wHdkUnaIFCS&)JUm7YNU5wk-oxvgiTQDu)TXXI(k6r(X^NeoA^vG z3i-p;cdY0-bLXJuOHtLY8>h4IH}SebX#{Tx7iLsOp~4PNqK!B;qQ#-^I5b9h{d^P- z3OLxW_&!-^9Oszm7c(`n7^N6J4P%?Znx!4uXZf4}9virWECwqfa-h#Skz&Xw4wG)X zJ5a1xqiPFT&@~=XYS5wsB%t)>4Og|-vwCl!IbfeOs%OJ@aai`o2PoH%&z|X!ynC+4 zN#-@p?OV9pRE7bHUR1~AIENV*1-EJ{_~O#@Usd6e@s0p6UXuW`K}7iWl^ck@KE7`> z5CF8sLQv;t>2#Sb-kE$c0>w0n0{v)YA^-3i|2PWW=b-|cI zwHVRXBIomgf=S_s+fRqwmCvD$(K8wyRiwKovw&95^s$rKH+9bW?p*G0V2*uHqGny{ zjZ?^_r3@%QuN@(EIH{fG%34B%Hj(7z0^UyF8N20Uu-LExSU#!xkzqO?E$qU2VFXYT zAKYMxVTSIj7m%+1S`JYsRJ-GRcfz7r?`2HS2X}6wQE=K1E~jNUUU;i`N{j0OA%Pyk2t_3p9psl`(=oS$0{3SI&WD_o>aQ%L!ycqOkTx45Fwrbg0F820X_(}XciJ7x zLyEnyrVWM0@R8BtvCsQK4tiov$U8`jYH-LGD5S&z+xH{LctFbpnXt(SVsiMNAXt!H zD?jub5nl@z{rmf6L%^Voh{)=4rSbRz`HXJ&yMW9{`}#Kg7mcqmeb{t}K2y!B%Qsgo zhqurty9U%y%K8~|Gn8F>+gHBU?L1`U0_{qs%qg!ez32x1kuWw{GKB?$@mlGAQ|l~i z&8>oS^)On$fGk*Zxrx3jtJYTJg8Rse(OkSgoZ)ggT3Eh-9ymu6E+*sa-C78&<#t2B z8<0MV)*De_0}dC!^1b_FcV%2pOR&~HhCZ*D?7d&~j=Vka@h+t-Plfyszk1j{TVG(q zW8Ncg-6Pm-!ROZ9(^aSx87MM0IZ_fOfdo_oMc38rpNi{Kz)uD2_elOa6`7X{IhM{v zK(1l)wN=+Zj~8y?hi#aAtj?)Ypbg0{k^|0A+-{ul%<&$DuQ)Yh7Rhc{JO6if@podi zU}(s6{*wJgB#K+VlV|&*K%Ah6xtfWZsID`A**Lei`b<<(9Zxy|_Jf9vpnjf>AZ*bv zIuUT5_NC`wc@TEGjHLHnA?L}_AG68K{tXD>hxsn<@AUKJf!C!DkymJgLGXu#`3&RAO;?%vbTHkMy4QmpQ|P`Ci$|aHDs+}WLA}RSVILfL z%1v_N4;Rn3?&GF(5xdz~`mh>dm=Cksc32tF_eob3%m^+H8b;@^WYCl?3ZLj z*h$jMY1|{pju~SOq>=lbRVQ+oSLXUU0i*{AIY~?V5Y2+26p@ZN;(Ba)BCD9!x=b~D z+f@Pb*}fjur`KOXgN&D5Gz*-iesbDikVRjE6m+l|a2RkK2-qY_?LXo@e{FzX5w)t6 zCBROO#uHmvCr^B}z_I-GD0oSF=5I^*n|kPmm{SS9UV4s;*!V!J*k@b8^AjKS>Q- z2r}oQq`=rHR^DJ290g!WT+B*)x>Q8TgGi$B5mEy*F)}1>!+PLPN%C!yJ1}4#Hn_W- zgq;-~G6*!>v3O#rjn9}$NlOFICCo>&y0YF12MF_YrLl}WE>8Bc^k67ig4P=bTDHwd zUxs9Lk#7+{?4+GiwMJ5aB=@2q0X;yYV-DfIOd9Gx$^NkQ?{5=RS%X0`c()#F(# zg695uZH5ev%uXaJ!(Ud|r$*H(s0~?mT{jS%crJP@a=|!B`g)|e6;wZN$Sd#-g~TE4 z=qd->4zO&v5>N1J)|#^o@yvw>2vjs$Kr;BH1IBR3%$~!#bh%-^?Y$0iJ_=3dbH`zZ z0`qVqh~mB2@|dZFil`e`afN%KH&gvS_Dq?Hj~}ZaY`{NpLbRcI{8NYiKS)02YhUP( zQna+fMmWD2e6fNUdJFMn>DMECdXNIgMMn-3cS-Lkk-s2W~R&#MU{^HXiiZO;rnNd2qpFBg8dg_bnt`X-A2R z!~DiN1rBnQIl2dZ_0Zy3K%6o|kjnog>4NE6eayWO|0G5dJPcDe_7(#EsAP}?y}bHI z%PRgXF|-~mPp*g0hMR})4e;Yv&2W85;t)u%kHq%FVy|~io%JilA^Bi9DT)AZS>)n39$Mz_fpj0w+z!a0 zyU6R=;BM4ft_3T7b941_VS?N$++_Ow3n?^b^B~_Kg6UyzL2a`pXR1v7?7U#;Pg)hH zBVozlR~rHP5NpPu`l^|>9c78Us3B9tZ^v)fCA{Tn7+xy7`@7gGMs~jTGr6#UPo*+- zid0=pXc^fZA)jBLh0RO_kM#%Wp`&jhy6ONmj%ekp8>Sg(afx`}^wB3tVZ!Y@;N_-J zWH%U3k|4XBgk-AlWJWDmf%66qz1O@u5#cpHu{xh#llUilj1$~AZ4eS$7Q%dAFdpou zAvsq{577-bJ^i}E`r8+j^xx@UDAU~`q(7D_t!w(omZVS`fJ&k3I%Jo0$lKI0a@J${ zag8PiV-7Aq=S=1jZ3*R|ejH1PIQym=ICWqgw=l&yUQNe_MMUQ|kGta08NfI3g9$kl z2^nrg-OVlG1;gst>81#ixC|oReDOgjKeaQ$37j;Lf#6FQ9|SiK&^CA6!!`E*yHfZI zXNhVBv_!cSjUn2S*&_P(Th)u5kAOV$TE5kb-w)KROgUjdsT{AYb-v2tDXhQSY8b&P zhYO!|i12|kM4?y@fm7pD7dFi?hvXO>k|6hwYVqZ1jh9qskJo?7{SPB_dz)<~QnKX(nmAY;nw!Zh8kk{~nso3K%K zQGm?Kl#@|gzs)?0enTu}L(Q*Dx||PP+5~3RGBLwyY|FE@@m#H7aI+{cBZ~>B^AD?l zN60GGbpCQ)e4nK78*pR!Vv#@P9Mixnm?Oh>ABO2Iv%s0baVFU3sQv1E6=)i#%nnid z-_U@}rz;%misA@JGFZJ>A1SS;cQ5x^Ox14`XNNFl;2!cSCOjw6=wcA+Qmzg+jLRK| zVUG=2sJ6}c)!a>KGGm;(T{=`lfu&mYdl%n`x3BJPu| zt2p#b-9yl4)HG3-V$Xg2JRRe%4Q{clMt`@AlAdeTSBwU7ADQ~k&v>Oj{A=rD;zv7UaLNRG zDP1WkQ@?PP6m2%X_guwta}xv6%?K*tDLO?;MZzSUA)Pk|C9S*$Q7v@Mh-OT7DqbP} z99LdQ(l24tIU0x_a3vm9dCryHaE{CvZ{|TYP+ssD5bkY5RmQ? zknRxa&LO3{OAKNt=|);odgwu6Xpjb}kr7Zj6i~wN4BpTC{VhLX=A3=4wbxpEUu4s~ z-^HfO9|ZDt@(x=%eIL~-xypdQvz#e$k;2Q-yO(yA$oVooM{rP~;vV}>leTE~b$ijE zfsaF1tRCcj2kClT=$9lKDb}`!ZMJ@j^(NxxP3HHyv4TY5WU->`5$@!>1G-zJ{i**Z&pZ zp>k_obylN@X}|8nn#lRwY5W!?#`%FYn`Mf{Fh_5%4V0c^7US#uUqI`2Vtyz>z*ms32#3*R#`ja{7n`3 zaTd|@na(@Iu$t4GUI<0U zDZJt0r+{yF!LT1rw7n?jm+@?pyb-BWm(Rsx{H=8%%@Avx&7w@hFOez*P9Kys2<(kl zv&sB3ISd;X24>!Oo1-%+jAImvBOm49*ChR>xVY@SGhYE7vx=&mUTO+#Jo|xY8W<9r zmwNBdBd@7{M91T&d6Us2a&iG{I~gyo6!gPXlSip$Ru0L^^wWt7nv1)?;u{6X4IT3d z2QZ1yIhFR>+^?Tc{LYM%tfYJLe8taXN#_*}9&rYY93fb2T2jtA+4EauWR0L`cRtrd zPoqNt7=&0sJiBfcVmD|oa(jN?7oQU22pt!bPOEl*8SWl&8}Mzu!vF2SP}Bv+)R+kk ztS|JppWkzRNlPybuY5>e{39>Jbt24lBF!&`^gq25MefZp_1jK{`kLN1-6gedfDIX-29oQ_IQ!Zt zCeiWM!&s#9#{|E>>nV7kPo?Z;_nbZQhdxDE!5;6xdr^h6_jvS0lpa<(iJsWAndkO+ z{y66u_L}~cTeluIOpk42^TO95e4Oo(;|C9MsJ@SWXD#O5uWS}5Zf=O3Jdr%C-xkw0 z6m&pO=Q3Bz;}s_4WHYYf?zvpG;pY_LTmPgTcxv~~yImnwmZ=L`h{B#|`qVB9k2&%ZJ0n#O<)dzu_lO2>heBV~T2PUSJOk+vCqR_~D(dF*w2LQ33Vw@g$L)PRC6^BsIG*4DIVhWziks>J-<^mV)AD$x40$P^>}S9ft5`c#NH zFf$w&IbZSfFXrDA$Vv`?Lty>27_M=*uVk>S=%I0wFDAA`$^g`{>4nq{EKUS59peeh z$WX$W`Aus+fdy%!aS@$MTD^!T`jZDeUySD8z_GNwrTBJvfOmXpjIbW{9uL@EQ+fFa zdGyh~)B41cx{ycQmnzZoenw2CU`XEGtRXY#<3K)Kqf2;Kn(r@A+DYj;r9}zr~jeEbTsu@BVmtK)~(z}LD=ZS76xG=3#Y%AMmfTw_3x~4ZMMeHK)L{%~=Pj>E z1gTn{8Wz^7jMbyE&L=gfBU|C=CllvQ3k0=I7h)3T%>Jnp&J`-ToA2?n%Bn6-Uo*QP zbRr*T93+;;tLL%KIn!=nsxu(C#v$MZQIzvXJIV;6IPMdQh<29gjFq~%TD&%BmoLAe znM4g(M>7^He`tFDVx?!!#(oRiHG&$7AC%G0KuYjrssOUgHz; zBG>qp(JEhM=F}M$1baU?+FQPtD5=-EV4WJX1vHiRPU!K*EvY~I&T4dx%e>SC6bCtO z|7wlFpOLCg$qbJ~9F#VG>4ucf{M}gRi&I~3nkMv0+6n%Mmb;dDSGqIm7a;tof)!ToQdqZ< zcNL@S1|R6Zh!eQDTC)b1P=hzeRvV~}@|L0-eH*MiV<<)M;Vu7pd+Ins%DMi=TifGG zoSfpM0qITh^seigevmrz7mYj3`)cN%=LH?MFC8*q230=a;1lkkdQJF2Zq*sIu~Mvj z7Hi|7)W+6sA>-}D(C}ej!orV~2Z#jNAgsvVV%fm9PIpI=8tAQ=X*QTw=$bh;q>l3w z6x=mrDajup13czTfp6f0F}+2W+7C{e#L~uVPivt3@J)&!D?_D|n@s>`WrXt5wCkt> zOtJDydhdfvEuL=^1cv83sK4NSh2e%Ul6M4JKFuxo%96=HbK2QOV@T6r ztO|Smo}18#KGwDU!i`&PL%YB(Ar6=e{1)!Yg}d<17n$+BN%TUr%mc1s@BirJ2nD${Uf4b8 zCp(LEiNy#i|N2y;tOYs+6JGDKxWUAXHojdgoD#nBhe97HC0Jhm9z&jcq1r7R_EbHo z6m@u=^ezvdr2pQ}TrC)Z9M=g#tr5BuUfJ;_%vLN z9?0C|!Lq`T#;gSyu_4<;XS}WuZz;7`4Aoi(C}1ZrMMsgJA9-uI_J3EMb<}di`)QNo zT48mIMJ>J|#zPRj2*7i`fBS}jfNG_lB;+1&ZguqOFV?C{*_wUDtl%u$x5@erGJn%) zB8T&#RkjSAwX}=;-GrP+p-9i5mcFb5b~(pYKE5?;&&7hF1 z6o~dDS1xe+sbqUM;OWZU;SE8ulG)#A2~nE%_QY=iuCsq23YqNO2ci!<)^2p0t$=U? zK{p>wJMcau;Yq6<37#5rXcO;Frtd_xj#EPq=9RJNDNs1f*ooqV>6dS(cL&LMZdD#pG70l1B2Fi72HcYk@C#YMuP66+ee({EGKO5@(6|GCzNt zIgv@Q(Ryv~6F2~M?()Gx9*RwclOp6Pv5jMW~I@c!F=@LJJbV+S`PbL6<1;_RS7 zcZcQ!N=CR^wu5)WaaV}_3#UDbVHl0XU@?qx{1VgfvfRm5cU`Cd1|So|0mR|v-Krzq z>X>>|3HmD6UrghkcowwOhxBS-O`Y)@c>KagxH_sdikJET+x^}2jL4Lja=~mO-+Yaz z_w)PBzOSHoBYgBfyZdimPztT)0*!i{LnY~pZ*3w*!y9_O(kXT#J$-qRL#X^ZL zC>%jeD=t3Kj8i%(w$3^u`3Zp?Cq4{)9|SU9lNf4KEpTP!)o}Gmh3bA7hD7ciZlC?` z{_wHX(UWR?QH(2Weu??a6JCTb z(^UKMFhMfQ7p#ps+s2P)PO^3YwPNdzg$iY0InHfSvi+%nhzf##HwB+N&;34Eb~k(U zirHTt#u6tJ#{^zoB5$`=Etnuk1|F3}E5s#~YbL|H3gPeAjqT0)%$_Bk`9a&8yfrZ3 zKx{{d0UBE+O#$u?2u(ppNvBg!%f#ay3-ZjCnji)K*??DCc(~b=u`cg!d*!IIlLRrc zld=gTyYTr$4i<}>R&BhZ>z8QZO<0|nZoI?{1ip2l1Bb^P?Qg*8i+NQd654P~NZ-A} zrj!>LyjM&TDkOe{GBPf?W5U_*do8haex0f##$ZSH-m4oeKfDTMqAC}Cyf9^en`8Ds zgIw>topdc_kqaJ7=>vk#zEC9)BGsSZz|z2C!)D|6jcmtwA}4OI>3jdXir@VZ(D#Ky zw$9J)=$52wwrUsT-%pews6oOVt7`T-4Kh~>uQ|2Jjwj}Ws8|+>&A-{J`zH5zy2lU}z z8r!7BCD3snOvVCDQu|$70+Nh+H3F?mlmvV+g7Z;j=$>d^N@5Par-~bvscL5+kj3=t!0-UA{HkuV)%urWD<5|tP`1_&KJC`fWr?}`WaNWZz% zYMSwYNKQrN8WlW;hudG`@N+DSQ`ODV@gml+cR-%vrN+$e)P2MD&NSMuhW>|12POWJ ztOApx8998c<^tzD@HJ9iUKW20pN4ikv~e1oGZpa zXU{>E{%{j!@J~z5Nw@9MdF_Q!ZOkp^&sCY*80D68sxJ3PB~RWwQnv5-Xr5kf4V!`C z^?+jI=VH(>wHtYhz0mcN^`qaFy;l8ck9=vDXU2%o((u11nzW8x{;0+U?jnRBl_%VD zpOcxq^yc)EK2AY|4k}-Jb!RlH+`Sry-*AO@qY251+-h5jlnY$T<}3VC5nZtx;IIdG zM_@}IN;~~wkZW&&X7Ltc4n~2~6(0(mPVC?(oT&>mv3XIE0w)uP?qL&sc)o{-8i0bb zu}MF=G|*r5NCI@gZB%6?N6##+URWu=_{DAnC;Yk)W_IuJ{{ZP*ueea@J1UQpqa%2w z{7&)|8g7(ol$iX=wDPK{?9iXD83}$k@faCb!R>E5H&=f>>sDI?>c=X0@P?T_+WT8^ z_*Z%+ab zt&-gj;8~chj@NuIb&e(!AfX`y*eZmS2|>F>G#m1boZ?ZO9=6DD&ewz7=x4;IQ=mJp#MP;L76?uW@1_qW&) z8*jb4#891wW%|qt2#Ox`2117i>iv#4vfr1RK1xuJk(6e__&Us`7BXesY2`WbQiM9+ zW-~W#b5Evnqyr-@bZRMO#B0DLxWQ{Ok+(q_`m{+Y_feGjTkosuV^vx!K#>P^0(A;V zx_s>)2RN^>z`*L@USfa7tUgk}m+@9+M+{J$?dt%VIar6KoJpO2#=vDqslY+b-3+)K zT&N~?vr&4<7Rn2>Trt#m+B_{$K5;DligH|zWu2YB%ZV!fhd?j?gkb3ujmD8~0i)8w zBZOKJ0`2EVcE*GNIv()^mVIAGK=gLCpVl34>(b0SI4J59j3=!87*P=hSjb= z4@``3g|hCt0RtMV!65J$U{*}Fu29dbr4xPxwUFy zxKe#FY~qg9UER1^nD}44BzoMjO+L)$(Ti^_EqolPXIi>P#Z>b=nAD8A3LlgD!-8RW z>_(i$%%-+|iIRnMrU^5-(&&>$!ysWU;GQH(NI*=RoQU|qLC)8u043#4si*>EquOU+ zKM6 zlAZ0djerU&Xcrj3G{0K$-bhOnxWp=MG>P-~US@#~G2uy-~{ z#_a=f&=&-u!_I;Z)20w~$poKkRJ7-EN1zz#8A-ToDulNN} zhMK5F(To)`pp<~0ZzY{?W<-cuZGJsB{-RzBIv4HrUIWKt&beNJbG3I6`>YB|kYppXD22r?5|Td3NCKY}?^D1KYmK%y zJ6!q21qh2h!tS`hA>+L0QyU;oYwx+m-HIV*HP)rRx39a>A@kyMdfif97#sS@^W(I@#VE3+~kQ z0El3W)w;{Gr{||)!T~IY6fHT^3wIjhzc$DgXoGmAyx0l5mmv(Kf#{qGjlJIWH+-Af z9_dy87sAL33TI!AGYJ+y`EsXe16|xQ=}yiGAHr*Z4Cek0>V6d<_NU~{Z?;CGA!6js z3$~8a#77RR&uNUlnWw7BpqwdzGQN8ztc{wRs?_4ZSF@<=M0aMzgY2T@z^p&~@%8n| zPb;G|y^em3;^Zj2w6p#7D&d0$B@J)HQ0&Ib&F(G3w#U0#lO0bqYZu)V#9lKy@dCC6 zz;$3Z`1vtkRHgml5r zKE8ZtS>|f@Cayq{vNiE7ND4TR!HXLQ7e30h4bNsI)Al=R)((8-_qa1s7V2kpaiPQ} zxZSV!q3{e_HGT3OQ&LXttjkUsO)OX5PpWBW2mCmpQlgw0IPiAXb+lUM;<)|g{vWgk zUT({KeOC;MRB(?8OUbCZioTocz$`7fHxOVc!$QW^g7=4`mFOyzsi&YpQL4r4&=}Q( zpN?IEKXyx4s#U@>Yza>9-{8YiTy-ld9xKNCuHZ-Vxh~~t^Zpd&XJs|x?5@o3ZJ=e|&8=weq8!bwxN1KndZuyw?X6umS9uhu6> zCXdOAa!v?dQXaF@h@U%Nenfe10JInY(DD-9n1<&;7suve8pQ&=e|-#F>Wpi&C+JAb zTT>qP$fN$lP6@ydvRO=7CIBv&=H11qa<7i=$M8z0JT&pA;w+d~ObO((MRwOust9}tL75+Jn&ds~o%J5kV@1STYJ%=#z zFZoPG6oEXX4ek>v1_;)EP(X4Gxymk0!Eyv7SM)r=LlI{@C11tWLclRfSO65dtg6gL zG>Q95@!nlZnx4aTz5Jv6T~CSVAYxHuyZ;N;6Q?Pyw{(-TSCt0?lX zHdTKtOqSd*2|)er2j4VkfMpF%UdrIr!#K%BwckKK+ zXonG~d!j@kog;tyWpNxOD3@;MNcHR74DquTfb^BGCuz$egHzegXizNdT_ z05^jqM+9bpHMENuD{Nov(8q8AV-Ij9uVUAAm%>j*_l7AeBicAUxQWgk0WFtoxv6kg zFyh6fg^)+`(cZ!StoLxj7JN3kgxSLbaS2XC+hdBrp*$?OK zaF&tHPoBse3neh@pIp{PF}&OlD;N4#KScmjrHFmR_SCbwCGlb7M0s8Hy+i{Zm1XCH zhgB#Xp%m&4k)TZT0vl`B+)hJWqXW_FD3NK2z6XJTv8oF0LA&_q&&5dy#l56HhSL09 zHL;~bm5ND=NI6pR(*41$i)s0d(_AnB&K#lEFY_2+K{W&3D7*D5zUV5Ty6`NFA+a}H zAuEOe9pkUhB(sV%36g1aQa&|qb&0RKJw&wT zo|gIHz?sr0&Vk*?5LMB37cS*|x8>-;Em&Msl&qSYh;v@byMqd>1sZof)Oi6sq@ZU2 z_Qc?Cz3@?@&qk52?INAk^=eP!e*N%#>;Y{9jw@5~hnEyyT{P}b)}#>|9UW_ifTrA% z-hL>Ce&JW_d~s1+z;eKr=^>|`m(&_TNy|f=FCTC^_fRgcxXy+>@b|a%lRBU$(d_2F zpnZ(@U3`hdSrKo2cZN( z1vE!ME<~yXm?69R*Y3atzSV9S1{ec?eGD)FV(%xx%JD7>ZID7%SZQ;) zplf4U@HRGA{~%(p)r0MkY#e%!G(k(Q+5xe9#JaoRV;Hc1y}hBM zkG`pU`AZwylY|~)Ac_haO2zw6Ij~5b^(S}P)n!X|1SMU<~HO39uJ>s!{VTV z2WVSOWM(Ksd*@5rO;69eZ2~Qk*%hltUp=$>8ytoyxdUnZ?srDlu}d!3X&EyY zp!>a6apEZ!URBSb! z%w&MM#GtZvyy9`Ux`?h3Xt>O-w8#E%kMR>;rn_ScgTHJt{V*n``1zcut6n5?A?qL|HAE;bDEY z?|O*+dmF3S%Y9;wKttJ=j*)^J|JpBC)^8fwk!V^&RU?b&%P4pte8`Ce4Gg`_2)Gm6 z_^Vy!4;)Q|Je&Yb2gJi)k~0du=sX`yz=C|9Jnc@XE;LC0PT>xsL~@VdUIokrpGKpq zOUQ@Jaf;9;74gLW(M0_x6Oz3CFJV$tf?kp1Rf^p>L6jyA%;J~%S&gp$_%99h8S6H> zC-$GHL{b+#XKkY;&xc7rUQhRu|G)-vq$FSz6uIup?Wa%wxT~^rY>r9tXHkK1pfguwZ!BSYmj3xW&q+6 zu|jJT(ubY*KsLakggyw3mAeW=a%B&w-hMI~&#QnU3Ti)$0re*8Vwh`UY%nl44K12txR6Qo zHf{Qt3lMIVc2o}=;FUVi_x2{~l)E|pGC54@mWhCLPt=^*TA)g9)fL^^qxJ&<;Jaq? zY3zNI3&W96FHzq-!zkJ-@cmRNR#&7x@K2!w*7ZHQ5`orN7;26Kdy|=f#98EP?m0D7 zY|ex~Qov-9x?L0ar4Od7pF^1LuV*IL)OSsni`8ke_R>*1@zs2|0{#`Aq@=NkzB3sT zwWw-&`c~~nWHcQ>EyYIZJ)D`;_dZ)PJCS-(Zt@@!jxU-(-<)u#oi(*FPsfnAZy1(v4#!hhc!fW^hGfo zH9C4V3A|rl{_w3$n6n#j-ehMf>TYF>L^+m*{8S%P>^m4;V!T z!2kHZJnYlJ7U>x7pWi#(JXV>tVuM-sVY={NE1kaw06>bwyD0i!7J$s3X9wOj5Hi7T z52p56IOXc%-jzN?+<|nD1$G!#kP&*8=tT1`R0O$uRD0A?^R@A#ofYen$uuHh4y@y= z|FmR}pkqEiSaA6jJrjlzCGD6eK;l`F+Nb_ejyKWC7^-xu%+mrj*+o}@h2YtZ$u5P* zEQDIhcW(B|zof?8W6Ox86&6b#^Af45)x%<{A0B&l36WF4*v0RL|D=BOdG_iN%5s1J z6JT9Kfj0C|uHE~$B*hbJ7-a3j7F(6r=Ns&H3~|q4s7f1y5X&yc!!axR)khvgAgna@ zFGeBFk`9d zLXO$loY^EW<`+3Ie4Eqay!+9F@^2gxlB9gHc&YQW{a%(lr2N1}HbX*rwjcj^LG)wb zui`IRuL#etmfW79pFA6K(Dn_+7Eb&Y9tc#?DPX>d-%rwkA3#!l3+-h>+Lhfltx>)67Z!8w^n! z{`eURLlD?M(rRVNO^A2t@lJA2maGhQNLUdmEiQT`QZ!F=Mn0$y7nUWrU9*Hjp`=h*^c5`#Zwpcl%BQSg8V;T_j$k^GWL`q<$-Uop?& ztpIr5ss(J;s6j3qYnJjKj@>%U34)FoI%AhKCBVEuUy|g;tyJ(z^jMkjShc634^_T8g zAyq*tN8b}-V5%X7cYJ?Lp!q{e8u{te3$myUG$IWBXvL_U7de?XXNajS^QZ|xs%v{t zNMP&xplx`GC5UhQ*zL0p4q3L-vRx%90{hpgAwNc_11f2_Z};cf5T(7fzAB+ETBrnn zc)et_6L!2cNggQ35kU=FB9C$M86uiW%24JZDpm@t8X`V#R|*8iDMqdifG$CqEp;Iy zmK%8ALRj03SE`AIO)?xrr%~4W8Bs&(iD{JjZoO}1T^w-e z0cq+;{8Gd#zyCm}H?Q`?c2zTjR#uC%nKgP5whZ<))}_6WhwHr#{7Obnk?mAQ9!7tM|_ih&0h9cTqWnzK@nhY@!>z7hNKBN zYUaBv_eb5pfMT;-rHgr!3B=q>C-1fv0BN``07@9}QK7QVCq zU*=RtA7McM*9#GzbOvKOleN53cKg{xhw}ljeT-Ay>8Y$jnpxRFeadC_WjC!tz4I+U zO!l0ZOK5@d#t=pCP#_b2ah7nGn{e`Ls0}Dc(u0NiP9fcdZ~0#qkv3HT8Pte+&r4Lw z?38>`td!83@q;$J`UU=mdsUOHYJq31Y3_mx&B+nAr?5%p{ok9XTq}TJ^EK0?27C`X z2wG=9S+-y8CG)Si(VeZt0znS7&_V*}H86MD4oB6(*gS0$)qh){-a zbh7O@<@GvZTc*?-6|MJ|3G~AECfw&~I%{WS3nZ)snnKa;wE*S3xeknWaR>L80#iPNUj5}y6-2rW%*KoX=Cfff5TPQyogMqK5b{%$BC)Wb<8}leogdi^u*AOYC3Bu&AptN+GGQNi zu?SmIfbiy6y3y3^I0AKY5ep~{MYw*P_WIP|wB$8lZCRG*UHbYWG=zgT&h94Hh*uE# z$9}bf@S^S9&_io395+aHRytGwXg2&%&+SFS)*pc{3Q!?yDo%(7$_-bZLoyo@2FU@lpju8&&9t>I0R86eg9Ez`nfVcemkdsT2a>DyHGNYmqYKH%YW#X|2A}@Ba_YJ$K}sQ9VA~qi z2l-=z2S%^qr}>nOHMw>Tss(_}j*>7I&*+QCMcTs!>$7q?V+3pD!*c_C3;QKzn4B;; z5vF0@l~PeRtDY)3jd+a;&pcIbPLj_co^IbO#5rV_CaC)wpf{YB6$%P6HeQbfD2LG* zMNL*|y*5_wpJ&BB?2JiyoE%BvMRClBIHJBV8GbT9c>X39`OCR{%)pshKRO3?ADc+S zVDR;+D^r*MgOSm8fyx@W~lC4x|X(bt+)hm?AX(|Vrd>((<0GHata(OzE5#4S zmC=R5TbVlFNkg8Q6azxAU z+d408kI2RFghg$1-DC2$L?(RPdz^0Ep`skbNrretHE*;ZEU^Scw<*HFh`Q<6B-WkAp`0Y` zsRiM+iiVj6Ac;pL?ZPFKo1Mw0l8J9GX^Go^N*43~vFK0~zKLMSBJ=72+@);DWBGVb zL!FjZU8g-Yw${LgdN&i0&}!uQU{y0POp*7v zcErD2JyG;h`@v>&LS22SqJL{sSug(TTU?1*Dj602X8my=o98SZvM9+u!a?&F8-(9{ zSb3i8APxu#?FW7${T1@WCNWN`I-yRen%+UZ6^-d)Xtc1#E;UJg%bRdh8WD!DnCYr* z15MEaxsXZ>6k=*w%cBy=X9WFkL0gP#upmC!4X!h#-y25gi0(0<|U?cpc|{ym(eCAlTNq z1dQkbvEM0ZXS?{W?&UawL;)zKa*pN5X`jX+AuG(~RvO5_1|u zi9M)*T`}X@gUfq!t%pV)ul3lq6XL%C$cSZl^6fOW#^y9NGg-+Mqzm;k8G{{lgYW-u(FNwz00=UT-?pY4wG5iY`oPy1&ZJa&li>RT+Q z+5cNW^NV$s(nZOG5lNhtYBg>w7jo)?vDyEiEaIFsR1i4K=`7lnDhDCnFTAO#Fm9qm zUxdWG{v71|G!+<+tlX0UKK=EX^d$beiIz021a{B};@vY56E#JQFH%Ic*!>K4`I zxz4B`Zpv8??2d!A!mZ*%WdHj8f8yPvtY99|FMTj6AAUJH4I|C-)cTzh0#z7PB zVIni&X+w6(;Y)QEkH|y`t7K94RF!YrKD+{W66*+YQp3h~*I#yw{UE1ol2+({F)X;J zqfT;ip-<@i>n9Bw)fDv}&)H~+oU|TD{XVMYew0-!Jz{JhW@;BO`AlZ3k8IMvx2bG* zV)#8@6Cmqs5?VV>ZaYP3Af|HkPKE$3pTDB&c(`RI9ARQ{tm_!HBBj-$$-%xuX8Lo#SHA+E)=kcO zlJMO9? zz<(GG?4fI{QlIm`I4x*mlNztIa zGA%eX7#xHL z+@9&xbl-;m_HqszMSz40@f3Tzd>_f~dFM%}8MQ%1u&uKsu%JVb1_P?)jnbs;{Fo-m z8*w|clGyg&V5o0>m(>1#~8u~lxuE{RLSUlQQQ{VBtXCM`y zCpTw_M|K^S`sLtiLz+@_-wBQ)q;2l~7$JDO9D9;MJy8sXXt5F%{7-Td$ zOa-D!%sp;m^(4CT=4DQ(a0bDs>Eiem8{Zg@g#^|2S0=njTVckEj5pngxmM%l;{4W$ zd}hJPnOCEwY#|tl)MEs@=8BmUyls(61@p?T8&~lNQh+f;63yZ5CKCkDQKd76YwY>I zZ50A$tPyq(nY4&FE z3oel1N<}Mdqt^)eh<;7{{;R4pdoomy2CG>3v1D;s+&`almY^MLZ3^o~GVQz@)xayA41!kh z&yF;v2o-}Qu#qyFCu_TL=Sp+St6!IQ!Y<2UHvR0vjAB(piG#ORWxlHI;@mS>r`kUw z(uBlO4Vr&dJX?q=HTZ>1Q@=@^)r$=5gbApu`SwW$|MbbblOo6T`-MisJCdh2hC z(CP$12$rw^)JVOrHTV#KuUMDCT*s`)Vu*$M;A)%|(O z%3XsD7G|vBYdWn$LY;$v8PgmT{TaNJIOZ&V_5l;xS`mvA`eo`vlU{%B*>AMXF&GW( z3Cx((`^t4-I^UNjN4vo|PuJYiUL05;@_1)`ltjCpyGEb0WK;qE^X1562me10HjSyb z;#g|pfU>IZeu`we%HT9}IfBid!_@#RHd(vqwbNa*e*(u?gu6q9?eL%w zpBOd4PjoRfqKAz4A#a?h8mlV{h65RDHaWLmn+G4|QRL^E2ugWOsTR!pGhJ~?F(`(R zUKL&?n!P_$a4_zC7S3CwNiOvGjM|sPr^Z+K*8d*Al4xA9<|4R6f`|D11y*;LaQqlXhGgL#HU4||)3f!U76M_kq=NWoD>a790H z%!Zml;`ol0HCn(+R&LEx5{M^8j8<4>`{hQVg_YMDX#r(|ck;mf*gdkr0G+uULZGIc zs8{j6aUtS!?*q$ba`N}$M)!Uamy}C-Ac09RLQBW5Q{vICSQk43m-h2Pp`5@tOa}&c zgTCly?JhJiUQ)9S#r)2V?zlxZngxLc;Wu092bZQ#g)fY>8y6oY1uX&K-R;Mi1rn## zQn+R)Z`Cs`yVGP^4((f&#k3pq|r)Xfk?fV3@^nb){kRX?{F5CpooVG`i( zS#+NZ-&SoH-#W+KlkY5R0$Eu*Nv#$2SNA1$k_N26SpjEEn0@yl$`cc-vYzpE36eYg zx%0&`6WZ5O0RMHPymrziIg@&R3mhxJw_yg?e!(7d#7K5}<0gwE-uiTCI}QYT&HYUx z2GlPQLy{wlrxuA1J_4Py&(Iask6m|I!By~>eXV0&hVnOn@ z+Z}y!D(_k?pJve$v0CQSwOpOvP(s@>7-oCB=f{$we;%nl{nLH*z~-3^KK5%adjU8x zq(8P_V=9yy7a#l2p|2>Y4P;JYF3^VCmb=8YWRGr6(KKl1mKawj(p>&r$UOWOxXs<+ zO;cIG7{@{U)4Zm#LOJP7jVbYMj3 zb`~idO|t)09bj1a!Up4@H>lKm*In<<4`R|8IB>EIziukKjrI;L8SY)19|~B0-~H5+ zXmA-lziwQ$g5DUm!5ZNS_hrB3KoUJHvS}?k{*OK~)T2t^Vn-`Zkh+uvsirf&#uGGS z1FTjblARR3{qm_N=Nzl@g&;N+`pr^1^`d5`r4(E1?piy4={R)(C%lIkfVsrRkB}{S zxf#4b3zwd!xOxyWh@u5HKB=1!(l#cfuZTYUi-zGuHhvg!koX5IlX#Od$G0f%;jG_@ zk+WWWZ6b^$VS`b~c@B_K3V0gFhek+F2PhRZRsyukY9k_y_~gDY9OP<0_YHIWWN7N4 zFiKzvJj3dDiV`LLYo+gYp$s%(TAt4$K9B#+xfBuTGv;?(6I`%Llw5q5{SWc!sd+Dz zv{$#43r0E$%lvZKP1FhoumC6x0{jzZwJG6(=f{@9xeDH3?bQex!0cKDb_p3CMckP1 zUq07f?Pc;W1hVeX$?}Xv7lV7V#KsQWT=kgS=7bjp$<2wnJ5r<+L{*VogMJ7VggZ)( zIanHLptNv#AB*gWX(>viV&4I;_!qr9 zm`b67BV6W+XJ#+DDP&)-QEjN~H2W14>mKIc9$%b59_UQ2)aD;y<;EhA3{hE>=fP4x z5%5d8Bsc#wtE<D)g(xoi9v1S zLV75Vbz}0PgrhSY4cs>-uM00Fg@siwxnlT1M+27*4|*l_j(gp{%+LAjl&jy2BYrB8I0g7mYnbXyff4`^)iY*X{Kd1S z=_id|O6)WeMC65i95B;0*voF>aLjY83b5PU--`3(E2J)Wi7sFi$A}BnK*&B#6$JL? zKKL+;P?ztaLUzV97TK-hMc=}(A*#Ba-&#UII-!E~uKK`pZ`t-bzm50C`bEucFEY;A z1Z;)!pGI+!^RUV1?TB#vl#Kvc!K&n~54F#`0mG_hPqO@%{3U;)a4879Z40_0!CH0UxUWW<*0T5O6HvekvcuQv}>a%kP2+!(%gNH zs5gjD^?kJby6Vi&36L_WUydt!k|z#R~8ozBnxnto>EP(64n zOe*UCHSTVEvlBxWC36+_TTEyR`a(sG>U$gibqlp?_@VX? zaBjHS$i9AM=S+>1z@y<4oGXSwY&EF1C{xy}963T|lPjYp9NjXPq8d|ECUQQm5;(dM zi@fF(o6K>}E4{pJk~dD@dCMu}K_?p=T<<%{(9u-ZmgBAIpK9p8?XB@VW3hp$3-kX` z^_5Xky91!G-(ikHlOfU#c15ZNdoD;Q zqUJ>0K)99q7Xt#_glVv_$^T^mXd#44c0Er&K(UB`?$h#NxBb|Ch%TUvrH-<^gg=Kx z&ncdr11i`=`JA(d8>be7Fx_LGu@+hm^KXtgjhETY%%t#>p- z_rE79C;bW}ATrHzfsA_EF0+@7`hN)-Is|@!SsTp5KXM058=KSy zWKe6)IV?|v1eEc{p{1LLt9C{Rbvz?Lv_8H1qc2H^_nP8ge1f&PTF?<*S~1d9a3yeT zJdlcER`?e#i~)mNR8v)R95u;Tu-{LX|-7rhy)V9N@M^ z#EX!VWVsOM;l}pCv!qzCIB>-+Tc+?Z0>Ywc`Hx!81fL+Gk7FANzDspCsQIeH(XnF~ zneXn*mmWwuYHJOnFZCEZcm66kGK#O*Du=k0%zH7t`QMrD=a+pq6?o-NSF zbsLAZHYqXenO}=VCyN+fTiZimpcra+J70nK2e{{Hblv12;q|!j3moYuu z=qKiGeg*JTO#{c* z#3{SroaY^UVp>WX&Vn1ieT4u7`>Rx%^CI3)@RLZC*Q8wnA;%|7z{jFud4f48DvW4pbnvM49M8k;0~zvokl>N z2FPwcG){l2{D|yl0A&3}`G0tDjC{)i4WC61l3+ygaLoS*K~ng7cU>LOC~mL4%LOni zVozWwWo(xB^Z$oDbLN_}O)9|NgO?ehH`Gxlp$x6HpoO9ymduTDBz>IRd#{JI3%)n{ z4YoawSO^~?CWw5aIlSYa4z3m2tgORB;=zVoevqDe@B>l0MSNzGgdBx6Ew<%Epr7TI zUCk-kNGRdG3`-)q8Q}pPzZarYBfkm+WF=@ z8$RbxM0az>y)2}=40vpODPXS>Y}oK5V{>^a^Bn(is-n>uTS~n?gyYMUGJ)TR^^2qJQ-ZJwWfoxem3+B>s!2^O)1OP`=>@)m~ zn$U&vK(|X`1>QVKI}AvcZ4z%dP}M2Su)5H=D95WgHv0-1tY?3h1)7ex(XnGjBUyjQ$F{ZLgnqI)8vu z%9>`YQQodB(wFMkqO1+rMihz1Z7zEG_s`(m_V@}nqT%jW%g0B>$gAU;kBb8QIvSq{EfKFcJoy>q6ACUS zCd`Au@w|*Tm1oEt`)Ll8=czELMrRl3V&kECT&OUa2-b*t3^Mt zkQIt|JW_5O=3ibL5j`bsu=wmadXpU*Y5~Akp{f z15aj9zkj*=Y|mQt{`yXsev!~+ocxCyKUmNP{2(_<{S^=6BLd;pGy4Q8U5TB*j>b}x ziMH~N;n4N$Ar7rQufFbOjr$`$_qv17d=*G@%4&LQ|3Wo< zMGbjUNB5sT!T-Rw<-|a>B^_5);C1I52AubbIIXcZ!bR>aVX{`1%`>mrB>0_s!16x{QBw4%8?>Z$$wz7zDs--8gLdtu8UeGuupBkq$v?8AbYFFNJSz*xkZYA zjLS$lY^HoR(uDm&3Xz|(cx;d+HHQ)&Jevet)2eXiLms2#L4s={q2N1lsn;X19H1R^ z#?9vtMSifgehQEQRywao!Uj#w)Zw&Ew28a5fEAvHq2rCmUkj%2+7PK4uZ&ac29ini4a(vNU{zAh zzUekPntF*0795zCCZxD4xyMDATa@PZ^E}Jx8lLLT_S?#65mV1ZjSA1l(!$+iF*sNq zaS!^m*rD;f_SekSJlN4LxXJ>ky;S^g1|T5{gDA#j-} z=1b==6k^vlU8)j|^ZB~h6WzWNuJqWv5jXqSocivQ_8J*RxLQxU?@kAjm1XoJWXT`k z3QmolviJ$kXVszo@JO-ZNL3k3mnBsd!Bh% zhM6j}G)@;4;FLO#6nC)QAB^t%e0X+84`)Ucf?EHKg3oBdhjW0(w?nA$N_PP#lqTUs zlUK@r(k?ZT^ON1wKsnaHXOP(Sx_z<9$^gt8l z?Pz9|Eb2+TVi+z;KQ**@_qr9$`;@_+TlUbq|)L zJ-k0w8St(@U>Yvh#g=rq)gZwox+v#^cG1^r_;3{T@LC{cNC6F}xa2Sh9BFhG^oC-! zeDfgjcy2E@oh?gvEHdELS0aYW+4bYs55I7{w5#FAV2B;1 zm%oK{?-2){H7A|+J>RzyQV}4J%84m6O#Nx?uE6bF7ufH4c$r5LW99@egDJxJVU`4Y z@|7ZvDg%e#V@rVK!u~ek_W8B|oa>R>_ioZH3@|to|M zMp&28@Vzgvaf>*vvkT??hYnzd^`L{M4GxwJ8XuM?NX`^i;CUy3fAU1Pa*eND3fv#W zJxcZy3BpYhv}-piXKt;%$&xB0THR4=P3f69OKZqkZ<7Ll{$W?6ye&J}&Wd$(NgD(< zdm8!M+cXHcvYq{}5@J&l2L&=i+75Kp!5>23heyOQ<<4dgiB)p_d01y~ z7jsgGRA&GkECsNX8n%O3voD&gXpSM&{w=^36_GfJ2H+#+E~}a`&WvB6G>jqKAbWdE zrqsSYlU~T^2REVwtB}R~s#EtkiY)L%uyEmrS;o7Xn#3JqEtYuKz*$eAsA&5*lJFe7 zDn5U(>-8}q=+n0pz;FH78E0ve$9s{iHJu2=Qp}_I>9g|LH&a8s7HCOER8wbjJd30A z^rXJb1EFHOis`b4V0cNaXPiw?181VKK?O(bbyIFAQcJ88E%*LQUC^&Qz1TJTMR7!F zfu-v+%z+MfrX_u+#YV1hpwwB%%S`6mK4O9#{ROCb`!RsQMp_Gz1KeP=W8or-0391K zIIh}>$NwB~fX&xv$xJ?gBoOeVwV{AC0|k!sU|`S~ctX+wpiBz6^S)Gi`#vsi!^ZXy zw_c;?4LBFIcB<+AN8eg4@&bM@>p}3gh`|wzO`Pz<5xnKqN2*Q~`zx8J6ItqkUc2lF zAvt*~F5H3lE>FBAP1H?GN!r_kF?1q5Q5$HDUPEDOo)QLt&>RhnU~iVC?-L+9RoeEh z*Q%5X5IkDw{6y0e!_Hr+91NsN?udQs5)FD3b~vnhis)^WG@xr#zUA^dCKb-=H=qC| zRQf-dA(P!ewxN9uf4^{>Cy1N-3VVSDMVV*?&L0y;@x5qCKg`ZRW&Ck6DL;#Xu*xb@W2z zFfR^hvxd-q?{mCmknvFZ}C%4!69)FmT2RXybNHbB;F>~=BVi3h_ zM*NRW=1Gh;@lL0w(8v6436H=wE|qxj!#BKIx|C^+!74MZ`~?gMYQ8m4)Wxjb>|#I! zN1KJ8NKZ$P-17x6lP3*4qdVNKZ>>iXDAWbiLhP$i6%3A^Ih}oBHNcp+lz9?vIt~iI z@N|y9KNV7T3llicB*DTYeQZnPz&AbMLH+po6qzKQXv>R^+?4~~YP;Sb-Mh6ffG!S@8JDo{y^P4aWmf=QE7!5C{6H_Q@B3 zd7haQfbEgf#{sHf(i{}U{E>R;o*S`4U?F=G7cTQ5ol5yGQAnB+IlKWl+Nekp_kY>V zTUnmZu}~VMO<^JaV|~=(oQ40PDBc6&YUuCV;eq%i#hPEL5olaa3dhi_2yok>YT7JLboKb1nbAk?e3DTc9Ub<8~GXcgU8*J13WbRVQfoz`7hjX~nP!om03rou!r- zB~Y8)_uWFzK4*lZhGA`&2A*uSgAdbz0f~M)dscbWgD{og66C{|Qg3CSrsyQr;0K#N zv0A}Ng7y_!5@`a777f?0Tx2`Z@K;z=C~Rnq4XT?^6gmR0fKsQfZgS669-WhLO_gRZ zbU0hMLEmAm*s8dDp6g-kKCgLY&wPR|!rrQ3zELU% z?BsQRR)hTz$0*5&;3?C*DQxevo zy?qp(gloayCYZjdEamFbMKsd(NN0h$?hq$>j7J<$s5%F>U^9<{P9jF3 zz_tk1%n*Rhs&4v|(jUc(Fsl6(o9prF>f%gYkteZo9Eizwg7fGw@+d#;Mu=*70Iz7k zMX5#z?CV&Ai@4OTVSO_vlzHOM`}W^aJo+JowCi$2XCPkyAF<@QR(vqUiHj+}-IFBc z+ir_(z=5RwYlIZ@7kr5TwiRapXHd%J#}XxQ z#4JdMetMSiX0up~%+-59#~kB7={G$z@!=bg@|Bp=N5u1}?-r1iQy@Le|3Q*RZ}=O7 z)w_WQR*xI-p(+#1&OEL8z>HJ(MJjtbxvGTGS8W@olQjajmzJv98CLi znd$BDm~{-q7{<`2i1#&;O7D_aspO~#kJ{^dsgJxV2k5|rMGTz7xP}l=q zF>Ynq62N$`^WWFLW?XO$*q?CbQ1WlTZvWG1+vWLdEuy^j$Qd-r$+2u+LsBA1GI&O% z=zeS*spW(V+1F$SJh!1m-A6ys1vT)n*_!KrvAOGL99vTSrP@oSyo2ZV_1M+DO0ut znTUNWAWYmy4So#A!dp^@!RHNxQF1MV-cA6S$rlP6<=#9@KzbPm;?BG&+>n~&O|2B7 zhBq_?AQ|yfBlof{%{kIcz*Fs{GJ83pWAFLK9vN+2GkbY_AN~=)0Df`ecJWf!m3brm z3BVcV$uqG59z@-su}K94uS7Wme~I4Yuwspxk|X~!_o zj5_CAp#Jr4?d8$9)jf1y zK@!b<(K59^U_p3daHL*W!`I`qxew$ziq}kLDNZAH7hRq$LLIh~hpxa`R!bXhqYS{# z{$=WQ@#;^&HIN?_*R}7@Qd{ZnZNO~fd>SfRF+8u3|I=}<1*hz9k4UPt!!?&SZ>5az zw=XrX@{#+)?23U5C!H7mW#{P+T0H82Sj7(Xh#PdXKYbLt@#Yv$Ic!b+Ij3s@ zbuH^X9-i*%EvY2gSJ)xHU1xywyYJM~F1q?Kv9#WJI8PEE9aT=?mGjQ6M26?0Wig&q z#YuSStzMOkwA2C)OZ%h%AY94CKQj>+tb#vx*J)gScGc|EVWnRq0{&CbI7ef!gKzcL z9e=tR=|B3T$fM~LsT=b!Mq6JAYlIbqYT3yGbr-8;`ltoJD23s+z3*z3(%^c_XlGf^ zCy#EX)SZ`~&&5Cc_xG)cu8^KCoHDgUI~V6pf)yS-fYY@s$j{&Syg&SL^%D@izKmw< znSwG|HvRnA=y&iyA4xqQEoBeA;+)Cc{bn@$L@wJsAXmzs**9>sl8>KYSfo;e+8^-9 z*-9qoX*G}#3)r<)#}96#e%Hp!7b?J%WUE!UVhRMptyQ9_4bj^{=g(iv4b(~_oz6r< z-Rkw*tCROu)*7qQz+5fhRMO;|yvEZ;f|0TS;s;Ahiw~j)=lB!k4fLngtL)XpO+X1dBvl=7*AdMM%V`!fA)O~0g$SB2sLSV!dF0) z8vrfwEBG(5;~VzxvL-Hho=H@I{u}KfCMQ9LTFqj6>c&;#!qLP(-5?)S>xuw5uyIjW!vFRLleIQI56+~3{Jq#J9e<(C-Z9_P+&b1crr6v)ih04t^TuYHDU8g7Q7fcrQ*cIBI6DzIPh z@^C2JAN4*Bn*2Y%leTsf^$(FeFm~_p?sQ{%B)yLSKrKPzsEqO=kQcIN-bBwuweFU^1XN+$k&H zsNaeNl|}HY*|hc5KRdb2u?gxzPdX_uf=r>(KbBJ7yq56OZU$W9Ih`R79;g3BabnS; z^Iq$ylt0b%nEFokvUf@M3JU#V6~b=NN>LMI$3<&tui)LP`pA<8X{@&zaG7l&l1dV+rkvjG*2|!m_edAi(wRry zOP);E+XRTUFFD26v9d|m#=nD}mZP=IK`OrN5CGZUbZ&jx&spp(yXGEwnPh`!!MbG8 z|H}eECnYCMw^jD&5aTJ`7p(;rSUHD)|1@=EU#F0UzJnfyUS-2Q`$7ZCO)|9a_n!#& z%#+1K>@#-2qSakpvgO%tZ=y21Ig#NVaIDsYNy;uOzE+kuP8&6I?FF@xAMVM6C%r`5 z1M^&g=2{>Pk*LZ0Df;)wTO-II42Lw+|J(DoD$fmiAk?HAn0J()e3zQC%Gr>)j@!TO zgrmP!fp)?`ds3#+?Ra*crXy2|eJm#(1{{^SdB-3w^3>!isWTs$L$M0inzaS*(3a+B zr0h-2;Rf8v>I@I5v|s4@SJ5frp&hAsFpi9$-rk<5lZ!DiWJ^BZ4(zpf#gaU-x?o!{ zE;$wwR^N(NhxsIy$K^KDa?y+4z^9|EG<3Rf%XKuwnxRjXamphKy+VbOXJb!&~Tt=feJG=Am?Gd|!6_r!-|$^az4TJ1jLEqh*e zZU(|y(dbwns#Xx3LAG(xx9p&EMJo;u{|ElPUq<^SIvb|`1TSG~JD3h*SfP1<8b}=9 zIWow}uLYP=xu@6Z0a#5v5|7vpj+3#;|SE3ZdsBa%k_<)a6MZKPL zTe#Pv#dXQ`^dXRL^onyoD=R8F*viGp!?_WFiU2)~eM*@kP8(;*k0QfoNGxkOpxK@a z-^}tFPhoddZOttMb@81A!G;CXps4+D^ay7Y)5~ajZ_x!2{nFoR2uo7hVB0I^AkL$} zz>o21ZbJNWN~9!cne!RTmYa2B-z&!Ue0@H(i9Y4w7bP`%yk-Avdm+7{hL=v+-E$qG z%aGQ_h=2K3gl^YjZbDUhV-klHOaRB7M8hSi#?Zjh0JUEJF#tF(PjC9fj2k+ZU}`WLviWiDF30^i5WSH2q;CGN~?D3m?-}wC6c=*nG7&X!w)UQs%u(k5us3EX^OYMwqbZRi1(?hp6pQ`RQdxVK|RuXlK2DXIU5??c( z>Ap!~(#zFPbJ-E<>z$`GHLrs&0Xs1Jj^}#kY=+n?mgb-%RW%_4GErQpE?sb}`bjFSx#3d*JaYqn@5xTlfOsA=O~iiyCU2 z=y5!>@+tO~pv}4ovCNd%-j0RaXz3=TD4LpcFze zNj^fn!LKmoiHiqcFuzaobkyS-WCy?@`T_;eWc}=L2g07r=D9ga_&NK3u)AG*y_BSs z`YmAFJ0jR&#MOKm+0fa6M(V+u-yw=sYdzQD^G7qWPg~qNG1%`|p=3lWX~lI5>$iI4uy|H( zkn!qtxTm7)`Qu1@FeVrX;i3#Y!Q@ilTAUp zwVwX^#tqU<;&09qmL~EemI1*8bYN~ZYJ7E1%Q7|m^s6U;yV@z@Op`4;l79lBGJuPh zrDHT)c>A+H$Vb@w;c7POq(ythbGyknXWW0%g6FESaO?+gnI z73U-Zuez1G^wI03ut)B1Y=HJF@ zjyp-_a|&!LPp>Rv;lN;Q36@X`Q}qx_Nk2~>syd@e#$D!qfrcqu|*ib8{{>wUI>JE`Hyr^j*A$?7A*)OT?F1RZuH;+qn~ntG$Ti55q# zs2DuK*3h2MYCLFT|5*Cv=6H^75cAPHv!A-_m1-K}gb+dRCH{&I;}Id(E+=>^pzd{; zz1=eFsWvH&{JoFQHW3R0G4i8EkAKzw{bGkyc7_BFVJRg)tqlnqZ-$Mx2^{?+dG zo?_r`j;75^AsCdR1>umR?N1o-corf;myNy-p&mu00aIqi_*79#G$3f27-&}AMT1r! z1{yVT9Zwk4u(kE;lU~Dji-8OlHOy0X8q#b%+zsoF3;#|VeY3_!xKrr=Nv8zyO)x?} zHZqky13LaJgVNry<4AIa*txh)?O&x57`5W!i*rQX%#GZJ8Og?6_4Ig@wpP|GL@;L& z$3MqnvG;ksDQp$0BLmDkZStRJN=wAC7WiU&+=n$mI`f9g)7vsTb9!!6@1gUt8iGA8 zTMl*Okkk5Ux|&bg^mt1+n7NLwC$Dg*+sIqlPJYG-zkt$g+TmGz{)(L4Y10ZULXx|! zxNe|_&R^=X5_s#U6?z;e-UxlNdlNmUKb{M~-p$&0rCUl*IcHA#Kc~r^buI;dkN9E@ zxot%t?ZCZ~-RA5SvH|?JMnF`U$1mfyFo4kpkNNyBy15RyhZH2L8+9J{Cs#38H7dLr zu(UOk`8aS#=kFS_meJP=DrD%eU#1Tz_|Y|fIKtejMek4z=AK0&t4q1YDlDbfIGW^n zuSKavsX@xWrsHU9>^vi5d((Jtq45%AcWFRrnm4AbGJvM=`Nsu zUakY1;#hZep}BE?HlANPNt8Z-EQ>Zqy-=*rz;8|z31tX@0Vjsf528G)?Jo2uFih9= z!J<3s&Avu;@Beu8OkxTtNLtYDY8EAt9(eo zF@aHz_LABc^`^9ZvEVQf8pJj7#2vih^XQtDlqMW%c_v1Si_a3MdHxvp8QpOKeRL+i z#b}I4FGB$1b?cQbs8Lu4riNORD?KUfcivy6vP+JTj^JA6y;3ZX-M4=WUFhtj+-WK6 zk}G_=wXJ}Ctx;%O|IH~cJ}neC&(hRJdD{tc_`&6Kh3zUR29hn-cLb>>Jg@sO@kF)7 zyI{b!2*VM3`}yo_`f@ja=0Zu@gr3c3hDie-f&-?g5Q00NtXz`QP5i7Q9^|JkLN#Lm z3-Hk`zUCJRUuqw3^ql--M!}(vwqQEUE>pOjw}03n^q^HwQ8jgI?TGij%`-((OP#=nA#rT=j-2upXO4 z)yr?q$dtlgqt5?>qxNGsYHe-a(|a4|sjs48{XZ(Xp;|jm_&clEV}2cU#eBHK>FZ=! zK@W6dNo+f}r>T>33C3AQsye)1&7bT4EA{*N<-*nMi{m5qz!^u^WX$mZq1_X&60P#K z^;)^p{o%=VGcAAmvi=jHCZ=YJVqt_-9ILRD?WQ#1&L{HP{%!01+m8kdf`9QEBU=tX zDL8Fl35f~51*+O`z#B1|#@V4mTXhS*_2)P%(s4h!cSj~&<&{pyZA{6$Kh)uMlf~kL zNy=b!FjcFFB93+u|EnIA8{~8GK_v@std;kCxn=KOe*9I#)j-EaFm=3=G!L%}WnA<1 zc$RcuL0o4~K{@iap1H{DONx+#xzEChu0IK9nOEKlA+BSwNjFcs?H*Mcl}0`1qY_;n zpmI_@i~-JUT_;eQAK3@j!$4m$x5>{aXDIi<*26y|QfjJs;?u z%UA}kf*HdX!cK_;J80l(h>a--fMM=A8Poivb^@cZIgh*1o?4C5Td2sdqMEepE|uP< zZ3`;w3nikOjAvN@#XV$$#lI>yJ-8>Ij2Vur^e7J#A7dWOCFCdo9j{kJ_Vn^BjBbDM zNQ$6&1fu_#oHTL)@<992^BgMx4T=Vij;>j}z#`hI+8uj?J58Yo>LkHj>E5_HGK%!! zRogAaP^S#ea9kf*1NqiI%3etC?R}Z>2dW;!**L+qj!Y95bNY1E%gT~e8D_s{F4OgGC?XsbLW;=x%Z zdAN~d>~bD*p`0TV=!C4_N1sFmucrv9M^M~w5fU>AhjHfJ_dRY-ALAnl&+rHCMy2at z#U8w$nJ6HWI`cK3vt;vnfm}!8)(| z53`4%o+$v+8b9_=tbV52KJZO%e6{QfLxE>|GVQ7WDmS>!>u}?Db-J(ORg+;b`Uj2{7SFkN zc;7klt&Y{+N9(s@!u`7wo}E{#zP!i3d632As530mCI5DXT3_ucdullj*is-*U*gLh zHE?9lhv_6G6EB{-ez;{Y+_?56SW<_Z1zaUu`@H~KuD3ECIZhiW3tja-Ha z-DXohuS(7i!}Ul?h)ei2QE~qR{ZY7A8Gj$5tP(W@Q~J4&^e=)w+6ZV-cfR6Bwx#8) zvGE`zkP?_sc(1)`!|>PFRCUxd^qh!}c>}kzbJ%&# zYUSE>Ts>|Nsta1r!t&^NkH;Z27^>NlyaeNe)FX-6s?cHV-zS10BY47MrTIQ;EaX?m z{(hayJYDVzz+RS@ZLX8r_D9%KA2kORUl1PqA_`FIjW(B0OQrBwD%r65QM4Pnvf+_B@flO5Dlzk_AC#FZnR$ zM$2fR5U5xa=0b_yJgqJG1|be1t3l`nL|CLtxvl8+X#0EyuC!GTF(joz@?2NvjVL&{ z71USv^m%Xxgfi4_l+ELWcD7TtlSDsxaq5~7;BV~pO4u?JJbZSNpUrZ1UKgBqxfdV( z@SUarSBZ;Cot?awM4>YX3xDKpBV+wk5^vsAm}}wvZM<(Ww8xERU&iq$NHMDJ=~nNb zbyttM8h?D8wfyM73HYzPLv!~xVqro+2JWG=7j;Fk;( z9JeTKPf(RLd7*ziXOn-9KJrmODNOg|(20sjXWizsE#Fz_a`r0m<9+Q-YzM=H9l@el zDX~z)MlwI&RI!M&r+)n?%d&KcnUz0s{KlBxdvdTA33zkc(ZL??qx6C;px$-7 zvD^=+)^W0Kq~L@0H(pyxch&V8XVosB*=&R9Mafh!;X-t=E4QP1;(Y^CeDKGV81U8* zU`4i$UapYn7x*EJ4o7rF>$ojnCuLeB;-_gOnYZt=&}AlCI@SQvtpk8ob5a3#$g2b> zE;&hpW;jY&o|OZPSZ|JxhWOU=F^(yLCc8X@m|(%8~PI6-8Q1lXY_59i9~Qez z8pI7yX+^~nR>n}g15`7qV6la(yI$|h$DJ1~irPAcHXpa@DtJG*8F=|V+NkA({)C$+ z?B9y_yW0g*iqZfREGYj8Vy*NaLz0nN8B^bjxG56MkTslHyDR>U`Y@kb?kINxIH~!Y zWrF{XtjMm5c%tY-(U|keH?L?<+R#kIA0_p!kCKHH7jM*E5X*Ha!ch9O$v+ zd?pr)k_m9Y@~l?!URoCGzXHAINNLk1wO?wZ;#17#Ui@6v?W{Eom78pL(+6JRA+NVA z6M|u&FY>EB4F!91u2XVB$6@%;G=D*1yW!IQ$foOh*w)A7HP}5KBHn{n!RQpbK~V5 z&ic8M;O*v2@%D;jlap1mmZMpD6Inhxp4G^;<&Wy+*c_W8+CNw30r+9iT+guDWmYt< zI${R%9Ah&Rdwqyo`ej#8dd1Uu#10H6QW17Pn{K4H>f2uM^Ow@$3gZz9nwpp2gi#Rx zQI6TqWOJh+dU$!x31npM`DlC^9p(`Le5<`Y?Ues#KT?w7x4BX*T%e8=yB=WsW za8O4MCIHeoVMGzHZ(l=NgFT;OtH0JRxspjG^>3QW!XrT9l)HE`A_j_89eZ^|NC_)}LfuOVvx| znivb;+XP7f$NYSe>4%k%@Y7dZd>D(i9`rWGj$CU}-;R*FHu9hfw(E3KeG-e+ElR88 zU#N~8lzlSZ5HPP0#5m7%YNn_f^e~Tii)o-;7G*V}jf2dqT1JK*c!fbZo+$&s76X_b ztD8!Hjd9tT+4%QAAU&%628EcPU^6sHD|jmak^s?cSwH=cI5&RQOTKZ4`z*vk$$e3z z4he*RQ4R3Jz60cS2ML6$^|`+ksmJIG+*z7K&1nH5Tm(pQTodl$q=+Qz;f1ctD(}k* zrZRgg*zxzg>6sltLw$XH^o@kh#C%d_M)e`{LCqAO0|>RCGpmgii2@_M$$(EX)D9E9MF9=v4v5?@Z|62r;Jkg{Wjtl*4ARTNe+~K zZoQmyG2N+|G12jtBPv+vSP*3lkY~RB%qk0mT5`u2)&UBuzHL1Y-uI|emcHKmLI5na zzOP*v!LePLf(;W#d#%4Y>0h=nMJZxezlGAsV6+l&YCQ}Zs}F6mz4ZI!)yhV|OmOsI zFw6(5R5Mrj&_*yfH=$#V@W~INP68#&+hRxJug7|Ku!f{=SqBv_@*IiRKVD&z*!=A5 zJ?1Gv*OA@X_!U5D!x~03Dld0j8vQk8O~~x8F|+1&AW^ZnK0YT(!69XBgu@UV zjJSAf@>*0BD#CWv<9B4PUmxnu0wPjZGP6=LX&}xL>`IQ=0UekDcK4a_=6*YC1n+}=E4e~+wh3^q04h~JnLhG^Q4(>@q#*UHONZiF#H ztk0X$cig-Lqndj{Mx>`NFzohUqKhXK39<9HMFo{`l+Y_c2WrBf$pJhzZq(uVnCLRJ zYbAr|f%ux^F^Ww#nhELQszk`UZc+dMTl}A6Wsj~s#bna-JFGt~EA8*8@rp}i>c=Qj_;PCgKoXxzxWscyDPyvCae1p& zAWWZI`(B-KhiNn%FMKTm8`!d#EHjnms5NM2Q~#8^4E!t$KMg&IdX?@|9^qEG8IQ*g zjq)-db;n>L9sAGZSizlcUA3{Db>{rd#)@&mRT1@gIqz_)%9B3Mc`h_d0lI4Pt7zwN zceF5dACGnsHP4XeuT(cg+MdiL$%kwRv^LhW8KTLc%rn;2a5t|2o|4$Y?GxQADl1I} zO=M{qFrPYm0i0VR8qs4J-u7?rzMZ)r`pxgx_fFnio=QCsQJR~>H7FdV#z;fTSm@yn zc3i`6j#vEYWYk;OZ$u)XC|NTdDS^FoE&Gxe^GJz|Ly~dGhDNPv z9o32qz7?x%C+T#2yp2zEDZWytvsAPtza=Ti%BabLJA3&Eesf1n>92UY@|Raw#V|jM zc_95{>lqmtX3*pL;Q%f^3%tQ1lz3*pe$XesNS_D-7#4Z-_CuHCfZXs2y3$VXCy#t2 z;l+X6*vrn9zuZQP1s@x2I8G9-;hEznl2+Dp! z(8c|nPg}-=fp3oA@VOXerXTvjM0&Hgzh{OyYIpx>Ef;q7Xw0{X>pd8dQi^EXoP=Ch z{MxR%9d|iudO6ckV|)H}B8wmWdFFT)KX`q9V{Fn}m2q-)SAsGLbo1>>>*q@m;h1~#T_Uddi4=7nmwAm!*S(Wu1%~ONsfMe}jMo0E~<->b9 zJJ14ZEpA(vTNig?XSrDx;6S~3-s8ll$b=4Lux5h#ZKr#fgMK0Q6#(RnB9x8)(Ltk$ z%7$m+kG8&=k2Y(+ISkJUZ1&fx0?M&=_H;d_9@oehA@JcKPwzd8xGJ@QO`f@_i@)!m zTcEYE;v8>ONL1m=H)vFBhYO{xdjZxw3Ffyu!Pi1q&XM7BxW?wm))T%vOEGP93I7oE zWlbwLmEw_UMS437?4|3ukUv2afY_H|e=4cG$W1_sfzlIc1a* zg2@3HMrc1h&#!0sM#k4{| zbJ*+6A(%0i#xA~PzR(xCx4?ndF|MEa6rPRMKYpP!5n%s2W~W1->=aWl?(8e?2kw@9 zV~jnsq^D)igD6UkqyMT0qDO&OjiYIkCb?d{}Obm1+|NX~tDm`4{ch`z<8_|-uX=8arEHu-v0ta`Q} zq5TDL8BG2`{hlBMNiHEsWb9}OXrfkjh&rE%of9y?darmKU{xb&C3as~*TT0weGPGW z4AUaU+|a}z#IoQ6ry%C*aC_HueLuc)Ug5w|WZ_F;hxxJcm9z{LtglbGQSz}(y{Wj*a&5ZPU+e(sa=WXu4E1HIfB}o5VSj(as*J_xt?W zKgYMc9DUI9r`9ZE_t%70C|d8`AK`w&F@P2#ifKD|Q~HRL6`ID3JZJk`r|z$M3$L9s zc;7ruIv5>YJIf2Oc{C+`oqCRkERLTmFhmZmI-b9gd-lco))_W!^}Uw+OyPEJ!7?ml zVeUY>i8uHw-U>eOZ&hBhe4+X7O3EG%dH?D|F3CAsYp&L55b%^=SeUTH>=RFgLlLm2?=bX)ClDsUwXw1p?D@lB#G6Hqd3yR9n7 z_q;}t*pco!peYQ(tY?$Bc>Ts+V&^J{jtU5v{naXWV78FUIKR5p?9~14ky(2J!sTq2 z_qd{z0mDVCKdjs=L&l|ag#X+nz{+4KMHcVRikSAQhm6Fxf0+>px~32kk*&Ujr@Hca zYC^k_TGvkJKZiQ2FGPsN?>P^=Qf2pNtg@4us}s-BhS-9LIaFI-92ZoaOakf;zvWkA zP$JF`rXTGbBFH7#9|znya^LRUgnap%Hfdk21{mVR3e6i&TsQ}eLm?HD zOo4#sNEy(p3pw7~&4YrZCIN!24}2s*uol`PkJ6)XRYRW$Fl7uIGD2;7&B%?tF-6vc z!qNM$T(dpaWW$9^rT^%X19a8^loMGLqOP8}H`mLX4Ci-9XIZ>|2%Y~Sm>kHj*uV`E z){`B&`B)n(*{{HK(dtLel-!Ny+v-hW-y+>QhMLOR}?0Femhdpvws+wn8`m4OLBJ3IE zChR$uT5$bA@|-6Loct3q9A>jj)}@A!aa$Zl8WE@)tw7dD+2iN|0;i3*@1}7K^wGxs z;;q-k5z}A|6BbS8klUsLuHi|%bdM@nL%_1->ddy6FH)5f6ll?DIia+`W~IU-H62Sx zq>mPGWo|&Y@fTr%bP|nryf{DpmMRQ=4BZQpo{URSPc%S`(+xalyJ!)p%2YrZkX~lL zM;E0ZEj1@W{V`6SscoS~BFy8OHQS-NQHuPdVe*eolunEk4EqqGpr&94?~mQ( zm>X@m^Xl{F*2;S-%k}YSFfS@}Hr2E8m^;3c6g>)xI*VD*QYFXx2QXnze79GqD<}0O zd7nmbPgMtNn3t?Hqo9wDYa*438dr|yi1LV_)8d!7QO9b`jVrt*{2r%ijK1}%M+wx0 zv$sCOupN>()^w-Ez6ZmO#6SM8^7nTcmwzc3TW?}kRpE_lBU#^8QJX#Jv2RHq#2zmi z!Omr$z0T(5;1Nu?3#|J#y|Q&JZ+-C|BpR%d2~95Ajl4rn1TBL=7Z)3U#;)Fr*oS}0 zvU1H|cVv{|8qiDPa~>^So3y@M96(VH;SW2P;Q*x8Dfp!%*x`Fdx`)XC|1J?a`1;BS^EYOP^jC(?W5+KQBisU=xp-3%;=|iAHaL z&+oPz4r3z1G0P(npq)_n;Edo_P!QcaUX{S)&O@!qGE3rS=6q$Ate^b$HUjcDO znSdq4q>Aw@SQ6iv&|JMfjHXnhzIn5nmj}Stv$@|(!SC?!GBU}@&Q`MPt}K=t1NHuY zEM0>znFq-3grMGF!!tr?grkhk5n{Tx@z`VBk z#1XqmkFu56t9NgpM1y~%>TlvZ@$-6*xv`rL{F{BxcATav0A8}PLwPmbdL}aHdVvTE zEeq`~{;TyjER&&Yugyqnku2XGDje*YI%Z|69C?1HbjY*@eF~mrQy@lP!-&=nWrJC# zZ>aw#umN#GAeHl}Kbb8-mNr6^ddsc|NfYpQ20{kV5*g`L*nFqw=5}Ux;uo7=z{p`j zAWT{;N3?9>r=)SfeEEx3PWBUqNh3h_q=_!5(&a1qkV z3Bivl)qRQ3zuPN9(q-Wvi5E-clWF#in;i!dDH_Oy@kFS_aFf2#{cls~1_Z0w_O_65xt#pj z%g*P9j4Ur?P_~4^mRL_ltXeLTFn#XBb~A4OcecMPNRq^od$Q`}SAf62`BUF56k$(r za554FU@^*NT2R4}+8m01(f=D4YXO09Dh0s>Ebb2Q1?kOdu=;ICwzzxXw%&^NSXl&FAY|T{IZ@BqA;pm$$#$UB^7*>wTZm@+IZqDX_u>em#A) zES6#F=Rw3Hmzq!F6o7f7yKcYk(8!t|+gh31hG@GkyP*?+9jaH9w`BMNs=}{kDaBiM zp#Fx&<0VPScMfJ8m=7^9?k*E3?cH2Lypc0(Xn`CjCz3wIFtK7-gVq{@u{8@4# z?K;r9;mXdzG7t6_RxFVT@O4Dz{-G3UZT9zH(gb8v+u4T&3-k3((U3TMR;yl1UpEHR z4!!IWPpMQUuo?ZG3S|2SfD9bMMlnq`4t7oHR$4&EVkZ`AK+;3Kr@N7Whw&R6z?a(Q zV?8BxY|E@M6f87>(E_Pf|HV^kqsdokzg%Y_RBLfjMZQ@Wwp<*yX}6uQ-CGyi$$zmf@ry|yv60M? z3Z>Uf4c86vgWWy|aCLZvHX_(Mf`QA@6bNSGz%UKK&REZFMmZWWEqHi^|Dzt(B)X{n zNS!ORzlvAI&D;M4LXsTtI=JkV*~+q|#&iaZ=dRuZYNna+gnHMf#w{m(L^w&{+3Pln z8?Bu?& z%&Eh%{6qpV5t-HL*Z1zote3$gV-r(BE+)1mj*ut`@yE}`(yu=UGJe{YF$jyU3T-Rq zYM&Qr73GmF(^z-J=~imZQZdv6`zgPr$hmr%b2G+%dg*W6^=EO}g)ZE3jKwqSe*8ww zp3L}!Odeu&d9}TWd?OQZ8F3|+8k^f?Wl-AdcjH)?tL2w(jLQn6FLLeRd7=JX>#Nyy zkhl*p^uz zv=ly5+1k!wLAWN(uqm24#(o97eb+MT+h!r_FY}OV;V-aDlIQ+SYX*nh%EX-BRoxC& z@K54S1vXGCCjtOV>tAm19tk*(PSG_$#FQC2m*#*F=9AV1FbYt{_==4!V!F9yF>y;Y z>UDt}mMr$D5A<=a) z=Y7CONA~`6HF5VJs(Fv^D@OV=O7Bx}L^OJP)bcTMoGDTtm}lpEDguy%l?h;Hpi2za9uQ0%vFqcx%&f`-!5q% zzbNDp$BLVQHVu1Ex2`1vO@-T|t=V2VZbs3FK-HwUIb6T#dX0^yMh8`J3z^m}$|ESg zEb5In)fxspCQl7_-Q5#wMd$Q=mIQbAYyKeJ%h4Y4$Jt{1Q%LQJ+NRJ*_!iZ;E@iLV7s%cO&;99V(j@1uG#H;Vo# zY4r7Lf#ntC5b0QEGBg|1LRV(EY!~0Ew1>CKF+UE`({a2O% zxG$Tv+9&< z=~o{X&5Z3TYiL{!H+{JN1I3qY8M6*%(pxuGJH^Bnn}W6_wfs))BEre z{&7$|1tVOj?#x$Yq{fDlFuRSF$45+#%PY>EA4H0%Fr880i?E6Q-Yd`-2;{&j7p1RgVs9q^_RF_uRO>n^)3=GBUD{`>* zDq`OQ3*(R@k=7iXc0@Y5;9_%teEB!xoK9e@>}gYa%i)4PeRz%`efZr5pq}alKC{h) z(oaIKHbOJ-sKL9<&L6=HSML96Aqh+bpjh$~VIg;F_rUJqSy&_GR&`w|A~t)bosa?I z1Ud0#|Gb`m>)KhUWU)}9wp>8C^d5m(q;kD?H=|&Dq6)~0%s>j@OP}*XPL+rcgsfsj z@2St%37@_iLeI|suSbaLkL#OGaAi(YI}<1{Wgq138aDh_^G z-w^*tIYcrztt-?qwWIylzJWX<{%%%81!UQXAEfAop>eD&)^HzxjuYxU_rQT|g<})O zM+-i9;g^!WlZ19Q;J#X;2_QCk(BB(}pSzp6P&LYiGVDyTd_Kz2iJ_uoWFt{C2?FVX zBDs9G@J~idQKMQMXTDi+xsni}Xedwi!@F7}3JBdU`pI#HK1wQ~y1KIU-T;qo5^yjj z4SmB(vNbVP%em|1jeXY^oUNj!DFjFaJa+;m_KYf7D&AVziLVDUZU;|@Mkkru&?4bs zMrMHn;$r-ea)O004ud^E=uvk4nb6DOn~k!cy%I5*PfMu(-}#f*6?RCx@=Cz!2OEZG z=L69xVJ7+o{^{SBI{9a2v|2r55U@LmI;(EFTaG#S7r*q zg$E33hd=)^6bgQ>&IhDsZp_IhFDFEZ2)%j!yx^+fuAAGeo;%Jw+Mc(N?{2XS4(Xyc z!?sZ3aLy6yHc4pye*ddu)MrDM6jzDAc>pu$ipcsxOVpL9zssuc*2W4AH$JEOj1(D9b_i_Z3Gh&Tfy90GaN<%<*Kmyu}g z;5&%jP$${B{?a@6;yti|;PJWi`2rx2(LBu4cKei1zm^ZHwWqf>&)u-xaRQAB*D9d3 zdcGO}sD!;?uI|HOuHMUl7>@1)gJ)W8T9|QIq@hrd@OM^+Ti^1zxFeDx$FLVbH$uZe z=2RQeV85BFJiqD$XUrF?InA!i(G;@)dB~V^Xd#iFc&$b;LdNmn|pfwAX!jIcpxYfN(u3KZjtKi`0Fv+7SkfBJ5*U- zA%2q|f}7fpsg{`d%R0JeTt}q<_REMhCzJ#DI zo8;S?GL&5s2#Zus&d*|rfmE=1TpC>0!o)FVZ@-*2bipFf)^x9FDp8A$p>JQ?2fzRE z+P9s@vP6!+0vo<#Bgia_GfT7=G+fhkY(BRyIyRANHy6~|-RfiXrei`l(l~WXbW8@6 zE8BvtVo9CF?M+VPcfYCFTasYPIQ(5lbLjcnUEn$kJSFn$ zbfi(ud~Tbid6W7f!-eZ?%V;8lJqX9av+fpR5AUfrGMv*L_M{!4;)*R27o)eeVCf<2 zM$=I3vrOsR?_yc^2#qwz`(_S5Bxy&hL2Xz4$}?{bKXh{XnjT2vk7=nGH~^(Z{N3kd z%}J{k5!=K1P*T;U(o(3r2TG`8c#s{e#~n~}ifGI>!?_||%d~bClim9!yxyN6i@nmp z|C?Ov8NUr)LDD#FpEW-Z<``0dKobsq+W3|Ubq<@;HhMEJODE#nPuzVTLmNih4Piu` zWGNFUd&4;y>u~&PzOf`WR2hGqS}h@fA_vOtYVZu>Hn&W!_zdONsK5^C+fvk;985x& z`wO@EoJdmofZ)RVscHc6yc3*|khU+_cB@lgO5JFJUOnD`@AQen(U{@ zMCwsOwR>_`?+R$|O6!%$yr-DDt-R&~_09bDKx+6#evDcF9uPbnSB-?go zsBP(QV?wNc1t))8m*J<|BOuvmoy}9?>dEzg2M4hT_Ud5)DEA}hX!GeH~ z^o&RiL^C>XW>I{2u_2nUC8{3PcNytuI>MKkkQ_gVA*Ie2E!6c+uGp-CN(~erTkH89 z!^CrMxd&?8SkE7SA(^Ow#lwj8?Lm|e=PV?HH6QE)2c{!M*4Z=OWv0(^Iw|57JSWRM zALx3Dp@ID@4gQT>Y*z49qbO=INBJ7@QJC=%V|C%_g`td4(K9KSXWsSDBLUMFu;qlr zDedJuQ?BNURjzi+N7B!wytzNUJdAZTb|n`**nd;w1Ek<_+2zCC+~v#RlbeT_>N~x| z{W@6ym*DM1WB!P7o-+ez;Hl*+@6#o^1TWaZzF?li(U72GcGIEYz~W=KpCb}S>;YGy zX3@tdYdY5h;>s#J$GM|#NO*O&4P}EWizU$0sHMc?@KIdC$B&jM^oM1t{P{Q%00+^? zp}X*%E>VDp|NMGK3-oVZYm>k>2_~@q;)hqGYZf6c9t8>|su?7v>=HIFfjKWYzj&J$ z{RtdD5?n!YY)gqs8hlIwp37f==7uEMExk$g$<)oa<&7{%0uD72^|WjY9Z5(_f2a#J z4Cx*H_;%E1YC!|NQb%6(1V+qr`*o{sDa3vxW_8bnCrjjBd7sVfRhb1gUdObCs^Hlm zZy_VAVc_G0GBrJm-&>B@?XLN#%)GgOkI`ZTFVNmL7zNw9y`GJ~6#x7wqBJ;T*j;}* zBQFZKIF=g5J#O7}`2I*VVd`4~MrbHD#@2b(dan=Hxu~dSAoaRuwv%-2fLXH{VJ*#k z7)j#PLf}uQrqUnS@BTZ#?2T!&oX3q6QnRen9&FvMe}vcN#Ur-p#pQax6*Le&=U!A2 z7t!Us2u#G~!s^Ro1;-W2`iZ+D`4~)?S-3-<_a2~s-5&G(R00&kCF!A7lW-Ll9&ig< z3(+9sysj{64!Q;vL_2?Y*x8h-O}U8rG;a8wk?fj3EDq~=BOwU#be`orJY%e+o_2}G zt#u5{6>o3V)-u8vweFQn1&oIY6&E;QlY~#57#wtQlxbN_bMUAL{(RtaC6H|~A=_Fd zhQ2ipyS3zu**99-8%I+iMWq%&@%}{Py_)QB*Hi6MNLDqYsd$Nu$XYWhjN$)uD zGv#d_)wLeF5z`i>)7hvMVFq{gB*U;C`VslPuYA5Fsh3&;>MPnQt{8S!sW-_k*HOmf zW{r^YIJ}eEb%{ytb5-S)V7Y`X4{frUp)QQ|SCCXr%!@lYQ_Kx|jl!dIG*pj~sZ{Iy zLBRn-Q%uV6r3kBG%aPw^U<)M+zGgxq!ps3`4Xvt?21)Y_F{1Pt2UP=sTmDD1L3S)- zLzgoe!bf)P{HRsn+IeUj|q#; zQSLcK&;0toEC5ZehN}cKcu1nFp{pU(7C+x!s3{U^{DFCd9bDLNVa7FKw`s!g*#2bA z1oSgIH{=c341t;3ra9*m)M9cUxmvc-=<1Qiy+pwv(!`O`~GzjB``^TTg7Ys zF|Darfz4)v&2vD81IF%x5whe{LQbg+1J47p>(Zn*chV>g4F^9-NNT=o~+masEE$llAS@T41Bm05n&tq0*%Ht0<|R z<#R=uYARCnEn?D;DQv0X_ya-19I87OFXS3rFW=fZ%64XYe{}x<%klRfSC@100{<0) z0qi$GF*FG*xOif3#L_a@Cy(}li=8-p%Nf1N3=%iq;I!}9$~mx#(`d)O|K3rjZFM`B zhiRCS)T3S+&5;=^)gj65rNiFSxgky=ptoC&aPXXMkib+%GFhSYNeWM1Qu*N6MT0cd zd|*yIFWv3LxpIw1z?M9&Jl%|n{%F8N+p~Cldnd@jszAz8eWSSKCNzR^;G)H#yR}6G ze1Ly2tzLQmc8MOSofh(10{4kMK|GjJL=ddy9Eyz&E$7rp(odg$c^Q4*>3S{jNDDH5 zb=tcUMd0RAjz^~XRekU2*c$3wR-LxgU#)zX>qukWnwL68!#FVoNG@19THE@8^VW1~ zlLl)2Tl6q}whoi@0jDtT@OdgfoZ?s%cHM2a&r1ycHCA~F&36IgeQI3_YkQFrl=_wc zI7mnhzzH1JNM)oYv~XNWa#LiVzSEQLl)xL&vn8eWV_Jb7X&cSG zN_g`T^FL{5?p1~Hc4gfDeQ^on^?vb6F1wE1`utQ_uNqQg^4J73_ZJc-|9%dI#d(>bg8^F zIpPQ~f_t!R!6_Yy=7pa78B(3Uv~897oLEwI%@l)mUlwm&5~IUgYF8p3qB?@&Cdjx6 zPU9f54sZhd^rP!07%@SZU!7lZYNisid)-+qF?i)AY<*1l2RJvE_&e~I-Om_JRnvrb z0Em@`|Cw=_VE8}??yymTVXAb0aOIO*P~EX;LfBZ#QY%=Jyw5itKw%aTYxYrzaQ+zp z+fN7dPxC86wCmN2mjcEv%_6&7Nv4SR%vG6v0vCfRS*gMK0+T;!mfkD9d6pn7phqTu zNxn`IQ~$KLWe9ymO!2i|aZUEQr5V&WU;fUqRZ|-@l4$Fe?*KUj8hvLvT#$doHpMrW zEfY3wpAXjG^nk^5*>}mAS(PrJ9jS!xcG%QvbYuDX6ZxOd(}e^ckABsGR?*>Dw*SNI zP}ESASzF~{eygEGGN zT!802lxdR`ZLM)JWKRvkoXAaL_+xQ?69Yw6O%dyLJ~|%isyu{w{;fi>T<^>CZKt?O z)}yw(4qcxDh2(B@n~|Q(uuMhQd^UowNPqVb2Az5AY5) zd-e9Ja|mE5p4pps+qZz~|C}+@hjweVN%&ph9B@SffW-^-e)w^M4RY{H4BxJHnY8ul zSR?wE5i*0o`$TZhyr}^eRtji;GJeogT_K`8Yp=Y#=OvfF?qzUuXC;+r`VadDklqMy z%F63W&4-=kc2|g&bD|xN-gxL&OM<*4!_+iYRfsx~6f)1Rt#S3!a0Unlpnf%9v{uI! zv{1y(MRhAX7T-~Nsj(mUgu1qSZJ+u$UTI$3o;=5DYY(dQO}K1f|9}!m9=@dM;PM>r zwGfuKZzDWQv4bj38nQ-&*QLW+SMnq={@lmRUdVa#;%+Bzj`OW61R(9>IN#RJ@sWYMb(;yiIps zMZeFdb2;HB2-beG)gs>LKmanY_^~d|*z$Q8=6AQ_w5_baKF_fdDK>96+}g2s4o@EI zcEx75R?$|yn)6S7vm||Km+2lGK52`W%)9bwDsK1m)OB&0Te=iF&^|LK!PsECc(;_w zxXe5QtqcSfx%5K6RVTfdZ3#Q3g${Ta&rKQADH>{cUwAj?Z%G#54N-;XjQkyz{M;-u z_1l){WOCIVW2cS@^t;Vu^W#wB#n9thW&@+**HotQT?0D13;95`(2Wpk8-YcQ+?eQB z2L>_DW~n;s71vb}yYZzX%^?*lbvr=l5QoRuC>_gZ6xoL4xA_{%H1+`jomJp7bQEvA z(1m@m)@U=C95s-(&2$>~_Ghg{4cY-EdU*$-G^~n{1q_k&orOGrSc@i*rZZ86FMT+Z zimzA28NJEw6J6IOS*sarrUbx%{<2<8YPMnK3K*r;j6P|ym5HME#D~{Il)a?zHI-$( zX#3W4(QfRU{g{GYlGJ0&E6~wN0Mjxg`>RgAA%GVME8bz^6#pR&Ye!4`auaZpFYm>N zzyVscZ?fbkz$fUka1tzbfuK{jrcI9GS<-+tl<*c6)67PE8hdPRm_-t_HF1>EQ!l_{i{haPpq*5m&SFbJtUe9zjqJ5}l4rU*@F(uWm_{C-2lbWEoX|U?q zb%|CG(u{m97jUBAI%q=B-1gWEDN&IuI5p>b?=vBwJpAh@x%TiNzKELK?4H(6V2jhb z_3E(JK|GsWsI5=r1VcUbd?(hZogH|v(*U0B#i+9OZDKq!z(@rc!otb+2UtwmOgkiDfD17nje<;w7FLU^sQhpZi z-wBp{I&V+IJ(97baYd8Y%;Oq74?X0%MO$ik@hW2AA!>Dl={jpwOf!(``Fu|2rAL0g z)T66^0x`+_oX{l;W3$LGBpF!f)RrL9cdmEIFvAFR^wG6HZ#$3U7>$13cFbJ*iY|T~ z5R49W^}lH58z=UrbX_7g@&A~#TwK+8*d{(VnR7A3*YfYbJMK-THk&Tpvb)K`mr@to zXA%b@i!vWcG&g86*0LOO{`lP@4O?a(#q6;vbN)JJ2Y^C#dezLny}e_)9mn{Nz-N+e zecCB1lDU^gmT-s+1|jZAoLo!L4$2a-S3K$`0QR&Sw8}ggU@Udld0#kINU#<13*s+v zWPk~?>erOoctHSvKAxFj$FOSmiZfb%QSX#L6QEYw6D6fsHzMmo0o9zQRvJ;p>44&r z`6EGcXk8mcMAnnF(>9oBCQu8@blj%sacSu`bJVKN+6mTaC zDC~TF=F14kD7tv`=lyGAiH7rgG%tYIV_nm zU;Qgbxp5b#4CyAh@7K_AFJH%?Yozwmhur=b^IzU;Cfj!E(@*heEQ>&TB2zpKa+TR% z<>ot#uMa2d*!a-@1xP`I?s&5aLB>tgiGf88xx!`O_|_8ZOu1?VK?8tohIohz8zi6( zqCY$k@Ogaqi>+6A&lIwlGtC6{lcoX7kcInO?C2|tYf z)-g}2WNTVcH}2Wt`X91L={}AF6bB|KYUo9QU#fcmc*QKzWrY6*$0C3QMPBn*QSf^) z^5i;|Vbs9w0|Fy_<%afX)lGgHTG!&p+n<8Cj{7*6^3V0o3Y;;m~=1W5*3m7z5c%8Fn#_COOrBpGfrF2I9FQ zOJlq<0u+NjQ!M9b|A1zW@&UY)^TnH)SNP(p9>8kPSo{2LZ}dZ42f;EF=duVc zV4Q1Q-?x77LsMf~4rz_k5B)S34GOKdyJeI26MZZ4VB?%gI3?-YFm35tRkVE_@9u`X z{(K`I1)#Xn2c_1)KTMnD*p3*dIV46JXKaZosn!=6JfhyXAwqSQF{Tk=*e{!cAg!C6!}7B z$mUaX$LN>eq6_by9L?fBe>09&KQpFe!)S+YLjIM@68Fr3bZKOdRU%$@xiJZV$NKx{ z-&B(ZtOUknRD}}lNv5!#JF_=q$jX>~L0TG}=kbw$<#JYT`;|H*<7BWg(A;^rjtmfv z-;x#lX4Iu`jaI=s>t`c8NgAi7%-;AII>rkOm|%)n2d zI=#f)@Ol{@v#R~-vwyvUrWt%LL@h$IAF{Rfo#M5~`_AP{g(4vb;Yx`=}7h`wXOiB{2L^IMOO=49nVGEDo)2Cfjf0Aa~ z1mWW!nF<6Bwie4^MeAOr(Tt^YG$pR~$v4)+pV0;J&>60>p zM=B+rdu$pdkfumbF3@xZu{*!-^KdrW&K%GtS&Naou{VbW>J(#ILo#xYQ zRmijN(+}bRhl$N1#taNM?O)q|=qWppERMyxZnZqx`0iGPY{$Vpvv$(*emLY4NIJUI z-2tj~DYY!gmHL+|c0+ZiwTV8{RIj)dWJ+1dTRy3vIgk( z_rJa(n~|o240f_vN@UAr-stK~mn}xc&I;z6m{fIsbx)S0^>P{`V$WjO^0&Efa!i(_ z_Yw<})l|LMba9ga)|?~~&~BQN95VuPWE;D_Ik&WYB_9XJaAUdU_;&awX0t+vmm#?H zKWSKJ#05^06O&!|OrHo4TeQ8Fa(MQdh4ujMmp8pUq7A~uciVEMaK$1{)l8XHxO_zy z@QEFvSNg-{K^fUCWLx#3s`7mywqW7xo7N0CJPp@TasE;qI0y;un+VWLX&c&~6_Uvl z2=dCI3rc-T{PH3UQvZMfEIKcQ!`Ms(lNF{uG%w`C_TEL6JKw$RK?^<DzzOLGmK@ z3rai51G6`34(6SMu2JdKG#mnB1>omU=p6AOQL|OwXZNrbG4*lJ@QX{fiBmaGN>!ht zDSCSezlQ29{TczE);Uozx_w%xci1Pf&sEJKZK%GvDqdCg_wzF6c#j`CXEn*DOrKDg zk1!-1-lp_hR-*Cz4z$VG!~e#WxhbBv+nnq|A4i1CssJPpD$~y6UtsDNJab}~!t;%w z?L&zHcbQNf;&-4_at=4>_EftwavN4mG1Kc}xsB+(l$b(0rGY$y=Jdh8Kpovs$pKMH z6?h_g2Dqki1GgBpZ#H8Ayu)?W1{{$Td1W-9Y8aLM33}Q2EH>HU%$uaKzwurj{NN#% z>%Tm>9EG4DnDna4996*5DjlArOb2>*mPbvgp!aG0?fsgP3ICI!TKaC!Sa{4%*nigg zX95<01kc{@=*-5^H^PFOqG|9Ez-jt%KYx4rEd4VxVRR2>!_us6b=cNBn-V8}Im4zkB zk)Vb=#S)Si^nuTAK;NBKqkk-sD{k)X;X%f65b7pF+xjE>(iz+0>mu+WB{2*Gi-{+R zLLy@lFLH6e(YBGyk^W_b-PJy@_|)8{Q}JoS1V-5z@?NvE^8m z>y4BQQNkTB3A5MO?n)80y#LS4?bX}N%hI;A)+@*v! zxERVvri^L`35ymtT|T<2R7(rF0K^cdV=l1X@{b;J8!MFfE*CUU=0JL-nem61;BA#O ztd2ki8)_>gmyJ4X&5-#_F__v5C?hrEt5re=T&xCt)%a3@(al_@OdB{=sAHI;!A)`B zM`&n=8&DxGe7Y#r^3UD;Xw-Q0Jj{%At15}&$Ic?1LuworV;z%L!;;xY*G37%wBuRd8D7bSFs;JnRqx39{8^u z6}k^@XL&Ug5bpmb#d=ep%=$xhOF9E~bt?22&;X!}vtmR#azedP{n4y%_xJ?@0))-) zyRJV|D=+y88i%^t<~#4M;J@C+UpyI67(sRmjtg$-7U-&Z z{jdl?$f25Ag@Q(kM>Rfzo7L{Hd;fB@Hi?9--&)G(8}9~HcZkr7A~cN|3us1fZvE+{ z0XudKYq^bo{3_hohF{s^K`MTipuiQ5BP-P0zMx*)rmyE zrT!FcmVo+yX}1^WVY%x@|NFFKoJ^o3bDZnqhBW59W8*e-GgB(bhdeacD25KSH0m?6 zxFEHU?bR+5-1QyZtMH47?y2L(osAZmyk~!RSitS-_yVT++%8L^#KqC)P3k~R_)3J3 zU&oWR?;1W?txcaf%9n_mc`7D*t5G`u`gWikaAK#toN%B5&ZDN>vdU$HwykUR+1un2 z7nQ9dU9qCLT_d}Ij&wFV_RjrOa9sk3*JrQjOaDQW7 z!lv&rL(&kjk#sBp!0*V+$Kw76I1~*vwRlN#_f}&kK`whkTKj0H_a9;-W}#zW%eTCZ zuRiFrxdrD0L?7jjegJ?6aX6;nKc=H);VNqz4FHOL>LRW!4ARo)L`7V7XL4Z>>L*o@ zCbyVxR5}l1F^6r02qWe%#oqAV>-E&=2n-QLJkHp+?cHpqjwt!Ar^FjdMx{qLm9_O# zT{U8CZfMeR14CTpnyCN*uIA3eJpEqR{G2E7r8h>2(6up&Ri4U8m*93%+D(9O z{)6yQ_Uo9B(pY@1ADU5%-EG%f21TGLg-UShzW6ADdMWb7k6bmgqT@I3|Cve0s%Wc8 z=SkhBjZO7e)vQ+r^PU7>{)^2}X0u{6lIX%Wv)&ZXvob|!2-boBcfY@U}U}vT^|AthUi#Ov!G;Oks4PbR@jg5Dv>IcCW#Cp&r}4S9pz2KmWjz z4igK#?F#7Ym+6DNJB_0rzd5`rG<9~LZxmPO-{)C(DMbC-HtSkB(Y=Z>lK=CHcKn_P ztvTotAT~c9rztnmd1xC>FZaYYi@8hNFU22tsS;!dwqBkxC{_gWVII7DTJmP8Pua{< zzxtugROgBQ*L42AN1ZK(Kh|`{fD>UI)0xUqIoOaLqGubVPdzn=*P<*HCz)6g2-d6} zhk-U{ZHU`#lj-o<#~#zM-sE!*f|)bCN^n*Md{obBY^K%xV8Cq9nmyorEn;MN;dJE1 z5Y z;&>XX04h=Jvft~96~7!E<{R;a5rHD;E=z~wDEb&`z&d&iK89z9569#OI8`{#vo!F5 z72D*PR;Z?KX?7-tDtZZ#5p3+G>T2YCOdXxi0xTmWW5nmFWL`!}UBjG=9`Tfg={|$zJ0cA9*=zp24fb>Br539iIA(-fDI#^0}V@Yb`75sr>JNeNJw9UO@CL z=CC|XXk=@yiyd73biDD>d~VuQ8Td00Pjej~^tcx^b~GAb6D5*%iiQ63CU9>+vUSZj zf9&w5(xB{|K^sp6`v-Kz@+uKe58LaLm4NH^HTfR{x>W{g@16D}I(iK!_AjYJul7%| z0n+u1K*)P{aV%;0$QzL|@)OLsmBNKselTO3z;F~S)`42=+&U_K8ovNi0I;FWWl_NI zvXjbo``{{)3 z*tfC%i3^C7m`v`$KiS!U4pSy8i}yk#D0Nh%W3uA54Wrx(?WgB`$Hi9u@+m}P&+|7+ zcx}7u+)4V(%36Z9qQ={wkhSEdb3M=BJ6^Q==XGz7hWPzx-{15y^mP99Pi_2?yU;-8 zr^ttTBMB@m-^*Xxx=pbMbd|LPa;t@$zzPjh-QX+%L!X^A2I}`$0VVl{br$`5BS*TO z_dC4)LThH?ip!qamfROFI}eBM*{N6W`gz|GD;1bFzSXu)v^|LEeupP+(Bd<^-$D)No${9EUCU|8D=F9E+^U(ipzQ+FERM%l`@aFxM^2QE;1a7ItGG`Z8v#h zYP7ePxF5cCJiY=PMhDxNZi{Y6s8_b3YGrqExg(PX{-pyA1A+5Tun3gfl461Yf(lqc zudNFQ2>NHTw-sAR3VcBqcw?+S>iN$ruOajaA{Vs|FMyVB24qh(hHmIx(TUJI-sIbA zgc~7r;n(iK1+-_P=asE1A zK<|`>X3@}>gIqC(p&ZDv35{9=__0l$5#kO@zHz0H)vM0P4B*{lg;8n}rBqdu*e7ezM>M$%r&b!c(vBo2?yPnGUWylLMd!hQ1g>Rok^=(KyA4&fv@JC3_m~Q{4uypT53Q;eSm`74Iu$0h@Fk;oxDp(ZqQpIB!qQ?{4`Rp-{ zw~uG5NA(z}@qvc}Y;NIPxYVEGHST?-i!^IzUh_!eaj&Q4H}$v9=3Y;<*rV1je}!CVA2=-j<0}Z@`7{LeSI`vIVf-mg#AI-487H!g7bHez2 zRhL&EXQ-}ZqVD!Z`RTbbOHYNhSd&QQG3Wphvuw$o!XNv&%u56&&wL9PjM<183KX~+ z+|xE=4 z8dUMT?c|R@EC!e%+^j?$E@& zaeN6>Y+cjX{b{dEb|~xF)6ns!&~9L!D93qW!I0(WY5K-m9a63_TG<3D_mF*-o?vT7 z!2wPl*BEzvLq`_EtVGN6rpB6vKCj)FHj`W=#FUQWRC3=09mEujghc$=JE zr6GH0(hdSAUU{h+svCjS@@yG?7CdlTU^horG@ERmEFBzm$M?z$z;F-62n$#-m0OgP zXY2{qfaGv!!JAt%t0t9FJ zXG^=eEr`yyTx^m=p6D)bnmfXo@L6utOM}ZG&84oRYzpDx{)x9TEw?sO$$b+H-33O^ ze`Zrp9uNhx-J;#1VQ)fG+qpi(Grsz%)_3T0Bye6r=#qIZeij+9`kVP{midukYZn3D z8O1+s4R999f#0~eUX+(O_6{0~ylR7FON94p1`iTdCq$gou1(ye6OgUDTLCEp8qx$yV5C>mk2D$ zK{`&TP3Sf87Z9cu?V`9|CCZlz-qE%(Vug}-+lE{d)9}&%j*lv_nOH}G-K`?rX`%Rl zb!tXR&8m2Q#~%6)r~LA=jL^B90ccJ zuS1(4hdbvFu@O2nZu$dSM#b{{@6>B~Gw30MK`e)N{!m1?u0W=V%9PV^@Y%KGfS8Fq z_yK>@bY$dKtK zO=f6UZ7Uk;WF97{2-}i*f^pLICy_>r@I3I=C6HEIUsCT13Cvt%Zr-VOXC8EGp(8iH z367ERv-qWBR@&zUJI1I%sd@QzGe(zPvis!6>xeqp*Bq@)oLX@*WgLK>t~VCe2{qz4d@PC-Hm z>8>FLX%M7i1SBL!S`fZ_eBSpv>#TJa@*mEcJN9+`>e_o~sprAmuVc!R5sCVJigGB= za|)d0dY5MUEFc$HzU(5kqm3VFA_hHEU@;^TfBP|i#F{HTc*?a|WeF6UksOoUzb1OY zNdGtyY{I0&gP2GRxm9_cv9R>-arN85%SQ6Po}8T2jDb7m$cd@%%DJ;_N7lpahfE4s zQ>ADE?Lt(ov!SzspLr&i(NBJFYr9d^yVPiEscnraoE~L7k+;Cq$_rR5mH|^A=-PS= zDCEIX^RmGn?U2Aeo8l#i1{pEyyz+9O%TKak*?;laAV5#57z7!`w$WriMVP`f@A0<$ zfvJbjW+ZOJ)kam`n~tkCCDaaC^~=lcY>#MDh~6O4@RUvMO-OEW={NP~Q56IXLR*pO z*oz(~yNA(l)qJs@13uUAhRw4Oinn=f1?V>Dq*0{ix#K|cYdwT^OKGbU`{u7@cYp;l zp;}M2_*tk&I}Hr9gY74A@17NWE1YC4oXK2=WgzE1I6B5lDv!}J13Y=neVbhmq6Lv` zlf&_UT^K6x1aQ<_KnVMF!7&)ZhLa^;AbV%g#kd%~$OrDlO!X&!qjw|%ryi5!G)vR}90tLl0 zf4QSbk6C>VW#v$I0FNYou?s2c7}kT{O32f1@{d_|02#KjzP7<9$gF0RhuM^aS%z9^ za5&8!&{JsAhuS@}V=z(McYr-NJ>ceppx+M9g%padHn*g9CGKNO#mYe;vN$lzS{AY1 zbKW}CfUhA8g+logyv5D#Nb~!Sa3`nU$V1pe69V=mWpU;CHN30Si94J-_mJ`8%NxEcIIixiXk3SgpR zUM}v)SSKg|Aj6oJkLr4scF(T38=|cigh<{A;4E-Exbah<5%mL;ML;C|T*Zuq6&sA| zK?807Ht~Ee#3?qYVowv=>MgLtMER~n&KOAv=tj<)aH#NkNzGh5P~~t|^7`1LHF}22 zg}~{LPnVGe8_NPYdm@p8Xi7h#St48N1I!7sCF)t6Wla z38;easxuMJ*ub!$tYoQr+bj513%|sMS!rJ2xQ{R>Ob(sx@x6a7FasFH4r?e3N^Nf`xaDo5Qs ziiL>zhNckN>yOtw;NfS&BfOW!-Re{P4sg)7FmwEUoH7_lbX)#v2KGX`~a) zXkz-vikFJfw(LI%W&>SY^ECj*yS0J*<(6kA>T67P+|QAwT)(S%S4U$r6*%ITu*5N1 zlOn`U3A8yXC4JsryeRX|ob{%s`oS{^(PT!QjXaAWeJ*Jo2T{@z3ZWJhcqwn2w6HG~ z62|5k3wM6hekYhCxi5}xAE=%#U5^@2^WDh9zqZ?-W$Zr)$bbeL1m$!G^|Uu0BT=`i z34jbO9&;#%!2BNPbHNe^Pb|^oPPI+4hJ?~_#vUCCM4^~Z*~?m-O5Pl%Qr~Vd+{XQm zk^JXMqXLEuLc3^>}M@Jz_e7F*h3o5pFeyXyY44uHtuiC4gC|VgiRS9aPysD3u9icwu{2z(aJh{ z4>%#sJjo!WUfEyE;gX=~DT?}lahNfz@d&?01Zir~NRi21Jg{$##TRKZz#dd~rldl7 zXrevh-bE7ho7WrcUa!YNTZ_s+mwwfm(#q17`$*K?j2hYUQTJ|o;A z^+8+5mwHo4B_*^S-SEUzXJQE<#ETdlib}$jA5cO&!Edp2xeO_Mj|d1X?56MP{fYTZ| z1Qa@X{zLstY<4gw3Pfset^T7_WXc`iLIfemz&EmMI~A~W1&n6;GcaEGZrnaxh=WWP zpA1?zMkD%JC|BT^FE-ntlrX={a<6wCmqR#J_2iE)rTK03?F?z8K8E$u4lcl?$M zj?4FN(%CViF`g_6B;mfBu*O(a5=nyMGu6|ofObP4uEQ_|VIoN%XS@nihozL{Unfr% z&y0sm-Q)w~FCS`e`p3;bFlXBRF=kdq^LtqhH98pjQq(qUF?IMdy4crekfgsDe=k<9 zZB0p(p#NyH15DyJ9m|VoW_F|PVQ^3t5&+*z`!!@J<2+Z1>9JQz2y_cQ)LdDllr3F~ z&gd9Pz_SdMh}$@RDGX&a>0B6UjM$N?k;5Gxo|NEFN6*WPcAsspKIC1ZKM_|>amshc zXox_kb|!IV`<#xx#2@}y*fyxkT;Din)l_%H{r*mmvYSVa@_9+*N1A;-kzM`Q$8d#t zPR)nE3{xcnhsL;Q&l}nwt-5Htqy)3YqD)zFJH4ss-%ugJfR^FPwNZU&GfU_SvCF$g zSCp&a%SDv3DqkZugOAqKQ@>P+uVG@^_;5atFJ^1jBN93fC&rVnqcaRRxkBH{V%@{w##zNS_eU)p zvs-wACm--01qB$?g((mfbjW7`mJ4r z8h@V@dY5NT0xC7SI>9LnC3-9p6~Wf}(={7WJ17_JkKqoc6Y?b4Vmc)%jCS<=$|m-n zB<@#=S7jCN9i|)!h8&3xb{SX3iL_w>E0e!Z$V=(EBudnFT%AWdUFh-A2V@kv0*cmM za?G%11vwNHY>e+%D;UDKm9?^?DMME#66sq+%fq2#@3X+_UMUC$ya~_{-GbUVN^X3A zYgIy#X-Mv_q*I@T$GvLR`?6>=Zv(Mo!sjA9@@ZOeTayhUgtfTqC+Jb0TC~;p&^Fgn zpM;?DhBnMC2J#}zSafUw12ygo@jHKiPVR@N#N0E}z)TFb4#X4R!)UXjFO_P-+SQ(T zHf2Hgf#RB_j_TS?YbsUZ_lBuT*|FRm{>*J>FT=gm#z8#uOS45#5bj8CLD>Lb}k`|DeGtz zyKz%(n}_i7;W^$XdADk{bwcT6k9Ri2>#U|8aO8k5&lByTmgVqVV#L*x{+hn;=_b2i z6tIQ5i3c{H&!zV}V!1q~9NvHmMrZZK|Ho@KK{f(mb1?4ka5j3Ubx%+4XAH zS@F?s$>!q8hkt&o8DzBwPX|8A;*#tYT?ihYAS$;~&!Sd6zp5wQ5XMtLl*h4}W|t>%TX+P7-ZMzvJZ}1|7T_A+C?1Atc9Q&;|39KoJOq1KPYueQIa&l-K@o-u(^VReNUos1wEV6isdIg$m4bN1qBEh<=$5 zauN^=$zGtwz=;?RJ}dS>Z;}|PdIzs>PA~3K)z&a>roGnS z$=~BEC?_|er_}h!*Jl3etJ8&>i;X2MuQv~xHzv9wMG04FuVP*>FZ!RtExQ!-xQOVe zXv)x##X;s1F`Lb|Y~{yKJ6(Ey4&oQ8J6GcOYb_WL@*1_ny}d3twv<0WY3f&%%DPq$+rB?Pvr#Ycte(kVZ*4yWj>=}ayBS0p%*AN`kFJ#l7|I@vxx z4mwHALoH9C{;hGSbq=*T3O)X>-CW7_8TTcljtl!RK6H!C%7m{yDR%@3WUZP+rn(T+2++xIk0Hz)_VKF!&aXwigJ)jUQW zK8TVqQ_W@Z9>XH^F=AmrdbPfhl?7niQ15Xr+^ottj$7+`wN1ns8w8yTNoynnf@O z12jc8;vusdZ^sd}3HXH^zhi%FboNSHZ3k%))9i5n$t|X0d7KtA^SF;`1AiA{Mk7rU zny{l6gcdsSHKQc;=54hkXgxy=jqVYhr^jGY(5@KEl#X}`HC@b}Nuh-MoC=*ASzPD9 zhTU|Fs-cs@GmSJTcZo@ylw~KJlcUhYqr!FMlq8x7r{g1VJ5`ZTNM$$+@It>1T*s8% z3}ZGP-KeM5aB-QJ6n^4%gSHJrcb~-Kt&3DDaOS_=dzo`zlV=vt%*j2xaT!8sMk zNgOThy(?(c&JO!KUHsXHCG4BM$O+%00?9zH!a#hxl^*pJ&aYkXe*Sp^o9zSR+b@;U zA6+8fE2cIdpn=X*@L_5aP!gm)<$ubr12^~KdCE_%u2;NT$g{!+w6IZLJtg**(09VIfiDnhdqI2 z1+ko1TbMDF6XC=u#0d*tp&c(mqb!OkeO_4;r z$l5O2*>F=9ly33PG5s*oM@-=M9uXZY6h1?W->7EzOg3Yu2oQ+^1TzKrPOP4A(_} zeT;WeSEfJuO|CXjim-uy=VbWqo%CM|hDs4| zazgWmc9-db7=R&Y0EMBJ3kV-_G2@6j=u_P+Yrpz%g7VsPQ#W3v9ucGgR?znam!{%f!BK`Rb1&lIO5gS^o zw(czp0n1~?(AHLT!)cal5x3(-o+t~gFaC_f*$;XH$q)F&^yTvJ*n&WKKlQd%+GMTKAO26>lM)fR-k zSI*+(__=@M7IkOyjv*ij?IvD^;Wy#$@vqpwyE!&!Lh~NzzwVA-EImAsOdQZ*{o*G= zkDJiNrb`)!B1VrhzpFR%Sxp<5^Zm|V3ysTblm{eQ&=WT{lY`!OPa%J3qJKt>#xx#& zCm;p^z;6tA*frH{X41cZw@pE0-)1|&8ZAQj#3LSvk_KJX8``;YHovX%wBdsjft`M< z2s6gK3d`a^_F?-z-3Q&#C5ZXNq6&Kfch^yK}nwrhh-cNukikr5{KY2E@74e zJ1H1O0$@8PiNMbjiIolbE}#z;!gI(+S< z4y334n0+p6o6xlN$~TwuY$ppnYgYlbTXHE8{^5_=>je{(mzLA>)`9wXhmh(J5TF!_ zB8n!Bq{1`lzn+uu!SXAFpZ>U}g=IxxMW5J}U56>>FK`0@J{aU3>5fjw-qT}A`LINK zfUf#XXbgf$h6{{frtsfuGy!_ zDL@pXioH2M&0!2`Md%1J80*={j+|%n>Mc33ZHSHRHI+`&klU!g&vx(-)(PF=jHXSf z5wmz#j~U=NL*MdX)@o>CVv?Dabu}>+et$ON*Uh@75E?3-M8zj_!n7J!I4`{JY1$=l z-5L?rmq%R{p|6o#9rT+axO4)0ee(E=-j~Blnk60!0KaJJg?p~T0|!mqt4Ah&+|*LP zGU#}9BQxa7P%GMo3V!CHfA>@Rc?QknpG(=3WgVSva6;reaON9c7W7k02~NW;Kp`-0 zSqC9iAk>OO%_8p($9jI+0!6hf8hk8v`S>uSeu^geu~cxFnGJ`aPgazXV@8A6U5WOojY?-ZQ#L_Q0dQX!f+~63WZIsmN?#fQe-^t?e7wbC@fhGa;k0+j@T4R=<2)&%U45s- z!7mX%2a0z6R|M@pew2TW+LLsB+;1FGQ{x;1(BKT2@#M@MKbppfPZ6SEdTlGEA#iJB zJL^2Rd3A$eyQrI;8LgY=rU6}1JbJj6s+2pdk$UP}z41qIV-54{maE#tfwZ8Ty!vo9 z76Jd3dBU@V<{hJj_m<{{z)|<^IlsN=44IVj!0#>fl8RT-@^c1Ab_F_)hPhG)|cmhhx=;Zt+t|G3vVt+59OX-(P79<_W;E3ajxN~ zjd$12JVZ~4His>w?yp^{M$Q*IqQ$kG-+He;^3QLl-y=MHud^>TRW5bVVZD$8|2FYA z=FfDr<4z7y2tivyrKFeisT6Pm$;C*Eb6U_ z0mskbhsiNO>B`WtS6G-V!ku*`n$nQ`mGb?};OX4Imz1eZ;oZbvHbbLa`Dl4L<`NQW zWwUH6*yC4Cj-v{Mb&Z@uDYewkN%DI)z1aSo|9BRyBFNtH)H0AvhbkCb2xSFxB{D02 z(W)@(msTBDSL(^~r~%iF5<2)BteF>YxSQ9FL5yE!8^xNdP7!8s=5mB9{9(G{EEj +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeMCore.h
    +
    +
    +Go to the documentation of this file.
    1
    +
    36#ifndef MeMCore_H
    +
    37#define MeMCore_H
    +
    38
    +
    39#include <Arduino.h>
    +
    40#include "MeConfig.h"
    +
    41
    +
    42/* Supported Modules drive needs to be added here */
    +
    43#include "Me7SegmentDisplay.h"
    +
    44#include "MeUltrasonicSensor.h"
    +
    45#include "MeMbotDCMotor.h"
    +
    46#include "MeRGBLed.h"
    +
    47#include "Me4Button.h"
    +
    48#include "MePotentiometer.h"
    +
    49#include "MeJoystick.h"
    +
    50#include "MePIRMotionSensor.h"
    +
    51#include "MeShutter.h"
    +
    52#include "MeLineFollower.h"
    +
    53#include "MeSoundSensor.h"
    +
    54#include "MeLimitSwitch.h"
    +
    55#include "MeLightSensor.h"
    +
    56#include "MeSerial.h"
    +
    57#include "MeBluetooth.h"
    +
    58#include "MeWifi.h"
    +
    59#include "MeTemperature.h"
    +
    60#include "MeGyro.h"
    +
    61#include "MeInfraredReceiver.h"
    +
    62#include "MeCompass.h"
    +
    63#include "MeUSBHost.h"
    +
    64#include "MeTouchSensor.h"
    +
    65#include "MeStepper.h"
    +
    66#include "MeEncoderMotor.h"
    +
    67#include "MeEncoderNew.h"
    +
    68#include "MeIR.h"
    +
    69#include "MeLEDMatrix.h"
    +
    70#include "MeBuzzer.h"
    +
    71#include "MeHumitureSensor.h"
    +
    72#include "MeFlameSensor.h"
    +
    73#include "MeGasSensor.h"
    +
    74#include "MePS2.h"
    +
    75#include "MeColorSensor.h"
    +
    76/********************* Mbot Board GPIO Map *********************************/
    +
    77MePort_Sig mePort[17] =
    +
    78{
    +
    79 { NC, NC }, { 11, 12 }, { 9, 10 }, { A2, A3 }, { A0, A1 },
    +
    80 { NC, NC }, { 8, A6 }, { A7, 13 }, { 8, A6 }, { 6, 7 },
    +
    81 { 5, 4 }, { NC, NC }, { NC, NC }, { NC, NC }, { NC, NC },
    +
    82 { NC, NC },{ NC, NC },
    +
    83};
    +
    84#endif // MeMCore_H
    +
    85
    +
    Header for Me4Button.cpp module.
    +
    Header file for Me7SegmentDisplay.cpp.
    +
    Header for MeBluetooth.cpp module.
    +
    Header for MeBuzzer.cpp module.
    +
    Header for MeColorSensor.cpp module.
    +
    Header for MeCompass.cpp module.
    +
    Configuration file of library.
    +
    Header for MeEncoderMotor.cpp module.
    +
    Header for MeEncoderNew.cpp module.
    +
    Header for MeFlameSensor.cpp module.
    +
    Header for MeGasSensor.cpp module.
    +
    Header for MeGyro.cpp module.
    +
    Header for for MeHumitureSensor.cpp module.
    +
    Header for MeIR.cpp module.
    +
    Header for for MeInfraredReceiver.cpp module.
    +
    Header for MeJoystick.cpp module.
    +
    Header for MeLEDMatrix.cpp module.
    +
    Header file for Me-Light Sensor.cpp.
    +
    Header for MeLimitSwitch.cpp.
    +
    Header for for MeLineFollower.cpp module.
    +
    Driver for Mbot DC Motor.
    +
    Header for MePIRMotionSensor.cpp.
    +
    Header for MePS2.cpp module.
    +
    Header for MePotentiometer.cpp.
    +
    Header for MeRGBLed.cpp module.
    +
    Header for for MeSerial.cpp module.
    +
    Header for MeShutter.cpp module.
    +
    Header for MeStepper.cpp module.
    +
    Header for MeTemperature.cpp module.
    +
    Header for for MeTouchSensor.cpp module.
    +
    Header for MeUSBHost.cpp module.
    +
    Header for for MeUltrasonicSensor.cpp module.
    +
    Header for for MeWifi.cpp module.
    +
    Definition MePort.h:71
    +
    +
    + + + + diff --git a/doc/html/_me_mbot_d_c_motor_8cpp.html b/doc/html/_me_mbot_d_c_motor_8cpp.html new file mode 100644 index 00000000..0da37029 --- /dev/null +++ b/doc/html/_me_mbot_d_c_motor_8cpp.html @@ -0,0 +1,196 @@ + + + + + + + +MakeBlock Drive Updated: src/MeMbotDCMotor.cpp File Reference + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeMbotDCMotor.cpp File Reference
    +
    +
    + +

    Driver for Mbot DC Motor. +More...

    +
    #include "MeMbotDCMotor.h"
    +
    +Include dependency graph for MeMbotDCMotor.cpp:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +

    Detailed Description

    +

    Driver for Mbot DC Motor.

    +
    Copyright (C), 2012-2016, MakeBlock
    +
    Author
    MakeBlock
    +
    Version
    V1.0.1
    +
    Date
    2015/11/09
    +

    Driver for Mbot DC Motor.

    +
    Copyright
    This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    This file is Hardware adaptation layer between Mbot board and all MakeBlock drives
    +
    Method List:
    +
      +
    1. void MBotDCMotor::move(int direction, int speed);
    2. +
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    +Mark Yan         2015/09/01     1.0.0            Rebuild the old lib.
    +Mark Yan         2015/11/09     1.0.1            fix some comments error.
    +
    +
    +
    + + + + diff --git a/doc/html/_me_mbot_d_c_motor_8cpp__incl.map b/doc/html/_me_mbot_d_c_motor_8cpp__incl.map new file mode 100644 index 00000000..922f3194 --- /dev/null +++ b/doc/html/_me_mbot_d_c_motor_8cpp__incl.map @@ -0,0 +1,55 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_mbot_d_c_motor_8cpp__incl.md5 b/doc/html/_me_mbot_d_c_motor_8cpp__incl.md5 new file mode 100644 index 00000000..2b929c97 --- /dev/null +++ b/doc/html/_me_mbot_d_c_motor_8cpp__incl.md5 @@ -0,0 +1 @@ +11b7f7e54e2cc80653fb6dbc7401d72e \ No newline at end of file diff --git a/doc/html/_me_mbot_d_c_motor_8cpp__incl.png b/doc/html/_me_mbot_d_c_motor_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..e2610586c76ef57c14b9e473d1e94653c6aeae3a GIT binary patch literal 67517 zcmeFYbx@RV_&!R5Qi8-HrF3_vC=C+Q-6h>!A3&tLOX+Twh81K9VNtq6Vx>zOzRz<%_kCU09Y&}q$zVTy@e~080b5R1@;w3qN-_ch;syp9 z@SB3&;*Y=&G*bl`Nrb!mug{$&NeBop5#%H#)V;EI7rnibH#+Z*&d)PKrD%g%@~x%p z3Af+ZO?4IpWz>@S>W0`?5plgL74u0=Pcmc#-gI4LO@kTe};#Lx24p>ag(26fDe4^QL2KE zm*5}~mIz!q;DCnx;@eR_C8ax7LUZTYoNc8}1Kl6UxkdUE_;lb~8@(kB=8JX%uHSpOIGw>V(<%g%p@=qC>B-$q=Ryfy_ z+@*EjYzR~A5lWM{78kf$CMiowN}lCBr3JQ?;9zd`b?o_`A*kuJ6|BV+0hr=E|BW2* z7c}T|^We#;v!+-((vW$?&U7S`JaJHz!onRnUjH=OP-DI z>(%EoVK>Ie1OIA^{CAJv(e`%NNw4y3nA7j~Qo`zZZ~kkWKut7vH&QJyoS-RqNEpehwJ^{*_R9??{iY|NVY2p))6smWpaj?f>M%|Er50e*e$vh3(#JG5lVC zFX08Tua3c~si~#Zzydo$9t~uGB5^2dW=0(o6Qe3K=qvWeKU{^!E$G&MDYLZU!8?I( zvJ?z8Cqt4$TGBah0pq$TTQLBh@$iz>RR90q-<#C^j(|g;>3{kUPA=J}6qEW}Mj(r_$j0fymWOHxWXMlBy09KR zX3%WznC`*nSp~luB2e@qmeiiA8b9;B79?m{eK&GL_p1f?xIXXk9AzB@8Ws-E4EZov z&9^G$z+KE{_aLxe_TZWc*%&#qRm{nA>lu4a4Q)Khz|P&C63Ra;_<3_&^9TsH_5`bF zQLvG~$&t7paOVW2&ksQ)=>lCU93EZpr;V4Q~Aw6bu1^7G8c z{L8&@O8)IeiTw94ZZ^4aUOOHpQUJLH-TgCJ|2y{aS{4osq4dD zA0sVc0kh@%XWaO+_~qeTyLYNG_nTQz{X%oUSwYWXE((Y@>L=of?L<-_hb(yCE=t^lk_QnH@-#hsOsf<;l7s?~jnF4RAQ#UIJ>66HHn&_}pr z4)uG9*Iqvo(9y7WJa=z@<=R7|Ns3gh0L~ett$H|vEff<_uIu4fbR(Aq=YA>jB2odW zZG?o`Hh1O<>??rQH| z`)O!0kzgw%WW{%Re`22hPON06lVeVYZg1TaAbN8rK97HHs9JV zz#f}3m*@I~66A~-^_MRi(`q_vv}DBdI_)5IprO&?7H;^P`a@BA0>$t z?P&p9!vAMA@A8t$%%4PDz&&mX9+_oP<(^WSb^ni?0$g)^@JJ>!xO;}MUFEH@B>~^8 zf~t@z&(WET)`r2fkq$xjx+|QQ3C9~~dJ8lEH4t(Iw$;&cfVBsve$3z(&d!PZ@?*Yw!V*9wO$atWjNXj@`RToK9^-nbiAkm%hQ(M}Mts7YotOzK6ILAWeZie~3P zX5Y#Cz|`&Wzy@ajx&By2=JHFDX4`YOL5q{l(md`NGpwiCUnw{SxTMBE{~)pB0GT~= z!hk(N3kjA8=A8M`jV$1W;7^9n=;$$HY97fDUbSggH^nv7tH?T?l!Atnmlq!G?!Mr~HJEnUeZu~67>{ZA(%or0C%?$$CW&HPngF_&+ zfOS22D&>91qTs}5V|ac=03ywMoI@fQnsEWCo`=IUX3uaQj$RNp=S(`z%zGz}tR^XC z$wJS6yGevwDuelh`Gc`_I)5%!XZC-F24KbVa?|j9Y~iHAAVDJAg+4RJfUTk(EM6|G zybgL+d$`ByQ-fGz+7WqD{)->OKaAO)!JZ+B$gqN^1 zG#r?qW8a9Xz4){FozCuU&ol`>3Yq>hz#1z*AfR8b-VTF)afAkWw!3mTfjF$;t-s%) zX4rejGp1wl3EH`=5n|5TN$j{1ssQoy@2+@*L&HDMh-$k|f4(YeTC#$?#CbAC_6D;0 zip&!B3KZVrD&UkJMi%8<>g$0@09637hu1!taZ<^AcMp5nfxiHsIhBo5*AFNM z|MY$b-W`nN@O@tAHJ*#LG1-|1B5Jr084g)nLl9EzH##w)MEblZLfq!mb3Vd#~z&4(AmPtM*?9JN*W zGkm_H6bR}?7N~Cu62iANxI}qNzU1f>N+Kgb_6(sh_f9?a_#IkSa2f|6etkv|_P$-D zAUl7!9miVHeE<9=>^fRX@;FNBL0uNoXY$$4*>SfQD$tQSp)CDDo0{qK^le61KwR!W z*W0=FZTTFO8h5k%o?EG3kX(RV03Q;4x-arXB;tes`h3tdx4)9u&m_O$q}nUkwXj#k z6OEK?3#t-A{e(n*Q^~702(i7R>4_KN%t|eu)msG8CtRc0d<1+Ax^U45S;t3`D}1h) zCw807ffepPbrAshdJ8%&;}lz8d>(NsIOAz&NTJ|=QVh$iVcl}Axx^)P8zw<5bM#}z z%4%SGeG|vg|9~_8K5k$CO z$zZ)Ys*$uCQw?L~u&BdjvR;*SG+}_MaK}Dfm358v5a?O4UcvZ0%I4@xuB~9%H|`_S zFg6r@>R?xx;f@Ys-^!-P8?<@^*kf7m&Nvr1DJaS5X|S|0n@v}8wlTY#Mr_%s7>ko8 zB0ue#hZ*=Fk84ypqR(q6<_T|~=JXT16D6Cfa}xD$5jLPO&Y?HbCfR6YD22|3KT=!w zEBq2DDZm{D9OPS2)hgzkk1xoiEH&mM=U$mYp0COFl?WAe>JY^ZQGmoc0M!r zrD=5gxf=2y*y!_yc5#7%q&3 znN2;Atn!xpV}^6I@U5r!{ALbnk|29%#<2}6=aeocyPa=NOar~1P`%eGiE#wNh zaC-CcV^yH1l>n5p;{;7XFK7}}LC%-ifH-=S^M-FC+9U?HfuEqS_8>>bVv-jRkpBzt z>&Y2Kre7;${XCdc-spNVjDKyFd?|0+8Tb<+7wRQK(j0ei;1!X~-s{DwW0&NbP{UuL z{To?NSHPm#HA9K+MD$KrldCU#L&JFh(;<2eCiV5`-utjKvMt4l#K} zX74lu+ZplV{xhs8w2~)a8^mh@$?U4#1e?wiELu@hUCRGsR25D50jF8{*Az%FPHbK8 z8wW;3R|U^jTlM^Y?H85K*|OI>^fnriwL==9A;WnRJ14afyu8HoXBgsycw5Dfjw4yvIAtb< zOyUT$B8M8=A>+`PXMG+04=F&O7Y3HfaV=rQy!oa*U_{ns_`EsGmDAFusy{N)3r#yY zdVaDMq;|Gj-YV8o7o+jjj?_ep)q1^odhToR=n zk2VAFWG5zuF1x*}LJn#rPNtW%=SzaEoPTaycPtgq(#(O{k~wVBu`{@EyG6SqgN?23 z-Y+an`@U-+y7#|V(d9zpnXbGJ-b3PRhaql8v6+H%;LQ*ETP@!=eN~OtCKffhawLmY zynJcZtXXXMC|V0xSncUp{BU6J)Jo-7ZF^XQ zNwgJav{kzrBO6s~(SsH*j8d#PIS+@X1;ruFV;j18v1hoxa}a#F4%X|}Gizj=*EEFZ zIjzAUEymJyqS@c;zVDwSPNki0>T4O8iVtqg)E^YHoJmM!~&EaaEq0zk7)bbF!5+3zU8PZR1xH11!z@1 z_a;NdiBYDrM16Wf8>z;*1{e~a$^C#qa3>t6m$k@nIb1H!)TpnKB+hyy?uHT48>Z}D zoFkl#H@28Ly|S*-#$*aR2F$aqDL9&l%uO*$G~JIXehX!K_`FLPiH)~~NMJC#@0%C& zEnU*Aw3}KRd-E`vy`vPFd(F`HEs-l*6tC<1NgCfGwN2Se8#HB8KMox`Tz4p0qVIj^ zsDG2&nmS3>jVeAz_76%UOFa+pqfa5+ggIy;O@ zhopRIn2Vkis6aNGRQ12~-LSTeI8=LYF4o(A;yf4($YSVNU(4LRdZKNE-UjDE zO>Z2#vYFo-!b{rfkj#AQXFdqIR!a_1qUI_<_v&HUGD6cErvb($1J@qHaW;}W-$^-B zS6JMwq-NqaE>+6qr(1mLC?_uH=zSm&!Or>N*`JOaRwP&Ar@m(f1%fJFv~8f}2)Pt< z;c#`H2)BP3lwiE<eGbO=8w0K2fWoUE_GJU(NZ?I~HaLU)+@t&4a#SsiV!y5K zOGglaAFjQGCgpBkLr_88??{)ky%R)9-KXqmxBY~m%H*)hhx&863-r&Hta_+6J5sl5dGaetjKKfZ>`v5tvJ_XG5=L7BdALI z=HR_YH|}TL5}nQ3gA;5RG8%Htnn+k3ikVHGW$F!}IwOQ?+#K%>lJ{s3mgLFHOH1`J zT^hW@+mH6cl-l1?aQKm8aHgjSTxGg6RB)FO+$zN(e0RuFi=@3;TmLzOUU=st z3Q&uCgnjfzA~}Af0_RjDej0^cTs5@->6IJ&HT4xs$93U*wEncVpEfmm`ih%Qi+J9# z-RG}lj(F@*n)w30foQXvquS;rULDd>oGS(F5@dzsZ_`)xge{DwY+W@lk>Ls-zy*p)I4rxU?k)0=43r zEeKt2g4|wBBO5_=h(P1MJxmcpeTKE*gbe|9dWA}XNGuD+yN<8TFJ1_k-V2gQtVBwt zR9}+|rV^iGeIZ=-ZtrR5^?7fPE} zTUC(fUY5LSLeR*JH7~Y2t&&Ldw-4qS*k53+3yKKUkK-INF&u7nmW~j`0eqMKBWyG% zB&dcqO71L~@+Cgw9g~w;{N@D7^Ib|+^OpK0Tw9MRVSUZ#&2tP~vVWNX2uFaYJ5xBZ zIdNs=`R0E0!hnC-wEQbzn^+acQ@UPNf9)T13RlMz6b)59tJzCOh46W5qDbtd3R+3k zr^9`R?x-a_9vQ)$*uwoUrKKM+DA+kJ%&(;F+g~IgxW9s$SNw*ujfheF>gX4j0zP!& zVrFYV-VL@af-F)chjxOB%@^2Wxx&}G?}K#{1P{$K&C^<6R#E$uj-I(bBMS?^Af?3 zN1I3}PB&VH6nt!Df0W`^@IaG3O=TzklFth8O9-sWdYgD@!RGLtdpZ6N^@iYr23B)b zc=<-T!{V}0h#e;;S@3zef?dFb_dPY%NgJXS)2(@EO?Vf=%k_6rcQOS=MAg_x^f3q! z*-dVqSe20|l(YXDWlA>>G`QzAv}{5Uj}vIwIq3+XI%v+agzhHy$3GolPVIW3wsKK8`ghfIzbd&MTYKgs#pYr@-u zNx^%_Scc01Xl+FOp=c*i6vn-xK*w^KK@qX6{T3}HBi{2oC51>jN9)+gyOR?Bijrdu zIajC84K1Uc*nvYE|Ahj}NaDxo%kR5`sj&jp1M?5MMz+SKkBajBOpjL3C?b2-k+_Wb zo6~A>kS5#Nf9{UXIi%Bwu9=t&dAw7GF)VKM3KQ4O&SKLG!-I=kpMTXSD|5HB4hrnX zn$F|7Q*7nP+lulzy(~F+&k=)&g9auQ*{&VPDMAfDww}zGB6Bw!475+qq(u9OAncU; zP5Zw(9->2)Nr8DHcf+mDf6H+K7C+N}$-c5<4ko%e42sWkBzKHyH%tRK3dfTq+UerW zy9G;0{FW$1ofUfMo4>yfPcvH<$=q`d-sK#Gqal(mGVVoKY03pKRh?@8l*ryjq~y7H z>4ca;dDbj=^926Nlx3+ag}yOU(xu2Q0kn~?Jc98b?Fb=CGemI@xTt`*E!%p#y}dyN;E=YY zmpF$SE3l7f#pfTFk5i{F=@(kYb54LDODH{Qq)j;931&{}BP&8qpfyTnJzkZ_tiv&L zh9ZRor*TqnX;0wS8(T))a{o#n3!&M(tfSx%;*b`OM*EmBOVv!U7X0#a08}7%EKr6v z?eT!(l7NE%-G!)qs2x~2;r<1#ud=O4Uy~sua^i>DY^tlL&D^=WFEQxhq?&)`uDKItKB2e;oeTC_JJR3B|`)>iN0Dod!9WC$s;do6UcWJvOuv#Bn9VZ*DIN{dLn(B{b zfeVwTFO?TA%qugJ%IRjARpBwd;$Bh zc*d49)^P&mQdP3 zD5S*FgYq*mv+m}%79Oq!p$>4(MK4SK@ z8T6py7npN9dQ9}uHXZ7^JGbaKE4B{$m^Z8()w!y6xCdLJ7U$OpJKq;A{RZ9+CDNW{ zu|<+b0J7l#F>3hIhs&V`5r{7N5Iu6(a2j_6)8_TjRuFul^>gvJRLLBf!iq+sm4aaq z93}-3d_BA(7anHGG6RmGZA(g9mj@&T&0_cyG~(vJ!k!3+0x*9~h<~SzZOiUsC2~;M z0`rCnvlSbJq%U5{EKerJo&_)}{FDcpdIf(GO?v`D?Jzm4?bRP!NCRpvl4NQ= zpYA>E$G{~hX}A>y^t6)83LLh;YxdtQ^>#G=qxMeZuhw3Fd)0VI9nQRPX&-zv8_Uwi zuD9M>6-Mw3;mCX;cju<@XQt-C^WJ#DcE4sggc*nDWA@?B(bO}Y7XSFtbKzmZd?AOm zd>GZ3fnwQ-C#v+q=g?uqWptzpr%mLtk9#+A6=^iY_lnpT2acT9<|?;iutwnu--nb{ zQ8@18!x;Xxm)FB2bJE(5)Iu72d3l}NOQ;Wka>#))scSH?h0f)# zt`9$~($p5)7yf4!0Jj9u6>i0IG~y@Z*5qEXbRN!X=A5@75F((G}+wPcvd4 zsJSy`bBEl(AgT0(6LgM@%SV!SRxI3_GI@ziboiL1_; z(@!SPEEmA2#}=EKeFndIB&>M&J*2 z1fR!x>X>~>iC=kdTrf6@qJp8hg7DQ+J!*jJ%7V;5r_8yTe9hI@!A1O2J7l!oEhesI z%m99p=AAaWnJ(t4Q!yzio|c4CMzE1gjtotnKKJtVK1K`V^EZ=@uW}I0&r30an-hB? zEk@=>_j)QHQIV&h$0VABbfI+|v$UMVwxR$=-})HdZ8;B>2Pe{u_TgcmT8MdHEsX6F zPdFAh6wbc>c)E6Ms6mHFcpC72ZgxJ$>rM9D$Gv2LJ{&#dYHyQeFI}?3fk^8E8o}!g z$3EgXAY!2;EH)%lNYdsot+A4OUDYRn{PosIA92P|E>AXe9B!|dp(Oo(HkOvo?$&c3 z3CN8(LWsTZLh!InP_05?_p9BKk>&yI<^tvduN}#_&zj4%WM^Pz{EO(7WkVh^bXSMU z*b~-ak^eqj)2JRauSUy4_j-U8{2@r2z7F80TM8GVNki!jyF@B?X+&#u4_-S>M} zx%Ph8Ds!|aeK04*48l#LGA6g%)ce1W^|8gC3)_1J{u{pz0%V^+K z62gWNEwS~Wf0nfAfX2aJ*Oy;~ao3@r`@RgWBuzTEi)XrBv#G+h%>3v{nnQrl9ee)Z zf(S59Gkgv_5Tae59LbFsgK@yU9C210R0Gs$w(xlH)6e1@!a)b4pXP@?6%2~Ke<;)? zWN9A2Kf(-N=Rq=r3chVOkQexM7+v_x+n%I)|tN7~Q}2O+wj2R<4h{5ZWL>e!S&>iD;oaB=hm`8Enkt_QKjx zEbq&y%EaDlyR?HpW1Ba193!-s9epbRUa6bB+TjpOX90%;jm@zvecoww{yva`<>{Er zzyk076W2{N#O^XCaJLkh>aij~n>#Se#9nwXE+TG*>szqiBCXIv4TA=M&RB|$Y>>V6wdznWb0H&!vTt+$A#p(h1|I`XWdZ)UCUbPPe&#>dx$_PB*h&NWCr>o zJpMu6&T^vFrHExCj^u`sq?uhRM@sUuOC52g?XNeUf1kI2Kxma;TSr%y%qTWimwa+_ z%xi!oM!*jfgw5gszskhd!*^%1d8}}4aiyeCR9+)Yw;wG-Dz&-uW~T|IfI<;7)31OP z|B;bwULbWFwV%5IV$U%+j>OJ+jat;+R-0<0o3lXKz0RL!n}w>L)H5sf*D%M5xU(2i zwjI>RGe7~dYl3_7X^3{~(>EmX(YMw1qTRL*zxBBrzWpU}XY;0iNQTE~?o6CPTcyIui)9Xp^m zEhTwo2lz^x+O{+!M^E(WtA)1%c2)X`u?z~A+97!e{h6+63gTV-_bSMpZBXUG<#QZ9 z42@!}G{625maGZn-@r4yhf0KKoW(L&>Xz3TESIwGB|~3};FO|{vZw-+>VXlom5!v@ z35P^Y1|{hTbfuTS9SFfj#z=@L>dztw6$MR|ESR~CQr zR2MYRi(+`>+!9Lx=0G6n{kP;`FUAI=31IqDHnYp57@}7TVfEE$+6_om0%>6Z|UVp)&vVJV2DQp2TbRN*qPBQZD454_ zVMnzQh!{W~b(B@^d}jJhwJ1wAb%qk)RGTd#2gHCpS??zPTB2#^f++pcz5tUc4mvP_9{*^zJmm z|H$I5O&H}o75(HaPCr@?P}iBx=(V+*Q~{a5vjX=3Q;t;t9n`JN7FK!aUSyZQ;8->z z&IsBdRGKffQxoqq1?YscmVcd(Qf?M+#{vKT3qN+2p<@ z_Jm(-EAy868fvEF_lZa~l)dI$Ay^qv%}S{@&4ssmy=F)rGuZOY)jjy-y8;^kwphaJ zEd1Rx8sWo8E0<-ZT%n)0cc+%Mg8o5L^t?gv$*Yx#zlc#K!za}Fu!*EcW$%BVl@ReH z^e}iZRI`E0^<%}|yC}C|%E9xA&RJ>S>uBRFz)b`~JksP+l5OGJ&S#2T4%2)*PJh_o ztcwd1--;zWr&EjkD#71QDY)f#ow;F8R)e&oW$v>IRjci?N9UL-2A(=*1GwTMPJ!(& zu)wq{3TFTcPoJru=(O2E%xrGp{>=PNyJ7Qn0rj+pX0CpusZ!9`ECE<)nLrK!Zwu@p z>d0vQ3-qSCPw=a;Nq%l1&Gt>(@nwJ;V9*ml!)K-;Z$q1!v3DcEJ} z$J;IBXXPsR38JL{b^&>?a-y>^H5SQ}g*7NI#o-&kQR%ij8UfOg%uy2>t*kry(CYye z6d@D9#K*kp0HA>95e9pQcKiugMSj)xy=AL>Va2}b6AK_v&{r(a{j%8k+g1wk5ADR# z!ru!;4XE$NX3`mxk$~~T1e`Yijw;|p=k~C%dM^bKpo_Mo-meml4>VZ*m{G+tUV=)eX4-DG- z>=u?@(g9O;ho1---X=pyWFET(1e~tk1Bqlr>1%j}oA=M|foV&_f4>^wq?g{FiK5JfhBsE|4+~d*o zBRyA3AVuD|pUANqR@2?#rkM;wgk>mHXEikUz$kH!*eh8dkoV#jnrdO zatGeEECB0ffnXH2twuz?AajyWr~8?4;`R|Xb4+L706fC|%zQkRA8)YiK6u<0y5jf0 ztAyL&^k*KGNDif?0eEM->APIYJ@hw2bao7T{vx@z9^w6c3NVpzobix8U3%_o<{nd$ z`XLu|w9Rx)XN;$?ANP)wqI7v)d+AMPxVnE_JXlY~?EI2_{OW)N=wRXktsa~}Ceu!j#L&%smhF!&y8RBzM!5L zS=71e7*%W{`fIy43or+fF*S?`iBG@|t0(Yw@hwtv(>Tc-)%yFn!7IWjKR*df1(x-5AkRQQU;vY=!iV@p@3f47 z*{3n*eND~LDzx$8OG)>L#rat^&53I{8+Z+9W6<`qbXYUy#?TCWl+_PZa$RK%KNn_UiZ&9A%{pb^}f|Li2t?7b9Mf!1uK%Hx^rOOQVp( zxqDxS4Llq&WD@5jqcuE@*G^15E4Dn}-_Qx>K5_dq=bz&m#|Px$^)nQ6^A?1d{x4t2 zv^lp3pN8JB@n~i_Ckx87JA=P+z9IvGc=+B>ZRiENLoh)*7&>rh6l9LWm^`d9M{sUw zNUZVGA4_25NZOc)qk;vHIbya>zE^}@IkJ~=nb9Ar+y*Hp`@ojEIm%cu=uwduh=)KL zv+?{vvc3U2^Jqk>Yfg+%+CkH-al#XzP8m){m+q|EMgEP|pyWfgJu+BhLio!#KTm+0 z@50}XYxnyKz2gg+ep9j#R~|%}EZ1n^1L#HVSB}p{EGS$>y8bPRJ6Q&J)K(!n4+cmW=^WKF2cT1vTY7>5HP|@) zd;XAvsC7Lc!q|5pE3CAB$-Q`4N|IC_WpAQ2tOs zZheqP8&9v;>E?)xF%PHDpbxDbCD&xq-eCc#NjgbCavxehGV+*>wl80d1*4JKVTWF^ z_0u=GxT}|Y^E%wV^}H5I29iG2nRVb77y5lC4j_-s0{2T+*Zk3K=5+?M8LoTZzbuShR=4lBLEoXrwekBM1d7GFQaQcZSpylv zhlszzoJ!juWW;i?3uLj81Eh46N7sD;X-Gj0~n(jY8DG#pd zfC;6U`V^B!4iS!z!dUcbbNYxKm~ewzB(Yoo;5>9@&7s>I<{C3`C04QEs+@%8(`N^h zRdG`7T^=KT2iKaACttXGj0@4DIjkysH7p6voW~-PYY>6SA2hhln_RhbI0-op+ZcD# z(y6_sMbUEWKC&Omnk~hlY(9)Q6mfdlaG~k$Af+=4m^}gFte=B|?FGa$xCRh7!sGYU z0G!!F=9@p2gNqJpA)!6<(t;Ur_TySJn!iJsoOHgnv>GiTlwTZwz&P)d%>&>+I%s&T zUmXkGC6mfsaSf3Qnx>^l^g4e;rVb9MO1tx&U9V&dN&yCrX5{kTXE71`evPt;t>d9~ zmTuf6Gl61wUNsvQ6TYMBl+1_qBP{m_jG9#UV%sm8zs?6pkr~Ufjq^+K%yvF(+~A+h z-``J>G^cM#b4m|JdrhaxA+VzA+c>ENJ1c0x+CNM(@!9=w##odxGc(gfcQK1brcjCn zmjsu126|gLpPUU9D-QCIfiR;ve&?ah=>zL44w|e&-`P|LMln{6Dl(V4d`{V%}xrvC6QTwhmAyGyI+Y?rpY>3+6 z!tB1=%FL94A=LZn+LLU0Gel*FS!e@5+ilFp5wZ?VL<-BuFvx{HR&~vNsV7HaWxFpx z#fTN!(26~Zzj&*?Dy=QxC`KSN2 zpwn9}2Y#@-fljB9C5#+IDG$ujk&|5it2L290SWPQX*r>LNG+hQ_h1Zmm_d6ssvlj)B}5Azeo;!-Ika9r?|>Rh_#x1tkyF z!!b-?jN&fyh>)ADf(_hWFz};oXq^)0qHQ|^Q( zw-;`ZJm*B9VPwkZ3KSJRqkR+m&SJ7d_lxlvyZdt_cxm~HE8t!C^M28sTo|A_y;(PW zC*vK9jNZ1G6ayVTfKBp3BE1~rb!MH41rIz0P#I9bFIaGMHV{Q92x>b%WOvSx2ujib z?HQmv&qs;wfDqf8j%WMpW4YX!Jdl<*)C=83k}NBgc;5lzw$r62ZuAd1f=^4mPxsgC zosmm7K**5j#0n{=A7PGVr{A|8QVJUGX{_`UJ5Xbx_!GpqR|WmRI{O!efb5yeQq@`& zXIATw+F#7@b6_0Q11H~8AtIR)%MOyBdvmwD=!hI1;)HG#5IV%h?boy4#tA0g9R)dz zmxcUFra0E`7JosPiX=+oKjzYDRMTNNCenJ~_!K;ta^1Bbw6N-)8$)PTSC+5oD~F7J znf#@kERusKtslJu_eLkQq(LXw;ka($MIfn~pJ~%}pp|GzloMkud5=YB!@|VUG9I0{ zDX06A=zsm{vvt+6y_@gi(Q3E}F_{@i%%V9(wFRogpSKWM=u**ecMK&k*H@zCDxz4F zYY9HBqAEi6>#9Loz zhAo-e@)3^w7Mok>-v221n(bIfxvuuVL{2DZ{OyJ&iU#!!7hb$=$8e(XvA^cjYEbUn zb1JQcGNdI!3sVuAz{RoCpUJTrCcz9z!fh^g$EJ&|g%P;wf{Y}I;lczR15#sGNJE$r z@##J=sk5rhkU6jUBXguDhI6U%3KomQ|y1qhMGV)R_1veQ+z4CUYL}b z>(s+NSVnWyt)hHeVlNSjq!-xKSGJqm7mRlRsZ2=lm~A^* zyF{~`3n`0jbWJxPXb6asB+pfe(h;e_b9!}XdUAC~f505pA`4G(siI@i*Y$EpNj_*0=%{%?j2YUO&^K0{6pa0if`h%GPJ~|r5jjOoiKlO zhCgHx5r4C^BVyR_=r1AbN<_X`t6#r?=!oCug;`7Al@3)$d?wp-PxZ?%EU?HEx*-zK zN)eBAlBQyyY~H9_Z8W5Es_v;ZS25hROO@5_M?C2p)%sPiehZ7$VqqfM{wtQIg{l;b zzVWK&grJ?3AnOeIYJ+V@y^itt(|$~xS&&&!fz3X8iiQ`?hH9wH^km(HCI^X{SL^ay zaa1<6B?$p;ym_xC4bNL~WB0%<9mV`3G zNmu0M`KH;h=`*>VDoA>pP}fqf2CtA>U4xrZ?<$^Ymd6ohG4n|g?>Nj2 za8i+#a3pS~yx$2fk@A{w_qMAs6j8$xkBZ(ZqZ^$Tm6vb96L``xK0Ux*4*ec(2;UwA zz{tp8lpB&M8MGF;+ACb6{kVR_9?a8kUa|ZIvt#4ws@exPt^QTil`TmXr9rDkz}??(6q(Dy2H-7*gPjsS1}oWK zDh@|N%F5s{({W?t{soH|hKg<#yZ4%cJwu{HUiNRlTFXmcM}3#Yi!Eq{{L%P~v+<qYpQTTL1t~O zLsE0>SsPC>m92%^s`P4}R{2#sOgFPv5LUlK+iF zc-AzjfgF4GG+G4|#)W^8*n>_b@@441db&-$J6f~j5|@NCTbEYJWXg!zZ|;KBB#F}< zut_zku}lOg55_V>D(-Px<|DE=uxK?7e&SHc0_B3}9es0bLae2kHCk0~b{BJeuO-!d z>Yr*b*pi2j3%RJf3KYR3om!dtY2F^YEpc1^5zwF*VY+rZe;&w0yk$7c68LfKd0g;K3^-IFDh7i2RUtE4={Mai4b*T6Zq+aC z4alcwrdDr+xeJUO)c+PcnQ<`?`{wjx{C&2Nem5eBL0llhj8oEwd|W);>XT`$JF0n+gAoGmJE(ay>b|T76-l{d`tP=A zxsT=%(+PZFlfGynvP?4S@13x5Lp3g+mV$*Rf7EC*u?Bm|N$8uSf)QW;&ny7>k#|`4 zUQ={kU3!am?3H*zBOBV^1dO5eHzTUn361;cmFh)YB#AnPaL!9D)e7M&(wXKIdp9HW zv-PM0PY=+Z0F~;JpR$Cj{?ls&Emm&)L_Eg-Pt@)l@4w<+o?~ zG2fC|MDIAILlBbjlVg@!Z`6$YprTooGv>pa?`nS5E0YIcW>*YRN(mHbU$LH{{EUv( zwD=-~l4xfB1z2d}Kc}V3{CQB}!ao%E{8j7ZjtHv;+gL#LcX7giYz*149TEF`_TT10 zH^FcUpn}BYY{Bv6wn#9VnNSiXbh7(Pt0JdAq(Dj+060JM;&b)DHwxK09WX<{h*89KJ-K&JIEy+;}lX*tx%=b<2&~)h)6UG z4MAytRnv}Zz9Uk1@n;!aGnlf}X}ql|+xB)_sHR@}d_<@c0VapCVF_Rq;iL3hl-%zd z8iyp^rg46Wzx5KLP8_q6)F#0l+A_47%^bRHQvip4So!AHSzCRt9DM#_O`NiuNoqMP z4*9>)&BGXCG~l%oTaS#N7SzG1q@WKx5sKTQ$d7X8w>K4W;^M$pNe*LLfTtcER^ruL z`oyH(HYbZ(n|_8EYoOVKXHY7FQXrAoeZ^z%4R>U@1I!`~XsT3Kgu=9L#FWZjupW5j zl(k3Qb3<{Z=j?fP-FvuuZnZHgEudP9Nz*&DJ=tu2*(5h%ZaK~o?u(^`AS<-t1jpP52y{!#^m zJmPcqo;$_3=!T|2HbOFHG};Zr_h*}}YR>KYIMBC{rN+-$vPb-nCl~FeE0Slu(T3D*uuR8T?PXP_|GT>vM%-}VEYS~V@ zHFy_>cNV*Pm8dZbPxC=eY(2L{G1<=ZN5^@7(d2SAf<2wBmRq<0L!V)koW2YucDnR1 ztrS_FJn@vIDR5Phw)_s_u??*}0_^>lk04D_5Y+^077&Z<5BAoaBD=cnDY%inPri22RAFf+VHuk)LcC?e;u&no;$U! zsj`T=i+m%1mn?YsLb#dsNQZD=7Hz%c@z2cl1mId$=s{#DLkY&AB`Yx zQKJpNy&P5x8hODHy|tTGF}IVOn1$&CwN;__c5ifwYRB+2{Zcm$=7&5$3E$t{S{?ut|>%H<>dX}DnF?4ANXXN>3cb3GdWyEd*6Md1FQ5~=b+STOT zmpvidR^96iIveh}?AC0JHz+OmUP`x$LsrnC4c)}sPxPo@N2U!9cB4-+<32TS@+4KD zJ}F;Vnc%huc25E|HZIL&hdNxJr!$c&k#PFDXUAVQsl@*L){6huZxs%^URCOfH0`C>9xly zz~9B&iNQY={?QFB6I=ZO=)}y?I^p;YtWaCO_QN7mu{MFku?oC=F_1c8a-dI6zn$KL z_O=w*NE%(VohaWZmG*by-CB{C8Zj)a*KrFyXB>F%LJKtKd(q)S0kP#C(q8M!=aPO# zbrtSE6J)mm7)0#9=ECTCLzAt?_2sA|P?7Af$>f=9MC9xk+1UbeSj>w0rfm}Bt%(bP zzRveasyENzI?-p$22;epX`KiU!NQNuxNeGt-%5W1aLdj=ZX# zp5S)caw2(_^&i z`5He{`FHWeq8t$kio4=3d7p<=F?eKv3bII0jZfLQE25(UG*{F7jwfgO0^}@ZrNS#9 zj!1guH-d9JQUgs&t}Ls}Q1ys#cq5}>`%ZgjI%uedfNvVMDp;P9qJ?*-+bazyZ7xz;iX<(H2*Rt1-B$nJyn>NR8W$}9&107LbT0U@Rc_ITI#qmVz+Hy*BeSSC ztd5=d{S<&KGz0r>x4VSm*TU-HYI4a4sXQVW;b&lY!5Jn>ku`hAt;x*g(NI>4z0W-H z&}IpHuRK1b0qm14I2EjlJRz}LJ0FsWGJC|_&j=5N|H28GTMmNrON-S*G zE3Kx?-+l_jCHj&Y!Ex1%zk!)d`s7>|=x%uJq{~JXo+^UOlzusE%l{gLA9wcb8|+j} zq0ae(hAE0o?fW6uCGudZ_njS{dmJJiRcpHUP-V; z$0hR1fUSY_C>H=Pr~4Eq|KL6CD2j&>stxQ&Ek0o`p=8L;6{o^g+l~(&~DO+)G7BLNTRG@k~pK!PvV$o7M-YJNu?sYcy@tXr4$6%zSo4 zrlRhvv5laK{*J6HdwD?yvF1w&(_DzXKO+sAILZ1$Cd+N!&vMZ;N|8WNDOmn2TR!VN-&|RsGd4h%?Pu?KcyhqPXGJy~ZEA z=9Jo7zi=4YH>&!mFrzri;jxOkgvS!rD*uF#166Q|kmA{6#D|!$uAe@+zbh?@uNq9R zYY@=duX{!Z(R7=qUTK_x75hcC3%0)h>SrT7(8nhpP`er|MSRV*hBi?Nf)p(H_nz!e zbnO2KuyzzPDgSKkczLAt=#q`+`?v&S?l4?|X2 z7h-{7y|>p&`h;r5vSY0NR)<;(S2Zh=OM$B$BX=qM(W4}b zQLAqsQpMP$^1 zRra>|IC|CH!ASgtgKqBdT+o2GO3G2QZ*m@e?7r7i{yJ6KTD1g+4>b$(4FKuE$8x&9 zzK{7E@6QijXE}f0zTe`+Mx52~@k$^1qgMhU_+Lm3c_+Iw8>E=_4gcB)jmHM$&DZHq z5Rd7j6(hLS)rNP-WYlr(Dft9{{D&9uiux4LRU-{Rp{m&Hj6nS`WG-nW!exE!saf!& z+@d(pzHtHL9wquv`tJyf<<)Bu?F zIeB4>Kf_u8RoY26YCaj`+^OeBeDSdj&1)VRf1mKb4zzDa9x;WE&shu{Goza5B0N*^ z%dngk+btuhSsp<&qbbB0jZB^(tlm+v`^`} z;<8rg@4BsSK-SPxL1PmXaCyL(y@fO z&Wu_85HT)i5b0NGUsERJHXm6Q6p~QqnJ8#AZ=}8FocyC^>qw8#1V%HNQr1J!>8|cZ zhT@j_mC+RALM1s0*a{u|MoVYigiisr*@er9{^Kv*1V~g-rB{Fe&ka?%VScruhs`$pvPP*1AmoJ#l|MTJ1s-1<@+0 z-W=*~@HC(Kr341V2ta-|;6`q2zXBA9bWR1QlJa%9Sm(|!m462W$EaTS^t4^-jk^vb zgJVEWS)*rv?5W|yw0o*Ab`rlL{iv?qRxL!jhjCKgG(j29S7044rhUq=P5?vi*{6<0 zmwG25vQuHd4aFs>l2~$RWwR$qvFW}es)o2nH7=crLu}pNzH`bm(af1q;n#+yBOZei z&!8HW3WxD?-$qKmo4CA?_Xi}?sqf9z*?@I%bgZ@xbo>WQLEWvxt*(!_P5_)okxaQW z#-hcI^}Dox+r~qjQN}3MKe^h=WjG74iVWlc`Wu)xOdmcM;5cN?^o&pB<3U2*(j1&L zhn6dQcE}WM^i;_R{M-mWk305HQ9F&^-}~NtIXTRoL;heW=R;F2W;{BM&+4cVJvwN* zI$6wPt-~3;!r8@v)LDC6F*F=B;9}>=W;Ukc^W@p%!6J)wP-sl4kB3p)mrQ!fG@h45 zH_E}){hysfq7wFG2$@RNl5ncGR>)@C6oQ^eLqtDx#TY(zHo;2A>to$eFUd^q5!bZ>N)cs&H1s{1pOS?7_ zAJRU-l0bxcy)qve7hAC9!(3v_q1 zOOJ(S56{)tjP0K`y}yhh5v2Zg8jAZUB?JEibFlx-VVRWj&pK7JH}G#Da_NF}Y<>XT zNM=qp8lKBylQnemIKFfo^l8ivf3M_)!%{%3L|$v2hxU|24W=VhaqR`_z}b^UiqRE^ z&xLE^ETirM(qsGFx#k5rfV1ZFV$ak6C{@hEPoYn0YFv=1a?CYJs1$=_5K}rj<9`sT25XK zY~DCLv_9-;T|>A?!O%3p{b^v}Ds+5i_s{VfNUs#j_l2~qI-nJT$eJy0WwceCl^8|c zkQJZYpt$0bkdBdF)~bh531aE&9Eg+Aj?uRu8&_Gzg_2)HI0$6>-E`8;Fp zib)b_bZZRz8v)8QGGI^1@5M{nw7?v;JVUCA{U@FyrFq4!YPIlJY)IEa&G@MGJ$ZW< z7;sR1v)V|{o^@-K%=v?!TxOS;CXj9(5Bcw@WJfm$g>jBQ)=b1h^X2F`#XG^C>AnbO zLO9W~AZHk>h5_TW{h?{66(&biV)&huu?oBI6n8wu}om+S8DD9ETZM3B9aiDMB9<@qt-_C;{z0Ihxx z>#buWjg)it=cdH;r4w4s9?R1)ZO#e@g8=EPmdXD0_>yiDhU6}b zh+8XK4~8{ntk$d5tNk^0`R;8`S}kwF;_4ci+{fuF9qPQZz3Q$W%7@tU@wt}{*b|_W z?2g9g>TZT80Gy8ymr}>h*xP(-j76WG{ZcI{*F2M#|TCFp>3oQs&D0 z%bDH!c#QD7zdWj>K7$@cJr_DsJQE3=Ew} zU0r4OdtBGA+2Ea6H&$=Te(|*QJ;`v)J&#--|EG5yK6|15z$cQ0@sgG9Jy+LQvYWw+ zW66ZRHO6}j-;H8b)rW~4?)-J9VTB}qpzL6G$hwUcocYuFi4#8!dTjjN(8%aJXRfIJ z%td8Y72v+uX!_n_{odTX$Js@?zwqm&H7XJS$^|UQUKxO_Qo=!RO3uAI07ZknitII} z^IT^QUda3jlIo}sV zdpLB9M^3c>$a@^!r@FGsL!Qh@=_K14V{QnBq`U|vmE~($i^tGSd3#R?!@4MMs?&CU z7FZ4{3Ge3xWm~fjBk3O-$6GG29PBi?Jf+=3#Qf`*ez>h-LTUlm)D+cpE#+&LE$}jR zzM-YSaf%X94)k&3^m*G~dUw;zUc(%xHu_6b66z2he%&vcyf?8Y7q%J$F&GhFxwDD1 zccd{X*j7o7kykcH+{h>(XWTo~oKsZGU*9)H$KMzgkhlMq6DvF%?ibz&IdE*G7QtV3C&{Tp z`j~E=9!;jkYE?Zbk<|s|tH<2IFIy3OoH@~HN#CoMkfi0AarvK2huVk8?E5q@WOU`h zRrwJksio@{!1O$~El zGn!_!NKewsb+visK`f$9~e|DbmA1cb>XDNy* zvZzJEk{+9``sB)Uyy+uXw?OGohe~&-KKLB+*%JREhM$M-Jts`Cr616)6@sO`!tHmq z+W<=o$ga!)HISQPN@0m=fEilVXv(TQ8Q=u;-0>_1Q`k{Pt_qZeGkfW92cl5&0l;mQ z7PTz*>4o5V_MuN@$$zVSdvKP^iG_VBL(dTOy0B@I-Yj2{TroW%YgPg>q?+==pI|tv>=}MyMc-pQD4Ek=S2TmX7xonP`a>mX-Mfx%mKczlxsl zd9qgs6gY70S^PI6bc@3{;0Q$ppJYF<_}0qjsHwFzUZs$9Ad$CaYJnmMU%p|8mCD1C zFa0%ZzaF11?B2a)_6omoe;cHEDS_Ye%!p#ku29;WVHpDNsL&G6Zq zog4Yfccw0Pp8QX{DQ8DvMPnLSf}shB$g;XqNpQp%O|ind%uBO4JCJ4-`%E}qaDq)S z$!?wgW@|o#-OvV-C*sR&H21pDpe$?dnLgs|^nEuZM^V>G2b+b5 z@bApHPWpT%Nw^is>Eu5->j#BW+mp~3r2Q3S{o?@e_o<7phgRw z9xbP9-xz{nrv)h?Dmf)I3^gvk^Qxrp7dLyYDcUSiLF9Bwf!pGomVF^|K-@!MmrQLZ z1SA&iuEofn=m!`wOA^qJ@C4p_l&D0x%IbJGmJT(A9RPcwy)vryUs%!twt5+lV$1P& zznxRJAWP>~d5-n31L=q=!q2ZeByeLq-@xzxB3#ROt{ml;GklC6ssf}DuzrAY0}sw0 z9VoAd_7~wsP!d-XaneR91a*FqB!*(GJ;_MDr+zY$FSYT-2d4xB3%BXda^%Ba=~DoD z{<_IVe1F{P_E&qw&3VrA#>joWj55SAekzPmiwTq3^eO$lKj)Q$xTA9RYVY})>k~!Y zMQ=9yz&Oz?>Y`?tuW+(J=?2gTWw30?6F0A9=!JAsBZUH-VfrD#JNW0H0AP?svZVZt zDNms%7&{QG&VdMsOrx>SsFK>~kdn+7gMCs~HIUhu&jg-qf7aa12Mx{rPr`@r+k2 zrc4fm?rkEAX6cr{2fZ{cX+i~*gEJw9(!hi1B)QG$7=R_)N1u(b?V zMUyfl;W7Lv*&kjbEnodEzP=?_qwbjn{@z=dn=5+q$DZ5EgqDR?5%b|Gt67B` zChGJ?Na&BfaXJe>AK=>oIHwqBx50=bxOQPg7~f+lv`_8t=$T4uXkb|A^o&Offb5(U z!X5i+y3JQxexJSj6;(qSBigeRz)3YFH1de;uR6AU1IP{sx2kV=qDlJzAO*@6GUQ*E zb{^(57d&l3%{ItQHKb1;c8tE8Y3S8=_HxCJ1`Jdw~Y zFa)A+fGQm64g)m?cHV>71j_AbnC$uV{5G*1x5vbbNhD|wVOX3TP|6rPmVV*yJPzK? znKELbn(|`7N;(ud)M6+gN-RD`-PmR@FRHbamfB;d-HzJ5R>SD?e^RiElJKZ^_=i=& zt$z-)d~~sQF)TMNtcYBh73**+Ye2mlq@cHyEv+tdC}C%=rR8)7tnxGn8o@5BIAQ`I|ho;FLivjP*`&EIW3oSnXc1jBa&<@}z z5P1kCJ=gFJ1Cr~4frw~RjQDX~O-zl*#uCYn`Lp;f&Lh^( zj({=FCr@N=VnD#fNOe^^*B;LSec2s0os@IvaHGm7|5o57f4JTj)cK-Z7zm)b8Q%1d zN{gs{W9w8m<98`yW>%v9J$o2IC7so}0jK!9a^eG#Oo7|8pJtm}LKZ*ds_gn-4)oU~ z{PqzXIOaYGMRZ#`sbH$AvmN#U=y@xM zlXAJAzhw$yqf7ewBUbGW?>&rb8Nk5bLZt7Cz6{@6XFp}&R>y9exM>@WJOE29SWt5x zFK=K694h2SPPJ%V!E7*eiW4m=(vp#CZY3Kt-pY_Nv{7C#{# zo5G>HIlZiZ{ocKx8N5)Qrz6@Geu@vgSJcDPPc}Ejo4lh)U_uY=4jq4(n3@_7+Q6~k zm+s1L?0HosRvW-!$Q4100{zGHQwhk#+z2Ud<+v3O75&7#@?3i`{36=0j+KsOPX`L5^h_9_q}>~mv4 z$OXU!Oq?4#yx&MF!$~1+6|OuRV_6LMX=!yLu{b7oT>&{aL689TY5n1O)SSO&Zty-b zQ&FxKtM<*0n(`$3HVGOQq$=^)Q0j`Jeh0{gW4{_-W7W=YEVF^y;1Y11fSe=UMA?Hm ztkVdgfZ|Zcv5H5W?|_Cl(3E)VPrJ+;_Ky_X$gIc}L2;m=mRRj~M+d_>z+@_*gGD__ry{fSg5%2r9N5`>UUc_YRl?<&nBIIY&IPc*ZxrQX!^C-Sk+hyXw#zWMc)8)^jnsAoxtGzEA%br$M z=aTfj?X}VhNIJY<*|cC=S;ud?!@c|tcxvB%hxm@zW6XA)U`U=VznbM;wtXxFgz2#; zHe5deDz25ZwXsbbr^;hP{L2Aj9RnaASy^Xjk=lk_6BVo@%vlb(?_?7 zWFO9WEnMcATmh!LK49JlSX}B^;QB_Tk$r{lQTnB^{8V6k`xH2hO2*X0+isqgq5F7* z7&K(_td5$*ng3#7R!`g54b~pFPwi;3_7-xytI!3G-&0s)`sJ;?mi|(oyL4>ZW*YNq zdmCIWboI8w(5oKB22X)|Z9D3FLaUJ*WD`xf<@<7`RKam2PtK>~>3(rOh!Yf`OX>u) zaB=HEM-8eNeZp+~V;rMc!3VOZ11iH@v{YhAvwdW>qz`cySVG3$B_Z7m)N;O|h*RgDf%7ErynEF?kHKs8j^}uWeJi5p1ff$Lpbn?Fg zm|W;2ZI1Gc>`Qv$5A>0jdI!;adq)DK4_SczH|OE>SQ`w4>4G3*z;K6L&){A(fJJ|? zk25W#;eXDsLf_=+ev1hZvQs|1f2NoEc!V_VV$H53*!;UFNzH`x49fFq5@$1h@8-|m zVR!X$a#W!URUkmMvV>)$i<=4T^#K^`{rocW55%Ja;}tmz*#otu%r+o_(B%bI!7Pj6 zC*J4cCb4gEGp76La(u?}n`s2_3 zo!ji#$c|oXe?3cHorrZ`s|}~P=gK;I_HPk*AW}zMbi4d0x!R6qB#ikD3HLP3OY$nn z-|Z8rgt{Wwhdv;RUS=sCie_Bo%0e@TuaPI zU2%syimE?+Bz%uR#bRVXSl@VRJI?{3f*4L&?YGa2R5mJZLw-{Cf(%wZ`RQIyPt=P# z0!BQK*I6xAnUhy<mdVV&*&p6L?be>;VG+{(eZr|a0nUyUNNv^#`%((C%h*3uS z=VqmjfmC(=w2-NR>rEx6fE?JjX`z1gShi2@fX#*Kl`m2WjH?78Dcj0X)*}R;L+?uM z&JpKw?9;q#=m^&!dK>NOXH1@qi1W!87N9GU%0jEI7*M_l$3KyJ?+jYxxXJ(AvrA$( zF8^{D-P&zg+v`+4?R!ln_nS!@>(%K+o5$U>8kNnN4F4P2J>~3uTqg4aKpUA8Y6oEp za~T5W9nRI$7>(h;ozWJgO88hQz(fioa)C8ngp1kD$00YhZ0Mg1C$1mC)O@bkZea11 zHwm>|e8K_AHH<1@kvz(#^>x(@VF7~VP0A0vXs=aM%Yf+F#gIV5mm4(0*Fb&~b7|oK zaFqdCnfPr#mj1M3n~Jk{y2OayCYQW0@%wX20XOCv`T`3m{!opj!150u86^Mo1E(Xi zLK6GB1yH3-Qas67@8I2`$K;6c_i-LtZyYpgQjV%f+|hkonZ)hWw)s0O=soPfE4al9 zGgl4U9_irq?AX#6xOWG-BPnTrlLOuv9t9Zy!D1k8mqY92Tu4Q`ig>0Mg8wuAun9cE z%Y*(4nz*RCl|}hKktcZ5BzUHvFs*TAaIWuNsztDrlt@`}cMryI?cD?_LZv;(Ss667 zu-6G;LKzA5ILjmkX(Z&NdlUN@s!zS5MH?ga>2SBE9)!` zpJ@%lznbfZ%V-AGm1oi6Yk1!3lk%Zqb`4dYaZWv7UG*m;=r>zny1MM$G_sD`X%18CdgCqBJ_kQnJiaCAgK)8 zCl`KQFPgdx%I^&v`&E)?9Z{3>QlOLkRBf$P1a}>AN^*xafjPMdW{P2lGQDg%ju-bb3BjY{Fhe}5kp7R*LxTKis6jMreW)ITjuRHlm%c7qh zcVhnCK#x;Q3AD&pI5ylQRnqBT0Nb22M1Y=J39`%n28IZ3$8#PN(!da-JF}j(#%{b! zPFGk+ftdF++Y^^j7#c)l8rbU{3Gp8;F6iz8*=mfSn{0JOUzf!Z`ZW-w0z+zXa4Q6- zmOsI&fZ3tQT%fDsg)IUio@dpZgLf^vSu{`No!glTZaKfjIrv$v-*rt)|Fr*xdjhsL zDJn|NE!>RqM|G8*m2uDGcQ*+`Tta;`djyJ|Dars}{zI*t8Ho}cbFb0|(BMp_*@y;ShaT1KdMiI)!{?o)i92=#+K-|E$ zQ(Ve>;!c&$65Ggu$YC6)=fO5yBS2XkT(!&!zJnNh=Ua$196vRKX8~1q_Wx zA6&`?p3*Hp3%(A$^jTChm*en*3&rlOduJJVm#<)mGvjQxZ@%SMRkzU=JLw#yU6_5j zC%NcmAeJ*VNfv>!s5-jSL}0j6;P(|?kyW-US+;_)K@f{sG8%k!t?J&qlfmqpWHmlm z^q{2OD|E>zNwod&+=4y`xSF6@0n}cWXzWi3mU;J~JeP4i%4kPzRsR=zVw%`#pnzy4hdOW?Y{+Pm>q+z1YU)N26vnHx zeIm|wf726DXB6R}H|tQT>!c}K3H)he#gk9qYD_wUxt*rZ!sl^-7DDCX^7iIbbcs}1 z#YKUoxc23IbbEk!j^&Tq$?-o|+{S2K@*XqN_h=yc&q6apu@bAQTPY;&>TlRvx$jI| z>fPFDVP7Hv%l%Z}2CZ~|yw9=1!w{=G*AQt^ng(J`0AmK}~gY4Jp zaCGK^Vamo~qrdl9u+hx8VccbUBF@;oC6gWeihiFeys@Ds(X;_9PMv-?Ufy4mCe=03 zYw*x%a@D@&OSeQe=ax%YeeW81p;-#4o*+H|`(h1> zBbt;j{HJ#`OPxg(IAm`#cbZEem1Yol&_|q;D>bfM9Xv1>mRB|Tlij*DmlYO3>zo!T zun5!gH$cT_<_p`uSa8>rW!h(>tgRvVoG4*sWK`9I>Jul364V>RBgDKeL4Yi_34>p& zaB=mI8qOxj>*a8}OYf_ZyBvSR;zohAM&rpbr~+@msRcGLE?NMsQ^Zq z`yWXQ(`|@8?PC8M_?h(bYn8mJZ_+z$dZw}T&))tlq;_KoTXd1gyzo{tGjNe>>8Ifr zKF<&ES&N_;C2-XhalLJK6Fu7ZCmEk-b9CQ?fKZe}AzEAqM;qox59Xks zU-ww?kj)%nZ!1&krB}$Snb!PKCi6;01Vw7RckOXWO{Q~Wj zc?vwV8tll2?8P)wHaHoQaVHxyzQBOKv;~uH)46^k-NK+=`|hfn7aozKxR5^MX<*J! z5R@Ex_>VTM=fsjra9hErKz!5KB|zjJh0CMRhVwOISn1pMjmI=Id>9&LW)CwfSj7$(Tft1g`%hGVZRlCS6z;k*Kl|4IJU?zCdZ8JcGE?dH$=%feMMFGROZfQ_ zQ11Tzzx5+c*yam&H>XzN<4KtVrrLj^yh+_ZaK>HkT3A6i=ev+oS?+JFBKg@!pgIn= zUF%6z=E=cN6M)8)$TWSP-@?i6_KZ=*jdRv1{DSbv@SLO0AcFqoH+kl%;G_=H*cXOy zdIIG7wFRuuN|wU+OqMv|)OOam{K-aaovO{Z0wu#|eVz?H?1@_@ls}>c?>^-CvW{pF zMb+A4oWpm5EGtY3E;?}HeNkj;+{x5;$?i}S(HWs_diPZ!a#s5iRRWzw)keYn{oJ?? zj8G-a)ge~WAHAke{`U}C5vZKpg%{zIe+ZlQOJSPMXCt^Iw0XclLxALjH5^0yHLD=v z!X(fNCz>^P$Qbj)9e?gGwM01Emoj@Nm3Vr-Nx?}WEC@jS42T;38?ad1UesQ7LMoF+ zX((P+s<^i^?vos>(!!KYO`vM+`&Oeu_f75=c%cBfol4P@t|1+oBwbL7*{C;$+k$b* z!Cgb(9%}uH^H{wfL_2E*2ZtMAYwLjtzGC^2qHH2nXwsqx{a^Rm&re#|1sDJoU=^iE z)Kji*8X78=dHnwtP0y$*vcJEY@~a{3(@ILWP0p<8zuSbh`Y2A~J+D{#dJs-GM~Oi> zX2*^$3IcU-%0>?TOc8{`zy>#lakBGHVOJ~97(wg!`%`^!D^4hELdQAV8uLknBu;HL z;pbi;j$;Zg?R}ClJBb*?6SU(bn-QZ$m(8#o?s%{7#Q6)*Zm@F^UyrvYPg?l*c#|b; zFEM7rc)f@Qu&Bf5*9bqb7@z@%aYyUsRK~9ySqlGI;@pprFXD7=bw%rBEU8VThnH6y zI`+jF-W`!|gI5){pFiMYN3-1utV7fVrJ2Hk0T)U^M4}zp}b!T-P=UR@I1xW zo-a!WA1L`Gz(?VY9#L_gHb(M}sPdku!(G*wh40HdMxqs=eT3Sd3N%SN8)>5tlO(D? zmDI9+Hd7R)nc0Ga$Q|aepZRaQ^~0GRTZ3`VKH&etl9gE(sBH9a*YP*}t5PtzvGzWk zmz+CsiyrcgiU1i2yr%U{$!MF#DpKUw(s^^>(o|Ik8lgaG$b};w>81Wr_RyI*nEc^0 zaE&jrP241eVc&&suvM2#^Ch}&c4ObYg~wdvO?D-8u+8-Gz3k+>!{bLO|E-mgx`xL1 zG<)-Dc0%XMFKskWoxLiQ*)c-4=F@&{e5Y1Ab9d}|KvUqYCuj8gTq07FQBO{S^dW{6 zn>sBamxNdVFKkX>8pW}a_#xl0_}b{6Cb+buZ6VD4j=P;6vGKB$-qNXraiSp$&Dt+e zeP+Ie;FqZg+do{;HRsoYGAReRoZ>s%GAlxuju1RFF-)igQ60d;>j|C@{{~798?Bti z7;f;vwQ!SJP$OiGWnNhiT4t*(UyrtnICx%E*c)S5k*yesA!noQGEkk zKXI76d~3On?17X{q{6pA$%3XM8O!{-}U#<{%5Sp`{+wsqA{hq4Evgz@WnNzZrC9S!i+d`9=LK< zpLle=WqtBT3TUv6kkr$|DS)?;>VMCwr&-$*n8I1Zj^{I0nRCLL*|mPOFZ{aD!orfV zSLZZ6Lw6~kvVtfE`{C>8w~tQnoyy2c?xCJN?L=V7Syl~84^dGD3&N~)ylD1}&(yVa zDN24B9amQyMNv>5iL3;|9U`k7l|edW>0cU9epvt;6e{4Ok4~TdZ)?dG@l6St z-LR8(_h4q9*`lce>gzi;PmX=Bl@BeVJzY(P0Ty(r8VJ2^{Rj<@3ZsH}MOmnCSU^OF zjfc@PSj+4paLNBf0_owWo}%KcUd)aDcp(o#=#8nIiO0Mh?|n{>5NYp_gn&!aiY`se z#h?2+4y1@}Uw!iSh&L8(D5@_yJ_Bes>f$mDjTW07w> z=e}FS#IGotJifa*eh##9d~~lmADVaTys@&e+?5&)b30zkhK?<^B}snf!RfhUm=Kcv zH*K^t^aKKQvbPU5n1OuVT{YpErF?Zm8l%16Blr-4{x+QzugKk?r8vsnBkE&p%32jL zfeBsWQH{l4MG2aj-in5nQbmg5&7fbg``z1Nm!jkw8d3irCYXpBv;^jGkaF4v6z_Nz zfV{%`!Z*T7a1g6w8U|jL_Q`*&7l#BYHI334_%R+5bd~H!$Tf00UlsW=Qi{p&f3vsJ zRFRA+L~HCuVtbuny|u8#DY^Wo2#a$powuJ5(mJ$phSgTCTIsYFTRO>7+Lhoj!{diBaGZM&Dsk$e>mpO?qb?SD#ZY$FNd zC_DK#$Ir zXscS(*(=>j1Wh=@zD%9GjgwZ`#gV_iNx5F4`>LjqJ*K+^|D&&O4=E!YA_r=Cs%g1} zzK-l^P;42;?O$w%L2qKi|HZAd9Zgno9e>u_r7BxFG`Trf%e{X_7}8A%8MfbNCt@+Q zWIU;$V_N(nye)J6suar})8LLQat+^S)zkPy*uQ!009Ecv*7lgZKd)U&VsZ|d43GP8 zXG-u8_f!@Dv`-43z8d9Eqds){A>aRqmN@a~5wew$#nY>D%$#n@t*U{a1S(J=;V2Pl zwDV+DU#F1X=tdt{^I?TChf>(X)57h-jl(2^c;hNdhh)38(n1Q9rC+~d&5x(F0mayd z@4~0#m=NFn9w%~VuxE8^y=eG$nLg&85~$c#DZwxYOhQ`!zgOi3?>Z>oVEWr{eox{VgK$^GI$|Wp; z00k|WOPelX<13x8s{O1z=H2H-I*^AjA;xJ?yu?c<7yhlSwwB;hYdVUJgfXQoT|+lY zFcaOzQO2e*)B@xq%};1z#Sp}_{Ac(Mbnuu9&Ug1a7@Trdj?l{?tY&v{%(HOP&f+#( z!V6Mfsou_)S_QtuXyWz+?+ES>%nPg?rSk7|8wuAxk?F%ge`-Tiu$N($VbZhdJvDnE zRg8G^GvD7g>s!_(K(^+>cl3J5I6g=MVV1=I79cJN0P^g(=)Er^EG*7Ym$@6Jaau6f zk;;+ffv(2}IhxLbY0N~FTD*H)Zc6^afhaOgJNt-2E3FqRqOe1EMU35miN!PYk?Ubp zk`^RXy-;TotI*=Zcq0T^)M1s=I2?7_Uw+a z?s`6Qdq20^Oi#?Zx*}@MyU41G8q7}a^Enj4X;!4*PfRel=XaGa#95on9wdRwV%;+l zPVllV-KQkz$G&WdCgDSJt9=wI`29Akt6@^W^=(0R|5vz)489Ql(126roAt_I?TX z5z)3;3sF@Thh$(!2zzNGjeW)Isof_rdFQK{t^w+RNJ84Cz)-86g@2dEPd`$&>hLcB z(NL}npXf#bp+bpw*$}1v6blJCpJuDzDk!I8+9x90GPt;2%;K2s(_F>hmcq$9brw_;#+BTae@Kf%{x`5ewx9ztZY z)y8nsjS6&spdcQP6>AWKcOMFJ?k{QQ*S4!2nHH*m+yF&MlgNEjk8}Br5|qQK$^TJX zBaq0ZML7Q9he8!8Q|yZ0tp|%sul#T7h73`zJ57%%?R$|NK0deUtL7YhqC2>zuF0m0BS zBgd z4JF3tUwpZsjS5A-F!&BYJ?vVH+IQIK`F)gTP9V0!9oX4#H0igq%Q0xINWgQcF+kZM z(fF8)l{&DtkQ!4`@$EB6v$XLUtV2bwr9a9YnH1B|x1)KE_`f#LpwC{~OJe^xhQ%$X z8TcJ+`Wx}jw?9s|+lr4cEoT2$j!eS#*9RQa`5V!?I4=D*uOu9Teob;l``GkL@I?2HO2YROmeW2_*Bkev zs+A1T6+I3diCe&6^WpiK<_y`lFEauK<=SLzgkZCj{z{8xzs#z86+{5M^J#9!-Zgsw2z|Dt1n2Q#-_lOVW>r*+eNXsERl8+ zvytM3BbdKQ{NR!HFA-~oB$P>1k;r8Bobp}s7#9@Hiv3J;UUxJ{ZzG@izJ46@iri^*n(OPKi>9l4C z=Z}z8#H8=$+o+w@IfLdELJ5RH7A@@T{US6f;YEqstpue6_;KxTk{JCBl3nEI`wuDEk>avzO$3OEr z4K1xwF<@nhD_P#Y3|14iyY>gv@w9WpZ+tW}-AZ6<0Pn`*iDI@6(lTn4B4qQquMUuyyjh;TTkk`Aag(s4g&SIAg?MStc{r8M$dk!{lbV$p2;Ox23Bhosz-GKkC z9#O%L^VdfU^}$b)vbfSwwfxDrM?^{OmmZ(H7r#qW(l-1p! z@UZs9NjFsIE&6`%-j=tXB*Hf!K;dD+wln;RbhZpHL#2h7X8ZPl)8zN_FhD-H0Qqx^ z$32_7noc-04qB+>l}-JmUy>KkyDIj^$+0rQVaEADmp)6k$BY)*zeU4EGow{`*;T4o ztFZyzB1>@M;63%;?w*~{Ha)9oVeLG>e&!$&!VD@k}c*Ap|WUiq#G zJKa|~AtsTO4K6+qSJ(2LyQ_5aFo2h}Id0!UYOK0{YQ3PAu-v2!XV=ZE6+dq}k>ctS zf3R?26JHEWC`&7HZ*KljY@42R`BM6@>*j13OBM-Zx_#6BK7N8@`$^w;z1pZl_iiT{(VJR zA6^Z~xcaj8rW?bGKA{Z5r-)y}|Edxn0J2!sWJDrsDAy>Yq+xVwrPNKasa$Pi?>TyW zd;bFYKQvu+TvX57C6$np5-I7WQ#z!(Swgx+y1SGRDJ7)4q`Mmg1f)wE1Y8;f>3V1V z{@%a!v)ns(=81F8bA~>HUsr62qfqFdS~uQ5!5nHMD_WD!6!SiktFcAO;b`~mV2bjb zyQUJ-ah@OVJ?|=Ffbh5%q3vHazR?V{fwyKX;%{6-UFC=pn3!k0&uC-%3baBo4KE3f zi6jWt7rwB56JE_wdh;qpt|mKwoPH=yE~0Jm4$2=XrCJg@daq%CqONP8^_@_J@cY8* z?>VHR(qDVO%urvyUY8v%e6sSpi~NU%r6s*pdGRrS1pTalb%0i^N22bDr;IB1F{YZ; zm|;Pu0hi%@YO!B)NsWdDfr3&pP)!E9nE~ z0@$!s#~jCZA{92rGFLu5kta$%R0#05h)74%bZX`@dL>LYQxq%{D%1GEYEhoWcNxG{ zI0JQ0wju!NLjWdNl=?03_2Cj&`n?3%Gt&zmdIuwsPox5CL!bXu!ux{$WNLH+&9Og`OP1d_;Z**|=2a2~vs1CqUvvuP4)I}( zK|RgDy~}p5^s%$QGD24}+pgrD3=(NftT7y(aI}rb3h-%_$22|xSd-Ydv`-TdiSJIj z|7-I|wFEj_AMF$q#OxG9aEh~HXOzAqO^O&X!TW$F7J{Z{KO?0~Yf9hI(NY*If6i7K z(d`n(H!28U=O8uZJ(dp*6so!iyi-xSEh9veeOJSBDqpMUop)GipI*YD7lKav<$FCc zB~kLZledK@pzM54{X6I(h7Oq~*OlN16HueU3QHb-nV2iC{Eu|8NRk?RM`WVnGrw-=K-dRj9onc$fPFcn`&Ok?-^;-W7I<0@Ont^ieykqW`8y`xh)|La= zVFb#i<1%>?R*(8J%6{xq;`PtF*-HC|KP`gIX&$`q)^hpzmu7yOi^G0zKfKg_Z}h=Q z$lv#_dJ49I57o4g%yLx91SG=KHS0grGL~kKBwa{gtzDJ?mn`yabA!M!nDunJo<58s zsyfdJMJ$9+#`7@Wi^RFThzd!i?51JlIK{-^tk{6`BP&hyW!wMQQ#qpKLL~Dbd!*Rh zGWXEm<*dR>tMg?!Uq=a=Btxb5*GOl38DGL1&vg0p4eF^aLXgy+gQQmEVElv>;BZE0 z%VX>NO!RcuSHexbTbLq*@t|IiChJ&{fNqh} zexzEyyR*Z;RCZVEmr>ZaFnEg6PhKOG5m)mT=VCt>{D0v7f!x@_?< zYZrF5A$~!$;ji3VaHtOIj~!f4cN&sWS~LG3`I+}dOple!9mbMdfUz){e5u{H3KrtD zknqy1SVq4-sF4O0ZB=1YvgdGK3q9Ek^RT&K1AD9<-l&?BG`fJKSBG$+wZ*UVO(A1a zV^pI7Q*XU;4?g6{WbwZH56{h`2H6hCI`;wz-^vhk+F$Y5>>M70OkT+}yxuGEn7R(V zDfLq8mIRpRG3H^;^F2*CEd}1Mb28QI$zKGAR>{_NKRYCi?`y2}{Ow5R)90^xek^c& z{e{TKpdzeyp88TtEj0P^N=o_FmkZv0c)0KK-}U&@B8k7)?CDk8iNB?n{d#@u{TWsu zC^3kWU#R2~D;9o`#OFYtNzdvtBK$=BR$h*dWg!|n1N&QKKQ!5P!5DV$XPoSE zX7l>SA5TSP`OUw^GJsantHpIIH+AqtLs{($J*HB4NmguxQz*s};;NeEazFn3Qgzq# zmg@{%@)F%tCPgw42cjx%SE8~Gw(Nd;Fdu#&;_5dOAsR$6C$78wN_q_uY{O!}2 zorhe5;vUPFh|Sdl@1X^LFE5I@Bnfm-Wld}I%8;}VSWMg*~?Fymgw1Sp*$xM z?Gu7;UDIQcAm6n@%j@ffYgvvqB1FEz^kHhorOX4|ko8*&;EO-#$Jp1u29RHdG8N4x zd^b0O4H7nNvWm^KIRcSgP2>qU#)uuiR7;?ofKlBH7Y2}#PW!R3PqJP_>c z?Y3~xHslE67hYU3M)@_-q-HsI#7DNKBj4J2a#<)qi`&R!c3+3~iI6jdq6EwOiAwk% z*t&tQ(p;OEn7h9Lbnok97-JA&&FN9i&J3!ff=!uCs$kdPH}sLBg4>Q)D}lI z`ha3#WgOPJ^+mtJiELo%=J0*)UD(mY^$|r{Lx5V{>amDNM?K+8Cicy?`>pT6x?sR+ zrqJpxHpjo>=UG9}RWVSeDqs%)Jr3qMjN1ZuoFs|4T=#SBT=Yy790R z`%2Zmw-4q@{t!MKez9_2$%nbnSdYbVoxRy|XpTwD)>g4`0Vi4)R65p}I@PyoMOY_P z*tl2nIg02Z%B>xpZzggjwa%{Htj0V_UblkvYgvh52L1Q4M<(9aSQJYm`kF1lw48*j ze?pi|#5s4>1>d9gF|pfYKO047HOknl>fSR0Or4OQN!Rz^NMbS3O5x6M3Hkb*Y& z83+jpGsIjrzpvn^l-}Jq{Rlu7zWD0EKHuRlq~BmivgUmn@Az08#fEZHQMJ@fT^n*6 zpptjUJx-U`&cEQC?kXGoJdyCO8vB>XGv4t54+mRY+l>s*6~wP7*M@2z0qwQ6oEg)6 zHmk2n&S{1s8IFB$9c0?Op7#2au3y{m#zKnhj*sL!22~ z_q5pIB-Bl0D0xl^?5K83lz_mkS-{N5cdxv0$xHa2W!zT0*r%pVk75QR)K@~?&_PHh zwR;FIB8z9h7Q1yKV$of5k7}!NSQZ4YT~HUx?XoEsBk()9E;c?I+@$nvN>%K@J*teF zLo&yEP-=d^?@}n?CoYxIxC%m(2)Q`{5m5uV>km%p9sb6h){E7^ta{tILjQD5^M0o; z#K-ym>D_BPMOnW`_*VB%YOYHE#yhMsKZqhYCmUxgrBF`kwbi`A?D{NAF_`I#-EqH+ z1D{j$P_s89IU67*0BcF`E zXYBtC&~nl%MnQgCm{4Zz8HzLRP=t^WGP@-Y2t;xE)Ao?W?SC#E@>qk0G6X}}SR|Vf zw}hB}Xqu)9rmtayH`H;kJWasMn*Ten>g$W?q6$@8K?s02ZMFG`41q~0i&R!`ZukQa zKE>b;3SNfYh81rphZY-dnOtALZYuWTC%z&J zKve?vshlYm-2cXS%xeaotQl2GvSiXbB1WS%p!6q`se_zQQZ!hqtu$2DlJZoi$-vZw zzpx0nXeKND(+PnwWg?*QSnpD&E;|v#4C*-wUQ3r*9@t|68(`$ELOzKX?$%=?Yfk$3 z|3;xevNBKz{=%yN=3Eft6(G^5zug_A@3|9!ckn3jqfEA_P55DA2G_llczB{C1%`nLB*1NpR(Um=Db-B zih*b6H)X9^%Ep0KJD2m=zi&!w4-Y$o?=w!Wt@SmjN2rBqBYNUE-@k(o4_M*uRs7`o zWENKvaG6*_tpYnuT{(lHo(;2irk}W`1_MqmC&sCyW!g8RfF@W!*!eWqCw)#&gE5KX zX8seEzT3Ut-?IRom1o=Ld;>>wl*~%lpbxBk|12K;Ukg>M??LDo+nA~l0iKe1s zi6*KIek*VHsW-0IEFM$aXiaN>6iNJ^qn5JR&pZ1zHS$l735;-)VPI*vy5R?k`-405 za;M}~-QLZep3m$R*|K5aT&Ixn?4KL*hs7&DL&MobHjoh0e(136!X}}7$eIH-mDBVcw zAMH!KC-BfXyFBpAyicFY3@o0Sx)T}Cf;z@#9a4lB|M-NdadrX0A1EB2)bPgArD@n7 zd4d#Bi3~rLSXUgi490Hvn=eU?UZn+}ibwQ3?oF_&taU35vbAC0G2`bBUiHPJ(zkN4 zP{fWGywg*#6dk&!a92*)Vv=HWm=tl$gd72n_++>Lrg%hmj#wxwt%R_MkPWrXYhvlI z8AQAQ2yrH;==qj@STX18ER`SWj1cbNc6@7TfrU{u?DhT5uz#v@Y`2|xVC;R`s;PUL z#`waJO&3$;sRc4&7~1}^V7NT%zrOW%ucf0uD}sA^`E*wQ$_~dfYn6G@lw0-r`~Z_U zE1QS>7_zPBYqh63+{?pc8I%vLR&s6^^t>64PMTK+bujn0`-gYSbN2=rXXpGsbk3U& z7FZFl_>P}&^zE_CON8c>*j>Q?*1tleP$wf&CL>b1)%WUfbI0$nn}fTgk?s-s>U4ey zr_F#Xc0Zr;PEB>Ra~GNc{HX8&ostryq|{)GNlVAl<%;%n=v_1&1Z-g}Oby=U_h2|3gNAmW1` z&SdeD(p=TR`{l)}Yaegb4Y!L2WD#Rym){@ndD0Jtt21JE_ALFc8h3(+X-&+PBigpz z6GU4uytv4=ZqcSKUDkp{>3w}w_D9`sQga&j&S8S@*RS|KWjPPzN(YWMw{D#EA6DK| zF3x4SHaytP3_N$f>WBB`HR=~@^iQC30MP6I0v{C^6nO8Pk~XN1kDA(sJ)!eb-21t1 zjMD)?nm64kz(2oU^nRk&nN@8hJBTr)7GiHSz)}34)1`p*99N^E@fFwJ_a|(ikV13H zEp66RLwaMoA=GtG$?pf&zu)3LNSYQ8C(QBAFRcf)P4YIJ66W-3-f!UTZZxTqkaF<7+DbYQWRv`ICFc|IbYeP<2Nzv|6dEBp7nekytk5Avyzlo*WNQ^bwGK2IB`$-==5IY z1Z1v$3mUvkP5!4d;>)+yHS%{|5IoRIlP+$Jz-M9Gl4Cp!RJ2UfyPBfQ$-;X%g3I?$ ztBKc@D`}paUw?(u$e0WWe7+f$*?=OIpT1 z3Fwj^-;`%3IR49*6wE*c^W7{as#iCpIycJEe(RL_GKi00R%pn6x2mHm`uFPSrwhR> z^ZVN?;j7Jf7Tv0BSa%pD!hw*<&F|@D1m`XtgoE;8A#3ZhvtjSUUYri+~dx#+vR^GvfrnY z`EP$&=t^thL}3m@4(sYXW9C>1ZATI9+G2FqjXbfXEHfrZu)c9o8E~#}HEgUX9bU@0 z!QSGw&iWQ0n>qUFm+GJ2r-4qXl@I1j4v~T}+xewL8chQMqa}`a5JK4gk7d`+9Hr~- zv$nGy1=vKIcAtgHKcqsKwE7V*GT2NsYovHRxn)k0;+lOhyF-u71&ULcG`{TozTU#{NFbGddN$t)j$amX%tWd~^Ix2~6yBBMBLx_9=e(HSIl#xl#+9 zdPHR#@X&4HC5l@dU}C2NUKOP^0ejl_2}5FaTb$&3Em|Lr>9P^lMNQ_nC7v@eDEKn< zqw#G&NM5!;taXy){Fz4Q6Hgx9rDE`98$4zF9CeYN0>E9eb+-@=lSfs=Ly8#DNYT=g zZ<@Sw+p=~H==uIrvma&qacWR|t1GoN$zLor$IBWPbp3JlIkTuPbN~^s@}JnYjyWCZ zCR^J^HxiwcY}GNS#RWhmM_>PMD>B0M)o-kkdUTyh6mxeRsH)^mGxExG!p|VKG~(WT zGaFzypo{+p0ae+Mwfqkx-CbK64Io%8aw${O>SR8~PtXJE44OpPp-bDNc8L(<4^>ry zFQ7XVl|pdplJnizhDJ%xlQn)kkL)t&8v@D;sOo1}`;c{wF%SttE{M<`FFpMf2=o-t zxXwTdq}PT?+(ba#);0>dTB8yGvHxkDFCJ=sN$1iy=iT=7DzLuI&i98vu1e{mi$ zwN(M<_(~wBcd|Y{xILJ6jf8MEx9n(avOX9B&e^dU{YSN67wqE>rh2BO7Ji6oq4^J| z_iV44P@6y*Zd_m<#WoPVqpH?{`6C8p>s%>%F&@yojzv!iOdkyqm~4jECXs3PW9rp{ zVT)tIqCtxFNA1|A8nloBaE;c?(B2uYyBF?<8-qgl(1lM1@E>X85-Rj1U^OJjWM2d1X+`JBpz!$8>s| zeYFg=f2x&^G7eP}c zr>%i@c$eHmuibT5e{W0_#BXINZI$Te(HJCQPFrI4c$v^R`5H7^%15-NAO4X9GZ0lz zbqUai3c&7A{7-GW72~v$8)VU@?r99yl{p9nZ|)ZqcYTPdO$zJN%ZT`u2bTNmAyylm zlY_h3;hCUn3$0jUCplX7kCAURx*%TjZbi3rHq^?mO?SUGV2|Au4q3IE?>Pp2&4pmB zJS#kHaBss;%Yn0sQv&*6fi1(Y8g_{^$b;IOMmI^=<#GPmjNSg>3K8fY+flD9y{{6TQGFt5D(tlc=tociA2}pVxQ1@+u@{H)uD|vuWW~1nE|L##imI#Vh+{5zgIj-g>R4V-Cd}+M z(}cOUV>Bl5ZGWDj)7Sx4CsBj>=e%LpC{iSKimQhFeZgXSoQz`gK+gFiTLZv*bFZ%w zFgAo(jQ3o2QiVd?jm|q#Y9(;kAZyenqQ{&jB2`axzr=*Ch@cPr<%Zzol#z>sxN6ob zE*%01H*Ch41-eca5-0b{Wf$uj&KY_pmqh&1K!C`2%ad#8mi=7l>1}9txCa=z%v!#j zS`26^3IXd8NDxqQtpCtqVC3Fb=MCTETvY#*Wh`uYrJ$8Gg8h+b5`Ty|Zk1CD*am0Q z2Yxm;>)F0kM5BfwutEZ*-^l3h^?M7GdeFjE4-M$nB^VOBCy+0B%SomlP9zWE79Hd_ADMz4esR9Wgd|Lz!(qd##q6rsPO%mQW@xLGyiLudm z0hD{WQZ#fY%9XVi8jung`cl}5mc9@%3w%rh9!hq!DW)*B^h8@eP|Y8k8Whs;z5NO4 z$=?kUUUR4T-_u3|VT=K-pGwFd41AP+#JnJnwWBT{yi{quy}rr%%pdpTra{En zSsheLK*bn9WdGa(NuZv;xY%jpj{)jSS_IdSH#sWayVk~w*D6X5=RG8myi zY7f^L#w9mvVUVHvWsh&7F@Mk$(=D2SrCxDntTSCSv)x$tM#-@oEam$)9Gc)sq(F2i zPf)}v$_VDb0Q9qXaQj=kQ7AqQqQKxDixHZvJD!sTEu_dRqc1-k-jxeb0eR6=WrA2W z`VYO%B~MTra)tA-_kfV5YduFF>BO<})Z^cv0E0^yT$h9=Wm>=lO|h$5POEuM{@OrE zDTHRhklw=Vaq}{?S|YqTbh^|fUzNX|=>@x21|#`@*s_buxdwU_!!cQvM9xGfJC0s# z>OR5SabTTjh@YV9o6%>x#aXVlC1Zlc!7$~&4i+6B$Yf=+>jfde{J#$qj4fcUdwve` zTLrmN1fDAg1#^7e`9sNQdUQkn0Lj?R6xbE-DPdOzmu|jrRp(GrP-xe)r;Rx!K*Id5 z#Y;QP1EV(Lx8#T7SMM(Q>wP{7AGsHHq(UqEB*|tG9)EOt?f&Y1%e~O;pV%XkBrCn$ zjXpxp=ZJcVeZ0w)p|ng#`5aC5j0*1_%vrgB-Ti+2t%#AqE%qE{flu;)aJa$$g+@syocnFzkYFYE*&KXR*%shEE5= z#_<6_u&sxcl)(r!x$ATHtalzOj})lIBY?ru6j=Y~O^~N+PB-nDo&Q$+tD)jtoKQuy z4nN7WM{Thub%JHGdceN|*27g=@ju;oGukt%@qC4uZK|b=1IORJ>g|Y^9|aSByYwz? zrcKjlzo3BC(M?&#&!up|Ri?J=YZf6I>Z3^5$SdMrud*l9wY5;Uuqs`#i2(IBs!rkg z%kS-k+g0nFca8ji1B{+p#VF4=oPT5W!^$}6J43Yhw45Wr%vVh_j%7G% zlI_d?=NV(;3MUWDA7>GpvP9UAt5Q`jF=Mx(l`%B?9ef(NRAgf@+#A)=-ZipEO(=HZ zbb4|u?4%!D#h>OY=$>#(yR%4bp!;u5ptg00)IG2<<1u-TeNk+LBEztdk@blNacvSt zP$xokNtrO9kw>;*CJmS`w+X5J7@nGl-Q+je!iCK`y4X=tXgK{D$5EVDK*q!ztoUdH z+woLqhry7NojRQe{d+I472JV0JxU4*fPk>zlCsj1M;@58*+~^FizPmh<8=^Q zHKyeKNyMZErlN{Z9-Dw@%;TF;DF(h4%4I#%sjUJn@C(yo{5Jz)YNBW=WPR%q)&_Gg zv>UfMpPcW?=~_fnMv6W-ShD7p(g3=VR)j!Wh&3oi(&&7*?<7JnOj0VNL!0ZS=bxE- zfXw3%1k_J|K;j9_y*6Ci)7R(!3Pulsh27);D4voLcbeQr2>UUV5M+=jvxVzzcb*5N z+5(uw2&P;B$BK84=?H%#hGz@YV=L;LUeyHot+{vHGdYe&YBgc456Qg>0MbP*;56QQ z{0Fy(wB>y;7`sIe=C?iD(79a|HA8j=BRZfBrf$y8-3G$pC zhB$vt5#}^vr7s0+TJD; zNVS?-*EEg!phiv^j$f(eGs0XdyKu~?u1fZV=ec}~1E|+dagUSACBEWf1~zkX7Yk{3 z!KPtScqKucU1E3vc|&nS*hGtRmEH2h`$k>n5`G`cTr!H(e#q}8Bd};$k~xhezq}pC zNCOtD9DK#HH$zO&bH}f7VlAWbims_=x?>xBmwtkx&`hU{0gEJfnmEEYs<;{NM%irt zJ)ech1TF_GJ4kH_t6`#u3v3-tQ=Z6=IrD!j#s3&0+eE3$U-<5epJUZ>)|*I*A_>f% z@;}+>M}n#iBLS~)&{5u?Qm8^*CT}BZ=G_Y=#)r2H5RUU9ipRQSX+0aW_-_`e(KFDe zil~Kk+>3uWX0>YJocdFsP+&wAwj83_cxDuTa-(eD^iIzn z3Mag$>T!hX{nBv>{FCyMuA#^&Y(V8RAKGl0eJ;CXiAN#Sz9!O zGh}`wiwQ{8ItVJ`j9W&{YsSDiO8Aso|N8JDQWA{T9+kIwyg2SCwiRNE zUFLx{@JFR-&O|?d#u*o}{M@dyTpN5`$r?$=9cT<>qzsrKGPl{k9s5VfU_P>PPlJFoU8!9ZG+LQUCB@g z=_?8^hHzMog2-(BW3POzB&}GsDP*2L7~yZUC?c=%@X$11R+-9n)H0f6Q%kfLK0K_4 z-e#mXm~X6<&}d-oLRF(Run|wtWL^34M|B6wB75App<0X%aD0mB%Iw-^Zc^7XRL`p$0Xt;tI%v2kl41#Z!|m2GCNW1LV={wRo%DpP$D*wucEyb zuomO>=?!BiLru=WcEJXMxZe9J-H@#UZ~<%FIPQ3yLiNBc{^n7|DM2L3h+vJzWe%Dv z-k}4IlX$VwGtU0aBqs@-h+{Kh2)Cj2V1ZL)CT&k89(MHOEfP>G{Cj95ty=BjGput> zQ@_R?+sETqnE_a)bQ#QwWvAiQv#DJY_T@g6WP=l3N?^hUF{H0#`X!2<`o5T5Z=_p@ z*71v~$VdGBsS6$->Hk`U(i1v3pbZs($0^ktcAq=(5KW?J=fV1kd?{4*#PW|7o%fBF zjVl>9GqwC3(NM~tPx~-IMb6a4Tyf(Mh?XVkb82)Kt)PNuG<1yn!LiA+_En`=v{F%VJJ|?oTlLrO+tA+aze4mys!!B^m!Bx$ka9>4( zcDqjOFDEE{j*=ul#<4nuzvEvGwb|y;6vodXqG)YoID=$!dLL)@wU-AMe_Tj^MI_oK zy02WfnBNpk;w=0t_0$L0(dd)<@+c>jSDbDt_%NOHdMSNS{S2)*O81sZ|UR0cJX}IS-0+YIIc=Q|G zoc}^5BV{PQprT18+Uf_?Euo6jgt*i`K|yH$x4+v3@j*C%-OA)6Jur`?>NWl8MF$j*++#s9WOj{(~;RHhkO_sl57=!J427TPS{uu1TYp zTz~VZnaeN;9sF90C6kjvkq-I^Y)N29zqoqQPv)-1SrNZUDsXp z;7R&k`m*%X*EsvcID^#{wF$YHU$#f}kqj6lup~51n2BeVw>Y~ou~2F-Q@~$A^7U_$U^OWK7;1+CGRXNbef`Q|H>y={$XlfvW(Fnwx1|wx_t^E zUeDE4JM;ixg{A=rE?<~lrY$_v)EH^PZ&6q~@RBQR8Z}#jJF!cSzjSA9|Fz&1niss@ zr4Q*mN^POv5++Eat!y3D|8CW|Th(P%7@?NuBz){in0kwCReU~b#|qWwCN z2sDHqucG?*cQRTA?Ak%)3= ztMsK3)fpd83Y;Ojb~Y^yFgdlt-UD@!%ae>!+=3vn$>t|_f_U18^{EVYyRWUJ;ss~J z^>WiOqn^Hj7C8LiI4sS8kXM{G6FAHYqOZm3jf5`8HabZ#ptB(E0;9p7rr&;LGkq?& zeL}a3UNraEQvM<>4_%~R=PhZ;rk4($@=@-vyJzQn6Q9461SVP+6NEbTTWc7s-7 z-!;f%#}x3+K^Uo=U-|;Bt73irS4fsQnqZwt-+$~`Z96r3`_oIG?2OpNp}GZ7eysd? zq>6qkN)cCU0OLG_?|BCh4XUQ(&Q-hrQ6rDBiw34&p6Mo)tgUy*L?q`ln?xKg8L8AW z5hGg*~_!!8NU^bG?HAVb(BUg z3hrS1)-O~z>@$qNT*cIOZpio?OKxZF)uxgbv{`*Exi|7%Hz#QY(=GtC{h=rBRnSe% zM3-3lI6ImjD}@E$-rg7E$-IFMM1z=5p9sJ`1w*C(KGxX2HaXGHp2)6uUUC&K84Nn$ zMKwZfgWiMSY6I+T8Euw}Dz18TgVDQGx)vd-B?E#9?wQ9`{<>BJzE};R&l5C*JhiR} ztEzGov_bLWNX_a~?`2S`kb*|uaq^+CsRwgBs^;wv4i)AzJcAT%{nC|dXBHF{@vlfS zh!@!?D1MaMJR!83{Dmah^Q_m^T(OK8@oMk7cfPcZPVb#KmEzwA87w-thFHQYZAxJ8NdcZQ!TGQYkjnqzRaxG z;Q);Vo%w%#g+WMlm#$!>tnZZhZYt9rul+C2f@!s}&}N+NfL-SpFcjOarX4x(j@9X= zC%f%H&{(v@ex~M3Usn|tONoFYNT3xuaElS+xg64@JJaxXzEs~vE9->>UB+sb(Y2K{ zKMzHMHJJ>LB)n3u?pj1DCH!*P(|-D{CIB)Bm}l9eSC_t)eOt*dNEf=#4+j` z9`x<=lFeB72RSkJahuG7HZ@W~lHh0Oa|jy}_OnA*xrUmix31Cdyo7CWyFjhDX)MUiz!7-BU@|I8k;N6flzDL#>C zI3;R%qcNtnrQ+k~!JLm`^wtsf6Lo6SG3FOxyPSkI(-OvuhgO^g)WfLI&C{6NlqV7N z?v5rdK7TdPo^d8jDAww`7j+TcAD}aw?YCQ=X!7S|A?>1KBUex!x<=oD2F^~gNt&H_ z{rTC?O0Cq}@c7qs3fx2aUWsL(J!*nKKf&9lEwT#yxr@{Ff4W9r34u|xQnguB6GMNw z`!#-t?oxP{h;wW%%m&@+2xAhk*T0CRcP~5Ar0EfOCD3!%)x$|x_w#RAa3uX-PbRCR-6YW(dh)w3bdce8lJ&wEl z5v`o~^4~`qLsfKxm0JR%4;U8JRT!x0J{gT1+Nf*ymuwnB$dtD$d`ll{(dsBl4nj^^fdus`7njZ6(W{QPc* zT1ra*#fwN6_YH#)6SIlM-%$^rEf zF6Izn^N^(rbDP1%9}OjiSfdgo(N{3of?4R6W!{zjGTtOMt}<|bE{+J_%xf3biIkE0 zz*wh+R%<^IeEU>+cV*WVv&RCuJ3nNJ#V||{%(MUk6E{wY%*}VR?+dSXGZ=`e(aRsJ zeBr{5P>!23gmGR0Ef77k73-Ygu!bKc8nP!3O1M!UHv63awuwYzv8^mZVpkfHt-5yc zK+8EoEK4%&!_c%X#}S`xbwE?@J0d7H!q8efg=kWrq>K5#^3cMp@zJ7V>EzcQc39}9 zbK?%Cex3A@+WM31wmBili#p5?IIGNwrIzzV_7fXg+s`Kt>`zCJ&#kgV6t}+BBtZFg zv1w$uL`8gdXx9+dSVLF6dd!Rkuq-tt6SXeRFW*G2lsa*}!>Nnl;?|}cY4*b^4E#(~ zE^~=m1x<_u=TH=0NFI(jOvIvwz)(BLFbBsBK}2cRd^Xtq|5^Z$9zux{xHq7an}V@} zlpw&Q6oB0GL;bQEA~bomak1qkC(8RNd=B)l7)D$E_*V{Dle(_=qAV=7u)`LclbF&Uebgc%zb$7*sf|>T$UAUxoA^Hc zQrMGC)N{r6`NX7iLjm&|&smUFuRLw25+mr11i_KsRv6}%q_zWs!xe-8F~?e+st`OG<&$DV-C*Vtlsm(?_f3m6y;%jK9M z^I5W~3?~Uy;wEymS4YxVYwjii|Fwk)wN7*|;>I0m47zVHNf-q$gT+?204xF>Ba?3V^B}Lf9f^2Xgl`y1g>1fUP>Dr+Y z#R6j6eyQ$?{m!f^G! zfBy?KShdSywtDY z%{j7(ll-*qTMYIPeWSU=#k`b@7c7XvF7i?)NG!*1`FB+- zA$$kKzE)S+VPdg?5sVZ654 zCw0eV`=6L#3H$WSB1py(#~|7d`y{ybm#x2Irf()LjVpTo&gD4=c9u4RI>ArARFD}3 zH$F1SBG~%2jxbvjRLORZA!cH1_{G9{kOKk&pL&mC4D&A@)XVl39$xl zm%CrAS4gS8^%k!KiqV&!BELKlE)!C;$omHh-rydnQArX&ok$_SojBR;O6?ajYSzme zOQSAjI_9l;nQ=xq7&u|+gV2Lt5>-?yrW)vnw*bWrdDC#37zcpBaHki?s!+BkQNQs) zZ!lcgy_w`C7eHJYmwicAFyx5f7t2gGz*T{kMRd@fz3Hn3`jxMN8Jdj1)k&YHxG{`) z=fjgip2gw@?OR>7-D&ecXr`8>4Q+9>YpOfn+QfwzwDBm)}&Oe?{;MWzDS7 z6H01WN$yxo%gxvF!dxeZ3aarIINn?oDjS#^3#Z_zym{Y6iF~kRp^1(uYf&6Sob_70 zL&KOZwt3XtrN}BJfHv`$B{at7Yh0p;V{F~_9U8;Q{b?n(Af|H33kt9Hzcha8>q}uw zdKvY^CSjoewtc(V!Q^+_ArUN*+Liug)y^|hPl~! zkZ<@4kKJsrHZIi!@@BRscf3Dwf7qgdjx2aevPt9n)b#kL`FphZm(;m;mctJ&sJ5U( zC<{Tn>ML5YfoOHbs%buU``3=ayoC2O<3zX%YP>EFbfnu=+9LD$C7yG0b2>O%)!gwd z=AkFs6acYd7Mdp$y>&?Q`_Ukf+TYB;S|oH^vlY1zh`=YFeiHKTeFf zzV?~JqIfN;L#s=C<~K=89?XCmL|8Rk$; zlwH@ec>IZwQFXLme;!f`hg(6wnhGty4rbMFqVzI%{aBk;s5s$~^gUaj1bccVU8b(%xa_KnB_cua^9hd!`)*gWFRMoJ&&{S}_msOKktYUShW2 z?H|z@(J2=zoa?N6Km+jPPtuyvMZN=}ih{a*=@*;Fo=8XeOkbTd7}BWG@5;I=@t$vp zSHORyA)PouDu4B1^xNtAE%#5@!isQ8ReNO~%+>zr?qvNTLUCT$%poiO}zKask?dSPp?VsC=& zO4WX3K^%Eewlw@ik+rUmrTB~aK-5M9v6+!>ukqM^4boZbIGF}En_|8m&f}*LoS0%0 zZ0cRXct$%tcF5VSi_XDa^1=PlqCUU+%*7pvlDK76>|oe|Ke@=+*~9W**0})($HgPZ zti=HGREZk{E=kxg|E0x_!{+6jm7>PEsa1a;q5DUgS~VMWfm@>CNQiAcjF7E8m`QPf zc7M?jK1h0X5?To)D;$}a3~paQ&P#YFr%{BcgJ!_bP8-__*l~dD5X4#{?Je*+TOCO4 zIAshHbmS(V%(};!DdmtTAWp?x^qAZfyKSC!95U+{-^z^<2KNT@nQM9tx_|MD8#{{j z)6!=Skdz~mBY9kWk`1nrksy|hZ)x1K>nA7$e2ugo!Z&lO6d2gc)3ok^gkO-x9Pm_Z z{t+b>A0=fl6#TJd5A9!%zA8Gl+vAiJKtJ@Bn3^Maf7p1ISk&2h!KdW=;$k^-Zep>a z;boa$RoHctpBCD{VZ&edTaSmv?tS*f#&)sr;jx0uMam&-RpXDAfy6x>Y$%J*mw9me zT!gXYttAf`25XCvLyuR!%XAly$M*fC^%kLs(?c6T-^aS8TF9*@=Cdt;KXUxv>B*ZQ zVvR%tfVVb;=>LspEFipewWQM|ezavjm!kCN`z~5RMSMtiI?IzSP7%u0)!35E-ip@4 zIsZk;k%>9ii?;U88;7yIZF~Lq-b=5Hjj6KA&IbCb)6kJcIvUP&7aLQ&mBt3F_wIzp z2ORhA`&v2;+hbdg_UsAKZ(3EU7(+K~^if2kiALQT{qD$qgqR5uZHRkAI8u9|&96h* z+c*CFSR%q|8MRd6{8|oGWopLyIYO+GA*RmTI+}p>IiG^1$1zCEkx-&D8RFPHYVlD~ zT*-ScKx6z=7V0Qg<8%LY=o`AUBZ<%O^lHSciRwxN%>79|Wsk}H_*pl}kLuQP^O8!~ zw!QCS{LB-B3bCXx7vU$HS4s~J*2bO>+&^#rYCAn2^5;4O4sHg;B>-l`c>LuThU5Gt z+0u%6%g>m;7Mgspx}=MX0tmVXm=Rz{jLGjlgC7hFz}qNp%yo9=kJG#kQ{mC`&$Ze5LZv;uVx&yhUY8wLml0Y;%H{j z5{EfySR-5%yXfnaa_`1`@&NnWd00-o_{QL}L&e~+?N_k?U#lJad;hT;yS;pCh`-7s zL0F)^0N0&hSX?y$2JV&HzSTlQOswBvvhr1(W9?M{#rKU!|3KJO$Dxm%W8fp-tekCI zjERPr_HL&04Vx+{eyPMFL)f;mXglAd6M^JXmOg5VxK02dhB$FKrNjOV$Vsr5m(RRw zHnCHxkb2spIJAL?V??e!IIlcKwvqL`AXLX66@7|6s9?2`ZH5?RWk! z9z@1>%#a7UK6T(Dk4&tt`ifRm&iyowQR;~4xL+~u&uKfCNKgf_!(q?%;llGqEjHHd zlj;p`{1MFlPQUo@$ZvkG{Q%a%b>^9sV;7j+eC?|gxElT5+YX&yidGC$;gi@=^h(W> zt)JEAf9`&X>$O4o5xyb^)ZNQbV6o580FHv*Sc~s1suN!ojVJ^0qJlM`ve6j+T6cK{ zDVm8lBYmE{MBo{nCwu}=;>lES{xyg*wTLD`X-D^2LL=yhFtWyeO;CxJ(y;p60Ty@% z)ER6uvn6~kw3tD?{#hn=C2hNcn)D+|yD>DfPFb&{*3&^_@f&0nR#bJhp>I`h%nho{ z8@=W`SjihIm5nuqx`R-V3iQ-!E@bW_R1+Ec%dFaZLeaRx-BsSFMZC2c!{MRZOLV>^ z;D@f)d24Rz&3SX#oFiZ7xD*hYre7-Ap~>d~!}7lbQsOq*l4a3@d>;EmAm|qKp4ab0 zUXvl&m8E_20h_PtLMEW3oUoIM_Kc8xzes|HgFSt7LQX<#54=M&f&8u~>ZnfgJZ_ve z_zR4w)78NUvFK4qF)?sZjyq*i3l}~G0hYy&riThLrdx>-AL}5hem?~oMUhw+5i{}w@PqS2D%-?r6&hP@W~9yd%DX8g!XYPi(vLTOQC&rX=XLwv_=pvRr<2r$ z6j@D7Ix{MqU&a)hgATgV{M-OQRiGlFC(T9ApmAzvN_zRPAc;~>d=oia;!?!a7){cT z&X)ywa3&v4;Qe1+@?=DO7SuN=c=l+6?_LF|BAs>N$i!?;ys3?GB_Byv!eDR@lTZq& z>Zb8 zDh;)!y^lc6YtkErB`_azU>kpwJJOQW!`4iZlTbRgr12O0@0OTP?(XrHG)_=u4Ome^ zR>=UU)K;|F3_KLo?$-sgI2UP_av37HaGDs25{{Zi;~8C(c1`bz4j*}_S(-^EmH}QW zna!UlVRvuOH6`!=8vE*~s-o^&Lb{O6X4UNDD~EC8edM1?19jC8fJN zu5@?$4u0Qnyf@xI@0~ID1I7i;KKtyo=9+V^y=ix4d#M6_$utbOuM2(2qT&`XX8vOP z+{X@yItP0LwZr)zO9R>Ca0frah1LFpmpH3PY^!+ldP1V6nx$IzoAKf!z}Jz`z+ZeE zF?Y_^tK@xJL70!RFQfr{dHe=%&co!PO)TVkNOY`*u4Qpw6^2Ui4)W7+_1qiY{n!HB z@kI2XWnG(Yd<&0_hZH8h<=VocQ(@W@McA}tsXiXB`a*lldEXRZGhMPu0Tm0H3}BeN zhYBMfF@TJM)SuQB@0wFm6t77q-3e+3AT3egoXG%h7+vC6diy9FbOA0)TbHgH$b?E> zkkIcme5hZJ8Z3Vg#-kBHkGE4Ff%kl; zA3L^nzw{Q+pSWKxzHN&J6asA>#Q6BqtwNJ>WWByhgzMlr)+EK(7!69 z@F-W~2=0n-y%u0GxNyfWaOL+TP1C&9R6yB1m?QtRs{zYoyEPuuuM*`r81tR}SPY8t z*hU%mK}Xvtjd-XC4e}&uea{t&8%Z4-*jkhB7h*kLXn8Vb^8E7JD4zh@tnM-Q{nYC4T7_-mg@lr{eZ#zoJ#Y@ zOU4tB$ZryerH7M@fqNPHb-AmDRLaAc2gP~7Gp*)I@XnNepg$=7$E*Jsz3eSXly|to zI(nrvk|MXu0r>MIep`laq6=FYAmA+$L7)M0yg$BNx0GwjKCAT(z*L@SkuZGcR5V3j zV_`+fSP1h~IL%l7^m<7d%DC1H;R~4HG2)ub{q=R|>tcTHX;>k&Io2_2ipOZhBiq(j zCh^WEIX6#)Qf;IxlbNG&#BvA%?CpmGq?w-Y;3;6==tdr*#9SL&;eT?`Zc_0#K)9=w zOh$6d)U#y3SSVZJrYrNe(9LxDxrp`tH%dZqAP zvilyYKWg;daVjR)1skaYN*Y2Sx7Qyxc+rV`mT3zkDK+-tt@AH0h2+B&)y zY@Mf-0fnnUM_5Bp(`f>$JK&@1eHK{QtdtPTkR+ixp(sINj->Lb6FwS1_&!Q=2}9Rq zZrwsl>;7Cj1XOg*p=o<~8%Zw$W@mbB!;FFs zt9_QZ=#KbOerL0c77(EKl*F&Ite2HVUcZpc_p{lgZ`a0rq%%}dW%0w#Rkg8eZtmx( zOWm&`WKz-1)kl>@bVg8AI1~X&Wq&*;>GZN6(qS0eNJZ{CNN;_Zp7qa<@4W@If9;+# z3|P;mLu5Y{PLo3!)vf!=3g>}W85!8}z=wV!e|p1(CE*0(>a@($e}ZpzOzb$*Hnr)V zY!`Y8MJ7DzEh(kyX3kWZ?vRtLMr^0;L~CmQOf0{H1suE$T5A0!k}>F*_Uy=MEy!Ah zqhS^nSSZG6(*EZR6KFCpDFn_}E#2exH%JW+^^~7 z16U*VgYwxvWuPk?gn^3$=*p%Fqi0GygjMg-n6Ke56k#GvqF6`o*Fy3iKBB;U`IQO# z1}!o)cuMr+FGW(n{lwNS!?+btiuZiv0#!n#D28gol9lp+Bk3s68+O#GSrPamMkD8Q zgr=7dh#vJM1YUkc^uzbo50kl_YUNv%#(#~phx?~H#MQp40Z>MPV0K#%)jPd)V2@AJ zQ2(b%FJUOb_0A9II~B%XMk3S&O~P}C9=g3VjgSrla%%*c6?H^TJU?6u5ouMx5MYNmgr|_Z|gDoOUmC%RqD| z=pb7WTC~|FrQHZx9@@?}z+^t2W$=6To>zXkLrQ-Q4Fw1wBEMA?^8_5D08jRr7DOkA zGzMTU z-~qqkes&ig?L}WWMYTBPGCNkCTS?O9{l&ephJ4!b;BV0m_c6F_XH0{`U}0(EG{8V5 zCD+1{O&$!G_&h2GQEb7WV*l4ln_6k7`1i z(Kc5PTicrfQS@v7!bE)};lqm#nlIHT#<*72RUfQ?9TtGjW{Y`ac&Bf6_S3#Fxwzhf z56RrY%fTMdPOT`D=PY_eon{Zzo-wr=c}-NmF=urN9bgRys0|;bLqDlo1L=SdFd_B$ zYPtx^Dh4R5`>5Wgn2dZj&nhF7-!VW<>kgSnsB@&hBuIXB0_>kX$2b)nO?%;jm)iH) zH4HG>iMz9~4Q)@MNNl>2Wg?H z%_*aGoy(+Z=tBi1JBJPLNhc^*t$k<}lCsLh(yCPwF^VWa5v;>(&9nboAzrhYjp&E^ zBtt@vSPE_876bIfO-M@dg&}Zp-&$(%qj8ccg1v+U*DrSU36Q7~hHoWDG7G2#MZI^^}0rsf;<5 z{{}Q`h1v(FiCTI3r-=Lk2)=Yvq$0_LO~N%~JI``#3WpOB?R=rpklL>C4&l0 z#^+l#%O31aD`6%P2RuW&LYiKXGXrbsv|ad&4ZJrbIIf;lIZ%Sn6#ifp!~ud-LMfBN z;O0hsmetcaR*(WKZL}-Jw{zh?_-iQ8uD!SAW>F5mec}+*0g$2U^Uy=wJ1>c9ZLrdU z3RD0>D04;o)LF?cx(>Hmg?<6aPKGN79w$A|tYDQ}dMAJpWT3H({Jm0s zO}L{yKwSBbehFQNUUvCc^`~Ks_gVsbXrM<#0|P6w@1gtl;SHl?cqhK8+2Z@ep4!$= z!ynjG+kPQJe-#QaoA@Hn4LC2BSl7g4EtD6G7mTrRJ$}W4^n+Ng^ShQLvj;ffJo0(Q^reL4T#_Onb5GC>Z; zeIpxY0>G!CXNrM?K*>zpyNsV4*f^raI-w~u`mHX)UEqWZM2yPp`{nR{D*;4av|1D7fv^iE1{&&cL=g}YgO+z8NV5u@Lw?D>#s zZUqc48HWXmHI-EucbYsoA@!{<`h=hI=+|>fDwBNO{90v?H{Z`FWfG9&17>~hELb|Q z-r0&U`W+>Chxt48+3fvv&^700 z8$)h8ZWn5TP#x(CsgyW30f&xA&2t;my#svk>-&P8q;gCEt{PZqYDvIo2JBe*oxJ%E zlmjo((*RA~4v5uH3aaoOLl^iggAM7xp)yG7o8IZ3WxSokrv>5 zseIrQ7!M7QU3X0``)8FYQEQt`hSd4|6_oJNH7SHBvofbL{YdA!hZm*AU1LH6nToOT zQus)SD+Dd>JmfSnQ*4!7kstuJUgi@yR$3E)*C$B(XM-I0`rgKc=|wBnQv4XfT#9tw zRdVJ(vwi^3hT@dO#m-Uuq)yL0G1+m9g57EH;a~fME$0NWIbio>G+e?>^fk2Mq9?BS zrUgB7L~8uCGb3(A|AS$dQ0>e`{^a7vG%ZL7eQqnCG_g^YJ@J6rw(yAPAS?Thh^Affrv)Xdd z)S4zf40^EJ2+6*6BKU{?4g22qlmn~uibX)#-bWgaGN4g>+pfVkyZt(yr7ic@xuq^;6~dM=W zaF)Pl5u>@(fu5OFoYDpt0)!t1!BaKHU(YX(;83yag%mjM68- zVn-^6c9d|fc>`_GPDy)8HNaGPZ)KR*nF3{D_RFJUWCKbSuZi+K`k)3sDlJBT@kvpO zYC-{=o34p~94yoXc8R|6OSWK_@UZmn-OuoG)RP&|^D|dG@8GL*z-`Xb2+ry5Dw%n`MCt^DyFL%dkg>{#>R*OREZVO z_dcuZtU%}#9lpg8x9O<)pZpdE<(Kgu)NP-@wakn4WYYl7gayT-uQDckk^@05`ot*N zE*SQrkv5lToU@mX<++p65P)dUPA(RWtd&Z6SYQwem*6xo>`dv18?ip(%`*s)`%6Ab zI%^APC!;}V@BTg~C%h54j?rGk>M{_Af|Qh8z_E}?O(cE&`xJotsIA*)4N(W0G9ClZ zvP)9L#K#yIuHtqa94b80+jVO~*M;XOJ(1bJ zwHo?c`&k3by!8wK%H@lotYNB2!D0yOL~Vwl`_iRx+Wl=LaasHd{;&qQ=m4xdqV*|n zH6lRJ!ujWz)}fyi9KIk}GcpBV$_%t$@RYG^P|Z(zq~@VAxFIW@TGEmF$In4Z{sM;P-(C=so zUc;j>Wvx7Ondx^Lz~d2Kc|)y+k&I?or%Ttt+C5De+YfMtgmnle@J^hcc4e}KXnIESls{H016&H(?`QzUGk|V5`h5%VOwtu)PXI+%}KTFRj+v(zq?LG^p_{XTyh8!l*V>Z7D z0BDk)KRw2(f94$2AOGERo)7$GusF&Y%+F;63@G$GB!zZcTblI z$m=aK;zYPJaR1mb4N{2TFZ|`EwyeFXCktwall7b+&T7DUuq$N3gu!qji_izG=)!&0 z^aS?3Rd_$GWDIj{*An1#8(jGvLFfbYqvz0tIc{&`gvEN&Kb{8R<3I_aNWtI*+~FE> zXg|7_kC<+9XOlx-^mDI=Vf7DFP10@t=k^`$OCF$mk;P9p#R4hy9+ZB0#AUq(j6*WY z<#`;A-y0auR?;12oM(Ny%XY ztld{YwRMcWonR%~C2La~l4JCD0aKy*5g3Ab)N>*Px=YF5$E`_=SQls&{q+%4@L!}S zf^AMGIk5amS$%HRaixt8QYF4;tYClcz%w*3yc;xXo^C=!#5fUN@;t=VR9($d_J6+EuBJ@7INO%lF4 zO+|ren&29VK5E|BNhO5!xF2c!?o{+pRX=(sD3>w{F#7&g+#bYEW2Yb4c&JFouGYPo367(H5IM(d#Ji-b#IfH*+9Ly(JhQ!vr zNYntUC>d&1^UZKwDEe*FRDGFKb0d#&XvZxGM@$)uN~ei=Yl_xA9=k{<^gAj}^a)aC z=b;W@*y<}mo7=k268cw{Xr}FOiArc1Vr5~8aGccZ$q_XHLUJB(s&OfE9^u+2fbNP9 zj#ex7G)mcl*)4TwH=*e5oP{!_ML7Z?O0uKk1W|kBcLR%M`q=b+XGl7FA7Y?xo_vY{ zh7YY=X(V9(@^*+pu`1qY)t|i0c0^Q)Z*DH16n8KpAADE1)DV?B@>-G~Tcri+x{?3)7m;aD< z9f38*f$Cjoe+W{|w~9f>jV0#Pl+}DTA?>hxys9V^m@J^#D0md;#E{A07JUfi*1`+z z(K9LhO!z;P@1~FBpy|Ze>E*aQbj`>Qt89u~w+e z2-L3O_2r1DT%j^VQo1GJH)~%;z7?eV%D9jaz6;5&qNo4%)f--U!YDRIy-KcXP(WQ@ z3mFdtCzIrEo_JIxH2R>foi|asSG8AFly-c7Ik2Bn<+hhqvX^z2z3MaKtgn0gRl&t7 zo)TX`wdMTk(=tzV3~zK&K%p?kawDcdjKkpEo3*11Rg7b&Q(9tEKZ>vLORcKE)0~V< z{dr?8@S7onq+TzUkh_CNDQdx_0EKRS`WT?JvlQVLOwxg!J?gvujgw^=3y%SN@TY;6_iQhW-&HNvyVy`$ zt4=Y;LF(I8U%|SZ{9bqqaf%5TydGk7A>lF-b7d-fBmbPrAlY+=gW1$gIkJ1 zm;BSj78-~OcWZKddwwO7E$-eq#-8KF+cZDu86__|=(;1oQ)d5XGiX56Q* zoKr*2P3giDwogqt{5q$FeM4X8$1PU}0^48#fkj~sJe&QM27+!PIJG%#HU7k72(8%O zLs`=={Mrio15CD0EMIIaKaIZ1eQlnCI|qMo5i}??`t#nN;KML*8%Re#5l7SAsaST|N;(qqG?g zj-nR$>6poCiOUM<@J_oLI5~pBsnSD2b`+*)M2;t=V6mJ&k{>~ORlW=PPPxQyDLm(R z8o+h3i)3qQNoPdLs8Lyv7kC40c>v* zYU_q6miE-bYF+`1?ajzn{APa~?frAL5XIq&`HKZy=I0?z#;37bi`RbE%)?DSo79e; z+lx?Uk9v~7RR?D@pM%Vt?JyxK80n(pE%ufz#H;dun$J}u>Dxu7G`GUa{TDJY9Bt}1 z?d0!hkYx$)*IfL5ZGuD{P@Gzh3KW~T?^R}4=On_b#EuREkzd5y6ll2ZKr%nl^pBB znkLO-*1O{L>syJbbzf*kY3verPKoVk?k!ehco4gnaol*&`A2GN*=d?8nSFm1+Ri$O z7pTLxy%&x@FGtogq4H3)dIxjy56?GshpF(+EVIA2+kC9@uv^XzY0c=HY}X{F!lIx>DtfS?+4c|iLP(v^W2p4Bax<$ zn#UG4$&U=-c?b;pva^rK%Gg2FU8GvNpBOl?YzmMnmeT(m+0oP18r^arirJ)p>iWBT z2!ojQO}I4l&ncG`^@*E}R7QS%^f;+iZ1HBKO=WnF=im^m2 zz|Y|f$(<1*0{5$+(ajrxN!B)&0|-IF?<3B=kNM&#>=74xd>>>57!pc3y{}e}gLd;= zBL@*NYgp@NSR-BcL{e?Uq$LwwUh z#oiO*<|qBFdK%aq8FhiUpuIEtdzVU!*O5K);#@;NrJE<#tbou|X4I5=2fQ@fSXD^H z1O^O21@s2jF*EGqzYyEu4-i=ux>?f=W>PP7Lr)^Qo}l%SUzc^J^*%k=d9^DU`=pJ& zf%OhY(%+}q^-^)+u^AptS`TfxueoNq^^3gl3t|?JX!(?Vyh;h9f!+tpa;~I(tVM~g zT+O(!C#zV14eQ|_pSpqCG5i?t>dvq9Qb}@MW4qklR#GzQno@}>uLZ}0t{Yw0#&$-G z#)CL!{BXVT=9SUtn3w~R1u*pSI@{(HH{}~$lx>Ebs@=Y})VtsB4|~TTY}a@3Z#!+( zeh`z1WO#%NuRCvMcZ8oYs~}OWbLmM65bY&i{&m)2U=cL*vI1v@s+i$7W zL9e`awO-6dsg->inhSs1O(gvr+0W4WDg}vR)+Z?1;@)G!+2GlJ}7&lxb;-t%Y=3`A7L=jvL^ zinHD?b0@P<_S6gMBfIK@+b$dV%7*e${*DlNaOlQ%%}`_CMXIj9;u?_{F_3rr>IvD2 zZ7M@s+D;LTjzr_Cce~}!!8Yy|T{3hBI2n1bM&qkZ?wyJ3Iy<_pslPJ^@vQkn>@QCS zysWTS&fJ^vR1YSSGw!|K-?O%)?c+@jZTWP3*DmZ^T3u`;TDo8aEG${W;56=*RHNE2 z%_I#*H4c!Jqv( zhP2GZ;gPfsWhHlY&}SSbP0uy_w&dM;w^S;@@q@@hc}pS@HpQFjaPoL}-}JN=e(PQn z9?2#zzPv`n{WOxz!OwTrZ@B+`rZ8|k)_y5+Uo#E3)lwvyPxO@%9>O3$)#CtqfIl-6Z}_4mDYm!qY8x>oErz#Q=<@mA22&5oRa|6 zwg=y$S2>>Suero0k8njsK1k%t4-&7wu(H=rXp}+N#aYSoNVn_%JlMAn&G-$n_E`jr=wtJ$II!F$<|kY)>K`O}$3I+;-nWYzMxUorbWCLllQ(z0U#Z_9 zSk(B~2Fdl2x|2zT`@0z9nCE7JyIzvBq3eSNBN$1QOXdeMj;iieQXJN)Q^x>eYWndw zzNl3Kwpoi{8VqPQ(B+d4MCt9ZCdtK!+TTjPvzl5AItXZNJ$5}`{j z{O&+`jpFi$yL;GIXzMGX&3v^T>2l78mdC`g#z6&vlHtaNg8q?e8N)99tP7fD{heMy z=qh}CMjbs!hcF{bNVxZRm*rxefS=EimYCk|kz3_*J2aNivX_M^Lu~*;peNp#>tAoU z0OKyU#t+vFH=6f${g#`gn`04J(cQke9PqkV6w34M*LwO0JvRALGb2Ac{)v+*_KBP6 zv~>ETDsutv?)I17Hi%8WB{Wu8DD$AK8Hw+U;mYQ{iVNTR5X+RtZ>(#c5-t1B5#AFo zEdvH`XFHOAiF{a)^8G${t!xdpS#GrXuCu}>f6Vm}L2|8Q(sqQRtSZAl z=#DAGi`2nmF8*OPpg8mI@nkHS39BHlalOZ_St)8qZGtV5-8eQa{#yf)iNkGcR6g${ z(#G@pk*{rDC!hYoz0|KRk-|(d+C(4&-WLAo-#bisv`AJhmP__OOurK`OAKVA2xlJt z%s|qWu%DpBT<<bGXXoC)ilyfbr`g ze#c%_O{SG}gAxt)<5Pc9DW^AU1v#ZM^sVBvc)l~nK79jgCbcb$~n_6?qTk{Qmq@7KVh7Y{yL5yC&&EPXL5|-VlAF${Gce_9DyrbB_|B+@vvPj&_F>_{2)b}mw&5V=wy0{ z|3!$&$?F8$GfEFsbWbKX$r$mYmuCwG#Cj%`n=xMZ+niN4qfTf|(sN%px7xf|f5_UC z>(c$Ky!4+?UkP@p>H7R@vvNz`OkgAtC<)5&6kGd7PZK=3jo&}L^z9Pen#~^ebmzUw zZ1`IMx^k$>DSh(=T5x2T?JJ~@=4k(Dwaa)dm}QF8ylCl_%U6P;m*)a5G(4qnrn2<$ ztPLSJdFtm8^>_x+G?6Y!ttr6+zI@ zlG5N(^9u=j;IRBtZ61sqkf`GJw6-N@-(V7cDq}Op)i>N&Q_$~JHD&WXoW=Ly=FL`L zQF0C3tK~>;!SdwL(WBI5Q(s4M?%Pn3hX&z8JU!!m{Y~jYSK!q%V_R6O%YQW70kMs! zV8Bnh%%7V**5F& zbQ>tK+{1d`NztCdEoET{WgO-x92(HaA2i~Rf}4DHa}&+uGHz^G_pW@#gSe%(MYvVG zA~KTlPmbSq@5BnoYTXqV*7s4mZDVElt6KVfRJ>!EIAN8d3q${T5C>qtwQFb$z8B2e zZ~~}OUwe#sfPCVQh3U3tt;s~X$B39>P*oPPP`ZNd^B-xy?47lM>SckU(yw)4y5#PD zk)3RXjCto#bG0X@f>Y%kdzc_a1^o*zm9MU?$)eqaNBFqp3zwAry0cY(E*)1_SUGUp zoT-Q;Db)^z9alTGmH>OpDivBzbWV%)tdq+m$-~8^TfB-c9$k~279c9mIB+H(hVUr4 z#e_f1aaZO`z9F|pCaR7)*zUmp_+!Xh&(B| z4Y7;o11AF^a%(vPrHu5R5?ivR^uM^DjX}PGNS2m;$P!h@Jno>a$cj0$uqh7O4g@#t z1e)poR-S&9Rll+!8j#Z^8e$#F%zl31C_HjYK718o*E7AaNeti6$W6M*5w2vW!i!us zM5)?i7NT1~TF}ztd-H=dw>K}D1d;oghFt!wEO%qS8~}H)to`^fZ^P||b@=ic4fY>f z`?KqU&X)vwvv5Z}%RyE0Jd3(4^(`}nCYvBqkS(?K>h~#6nL?ot&5sPP`cgk(d3A*( zI6Ex&ZtxN>jL4As=@jM`ux-8K|AW|PPL|^cCP#Rje;drYNa$(5AmG%Ke$`SI@B{tB z(xy%L$cMRQk5v)q(7Yu`_4Ul^csIuY$>8_;L7XepWr1p&ui-8}Iii*{;p|3sQVei1 zmP!DMe1AB=E>4XaVexZq=!J@0_W{H7inGXWHGBYu-)w>3x92)!;l3ixyP?{1^K)Vn znZ9*l(7sTHgMNynML+Utb#;6o{0il(Z4T#JkCYWzk=!dyWGv|q?K3ET zkP^YcwF6x9c~3Ow0|&^emgT)sz-JV9vRZI~$0Q9Gq~3pYyLeKhNAAcu<}ck((y?)2y&!yuwHf^xEY^*wL!H2MV zd*-G?$$&s;zq9?TImqprW5@TqphfGe&7Nptaf8E0g4*Y`t+Z{-(qcjmC;*ezIv^b>!dndM#Tjwy?Mu|01r! zi>%;us-l5H*m7J(M!Hi2ZeogJTO~wngiZ>q*bv>PRMPZJu z+T1JoIQ@Aj*mv>U^I66tiT{uokoPOr@{8FCaN^9KZ-Lorz&NN6GTU|ooh`w3U|OhT zS%uhEF9e=Xh2SjXiJBUR{y44=JR&)lVte>>CCtu`klD09|JNI~8gQ$Zutzza052|R z>CzpmV!Fp!?t}up$qXx8+ChN``jvBA=e}0Pq}DJ|U{uyPJUk?BzHcOx`#~{ukPm@C z%u0SxC<23EkTR5?peK1>k>J1E_ zTFZtx*8n>D2a=<7WoGcoj2oKFv*;KUe28^XZCBed&98u03fVw>7$_W@n$kMP?QPA; z$@vt{Y3}xC$P74);S$@z(C6uPd;X`bW?NSRmr^EQllZLMj7kzf}!pquo z`@OSYkIs^VPZd0hCt!ODPCr=0CjI^EQs~C9EZbF;}V=5(&yt4jom) zYC5(mT#awn1@{*%Sjq4X5Ts~QYoIAG%J=^n&g|1v6|JA`c)&zl5?C}qV5*C;&yUoaQU>5b*acnu+N4@|N63S4$gQC@lM2tCFu zGe%W&wGW2`3pz}_io|W7m^}}^2o+0_U%NswJN#$|(Z}DWnWJYbN~H*grQ$TSt*2sL z8Zed|Xx%oJC{Qd)9%ojpmPaHzf3IzwYYuy=(h@Dxi(xL2wk*uQ#Fprd|26D`BK~Wb zjq>5slYK~9T64u%^X*%L1?SSYaxP)*4Zr%D=3F?uT0;JsjMTbbQE41C@hl0Yu+9Q+ zgi2BT;YWxlxLp^IsUrDqOwA)l;Xv1e4zHADOM^qDtCHW_N03<5 z=#8v(;i|#WLr^DSvI1GW>nJfe%Y3_6ZQHR)K5D#|YpHg9Cc6T*=`9EWo)o4wyY{Ed z%Z0cIC1blhS{l9yhSySbdGF7EzNi0UzAf>DWp?BY2A8?(7q~hej9s%)*C*r_Qam*8 zF;a8s0~1eIK7~{}$A`{4nbKb}MMPTmqhC(DprTYuk%olaNLIQq6+Pvc*-P4zOFfOh zwA`H7$S9_-!`uQ*Vz-Y!P&E6c23E*udEUt4(p?u_#DHyO;d%3?G8YFKY15rEb5OJ$ z9yk(6fQ6Pl>fz+vcL=#z6Ow6Ev6S0vwNM^2p{rl zL`w5AxQfM>`O>$d+e=7m!sX{NF#GFTWqu?_m+Ps72F5D$rDraxDI$=f0P&=CUqWzN z@`tMUVhY29OK>Xxzdt$!Q~uv8fJlK_!==c5{l81)6yTEZN*l-B|Kg>yUKrp4KL(#F z8Lj-!FBGyWF#f;S*!Z`lq@`lz%sukYTI0aMW$rP9Ki#%RK83%r+B-gW9s^ou5D^i1 z=i}olBc?v@DHUlN$x8z;HKVYT(~lnYvvbEuC&neV)etu~@PpzNmt+>quJHT2yRox`vp?nCb`%k#TgIKD3cP^-KNm^$6H1-n=OscL SjuSZGl9y4Du97tU{J#KXS}AV; literal 0 HcmV?d00001 diff --git a/doc/html/_me_mbot_d_c_motor_8h.html b/doc/html/_me_mbot_d_c_motor_8h.html new file mode 100644 index 00000000..d3643106 --- /dev/null +++ b/doc/html/_me_mbot_d_c_motor_8h.html @@ -0,0 +1,221 @@ + + + + + + + +MakeBlock Drive Updated: src/MeMbotDCMotor.h File Reference + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    + +
    MeMbotDCMotor.h File Reference
    +
    +
    + +

    Driver for Mbot DC Motor. +More...

    +
    #include <stdint.h>
    +#include <stdbool.h>
    +#include <Arduino.h>
    +#include "MeConfig.h"
    +#include "MePort.h"
    +#include "MeDCMotor.h"
    +
    +Include dependency graph for MeMbotDCMotor.h:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +
    +This graph shows which files directly or indirectly include this file:
    +
    +
    + + + + + + + +
    +
    +

    Go to the source code of this file.

    + + + + +

    +Classes

    class  MBotDCMotor
     
    +

    Detailed Description

    +

    Driver for Mbot DC Motor.

    +
    Copyright (C), 2012-2016, MakeBlock
    +
    Author
    MakeBlock
    +
    Version
    V1.0.1
    +
    Date
    2015/11/09
    +

    Header for MeMbotDCMotor.cpp module

    +
    Copyright
    This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    This file is Hardware adaptation layer between Mbot board and all MakeBlock drives
    +
    Method List:
    +
      +
    1. void MBotDCMotor::move(int direction, int speed);
    2. +
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    +Mark Yan         2015/09/01     1.0.0            Rebuild the old lib.
    +Mark Yan         2015/11/09     1.0.1            fix some comments error.
    +
    +
    +
    + + + + diff --git a/doc/html/_me_mbot_d_c_motor_8h.js b/doc/html/_me_mbot_d_c_motor_8h.js new file mode 100644 index 00000000..397085b9 --- /dev/null +++ b/doc/html/_me_mbot_d_c_motor_8h.js @@ -0,0 +1,4 @@ +var _me_mbot_d_c_motor_8h = +[ + [ "MBotDCMotor", "class_m_bot_d_c_motor.html", "class_m_bot_d_c_motor" ] +]; \ No newline at end of file diff --git a/doc/html/_me_mbot_d_c_motor_8h__dep__incl.map b/doc/html/_me_mbot_d_c_motor_8h__dep__incl.map new file mode 100644 index 00000000..ba2818dc --- /dev/null +++ b/doc/html/_me_mbot_d_c_motor_8h__dep__incl.map @@ -0,0 +1,7 @@ + + + + + + + diff --git a/doc/html/_me_mbot_d_c_motor_8h__dep__incl.md5 b/doc/html/_me_mbot_d_c_motor_8h__dep__incl.md5 new file mode 100644 index 00000000..23f4c196 --- /dev/null +++ b/doc/html/_me_mbot_d_c_motor_8h__dep__incl.md5 @@ -0,0 +1 @@ +3ed95255e103c383fbc800aba0ff348c \ No newline at end of file diff --git a/doc/html/_me_mbot_d_c_motor_8h__dep__incl.png b/doc/html/_me_mbot_d_c_motor_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..71cdcfc149e727980aec0ef8d2e9ef07a993f44b GIT binary patch literal 3568 zcmZ`+c{CJ!_a_fZBu|Mb%DyH$Lwd4i8w^%_nv!STLVpaxP-V^SXg*W?;3(w zSXi}~`{2_Y%sG)QV3E0Sc$k|QvYh-g-gcofnUY9T!#j52MO*XH!B_U8`*-%ASfORl zghAG{u5NH|7ywLNGRC|h7w)nVrwp!X^@fo+lNAR*u^kd#LIvvfb+hcd%;DL_DAo}iTES2cAWoD>cdMc)$5`O|6baqHMTgJxeco!l=z z57~#cV(ES{ktmn*eE&=7W@rNI*!}TJOMe63HvvgyYuR;mb?F4{m4Xf?qi0xz7jXxz zm`a)NDPUd-@ssl6<2f!VI$s3Ddl5#KJggJ?&tNeK|`_FJq6UT4K|LF2hB zn<@*SIVyp|nv)m0tEWy|^>!^Xl-8%m1Lb-4UCqkH+f?#4PFG}kpS@)xCDJ>*GGMn6 zF?QgkIPLkyE3&EGbDCw@iCZGS%pL-8!S7viwrUKt2rYv@!kMiAGn59x z?p4o}rYUd&006LPxNNox?OASTWJJWT*WLFjWvgF# zyduVs?7PzR@Joz*ycH{z)Lx05>2~bt=n=?r5s)qUJcjT2=b)D#i zkLGQX8owvV5EhSa(zHim4Z^z*j(xYSw)lkdh^&Aw7o0mP*qochi_M^(4>iyp1ikVE z46m^)uxh^;>?;CGlS*XUd-sRf7)!D)ma-JfG!?WqM-3bVm3j2N8(X{rH zl{@UYe8RK?9hf#$)w8J|4CO0_KWI$J{SxDT?g{a8H}?c}&knPt z<~45ZP0uv?*LFG0zsO*hYjY0!eRnN_e2(msEQsnRxP|tGOzmmT;2}7Lia-K3HAH-M zC_t_;?s5?eCi3b$V`vL0XPhO3(ma|{QSEO#L%ATREdz%3w13f_So~7A!CvHsKP;MQ z_PmMyiG3j;6s0i;Gs-SAHGW5ikTT*(DL;A0;B+IH$j;^A4?^u`qw^jn^X;OZ&0os4 z3A1y4BlePcUh!OYxWE~Yo!6Pi*Mobw1U}2)w!5=wwGbb9Be-6SCtj9ox~>yu<(|3q z&O>3~G(VVQ)7jtmSsLX7>yq>$^nSZ;Nj)6>O{5#2szdU}xtuij2FLyV+lQXOGAhAl z7ks(lY0s*#uAoj3+XDIH`i6G0Qdlc-^sk-7L06oHCOr1!!xA_C?+@P^%A$!uy!lp; zT;`Wrcn-^K`K)x_H@xCM)SVV8Dz?6aA|2`z-WWZO=`p^w(v+Oi-&jS%E*n4P{gJz^ zO8{)1yy$e>%QaNH4{@Y7Xnw-S_8R4sBcHrvaQ;PgbAR}hL+j+@$C5qG*{L2I^D)5E zq7dB{oohlpAUovFov=3Z&;zw@aikgNjxI1*O7NqyDFHQc{jj$q;Mm z8zs#Hzz@W@a!Gi_XP`w3n6Bqe>LkIz%i&Ebt}C=V*o;@KWa*`c>w%4;_S(f0g8bl= zeCl`$PaNFHiyK&+lVoAU?qDz*e=I@{nkUX;GptbSmYtIm8cRvB(y@y;$H{5Gk(YRh z^@`^;to~sU&|ZC!o`;&Au%Pl=f&g2;Le8k)g?#RzZI^uw+?#G)0%TUCaot#kUZu5u zg^6(L{dt)hA+%LR$RG3g3LH^%?8%MQd4^r{M`L*rrej9zxgJ~esK&J2i^c|CQSVWs z=U(8mi~|ke0>LH1?(pf;B{S&HD^u*E71#K|W}(~%^~>TMA&+b0Md-&Z{bJrGT2 zy6{#yA-|%-E|_(`ad8p8!rd9`PjZ}F^ouK1^-fJqT~*@;U%P7Xd*~^V?SpE(uqXuG z$K*Is8-g@e&Hp;dI3#s11LVVa&JM8fgIR<*kGpI>UHf6XtF|9K0Y48I2NN_lYq+~t z@CziFmJ@i?@bUjjA6lzBaPgGkF+MJg-H@UIb*?<#5#{ zIwu@oQY}`ev|p%)MekeEAZr#d%b=vIOUEbqZ;``uJq< zbj_367EJ@+f*NMVr8DF2R6k64q?MQco$2Q6Qdn^I3N)}UiuC~2m6&_u$>x4*iS`gh zD~2TsT|Yp3ftOfDKCgNEl}+y?Yv(4e|LY8KE+8!)FCj3CUZlEd_i4Q4U&VL(P`MDM zgC^__*IREdW5Y42(y{WCynDPYL@ZO5{rI@+(f+BJ>FF=4s~adu-xRL8QySby{Mw!@ zj%$RmMK2S5-;8gw2~p(+0zd9#*vbbrDR?I z$pFfo&*D&?_5vLq`4b#niO$A>ad3kh{b#p7V7oF4&uyEU3yH%D!8K2y=gL*ZSQ zXL?VHla;>NyB6P^|0QN{s*r;bSLFG}>Wj%ni)D@dU+OdGihNY<4N)`WJIzYm2vaWG z-t2dw_4UaqzTBw?PIcd1p|}5u;x&Ja@9xt&b;|squ2R4ink3UV6ALOvTbrBUOZ_|Z z*FRR|D={YM1Cz^TadW(pzrm0bpmJgvy`!VUSgvs!kH>dXwA}1phfY_#%yqw_)cMnZ zHZPq@Y2&L4C*AP`8!qjrgPS2& zzMql<1&3Twa%uJ(-H4B$(EDTZ$)<1v@%FGsbOl(ZKTUKMnd?@ti)p<`YGZ0mWX~9U zhtu=-^CJ-7*l9mrv+jL9uC2v4puk`BpQ|GznmoMu{3J=yVdE%+1ogR1cTk)p+1GMu zYYeu;NTt?#cm{NM5AF$iImw-cmg(!ruH((oBC37!F*GYSNrZlKN`4;X)`fnDQf2!= zEd>*rLfZEUe$oNZa-4SW(fav_0K2gz<;oC85pVf6{e&@FOW6#IlginummEirsg~$s zeQmRusetd_KP@+j`FnbH$WoT(%n+d5>Z~#IUBQckxn3pNXvDzn!X?a%%mK>T)B^q& zirzs)XAfEfvp-$$>pG;;g0PLQ)MwJRls*v zc*g;f>8|7qw9%t@yFGIWlVAPiVheHK_o%DFePm@d@m5b$7gqJ_y(F}X#-O^C4=h7( zAj0=ZP{IjQG=c!ZHL51MMjZ?*!2i=)Xz^7gLa?0Y{y9C6`~N5qfae&V6V-d)cwL>M z$iBMG8EeJyMa=sq=0r}63FL2D3-_w_l3x8E-3>g95!k(^*d;AOXSQ%Grba-+I{o|4 F{{@`YGf4md literal 0 HcmV?d00001 diff --git a/doc/html/_me_mbot_d_c_motor_8h__incl.map b/doc/html/_me_mbot_d_c_motor_8h__incl.map new file mode 100644 index 00000000..c1dbf161 --- /dev/null +++ b/doc/html/_me_mbot_d_c_motor_8h__incl.map @@ -0,0 +1,53 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_mbot_d_c_motor_8h__incl.md5 b/doc/html/_me_mbot_d_c_motor_8h__incl.md5 new file mode 100644 index 00000000..85cfa770 --- /dev/null +++ b/doc/html/_me_mbot_d_c_motor_8h__incl.md5 @@ -0,0 +1 @@ +c1537b6d0fe64f3eb44f53391661b47f \ No newline at end of file diff --git a/doc/html/_me_mbot_d_c_motor_8h__incl.png b/doc/html/_me_mbot_d_c_motor_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..1136b98c39a7de61deb5bd593ab1d2a7174598d7 GIT binary patch literal 65872 zcma&NWn5J4_dQGrN(u_nB_a|ML#GPT-6b6&UD9g2dgpigH3k!=xNl{K43kxp=3ky5*Es;t*C$ih*;sarMov!deLlxJ7AtT?uo8E24Q?iDVG_(VB9cCRI`rjC z0d9~Jx7ca`$!7!cxQ|vrpn5frmEXX%XBfzr7MWzQ0nszW@3Xm%Dz# z?dA1}@X7z~Az!;sseJvi>uZGN_W9TM=gR7GL;<%yOiOV*%?7ym#8|14lP7W%YEl4?e5N_e#Vc<7&TBkK+~aE2rD-cDev49m3!dL% z{hlowc;06E&AStEs^AuDvGvcv^+(1q15V&oihp&!u>q?{vY$1nuPa+|+%m$ipROlN z+e%fJXmnNBu32fB0m%n^{!?cVpqw9f&fvsru5dY6pVxBr5%_-*#sAy4mg$KVWZY$Q zjpIS8rNPd4)@CMAcA>q#H=DV_RdY_2e~05Ea`Ik+!J8$o$NEv%PFX`&HmF5Dj5Q zS_1GHhs4JF?AM>60L`EoTd*}{m@jx6knw$P=k12OM5C6k#&ijAD!CQI#Mg(AD7oH~ z1PkPe-{?DY*^!o@vo@hKafR|{!zGd`9;1tYP>?6K_I)R11|F%+!LE@d>4^x%&Zd_R z^c~a6edLdh74iKweq_THTzl7=VfSOZxa(Ouqw(Cq?tz z+pl1idOd}MY(ZdIWDkqYSuk0I(wt#kv}}zazQJiI92VtFdY8}b$ti0owOmSxz~1<- zANVKk1RNm8v?eIJ`X7=fb`;zOR&K#mLzeDbYgLX)F>N61G62L(CBVEvTp5bJP0UAq zUlg|^6k8M*$Nobnvj~0ySK+^i%-KTyp7IE}8IdHeZxg@Z6z@D~C_li>874BSP_h$U zVDITrZ`l|>9wV1BzsuSC^Xl{jT9krGGy~aWHWS{{i#|uyCAj|64fO)Ho}lMc=$M zGhL;Iqm~QRLzXjmRmIQalA7$!cKmLN$_j}y>^ze+%_w3zr8DCt?{FcO(tD6POTE z@{$zS?O24Pqus=^tM^Kbh|pfIvTKJyzZ>k$lh-VnGq*4>RPu;C(OK&z6IfZ_ly`!@ z&pB&9KEpo4J?pk2CjN!xp|VXXC^{UQ!+^rUx7u`AwtLa#p|ZQs?njB%vmn`}MRHM9 z=Wh*_)Sw(+BDjhgS`s5abF+>V+@>gb;-8FDuLZ7<_wTHd{}LHbJq3=8hyXjB8@4n0 z62Tl9M&*%$v6Cmkj>hem5=lI^TO#Qh^r)WOEYU-(4}!8e?DT#vlnyKTva-(R-)v_t z?&VQMNR`*xNTIbN@7PSS?5MbvJlvVh0H+LxYG>EVr^)I084Q8#LdQU`0zip;KyzAdzN3xo=wsb7?p2bj+uf62{ zA1?kL0We8`xKrmlYAt#yakoFi$=_e)NV-j!#28S%jQ#airZEC`h1CfpHag4;-qDM z{?Vgu>&K@Tvo4kT9Qo8~>S~T8tlm zw3vx2Wn+4P8PKQEmE!ALmHsfYtz^AxROcXK=8_ro zgmomR=oY83#yx`)BF2_Xi9NSby7sM@R&t^Z>;WqOQRLP+;NX1{M7=v-Xm>n@I`}rttwJBH%LHTES`T_B zAl(Jcwy&WVw{C73Nu>!WA;S0?6}f|_1MZC8U6OrquM!(`kIa`Xw9B$5NeU7fB8K|% zn1p9bV8w-L*!ag+Zu*DRop)&-uG&eHRL{wyBe4UV_fouICLgry_xI3MRwOL&z`PTOtR)rmBAHCX>e2uO<=t z=xZ_lV%e26y&P93j&-_3C$oVl97K%Pylkn^0l}x$;7RxNGpe|~(zJe5f8$TvK);X^ zm%V{WMKUeuu?J+x8sa(}trNYMBJ1(zRq*12G|+hN1)4NO0KM5r*aRcm_NnVMP*$Pw z_k_31Q_|c?QZuXdc>GxMEmt~3%Q*nFMS4zz(E`6-i z_?!Me_q%R)ugvr(qig2Cwl3Ux&PH!0jP&WP*T(pd^*>a|$@yd5LN$51%t<83|-w@H4~ zGB-eOlBPrINZ>p-h3B9*nZ^bj8v(PlFkA6LTGil>3u;%9m;$1V(-w<%; zIPc{1d>(c74gY+&Sgp8oTS;>>*^(JcC8G{ro%~0$g5X+CgA!xY-fIvRnqd4Syi#9B zX`z8-uGX~`(zL%&=NafLykxXAr#olov(l1>e)q_)s$ylAn?Bz23rzv8Legv|Mh((M zO~l98Q@>v+th*yoOxtX;BPA*b<_DX$3(`~9cUceBtB7FpVyp0{WnlX9vC>-W!Z2R1 zpo%+R|3_<{qfQu~pxBlOmvBYN8mkK0t3+#FJrSze&A9(g4$XSP{HUeu3WUF$N#{Q_j8fS*IHI*z%>l38kVIp21ib`^~&f{AF4@Y z%zJTME${_0peQ1{?6^A(fAdp0+9fMm-d4Y)r=M-lLnji3n)Y6M$iOuu4nfp0dz$Gh znWNp)=HF3p(6~d}4~xbKh`tDlYSkM21spO0m8eGT(xe_+Nh1@=$MqS(IO>N9$#bH; zOITm;VBEnGtCC~1=x;RETkygIUb zc`zIQO-I22vy{Y={Ed1{C%pSNQ?PQbyB3R0mKeXrIfzd7zgl^RmnBf?|I8!-fkmLxu389;oT+{RI{lkrpED9 z(Cx{t<=0*)o#fIm0*;SZ>MqNh6U>ir=SI^Wg=<)Fl@TPE4_yztF(SDE7}xLpt7 z7AfX(&W9h+;Q4s>rB5*9G5X)DxwFR^hZbGEl6M6QI7Mrk(lB}jLHbx1>%WEbC6LK~ zu2HGt63n)=JS;Z7#C91}JQpKM#8365%EIkl{L}t2q2E0t;ZHJ~-}3$4Hg!}|9);*~=^I%?Rdl{VlKs*GWRHJL_beq<|KW)aZ z)qvWA71f)?m9EYXb3d5HCvs=J8++$M*~k|_dj@yYXIOPH%~O*ezJI`c)HJl+nIIfA z?s6-y8JT4Fs??Vm^{f&m=YCd_=Of{_e8C~IALF~$#4k-?ibh>-58Q$hSAkmY#u{ z2`Lt5+UvzVoIU5@sezXKuZlyE@tA^fvir-S-EHNq*90nW0h7TO&pQ^>ZB9|{ofY!4 z8(2cI(x}+kP^-v_Ndvb4*NoRX<4aF$Z6)!W)1zk_IBM8NTB#dEC}I6M11u3G#qHJs zpWSom3gDjNZuo9@;jZUQK4@$rqx+6|4(oU(bk4@lbbE6Nc(eL;nU_T&=mAki>et)L z9aKw7K8(WXU(6Oi+q)!-VpsD1M~z>(#OH?GF~tvzoJ;zcZLf0LwfbNNXgmqf@{pL& z*)T3`_khP8J#Wgzw-!mkC83Gll*g}9jNS=cGWfKL+OQBf!jrsG>J#Yug$LF`xFfRcnm16^E|N|tStE=qh;ys! z(}S2ziW{&RDR=@@U(qNHi*st~-zacWXo+iC<)pBAvf`O9$i?&NDhji~wS~I-81s5d zlIhD}H6CV0H}67pT{7AJ?3X3jo)4v}H)WoKdfcM3#l2Wj_eqCDdL3DW|1^OsCA+;L zKH;pIG(HvHYEg ztx46gPwg-mUuxRYLly$42G$8n4h;{bf^?HGdRc#qIM-wH9C`4+^%U5}Wp853;7i-_ zF=5&^IJcsBDwJ|B&YJTK6f`nq7cg}cP^&_fXI~s){sh(bb>fPxmySs24jsK*rElw6i^vJpt`~2qbm6`l#=MUDaw8e7 zf!?j2YBBChK{UiAsSzR@zu#Y-J@RCgq^7Z5*$$LPXeeANc$< ztL?2a72CYC>uRyW9(Po4yB2ley;OpD=UL8p ze&5GwW2{mRIfOW6*j2x;Ddb!#HL(@eG@UCZ&3e~&V2R7yz3JJy|)?_+65I4gHIo}eQvmT_;w&|A5OD!Z0Dn}{T@CUM5b8} z@WN}VtferMCWm~wG)Ea8UVwD=9`lnEXH7f~;zJ=$sWnOINkmaOcmtsHMdOY|yOdev z+hk?eM1V1+?g&Iv+c$X%yAckP`BF7>GwW#gNr`-(o&Cw4y71zrULJA+U2KXi92@;` zNksq0Ve|sgj7XPpCXWA`IwYGEqDRtdawVYNDK={%h*SvG zUkVPFw;Cv-v(|VG)ges2jZ8`ayt-p|z8t&;ZHu6z8F)-evUWO4Q)O_^?rWyfI+A%= z&nb?h4qB>>vN{?-dY0y&#D`F9v{JauiN&=;Kv3jz0bz=3jm_ju&435?!B|-E$S1d- zPb9#vp{meRc}Gj4|8GB));8Y^*fT5)5wkrYl-~BU_uLLr7B61#5dQ|rw1)xFK|kwN ztb~j(dVUyQE$u=g;jeC0p1sNvB524EKa(`%0adK zscyH%t$1hu^5wnB#y!8KcBizVA!^sFxnIe1W$c4K^9}eXy$KP40VV}4M^q0oo6WUA zbo9}o5>~sZFNyrT|35CM*-EY^?DsR;Zh;S7;!PLe-C+u$Z&wlX0_i z5RURnz0Oq!#RvjOJcyAROL7&NE!jV?hIUdKqj}!S3E73vM3SZP@8Qf1}t%Xa~i3Gglr<@GSYKuh$lkm;r>Z1IXt? zyyQ`7fe)U<@)D4j<&wb<(|7pV-pX7Gc&F6K(d+n!&Ac|7YfJ+TiY_jpoo!dq2-n{I zrZL}uXX{`JlH0Ah|8DgxY@tshEQa6iqfskg5TtB+`rxMj8xHl%r_%%2-4u!YV*}_h z7tTqP?A|I&tfAf5N7~HXflNN5BByxt(m7m3$6bPLotsr^Fv7FBbWD`)Q>GR+Jx(d^ zs`$WO0`fSp_2G1e%}DslQ+G~mJ<)7oQ7m7)hWY4|`D1mx)CHy6oc4{9ujpu?@uf>o ziZ*GK8Y+RVoYhf*2t+@G?j2b>Yng=~Ge^~4k)E*KpWWYDt!*UlJW+FcV4fk~J|Ul6 zX$|N>NGN=oo8Y$GD&#&b89YfeD*REzCK6CY?Msc>9!>|f{HH)<+goyIdQF7Q3s}9R zaUn#9xT|6VQ;(O+uM6m>$I4l^^^Vc;w-Xcfk90de6jWSzZ~QpRP0%53hY4?h;2*BF zj(dP~n?pdF+>8NMIP7mQ$XIgOIh=P)Z^pHWf983H2aIe=_s7O6M909v^E>LXHpe^r z)9tb@NHl*t|*a^`HVUm*Ae*MLt!8;$)@U9!VWU+v_34KI(x1IYM6quO&|_S z$ijkwKYp2uB%>$$!;vCQ0Af17nRB`@#f!%%y1MlSF2WijYWUc(Fj%;5X?}=#(VCBG z9_H0^#yO~G5zm00>$DeQtB!*Xw0N+)!Q4+Wikz(hJ{)yB7?P6ro{_P1BifA%5CpcpnpG^Gx30$`ar-pXpowl&m4 z=K-FPqieCt>Old805)23i7#>z$2zU^&Bmft@V6jTLKZsdwAIx;P37(>EApFY4bRd? zKrs_pcdFjF>HZa$uMcqA$_4LTsJQEDUz~bO#dYUWBZwVpkQ51DNTuEVg#aoj2NFORQIsKC-g7%%;EdIl>p z)<1cYX#*cSz?Uj?6h+gxytd+&gby}Ve z&GbZt5MxUX1?sX?{LAys_Tx)>Ou&Z7E;{3p z;d_JaRK+u|rQ~n?jgOzUAL)2SO7q; zpf>i<(t_MU3 zk*@?L4EPHx>yC)n*5mmi4>Snz3qdHdJr?CYLVlyt2NILOd{>Rb-(rm0aEPd-ar5>h9*QM4s&{WQ#?p!b#KPCYGLD(5zYf5qD(;U>3 ztJ^8hz6&rfiV-?cVa7hUx$tit&2VL(IlkwAzX3!EQ+h*Hi>Px}Z^b(SUK0{8t|2{^ zd+{!k2&f6yyE-Cm0;TrhtRzj3<@Z#)7yAXyCZV0Yhn_!u;`X1!QCU~u*^Tt&8FjOp zy){3aWIj;);6&mhpFpK-H*Zpsiwu`*qQZV)fXHbyuDqhCh{nlIW@jKhqT_f9HpXMu zd|~`@Q^eAaM5jO0ht{q zeB@h-TeCiGIyOymz9qx=!kMs*JX=TT?0-?w-c-pXk@48zXc`}!3V(9UWPH6X6mBlC z)*h{s9^vU#8i6iQudI^@KrQzsD}0$wek>3EYTgzMr7>$9{@oSRxw^W_qzV-mnoh)w z3;q)ovHP4ha<%FaAfd4*mrJMm1^w6xdFR{Sv+&1ZD=z0z2^r!%>h-q3fbwhJCnhmd zLP4x-py0R9`ZZQFSHUb_o26_=(u#|V z0Y0W_|5))6e7(5Dc%sy3^cMzRLmR$ohmSMl6C^;s_8ibsDVXoEiMakDG5xfc2Mpq{ zXt|MB|4{o{svgl)QS9fxn2`ns&{5Uur*lG0nPwe;4N%EFSa83+mu*Vrt;ft9vK1$+MWQ zCR9bTKS^$esm$e&%W*VVb4)DHzA%3FnwPpah zpTyCa7gkjA`gAEt1Mj?iiP#C1Dd0SL{YWkqhY}%y#j;86O-0^|3#tGza)WELUzSQ> z3gTgrNMm4c`PzGCR46w1XBW*RCRBPm&C}^k(44d*D&hreQ(Azo_S zX0+kBM^<@LzE?4rm$+Mq`^B2SxX#jXQQrpss#lLA>d?P8H^MvhJy7hDeaL7&xwq16 z%qymLe33)aQP5;3IC(g)j6{wDoM4{j&Sqvrcgd(3qj!Gms~gVaHM0!Av?THyws7@P zFN-(P0bcU+&u1J=I;e^(4W(pBr<=l+(o?KSv8ECXOs}rz6MB}9QfdY6H~g3IQq-sH z?P}gSc+qhFPk{nd=erg_mVa152+s$Zb)d(+TK4Nix0S0vx8UM|We={XhP{edRqIIB zT5-T6YVQ}dOjko|`N;N0@tN{3 zfQnvIvJF-BPl(-fT$-M04TP0!bG5u0cqQH<^7+%l)_=+Y*G+ORC$)t@&{mB7)kxRKvTnT^}^GBXK}x=jA;ulZ0^^n{m>exb}N-aR8WE9g`7V- zs3KcDd@Yd_Yl$#Gzlw7OHawU}V$eh4wqJwuR>0WjmpL5F^-f;96~g>rq1?=t%gs1kPU*6I^}iA5QP8W=A4Ka4B0-~FkQ6)Dh(T?ZH?3xG~VRA@uqfIi*fkrq+T*vj+%JII~znpAF z_eT(Q_`FzM>j>jOwr zlUqi|1eKve^8#N#9g2gHvw&A(-q66Z`vVITZk7)wq^7GmMe*!Ni010W7)_qzU}5c} z8k7;jY}#t|TH3un{97i*P@I8LFzN|^q4hSf7D%h!NyDR=iwBDXlhh1Vwp!IS z9(f|G)6*9@Cue-3cfZzs8lRVL0N#5&%mS!+EhRtR3C->^pR5X{vu3#*gE|I0<`x84 zIUtdH1tI+sRKp958ChrioqT-@U9AUc`DDD=OX0l51Z`Uu{O_9nuEUe_e@A zX`eFfS1qg6^LUZs2%~P84l8Sm!u;C+AxhXrB)3hv?CZO9{M&}`s7H>pQexK~jko+- z^L1xP=T_gotBuk4JhV4b2%;3Y&1JPHc^L`8FK$%j<{GEhLh>ms*YxshQka!sKIfJX z@J91`>E1G~LdZ-#f*S7&l#TT?QPtRx33htqo_XI!jKV&j&YToSpG_b*Kn)omFP`It z0#_YFXwVGm=LX=}n;g%7mA4iEn4R{S*hTy!20=aAWXe9=#xJ-(cfF}u201P&GDz(>wBlJB zIOQ+9UKW#8W>4!}a(8B0s!@C>jm`_^GZ&a*Sic>S_bZD)nuPv?JH1u@O~kj$4YO|Bh87Lq2I^l`)QQ-)gMg)D z79x19MDRXs%D!4;Fi)3h=1$d&4Vz8GjA9?75)Y*aojlNwN)CJ#w{$*rtSmFBIJ zS^xnv8*tZ&)qOsAdB^r0zU;^iA@Oyfk>@t#{z~xFq`+yYrG3Uy?wQiFWAoW@ijAM((fA0wyJs zVY~&u-@6&u6Z>$pZ!ZeI{HbibCIXtCFHkmwo%JYO0k3TaT2w)Fo z9zY@_v%OKI;5%=iIb{griQ_5pT(vL#ONKpeBBY+war}~@TBO+>)BVPlueo@lYTK|R z9d-p#$yDf~;4;ahe)oyF@r>8Gkpc(e=>!8R1AAz0B#eGr-R7jA;37o06eGgP>7Q@H zwOOY`b7ix1Zd-9_O2P&dicyD;fc;jHNiTWt+4dYBn+_nxz~birpy$%JPztlcqJwmU zn(G#e z@^?^}rU0jBs@Lp;b&ClvtGJ@l)%mpbdU!4IguWTx;J%PKEl7*j^!bm1Iq}$qCv(P* z(aB8y?*jiA&}KBO2uV}N@OR8cvwNaE8V0~g6i=N@#9>p{lgv(ELA`eEtu|Kesq0ZZ z;>iQLi!aPeT=*g>sqT7e$dE!n4CrS^$2>tPG45UgItV=NnMZ6KGW+hg zqSlVqxrI#E=b3M9)7uq&`AaV62@xM>>>$%SZ`&?s(D@Eeh|Uai1(W58h+9?)dHlRNml?R>vF zmQDoOWL@ffFaENE%yVk`^XbR&koft7&VSBttYtOCMJ0oO{|)TT4xy49J@E?Ic06N{ zW)A2}aozi|b0y-t7Pj&xvvHO?OW1klH}p+P&&f~GE4HP>F~fkbT=?5g(+^#ir~k#z zek|{)etbQTF`{7-KzD8jQlId-5yO))#)H0n(C#_k^n}-dYh`MHXmdUgLy=gXoW2$5 zi+~L(rdR!t4NfSo&CtS76e^uPqIVJGxTg9*EIHhMB6bu!n3jbmT!z@JC)Z}AgTq5t z-N5w*}sZV0tRD|Qq1A;c3$GOUT0(G z-B2&>BI4zJnZ=fPe1(nD(Bo^Ch#oG+=Ur7u5Z}n~Z|+Mnp+8E5Di3dWOMel~28N0|aYVe20IP z0x}X{J7`i>KkK<4j2nn`V#VnKbKRMdL%Mdrhr#G|&drE8FaYRGZqYia?_KOce|3A= zd5wP#5Q?~zRaEZ0h8EP=jy4%(0aHbj?0BbZKN_{Q?jOi~>YTaLyTeRx@fkf0ABqyq z8v=fUgVP>nR_Nrh>{ljidn_MI)70WmzH9H9^l#=_2W-0--MM$ycyq&0*1C#EgG<|6 z5dTdD2MY8V5k`TB@Q;=Brk-ip_DJ}s*ql(fN$ryH{{9YlQ=I}nPYV7Ef$tG`N}Cus zv~B%ybJp1lk<3jA^53v4zp*(qS+g)f#8GMTPVW4htX;!8y}UA z_w~N-jzrNrVCT%(@jEUJ#Zq(42)9rDN#Rr8@|zV;d7R0 zg)V{VPdRE~)??m{T)Ia}42l($kF3f;3kq&Hz=(>T$Ukzs^RA`rvOLvK9tR6Q=w;$U z6++#CadA#xqQ(RJGlU^{4e{2qJjfAOX6k1VU$THSn;WB0x)I>AZ4$7%m1rZ7y`x;4 z-`I&>e^p1ff{45}VysI_gVR%z(JIiDv=EIsjkw5U_m)DFe|#1v|122` z^1#j%n9=#jL7$qx*A`|VeOULVaj^Q?W_L2EZ)@-kLmSZA31EC7qi*WmqKtnC{?DPa zj@&1MN_>QK`(dsBMo$=0)H*{Gm!p}c^rx4(iE1Rpu8qiv{7(UI z;S{^NAVxJZJ}I-S_Gu-41JjA)-M?)uS=~N@L>h99X0w|Uj$tt*tM;<3l0gujC~*Vx zpY^&If9-U~^ro5%59HLY1tLXWk6-k>vpipWzYRo-wz$-`(0b>~%~TLPkKXG3)>8EF z?X1oDBnY(!XSB1rqOeb9sTF{{C<(h&ERH4 z1@J5>8PWLQKCVGINLgMb-;OCL?arIaJIZ6lH4GGinQC9G=?YSh^dQDUJD~L$K?66M zpjI@VX3qQ(OvC$iRy~ac?@|5e0e}w??RALzTY5j;p*)!!R@2AADH`ljzI%A`NGnK` zJ3gvA^df9B>};UnDKQ*&t#V}up+{y#*%HCyn2sABMU&>_^bde5Ge+f zp}RCyv9?|c*iEoE$Ly8BwvSFXSFUsi9|bZ|+0bn9(b^MNitG|1FYpgqQdQqIw~Sp> z=;r=y0u&gNxsEG~KooQ_lI63HS5b+VDlicQo!C-)IGLMy6ke-gxsM7_C$X!ht9-4} zE(g~R9M-LP3CR&U;fhlAvnTi>Vv>~o9zSdMj-3>;vfm!MS_bk8O3#cxt$s2hJ#J|e zG^Y;yK$1L=*E(}>mJRx!5A0@+gd{jJ#APlNe`AmDvZ~5XH7QR@6iE-p> zVNN*uUup{IIybNEcTnh@(sG%&5ESTMd&FzUH=JL;PuwZ{&cW%z!S~=kjMlisBHjMe ztCDejlM+3hi}A*ZeNQqF?tg|v_0ccv*uT1C!~Qd-9IM~gsnjzO`H#qGRjf@$pqBq* zf-UX};DbrpM4V=waqR z|KkiPv&&yTjHB;$9<7lcMGzmSu;35~KNH?kKtFTGszaP1A_cQFVUJ=>HYbV{v_Cwd zOV#z^1=FHMVA_$_ZQbn?9Cv_6I_L1R308%1R8VpC#+F>CMsx8NeTR~nSR z;t}3e38ou9S^0BajRe>Wuf!zuxetIZFv}aCnJq%gYdx3qEi{nAECxjfjwDvGKD&6} zmaEhKjS{`m$*tflKE#!!O-a_92mkVTvX5%Le(lwQcKR$-hU~yQlS}wspvgClRe`*{ zqo{&P{SO$yL0130&9Ao2&QE)2Mx`@?y*}d_FgNF7qoz%3f=2n1sn)k6BAQt`NTgPF z6OSwZOX5dTkCMDj@`t>lrpuGB)?Fm^B%uxfY;Tl7<% zoYHmDj&B#GFY3F8bH;qAKxbaTkxRbdlQJn~S%+I9eB@MZmCRq3nKZ`2IB@5fV&%WL zRp$#ks!~d9c?QKEubC0plsUF#i++tslqq0-WV%a!t@2+IUrDYGosCJIBv+Lwl~sqY zuI3B+=`>`$x#&_>ifcA@u|jb2kGY^v7*Q*z6C9H zJyF$Po(g`9hAU!$Y<&xeFhuK%#eq&?6Q`M7{+(r$mka5p{fGF?WQOtG(^XabNsAf& zI3jrkIp_C&{fIj>*(@*pY6I-E*MkhRyGj;r;)7Z>$lkMH`*%^9BYqrBK-&GcXf)HI z_V!+f6ynSmk{SDSGBJ0dK-1KGXt>;odyDjLz7Jg2nADtWC)`8o=jg2UWM5^&hNUhP*c!W(O@bB7txUkst-O^XB)pYng3i~B3r zjLQvv7ybRE(Qluu!Ct{{tuGy?d4j(N{Q`YmbLAlisqj<0YazqrcV6Nqa)HV|_lxx2B0f&Z6GMB{dF#{`-QVW3B3I^Quq& zHg}Ek8R82q=`=0j&@H6xLo$bV9!oNJkmbCD&+bT;MX`D3b#PTBs2)qGsPvW8EzQTC zYe$$z?-l~GSUs(w{TC1En56P)#HZ5-xzFj)^$GwolaB32b)4=c3~aBT&T^UNEmFjf z1d2Q)^Y6g!}DI^bh@LHQCU4fzNe@P85+sBrS$Q zj=4?)`vnfF1*tq^(2#Wk1f3#ube1#9r?$dv3`A;?<_Yu}g74xJsPf%#}pxV0X(vL5+ z#|P-aymFg6PprZG>>8W}kp9&Z7wv9rqA*Wu7C+`pYaizR@fU1VNiTy}r;-#ujRuhXpBF%RNZXdN?~h@X z@0 zHKfphYwI$I-{6=uvj&N@se?ae9Y}Hxr*fqe`lFikm0T z2&V2IAzehh|HW-0Fw12|Y3VM=K@K2YnSoK>HuSw{Br;Xy3_Ik`D!$~ZJ~$QTAr%6| z*Yi?aR}HbsRI3Mw0Gtv4Qy}7ILr6;;q+se=w}^Ras+nu6gkx^tIuPURkTD57RAG^2 zc3=qUB+dWATy>g|=TO=ziZkFLVJB=%PMGOKvbeH^k~AfMKAYg5d!R7mFr}XflF%(N zAm}aT<+EN)v1ksFpYC>)Hyaa8jPLXJ*`EGGz0G%6``JQ!f|@Vrc^Zu2$G1?{j`Zat zPnWaS$W3L{JzVd?^@&XxY82P7k5Q}JMFM4EVH~bD#FwW`re~YT$&@#WXCIsV_X0Hr zO?l!C6Fh&DTJpPV-=yteIr_E~N`D$iH{+!ZNG#i9Goa+UZp?*4D#zuCQL zI~WKT<0Ead7X4b}w0@n|tC1JuJ^3Q^VP$x-T}pPOx|c}C*8C2Zfz26n zLZIdU(hxx6(!254ZKwiiIg_NdI?X$qbVR+27d@J0<*3G-hWialOGS zI-WtF_hkqPZO%WSgP7bV9&X;fc@T3mmLvm_hkh$GX@XXyh!SC0l|X!8dx;#?wZm1w zS;5UluR_ZEv{K!o6<&++X(B8EautMHUH_^YwuSp)!}=wBa7PmBSBlx=K3+*tJ3B?Q zLy35P2EBSsm@~&RH})e@QeT4)0r&35#wC%Rqb9YU9Ml?QGtj({MMtxfeH6{0ROg|} z{2=t(wtiHsbWeDH($tw(`0|>$(2j7EPw9Pl@crefOdH6XAX!IzSnIO9?{v>9W5p-S zspf_(p=%t*8-w033>E$!zxTLtRQgO6_fH584Ef5#+F)phy%z76*-~~~Cme+A=@-ie z70D2k>#TeL%6aC-sd%5-x-3VFRhLKcj*+&%WFMN-l!B~p3&=lq6Xg=GMI75`PRp^dr-bhy_rCkq`-8Puuwb3D4}FCU|Bd@WVp)sc75X|0*V5PB zAN%~bbc9)f>Xp~+E4Sn9LYHyN20<^E5~@TjomJ)H_Cswj4CJ4=J63J(L<1YLbUzcR z>0fA-Hg0Z+P%y`$uHxmFdhhtrfnsh=_1g9kQZ45YBJmY5Z-0`_=j?flFuzYBFZ=MA z`8!f}*}+Ud#+t*Q@(3aL4K2e3b2KNdYVmDix*e1ZZF=ClHtxlNx^y|DQ>Be`ugXW8 zDmaTTOOo~O@CdqgvN8p;&ijqaqlh2>c^e%O#3X^~u1|E1sD93|xRxKla6;T)Rv5 zm(#Ewzn0(cZ*iX}WPJ*^`UFh&C^2!59V~v{mc{9;$uxg*m96C*rF6VajQeF0)DLdF z6qWTavMbAzE5CKW*P@wPuu8;pl!%+a#%|Aun~iLKla5K5gMFi~`>d4h6bB_Fj3DOt zWi~ET(-eFp-}0fCB9OycHpm#~#j}t_^jpGEnVk8JbSaf!)2q)4(l2ozt%P}Ql;Q~Z z|8jearU;ZC^79FHmb71z|2TyQCYF%9aCZ{~xz^6ficqzGf{Trjg%z#&IRXRJGJ2jh zg8reG%Ef4+gr}q=IkG?5*LZAi-BZc!zH5SamPHRsePcL|%@fzaX}J#m=iwaP*bM4! ziEZN~H(qCUh+p=zWjjqOAbH|N)6+{fVX#q`7MLeBlrbWd#mM~_}w^XVns1lsM~Gs(XN?B__0 zEm_bAIsj%{zwJrT$BQQK+UuRhQ4M6aW^vTX6Mqx*2nmpH5u{CuG#x%`ywDZXOBUDe z{SvueTb1>(axQcs+LirV@YPwr1EERUycp+V_>lSc& z+nZ%R)m%8+6POZn`XkEI9ar!VNM67jjQwzh_@$0MUMQ0jUubz;Dt6=6=Kb2%>K?wU z31dCogbi`z2NL`C8u!`WOct*!hu$b!$W<7g4o|bhNaDat-5>6QU0n=L9p3h?!Fo=8p?reuq?9_=)=!|KVnR4ph~4Mo%0)wX1+;iXJa zna&tU+pPlVrDqbOD6c~DNU%2=+#qyKva8;cYJI}EMrbH6B~pWlt`sGdu4ck1M1cff z`r2u2V2yBKYsS7`vj=)}lrlt1*M_L(IedG?X=8K*;1-<&Z*9`=I$u>0*d_7;S-b6O z=q2^IM`ODjX$@!uSy2bfYMxZik8rR;OfbdW^lUHXQ`6H%fBUir;Yd{=EZ45^6LwJm zW*#$lV9yMSHHdon`;*}~5v z2kTtpbwfK)>vk*Zdsqn!$L5Lp_Dz7vbBwbJVZP_NEz$sxqn}=I|2qO(gS8AgcI;xz zJhYM}ICSR-cz9PFw&dcI%n+!jc!gH7J}6*`Jrym+q_?TWvj$j9!taC6_>#{;2`n&) z$gaiSif4_tAh$x$!t|q48UtUvtag>#^9-$Nn&YUaT;4F$u0r*i0yKM}1jg_HBL_Db z`^3MRLvu+0E)Iat1x+q8tSYoqy;3ZA-?O^$Jts+>7S%3TUkH~|p*Y%7$tgcV>fnaq1Wgx{?mZtZ{Yssd_AO56{$-!UT>2vvkO)qPa@G_A+K z?s6GIPXhn)_E5R0*QL5nbzc1UK9ee^KBx2nhmsO3Q4F%gmmxW+tF06GfFlLBo==OV zc%;l7D|2VM!Cuo_e2K5ks-itP#wTX0e-2D9n~}?$h0)H5`g_kiN2w_#aryB3xI)`A z=itY&pF@TsH7+q{ZMbKZS5a_16UW+qji0YbOg%;N#9wWVGy&ByZ*`vz^~T&0bzj8( zG?P#BW?QLg_)Zl`v`*)`uO%wCXDrh8k=t>h=yn2{c^J#wb=nQBvgxbu(6sK7*b=@c z=;SEkC4kJ;gT9W*d}?9<4l-hta{ywK+M|LYzlZFFb#9R78%5m)CLPM91}`7P?KlYS zf4m@D8yFsT9Q;x6x|V?s&y{8$bLl=TQ)rx5c+s!b+4&!^BBc4n{tS!A3F0&p*L!1# z)(HBmZP|z{%Q1EWW^nfS_h&~WVXc)Yz2q*zDEUYZe+#d57T&qEL3Q_A?ft&p}!o^+%_u^nL3`=@dUgF2ZG%r%D zXE~9Jig6@-s|9nC+CUl%chAJN>{|82rYq~Qa|XeU#KBTSyNB9zp5CPE zeFq<|iUp3St#3FIMmr?p1{Clx_b|HDsND7{;_JTeIl-@mC^E;bYmg5-MR;|c{s{fO zo;Hp;BqsUc-R*#@?-^#52vF?c00#$=FZ$yFdMw4d6RTD5Wa^NykGj>p@c%ISuWLmN z8%Xz1lRD2beJR((KL(*;RG}=2SbL({X>z`U4Ni29;5>o@CPqWNA;5fRogD!h45k8Hir3y7^QXZg`2c@WB<9 zi^U9STj)fHy@}6rLlg$CzzPImI9w+t6@%QbS(*I}VaZxERyIyA`WBe6f5`BB|hug|e!?^S#73HCeQfl2t zd`Tm^UELmC5gvwwZPPWU>RVNc$Swj8vmwRuVC==a#q_!-^(W4a-7+B~R*$znt}8VT zYiy|%_$z&qEmgW8ZRv!+pWV><(8l>isMqP!S`yLgCHEwDByCc;)nkTj_G@qTfegyb z2RN9|f-$E}YZ0}w=Ky^pud)5y*FHv3{(dfWSdN;nCLFV3>OyaQeY;&eYq8vwbqUXu z{Ci6WVZ@o*>@^v$PE@~OffqNqfB!fB3Erz4HYAb z`qt`~NnGD$@836Ne@oaN>t0z&Iwy9Eb%m;2y&g_8?sj9M#AWo)WlhRo@VXGKr!hpC~Z-c{pXH$w23F1(yK0zvn6f>C4kQta|{IW+(t>L|+Ai{VvWU3!mx69GPY7@g;vCt7NY%=o$5JbI` z*yz{4()1i|ny$wc9q*s)__T@(p%EKwHOpVfa)O%Avx}MUHsK4EJG+Ic1`dC3;pJ~N zmQk0qo2zd|6<1hjz25qxDu#37xu6D}O*E*>tSe;aaCavk?2>?u7l!uCqZPZlqJmS} zH$wz_$+JBfCI$-^3f|Zq)0qgf9Zb_nsK<|e|5;ck_VVzU-E0Ee83=Wa3VN-0R8>)X1Re{Y{!a|R2s7e2u8LsK;l#bi>MpVeKM zf!^wyJCpTolGoJ21FN%mv&<4LE+W+***hdClVHvP=L~+oWdGh=i_;gf`Ca~QMj#Lu zGkul+6#EylBK=Rm(NrS#cixM;oCr-En~>LrdmkOts&a^@bZ3Cv=>go)lYgUsq1~z^PTqsJ(Z(T*48gt z7cbOD#u}#9SUn>_L4b&)^=K@*Ew)3rzRsRUujrLI&@Xb3Wg9)LC9#tny#rKeA%d5J znKQCz%i^H8HkAOgq=CYoL;2J|^d{0fX;94a7H<-5V5(Wkx}1t@RRLx3T`)Zck(S`K zw@)KwMfrLOXfhw_7~Frrcc>KvY0?lIdX8)|%YgWKEl}4#?LUsZbbAr8P-q_*)i>s% z%2*IGV70nN-*uFpqmtwRTNS$Y`JsG~G*saP2E+r2xPZI^I7(`Cs(MQ>^f~nLbLAP0 zpW?_x1vhfqN!F+NGlo0bHq>&Bnd5BZ%XR0}M)9AuJj<=`&@S0FK{$qH0Q%uH#%}C4)_Y`I*FA)E>GR3 zlq?w6q!mgMb;#{6kbEQ<>3``TGX%vJ9lMbPidjdu&-H5!Slm71XJCJzi98SeUa!=z z1V9k>I1;=OX9pn$&21LFUGlKMjxR0FfoIxIdA~oKR77;J)QmUT_YU9#61~)`&4${P zDf&AJZ^gLv*CS_)I~i4eY8CVxvUSy`=M?7WtixdB+Fy9{+6q?(={cSvqtYLuxu|ZU z*)=aO!_dm2kC%FsA&k(L3@@-4Z68|fom#N_(!H1gdH%kPbeHt$FnW_lz3juMupVi2@o5?8DVB*6+aL%vq^#d~GC0e|*vZ*I0i; zjVn8{jTz9)IHn?Yu7(pG0j<)&LQAjn*!O^6b>@g#)T2UT%d4pgT)IjG3n`*8{s#kr zo_qmkV%bA4jxXwkwypKAf4T51C`HK8zsyyUK zprrXVU<;^0@tL!xpJxn5;+18-Qfe%|%ru)!Xp(4Rp2--XPV6dp?9=81W5~GqkXx#~ z(9B~e4?em2Y3MTyAi>MSq^HOwr&v+X_+4$b8yHz z(>V{Vg}}?-)z?AXy{|?B{sUp*^Z>+umJUXV)<>>80|YQ5bM)P~wb&ARqP1-Lsu%ne zR6gD@)_sq{B@TBTFb^8~HX;QwIY^y{H+p|6FZU5B_BzpnX%{(LYbzj(s)SyM&jK!x zJzVbLEOI;bkKz0HHFiRMbB13}(c{b!pH(UJ{{*0%sv?Ch2JbNc!&}^jd4^v5&$E^g zEe6Pal(vg}sX^MqJ(r#$3gfh!@Js9;aK8hOe`~}`mrs8IHrK zo%G4NSJkQN-^_@8U9ZlNjJ8(qfI~*r~Zy;p^6|0O#~V0V7~>umSml zhXf+pk00|6XlxfK7ZdG^r*26>&(-TpwGRh!{B|#LO~&G$UcWkWY!=iv*?2h+;5?MW zbyoprEaqLS9$1F1@;?4&RBBbpLwxlgA;B<7N$Op^WEo53s!vyaqmoE*4;~ff82Ihs zd*GSvb>r>FDm!3VT#}tz*EQ=mY8ute1qpnTeZO=LbtG6UL&-t{#+N5tA#4}f1Fwl= zR}f8sv?g9P_9nCNS@_BzywXLZx&3L!8xL51%I@MEok?4@fNC^8lV7)vf5W9J)}BlF(x)qk2DduRm&=@7{S)LE6(mJEw9LLQgLpTgZZqN~Cx-lRyD02+#A}i;j5C74*Sc*YfKds+IljP`jw3}WRXf{( zYOQG_cT0fdHkXmZtF+Yb{b38JVKC)lhKbo_h0rnj<#F%YENM1SF6JXTq6(QJ6DWR$ zlg5?2W9!#FiRZzP$z$A_krf979$h3)z?I*-%AH>R66ltN0uso5*c zqY;mJ|J+P#A!90wB08EcFpVV14&#Kbpqq}u_9J_?ustI1^PXw%8bql%>qP!;j)gvJ zIN%klhZ6F$MI2KDyvN&_OKW9cV5y|`ku`_hq1l)tTyN(T8CX_v%w}^5*r;YO^MWfD zA$_w$aV;dXK?0!Wg%ZXr@2TdZOi61(m6{8Ci z@C*4afO;E9md4J@Mw=uJFtbd6ma^QRL+rN+y1sm!b=6qBv+Y1bfW?yimm_JeXg8c6 z*AP%HJ_6!La)xl%uJTCXsYIu}TX|tXb~K-)mVY!<<9X2{g4p#VL7Y5<_L6@{Ya=$9 zwyT~dk!#4{$7<+N4l(tDAAAwc1g05_9Sunr%RmSjhxfVp3gZKQRFSy)b#sexu63k{T6O>vpI~)$1g!_qa!0CYU|2umAmqLdNNhj~e5v9nb6` z%N|ziCT_1>rd+g5MbbaPat+O&OI_tgVyOn|1MLJ@O@s_e?X^~ab5Zyif9&G27V5H9 z3)%(E9@+w(S8$c}*gw>*KpiC^x_jEKC)VrcO(TM3`2rY7m&!D(M`rNHUO9wptyt7i zpQmd-`2PYtujuI+g{Wc(0X4yuUML&TRjKu6;~dqA|APf003GPzvTf)?0MUdl`iPYS ziffpz*mH>lyaB(byn?sEsY64G_XO=}JJH!BfFRFwr5IXnbqk|z(STqiVD?zazD15; zxwt2C*1VtZJ?6YyF8qKA`sg<=)w$o0FA4}a7!^mIEWH&od$2A+!P@(lKfjWrio0T* zX=#?>>Pa7;xRY_COEn4;d3dtZI(^&5tusiz8!E#w`8?CAj|}I;&P=-puLOiz85-eQZf9{M{>bt@kuwBHliqZ9;CoK0-sj@BEfU|G3qg? zTeMS}vkh-ihGqUB+H9#S$}u6S%U$k$ZJ98S-^G64z2{#phBf z@xh;>iCg||#lEM^hcA=-4qJbHmGBJE*dFmdUwZ#iI|azgy-02U^Ud7)u_$W|*=!WA zdUB@T1BxorIO*#0bzR~70iQt1pa0DQ0P@5V{B=7Jnzk=Za8QL*g!=Lbt z>^jyadW-s>v0z)Cdh@|C7;}^;>`h;#?k3b>ae>GSZL^HOFfT+63_#~>8r`IK$yc+x z`u{~O9&ff80;=Xz=~cHkD~#%U_dq^-V_MSJBYzFhX_Q?7me-Wbh$*n=T%#K3}baXT~~EI zasQ0ZL49X;2yx*7R)(5wOnm#?!bFCvTpVQ!;}j7!BTq_?5sl$_tc;$1FN(>Id5q*# znd6yt40c$%F25G$^&j_Wu-&69^j`?fxV758GH-y)%?KNIq5mZEV|vB2V@O?sHvdLx ztv=}Kr8nCA*6i03$Nb%+(-@-`u0KQ9AA&l^Yt_w}y~F&8eg0CcnZIiGwee4?K>vYO zkIt>UHGINrDnX<~osW7ATX2Ca8W=vVQBPh64r<6X??&0G6AJ=Sgvf0pm&jc7<~9|{ zI{5pqSNNlc90u0zYuR24%fQ!xxZ(m?e09)Z7~O5^$*iRY64mKyh(O^UJScpi(tA)SHr=)lK~cP{xlKt55Z@H=5%j{P-H-vGF1oi- zw-REdRc$6!{F;X-T2I5!zANwW_1_maZI6n@Cw)xW-V#cf=zfl%HbqbG8Y%`+0&f#k7z+*;d_p24BE?P7nEU|(Zsh$Njr?iUD1s{&R+GRGWMBmdFO~x+2!9T{LRCB~Gs@Z5 zMXuzrDNwP5>m=VOy@=%0imbT?2*{a-cqp)QDKtrz$&+f4LZA^QPId7sgg_9Zi)vrt z9L_JCxvIu1F#x9h{OP?Mngi};##^+vZ;Z=?YAs&^0j!;+bGz_;H0^Zml`JD>8*8O{ zAu6EoGpLiU)8%!^G~#*?Z2OefUw`Us(jbb(_QeEVhdTEz?L_oIF6~ElpmgSsX@cUM z{(nHIN$fUo(iw0;*u7{aOS9>f)6{ailKkXJBJV6Mg;-xa7|?Z+ZUZW;RIAOYncp%= z;5ea{x8891W^UGK2s-FA=>S6(N#<>AsUtSTXbS{j#GeL2hzaq!^wzyY!(J}cO^Iy1 z7Qh9n8T6cmA>n{)A$OdIVi>^DZ_~dlh(fuNH;s$GS9fv$A)^Ks|c` z>I3=XOH@5ToOr+3HAHOvqO(z%uasq{a@8~1!s{ExLkSp#j{w4~63sI5pwhI71hhRU z@!iU&TVtyh6!AL4CXv$N<*E0Dl3lM8xPIGSidTBf(f%!x#Udipie4oEExcFm@GN%t zpwZdAj9>H<`U4cEhu+u{LQPs#0&rV69^OwCXRd>K zeaA7w$pP@{WoynWAlFn1Dd=Vg?(R{Nd4lQ|3qy&@+HbnOx_zEOBI6}6jYd&Myo*K8`reXg%%DlHZT8aA~(=c53sDO|&HRR|p= zcBd@=>?|jLKmr_7Jj#9G&wb!rYmWAE=q_8gL+D=b+rzK6^(-fUp{*QdoWge23+h1# z7{;Y|_qkJLlY_=T8+N5=u&h`h1OxV@V35c^QOUhg1KuyxszcCctIz)%&FO(RgH0c2*^z>9Ld0-8hB)IFoe~MDG>y{mpQ*Nb?_2Ua~ zE7iVZ$juVFUVNx#IHj6RQ|~Jk+o#_k7F(jpe+rqx#^}>ZyBS9r4^>3+iP1e)dg?ec zkA!Afy{v&`#_`_34LJJiu@#u2g;iUvBXisUYRJtn@PMISO1-yX1dxJm8XP3^n^Jtr zBxp44RU|<80HLsUf&oePv`TrPBWQ8(;9v36CYS(Nl+>$sS2lPW8835z+-zwrZyu2+ z^=%?J!+v8W-j$K32;|}7;>X*-zWIc{+vzy z7}Ad%=UV>?>u0C`36e%LwJ_%oTD;Hes9)O-eCR;8-XAU%0Xh0u3L7j}>Lv77WkN!K zPLoR7z;S%@&u=@rNuOj{R+yHwiF)6^D*I0v+B!fDOc+gi%gu1?IG$$%G3S;4n~3^; zn~0K9m?kz{HQ@W_jT3F4Aq+o=i;E2x75|BOi_?q##GX0^5`0M4J+X4o2WT+BwSZmR z^`853OR7s`u>J#!J}q6x@@_e945^tP)|wBw|58u!&C&p7l3>}UQo@xkEK*qxS3as( zV)m%P)>iumx-f>YBE+|4vgOHc7PDR=^D z`Zb?W37dAo2N<+iDePCK1m3(rWB#hK&kF6)aMw3(p*epKY8E=)cwhCiPyjIZ^VM}) z)=z68v+u+F3y8!wSq9;{83}*#3C5W5=iQJ;roWUvZ>x7DCsXNfk96Yk;#d}dnS1AO=rH-ut~h3x9V(^m>%0Ih?h0@#FgO|n^b>`JTlh3Q?0sFLE6aJmX<>Yv{2U*CqoE#2x!cgN0-L>iSXm9jZp^3n&xVL1<6 zAi3y3G-qw4DhJ3{L}9!1E`I@HYzy!{&WTT>Nbe-lQ0rhGf!XzqNneSCDBFe1Rn`+_ z*eq5o#)c|-s;3Hx#3H=YHYN+ctpC)DtyWrtC>9bNmmNMq^M!RDfaEN6wL)O! z!C^auB0;C1i?4g8XaG*e4J0G%Kd#CWPWZN0y5HXIdGNt>ai$TlzU7liDOk~P(HJrC zLoa6Gi0$pJO+dub4%-Rw&_ldgO5o;EEse~yqNtIeOkj8R3D5jy&ZHg;z6VRuk>Bg2COw+;UPLg+U@q!flGaeg#58SsGY}8bar`|MF!4qZ!9%Qd6vJIP zV;1+!w?0E3EJXl+^?W2T#= zP)ci70RDfT{RYNmxU0P&h$7H#=7p7N^G>moj0hLt=RAM9cjwkoApM>`jdtifDg76O zU4BWYDlbY#jn-b+jgbU<7wO#{_nU}Jx9xd+pAGnm&M?f~=GL0_BnoE7zwavtNqRP8 zJP61uVFZ(3Bz&f^*P8Of8 z@FAOCy`w#Cj(Ne%+KS)2Gv?xD9`7@B^M@1{aORS{XgsmxH;H0bp;=wN?8(plu9sY|OK3XlD{wK1*4pt|{Lw^WOCmuXF z@~dtIGNsqOF?8T=ybvA1Q|lR=bD8B4i~*=orzIxO+B4a~G*kA<(Ev<_ILyCQJQlAz zEB-wFYjX<)|AAZIB4yRTMW}BDOhm)$Dw@uye-Ow@=0VHT8Zv_m&q!lOCKXAI#md;_tl^YQP*~h@Lv$QXKY5#RW2aABbobS$C zPwd)aDU$xXA>9D6?a_W7-ltpnAfveUu^V;`dRTo_D2>&Fn!m*60(?})jQ`ll-|PL`sQ z$Z_GzBKDlT^tiv!$C)djfRdui#2E!!v+i1@9W$~~d#&9T;t)E6mSswkaCSBPg7zN* zx(yMhF#y53Sfqm<<(H^+|1S5W!7=AQ$E!Fx+!!0=6nsN_$q*A#m7jmXbU>ET+Cwz% zqv4qhNVdh8zRAm?utZ`5kC1RFe(+%1#}bgM%$wuY1OgHk&;w}+`>nb>oJq~{0*b=D z^e*&(vm~=QeJQ}H8yT)#5!IK9wMFj9ZXS0h9(MEH)Xu3Oy6OZhXZt?jva{03&6a(UtYlmNgM867%eK2q%Dj#xS;|w_4oU=!1thE`|Wko zlj%$HqLoAx^E5xnwhopTGcD?SIc+CGO$IdZV90gMs1|`m0_@RDJk=1q`kBiqBW6G( zLOhhPv>+;Q{th%;#YWDAHAXO0o>c6SG3R>V3;XIp)tX}D=%_=-SHwD0DZRAD;yKqI zO!v=+qI8Of96T4#VQucLOco2R&tD_EgFm z2*Ng0#6Y)|=@|M}4_uRTUMM`VcK>__bNHALx93wo7jjnrjq4f_FhYCMvZUWr(B!$( z%>9z$6E?PO_Xt98#~hg?s;%w4qzx~p||!SS%c zLRTOaQyQHC5(ZrK&MHJb(I;<2&z;Qi-nRm!>S;zlV%akI8di@*gtmaa4fWPY+RM)Z zelJZd>EjODK4uBs3BlAeGW^y{%wJ2TWK%4b8M~2-S6gG=DV1g&TJT5E)lTG*!4uI1 z84rKV^GZvzq!A3t^6 z;h>M`q27gG5fn8VaPwtbFDisN1jQHU>fH34JgnePTQ?6g`o)mNDUV56XFM}a+_Q8{ zyV5$g{RD!u)jFp=C7<*4gI`-9Eex+vOm{c;SD(HOn&+Fl6P~lHrppA(t!EOJ^b446 zZmZO2YEdqm9k}gV_&vfdq{TLi!(vHW^Tr$*U3m3NC{M_2ur-RcU#ME(zJiZ>Un{Rt z(owJu#(i#1_Lu9!ub*~ky^ri`{1y;bUCM7{Spdj{AhAjoHo0rFoePtu>mh+w9v!If z0}wQ9wSMbajwwLe=k5+pi9RNuV8l#~7?9n%A?K%_5XI=iHKSag+lKgnvp2Qg%S&f& zd@0Sh!JK;K-49|dAGjB)i~XiJ0IC=R9$+r6YqFjNKI786IDG=+Nlc8t=QQVZM&vBN zHWk+-y$QiN_deGWHU)RwdGYX$X#l>0XYt#I_{tV|eTI*Co5UXJCZs#pke2_PCzMz| zax>ats(oyvR^9K0p7{T@OGN! zv_BB5=375$%be|f7W>V33Uwen{Nb!)I4Q0oFDdh1(`DUxlA;kruzYFRbtUG!>HLj8 z%k~De|CGXIihJ10C5?4xODu>#d2-uqyQZIn^|&$mQenWekCHKw#1^9jojJHGqR!OR z#f10y&GdX=eyJIz|8sx3^j*E4w!{`*qOwC>BzoZJ)Ym=SI!K1W+mp8HhJ#ljV`Z4` zixzQYk=t>>9^L4ok0K7B(dFsNoZyV)0O4{YW z<_Y)z--H@fOO%yAc;oTL)^vhoG$YpIJ+QglS`;V@mamj$Xh+=^py^a&g>>sAE7AA0 zQd6amj*RCO=u|`aLlD8l>m;Ez+cg!{_E<+d<9h^+80!=0MrmcU-_1XjYEqs*-G4&i z0(L#u5sG<_-*dbPI`S`^_5+Pv9F`92o(G6LntdX$sQm=~K{3Qi4^Pth)k@fT!ZMa3p?#`F=3Y7ek$kLGv$3D4sT#buK)O6M+cT6Vb8ac1<3=u^(gtHK7l1C3S{Qu4uZ+w25q=cb*8Pc?1?lC1T{w*%e6g2Yh< zR7oiF#AH4r+rHNynbwJxuykzoQdKJ_(;-`P#$4=gL?%L}3E0s0%H7#&iaez2oD6Q) zF-qPu4TQp)Df!!qJSwZ8C_QWZ{^2)sqq;3PZY!c}91K;$IJ{qdv_{DBe@m?Kr_vj< zB~Eh=T=;SKGd+|6zj?Abv&4Fo$AUJ`nt%e(1*&5=c|9++7kG?(A?O8RZ4oZy*QC+eo32e6^Tz2}IIG(5tO~q7L4pyh%t|c9s zk|r%~Z-d?>g?g)`e)T5fHAp68E+#z{(-j+x+M-qx#l=H6$I2nGNpIu)=$CsmUOaG(^48fizDX1`w(kyES}sWDbY|x zbM}�{zva-^^+9M$L~NY58SOyr{N-@{qUaz|@!nTR-hcv=0C8wKT10CqBz~OpV|p zjNgcVHz*~riCX3TSUoYqZ!`^|H{*}&Z=m|1iK7@#eGvRC20V!`VL<;OD#5KYDrF~@ z3tJ*&U)>ulFxo2kr`=fctJ^unl2VJn?qRk<@gbybI9D}7Zdh1ESm12_guM^NBs`-ZPUsslbW7O+tQsiq`iq;gl5jIYn{o3vSl?EsX z?rC^rSgaiCSnuOOy!jPmmd+>89OcbL+QjR(d>yJu92CQmSZmzCI^+k|AsnOnpQ(;{ zg7WU?`euJ7y{2L~>Yyt{o0%cfKom<4RyzVLu)1VBy0!>IA!}8x1A}^i{@Zar* z-#If2uHx**1mS4dos`2`lh|eoF|jTjE2=u3Rr^>dw|JS|<7`9))Q${`g7Qf@U`OxM zb@%s+nSm9q+@IBGnk%$8kA43o+AKRVR8sttEY9z~w#Rq(`P#-0{H7a^=FB18<)6|P zez$~{tF5zF*R$%b?Cs5bnS7dj-+14FFs!txnuTrOT2B$%x?KaxNM^`!*Yi6m=!cN< zSBI+>P%n~mU7yNMeMt?51F=ND=`V`6k*R*eb)62<_0C}`B@ct2yHboJ7(vwA1P1de z>SKS%cvX`Rl@W8fzdVXY+tXqXWD(_qAv3=_JhVUL3Mb8AJB$7;uvE;<7=aZ>krz&w# zOg%IW^B1NQT1pFdGglVto;MxOI{0D3(nKZQG67(UvjI!`4cdZ|5l6Sfq^0K=?iH7T zl3V&GwP@c?T#?>Q_t#a&%7cPJa_qu)3Pdk~!ii)OJ-G|%GRjp(2!M5VOFt=>mtMru zs&e)Oitdvo;hgaC@avgr{W#ENH>|!?eJG%VdJv1=1eU<#AE^56`df zR>IgLaME9FX&pSxl!ZyoUO{f-W=(cxqxQ+Q6wEQ<^P9SJrHxL@?{Ben$n#)D z*i)to{pH6Tyy-+#!aq-khAOZLR(sS91y!W>#dND`-$GpOr2puoms0KcGNJlOanF}2 zb+|o4(+RKYB?b}JPPLw!P~6a_a_vjU8HJX1kKrN z(=YV`b1@LTqSiSd3!M>Q!pY&OBFs>#hZ>AkC0r z7;&KS^13QSMBicYPg^OD7KrpFD6SPHeadaCxXxmKB&N&#Z!8#YFV5gk{47HLK)d*J zM@HU%vj7i3vaRy@I>~`ruYgia>v`_1RT%SDC%X{E_+`1LNhsD>@cB(nMdk-}dS>FH zj^NjAgy!vIxFO5}v$EHv!qm+@`V+3Jn zMta)DP%saGj-usa@Q87DUMm(Ica4M{rs7}V8YQ1^8(aK&kJklaUoJc>t!l>54UAMzo_wYw zIZwhcGd}2vY;GTZp$@Mn`8P@sP?HQgk2s5h8(QL$O2?fa#=AwE5Z?$}D0lAP!RrhIwcR9wv$077i}|9QbDV2h($_?S&Ym zsoO=dm}x8|e5sU_Y8g?J>o)CsnNaD3_@kJ@t71XqinH`+98Im4Tt_%P<6f9Y_lI*UmKa+CRY(;zAEyeJyoKg9^FUFX|Y0zGuhK$Jy7<3=d$dUJed z7~5GL7lj2!!v@7Y;v`G`*k+>QT>6$z(!i9GIpX`n+#hqs$ebv)0l)d*4qF>^Q=C*~V>=|8M3)ypLfm2-w3988u$e-&=Y~i2=zV z?KB0^eLrY>fdeEZ|3d@#H4D()Ucuh!FG=?0zy1XEsoNobrgP1W8WA^FCum^*LejM2 zuG0d&$%?Kxa`2=Ik&gPzupCS`zIYAR-&&|rL+aTQoQJd^jbZB$WNtazfJy(?$<+(T z*RM@TUPT3NbjXww5CU*7uO#4|PQbn8aF^3-a@gjaNTM$o1LkmoL&uHbPrr#n88I-i zz3;IkvGllad3IiM_~MZcT>y6K_BI5eKH&pqn3Ow{Y--`AQc|_iDH~37h%l24!hW;f zHNt^L4qa*_;WnrKnl$K7W}Khf*Ebn_feb_nAg$OfbY2CeqO5%jz{KG-6P_2ww|bI+ zEze;2#5;efSS3-}Wp4}Nyol2t0)0&481@Z($6r|;8^H9#oUbUnebo7Mf7Q~_{*O|K ztb2-SSSk=#L!1jF6dsSYeQZgmn)n>hU062HEkQzMXh{FzqW>#R>11migSW zS`-}BH?3zs>_^k0O|K~;w-$9e=T0s=xEO;h)xDfUg#9>K@!iOko|l;f znEn`Z@W@ZQsqW_aC>l%90BUD)Rq&MAefaY?>Ity93s9t7H|Y#Ec>m;ulj z;*$eK7#0_2eA9s%a_#NhgjI+qb3egtz*;6&dV| zK@PK}3k9x1+Ibi&hwog2&DRFVKQAcqdJ0}}Pr;NfKYG9IzxSz>VFhnT@8Y@0qs1dJ zEus4Vb#=0`F-EW{yPVGE9$`zBySXmeCaXU0pCozdoR|jTs8i2tpSNYak}IigvbfM> z?PxWfz~bK;IsOqjn$o{!Fkc2jiS>)sVMf3uS$;BH-E|~x`o5wNCh`e$kSQz6uH6%E zB1d5D%kf+$G0%m*@%!7v1n?W5_+Y`~*U^V*Ia}SM43QAGq|}F*BH!S#GNqbSkLjq1 zzUm;P40y{X@w3Q@zFGp`*ClgJEI%pq)=pw>*wc${KKJ+Ubcj6mYy9dj{D1YK2$Ez* z%rg$o*mEC?Q&mOsZt;S9e_ycm=(T*zi#hs8nR_UE0hWA_N=D9_pCxlizIzrjQ6O0Q z`Q0)?BAW-h*@?1Z>;oPlmgc}2vFQ8m|7XwnK=-h1!MW;2x-!u7`GuXG6#S-1+106T<FH>ayVW`0b-7e_-vEDEn#SK>&KnyPZ>V zmoT*)OPo|rY_1Ysn5|KlUFb+o!KRVTFL~C2PS4spN*j78Y&nky3b%&SBL0EpmqbuY zxdNmh_7u7|p=FFr2WW>9Yi;WjU01uNmUfs)!?kC9=bj`mCCqt@*isHoYlaVH#a(ZE z+kE9OD+IPl?H01Bs$Va!V8H=L`s5-U=f z_W#4wTgOH9Mcu=sASfj%r6}DXof0C_Fhe&Ch;(-e2uLa22uP9x|kWnTvHu5w_;yYyG)15=E5-F-~!BI6<;eJ!hz1*{f zE~O^fBq4CI7S30c`@T;a{x+#&5xF=mv1cZxXH58!6;`Oup(DH3&#*&{TKYd&nf}C- zL26Nl)iO=iA4Mrc3~)Q0EZpUpHzu~H?x_}u6d|ziR=BdfZGG+Q8m0M?UR=4`ldo3{ zs5oq7y+e(ICi1!e#wjL-tNwoD`8WPz<#(TGLI;Ur%(#fPfmVT{(Q{u_(qUM=wD1ov zkyg4ua-!TvQI#gn;%1-Z);I3G+BH?OvjaGH{C4rZ&O|HTP#AUFiQmshr6eG_j4jeU+y&|bT+oP0O&1%Qm}{qztaSISJ=8+fd<2TV7GWn|YVpA|yf$^c)xhs!nCrLxnjOEbJ_PrY z%bX1_VfwctCpCfhMl4FKberIv9xP{u=PiAonQY?>J9#^D9UZ}!B$Ln60xE`oN*II+ zPjoVljPn)$0(N)>pmRV!C8kHxFDc3Q62~e#Vh;uHoP9r=&zggPs)nc*ZFv@uuNQ(* zoJp;@2%}vuLuS4YM(vxx@t~4am(@q^Ej9ZA&K^OSlo91R{u21rg%$4tiR|-rwh|Nq z`bTaEYYrIf1NAzPr-c(8b7%h%Fm6xRH|z>@r$$`>c(W2rcJ-$uGDhbp6MJD!a5Min zb>z573YQ$&E3{c5MHd$E;`Xr{)^fpzmd3>J*@TjhoUBAJbo+~kfIuE~UbyB=TV}c> z!D?7sOQ->VcS>wg#f|8`{)D+1x}=sP9*6NF$CzYB67TblW9vQY6m8^*UzwlQ1Zk7+ zztWu;M+H{VY8qtXZyZZPxPw1YRdv$3l5{fD`MBQulvnhv7t+Xc9Dc0vj?dQ@)bzc< zRP(W^c!i_0_>q>ZOUwb=orz^ua2=Z+OQJ`>_DVO8gHf24R(I7U8n2NKvcL3|mNBI7 zwAC9+WpS{Wa%7}`zo^z5<0`4>s{ZawdVAZ1ETjF=w{Av{B-7n zzX|AS*r#LVPx}j@Q(sO2$Wv3gM6oED?ys!e6id8jkCEicZnBhEh6z61!&Ia|ENpuT zl{-&IZuXPuuRleR{M}hu<+0y5yVx?@Cogmc+kY)fiU_iXpys)!b(6ABV*)pDFEWX) zU7OpavnR!Uy29CS$7Uv_g$vCL@;{#`(yj)yUfH?_`i zTf9~YE#z0_&w_r_3_>w%_?6pq{=Jru;)_pHZ{v1uN|#XN>bA+{iek6Il=*40bCdPy zNu*2^dENQBhRe(aT^3_)xd2(Ew-go;?rYE5KCNcr#0vbTBv=HGCxgE=@MPcq$NiY7IR< z`$2xQ@PUwR-#VpYlZfT9<)0CO`Y@TdY0dMHl-Fu1!5_Jd0m1(vQ*B$Pq}Vpsl{L7$ z6J5LvSmqy06W8i)d7_44>6few$z#}?Ssk1a)$a9oADCreEgPL4&pE+sEjQ}u%HN@6 ze4KIZBQNGdQYg2csSGJYFJ&(qe-ETnp7Y`GUSULmmq=lMwH)l&hEC!}`65sF{%Vy) zv;5nnb^O)(3&Xb=rH9Qo2NVuH&m{$^lqitHEm##BRSh?|M+CCK3iyIAAs$HhaQ{VsLqF=6ZB& zo5uHtBvj^Qg937>i3EdC0!0X^9!-33E{f`NtGhe5X%Bp8)#826`l!ZiAbF!ir{==* z2A@sCd(93Drv-iRtsa*NS3*g-AxPw;F|Q$s&*2VbgVaeZ>_|f)T%$#gx)S}LtOwo` z#`r~|znnqB55AU$KVc6~cY4osx}Hp)D_dEwiq`jJ;%}R7q;` zXP27ai+o*giIQaDqONhCH`SFyA==t|Ul$5>ETfzqQO-pq|OyeLxQb`DH7r$0L_Ok#_ecq&dxGV|65+|Qd zu-!CiV<2{Da}!x+`gF%WCXIeJf>Nk@_OH?e=fD?vj0yI1mP2<+G=ie0hf!TYr%i*= zER;jzx*mfYBi3a3&G+f&PK#%kqH>+yDML{j8X_V-0p4jRf13A6b0C^MMClJW=_3B! z5BK6c<37XBvW0(oH7Y*y>qS}q;r+rl211SMNR-6`St#BuLzTYFwy}RJ842h`Dhqh2 z#w&8k{aiA4%fsO8(*D%~>7FB>4)r9g@;mx^0u2OIwR#BbBlxdbtN)7=p|_x%nM!Y> z7hd72vZ3oM?%W3F_jB$0tuiHW-LlF@<5NFODla6)AEk;cbYVv*ut0LOCH|`O)DuEXU(d^N*TMuSws_^F~Uz zV@m@?Q(8mK>LXrBSBLdW+h4ThKg!MIf z<*HHo&?M5)IOqoc-OOAi$+VG)$@?_lh2zS|j}WEK5`R;&t&1cZtCg6`$g)VjLCTCS z*Lz6wY4x4^lSQyRSA$XC!Ylu{5YxFi#qMRgKyQ74PrdrEt!;tD4DSaXxA*s=&I#GO z0%~6~TW&Uz?-xksxA*V24;?KzhT7WJdU*>xM0U0*0^BL(_@Kln1_&r1^3YHo7@xrC z)f3%K8abuxn31o~<8C%Q{^s248=hCqE9VAJjYYSmP>$~V9W(uE92`m8VLV|e*Vbh_ zWs+1HDjOt;&3W!!tYdpk19}lcTcNi8+B=TSk#;@CL)3xlk}YYA>QwpuJuNCJibSCRVF-h$tZjW+6jP&(i<>W)7D!$ z(D12i9@cZd*wTEE*EV;*5IMcr?NmP0=H=O_3O4EJG54QlB9$!dC=T>1v9eWD6#P#` z+OHWW|DDPch^usl|7}Cr>iOkn6L?9>U+TT%KQY`okG?Nk`Bv}OEBN|OWca3}3$W26 zQ~z->Yns&hQ(+bVD?sHgN!(4pM8C!^SvY3!6!$`4dh+m>^2NUGr{)XF9?|Qg8@|Mw zTE}7IXWbM#*ME$oCR=Ov5ARaZFZY?g{aJZ1e;*aICRx_urVzKx52{KY-t_^{!Zy*{ zZDB*lC&2OWN^TrKn#h~>!Y5D+nY?rPX&H$2@^nuU9(>D(k;}NH(LM>`(A5*Y5Db=O z`)48U6{H-U6Kr;XjeYIqF3hrPWO@uDRvG-AJy9uMBH+eN%T7sS9(F}irc95Ph0_=2 z^%k|>U}3m}ugd4rEe=*4{BMsHe=p4NB8!QTU=|>qdTek(7>h)MY=M-8GO4a!*pwiT z!YpN4lc4X>OC>qV8e|SF{)Xnq@h)?Cmz1tB1nq@7pW~_R8AP zpmZp!?^neyQX26Ap^?s+n*r+nX|!&p+p%4ifc2jz0dCK^v9W9M`KNb5t8I+M*t!_a zo^~}P81NJBvts$i0z%!`WOT;pIlw}Nz|@9BRrP>DWLPS~l(GJ>!SRiB9W_V>{Q!+> zbrBb0cjOc7K`}`>s>Dt`kcqRm$AIgR1}iT#gLk*(50WhV8$yOaW@Rhm2C41S^dk-j z441%L>$mgjJ?SX5r9`m~5r{c2taxMrDH>(T#9qQ zwqEc*AVu~HsZgQh4e8TnG*vh^m4!pqr&Z4*C^{j!A8Aq_y+UU9~mE45#zsbxmCtj1?wfTq~qz_V$^kiPIX> zDCI3d`3w24-0KX7YyQcm1l;UiI?)JV~N+%emrPH-j7P8EFk{T$%4mm*x zar#fSq!w!LNB7Y>aHe91s25glzpqA02trlecczNb{a08aZwWgO5OqD2M|1f$I>r8Y4Uc z^+FwW-Rc`tOC2wB`nGb^zBkcNm<3{>?dTb~n-*$vzmv>YG+}BadDtVMZ!Q}I*2~hq zkBLh}Vz166^X93EJnw&^g{U%yuPGR5As9tMz)bvimMBtxi-bHU*5qH<7D)uR2}=*> zi4g@y)@c90CZL zBDf{wx9a~`In~^o4?s-Xa(n(*{0DAi8CDPZ_TX=7y*KO%$XNa@$mdw+o+PJVA{KhY zLemXXh}go=O#LU_Rbf79RNGiQG>w$O+t_y%y}R-tp4)_8D%du#(X*t|6*Ud61}V!c zN!JzCCaPQ@OCJ2obH4}1sxCIBWl*G@lIwGE$Ukdqr5s4SL!46jfx(smf$I`gIw20`VxJi8!6SJR6 zWXBo0+Pdt&EFm~hFf4+N?GBAIp~;Dk9>3<&VU-OXX;BYZt>(*Y;Z*Ft-jpF=o{DNEjh(Z-67hSlw|G>xV3jGumm zJ*Mu@=Mkb~`&GjnD#d<1#Xrn-@JIw~PS5VuV&sJ}vs@{~ub^gqJcjUv<%cVU>kB?6 zMQsfG{SEHmzdj9N;cmi~K7Z}60NkI8yDZxdvL(d6dw9rZ2wmN8*P(>04!qTcepu~5 z)PQ+5=Yvtayo-H+&Ej0Y8NQju%{ormY2q4U-ZI@L8n{CXV@8ri zQNbii@t2K*vzh-R=M5rb;U8eczp}}6nPv&~BzOn?$k~o!zRbZR44rU~&L(lx*dg&| zD^k&CpnCIcc5~B}+oKmlSl0MV^<}GI1L=?=V5#4aF^Gy^dpL^|d!*5qKxhe9RhP75 z->amaHf^M66|g!l(2mKmNr zQJd^S6+$g(Rbwi?G2KbdFz4Er5C(P_dbUb`yd&wEgj9n)OWM?j-u@EK9wP0N{%Y;W zp&n^@^lgIk27%)!zP8L}8(Fdy1Hk6XA(T5y)E2tKB^hV|TsA_OxCIrBwGmGn7>20U zt2}-R77uL};371ucFNXnEb})g6~q5dB@<9iDPY?C&w@SDI`LYFeBW7;zMEH ziBv9;!hkP0h7Li8AYLaAMX4E&XY2Tz5U~xcj~{^9JFJAGw5^IpE%KLwVI;uFKzb#^ z|BOiAoU;Hi|4Y6L3nYBm)Q3A9Kl;Y1SW$fU6YDoDjlAi?H@4+~7^%FPS_TXyKU)LX zSb&@`U7=MmzU!4n`|15({pF8V^;0PbXEuze{DVBFIaDzk`2BO>2oBs4J7x^_X_Z4S zPK0QII3#oISMZMy!!NH}cT+c7fP7xVM1a#{p>KYyjfhlFd*hgNAI|MquD5&bu^Wf? zT4(0l5I$GmPdEf6!u)@>XJ`M>B2ML63a!2GzP% z45}4Y&Zd@Edj8!wF4947P&GjS^NF8AtF`@lE^ux}cOTaig>Tnou{^jp;D6R~CO9NM z5Vg%&N`QJmc8ckE3affW-V}Qc?v!NQ?u#6Ul1VKt=`5pt*48k^)H2pYw!de##b%we>22Ju7tqwGN!R`rG9#q`(&$^7`4Z7NB{yI6j`0LNMzMry zZQ`sRTkQs`X%!4I%h*5S&7t!L(!N?kqMOVC2>2}Fq? z4@cM7*_0v+=0dhM@P17C;8oTwr3JP3T9-RQYUti=4B*LobIHQ8CLD_u=xgN)VV-+$C;`O0EE*WHykw>7hFE@*e~pa0T{l{ z$9<-koCkGD!gnbA3*9({Om)5rQ~uLetZ$Wrs6X5JhDBW`{lv=S?0N*rS7aBjwdsEm z4o?^!p#)eEr`c?Q0A?c^IS8jm;Ek8#z=5vH;*|rC(h<~OPgY(Jl{chZJ=WP%w7qir z9>o(8FIiHH+bR524a1mRX>K`F)Y+NJM$7V#@X9^pIbn4pp7}sI)mX-fB?lS7y6n{S z&$mh1}T&jjV@fSwWEYWxi; zF`>6e4j>O(36&BQ988Qg{<6yNIt;m+*>jBpFbz+oud|4(NA@$az|ww3h8khD_q$kN z%}7Qhkx%lL!XkvBK0F|zm1m0wFhQI3YHM~dEzSiO#b4&G+)BrpSF7c&&+NR<6l9gG zrK}aC_yW*DjI7m}>L1W}gli}boD}DRa=Asot}(MR_pf*4{Y*O%s6@ji>j1obCgJ>t zn!*PAX8j#vX&i+r-*|xHhu8y%`bWOSIjx=!C%A}<;=P3XyZ=`LxcBWg_JWQVSBCdS z#Bg-1VALU0>{WXktyg*rXM&4{FLSp`&==U)Hol7~M&p967Az1xnI$v>sUbJ(B*0e% zL70AI`28=M<+%MQ{Yju&w8~|yQZMq}#&mO5DjIM7^{gHlXnmRc@E+N1A=FV(^x_#H zpz=-<53=Fd|2f@ug|}a^=bBKgOGDu_ISx^Xh=3r-MoSQxmj(ylh@u@WcGYj*kAFWX z_VLTyvi+*`7TC>LRXSoH!iQ5CIAj93p%$nIP|eis$JIAndHSwwRwj?Xm7r5(?B2Zt zQq=>yfY!h27;73}(E#v{^L-!;Ug1&;BKt|Al7c?LG}gez^ItDi{{w`BCulvW{Q%*| z0(&Orn)ytww4($Q17#5l-+U(FU>#P$J=m$)}U6+nJ{yxwDep&cD5VS z2PY|==S65;S6=eP$uwndX^fN~RqoVy+kH zp93&oAL%}Ipa?zX9swoX^G$Y=YxlFG2qTf-AW>&oL4qGMkn6$*vQ*uBS8FY}|Hu6j zh!qs$$LHT^AAFQmaKc`8N-GCy#HU*AcPPO{4pzV!dkNYaXhj7YRAWzpb6g4B_BZnp z`UFPgaKRvt3_H+gk$x&@o{K46^?JGUt@uYk%9(}6F_0iPd_J20&;oH!0~BdJ(B!0P zX&Y(bP#^;dm7RW9GnP8Q%CP&^gxiC7*CbuH-rToY+u5#6nsC%EJ4y-QPU#!vFobnKT20s0+Ao#_c`7b^#f7j1JBIkd+QTw#_ve~< zf9czaXi|0d6NDNEWA+hws^)PECbx1fO13Cj(^|QgRBBw^#9mVih-#qU@DMd&+NmUy zS*Nf=?p-ZbtwdY{_DpU5hup?pXEu}YZDpXu5FQXG3~4CEXn+%~n3=!8+>SHuBhUt* zvIqzo@;KW@J2RPnQDAcb#HPY*X`A}|(34`CJ2U?vb}Q8B|LPMCbI;WLcMM$vG^u%b zJvDS+^+3}i@Ho<>;$O%`Ou9Qr|EuMD-7KiD$myU{scQm}u48l^7G;t zLPYh18Uw2I)f_B_8Q6tc@YG2^Ib`zq@N}7eR!&=B!|`0xQK1D0J?sb!+L~EhyG7uN z3QcLqWeB!RNFTojDLse(1vE)i!o31)6+oUeSb1-5RX3f#>yE+BqNy2r^M>U@oAtz=o?>P@Iv=ByrRo&X zcD7g1K%TKk)^SjL8PMP4>RKxU(HozAjTOIHZ9jqhzdQQL|Dg%h@-xq-K5E2IqTee$gHV0}Y+o-S!k6%Lh?OBPjH{_0LUjU6*+o{rKWbFlJAu`%`b7!7VZZj8 zi?MvXBFU*&2tV?&>`w-d_<>ZudgmtQDajSA4pD<#7c?pksTD z|3U((<5y)e0vP@bQTUND0rTHTm(*I!zv8bo1uM!`UQbfXJfp`){YaEjmNQR)LudIV zzP`q~lD0V1w4!mzx!DP;^UNzY2s0u0?!*!Vhh)&W$4u6nfoE1o&=WlTAt_5Z_XbIg zkS-g|?<)g)euqPBa_*Z6Q%`$g!f^$f+sqmE7C>gO73B{P+dTJGW_VItm!HUNHU8Q} zzCI{R8~ZK)vm8){=Sh+KpRRQ7Rlbk5Iu(qPr3L{m26?0O_q;bc#WW~8I9nA#4_z$Q zuGNnAU&N8yRejzrApX4lt~I)gb!@|=;}}uvYCX7p`CoD?_*Xm$&7J?9ZaC%0gP;Cg zJ-jg`CMHwP*Fmqb-Bq_HDhbh1c}9jeytDLi=}X{i$X;$$Sl`utjq~nM6H~{_XSIX1 zsN4^~WjiAmY8J(PupIv^S5?cwz$G_$ck_ZwD3ZHBey#VUu{3P=W75mbCxfyMC#jot zwt*&6{LNq*i@Z6UZ~d`gtHlaK=#cJ*l%}&fiGUX@v~TpPiTFx13$l$l@7L>Z4VPcK zk2s}!;f3#56y73Fu}DZ)X{aX;nrf;0Vu|ayJ9^UbRY-v(W>BL;`nGTq+wjJv(Go|X{qwThai?6b4TBs{0nRRZGxj)? zS$tn>cBm$l<0E|$P8@LuXAL9ixEi!hDTS0cohe0OvzKI33N(|}qUZEas8_Hs>k(8s zDUxgT>(@=ty6F(4Ihxx#Pw$q>j=UF)iqm%y@2ybnZ;^0~Bb6!aPzlYk3`Xf}rSsoZ zPFD$bW~EBk6V?~yO5@Xs9e=OVtK8W7C^p7_2vVS8bT5(7XegLr;UD5d?Is^9Y< zL-biCEUGkcxYB5;(X#}lmw2JVq4iYm+$OCR#b-=K!~V3iR^oNfAxwYG1(oWrG`31t zPH+R|th9n|O)+9wm_wP=cYaTh1`EIut2gn(|CLaBCmENApMKn0kFG!QBJ0x&^R%UR z^GYVbTrX!B*t*KbGClX!djHjRyHm3~hfo$q?a}x4osamp9HZv;rpaU~l)B%g{6v2G znVgnvsPn#0X^NRg zJa#l`S%(STDVK4}YD6p1II+8ZZVBt;ctth6*Wb$Y5RoA4x=uOI9{oc2?{>OTnp!GfberQdh?t3lhMdy2xH1Y3$Q%hSu)IB z(Ra>uo!z+i;{IHSWkB;5?I_Ywl0R!-w}H1G(|@Ab2>hHQNTdE1Re8_fq{!>U=Vmd1 zZ;K-jm=l$3I0%P#q=KjAp7=>D4T15+(Cp9dG?Z1W1eJ`FVRrefC+TGWp1XP}zEO4i z$prCW@2{Nbco>Ytw<(>Wy@QP+SqVmhg5N|vmG|T8;kwBxIrAXmI_PsJEo6V#eZiDr zqM)_oKYIL)=&C`lK3XvlO`r@bTjX=k&dXumdw57Mm-Re;ZxX*^O8vVNQFTx&rvYx>oRLYhN zLRiLMmjs1NC(^(nhOSF50=v=G1>hr*s6o9eQCsruCTU;GW8QOpz{_uh_#m(W!!dxy$^n$ z5wj{Q1Z$_&J%#rNFvx~rde+oaz!H$@G|ClS)s|%g2U_iakV;eGDj|8&+Bi7&(2H>= z{N7>w%QP>iokU~zv7J*K*}5_z7M4A6VpV}Pg+b%NZKv5oZxVg%rtXk7`)!to$DY=X zP5BVZalf@3rqx6gzJmr;=WqXt-FQ;GExfI)o-Hl;?kcRc=y^t}m0%Pso>IBuB+@tN zfaxi#Rx7rbHqr?B1Xu`YMetf%db^5E4r31$Z$X#J#z#BS~4A z?+JQ#y>?s&5-t)J&8?bI;;ut~yKKdRRr?&|hpJ4c@vX|z3&Z?&h84L2rwKvSPcp6o>WS-?Iw9a=-Td}g+ZU=4m9D_+J1b2hz=bi31qUDhf zWx6o7v~h#9e*F_9_UObW!i!^hr35|=kePl&yh0&*p1~puvnl#ZaI>4&N`zAO%g{x1 z{Pho(B3rY`qDdl}LJBY?BTr#dHn`Pco)UN0pIJh*uFHw4Pgv-i>3TR@eCa+mKez+| zxS)nx{kI_VqTC+hj<1#4D}Co34A>Gm4#U+pI)ERUHQ`q@%*D(r9KjMUF6Upwwz}-v z3t@9vb|T<55ez}Tbbq64W9~|8kQLJ#gV`~xc>gyp$^`W)cYh<1+)T>Z4xb{AjXs3q z;nd?R-1aAhEX+2r?ds19HyT@+D<`QkQ)O`GGM8KLPF2b=!7phYtLqUEQQRU|6qP%i zawOO*JH6t>cQ?t^EJfU*is?hBw!vNw(O|z3guJKZfOCHg*uTz22MO@q4|iwn+n`{* zqNWqG3hD;yZSAbpnXgzT{;ylj8GJ2t>WLlQ;lvDzrQ(pgtbUEQfRj*jG$GfE%;@(< zzI1jtXOKrtBG(NqgFC@|eLCTk{_KGK z2c=f1kxLKrveRazD*F%NOEmvutZsr9<>M@dK08fqk*_2(xZxPtf*NtmGNnergJzE( z>^c+RTr#HG>ad!VLLZhIRx`C=h~gP3R%uZ2QTA07_Y;KdOfx*kXl`hwFH0PZ!MXQf zC3*hxDBweeFbt%6GLU-Wxb8zDNsOA?E6O!|#xlAEYhKsP*2f)&ay%t{OrhZANAsZZ zP2-a(LHzUuYaZX~J|9&n=ttmKTRyoEBjT@{p^rj}<=a9UQqK)h&a@LgvNg2tfBy4* z)@{ez1B#`no%KiuSq;>u2AOmCOmQb;d2sJg*rzDuj;RatT-Ewht` zOr3OGjGvG{^{ircJnZ#~ZcXSUBs5SC773m#Uh(Ms*fMR9-4s1Z@}LO}2kcndG!RI3 ze%0y+Suo|-Hj*;MNqTtvt$2F=h}me7H2e)IEBtF~o0BFGUv`b9g+V8Ou8eyC4#WEu zoFKLL%$N#|KH=E-GWkwMxeVsWvy8=fu;U(NVTgdD_5kgW&*{!jx3G?e)}vCJ7rzVP z#DR;QpX-JPmET34JfKuBkE3pA4+7dw^BjjFa_|#LeXZnbzj*t!0eylTtz~rkE0ykP zIi&lLX4YexrDs1wDrAk`^w8r!8EV_nepaZ4W~0`bZD&74AEsbl!O~YOF6E1(n~SrE zqZE57zbRYw>!calIv5cVUQJn6a)EfluMpYT5$!d!REFW!!6NcE7em*V6na@T^GnMX zrvaij*c8%UyseuI?1deIvCff45T^J+t@$E=O4-JcG2YV~;g;S|*slBR#fm|E-S33V6ZOcT8v(xrTdKEw5_Qc-qRZa5G` zE8~i!6HCfU)sJjp2)5?0BxRfj2I*LZE za$wfr2kinbUR|alg|*6lY^ih7So+W(!8)yjR0*mYi7$_b8rA)4AXC_Pe@>uK<#+o`jYt)Lele*v3UYZb%d*2)UDIQB7mtQf9)U2k)q zS$xG)N=?=F^;RYPiO@a@p(}H(YhdPhSP0IBgLA=H5@^RmJcYMf*smg4Hb`~a+jqi2 zPXF@;daGiFsT;*%s*{#S&?hdcZuH|tacG;i5LEaSo#xLAqEZqC$fs>&A?_E~Ag3zF z6&$Vm?PsqnCyYN?v;CB<^$X*nFclkkNBVJTa1c{I^PWlA@69}MsY7WpLZ-MULicR; z4)+gd3p>Z@e7@$kz39(B>AhhL`EV|I?I7~|*sh`V5?bplj^9!}FUQL4O1q zn>WKO#!l!WQ%ClmK$@ZxY+!@zaU(tR7KV?j5Rcyl_~LeWk)dsW#36Yvc{0as!|3|@ zjM!xu(WH_V=K71;Jnl08os2HxU<2euNN@%K960_V5Ae+jx%zPEv}TRX8MH)PYyxa* zszTrSQ;+tJRNLg|1yNdOZuG}%w!5`pcAsA)z5uLPs+#r+pm$T+D*^f@9FmnIxeY7QERB%{fq(_C^)|D z?B_+9c>HREie@h32d|(wK_|RL|N!L;XZtaZDYNn{A5PZC@%kZZ0V}P&jHr8BDLO zJ!O4N=w7pW2yA%?Oxc3>xjHg1eq$C!&;8JkOlAK>@(q% z+co~do$J$0gUN)OKQ9Comv{}$mrlCg*c7DE{Wv%<*HYgo1QgU`g<_TWPpdv-DPsx)E7dwg%y!Nq@cI#hAuZ>CK2>gD&{+szJ@&2R z|4C>iqt=F(jP>cQ<1(Jo?V+Rv6H8_%WA0sI4i1%1Ecl#%te1tI-em}-%hd9i$mJY2 z5pIUejB6T+q4LUMfM6Y~*PrdY#^X01b|pxNi4`e1jeqGk>{ZCUtBG+pE+1{nmGtVo zIcyo~iXdO~8_~GA@1|xkyWQKK9&i;_LYISkA)*d%^2eK@|A;0bV^d#F z&ZO->EBh_59D3qKV4@u#_r{j*)YAV>H~4V<4-kBgiisKGQ3lHcWYv|N1lBzUQw6sB zjn==ZlZY;0k+=9oHT%(8F3Mf=UV@hwdG6&-pALy-oFLQs4QI=6!#=aVFrFF7kqdp3 z&A1rpO}QDRJ2QzxQ4GgUyJP!7Si7j_A1QY4h9h$J`(8ABJQO^{OH1*G&wjl8QQ=i5 zy5v@?r>lOG{UOXnN1YgJV)u37?Yrd_ulGNHWG0bIlkQ@52X^&guWb_^Q9X(zV6 z3Xj~z*BJTbXzO(D_)c}-I*LbL7XzDa^G<}!+|UI0lXQG9+^aY& zvDuX)Rbw+hm=+mL?K@Wj*mL+wxyAt(u&OZaIN46-=*Kw+=$c*rd>sg@GXKA;m0dE7 zZCU#>f?4ESh!Yq8MagCi40XJfj3e^TpFq>tR?Mx`Qg1FQh6Jl0pz&IAp8_bAgDB+t zGjY}_lLfXnWJgQ|W8%{O-wLNc&Z)BpcK4Bk64lR+25vM1FY*t$&o6!>^6$$$HtpEd z__ZkqF_q#5a!7>>U8^p)qqE&Rw&|u@ho@Ut zns-flbhjCav2c@`qVBDO&E6S$mqoMt8&$6L(|g79<^wA+*SW>JI)!fQi?iCD1KxQN z-<#=jYZ%YYYXOcFj99K^@AABEZ>8!uRtbHr9gAfo6&titHpb;T!?Z}ww7!ay2(heH zXsy(8cir5&6{vD??KB_k5vtKa0AV3-UQwX~$A}g5sV#D8epPul1k5^Fg$6gHDadgP z3-m;PZiEGQcK*)qXxB&04^}VEi`Lv!*;ed(_wEQiDO(-9aPHo}IOk0h$vChXoj#sS zc}?q?>SDWf;YCg=&*J$Ymh0S`gL;t}REhDRci+jF0u6{v<|z1jx<4Q?iD0K(e>2XB zB&fxxW#5aL1sf#}@Iv{&*HsL~&<=qN)#pUVe6#*5x~4jYun*4bP1gFe+ta1|hSAsb zr1^kJN7PGJi9W)f zJu-Gs`Gb(`)!NKV9{k(U<4*!1rzRP~i{3L~*h)egPtLyB&aMWP+c*@QB*){C6 zSKC#dqM`Tq=&Gg8Wz`L@z~#2vUr1BBr^jFGc~Onanu1BN^rn*6?FTk73Mb2MGjz*_ zw4U(|u$>!2t~L0N+V`nmPcPt6b^?zw@z#g#^B1;!rGgO;w2nrzj0DLCYQ~bt;>(vt zPlUMXy~vXB%TrZg88>_?^x2|#uE7`RuTOhQnfmxN0(qKCWQbjfNws-DS zA_c*}bzF8l4$n5G<|jDE$4#87o9<1kJlN(B<-7%`JWkxyFaK1Q&Hmlqw-zL~+v&58 zKG$t%Fi5|#;U!r+D1tQNUR)*)R+(_VlD!vp;E`bhAd0QCaR-oYqjfCIv$UV>{)*xI z0JcL0?7ARe%4}e#h|dgnjtzA&i;lz6;`}y7O;@UVzJaByWZO`ph3$Rqkc_SItK?w% zE;T9o&ZF8v%@tLV(suO1mbuAH+W94i#1eaMrD;s*0*0r<+-3@}y?2OeJ@V3tgQ0|h zEx%qi=`C+wS!_iZzLSn}`Airh^0f%@XGHmG{Np zt=;=Bq?h*U{LKAq{d-XjS;-zu3C=CaWH1yzPB)uyWy&lgfcaY!pFL?Xx_9r#wD0o_ zFABCe0hDeOApsm;oC!-9C}=s-1}Z9~!5TC}Xeu^e3DBvWDKRU@`@SDU-qmlM?#9X2oVmGrP5= zFBqFv?m_=VG~iEG(d%4mSWUOaVTj$ca-(7X>oF(dCl%*aUk3`kPsVzTan#onfcbs& zSD$~#ANkFSVtEa~{tc>A*#$n|v2*yx$>*A4vrNuc#pU_ErouHLzFH$1O)8#?k44V8 zuv~5swBIjj_PO3q%&9!Tq_nLpiAirB6WHEP{%gJd_TqF)uFH$mujji7-*mOJm+8AM z2>iQu3VhO0=^$hGMkwaOdDdI#W^{J;Oj<)Oq}qA!T)mW9sVN8U-`bb!=tLKzPcGt4 zEw2%;s|+f9NzpnL$_sRL)bslgHU*Y8!1cX=GLlKeVFriVN&F-DRV%Jv{Ly1vA~Osl zw38o4bDstA>XO#_ld6UskKm1~(*45dy0J*_NKE|`k%8g)7NLc*qRlD2NK?_M())S6 zu4ds&t616YgKD42@%zJrOK%ZThu3ubv!>1IHRqLH^WbIDWkRzn{6^vZ*`v@ANrwxH8^*uw&d5yvv= zC0-7}GE3lgT`d}ma#=UF@OFLU#<88%x!ZLsShSewKs4V!yihE!dfZ4{SP}Jh1El?H zAihNL@H%j`pSKc`C%f6WK)RC$VOmMg@P@hl<)jlyPT;De?$NAxFxj#RA zwBkzZg;Rqw6dP_a91r^_;^LSvUvu4YU|GccBWenR;dAGSqj+yKFP9v6>NIO{a%rR( z53QWy@=(v~89=t@0vlHT;l%Ds!>_GzO)1)|%(Nf)C2en8v0xH?!Z=jkprjlR4_rZadcSl zHsB*$!==*0EGNQB@eKZ0947ma9X(sH4Ir|2!3dNS+0h|xYRc(|*PDcI_ZMs4Ijn;k zA5dmbFQ(gGf`a**=|3zrj!{UFPd2kWP=N%97DRSL!$H&6fCY(V$uX<%Fmw#FFvD)o z>y`Rxv4r_Jy2#>IzXLtc^x?!dsl7WD=>~pe@df-HI32fU{|A1=m&ALQaBM+nSc{pI z6cs>TmQuNh>eQqzo`eIQ(@HP}Myn>BcEH-cit^WrSh3kX`c=|kEDN9uHG=60C#;Oi#a1@F!m8($M`{&D2-X`-((s63bAv_BeLckH~MAGBX3`QL#w8{ zZZbULQ?~yyB>MJX)hrY=Nk4atod1aYyPgLfmt~1DQ1d=^&rXl8+G?6Bo>j+85I&h> zC1%bR)%`^7oOk3zkQjsVnALQ3@p-~$Y}^^-YA-86>A}-SOX3>%H9SqI@34tk4BI}U zZ_k-34jW}Jg(-c_y}e^o7gA_OD#e-D*4sG}`nEtl3@hcbMb!TM>9BKIKr7=jo1*`w zL3gt~?WNDWMge7DA{Ya!x~xK`g?bb74~WO#av2|H9t@K#Jfm*X z?;f38WG_vLwdMBEJhGZMijsZhd-3VCS7&Ieh*`a_OGE5kmkGV(%GJAvpptadtKo%4 zEiy~GP_0GYtpDBVn*6)vez74FbNyTJzG9jXhvGRiTSKyDWlDedAf%+ES=mw#YEr#aH|}#mhuGjxnCY2w^fm+x3Ug0`70=gJD%||64DM zpV9r)!#Yye`uUJZuC&gbI*_-QEX+{A)HE&*JXi!j%RNn3({+9LOZx){wj=T-)TM5q zxA0N)Rn$X&KrlM7LXkW@bt4Oa(DN#-pauS6jN1t_q0o-8eSW}Bv6N-8(jkgcnG5{N zG0G+Cu3ka`LS>CUp8{~7O!fb3>@9=h>Vj@zBuIdu0fJj_x8RcC?ml=1g1ZwW1a}!+ z0>Rx~28Tfs+}+(m(2#q```quVTXlcj`9m?qFz1}z-FtPf)xCT81Jj^#P)eW4B(n>4 z7t{6EgBz(xcsu=?wsg-bfRguVButRIlKGGsULfpffoAi{DFgzBTc$Fs0H#;C`Jf(1SE% z6>bd=&*hgU5`(PnK5&{B#odmT&Ox|JBn0Kx(INA+%!-*OU6 zP2fLs&tIZ}r-CR|V>ZA>Ob^t>KK_|YspByXK`lZILLvs~PErfUmFV0e;Cxo!*r`?- zSD7_Wp4o>|Nwml(p$E{8^(-rXep+C_o`_~h36|f{p3*CSVs`jxs*FdE07fvv(Kp=T zR3qTC-;H0iN)QW14`*+{Y1aGNq1jTRcN_irZ#9?Prmt;D&r=LnZmXsd7qGlvaI#9V z)o){)Gl|mQ`ahHHtpH=oCHXJ3tebxQBPmeO3QUWgX%x)lxeNFaD1&1y(i^Tx#>85( z=+1^ddql*v9PI3;-)T}TPua7AiWk@`A?hWvvoz}RtX6u{D*@Gw1rDK2)y`sO%4@AU za&GOx_}US0{cqCQJC^HL(?>3wKUGg4IrI-Tf3Cf2QD@L77V)OHi=SmEo+?RBC6Dcm zqo|UuD8YD{w=7v(0n#Q`omun^2FN#E;@^9!0Q_nTq#+Q1npfezX7Hho!t&awD&)R? zW=R~=TlAB>pjp2W;vh=L0qV$dEI)L^&Lx5u4sL%cv#c;mFiN~Z_eEg&(ML;_#-dv# zrb_k2(Qt^lOMcFM#M;$F?xhMtQgc74spUw1vREl!gnBN_X+vGlPEe&29k?hQWxKM- zw>@oa!U4FL58Ld8SJ%>%dHzV`sCV0!n!-=z#WBC2xLN~nDY2m51_&g9Q0k8cRSoEK z!BH(RTcOk-4Hy&ER?^Ful|>(|-@A2pE+~)j&FEDok}wJGb^`Q_U z523AvZHrJj;TpKTP_eu<{ARp)B~#^j%eH2{=L!gzSnH*9Gbnf@z~+OIUs~n+tbY_K z{mW5J{ulG#dL){sfnh-ht{;b_>keK02RDcU@!KjkqFi%8bjrV;^3P$#X3EvqzUsXc z6AK7efpq}0x&&yAc&n5nn>anxkNjTSB0G1OXHXeQ$!wQo(Ngdp2w#{ZV(*B;EE72kgVGd~MOT|fN z`O5`V4!i+T6S!E@HQ*?E0Y^j}!i8Um_!qI9us|DhI{r0AHjSDywT{@+CvM~`KrtnT zlQv!%SdUfeR57#Q<<>4TckyP?Qvk?lF*q$x5v7sPQ+Vo#`gsA*BAvl*CCf=6cAqJl z6>=q^4nhLgMjUxfjK>t0!!?CXXwWd38`R>Nsh44a& z#Y%aY3O#r`B6w+B@AH(b5IL6J1bTkeqAcC9^5Sy;%$D-v*JRo$yxLCevkjOET!5~= zUG*{JJk{mVd$N0H=!`_&D!0*7twNA*?lW~%|1ls`?3<#_#%?#KpS`uXFbUH4`xme^ z+fY9APOfHGg76zAHEY9WdJt1p+IR{Yx6Z-&mp3Wl&Y~AYu~*Kyy~&U?Sjy2jIaVw@ z(x$WT^;@q&*Fw?oIk5`yTaj~bmVr?~X9AuA$ayiqyFwIXP@1#vYkd+V(ikieguaza z7qh-TZF#QG!; zjNV?=^9R>ljg2r7Q?gz!SkJU-88Uk^YeVz_I7NtMfarH$BT%CGqnh+rVK9n|xvjnp zRR{U_gPG&7TJp!M%goBrm_uEi7NlEDShN9TZJAe&SZS};S*Bl}3_tQB^#e2Jpyg5j zafINC(5@qiV>?>YJi35(Wi_I_9%UBUy7%FTAl(ICVPasQT}6x4W-iEB<1BWcHD=wz zFy=?`<|trDlSx2yPRJFG8HuUn8u*1#51P$oo7BWHvvZ4=CQ!>ca_h!bkk!XMJHsmU zc>s=N2t_%49V(%D2Ogs5D-@Cd`UXpB%z__fzJ|{j=~+GVIf9_CLWsA>)tI`Qf$5-9 zV{O3d6R1Yt-@f`8bsqUsl3>qUiIMsG3$vS8G!DEd>ub7?Tm47wBa;5;k5l+e1m55Z zfPH}gyd$GR>OS0@#=q?ll^)nrO{mwI%5lL?TNdO%?S8C~n@)o=j}Wm7uVAznTIf_#k>W?^?KuHhs{|&w_3052{?K zPg~nryrCYcMU-FYGXZQ(zWy>3A?aljLPlT#YC{Xh6lIO@w$XY~nlJvEyWdd`kVhf- zF@338WRA@kPgKCwn0waaG|94{SOrT(%I~n&9gNDpCjQfObQu(!xGk5c_lQGAU;RdP z4jcjq9U0!tw3LGIFS%HzM1v|ubymM23Xdtuj-EeJaeT82@kku$ZK(#aG^^iCY1@mZ z!Ywl*fiy*oL^-lXVB~e*y}y(#1H*=kAXCp0l&Lgt8a2ynuJsS=L|RPF4cY171^5D% zkFAIxl`&B18qo1FE$OpT105_ChGQ8X_}%*CEh7IFf)H7oi(Pi|ILp@^Hm;7!teIaX z?p*ob&M(LzvEjMC#x%X_&6l4o@9N{#tJc}|kAE&QE5MBIPsLKy*x3ED0n&9Vu1_6@ zFn+oAP81|1xP;*VQEZ{2jA&Kdj?J|iL(&ZmHU>pi^Al5TnVgNPY2A7je_1EB$zW2Z z+7U`2;$&egqha7|5YFJ~#o4WSv6S%vKA#Lr!gLhTGOF_N{5tg-hV&b0ReQr!>r{6? zkx+5(NI5TV)jGH#gG7MQK;LI^+@S+6?2waz8K?54*A9@B*Xo7Rk{7{Y_NbeLTk_)w ziC-9pD}Sk?Bz4M6F`L85bWspZq~Q9 zd=)SwJ(fg4==DI#iQAS#vroM4WnNEK+HEkcTEMkllF}Ha*ia*L2;l5LZjan3aJ0)V z=ZhOMwShx+4ipy{E;@N6Op~Eujjgh$+NZ#u`rdH2bf;JnNtKQ$HF%bfrx8PK~HNg(GVQ!`ZlYa~b#>Db z$q}aqv4)!IvSHpIKwDQl7vT(vCoJg9WVmNlMfL0yaMO$|n1I?c!@>~`;BYgU_z>2# zH{2VY!#n2V)?n84#UD{UC^K1l7JvfE57)wMc^<1~cz(DYX%*&_B^O!dwR!jgU_3Pt zkxKz8Ln6fS1&74fDXTg7{;3{AEsc-nt=!LDBc>P)P%KTNjIsV-wtG#L5I_tp_Y%iM zh0#P&8e&*6)^*ZlIjlTH=@vk z-0;h&1I2@PLZ#-0J87x4mYoFgO`|V?qThvM0#q?rBH(}Ui*2dWLS^(lK6DSQ3&Te* zf%UFpJI$yF=o65jjw0B}w{79bezX6F%rO~i&h+>;F}d78TM+PhP(0G}4JBeSAfYh_ zF2eT!oB1B0nR+*3iE_Hl9l_v{lx)^PQC5@f|YO zQmgD|z?I|}uz268XCAnz{{u|&Z_Xnwmy|N@lp3d#6hb65qB5i_O~VWcY|?&#@8C8t zHn}DK7WB|8sAu5fDm<8h=wMz@K@+1PdVc^<$;Se4(GX3y6y~TV4>ZZpPNlU@<}DVeJOwcm&X=o zzdcKhfnWj;gka+~P6d-QtG{;9RVzasbZW$*_hc_<>|r7G3p+3aX#mcng-vYamj$=> z-_eM}jhM@7)V~wjgnP+d(EnxxOhv_lz=(iQ zt1UxjtpOZUNXOZ{O;F4KJ<_BsLJWoxj-^S6s1wDqi{<{#?Nlx^bT#)}GjXK8jZW_S zf#T985KrWzNU&qzP7@H=YIks0j=F%T8v~mKqAp~g;IdaT9!4YOITws_Zy-bYW@e&P zn6am0#^@!TkVoOr&A3C|(KUyTCqlExc47`7d|?C>?79tOC_U)p-nn50}uWs)s$x|1xUV~xtG9RSL=$y?SiWP$+qGTZ2@m%%04 z?263MUhxjhGVmGDfpjTZ9*;&9W3suo$OaoTw1@Y`_TYVQ(zyNqv;e^eAZ_OtfQ)8c zP^(nt)q1-kIftz={Y%eDr`zE#;g@;O;Kd5KJWB|7W(@qS?G?T=fukUW)#`u3*0g>^3d8l?eZQNLp@qXpaWC z?jY)f7RJB);+PHAP=VNNJ;A?VEtoRn5*T($*%MSsijawOIqW=@Cdf@w8Wfpy6=)1s z0X;MCU;Y%!H?sH+xDPDnV!)Rgs%Qe7TLIy4Cx-(3O{4KcX7eEk>v#{%9Dt-jHS1Q% zDp_l|4_*T2WIFu9Ilo;<{#Acqiw&86B+c}@*!nzbPo{##oj@_idi~kud9w<-o<|XJ zgm^(45L5&?>R|L|8RHNP028Tw4Q&X|P5WK2RC}LiR)QIU&mmAV>h%n85v&cqqHuxl ztT(S7K9H^`{1ecjrG98HtHk;wt*ac-cKBO5Pp^*`N`w&m@{u18g`u3^UsFM< z#lZA)yyNAG(cMqi!r#vi$C1AXPKWBa5SB+Bs=&=!1O^KNOJeEV04&L8ff*8uZ;JSi zpmWN{PNd4Aq%x<21Y4VfI2la9N_^?6l)6ePx&`X3Iz&a!<0<&Ah zJCdn1;m-!lGHU?6imjlAF%XPo0(DA1bIrLDjL4_N7`g?tZo0p*V6IsSz%AcLweg=EZ-NTlgtG^%7uQ!Ri8x zmI*}N^L>omf}Nb5B5iyI59oLso$3Py4%8ZJvmP-Uy8U?33AC*()03YTXH)tscw~!9 z{zcjFU;v|ypn?2sEwl4gDDy%=LUE==WsGr zn1|OaJR9dwHL|Bm+(_T)p_i+3&o4eTYtX-XM**#C`p$>Fre|8ckS-fJ!mK}PY&Wpx z9pKGbm>BkDkx6nZp5?0mr6;#u5T~*Wu-BO3M0t_$l4$Ps#<}HThnZa&FCEHhL22pLatfUsAdbPjO0v_AG&{q#FJ!t7`ezze z1644GKmr^l4+AB)!K)8t{#+GClfd@-)YH3A3i|Lk-^RXsp5cmRt*_k)Bs;Sy-iz>T zfQl7MDcQe3z$g}w=c1i^o6{6Ey^7KT2HY(vvEbdZ0izV@{X_A9QWKe~HqG>|`o&hI z;4|sWc`h_X2IOKL@7JT=B(eP(Mz<5Yk-3&uW6~60dlpdd9K}8ht2d?r>`L8!)PqQF zy73RA_-e1wu3GBYZ_(Kqdrl+LxP1QELotzt(8N?u$j_}|-2_|-`2{)(9BMNvClX43 z;_ZcY;8NM=OFV8yR%RE-OtIwLiQZK6@Pb;JY2?ZkQIJ_Uzhj4WC%r|rH?dzZPw5utIx zgRs^+dK&|}`m@J(^E(R_nCKvWbk(GtTy=p7$;#)ym%7C^Mg95JQF@3O>w!klz(mwh zdx+j6V`x^#m|TGaapx_LKJSx0XtFuHb- z7+4)>+Ky(tf%8FpPKER9mXMNU0?TOO8%l+mxL}1j7_Uy8mlt>C;-qGxDInq zo*q6(b(V74Tfe!?I>J_Q=XVfL{Nfw9M!>^4z2OJx^1feH-g#HIP+m;l=}7H=So$JF ztaM7Mh0JpSU)f+E^2#a(wNDK1+z}r8?Niq8cZ}Vv^FC9x84Yj``Dui%l-v&T6p<22~(**U7 zT?f27pA+^U>AnzpYHYN{H49etfxs!17PSQlVtG?9PLU+v(>|rNY4RIxA`$v$oGN|> zy30NhT10S>%^R&d5hi0W>~)dj^%!T(C?12agH5o z8#PqkR+eUAj?#%Tn~PNQ6Kusiw>nx(>6H)w9nr)&@lywu)uw^r#dIza zYBY_*n1QIAfV+#(1uv@AoIk}jc!6$x6ks^ryRVoD$+3NIXAuc0dJ!Z3No%LN@upc4 zWt-Twj^?l2^&AJog8di<6BFvTJ55;<;vYV$3c@!6oV`+cF6VCCAVk!gh4~`+uBu|@fC|v z$29@Zt&of>T|s-9hBi`&y3HS6^79uBp?R+{{4&>~>y`xS47j!kF+-P^V56K0IuAxI z_5_eiYF4;x_bq#mPNOtL`NGb=j?SX7?H`^sq7@0fx1iR+$^*}Cx-eQje=uh9R;KlM z(E;_Am*1BT&89uh$pdnO$x1Fw+TGQ(c<#M6L?@vt!w14N`vju3r46!UPn;XVb)Pq7 zW)E>zyq|uqopoyrx@?PAiRjySnPr`+1Rjmb!ejCKe&Z4c!Oj}Ln4tw5|41GFQnG5p z54n!@94g{OV8-lN#U9~YvvhRcU&a(B3t`dsOaEhC|IoZI>VJJ=IZu&p=zsA?lzV=l z1uFCE3AT=6znpnm^B`@2j1!)WAU~;UHBg>|DDy$d;I7<`?5ff zwecLL$v8cVcSTnn?NTmqc;7?d9HL6A6Bboj`pF4o=r#zsEp#C5gtRGp^j56dDJZx= z6y7bByUQr3f(%!$YdkYnVl31tAhTQJE+D(u^0#jNqy&0wb2uX!8gz$ic zneN)~)iURTcd1-`g2YqR8wc>5_l!AJRmO20UQAkBK`m&f|0P`JW_2p;TO-Qss%c<2 zmH%Q?3ok)1!IrGjd)7&EUZXw{lya+r6c4T=`i*iI%VCqMisB|Cv#hT0ICkPpxa9>q z5ZUN@zg_R+Z1iUZI~eKsAC%GUUnSma%9YpVtm|T>hYP~hz#)gt+{xy{y57+RA&-W+ zHNyLw)$y04tmKzooaQeb!-?uh?Qi1PF@7&@eP8Jcs}FsCiqurm&-;p}l z?kMTfM4sKGpe*Tu$3KKZ*SlSppBiUd@x9_#5s!ne;*gffF~CJ5$V1a%w<4#RYWS*aF)li-a|BK1In=dv zld5HP3f%>Ki2kly_8+u)4|lRg?^DL~HkIL)8}E=Ri!;uO_}foNqcQ>(P9KFiluOYn zUkB_QG#lbxpYg9g*;kx3@~(FUNZ91#!fi1hkhl4=JjjCo&`|jzqi~A?7MW2x$Jo&) zI5`iH|C z{g+M%Q7EL9sh_;qnGmq|5L_5{ro+2WAX6dqb$-0#uUM(f&NtnjT6F^(-k{WO5np|AIgc<} zf@A0PUPF8vIH!h*-4k&sNDVIFJMXgGd#D!5Tsv5Pji&{y8wpF54;Gj6>Bl8r5+kM~ z3XeT~COj7*q_f@XZjIxnllh{s=@i)g`_s&$>iKoY!(W%DU2AQAUD1{S9r6@AfrAW= z+V`$Ld8@zKNAE{0px39q-?SY(*gIuAysPI#DX!1nW#dZt)e$L_h^R@TKGFi^*oo1o zrcVVwQn@p#ylSHD`LWNJTw}@9jf&15MCmaEeq=ER^1+F@H0#~POVXhrCFK{Yf0*Ru zL3^7-)S??W7dwX?4MaA2?mICTiy1vytVj4gi31~pnc><7>k0YTlNNe<1j2MD(Q1@& zi8p0EasJ``x9|5!^=5uLnSfbjs1IKx7ch>qyWHBAghJWih4_}&%ax-nRWR@5qdaDr zP~s395$5byM^p0TKY{KInn}!?vYc06TjI2LZ}=lN|J<2b(xR$u&^qcr*#O@NM**b{)olSyk%gLm8^ZN-o7r$pZYqYm9 z^<;X4(JCQaC_)#a_CORqx$`=k+;wEjk4BSB?w{sjy%@Jmd`1-GXsqt zl#{xCc*=czd>!P*<4wmx-WHm(HY!(9Ujf8ulIFoIB&`monm9ak_@%Ly>4-fJ*S$)P zZG|Z-ZISpAabVv%NO1F0%!N*>(;8>#mMc>ndbi7hV1y)WQ(bg+e_0Y>e(mjUoN$eldxb}gqC-l*H*SF9bCN6T zpMt4i;p-4&EOacv%^sH(Ti|mNLf7<}L7IU7n;^es99HDsJ_O1>b}P?6%9n&I{?S=o zT#i`Zx9dmLE0++W6oK~sh^eqy67AWH7=!Ot$xGCbYZ;O4un0<-)#%jjEP|~=_no=@ zeDvA-<1~0dDq8KdfvJl#!q| z{hkr~+jN~zTYUTX!6)@6dn?>@nqr-~V^!$F@k+ZD7nZ*g_%ptvc96S>cxMt9!unbx ziDgo(o=7;=UlML@^JAl`q7>CP2J@0hg7YH9-Lx@O@smak2)D43BW>NM_7XYFo?F2Npbze)G}cy^d$soorrH$ z>`haXB$1+g`PH8$WMS0y6r3+|m`h}K}0Lj&3M=+>C!F3LdmDZk0bc(of`X4ku=FkKS);CDBWDW;ci7`+4nVF2w6; zA-YasxSIm#9P$(T4bk0msErHl;IEr<=dS$mV?9TkrGA6qCJ}Trh+B<3pEBUU$7~mI zGQteuSC^)NT(I-|LbD=ClDd==2);!P~@QKh1?L`pG4=tqp=-`(*z`zKszoGxiJ&O+URpurI-wYjI*7 z6EP;hc=}9fPaplnhZ7$TL@c62bycbjX^L~E&@n>+%!9sP+2KB)RWiDzqrUVu7(QI? zl-#T4!0w|@K~mi2%O1b^&tm{cQS_=GfwE>?g?CRoGl(-LqP9s@k88^qJ{gXgb^FkL zn?vr^-NUl12FBY4Z9Za4cWTBKMUn6*cAjR-wwk}P4t`+E$WULSa{h*2dT-DfpH7}U zSO#mI-XK}RQj%W ze%NyCw`RWduJdJ|RYlg}YJYB`*Zj9IhHr0i7^6kRX0qPG`;#8m07p3f_&AG4?)(@P zVAHv1{-fTVE-wf7~^$bbag!UVAlLfp;Y`aR6h)B$X|=^`1t$aAmy zP6pNN+v@+!X9_H@kB2geu1dFzc!c*hLWwG$Fw7$b*2wl7o{C54G}iJU8Vc=VfS9AzAhLUw?-@j zQX{MOKlt>m4y@N~40Je$K5|fOz4_3Yb=sg3ZMsGlKYAOw(%fUhTTR!PMG-{{=kGL& zg_=17o#4+U5}@oCqJ?YuF?`}2}TKp3^bgLn5m97s6#am9FD%@>_C^F=9s3zlO zd4u2cy`N9Rl(TR*GB#d=#T=KXx3L=bju_m*a*RISo@8{ox3%R=RhrFA#<<|>6Ye5K zShWf6O)9W!{o#MP?7n382kN$E7*pdIX)5YPkHS+&^KgGp9_ih7(yr1#UC)N_!^5|0 z%X^`l)M4&Y#^&W_0!r{-dlme;4( zSbn^-lk?&(C^zo%+lDL-k2(Y=pFKGkH%0-S&>Rk{?eAV&A1>Bg;i(8uILA5=$+Vp` z8a$o%V$J<2?+pnJ^?JM*Tht^9YSO~{B(+J^ zp80t%L`8c`otR3zKDE5u;xgEVinsdFe*Q-~ufm?^>({F3pf8jRqgg^aH+7gxwO|Dq z1o^2N%#6_+viMp0f4^p4tK#DP&nrF|Fx~(CKC7CzoaBEm{k(vL zu>W55lJKcZ)u}^gf!s7btbt?BFWR#*LpiBtAnJ+E!c1YPx@A@8xy92g%W5cW~FM zaAO`(wdop5et%fzwp{wdrQ>S#(7o($7X(~!ERjEBW0migS3ajH7Na!1=gzW}EkCFw zX>C&|GF?1|*Y7u@jT?WFPYyglXYpL$DcfC(`QtIG{Oi(`Cg-WCSI(}|KFhE?L%$}9jUv1=wi?KQXErS%Cv8{n zz(b6bJ8;=3T^Qm$C%%JddS@9w5z$(y*7441-!oE{UK6>bOiYJFO0p0gfbCXlE0jle z-?jM+)BMs;YI2b?qO^q$(~G@{hv)Z2sj0Ix%lvdYXsD;cL)wR%OFgD$#yl^}QWW6Q z#kwFz2kCL{#hsPJhD|%yGHBQhlLm5gZV&Zaz%q$%-RHH+G=vRl76P|g@69)KNMg;* zw{R#-umd)4Av((a#;vdPs9SOmn!9g@fB`R$C_YTrUt<2dJX)&{CK?mf=bZVgohRCK z-DvpKVp~d~g99{zdzY--(9CF1PhtW|oPu;K&WyLNHJD@u%WTZvqy7jso-PujMmi<^ zez3+*W)CEdtM!L#a*u|!tf?K+s&TzFo+sQiMxJxv2$K33YH@U3Qy+BnS#?C*W50o=XcXadA61Q4`&IIdvJh* zgDa4ee6RU`bsT2~B^TgC7Sc0nSrWUIR;|5esf>4a#K5nSJseR7f@kd;8yhjlGJD#R zg757LcS``j1)~8UI-0AZc>a*c-^VM#L9QL(0K^J~xx48C7iQ|LZ|@TS`?mkrAIF=2 a;opTOy{D=n1+EtkPEJZ$vhst;m;VL7N5a4W literal 0 HcmV?d00001 diff --git a/doc/html/_me_mbot_d_c_motor_8h_source.html b/doc/html/_me_mbot_d_c_motor_8h_source.html new file mode 100644 index 00000000..bc8614cb --- /dev/null +++ b/doc/html/_me_mbot_d_c_motor_8h_source.html @@ -0,0 +1,145 @@ + + + + + + + +MakeBlock Drive Updated: src/MeMbotDCMotor.h Source File + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeMbotDCMotor.h
    +
    +
    +Go to the documentation of this file.
    1
    +
    38#ifndef MeMbotDCMotor_H
    +
    39#define MeMbotDCMotor_H
    +
    40
    +
    41#include <stdint.h>
    +
    42#include <stdbool.h>
    +
    43#include <Arduino.h>
    +
    44#include "MeConfig.h"
    +
    45
    +
    46#ifdef ME_PORT_DEFINED
    +
    47#include "MePort.h"
    +
    48#endif
    +
    49
    +
    50#ifdef ME_PORT_DEFINED
    +
    51#include "MeDCMotor.h"
    +
    52
    +
    +
    58class MBotDCMotor : public MeDCMotor
    +
    59{
    +
    60public:
    +
    67 MBotDCMotor(uint8_t port);
    +
    68
    +
    85 void move(int direction, int speed);
    +
    86};
    +
    +
    87#endif //ME_PORT_DEFINED
    +
    88#endif //MeMbotDCMotor_H
    +
    89
    +
    Configuration file of library.
    +
    Header for MeDCMotor.cpp module.
    +
    Header for MePort.cpp module.
    +
    Definition MeMbotDCMotor.h:59
    +
    void move(int direction, int speed)
    Definition MeMbotDCMotor.cpp:68
    +
    Driver for Me DC motor device.
    Definition MeDCMotor.h:64
    +
    +
    + + + + diff --git a/doc/html/_me_mega_pi_8h.html b/doc/html/_me_mega_pi_8h.html new file mode 100644 index 00000000..22e06bf7 --- /dev/null +++ b/doc/html/_me_mega_pi_8h.html @@ -0,0 +1,576 @@ + + + + + + + +MakeBlock Drive Updated: src/MeMegaPi.h File Reference + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    + +
    MeMegaPi.h File Reference
    +
    +
    + +

    Driver for MegaPi board. +More...

    +
    #include <Arduino.h>
    +#include "MeConfig.h"
    +#include "Me7SegmentDisplay.h"
    +#include "MeUltrasonicSensor.h"
    +#include "MeDCMotor.h"
    +#include "MeRGBLed.h"
    +#include "Me4Button.h"
    +#include "MePotentiometer.h"
    +#include "MeJoystick.h"
    +#include "MePIRMotionSensor.h"
    +#include "MeShutter.h"
    +#include "MeLineFollower.h"
    +#include "MeSoundSensor.h"
    +#include "MeLimitSwitch.h"
    +#include "MeLightSensor.h"
    +#include "MeSerial.h"
    +#include "MeBluetooth.h"
    +#include "MeWifi.h"
    +#include "MeTemperature.h"
    +#include "MeGyro.h"
    +#include "MeInfraredReceiver.h"
    +#include "MeCompass.h"
    +#include "MeUSBHost.h"
    +#include "MeTouchSensor.h"
    +#include "MeStepper.h"
    +#include "MeStepperOnBoard.h"
    +#include "MeEncoderMotor.h"
    +#include "MeEncoderNew.h"
    +#include "MeBuzzer.h"
    +#include "MeLEDMatrix.h"
    +#include "MeHumitureSensor.h"
    +#include "MeFlameSensor.h"
    +#include "MeGasSensor.h"
    +#include "MeEncoderOnBoard.h"
    +#include "MeMegaPiDCMotor.h"
    +#include "MePressureSensor.h"
    +#include "MePS2.h"
    +#include "MeColorSensor.h"
    +
    +Include dependency graph for MeMegaPi.h:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +
    +

    Go to the source code of this file.

    + + + + + + + + + + + + + + + + + + +

    +Macros

    +#define PORT1A   PORT_1
     
    +#define PORT1B   PORT_9
     
    +#define PORT2A   PORT_2
     
    +#define PORT2B   PORT_10
     
    +#define PORT3A   PORT_3
     
    +#define PORT3B   PORT_11
     
    +#define PORT4A   PORT_4
     
    +#define PORT4B   PORT_12
     
    + + + + + + + + + +

    +Variables

    MePort_Sig mePort [17]
     
    Encoder_port_type encoder_Port [6]
     
    megapi_dc_type megapi_dc_Port [14]
     
    megaPi_slot_type megaPi_slots [4]
     
    +

    Detailed Description

    +

    Driver for MegaPi board.

    +
    Copyright (C), 2012-2016, MakeBlock
    +
    Author
    MakeBlock
    +
    Version
    V1.0.5
    +
    Date
    2016/09/23
    +

    Driver for MegaPi board.

    +
    Copyright
    This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    This file is the driver for MegaPi board by MakeBlock.
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    +Mark Yan         2016/02/20     1.0.0            Build the New.
    +Mark Yan         2016/03/10     1.0.1            Port mapping changes.
    +Scott wang       2016/09/18     1.0.2            Add the PORT[15].
    +Scott            2016/09/20     1.0.3            Add the PORT[16].
    +Scott            2016/09/23     1.0.4            Add the MePS2.h .
    +Zzipeng          2017/02/20     1.0.5            put the array megaPi_slots[4] to MegaPi.h
    +
    +

    Variable Documentation

    + +

    ◆ encoder_Port

    + +
    +
    + + + + +
    Encoder_port_type encoder_Port[6]
    +
    +Initial value:
    =
    +
    {
    +
    { NC, NC, NC, NC, NC},
    +
    +
    { 18, 31, 12, 34, 35},
    +
    +
    { 19, 38, 8, 37, 36},
    +
    { 3, 49, 9, 43, 42},
    +
    { 2, A1, 5, A4, A5},
    +
    { NC, NC, NC, NC, NC},
    +
    }
    +
    +
    +
    + +

    ◆ megapi_dc_Port

    + +
    +
    + + + + +
    megapi_dc_type megapi_dc_Port[14]
    +
    +Initial value:
    =
    +
    {
    +
    {NC,NC,NC}, {33,32,11}, {40,41, 7}, {47,48, 6}, {A3,A2, 4},
    +
    {NC,NC,NC}, {NC,NC,NC}, {NC,NC,NC}, {NC,NC,NC}, {35,34,12},
    +
    {36,37, 8}, {42,43, 9}, {A5,A4, 5},
    +
    }
    +
    +
    +
    + +

    ◆ megaPi_slots

    + +
    +
    + + + + +
    megaPi_slot_type megaPi_slots[4]
    +
    +Initial value:
    =
    +
    {
    +
    {35, 34, 33, 32, 31, 18, 12, 11},
    +
    {36, 37, 40, 41, 38, 19, 8, 7},
    +
    {42, 43, 47, 48, 49, 3, 9, 6},
    +
    {A5, A4, A3, A2, A1, 2, 5, 4},
    +
    }
    +
    +
    +
    + +

    ◆ mePort

    + +
    +
    + + + + +
    MePort_Sig mePort[17]
    +
    +Initial value:
    =
    +
    {
    +
    { NC, NC }, { NC, NC }, { NC, NC }, { NC, NC }, { NC, NC },
    +
    { 16, 17 }, { A8, A9 }, { A10, A11 }, { A13, A12 }, { NC, NC },
    +
    { NC, NC }, { NC, NC }, { NC, NC }, { NC, NC }, { NC, NC },
    +
    { NC, NC },{ NC, NC },
    +
    }
    +
    +
    +
    +
    +
    + + + + diff --git a/doc/html/_me_mega_pi_8h__incl.map b/doc/html/_me_mega_pi_8h__incl.map new file mode 100644 index 00000000..8b7e43c1 --- /dev/null +++ b/doc/html/_me_mega_pi_8h__incl.map @@ -0,0 +1,266 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_mega_pi_8h__incl.md5 b/doc/html/_me_mega_pi_8h__incl.md5 new file mode 100644 index 00000000..0be7fd52 --- /dev/null +++ b/doc/html/_me_mega_pi_8h__incl.md5 @@ -0,0 +1 @@ +12af885d42deb3aa5f7bd1a7cd94a003 \ No newline at end of file diff --git a/doc/html/_me_mega_pi_8h__incl.png b/doc/html/_me_mega_pi_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..ca1edd543810f12e52bdabcd7eb9e759a0e9556f GIT binary patch literal 874619 zcmdSAhf~vSw=PUC0Rl?zO$C(RdsRefD!m6#dIHxw&!g=i&{luPw-I> z?2j)COmfuiTmu@y*f`@HXh}F}<~O z8!xvi8f4Yp9F0n}6wg|6sKz=z3A<%g(ecZy8K2YHcXsYr)9Uhk7lYk~RGmdEneG&_ zv)^D>k#_o)Y>UuH`v2b;V2$b8VrIDU42QtArmA7l*Gic`QOa-Pv!yE z+@8t@|G3$IHp07^%*Fo68UMz1Kwe(&@$Yu~5B5w6$po{Mf7)s%32*qG7WNuu2-~?R zf~upp;^@`cE?_&#of}7t|1i~!8<|JCb)n?{co6u8`ky6I_~ni-z53PNbwc%|SVw61 zM#w+Tb0g%ar^=rApT5hK$O|kP`!|QLi~TpwZ8=0z^8UI$%Ya=Y+-Lb0ua04qSS2R6 zE_e8eT=DUW4q@&%f^Ha^?_Ts`;h!fz*#5U?TOhj}#Tp_O<#$r76VG#vud%ER7v7UN zIQHK>Ih;tf_5bqHDo^+drMh_J5VB=_kxW;9c@I9-o1-d9+krndr!6mQJo&gz&ybqP zgTGc&+-5C3VMv=Fd5Z$-S`vDwM}mh{X%aW(2k9yLI(${=x90<$TN`Phn3t$@rEi7V zq>Q@Iw$0=?K-a@>i0L%_%`H>OqYDk_-)CK z2q{sW&x^(u&nbo%XC2uKQoPNPg=}ezsrRn-5bfhv>ZQD;og$VY`O#S4sPnla2%7O% zxC6l*U3GbW=Ms$bwkK4N|42E>xE?s6XE8X-pj;XFfz=4osKVW#KhJ1uSQ(!PjIi<= z$sJWgC%(DyEyY_wjS+Dz|5?w5+5-6s8j?n7J@PXZ=@S^HtK)*^!{q3@c(u-oB_Un4!4*-)0~+BW=yKF7HpPB z&unlZ!QE9zHxssk-bkw6l29HgFS#UN?l?h*MjlUl@P^+xp5eV;G#%w}?SA*~9ey~E zS#sP2f_XD~G(nB0WNmO=a7wpd%(M4^f7<@MhMgeG*Bs#tqM8Cd!^OMu?GK zkfTb-jNyLUa2b+-i0jvOV< zdZ{I@h(@hb7x_O*`gGXWM1c2suc!2{RuPEt(0RGm(+BK;_{jH!nZtGqcKNP9=hyS- zs~=Iv`LG<7y#=Nk=R`zlL?@nE>^KNW2;9lXriURMD5mvaMa+MIVh+;M=rhrEu8+P( zW&Z3tQTJSFqsNrRbw%Tl{11?WkG{c$qKn@f(=jtVj1BZtuvzx4D7`L;3EBJ5* z;hGA_=WMx^Zg3XWMzC`{E6HvC23BPr+^l}96ggP7-BWYEAXbBxiIT>=w-WbQIbj;* zAraa|n=^e+E$fd#_*#lxF$(7TbzKghV4Bklx7WT>4ckd zP9m=zZfhI&FEHWtj&g&sul3>0!JBXI`M}Qu=dSSoGbtS?ef(dMFf(lL>Y;sSWB=3Z zeOxT1BZg*3Y^E`i$mhEv1@Nqn9;M^J2y>OZT}}TaNU>*%Oqf$}k>LaFb_bLsD}@V_ z!oI%u0VZu2-5~QVPZI>uR?(bU{_x{ffWMv}%UEc0Z~QsCMaNFak+d->XKd2og>RuD z|5I4mIVSIEvtumL&q9AU4jRo{$L7dN$+78th{4YkL(3EsFI$B~P;fkh*QGTFLl-a! z==s$pk+oqs3(djc1*N&3_mGODcg&oKJ(CG#7eSA~w#j@?ciPYt1SD019I^dyfx=xi z%GXxu-$r77qnU!u>YiCw9F-VB=N2D(a%*7PHWSm-7%SW;g;hjfDXk6(R}wU@LHH3W z!B%=#?mQ_c2=F74W%%+Y~#VU&0d22mG>bx{&^HIbkJ`+-0+%J`bcvVe)`KY9x{!JCZx0i=bnulE98(*s} zT7ZuuBrysUIpt7c9^A=cv+}L($X8owZ%ZUILiS3c-D}O>=i>29c;V z-=2oawG6-dN^~h;bPru&vJ8}1X4;VaYO`=2Vf%(OS0+RY?*`Eryo1Ydxi`1kmh6ft z%Xrc2-=4z`b=Z}!V;8kPOpUmI=~;Mwca@;}t$Xswif))Ng2UBZK2MQZvRmwL^g_7K zuI|rVtwI6kQ7^l%K7Dcp3_En65&cn5Y2~z-8^IJv_w=;5KV)z42;;P!d3jZ#YBzJG zRxfoC{xd3LUG$@ZBQAgPr^$yaOe&3h{8F7?c+RVNtN8A}(Vd~~Ky0p(nWmu6CYhFq zX=Jn9lV0YBKi?1>7O60Px(+%&7_<$?Vz+DO%>R3gEIm#*B`NzK>E8=~nGt?c*flY_ zI1_KDeX{TLz1HTWfolAU0*=O|hd5nJg`$m)7ezXbpOpU zXDHW3!cDTrkjgd-&OZ>W=?JBNP7Q7o-OWB8`mnH?@oC;yRArEGinsD zR4t}(-sO_ab7ty{t9yCX-<=a0a~a&Hjf8V19;Q&St*Bl;z7b8N!XpwJnB%O=CmAS| z+c;;%l8Rw}f8z|R7WWAFTB4d6wJq`-oFxR1#YzncZyA45=r0Z@a!aOGOfb`mnFN@R z_?7|E?WwC_?>?-j$3RAYWZX;StD3s}HY<7UQRt(h;0>Afe&$EX;yb@`IlD$z<9Xds zatgajual0SGSUC^wqwe@sWS;eR(j}kpwvTL(R4Qz_wZV^XTC?NSg4>qbjO=8?ULs` zxd~ry6iGb`1XNNiZ8eUS)9Wh!6y>g&hk(I)w>3XbU{5p4TC9)0aE^!DKJ1LfTZI7_ zYvaCQ+N$GLXraF3Z_6N&u|eV*&F54X96lZT*qk>IGEv3FxwQZG$vdhtx-RmCxK!-zj~s%Y-uNFvmPrOJQv=aT}6A*#wkFmYDNm3W)Hd%#w|7LkFkMZC74{J7hnAWobloZK#$ zn&5A^0G$R*rVDR9@jylKOF2P_l}>XRo>4kf}C z^|P<;*tGN?eA`C_y@)#NXrjk+DK3W2*NoH0kNeI=jr-oC9}fGF0ly4I7gF16$cEQ_ z5($_NU3kWeoQ!WYmFyBM!1?%0MsK`ch77X4BWd z`S{eOJ^xs4|Mh^_c&Ylq@E|p2T5LQQvI487fmQ1t&gJM#J4F=cGfWygj~FVozu>VU zd+$4r5dUwbILZHnW|H2JkNtgp+RlK?g*jI{Sx=S{12`(!VbJ(URQ_lrV zQ+fN^9-dl?Xw!O{*wr&l(#S<-o=8T{*0BQAml<*|lF4m-x+E&PlXtY(>-ZRuQ=<)< zD?V}$RF&-C<;yU+U*Kmh>$^3W)J&EZ*FNpeM)?qTRk1LG=R@y3ueX=XRoGz+g ziVnYOXv)|nXM3P{5ME@htDQL_GO4V<-8T^CVgQb{VjNwqUttjCemHjJNtR+ji1E;7 z{G;(>eA(T80_*&2tzOYUgc^xMTXz+xX7o5;jtqgEC?6?qpN-oF}QM zsGl2+)g&anFT-$d6cI4>qsphK$~5Pyne+v^4C#~byy5Ydb>9i;O77+6`r58Nk1VzZ z>)RQ@k}juQ(ORiSuhx#^ZVWe25nji-(I{X*MtzT#*DP;=M5)`<-l*r8jgAS!cy&vU zd#6bSQw;DoX+#2dgNM z?viS`WHD!)iGsK`z(_egvytn=IXmjzLv>WEQ{U-9-VEID=sR=H;$^!x?XAmo1;i;< zH8Q+{sN*hC`{j9r!THC@Wh?A>q>o#BAbNg+5FbUq|I;ThoMz!J#cwlQml+>Q+vjbC zzqnG>yWF{CvkuHWTMZMY_0kgZzM}n3VGK*D0GocwkdyTlX3RArT}HYUxz8Z%T*}8h zBs@>WBlXPj9YdWr5v!A0A@9W3$5^Q(x^;Oq{Ge4Ig@ z>x4!el=KJA)68b-`S!#2=N`OnSHoc$P1ov2XVx;sBasl#KcS7=!;|n#7rT}=>n^c@ ziw(E3%MP&3B5H`-O?=;GRv9I751OI!7`KSSwaJxobt|1r#5RX8D>@rCaLO2kf5;s{ zwbV531(GMqlfCx6OW~nEGPs#{=)ANzWhx}Nb_y(f3+HmY}&qk4Cw2ur-ZOJ*HY zrzG0O*t0ESS;fw796J4UFVIT9@+4xE$7M_FYi(cYgFv4nxNI(Ae?& zp|%%`>3-BOc!^46puUj4FwSjQECE20`_#MyRrq9ey}_k6=Bb9|jH8E9pK#UD0h4kx zyFQl?$dsSVjIZFvUZ?{h%VdbkUh@fl=Veb^t)I^sW4jbgj$doHfWn45Ye%xTl_T7c z3s~}IgmP?3=&^^9qdiOSs z&z7Gp;_f7gM((j+Riaou6R6rChHgc;3vV08u+xZU$^j_F?}ymZGt9|JVUN<$6Ko&4 z)2+y+XY@Zf)iQ76@MyKy4ex9r7jwgDFHldIGp8%#@ft26yx3u z`h47bXgRR#^MJWFueYRs5?HG5$l;7jm>ma8>L z=XrmM@+frC@g-ypm8sO>!j>8FY?(yCc~RiO)f{j0$Saf7M?P}~Vu?Rr_aYya5Z-1v z#r>Of3vuxV zS<7{XsVz*ath3g0mO?9^6E;+jGa%)5Lr>Q?gB>>YAl3#~7`{6BAJvd3_y3<Ic{pT~adU>1tJ!%uW98a?Ux%vZohEHp)c%t(%qQu&Z?8WWAGg2)Xg8$V@Ln#~i7Afo*?vh!7>Fq4#5zWvx1WjO zoPxq$e^Kdh>}_xLWqvt(2&1hX*um$x`m!R#N75K%7qAW5j-1imqO8SN zg+b_HY=9i}cv|q~T)jSQLUSkF*ySbt;@jQDm2K4*h1!kWzzSN-^$2+sC26yFvqYJ7 zB6+XlQryl@qvA(U^|%w5%BAqcSIIvVH{V8_0`1h>ey?{pz~+*Hul@@O5$@Bq zub}YX+ax}Oltsd)Pt&w_I@uwh2aM%hg5L%@NCRvfhaT}+&X9SeKkMG&sb6`(!<8Q^ z$~#3!GKf}t#wUZ!)$Koso(pnYpEl8Zq{cSZDZ{7OD)WW(y%?ngr*nqo2cQ?ADE3o6 zamld<#Z%?3n9BK>k_KxnD28NkR}aZmkBPiB{3##_>7V+dv6`G1--%~pn*e^3)tAak zQH=?cb5l$dw*dqeJ@G~}Wo;^HqD0r+%n3Cl&$yqlHGbPwXCkJVkC|I%8aYE^Bt~h? zDN1W!exao|>XObIeL|F|f95za(iR4l{EW2XzBy$8Q+_?6)G&Hs_-SR5^H&}v@PzVp zHnN@6_EY2YUv$rbkoA>mI$QC=8R%6B9sO7YU2|N1WpsHEgNX|G3&6sIQntDm`De$j}}4m-kk_&)0FvgA!o0e9SwzX#W-E#bjO7Rt}t>f`~&AkDY zdj;ltMnX&#%&~-g4c~qu#9>5KYuF5z!x@&LxY2~EYxHtJ2cN)`OGwhZVeM$*(`l#| zGf#wUm{!hMJ))<;2do!U%tJ{&ijkl39+z{D(?tGdd*^_GlFziF&k9_NbfE4FuGVDh z=#!Jk=4$4T+e&+UE$KF=s?G}`Uerg3A2)MD&MntPMY&zOj;vkflHg>u2kHx*n6{Sg zp-!ci(7Qz7<&lq!n!K(2(!Fi`vUqn|*Pr`DIfLQb+{$-I`u_5-3u-Mojf-{T^qDFW zf5v{zG{%BrppRXx6%$>!L~{(NI`u(L`azOB>!Yu^K^~}Ikg)zScuUSnU612)kq?b~ zhqih%j3Q6^1d-ax4jovAv0c}ZT|vkxeDzqH`464DhMwcJh$O!?@cA9)bv{M?ROxjF zaNJm7u8z(yT}5dV(`#;Pezc(e4iY3{5Jr~z$h(J|qDNse_wC5F48(;eH)N>ad}6NrbFMpv{@AU5%ZM`I{bm`!COWazVwVgD}I z>gZ%I*V!c>49l}lS4d)PLKV5RTM}$G0C@$`t=f6Yd^^c3|2E})7>Qn0OLl&ld}gTF}}`m2=l*`STwUds*F@T%D-uT`RU>HmFpUUaB_Xyo^^%V#b9VA5X;9a z$OG(D{cZaO5I>~nJzhr24@)^X3c8W%9zPG-USHYfGwxTZtL2=hT89-Cb$S?hy?yUp zpZZ1kKC`(7r3-~r`Ri-xYac0x^1K`K(R|eZM+-oQQY@>0=#T|Lj85P&9e!ChayoM! zZ|`m>F^4{y^1Q7yJwuTDh_p)Gyk;x2f)@phh?NScm`Nfk_R0t(*)6M`1z!uYY^P%% zoW2l;6CmcW#Mw)YwWPu|;pTA*K*fEavq{tQ$Kr2RHZM#OST?24=RO-0-W>{Bb1c(> ztiPq$er}Dw`qHfxDC)yHvq|Z_=$Tu^KDEGP{}|hH_WcY`6429>?|C`!4hxSCx>0r< zXaSTpo|;%7^MWSdZK|C+M?M+PFR!`Czm9&3fd~o|L-0|nZ=uKXEDs!gxK0Bur5bXj z4t}0#4olma)JE_GgGe3Uf<5^{mf~|hrxKzl z!gcr+Y!>TWQAQn_Yn;tQ^W&sLV1LTFK0qLN*~n`nS3FzB(6 z&#wUv7&a?6HT?FHA?G)4g6XQ?kS3>~qM%o^rQhyK;d)3ww(pk@pPP9;157j6c2Bt8 z)2S8#p83ovT(xE4A7*94%3-zLgiFfAaD2=N#BBfP)$u)uL&n6p7Gd_qRo7hx8#Vj+ zd+a}Pf{g)qXM+uKp%c6zY{Mi>WT^Gn)az?Up#ZCkXeaBN`MdY6AW4o#Vf33}5~Red z-9sxLVRDw^&~cmfA1Cq$B+855qr)ZqKWGM>!*#nYSW&l=StdOdPLz zpYZ*cEVg=dV2vsGuW;u^W)7|wf4;FYc&8fKpNf6pxwI1N=a#UI8X)r|xizb$euOWP ztCvh1oIt~3pO#R&fL)nVds64A!pt`KMzpvWR>+LwSo;6gv#;Y!XrS79CBr6(9|082 z16c|$>Pr}@vrOYARTFOL_Qo|F>h(!-L7g+>%EzL|namj=(Po>OW#j_7pL_D={ftS8 z^kuS(VlM^EgfksOh?Z|Y1KdKz-xVECQdG(AIpY!v1*p?04R}1__+UL6{}``xZzJER zekaA>NFizYjrkHbultoJj$9@Tz_0_{fQZj`AQ`eLsKrC;)MVPV=ztX^tV3Ldj5xYy zhxXm~*{EE2I5rggv%gg<@PUiJUGJH3a`Xv9O%uNQ01|g8b?6hceF5=430g3n!O9R- zUj|uO$5AvhSs}K$iD_D4kkn6zM_8;Jo!UEuq;cjFBs`HMOouDn<{${%6s0poByYC1 zaE_gO^%O5BjTS((ziW9V_8`@FAgK)&z8!~G$>A6d(qKSUzB&J3b_#iuPR=}=je;Av zPmSVRSAbCfj*HP*-F~WHFz#<(W`pZfHXDKKw}W9TA6m&CD$xtVMsJP>LUP|BH1`Fl-l;~Ft>LI^4iF4-GVYzN8)*BWRBrrsN%#X{hTWgrNb+ zKT-U)cojr`Xyo(5vlKO!?U6H&USlbd9*y$z1sTO~};m30jzgt+KQD z_oj$$8}yF^DE-)3c*9+wqd(`J>bD^h9kyEkmN(2&&7zRBQ@K_p!ynX74D}S^RuLU) z`#_zhDn!m!V9K9qrWw=AJ|aM7<(s63t27@C*{u?a_-jdbM6N8&SDjzJk4ld z+=%zzvh$O@UtHwep8Pz-B5+|gV8mL?_6g++n@G4_^#}Ert1BoW3){#OoID#@&|>6% zSY(sUUW*F8eP4dhJgIXBH3#&~C$zBRgYTN|1zkBEXrD~ifO zNX2wi!vmuq-3?+&r!#ix8W)u{6lR@{k(XiWT`!?4NfL=~Btn+#GQz*7N|55$qwvj< zyOcXz`F=jvXV<}hRyTQhMXE!mDS5-6TwkulugMq7Gem!>Rw=+>|jL zB!=^eX)p20aJ`fjb}t%f z0t#kqvu%fhgt}$RM+f7Ymw$;IhHUD(8wDgXP_=>HDjE3Dw6p|>A)2^2n2@5)lswm8t!mdb*2)@|J1;|a0=jCG>2m$H&Hg+GqH9M!8Ho?PMzfm55Enz>j8^LZ36lH> zTdKtlXK?(seYt1RAa_ra`RK-*-ci7;ION(^k6bOU<<@rMYcyh{)lPA+Fwy*|1R0k* z7n5E4E%_p^x6&;Sie3vdMY_~z>z;6VSSJ+eoXwd=Snj}!4`F3B6wO6Q!;%LBZlz;ZZ_k9|Y-{rh45B?S%L6Dp3 z`4YW(_Awjo0(bAIrEywp60iHw&bQ~opO#&s*?;i|v=m&C@uBQ){8tzDIIUMYC&5IR zRsgBiYcq$z?n9jf1!Ca>6Z+~V?n-&r>-{yk#t57FmyK`M@-6iq-(L-!koZMyxW9DO zba}2mDt6blA;#%;pkvmrW4GNjdNMtw4d+ymf?FtlaM=g`uj`pm%0`q%N<@(y}2?C?{@kHnma<1Cu|N0>}Dkn zb-fd=qaN5Y^|AaB=gs|h$4l+Q8_Oky&JXZaa7aX;@ofb3>s{hHA@<67wOXJVbEa~?u$#IuiN|!(? zgQySZnPEJb7pcS6aT6WXoWy~Aho$x&Ji=}wqJDW%8L}D{aTRAV@$`7Vj;13@cR8(Q_Xob*ea+I* zRT|(b1vgJnw>dQOGRFE+%Nosazw*fkbn%JC!S6z~^w}8O5`%uz4Ap?%Sjg%VhA}@W zU7%p1Fdyi>-n*tK|zQWlI zkPr6ZdQ20nE*=v9LLHUklFR9H1Kt0&EQ~{vW9*F57@Ilf2-AC*b9YESS7twehp1wJ zAdG2X*dj(}qi?s$$l+*Bd1mt2e{I*_-0;)6hv{2VZlS<)*xI-y6tF4qsPG@l82A6k z&5@)BuZ48iBSm>nTuzT@WNP(@7s`62g8^D8;1!XkHb&E%q07ShE28l}!aoknRferT zTy)jVfIbZ7e^A>%XiP^5Gr>b^HR=&Ozl>+=O2%2Luq$0tbmaY{!Jzxka}H-^pDa!{ z5By4d-J2v-l+I}h*a{nmN3F>gQw#0PNhQjoFhw@&&d=WKNMSW!`8kVJ`)hIV!NFK* zGVz1%eZpVq!i|cbN+)k#L?hUhaugL(x*eolo)!*1jHz1ulUGA_sap5f`SZPrs+GyK zSt6i-+rcvh52f}#GvB&&Gn_uKX(HjDwB)S)8||&GloIbG4(vbq@Rc)j!0hRh;9IEJ zr@$gvC;$>m&hyPQd^Lt$(0Gb!d}F)$cqc+X#@g&>Tw-am zRHh5N#E_dNia};Wp8(JwS|4s;f0?jdg#fD&clB$%dxqV<2R5v(|EKoIh7K4!+;yGF zdVVfKtHh*=3Qi^XL_@jZ&rx%`flC2Lb-c0ilB_tW3fH=Xyd_w zichzTBeB?1rp9-BwF>j+yr;X%Hl6*kLM*|nBZ6@!m|&*~^jgy?*h7J;K~BiVaEe zxv|-c9^^I}()#Dpo8i(-LzWVxSkc6N`*p~7T335Yd&*S3Wkbj0IFRaLld%R_Iz~~} zA7y^t${gk{%;8y1#vNQW^-~j zaX%lbf}3srf*b{F(RobC-l9plthOtuek`|{KK;sOe<)149R`?JIvn`iE-s74{yc;| zo=P($ezlp0_^I4q3RxBT;x?$Xd4~VGYitEc?^F67VJu{p>j=&!8_CgMcl@!I;v>^V zi<`Z~&0g#rU$wVfwFh0z%ERl(UeYlq$DZSgJx^fXq8w&jp#0xYyVPN!XGRV-9mO>h z{gayxo<~((Lr&ZR0tZ_c2O9gm?hPC~aPeq}sq`z-h*cKqvKl&(x|D|Iz+~5^`?+~_ zEgf6{n<-aERWDXuFSSTF(&devV@=;Pj2oGL=)Y-y&AB zL?mf4N|o6Fw;xawA>Bk2*T`l;im2-GAeCST%GLpXREu|r%Z`O~E@e&A{T6+h&2H7V zzZJH1f{2@aEFb_oZN{I+I0T(%oRQl(9(9<#+k!_Og|P|WbV6zE!oJwcn8rVE)(|?O zY+h${o0W2g3>AL)dAI!q8Eo>T`M`r5-x7t%{cSLZ^KtKTn7!0CCSU2iQn%d7@hn~$ z7M(xG!5MJmreRmUcavROExtW3^xGh}z_P-{y^EDDNra5vBPv{mb+Xzlea`VFhU2Q) zEf)2=iyAknnrQ4Rb{4K`r}f{_BwOq-LO(EW**HVwD$STeXk6Q zonI>s>rivA`eySH;#70c$Itq?Hi}nx`=%gkYChg8_`8$qPw&Rf4#)qe3y@gMm$!WU zUsBS2dkEr>nuc<+`yOgIm-OCPH~&3|p70VXz29XNT@J#kO18GwP4GT%@~$T&G5s=E z8bGRuthTA_wE;xC6pDH-E2Ez^%7Skxlj&=f)A&*-<&=VWE3t%?Ph96K0hHIOQ<{9n zasIUg3VUn7Q|h8v3sK3!UlchCZ$rbwi?*eU6!<1EkSo8?yZ_UX|OgxtcLPW0L9iJ zg?UHCXiw;D_oE@wAl1L1+hxfx3}hs{zyFb)%wD+>f1zW;Js@_#^{+zKPWPBaMI`s* zUs~WsVo_{HhCkQ^FhH-Qr_5WI#&ye^3-zWD#N}iVO`2NB1(3T<`Ru-P0c9);MvRRX zWCW0~3B9%M{QOlMIZJ6YmW>#q9mpjIhU%VfJ1IV3p4?8ye!wnm=F*Lzh> zBiZ_yM8tpkS|Aj7ZM^IQp*d2z7Yg{2i=9Goh0A#k<7b^@h<<|Dm;VL>R-isaypm5$ zX1xruZ;L$Y8a-1`>hyjal>g&jz;}Fvng&SqMa(2Z9LE}3G5n%L%}wR&N>@;}S=^Vf zxNf?1D)-Y#Ks1`*J^PHojs925yVuzdF)}hNQeSU@kVwZ&jq4JCegIXrP8q=!0q)1~ z1y!ZEnU*9=n0wfSNUrnvJ}jrN3Qvuw4XDk#cSSlO^_7B|GL z{FTI84{xxh3_POB+R^GPw)H!nubX?UH&hjr^TZw2gwG>vENGXRfQ=c2>H2jX$AJCW zybijx<+|0tO2H4JB3+;{2VYQs!F&*(e9cLg4kOeCcP&5XkXU+zCwI>GvrFV|>1h~l zYcU50aeG*DM-lvB>I;8qF5fFsBlV1!f&cg?BfU^Lar?KS3u$|0L=LEssb#xViMKtU z7n_;9=6r68Mi;L}Ma2=ma29ifdyG^_m0nX~$H^~l4V@lBBa!CX+3FJifo!<;gKmVF zu1kXA9zLK%9UMrt@H9B}DP|i~Nv<7-AUqlm(U&zX`pVY|b0@XL ziE()M6#4GQnY1K-m*?>y&2m`(t)k(YlID4!beP8br}d9t`))gRs@I#^7^hOU5M@MD zobp_RAd!zM?de&iMfKi5KJK-$B+!r*1#yH8<`4If9r*8~HvhSeG2o<)YdHiiY!Lbvitk zG5oRib%TYL?qA)C`8!kRfAEnL6r{rs?!&2OFKOQWtK-#O8`|RVwHwMwY$MA*`!^N4G=hGsx~a69^06ikZpGopYGZwfl4IDj&m zm_jG+RKisP9x!_GY(`v548N4ACM>w}bRZX6X2m^D-aEE|d|lywa*|xQ5!n2K^j|6v zr;^asy{pi?QTKn_Tb(ltze=+HUj`EpC=UC}>~`R{<>Itm7=x%cPn_QO7!x^pQDj(p zj=C}Dk|-?+P!5?QMJ8l-w90p4gw0+*zC3e@{^0}UxSd#Omcd)kF-8~~df(<3w}zyZ zL}##zyasCl?+1ONMU4rP$Ba3;OOa>j=Ed*=S!h+IQO}}9GXFL^bhViCoKxr7tU`;w zwFhFx1QNH0h6#LR&dVZhqX*FmO?e_unudrgZ$HU7cc6>|*J; zSNm352!AiykN8M4X}8-3NBh++F-NrikOQLHV(&ap%sZ?JboQx zYc-dwK394)_gO>H9C_zJxl+5NY7vXdG#>Y>03@Ynejk{AB~lGRq;99`8VH9dlrMc! zD=1_L*5n|AdDin1q=rCKsa;$c4e9AulHW91VeU;nntVBcMRf(@Gl2*sUW zrRyX&ckPF#OV;TWe5%mI-7|K)_?fCS(qpm#xyAj-3Frd<{(uTI4nm!=y#O0jXFN4p z@^wq!JlY@BKKVnHRU%jXm)s8Q1$uq|{(Od(HvEFrNaJF(9ZBk-d5J_c7Ebal-cICa zed5MC!baufLz&8*yY|FQpE$t%<8JiA--`H-K`C&0pu;z;8$6!=m}b#5YX#m!BRRBx zhG83OP1=OG@H3CKekVphSb$aW;Ygfy@486=MGotUl19iXXun*_8v3S)fTXxHFre)b zMauies$$Mw=;Jn{pX1Po2Lt>(BDquCwPF$FuIodp2}<@M3%V@1?;*=5I+5*t)KYGD zkG?wjV|v>q(aPhb-XWUWO5~^iRGzwWPHv}}kQ=aOKD-2P-hJN4D>_f@VuVbciz7fzA9oF|zN8j$}JZ`6_bgqqevLGHy z@T=b2INwjx_)F6iF@#9;gel^G{{=z@jLMfq?D+P&c(p=e4U$MFlriR1O6m1%DzC~# z8hNC&!qs}zneone&c&pC`+wj(Sa1fpaW!)#r_Na?XD4;(j^j;s?T%WA;XCOZQ-*nc`d%XvX#KEqDuG@SsV>GN&Pm>?QWB22k z6fcNKyqp6)nkq>j*&ULh4 zdFpx*^;f7je2!g0zQ*mg!2kujQNZ!9Q}MP~2(F>GfxUllz|66)0n!-VbI>-PHed1r z3V4hOS}=|gz*5jC{8+*S&x*f*-?8Dy?UkM4r7k`0Q%A)!@pOK%Ywd2WoQ-080mSdd zdxUwgvYuXO{FwR$JEB~WqY66;FOK_2<7&k+G%U<|19p4mBZ$>iqNfRP+g}k7Bfwff zy{lSXr(Y=$DRSSnZfmfn_qrM=9NK+6bs_UC$_~&6v<(GFsiRANSFrsQ?B^%nFL(o} zw>8CQ4zyJ)?XOfy+F1E}Gy43!iDmTs^ly*&9)GaE0&nEvLtck+X9E?o@ocg|~J^}(4ZW7rQ-8Nq8%_+d;Vd*6=22-S@0#S^b;YiZa&+15;#vOQtuc3 zmW0z`NwMD7#7N`7u?pLRKegDNgGv*n;jwgJu4Q$Lm z!6KPq_%sbOrBE3u@4WePd0V%l31fVdWOu<`C#y7lE+S5v)dN+SS+?^g()hYK7uqu_ zb|Ph*pC}wkyeW|y2E6NwU{yv~5Kp~(x92kkRl~u}>B$H_i&dPAVVV4EN=+TiU)5z? zbphMEEuRVogF0Nwc7FLP9L*YZwLHT%-`n|w6}F7(LLdFj*=OYc@227^^OOH}*)^O$ zd?n*jOG?momqAw~EAHv{TjhLMCGM=a2+Z2oK~!g+3R=gjH1JJ+@aGz zj{$`pAMQsR%3eyoNodCrJrR z_3VNs1tEI;EGk9Xr4@<^WfC10j+2Z9Aj#yB^fE1K%2Txr%vexUlXtPmlbKXcXo0Mx zKo^>c#qAV&BFg}BiFwLx#P}X`)SdDOSS48r{?4S>_7-aa)*#iNjmn`>O?(kRNhzAf z6rMTt3FzhL+f}Z@2YQ5)n+!Enu@xk%)i-wJ-ifA*wrt9N+v}uBO0;@(oVIwDsOG@3xKT8fXu!&{?#{=x)lW2iIg zeZ`U`eGFQ49T{NOY8IMib8o0ELRF?;Ocrg1v>^Id%W++adt5&3T2NwP#*-wM)tLt+ zkSLFy=1udLWHuPAl+^yKl<~j@=+qup5h{^=kdDDr24@0CoS-(a*CWD63N-=hAFS^h46!}@ z)JM(VT!GSbmrN6>Mq}8mK!9xq1BvsS^9#)(9rE&a@~TBrRaPiJw((OdWM5TefQIZTW(D|w+VfV}b(E@ZGO%uCc zEA=T2m24$eFZx!tY*25`u3*wqI-`o0Y(WLi1^Ir4t3T4%3jJ=his)03tCT!vC*^l| zSQG!KjtnHPHRju3*P0w#s*$Ly)gThw0w{Y88?QCekO&^E22U;tTj|F+-TPXnj2C; z;Ryq8sqoFQpQ9+0iOB+=)c0l#{gFbw3In*x1dC z82Lx#n)(_)iX|Za6kY$?$hgkGzTE%0>dI_>dAfJFX;K6~fuesS_Iaa?q3p%IiJH&| z!thUrZsZ2yuwLU*IGd=YjBLRojMVCxR8>TvO`@$u|4(VKs*V5CEH0xU#k+zJ*SXeT z@K`MkEDN8|@i?mTHJ@ih3(BPX7kg=JcRW+JwY)3tzxL(Y_hp4Pl*dm-pzU!c`JLU= zSgC_wx(odfqT{m{AO=CDKg!G^*47?^rJgoIp*{$eTq|+WoU_LjKHH=5x{K?w*TWKG z+~>8!twAff1Mk?UfEB0hzX2-+18tPG^KHTf<7}| zCD-mDK?{l;Hb~=((4loZDAB;iixf2=AA_ZyH}N!C0QBN1%?^k7dTc z90B5L!(A(WicdbP=^j<9ATfu1*Jt8q_1skM-E6_-;l4b^o(qNKtrxLq0wlUNjK)M% z;r>zgG=ey)sSm1ahm{G`1^0c)!+>PLFhmuJq_w}DX#V-gf5JB92N4hM+do`9BaQlX z)n#Ite_h-KrGJA{roV_>Y`e^TUsOcd&B}N4R>QqHffuL5FS?Frzq~N8Y2sNk4dKuE z^hQU=+B7%$3jF5rS8-Q5-yhA7uJnF1H~S~ZyT53z3>*klvL62x7x3CpN&K6B`*Tm~ zEyoxEa*}YO+|Bo!MVq@}=o}3=q}})Auv3zhp>(9q!{aOjzw_6whQ;8|BbJhXp4&gf z>uKA$!x@kWl+ZUQGqWMMn&h&mn9i?<}trH|-%&`*R zn(hX(j)Vc2DNX#EHskC1yDv}38fXp+nI~%*7KCCy4?|F`x9PsM zG}fo9r_;W8tl9=>qpB5lOUfE4);1}Xjgp!`M(cH6s9G_(*TxNC50ahFnD zO0eQmXmNLUr#MA}yK8X?!HTq4ad&s;qvyQ$eCLjF|Jq}ZWF&j+?5tW_(;Cg%%mR@`FPTR+z&<#v5$m-ca97ir+N z3%ALOjs_xgdJv#I29s(LB)FD|i9kE+NR6Y2@C>4YsG|y|VuzZctenY;JGW}t14(O6 zWcBAP2XJVYyB8bCT7ecPT#EYp$NwDK$Yg8x{@3~cyn4U3Zt%O`YB?T0&Ap`uVsK|1 z|CzI=7xyNa7NHpm6rfECm!PNWmd`l~L{eq(>mb(`+@{2!UQ3PQ0ZL*az3yk3p)4dTDW$O1HJ(SWc&Fl{csJ<3-d5#xUlAu_DEx@d`& z80ua(J|~lbcTRvYb>N*M4ZU3?H7}?zFJC2?=(~TtbBtxPK5bkX-5b1b#>sDRQ}3#E zDG;B?=qr=OjRWa`d<_)ULr)3BfCF9$q9=Sby^wJ9eJW0bw_FL;nPsPft})4bl;LbB zAy~ADOP@Y!VcDb>Z|6kLdVJU@9M|pBFLrSaZZ~U21UI2uUb^9fOxfCkn+5#> z`RWD*Z{}MyuQ4P9Tq{=q}0cU^9yG?;)ho zJ|EcGi*Jb=z}p%Y#cDKi^_h>?t3D5kYsWPu?EN{m0w7wqKYWGn+g!1hOSlvkMkGH$ zfOns%`7Xl*GQgO)$A>P1!XO@`pI{O`9+k?7+Eqoq1)>M?bZKo|x(*t(@)NSZ0`PJV{7KpvMb$6ZKg8z*ih9a%6XeS>%@ujt+XuYS6V%HQ zEfLF90|>7IMd)*?JL+jt5Z`WZAmWZGn@PZ!xs|lgxGvJF-+mI;Xa+W#d>Llt^w2Uk zmp78ksgRQ|w-YCMyVmbE|JTwFe<-90K0i8fP9(3Y;MO8}KNu@#+X`Z^5piLJb|k3E zDquAu(%VFH&46?8n|Ffc%ZA&Ylv2*EnPKl`tsgK6`~?X!NeBll=)6+I*L*m`@>14Z z-OGnas+zuDmCj>(RHlS=hB}BmebDF6W~>l0>1VvoStzp0247PxME{}y zpXjZ8?&1Y?gr7vqb@Rq5ou6r#949DSSR2K-64*(shy>sJchcCU-=~`=$8_92v(al` z3I;|JushhVK5D*D`vsh0riF-Kj92~y{+()@WuvDMNXOl*q=Pg2ufNeiL&_TYr-zCkIA$n!*WnR`XG05Qbv!yHdlc2_X@+NU|QI|IqM4p~P zAtv)pNa9XpHs*FE@s9RIr}_&q;av9>bTdty?j5#L&Fv(Emu{YVOXQ%!Hgk`7uU6e1 zW2^bXo@ZGr!})PF=A8IYpMI3yj@oM#zV3Bv5zU|YZsrqTe%9DQv2$rDp1b(D47^zBTOZFf85Wa*tCdo}r>_YId-IHt=%KFNT6 zrJZ8)LH_A>b3M{w%sJ^%4@GUpBg4aqYkA*vXUwqm4SOp4hqtFZg$`U`;>HrY!JCY0 zt{L1WkV>n_rxb)K`_sZ8}NaDskr_r zStF!saAudMUq1n0PLC7b6k!=2>~9$v8eY{Nl1ex$!nQ>TNKE>xTRt-Fsfavm*z*tp zOXnBT!=A<{kOSpcTi&egs@Aj^p)QjC)EVzu)w|W*4Lyf5g^}#bMD^X*wD=9Usd@yJ z4pjT*4b|g*L8}P`ylvpOLO;&Ns9_0^lpuu$jkg0(Kj-*t zX>#a^wH9+R>v<#r>z8nulqSS+Qjw@a)ZU8!j-gz~PrZ)7g_nchRw?iseSlVS(8xg) z@B=71%tP8SkRncsjI*_;;wwm#RUoRIs?et8&yeE5hG7j1(ESs#z)kmcGg8jDvp7mc zb%07D@*=flxD)>?9q7IUHRSdh+u|O`QPJ}a->1xhTEn|{x_wDZ^xW@_)Jk~YuOSUt z0nenVBQ*;yW@z;FI1t^s-kiQtGwCZ4eW(&+@&=Pc=Ic1olz4u-=?}2Jpj0iydxFVO zNH9{g-7i5F&+RKE70BJFRF$`ag_a@pbO)e4?%@w?R8Y?!)R3Rl(DMf~pcJyLg**1s zwElhwREp=eRDQktQQVUKcVXX`(G1n=yZghozgayHg^s{$QxJ2bA5$7;r0yGlCYrjP z%V*&vN-N}oAr95jQUP$G>Jiq|S`A*z_gU9cZkAkCO)@mi;VOQ#xi`Um!tY)J#^Pb( z0S!#71QAljbPUej@#9`QsNp7B7J)U!MB?;#S%kEd;Uuh$sv-<2kzDGDLi?Dw4OnX5 zp0cy2w5>lKYHFVl^s(fR-K+`k@?--!%gk@H^UZ{Yc&l=KG5NN;ZmP8;Q{C}|nv&gd$zrQX zo3qPm3FuAh$9quLtgOH!39ucDyb|=i4(IoBm7lRbQUdd~a>k-j17t}s;RrlivwiO` zU>uU6!WldV20Zegxfd#TYdI>VO5nacG)TiblwRY89+1B+or-BaZ)0lC%3@R-IIgDU zI<9I#RbEzv+y8Ap2rjJ!|1%Mld|qyn+n4OdQ<~)xALo5+w-xnM(-28b(iPSa1 zL1C3GmLnBpekbfJt+aCnRWJ$ayvxrVk8 zY6vwKT)@!^I#{hqR=2O{Uo_Mo{L!B^?F8G*~@xfyY;`?bP; zb1-&D;PXjIQ9}ocBP8{l2xDn(^j5{qo}9UqkKzg6&)xr4CCub|#l4(&dF&)&GIH`H z;9GggxTJ;P>`8>{E4faf7a{wkglKt3i7j6ur|pbr(9LJSaA|q?_$OsdtCbx-=7aD2 zUCiDLe0WtcZs?!1^0#FeGaTDg>D%3||Iz-%QI{sSSPh{EEIyJr653Ki&S>sfy5<4ZTt z0!9*(1-!EUI69}BmzCGWqX)m+Io^86_>U?fEFcv`NT(~}AeKRxA6BB7msLhRp8wz@ zPCirT(9LM2$P=!A}PXv3E%0#oyA+>=)y z2B)RBTlY{M-_@X9ezdCAYKw$<-5Y&JV}%K|{63UWEqP;-XzXR@8=>QDqGgv`{Aa|B zPgFmGhB%z;wVeRd-x%aw)a#@zt%p(L-IniWvS14X4Tk3hJIVK9y)4KjVGP_=%||WA&Sg+ov&5$e@nsk@1|4# zQ)~Z!(HM1FQ{-$jns8ZEd<(2+65gWgMW2iWiX8+YUk-?wz9}AL$tQKvmD|etkg68T zS0iOTMhTpLOUuahQT?xS+^GuQ8|y@JI``@@^lTZ#_wwO%h}HpogayGXkke6QS!3C6 zJEZ&4K+KfjkV-@TD(LTm;*tv2R#c{7KQ>C22 z-&q)*-}n}FIEud^>s#71v_+S|Abk3;X}B;?Ql8~5c4qk`6yE2YpV8Hv#d%!XTrMxo z{93g?3QPR4fafR6v29Kul7FfNCG_wE5>@>eU`?nAv3O9Wf;Chj7d%65i$aky(2Z^x zxpN&)XiCxKJiA2t@k|W3?Dndt+%r@L8+%&%(6OYN>Pnd3-f1eI2D1P-0OW#Xh!xVm zb}>HNXGDT);cQQnNRsTVYa@H0l^F*NS2AfzI1HD*fqh`sN}o~NS=%kHa~VUI=iJSS zugluB@~UD0C*xLl^khu4+S8wlA7Hq#g37`q3@PROjb>-Uo9JktfwBBz3mo5NoZMQS zNZ-b^a{B)gr_)M`G)TnINemtf%m-ryze#`qq95sGVlZ)ZP-Hna9j*CWnA*($TE;bc zP7km!%0SDsKh7~-M!#BO3z(MmZlDfpqrdzkr5)8%1>VS{d}NXzFElizSolu)^$5XR z6##N*Xq4r|_O|=@Ixd{j$hXS){uEE*{RNh5ZXlf#dkRjACP&)DH-!+KgkE>-WD{zA zt32aQ{v(o>>NQen@4$lGn3n{7e#0X@tqoq$vzGap0ESZPH9rO)ejj&LPk@$SLs+$+ zxyS_>3Rmxm@0UpFCZG=3I*3P3#z?O`n$b^0fsj z2&epbX}4Pwy0Q29(!G-5b%}L$-kKI3U%+-T`yw0Jxhsc9o6PQJJkp>QQ16GG#(_P% zu7Jj7^r`*RAVdAM?h1Ypsp^=0P+lUe@pEMHm?bbYHnNyE=-BJ(^>4PS?F(*!V`1NU z=4*@>71;^CPD1JtUal_Rbv;KQyhe4Y`$6ZTR&C(Ao zE1BiXyrv=R{r;{jTyg0V+&dp}+-tqU^WlC=PXVvpq_ytn z$o|Z41Gg6~&9b0kT49x}=gCKFM|dxY_Y`{(Dy5~l39v(Mj<6%zbZGXLPGUyXRB!p= zUg@;2drN>dl(cAL-U61*=*&`2l}d!M_WfD^eKL?^9U9+9nB3#q4!D?1yV1c==aLd$ zLr!7DG&35`1$%-FK8yaoi_Pj7wqUN$EYd?$vSJg6Q2bWP$BE!VMnN73W9|2Cs&<^n zIlQmU3)n93UvS4jci9BmlB=uMyzqm=WFlf~vqCOKJ&zGVs2bY&Ya+S09Pmi^JC^0hHE&5V&7Ot{D_iWmYmC=2cCL8*v`5 z!)C}Z65^hvkeitP`~A$S^DNPe>T}mW)6t^ClTNhz^-kCE7b9o`(%LaYk>(mTVqoBFktl|w#@Qs z{tgH~y6=re`8tYpN8AT)2pv^s-J5e%(A=8O{1qDNg=uCSq>D=^A``wV26yaPc`qL1 z5aG2l)6g?Er;az#$ncX8Ucs1At`I+@CfE8{I@|95&&pe&&SmuwTYm|J|(XQ z`MK0Xtg+KgtqwV?)4$crDq_-3ZZ>1ay53^Y)df54rIfV?xt2HSrVB2kl_9BPU$G0P zmNdKn^aU^fnzpt-8^VhzWulft=I29b^3y!|R#S$5ZFV1%1Lh&vK}sa-{ONl~jC^#} z84BaLkWkPeC*KEbEN%VfodhH_LjJ0#kTTC7ns8{;n_%5*!zTVJ`;YzK(}2gg|JO9Y zZJ&|Ow9ij|xj?lbTz9L03+X# z{3yYbCJW_KFjXnoL=uf3$zdrAmd6Y5rYnrzDhALxkc|4hDMeOag?< zcQ7iqFTji+d~>G$LzR^}#W`Q#Z6TJV5m?=W;Bxe0rhV!Q^__?xv`UIgago(~!X&Br z&a5mZZ=nYGt}-x^?SHP^E(P8EF zWPr-@oVGH=OsdO(fQ&Zny?+GS=sjgx*l)F01w?&kAbBPYHwA}^pH2ZL18FveJoA2&`-w<>mw;ZFi`{^J@d=7$-jFMrW0H&rRp zweCnd94H4}mV#oyGO!?5LJvyc_*U@pd99dniJ9G9|fv>wh*+xU^L>XV!%%W=Uus( zpo_G9(ZB7OGOAck77vlKV}%MLADQ4y-_>0GZ4Dw5?=Bp5riQ%?5ExK~LvU9;8>}@) zOV-^{+19$U4EDy5v+SDA1O>xYMW5)bClj9$Z)CJ; z&uteW+t~*4%j>uXlXYU7FVl}Am;0@1|C-H#J#~aiQUWWFq1cONf)thCcr-94c zq>7IDPX?2y(ziuu41S_afKjh4$+L!vY45$rJHNo^H>)(?f*m?2d$!MrmA$tR{?6`s zzsi0H@EOOTK=RR9LG^nJc_Lj^hTQyVz#p@2u+8+6sN14CN)EV(Ird;M^gMZxiUl{i zX;cHip|Ji>{3nVl?kl%}cv`XN1D}4TYVzrHVKb0wl36=q9~tr4PDr~qc#TBZJyFj6 zVjR>|C0qEym$Rh z`4i}nSc-<6wRh7P^|3k>rt9+Q)z?})uOiO%W~6%*kfZy{WMRQhJ^ur@eibI(drUj{C*OTZ*0C*N%hfewUYIZK z&yEn06}#P>`;*K0!XaCMz%HTke+X&R3*FI6wZXdoDIHwW#+7K(!=c2e7SsO9E})nq zec3*6fANZ(`DcghE4BjnB!^Biv4xyw#e6D(Gmq9Kk^J!Ftq-Pu7W$go?kO1wPD321 zZ0C~$)K;zKq@8=x?*}NiK&Ka8vI~a?#5;yI_ADKNzneuX+w7Fh=~LBM&IcjJ2IZP0Mo?R@==XE*zJgM$ z|3RKp&4{XH!Hf<@>$MC$EI0YfxR;a>(Qw!yZ?1EAyL<~A_GEPVY1S12w7#)r{87>r9*0l?ym$&e!&Q+Lfl@%B3B?5>l1cM1{nJz=-z(7vet-AgYws9 z0Hz+|UhlHDY!`I`1(6@ft8}G-L4Ne9U6f&n3Z^=MD@`*544f#3Hb$1Na~Xwcmk<@TJ3WtY$!v69}Rsz2W4I3;k-U4wFG+?ZSY~NMRlL*jA!qC zwp)6eG#xB9Y7_l+uthHzg(#GCB)BgUB}>|Q(qGazAWYi7l&LOtr|QU1htU0i?_0cr#jwH`yjDaUuXbhx^@&laQJ{ zA~sMGAtWRWh<*EP6AERV-kO$3UjY_EN+R_*t@IO+M5r%n#$7oPQvXJ!)4z?ER>da7}>nUa8R}(-@M7sDf(X&4FXN=48 z-Xy1idHmb*D0}el=(D1if)KFJ{b?}miUWmXsDgz!Og5ZrW$~e?c2w?YcWDQy z`j2lpcbXQ?phtgO*;*|dsNxL{1Vxs%ASihCbX8vM0{yp>zW^KBc#^h%>0HA(@+<6b zdx43Isxwf(_EDd{UCG>WxQ%6VJH~EZF?xKD%LgcJ1Ib#)6sVv~ zf?_{*bIrm;mIb*Ni6}OH72MMTC6_XKAN0eGE5~02BFOgRAfp}^*DUX&2Quz$RliTG zM{?iQL?c?6_(dnqyqP@<0dhNw$uG}oA*Uh?9b5BNZ(~o9Q)%HKx_HH>I{Pie>1FL# zTT}gF34MWv(jh$6-epyCQ~{a|!oq03O{nsS1!Ey8(iWk8UGJ?ZY|ElQX=dhaLRqhx zaNyBb#s^Xi!6tMaqsAH?ms}3gnP05JquR!gFXA~V?B-l#+xR6HK8@MJ;+sU z2P=p!_pM6q(!m(gnHa}GH8*18i`&I~_{cFU{Co0E^6?`yCbqF$Baz>J9~Dq`wGrl5 z$RiT8+wE#4@w#xsFJ3_JQl*_6D)yytR91QuNR?vP&8+GCbCF1u;q+!&@=Lt z_SAB`oZyq(E(|a`Q=3?KWUP0brb`0QdvDl7JrNgtjc{$Ews#D_d+=WQoXT>89ORgG zwvdN4Sg>eyFYa)L{_BUL4=G$$)d&6lVOz@mH)FQU%?Pjx#;Cs z!?3O1{>}bm%B4B%obLGczVli9w#n1uIOT#@>UK(Jw7v7(Nc+dd4`m-!U%6E*f6cn6 z>=%5pk;IyEE$ywc;)~>?zN+kJ;QK&zTUMd(dxoBwWqD=<^3h(QI?%nf1!lFC^%JS={V)D4s(KXX{mf=WWW7BXmcbUv7;-yivNEnst*xew*rnc7CfN z439Q}`Zeq-zCjd6N5un=!E!CCb|U|@>WV*aq-WRTOJ!L?k1d5iewusAq1`RqA1t0Rh=Cs92!`LOcbpzP+EjA?=?= z_W!_tL#+;)KDEjZ5D9PMwuMT0s@eBF0y3^xC$iLE*%z&aCeY4(eG>eSqk5`Q3o&vc z#FvS^hD$GU(a*9C3merN3Pj;6##T{aI}Pug4X+1wpP8DHa*#52xp6u-cLW>_N>5u0 z()TZPY1LewJmd!mS36HQ&la9|XnkSnAWz{gc_r9&I5r{R_~GHb59*6!D`0;|lsWdZ zSz_?)YosJ;T40U)Cd(%-3bPq|B@{Hrb#0)r43%R>HUgAU!i=SoceF{2#m}(j@$~UN zS~H5XAZ%Qf!Wdu{7s|PvH_swkdp1FQfCM)4WgY zna?ZA7ZQ!J-4svjEmetGT)px_1p6>&4$LNnMk0$4O-(hTaAc$nmGHKMOK0C>s1_UD z#}p4XTIPlUoFPnnz=F}Iu@-MC?jMf`Nb__Qnn){Kv1(i+W!|L5?u9uL4! zUIsJRRQl=;-A-)KqBWuPbfwuoH!HIEXJ_Er!XK51FaG&t|CfJlJVvYS{Qm>=|4h@` zV0|n7K1s;gR6pwC&~XBZ^YZIyHAW<;g@ICq5}$;V;&bZh$4?>>jJno^B0k|Fs7uQs z#I-WWZN1V-RcWrE2OJ9Q6o*S_Lh;_8-gD;Tg%*5;YlG}4f>ppzw1Z$-blc-|8 z*u}Q^{xfNHI_~X?j=-?gKjmG}g$bvuUaFF7jo=7wZAED#?1I9W5Vt}|aU^o;wBJt& zRJ@976SwA9cTSNY)fY@Jp6YDe}h-Y=EuhaDIphxe_(pB9s=bgEmK)L~1I%{jz)Z(t`SeITQszSYZULQFeJ7Q~h%A(=j^LaN7xsiL&Pc`-OXrllXI~kB( zczX^*f+!y-i9nU@e$r`R$UZVQuqGRa+yE2d(wi2kHN|vP+-if7;cL`U-XkR~GH;t+ za#~8@qF${2)cj%XxX|hJ*^9?giQ-%`;pF`Vc`ulQ0#^W5vjb(DM$JCgs4pOz_ke6k zWLx{s9${hBj2Pda*;pX(%V8wQRAD2XYX!st%H6vdy&I5nB#=~bKM)wN2LL2OR!-jG z5gXU)C49t!sWcrJ&xcs6%PKT3^OP=`JXQd$>1;4x41L#Aq|izGkHL}yrl<8i71X2} zt({?XOVL+R<T{!$zb1vk7Y zz`$L{)|oA=cvauu)9WVoQ99fZ%Z+H0&faUr1m{~21|OS~aMeH9?NcTK_aXeA@I&{m z_>J@*nZS!DG`mEOBJRd8I)%Ho{2rVkY1EW8>tOk`>dC6}J^k$(k<0q&R=XmCBem5^ zN@)9^-b_SSgyWvk-S2F6*v+rJG=nrxbx&4ZP?m-7K>D5ZtNx`Kcb|?5#;{i1vcbo% zebD$~8pfEx2A|x-gB+XEW_c^+=zt)sR^UmEzu>|1Ww7Hj?kzfh z9nQX|=~osjOiQt_@A>burMu;s9Z%*mI~*lIS-$&X%OaGlz)TXzzwZM&-ipXf+_6kGBJSOQoO)`OcQHbij zF-Aym6a3!n|6letQIbCLgj|@j#-5ucdt`vNy?Q3)UMOcK)iu&_8VITrb1PNy)dE90 zRmRR9rVbi%saj1R;{-r(+|)ec~$4eMf&zQ z4ZE9aL;xB?4fqAD3Jxs{Y9lcGkf@;8CQ=X(23tNBw(;Ti^pzokQml;uau^~?LERVB z7lBcF*aBehoT_Rj{Ory`Ib~8kNHR7+sEoQi(j@Oh7bHF9;3V)W?YCMe{Ll4Nb@r83 z=Gg}04E_JA#1+E3A8e}w0gS@n@IcdhLvkOr1@`FDcx?$l@y!OY?!%|zV2dWJ zB~x%;b-`v@a!luA+SA5MkmkiJ3=DFTOB4_%k5+>~>FLueisM%82i~I_P(@7UsDLx_ zR0@jZsEiS96WOj>T|feS0=Z7uI&ODe>4?ZNGwnr1AhysDD}hIufbmkuy{YDJnF0LDHPm35 zEHLbt#4<2!HW)*24x%3_XS$5Dz`kFKOpJJYASMrG9wP410T29+xUXk=fgalyU*iokY842n^!9a_yjuxalFK2Y>;b~M6KqCt> zOLX~|to0TdNkC}_iAYQ4@F`;B1+ABO%rUxi)O_xTc~Q4vjHxEhzhB2s{OpHZ(=nUT z)VD&9+utVMaRiG`X~d0i?z_5$1ecA*OyF0S_C#oL&6T3byLrAbN(z8fObkIcx#nIL z-lYHDte@c}QIsCaCoyXO0#G;kdh8R|yIP49%MB1mX)7^=~n9?)vHP-2%- zj9!9$gmeUMFNi#2>Ol_DoOBcq(uBCf`1OA|>OYQzZZufl_4M;yx?BHb>=;85%-uDHsh>H)6+!%%{I|F+0^-C0FD%kd<^1zh?j+b>({W=6YP)Z?G} zeYDwT=qwhkI+5vGUeus$Uu^W2^_5ICsMuV%7o4Kc*rUw4h-_-B4>h9ef-{yvr~lyy3U9on zg7a{sX1=NIyLRVTn47BTQVx|fG#tX8GG;2T-7NAc$To%xsJ}|ex@L6N!fj0)#p|KX z%`95vg0>~*jJU}F`0q=WT8F*!IVZ>#jPsZb1G@58XjE$EbxlKUPBl>E7*SI7Jl|eS zFpPd}TQ`|98Z+CGACNDt=(c!Vlm9*$j`8(hZD4l((vVZ~63f?CNyUX{^kmezZ?$lw z2*rY!>$fZ7=1J4<-t7N}VtlhV-8WA6TR;Dzi}h-naZz-=@MMeZAD*#=2hB$O z;!O!|T!(f2CRL)Y;a)!_=U|y8su~t+?ss^kn|n(y>*fNFv8Un?&(XvAV@*VYn7;8h zq3`eRoc#aMQ#J255k)vy)?W8=e)Oso!uKCs|9-QOZ$G%w!n)SKc28y=H|?i}wpD61^(Ktu>91f_#YpgYbxl-Y$cj z{zNnPLbT5))U7*4NB72IHW>nOK-FvD6OKi3@2q8t5o(m))Ux&mVMok9ZR|UdNSIg1 z9UtmYdUf{Qs1OSK-myi?(TxQwi>rY_2LbCEr|Odcodtm3CgLxIVy;LI zx)qf|z65r+2Y@)HiY`gb>unyofgVJS8_@)+7s0+pO)UCc}5NJ|0jqpKZ|3&Lj-?lWfzgM)g6FbU$9xb2hODuy!9K#(5*P$InqMB-I?SGf+gp=8hx z58}1rGE7A4Yn*)i*I#B-dC<^(Ql*AzdnE`8D&&-N$fWu#(Y(8#*0mu6*!L8H6Anf& z{s^7!9~Zj@N7bhrGG^ZQia*_Fqfc5{@L`CpKf1~Rb!%y_iBm^xrx`yjA;Nxu-v<$^ zNS7Q*k_rca^;xx;;rW58H**L-sjb{*?Rr9ZyT72qYniNT#9&h=BnBEX7-OYw$;eCP z9&_{P`Z(bv-D%u=`o5j$pYI^}ULkKbj)tN_e`5G|yqTXC=cwjDyRa%&bL0Y=saLyb zQX;)V)fRG5(1gXDx6{1?lS5I%Bs9B%*Kt+Z=HT~DKpF`gtUm0#COfz> zfYDCLe>2{L)EJH_p*TB-`TmxqRc6&YBH7qcL#Fj}U!hWJoyDQ5a_4d-sSf}*^QpR>Du zgq+*+ZQB&986G-{KKPIz79VONH;!GLnu=jx`4i#E3)n*qfJl3<#H(rgd_pSPGTOMY z?giML{j~6m`H@Jr4ev3k*`}AppusDrc*NJeY7R=k4ZKpfZI+$(HUrE%@`#8!!@JsM zp)2uMzxi1>!z+-^67D=a@tzMp&|!*7~L z{jM6Pa4draf@8?j%*z2q6ytHNsRBz$*M22Zrp&Vcd$LGCN6tN**h>XjG#`OE-K>Zh zr6aEuu?yR{=wcY1uI)b{wuEASTW4(Ot9)sPDI{Qvpdil<^j@la7q`xr{QD{Eqt(_0 z#eS4V3&H9V;t^<*9Qz2eNxq^Vvd#rV%4A=4L%+d1i4S@{;vlfuTDR1Vi5--c3C>#O zNp|AP0yoR55RW#mZN<4U2SqY|4q8S7t@eDY! zt8T7c;)G=1)sllYk%qkA(6x&CMVo2(+ahkGNi4R9$^P^xuatX?~Juj^dn6%)Oa6efR#ONG-IDLyiBTwA2zt}$S)u0hh+WDF>Y*qpQ&z# z1Lu~GpY)z^ZmwP`6ua)egVO&kERPyqo)asZm}SH#k`>>MeddQbrL~dx`nx7SPe0Ld zfH}FZ%INWz`=?ccOCKx>)Td7h#7{ye+9fBbo!2>S9qDF4*4Z|rr`H*03245`tH&ni zItIvD5Vz@>+d4~Z+1SWsn4`ps%v8TXMD#7Qm~_xWZzQ5`<k&9RjI%GscIAIcNVeL&Sam zuz9IR`7YQSHnI(V6W)xMO{g%CLsc7IWS_jDz$Fl_BSWy?6 z%OyE_y`^dU?-xOb?U@zZZ)FJ#)N0D z$1*mhFniQ%#jZ`3c|HrBUA{2~$3FLq!ha3XDDN8kM*Ij3+2`Kp{^o|?7qK$BVo|Dw zo2prJOq7ZXEu{Y#>u8LD_Ff?w+pKYZaAKGRpTLl5?Q!6-iwcK|*40o5u7K9} zxVKm@r9qX)E9w1V4U;zy`LnzB;#b%UQ=R)4O+x}RDQtoYjkLx!bM$v8HO%z!2qN!1 zTFEdR-qj$6J6DZ_t;C&V{KhNZ;W&apS6dz<)9=JcaoJ2}lIBV;fOj~69S<{YQeqQR z6njoFi#$ALxe3W#OSkM7Zm4%}EhvMfysX*l2pu@u#5`mWWooyaz51U(P>uY5YmE?2 zkAEGJv{0I}!+=sO9GzDazr8~0YS5!(n3OZ zVG-wj~a} zLW|W|`p2$M{{+KcSMo)Sd8=r=xTdcghfMs9PW`mr8S)~J48aikjmevs^m&GNoQoGZ zGAy%SZf=>e*=KyF`O=TtaTis*TE5JYdmW3jmi9uR!pzLx(r@>FSbECO-{CRw?d_$B zr(zos!;EIo3Xuxss1Hj+$|61fPZprgtK=IWdxV6dO$I}`3b=37-kbBgr;Rr01;_5? z2fl3U;+O8UeK1*K7QotktN~j?*eSC%!u&l!az-sahFsKfUK6iYyY@@c@_)K-`>q9K zH8TIV{rhh|;{t9Y@`tKSQ>F%ydbA z-OrsR^$S9J-GVi>jVZcHq8Soa{mY)9$)OTKNni&SWS_0BQYPI<)rakv)D zPVe&)Ug#%UW>fk*;#dFDbz0y=mh3N;YFda5fKPjA}4qWIV>vwy-#AH4lasj0lQbd<3 z4>Nu_W4&%J$enh|6rM%O%L)hRgNuy#c~Q$40p?UgH!$sc!h|>wmp}iD>bFu6m$37V zJ1+})rI|o7$v6?WwLs~59*b>YeK!Qyph<~iuId)CNOTB}$0(&s@@v7tu z6#i1Xkp>t_Tq<;VCb+8iwpb|NYljm~S~m^*FN(c6LYc)|c}pX)b1G&_s7OwPbrW;U z$h3M3RL77-%WM`=h-Zvu_#A~1(Fo-JYz$KwZ6o2lpAOin=?hnk-%{(5;v2hsPlFrF z{K~v1o5+3y+5SPns)(Zmt^h>*l{*r2zSf4uEl69;SREC9B&dZr2hb?b$;&FByxIkq z=aiR%%DzULXa{5RlT}QVg34QnGZ!PsaKqc}?qZ!on9kA8y~h@b7D{4hs25f-Y~c1E zg(AhJ{=6!bE(z^Rin8uE(7+1PRdi~oq;J&uL?Xi;X{VjYyyqqODWfvCE=F1#MCfx!Y${P2KeWav>)k$Ov4q&y|`4 zNRXO=7i0QFVA8?zR0v*_I3QeA{fnN0L(_zrp@03T?qM{z1r?3$a6&RqcB6Us3Fd7w z-JZXPBy=`pDO&=YBEb~h`3Z*0i|2^!;EdswTUYO30#_VN+XgGFW87v|w$Cfb>=}~o zOX%zy@AaGi!k4oj;%lkq$Z{im`@ z&P@=pjC~oZ_fdVN<1{sGR+o=tPAKS3*Z5b1aS=ts8c1*e^ZkNLC13;%-SGpHdAQw2v>M* zIPQ#%^tcV|RO8TQXg}g`oVG7%`U=HCO#`hLNt&ST`=Q%Rz;x}~k34j7g&&1bQ+*W2 zF4nWyeKQ}WShILmR4W@&9C@@8xO%deMSfsi@2GQM z0oX|=mNAWB=t`$H4VjT}+t%t@Po?>CBgKD?*K2KwZs?o%4AQf;c!n<@H;Z|wO_bMM zXO0Xj7$?2+h^E%I#K-u_KD^m*$FO^yH9!zQCa70#6@4u#QdPesaI)i>s()gsm1+g) zX782gfd8)Y3cIsu3sIuMmSi<&G&6DFaiBh!{bipNO@*rd$yF&Wfj| zb|4jB`~Ce5kIhnB`1tAhrg#t;+JZzr1}VcCf8It7UI=X62;9{{2K(Fpn?5(YeD|w@ zZ=tf_sEMuVX}lOE5Df{@UyQQ)Jx&R@i?+t%>?N$D>L;a-!CWxU5kE^mCjVp}Kf-gH zt$qMfz@PsKpUJwPXDM5!S-h&`{eUwanQ-y{k@eM4QMO;Z(kU=>cMRR#-6_q`%}9fE z3P^WJgLF4TBi$&iw4}6jbH?`<-}%n@b66~3-8|3U`-*+tb=@Y_R*8v-PM#P+noZwj z3BYJ%u5*#yI=*=!oii!b0nAgg4Cdaa9I z&Q;&~jt%Phg%J%@JBRp^!f4*%XY%2bNBy7{vAvCnM;$v^jzpLmff>rE9|>or-Ptjf z8!W|WDpz6Adr=1|ygiv=I!qE_iFilk@5%|KWmI4aZPr}h@s6WM5P=zKWH#dkTXqJ= zn&S*n52HC5E`7@r2{Pd9zNt?9;E$gWBzdEoDi->1?RiV%q4V2E@q@Z?(o9cCsVS*L zRDJO`{6f)s7MnD=<3-+D)%Q*Qet7ZFY~6pK9hM8cf#-ie{OdejQZ5HwbB*|{Xypz3 zCS?Fkt}2S?1~l{Y$pC3OMZ+P*l}2RVd|F+}F=c8WcNi63P@h)#6kW6+pt&&^4b`3w zChm}~s8S6h?i)5?p9F5!N zuC~&A(;-;>iEj?jAFh`;E)KGQ#Fl(vt8c08PX;Pmlz(BN@zA!9v=#&#O z9Cix(t1dT`qt9Z{YylgFl5mxen@Q#u>?rwb$oJkR~} zMpQC5V{q=VX-+T%#cU9v0VAxGbFfv}R`>U?((P|dW!r(XKYUhNzhshm0MaHFmBgA+ zVF8Pc@`boW(fFu?^Mf2T>7f}4Gn-a3J|RTmM5*XfI}{tAJ*7*^PQ4BB3E(>h^=Ch- z(s33ev=$9)gJl~Bc&M(5;XlO|UMeRjdCA|fV?or!+@zQdN)mCR`HD(4u0nUYq;yhY zBSM*4iYe@JL;{CzH;jXf8LKp~m%Qp~+l+HE3y*M+ay-cJaXXO7T)+M_PQ_O;Dm+Sg z3tCA$?0g$$qjn%?YEOTeGSp#u54skBO;N|Q>_g78L(7E%)G->~CG2@DDU#NMixtt$~ z|C!~n>*IpuJVMTaJIpqGev~%{AW*JfYUCm=4%ww`e7nqJc<@*qMR_E=YGZQzWr1tl z=TEYWOB>E_2fi884LhhmSh&JDF4fCmt5fz~ZL>4@(RD-GK0coG2-CHNNySm_}KKpQPhx>~%@-$}Qwzid#BpQeHJFykeWh(Lz>F-AKddbaxfXVn|+DD=}m>~9C-_=^^7+1U?AMB^& z!$w2u^8n{&{^jiU&pRQUYi~kt^j+r|4h;befBK&jXhw?U0Z(36r=#c6sF+dblB>M! ztmh-B>`~{l+-LjBOU&W{PpONOTxYmjlHqVgT_jt%61tK@EwHf7xIGT3P#8q;00_GJ z4PElOe*Y-<2U=8)Y}+>`s&ml|Ar!lTn`Dqb@B6b52-7W0*2g}W5v%8Zd%|7?$ghGo z)pSnrA@W;lG{<@qxyWAIKVzXzPX_h0aa=IKxL zlqN}0(4ulSr^KAvV(bx4XGgG)2q4Nqn11@KJ^6!I_g&Y~D{+d8m!j#Rt3WKsz2c(u z$dZ&fZGtkv7HP&XT_Z%X2qJ^cuZh8rJwOKy%(m8MvFLvgQc3KoF?j{C`Wk^xxN*O} z{inG>>$H>4EbQzMk;-tLrlE4G>xHJpXrwQdqoIt$D3PfQ7hSjPP+a!Y$#=*YdI{u> ztR_F(Y?@{9tcH{jlLWjs;P5&n))BYlw9PW4SVMz_Z5<&TMruObPupAJ0A@_YkAMKW ze)mV0YxtsWL-SUoXx8mp(v%Uydw_ z5F`8nNy0QWkJuMDfeNRCA6J+#+mE*nzHk4kt9AU&@@H~ktEk48+5 zxE2C%&|%`AzS!qPJzDwSPyhZRnT3{=j?fS8T!l1R%rczv*|B#~gK-Or??~Pr8*nQ+ z$V#0a?v#fshKNWv7%@>D>ZYKIf6$645obJq}S}LdHGR{1Qz4Fv1w>^5Dv#^iTjpT0E9acr_4^t?YCH=jaLZ-f?hE zel_4aWWnOMfxZfC4IV?3+^VxRZgCWWB7@{2@pmGY@2se~SYhqS_HK5|ASs^M(8o`X z9VKQ3#S!R-@v2`bGNLs{Ek}z6jvmrAG+<(|(FU2WG;fVSZ=BWNl4&9yKERQovom_ADEARTQk78mUKF!%}!d?o$w4x1r!O9buIoo+xco-EprdfyBxJ~h^Ma(Zm zs@X)@ln!1%GS4e;vYdB-)&;}{Ob(1jg|z9(gnQK`VTCN|$x^amOd8mF@MYCXZwrqf z`f1fX< zQ;7YQoOymwOSiBq{=ILQMK`44V_^jw=NYk!>}DlU&vMH%M2~K77t&XfSdN8!%=UNi z{3zsX-S<3sy9>Sb0QfYZ{J)(E3`-wPnCU);8NLWP!e?g|-aviJJI>X+Y{cwKQ z)_ve2?qtHHO3g1)=OX#!xG6==jVs_Bj#eX-;WQ}n>#JoJ^U|_ys^4N_$tlvQjfdlD zQ5OuTPe7ANtvtX4eIHS<=VjHeq-XBTkNA_x?4#;rC+>R5cqjaNcuEA53&vd|YEZ=P z%;?4Lm$U7(xXB-)uAu!60FsQiMj8@42IZ3~sMj<2A`8_vPKdDuFundb;=gOdeB-(k znYGlLK~dkY9(iFYAbD-dM2fSu+>|hC3Ys|*_fb;rW~0!%`vjpKdM){}qxZof_UU_y zFY>Ov4hHFS!PD-CuD!yP2NX@QJd*R9IQmWTm(GXQ*sWL1T_>>MU4{JahNFicQi6T0 z;jXKW7>qWQT9tWv;)dFQr@GD<;*UW51E1cCl%9*_oL{sB&yYU934$!NgM+3;i_fvf z2O!`Ly0BNhO*%_&^Dm*N*8*-z+|C~Nx>X{S{a!|Q=9)bNXq2<_fN5lZNu(zy$-7(r zZ9@Cyy*^PJZ6IYpKo7(96#{6*ZJlXfMj&Ify2fSe;BogUyNQ4%Po$(|*ZP$ASMj0) z#3*O;!Niqot$2!v;D`;@`Avq)$sY8f^?@0X)tp|*RPL<7>NAvOmigSo_`_2v(Vw7d zUs&&&4BOR(x>GGC@$8X??KI-UzL3lkc+6ifvUUW`RW-%f`I_5689#SD!Bz7rjM_4# zXD;foIfB&Jyom5;y#}d^C-+jzRhIunck%8-Pr`TTHyF&Dg(Zak@``|mY1*d-jMECwZ1W3(O163WD{Xj_BmbgFnD5eb-4 z22SZ=0T|qBEFn6JHdrMSbRW+nB>*#8`};@qzP4*7F!@Hu6>HAO^Dt8cW_>c;>nnVA%TCR2BG^tG4s^rkpe zuFVibeRI#IrpO9Bv{9!M`(BBv@lQ_T)aa$&G*wx2eB2C80s)B;XNCy5^x1xj^zjp$ zq)y%)8Np05t|qU63iXs6BYLWv9Ai}>IxbD2RT`|6!CHeZms5NlFcD{fMQOS}Rzi(( z-#wMu^D+dH3XRZJ>yC9lsCpH%nthYwjfJP69H)|An0}ZnxB=3?q8k>0%E`vo$^I=i zjgF>S!?2;m5`Brf5R3>q-aFV!Z^uG$9YsL@Pn(CGLvB3$A7J+Pc={a2pl|VtUIF1g zBRGL*N<&xA)lbf%vSKqsuuEURz=0}X;m6Z9o*WE29?0T5q}-Y{S*DQIwY-pn_J+w3QtkMoqj)92*oEt zGkMw9qnoldp}u@kQ4+vYQB;fn6$?cMNCd(fkHvE<+DWPiNf>jjr;L#G#O{}62ZFTq zjJsK-*7}Pye^xdRX%Ohgrpag;5?cos zTBpGf84_7zdD<%`y~L#_p5Q0<&C^jiU*JNKcSLeWaCbC7rUnd+lp>NG#tHha-Cvh7 zEC=*q|0KJ1P3C{W-bnr1YhYxZut8`mokRB)TmxdI>Sj5yOji@H=`uSKb#ho9+QH>KOZo?u~AHIc>%i#UOpMC#1hI)|BfHhp5{w~S(Y{M5!cPd&Kc-YQ- znlheC!^r@9suluA@;5!<-}Nnl#d3mWE{n*v$6P_4SMnt-@6McAlW5i6beR6Zc3}8M znqfnS_rwhA*-+_Y^0S{E|9qV9nk43>obpiRX_2akImBuGi64`}?4r-+zmIo%PHE-i%Y9D#?gG)FyPGIx z;^Tt6q$3wUzEGr!L)IOO!zS_vuNz)(fxm**#sbfwuUVD$9n<-26Gh^{%5}#l@wx?p zJv_X?KL<1yV{tF}P_0iXtoQBHwyikj>wE5%fWxr84C+9kXQDmCr=}W(Zy4Rhx61jw zG3U^oRivKUa}r>0ps3c_-(!?Zc$G=JrRq{oI~%xuoQBOO*p=npyls2*7rZJu9l3aO z9sqlWupU*9NrwOJ9iX-_2d1YWVnghKqs(jW`aQEqppvc1KV(+#| z)O(E{_&q-HLBs0MH`v?dyO(`cPW{=T*-QchJ&IiW{rax4#X;17y0g~%$hgSbxuZ~$#U{Ha$kn`_S2s9mka3E2qjF0WKlMaNqOX(QZv4-tq} z{fht7vR8udialK_H77B^G{Y7A^=(+X>7%hsIm1!^OOrm9 zosk_;iDS4;F%OTlaBH*eL$kA|>j4kogRj#k%6<%ZSbk3EvnLoVpzcFy1&vKlY)dDV z;?$x(dW;K-nUyidd%#72*Az(1}!d31lny5-0gkAkU|fFu*S&8&bx+mu1Osj z;1{dJ@A@jV*RMuj5@OCi((;dWI~hv?9*R!S4u>s7d)Ym8UcFvlVPnP*&MY)idmdhG zwUJTKJ--0cd!{;i8GKaUNCp!_0Hn~vO-ejNNmCeIjwI$Z00ZCdCot@^M{3op@qsi) z2@4|G)87ezA4dOw`aCOq5S3H zo*ApFutcvsYswdN?En@pgVbalC2HKkU0XcuQ9|=YChovEOT>X{LpQn6N+ZjO$Yf21 znfO8LCK;pVv5MD*U(q{5hgLt}TrYhB!fKr@(*fxX(p!G=sqr!_!;8Cu!~?wGcIt1F zz&J5zdRE$51MY^ZUt6s`(qF3gA9R-X|527^OHiLGYm4OtQ8{$6Fty!I+n_rdZIvms z$|6n+pFv^DuiZm3XV8s}j<&Wju;q|ep}3H3%mqLJ{|g~0CNQa6O-YDVYKF=43wrf8 zo^P@Tg!-g1SBT#t{jN69eI~NMZkIL7eIiOJD}ZwtMv$YuI52QUDda7n?5}Roj!TJ{ zc__%IW>c&zl2Tl~70t^LM~O)}VEw{U@#s{Itn3iwnl^~E7}_U+KqFPm)=bSTMLQl_ z=bd-WwMJcQ@gRp2on5X@$;YE%Sj19U7}xPgnBnq1tpkcL+!RNCh+Sj(1D27Y<*fb6 zsZtRu1*6;t#TQV*l1LyuRN0H)pM#mmnk}( zc4%b1RoX6| zRwBBxe)`|(c%5y;h_W8v2%wz8q{2l{^kd@cXyPWaB*oo3#VvnC&B0Z-!cN5p#O2s! zXSfjMr>j`HratwW2kf(@y|gdn3Fzxgc|=y#G?bV)Qzt1bfl>mhI>fFjof-uJo%ou_ z$4=zJ6+`}$s}i4MxJ>ra6w1somEJDxD-7!CoF~+z@f2P8Kd#{sMix0>QDQHRC`MNm zzl7)Y@#@q@o+I{)q%-&7p=Sg$JA7^fTncVoIN=l{z=lkvAP3f5yy<`LgV}_66(*Wd z!_{IR>gvjM4`G%`P#f(E0Qx?LFY`YB;bg}wr=a<^aUfj+mXWY1T&kR~6 z<}ccMTiN^f)ufN}U)(+jx4J{oowGltIK~rfzmc}jwAFonzK;T%@OoEUZ z>H@{j$sq1Wn85^bTSKOPne1mWjprI7&UeB3nbQsMb1JJhTWqINn2HV@fFnbuBL%MQtz;FRgUXjgM(1UgN7j$tCpg!$k z7iyynWcxNzpH2KdGPTw4C!ex#?_~c8tyUm(wn0ko*OKA2&1^UoE~lJ~gwi9i)`*3% z8cKuo^o(JrgU7W3H{+S9#7Fz!_B$NCH}!EwMh=zP8^*dN=3()sMwMl|ON8mqA|H%X zt>X?xgMFLEw18$%s9BrQVkIP|>#PraBN1-Eom@FZJNy262JmM|K_cyk_MbOi-J~@q zbeCZFl#PX~*u|&hBG|w+^;KeuD0EaZ6X6V5V|2wv3<1!DdTmRfsEhvlzB-gWKNeOz z15||K|B`lnYOYZFXj{O8u00k@!hmbq!} zEH4nRmV8eCaGC?HnD}p>7h(b!(=H2 z`E#EEnVMd!d;X`^_#7s&tna^?meFvw;#ot}6@=rFimo`Wf@_(S58=;P3(i(TYmq%S z@<7TLTyz#8nc!#A8mY;lUDEEF;jI6HQyBR~o&RaU|8(No7?03#Lkq!_FpvKT&bktE=GGnDOe<+erHHT8!%ZQgOHjxVTKO1gnTo6t z-X-8;he7vI5Z2Xn>A!g}-(kwx*eQ^lO( z`W`kSWGGKYVGKNf-TXrQ;2usHDBG8f?Pu<1n)V_2?o*28&BC)Oi;}ThpW5k<*gL)R25#bv%% z7`vt^0+zyR0~{*nt!N9YlNCV5B)lW3Jz*OkltFLY2hd1zmUZkZJl*sFS@>D{w-7)U zpM|7fvq!qFg4Em9T3U;o9mBLy*AEITZ^73~Rvvy+FE5#-FTTan@@n>bAQfIX9UN{X z?HbRe0>h!H zKl;>5Ss$Z@KH|GBeWE`^`wWqx!;M8I0=ZThfX<(CUUN&4CgJon*ib-{kWdb1R)P@b zB=bC&OR_Bsg<&YQWc*izhpMQ-aoeA$s|k8jmA$q4*{cvMPT z9^P(~)tz|0kA6?1Bgwn8gq}Wi%BOdmfjVNmgy-sF&*nasE3KU2BkI3ZN=KHo?`!_T z#FG!bFaKMRYkCbjC=S#}-M|vCrGA;7!<+zT2gEU`+gGgY_QJl%OUT}r(CwN!wNQLG z&y-tWdi~6l03#lejrnLCK7-3T(q`%OdX_&g{FvTba-PWPuaM^F`aHft;9aq_?e*b- zQ1A)K*R*Ri;Y%0A-G`7)-rv&9x?w)dPvIf#=&2htGx@8Pmqwp@%YS_3J>?h|b!g8| z8uaaT*6WS?4k<_=!OT&QR-?55hg=%p9m+++cNzQxJ@Z8sO{p18%-^}$uAVqsSc_W_ zUCT0er3%ozT8Dg^F!jLta^noLA09Mn0M49Z+$1bOpy8TKh0VbO zFH`=r{F7rQ0pxvJRg$?_E2srMbebwH|YFTU`^QW(%vgVw(#Z0tl{JJ*?cEl@&VGOii_; z;FoN@E@BV#{Y>&O3P%W5$njWVg5zp-A#udbXt*Rxm)>gcqb;3^Q5j#b>VLWj6G?7w z@JVE1!*CGQtx0*$Wb4jy#y07=`jb?ow5iGON6LwtEiEn*z)wX5AU$QM)MF;4$RY~{ z67zr3Yd&3OiJXwm{W|1MyL6u;wL^CnMd?Q~aw_oQZhL1L&a6O5ebqAnrI5M4I$bu* z+VwAYxsg*3u|I7!xC&|%aIOOF{2RCRIZFS(J!F+$1S*lq0&l35 zX1`QQB}Ik~YRdxe9Y$nz90*YnqfJT;Z=!Od2zeE!fsH-dwF%0)j@z)fSrSNXkw)q| zhqcTe2>7ygOdbu*^WXTsArQMxChzD^vo~Qeua$|jbU@|?B7{dvkTXcJqweTb zeAWy#(m}tU_vFHqwtt*NT<@o@eek1@CO~7l0#qAfQR&h#!;1BBVMkW`Jy%0EvN3V9 zX&+ZZH(#MedBdTfrq56@fkeSu1=fatz{-H9K1DGh8&DtyJ+G$2+CKs1(Hd!)l~Co% z^Oi`lw2E3==hH3t#dcOm7oEoi;VpI)7_Ou+B7&g3)n7A&o-0{pB%&0(yq8z~a@5bd zer!er3sT_&)s%*O#-GLLEJ1|;8n*LyVaXX?470b`8aD`vd;TkWX0#v^ZbhRoIvpY4 z+c5lZ0R3jAHAumuEQq4EV5}2#;-7e0n4$~;#U$i>Q!=?z1CYa$!v|t{3%?l`3=@Y} zt8(jD_;uC1eRNL1TXpFlqeG4*U>1%v62BreP87~foujjRHHjYdFmaZ4^LBZGKfJks zc()ge!9$#R+?Mre?>pwWsnabVW_JN5$`kB4Ti8Z)c+l1AUs`t1I-(aBDH=#bPF9D=j5ckZk3Vn1v?fZ8${*qfWjpt`U*MRn}xic_-;uTWYq_23- znp8W5Hxl#80m3G!B1s8!5tAXpU73@8g9X7cA^_JE*;1d<()!h^%T9)Xfx={gUvkaT zN-)TD5X`^bbyOcIm;e0RmGy=DXJ01Yy+8hN%qLoGmvFQw$nC)Z2=aOH9X8Pe{_qPJ z566V_h2pg6kL=v$=0LM+A( zYoP%ZN`a@H!A4Cvmu<$!!yfn{7>A4N3RAB!DFPlEhsh%9cJ~(bWN0yjhtPEL@Obtv z!ojy85@t)T|CrIlqKFj3z>CS!KvXM@aS7UpXr0*DUn_fWupAr!rptU6U?L*2AwztP zi;53Cm?l44U9l^EQbXfT!$ktRB0Gxma*NBm2oWI`>kS>es@F&9<({y-adu`6zZTsr z!S*R7`7!p&`7g$@hJ|mToan!Kw9d4@PwEghD~eA_S>kUhJ~vmCf1G|{)%tBOg;G-j z<~J-H+p^_Ofhxc%x|Hq`jNv-k&zL~v7F+Ln531EMFh+lP?`8y*9p)5v&Xr%vFj!E;+7#b`;eTD2 z%IGUxm^?kKG;*?h&U~O8n5{{j!(A5m&CAxZ>bR+v|Eebmd?f7^m1ESG)-0eNf1kXv z>rQJELaKx>jYzj0Lr0jZfRLnmcR!D3*@nz{`XJUfMD@Wn9LrZiKD8BD`Ec(dOaBo2 zyPUmcJH9MPvyceWE(`tohuFT8jKAW4Op_dH|8G+}mLeA~;pQvN45|G6uAenJJyxSh z=_|6V4*QiS^+FNhp39hxY?p#sSSXXM?zlMp_kOxG)?Z8zuizn>o2qeaHQF^P135c` zjN^KAoLGbs7+VsFHeFu% zh@pH}EEOc&IZaO@aQ_~uu&~~$AcYpmm-9{vJCgPnws=6Jttht8Ga-p2zb;P(m3X~X zip**=vT$x>XVGkja@P<3-R|1lFd_ObHHMv1=8CpM5Ne1<8~ZlOT$FBFSTyB+sA{w)u$VOPUlD3>7ySZe9PZB{xPdJ$-l^5O zqY-oaG3q~iG!>s#zW%Mdu81kFjo*M@v?Iq1r5UxT(eUsFBf(4Bx!;x<4CGPiQmYBs zgKuW-JS7WdlLsXkEDb($KwRZu3J+m<0K_kU()%QgNq#EB?xK6>98g|q{zPsdIIb#3 zL&lR{V-m`{v+eY-Njvrbv>S)~y*1`~Ck3p4!pCY&$nIZXno5;~bu0yd(uX*-7P}>p z4pu-#m8i%@LkGffMXdS`u%Rjo-L+&ISF#$z^Vn>vDs&qb*0G>aNqUeV+cn^|BSV#i zcsqX^0as$c@TbGUYNQn9_EL$**K|g=oMsklR!IyM?BVJzwm4LQSQN`>xY~%#nZBt> zPvo*Q8@I_Z-~G8zeP5^`YYedAEv1$kE48YHtTp$QV&ID>+qJhp_B(^Y*wl zU4_7f^i5yGf8huwduF#O#S(9UL{#fn?=>sQ(P!~HE%6*Q;8Yc z1K)TvICZU!khR$ky6L_xDIE3E>lq{MvV1dWt+x&JJ#w0&Od7TqBC%;>(+zv{28?IW8xMPAlvJV0R-eaKD<(K?zt(@a zExWMYY5(au@83W}g3^V%agh*{l4w6J;m@1l5uZ2Uxa)|Se35lH0_85<)nmhI@jYc! zt`3lNt=BP9{aiQ+9Dg3|B9q|Dh-L56_;VK5h6tRr;1drY_r6FpW`1hQE?P_kwModx zi*t8VRv{#Fe|nSyoGOf%p4AVc#husElpX`>cnbD6nPiGGOJV2{QZcB-=HgIkd9lb> z2dQ9cX7t((?bZ!J?mjnTbz<^-l06A)?bS7vwvRH`WF;tyHRW%byhUtQ30cbXt7CD# z9Qlty27>Va`9d7cW?>(^8}Y^TX#t|D1|s?N-YSG+`TpPJlT*`H^ME?piRGT$iYi{v z2>4%K<^PQMC9xW@;gy<9OwtV=vIQ35$v`^x&$SPzo3iYZHCxyTWdRASIXiW6%C(M+ z%?S89_Q*U7kjGz4v~4VExV2KujVwP{PA0LZN=TLSePr-8(-QKm)VSwWCUXoOnC3Mc z#J)F`YH%y5u03M?y6jHGSuWG4)Wq!-a1B1l|sN6a^Iw zadAj!gzMv?$-ow&GSyzRBLg_9IGB%+e!UGpr=G|8;YV$#=k>N0j!Y*#wvbctxK4>C z`at#{-?~?On1fEDm5{>wY@AI#=D2kb<<23c!m<^m)$q4=qOjt>!aqb_mBvBt^E+u( zR$lh{n$Q$l{Z6T54V?(Lu$G^7^rs?r1w0&V6&nIRj&S-Kc7&cY-$zB+xlUj60`-ac zci@oW*J)=%f1_&;YV>Qh3Ve-_8j~K3-}V3qQwNfYFTgv#5C? z|BHj2r9F}K3X>bi)U`cj`!sfg)&7^%#%Pj1d=~Tt=#x9gOI~xpss^@h07_tQoTj)1 zxj@W0UPI2%IiBV;+@Og_F7l<`=;a#kB`YLQF>A;0cdgzFpNr(baZ+~0!Suhd*UOHf zSgPC4!qkUsLgSG~$jr6KubrGCH3ilPcU_3fl{wq$_{GlO0v&Y^!~0aAPcGxl@1$ZZ zFZl5s2{{M|c-{K^X=k>0>24IIW>T(efC&kUoM#;FaInGat_*}FU>V*7EQ@oo;oD<( zinxzD+4;APeV6h)e|!3*smNb9Jg6yGYs*#aFMR1|(7-5qD%5%T4)xpzwY^(0N|0u_ z#wqeAg}na29Bm#=c8;jEi<`r$kY$MAC$WTtP$ z!n+gb47W~y&KKUcwdjw-M%@*?s}rt=V8VOufL`~L=;gsi^~wLZ7~d9gwF=-xb*#7R zv`M~^09jG4J+qjvrGrSxm{`2cA=nj(xMTuFTCST##PA>OC+|TI%ktrvDE`OXv)cBV z(amGvJ}u0hOKcuFe*%G6R9JXm9=}ug^|E8$ex}d}=L^wrL^wZp;IBXL3@txr0ovj} zW*E_E*O(4ymhjQ{)iTZx*4(ON2i&^4k9vl8NRYXPf&quR-8(-gYKJr^2IuLdMdwOh zY*2FN!oRBKC(EU(sxXRfoNn_f9map;(%_RKDmfOQT3?=OU}g;~m6+&| zik~VxFtjfWJYg=Si@=976fE(f+5hRRyO@$3JEC2JimlF+CpPeqocmqq!sb`yVq(%V z%aT(#A0yN*Q2KZ60PeuH;s$ND zjl7)Kk{DC$P4(I`&f#MJ*D_UcyW~)knP=eW^h9GoJaV6|^$&jKc!j>de^CtgBs$k* z)^bcOYg6Ef)#8lslFNwM*SeZX3*hD=$i}7JUgtH3nnYMP8+GE>9*H5cvf^q_Ur`6? zcc`NV=y-G~84$Qz1dPf0QYdQpBXdYYgFA6=lXL2XS>t%NO)p8djtP+Ue z+MbS3P?=r?uwl_2togV*|2+NhNYodZ+z>j7NcNEl*r61$hV%d_niS1{T*cRyvWuKO z7yQo3%kv8+!%dKwYctEno91v9wg2|tEjBxYvg&`JBotA)tRx|8cXCg17Q8PA)f(17 ztOQ!KE3%ez*%m|=25a4*1S71fza`+w&utVW0M@ZYnro)TdvCGVM}Cv6*v2mtj#6O5 z7CMAICgCb5kzxQFpr`fgrC?+!V(XUCwa`UXfoYp-^vwMlY5hH|Pr}X3lnvKgU?lGf zXY37Z%YO$Orb5}E!KlY-^J(uS3Jo0dX(SC=aj@bO@g2N2`*O{8vP-U+p?#DFL(-jr zAz~Js-SjYzl-usf*S|YNag3NY6$in@>2CBz)r-ayIu%h`eH!)Ym6161sHyZIk{A`W z2(|jd>B3sV2L~d`D+FykJU9oKuLV{J)Od}3u_0X@1yT0Z$x1XHScm#T)GTk|Lc{1n zN-OK|#Z-}B=`WyzFeXblZ8;MPmNu}ms?wxCSqHl7x6?}_&BQoKNbMN{B-&WqRTz9w zqQb+~H+wEZvB!TCGb`b*)%FbNxSU3(9VxqZKC{u3eNpl zRf1ggkYrEQ?}SxiMdQ%m8LklKS=B1*)rhaXK>mub3$O68_!>29@ zDJk?J{un8jC=Kt#``7IJHCWU&zdLIS1E)zZyt|Ja?}qs3l=&EMY46PZLV&}D=Y#6c zTZAx#O~cujM=5DEO{Jc!|9Am(^+#n`thhjrySGZhK1u%=4)cW<+}d2ZYC2`w^>ST& z#m9{yBWE@xR^o_ka0IT@H51fbg)Tq(5WwxopfM{5VYC61&zQP^)=Ng2t~tXVxB;)C zE}T0IIjvr_J}`2IPJ8t103B!&dG(80j<})~f9n1h8v8X!Up&jc(USMG4U6~R*OA0( znPNb67_Gdf_oQUr*?QO84JIdyc(==&iq|C%ecy2D?r5bVvM;5qxw&i7E9RWCAG6?z zL#<2j&5P1PR0WN|GdRKJgTL4{be!qJch4Ur#hUo&;QfY7Y2mHY)TT8y3QLaWM27fv zIjFtCufvZJNBb41A$9+Xm6yQMdwuog;+kyjBN|bf-v;S-SKMdM#f6q4y%Z z+57cc^ws+7Mb%1@j6YOX+C_!lKFPQ_5**vVFMIFdfz;c*wtWEwg_XMZPCDe+-U?gJ zTeWCGOyjQTGvb$lJsvbm_80+b6Fc|hU!Kg+&p7*oqK$A)U>x&P#g6g=CAXS2)vC6d z<#Gfc#7t0*luWcpoAP09%YLprYMvsQB3lf?x?pUPjteH=EV> zhI4%8ReSVXi+1I3KiB+$ZUMz7GvEe}@_yDO&Y*zWLoJd-sgI*3?ZgoHgBp>nDIkx@lWjmh zbKrLc_qSe8#&ES%ARP#OtwukuW^MFqHt}ADMeWPOm)R~VVWDuv2Apht(=1)>fXnbH zbTlYE*hx2R?Z4(IQff6$EYWfPWC(U~Ap^hpJ#$pcJ_|93ChPtYOL4Xh7LL-eed?sU zzFQ`qX?CZix)02ym4Ckdz1T~TOudwhZHd_nW*<-t+PEakYMX-yL7NkOLmr1CiIx3! zQS+Z)9CORbl#W$y&EGKps~W+!Q77ciTU4mC5#18eC6q|0ED|db#tyO}YQ>T?mAILY zLskoEZHMEoQ@bQ!sH&7uA~l$h`|Z|f85^55aS3M7YbDyL*+yic_qYY=vy9DZ9#A*K zBZ?&qKln&w=vf|A&GMc4qWz&!mZnXmB_iiq<9(r}^3 zQJiv|bjtWt6WsL2qZqWXX4?yE*QbZIm3}u*0{gmpUV8k*61}cHEe;D`I;%RI7P@b9 znr>hCnh+g+8xWg2x*UB^M?f>+y&@i7kOyTV|6yIBtnZ4;aq7*AScGBvd!?~Tx&(7%PXbP>ZU}!2WJH??n+j+8snPfh(YFyJ)gwBM1H^UXf9H}09H}M_5lC0>wl3)&ByP~yI8%;J9^~K8t zcBL^SE3U#O_2Ps+WHsE(BlR?NV*yQ$0FMW;{a||U&Xsp*L#38HX@JWL{i6)JqRRA{ z^oeD$l&%oPN2>h9v=KU2Ry}{Ml7P+Vls}jZh$+ntL0RVb7Lay zM~tobrZt5dFA_lcu?`W z=r8Uy<&cuJL~YO*Ee5VC@pwZ2wN+bzam$Y8b(%Nj=9uXL$ek|9^~Nu=jBYhBIDMXB zRVF6BWY+zCZ<)JnENgpD!K=taS5S(>NpY~JbPN+s1RHIG=G++d_8#^VJqHa(8P?YD zhnW58CLoTtWIlv5rt{2M-i4PB7sLNEc;$Zi@2}*iG0DKbF*5J%hk?Tc9wVKO7<(z* zIl)5Xor=0D`|&oTnKB051bKNOJ{578ihlJOz*raA5M*4gUnQ?B%{fCeqP zpQZTjZ-}`Ye%hxd$KFc(8|z3L!GGUUh(At;$42O>U)~ zcS*!oSDa~Fo{QBas0|#Vp1*J=dw(lYhZnfVk2#@tcJun!XRyY8ek*e?xS56A>mL+> z1IEku`xR^Bhc528sTke{C##bO7q~xYc`<9)HEfX=C@HV8UVC27*(Gm0kV!)AubDR2 z`bm8Gpfpfk%^`K>0uhf~cNYNdd`nxz3o4IN$K*OUThnv0se1D+>wV0NZeMRM-0Xx} z5{*Wydq0L_|3ct8Dvk>43$s5b$oB`?@a-E{i{`%Nb1B;E4qQ3Lc_maPNx(f{`LYHY zKMMeF#h+UeaT2%WD9wGl6r#V-DMbF&gw`c%;a1K4CrUrBJM71&g>B}#?N|x30%&GNg7mPhYayrWjM7fdZL-um zN=ak6v=i197-$S?zcaE-BN;w@e$4FN&^zpVzqB_X7D4f= z|Nn6H6@G2C%hoLvinauo0>y(n!J$ZSio3f*pux2Tin~j3_ZA86PNBHF7l-2ZrSG}t z-0$3fAiuqz>}O`pT5D$h;&aPri5NCk-@<7)IoojL_6df_=iDxKUW8Op|e z9T}y`#gYlswD{u6fxJ8k3SYnrDrIk#R&6%R|HH;%X}$f%n>SxhlcvB41Xzde6YMGH zXzIfU_G{6#TwREsacdOE5zuvvmSTspg~VL(?bByPJ2)MDMsC1Q>Dn%=N}@DU4ntvQ zA#bIx+!>#Ka_6fLN$2zowOyj`*RY~cldwXWifhV}h$6Mo14ZYJ9mFWG#{iJ+B!r`g zxca6Ci76bJzkmsq=*-D^*s{C)JF>f~yZn<;-a6Z&ddUQqLJyGe5NV)wSa`||D0o5N zpWD>27)(lxiswQ;^AuZ=Cstcv!El}yRrzNY`zsT^uh#2fM$6Pl>0%Ve;1OyRjG>5Y z5MsAiTI7tO5UF#BMvIzJ(8$&jbLM^~hU@&uX{B5(ue>xcpiJD^lmME#sUCQ3Ap^E?Jp5tq8ZkUk)y@-FpEv63V_cL2 zbagxCwYPTAUF(};%<_2Q7qSjx9!N>>VWx0ER$eivrE~a2D#1teEww=^MHHZz1CsGg z`NuTi=Bqj+g{^fKKzoEIq#`G*AQw;|UD78TiHm2g%#>WRqOiWKKTxR2z_7%QloHTv z*+@C#&^5r)8`(`N$s8Vjws^DVsgRh2!rnGni>7h<(kq-YzZdCJ6-boz0;}Tmgw^m} zbG6ds)3E&sfUJ3DXrVT}<>|$6Td%nJv4#3JIz;{^gBJ=&iqXAAq@vn1uoQ&(o-QhB! zoz5kzOHm-Q5F6iLa3R?J!rp}5*PMmkbR-Zy`r0@Hd(QfukHJ^@v<$*oqs~&t(rP5? zN%|Z;f+3RS7slLz5b%%Ip=ueICD&D{osuHtW$td`s}sgiR08zu z7PXzbBQC|eQ=+4i0z&TJTQY;s(@Cm7RINBzBPuLkFOYgYj_s?TRMV zlBSwuEPXYO%bFc~MAX6uG9$zSKMpeU<85 zRkb10Yc=;5y#6@K(XJ0Nc(7M3r9J?ZF-PmtY9gpw;DJDUt zQ!1E;ltN&#`Yl?QCgpZn=JzcsI_~(fbA9%A*zQW}6ak>kG^GH66T`iPI@fsJ)q{5e z1*VYTEVb=+Tz6bh)Lm|urF@v*^I@K|57krj+l=YQ*mHC=seoB5VGWkE<_1nO-H*af z;Qq*U%C3H4A1z<|JcH{w0xp7nZ@Hl8EM6w^=EdC$v0^{O7KOlQK`$-g8sul%{zU7x!yKt%jH%Uy#3O(_LqcJoj7RYWLYtZiH!6{Yc63`9S{t z)F40#ZzU`o)muDal2B3TUa_r>h~qLZYt{$*qMDctFia8Hur?z>Cjm1v1~X~13r;0n zc7p&0fP<(=>@zx&x@bqKsEnz$9KaO|)sH7dy-u$#?9@7S7O+#D*3O2a!1X)6lGGeQ z)3TK3mHMeW(Vl|LmYq7A#=2%7ayb{SrlFL0Xdrcc&1B!!vO7FU-BW^lIglf?AU}uv z0eD~}@UJV=qb#ULsWza{-&)-b^9XD{dDCaEk;*||sFDP4e^k{qkC+%7--Swh4cdl# zGf-BEkwIrod=x`%wZ6UfgPhfEJ;lKqP@vPdm$v*f)$u1;I%p`pqrnb;RF?L3-ZXT> zw?OQZ7z2^`tYfIs9L1P}%g1U`9mS5quD;^=`8~xMuEU+Rgfd73=`8Qnl<4wK+4neP zm9xt?$bP{2H@@Y3*uA+dg|Nr9ARGYL%C_(4h!mLBU}%eHX(0ogbN`eLixc7(kc;~X zfNB4faD)h)TywH^8Q{0CPC+Oq(-=5E<3t;!);Lt^ik6rZqfSk!D2c0QTO^j|11(HS z>pwv0xO@LX;h!6WKls_^sN)C5<>NnKSTl)hNE6YNVbPmKQhZO!K%oWXm2fa^1X;^c zvwQ@7iC4eO`BTaUbTIg4zP;40Xd{XUq74C{i5~W&Dg-jXrG%0J6feJm$g(>)49SVyfd|=s3g37D#FSbR0g1?i-C%HWRp%>}I!Vp(bsyx$MVoah^5bkT2N? z^vI(!C!Q>N{LKjCkooYCd${L_#Rljxh{-ii56~Nt&X8#iHaWyURe5~A1?xzzN|#MU zu>xsKfjMgB_nBd$+TNtWgbdiqp*zJ(_Tqm;*Ti=}RT~t2oID)IZ>A)$T`FMTv>70# zam3_Pc1A;#(US}mF8dP}_dyyxf2tz6Vy2D|vBr@WL|3`vqoIE>Uh0l2Sb6NDV}xct zfu>5oeWw>(_6RN96jF0D5kLA@QohFjzeR~QK02`g;<`+y3HA#^N}G(go+l=^J-b1j zN7K?IK3D<(5N2%(n)B%Nq(alYLR9l-E^oeD+H&gZ)0q%6~|^R50B10=krzF zp~7S@#}8~xUz8Fph2`2(X{*>h0M0f8hhp>(o@~OZRDeml4%wa(SQk zF8C8T{?y(L&<<+Y43<$)%|O2r?41p=3W>IVj2L{srNn`Nh=14nC@5E?7)8uU9HLQ`Zke|c3dc5Gxp@rXUj&^74a6lj7@x$SC$w zHcC=cRkIJKS))5b-Jh~_6VDdq6Rjb;wO93L-%}_z%qD4b=d6_TvrJ-ek&n5LouXi0 z3mWmzcfN+chc@=%l;GpI#eecSG*?(8IYd654G{ufe`(e*j_&Z`?Nlo&o(zEm zXEtTd#1#pbdCB*5lREzfZOkMa;BC_cv8IQxt|sq{#a~wc4bZvo#5}OvQFvdqylh~Z zeep!h`?lq?69tNv<_@CeCq0blmr}3ZY*O>G(q|;$K08n~EU)sFHKz?dV?2C>olS}y zG&~Gf;Cu1I>j{>j*y2GqhgzoNJ?+P0Ao*ae`(qj|PU+C3#3 zyNtHc4v{|-za1GKeg{;YHruu;t|3i)WbhU>!q|@PJzaE7^7Gm#%Kx5JH9a`Vx`#5f zh)2d9d|m9E)rARYD;~05>?XHMO1TK-Ogkd*?LiX>J_iAOQ3l@Y;SOhMr?81lcDaQK z1k);fszhrs2|@?%Qt=uxT_hWSbN&a5SK!{8%q>b(G(s81w!J8#zMJ`!y1apYJy0EVtJBT1 z3qWPmtH4cN`h9*%H)`ejUSXwvpp2p_Nl*`Df+HLcS(|ybsx5MR}N;j5f7O!!{2;&GmL$GV{Hp#&f2#>os8>ik` ziDWRaV}9B&&9h&JQa0ij6a#1`bKi;ceRd`tYQJ`%cbr3Rl;U-jy$^WOAlKHxAd<`C zR2Dlqc9z^Ziw^bw{{pBA6pdB|K~<**Wi zGXDD}3mTsb-3kB0Rs0&D^ly_E7HpQ+S%uT|5u=CRQ`dGMo->`Upugi=^#>9eq9;$;5c!dg`w02+4e_qqzRU@VZyrS%xrOcom)hnQvC)aK zm&|vm)QBMhX~Yhbltxip#@{6-7+aKWL+zwyihaE^woNh0NdhS3MY6cGVMwI)rOjqCS^Fi2*rdXo#UGi=xqvWV7MTuH0=6qDXkX8`P&RqN;&> z=$yHV$gE0rV$&$9JUfN#OCijXMhhs<^E$HA4AWSKsQ-{l)kOcNEmk0AvwvF8kF&AS zAh=Fa82fxCj#F$!tWtjfiBB(k4%!V3=%Ud31+z>oatkmfpmtprY5vqVy#< zJAB4@Ozfq3kbOBmIh~5jMYrQ5`;+L zsX-Xn9}uWKwdxwpYVe$fSQtR>C&awrP{x5Of4^2AA5jRr8d16F@d6@u4v(%4$o!1h z85l!r{3I`o?<@?VWSyYMz(1dJHMVdrAGwtS?Kqw9Y6tK^Kbw|iBbWq9XBhG4$s%i3 z*JP;i(f?uGxEkgVlT0Xu<_?A_m)aD&9%iZ6sj;ic%a2Cj!f6&dQX(-GWLuF)F+Q&T3xJWnlb=PRde>^>coRFfq1A?0h zk(d+E`Uv1Ij6hmh!^NiFCA0ui^K7%e>z?{|gmX2!S zXV>i!wG$=`Lr)WCx5n>8gJ0Q;S^4hW)}3NvB)p&X(lXWb(BKk*yEF9n-pUO#(JZbc zu!IJ@*I$8o*jIrG>@p9yu(@qw_ZBy8J3DON9s;+|My{n!@-NA|C^5eVT&osD52Rd~Fv70!+)82gdc}3Bv z^~%V3Yu{;h(AOSkl=at;2|TCB_oL`7xlRJVeQ$kJicMUTwFee|`^}-GX0Ihl>^3p4ZTs?yIG=KwG zp|VN_G046PUS|-EauB2E@mQ!~n0CMb;AswquHvrZv1Gz-`$Y%LgkfMjN_+=yR{}7; zR6f*LmKollO>AB|ZZd?yQHR$L9)=JcTn+aM9a}B?X7^6H;+ZiuU@Azp6uStxN;A$j zXqV*tn#?A1cALr44V5{ioHRELy>O08Y(tOnCdXFZKZo=Nt%fSnTi+PKqhCi7MQkn& z-`B#y_rY8-Kf=yD^kW@UVqYSwE%6}{D$!8I^kU^~sfYG(uSw@&xT1W&*A{N@VRz|> zK;g7Wy|_JQ)>F)t1k!qhAn&N9C_`=;KaWWT#_5#9C)m^ghAQweC&iinAsR4E4*!Lq z|59qK&TyzDHA|?+)E{Mv+#ACqtFbIt&D@Va0K@=dgxPv#NbLjmu1yZf63Pt?4|}Ii zQWKwXI;Ii0B}&3_3T3;i1VB!amkbD)K`IkiGJ)UgxLytQDMcsFOViVj%yX$D*8O3M z^rFXyHV8r$FD8saQYa{cC5X-s`uNl}(J{BYF+Ztf&1;u6st9?_8_J>;m2B+2usCLO*a_+vWES!e)_qu+%+ver#DzVx*pri%CY~e}-yT~bh9QHwj(lGpPF80aTb(LZfw13i$ z6W#wwJGwEZthP-aUs~9=regZzK7Mu)##&4&DUBl-2yM=MwV!mLq}NNckmS^*>ZS`U zEnwQ9?$u%lX}{^v*8zS^EDk(QcN^tLIWkII4w5X^HFt%uCo6Ea#`Xp^)L}X>cm)lmbuTP?Q)gp&rygHFx-(^>QOBc6mmUgkdCvBb?*)NXds+l(-*cD2~<~hvdqW zbq$XUYJUrOuSOPg%IsOA{G%!vz2hX5G@FVe*z5dNWkAUsqn`6tt_pCDMr3S2SplDL zB~dGeo6)XOA!Jobu$!<-Ph| zs5=?q7FIbWCnG>@e6I~WOp#2@R&^*iPLoIx>M!^uN`-~8#6m8dCsc=xYc012EM#tgf2 zyg+p2FCtG{n;eZfB*vLm;jOywxVkzeY^(ymJZbs)2O+c}QA+D|2coj;$%7gR!!nM) z!9O>hq8o~`2g0FlgD^p~DYe^D6xNb;ITMfh4udj5;Asrro6z(3T_2v+kP^_*szRJT zBwi?VX9d$*HS~|QWxp+PmI%7uFsq&HumpTNh`xQWkbZ#I^fkOcR}qCH()%B)wmF`? z8T;Ge3WEqzOWx}FaypIh|LPa*N&TgN`7iJ-#wl`89^DGf^Q?{#$UXJPsd7Tr%O{Zp zzq|eZt;Ra<$iHEEW#lX#`J0-%fRjSdF2=*vkFVPgo-G!1Cw|IOlL{*oU8eXeG}Ur} zv;G9-=X^Ui4;G^|QCX8yiO3?^LwN|%l!E1ovfEqJrzZK{(_)Ol;wWDu&a=DTZtMiC zksuRpw{$UrVW%bCdMF32Zhg$eHr}8M1Zx-fC;uJ}6KtRKC8zh%!IVp^_J0RJ;RM>*yQ6A z)n~CIvpfthzkN&}|BRaN=_1}j8#YzxY$@B{tVaJW351!*T#A3$GW!fRBFj~w`N&LS z@{jUqJqtWpl49~=D=Rra$v7)&b~C{);&U6wr%}*cv{GmoxXGtvT|lQ!S+ueYtlMU5@aKu% z?pZ5kW#o9X_EjgD7PwjyETkS!;>X&zj1TN=b>hhW4 zaOerIViqSn2l54dKomj~LJ@+cn4`58s7@f%Ffa%51vH_l=c%>)X??Gh6cWb(Qmzc; zpy(?5nL>X@9}F%1CkY*selGuOBlr)!1>J~3OWncIyZ+^~(#8d>uPx3kOJV=i(&F_^ zunckH{c1cdIb(M$g=3;I9xIOKxiBo1z*s9&%{wI#X#*)6s8p@Eqk~2FmNf)2iz11K z21sB^U{3g-Dj?GHWEo~|yg8A5V$k&3+p!r2p-FW#I&gsl%gal46AUW)&A=E2dm=Mk zESU)!FN3z!qI7xf&{)?ADI6;bAQ}RAdDSdCQ|-H+vMJ>b6J2IK(vSu{@uo!Pj0jkY z&H+c&POMRyNpO^2781pfx+=l!jE z1~~IZlWTqXegB9h?RX1LwmCWUp%(-JE+?$1B3NP+Sz98$|AFQ6dMw~})wT;&jI1i| z=!1d9IsR<=X@yu(asmFE@EQbTn~0O$)PTBnn7B`Z$aXk50kSmrzL81ss`3R0%b}Em zUQtwtW+(wI9-JDMNRPvgN3R;hp-R&DmJI$a-@d#mGtNT0mxO&xy!S^0-eVn`t}iHJ z=)GnMXER>sNMa@D+FEmA8mPIX~h9k(0sN0e;&z;>|8s`;nULGyiyA zGPN@kF*?Y@n@^3os6Sp|M@!Sf-0y53Enyp&G-OR zOz>4tgin8tLt9k~=k6kL>e_l8aMH`20}+F+i?PsG<^d> zCLVf0&&YHFt>r_zJx=_@+d)71X$2oYM}?fbso$U|zPq#4)mOnh{eym&*?|<0<#nZh zo}PZ`2gl$$8!3(@r)M}{w@qztm;R<0?)9wj(;o~EcL5k8?KAzuaB^vtpx}lkA?pKt zc-wH6FjLXYIX8aG%I;+|<*?stLDUwq8_qz#%;44gA>VO(=0D-i_Ft0zMpcLKHvqh z10RON?s}Tp!KM#ht(t*NcgXBV>`mus5X|yQEm)cjIin082Y?q@9(IZ;+i4)u3Sf zT?sfx;Y*-66H%pMyzrpW_S>Iv=i=K*f*ky!$p(sPR}8;ahImj>;>w&$!256q#YzCG zXpu0`H|`|E6O(O=2|9 zlf&?POiroqmjoOX6B+l3DKKHON>`6+}Z#94>re|^Az;Z zc#WKHw&O{}Bl|YVmr0z5l8U|Yia1~Q>nMuZG)RWSVOfNV4c^|Ee8wF!=-B}{qFY$4=I$t8^uFi^9LdZJWtMUTkDF(-og}O^Pd)HKkF6%WyeKx%;EB33OjD0 zEUtK@j8UG)dHEX&=HLj5*AZpw!Zk~DT`WfLj9;0f5Q-5ZAVX|*d?@pkRm%J1O0)tC z9VvCBN+=QlVL&7}F>67s7oLb3*+^;4@^$WC{fLX<|82|7M$bg(%U?WZFmK7!*J_6J zlWM6_EiF~5L|62X%JeK-@^_sNb~N1SHKX;s&2Owx-=cykrWNNe?PtFg7~{U5 zm#i3#Kt+k(GkMWIDdZ&bh2x9+dM%F97bEX3U*v+1*@n$-%vI~?JgKaNjMh@)*{iSh zA;uE)4k}S9#X4#E*0NtRLifTGeK&D1yp?rV!t?b5(r?}z4ms_fy#KQq^?b|nY)FR> z3}wrcB~2Do5l`(^5-V9Zn=}tdLxV!}L(6`LVKDTmB;x+4$+6o_*;m~WJ|hcTtn&v| z%M=gQOh(kJM1T$6IU1`m=Ya|9hURh~dHKlSu=p}SOjE3(gRes8>UW`Snlna@BL-A-F{i6_7%<)QN4Yg? zFTA%1z_8-u!?dPFCT_VpI7w=Z^vyy=->On{sMQ*%iw>HYMRs@+$Z_J1O(>0*QHa^t zFd4Unla`-0|9)FZCbb7=u9&^H4OB1XdZuDeEo}LyPiX^BuB-ILZ-a^H3Xw-o#!izL zt(m5UcN%!%AX)25d(Jixz6Vf(x8s3d?cP1w39wB$2w8O+Cw$@`fq;VHaCt%T?6Fjk z;S|`_?b~`*+NBxre7J3r2lh~c6DSBmPUroa&~(LlhV_qM|}Ti(-s+=MUi6uiXa@N)IgP6DgpX2G#l zs?vVPYss1^R=fFZQn=mXS_n3Vpl5uUINIo3G;-G==Y4NrpRiz#X+nPC5+H&6@Z!S6 zX^-%l&e`b!rnb&tO?xc)!5x$o%fdRlW_gk;@^L0C}qS+l(x zwamd;puJFJXoBzP9ZT?>!PrU0EbYN90*(f(N!7Xdm_x)KV#+Z0@>b4Pp#g?71Hv(^ zjZ6-STy{Oa@=?&LZYAKtGPFo{3yW~miEwO&(4E@`8GpI|_Q_ky6S6te3yD>nk?ug``G%TwfA^G8ZYzNjk^~T>>XIm#B9}9_A#=B4;w3t z8bg*} z5PTlmZ$-z_?O>SuneBdxCihNX+lBmBA9&3QKcYyg|C;h&ZOZ4YlGphG+#{zZnS`cF zppX61H0qdgidONnju?HI(w|;s8uD7kQkA%<#flUYTJe&Ze3*XNN&|m?beYE`b3`E( z7!O>2xAqMdRgdNoWXzgI+UHh(IooLdt$v_ot={J-$iH&3LavyZIOkUweIaI$Sn3Ac za(4%AIayr)3o0#%?0X_oL)alNv)PsV%GqcYM{48(+0|Kd3>FF+(d0MKI*KGx)lzWR z3+t9}H(yPGQ?XNyYvjM0q#O;CB9C8>>klod6^Ap@+P|!i+7%9Fk##Ot&h_65k~@Uh5iC^e+gad*)3Dk8g9sX*{YJASO8Lq#neR}j zHvX&4T1AZ~8Bf*YOP}_qi10v1`?2|a8(y_q$AN)t%=~`x-z}aX(Eeg;+mxpxDRUd~ z6|48vnExc-q_c$YQj~pD+%yXnN&19+kc*yHQkTA7jvFE)>}}*O1wStp_*MrJ1W*M> zB8U7acxg%Yep7X~79`aD(iU#MA@4>+zA7^p>GEBBfxe5%*kv zl=a$vaD{hsYM2CgSBjrzmDe%FJXR&*KJV>9vw&Zf$iN=?;x}57 zx18MY!5HM7waxV*C~Y}`yEOX`&iJK7 zibOu2q9ee~o^c(l!uKf;A_r$WsBqM=VwKdd?%v*EDk_sWCIQI0nG)D0Ik;WOr2gyy zSV0#=dxwCA!iv@+-E(n3f!417x7cw{Ybf5X=!ixajIhmj$J-8P@MaIY?f%#*)t373 zGd7+WGxF5GN72AONPJ_(kTQokThX9ZzmID%)q%s7>YdsgUDts?+G4%=j7FnXOCaAs z`L4&mPF;tzRm6S0-{mm8 z)QP@c6~yzc(GGD39&{)uIG}?t_3*Ymhn+V;tIQzK!%utVzb43U7^V~FX9%kj`U&h% z(_wZadFx$R1k@wVdZ|83BIQ*fR%IFVI@0h*L?X#!tNc^nVt!NX38WPsnm8K)!OGyC zri=zHqO;G-fYs9>?so*&UL(7G(BWCFUolz<2z??J%ce44Oak`jl&Y-@{SNFon%Pg> zFWliUGe0N;;LJ4`8uKFtue-YLSeOZB1|Nnox;x86$59Ux>_HGi1tl}zA7DGQXmJF` z>7ey-^RdPjnkA~J(m#$Gm)Q64pe&_PUo*spv(QOto?SQiKQyVBIsZtX`O85VeL0J( zwO}PeM|6z}Pz%F|!I4`KhE8z?K>q?$^US82Hryl4fPGL>=EX_~83pSMbm8QC}nB&yfe9F)g7QNlDqT8#(l6y9m8j z!a&IFuz-Bs?O$eM*3ffu=;5XBbl&Z?cw6;2vzQO7IpM*AaUNHXi-BGmb^Y#(BMo&P zbpNgb7byuA-g#+HMjlie%MWwlqvjFzm2=dK2A@bwINtD~QI>0To+!l^BbyF0>@ed8q^kYUeJbaU&R`O+A{@|Yf_AszP`au<{d1aP3# z)7%DAegdq+wRy9o!HOnfXLyk0pA>f^_yZo zWY9jSY>@Y&N5I@9b5#ybCR^kQZb(LnLY#Rf7#S$Bc zZz!Pm6AD4}OtBJ&Qu|0cFqa#oJVjaiK=dsBks!8cEw8`6H{R|=<){}Tk-9$~Rh1RP zw^u)*nZoZE+-VBFB@bwizCV5dFLhVh^+T)Pew$v^+-|<|3nHIm=wJWelHh>b!1oS` z^ri1xI+ds1kL_~4P$7fYYw!-MZsLoN5;v#;1d_KwABAWQb*pCOZvMv%DuV9)TCwtZ zQ91sjW3ARRTqyq4BWRP@49WT1x4`C_3=N}mQoSG)4kWlJ4q9O6_=Gm)2|1WdRexaoAxa8*?JztgQLLMC^bQ0?o5ttzR-)6_Wl~Si$Z45$ z>H80}-O<|nb zi@NsMN~LL!V??E-DsE~AMYU8uj3bC`o1|k!V#&0|yp+zwxwJSIxEZHMe%Xxq4waHo`3P^c&nG+RTXFC`LG|iF9A2oYU67?0{R-pjf_2;iUuUV70ulobV~`N0QBM%3}VKH3gGwa+S|el4Ov zI89I+>G^l_KH>Yl6@bvZB`t0x3+PxTtcX#PHVeL`kLS-%WQ2y!4Ie6wtqPV50u+a~ zm=Sb|fd-t#q=^^ptfDV--iKemEhrZ2?7O%?Of7K#>)We2@paL*Ht6F=J(J;N|Fu^4 zD@YhiODMdT5y7kG@PHS5tPXP6tB)Ry<@){myPxZjQiJM`uqz&GJ`cPkAN(ug_3Tyr zD${ko+!qG*TfK6{?O7HZa5_L>APFJh#nKhKTTMcV5G}Tdp(^O=lS@OC$AX1y%3lw; zUJ?k=@#RXcqWt3vhs(Vx$y=PYk4)Y_ug;5fKP)XJ5wIj2kV^1{+zaxHgx8x@rFXEs zyJ+C~%a^8X{>*JrT@&g^caoG>VK5FuP==|X+omf?JK1oLw zFEV%dOt=1DMtpc!<@441nMl4vUUn+iaU!YkH0s%h811V_&K~SnI;4waAaV1WgvR=5 zO#xA`(M=o+U;pGcvfD6pHws7L z+s+T!4AE$UrKhH%(OK86z*7_2o!;%Jm;DAawTkB;6JF}m>@IQAp8_u`88Y7f#Nvr= zj@5P>ef~1yNimi&v#t^5Q)8$qGoy*c+8F$WDdK|mKpy7?;>xl5l9m$2&***c_D0U0 zb7jocXr6Dkf`qJY_NM74=xkABON@EUW}`NI=b>3k2i9U2!K3ZgI(t45cVshV->km# z#7w7S0DUt2-exi>?-&FP|CxOuP$5=T_h-5A)H9=CA}mk<$KY#ArhT__*B?dY;^KRU z64=QofdB{7rghARNu6kEEcE0Q00&5APJ%9 zem|QTGatqy+_N8-d>ia74&&1?Fdje=_l;_JhmlcwdaQu|!~OZ=9`ip9G=0=5W>&Sv2B2%SUcZc`;oZp#nA?@sC0Lv%m@eew46 zy4cbt-3y=312n4>X_~+7a>xku1PwVrm-XH5eeB3S)Jy?(UZu^Tu0)E;2Kg#`610C4 z9p+btE{B)B>_IP6{oT}iH9TY+WS+glO0#rbM++YZs2o^&cTb61-d-V#Cq9nCjaX+D zHFTUzAM{?=sQLU4I)CmEOd=xGeB>@46VT_)8GI#a{O8&7Vk12YHj4rYFDg#pheb@hnX)yG#fb;e2eu z0Wpu;G{-}-6+LlP5~S%nd6Vqx(m!P=O83{lVtG-c{xT@&eZA*(y2!DYsCtg53UA->+1ERFeExzkGvO3Oa9W0^|<9EjT1SN#mDMBG8!~5ew8|oFY0%>zCNg+hF0) zB@t2BGt;vl-{+W91C7lzI|g(@@rAxc%6cUyB_ykoQ(I%;li+cqa^*~w{dzUtlI`A| z%Qc>%WQ;{&u1C2SgZ-0qS7sR(`T5j0RqIj6+ojgcy4r=Vg2ybn%K)%|>x$S6FM;e~ zW}7L>*&o-5ou*NI@I7nv6sTb{aoMX`MS|ZdKdvxTWEjeO_3Dv zX$q%M4S12-v@|)tPh;!k=;ZZqwLR`y-xN2sI`3(dhY5R_?FTPk0q}K zK~Dlk{c_dgJO-m;8Q+mPDs!>{c}N`i_T>qVv0~znj;tgzzSfmdpJ+GR-b1G77wvBj zmDWqJZ;}lKDZ6c3?Hz-q41Vn@|Nh25|`DIjl_E&#Dnp20MU4(8&pZ#iYM;b%U9URL~QYGsInBFSu-MoN(P4RBk zkK{?@6@5Hg6Z0iI3uEU$!0w{@oB>$~4lj1GzQz0R&P+BoZYDSk)86t0h{G0}oem6E z5e-z_2b0dvkIpfi`;=e%dj)*y5OBKqgPPE;3jDqe=NN-q z{|YEQ)tZSG__G?c{*2>C98TJa!!ynvi##k|XOk-DTSKu+1a9r*&8NJYgl`;1gt6oj zJGtXSx7r>x2VK= zswCG2hTu3PpcT`j1(o3K=(_;at9dMQ$=-Gh)E-uRf)d046W(;ueeG=Vn}QlIrOYby;M$%E|q%ukopm$h7!|#;#^mQtP1D_C5}f z)3vbIO0AZw_9Ahw>%J7B!9p9Ox7Cf-2|JZ!IKD*35<*oR@`AA_69~BcLJH;}$4hUL zc9QW;WjIj)g%!h+nc&pW-<*XszVARmA!(AuG^P>v9!u{`oFo2#v8z1<$^QPlyCB)e zk)t$$I8KpfNz*psB*Uyg-PwNDk#-)F`2MJiG-?HX;M78l4m%67hJ=HDczEP=Y}Oc2 zd@xc8R3~%KQyQZiVmCsFY-uT@@G<_}MQIG2ohMh;rE(Q-_O@CsNF$IIK&)00xsjF# zBeWor#U3ns)Rw3T!O;tM7RSWNHS*mw{ ze#q$lAH5!jwZ|i9mpPD^NOj6a9|#ao>To|z=DWYJ$SD40x^8hE{=r{4P#NInSV|;x z=8$R_w7eA8BdNCjt}XzQ%byLdh_{h_xXji2LEFSif1|1$q#XLnwPWvd&l|A1G>JL2 z8kom4U<_U&Utt#ziRT4!l``Qzap!TZzcQ_Wnbayit4(51lGC@~_t~g&rcCg8DWEh7>qz0RLC&KdMr0qRP5e7hP|aohWdoSP z@B;RBgE$KGXtis1(QqprXf9%1f&;(X!z&sDe`l&~T6oEq*M`h2#oE?V~3q>W{mT_P(+}3Z-kr=473^w8JG6s1Ohrj|5Au{pJtc{rS>v)KnW+ zksylXr9)VZa0BtthX3pu82)u(eLynPe^!!s)x3jn5AxX*IQ5)C1f#Tq^`w z>339s0ql8DYzifp*+Lw~y%~P=ZX~2!ci1e-GrJcC@e@kI=bj2L_<-^A_lzbn&2TyS%u;n9CT=sV7^W5F!z(ej4N^|*l0`ut3!F;T%7hVAx`29MZ zqE!s72(2iZ0S0-0ED~4jI;N}0VoSIe@Zf(ncx!ONxleL9A{H&3mL=8|k7p`;+nNMo zH#J`o+Q#QAn|SZU(VNwusVlzry0j(Y^ydo}?|qbHjmP7t+{AH4@!v^xpW;*f_Cxs7>_u;4Bf3@w&a#Z)1QbVZ_(H7b)6- zWK63y!N-BlZI^g$C+W)-ESZ@$cPrgq<)<+yZ{dp{7%4qRyRv9@JbZ@b{=L~OYT1{I4XOBNL_O;qkA*U~fq#%--el$b-O8a-`kIvT2^|pLu!g-e;I=-si zvcdWFw{-Ona)B;9TZfqr7iX4r6A5QLWlP~sN=&Z-E2ws_zjwR^u!L>L5wpA+y2X() zH|ljAbs{5Gc(2t})tP_YFN`|}4i6%RtFl=M&Oc0x$-7{m#K zC1rG_L)i$!D{_Nca6sb>(JBnP}YWxgAa55$qCZB(M$zIzB59_RvVL_hvJM zArDLm5u>ih-y|aekrQ*X@pFt0aFQoGL9bj*Pv@+c`AC(_simAT1$w|LwmGtinP+2I z@Fqup8$c;ltSP&mw}-M5=_arzK54?P0kJ}mXH_-CXI%)(f{P`iBpa$%&q;4M{citMVcBxA2HJ_X8h}dXr z$iVR8oR0q+`u+*b-+s!#!PTsWvb8vay=a}fE8$#@@&y=juq>cf!Xs7}#6W*T)Jrq^ z;>T|r*ZzP|*kE2)AVfGALNa|xJYYnKK0U2PvrDAwXd8Q^ucM-^keOM;V_Zywt%uX! zZ$<&0A(Zhs(E6QAh#2g|eplO(9fT_;%S0dW0iY5PV{^x2oh80EFa0TFqQ3FfJz_VR z5$G4CSRSS|R*p`NYyukIQ17%UK7pP%a3})}H0|+{BNof|Ma~#-R{FFw@DIDxT@PZ! z4PolvchSIRExY>P7gOljT-JfO1UHFVDdlM7O8N%yn}z!Gx3S8Lrgz~P=ldt%q7`qZ zb1)1QYk_rH*nSf{YJL?fvG|rigKyVl@*|Ts$9es%RUI^o#3xs&=HeWY^Yi~v^%j0n z#ohL>bW1ma^Z-M5H_{A9cXuO=2jdZu9qzn=wrF1KZw16PI2cO?_?|uJ(IWu!U z=j`v=YpuPu?wc^Lc0W#oF+`6`&q#nf_SgQ>9$ ztg;H^g`Jno%H-=;JS>mh%Qr-9r`pSu=z%&8tukfy_z3NU%0?)fT<0Q-Tl0*+*NM6i zuq=OQmSNX$l?)*-#=O%U<2TPwo{-8;4xQ*mCe#RljQu(v7}_zo-o-HWl4$M3>m?zv zl~qrsKVxR$_UWlf2f?TQtz9U1WkZ6B3*g@{~@Z6EMF4ov%N}c(c zlMOgiy_Pnufc`a$_5A@InvVaC|6w?TH+0^h;<=zt)oa;4koU+2;bErI*n5m}qDXng zm{eWGxUQ3G#usFB)=Dd(m#<&hyutZBzw=d_>S&RNS0h1FaDcdz(zpN|P6N?sRV$Q#&g70+8q#9a{2;cJFzr!3r zx!=k^T?X)>X2z@OvuAKgv|xfQ4VkTwkUvfL_VQ+eQPb-DOY4(S$Py^`E$F50h8cv+ zNv8)+{Ea__DprOFo|lOsi-k^#-}JN2Q0#p*+1L_2I{p)U&$y zFz?yHuv@WoVd@G1+?Ggj0?$VM=Z0IwAT+$+uLe@33wkN`!tps0lP&~JgL)-^n1W38 zj9CgnJp-~C*1NF4k69D8q14dA)iG9v?>SU^hqjXyT`Rl%)UiwP)|##fck9$IKl&S@ zc6KZl_4p9gcV00c{4j7E{d!ceDollPakA3jyFa47)9w4~tZ7JUrIXCq?cnd#Cw8v^ z*NwI}B&4;I#n#(a_=4am6GA2H9~*~78A4IT=6xZ}O3tf;-(vn|I)$T7?yjV?J`50_ zAOB)fIT!UD8JVOiGCs3xHpT_{N5QaeM2RE5UtjLDUaZ&Op!rs0sQQ1Iknj1>YB zedFAKxq*o3JZnMOXQt{`)#D;5{K|dAho$>H>H){D-A65%ijE0Re?&kj%Z3>i*s`d4 zGaBR(K*g}t4Z#&J6jcA&jjrsEMH`sV^eRI)%$9q;R*Mp&p_4w{^C;5VtLx9OlJ`Lb zKJ=)@n6!%tUW0-CWL{@*S)aaF0rVL<^7%H@gOF)cS{` zv-bJr4IBjVf}oUMbrMAO1n_Z_ND|>fg^p4gHZ4|IRvTI5aI*GLG6~s~Dpw0}ENd*$ zSN;v@W~)L-UG{1u!{4;BOBdMVmThI9$|RfPvYpKOyUfnmw0FlcReCCA_%%eVIw0aH z1IgE}ow@I%NGx3~3%3KLHW2CkIVsT(SA?1>;Ps9lw z$(+wa>0r^_2iGzd)<&roH1=0@r0eEeZ;)rp$a8Q0t?neLWCu` zoT34l966#E3951nc4Io;8}Vc|54u99gUKqdgRiE_hiA^3=M2`JS?t8IA+d>Ro_T2O zicKBM_v{30>rv;y_`i^zKchWG+6+erCfuhuUu?~-5$HOAIe-pVv#+LxI^b zGu>t;N!PO{^%nDkXcYW_L4CdNZTtxnY*lO%KUp-|-b( z@!!7@76)gxE}n;RZg85J9UU7a{{M05;!*IQItlZPN@6XA+YDw&*2lLMX05HS)lO#4 zC($3#nrLne&2R5x?)KU)?Ns9T)aWw9CJkb&FPTuxn z0ei!5h{Jq0V^NA;`PmwM?7mvuZ0J*os9{~NhSP@0Vh)6|1>94grVgpZi1a@wl>Y^= z+_z7sJ9JbdCiJ+^Boin1veAN(jh}IVj8#8f^bz7J|7keRKWJ#;qMkNDnn*Dih#0*p z6Hf16<;UYQL{pjzIZwW<+j4a#`-fg-TEk4nW*swZHNUxczvv0oUCj-2Ri9^=Wt(k; zdqX9{5Nd%a!z<^^BaIMM)FsOh0iGu`$)FNZP&tZ;gE-}A&(m-lh}GcNOH7&u7pL~> zdUvuEMhit~#x}ITtJnYyTMS;sCU0H&sOg^o(M2ki1oP__!~3?Yxhfo3++Hz@#+h*{ zYi*Z*B4to;7G0S&P2({ZoA}%aUC$oPIMjQ-QkXOl`LgzKB(tqcG*BO8H-WnQ({A3Y z@f^yNnUl_jadre%{iukf)V*IbhMR@eq^RT2(NU*3WyWs~b{5V`iIieBup8|M z>aaD(uZ)mJ8MU@)Em{uO?p~Y^{DgV2yVt`CKzP|g=u*>VOmYj{-GL=y;8D7}IUw-I zzq=Eir4#sHU`;*4I_IH$fN@X?9viEwF*a8WVWqVS*(t^yWn7g|mm!oDr&?FG{o8jZQa_gj#H1@J zc1V3gpnVJxr+{Iie>yo-Nk@UJys2EC46+rl$?$B6Z?l~lcVZU)vwpnQ->)Ei$#T@t z*I4l=PDuPH47f*MyCc3qs!$x~-``mZrt~(l0Xx5~Y zVS%q@k$Ji9Qr?-W{dva#=U>x|J!NS>qQpm8>hB9Kbk()TW2XLSL-2hZLmMy<$&mA? zN9GRkl*6Tj%R6GlDuCNW{*K*g*$(=5u|)&=cF@!u_tzsiFRC$0Lyf!qW~^aDl{>$x z`xRT1wKa~r z^7feHw?bioqn>zM%m(QhxCnqo4(r>-G>??Oc|WM4And(egcKYSN)5 z5<*0WhsgUWfJ4rA|IT$TuK0;ccpeJi6#g?JsSH zpim^jdfoWJwvXd~QRu@a!bIKTkwk!kZ}lmEKK6}Zp$My)e!|jJiteMzs__pex*%6} zxzD&opOMB+Szu8phmd~u$i{5phcAX^c}WB1cZ`z}pks7NG*w`UB)&T1=HuUOd~(yt zW45to*Ls20AR!SA>anSaaczH$En~XPpD{@v+Xeqzi%vUfed%R~Mj)ci^9TBAOb3jH z4xxm_VP+wA&HlmMxK1cs?dmT- zcKVlzNk+}y5ci@YhwYiqFQ^8D1}fep{#eL=?XR1)GvjDenvRK6J&&BB`!z-@2Ex)r zA7BiFBxqGP4Wnm(GE$=7VRlmMsR|*fi|~f=#7vUsATt3*T?@o)JPTEJLUdpp9+7ac zi*-lI!qPflX~TN@2~HiQ_^n2kfIn)PE=vvV@-a`m7$)XppKxK&jI7=2E-<5~{-X8@ zu`(Y03yCc<4+Vcp^qAk5K~)Pc46AGso3W(p|1CDk7Za`TP4=re)U;l(iXzFjdta10 zmT5a(3c(-Q>m1nF&Y8zG6|~PQ7SGr-O&Tk9-vcx zxb4XJ+OoT0$Y#}!nQ;h6S41xN=~IOtm;nWRW`B6H<_S*!2R|ODo%(g^e%dG>WvV7s zDe#tQ9n+V>;ftLu{^ilkaK#sgct|u637#Ae=UZ+CUs=aZN)!jmSJqBPJ=2{f;d3n&76U3!nUiNAaTv8$QGZ+xLJu|25YJ7063!; z>7_Y)^lEUQlc|N4IgyHFBz5`{(Vuv%=*u{ps*3dVETsUk$uCd%L*kIX+_YFagGs-O zMBvrZN5A_ogL8CC$@;%25&~a34$+n;FeX@_t9(N(XC7C)lhK31s<+tD{`-f-&lopsn_1mX%-+@k6L@zSkaJwwGT;aKHsF!LvOg* zb<^pBQZhS}?iHY)eBd|y>!hh}C3LlG(SHQG3hkF0Wm?g}N|iTU?qH8mRGQJ|<4cpG%9| z&xUSR+=)O*Rr^Q_lLftUN9?BN&sPxU7ye+jo{&9y=JhSyd&z9m{7oR5tBF72o*NNI zEU@+oD+au=20j>^QhoX{_nk9p%NTElb|z^Jqd|U}#^ApI zQo8-^=))*uSU+nEU8`wh{Yhd!%r7@nKsdFTt8IoBfD(ZJ2RT5tLNKp*M$k6UYvia; z!9mx4BCc`t2v2>xCojn11k535Z-EnD1rc)%l}~+;@$_%3%e2B}?^u z)Z*xMLW$DCoa~+WZU{od=NupLicXRP-caR1n6k z$%9UwZ!bhI!<72mt}ZzR*{Xuqy7$KY2m5)Qr;$A`!5Hm|DB=45?IW!^LX z-c@&+bt14Lyd|ZH?;< z2yZ>C-H)!8i2sZ%lo`J!Lx)O0CHS$${1qd0t!TswGfDyUA}(mJ%H*I^F)_GawP>Hj zs)ksff>ug*5~Cb#4vH5<7YwxsGu3I>vbulbJGRbR9RFLV$9Gs>s_*yNq{OSNx>!{6 zU3Ii1>WdtZ&MhVadR;zwF|DSuS1}(fQ-Qv%ig2;Ln2#>S*{k}-5tDhIY9yvAij-l8 z%Xz^Y5n0Qu-%P8v+w3UisT6S$XhZ?Ni_$jQw$0dQSbLVdQZ%zk?l=`@=|`qAeZl|a zHzs=)JYNnX2{8SMv*nNX>7pT+f)H%=RFY>(P^~a67y+LKI&Nq#*ey+)nP@4N>Zu^QYG!@tAKJSuLhYIs&$@_}wsxO~%DqQ@OxMtaG*)!3J;G zy=0SLohchb@wU`;#_;ocg|s{h|3oN&aTk)m356-Z4ATSf9lZz~w!=44!zD9Dy~Ahv z5@NY5*;!&RgTp@0@(`qRwXm6wkfQVkXQnK^Z;nhOZHrdmkze{=eyTrJteJIJRTV*J zaw01`MyeJd#x@BEB0QQ3we5TcvbCDI+786_5W!c@BU8kf^5<4vyZyAr!=)Crm-N^c zWJDE`7{gDher>PHQ6lj4Ro7YQfn{Tn74I~E0}ivAQnP|rKNubVXoF-$ZY?+hC&~fN z>SNmL-T16%YPJ;Uw|YBLr>g7^jA6E1t}jGg%L$kxQDqbm{|Lmcz7fB8I)|q{X-*NK zW>Uh@Y=-@aL9);+?x39s+50umgYCrEhIU>y^O53~U!$7PmR0(j?4Naod-5B)^*LfM zfsJ!8x_?JqPmaKUHQV)R%EkIWyY9jkT>48pB;RbTH4FpCQ+6$ZqQY=@7B9?ngxH3@ z3g5)le~b1Kf4b8)j3>jh9B|GpiWKA5dnnxbg=7am6&#U$fBLUEVHXisAd#lsbrKTh z`|a=W^ewLV2>S2V^#l7c5EX87p>Mv0a%{F&Cc-%z&-T~2$7c=?&tO#_x29jEUOuZ*LbIFgTsRw z2peb*Wek1+;zZ+b&+A+{!*EO5kV0q#U-cp9YwcZ5lm&T-PszKAPfczZRNS@E9Iz~-CH?FrdAuTImA z*7GO2oN%t?)1N7$37Q#B&eq@@wqWtQgtHNH_5#+Dj9U<{>heG`;eMhl)~zs3D`;uL zK!u+59g%DjF{*knH0;Xn`3j^8UKXM*>ysH-UcyL3QFax-4@zP)m33ttz|#%0!0&W* zHU~MH3Kf6$PzE98P+q!qob4K(e#9~)M92B6=$tTX?~Y?l3~+FD?`LP@jsO^2W z&o`_Fy(|Dpy;w=po|)3jK#z@Up#R{V@1*x)?ZldU@wFl<86k7Z%;vTeIX;grIj_gB z7A{+uDxC_GBA2bx#EsZ~{i~8oikRIzlvEqpV(Qbgf;>)->)ffEe9IseyLm&RM-`?ECe< zJUv<~$7gk@{}Itles07Ri0Up!wV>IPlt{x^KZBNJn$ZpP-4%9u=!S|}mmrbyU9PYX zAY3a*`oozA>f87Y;EY+M{=X8KQTTXIyX6BDdr8R$uyXRDjsrmn2J;W#ikcbc;gzDa z9@=19b#<|Fu9unVtVkEM!#W5K1NyxkPbhSnEElQd0|j$$?Cy5+X^lY%ZK~_OCsJ49 z(Y&BJ{VktsiWiw8`S2zfJMhO4T~dE}!eUEa@)})R$VV|-#x;DfLVGVM$KYXd0 zSeLQxCK*Sim$~4-{mb^pT}N{cAB$6(LNr$;t7Ss9*kr^rMdAs=DXO$ekWJ37_roYb zWrHt=bnt_T1~;Zz#FfbG{b964ct6gF{xQ8y_O^v2+$qJM<_JO>MolPSdd_pFk!8kI5;nwq zf2^jbe81nNMD`bRdaBTK&Q_!b6k#Txse-a#V<1{il4$1{|8HXI5^rAsgZX$*i%8Og zH{5OgpE!zxw4ZuMatby6mSufl5*Q~ZFJ{+%T#tC+mD-kw+PdEl96oJ^N`t7P$$E~b zNB1841a}L`^5z-5#{;8tgY@S8kl@I9mc}~g+cPhc=_^g16ZTwOsSme>R2GIx7?L-C zap4I%YZf!_OCWC?(ve7ld6*@5Ub=tA%z|)`ZCQ3e;{pe!jW_Q6NHfuN{GQ!77)#%E z5}CGSz6Oq7j{2#Dh%PU=~5T$G0nZ`JGDpHj{Yc83bu8TKE^fOMFG04F~V#=W} z>BLTVEreUg@_fhN^j7Iue6%6%cR!B~3TE%v`po-Y1t$dg9{ZFMfY6+E`$wI=4oW)2 zdsnSfYb3>!{mKSu`aOw6WgQdRkhh+AT%&KE&`E27Eb{hMLLw;|VtO zflupn9?Fjg&g-wn$iD_aEJFBwUO}8)UZi~?z+fHU=)*M z#*pJ~jL$6*rTV5Gwm2oMVPK!%T{ruOBlfsc)aDlI7ZGvdUe%apO-~Yj*_~Yy+a;)?!dyCzJ*76KeLC}J(;%0BI#6(Y-}gau5c(j zz<`btxvsVllnSUGnZ`_d7TkGhRd2_Z|EHZt%dEF@TLhUlH#HnvlED%YyVMf-W@!co zl^e`_|MiSL^f^}?_=e4GRdK%UP5QEFMu6_>VpZf(2t$CeDRf6})l^r^jQ5D;g_TYX zXZ*EXhRu=e4ZBVH!}AB*!ZjIbTShK;Q7`|E4~8Lt0mCNJcfyjB5q#9Qb#S2O=|2Cz zHIFhA5L5MnBO|R-nVcNt?TIRMOiJGNCI=cJw1fVlvv?ECf6$kz$A~20FTdaZ_3cSL zc1h)BS~aT$u}-IalMN&zWqbf_a@Dzuzo)?iHV~DV7d~YCEbrEQ;vsA! z#nF2b(lkz*W%9z-4l!S@gtp{YVsA58EfEKJd?=8hzqBCZ;xz^u>xHc}JMTdAYEoG% z#6ww?0v_akziDc6cHiw?no|@2@U-)I7Kj8*t2&KMHq-L18CilrX zN&yyZj@26SM{U{)7AE!aQ%)O7#&`9K9SemjZf;Qm)9uN5iw5H|{4^`>If1 zg2Jvz=pnk|e3YS@d{yjTcPOdWG|@2sAHuaR3JcWsV^dfDLt-x36gAqOL|%;61y)X? z@J;gUE{~_?WWMrSByAQOsS*tt+r}%sa129!S6CrmBEKgF^XksaH05M4GAd=bEF#(Z z3*;aLQ-kDxNZ-6e=VS{~Dduw&+iYlz<2mfy!i=!WE z9&$r?WCZVhUNGHBOgyR#+Za@met4^txnWxSh#|K#%NjfZ8Yhw{PbS%8!_+9euevv{ z?_k3PEFM%R+^5N`k5a4r&Qe<%VUjudo19BW6f&2Of1km}(+U;Pb&jXJe8Wi>F0mEUB@Z;yU#Ed+>YCF&CSq(Zp7_ci&^4 z`b2D%>iJ|id&i@pENE<=uIM(SA z!;ts+&P&F8Xb9RKkH)20s#>?#yZ+Rj7iKU~(^!JATGGd@9728fbM?WN*>Ci z11BAeQzlnuYB%;u&n7p|1xD!j;Gc$WG;_wd2oq>4!*XCApWyYNIg>& z>S+R%<}5bd2s&h}SBvB;`w2KqS1kk6gueQyJP*5l^Pgq@*X;)#g6bP z43lFS)}T%;XGr8#yLPf8rIR_nu%6DY!;AzK`xl}lX&mM^(-F+7bZQi@J zuHwe=~9JP&@l5^pje_!xeeBf5-;myQCiMfRACgeW;`vJsxg?2 zBdl`+6X~hb*y^_9{~wpQ9n7$K9>Bku8gW{cGWA{7$s()u5HWGI_~>Na1mt-c!*u-G z_-KofK}GvDesGG-?vp2t}-sDg98>_uA=I%GYS4QnHI#rzpFySmd~VX^VHEAD15;5bNdJbOWoWi_H@a^;UbxhUF}$T1aF1_HwI5iTKjwZo zLGNkNem(O#Uvc;T89d@YaudpFJp0~^K+EjuvezF%>A^?Ld)Cvpun=D14>Yc@qjey4 zNTcR-sq-cSj8}6mN_U?JumRs4T~;VdcI4|ZWjSh3VQH^+FPysBi-Jv)^ns~|F|y!2 zm8iYI+CH2jvDy`tbO6p$xEi0{0ay3`=L}s*our@nL9OPln!eK&-kBA~sit~bwDcvr zY_s<|*jVgB7;48fCfrkqk~VHO_m^oGGJVC5alhaQGP8*6tF4Z`-uunH5#n_b!2a;zHLf9f%7Y(zPQl1L^}?tCh{9J|1^>T=GY#uhgi z-fN^vO=kYh znupXQdL&5Eo8tKIrWwsb>#gOoJGfrUg&qgL`vhhl{JrG#U;fa}s@2)mciJk`$(C}Q zcKhZh>&V|sZ}G06ouU1YORAZetxj@@h-kh(^Vn$p(Cq%`=Sz%!t7W~ zb&r8x{-4sTo3P3es+%88R)TLsDuV>)D8|o9&lfc#NBW~fP9!Ut`9U#T6go>f=w1qy z;G8s(40>XHqShAYkbkzM_=&vg_!`S55G^V}H`K=ZcCc8c2oymUpc#oA&>Hz6)t~`j zXI&dUySh+m@7=`lVf}n<(-_uQ^K+D#=GO;ensJN;60(tr*9|3?n3sl2Z(9Y?e~6zI zmoHgM3a|jSk58Xow?djcoN_dIIWQ!$dJz-4Hm8!z;K` zdphKH3T^Qz=q8*jKAT`F#w2S^hDu@5+E{R=CK-sy=H-+6s@ECL^~?1iJOyYi@Eyu8oxM=}->)#B zfd;Ap@Mq%9<=R`R_#6Re@#C$3z+V(WrbP}ccvVD{7q;#Pb4CqIeoCLm-T|(l$G}?@ zwtFNn4PWOEME|=cdQ8V8;vqQ~fZ$YOf(2%ovi^4T!Ck!Bsaljhq(cm&uxHtB^ z@8#rH0$#0Xu&yLC+)kwhh;+2Acxq-f9~3jL>F&Q&KELR3I(rBJJm|J|w^4&`&q_d# zu7G~0yJ1oQH#V~H7$~MeXN~izS7yo`nw`nAqN|jzFDGph6BXQ zDHrKRnDv#i!EK96xl^B%mFkBL8VZ2vfF;W!0nyLdbr`br%6(F;u*e&3*Mdgs&V4f)FS8vxIA9B*U7Rn^vw#;po>sr3|PX#4uLAiC9J5Uu8x&qs+`OJxyki`l0 z6_x^~4-GZ|nZSQd0B)-S;$*TxgUhjSvf7%ZI|`(3oQh{vg!_1uekx7N-Fo*UofAwbL!_xNf2-CS;+sIn|#&nDs$N+cP!)vsk);$h_nB6dxf#d zb4qbqgWg!Z*N$hJms`HHgyb)P^#mrAvE8`g;+9>n3XtggkLhwR;&|d`?K0ZX1&M4m z<%$V_4p_&yPRN#|E7lWb*d~l^a1XBm89}d5j6t@xuki^UQvY9g=%x2$mu4!5-B#Vm zki>HSJ|MCLAM^O-$zXH-(hngLUc4iXbv3S3@a?^rkkV!#j%g%G6uvaF7{od@r5P{$ z@($VrEDg8JH`dSSYXOxf+RS?m0#Y%io?KTc5TjI!*!M0|qNwYB|MruCOLi2hx6C)D zbP;^!4ZSKtz4`g*o{hr0RhSI94f=2s$N{TbUy+h*&Oou+2EH(#w* z;e|F9Fot#1^>XQDLo~MyQl#3)Vtg(3it^qnc(0V~blTy7m9&ToFk2 zQryN9j`lJL*P+&lAM&ayx~v3MhszryGi<|9|->G@52Z5`Vf#`9zAnw<2?Y3Z=3Hi%O3@olZxh<~y#1QVCHYqPI?vu>?Aq|bA z9aJH@Y!&I_VIi2GkRF#tkRPvsiJKqo%Z0{t9xkG%N!qs3^Gqdju{+Win+6fb_9AwD8#GRCKNK^anN!{*?p_5JUgX#B@YWrR*Y_>n zJ*U}YFhD4@tGMCP{8aOyhc7ynj^#SP@N%cWn2q;CQ;B9y zaKj;HZd44oOWt;pjXm#`>Kl-x4ornDGR2R!HZ4c98GjtTkfg_~uh%*n{kWs?6=CYT zgOzl$Qi(nZCegNKbg9R^j5$8X8NYDl5w?2#YIt0|6Tx1WPAU_ zccL1@teFK4FiKeNJ1;L%EwA^V-(l8rko@BN<$<|{40j+_r#yl#AyzsMI?!Av8^Q~} zto94}7n735{nrZ+mRcG4Rbiqv*$(;@(;u_d2I4Hv{KNk_X&gGS@28Ha89ROlgH*Yt zK?9v>Te5GhV7tETbuY$rZF?>^5#heCyC|7dwY$%{F@;e*=l>R?0QNG!t6nN{IYf#-HB)eC>YQ2~QBD+UJ%h%=!XTbY}w zHlC>x=b0k-o>8%F@#cbCaRkyNF~}-F18VtK*nVeNZ*%U8V{RiXtNQ- zW~6sX`DB;#GT&bdY-SB|YMQF(*Vti1y={Tn)$k;*=4ro?HP-sFt)faX%;oX*G#uN} zfjMHaG*kgt{vA(xt$P>`)|U#0QE-{1`>d0KM83Xs4_IOHcd}eMKP)eoi7;q2u%EvYClGNDHbmcL`-D5Affe>+ zqG+LN17Tc8DA7}EwfnG~LVY>-o25ZMI4JCOf8+PF^1@w@EbGr7n}QWRH9?ZUc*0hV zs(E<`>vV@%HFd4JNV-t>DDuBQ%U5i`7mD2isk8cPW524rdVO?KAy(LI<(HC(kJX4> zC`#(?LH8&R6N!Ietg90EvMta7NTn*5;kBD8aaZIXD;Y&ijdNvkN2%gLpSdD9rGP&? zklkfIri*M8{WfN)&=Fa=bT8npYi$b7#wN)BcvvjeE~EAgP4vCcr4Q`DX2!vF)iViH zge*EZ0Y<>T2?1l`^ zw236deK`<)ng%^hV~(p}$vBRSb%?f!pja%aLtEUo3>SgaEV$1~wYSeNJ3lX<4E{+j ziHf;097l(d3Txg$f-{urw>K@?Z_Fx<2Pk}iWEtIdKZOAFUZ568!x zFGS4M%*Cg0m&c{Vus=Mh=3{a+M$1Qv_oosG6Cx&}O$sXtD|m>w)_BCc8E*Z- z)fh^MsfOsHpQ~g4VTzP*9NOV(|3|&qSaDRuL`|&4sFhAaC^lO%Gs09g$d-G7oPdVU(BkC7*`7ak0tOTxld5J`Vvfu!goIt=t-c6TzzcCw z!YMX6f}wJkB0#xFI8tfD-g$tZWA2X`e3w1K3(wyGMREF7J zdm7yq{C6H6y;eL~Yen+kJCtY8?=BrUoBlQEcFE_g2?bq)b-zN5HQ$Xx$uVg4pgEQ~ z4zL^<{bHFM8(0qAC+xqDM}6N?-#9h8XcfD5o}R7>9cU)GMzvFq~WMR=&rh;REP7+Kll9I z4D3vmxRmZ!s<}8^#9X}TdDnB_pfODfovIkiZr-g~n9xBBA_?8}Z8)L9E1shu)bUMG zkHV~gFp+c-tShFmlxd&DTW%n9f!E;wxUCLY4@yjOmuQ;gu;pvOI$66-$b#PuqA6ca zsQytzn=PFMyS{A0uUH^s2IJS`lT)Z&F*>Nk)>gGA*HPh8niv=5 z<6!DG_(##zGTnQtzm-aGe+OAarrw)SzE2^iLIxim02OAy$*0^arg)AD4|AccaG_iL zutTn)T+6p|$;+&a9iNI&k3l%;40`)!X>hk+ogu{eIwq`88=_V6<@`LmNU;e$JBbT7 zyAe*Oxo?q86I(?Z%OzPIDnEj!VJ;AVFep`*DgrZ$z97kTkZ~Zc7{z2qtS{wbOz&VmNqt>y zSXr&?pD~sjVDN5;HH^QsPFEkLZY&`yl#OKJ8I|r9dP(v(%vZbzkbz_IxuVkjK(Vw! z1cwk1YIjxWY%!IkAFVi<^z$L~Yj+IUz|SgF*Opt=8bpeY1mM=pJvuO{P0mn@`>Hc{ z#F^HChja-}>18z+r9Kk}m$A-`ues!@u^uz$-Am1x33t zs37T3=PPrh$rr+(dCD;_@`^qiq>kEd#&sbQY;Whc3MyerdGEJtGx3$3bMM9 z#g}M=J8W{kGwRRaSm^~m*q*6Td;ZeBb%-{svd-p}NTO2u@x1>T_OBrmw74+ndx_OA z&7pR4Z#nEHO$#E4EVOYnXA{Y`UQ0g9_Dn)|{Pp%0%(3KIYIeHz{u! z7$;6}k5~Vumd5_WXx=;)Fn9xcQaL#<`8}{x=z6TctnN9SU4G~sBy`usuJK@k@3C{S zkuc7;pN}#2Oo$=4on@HEWyFx{gPAj{^z9gb=!$dp>W$XU((y1BNMS|0ggtfO5BJYY ztB?1i87d72yfPlF9Q3IDRaNgw-YVqt{_t%4o|FH-09J{nn{JnG*KoB}-xDJX-?r>i zKX8`5s9=iceF4IA`QvBxgml2)2#Ms%Jlu^L7c4SQY3jV%5FY=TtwW9^OlRfxkye5*&8w z2;L-Jam|_rxrKF!CYD)={?IoZ+q`cS%`6={kx4++zUwwk8c+M>XVCutrV7S+VKIQ} zqH~i@2VrUJ#?Mj2ec{tZ$}Vg^*kUdCx-qGRH7SR>yCdHP zkDGKqU$f_`MPt@?9APBkXXT@;kjF`gQO$je_r0eQKyBo$`j)^(5(Aboojh$lZ%;-p z`XDDtrF>9sw7VF6{SRmHq9V;i&9;Ltdvuv`t9im zW;y$2xKeW)(>t&2YFw2WxyGj!tm)WTHosk0pMJ;??1Z<-<@X?gGhgMYh#iGZh1evM zVz|zBDq)V}O7$Id%A1}wdV1l2VR}7*T{tl&MKEiAz9&VXuSI8jX~;v$XvM_*2ffX( zWQsZ1e=HZ|FN8@#of?!2)}X=0?)Tex!RYVdS852H>;1S{A_^J10|^W}yVhrlnKV*) z8y(ade>Am9a=N>TiiskvIAEnjRakIVbegzSi8-{k627=u#5Ti<2`NgM*5epFF>SNq}XmD!_{a~&e zYPu?P#dtSR0!}?MOa0uA}dox zsz|ogH>jZFI!x>-R@$Ti{To)ox;7eFIN$1Dv~N{Vhrj%+ZkXMUP>B-e*gRjgRg9{A zas%>?{@(NV_>R?E>6x#g&FhxzFX*CHr&gR%s<;9tOTHd`M7ds zMpV1*=wFyua6}tX>uz00MPiB)J={-NIw*Uu%*C(=UNNYf@<&_Z_jfYHZRCBL8~h(M zTIdQ(>iqRtqoxT*4|LdCErCi?H;?icP8urtOg;9L8J6=?vGRDprtv|fiTDOPIp&<6 zTde=@^O~{k0D;9P$Pu?iIOv8Igxmydg6hx87}d~XVHqHx{#tK9iYP$`XAVo+nI>Go zl*GoC47z{r&pxUKEX~dsGYshVQA~M$!@o)<#J~tHrNZ7c|1jChO?}~heY{|VxRvO~ z6tXwIG?!FWMRR6>vbxr_>bUxsOv+3s*ibY%pOk5Bj8}O7K#3{RV*9M>*`>YGoH(fd zvp^if`;^et$z$mGZ)%B2Q3SH>X8fjNXIdK>^wfj(!s0(N85E*r#i6A z528J4v-#NXzE^rQ+V$5`C@bBV`Gj(!)QJY^fLw*6T?6TBscH{&P#jm#R)RqGw;TR@ z_Df?&8o@|c%>aT(AI`DMC$Z-MP8Q5g!_jXGJ-S8TK2kCHvgH!p_z!U=OE`o2e_sp# zM-dV$tj%aS;1et~&%xK-GA62ZZ&_Wy-e+QjP=uDTQXwQ#?753=euO=D9Cxg%`~RqV z>!`M)ZfO{IcPn08N^vjlZoyrOYl|1x0EOT##oeV8f)|&fMMH`ghoXfy^tsP>@3$6< zwa6a?emQ5K*)y}}v?w?G#p{JyV)q-FIRDN*!zUhmFDuL_jonX)5gjJs*yfV*!+I7a ziFpCWgb+69Z=r0ZpEcrXnry6ahZx`mr+?qtI?F6=$`dhd2DlK`5DYk`F0h@D8(3hh z{k^g@nYgpmN(Ag^a!lcW67v(w_Xhv(oK(KjM9^2ConTI9S69PwoN4!5vI#B21F&` zU(2_8z8qv83$h;1dp|%Do}*vbtc9|<=CbD4@?88o)M3Xf(^VXVM6WE;O{p#uP@?%N z{1684j{B5NXWZ^S_q))qg+KImgj{4(;Kc1jVh!~AOT{vq!ixWUVPT>OJsC`0fK5bT zYGf4$!GM(>$rhvCsC71}`%*g;jK1dKsU1mz$V}LO?#u165-)r(^qk*lQ)o`Yw27q{ zThGzyu6t*e>QFI5@;d3bL&iv_F)?3Cna%rWjW9=9!6V)3gBAMqnTt3h9a-*YqxGX& z_?FlH@7K;fgayx?cFujd3OSp>D?BQNIX}K`(vQ-5<_Cdc zF(;I-`}|XVlx~1ayeuk*a__Z@#d{hqao|qWZMH?s1ZNi$0m3R zz?y5pu@8q=vM77xB8fJ7clxu_el|@vkuQv!Y?ugfPh$z7C*|-DR{52oDG`zw`Wn+% zfpl-KteV z0$3AIr6s4!i~|z@h31FT43(uMe}k)Xu}=r9@Nhh@a|TQSKCM9Q*q+B~Cu@nOg{_ z6SLLejeABAZ*NOokayeV>sNprsPrpAns%m{N;+NCggOZ@+EM`hg5l1W&pw@KybbBQ z;{A8tB_0Y%RGafd&K11C02d_-}X*tQkl))bbI}tuA8ATa@ibwmF!l zq=_$xNyzBT)8tq%(ai}-?LiZMg~&pzGj@?s7G`O>3#Gy=EcM&Yl-Qy#(&dvAw$x*R zh?ufj_K|)Fm+oFhms-1Y69Wk{ljMJh^&u@CVPfSqFT8niF6^hq+_wI6ICYf%O1Jes zR+{qcja1$JmiIq0LCH$gt^w2dFw&-f=gSh_E?l$1ZC6Lv?U!aq_k>~Y)eVRHBH$() z$li>jJAd3l?8%*rqziMMMLYx4Wq&>Uck=7O z*+cg~1Z6PH@Rh%s7nH^G9h*bg@umH?%3_TY^FDKnq+*!Rw`3YqwIEUElE!gegJ^Fb z;cRtx1uT1^h!A%nO&JR@pIrahcPq(lmo_N$j)UZ?x%W_Z^#o*itARho|9=qe1enbL z-L=nv?#@4iGJvHDDT`a%&GU2OHU zBiuoO)%I0qoq0x|lSer*+G9L1&&<}k%_Pq-w`@~09-xm`t2tk6=TBGay{!M%pwtl$ zIJVXhShk{7r>xQ2hcY0z8Tk_K_*maA{1L6Vf&PSf1&aTVmc^Vv{<(N48jDO`I?5?z z?Mr*ROeP$ja$GbclCQAGPZ+MtYTnfp8vA25q&YesL%>n+oj2HdrP^z-=_iI$@t6;N zjlMxAR~3REMn-0U?oe!{T9`FcpO$&&$r#Jajt`>;S(F;-$5@uKu@l7&zLw!s^?&dy zgomk3@_G~tGcl!7*w`w(?^Q-*D_)+&B_Lr3#i>&XOAu|XLRsoIoe=yf<}5qX97Wnk z0o6_7FY7^K4>Wl_`#SwhiifCL8wjeqMt_`Vd(ia_eoyk8oOpEVcN1Z?$LT244aHf> zIQ(N0_d=-}kI@sB&=zqBC`)BlWaIvdj!nG7Qp;3=V@67>Cd|kqDw2bI2^DY>c12WY zOw~7cUm}p)T{?$4>xu0$@6)EH_DkPI23B+6 zl>UeZ5j2t_AY*Yx;FCfk^o-<$C1@!>?o|sAGnaCWZGGv*2@pFNuRxd>kEsBSm_!jp zTo6Q|m%kJeR73eNC*;MLrk_za2SQq0@2DzJ6AP)dAr1IA%v;|C#T|`dtWL#}s zDV<4*j>NH*v04G0R(Lr#M;M?jfyh;NYX@OS_h>NBZ)KZ{HNbd;ICLZ^t&6e2c_p|! zHEGFB7WyN_;u}Dq!t&LazX|O(_%8RpNA)_i1;@J`Uu6-Mn}e#%9bUB8RVGQ8zdoUi z5av7_7O#Ia&hnG}2BV3)h|p4Gu1jWaEf`c~vD z1t8J>k9=)z6RTEPINOw4#-h@?{n^RYlcPT87}BI{3er>#eF!B-lhm?ZO|;6_SYpil zNAm#H-o=9DO?c)DXvJPl*q+)5X>9fyELCe4tM_~(5oB&eg&fqWv;FwnQ~kmz?=`T& zQ>MgyS_2X$hEiHfI;4g>3RS=_j1Jjzjif98B^e_D7n0$dX^(#j+UD}}S<@fmr88kl zXS;jiNt`2F=au*HvZ_!kr{6U|d`(R8Ys#i^7{G=erwb_7WK`A?`qL9pbXog~p3krp z-T}`6A^Q!VVr~>nKF9-JPJ{AL*?pu6awIu*zY8kEM@jp5RjTM30&`@N6t}kXvSl4w zXBcM~(@Boc>WRO0A0ynPG?uV~hFVFMLxkajm7S6yr% zz8aTi)u2BNCf~#)7R@)}u0Tva9SJA-nQ0m^ zf$8tMhp5Yezs7zRg_ubx?{opPAli3g@<6!G!@LV!`2WLyt|A@^E^3fmwaZ|0W(R>oWbQ{}`l!qq9 zZ|S=8^pqcK1xp?$EH=~o!brl7R^@|C@Vjc~c)JUnc!iFj%Ku}I5<5^`@yez&&?g_i zhOIz%M0Z3kQj#s9Gxk*Tsx$V+M@Nx)pwI7vmn9v-4_K_S%mZh?+4aG(2(?D2XM5~t zsYi}7=+)z39%;gcwe-u~8kce_As6texb)qq-=!<%e6=D-2^#j|JXdr}oh4Pa(e)`U ziN_oxowVxIQhpR5ni=dE$loSK_z)a13yiIJnCT^rcoA>^Zy2ivMrXUWy-mNTMQ8up zMh?<}w|eOiv!t+XB2p@o=pr0gzSB3J`79*t1$*nuYM}Av?0@y6HP; z?C$W}C$;JmhVj~%^K|o7+N8~V_s8PF|CLOer7ga(9YryI6^03LdKLH;i3ID;VM_&F z#);+L$V}+}G@o&0{u(^n(thRCG|2P0HVPr5NJOY?zq}R&$2=;0!s48eA&P1Vyd6xW zy$$KF6*{n`D%Fb2rc-K%DYS~4IxzBCiiWZ=kOD$&Q3fNml!@7_gC39C)Gihy>T>O+ zSp(F)2tBA#o>;Kz9_9!scc!%$^6^0{YjjEt!jn`rs0X=F6K z%6Vf%zT{Cbaucp09U02%;4g}$G~=~B8>n^RJonbs51o{G@4C?SnJPcG+*Q&QyO7h; zL2{`t)*BS5%2@i~t;f-4%@*j`Wvkz%*n}e60=Yw1c>=e6+^c{fbSriUF|G&*)A6Qq znrXi%o!ZmkXN zbP3nXRl=@Wj&#@miu9|2foCp=1UilLEV}VUZOtGG?(df-F5L+d?sT7pe?w*N!32K- zJo+2xf-JbH6hDoPFYxtdXjE&~o$ZMVj6n(S9vH?3qY_`qhNirU1B!&SC2~1#PIY$w z4zXiYKhL3GD{&XBL;EF+{|7N3!Sb|iwbWz6V41h>Wv2x^+!Bn@!1sBNPc(Mi1Uh8w zUZd2IT86V7^-By-0{K2*F34A~`eq3-NsBc4w3Arfwy+hTBc^MxJi^_Udzn7woEDVj zKinMpW8M@xOZ!UJW&Xm%_^NmYWj;xd(rx$XUg=hlj5&K98W6HX^kkq#@;s7sY?fae za0OaCL)1b-#_#C}DtVNvTIEkq6)*3MMe<<_v{q;ge7$f?p1_&rp9g-{Dpic!+|=UO zRP)J!YtujUbh>LoGY*kqG551#kW_4!@O__Vhbrz&P^1bG*izdXeIi@!4a&(?@_CSl zdWp8uGK6nRu}XCiFVO_)Lskzs*3|7TgH7o?1YXz5pf)(Y9c^bw*_#7lMAi(gb9)!+ zRznIy9i1v0SE$I8u$pX>p6Gv%hd#KkVT6XB4nrT4lXfz@UN{NL0Z%P`tF^!7G3;@P zg!S^)edX@R=uUD%Ov*0(+LYkNP2d>Y$~#EU3b?A7L90kFq-m}$2sqRy#V(BT*%{n$oHQKyzRv>T8fh) zoWz`u*5?H>8+rj$CGV{II}uf$Shlz2uqOFmeeRNLG-GQ~A(NqVtIcdZQ50NwOQm&c{p2Op-M|AHKBUFOn7@Q4y1FX)7rXyLF4wRd0Ha|oH=kLiyO-ETJfj*=&tkThJ zuPC@myy5a>$Cb-5j>$v@=PWt%$T9abRd3G!Q4?Pnc6J=qyQ9}mLSX6KI-Jc2-y1(O zM2SUG>3Je~79Rz4tINOrc1n-$^23$#-AdqrSRyoJ^#4j&8;_f-7~Z zVqW)G;45+(!pjl@@; zU*6=8PQ5%5Ojo%(&PZIu-l!bGdX#+P<%N|Y6*ocZz)N0{ahv9!Y)8n8tTm)J>zD)W zEhY1eBSv|mBT@y%uu`#s{eKL&KnB>cJ&`#?z+l2q6r*R66}hvW!d4vTt*(xBjWvp4r5yZB=*0W8y4*auv`A>05^Y$Dx`;hBp`N*6I&Q4Y7!9SM0H zg9s*XFILvGLF5hk97}XH#Fm_6j%xyOkQD1|B%Eq@0EZh!cV*N-q-2RDy$z90r~~}~ z88Z=#V;&QUu*G6RN@OXalRtKt+x6akp@NqNVB<#IXA)aW9-~wqg%l9mEn`Dz?ZuJ{h5pPqUu_lNh<&LnhzuybA-Dlv%zg?PykD+V@q#s|!(p|9!dMPwM_5q$Z zVh9|`Q@?Ew+Np%n9#|u4H~;$83{U3+{JHF$9jN(tzVHPZ?VOP_1RAFCzYAmO)9rYQ zwekz<4h~?vqlWZUMbvj*o&=(R%;4`scuk}b@-kA)$X`I`!Cn&nQ+x>9psryvRNc=@ z?33V6RG9t3HW^LM5+NWI4OxU`ENNGgNGKG<(MIN=Px^i4%S_bF8qG}l)CCbtZ&Xx@ zwA-DuQCibvgb8!n_;K^2xN-eEzal~f3boRh82GATZO96lk^h6k{>g5K0z^jn*{UP0Icd@HOlb)C=umL4k_{YAi{37>hLQ5FL zFY@)zl(q70EUX|K`7F`U*rIUb;`kmH(~~a%eS%0zPr%?pDO6I+vXuqnu~)-6l{@KL z1DhzOv2JEFM0aeoB7?{Kv0kl^pF??X7#_Q|EqXvyf@^O>O|ll*-gF2Ze z_HP2)`mE{rU@cc1_?WEd?C$hO3*efw+8~xmt?n_vX1o7}1gtDM!sb;N;%xzfxFJotmaHd@ zK&h-&tAEQW7Iy`k^jD*wh(+R- z4&45+P|&&A2rqw!!=~V`NUsjR*{7t}#u4uss1OINDHzr~3cVSw7-=wPAL}rV8D8NU z26;ammH%TYtVa}={5e+GR8@L56#kn2Q^&eCrjg$&+}-!}aC?_r0o^B0hesR#`n*ir zzhG(J-Bg43HNsPDYVN#eM`)*Vo#Ywq!SWHG1}?b4y+lvBOCwHHZLpTEIcu$EY?4JV zn&4QkWBKxfo*92s_~J!#=GjGC!khs0@tH4ETy(X!od!)WUHU4%0Q}MxM(_#z(|Z_e zb~?;_{g3_Vy9Q&UEtQx=kB^SqXsSQ6>*3H-?YB}ro|w+@qg3yn`_>`+pR88Dj2E!m z)69X%!R`@`Fq*W3rT*q4!B{MM>AZY}LM15pFi?B&R}liI}twmBP_`mvqBi zL|b_MmTK-oif3h#O!c|$aFA*`jBXl`Oiv@DRR*XIz{iUr-p}(*S#` z*M`n0J-{YfDpU1zNRj))YO==vm}CM*W!t6TuMwhD<_1D0$I&Z-Qs$Pm{^XJjK?Ak0 za4`x;_n07cuZEiT@&espg>))=5_S_USzZnY2h8o15h_i~46FC(wP>vjc_o2OO(VRW ziYN70-({jOFjFw?u8Q~w|L7EN3u;LR*fF_1tw-+!9xe{^5+tWuDH7il$tB#w!eC%6 zh<*i+v=2Ac#h%x+u7%?BN8jyW7^3g|91qGsIhl=$r{?=jiaeA4rscFFugyDk*>5;$ zGT>SuR8pZ6zX44iYy^oGjVt|i9K303GcSk5^y8+u1;}_EXYc7OW|LI(*$o61$Dl#L z8XHFwMTBIz40$@#eEPxL=v+IWRB^EcHbPEj8CGjV=xzV2eixlA(GHW?;+x=YUo}uK zhfr4IxJT9`BA|LiB0CXyJpHZwx^pXA^F#3k+nyuAW?rh|)f)!`P zTTn2&yx;G0(bBgI#}u*CCyTl7;S02O=(d=)u(v+h53i)3AVj{vc|GNM^mYTtwto)| znuc2XlP%+>Jgd|#94vX824OSn_fl;WV)pFEFn*qa1PsAAcTj(V(Ckv$XE=4%!1oF~ zn^_ajr1_0d7ZOW~PP7Mw%F72GM@6oF@i3qm!Ja(OOi{(*66#QCUlX}VZpe2lTs+Sk zHt#3An(vA)bqYeAZdp<`;YY76x|bcA zdhu_HlE3uW%!rgErGI4bKl2@qQyHxbb=E2~mA;ioipNBj1+oOw9Cy5Vk;J;;{xiwi z$lSGI{T*jpHNbc&@HM4DrU%`?1z$?XZ5Ma=#Zi3S-@_-)6tj_C_c7A({|4sEz8sPh zCaxqqf49ZZdqa=f^HKg3{hmm|^b-jF&fsX|p;RT6ukN=}q>PH?Cx$5rthu&;q z#Iv~rQW5oqLOi$DgmGRd&EWRlqjTRf>i+{GP2m42j5v`pHcDKbmf{WBQmo+`>RHmx z8|8O^MbiTTQk4YhRx-zLL{3&OzJe9unx-+4f10#wHGjtz7IP6^RmrhUM0O$<&K>Qa zb_K=hD-esX+}zdKm23AKOQU|Vm77>K?jfhAz5od@jah5-(22F8zau^C(* z)305K;CVq35{!n3rTi(P1WX^V?PuRoOS4Y@vOWqnRg}c7JVUmi2>)A1hXzR9JQ5p` zoXl1;V|;~!2)o5g+~~uDE%gaSikNzk7CnB%TM6z>71kTQLxRS~WHem*H;-$KGq_@1 zu>SJ+Y}%}dL(=darV{$_Y$vOs^bz5Rc>d_9+(pv9$<`OdCAdx{HySPKq8WLVS~+gb zQ_#*_#xEXX%%g-RbyJUm{ijC4j|FB&r$59&d62hJ<5!XR@I$Vd<96;L1(aF{d@Md)>3tp%!Kq~qJq(6Vyjs?uUP!xL zPr`IHw$!b-ojf^TvouqI_<~y=U}fLm=|e}#vvM%AhjgFCcgj?Wh+buz^YXIjBcNqo zX?6dy-^}~fNcoj zBP6ci13hdIFT?1Mm|sS&vX3Zp$`_BmO;XD!y$^U$?vHCstuL6(Zk)PS_jWN+bVs4m zb=ww=--s=)Cx{MY%@*#4_SavFfiG<5OdL@)zf^;C7iy!Yl?5o?$gOu z&|f4qjQEx5z3t^MA54I&;727!3x>5np))78yE-71 z??I@$Q2EdITo$*t7q&J%qh4Og-|JbzL1zBjO3YC-xM(Z%s+4+<5?39Wh&Blq3kFPI z^}Bdrc#65FBIF;4f)1>9o-o){zjaw|{nXOWjc59h<{FW&RrkF9PQ$Y=e*eB;LE%R5 zw9L9{g8#q6nkcN?20zXuT;EQWxRa`zC9pj+MVP7v7w0eirwf3gf!eaxXpy!CC7oA@?h^_mh9z20m_CXDeJAG1 za}c#zg98Si58Z5SKX1XV)^2hShc({hC)DkzzKFhvJJ*VtYYTFDxM6`0&ajZ#IEcQJ zFU?p0k}Furar<2Y*onl9f6VFJ*(|4O4_uqpwZ=vx=q}igs+)xZlk5GgZ}-S_gQ@}Q zJ*%5{Yr%PxM|;NfkBMxOZ+M=3AC51EOC>JBh`51$Mh{OPA6E0{&u^hg8M5QXAC4x; zde8z#xMSeaeixrvL1Bg4X9gZeUJ{ zF<1fbRyLpiZa%+$cOYSEOCUzykJxea`}K`dXh&CE)xhRbojbkIZLht@Q)=-!wR3ld z>?d59eBV|dE&GW(c7xiv-@INYCWg;twe1*lv|b!giFu#K4VT15TY^-}c1721u~o>1 z3??uku!R4dceU6~L@~5(zz<)$ouZh-*+O1A%CQwe%HuBvN`hHCCq|1DEwegCJR@yc zRAlJ>TA_fX0z&Ny@k_M|H>5#4d`2qJPA|TD$2Cy+oOl<FK8rD-zz&=#_$RkeNh(`scsOF+R0$MYjPg)(g!<|Wc7$N^ zqf(~z2zS`3qu3l#0BTqDGlw{*?#bPniN({XEi_(_{`=%o6A&o1f-#qpYPFWFBi8M> zB)?INu(atO`miJ+6d+Hr2I_D=n~RKfG4FJKIvJyyqRROkk(W#sj6<#Q|Fa3a)#`ny z(@d*<@YPI{BrM`8N-fJV@w+tprWNrVs$G1Rf@U624ERviWm?D1-Q zFLWDfDG^)u9nKGugthDpAb8!pA@#kTDPT1v1E$tv{pM?1J#1|FWh@1(UD!_$`I=zT^lRfTi@4=9y#e;flRuiWu?>Wvsjh{SOq|J8=HT(m(w@RsY~OfMy7z zH=#)hY3M>G)J-h7{P7_|Kwhuy#6Ds8PK{WC@yxixq!qJ+tm=~<#Jo%7_QpF&>B3ju z>Sc9qU3M(5b4B*XU0)hNgPvPjwKJ+Of+LNQCE!ew#^GxfeBmqTr!FFYX`~LAtdN zPz7U%Ab+Z6j3x-LirZWBsC526V^PQulC8h=YZ%=$8HI$fl$rr{mioA}!xp4^jcW{0 z5#KE#cqEiE6esl?Sw3Y_-#q8T6(ZmXUz2~W7iIOxZP7H?*Rm`R)6q0kxSXH8M5WFc%njb`m{j*pFb55*Br z-R8&_(f3Gx4#ypq1e6q$eM~U-@Me4Jazz{NQWO)Xj2|5Z{Zc`PYlovY< zpFTgG(&PxbZNv@5lO{opd^cEKTwHP`g1Y{=J^yhtK=_aFK!cDJ<<|MDQ%Nd8G+K|H zkDZUaNUg}QkUzQbHA8s1OS{URP<`A8l$=?ajqm$-Nnvln4wFR|AU%3++_oc3;||M= zcM9I;-8YPD`S-e|TB)#nw`Kha4{p~?lYbK)@JrU6>XAoybqa>lh5Iek6*%$oubMP# zv$}<|TMnKcPR+UL>+6l%6Mz4P-1Sh093DEZuC6{Tz)r5T@-9xD&=ib30VkaJ17>q9 zKMLgvej*J_4*ieR;{)iNDb}q1?p8$~LiMqSeiXYJMto>(0ZBPI3#eIhwyd?etorK( z1)Z#Q+Sr)Xl_lG=c^=NQ<|s1u+`~@mRKzv&%66k2jgU=gC0Yab=`vV8if)<+qR%1q zHIK?GOb1m`e5V&8_m?(SAjXb$M?^cR-d!X1^4qwQDP#;4>PBi?u=bA^Kgy{3{)~qOim#~WQBQB_ zhpvVsLB3RyA_bQ<#3M=eWQSJ@p3dUZ2P$p3u07svBK;N1pNj2&TKlwvC5fs*l*4|_ zqeVRlY<|qSQGAen`t!92*7;*b9D}1ndNW=9IM#O++D{g530vD957MNd#2CpSMP#IKS^n)EgKKWLS&>=c2HG`x(UUU9q90Qfj2NyxwYEe^uh6z|mv$n? zkY%MPx^-DX6AAuaL{oeC>&2OJ`&odq8_|(qWZ$(M?2^EHTyebLF(Je$y>&Df zJtV?QLdTq$PR?Gpr5)MTp!7xyJwh&&aj$2ySMuax5Kl%C;Hln!9Vm99(AFHNe)1r( z*K>N*wPDaJ;ckN$NbTtIM%S|N8gH5aE(A{ zi7tbW=*Om6WMe9dx*F|XA*{G)_{DIv_DU%XBV^+Ni+=D?Uj*G9;!nSdTChCOe~>9$ zjR2M|7a$*m*D#B0A}YRcb$7V>i58g?B>8FM$;_gd_N>1?E_j&b-7m|lop_h?_na;l zF(~BN^0y0^{q+gZ6YZqCV2_;$7MFu&u<_9)yE zM-rO<7MP7BV%pB^v2 ziJ7-9Kpt6*rw-hKB1Gw{zMT)@zEmw^3d!r#WPae`x)_x64OD~3wuy$2hVEgdUt#+W znaX(jr_4FNBL33RxAoP|856;EvnS7QeL=GJ*Zb>o+&x1wv%kc^MuH&p2jb^hpyZ&X zlE(h!p3u~jm*qktR0#H^UhlKc%jPgu#DZ6XC2vI}M<-H#=4XE)5>6c2I0yR%AiV9) zI}TsX6aRWbPRuthFVBD0v3_CX#w0O1ZwJSf>lS9;$6as7)-JD?)IrqQIWJ&rt*9 zTb8ibE~rEy>8aYOu5&jeW0%TgJe?B?iKbz?-L0=5?2tQq4VK}9B+HV)(c2$Rg*+9xMP-KGx@1lmQ6Y)Dtjg^alE zsy4B&K3rl8t~L12eNmG8QKlwJwj=uRzAp?}S5L3@ocp;QGkXYkvO|hKqpp>qThzWO z&%eRZn`&=M#au<}9ln-tls%Cgd>um!(;Y%K9_1W_oFwu++Tr)2wrzsNuC2)Y_xFK2 zI1_t}H1d={XCKp2mab8fL5v`3)o=706O_$mhCv4T%&+u=9*)~}003V+Go|T|t1j*Q zu4^6VbwSwGJs!#TSGzbqf?V1K)7w~y$V9i6zKWLPTLxsxMAB-ve;Wfmwi8TajEcA3 z%hoO(21uFuhd7lD*vwfjSdS#`oDJYk>yoRZh~KPvC5V1J=|0+l*y`CmQjy_)*_W+w zW8a(1a;~S!#keu2uOtlBwm`A8_^!N_ylY1tV3QrRyfWgkG}dH(pAFy(U2UJ}AmyQg zg$O!_Hw&vae$j?bK$!-g5uMX+Uk%F;gN`Rvmp-ttRq7{~X4<)DZLvqVXt0MOhaDcT z`krXwPyO_m4Z*HiJLnR5Yh9F>7+}H< zMd|+#Q;yhSf5I3b{G-)Jex;e>^F?R>;3k2O=o#?8UI29@Q`Cu}JxKoB11Z1G?(03T z#y-6W2*iW17jtWqy=*x?tFE41Ipu!2KST&i8v!5Loa_ri;|5TY62j<|?`t3Jdvjjd zhFw@wQxo|8GhO@BZ+pojP+taw%BHoob_2eeoF(nsEvdVRYns_`paBLv8 z_cE~JeE{}`*y8UiKgn-@MY0ymaxmnJBA3`TO7aAVBMZn|zea*2r@K_KH$MDavRfx1 zFtb-bt(J=bQNwPiE2!7OJv^)Mfn2U|iZ{Yd&PuHMi=%RG(u|z^wV^q-0-A9Vf! z^GMCj*d^Q_+YzzE^?~FNcjqWueY#b{atRX5o5|hwAafK1b7X(;5%}%@Kq7I1zSQ^X zrC^q;e0qW=ld8WduTpc{LAaGOuSwy?ubWj%~hV<*mS%XibT0}E;0~7 zUZ4*j4NC%fqc!B?*)8^2-BzB9vEQ`M%u(mRLnfCxycx-!Zi><5G#u-*!@C+j>(|tu zt`PK5;7_koLqorQ}UZ%@C%3qPD5 zvSIV`Yzz*Ok-{_J^#F-cxRJJJ!O$T;!sEZHOFvy0Rm8?4W84^?vKt7GR>7c)+tWC7 z4#`YQU0Y1=O!FZqSQkh$l{FZ|HFG+{8xSXsBKE;H?S2O-*TvHPaft&k3aVN_sU z&c6^{izQ@)B0jAA2cr7-A_0ld*@o6N!r|Nt9$n5l&p)E9*Kl$XX=Ab+`hULq{7n=e zFKXXL58wmax7d5UoOpuxDDG}=&e^%uhicHEHhv+8(%)YZ-67r5s4^G*2%r^;SAFSLadF3H5!%7^!Cf1*2H zH9g+4e=mKP5bwQbPyOk*??&ugyI5N#^dWlZ+CWUxGimGQHv30b5+nt`Vc z?o_ecR;#xG02akAXqt*t7hYi$5d;u&n!CHCC92*Ljh1`|5+cdj<=PFGhDoE3UluY} zYGCQ-02r)WEqo>brDWCiq^l$A4^=p(vmTQd4tHT~mWzFRgb|5M&KU-lrtXh@W z0a&6REEm^Z-HzIJj6M*FC9z-)&ag!Eknyb1s$)26e^#u52gncsT#E%>y({=JkxlIb zTvM5#bo;u$^;f9YRx%MG0i6XaW|1E#gN1mH8N)A4Uzz^Ky4zhG(dR(v?P$@52RjM( z5#}sHwJRe^&R6OdJl3%n-F7H`7^~%s7!$=7PGoUpudS)J0koS~KY!o&)FMV3w;Q%% zP=27R{3h#t(z0}uw)ls_ofAV1s82LUdJT<3eToXR1!~W)P%=mD_j1$u2%pR zLe0Re{_vl&=?{DeDXG@cfq|7e8Rw zBlH8vO*bW-i{=}493yG{xUz)~?ERu$;|)<-fhC%4^NR}0Q16lFq6U%+>GcmR!*yE? z%aEM;dx3LYzr7NA!HFFszU0u*^I3@>4%FPpZ*Ut^<<07DyIiKdYuAqty%teLi{3imMs1(F)y z_E1dz5}BcWji=?1MCy*!z!6?5`prbHu@>GAzIkkXr&h9nSFGc^*sux^6$NfGf;`k? zAX4wf1|tv#gl-UT5K~|C&)<;AfF1g+J1;{J-l3?4Nz|UY6`wA|^Vyu}t}Y)Bi6;Ii zcDW6eP3~g>YDr+JZcg>%EIPee%=8s`74|Nd-}STi>D!cZo3CKvi>pLj1ga^hnwfga%8!4}hk++LrJ|^hwBD zSG7$cM1fZ91`GHDuiO&I=Mgo?0+fQY`@$GVEBKfUw#rpXkI>8D)JZg--n_qlBokU3 z3=|`1W;Xm9sy`Jf2*dY?C}*!<&gjw(v;kh2U}3VI1?zdjM0>C&O=`H2;ROZaPw}XE zpQ4BSzDH7spz5qaB{pGa7?mr+$#-vYQ+~I&S{XJj(+SnsfQ!q{mKJ5+rsHoC6i6SG zluC!Q&Xe-bB}-wsEVt(aI=>fGmzMHbSWfW2D5#L?a6rGtFgsEh8mG+nUSVcZt}{8w z9gnxCasGJK$JCS9K?2b9qIOcL@;2wyl|2qIWIyE9gx7@;Xx@05yMAJy3#KJA^bhIC zaVN5zb9hbd1F~`UegGK4_f*HG?y1VFgZW1#;3eSA93R@rRZ{ImS>s0fkDfzGBMk?< z!;9Zt(P51|5&^Jl1gu*T^v40OV)P1J%7^m;J{APwG`muM_}yRAtZt8>v|6(%-S6~E zj%gSnl1!#F-TjMc%un$;DA`f7AAQn>v)cnt#9z3{k~el(ghUvL_*gPT6ecKC;XE^N z+Mf$Ftm!L7ED)^_HJPo&HJzww<|d++wdT7D{r;r zI=GJqmlx7Lk3)n5w-e7_YDBpg&J_=wd_H*)FY$+Crf=^5UKEVIpIkFBs{K@!MPrpZ zLeVLaJTHlTG|;VT{+ua3x`^Nu>Ie5)qgt{v*LD~X>j8ch(|33Gg+S?>!aNrvAUW>R zpNQnQ5c&04=^tu$IVEi9Nm&DrX%;9@XT% zs*J4|jc@=m%6_l9;~yUWT%`KPFO6>^)TZ<(UrWjwsAUICCwu>Z)CmFQU%2ILZ~DLE?Q-DDl+#^sV+41!5;|6SpNLG?d~iOelrI!WLfH2`fs8i){HoVwPtqXZ8XvWfCxWV3u2-)j>waO_saDmWTL$(WV-aL>3b- zIMGjH4`thgkQAfGM&3LUevu@c5bot!plaO_3@tri-2|$m4Wff%<*ycmij=P8LK+8v z3wAZy;P@B?+nPkwnjOW(ukueDtm__Qmt^GNiv7nxzR%IKNHzTc95L2LvHa~;!ynEH zQR5%}Xu;rCHfBd^$ST6Qtys1i8615ttkk1+d6`Ft9}o0V${uFe(dr(@%^jS-R+jrGl)3WL&M{D-insIKek2aZ8C?ZDQOMw-`b&&1-h81H= z(1pZ#7lP}$O*ZZ?JI3nwJ``$NnZbRW%CS0nYr0yr^^@(@3Y9zlFyEGTtQ2@8Y$)dR z*S)Sns5Z{*ml?G{neAcPt?CHS!W!8XL`x8D@c^fpX?Zb)ZQX4<{V0DHQQY&H?}u}y zo>8g&>s`g})c?VAZO8(0E(N3+x{kSij~pQe%AhJ7v0z=E*(NW9`LpK-jx%SaQuTA- zDZHJGJVO)D2K1< zFg%m)g9XK7z`|ib=7&M7Resr{C0Q5$XKbK|V3GB%EXdD|@wdv4y7cRH)gn2NAA-y| z3;otOtfKPdh6wST9Z8z+g>`vn-nl-sVe(9~nWDeisI9GC_*GX6OMy}ng8z+2n~x)- zqT3kn{uOO?q5oZrQK9do>V3Z3szFI_I7!_PUbZ>v$WxSQhFI;>n028x7I1`&#hMnQ*WaqpqRN5t1_?3a>CrbrM$9~Z#?@m1L8l)uIyWVdVQE#u#bXF;wUNZdqaH+$4QZ1b1mLXA{ z)y%wX{?^c7-s~RfO!lRJA$1pk|6yZ-61Y@vub`x@B4!=ROd@NIN;PsoX98&bhbYA>$5maV#zZ*4lT3p*m^}(6fU~JXQFMN%Uf$W$&=M2Fpf!{$)_Ff_KuODp6SU1;WebS ze8YCcYn86pPZua0KG>P(&d2|G4_< zxF*BCUvenjY&3#^^ym%+lunWE?orYyF&P5{=}@}6y9ZJtCEX(34RWT>bKdiL&)?g) zxd+$x_pST7q~oF0(hLI=noXC)3J3O7wi(9TNHnpYX&F-DE9Bd2MNTCuFSojWAT0)U z7^0dv0=@TGm;{pAJrPV1o>EAx5b)s|#Uji!OeO|O38FGr=W`&YYkm;B^LXxf-D0C1 z_fhNjYm$M2urbc1h}TM07aGA7DA%pw*)s*`;}Sg$Z60?tB2&&QBLE84#k=NU2ZRXE zCCg?F^1Aieyj8^nm?DzsTVNhS%q+0FSr80O9FPW#68^TDX!}TMs~#NHh}XnX{zLV} zJR;|TgT^)$zZD=j+!L(i!=IOC``d-T>BRdlo0$~Q__F5p#oFZX5$S0iCHHpGlhI-SXj#_fdw(a|9_G9dwhWfIb8PordL2Nj}CzbQQ{& zyD!?>!X{RkIXwQ-wr$gNiD^NU+2`cDTt4?dVUMkA{(l&%b%jP#ZI!NWQIhYbt^ z517^+xf7dOPd#0h<=}-BaxaTla36h+Z5#==5k6?~jgRmK4?OEYgI)B--B9;LTv9L{ zq8URAy+`pJg@vs-W)!M}6@Xf{n+~D9!Jh%q=qHo(vD=HQRY{Lp#Ymw;tQx5PyeY?| zi!XKGP*1a1Yx4|i^`T8tStK#6FB83YlzPXKhED>Qo!2O0vOVYfWMi(Cv2`gVBWnwZ zGs8qIXe^W&^bj=H91zR(1uow)3X>#x*<~NwsvXoX3_s?%FQo^ezsxO`C zqWS9UG{r&~PJyAql)}V7;sA*>`CA$OB5>P+O;jvc5+F$F{{cZoUPV+5=8^o^%>uUA zsAR4IQ;G74z>!Q8;_K`7wK=uK!df#ol!ufB?Q*NxRNV|Vqi-Wbo&N2stp3~K4AJ#f8>!vEqI%Suer&+iP zX+P4!&ST0#Im{#hbcw3UkEEFzAeC4r)Bu@~5uE=Xa_o63Z}VBZG>z0<-1|lRR6EkX znslW0&<4+ygzO@LiRiuWK+UH-a{Vr~ZRPq|KBJW^S+k)=HA~vc7ZCUih^5-TF&>m&)!Gxc0kg%Y3tY6#|)ERJe32a9B)d4PILYDV?jA#XIl> zZh~f+KeaRtU5DccxMpO1&HcVXMNvF%(@Z_-d#Vi8U@k}p8$P3TxHpgU6vdbgr?F9e zy;tv;>ZX|vT8Do1!>Lu(o_Leav-f+k6i#iwbUT{Sj+xZB92D}BFQTE$2FMA?km*FB zx4C-IRkz6@uO1Me!H_rV$JkwL8OtadKaa4T%N3NlK&nCTM~+qh)pTBYlq>?K5?khC z-!BaZzG_Ds&S;zacQYC6wPw9a5>KMo-&Cd zB`h5FFCoQWa1jD!8><{l-50v{P$<`F@nm2T<>_{=cNu?qiH8wC z(Vn2`L&sv!t^dV=R9vX8bO<;0yu>m&CULJyhLwCs&r@#rXUM-|f6(+ip%P?r>&JRldM{`sQN1CT3Q7RO)ce?3U197gk>@;J2T^-bbRCLpi zsK*|+@2$q|rP=yH)-ZV(fLY0Z~t$EQV}{4%n4 zQOT~XM!!8H0bMbb09OplWgB7yGXKg_0yF|+)Jt{U9Msg#s6oVK zJh1{|0n4$XFT^6_WHrM!!4bjWEU^5#;p$K6Cl+ML7{xRZ+c`SLX1Z1p)fqALuxQE9_#(Eg`R?DbnpTj^Fn%Rg^Lw(yqiIt|U%0pB0Cr-g_Kc`f*MQ9IB8?yFPw?o0iG`2me}w z?oFc3?#x_*&myLQsOmV`#hjy1RMlTRFaXYo4pOqBeSEGe@VgOFWnqzTUgp}JlnQo$ z382?c{Mh1gfNkKKPuwoa<=Y#jcwX+`G0_QpqPxNUt91#tugh1^3h4j3-Tqp9vLsRGRtB*N5ZoI&x7 z(xV2%B4MGIkjkPq=iRb)^w8me3 z;IwyeB%!~D@D~@jKY^gm!rhPS(gy2$6*%W>3tg3_m=}Kl9oJ=v4qVLRV3L4q^D6~> zQ6gtM`7ks}bNR5NiPcMqziVagJ#reU_PBSbvKtg+nBs(qXNPJ_hrGU?Qxoo%3n7Zo zPX~U0v_ai1NmDd}f8!9MkV}^lDVEmprR|&Zt(|mPhp#kpFbk$4nE3?Lt3_yS+&wt{ zp~D!1{TP!URTGm&z8&$^-Ep8@{-6BHrrN?SoKfU73E9rYylzuj@|QRuQ+-^D#O7|xwlKu(a6Eb zWky<3hniob-JLg9$xQp)EJ8$mJe#w{V!`&P;ke&3sH(2QNo`@LyJE}KS*YD9{XSmfeTxbwA?s|}KnXHXP zcfZ@O&%4rv&%sw8i)y>8IS`7!QXkD--%=q+DLjgXTZGf+rZy6fIMpTL9!s;nNG%t3 z$M1v4ypt-N>^%CN@-_D?=i$K+A1?VYD4Sn`W)V73?7cg_ht|J(8_9Cw@LuBZJD+*q zlbLdZ#_=E*zl8=-zZLX+r}jB@t#=+aT~-V8ex^UGaP)=Q%%cat7Ngg*)UCNj zOj>_Ej^}S%R{A(+C33NR`!|)W)9`8)OWq#bXb)~|$!cER2C&BV1k|ebTb9aGCg_e> zF(0BBD{1e%z`V~h|Ja_sb9>3OTc{qm#MjaZ9v~RGwhNS;P1fGMJXrAIPmdLu%<0g4 ze0p!ApxFmT3TFHj-m%F9*D>w?+g6+7GnJeoB8^Y=De^&in#`jn}1( z3g;8D?u~w)E-vcmCq&fROcXE8*fM8D)r%<@3V*b$W88YvfEr9VV5%MuX!VV>m2AueUZO4SYT zsLw7;GoJ_^8t?>fpaGeI*5*yC!q7GA3~ulUJvWM*T-=*o##Qt%O6UcU&U>H*WyX$z zPTR7{Bm-UJ$tLZUOVmsDJHEwLU2(VoSey`%2H|jh;mR=}{Q@^kMZ5ZyLiv?xm}xug z0A`zW$VOTW@ddNsP?6AepJ^`47jp^=yz3sLmP1I1*onUs zSR}rr_GmXKYRicm4$jf(J`E!b7?C7s@{pPRr}iFl9D?ayD<#+YQKN+QZ6naS=wZ1b z@m*hjZ+8>tac|v8GJUc)zf#{*;oAJCneZjtndd@x&fYEsp-Ay;M2hu28fX^($XcGw zQ%S!KJwF;wX6>j*-LNoE>@JR)#6>;?Fz}_5fay~S*7EB%8`>kR^#C02PBoL|_lTFO z??$rhxu1WcL?5XRmV5sBR->Qv&Z=N<_svv86N;|u#t+L%!68Ij55o(Rn#_-9G*7ElS3fY2t@;A+kZ36G~|AUqgW2LOh%>e^@B zrwI!}SnQa+NNQHy#F|BVL>EWnnAS-53>|`9^>iZ^AS57AeH?FhX;!c|A_!G93WX#P zB%=yM-I3+ynCEylGj4TzAWIc`T}L6~w|Ob&bP2V&y>72%9I+H_08lUHj9clcmPVOU zXX(9dBrN`1aQ7@!#=y3@6}XaJsyFfyY~$6EnOeFLhi}xm3=reNgdi`KeuuL10>dGI zID+5_+bT*6%=OL@T@s8kN7A4`{}QL+eRfw~r$&X&K3%>60YSGC5N%bzDQI26hocc# z*)&FK;=u#Qxg>qFq+bv!-yXaCr;nh?fOcbagSZc4m6bl6fiz;R5g}Xave_Km^J+E= z?b8B|?{YF?Q2W|VaAxy^VyS1M<~=1u;;b1$Sx{o`SDc8AS45mFq(Uoxk}X^x=y)ajswhdHQl7cunHMp_eq|Aomx@L z!isDv@KrdFub_FMxRY(K7*RQGd(8R;y<-{J`7PNl_rK{FmLf7^O_elB-rPQW-!*O? zJ#NH1? zDCu(jw}fEMsk;MW*K97!5?XHXxN>lNsX@57i)=Rhx4Jb-N{LHG`t+kXSaY2hgzzDB z`1m@+Bd4Lg>vYj@*%Q5-j~$!apGALO;IDc=0sf-u4KbsoW&x`HJUVZZ#zn1?jC*5W z+bs$sAf#i(Z2Fv;nCe`x8w2qgEW-oV6729KBun{%vr z#bH(TzJlgS_FQ-M-J;mH9q+a1!Y*XGZjs)hyHLCMHp)jd-^L%^ezNoRZ$)cB@I>Kx zlGj+SOvuPsW|k3y!W5Sbmv@1azlrvm^|tK#jXKs;s$A#UjrY3@f+Y+JeCZo+rHTHk zc6{`TwI>AdI0PX{A?oX=aOrctFkKW4TV+0V7x{KsiFFH@FX$qx2vJ1P#}c9z;0*JH ze_2-P`F#!mVYkr21|`&GW=~`sJ??VA$Y3Ov3(egNL@tSOXv?47RO zjXm4CI!SRn_B6#-M?tz><0x5@hjPZ8{|KaY=07t6*$M)!BnYGHay9vS(*=?k)s3?u zn^^XJ7F|zP?``9VS8F;g!O%ctm0pzI|$1>mBm;>`=vi`Ir}#CoSQT6 zw&op53I%7Pc4-vp2H^%S7YlZ!pmh1dBVH=R^6K5b@YvU)Jk1qYXh|cLp}6122ekqR zw~PlcU$F+NI3UAz{m!8A>`2YnED$+Spx?-UKam>qmZ=7j_zTniTCGE(`Jy6K+gtORiVwd2zU6uA{1va@(fky=0lLg_w@Pkobiu$ zO5}SAINsmSbU(e>t=8oWlKN*8c3jFj{V=n=@bSmFE~FnYA%5$NeX@aEI&YB{P(rho z6QirULOv~TY!F&ty6(tu_p_z6dWN-wq7=vJH`_^EzYK`qUmtrZXvPjUwX>Y}mZUhk zpi!`t@T(kG0*{h(c9W6!G_LWzctbd{2p(GIVwfkHz2$~moP@IX?EkZk_EUr%BBaJe zXB*kvbE+BzCQdQ`x}8Sr!cvh$7^JC?HrR$r2D(3vMHNO&3~Ri$(YdgLN?ANY-_!}k zA=WRRV99r^%~rEGHu&Abo!>%0T5yjv?gea;D0vw86@`1gasiKN6kxUUO9jG-t5UM5!>K*)jf(H?ll#)3}0@GNJDT?%#i z@VD20OU9Rd>M~|Zrm3$PcoKslA4nK*vDQDzRCwXMC?}g@u$L(6#R(ED!h^M}aUaLu z?YrtPBnR&yTM^p=d_|s3S>X#dUwe*lFc_5$=~-oQ!BGfvvnGLyR;)e!x}^sE=~rt< zhF`KK4Gz@0wvg>gDK%1W5z=c^%q-R?QI~QW!QdyX($tt4^K8FcP}b`4TP}MaAna=$ zO?uzy!@nlgVK-`DpILWXLq|u=&o;E27Ete#|K@^Y3>MjNbf(r_0^CzHKq}CZXAlR7 zi>t`Z3>XrAhV4O(fh!37@a1AVDCZ;dr+HjQG{MyBr$4DN9Qk8am<2J-6Z(IWlBA~v z2+~|(r!O|={ll_sTi8fGR8d7}gW>jg^haJrw!~c4n1|Dn*$jpOK^Yc#39N`RACV0nJY2R1k9`&DF3sgg;v+fjPSBVy6vdnrxPiNa=x2v6AJp(ENRu~y6AP0 zRLdK)`su7hH8j&Q%tuh5;QWo<%8(__&s}Zw$=W%J<0!HC!}&kzIYm{kT>q!xA6=6d zaXSFS0nz|-9aho&0qCP2YMmrvPo!~^TBR43t^O-5{~A{5z`eVSn6=a*5)Ppz19Q7L zL`@ctUlK_Kg^%Rl*$)Amp&xh=7?UsVprN$P{+%QW%76kYWt8=(WS&DfNNxPzupMxG zn>6)Z+OW2_shi&9xDGRM6v-H^S{mR}8HlAWQgNUG(MhY@!c5S@?8Rg%;_%zb zd}-&!(bZOmUrDo&V?x}`Raw|Y(Eje_0}ax|VbocfDC9 z?aW#OfTg8lKu0*s3DtxfOHJc`;Q=>Y0@h+q`796Eu(K-HAC77O&4B--K4(u`&&L_%VLuNV%7dH(?%=eod{--zXN~WMvuJDiF7}mF{QQ;!0!HAw z2fGftPdjSg+yuZ((lh|#CCtt#XPygLJ1s42B-z}4t$^vzXFcdXfpee7%Z+^wU+C?a zTLacjLK*{N-G8anUGW*|s3ALLx0mBKWinv({oc7?++~zsI3;(O_d}jhM`@oFGtCF4 zrBnONfSrgYvoTqNw4Hh1lB~ed>cUPegv8-lfV1<+8uKb#dDi{QTje_aRRbuS$}92B z?Y}T5g#^A>%a#TSD8NKY&$yy6=lgCpDm$_^NQBeGm|kh6tz7*+gxy+a*U)5f%jaGV zsWVaixv@3J0+EWglbw4u$XPhn#o|5}>xlW2FON{akp#n3z!;MOj|DU<=4f39)c9-r z?4q>Pah0?6cTHt&YyA|hqRxHe3R<`P(up;dq2`{WDKNwKQ<%n0DMMi5!i}X@biR;b zvGR^!U00J7HQX8(Z>r`n8Vu))iVu|~i_zZgl_+*_Z;D%J~JkJmqyM_-@K7 zuQA*bIYEp7o&POSEU~;GoJuW{D+9+06dUUN&D&cpFh#NC&a*VAI89Qfa_VP7eiJ&s zuCeta&b34~T(R&eOhePo?36!zwcH`xi}>BV`(v$ZQ+*HZM!s^F@U7>PzWyb@S z=6B|(c9fj#uU%*#bJUk!!a@d|LwsX2z8It5ihrMvepx{lzFQDBw-NRes6xLk+^$MW z+>UqsrSwYWD7w7&m%-(0jqhx(fkn{xP&61?7=!d83a&W-nunqvx-B*@MD{%nKl}Y% z;a}w2N9U6u4p(}=6X^G}ISDLG7^Z^Dw?W-!+HJ~rOY|XO)SGrHg8-WMW4u%0!`GRg z+bhFGSA7NAUCi8(Di4~DZUH8L!$zCOkyLXvV}txh6(|M6|&V9Uf&(BoGt7_lOf92k0>_C+OA(h&e3fokhYwLL0o1 zP7MW)_xzPlwPkgOF?b@$s->dhW5qN#3OUm!N{o9l)OTk0fv-sDl8_$CS*nmtNqg3s zCQaeH|9L_xvWUHOikoHCkx%|r(=`uq2uzeO>-Bv?pBshh;@w|b_afU}0?frDPh|+~ zq7NH?;{A$NiF4I?c&&M^{}NKL=P6p4r!SWWj6^oPv^A;Oucua@cXN*xNnXkszt6mA zRkO<Omutj*}=@!Z2`PH_H? z&Xc*!$0bC?2(+K^=Z|#9*h6uUNp>w?tY?vPLRHY?`)mJ4mxr^gtitxY!vn$0^7_&v z8ybnruMJ2W&j3jv1r56(s2RKAVM?l~s_3d`W<0^jWaIs@_v>{v=H=v*7 zzS_#JAsrf(Tg)j14x#Jt#XJ*GZ6^ZL@5kKu#%0!(X#m%FragPe=dRAr$-@Rgk~Z`M z=_#h)w}Yj=PVUv=={i5SFPQFKzDyEp33`{+ntNm*MkwI<%cu3U@iOpm-{D{g*?w^0 zp&0CK@<&2O+)f&PLj{I%;lVIcZ;s&*Y~EPClWg?eXx@f}i;6a+h!B&6_?f>xP7raX zzcH5EHnLG7r6R={K=p|d2t@{v?g1r!F9)p~kb<=N=HaFVWEHCPr1$F38P2y*&+VCg z*z&8XQs83hYW08D_m^*JiNde`yqFo}#{KoY|0*K}<^*{Ubv*VvCXz$SdBq)CWzN=WQycjoXH=dcM zY;iLwd>;iEY@l=Fn469k5hQmFg^@g0<%uOBOny>Ah9t&f9uCOm0eS!XyR3Vv##QgmhTv7cVfl zCMON2Z=jLgufwi}=sE6T-OLT>0ksbtnTBT(pY?-g06$BYyb=tz9oh75U}Tf935v7v3295F@u z3FYcbmku4+EdT_xq)QB&z94)%W-hZ)g&iCV<=;dgWKc@2iLJ`T!U_O-mSd}ir%iONiG z9tr-?BD351UAFXnU7Bq@{Z%Kqtw2iTn{Vcqbu6VgRxdAWGK}Oa&(7C-96qBhadhc3 zx#_qo8;ieyv$RO6E@y-l2~x$6(+={EdI?VlZf2V#YfH( zh}eJ2N~4nlTRXNzmh zQfW|-HQ#rVMZ<4yIKx(YPO`?h9teNxzFi+a@rBDWXS0^V|K1D}vB+y(&ursO_cpeK zpT?XJ5qY$IK!?r1yS8g*uC>#o7VR-wot4~6e#8Y(2t`P99c`6$ptq|q^QYVK6RD`qom8v0$rW+BhcPA; zhS>Y)Eri)Xx5dZ){28GoyNsQ(MdZob-knz*0@nm2E>a#JRBE4_TWklkJkfPHzPS*Z zOD+(T*nre%{?ZcpV@bOwYbP;xrlNB@Hqc+05a6VI{_y!O^S4Cdrvi(7dLAF*Vx-P5 z4jk7ySsDQp+-AM?$>K$D?bA7Ae+y9az{~!~6VPU%^6O9h;9S=(B9WVB^QBTV8brhu z)Ah!yi8Q=F0y{yPj^e%#<_D&I*P})*G1371&f@lL;K^-$UnJ&h@b6iE*OrUWlVvHg zix@s5E}N@bI;&W<%!!28)=XB_?ptTY)Va!f#1eWrTTtq4U6BjRJiDAb)nDLofQV-* znSpi!sV;gO!Ee;t$VFlyJ+vD20Rb8O&?fxE zR6d234d2Y058rQMyHCS~T2OfZ%XlGmIdP=lt%$#<1w*FMEnSxlp}N## zcq_HL?>{*|wA<^nxvw8PNkCd~ib1?AqU!8iQfRW};c10<`bf=tjhaQ5Sc#2wA!(K+ zjt9WOz@cu_F~{V=ilA6K9PUeO#q}~1w-^vS^8S{eQRS~1&OtF>Ij-bPWRebl08QHa zXQYdPYcTUxY;Y$md<^4=qeH^2If@eXEDWES>ELA=?P4})Ch6K}I=DF+B_8i9b8C&0 z)%Zg6*rb>d*dx!$#k@mc?{K&Ti?5Vb^f}i2ATlr#$+`W`3MGg;JxeNmSci0{X;vELBmhYX9;*i4} zaX*WI7j9gTlAJxLV#VvN37#WI$)0b-w;aNV4@fZmF)X)Y{XPR71VzHnVBe5s?3N_- zX|;dCrv~eJMYy0z&M3%H+M0F@RiEAa$l{pq%k+r#MPBItoW zUSWG!Xkl$D{d}N+`Okp(m8aJp4OP!$oG`wrty3XXYugtv0LL~X=90?AgQ!(wfKLpq+2&qB*E@7l=E@SfL!Ugs&6YqX_R&J3oXDW zj+P~rF$qWjeiMwi8&$jbS$Os^Qs6H%nKE)z;V+>aY53*Tz0XgBiMQt?r~MG#2^x0= zPZPBTc>QBtBn1_d^wX0vkU{%NR9L;Sqo>FpMlM{Ka^hBcBEOJZ_^N)GgQa0YfuT7) zNR85;;slGAHb$n?TCiG`462-AVfB4OgPbe7fZe9(eHqBCP=;$ zs@GL=cmC|C34cS>)18J#Z9rxAS zw$&nWF{#&UtZW@>DHL-;FeWgs)Zc<1jF`(i7_)8UkhrSQ6KPYj&rMS6Z*{{QP+kn3 z?uz^&UW)uWOmL&59#2QTyjv!PiE2CoT|JRVOZondf1qE;RptH+4TXPXt4&?-fb!m& z(oxI1E4-~6;q~aur7}08+f2{leU{10Hoj30n2>6}NCBIKOb9MMOKQ3kjgTU6vv1JL#(%- z172;E|4{r|>#)e@4Sctm`D}oz6-GKR2PlrIRZ;H|=KUq8@zTPDPw22g!&9Ws`jr3w zb^)k1u8ncifIv?!gobSOsenyx?3NsKaj;qu3w7Mo)2?nrG;@5S{+%AApM1J0F+4E> zb0#{Zzw3gSo7XlEV?l{jOvs@XWPsTkocWn|FQ#&PXO7?Iz;W9f&E30WYl^vclm7@LorL^ijG-*DjSrI(Qvnklsy z8JZ==jY}d_UNuZPuT{V=BX0YthZ(BOciPS7wfT;h1N9&Fd}yD&h<0zJkpHI2`_)q~ z&EZ?c0k)ZQbsCM{YQvk&jCJkjvpgLi{$PCC^NGsS^lg6Foyc)u+?*g$tjJB2B>s!9 zPZLHdR?;PyM|QEMGYUp7hNgdwVZT)e0RU zJ`9Y`e}kkD)vu}ox2!q!gA&S94?R=>bKb*3AueA2ua5H59)I?HDKN11ifsTZvrY*8n z)7CxT?`Dj>7fLw2mzCYsda3Eu=%n$Ang^~dR7yAX>~j-`02kkeCZn?dmo7t8@=)-@ zl(^dZ^+yUd=Ht!o-h1%|KSq{+ya2fQ8K{IY3v5&TjzOK|tv#@kcI~V`np@lc(2kto z3wuSVtkR_-X_Zxvg#J{WY17b z2z^35eptm)uab(>B#B6g6PrC;P4Q@byLe+M$di@m!>mv|tjw=cn09CpKFfD-rbgk= zz}nc}b@Ws+^tw^D&HrHZa>}F7K~z|4Ygo?+enU)^G>4_SRsQ#Fg|P!6AAYrI9DS86 zZ52?O62o~EvVF<_Z324)-57V|#0>R{ntuD6Ni~idp!4&u=H^@_34kA_-{?=yY6^?& zFr(1+q$-z(y*WR@Sk$t^AEDZY>`lwCd|EEFTf7du`{q8z=4O8(k`&}Rn_g<+Cu3** z{UWTAkc#wKU{MEL^s zw%}}M|HnpG90>gscOA&1MhBPaV}LRo{fuR8;o1JONiFt~c173JZwPpsuJEa7n>t%j zYuRA%jCQp*0Wy-R?6q<~ywdU7WO)0gNvK7%#iJ6oV0{}JRa57Sgzfs~R5I)PYH^pn zpJkn+Acq;Q+G2;*Y=EB0nvL_p3`I%b(V%xw4CL|ZU&TnvA!bKa?$+qTV#O}p!rrtfCY0gZX(Z~ z_;EZ)5({5>N2JiA4N@}>PTe>uOpBOgeutyLn|-WdnS=3!an#cB)z7NXCd(XpoI`Uy zIQGlcmtdv|ESW)ei>|&n&~qQfP)WXz(lQb6U7vt~lI-Z(hOUaj9|}3xl`~_a!Y30^ zOU=D2Y@Xsz6GQ~yyvUz(BM_U^z6?`K3}NGPs~QxKb~P+Yl>600Sp8%Jjr4w&_mcA7 zFe`Jc+Q2+g#OpfIX$FNl!0Zy)HS3*Pk7mT zMJt!@7xJk~H77wqb%jt{%8QS=`UroWFke`SMrBO=Lu~tVAnXNJP!?$$3rV=n?~QzA ze+jn{8PiT^TaU0jj_Y#w?*=0YK${BB_pAlkISsE0?3b^U6I;didaog%Tv79NT)9Ubu!x=_% z?|aEju02@B9bZK$#PMfNQO`Vc2!`j?!jKguGiFVzXJBP>3B0?KlD9T`!6#%v6qk#U zxkUQ2jI|biypvwu1*s_I&Be$~#YiC}wD<~&#+-e|g_0Jr)%i{fsSiy^(z@iVon zVrs%~litr9SrBX<8B+W`EUqSR!qCEu@lIDbVzZ^3cRZ~!?#H{$1x0Xx$kC^#yThOM zZi(+|PkH|hm%*pHeql7vFxc)Zp&d4h!Q@rJ>SN=4C+48?sBr0MlCO02qBuXv2A)L> zU%B1Y@r^&fF;@od%jgsi8yj zcTm1z;vLrQP*6}JN&cq$48m!abG{Wtdi`SHYP4y%k8v;Q)H{RJ=d!v*2}g6Iq$Z$!Ls*zzXN~`3-PPFMQm(YeR!4e&!qX2<>{RDpOjhg7VlOjJ z_-w~qp6#fP%L?l;oM{ge!{6U0DC}8s!6e?LD$EWH{mIhGOge!Fuq`m3N{lmwoO-y6 z&Ti=*Wfrd-coaDNo?kKgjYGY&Pbt}16Um}%#7-nDCiN<|b?^px#`EO6^D`dRic01QJdm)-_$FN-IWuN!MdEHL(liCR4~vxO}| zMl4hpHR2*V@en0wpdfOMo-=cCr`DHFO(sBH_)}N9> zyT4G#h2?~!5BsRwec@`pdT%nU^mwh^u|8Q*Nz1K1q+G)I`@WRCqy6rzvhG8`c{Mk- z?X$ujf82El_8gI{=7`%Q-1dupc zbnF?|laoktZj?v)xt1jqq5T5ZrKLCwh?`2TZvoti+%bJnFd-_6$(O0sYUV-%wBmP` z;tuAK?)$8`CnH@btu|qnYne-F@6OwpsnS~n!-v6&0Hhbk=3TUWRtcH7*{m{;w*MsK z47TuOtHAm*+-IYOh(PYrC6OfHuz6`Hcc#v%LYfk0@zsa&O-h3AJoQv+F5U!du1=N? zpFM^E056IS2i4u4$!%=VO2!S>^+9@u{3%|Bo0{~cW3Z9`0g6~-=BZ7})2lyxKG}`C zzN7VZ##>exZN=p%~B663~xOx0ZgB*A6;8T5KT(d?(T6zl4?D>E#RMOs zNYTI%?C8^cp4W z0*fVtmv+QxO?0iLbZh068ah9{1<;j3+M3;K{}67_irBkO70D{mrfKDZCT!u%K9s@o zVaPTXIa={F)s(fBQjFe{JZ2529Bjty=_TqozO}Y^LbT%NcGz|ep*@OSr7H&OYhtR+ zV_pT{K25&hW)}1A(S{?`teTOBX|du3uDI0~gQi2pBVJAE#u04~-s)q%t--#ju+eCq z)Q%IPI($i!bih{Hs2wO)p!k|ASBSVzJ@b8 zRo#=VQ`4kt(%0SM`8Cq-7^H2%d$e4rk$K8L4&-GQqH;tolN%LCGcANsDk3G%dX2sh z@+$C{4yexnaI^7l6^8~pro$NTXh-=Hmm1Ze*bFN}-*N8mbgBM|T_ru+7w=M<46VA0 zw-sU0TM)e!U+xcJ&aiCyhBOO@w`5W=A)yGHe)9UM%a~1=HdFrm#JU4Z$w_Yites+5 z^LJIc<#F41y3fPJ?nq_#bzU};4WMAj|HYNVMmQWr_blMa?wsX!*4(*1^OxVt)Yb5P zY`b8nFZ^i#0CDx=)`YA=BvDI9;d%v7b;-}^5{%lg**CdIWagX3>b+-&m;o?c%zRr} zHz&BHo#g^6#0$6p`qq)BO}0>Go(}e&C1R2f>pZ13#r#pik*W23 zeSF|ZVI31T9O@X=gFjr{-Lk)dArFt~9Z*9jvzC4v*!VMp+ z(QT{uhaIQJe-(}8mqiBm1_h=N!x&>CSqjqE3+Qt1q9s{quNJ#|RCV9~GUy(8_fuf< zj_6r!?7p$!+T9$hnKSd)@PNL4I}WeJnV}xTumpjtm4>s{q-#}_(T2i#QJewytzhd$ zM)jM`Da&&d7i1&V#{v#=uR-bTB_Jt>wFSmQlZj4GsAbB*&zcVjLX6>rr@v95=sdS( z@P{r`k~=(nQmxCY3kZFZ(Z4_=BP9XP7UIyj>pDUKdbW;o9u39zRMS{$1w?Nxo3tM|4!d&N8|y#Ew^B! zgv(=%?ugGz`kE!{$ZZkF0BZM#gF981zuTf>aSgQz_aI6?+aD4)8{DfNqn|lWY9rtEkuf zeOEbUoBNiYja(`cmE91|_30OeA6QYPP-x??EkAF>cj}RgIao6e3%#&&UL{lXMqe)= zH3oQx9RVHR#9+Z`*Q@8~`GgJhrt{gEl3XGUMs;z;IXCva50||YB#`!cy3=A{X9*TH z``sG4bSu=ectg!5J$Oy`?^+|%jh?87q%Mgdy*Z9=I1cQOCPTW>>ce-iM(GP(jeYM0 zRhDu@L92g7f>E&Fe$RTX3a*D}#_#!*k&W03KUIEC7T+UpgyJku336I5iJZH1)jD=jb2JP@S|$JUkT0e>H!8;yxFR@pUv#HiRBQdz^&^ zmqhMR_xj{Kbt7uENIVkHmvgNu^5G_t@wtV`vaqAvM~KWSKjYj-E-p9t@bUe#0V}{e zlw_g`?vbA|gql*;14g`ongV?rCymh=xPL9wc6i!LvU;oL7?N^p4&pYn6HORJ9*+ra zYPAX6$h*U0Kt`q;D!R%{{n%a?n}+;nkj9fIlkrM06^4q-XYtIWp+LJpaS{ZTB?>4% zlmSK^bS)NnjATDTh?G2@09SD<=|gpdiC^Ss<5R~$G2y1TB0y5oJo;!s3lu~g1^U?J zc1+;v8?UquHy%_G{O9rvoRFV=ra$`rY|_6TAdy6x7%>$QUeIRV`HVsp`SdTG>E9Q* zCg8TcO)k6p)2>ah&D-;^hr--?gva0 z34GtS6BsmmO_*NI#r&MSbPlrZ>E)_PLMF1uI$Xy7D7D-G-RFzH%63d+u0j4$MN`kR zcERK1JIJ8Y9)c-pf2_JHM$C;&U;;&#cG6T;3oG|!5u$Tv8O|&H)d&&V1ml4VI+Tsl zD1DhQ*=6c->6kDt0#Cp+2H4OTTSkIsw~cL6g=-LV%XAPA2M+}wO|Fj!Ce!osfRXsQ zdmSz`8KoHNXDJTfrU?1uPEEWoBYqH*8wZ9!yEo$;K=gE!f5UTNp_ zQ*RShtT1Ca(ITmUZ~oM9Q7yf)gX~lkJ!UGK-?3UW+igP?j8nMVDz?dRH?u0N2Q07Zhp6zzZ2PogbC+SF zN5w*~W1yn$+I|`i@?`P?IZ5;vhV=37Ys-fbm~*N7lYMEYp}L?Z2KtZ?jI}TKl(q-a|2ysO$P}F4Lfj)rD-0@ePKDVytK9D|WZjvi-oQV6fg&M0g;`hVi z=zi+A`)23jC1jHGr?@y(iq!v0G4!#u*5GKaYO2F?{k&1>`l+-vm=csUv;3?L-m0Y!apTL!FmRo8%!)CppOtqWgxgT`R&Z!R=-jg5i&Ob3B zBAIBBs1id!Og-KVY7H&YZK)TA%k_YuQ(NP?T=T zSZwEHeKMGk576RX-*Nc5U+tyMtCLh=s;F5$X@0EMPN>1}JQDe74tj=A!!7DO9ayKT zXlotwS~8IKzU3NK>{{REE0(v(&sxJ+*Bh!+%xreelyr6cQQAi=eJ11vG?k0Xw;H<>287zm?M9JJ`(#3r zBJ9}A2ci>-Ko&?S0l$2sfC>&GB)@iGEAmFtmDgGNx(U@xe=Ih z+{5TQq#k4mDoNHg`zDK~>7iS5a8c`rddmDFD#jTp8?#e5?hj@AAeCE1o#(Jsr6b(W7|;#-)IJZDe4R=H9>*Stb1o?PFzLFvFCZ(EOs94VluIun0E zon}xTz9(pyYo~H!!}Po8cp;M#=XgQ`^`6iWR)i6P557-?BEbgjr1H8SanuCGvFzEn z*K3Nf^N67^FcR2tAP~1Ml<@&%o%bIOhq9jf93vGMO+34-Oq_?2oX2MQ=PtMx`+Lmz zz;(t|w6dEIgY7KeZD$O`zWZTxSS4Q^>!#X!yU3M(pz9F64WvE!E~ccVYp3O!tN73D zqCa_mxie5>_Hr_2p%Teyw9_ck*tcF>@UyKbsm{t-iwH3&tnYE-A9$kQ!xU&hZa@yB z_EI7+cg%(B<&c0;Nc`%~1fK0f*ggEHdG@#OL}l*(y8huY&i*!dspw-h!+W$B=3O;T znguMPdDWrdj2JwB_mx$YlH~qU<%3c6t*`&#CivBfG1m1foxden-TzCny9^jmFh2Y1 zGukZmHWuJwlq%0NC&owVEKyAN57+ka6XQsJHiSG#{At4OQd zzWkshSfc1o=G3F(=%a*NCS2B##_$b-F+1w^_Bk)t^fdPVni3g+QD2DaRYBAVQ>AVJ zrz`cK^Nn`B6`9VU8|Qk{_QcwT&(1ZP1Y*;7k4G}|e+FKj8sX)#?tk^EUcOy~{n1m) z<*^8v=I&G<+heSngtrHmfA{Xs%6!;uD{meIhNA{5Tc(=zZo?MfoH7EH+<>J(%t>nkt> zHL#G}kJOGz3=8XMl5|Fb&XM8h6{LoXeU8PWPLFUqYUZPzoTzSKqG&Iep0)$eByA_F zCH9gzq$?a>VKI6HYnM728TcDMA0>1xY!q%J_%N@FOX`DdI1*Vox@)5(PM!31`pf6h zrGiAmXcPdJMq7|lE!dEt7-Ms;imRALgSQE5k+WhIeSU5!2~=fmWKvov9^_-y(}xom z7BWu#uE}$6Sm2?|5rg(|7Y(cD)bj4#?X<_{$1J#n*Gz}R`bdKl<9*cy$dbg)^FsDQ zheeRhi#3ygQcG7MmVrT&t=AK;iYe7}Y4W948Z3fiD__i8>@aX}aF&V+Cj>9+Jwj{w z`1mea;bFJLN?|&Y>dNA5J?abIp7eD(7VY6utBpFxZT4&kONCaQdH9fy9;r|^vxdW0 z)i&{pk6a*rozrBpSB*&D^RL<@Uk>H)GfW|da6*P?B=6M8LZqx}0wK0jfzp+)LS$b7 z<`gs;QY%n(l6ADwJVf{jVUt9pb~0#^r;vK)=4Eo3xslAwMavWTKWs4tZ?p2o=In}J z4nK>w0F)HZEoAWMk|nGTS7X{rnZl+aodk#?Qar{+Q&(d>4V_PiPaKUd*-l=3S_=nM zK7EcUr9yGQ1BgM5;%~fs`0EKKy?*P~Wobt6}U9M3u4~^P)|> z3YuNK7>f|V{a7qbhK%??!i4rP4OV`LQXf0jF zPF`-$CEG!D!}FVcrQnkR{!bymi1!(X;yr;+LZQh7UV=hgkz9Dxrz}tsafQMJ=bO?z zjJ0u6J65XS#bMDECUpHs_G12~W3sv4qE?lD6IW=ctCX(Z7#DDJhK3XHN_}_5efdbL zGyh7u)No&*o3Ny?`pXIb#o0=4#t|Gczw+kq-_?Eot)6PbyHi=&m%?&5iN`FshCd6g zc$1=d@m5$Xno1)E0a1gn{kv1zC!o`1`Rwj~-41*oM)6FALN(8{ ze6X_~cE+*l{6E)O_65yub^FL%E~bY0o-ovEFaqz~tdHi3LheRr6~FLmcGLw4w>Ttk z71u`n#wpd7clqm)?WDqg-nOdzFabdgS)u*WLMIPN@NDfg%A5>}?ETZ$MfXLMk3x!x zv~oQ;2c>av7?2@}ThVN;X@+jBzhbg_>;BL1+W?antiP?BRB;%rbHz;#OLCvFB5o3cWcA>AL`cSoOB<+i<>?98% zRauu`?@!(4+rko5_Ur%DR!_!LSgxpuT47$=E(k2+ch7cxM&AFYhykTkhAEO>F0I|1RI(y5?K$0x zYWhTWzjQY(_V!wHR2E{{649#v{ffXu8uNip3#c;uM6W^K#DV(C8;MF2B1jV3-f8^u zHmqX;+2kqj*N13xW$>6uF`k^uyxj2G$$sLuV2nt-s8R7u(@fAQoUIE}-tRIBM8Er1 zyJA~B78Oex#m@7)Y0xA9N0e6aBq-)#`IR**)NqJL4={q}p8;}dh&|80Vxu)#@l zjyD&TkEU7<8lNeK{X>Z2pC=r`p96hPcF&2|Hkw!_mdcQAws)xtALHPpep56ah1kR? z#W1#aOZ@v*TUss|A~%T2SwD>D$Of&)?ziDwILEw}*>5-hadE?cwg86A5mEblMEe_` zXcUw8ZP|Q(U~AG(I@dFt(^peLfhWh`;6~W;iT`Ay@s@j8ZdJXXs5~UTa7^>U_w8*W zWcEL|kase~Wv0t;pCl#_S!z&(0FPzAjE%a)QvCC8(r8{r={_6sfp-mG2iym&mY<-F zh!noYi+dzsh{n&+p8vEQ_?A9q{PP6t2eebI78qv?PvhgRaRi{>`SR>p zIV>@>O-wFcrIGezoiaC|Sk`7?MM_6s&`Dn;$EQ+#H`5^$==sNHBzqTkgR%o~=rhhL z221jtf`C>97k{^ zMd@`|A9g_Fs6>C$*$lYmAL$~@pM(=_N;>79kFKwj;Ec&>`9Lkuv{tR{A?9P7a!)ME zN1vHRrcX+3_?6V$4qpRwIF+awQgs@ex_aNFiKOSH=kn39KTuAQ4E@^oBZg=&S%0|v zq74s-W6-^EAsOUvz!?fd*68C1w%UBVrB>zhRPmD7EKNJ|GW&GpXi6nRbHC&+w-DkV z2;)A=I|OsVl&fEOCGDdf8q-y(_kOZ{kPe+f42XbZm2BJo@+#&dr{CIc<&&l2L{ftI z2Ld;*rHaL)x~fy?fNJIeJW1DtS=<99bXdOUUixypMoAOw>e$l3H6$;74c5XL*3`w~*R}J2Gx?X?BP=Nzng$RR%qaN$I zgAXo;((=B+P-oY8kB3@mK_%q#m|;#$R*I?MC(Se7VQG=kXFZIrc6h92C?Ii_awIw_ zuoLERPFsI>8L;UAf2u;oHWVkJV{ZUh$nf&pvUn8KwXer+Qcr1W7t$A%!4yEj1e)dW}aAo?AOl>Xnj!w!8``0Ko+F?z(@Ksw5#DNUa zXYP$)0dTz3QcA0N5Bcs6^>6OI~F?89uBp_Ov>~k*r7ZJKl z%UFkOw)}L&H*zKNI*PQmv}Ju?9X*Z9O3JL@j<^VNB?2YBAn#(SuZwzI3%PLJH#2=P z>pDIfg%B&*hG2phz(p*}mPTtU+s}>_ptt@LKRQ35b`?Ddx9_U8IqDnn|3zHAZFQ#Y zC(auUl3*(VexgY+>FmTmxGPsKlpal9o3Arxe`yr>SmMkgwaXHElvihciE(O+>97$K z{u-#`p@>ubA6t=7P2)a^B#kaqAc-5v%(K~s#hDE98Y8*FQgsK^znJoU3(V+TrORdzVIEvS8GlJvSeo z=~w0m9#Ea%l53UnES^yL1)OlAoEW3irD2fPMsQ%YEJ>!dF7)Ks5so3F$2PY-JLKN9 z+pmH-zJ4;%#%}3%0jqmrR>w*o#Vn993EVT|P64g=3dlzRZTKN>gYmDEpK=y*gYL0Y za;7ndY@$cRygsEZz)C%8Viq|sR+qg)%=bg*uF}M|JAW!Z{F#(gVj?8hU~#T-y_hfP zcsU8y&o#zh`zYqD+D%tF`+V?~Mrb?Td=Wm1^vDKnW8g0Jo0@-~&)id@Kh z(ZvD@Q}Io__OQVV^OPC*mHkte^HW9IFX*z^il-0yS3BwaEc#|CKW?a}3`>QCa5|0f z*pd4PWQQfPsH>DsI;e3aLXz2$xdDiL^J#cPZ->JSy|@!A*1hnF3m5Trqa{NsldT!~ zt)0aaJ(v^@lQeb}!Gd{nN1;ZO;YVe##9%YQCFs)4H-TJ4->XPTFOK3Ku(p(?{Zh_O;sr~- z5d-E*_y}FOA1!dZ6!SXMmNBBKg0cUG#{QN*Gt2pwO5aUOy5$IJ5>tAq^5__@d{!1n ztCO*JxecJd)%rBs^3VQV@KyvSnae*=XNS+{r@KwC>l3m+=q zsQP#aFYp-{&8!Fvkb?8UmRc-f%VZ(S?a=^ItKNr{*0IjY+nZ9T@GC#IF0l!y6iZvWrDB~wIOB*m zVZW*t+v;$4PtKf-`|!ab0K-F@FaSayV<+pbkcLJa!2qRGTpYHA$&N-qWI3^}?4wf<}={I~P60B_QL3%D8YSO{Hs^a0_dcahpJQri}-UUAX@n6jJ#$azxbu3Pb4+-l;fgzV7}X6`GKXn zU2Ux;c_DsUAWX|u(!h`K6NxzzfG|pKrDD@g*dwsZ+)AUC@ zfzpo3%Dwvw^a1sTl_l)-qr}ZsX14bIyNjlgn6-Tj$4&P`MV58GB~96;4URT(P`B?S6eMfA|U7QPRUPYZW1z^9xqPwiZddwbiVwxB>tJWvHWq^RGLYkCW z#2n&poKN3nG)E}(%efkf<+0xkA9_&i%>sYKih#`1!~xfeW4chjDN8E2i;TvOkRwKWb#@*r{}yJ^6ui`&LSRnTb?0C(7|z`0fIdg;LPogBp>aaTMdx zXn50a@tjJAw3u%Jk6(AIyhB#W{w}t%^T0EONw$f;wEmv9oGgtPThMzuSGlW;zhCZI zH6-0HmpIOZ#>1lN!31Q?7r%U`n?5UV>Ub`Ej}t3dt?5 zBu_Bs!Zx_MHeDBVPaV0kwnQ+0PIu!g{h&>Y|121WO%Gw0OYShi0_Bs)4H5Ik+82S$ zheec6U9PGVN3+BZD%zw8VBP^}OUp6d^|R)x)y0@cqmI0t3`+Q7ZksHB);LX$cFhBY z^S#`;B;NrqNr&4@1Y@6H;ULM#o(+xd?6a~T{G^OD z5As(>Z?+viy;SaVqsHbY@@^h1HRF1)v_fw&xpljla8D*2RY z>G0*Xp8)*B9opmDNM1tqIg6~%qjTHu`cU`=!s*CG-t2aHes`TdE0N{vchyR01Td$E zHD(a1yzqRB_fk5!+jrb?O69t8C?RnjfJzV8=XysC9B+PD+-zvZXB{8XWj3A z=0#QfD#O#>y~<_Y|8n*?H}P+YUK=yf-;A^F`#5JFoXXW>*7~4`NAM`1DaK3I&N>M> zT`zDusg!D@_y-p7VMaL+S-d7n%VUghGL3T5$UCGk<4&HekXGNI zlk&YZHa5{*qfImt;DrI;Wvc*9h>r%0=)oYPF2;(AMMqqnxI_c142BcUQ1~>hdf84$ z3fq7sXMm1HfybRE>u?5B-u!;3gDGDmaDP-5PfK(jByF=6Rd^La#hAk<8J3sMH7U&q z8*TE_=2adWK-$KUObl4P_h<##NSrIQ97@;!iVp-I2GAE{;qY8GZCiIo#WYv5&_o$` zfn?35OF4kG`SNgqQDUEkERavl)y5Jp_gnDUH)xXD9RxU(peQrsMbe=TQC)rG= zl)JhD+b6qZ$h@eZxs~NZiMf!dYjq^n3dHiBagE>1lZ+C`^&Ldt`xfHw;33hR^xNXwY~1fQ)O zhCL6iWP20ScjXsZ=$tkuRN;E@8tdrI>YnqhgPr1$RF{qI)8;YJiI?^u6PcYn*05&0e5Hk zr1#k1&cqF>s^D=J4WF16tH4`!k#0s;LW5Kc2~ACh_M<^P_sLa~;rn8=z+h}H%1^&4 zoDh@F`501~btDpj$8&Q_r`8XZrgp-*h1!P8N?TzA@|dD(fs&^8eV!ud8Tm%e~zFqyTw1dO)tjsauGCEwol z1ph%Mc%+)#-Y_jj4dhl^rXj&Ri*@TRs>~vQ4jG@L&q-RA_nA#8O*m zgecK|27g07lh3NI?~`wjP8Uv+S|`%A!Z%Bw={<^VMpDg&@c0dY!`-f}o|xpEn8O^j z|Ip2&Z6j}13d?Gz26(LQN=AfmnE#R z48N-(iT$a-6l1$+Qzs+YP(mYpi=z8|x`o?FhE*ZK2SJ@q*GFBgOl#L#@#{Rn!N|?} zFu+iC;xC(y#CItH%-GP6eL6Y7{MYTy>Y_@{2GB1okBh|aNnUpa+BcL~R^d}XI$?r_ z2M^@A@nhA9IZckI9zi=O4Q-<2h3pw{yjU(WUO+_&nx4?jnL1X&*m8qg&nB^QKt*X+ zm)$&<@FsO^nrVf7LR#gz$zHpaFqr;Pq5GLgG_DY+U;k^=v7x;p73^qN_?i^mi#F)v z;e)%8QU)k_ekti#$QTAX`(`cVnX-F?V`!GpzMK@{(Vb+1b4=&?TDJ6E8r@e))VNtu zI#DN#k2p~swa|?mR6Ls+PhM8JRrVkdqUzsicg4LGvE|o z@+=WvJ4$|{d;ue|`rz9C`(Q(xy*7n9o}jW%gGszO(~nCzvVAuzwP&pJy$;ao*Jo%l z_~FvNPwsxK%nd@Y`ly$@faj+0*La98Y2wdHEDh4lTS3WB%Q>(7Y(mOCUV}O<+)6A@ z+{D*Md%wzT^~%%!JUN&hY@F4Mj zxpIGee5&TC5&d>dxj-U3L5m2tA0zH-Y&NzKG5AW79QRmI57HurKmTw!3+KMMwfo;H z?B`O}jIU4*6EppeQK~0ic!fALuV(J#Sqw==ordj`jOr7!7;zm;i&BY6YB&foZh&;1 zQsRi;`g|q&bXv_{pjLT1qlHWT*_Qx_v%p4Haa+qGj^y1PSLq_unKVFL4DnbSM&P(-)6yEDV1%6P20$7Sb{$+F&)T-GtO zd_t(b>{9%ptFFAhlUDc(;Mq77Hsl1WT;1Z26QI|EPJTC;toOM-TmiVuF2Sh#5|U9V z(dDLbt=qvuH!j^+D1@GQG4$F(EWS834D)$IvO@_z*k)5S7i*oDA?tZZyH`29c6Nnt zUDrRXVuVSMcp%b@t?>irtf=R`l1|^%iWwc6k1|J*?RDc{Ne-zBh)0r=gQ0v_8#LAp zp=kIG$XVDQi3#7_P6e!uAZbb#4?eez!ZvrDGZD;of|tnd)^mHG0z%^W#8`1*Wo91pS>l67df<+{J;;;7h@~@hazNjM9OXdeMuKo)y&^n z3WHa09_z4cVi(1`_gk=`!q8DnJZ-^M=q}nI-i+7FE&OFjei|QLVsvVF{m!zk4H_j| zOcPB5F)Uqz;DSjNBvPUjGNTO@7#QQnsrn}wr0w(9KlW_IjP-HMFw@FX9G zBW@DEa^@H!8qRz4yx50?k=Jq|D=Yuc3!u1H{XRw=ol$5+t&-F>)*w0&&-=6`HeeS| z!#BtaC#6&OP`eo%?}mf-=i-ZK%3EHRqP&(E49U#5k-%L3MgHl$!?jNR{jp6siN6lJ z-}^0sJ`4r(Jxg4sb4PE0?~<-C{EJk5)@-?Mum;KQ{eSQaJkvs6(o^`p$dt|_cDfJT z&lE-f%crhfxpJ}!uqMzheQUoq~Ev(R{9 zq!N!Ymh?=0q};jgo@&=(8E06DW1Dc#a#^ih!-;Ywqn&n2uM$f!>HrABhFcT^EDM4? zh{rZ;Tw4%iM>P`SnZ5EI9N9D5dY;kr;#wWnM@a#u<(Iq_ozHdfjB;QY#WGZ z3N=~2#82JPtzJzK!%w3K6RhcS?JPUY*O;Lp2w3HN;I0OxuXgABwbMzb-nIxnkigiN zG6l$VY=fVM0(L2X=BzX^tEQ2FU-|t)b8^SA7+&*nqv+0PApaaup~ofvE;ZmA4S+-E z2knAZq*5d;7L5jkcKXUmEmms&V-dxGhg%7^%Bw8+ovd^EKvepbYHY$Wf=}T}SAO zEDSKme&mEK6K1J?3V$6OsWcm)U#w&=c>+%o2nk>_~m#U%fDFRWnhG zZBGyaytk_pGG_EL$cnAM9WIQ1ewB^BnidKOMt;yZlivdd!W;L+mpELz@oNg%*4Y!@ zEede=cs?sgimWL9IH!mmCnNlB;F>1)q-9VRjt^L1!|_SPe=yJbL0}&Q28zSTr@U?W z`HLyXIU3>vE^3=*jEvo(Eu+RfAo8Xy$YInW>U4yUdM{*Sr`%eYwdLY$^bg)KzNhFM zSoCbSiJ0a+)?djwC9OL}yW{PCLK5Uq;o?=WojK_klwTAF>|MeDS>yU@Eb;0>L=As*>rV#dQI1NX6Ao#ba02Z8}7FL!K(j;;$cJA!wA|;G|usidiVYxWcj)4?a@mT;IaSL`X%D0 z(A}wb%Dm&xVxp0HqfJ(LqVQ#R{vK5@Y;(B-RNeWOJ)v8$6RC6O&R$Ap_R7T}L~!=H ztY7viR_*U){p!Z{hwV8CBvXT>_J5Z(F%iI{><^vCx> zB(|wk?-+hg)bE~}ApWVA|CbCG&ko`Yszt1W60GfRaR`6jSe;N3?neh+8aJ0I0dTZ$i5Fot(O-|eZro|o7bk0vWg?0JG4Cjc!Il@ckm%4U*rx5xb8Kj3B_^7Jb+ zivHRiDXBOwx4v3P4iU3iTcYn3>m}PBTqVqf)yT?ln2%7TlrjiXX-ca)ws~Hs;E>~{ z&U{k5`pu;+s3Tl)Y=a7-n#bk?0}rh!fO5k&fetthvuslWiJ+A?^zD*klPZdu%<0oV zCU7MD(giHzVSa>-?HrsKh~2>`B{#*5S{hgLtc=~|EG7Q3g*}F{ZJVI-agl^i6(K>~ z3mRDiW7pN_I^xtRxuM>YyK?)NpX7Qytq>pd#*YsGS`N+S5P@VEcc-wZQZbH$FA}w= zAwF`lvaCB!K&$8cCoMu=d+$>SWbBxBfuHCiW3dXKvkwh+PWkgtP3isFzzyd~O@L)u z0@k6ZRxws#vrZGC71=5&zL;u~Amx!=TXpI2XqUC|Wga=6N(d|P)==_6eDs-dQg^#s zuZSCita6{wW&d;kD+||shVaX>n02Ck@T@4xdeFeHWt(kR#c<431bM)Kp89&2IP2lS zgFE+pRWIh1^X{@da~O>iA}-xeqL3Nz1yjA`z9W0(LZ;!50*!!8oahsjoWI(3pJpZN zz10J*q>h|&9rMYl6Ug=hssjlL?!oQ0a_xw6?ZdKSW|h|3AT5mmyti2~xtID}35~at zI^N}ZK_6%H{P+}P9(;SBtfPN6+?0o8cn|p*B~+zSvy0}l zi~DMAhu*}!$G(c1#qMM=^3>Z-zZO*Q-ew#VGdcW*caCXR!IWbluSfo&9j}nGfSP~Z z0!=dQBNOeU{X83hcG>Z4QJ|gHs7W+t62%U|#Efzs5>*@vR#i!f$&%ZG_JaMz#5LOR zV^pV+`{bE(kT6y}-AMd&P*Oq%`)>Nt&vG5JBp+DtT18HK913|3sA$#nq_wB6DF@MV zgMvw0_!>Hm)jf*�#fqSLnpsvPdCO-S>V~-xOLED0vbpFjk+UAaal!6Zyyv5zfQe z8<%UuK;QZSeUEp`wMYcqi(j{u3A5SW@*vrR6Ukvw9A(yKCbk<<6XA-sTit*cd;teY zz9WMl1Phl{`v#*zOh-diJ!MAQ9I({wuI&~$|G@WLFI&6oFnzUnE<5v7_jg%hxpihq zYE!OL>sWot7j~?zS|ze!k+#@Ax%hopsI!Rf#GNtWhiL-83Y~{`+R5s7g|wtltx4lZ zea0%n70i|owZ4_2n--5bV8shEDxyY@O!{W zIs-12r0po>TTLo`xn;hn7T=X+-FY#mua zp-7*lfcoFba^xz%^LsQ@Dea2eak+sNM`e z2QDql_8(YY2Z!u*hrW@IJh*dc*9@pgSfk2vVf@B;jVY)_B*&QtWTfr4a@`?;`6G*Y z1)LH>u_FSfr0eh$$4dR@3^3%>`E-+hxnXEg9B!tlfE!;~jSP}kX!-_?iwA!8a@C$v zJPH67iv$PIunWUdLbm5WN_umQukH&q`Zw@SioMJgot*tPu^tF&066u81N|5Gcd;L6+PL;trRi|WxMJM3FL z=Tmr^#hVkg>>b%ha~Ty;@BTW9MnhK={dZ8}{v;lLh@ar{`nT=xMxaF9Mr> zarg}YXvD(^vuh5F&mgI%?{3Se+GI7>uzjPt-IEq`0&x#iS4{Hp-FR~REE&S%^eZ+*u)1oX1gybmnJ|?mY=EC!BVh&mSYAG3#%mRwsAK1o4p_Rl$ zy>Ax99Jp2AUlG5bnwjeWQnK#Sifnh9o$Ik{h#l8VhYycFvMAJ+E=iuN8nYj(muf69 zFFK_7OH%U}U>E2Rv!brQwZyzeI`Zf7`9*_3OABSPYh_bJaTZ?^{XrXDgSX$Dh_&Bt z0wIKUf!T-Dvzn6`711%q-Uv8^Dl5}u=M{B&RFt|IP-Z%2y!M+m`Yk8fDBr7jX=+Wv z2fjnyPgM``3B~$Dn|cxQqSdz z3Lp$*06_2hhh)hab)cEn0`u)CSxJd~>wN3`pYcgHYXOYmwPN9;+-m`ATf7H zn~uHy@;0pV<4TFjU~u~WCx%2!+fQCY*kv9W0m@wHx)K$~Qv{VuS^!B^0NH~(=8nL4 zY1Yto13wL|wk=Q!yYP}fM4J++z1($p zxhMJaFS1cP z7}l7rmJ$B00uhXrw%=V_glv~(bb$F#y=NC=|n6 zjWD4f)&CsDRVs{){-Pw1j*uG%^X|akZer0SF3Y1+tie}lC>TK^N??h87vwbp*{j%c z0)W(IO^+hIqHD-tr2A7aeg|&*;lq4YsZ3%(E5}m(8(b2z{O%hu%n8cBGX}!QkGZoF zzk7--%qf#DLzt`%iJqeG6GwNxbDZ@aatnL+N((SDGQ!juZnMd511EThJ8zSGTi&cv?ez^`0Ul@OV zO9btnX_tT^%R6Ax$Ei~duW_#NqExrYrfAb4Lwetkw>f)T4uVN#eOzBU{<7^0R}?K+ z#Vw>ZVALEbY}v|(@Q}s!8>a9)&uyi9&GV|JM50eF&n`;yx(J>rBadnIqTg)Vhs2O6<&Y+4x^;_u+MbJ5`DdNsmR^!6J#rh^2zyuE$qDNwx`>Y++V*F z8;3sJC6}q0fS@v4clLc8nD6JEZMSaaFLtU^XPJ7Jc14Q18pB`r0Hr_gS@swHJ>;MB z{r{pFfdzOpqjShVT07fSz(I+!g!%{bS%2TG+p<5DLp@|h6zB?19k%&-)4PUuF~O_& zc6PzY?nSdB|B&HhTdxUTUU1iD_%`@ zU|*UJ-DCw&Dz*-361{wW6C##5PHW}9R&ANvq`__$d4c4y9o8Ni2xlX9wiqwuz-;}y zr4QRVkk%xtmy9`X(z|?O9(5|-!PcP>=jg-NXyqh(SrJxVL%JUB&>s`?&nIe!U7d8t zlxb91Bnrau>QsW`TF5d&FdK5b?6NieLuyeTGV=)ISH#HI{4dD-tyLfU>;1eSEB3t09pms`8DXIscDAbY%f=Od-`RAg(GHTrw`OxbuXS+}mXYyn) zvDkh_Rq|4w5q$0CJqM7+05LI!Y2F0< zHd-EYe7*7-0*!&=!mp!TDdmzCSj@0)d+d_qfR(7O4I$O_*O1!$yDX8P`GvcbO2LKw zaP+~Okp1iTz6nWeTOXhnzZSm_z!|xmb#jD?;GnKXg^WuVHydDn>87XrnGdv<6#YN5 zfQbx0BkU{8_;3Z^j&hmGMQ;(rgV~_BGTn>{$_D!ZYJ0y=*AoO7^&G}e`*H`?wj%9_ zl(I)-L`O@z&WBw;8mAxuMiN5BM7uh`dwQ~k1z!GM@Zd{er18Mpoc9WoTq8kclr0WB zY<;xn9xV$&b2%W56$_cC?ElbomQiiBP1_Fc?heJB;8t7;MGK`^DG=PHxVr_X5ZsCu zE$&hXZiNEHJ+!zxeChqY&!7BB*4o)CJJ+0Z&M`AMT-INa@79QArOv*F<(Hl&i3RQt z5Unlt0H^w_{W{@;kbL4#{dsx#TlEv-@Zl6{uuFLJG$T1)CafVeD(CFUwh|qTT#e6= znJ{aLX%=PHA}n~b#OGsrbheAoPK7=Sb)jT-I~ygGZA7OJ zQa9br%dz5TwUgQFx=5kJPCe|Y6_g0jq#qC5zy=(^T()7bWP6+ z&ZrBRh^-~UbQF^Rad5V;bp)tE)RwYn6PsbzVq%&i!%)oXUymJx*!`@?Dj3yvI4qvW z68?2xffXk#L_A=qn(PFfIWvx!0T{Y;&PU8l^URn`p1Hj6sLv}pOsk~L)5P;Fh04@W zzIJ4fB=WYm+2M@74`D+wanNWYZA|VT$_Qo;EpQ@)#0*`V@y3R#uv#HA3qU)|4ykoQ zZ6z%!imlRcO1rE_#YXQiK^1H?)rV*8vP~odwN#I+p{;*<5)vDpK8tx3HQpx*pG*%) zh~JTfy{Ps3!3|rVx3^(NwT*OKSHe;>uHD0|!I}W0E(?+29m*3L(jDu{->W*R@ zO2|i|%|{0>rEddw^`h~tIsCCGf?Sx4uzUROz8wvGOPyS=7YOSZZqOD%9=>KRB1u80 zwo)3hrSxOZ$$sx_N(xN6Z%M{n;C~ohjFwye9csKwK$Pe`#5j4uNR+6X<-OC8 zvAj6)C>1xM3D95s6r$e>ow`ytCXZ7tLYbjnR+^|^pANOTZn`pmSwbQ3(&6%*rS4$j zj@}b}p_jyUr_TC&RuJ)X|5mQ+t&SgGP^5Y?>K}LT6=}%p`s4S53Ix3p?*wAmJpB|1 zlqu-ewbMYWM93u6V(x`}?v&8MY!q%%3$LSa^VN^!-;gm-Nin~vza_?rB~@5sk5vA8 z^@QInGQa>}A0D#@Z8x2KdZ`qu5Wa|eBTp`YX8Lt)p1Q1bM~_%3>UvMX-xvB z`0sxkv}ECKRF2s`q3z}B%)j}n=O?XP!eZ^5X15JFBVDUa;01R~u8~N8}Ic%0I zluo5*AM0uYr?A}fU}aF0XmwOF^Bhgbz}TdMztqK24hyY)0Po-;;ImJWe~`>}Fa9ZnKw+LR5wv-7=9)L05CNWzCpYpl zyz`4^jK1`ZPNXqrYc(z!0{{B%Vt;%n`CUyD%7!_`47D-bI#aXBPIfiF8{<609}-P$ z*0T^hyZjmp%Bq`JNc6g-_hk~!^2U&@YnznIrm5ih74AZ_m`MHwXcxYYH6;0;$zv5d z@gI#Ukh>UFHDMXJAC0Bz`J|!O7XDtN>Z0za*!&=Mv`6nCe~qBNdUUR7=s%tY$(O(T z1p)jN`ox1-tpnU~qZZ8@4EqOnXn2`pKfN5#%`rwxpU_RWjbJug;g$_gUjy@xgg2VI zKel6UOG8=%_TOD!;_VaJ5(VW=Bo2$}jO@_=N5sHiuv!B%CRM0w(Rf<;HsP7#q-UZ) zx61IMS@SkAP zN?sVfWe#gWJP7IPrRmKueBB|S{i|YV9-&$#jLQ_uMM^g3F~etDAisSSm*;3c*T(_= zFSTYBL0Cply$o_T50!qs%tGk+6f0cHF3rE)0tacI9oSoTp;XR~5&{pqB`cB4B>~JF znxI{xlvI*iCV9Y!PYz$hVAw2h%ppDw{JTuoLInK1i(b*(dK_(xUI~RWzpJAcGHL}MB zlgH+V9Wk;Y)Ufv^pT%ubk_RlB%j832iMIK#5v0?$v%m0va-_SR;4RtxeF1Zp7gbK6 z+SBTWLt!HFKamHw_f@|mf9rawh#d=i+sn*0f@IoOH=&x@&nt>4pKQfWm~BM8S{&Z)|dYV7T{+M5Nl)&K$V7SIlY_Qs-Cn=9^%f0m}WLpUVK9D?C5u;WrgWIMi;fxua%ft zu*py?6_{Cw;2j1ROy-mzQqYnghsvAdoU%Ks5CT{ezC*XC<5(-%F03|vtW`?6IOBJr8iwNWicdfRSG+>Afr*GBz4Z{wHqWf zAQT4|6PE>JySrbOMAY_N@=K<}HJ8sJpJRW1<D2D0|fc}RQ49T)ukxkBnG ztYyV*thwa=v>{n>ciy~9WL~@;Q{O1Vh>E7UAb?u2*nKJ@?pzRx?4s||+ecL4z0#Ms zD|)MDeqiL(wrj3ZHgxAks^x*=(8n#@ge-JvFNv|X=k)t~_?#O~kVL1@%FprS_O_mg z_{g-i%ufrq;r8XK_>{j%=1%VG;=l14 zhEo}zmx)f-<7{5v1V31^Uvys*y0zfQKmAFD|YeiQXfAz7_7z&&BfJh{B>kF~RLRlE4|v_Rs) zhqncHEx`9<8!%WuL^J>Vcgj!#J}hHwsMQIfjXIr}euOatuYTR|Q6y%J*-VTla2YLM zo4i^KfvTuYmVC9(Tn@&l6Web^Y>rDJ=TJ>)|Dyz*m(0_>^9>9g1xXx;EBo=)Dkjzz zVq8P{Kqb%nsF^ISE?Enqd*Z@-+gIQJcD%KpxRBjI73fa1UatOdaRd27@j)tL5ng-! z!vMFj=+GU1_+fkM>O8~#=)UPZ;i*>aT$M|X|3H)g@6qv}?Gt%>dc;N~UefkQ<4X6u zQ+rFj_g6Uis>y~Eg;y%fuUbcKoOJ&R#n3o{R$z%)yvs%t?i~xPNsHtAP~=AEP|#qa z*orfagN6J5tjo3T2qQ!$#|5!sh8|ikBoGZ3q7V+FkiE<$m#S>5mVRElGCsdJX778n z(K2v}*LVvdU3m_O{aI!*ras<5rf-;#&-{jLBqI&)rulQ9<*=W_=4-|G{w0rTupi4` z-KRdpZX&9+qVaU{&bO4Ek8d}`tqvtb*GgUa6g;ADI|-+6I$tF)|%Nx<=U&81iZomFGXmT ze;4`1rv83eY{b^;xh`l%7+ck?UVAH3SlOgs0>pw-ADtpgG7}5jju^LbW#EDNN2`Ag z9k2_~Q!WxbWOOgof4kD1u*6T>Znt$D8K4sf>TQU#Dm6nuQdjG9~p6H#Y0F_;v-{ z_@(>yTnrg`XyooXb*-BGeUMzeSrLElv8L1V_haA~3A;xPLoLlE#Xx#x z-`CbVeITJ!L!KCJ@w5VGUSx&8HNU|D1m9_!~NQ=)#3raq+2vnNTPPYbt zqEByVkM9vzRUOfZzD87pzOIaQ<=`IOqb3UF=sT9k?aX^q>%qj*3DO{FnBSP&VRFa# zEVjV$=QyCU6~Zmpnhw}oUCF8KCEc)-3%S?b?hPS^W|MBwc8_MeMSQ(&+`xS8=^GZgblm{c`Ybdi6oj&fNjHfM`TzY*r_W;Lt^| zsM^t0tfW6gJK%~AAF5S=ICtN)C@Se58`c*83Vw-<>|-CfmMj=vi1WDLb9PWrlzNS4 zwp%XM>V+as8+=d2sXgif)^l;(?T}dG{dm)bc6D5wKa%Lm$?tUcbl-#24v#SR$B!G^ zy#(NOo{U@g?jo!y4_nTt_ps3~obU^@@%ROp*UpoI)}p+n>u_2}rwFpDYuWVK+FU-`{pDm`)9|h1rh@QSE6SNja0mKn z3ry{?Z1FaA${DsyW<&_vEucwcqomwpv^rFHl;q<+i;fAp*r2&S`sK78bHUAuxF=fuDdb*~MFjPyDx_jq5kQp$Y_23;?t1F}&dJ`~ zIzM~1f2<)_l&9hZxLP)@OTaL9LqZcdEOX>b3h_-%s&sQWmH0ns73w0?$$jb>A2%)x z=OnhQF^w24VA3fRwAsVl!&EfZB~bWYZXWrgC?(Tfh6#rGhIDvtECbnUAUYCU*_YEN z2-Qt_!_P2CYoI=T$~0Cl7|Z%Wh#v$#ow|tQ5!R ze#3T)!EPxtPQ(R6T@JIF>Ri1;x+{6A^&f|~HxAEp2dhV}1T~F^JM0F9i6KqSWxjuv zZ)qvE;%E+H119yZb1k$-jCBdE0H{2c&iZaVA!g}I4m9|goW$H>O8xx0f;uS}>*9ES zYBpT=#)%8~GC^6a`fZN-WgfclAN1eD#z_{wv&QmEY54TajUHtEaW7zE`kZimoP>mA zL4QRw##cLZQY-e`J3LIS`)1Bbqe6d^(C`UEjFXIS-vPn9qjIvLu~8`za&#mp`f`JF zTnb5~&-!k;Y)KJY$$(cJN z#znc0{KiXl635&2ESKxAb(7xfevuFUZ%HsP?FI1E`638prf5NgQw-n}Q~zbLZV8=T z-sc{YUY5y7&m*19UyyI&1#^FFs1o-~o^$*u#Z#QHm*uf*>o zV=J-Kbqxdx^ojCNO4m2U{&$xM+Q zp+aJb#n9So%$JYYa`Hg5X$^rW>vD5_Uqh2M%XYRM;X@y$XY?JrTSEWle5t zUjJGjYkH-TE*AwCa>jk)GY-(fO>{d#7yp4^S)7q4{X>&g)QK5%VF0b4~SI_h^dwuCb_q)Hpk8N{Ae&20-1h>&pC*t?&+^vz*qPf|(^{8@!Nz|tur+8Lgs{h^Kkn6H#2_*uFmd1s{teNvvWj+X;&$&<& zjE|PTvly+Mdo_h|0q^u=IX%7Qy2#M^xy$NxfGQwm4_!yj6I#6L^?cqjr*if@O7T0g zl8S_p0gsu2FW{>j6!N6+A89-tnwDFQnd#3Yu%*~;=@C{I0r35-fu=nJ&w*17WNvCp zH6Pt-SH?SX7d4{4`SF?sJbWbd_MqwZ?WSMpxrIRIy_Hx8wFC$B3pIMcO*q=$wT8b2 z!yH-Gm|90o1#ppAxQH`EH2^<_j(~dKoYHD>go1{0jCJ*_OzieBA)MRB1jgD{ibw*3 z4Ivh}w|6cPlfSFXl6@y!vw40D=%wG@s)=I>>G8;7&<(GYPWIzhe-w9Me&;all6kb& z);{u;FYhXJ;+KL~;ae>G@4WHGBhTy7i|MOXv&W-IZt{TN+64$hf!W)WYgxA}ud zNy;A{xT+}x^pL48_&|Y{LrjVxdY{1;YGo*b8LQ3M-!^vT9x@vo?j$ z?A^9>WYgSWhIJ+VVp+BVUp}PofwHHPD7ZU(!*NCxACr`*dLIo3;(M>)htGB|0vKuU z$ND-onkw@%zvkM<*Z(4M)N5_h@?6C55a9x0KJ$KNnIj=`&>C6+b2{-0HejE?Fg5!( zvf=Bn@+=!uHO?x=;vE5BgeJ5%n=55y7`<43(-CvyZTs)%I!>kXNChdGU2KY-Fm#vv zDw7#75O*fp^)&==KQDiCq**O^HJEfb7AI1;jF# zAdOFD%Y}b}Ug?K33m79-b)ek^L5NxVE3CKl#tgpU!)F*);8rf$C-b85K1wh ztKAfHa8XEDz^`RW+VFv8!LSC4`_U#c>^HBV))4&>(PTt2SKW6KX*ZXdAZ$8+A5w?N zFPF}*ig^+E^uEs9_Y2W78pCAMc`AQ36zCZWat7qeP{Gg@p+kP8Ki$9?_Tx{-L!ut_ z)mOZ_%n?~N?@_JPubW(jxFtT|h$2wGLNG`Tt)@YvWDdMMRX&`v3&=2T)03B=d*8!b zKjSAX1`5;M1E5mj8{r?McBZN~{@7$#v`zpxn^LEXnnMplizhF{Q4$0(sVDQl!J{+o z6{7LC_k!MU@p?UYH(odHsckC-8(1SOgt}sF9LTSU<~%sL|2y#)cFV0?OMPc?TOu3^ zGwbrYQarO28=@5uo1AKF1r#mM5mVuzq5bRU6WXW74Q--Y!(<7%MJr{!4)wOlLZ*%z zjAI3VQg1XUUFLR+o6S|`A05BX#ZhJWpZrffJN%lK-5Cy!d2Mz2&N%r4b9)25Tj`$@ zADkP0d|PccZkvoee*^u$*t1|+Mw3|XYy-J5dQ8Ym8{Sgq9SB}k@E)wL-IDd9@jdfhKTc%`biVxi zw!~+ITMKlZtItPvjb^aozlq?y;0>|j!_mtdU*5`hS|NodCq6$;8Ttkaa+v%IP?_V{ zK-fN-eGvnwfE|k7kQgayq&<19W|3GPF8KNbJ1ullD`=*tw-aIe#!zo!Ub>>$1xN5n>>=#M&ar?633d~Z}V#m|hU zVG(i*;;&H{A3dw|Q6S|nBGrPT0FuV!-tO>?0r;7y5sF;7^A>G*MX3OWu3O`fx`YX% z3ONmDRO;~%4U^@5w;X*`gJA|;S?sQ>3V_F}k~XfbppO3b)-Ue-&UX)`9wl0i5n)Ay z%Q!m=oE4$aQfazoYQm8GEfS(mxNf~;D+;0<0!LN)REAbYd@ZwMFo#m+I51(H=vj30 z5BX0(MiD>p=&6%cGRpw5Wmv0-N4C0`Q_-?a=Wuu3f0k)&bb{0=Id`^7K>|&oX zh_qn-`+2-}<<#6bm|eysWaVjgx_b}h3OGuZx|Dgb0!n994CcjA-*9T=J261qT9^f# zTgdf)^b22r2$;}6IXodBxlx)!0Sq}TG6IzF%ApvdcPWSV4`580oz@jJ4eJR+0va`4 z^RtVH9#PuIvghF2-1-v2^PN92E%!o+6m%GDoBgT6IB>wvx?euc;G$OtqMN{gC%?TJ6y{JWY zdI=`)aZ{d7oG9iccFRiudcPC=xquYrA7cg8m>91(r< zU^6j}Ng(+UHYqqZ%8dF6=37G?Tv7%9^t z`#7344H!gym50=eoIr8W83O#W$OfH-3GqX>;R{Ol0+LfRe2zaO3jKkq3{0R;01S_o$!p0T$swqvSY>T zkV2(gC%V}2ebjpIQUx^RSsU`gIWy2q{$>n6(7qUoa;YKEqJy0<#PlGtX_A2KD1xn zCy)J$4Qb!TG~XX$tCY3SW@)CcB4{`DI|sK-ULb`cjNRJ5PE!}H2=G%1u#;uWKH}d8 zg*pSU+%~m8Xy$!(N2UhPzG}4~vhMoV59HeZ|FjK0*Xg8D4XtqC6JvaaWGnTKznnP?4MbOEk&g#p2HxPWO}tYARc# zHC+apdbj4{W=w#x;l1Tf@y5KGV+@R@uVz~XkRf3Pg*M&AX+*f_{>8|lo-;hij%ZbG zs=dla5#9Om@cUVUJCp#+AVkMCObV79=GIp}yh&w_K664H&>Jlm(kvBb)@RE9LL-OG zyx<8S2Nr8?X7TP$T_gA2WA{l5e|gMi1m~xYbOFO4y$~S~56UOMsT?tlP00KB-zktz zT`U{;b17N$bDFY7E1olVn?s<6&=|uwrZwx-SJZu2^ps=ky_kvH*87+bK$94dNx&`W z8d~X}43}qsr=Q!DZ16T2VGgS>fo61JfDv-GngjokRSeE&xvLGFJ_c**Wbf6DaHl&Ou9wuH42F;5)V3g z?l`=)YdJFi6_9v98UvpjlTX{a`uxkT1tzyJyw&q_{gR!| zxj^yfTxM_Qe}0nvk+;IkF#1W_qE(&xDT16^KSG~LSXT+8tH-a58)IqA!}TDqt9_nw z#nQ#P_QAAC2Dfdp>v*+TC{$vimB|B{Z(Qnp7niQsC}KxwF;{RH59L8hT^>?kh^`nhdPFw@#dhBEG2a0azn< z2#p5PTdAXYSIY#m;oTGWQm=`GNgs(e{Rz90@~hr=15A{AS71@IH)#Da~mYaH%q)x!g|%5ay^0Jx$xFEi;(F^!{!& zfm_#16cqA}gy9Dxucfk@8ExN^ZA=s-F=;kVl1T9`CtL@B5gTcAm}I&pzlb9c1I>SK za8RW7x-JoMEE95};BZ}Z*f7N;$zWBnGyw=hE8nIv5(S4>WpW`R&`W0IILo2<%L*3R zi8}WImnpFC&Q>XT`bZ`hxj^4ys!_9DjT!1=k^uF|*QQ4p8}z4H6t&x8`?Cx9BktAi zoo`QNHz@lXF2EF;7~Oh_w-@WnR;<1s=LGMt3}a4n@yXx7&ovpoa6i-Of{l0v7)5IR zq$!umBnEyDU?7(8G}aY$<78(kKiyI?L}4Ly!2@eVRfzc|2XbTk9Rd-+icw|R+kq&J zLm=mTf2e1rWKOeUK_Q$jWn zCSP>w{UQIDoOc28u$t(~5w-r&za2JqA58J-A`dU<8TX;#my>4AnDRdd$R^FhdwzS7 zZAy=9@9_hb!&TkdfT5U@8n%px76+qdN*xc-7OK6GL{W>#DxT;DK>a~3e+w9Jg_h$jN2+5JK_OD42%4iwcPI|j z@YZ`dwPBzw0wSN&R%BTpBl78XIMdG`q44q7H&7j&RR1SAb(_0i z0hBrUuw1JZg_32ypx`wsUUYsI|R!M1)LIfNxLT$(5Oa zhxG4)yO9^Q>j+8<_DK+mCm^X=*By5(X|+W6X^8p8vwHxbI)Z{vQjVPZ!g(&8X_C*12;pQlBYIbZn$`*u>TKtiJjFj{v`y_`w3#V^Bd~ z%tdbb`nO(vA@eY??mzKS6KA!6PF9ZcWf)`)^xKgqlgz5cAlSd16W;}ID_eiTygSV zCCGbsN5Ka~@F9D*9t1~WQQmr%TWRWBK%HlG@zB49Wp4RD+(^*WE&Oxxx}y&GJ$Jki zPM9uzwEOpSdQbK^eKU)+)+19))}G;aGEwpgonMGl-5|M;0;nSDxLCHSp0$e(v!b?H${R$$r1st~?)+Rhk?5Wz92eG@dLigYL?1^1 zt(Ow65nN;gRfom1G{>^M@q-Q!fI-nB!6M_LA);G28JUSC2gg?RYt3hG3WvYrDZZWc ztCABB`d*5|fwd|{(`1f3dq6rVt;nXk_whXNda2~VOu#%se_Hj>rj?wxSW_#WI%08_ zi~`3;71fgNek4Ue%?_$VOwW!=aGb2|J7Ki^EA%ywDM+<9(Y@E7=o!+)%Un-Dm2Xx= zBpAeQ2TP@l2?+jxRU^2~abaAd6~3vCyl7i}E?*GC{5+t(Rzm#^(5$PZyi6|+>$6TT3*u!a7JK#e*VU4ctS z6Sz()sW+R4LJjE}g!$(&=d(e%lJ?w>-J~FHbM8VHuUd}>Vg|1rHfRh}DNJ+|rfp4~ zvF**Ip|$OeD>U|>Ak3)zPuU~d=Pu?f!h9#XYD-tGq!LBbNORp?$cGqsaTQ#=*Szm; zT9(gah4=pXgg(;&eofjq*Kq8|DZr&8z`1ET?O?@zfu}9(WRuMDQ6ThWM})QPw&l|; ziqRZe#&tN>o(Eqadv9eYO2&a}sK zBA~Bb;m&3r|61%V73N3~N?0vs_x^wg=pdP^^Bpt7ko9NW7MXqnJtcy5)#+q2gXr&g z8#yyvG6o2O%Xy-!$=)n%g;sghqY6fC37k2T*A%Kc(&7RHTo-bG1An{={*xK1HIeV-oPHas5(vx=C*Qp9}F{=MZazhy{>P? z>|}5iM3~4G6x}o%1-r8DF_ogcrwAap9BZZA_8ssbbViKiqx9BbmWieS`w%Ijuo@dg zx@)Dgama|ol0tK4{~VMgt#oWj&G);nzhRh(Zl|t~i5*CyC}B#rjpTzWvZzV{{#0!n zn=r5sBbh|1DX3^jVGDQXEN%9Jy>R{g7tGP|($*FgZJ-Q-^~uvr?0N;X!4w#rN>gfDQ;cA`(c zD5>f|H7=J?`%6-|=$NXkIR=+{-kApe^=`^xn_;_G;x$49nsWnQji-^@uAy3fpc*J1 z(a6qRr_VJa<{-o#`2d{s6$OmW(ae`4)40Jn+Y8))#C))%2H>hZ{xUnO=Jf)!zZ*7P z1#Y}eduN&oj+G2RwN#K+ngPqA(&w6Lv>`W|Vjw~w54nga!<6=`gg4Y^8seZFzQDZC38~ih4v!^6LRz8uUtp8q zPuu9H$Xhc$XSZ(i9o9uC1#>3_C>ei4-+kclhrQ!Q&5DS#z;d<-`8iq61`wL3!1e{& znI+7yk_!U4iXAqkXtmm#P5g1%xtLK_D8uhm;e3B1BB z`nJjO9XGaumF~qca8bIyK|^>#&lKdlp-jFG^w!&wa2j8g2!#(zYcSa|!V4PMBa_}PsWsUE5P_rua+&xEpoLY=r3^Nr z#RaAr727^I-X;moBNw0hL|fl^_gZ^?lRUUZKNSh-!L35dQ+zBWxh+O>sz1petPPT_ zBm&PFm^u}1xv`^H5QWYm1ru*5bDt7aQ5P+Ta#_nNzYQ)Ha4Ej4Y5MtUa6?@7dr!M& zShrFTxB0Xkc$l2NXx&^X#YZ)0i0FD z6lDhDj2p703CaS@rwrN9`H;r9Aa>-bEPI?DrJ879Kj7cIp(`VnXT6F(p*EbRmOzhu zRH0d1Fc?dhGGZg&Esu`u5zpI6WZN%vippPT)vK-Gq!C}ub6KvyIn2ysyvZ-5Ti_sc z9>#@s$(;k14Qm>)CLyHj=Q5L;d;UF7wc<-FD9gH{OH=Rz@b(CqNeTJkUGV3~Ce5Jl z6GZd2+xl$LNI7o;deh}@mw)ZP2tYJUldDU8SPGE{k41O0^KJ?(xaY)ceps^(ebLU% z#&9pk!&1Ud@ZCPZy#{DX)vcOrA#Z<=Wo_k5i{)Ix->q8S(l(!JLk z78Ms3({su=H5@})iGurh$Q!xQ$0c(RoI9fvZ(CEH<0(QLl*YXBLC%8gXgXEhT3F zKs`A}Ou3bs;@jTnSwxvQc5d9p0VhV2xaItuc9_$u1UHTSpVwhlabe>mdm?db4Xp&|-YWVX$vP%-}Ad-IT z)L(;J7EZWp*?z*PkI2tsWt{j58Q?me^QC?7WHU#|PH~+I@G0I_^3r|&!jG%;E&kWs zQL4FA$ae#j)$w5VG`vb&`}I?Q{3Oo_x8-^D2~%b!ziT zux$(l*mgiLA(e+XI-6-AK?CBdmS;5>>hqZ;ZqnHk3*THoCKgyNXrh8LX|1uL?02q=1+MPpdh2?~UXLM4YTijMz} z5c~O0nF%%H!;kN8ovr=UALwgXcEp`ZEE(}nBR2{Ja8*0)PAQ?XVGG0;e+LAk-1TkX zz|Uma@miVohuycmiJ7oww39mL+JA@`-P2zwoO!!P`Ir|1?=^~^>$an7*tgZ1IE|Fm z8_^*8+j5GN?xd}5p3g`AN{T_?7d@ym!1>GVHrrOv%S!ci?k^{!8e`5GMFf-ov-aTk zs@ikjDm*tRyg_P8)z>N(gP0>u>L(o()m7JCJ?>F+mAT3>B`Sr!vIjO|4n%~Ac&na% zb(cJAGxEOnM+0A~;;Ma-lkn}z2$l5BYxI)w6y+h>S-c2f+t9^T>Z&696A*MBoe4^;sPRzQEhbHq~^d&&@_uQg(`DZ{OM^2}nr6 zwIu7wt$%fcqTfabx=e}{lK&zL0M;kLCq!hfY`uuTsk>e^^j*(Negto$di;cjSsr{0}P>354*T zNExXG2;H^OPbaS1uW(S0iC^ywsX z@o7rgC?z4pjpTal+6!Tyn}Hd5g*FX@H(V>!Yv8+oKT8u&QEyLKsFFB?79{t#2*7H$ zmQ&|*Ks-)8A6)Zn;R5iCHpX%H?%I=!?5BUBJ&e{dVN)7ufx%PKyCY!N*nhIi?{X^G zh^})Y&`s=tH@$I|(`<-}F&Pw=_qXS%EOQbum^*9}onbPy|QxX8$vY zy3UNEX;A%uf!iTR%{?C;q}z-RieDZ0hc)f#N9nUJnwsZQ*jt)WAwU}Qj-MBhQmw|> zWGpHPg#`W*uJtkpeHkv`(v((0$ina1olFFozSGhy5Mr-mWr9)agrXw6Bf?@y$xj9F zTYXHi;LN|o$sDM7qc*&GHWvV7BB+Gw4$ijf-Y2+M<`H-;eIHktm8t$`?8F{N(r_ZAK4kG)*~#FxgY>Tk%=dkiS$JE9CD zdwiJ7m?$j%F^gozKCKFCYJ_^nV6uS~mXH%3(j*Fy9m`SOR z3#Ev;zv<0VR9%GZS*2gscaU8Kb%O1gABW&HC7jj`Z)XzcuzfH9{j z2Xb$AT()T{0k1J8T{5{k{fiNCJxM(RXk79Kd6-q&7t%_CnOB_2jh73mX`!}hO!*Rh z#7f~1uSnwSWCaVeiI2p@Iob|Oyb3|)K}V1N$-!SS0=D7$^ewCXedHY z<5>eO_`%p7e&NW-TU!Aq*_GI{yq#)kG|%kYbEKAKci2{g^b-VHNgyIVghT5jIHgYR zT=vCVB*9zuw3CAO&0!g|p$w@{biojvZS`9c3Lg`QNUHaR4;6Ti&loC&W|_a#20rJ< zlzQj~Q&I)+`0g-L_Uu*#f7rbHrtF1q$YPi!r+6=B=aY9%T7 z7sEKPn-_(z$=$z9f2$3P)Qac#YrodDzK*W#)o3rVZB`=h;YNxF=I)TQ_&5F+&&!9W zb|QEF6*w}v27b5L;HY+PyZSb*^{gAF6>DC@OdIpQ7dxJX2<;C-%Ppn-x&W@yDhO=q5?7Hmq z-e0Cz6BJ*sFTLKT_qH}WrvA_n2gK!GJzwAIT#54Yn2R5I`;Ui9-q|H3I((vr@}oU` z9pLTJr61Y6%i*(^K|u1DYx^b zT32a59(m?g{G;o3t=5h#RL?jo$qy13A=-ESO~NQV`8rP2F|YLPF7z$WaDLd`e-43Ekq%$DeBt#zKlS;@F~ zqfCN*2=A2IH6e7sh)ZSwGdhgF+kVSu;3h^ilbDkJ;!a0fn1y{i&h|L<*5c>7CK*5E zAGtjCzV-~4p6Vot1B-Kl<708xu^rIs{vvJZju3%Aurmr^gX~bRo#@01Z2!x|U$=>mRM`^t)->~49Zr-t@W8J)N z4b^u?;KB2?6srNNXP}1h{vt1tK#E;qzn#~KPKo~Rgw$e1&6n2sCYgc- zmX2QpwVAHHaY$Cwz233}Q<}LuU$9WXDN8qG%hsi#oR@6msqdkz({Hh$4%xuyPo~v} zqzU!cTEg6br(@vygujXNY0!PQ(XHQb!+fZ-sSIDzt=j{-XEHirl1DUIHRAh-hlOp| z&!k^4@;}VWt#5CI#@}#6r~YCm4R&I6P3StD5IR74(b$H3Kd%-oz5bYK3q3ByA>rRn zV;+nko;OjH{e|72CD?CCKXE1KsUi6C3{p`$q6}*aKQk?$h$6dx{PQ*U{oCzIxs?UL z#yDFvQ-bggT8@T;$whlMkW*7AMpk`W#Twf#51_BP#1~(lT^u3@u7IyiD0n&)%1;{N zG~()W9mU9m+*pFeVgqnACP>JeUR_KU4@}8Y3)mzS38+a`=`3%>%t|I-zoMxw(u5`% zcuRBZmymK%$(>CiCWM-@wOw0Is&ly-8cVV)7J_0b#q7NQV&WgRyQ_fn%YC-P`*LE$ zuuxvZP?QNgEVul)2T-B$s6rob7uG0qIE1Fp4EB0XvF3%IbGZZVf$_iMjI*IgLPLD6 z+)QUO-0?(PLAXLgjri;CkXKQ(_iVhoF000E?O#Zr5>mG+QM13?wuA8#m51eza^i&Y z+vbK8S&kE4Me%&Sv-qdE^0J;H$=^OD|L&IOOFzqSF7fM1yC)wa*v6C^kmoteEeli( z`;X2e{Qq>`V9jAphi$&&Czy$%M435t%2k!^EHdi7)?CpjyO17N;gL5_Irl zf#H$xu6R)U1I9-(pJ!&5Z18$!*2YQTCRvqr;f!(D)wc&h{pxc;^X^an8~(5rUP34>g_i5ht={;@O3nb$HS`U>&g*QS{E8{WCEr3p~i%o{u~g6s-V-iG@l?bDxH`b`7+y<@JH&C zFZtIaM37;!9hFf2C9r5u0%Q0hpI@gG{5AdktLPU7Dh}nFjkym1d-T32_za8FQ$m`c z7ZbNgvZLUcK?^>{cEU~4r4}sR_IE;NVZo;Kub4zigAIvzu+H_~G$sIygE4Qifd@#p z-$VPmIQTLmSR=P%ZGV(B)1P5RifuA;`Ov=mQm>~~ai`bw3QHz&+#1_8eW8fOYB$Tp zoVN)vH+3gkuvI@DRTgby!h$e50pku(%q?nvjUZsfh7pXrv7J;NN~RbVYPuvAJ1_z3 z`HKTfIbhSK51^GJR2wPaC{_r5q9^FU|7xUh)8Im_@=n8m!A$AvbjT^q_Yq0!4!p_~ zscZzp*ZKZd?>9Y&14~qcD~Lz_A6ai1)MguX3*!`bNPyy2JUB&5k>XMuiiP4uiWG<7 z60BH|qQ$)wE0z>U;K2(8ic5<-#qCSq_netC^Zm)M%-nY-m#nq+T6^QY$B+9UAYHym z4ObfKa0M(gssul&z9@L&s`N=6tFQF0mG~sN81$7_3!E<2bp52So!8IWKOy?7HaU`z;l(7GEy&8)PBI z`C$9rgT?i*ZrHOC&Mh`oONy;s;&q<#_%t2NMR!uQTW=iirl{i_Dhe#goNn92ycMQ;ots=%>;m8=qkdf#;RAh4)lO5ddT= zw2n&x3m5ttoex@3ligcG*Sovh?cLv!l&_1BSif!6HLOUS4h`!R2z&Uz)N-c&=BLx~ z;)GZUUKWBtz~NknFHO}CPKxn>9@U`@#wt!A2Psa3e)mtLzl z>pVy)R)ouQvxbp17z@1Iu?v-N>p<*4d5tx=2+;Ugr^>BtVx?t8DO0>K ztG^t{2vNMSMbU7%h|ZG{1{5dDE(ZY@1H1sY_w9L=+&55+h1MNEGB(^+)GGVxHMGHW z#DuB6kF;R#D6C_9qf^|H`o3PPHxc;quLX~i1V6w}ol+e61W7J`xBN8-5iX031DG^e z?cgQAm?|pAK=so}8B1@9d^*+?FU7Xk7 zcYej1vmndXGQ>skoLj;M86!{s@^SnnGj04p<4ohTlfgYFyKWQOHr3Nj&RO?wT; zSi6RLo&e&Py238$4mHvtmrGWg_Ji!UNq*< zvtb_TZEGX|Zx}~|JDP(&A~zDq>{j3npduV#*&N~ClYu3#kvNVBN^FvdNqIHl+8+k1 z4j@7G;;3`3`fRVK>w&A!BZTm5@X&S50K^$-fd`z3Y{gxu!MrcKxc;1JQOk5zGMpLf z7IIH{TTyW5-FA7@jsP!E*3L9f^ES(!dXCY#E)?dbv1zj~F@DTcu-ITf# z^s;7Ex&P#Oph~b;7@F1U9jzo=Jh&)TY%^X9 zOeffO%vwE@`D2SWUW?1TMvbgRKog~-!G1_l?{eHF^dJ5#-a2gCFX&inEWM^Ih-ua% z=gOiCZ}#`V+L&cwpyg5eRjm!fv5~0!E!^*R>ZkkcuOD(jzIEd5nx37apt}u46?z)*Hy3RYxbGG!SUi_ca>9qdh zswqGXp>fdU7!CV)#54b_lx@XIOd9BlFI+EiLIq!V+eO0zlSRq)mBOjrrGewbwrb)6WNU zk(AbipZd_RV6pfXqMnbX3#8`$n(<>g>I72|I|R%43+sfWRWXi;mCVQ+a|%|46mB$+ zSh}1Yp|94u`hObGpXam61$&&!cFB8xI>w-T&c7t-;luDmys&um=;=@ZjsHn3E@`)K zIfKqZ4SXO6`Q|d>)WObbzSWmjs?91|EMk1fmr-W_x!o3RTm^&D)4gBIO;a^AqDw|a zO3p8iYn4VuW%YDehG`<|N}bH|?BW7o20TunBoODgJr;)>5}6}TBa?zsc-`~vcUfjVUEpY5b2T0CoG1f3Nw&|N#qou3DmC@N4v!Vk{x*9{*GarlIG&cOaA{oi04viRgZF@5 zly^^B|C3J2=m#KI#SLutj|nFb#ozy)6m3rjWg!DgI0VNjk*@U{%_-?66=s8W}ed$b8}S3sAfd=)2@vE#2(8;|Lgb93=8>Y zcXt0((#7VqB9q`WrdK<*rP1QbbIbBGKOyV@dHZ>-6Xk+Y_?tebGU2Kd}hTvd+IaJ6!Lx58e0ej>b*Kf?RVBJl_#nb{JjMtjud?I?&s0Y zLA#%FL0?B#!?2eluf9n?*e)~w`8JW+SN%V@7!6G6k`8~>xV{;YKuGl0;lO|Yk6Tb5 z!hP5~KpQn0dIM^~?f1odtU@?t5Ugi98XmmpX3rwo7FXq`8rciEJ)#X4HLI`wspSe;o-z{sH; zteXj;C|5t;u^6?#`rR$@q;5FeC0e(TfVsz{&c?8NTemO!!P~_1tbXXS-P4D;jsf{9W2d{`f}a7DX@YR~YsO77jhPqs&`9BiUxr zW#Meq7+pdoCGP{SPdELty?f7O*2SR>nv72%oXVm~y}&GJ-b)9=(c82a@ivgG_h(HE zMkvAqe)>FoeG!chmpMp{?S-7m=oZZJ)%#+Ggn<%Vwlo`6_H!Z!(g!PzlqS<{qEX3d z7h1(Mt%)y+Pw(U~V-r*i z&7OW=#B}(OY;Ha&#MSIR>y?H(i7nrn*;a>FaHQR;wUtNHWr6H{a!e47qiAN zVmkhga;n-7`>t-luv;bjS*2FJg7?9%(&M|7vnXKp=*aO{?^S?>>~*QervyKR;->#Z zY^#usMwK**g1%5zEW{U_xG|#aN)lN{4$e>&kQ3?hQ#!*Dm@tKbwG|C99*DnJfpW;8 zx6Syi|Knb_4Sd46|Am~H@^2OVJ73&DD8%9G?;(655eI&ecfvGDv%(JAjG|KXYuf}b zK#HV^(yj23A$VKRMa_*}By(E(uT=*G{_*+u7f_+x6I?3myJ^y(z|n>fDwoU1`K+H; zh2deCvaweOw|>WuZnWudvxmfh8X!Rh$k1OlV=nJat||45qC(u#DyTZ*GcaAHc_-ec zu#hYbowRJ4G+@b+(+Q>eKe0Rky&8Z<2D&X6HrmsY^1w z>kiM|J}B*}a%PSWE*Pl8;}eSPK3n%rDvOb1;SM`!#i!Gr<}^`JkEC%6egfcqF@F&+ znh|ZZY0(hr^Kmxp#j9yy)!!J~5b7gfQfP>Bnm$zj%vT)*Z05vI8#T32wUdBDp(>F% zJPxD1%~P%+DY!2&mpKeX>K~VBg-O|ZJV+tZ-|CP09MWJdp8pMeGY+}~J~A2E=K8y+ zbQ`}uR-UMD(Z>sU0p-) zoFWe*DMs$~_zV!lL4floUU0IBiM{Z^0-o-Bcb?=h0%Uey{X%vMJ|bDGb?Y@`s0S}G zTXyJgAe_QvszJWIFm653VbPHOg^q5aziCL_Tn^dqGb)VXAAy*uk<&8XkxKiEcR@?? zYPwB*7x~f4-qaf>B?ULOgerxI9;$E40e8y4J|{uW zW2lEI$b^y7Gxco+*Kh_2fk)W0UN1xfA+Ja(*9I0{x+gMPm9@MZomY*51^xP0@gt64 z+z!%!7G&C}W!K+qrYSw`u35$>{-Vb^Hi%WtQ>@zC!|v#YPdhgb;yf*@s*C+(HHuYW zWShd7eh|H7iTz|d})1?5Dd-lC~7Rtnk3e+JNauY32XptN3`j=6CBbN-bBu)g?vk!i~ODwQ8sJw zLE&?}YUXUj+)35Kep8bB_;tyWt`q;TzcG?|IjrXXP_=C{b(%=G7Fwz<`B?ex48Qfp6vg%OZ>33)p5}dIo;$ML{ zk6;LAZeF$%hg4w6K4r(hxxGf36Ux_T`zcf+Ot(TJ$S|3ex`?c0(EaC$9=^E;Kll*t z?1$<_*3m0Kywt)AGuyH7apjWz^+=eyA1mHzM{k9_>y63I3LtCj3l6;|m9{y;k7&?a zQy1w`PBIC+unW($>erCR=VeMiYT=?G%=b&)!OYyeZ5#j_uy&2jyU;kT^1|UigX6os zt9}M2G-Mm|Ez0R4$Od-@y6I|7`F+bO?9H0UJ>Hm2bar0t@=i?JVH#r)X$>s4^=TZv zf{y6#UFii9eJD&>?lCBn=#)QcyxH8dv;|7C)Mw8zK@TF@)-axj!)Xn{3;Ie_b#W)T>`*hzgVd zvPEY7uB$Bv=f>fRS}$-ntjRJR9pdizUC=!rZz>U}mDBMm=e>!#|Mu-Z`%S2=>Ce(% ze;9O7m6x(AkHUI!nLaHQ!zs0gsNY*=UWe2s&k8yZT6V?WS2av_)V0%LRVl7en@par z1j)n*wt_7q!vqET&m0(`NC<{*cJJ+IU5QY2o6AYA|S5Tcwd;<&|lW+zH#&M+k{l)!%* zcau=9!;@Scs~h6WK_PaBKPT%>dZYI@c;^{gM&gfJ!TTrvK1+Qze}dg}ML`awUboS$_sV<=PU&s=oOP@I3? zZG0=t2Vw`$KxaL}_R^fX+(>~($zHcx6Es^fO4h+ygdADCEjeGk8}L+HJ%OWN=^U#7 zZoJfa!QZo+MNFJOetqPUB4%Vu5|8McmJ++AAFrD&u&hEaj<#<%AK}XLTZJs=+!~F0 zUuS#G3$dc_A7qchr`xE#Nev!P*ByRk3mR1$qQ7oDHP&67;bDZIB1unGQ*7q=l-r<%r^=f}ZMK3TUS$kfs zk{x#bWLn(z%j9jzogsC8_P;Ns@kVdH!{q#3WP!~@rCqh3LUvK~>AQNR=VQ+_mFqXPa*@7FOLjp@Pg)T=b$WFJ=efY5s-jIb{e6|L4-i54^!f>KuMg%4LBhhW5{6OcmV?d$g( zX+&+SrhX(GQ9K0gay%`!-~E1{C~asV{HciNolUygjU2V@Gu+o+P%&ObV@&VudfZBK zCsh#aW6P};PNEo2DP|T}QQA}0t_EGpUyf*}1e+aqArhr(Wq**M7&s*jHYe!!B3A3v zu#E6VK5x02lQ!;3c(jGxMgVI`hzmaI370rwJLLMXm_B{&N1Epa82`9PE(hQn$x9W9 zsr?u(nFd0<$NkbJl&o4xLIHgfGeZhT6+4sOpZq>8io-n%wO+zN&}(cBV=i=W$!G(= zQd;6bvj%Y9`gvMp&CeE@veHz)e|7eS1*ZS<>&VJNU|=shX=g)vA&Ls;eYz`6tWR2U z19*=R-&*_NNcY8S>f7I$!jFfazgaouJobDWbCwGUV_@`!sea2af}xKf2nLlo8UVv)fm{zufm&@vVQXCk!Q|UUu@(rTKOjo64wAvxKu~2 zSK4v$a4fW;D&WKp+hP;%cCVu+=&(uSpX>o!Bmc4=>u*I!SG;2dYEQ3xXVKdU3O(~n z3ykjUxDnh9-q_HB~dUt1W+czSK_CemTA zXr`4mKT@!<(Y~2cUhEVYdw! zv2Jf)lu)67fyJ@f-)!Oe2u7A7IG4oIazK=mU4nqZjlq|DsqJxW?-`EA=OI zw`yqqtT(;enu3+FL`abmXYiC``YY1pxrB{P%utvIdDW+5GiB8xg0EW7lGnq|@XqwV z@=u600c=^}2E-$=P%fI>|6u*Fbf*}2e!NLDbtmZL*1svH6XOYgzY?^~qpI1epl0%F z%HqIYg;b|{y{4MwoPq4f=CHxi=jc{^7Y#lbNP;?q2e&& zqP_n@1$dL+%;1K_*g@SxrWqFU)$ex`zMD9^XS6j@r3m%wCNxRwhb#02C%nMa;-fUe zU@@bhesjh2)h5s>9(GQlYiN0<)#Ba2yMPCL2Pg$Xja{G`P`t3-g>Yv?CFfjB0A!Tl z?rf-d3bn_bcNHY_37Z1~q-qxFCDtM=*VeMtGPCD3L??}O$Ao>Wn~JO#8rI4<>*LaD z_#k`sT_BwLwDzb$6*z4(&Z+`rWFr>sX+_lFsZp$;{H>k=Yp`OQ;lBfwOicbA;?Sg% z(&%+1h4_?F{BV5S+ZeV&g{Pu-W8L)a{&9)fyj?UK2g>M}`18mEpQ33^$_Dx_Uf5T7 z@UCtt+elBI{Cuc$`p7ifODdq!f-vbS#7>~@V8V)dlZiAp;m5di5%{+RHW%sy;?Hviz44H) zqFfucRCyCuR34WUhK^LF;U!>@WcHG@n!yAP-l(vto%DNpd^vI z>S6*)l#K8KxL@PAFH_k2KSx>9K$3{N7{2LB+{ujCnA)n@Dw=|61`n^o|MIU$=iP!j znI_`SPtxPa?1GC2WMr%)D>9bfDH@kqf3_MTC^c}=oNIq(#Z84(g?EqOu?!JjRC zrKd05HGd~_9tvgdyB9+*2;m+8TVdy=UyxUKfww5HP;kDr$HnUuId4N(VTa5y&_T%{ zF0N4i&t%qTdSr52`bY9nbO>H#UwCo_4IFBlps4RlSYGB$8=~9z<;sQRTfv4KwatOR z;j&`1UG)t1v>>&T=Bx>=j<$Tu*fT;VG@CW68ZI=1CZ&y+EnHrND|gzxRiqZE{vgknY|_jQgK_YI^Cwf->ogZWw3=kDIs_;OS%oFROtL+@zuNu6Qc#t0LXe_Ef8QJvhsl`Wx_-~M28wp?1#5e z#pCCSov;HQ2yfc+9^H31F&r+e_|j^;iq@xp45zGd7kj}^$CH~VNkji@kiQfRFMRe0 zDNn44sJ0dgaKWa)w*{vTUAluqF(%+n>(MrEOPnWO9gv2P3@V?B$Fm5@TWJQ>i=Qn4RHi>k)oz20LzMqEB(q)}6UK3Ogzr1WHT4<+X}uQ#u;~bqN#MsiJbMgv=oQXph(Wq*~isu8t|#x zRgFd_??0f}QvI}doM_l=|p=z)L*e_qJiZD8cSw2 z=^xVFP1)QnR=BssN_^8U8>|1fR0cRhEs!4AVb4YT!h-6zY6`WN&MP0DTy0Sv^*l=4 z{-dOpvnb|CeD*s&QF-Fv7sm}pE4H_i-`aY|j%QaRJDIdw?~v@cnusMSb;EV{(n6-=3xQ4%5V+L!mb(iPfD7OL)8x08q#YdG%iMZzhq1I@B)&>l%y44Kb>Ihz zQTjXm>W}CZ+tlXg@;qa+n_+Q9XmLV>wMHbdntwuT=}ldfV_e1Qa~Q~P1%9yn(8bl_ zk#uM)zFT71j`y*~pJtk0J<$0Piba|md7w%TQ4}~IhArL&s~#2S(PmF&@*IVMVn08F z%!&lCh5ft>RjD-BD&py@W#Bi=)Mt&rb&Kw}8{yo(ljs~-YyB>}j3=e3oPZJLONj3S zLEN8@^Wn!|Mm!P;`(e}tkI^(fE{B%S+co{zg=+5MRy}`>UT(`cclfKutK)XRB^5$C zpDwLBymJY;Bj`3lbNTi^%N7UmN$$E;RD1Pm=$X`oz`OLI4|CX#fjt|LlH%8mf9#KG zx1sn|{_s>A9y#|^(yNu*pjfq85Z=M>#$Ky|>7(I7+CiKcGUwl|E3x#nbEgZ(M`|;4Tull6r*Z>etcU)>q}a`^dVL!BG*&_d{Q+2sS)-vKBDu%kJ?;DJ<(5=fYS z87&|GK>eXw^KagGEdGhqYi2#kQl`>Jg%{1DFKA_hGl0rN>7YnDc0~$Np%@2$*~L;8 zw$G-qLyc3g4-IeFcv;S_j0=u;Pg`5TF%_a=3i0L0f~Fqi%EV6-E;Z1jV!>DDCvW4km2BOFxU82RDM$vRQ>3Ho2UyT-se%#My zUO#oobOp8IH@!jnM(h#Svvb;f4(W2_=y8M`Jv-InJcf$_6adhh!pDkA(fAQg5<6N%S%w`2Faj`5nVkm2S*PP|zj&z$%gNFr`_4tJ8y z1WB|trB)91?j`~Mx?-#+Q_#uJ*-P%N9jJJe4P6idDJyy&e*Org>|CHP#EL?5Nz zI{i)8Qn&=WkwBitEr8s$k5H1J2LmMbWmr^2!u@H3Y;9u1$qT4VxJ>xTMIg`dgbi|| z;x)_a`HzD8>Ym1t%4%rMfWHcqS2zLy0-KWNGr3#G>a&4GVj@8w6B3~tLDwkkvfsF` zD^BFD%!1t|qhar?FO{%fOXYhC;%tUH$M5ii-91w~MoB-cXw9F)+(l13XHd!=c-Gec zwwxKVS>)mP!Q$Y9A(H)Fgyxh zIO%TbrP~(;TfgPAUUrjjntj>HH2a5ZIli4K)^zLf_C#rSd|1ln`0J`7Zb5GDnv5g+ zVNPFBWMt6_w||(+tSwZie=s`|1+2%G&zhG{I%)5JnIQXKVk@EsUbB*PTQz^|0=!iS zsi`~e%6$I8=r6{W`QZ`f`-|`2e!f{8h1%L-Rz3|>EOHs&@;;v=`Lc@}E$R4wy#NA= zCIf^$x)imJg?fC6L(tdIwD|-qpFTaOjlELAcJ2W--{o?%ZA_ObG=RN|U2x5~TO(Z& zylMTGxDL#j#B@Q;k>HBMQgFjRH0m(6{4Alkd5)S9-K^d5`bjww66!p=@hyMw95E-@ z^u{wXeh-B1ts*HJPYHicgGYpfG>eC31>S$XRsU)J+VbuHBiCYPf9}gVDe=^;kcLBS zWZyKLExiv3aoJt6enXOB@%QKjs?S6gNx1yZ^T=vjy8Hw5UgD?GLDT?EHKCuVlaG&A%_GvkFLj3?nEbDK>Sj=C|MT& zTweU6-grmJg@T3adaH3EpPQur`HbD5c^5TZ@f#KQLNw-7x-(eFL(z(-Ro4!#v(=WL zu#`uUL5F!X*agJ7{^0ℑ*90p1u~EkagW9d9!4HRS*#egJyN86=hke2~(7CHpI|r zNgXU!i1YF(ekTbdg9bND=`=rO+bqC8>(06hG0jQ^CJw!9a#E#Qam}H!cNnQ4nVU6O z*2Wh4*p0ytqY#y%ypwj|gE$OI%|pfNkd#DSw6?aQf&7~91P>N#AZY@Ys#B046*4fU zY!L2}>n+|fFM))`Um;bmMy%Mn?}-hLY3BxI8t>k#U+|?g)){~;+?sx3Es!tZ(B;jk zavwSH^^`9m|5N%U;1pDotj^dBr|1V!HT)-44sRl4)K3Isd-{kT4F4}8B+~sLS1q87 zrbd#lEWw^650^22XP23&7(rKjBAt=2mUY5HzjNuiW(izN=ce}ASv%GO8w&`{S z_CrlQph&e+uTJT>2C^$WWGTGVdJPDjCrCQ`lw3IM$U2xj9<5C-|wK__x<0;B~u6B)2QUP{Yqry{zw+rJWci-gZHYW z@g*h zg0Yb)JdLLsv5lfSy7erzd|HVkd7A@l!5OPR4TQup7Ll;TJK;IlgRn41Jcv#oM4u={ z#Lbv`U>BMii~P>zzHM-4l27xx!YN;)0>+qth{z~A%#a6MNP@d0gthWUP3EB80?#6t zav3U|fA&J=(#6ItYUSgJ1zZ%-e*3y@K3n43o2>{xxsnyh4Z8Xp!r8-LV6V~z@8U|> zbPl(7^??6CA~saHG$EK#e4AYumQoQ>D1OrC5Ny6IX@W)kOpjZ{{`xJx0`6JUfakFq zZfr*_3F%hj9Wg{&cpe?Q8)uOBu-KED#>v7Z=}R~N4L)E)eq{4Tn0^E;6zmnU6639= zC^)2ZJ57DtK8zKcto&kRBuJnZ2h4HJIXu1cX-FnWHbdR{aY*(K zNg2m8mVW00GFG{-ZJ&f=q4!p-mex{G-u>C^nRsD>pIlMe1SPfY(76P8Sv=nPLhsIg+TM(c_W! z@(q8T+NrpD56b4Hm?ZUFYR_fB>H9%S+2)l@;Mhenj>pAv$x2bakAn@>_&1;*@PL`y=l#=6LUsQi&~~nT5buF)GceE z2Y^}C_8FVbyT=wEWba!EhJtAwA2!^VnGm zyC9#~y|U9&E%d!fXrcRjEd8B-nQVk(u%DPT6&6pb1yjd}-tk)-OQusq$E{hZUeg9I zO0W{ihoTZvRzfr%9^Lx!J2`%#n77af6qgxyISHluNPATa3=24_yV$SFclpQ3O1o0v z2b9bM#hIdbDH?ZM8kuTiVju+}Mg4fK-vitnT&G8|@$moyiUdO_7Pth1v^Q!ag@K#@ zxqjTe4q>kjdLrm?Kc}w9n?uL^5H!n`C%x-LS8$Hi$pl**4g$4$!RwN{0`+ox_tUta zQ;w!M#X2mI4cIimLgZEC6c9Yld4DSZuCBFxNcPu;LvXS<{vFA2RQ$ck!_$=>y_=bT zTTXt%Ww;%|c4W93*iQntIKI}Ry0VgaAl1d+fYVs7F zpyMiHVvGA2SAj1|uD|j2GJ#LcxN~l==0O`JCJbFqSZBHweo>j=0Wt|)`N93Qt}Bj% z)6U@HO5OU<;E-&E9v#d<@Tc>YK-U}{H{fx*v&+k#%iVV|fAnN$U`C|-I&!6E`{yOd!tzMaDEv@yJWMtT)a8Oi!ZAI=ub(0Ih=RU$7)ScW)^=Vg%g|N( zLqYX(Kn2{Ftkg&~K#8!`W`{xaZD&0l5ugG)rmhjcyZ|+IcJ=AmO_wcFEM1Bf}A^*uDXJlX7^>U&?fA=P8zPk}7^+}@3dKsU@mQA>09FGK0H zx~Q=mTDLG2<3{v%EK|~?T|Vu(2rn?p49Exq?Jg{b8aniT5{(IdzX(G7>JB2GfNay9 z(ml;R=-o>rNB8@!dVSX_Rv z3~?4IFQKb1XoY`{ui93j+!}FGo_s>u=Z-ZPf)nD8nG*v{+8zi=4B`z4)9(Wt_w`S& z(2KJlpehf{fFjnhIMAY3Z@#W=K$5pOU=((!HoJ&jbt0_77)l-n@38n0IaZA}$xn&e zc*>$#aj6$kSvUefvtz&@|6!5`tSSEvMXwF#u zAF~L|TABr))nooAx0&=)NWOLwLT^Iep|y@40SC;^Yp1+awv0Y{L4#UXUnO7XWOTU4 zO6!ZDtMYsz<#V3x-;tk^#cM>^HR0$KSn#5U%-s{1Hr#p9OQpw*|K^f*$LZ*U1=j8` zj5tkQ>07}?D;=9qMpN1U!bS<-ts0JhY0l-q9VHp~zaGB8H|)y#Yz z_SG@vJJHda{AwYlg7*q3x_|nD;qLz4*!b?dOhPg&?f8_Xu)L5Dr3*fS+i2~IYjqFr z@nQMth0s4@nI3u$x>u&|#b1oNDnWRxpzrc?)wY`H=sHT{H~-^IkWiMntnPW2THNYf zJ@87nIssavG$4YsH+|&*M(~jO0W{+C3w}EisM5)xQ~{blzb`rMt0rRxm!A7jem}*j zFjFRK2=C6%3tt#23@>43Ak;G!E$1+dYNI5&#MdP@`fOGujK4&_Ez9atuezb@(Q-ZI z^jQAmpB*CUBvi${ubo74bCd`@JCjy~>2X@^AScOv>m=i4T=s2FrLt-%faK~CCz~l9 z&<3v@z{w{?SN_mw2NH^&khkkFim)QRem^m5sKHT?CcVgq`Jx>B83M9UU+G8%{j8nX z_7M5t2Du)!g!~i0T9QvfsoI9GU>(xl^c!AODLDRr3!eJZqwD4M!KHDgg@Hpd7_{)vlyWsGJy8 zT`A_OH`F*HyTcx92PT+45+1J(_8UMs9{r-3N_nQo>(2l)#0A(^$(3D6X1?Cb8x>CiR71zd-2_hNL1JtgNu~i_iVAM zwk->{&d|PyRWfQ6J8|ccQkW0SMXyPlBk9HO^U;{Jt>2*RdwvTnsnL>7l;QsN@d_MR z(cggm*s^GOyrUKT1*hy?{$Zf9r0t#Bss_~~>M#GJpJ)n2p1O1M8a`fFU@@Mi?pxwF z&HCoV_#lAo1Qb&f>@0SZzSizRBRn0SX){Sl$P&PcJwkQPUq>*b01nMt>%f__P!z^wHR}Ey>O4^x%NYEA`5h;E~`FEZi zs#ew0Qa`HS`!~~RE;L*Jq+_^?>mQ9nn@kcL^m{S)srGB!H$47}D)QF6wq*E51=Yu#X~{3?R+APM3_cp7)wB<{3Jq- zw9xOBN1rTm<_V9SMc_`M9*ZbWf#3Z6bFB^_V$MCJL(fLE8b{Ll5o4s-vH zZ?#tUBq|4>(gb}lQ3_lVs8$+3jt~nSRssbPxqX!3-v*_km~F{QE{q^j1!inK-IMz_ zTJOxTXn!AA2*Y%<9V20h!pvAx$_}O6ZQ~X;ysDcKum+V)&B5h(BdEGzNn{_`9*#xT z-Sp%&R$?N;#u5sm9!R}DDqp#~l!?%%Bc9(gnj=pE<)NA^xM;ynbfljoQwY>-;Lu{g zFBj7BR-cs@qCM;z7F<2Jvc5+GcST~Yg)8&-pIz#n)$eLVz+ddi>9I?_pzPmwm2I;+ z`It0OkMa$mS*86=As?1Wv_gH0N%dR)nW{F5Sqmz{PcOBpJfm82`uEf%SSW^jFxnX4J?u@_N zt_#9!c6qj{ zCYFW@VFHeNe~}gpogIc6W~*$F#y=9a6BMFCfc`vjjwN2=$Xjw|WN(9aTp0Wc3rV-9 z-O~u1SwWZPUsaxA0u>0l$o%P;(*1F-z98sIt_He15664d3w_usM=MOj@egKd?W`Pe zA((zs%3UlQ;hg>f)cAWyNrix#r@yu@JU;(p*gYEDGr8xWAH1}suL2wo_R`W!+nE-J zr#-!h#7%Vc-S= z5MO}Wk6s@%F&6B34hqa;iY|lf+e&mEfxWIHDG!gA?SSQ^eLk76V}2|XOfe~ z2+$t%2NGil?L-^V6phDW&0M1cth5SetgdwLq?gSVNpAKIK|A9`x{z-w$Pqwt$vES> zLcT1mFE25k{>y0sLmFTPpixnLbm>;0yF%oKx(b`dyYS^hs0mIc3-6cNxAMKl;(t=T z$|5i{xuTjri(O`$5;ulVCN%ns=uX6M-l9J3(QRI%@-|GciRivtjVzHlml*vyT3@=7a*s=|(TW0?ZZSpj5wEidfXPsam zTUb5MD%_hq+H!j1;a<)hxhtW)M#lxpl;|+}0 z_UHdTTC)bS{RPKXiYaQWUr|eajT@)K52OBN?Wlb^!|QRJ)p?RQ>|~;N&Af?jWQ0LQ zgN#Cr=F4b{kt@JD?P8R#UgJ0x*<0TNsfD9+A-VG69w-4+z+Y*S7HIJsBT2x4ppu)b z){_{eYwC_Q<$t=v;lpBans6){=iHy++t*rdAuO5-x<@g;-3^Ww#jk~tXpe@W zyI&aQ#u=V<9P%<=`Ru<=%*Xm^WfAd!mRn4=d(0T>N_JIB)Be%WWyfoR%nt5!y@k$tY3h@2Yp3sM4;?`$Lp@Rt63lUxp9Tu*>v1S#%OO>m3R3^ji{0LmNI7OwNnSv+1awOvu(Q| zhaLTt>*NFdPp-pO^>9gr{y(zLGODdMXxF&A2Dbuj(cl!%oq()RRUv>905ZB{b@-k{8N~oPm)yn#V_od}O`^4n1$R+k3W za-+iSj&a)$O0=IDc#^bz@fd_4fJXAdAhiCghp{?#|MXWMef*pz162EoILDdyU%qCo z*HmMSC-xN6$n!xc7-=QxMqtdbit?Y<9NMf1|N3e+>wK&n%QMsH`_7CZ3QYWFaFeMp zOe0{4=taaKCh%j`p$(B2rrciJz2nNr5Bo}7(G7udY6%vaC3V^2k!VdwKRZt0D{5J6 zGZrN1eAQ9x6Bj-II#YIbd{aty;2v7MKKSKqYtR6q05Kq)d=+!{QnFKDQ8j&HVAFxb zoo!p!rln&Rp*z)KHak>}yo z7oA{tMu5$V{7_WOG&~A2s66L4i7YUa1z-^^E&bHG%Zi?BM_2Tl69HzPvz)PNJ`b@# z7^QtYfIP+zb{{%T(?`4Ua)Su28J@;M+b2SeD0fczo*u>g@_$f{v0sM8e5?Evxnb;W z#T+hT8yY@zl3i=CbmI{>mu&%@BW`2tt$t`U1OE-FNWRBvbLqu-mfq*s4`X5urvM}a zlICPV!@Yd~qh0Rrjh`qxMadu^UYN?ZS!_QSo@x#I{K=?t+mc27kW=RMchbwjHL9y0 zO)4h%xYK-t359UQAK}zl3A#lHSpifw1&uzTy`PFUn1LR#kgZJuINFi!{IAm;6E5Gw zGr*qM3-E7{7ThxW$?VlvGnB}^B=4IZNB#lXhJS>YB(8*K^K7TRcWhZFCxK{i?E*XF)`j?w!ba-C5_+h>Np z*~LiTW)nqs6gZqCfy478B5Vh^ZZY^pxD@maBu8XAsAn?O^UVDrT$51uT^B(^r&IknltOSg2>y; zfH5>_dLtShakZm(H0h?2R}z)?`U&-v33U0SA8=oitD@nE;xxzhSC%YvOiz8kGS>0c z9B6wtGY=-la*(5Fy)x6PkY#Il#hX7s6v`E?g4Zw+lRV5~`qlr38JZ~;d|iLtpXuD| zB}>`+)-`S7GhYPIa2sh6)rC+};Dl~Tp9kdHlekJ_+d@PD5L9jcfE{CQL+^Zhgx(@9 zN%#j!RWL_(&{!P#Hah6n*hAa@GopmjS`s+(`Ov@>*6vj?#z=iIPQ$toH$|2=r%PX7 zMH5fo$Q*KYJ5wbBFWnNa&|U81d0%4d)#CgkqIP{M&cdV1tsU7BbaX2qd0jzFtNy=Q z01Adtamot1R!r{hCanz|er^Rvo;9QbzokGEVsicW$CqKC(IsJopVLyQfEZH7nDO19 z!!FBT;SGAjx%f<_=-#W>*A}F{?jSEqnd+q{Nh-D8EP1@H9s5|xU|im0 zDgy+x%ul!CG|Vm<&(n+>uBy-58@#&6oBS{U_zvg+@>!4DD0YH$;Gkc+{1D>v+o0U$ z=VEom<%erC)O|bk)sv-9_1l?N+bgNis|VD)i)N$fzs(**Xy^B3b1hvH%h&6MibtW{ zwj1uj&Mc0(IAGRDQs<8L|-r4Pz?M+e38&5~bZmT$JXjI~xYFSsMPVHugn)#Le7i9_dV z`$ih&)oqn!(W)2ru`@gVarl|UW1I7@>oY{({6Lej^`DbSIpvowr`88F161cvSCVf@ zPrL1(#)xis{>O_DQ2%_k19QY#@_6RD+EQ#RotmFL!W4u~->9s;MF}|37CYRF zcbY6tv-Fl2m6H$pUX{ymTSz#+G{~T1|6}2@$q9Jc8hy=3FaIzavAxV$fBJuOM^6H~ zSyXDx_@Hur**IdVM>a(w7UVnZAWt zaU-x*R;8)KQcZrX)<`NTLDiZBgQmy4lEDQF30rKfjnh&avXNykE+A;hPMS{w6$7dh z#tJegb-=q54K{kjHns#4LfaP?C9lgZj076eYo>dJd{O!vE`((;-z*!2k}t`hWOO;u z9;>Uq1+xK?xxmHL(Db1A^mB|iNuUVP>V9fSACBjFkhM~QQ)moU;C5a#v3xG=mqRuR z;OES5?YYE@yoxR$%fG$&`uXn|H^~2H!i;Ge7E7I^cqVLV#2@Bt;op{;__D7>Q&rd5 zQVogIlOkSsK{&(piu#Z&cu5y4WOGp{4HR=h%$NCvO$JVA6S*O;9x(zZzO0+zL9c5A zqp3~TS2*Tq$mLUJo#|J;beg48;V&iDzQlCqiGsO#fQM)m(X7er3_>u+qzZ9m;fZeHWYRo0!T)@kpI!M+R34rYtJ@Q4cYL>R{W~kl zI(QNpl}?DT_Yu5Yh;^T_{wKnxuP{jMuQpF_U`X_hIJNt%0?aZ~OMCzns5zJ)q5&uL z&kVfyQDZ|ZMCGL<7yClVu)6K5Cv?h+xXn^y139tjPO_}^%>OFkdZ_GB5j7q|S^#T{ zbVAyb&S2iaAl)qJ`2KK#a|nT9t#( zoR=XUTO~w4=9CjG>A>eJ4k}k>edo34C4?J92+&@eJ$gu#XqqX%w4eHMeGtdDGBv%? zQV>eIh8ALQ7rv{e_O+cvf@1f*+TwC)Xl;~kcQ!GQZZjq5VFeBHnV{J8udl77OkrkM z74mk0u=^MWkOj)dJA%^%)Uf|;$|SNaFKFTHE6pH$qe9y0avy&s+~3-!t()m>3l)t# zpz8TW8D1O?NCiS3y!j)G6kvP#J)B-R&fn=#;b>rM$U5&VkQ7{lq+vrl&>M<`NeFQV zv4V$7=w}QrDHcaWgkkj#$YDGVL*ag{3Qs`7wx>9TpEjm3*K;iLOc1MqZj{|`rScP3HiuLPlp6_4Dh$rJjz0b&eVghU6t7iiKcZc zw5Wnhmzz!V{O)Mp&$*a3N|B^gh0!m8PF?Y@21SI_TKcd7 z6K!!mErRsAMEldFShpm`4)9BugG=qSF#2`I>8exbN{-3FrMRBsO8$C|9p|w{p4C(= zP*C&|u**)wslKWJ9tfydN>jC@x7Z$EMMlCM)S1ENJ5XaQQ*42Abq^~&GjKeNFxaUBFuA;tpd;_p85yD(j)ctq;v6?oUhB;W^!P za|A!%DTlJ8uGAV$?0o;#C4__?K*Jad;tUh5%P0Edm_<)hjY7ahtrw|7w(j~jWl#FG zautvCvK5#2>Y#=>Gp7T64dAYMF2GB~3YKZvM%zo;-y+M5zJ42E!6nNT-NHE{^=7NV zTB8S{OlTP-VEGK3piy*7xIP)vxr5FSQ|-nvfl??WOEKgP zG1=}LV z=jx&sO^Rb|eB}4T^JAtTVBf7t+2(%ZPQG@ZyUt|9L6=6!o1v_+Cs3S`jA(4up^$!& zllu`8OVL%Ix>jew&94|I8Wp#HD3O(ao_b#=X=%*m6C84_()Q}dF&Orl(Q6o;-T((@ zx1%gH$kp%Ih^+E)lNdvM@Zkz!ad_N( zn;QaVSdwE`q+OLrV>mg2V9Jw<-dgV^5N4Wx!Uq)E_T8rKoop29iJ`Olsh&Nh@!e)D zPnCYvm~}GhrHI^wtMr~!FJvj^GqTX|w;5tfCoeanP-UEMe`3h;Q1)iIhl`lO6+tX; zMP?e{Xn&RZui#a@6J~;fAST!lpK0BIN|=P^;oj%NQa^xR)!3oN^AasXHH47#me+*| zE|PSNBF1&Hxtre*{z~2ti?D`TSq3QQ@nrU%OPtY;Vv=qEX&5~ z;VFA|ac9OaaP)=aV)4mCYxBE}M*J0IakiWAxR#qZe&B9Z*awDer)KqoT8OZU@#oWG zw3?1E%PI0hg$JTdY*Mj8tklyt;)j=f;z}Dqy%HwNOTnBH3P$u(aK@GJCc_h_wuBmj z!_*s0NY&7d;v;8=`|A*o2J!FlsqXbCv(P5$n^&~MEx4Np*5Vc$2f=OhK3tIhU2}W(@33P94VVgPLOFUp-8Ic(g9_w7me-YxAG)#HTu` zE1Ryq_Ul2iIE1zRIq&`J=fegk4>)Q%`GQnuZFl8+BS0GZ;8B6g@NUryk$8_P)RFWW zs;seB`u5`Tc^RS@^bd>{-*lxnw7;iJkr5`Y#6s_#YeJL4(8;}}%0sbW=p)BSOAC2h zg5TTm-81A`hD>69d~XOtge37^iT8*lv?&2?-4tallJC>K2GTXh#IZ)?NAI=8r>E@x zIZhA z4x%)>Q|`JU z#eZ`@XC7vhR^CO&0So+tG+Tg~KQ%-cC;8m$CGn`#{?JkXp<*!QGM#RJR^ZZNI9sr^ zbbE7+`GhT6Mn>;~rwHjzQpUPZe+i)18_Sq=bv@;LO{2dbDvT1|WK)yI64lGV9R9tV zV<+eXY6gHgq8_XSM7P1DAo7Gnyi}5q9IE$3|0BtA3mHSCT z!h7(pBMa##4_1!wDKi|GEyvlaO+*5YTM|#$h)92{nttWa6q#P&IGOyH4Zjz4Y=3LR zBhVxe_mRZ-HCQ`iww+8QS0IgX4)+1e=T|R3U(RPy^~oXr{zZ0E#9P3#GjDar2v1mh zb%AFcQjgVtjSoD_JkC-=rp<_r>G^`TuMQ5O?G`q%|DJS;+t4+hA#z#p?a9y5;D z2R&h9<_~piRrX1%Pu)>}b7%e9UuRR5fu{d~U5_x&bCX}AM^-MC?>iw!8GvE;JGnee zphid`Y16cG$^A(3C(JESG<`4ZbzTxWT93@{y#~+>1Us*EKvfC7r=Z#vZVSn|;NU46 zwcHa$C+jhUj3^lDl4=*R>^1ytL2Kepcd5igz%(>MqqUWlEX)K7Nxz{$L&6Ho85^n{ z3L<+doAtHLOPC-3=ogVpxsl)QO$L9Esy|dqML)in>}(Ug%KI8biCI!Ca$|2hio#QU zSy9-CAy@M*cY4H^+_*o2_?S+$yZT5`hwFEq7UNTA|O+- zz9V+W8frnar4nM12M9P1AF*~7{Mo*y{)Xo1j3lM`Zl7Qt3pb+4F7Xnh)HXwhdVQRRwZVKs z>3hT@QXMfhlk;`ni(V!L13N&(wC48K%;!B1q%H;?2zsi(CqH+vnai394TWP;r7gWY zh+e1KnDk&hWfY$TXAqYB1jN-x>C7h5uM<6SV~eF4f->fWU`$RKw+MV(o31cwJUEXw z(}_n+M}`g9czu@|ofONRsG{g$^Bdf)&tf`1=nh2@-~x-#;$+ZAT7`sE+VR7`v4+@z zhfh}H*bZO9!+_Lo@NH_y2)*TD3N_91f>(AeBfav$QQb%I|MoW2-^o zfw%IU=i9Ac@$pWM$kxtlVKkxPfM5<+=MQoIqn5Ax&91)9KpEQANFcPvq&ULdlmRF@t8lm+?D5>LJpvuWy5bdTs z_;5wNA&6Ro|MAFv!`KNw>WRmcz>Zw*n=o^i%h++q#I10o&Jm2#e-9p}%$H5=-umtE zIA=jO>HNtq&grlorcZ`bprE9<0aLxW&O_e}bni`3?L_}X?J7gCgT5)-urC9nRFo%}8bd{)8Mz`P?3@G3ogpX4z=gkCoH);$eZ*+cGeUoa-KKXzO` z3bP#im6%>%5r+>~@_1RG=Ovy%s3;_FppF@c#s{(X;1BHmPPs~c4x&^be2Z(H9nufj z6Fxt#HdwsT`QG%zC?TnXr0zMR%ixBUZLOfE+B&8+;^Uy>^Ew5rO_MZNNJ>D)~)wem?+ z+fb2@4_V^ytDTy}ytt5>@zMuKKN(tE$|n+^AQknPv^Ip;g{Na_vr%l#X3>d!lY3zu zy@f_WmQF~JN2$m=!SFZ-3^B{S2H|C73bekso2>cHA=~rWl9O}WHf7t6iJD**zFJkR z#H%ty^p>B$-XhxKUi@%1W*A}+o{^W*P-xz}=01DLxDWio+H;B2;e1iF*i*EcaItI# z+riu>!o3l9Kh2Iq8OHy@^g|_5Q|`iDKzi?YfFdw0G<^I+q_WuBvRX}&D}QkT6uX+I z8!xn3E^n!?!5C%RG=A^Wr|ve$B#Y`8eI+gm$0YKYNlN+md-x_Bz3;NT677 zMG_7LyH2Xa_ZfAgM-BJkYA9uLpmi)g15>&#_9dZ)paIBus<(G}}bMu7kg z{AQYl?^d*mrbaToQc=VMuc2bE3=l=`;<0~NiGTi3iew{3{x1xh*`86y%*wmkrMkXT zmA3Ci_wlI={s2K|#3f@+oJZ28Ek!@JIXHn&~fWKwYSb#QR>$B&tW z%U_#f`rNI~ecI=$#Cnf32>L>oC+6IDJP$>)9WdCHjXEljJ^8Z~6y1O%e2QdL4Y255 zC8C~*k^L%U?(Uv%{t49sY^Jyw(ga^qXY<)*@63Xp(JYMN-;3_;;b^#!+?R~c4URZt z?a9|fP4m4x8}Peqwj(F2huIIW*DC)fi-{PCZVZxkT`HVco60HANGPt_iS3w7DaXNu0T>Al8be`SjoZB=qZuRAFdU8xd>zi`(MmJ_t7&!cv-hVS3$8JDkduL8j+R(lW zWQpkTk9OV3(90&mgS7Z2UMK#80hHjmHhKZo1x4$+Xvm-g{v-w|pY`A%*SM+#5o(xZ zxC~Wz^m@+)bKOBXnfcVsbLqB3nHH9(HDo(`skWzX6-v$kQupi` zkQT82>qu>jwj0N+PYkukV;wWkl`q_l} zxxzWnNvX!KVYvd)3$x>qk1pkL>Vl{eb5;`t<__RTk2@+lF{|VTR!Z~OUsn>8m?nCu z=gx1eG=h_S&D186Ceiq0lpfVR!&{W^vt{_Zb@mr&P~q4Rl6hR!muH)a6P)(b7`_)B zFDzB9$4LZIe0hv#v#z`T=9>EnuJ$0FmF%FhwV8kUpU$4n)HdCIWqp&pXr`($b^L6m z4;}pARI)YX8YYD)&f-J8S;~1HAp2`~G$FL%xyxVJbAp|%JCo~wGTNP-Rd8?vKw zT9i{hf5XxHFE93))LZEbal;^^VgySknTPe5;o8=xcNEj{uN?Fb%?!yL zR(sHf^+aPvi@WrzU6Gz(3uM}~Q_*n#lsQ|B#z&hW6~$E7=4PC>>hUByY(&cy0tZ9> zITu@=Lm-a^mWUUB_y533E!$qk8Yyfl9Ys_)xqqKlLY@==Y6-+bdx8~}@tIjzweJin zvTl~`P)@t&HZX_)T+~v(T%x@uqi#1b1o<(Q8r@p>+gu0b<>2!efy5YLKq8idkXejP z@vb*`+TRd@C(W(xlU#1vJMCo6WGw6q*8s4V3Wx^iOfX@K8~Fgd;j(6JOkn zf0Jj2|LJb5vL4l;JvK$JYD8=*Tkw{A%?#NY#Y^eoKCYv$z5JEO$3UISL)JS=l)xGp zmMuuH5^5n2y1zge&{$v=88w=_3$%DcMAgkCC&^7}GRKVcto)ks&1AH%_yA}{{1E&L zBpF+Sq(;SWtqLCqz=BZXyCJi=fh7T?=$z%~oAq|v#}81o%9AH{<9|i>iIY?Ejl>!| z1!6T9;i9nm)R|PXN#G-{K(T`JkElwa-hg*C@Garcg^D=bGhf~M@91z&zJ^4gH5Yt;hu7axP-0WGetG%zH{(FCU^-i_q(nmItsHBlEzpOjq*69ZII0p zZ8CTmvnCPV**(CzO?p_zTFA|+-_nEPK=GZa;NjenYAVLAgJa~}_B5!KY=0^Aspb8* z=5~$V{MHEC43mnm%tf7w+EQ>va#Sk$xvu7Gu9CWAhgW0^P;5JfG?EvMKAawFqj8{f z&K2(-@$<{MCx}Q=^(^B2Ec3U|L3MNja!86)KxT0{MJXIYLpwcP|3&cFT|#0%+jXi`A95c{#*Qzn`9x^ zT^mSORq^O!!|*DC=&SkaD`=8}xi|0fuiw{|efotF6$ug3qnSK>PMqnpPBbDYED@)g zdmSXa-k(^UC*|;S5He9J#NyFV{c>%>(0Os2918vHCyS?i{gR^dL%ZyjQ2MTxi~HY5 z!#^oPsN4Y_I>?a(y%#?cq`yvBb-$oyk|tZmR$X=+mwuZSoX86DxmVh_-&gMElkrpA ztG6Z!B-pYg9~meNf7Sx-z z;&0gVSE6!v#pkT1oqEQJ|J2wiM-)QVaB?OW-%lKzZme*lT{K*=3#Jo&fqqix3lReWBPIGs)mT{Tjp+>6H&x=(L9J8FGhg=|6CqoKFMM zylkr32_ZQ+A*-ACO&oYjT>zBPSYEP#VZo5G)r&Qv8!$Guh?DJwefQ4Q7_Tc|RTUwr zq6d{ErP${i^ILzCR^JO3=^SP}cJ%d+h8VK##8H@O@#lpv*6Oqv39yy8=H#-MlQD1K z3GP(utBf6^+qMKanYj^gjqXL2YmS-Icf>_a6QC}i9YooT+?YEBNXTE2A)}+$t?P(H za+dsyNlu}JXs50*!N?V;9gZ73_Mx2*50?$zKW1xwmzE>g>G!qZ=5vhu2g9nNy^0@% zb}z?#_29>=zU_fd2&AJrGjs1@M}MOW;vi7FiyOWPmul{!H#_h&QqeuxXK^@?cq8U~ zQX8F%DH(me_=E}%){g6B88s6He%R1!1~3P*Kbrqz*@T!&ZGqcrbPaEQ$F-9#2n%Zz#K^R?O+UncOsK^hYf z#sVeX>Z6_dVSRM<=MID)yttDEq0%Qd5iqDwb+iSB*{F$!*Koi#&rdA%zzsq}^443m zfxD{s1-^oIiv-g_Z7|mKCe@^&;Vz-HqTE{K;U3alS#dk~`$<9j*#Ff6#IT`2r0~^-Qo(t1@#BlN~U&3+DppG2G8d2D%r6@ipxa~z^(gfa>LjE75QM*mOlNb%bfr_t1;U~0f8QlGW+y50ayZ{0IY^Q}}rQrylcK6p$oN`Uc&89BHB zJm0`x=G7iMzBwJaT&3ShaMY8P<`0aRP?ZRl2j-%m>3Pg~gmB(vO@;aDyQ?tcw1nwL zBOBbcX-oW6fg4~TL_UdtpGqG*o)u7^?Sg}?2Hr>rmg`a_N`1aJ+zBy|!Lws{efN+G zsqKGYvOam5L|B_cuUmwG)~W+x*Iwk0hQADUO;6}6lZmJPfzVBD^v25nBn1vXGLN;u zAUetlBCUoHOr4`x_$X4s+nPA)*4I#{B4u{H+$Qz#W%#N^Rf?l=mI~ zDwmlpa}eWDQyF!CRR!X>nV}#G>wtcIFPDG7boO6O*qQuHzxmuP8W;?~DRQue0xDvgtTC0e(^j~pDjl1-6lLdAu zg0*e1CI*u#LHRq6vBNalgITxZYKv@*F&B4Ak`xHIcOgBM1m#lkU|$)+J87^)Yzcch8cNHf>27bka`{MK45gCYb<*@9pc z;47%w;BQixDz9~c9JY-SZm*(Zs*RQ z4Y04wq+JO$V3tW@d93) z)UAg}G;XcuEk*@C=_CCt->cqudeuc&y)fx$C{M$yM zE%pKqYAtf{@wlR$RxWnDNAX-odWvSe6^_4lkvcF~`NCyTs4V6JXfAN~0goc$ZIs_L zd$K-LJJ}L^{1p?;XG}C4f>v0WUkFWhxgik|v7@)eh^imPw$=u8f8@1x0|tt_P`(s& zD`p$Lg_#jU+cz=p=O&&W5zk^QaLG8&8Xw~)o8UBnv4kG=5#Z@&>Ja*jdP8v{{32Y7 z@3p7G1Px?;7j$VM{vlxXUVq+00Ckv=jh79LzqHvC4`|X7M5_)Pw(D&|(f*Y_$X6^o z3J6W#8@LF5tfnIlxwW4{AW(B6Gx9pDfRj{&WnYHL68exf)Y>5{w z;;E^*^A-cX|4=*au^-l4bHZS7PDy#NIq*|e$WY_#4+SN`n6o>tKl?~&$g;>#vxnXW zyAFMYy~O58Zv8gSR0BQUNZl}5ZR4GkZ-3Hsg;ppJ>d9`hU3asNIEt86%f@M0p%V0W z1_TyVwP-kI*1`Koxdzr!XQw`Bm|;-_FEapQyt@}03iqFV+h3|z(S3;5C;g$fg+UrD zkb7P!)j3EnF%$37vR`{$>VSiBzzg7yEX3r(D;C|CiIIUYLCkxlU8Q)VrG&bZMm)7| zT&=Zui9zBc`RYXJOztNhA2Fuyn|#fhSY6%SlLU-UE_TRzgg{k>haYdkb( zyAcL5#`;KR98FU=D!kdvs<`@Y&38?q3s*)w>NGim!oQYUjS86Es)#qL&1XcFm4-CW zLW_gzgo62Q+!vAtykaWmazO$lh`IxkiP`uFYXG7$@WsN?o|I{{ZJ=A65`7PeR)}d@ z?0GE{bFCe>H=ZjISc<->PAuUN+vP-QZ5JUnSkD`-QgmF*Ux-s%A^HQ_w>8E#)W*GJ1sy&lAI!(3OS;w(VI$XAG)J)l}ecLvM8@q?QXCuHh z^z`H}!-iN1bF^Rm!rk}%+aO7-2j-J=AL;dQid&xizO>F0O|deUZ^|~2ziD@McqQ-H zXBXQY+9gX`8$Qk=#*2<9#;MFu(;5w;-pLAga-K?|q)|QmfJilM$}Rc7$s+vx0a0L! z2a`MNB3APr_s5H}z>xW$Og9{?#oc7Wk8>-*S?bG$=Leoa?>BaaeHbKX&-1#{&IZ~! zOl$)0Oyj@GMVQ(}UygW}+PFY-6^$bhtAgLJSv>eXQnhVAIL3*;k?gxZerg(_H+QXS zO2sB@r(W%+2w@nwd9zW2N6!J@cWCbTAI!8>9Xjz z-Rc8EP_$q53RB;EKRCN(mAUB}ScZ3dFmtw7_pGlGTpr7`7E8R0qPwEq9&w`C zrJ>n~+=Bx*7x%RkbFr^-z+XFmM<213@x}>e)UF$u<_E)*o>sb}kc)O29|3!}Z*k{x z{(>967jmPE$zjHJ7&h^HfOg($+DNAI-lxdLnqQ!yld1oMoKk1|oHNwYKR=Le|11l! z!5v^0l#x?RyY;ryM=V7f0EJgfVwxZEQqcf_q?AC_NB6A z4_T|z1|+HO@voE*1*rLJ(QN~Hc-{cOv=iVJb=)`DNc=;%QJ{&$1;=c6l!zkd*sPnq4UQKABWOPr$5 zo9B*=p}hP1=L)o&Cw5XZBd(JC-!+KhX@BG(fZ~R0>EJSW$K)Z%lgnUFzWl%3&rac!CO=zD z>Dr58OQ$(Dn=g=eg3yYLkFT>!7uw{O=kaLB=4?apF`VN!mb-kk$!PGEVCw}kC`t;G z1N0z5xC)yW_%QB-WWx$%rgoS;;KCwi@1k^IR?vMPUrI zUuOQit1E^d4fFLc+=WdN?Ns28tS(TS+6n!d1tgq}{>#npfVCXb+j%{|%iS5wx>1Ok z#+EkV7zp1e&iNkE&9`1Mmz{2u=k+m3d!EY6mTVlv zJ=&SE0Su$s5CbZy9yPP*3KLA^P(W{^9;S%o!VK-@heISGcoU8q$rBL+U+iEcN(;R; z=vYYDtLSLo(1N(<2|m>8hez0Mv1MRr28|8?i}5qU?9hveli9Y3!O;<*VR;8R{2kmI zFXSitOdJ&c30pWDzeGVZq77Lu;OX=fJ37K=D*bRqC%mxiP)}b{CK*_@pcXk<&^WV+ zFW{)*@m3C)?pQHJWGH?2TYp4rJn`L1n{6nu0w!5~lD|2jxZ%r*GA zleY=(Nvl6H%*@(fGg^rn$B5n_Z93j~dgJ;~`{4PgZq!7;yvq-IKbZcj@?pF-n4(JK zYvRl_ELoHgHEeDlHnBW|q z*Yf6k09UkKaMkR7c$bhD5TBDciCK}x3Xa(A>;JnvXbS{6)$LMTfG?O@3|{rZds~2uSUKNJkZlAy)|d51HS<=##V1Yyo?}%<#mq4z)nMgnLiI-&lWG#O?{pbRb4*_H9aea$xW z+rKKz_LQ6ISiX&>2}hW^gRHL+MVypwWtqKcsrL^c^Y>7HC!YnHm@J##_W*^dy++mu3O=i;74{M^d zdXn;6vXFQT%3n-VG_F2=zIehMr{dK#n40(XQFChWBk`R+RiBY63*%^KwBmNR4lA%J8}HIPpp>Xx0www2T`Gax1cB7xZzvsxmN(a#nKuBu~`+0B4Ql3 zPAN%~Ym?AeQS3*)CfU#-;>_Wu0PI5x%0Ak%IdVugm{i>Nx}VFewZ5v(kgIG6?anCl z{3nHTx6JmAO4}%8Hp#y1OmuS@gU0}r+Z)P!$mv5@65>fuL58h?LMMwX_NnM{5sdPj z;_)$L6dd7B&jNMls=w5nHUb;lihf|^#;io*#^f&47UoIF_clM&fp2;TCEAqJ4^F=Q z$9zl#O`Vfw!EF=02k6fFC~p=Le14&*D~mgxeElPCPUCZ>bHrMvV<-480yEjLa0#J< zwZod7Wj}T^Ju8R=ke*s-Y72lVEz;1v1gXV6InRZoaM^UXvJBS_cO?&MnJZL6R?H`! zf}8!G!ytQWJH=GD;=>*%3l6xsozP^axae^L=VKJ94?ONGl1rlZ`k=8PJGJ!%>kEz& zI}L68+AMA>0aUzgi~Ll-CFTo5geLt<8-dla91I|f7S80^hEGL5ZrbDE-}n5s937FO*dT)MHSt@e=Z^~-e7IK*)O+1016-XHDY`!d7anCsOIwk0nQkO751R+TtQijh!* zigm}zYIu%M!}Xt9-o~QMYD*8yIr`-?ZpJu1Vophdk_#hDlYjS@_RIL9l|kk@Md0H| zc3@1m6e+~~R>&h)Eh=9_y7vBe!>(0P$F!UfGI($1C9T9uvA@peAM;5ikJ_L1gy=b??CBLd#Hjt*`hA)+N=pA>KK{3V41M?fu5iRF z_0QLAi%ln=1_*M+yg<#392l4C58F9$v*a~?NMTl@;7O0h%d?4 z=rmK^qf7l9@Ghts0y#t4^v8UB-`HH&kP)SYz5InwvDY-=Sip|K)A5qroL5mfW|&4q z+@~8CsBq?H|C#f5SvciiqaP5c0v~z{r&cWz*F>^tU7j9UYxo2!!VRn7+16a}9{H<~ z>;*=6AstvD^x>~DLuIoicqk3a&;bSabbEIy#op+(z%-G<1LGI-+L?6 zXPT!4zn{RGH)s;RyuJ5G%CJl8e%Lan?yFyn!MIi10O!V_N#r7(Y4t3MC~|`Q_uPr= zXtop!6Me(;3IP0=q4BTS%es7w8Lze=X_?DT%aza3H{>zpM{N^1Z$g9Bi+Xndxf9U5 zkmB)Hyvw>f{#}85dK-g%mzEjOY1PV&cM=z!8S1^}PIiqP%+JtN6~@V#WZ5VQ;{iQz zyCn5e%4G+;zYhDwLHA!8cfwd@gu>rM!azB^Dcva)z~ptlTMDWaTlP3N*{3?%>=xe) z2**XE%y10~>oN(ETNCy_DD+|i;K)T(3p)rq^`biNp@}2}1x&B4 zGaiZNxUV6|fvZ`{IV{{*x6{`1y&F2Jw^pgc>cQiV<-lcIw0BA7Rxm_TY9)pVKoufjOez2GVk7s0O6D~Jki58 zkiV2S0>WJ;CsJWvhjd7RL9C$2@2<4F1-KuoANkilh8A>A_kbv<5V~tFM}Ddv>x<0Y zG)xZyFy6QERf|Q+{7zKb6~>m3s6;gqC^H`+=NiV4t?b!YNu=#3w6;{uS|!xYkEvDR zb&cU&IlG>##a*(loI-^ZEb*MO69)o zZuSH1qi{Im^Fu54g+|DCi2)})3$4&cig^ckDAqk*P9wF{XD$LV(C4Kcrw`1+IUzs1GT!CZtp#_^}hb0&$c-9(@vUB1f2-3o$EokF5ff5yx>vegv{-MK~ABYU_A z9g^#BkT$~kBonXV!%55p!TzbIYm}9>JMXvrJ2EaD7Cql{oT*IQkcWFiPnkEQaGx$d z(;U8aXb(!6Q8c0-ug4&?!mX&v%VmFS)NtUf`e0qy$C|>lJ2i|v78bgvEoh_CKeiZDw<|P zv`QR+x!H=b+PsM&)}(h}_&=@#{C}L&U6hji1iq2A5NX=9P0T}9jmz)V_s>!ygU;sf ziE#BTC~ci7t6l2DM4MmmNxh;)qx0qI6Kr}h_ojzv>{9p&rkBojh0j(SJV z5I%>fuOx_n{%}06KF$hC?DucG9^tL2m`0p@HP}6WeRIcO`_f$rC!!s6U z*ca$8{od^NoX<`}BQi1SLe-FjVr|~Blq`Gyn#+Kp^K+VJ6p0PUM?KVd|mB;$rthMl)WUW zvu=bOr9QsR)vM+QQ5?5R1=7G8r7OZ($?CB+J%5v-9fYXikIe{st1p;ZD~}KqM!8ko zQwEA69l{6+MGBb@!6@Y>^6xVXxN+;PHA2A3s*55-4n+44#k-6gZVAOYCt{-wcN{M# zwu>^p(_YsqTqA*QCFK{#JDVbqWcG;-`#b(3a4N=FyabH`f~ODI9S41$0Ogpl+p5h= zuJ&ZmmQk`q*In4ISoRGyH4ObhRXor-isU17piK!bAOFjlv5OK^-Of8;vd~tgTYN`! z;HRAc`?P`s6vc0w+{P~2Y6D`v;;$OPTqP@$MOV6m#jNm8JAp;J`#c5vyf#H_#upfH zB(!4Sb!=0jX8QzrS0><->_=Qca-+lzA}-=CzKlDzTeb&OziF9uMVZS8y(DX5HUHja zo^X&r74#w@BhYd+i-^tQ>Gy0`U_XQVq{ZHkJayg*fgVw==aD@H)s@IX>(7E`=R*pW940*@ zXzu^A0H*pEba}xcf9UcoDo)%+=1`>*=X?heeXoqG4N43;xeR@fAEZVfH8>MwL_u_i zleuG^7xgAetwe30>OZosr3)e59rFd@j#8tu9t=G@xf|;5!e08^P9t_B_BJ=!pH!Lu zI2S>OP^a`c@f(h?6FZs^@WPuFdUy5{%UYbA{h2X;XCmb#CO(ipKBHo+5j-!BrO+qKj{d4%%Xgm-1v$o%Jc)xrr@^b zhzh^|*k?!wL;%h-f}zbISMU>R3&p6li1@2ZQe@0_7C~7&c`aNA=yPR>HyG2!OZO1?3RKHHk|T{ zJo(l!0LW$d$Oopk{XLKSET?rGwDPYSExYKHpqAb4w(t)^??}MnPR#nk@3rmV3-vEX zUq*!CBJYKQm4ou{d-5)$jF5vMk!5XK&MK|OW5afjFxe{+aU~<(UB3GQoN+YOMD3J^ zk=zA0Jjo(r{$Mw&#jmpR8*umu{pf<}ESZ&_CC_^Xm=KzCl@1nQ~@z!97Ei*I%+J$+Yk9s4}DA;(yny?P7cWsQ?OMRT;Y{&xfia;?RGJZ2|kv~_Q4jjPAuNi^bvg!XcWUC#q#HfJ+Tr@;9o z&A06t$x(}4RzR})ND*L?wxn;;jXW>~_zoheeKw&bq9;9CtdyO)bI~G5Pu7+Xxa2^M zC4RJrqd*PF7*oJ=M5tm8{%oL!XL`d5+1P+C+Km#{9b<|VfzZGD3Wdj|z~4(w-N*D} zSJ4J|lbK-o@b^i?Q8i5HXuq5?>Uloj&RW-q$olHFc+7cW+!`yd-`G;%{PZT@k1)Hn zp*rHFso3{eP8l1;d%vv^!6qb$&MQdGi+z<>{IbZ5(SMa}$J#hTIqDMYqbt)vl<}zj zr_yE27Xa$CQBVq@fCDaTB0wVgP4~E6ehNM7!E9^kH4++9 z6>w~A%m%KoQM$vdTtuQ#dQT2DwsJQ1D}F~$jWxolcM?m{y0qSvm#(!9+Gr&#LCmPR zhN5i-h#23#BP$$WvI zQOyFr-n0o8(HE;9Gm}(Iq;MO6khm$m=*Yi~3)Plm= ze_e^;2bXrY%>&PSPQ>V%sQ5khlb!UY(gFveEA_wC_3`gm$9A>5Ndt5S6JKW^p7>Ac za_MQ+cEz(!Gc?xzw#2q3@9tVLI^%w0Uz==oz||%`9`TDaG}T;P4{as-Q5(C0c^85W z_W|OHcq~@*nc!4ZPjfKJFWa~)x(mOPPR2?yzSekl0-q$uXyvQ$+D@n>VKDyQywoU%x#cA}1VR9`|1?_fqt##?S zI}AV260uyu3*ah+G~da$d(@7zpNr1={fV=YqKA{C=E0~Nlq~6}tHQMn)qNTKvm|pG zlqxiS4pCHuZf5Fd(^xy5v<-V;9~SKDpVuRe4VQ}-blRm~e2zA<4L~-e@G|TY${-e5 z6RwkK=cJpFh2uB8V_N}I>%M(K0xMdXVbbqU(AP~M(jLpJCnGUHx>5c7rEelgxHcHC z8DkgdYZc5Xmb{!Xb<^7}RbOfNwt>rechmXfe1hUlS}dKCKA~)fE+3e z1=j5kCxOj-Ha)AFH59TPO68o|D!~t$&f@nfmaf2?`B_U{I|Q8;5m;UDj6;h$O?<_0DyvZpC(FbVpvuPjKw*ITc`FUj zfRVmuGx~MnpdwLrE%CY?O5wvyWHvdKhk~wxr~=902(Qw(L!N=)MrFM%nwl zz+=ErKoSmt^&9#<#cE-JdH!b>QP?ntaNPEpjJ>4`IQ2qmTEOtFk@0~J?>W|fSwnt;;JW+a0_S?T1OXoVJ>vE4Tp6cj z-V2xc<379_y_jC2Swg#PdU_{B1AlPWShipD+`@ULq-U|!zW{NSSnlXM2Ov;hRv`#w z${*Hm%F`WZ#DO*8k}$ADb}Ll~VvcO+N0+m7F)tCiAM$?=m-u=)w@leROkNIA1df&? z1_O%UGD>aX58=d|*b0qApTP~!wJjyOboGvT$aKOXq+^(#=;J!zq|WCPmdeETm9hi# ziH|)f-^&JVc^wPuZ_xDTYYY8}BfR!Bf)FV8@9gnfMqyWT?-% znI9{SmtA(CfF0aV+wKn!j))knp3DLYn7k52sa%nzN;OMi{p32 zY4s_aAKfI<>LH{5{7o%}6vHT?K@_@#uLx^%Wo6RK%qtRfieQ|&r5ag$-$Z3f6iPC- z(rbXV*(WV|VkBeTTyaq;JHB-Rc^b2=)(&@K5$tz&H>$o`-Y$P0%x+QP+D5QxlfN|^ z7j)xWmB~kXLB$&w@hVN<>cY&APE0En>Q%(pkB^At(4^x}XiR1oR(}VXW>uNm*8I`P zs$$ZFy@DphsK4dOLltj_PFcBs8N(J2`4%H7WZRmW{Ttq%+6;JKz0wJbw>qSYTXXYx z>uKNodULCXW0-3_e;X>*?%zZe-yPbmPGJ5?=h8X}7qJJ(PrBL&WicbluSDsQEt-vu zS=I4^u65HWhpWfNIB;)rzo4m!MH-_@^uqC0|N*9X* z$-@g@fY2x|ZU4y+_P(TAPM^?bW?kxH$Ic#hg+meUk)Y5I3L7;&r zK6VG?de;?Hv95w$#1cM<%?F#fkGoEc@11q%M+K}+y43WA*}c#9Qkw@D>f z%$bf-Ki`Z}`VmmS7svL2sSYfHo6P*2XiW))6KxESOhc@$MgLhMQ3ElmbfBR%*}#W* ztN7>L;X?1)KoTk7mjcEZ*VHfgLN%W|RcW*!s4B&ruO60Laj$s_Cm&{;mIikOnJ;5z zpO)t4uJV1wxBUaceHoYrr9Mr^*Zv!6?U&N+_b(qD+R>H_D%K-=Y`RE6vu}JSHYMZB zh4A2&pQB17(JXBytaH!L&bJXZ4%ZoHjBZi7wC*$DPb40)teb|Rf=7T$U=;qIUXj)# zX_m{qTp-!Tz;WUf?;%Sl=CBNBtDEIWqjg30o7?sx?GF;!sVBu9>7UX4EPBxdd+}#o z7jnL+iF8~`-nEG%PJ{W+3N55dySqkh=3?Xy3-QL*ii45g9~#U!1_ef7UUBX%*g5qx z=n(=OldYo**7H*Ks`TJHI4c9p8xUbSS+?I{-2L>jTzuwRFxESsx>scXn!r0v7{xI} zX2Z$%%}*&}$YFoPAZwRT%G;~Zyp}N`F$?UN>fdB-s9tY$PaUHL4NJ$qm2Cm1UmHOG zBA;=8jlG;E&Ccn*?g=oReW9CXt??!frFMx4(#u9^{n-{ogd>D}F!CL*I7%ojH{Yxn z#2g1EEf&nBvNI zeX=7frq_v=%|T4#!9EBU0$Ndu87BWgfrMVX{tc3Ed9o2M;9HHhbr}^ffhOOz`Ns{! zy!=E%$M->_E@L+;kt45Lx-zAUr0dMzO+qI!GAWPt-?cE~6JS$qLWQcqk#5S-`O|?A zPi5^t87CN8qYyr+f2L3}`vzK!H@n^_z*X0YaC?e+ah1s+Ngn@qlCOBaXeU_08Be{$ zpHZ(2?X7$g`jX+EG)3=q@B*FQ%xJ>y!!;t24v8tm%(4gW4-tQodAoM;rxzS;_gO&M zZ5wUOyEgT&MXn)}p=3!i+lrlIzC}Z2(TrTmN_C)}vPAPCvp&<4wh%NUHtsa*PZD*7 zdn6zd<4mvs`!v`Ck?#?)wdXey@pfkcu+d<;tSZ*!CY2-a^=fcOjnB7#*6jl+d%v8f z2t?QeIxz45&G=k;Jt>VUOy9koxA(O|D|amomxqDLJH|8req0bB{2~ZJ(n;4DCNuNM z7aEjuYg1K9>Xr`c<@nmmDs8jFrO!sLtUJ7TJ{X20YZ!VPI%^cG9yh`BUQ&v`ts93d z?mdWTsH>uwJB~_q^@L48pnCiH+eBsL9}xJo&j*ZqlFnw?#fa&HOxX=xYa#_&@)HQF ziP+8vhs1ZGy>tW;yPs^jsEWsm)dV|^-8?2&p*N>X;kD5<^0_&Iim4k+^9%xSQ2>9) zUlonvrLeOXTfP!5F0aYV5&Ox_)3#lPfrXB(y8cZeTrg1;3W8eVfzCH}4SGHlU>46x z+y=*xwxACD1DRnI+j%g@3K>2e)QA4?ba81Lh6bV2*Aj8<0eu;Lg@wQG6UthmUC`N; z-tI-@wQ40Lqjmz8aA?sVMp&KimSPX@E}ku?l{_i7AM9ee#l7V2d{#+fc-rg)b}xmW zi!TsiJa>v#Zu$&gq1IKbi`R!jo~IN{$4Aog#s%N!QJL*1al~Q0V?>FM7V9+;IO!VE zq`-pnfOM3Z!(CLZe`B1vQAG}->b&M4=b+LX>A3=;)jEU%z-*KqrEm+(s5H}SV^Cr6 zw=90qgEw}espD9GMdq|%7DF1hl-h&`zm^5*M8@Cq`Yo;nCbLh)%)-qAGpK?h9=-O> zE|31mz$!G6+Z&GX-BfG{CLk|-AS;+JR2Y>{JM8Kg}CuSjv>BOYBeD*U1o&b{U$wQ=yxW-@GT+ARiR;z8vnSP>SE(al-_Xy3r5HH^8kzEb zldWhshf*=1Q>s{ZSqhkspZ5cC%6 zA9y-kYYHRZf$TY1xUV8#y78vCSK+Dm>+FYo-v=Rda_u|6`0rHAk;IhmnU&k@=4fpd zPQH+4J{QtA3#-N#WJAwf!A4zb!rf>l-0@fOgsPW`9j#@?~^wGqyD2&A^t3pQGV?*s|)BNAS&j`$kY1!6l$R#{kNBP|r3UAV+&v*uc z&qfT+hp;Fzd#)fODkGQ_o~>cZ@=b`(N`#42>=UM(BjO3+iZ|@7Nk^D%ExB?`ZGc{>IN9b zd!iZ^-&rmdzJoJ)dpP9N=v4<@WL-gPOGXIMqQO#5c+aH4`iN@&zJSrE=j)MEo9WR) zsSVK&Nbh3;9z6G#FGp@35{GrB0JE+Pra4Kd{5A(d^p;LzbE}Kv33iL=M~h!DT4>#L z00y1&h*1(Tv>0)@v$k$OY=-fjJpYG}KMr>&?&R(SF(>_-m(YGXa%{6J|DUnqXa$EGlIaqrPh=j!@L7~V7UU1)N~X=( z{rA>&L^tsf=S&Ysw;Y0l&?tlgQo5n;`qvQMh9wW$-{PeCgL;zBmOvdl&Rb<32UC;< z@JG9^B)``v-tqgsoQ(N(d&uS6cos-sRjfaKfacf~Yu@8C9dX_|M2l&fMG1M`oWnVl zR{rEu*Zllmk0>@iAbwA`(sjLKgNHHUg5Hi<(6Aw2@^d&t=x4y0`BrjTmWjtmN@hYP zw*?Y-umJZmnymN+?7Am*#{) zW6Q(JKd66hDGzefHyKSH6f&}V%2v&mDuKSt;;dN*NP%2VH%B?F3t5;cUKgL(c%$^6 zDOcQ@Wm|1q{?P-HQ!$f31fm6~$Q7*%gMTdCoj?Q9(u_(0Y^XsgJHA&YxE!m+_AG2qUm>{-MQ9@^wAsUB{*4G=>fLLTAw zdew=fhbup&itDmbG`o-YM4t_rp2msB%+?uoCzwJP!#m05^q^52v7FzWl;^dARuPs^0A{qO3xAK_*s^z)5l4_{X{T9$ks=|ZM0TXF_m zc0T?4>21~E(ezi~ny@Pe+~It@Z!)vM{hu~c`A-|E7a+fX!^#?gmxeqxu=tzkf+gvA z3}OWt`ph!Rj{NaG-eT51Y$)kxTnEO9dEQ;YftLZTXGwo+qf_!NRQw<#gQ;I07TOGM zUcBI89#@Os$FIWFhcDt-N^IcwTGFb}GDq76;j6I?ZI@q90G2ETRI&j?*#l&_l|VFN zf^4DUT^W3jwfaa7TrOp2a)N?A+IKlzefetdH2iz4A2Xpkq`i^P6`DKADA9s6a`lp2 zp`?1dV-iWYN&4?;+h339800)1bfSd1E<8iJM# zB*9B&S}#!svgvd|rWGxc1|oD4lns&hD`>RgVkLCRfbNL-e}b}KrrhYkXOX_!Jj-Oi zZtnfOGN3uwaoFrKEiie{aTX~|F@Z-*o*B#fN40NT{R1tN=~A!VA}<#Ie&eng)b@>MVbq!!68tJ-+@yTaokTvJ;0RN2kzsrTT zH`0$Y(8Ml6qRxg3zK4Nn&oO^iN8~nOL9gqv{8gaN2rDy(k zWc$f7$m<{I41$se8{T_PfHfOjhNp$C#iX?^t|Wk;_Z346_m)T7trts%Ff6kJnN(CCjs) zFnZueohzq&)7>RA4e-KpBHRFZz+l*3qQnA;pg}5`JyXpu8GrdhMuv9&twX;4D9s+w zSQpI!p4$l}8!fN!Mweq*l`G@!VB2wt=fww`dQmewj~7RGEq$O0A!+ABKRn}uTGc}P zIimHfznBMVO~h_s^!eqTIDb06&)mow{7^BN|4*2V89YFhsAiv0OFQsdS6W5T7~89u z7stsf#$nr435y|J$KPC#iw*rcu8)tS>zfphnF;RM4|W0bcw5$3o?LFa6ZfCevA38K zfi0oR6^zV=>rBB5Dhxh6wnj>GWu?@txl(l9;tb-BIE>8J<@SC4K5QSp4~7N3=D54i zh$g%OV5*|cg9|iaXxyH((yI+s$h{zw9wIA2v1Y_V$uLWj@C-#^hQsdvvH&0OctmXq z6?3$07~sj6X7sPp+q*Q!Hr+vOat?KB_f!T4+}3v|Z0g zAb0(_eOb+ebSABXXz0N)wEK4i>ZCHp2M*dI)2wC0O=(J zscXI=7703JrV0kPM?GU#`jP1q-;H4jaJqMv4`W9hmp?w^hj3U=H z7c0&%cLWVdW4bFn)0C~(#YamLk?{A5Htf_nX2Xr)A*$+xVO}!AuBRXpqq#RZ}52+H$<9!j{QU?0A?}YcO~Rz{l9wWOIIW5HfGe2hfHXvQbFy1 z_Rhb-x$?!&T zqRHh3(}mO)_CHx;VJ3!kYSi`>pc`Qmd4+B%<2&C5b8U?K$Yg$#ht>SOo^lolFrA zY+QCw;X4!>^)5^eQ~|Krp`);6SbnCXiHo7oy>>>Nqe8P!aaC~ztZ$Tfl#g-`=Xm{H z96Mx2JDFnW-%kaQ+P%(Z=AnUFLJ?HmAd2%o&#O;YcqK~ILSsadfz(5IeuQ9g-SOel zXO3f3_%;}l?Pa^P-y$jEi-aUu-$T~y;+VRVUw^RonP5@@hyG2FSI0jNAULrT0x4r~ zWPw@6%cXre~s9ZXp!VW*@8c{G?YoRW67%-WwEF#YGvZVEw_IK zk@@7F@g%&uJdw#wYv+2zD@S65dc3+9NQp(G-Rq_f2(?_UP8uGcjrl)BdnHHRM= z{&c+0cn1s>TTB-kRs2tvc>R9LEHdrP$AsA9Q*0ViAj+8<%=gaVval5`ljEXNVm`Cu zqOOnWg4O>XmPG?O^DU6808)z7%Y~_SF=v&ENQYViTeThPL8LT~V3~*oeFEcbZaVlT zDI@I+C5;7(Or4V=XB5Faw##P-A_*Z+5`tJw+-#r(^GEAuS3hE%rwB%?$(k3TK}7plkVZQV>Fl^eWIA*?8wAbzQ-LI1 zoSb&hfLEw;_?sBXS=ZKK@ztgW{Xh1)CR6Yk8!QWv4@h{Ul`bKA|CWJ0mvUZnb;lqZ z4V0uy1eB_&;03<;LJZ^&G5z8kmEG%9 zs!o<#tn2Rq5BW&TB&E)uAd9c|KUE~viE+<$oY4Z7O^aaWOGHXV1I=KoVaY|)CoR&9 z)FO?l_t2|0DJlL|fk4ZqQ0-%fzGaiy`B`L0H29Rpw(aB(dhx>#yBHDLq$l&aCk*a8 zGd~VyBni*H&mh;Omc)4Vz}b6Op@$F)dXqYaxsvJsDG$$B1TI|AQyj2QOo64cW;w9e zg~5@w0X7oWC6*F!&u&k<%2dNK#VLPmagbZ}pt!U9&j9m^xEHqK!5wR}pbleuiR~P_ z4nn2ags(BNg>&v!ZKF196MI-WaL2!~N7{_Hrb*wq3x*iJLA)(dgf($;-x0)X*?E`B z+1)!~q6o{R4ar*srXZWFQo-RI5-Rz9;eFv=c>a_7eez5|F9~3963n`%ive#8-QK^j z-YTPNTgs1dg#1pYx8?|20LbN=4xg!49d96h;e zxs*L-o(+AzfLbd*{ukm#RYabwY1A>!{#Tog%ZJ^1i2(oa&%l-yu<3JZ6-3f75P}Zik(LQVqpeDP(&@wB3{rh5Zy1qO` zf*Fp(TKUP)3NF}9f=jgABDig6*z2TN7mg8qv&9m5aF)_F#~gijNk@qEN_3#TB&(Ed zOQ}08kG?2YHeZ^$<5|JK+ft1!USNsx+pXtbVXen0VTnu*hl^V$p{G_l7m_+&p}ea*?g;LbPu%Ujz4nM-s1#~c) z4tpB`Uio1sNlfzMV*KsGjw0Q{VVCmsw%{AT^ZdnrSzf}hvV}xFkdX_ey*zE#bvl)H zc@OLxeIxyJQ045`C!^6d)k6OM^-@>}?zM(1%A*i>bi1VYqpJ+s!93DKRBj*e{PyH7 zsFIj}Jjrr#I&6B1N_R>Ve|V=*U7-*HTtF5d{Wl%C^gDmIx|LCE(jMtc%Q29hkwF}%pHvcZ+!mWb+lE+UrQ)A1 z_V?JBt^eKU5;q;~QI%xlQUF{x!_76lWZ^e;+7d+i9z&@Pkgs{9l@g6rf;K+6QL%v8 zg=(x?_*^yZoxXH;#r(!wREnT^KL@$2c(NA%v&5&a|cvIxFPCTb>LM zm2>Cp-bPAsf+xGbvBfll0-?nP2z|EZg?HkgRh6P;csBY!$xZ0^dJoqH^BWmF2P&^W z7OE(-8{s1XxgGjc1>e?|zN;t`uE#|cr-a}dt;kJfouA}6x?OF)O9al!dv!o>OwXBv z7TP{mbADHq@lq=2hqfu^#As{^##4BWGy!~F*=Z|GuonL|H+6j={dJJE`X#@g^z>7Y z`)Otj>S0!`9TePWh%T25XS$XZQYQcYr#LcV7ne&yJWal{8eZBMeTz0~5}g8m@mykd??hY2M6LG?_&7=y^yKQBtIoVR1! z?o@5|Yli!Skh5}iEHUPbNLf;5**1!Q;>xd%UvGfAbwAkv!0XUZ%qZJ&Rb2&(6|i^5 zUFMU|!J=)$s-42+y`2bG6qYI`)n-nD9PPO)7Z>zLhP4snE}BXYILG|CoTau%zON4x zCrc(|R#QA`hN1}F61OX=`k#Ni8l0j>`GY2|mR@FHtL9kbUD#%o#iuQEUB0b%%9D3G z_bkMKSfdkqa+agF=OLB)O2hgbpyKH+>~U_Y=4SGwCC!GPD*9RF7S4#puU@UkT9IyK zJ+ikB?6C9=hpjn35wi?PYvXwr-@i_Ax?>ojtBGBh!PAjnfBTz`mzI>D;lX}i@(x)5 z?|9Cl{irvBSF>4z|Mf>lzScD!&C>!|F96Yy{AJ> z&yotpN-`YIDwu8*e#=YDQxC|8EqP1GXa4-dl-ZJu%1(xwGmy8-G~gkpaMhS>xc5o+ z3-Xia)jd%xzed$0^o@G(1zkn`+bv5H(e{ujdAK=N7Bjy#al$so8~QW=_PYTa5Kx>{ z%XeGpd4%b8J2+k^ve1qJLnCKxz2^p}z-+?q_%L^a`vx`aQ$wby33A2j?|9ymcB>E_ zG4OOqzdJFIwHnwtY9zg&vnjpZ?^q6W(sKTAauyvjzsfO?FPe6<;2r^{O>~9o(_$3# z(gdjQc5!4*W=9$b7!$`dbL92zvUG*~65S`D#h|3vPax5x=okb2u~KIJeoGqd5L}(T z;)x~JTS22V^}^a({uOehAV>s^NMsZOhU-iV$DqCF;^-#R(HFpiTBV|=t zBNl;9qzEIB(B8%9c1X*_|A27UlwD;2p$$UP>wkghzXV5-ZMZX1=wWZW-`+VPEg@#4 z=g?53jf7rLV0N4Sca2hqU!J0u{^=(f_BQyL;irn@F+8lW(D$P?kAr>f$P$Vk>0W&K z+8uZuO-0Y1TX&F&Co$J-az%Y_6(;wM%KygOWub8UbJvTmYEt>+N3a7zD2w>`mpu}j zQHr_x9sb3QRX$<3>*{SVH-@goaN)yO58`yaUJxltFgHkS2nMXRAqjR{%=3LK8W#4? zcS~|xaFuJM+J9ThrjQD^9lY8X{F7aSx&6@r9c_m zl4Kd%oaCFIPT%3{qcl+e<0Jw8q==ZC0%@zqGD}Wgz~S%`$xsRo>{Q`1#;JeQSy!p`G;~$+7gT&FR{i< zY0prNo0OuNHR*{5$VOC+2Bpb~!xf})tuuX|uN(cLoy{>s4yvuivOy6k6ruWF(_yfj zoVmt=liNb3gX+eJ5F?8+m5Jk{Qpw#RO40?zG#^r|`z|wOI!$mkC!Ji3=-DDN5j9lR zj7cEc_iK4C#=Jf+^*LRvbU-RJe>8k%s`7JhUmr!>VhI>wPm9D09y24}Al`IW0IRci zN?B1PqoIdmfm4f`gf~KkU?fn>%J-xf28*V613_3Sq3vDr6d&g~?#5MK%KkWTu ze%f_v_hQ695|e}^xsC;fw;9Gr_1m4lIl!{=0vT>lHp5;WUwkc~tYtDEKM*@9QFI>1 z2^+USzUcXKTQ}y2C~%?-jsyU*fwA~M|DK4@QujsvP8 zPL2Pg5x88Q47F%-J*GMRN*KTikBgb0Ox{L_U}W<;d+&6*?CNWS={B2mljRaqvr)|g zLb*r!hf3S~6V#e<c)VAd^sGJeh!(e~$;;f7Fi)jf^U{=n=)TOX z>m?Rz+xD&kZN?<8wx7B8R*pFACRWgl5Y9@=iS7ZiyXVP;un#=sQHSi=V@QR7%ju0P0LOnlKnO^CpEdQ9Lpn z8KLSWVMec>4v(xZr5wOgrk9m3N-I_;e+O2Ruu&EG<8|IFxD{#Vu7g{$Cmr!*i46e~ z)7Tbx3ys$9%Yxs7>kVN@-lyh-JmB-_7K(IYV-04u~= zrtbqWX>-bHgpCVCS=?sg=a1(+p?3qA4m6w-+0_%DrCnYsIIY;9M>tKa(`u3&8v2+x zlGbnRb=eCQi$vB)VONi41s9MEtriVca_NZgZ$TIthuaZ%7dLlBhB<({a~i@wjFwNAQ!Ss&1>;S!dW=AA zy0A%ANG8+BBw#lp|Ctdz`w=p&-9gCV7A6IO>a%glsA0+1NlS32+6ZTa6?T&A7MGVrm(b zWb>cokNG=`tl8>e-KCQSXRid}YYpwf#rei{*v%{a3CvbU2t~DVFqiI{x3{>1=l=5; z?yBs<2UzKreJNMfBAl|S@IySCW>hOPYGFhW3G4&KgI8J0^P5X)NbBKE?y815j@e6; zU#H$&DpeE=yh{FR=&A=Wx&F-`juWnDSyN&_!?sEJi^As|BY_0cs2F9e@okQxdG?4ZN~cv)-OMPhOn>ONji(r zHycKJM99XPFkoln7T?|Y1sx%}kVk0h9jk0&EzZWvc$Z?B++)g*Z(*k!|Gy(Acuni> zxePp5!to5!^5ST-81xuniMXw9p?x%HSC^=QxF9#nY}C{RnkFN|HrNY+r3V0V;E(b8 z-s||z$6o`Lrn4v(Oi#OIlu|mF0&fNytC^wv3PF=;zjDaf^(@KXqYH|L14(Dzlz1iC zp9~@Ssu~e}%HvzpXIa=M7!~8mqs$Xu7)>T?#!ZZhy)5tN=zH#tI{qcsMiHJ_pwOJ@ z87E4WryQ<58%aI7KAw4c>!N{TJWHxMC?i1NAUw%kJRsd3DeHCK8odJEr3V!pIj$!C zm+GMUN!jG}J(JHtC`IK(n(@LqN5@bE&0b~`Ag8I@aS6CZcj||kW1J>MS(XVslu?u7 z<&;~p#JxB2fk}V-Y17=5Q97ycQk68@7iLd;Ky$flMaO|L4!?n6OaY)|C@%0~Q+U|}o+Vw?Vf zNJbA4{P=)$M(H9XVyw|k5+qU*BsVi(;QXMAH66EgG<;xi#}Rj!`1Xp(^B3ZCd`cJR zQBTO$9v$zL%(Ten{5i7i0B<{Mr{~66-0p(sV$D=kCe}>t+Bi+Y$~wP?wk^TyE)m=( zSJC1Z^}grq5EIA(MBaf(d|-yV?{{vBg*e$NaklLpn#rybXpd8s8zYIHct}8S>*opY(AFnvan^;{V%n@jKHGJ7bQtJtV;G`t8KJ7@FTi zv`J4)#xp|rjPgE;R6A%R{vNa%x>@F2zGBm{kQynMpb~J6H?}UJWw$gkKT!gW7~y%q27S&ymHO?U1+2?#h5jHRBo^p%}9(6YZlb8-RN1 zrtU@86&QIZI)ndYfcesY-80QXc|VY)9x8jwWRQN)280qv0d+#MQU!%pu?_1W$?%fBmdxFh$6cs!Lg99C?`N&vR7^1+6O0U2J zHPYmD?rmbAm(pm&A7nUGI!Rvu|DB%qZ9IHbOZwO*{#OQ#PC19y-89C{fNV5Zk=yd1OX8 zq0LXrS2!i~pcio{iu@?2GU(?LQT^f(OYYP3VjhjBvT!T2035n z%qnIX2PAzOpVZX=fjECzxVbr&?)?V=l^KTHJ=fy7geyRA;`-y1PC)I^UF61HeJ-WW zaO{92Yg$V07Q_$9s#noo!UhEu0z1qA$Ei|i(S>3Zo1)(Qz%RH`s{BgJyn9PlA8pG4i+xt54RGj0? zCU*Ob)hg61Ate8E)ti$%dQqZ3AUwLAYM2eT0I<4So`_YSG_auvH5+! zN5eb4Jgzi0<~_YHmv_?roa7>vUSqO$)$KD!L2@=7mL*IpF4k#%o|alnKD;|Ur-^mM zwG!W74osR;$xz@VY3GP|cYKAmC!P z=QFx?YmLf9L$qlm_&{o@~f; z5v{$Hg~#rkSajnDMgXO#y%$bS!wZrqX0tMxkkpU5=__j59UTz0R$9=!MZ^<-;I!!(?`@w}ei8Xxe7u ztkno?p%m<}Z){@l=R`wsz*PJk)5Pdh?n#Jpu7?fpuf|vH?#8dY z2HC9m{|`-985UL4bwRp2hVJeL0i_$H6r>rty9MbQx@!=Sk`8HUW@toO>7hfqMCH4_ z@B7`qJP*&Ed(PQs@3q!m8y4GM-xk)PK2$VcyHOonc)=N8z#>~LDE6WWrkxpNx~VgYhmYJ#v-{N#H`X@TDXwqk zQo*5KSjIX3uLZD~Olx{600-d^db953fqRE(BC6`{gFewapnZQYMp7r}^PI9@a0l$A zi#`TM2Pq;b(^jiOg78TiG{|h~ia175W;jW%eaICfe*D~3{NCZhlk#((i{Or#u0NnS znyHBbt(zI4p;Ozoq%H%?bS~Z_H(U_?CNled_Iawhc+pcsdRCfn8hc#vP;g`#Gby#A zT6i=O;H=5atm{l+&QEZrs}!9RJvdG@aIJ`zGZy^1$)JmAVsrJ2k44SW7i#~b9JJ!* zIQn(3hA(du1Pe8sLQ8HYE-oG9=8U%;bmNmqhvvQ77;a1p&H4*4$N68=$tb@LO=en8 z;E6o^g(z=vY#0|A^}_Sw7d#{TO$f7&L?=sVRhS!;-Q=(?RthnOnwh-0TC^!lly21! zB@@&NoF%nYwq2Ue#hQG@A(iI{(~Qp(xD+(^Dq{7pb#16!dz73HJ%NL*lX!_uqsEAC#N4vbV zP)o=8HO+-Na0WffHiHJ3q=hGSCF>96A+w1R(GpHDPB{u?WvH>;DrPMUjRKtnZcofI zJ78trlRtKGv>O^i_q{xSTzcsdSA5L7OcD^wk__V}MGf|Fv5|LB+~%TVSzpnC*oz!) zz8*nP$giZ5Z%xtQ#lJa^y9xp4qg>w^Cu5u666c8iHPq_#_h&eN$?g*-&UdfWu=OkO z>DS7>yJTBr-uJyf#`|jwE3OzgsUE7J?c($6IUG&_hJk!B1rEoX#j|gK6LdfzbXVVz zFWt*(@l@AVWEjQHg}8^_A!Bx1+N8bq^I3LKh<^OPlcU%I!N9s&R1o@0G@}nFUU3R; zKTZ0d^Tl_E|G@N4vyGa(IVR?}?4casE;gC^I~G72P}lfZlDFSGae#|+)w(B9*VCYB z_!k2#RO#fo#az`MdDfD+N91r4IrM2eB|7Rxo=E7%Jvk(9C}IeN_)1bE8CYI?r!`X} z7wC2l(?S=ICz?IDfrtq_mvc~k=!#upzW79g(bX-PUXM}!5qLC*E52~)Q%{h2wrna3 zyQS{4K?*RP2a#kVmb6a9;m#3DrqDk)HIlhv8hQDqK-YGkB|Qk=JXyJrv)n2KK|a8R z^X$qt>PtP%wnK?kxn-a5E#8oGHR<(tmO%OrqK?^UnGe+A)R;?MMDGU#2jqm4G4XM} z7w!k({?Q$MGf#TE@TGDQA_PH?gxrZ(X6EUdwDy@RET=fC{#9nSqOW%wl!I!?RY*W6 z1yuSJ$qxkMY<;%l(PZ#rY;g%u(}&{By?4GGFquyH7o>?Eq=3=u3QI0?Whc@!mS*%| z-qU-1)@U$2n0UVsJ`+AUYP*d@#||34S&ife4cj$3!!8BHZi zeb$=EtzQc}QW=%DHkcn~35<>n`!YE7v(r}9WqYP^l9py>&#BXwzC^TsUPxc++eEc( z&A$BnwCpE(^JZJr(l&0QiBv;CS(Q@S1ph~)&OU{cf-Gd8KI zS@%-Wf|40I6}m2N3{aseo2;yOK=0~N?%Vw)$$`N~eO4=T@7~9-*Y!RuIJq{P{H$+& zY434HPySTA`+>RAv|amC^5+$<@>1!{yRey}8~Q29N-d}G;Uc0vbqy27pQ+Rl_@g~x*V;+%r0^AvW zf*mcDv4+)m4wucLl|KdVMLfzNGj=pj5Anfu-SY_bJerTqN10{s7JH+hj2x5 z5hS6Lk#`9d*G&90ih>hqj7D2S2g7hjEh)aJ6_MG5Td~Io#DoxP;7XM(C5B(S8S-IRS!`n zS!gQ5)+vjmQWQ;=Qlx!V*SP)-$si?aLCKKV&Ruioi(!<<>ccrDN?fg+xt03_yTweI z&6MhUj-f3cQn}ZRPK`JT;WPAqbrkzZ&=DjL?lwN;i%CJ<4q-mh?aUVcVKAF}_a~^i z@vp|G8V;~w8>BnFlcWP=1b84hBEO43X!md-j_IIh$6L?mtfo9ew$df@(@V=A)UkCl zNd?HrxX8rcgrBGMP)On=vEh}uXhx2oLpQiRvEiQ5?$0G&bBKsK@J@ym6qkC1c;c2= zimEmY^#l=tZHEKpJ%f_Js+POiSjb;LbI-p(KeuzCX_2lpm86xO@j$(4nzdBAqfdu3 zuI?+t)}P`JB0e&37lui}HR`8kcax?$D(0w*I&q7*%|BdukqgPTnQ1-X;%v)%+6L5O zCwaamUKhtHG&FS;{9|K8x^H|yBOcr|2AO%{s`S{|93q6U1Qb>3x!$PPhbrN2&OSR!B`9~vKGroS^k4m4x zL3^XoJ3iLR@Mqho&xG4_QYN1A(oMc>Tl$<9#Gk((Z3=q&9UWX-*2=8anJ&`K@u_BC zflW5qlftU*KtGY&LG8|iT|DLFtBwS`PqC4~_4bXFm`p>A#GWgtc%|*Ttnt4y1)^Ii zAJGN|MuZVh=KyXjQS{qkZjYd2-ivcKR%*Y)*MW2*h<&W|G;zGQ(ycBg;Em3&GZeRC zg#L^_*-qRIp1DTk6a|b>^V@iZ_%d-SkMHg_ojOq^8|~7x2N>-R^G47!odmz^zz@b* zCOF|%t>tHdIJ)T?YTTu1LO>y&Y|u|wQS05dLT|XN@sI3 z4fV@7v>vlbC#o8oOH&W3r&Yczeh|!?84Nv6ielSGG9GS#4N}}bIsgJe&><>}1$E=v54YV(v8J*?iTuvo& z`SH;i>u@#(Ph_RR*sBCk3^4GwijW0*g|KuXg~ja zaf5~y^xo|Q^=#6t;k|$QfMi+3XhCY_xT4P<#)0PDpgLSN^f+Yy(7>fAJw4sac)3R< z4gOT`=S_M)P{4P zJ-=%(`t-HanQdU95ZxSV4^-gzg-q=P(W|vR%ivauJ?!4QHlpOQG&DM zgCOdPF^Q7?SOhzhl;_Hofo}!ZZ@1rDhV4i&ASTm=w6)qIdVvV)>)RtvbOab-MMm&A zQo!_O)=tzZG%6^f!AwL3;v@-EcPKg8i2e|Vd&Esc?{%KK`NytR z{Wn=7YZi`qu**7+|Mi!USKB1$FA@TX;Ph^0t~xnEE}RrIG4`#QaqL)^@h_6?F5+7i z{0;+ra@O}p5}Ob)>@O_cfv?W_rWo(}jo_v}@sl3_sy?X$vPf<3#L{03!frECq*eroUuK@Gq)VprcD{j7ee>!UL!oe zlpZ8sm^urMa>c+!=M_OsAT$&j$66}85+L{TE17m!HdN~u#p+^fp4Lupv}9bB0xcER z8`7FaHFIYX0KMx&UNqYQz5^Z2%a;~Qev-85;oWqHZZ1HWJTn@_0E)JJ&R}> zD>vbK;oQp7FaFWKm!a_pyPgDuGauX=r{*D4su=5EMQ;mLn$C@EdTC7;Ph(_V0=mN5 zuKzVSqdE-G!#-n_{lYeu>NX40RjSZfSOHMr%ZGCt-$Hw5+e$zpAD0SCJL{1-S3z_Kv5rvjpxHQ`Jls6aiKudK`fL6Z>w>vf>0NBOarJZ_NEjL*v#mMw_IWi%@c|vBnlG*Zjt7-ijvjaY+Bd$MQdSX41; zj?dcy2lE`7HL~<#%=3az`R+-jz6twLcD*IcD8#>6WQ=p(i_D8CG&f%}#*6>RGt*d8 zA&s<~NH^+Xf87VG!>j@`j?CWtXsET;#@cYJ&b*XP87V5dc0JNF{W1|{1RO<38--04^ zWiPiNe5J`g8|3}I6TQV|a!?opTn}ntBdoYZsTBCm@*VGcxEMrifK#ym#Ll~YT}mNQ z1ijLO&8?PRb}8FQ3Wn``wlLzyUHN%T8C*}vB_W6HwKy335|up$qM$FM5he+IQjwbc zUuhxW?1u;{?@3?fA_`w(Z&L?rUH&R@-K-s|8Zs)&%z`q#(q}|@x_rt`mHeMVrLeNc z6d^<;m#>D10|z_bsS4~^zEYvgo=3S zl0rlD+3{;df0kcffkB?vuSa~^3BGz)KlcAC%<9SqB&jAH&P&HYN$Ybj3Ezq%;jxq+ z?}Unwz0=H;nG)u@_!%|(o0MwmHL`t(bUtqlSEaBkmFG>zhvi?Zk~J;)I|{O+J(M@OlhKt}>LJjjJHHteT9gWY!GU;M zZ~G4Az3I?XSK+GB?&PZdQ8vyop^i!Y89zG^9H>Xr0nrUtrISFXA?|UFW|F&TBZ=*L zlt?4@0T3;`e-{h!RcTyw6y6LP-*(W|>PwFAP`Lxlw{8>?^sEISfnV?BudP~xJo}Y; z67I7}HcX5Lj`i!}eE%UrRzG0@{lk4IdyM$wO|&!m)du#z(h9}Tvi3tE1jfrA%kJBp zLcbe$@4naM9J`bGw~punx)83PPKlLz%7&iyCdQYa&)@l88kijXGO@1g++(KjU`&O6&Up2({(3qiy_k%27L6PloF=M6ws=-l(vT;U=(73Ixg^+=ze?K3tHrK7SBns2W0RE z{=b7GpHOQ_PvVBpLjMC?HkF%F0iWI~@&!h6K!8M6cs3Mo=15%dFJe(t>}hbL$g8f| zD(COuCec~o6QDZ#te0Xh)Usv#4jUmT{ByneyLo4R*yGk(e%{!XU?dz_!6k9nqGzu3 z4#-(z`!U+;o9;}ZY1(*V(q-jdzq3KqXblnwabVfQ_-;BXu&Mo=VrbeCook?WjaBW` zMC2Z{laXa-=$FXt0)4@20pi@q2PGv`?sMiO3^)a8p@4%Hwvd8VIO2o2wo7*o31Uf- zZlfgOFRpN+{6rZZp2`zUFJUks!d$pZ^Ezvmg+Ptlg_!pB(tLZ7gLE zv0irdw4!sC5Z9N=@pSOVDx>Cv_$6*`9JGuvK?5uUMlQimn873nYLdbftmth!++T`> z?|Nf=DetgCSK}>i<#?p5hPndi-Z@@<%G9tO(w=G*ATYtI73o+=G|AXwBq6H-#MZVw zN5hE;_g*^ej}^`t^GV&J;x8r(Ijk9BrjZYHd(Q=RN*HYTaZf>{MuWv4?{At`}T6| ze(olvZR@YN#cBq=Udw?j;@QtlaSXy76&Vc8)Q-42!~-|EY;r?1dFtNPzB3NynOiDT zu`#c)r?|PXmMQ?qjN!uCPRv4QAB7XK(xEXy^wh9P^g&@e#XI>at^SQB9}veHP*PmY zz!U1ynT|6R`wN8d9$vuV;`I-9fI-Ww8Hy>&XGF-6q#&IkuMDt4m|H2VRHSc{Dfgx%pEed2R(uk4ADCA~Zo_~mp+8_2-gEu%cygUZ zr82$(1Vor-HqhQ-i@IXX)MT#Q0hOxZOcB1_omlbbT%rfS+1@*zn`BmIEiJ3+XsYmX zNS0G8GP}TAvSAfCkt;ErS;b^}PMwvVf9XcYJ8}Hjt}*U6rS4*aV!k&?+0vh(I7B}d zO&ywJcDhW%K(2VjHl2k!@Qm-;U(wkn5A!h6@01g_vk=eGTentk8FjjHi9)}Tq85@& zR%09I`Oj0b*m^bpm&y=+U8rClx_IT59GN4Pqn-B_683_ltIbHM13w098hKA*d2Q;i za~)`_OXgGUQKgeWY00F1J+7}B$^&*Fm5Px3EB99=U;95Rm#)%i#U*^i3Xyr0Tm`RU zvysZ@v&I||I^ijytJRSk{E>2CEdrm5JQ$fxvHy^|8?W>N6eJvZjfA2jZHe+`Z#KUd zBJv%&*%e|+l1h|zdcS)3`Tkeu_Yj{Hr&#N~4jyk(!5_mskWOs*W8&H;PX`H) zhpWp)gKRk--mAuRrwTvArgKpYNEySrBzGFbF`gQ1?%3nx9d~LLR#Rn6aE{g$ z5ws(sNAp01+TJ{Gvg5s8vj{n-g`EDjK3=q;FU$B3{vb4EbXQpKFX#{Y&2o-Vn;YZV zwxzKk`t58h`IIl_qT2b*Ww|;9x%k=NsYTIS&1!gtmu~=24x!V)QH$3B(7Ep)Eg;ff z^{E%SgzM*G3{J@cDq{+G*~|fY@zx#T6nZy!1}+;`e98}`2KBPlwNksyO^1$#kD5#$ z+dNFJo8mlr#vrc)@wWh)0HT1#c~k0@TtQ95$(d1*hF7|(y5E~c$!*Ky-T2bljTk>} z`Y{oA>w;2};dLsOA!(>~s;>u40QZXJI{&hNoeP%?0B5em1q;w2$to@zJZ8tA=9nlK z3W+)ZxZFFGJBIx5V&tQ#0Ih9$q8a0u*U}3CMi^ zs6O(;APLHy=7qB}^=1ue!tN-;9K8&-`rJ z(o5k+143BK%R69It^iSh`r$H=Vk`$gJdb};*scfq({A)q9EF-MjQ>PH`qBbye!LC7 zbo#TV;^*LJ^Sc>hfp*FEw})p>xcJM46hHh-hYIU=3Y5;N@|W-aNNQn5XwuiUOTuju zlcjTi$Dxnj|0wPGX*{8y=^fM^cpZ6-w}JBK2_y}p7vl!$e5BZp)5J=#*7;cwJoA`{ z{CuOJ!~fR;$cOi)N4$f}?FU=|1X1wsvyBcDZ$z$b1(D!@kYzkbgAj)_Di|p@P38L2 z*SJwDwsBJVx*M3Wv$okwYDS;$_=RkkecuJO!G*B7?3vkh!dd8acLg1S>dPOVMk9}L zON#Bo1a+v^kir?nTFzs~F<%wm6jMxx1&uF6+bE1HTcbFIr$m4!g@`#ukR|#K8Oz?P zZW&1E$&iUl;#Km*{3W9wnO6zT@_+vO`bu_<7Xr`b8l$r98#eDGo zH5?*e1TSBv$sI-W0d8k-d0lH!I+oZ|*ELtYG+G>TD$$Y}iM4K|7 ziCZR{aE%6Zc@zBo5v`zk
    9eaaTW1f7!oA|7(S-?zVequvM*2y z1ywMt!n#f6^4H>WV}aK6VN0x%gPMLMMiTER2FQzgX?Ee585J8Qok($V&??fZszazv z6gmw?_|jy+TCjP0+>%%FQm;pfuj#=>A+~gniEtT@cle6#urz@;?jFM)Q9`X9iTQ;0 z`y#P!v9#TZBMIsWrO3phDLvw7NrQIp|Z}i7ER!ggzpas?uwX=|JtYdUKfbSoH zP-yntcP^ahELrODWv85cE9}`Xd*fs#vRl*y9J%UEmA3lN-5N64q(*%jec)}xZeVt0 zL)sw_77t^|TFgsUf=SNFApFY7eZ>x^L7!UOQn<=^?w%1ahN7QGtg-ceotwx}Unr~s z0E#5M9{3P#KqxK(-%^s%{}%n+cayqbJSgb?*2lHfK>c5u%?MX79u?i~Kx<0y&>}{b z9M=6eBAAS2k#C~rMO=q7kZXD*vtIHTE;HvBk2>zLKI(acTp0{LkVr6kep{_te(M1k zd}oxn3cxS?nNoprrT&JG{6U(#r-@}{=q-b|)}r9&yxFJkR_|#z3NMRv{W-28)!1IYcA!S>WH0=2PbvIaN8GCBhVf zi7w-!d(;{f#j{l#$h=f3QKH^<@IjDSL9C!JS!@0yl6DyTU;sPIVuL`T~1XKiD1dj-l zB=ki%*^jUTD;>x(+3k^Pe!SxU-JpAp(f{aeLWxJ!bBM^fXIL9d07d?6S9>RBZ zjrmJpdeoskmyaIJvt@Uz3%gm+=3GQd_bllxhA*WrHW+{V_-kwLYb%RS=5p`X`d5tW zo|%oQh?gANi}L|*oxRRJ}nFrqa@ffl~M^bKlfRgXIos5cmFOG1)Z z2cH<{S9d9@*$j|sP*+pS8?OykzG8x>OnA1(cfY4++!5=;J0U;$dAh~zD9gC34uB19 zsv;)CMb-Q+zZ$J7|Ds;>FN)S`?)OvJ4e|ZK7=8_*U+?)P$PLTgG|l7H9>bvF`uyMo#Y-Eh}n6myiaJB!K`Q$=#Ah z;36hcyx0iLUOy?rOA8$IZOp}>i}wQKm;uA*B$wks%!>$f5)AR^-Ec0WkngtwV9l#}DivA*yX;5CL^9s}Eq8!Li*^{P_MI zAh^)z6mkhr)`$YPvevb;h#%Paq3p*JUDx$dC#?p-=(ZlJ;<0Z;(eb6(41Aj_zE zgK(E^)=0z)of=k_D<&!S1zJJa@VmDCxI)zJqZB5b0S<^B!QfA>K&AncfWR z{jp({yDGncTnqHj35fZoKSfrHtB~pv8_7QhneIgD-3P%}A#AtZ77@ll(Z ztj}ZyIN7xy;%=|IuD+pe`-;bU5!x*~Pw^$A2Rv_6oC@&q*b|mm zao~dwi)?Di@$ohYCAbn{a-uqfOTMhuJ9-x`{7X6p-FIsvdjDJcOve5k=^_zax-!}q zwi8I(w|MYB&XO$fWrM(fIdVD@0ykslr+cq`Dbl{r|_H5%bKqb@D z1U-J2YEqjjZzTrnPM|AGW0N0A&j^uxtT=kOl>bNY7z$pIMk6HBzE4G;cSg_bBjI3; zB#!tXxxOrjes-WA0Ti8S4ikZI!{;W<_vXvT8DzUuJ}W5vZUp&b{S@m+6j=JH0F0nR zgHRChyP1LQ*B_YEgw|HBTkS@6LvSy+qrBIPk&D$+8oo7q=KO6}6myM{l2pxq+4nz$ z0>>ikUkwKF1=923&$4$KSjXGGH@`CnhWcZ}RnJ4JS*LR%|EGU?A3J#;_<{UF)H}pV zV9%ZX*nAN{J5o~~blHF2!d%h)iR)!9`;j>(3zz~}U5|97U=}Ha^$l)nZa7PU?6|jq z;J(Or>n+7R8-bNxCBXR>pBG|JHgbS=QsNZm?&DZHgQ3FYs*@#E$cD`g^XP?4lYf5j zstSMKbrhGNO-zQA$pC8A+WcFM6%tzG4Aqa`(Km6WFl!CUZuHQ_w^3wNR;+`u%d>fV z(fWFNdKDCC)fW<2V9&BR-EhY(8gBe->W!jWI`NTo|3;2!{b z!#MTLudh{K*r#VnOV&`!50Wi7a)<* zHywk)^8ev5{=@KgigV^fV)$3}a?MOuK>|DDR>rkc6a#Ebmvztbe%PJwL8@4X+EbfA&)9c7O1f8pEE1Nq-hqX%t7NET zLuJN}K2*WJs#Jp)<}F1om{{5d_D_vqsp)DN$ZwS~DP# zl23!$N6j&xOfHM9qDMyb*V)YgE7e?AYb=Guw>0D1wAd;865&EcGHIFsD)PQ`B{m(Yvm?9!y7w?tC))N-qXRaNDK^80gFYJSha zO5cP82xgVsEO$|jah^2{D6*_2;aoZhcky$i^QGTHM$Kr7$c)kV7rz!H98}-~?p$I7 z1O)+v4kF9U7m6YUVFBBI6InqaoNr>1W{&MfezTolMd9`8*e3Bha#%Yx2c`(YWA0r+ zeXg(<>Moii$mPsw%dN<Rk;icP?e|HS#o$ht=60!E=5Pq0IcGtAi z9aJp&9nm@iF-b^ZY>or7pj{#&A2gVfHGS&tfpTS6m}hj)`1R{)K)t6Vr`I@YnVeu- zvGsNtX7;%Eo)0JeJy?BkhlG4z2SwL%d|0|mzeajBB>)NWg&cK^AG@t!|Ezu09uE9Y zjV^304$NF^ZvpGT%El#n;LW@if^{C0Vt{RGl_!;^0A&#agZ}x{gf5nFYH3 zL{r!*DAQ-Jc)omu=r4WyWx$oHElCe_AGAae$zZ9y5h$k zRk;scNJf)JX-BCa@XFxvj1cv}Bf&kAz0<&9BG6+|fKuZO=#ip#xJF-QSwGhvrWS6k zhbc%uXe!2OWQrt`{5Y#kyy9aetCq^(pFYWpA+5q*^U;;-6$eL>wARIeH!*fOcKZ43 zv+8IF`5eWlH7=6fmIUAPrS-SXIg4jtZ3+0@Q zf{L1|(Cs9ONgW3u^181t1v6f~6#Fa4rMjTZviLGqF}Cwul!VsY$4D{O`a7>itry^= z&P&XVTEjDnmo4{=)c;xaluw2k0IsX&fMHQ+v+*agl71A(H;B+45{dAH;oGs#H6WQZ z-E5L8z=SsX&(j?t-6IJlKZCglB3j7;VWR&>M#|RfY7>9qjYR0kCL-$Df(~BbUly6W zteBhUH+Y-e|72EKK|Gw{H{I9I*<{V3_JJ@#0ZW(udsM*9BkySk zvB@~_7|s`8`JP|9ydq%i*P#L`@?D6$cOU<-V3?#~%Hhq7WBAA_D|~IQ6AvLaNaaAV z9UKj#m)$Ejc>U_F*qJVXU=t@AM=S3vv?GZN=gY`y^!O{G7NooWX5ZV1%|i%T6=MtP z2>h_Duzbxl%AqO*OC(3?3fHHkB|c@7vKiwo6jF%|?BXe%*gt@bA4D&z*<=U(4%Zw2pOyj_TF2e8(=~=q{F3;u4iQ`I z)X=y$afGB0oVdjCT=!dJeO1#&+uhZzLEc0KY65j6Bm=aezKlY*LeRYPa0~q-32*;) zaz9@#ki%9ydX%vrHi(|JCFO3h<=YD=`OA+dm&Bqciz#X#A01PT1o_Uytx)uHb{DRt ztS%b^TTFkPir@m81E|w}RTeOqM-)osJx?;cv=BiR&*p8w?wfdn{b;xlbrr^JWieZX zn7JW+cTJp+>(AH~P6v`fm$@8s9re9YRMuHPuu5I`|L)-=^eR`S2;6rUqQxQW>rDokVuFP|!QHu}(uq3IS!8BK4n@^vwI`>U$>1AjL_KKyu<) zhS|7WN5EDPUD&CoN?iWul490}!ND$f^r4cgE|jQLh;*tqyKb`zYKGTM%W1XY7H&@^Uq8-3~GScUB3HKj<3oN;oRG-qBO?9&q6_4{Daim2Kgt!KUa-1&YXc+?;Imzs0J?KnUppbG3kGx~ z;FHu|=izlgVG1A)HD1tJ@L<&%*8?dTjLjX;7_RHHmZddX>GRGWK-B3YK*EK(IX+Ac zC|pFJUq;jHl0TE&$F?CQ5yOoZ;CVPh3!Cl_rqpElrhrYoCW%8^5R3Z@wFtFDFNYx! zLpa;2hq?)y8FtUMJrS`6n)%Tg=VF`O3js68DC;p`3SEKd#K6oYjr)(p#r*!i4ZEuS zTw5-Tzu+KVVEyGir#i=&<@xLPX+p44m>N2(M-x^=`uZ;nsO$6eQaAxF!2qKqvHeXh z1?k6-KM`jI7ue9Ve6V}hOR;w=jr!c-4bL`=Ob24?S@X6D#$)Vneo*$&!hauR(6^qM zRrdj+oKIarvTo z6I}uLiUZmZ%KONVRtv>h`wv4i>+VJ6bSBmJfD#xV?_!92dL}x>1c?ws&>Yn~EnwtL zbNjqiq~gogRmg6?*A>ql%!~PVfiBTYd{0t@>!$0#5AB|$fFF|h#TwdeR+V-P>yZc< z>=FK@F(U^75*=Q#Z>cW0*mxP!xe}ZbOcHJ$B547>704}_S4{x?x+dTcmbTos$J(Br z>(?Hh8*jdHB8wyioL>e!3Zr~+@MhA#?%vzk8%9(xReR{Cy$TR3?4HdVXe7`Y_v%O5 z`h4tZqqg(ynL8mPlRSItrQ)>_G^)T^;)!Y*N#Om#z`?`QO7Im&=cmW@yQ?3SK~T|@ z_j#zqc5MSOxKVQHg2}YqU(yNVUM2RXM(y;ngm!k0O&Fr@OY&>GEqUuxUk0r_l6rjnyIk2-V^W8l8k9P1U-x!F!FS>3C#lNY zzo#2#S0vX`2U)W*l@uxjr5Yt3)f5MUvu<*!vx#LIr3%UB7K&$xcH_sqz&3ae%#|wv zUssYP_11typOjh@oi)x&m`gB$g2OS9*9o2;SUt2cEiN9b~fR3#;FR_KHx2}s801*kZ~kbqGBfD@J)8Tp3ct+ z|2Zgmg^ujcwW=dM_(XrAbIuB!9Uu_TAdkfhKKpsENwIhBShq`7;_{|**@4_ZKs+Ul z*y;UiVSMac=C?FGMVbj*HuHJ=LXZ)(Fp6PqWnt@XVLu=Co`U2GFa zYG8H>p4>#0UH{ld1yVThbzU%M^YkH9DONy90 z4xuu|Qe^@7AkFiqkapr*8b9@uWSRyT(bRtTyj_)tZ))Hkv1hM6l%Qdz934l%4(F4~ z7xs5dHtr~)kbn%q;fF|8n%qy`hndwt)YRSWN9x1=jn6=0aX=E5r(OfkiJ5X5xWD?W zaT=z5ZKU@sX{L%T`9aVsWglI>7KY4rvE@5)`hwl(Jtqn5Q_@=oID0t8d*}D!;e9BJ zwPtn=S_hl34^}OFS)L8?7AztzD`+7o_b?lpv*2>if`s|;T_Lx$jx3Mg=4!dIc%m42 zJi+3ea`L)nQ;)siE!L~pE32Rv%a&;rN;3>$~yi<*`Nq0cU7ul|OtKB3~}O+)(2 z8pF%V>S~IH$jBynxU7@!CgDI`)Z1?5h#@cm0by^XxV>G*X=MWX#zZ}No&w_h>{|n8 ze}0&vb|s%%cW*7f8q5Tq>WT46QGyw3d(#uEc#=f2k1+4_0w1IXvT==~+12&2X@gp^ z&k|{^A(^#)4o{;4_-Br66B^Z)-cDEN=nHs?Jf6uT3h+SlHmXtLZ`+5rOD5t;iTEs*j~t-jTmv;-#3Y6D3@F6$SbG5QH`VZMv0v5RVp5 zWx9QWjl1~H5hQuHP~?fF_{ZwP^p?-hkWc|1ZH`o9{rk_JjJUhw_TlZ}*}pr(dzQa9 zEm31Et=aOD-1L3a45eGCLi+D0YA2uDh4CPDnCilN)a@CNM`W zOxVIZd~(&9+d>KArWZlPNn_a3G=FW}M1tum;%qmjNYEr^w;s;r*^iKCk?-g3V&v^7 z8BYt+&zzL(6~SC$EZVmtUeF@pqhMerDH1T?vx}<47Vdw2nVkKtlSa+?004|&iN9_V zJ~?-SJjJ(}qkgB+ZCVgflU>+I?P~;zOD}&U2yRk>71x_Mg<&>&WytP98nB%T5nb?~ z%@piGg`D=uh6Oh@5ijPDyys*J=E|%x{-S}?29yVe-Vcp3{PjE)dYo5G;orS>aQQ}N z9wK)x+`sf?za1t_!DAbuX1lOYboZj>P$|+h5#c1g#6p{!LrDJ1Sf1%X`vd60>11VP zZm3?E7a3qf0{06`=g!I@xcB&~Hh4^u<2)PDx;}Yj`b;XAbUN&$o5Sdj|AGM#C`v~;u@nZKDrkLU^ZTv+k4+VuMVGA8X zt-1QlR7G|BImhzPVL!<>0_Bji8vo@V2pJd<8S3+45kyVJX=;sUU4meynsgBT^DgdB_^=XX!kmg1Hd8ly^@+zlrkJE>}%EaWfa zY&0GP3aiq~cTwn0uF;;gqYe}B#;)&5C2))@8@$#0Kc>FIE2=l@TBJLr zyBmg%0i?T;mKqqkJET*FZjeSmL0U?r9ENVByAhO?nHQa27Mik=pXX6P5}No7>b$7YkGHn4(tZ-gm$$ zG}OQq=M^;OHnx#%5*F=95h2+ngbJy<6rbot5ZY8dPn%7hJF-;_PcZPWKGPodm5s{q z_4neJGScF`m;u?FZ*5`08T;4IUqtsqF}!nMlYfbL9dER^SO~fX2UYpPx+mjAt9i}F zY`_cR?OF)Ngcy`QwQiLGWTJLZ^mkeY>N+c$jOMBEI`pC8c!JNU_i5sAY1jhjdgQV* zYT@g7kRxWj_O;X(Ws#2+Oi(4y*dsCMkRUcB7Iwr6#i*3b{cx7Afe!U}p!O#ykDKaR zMq&}*1R^*VVe*j+G+mSj0lI{fmhD+&lT~7iU#VWbwlQ}_@I;zL;G4#4?g4VIAG}5v z?tD%k=Q$=l9Oyv`bNC|!1+~Zt?w&O>nsz3i&l}_pR%vJ%J~e-=jkZL3l4NK*xGXGu zs5db6zII%#ENjn_hV#|FcGK4Q9iW$P>?|zfzKt#Ru_BU{yr1e}CV%gG9FrD0!VKU6 z>D>5|un7LRKXsc_d9qJi)4{dAWr!@H`iJ(Ydz3chLFR7M5Z5(Hj5?__q;0p1gL4Ry*YO=KsY-NSj- z6v@s6%4lJ~C(z2cgLc00HM8>(o~-@MP!sxe#I)TMv3!c1gHbjwRYjP<;3q(L(3@bp zNEfD~Oyi@Kw~&ZmnXkEFLi%@?G|AACDmr9q=accA*XN!0Irs&Xwgwpf5QHYsxv7#rC4m>TYHD<8$Z z{fV#`)uuk>ZaU9xE??j-Fd*v3Hql2L?axt8d>>JP!JsRE@Yo8*){Lvc{Yb28=j-)> zarZV!FynD=d$n4TZxjvPtFsVisqW=jn zGf2bSz^`8hr}IgLSD7ibdH)XDLOLi>(b-n8b1`5AT{uR!`_eEe4g^Ysi>SlrNyf;+ zAr~$Ao^w>6E~t}flzUp|g4Sgxw$D2xP{k7=2?u<)v~jH8Lg5`l#`RPX(RaDuhHj29 zy)`4UG4K${twIYzEG&B(mpVYX9}p0ferv3@=>Mh<9%~L?pz9gE*7!{hWQx?}|89Wi z@P|&rH6u4(VlZW&FLl8s_Et9mkUt6)b3wdu&R*Wo{vE(7i7)IpUvkUc@HVwvX3jwy zp?;jb{Fzv!J=0%NKI4~cNCJWWWBG(ucL1mI{EzQmN2V@LX(Jyebty%E5Yc&-%N=Ap z6Br3{7f9iBxgZh)EG7aiIE%(7T1E}jM&M0Bi2^)t%ySdlSK)ic?WE>PVxgBvGZwOK zG4L|4{#d@~Q~c+jNTcNx(R{HA94I1fcV5Auus3iY7Mtv)crMWTWCK47a|BiJI9tp` z@>e^M%%6T`7pr$g>8hHKK`)HHdwfaIMv_rye^^Vt&9=L}&X@f8{hU^RNAM#Cyc`36^X^#7l07@_~U6CQTgao4^KD zy5xaV%2nJh*zL)(-Gh9miO8K}fEpRmw98Z>X#KCK`cIW7f8eDxeD&>sn|i@A5iO8i zQ>nmQNa#pC9vzeDOJi!^G}6v?OM#!-H`cY}a}vZd&>R^7jVEy*6Vlm}U zqh>;s&=OVAyj%6Cf{1$MGszU*<|z9=o=UR~CV!Pu36kDOV|dNTn755R{dP&&^D(}H z)qx9z4?ZS!=EYB{0*Y*NNA3pLGM}|J#Pm{QHM||wlMCS+O|B-o%_82))T-R@*l5=Z z=|W`jF;lA9e2-VS!KO%lgsE8ZXn64PLKiGIpliV0`mk(51wJ%8@#u z?&S~xx4L~rYB9BPYCA|m-)lxBbT!S)yIp@&#v=h`FRF4p-M29-#L)s(&Du-&vQwJu z&>!*)m4~V}iFZ(+Z%IeVWIX7`{K!tqGNMx;gFmeAtixE{tD7Y>TdTLY!k$*`tMn<3QqYOS_Oo#GXu?~z4YXun z^;!Qy_JhW@t9RGWft9rKSK_A1WF^9G`e~*etBC_>>bu6^kH%o^E;JW(KPw?+o0WiC zU#%R_ezq^kgrK}`@AG8$t|>HXq1Z$u6)Xu9bf)r8)zPA}MXBFe{Drm@%8PIvO#etxnxJb@9h=MBK16*<@CwGgI8x7mjyWEYLXT&CLVThz zU+a3&qN|`@nf<8msFfw-KiaOiZ73%g!G(D_TUu$je(MHJJ^fm6Gvrugb}7TP+g`?X z;5Zsq7&bAxJ)cQ@4wOXPpr-I2^(?$Vcp`0X9 z`6!bJ(zYt6vIII9!}`~5e@_*X1nn-S+cgz~3f`{+yI=+}yvOZ9PrP0s!C14*EWqtgg9y-Z1v=KDi@M->pCCSS+D+Y;-X{XUmZDZ_n8YF7>Mrr z9l{h7g(jJ9o(b(sHZYeE7MIod>lAxDswAQrL&N)x%lTKsH)8Q$nKw#6ab7U=&NE_c zz#F`=5hP{npyEe3YsY>)b~_k6T0UGoh)BwJL@;`rC%3P{Mp<~#dF=v{rr$2IK-vWT zc9se+PfFiO9X&|wDb%i)jXfcK%qpF4nhU7*n@-*BOr9d>N}jU%fR~#sxdI)9xVlSbMl?mm}hc~^x$*GNR&@~iKViK)fhiKX>R^yoHL=ZY;$g@f9>SEBh{LDGx4vSorfqPPAMNSChP0&;$3Mj z5$VE0jnjSZDODQ`dtd*d2qem4T}|G>`|)-~+1g84?7|+e_%{Oig^Rp{eu^h5Y+pGz zh)4hH5V-r=Ir-kBks_T!+N)cmbelf{t?hBhEa?Y{p1PCWjSqOJyi>Ol}@JR~jaslkqH$Vtkm5UoCW~oG1fH5F<@q3H; zj0E=5PvQQC{AOz^wuo#gjiWE%&FpQ-i(&Q_T)udoJLHfk_MMjBAo5*?-?iaUu<+4kYEkn~%v1y9>4G!(HJDk#m8mUVm2zCD_3i>-6V~J;OK`&Qa)UT7=AI9eMVk(Eevp2c#~0 z*WYW#Wg1KtByU+6hTZm--(T-4;EV1BP>LKc;5_NEWxoox8d$cw{(MetG_w1?RFzH{ zY`xv=oW1fRfp#)rcB(=~=|KWyRR48l9h`Af=tKL&6=nGnOcNX$41PbtC3;K=BRf%W zW{%jjU*KsAqo@ZJ#>bBT!QI6FBXugN+kb^j^?6aT7BD#%5kIs6%*B@-@SNvPMWgPb zX6kb{(VZ{YPZ?wrmAUq{D83iZkLbUSuubC9S% zhaO55)H8DEo%$*OKSzMtl2YNsKY79CoXM(+IJimtI^>F0(xbH~F7t!xV^G#OdzDW~ zZqtyy5j$&k^{9G+=G+Uc1XN!pTX<>vu8#uzG13p4@u*e-A5jw7Vnv@|8AxpMOz&%SP>JiHY9USFNZK>!_BTJoD!KlYYB(cA1}}!Zulc*|Ntn0~sKQW1bnlG*8?4 z+2Uz4(lPX}#vTXIPJdq-(AI=5&5eW^zEV}FtRl(5JTSSKIoxFxwh)WbU=&AH?qE6C zsqn01cuRDSi*lsNA9S*^+#!7M%c)sU^QJ9$k*=DV8jr%CR++zakD;eXCf3okCbkJtED`+Hn65_nzelenb zZ6m~GGl;sem(-Y?^pBY^f@fK9lbWYdyBj?tBihd~v1;2)s*qJdo7BJ#{uS7`WF3Vp z@aIf{{8g`zpc9K4g_O3iO#&^k@(aYh1mU>!V5=C^$dWFO_44kI#yRlC?ZNV(<|NA8 zvgR?K95xKrmR&>_)b%p?3w~Sk6(utAhWyrA5uM%pl!KYXX*0W4_+W&3xh8TZmtQNl;yDv z^PgJj7ptv}rC-Z0Hj5Lw?y@YDs_IrL#Kjy-6TeZ#3#O)$X7Zv{h#n+{kZgfUv{XZ; zSb_;(#w6I_3!_cIZ0;&3veT>sT!}rM#IKJ8UJkiS6Bfp2)c;Ic-woALnwNVxfiY}x z5Crr<9vW~SfPo03swcY3mKUK+0y)F!`}{2N7*=3uu>L9!)`ST2+^_As_?1G`vkmCEZQuXAzj)l#6~rqNrb!|5 z%UMrRRf7i6Vmy}z8aHR`(Au3>vt7U$t*h$O`Q*a@`et)XnC^@l7B-e(Nbw0yJppxi zT-K9ha_)FxX7IyiztF0Sq{ET}BX_Dcd$a3D|H ze}||xjeH2+-L6QR8i2tTuGo_L<9=XXTzCtdXl^iZ5Ca`^R#q11Q+2Kcv9HBk9wY)z zEeK_RKAXjLdXX<|XgVar6*Wux8eL%?R%Gl`07OrHQ$n?jBJ3oQgn0#iEY#&KCjuqz z+{DCrIbLjUcfpOP_7$CVV;6%*xGNQs6P0!kqj#>$BL8l+FBkVigk5ojLcv|Kz8yH1 z+sthr8@8eerRySAXA=9HfJs|P?%l9JG`Wgj`Eqs!Of zRhXKtt;m*_MeY@Db(xLEpH*epcHDsl!aMtlQ1dS6hsS^i$4)GF+mLX%v>vem#3?yLp&DoE*t2xGL!@Cl9`d z)KR7EM{}GO0tStNYRmejAEtH6Aq11?5%{D&+pCc6Knj`Efc2aUx#e*Y7Q1bS5WT(b zTrN~2mbD-CjLgC2xvLd}u&+cv!}-$Tau}OefL^AV5GpT=j2` zw`^4W>=vFvi1OVZNt&-38XhJ=mPn_kH3q1WlYvD(gvDZo+p{mU9koc#M|-1sSx`LJ z%aPBne5S#lRTaK(h!`iI=K&1FC1lNQk97^}p_D>Kkokj_9YQ}DI1`qg>F14(+_(Bs zZ4ola-J)VcZ$4mnUCcD7wn4y>^QSmok%ic8UYeZeDjXH1sy(pVw|(~W+|50?hvzUd zuHx?l*${L@nB|wbrvr*FJM<~W47cE^J(y*%%Li96$jx6o-~|C7D~A?+Lop6jc#X(W zj%~<`muGCp*-LaJPfro7JVKMF1=BC%ksqd)_pag5IM>|&y1pmZy6pBWdi1Uc9UZ$~ z**?FhQ#EkT@cFl9UHX6b$3I2YjlBb0{4$7wDe;56IU8S@$n_uUpVIP{Y1VqFx;rKg zh!9l5E4f%~Bv85bHc!mwkot(cDm{dc;64XD!p5pzj&Rzok9JcyajE$X{X|=4a6;swhu)Cr7uTeLQd{i ziGpZCEj{({kT*!aEs`SlKAZxChghSQwB9lzu?mYIt` zCImu<-~kcg?POU@CogDNNo=V5#1vBVXysZ0JZ-1W4Jpf|{T)^-89#dk;)w3PpFK`>mnoWZCso63yN#s&)&D@ z8hsikWU=J6`eKEi2=;p=(ck>Fu(}6=j6F9Am#5)tY z&_z8#FN+7RGX-dBSU?+K?gM|gFroM*Qm*SE>7jxkj`uwh|1);ZWo7`((0zu=J4aDr z^ouArRqg&$JMVKpIT9Z2z7PHSwx+VN*CxB96k(l6u@vCAOG)NuYo*M&7!7Cwoj4zN zQV-0DWk1I`dCzgAnPPv`WMW?UEH8sE!zItFiO_-7j3YTzI_nzvM2XdeO#_!B~??APwYO%(oxAKD2m(t&MF@j&ebO?}W z*Pf(_>{jJyF8qqxWD5KO zI_Cv1!REc(Pq~5Q%`E#=W9c9|5LK>oa!2`kj`*euqp*yv2ZjS^Cv}r2ij>WC-*wL; zA3O9Hf6GDfJGP7aN7MtD++AR{PWhsqaZ0L?wfp(wiPnKLM@Cji`P+BZi2|~IxEdMu zoioF~wf@fwKz&&VDFQc#Q(z@=e-!VIkbH^9l+BObIJC2!mS714Wv!RcL3H|Nw=`@+ z&Vn)txAR^MuF3opfY3i&ZS9gv{*Y>FI6NRRaeA$W#IKb zIGEjD`$sTk*pG#p+K<_tJCs_xmo-Fv!VHtGXHvd1vBdv19@4v*fXf*MKs?1)!mD=M zIpHb96AaoEA-=Mh+V6c0Ik;M@=j`tOYJi`|gI0^s#N8kEJKtZ&oYPs4EN%B`{s|W? z^7r@-8Fd*{NU@(`SQ;4*nTExQ#i&mPXNT-D&4aa=)Wy{S?SU4agCQIcwzxD*R(#ts zP*e2XWp6R6x*rrD5VU0|osH;bmHAK`lA1ZTQdP^+D zj%^;;*JzZD^vHWmOvZ+)2CD^%@t=h!U^--rtK%21jP#k#DbQ~QlC_m}7_?o}jbAIr zQjiMDTN8J_4LMK(;?d@1I~4XwinAfS1lX#iiBYUgFSXOfR^q1PswSyFS@^KX6*6I+ zW`xQXBuG;~UbFxUwG*Berw!BJyI+e)%nZ+efqYluN!_vB4fI@7cG)|6(A>%3OiApZ zX~#bYJ?j(fB}OiCuPQX1&<4byfr)c&>x^yfdEU=|?Q2&){Xbp@rUW0v1d<`}x?7+f zU%}nwTH;jy5uBk<>#!6|f%w*1h;`{I;3iqKK4a_Ej6WDVM+f@H9?i`L{dJaqeDmdr z?TO}@@fkXq%bxeq!SCHl&*puE><~x&bbj0ew~?{Gaw1= z$bN&qp=t-`_X*o`egKQ3Eg<QO#5mkk-X2=T-3Z}JSg6EAW)%Pb zt~ITMb}^3JYVT~7cZ!Anb6Xt3m zOu&x<(Ym(VUi54bz9O%ZIhYzi$(AWNNfc(Ngkmw;nnY>w;n{RKW|M?dxlYWAF#fV@ z*~5l2mGjVDN)#l`(XN+t_UXNqGDs~SDN&G}(uu7y$c`_U$7!1>fd@N{v43M{iN|`& z!ihQPgQ)`%(W4F~>I~;Di`wmYwj9B&)TYp;UNJ*j)F!QvBj?gcLuNap%b1aUNDpl= z_G!JI3F{VO(@_0jS-(xOXMiKY83G!}evhV{RwBU{Ct9BFfmegfuUn~LXrr_9&pANY zM6bI~bo4fsg^DmRLG^a!!825ZnVKg0v5Y@@>M(P+5!-H(U;Hq zN2ZQt+bv3z&(}*XurZ@&0nTvFnNB#@OHCPx&DhNd{HH6KPbsOq1tQGhk}?mz`P5-g zXT3_}EjSB#2d0tc+mu$oRWcoQj&+s}PfR;+68GE1HV15XP|Gn?Hul`t@G}YMvj7^% zppHDPwm0iHt}1=*l?IcX{M+zNNaHXcox8;EN(YU*Kd-3g6DSU?W~wwQ6&d zM-;IrmK&ovl;G_ji`4Ts#2ZGjpN@Yue0}zh^-b|4+*X3&KR3#QFqFQ0PniTFBP;T# z3&B2@Kv4Bc_nD$V0dFE%CV-f2Ht18UPm%R~V+zC&3SAsYBoRO5FPLp;8`3u1$@+8;x z-I$PtgrzNJjnU}Wb0jE|U?TOU4MfDIwQse8J&2ZHvO|OJ>R_!GNzVE=k|5q4LC=t= zs93dtY2^?5zjtFJntxI$!eqtpL!}}&RPE&LW3vi=7eF88m+eHt$_CSkY-E-gpLiT2 zJsHz>pFWSCME>J-=MG9)$0>gUyVVXN%rK6BhY9VRN=V$c&6;?Ba+<+ipLIAJC8tmz zKD+JLd*a|RrKbC5VP{w`+K?fl>Q4_YbX>LA%mCr_>ajL4#uq#<4MS|H2%Z z7KUZp7K$y2B_k)QW&Mkmy_<~rwc)-Gb0LT3RSk_yy;BzEk#r@D85E6^#ycz56)n{zLScd} z-c5rh)imWW4fBg~qgVr`X6L*eXD<2(E8K>$G+ujrjuGR5t#Yjtgnha^{|y*(|5p#2!>3zO4hL{;V9-R;ZH#6QAs2%81~IivjjmjiE2=aJpbc3&6SOC!rEl2&>?Z;`=K zuVoc4J`{Ajmb_T1Z%Q6#g|)hu-rRQ$Y%)J`J5#sJD+ngpQ)h!3b8v!Z@8;(!|B-mP zWcUK3jHKjaYU^>$m>v7x>Bs$0eQ`lN^)5vM(^EbY(*g(80-|CwYX7>SgH#&6?zqTH zgRO&xO?t(aiUU~Y2L%8k%sS^v69|4&9OIwFacAhkfS@6K`b~X{5=^khIb$Ic4E{AK zsl?eE{)s3oq}y|Y>gNi4Q*mi8hWZ~`G0Nu@Ib>Q>=BZ3sHq%yx0Ozz;;@5v?CGtq&xndhQt znDe-ll+3`r-7Ozp0=lC*KvlgmI@hJRq2fkPer|b%$mwpHyVm}FtA{B5hsWn`@etqH zz7$3b-cIDdznmRf+lg(Y3sWuK4#iHq$+V)l8Oue$53 zSTgq>wodF18oOZgDpch7PW=+|LI8Q$MJkM?L_)*bErZW-v`^V}$B$ zSA`!(z^vG|Wjr3@ZooIUUcr#axcqdl^_km>kvFmUSklbx>zjWfD{7*8@j(_shpAPj z$?BRRxdi58NcGQF2>2uh6Aj1Qiuau0KOnaun)G@4h=uudkdz}wHW_AKl zS4;(17vV&vk3I(n36|@;6h|J^2>ikCWNRQ<{+8g3CyIWSK|^Kz6MH|CIgu_cfsfcu zgON(O-xNnV&1B=E=OTxSEzy#^J@xE?+Trl;>AVjWVT^Xp91uXyDOPwOF7@`)&a+35 zN!uVp)>;7_^P_V+vaWXSNj77v4VV!3;!63nao&?AWTe98JM=Lcf9+R);9!7c{={m( z+>JtifXta?_zlv^cmMz>H&WIiU)efOGdW^yYl^Htfp0QGo^sPNZXW^T$>k&6wi`Gs z+_Su|Ida47%UDtIrfyXix}n>A2AaBfcdyAyckVj11sDCO*zq4W6=EbXS-3u6iC|-e z8gS@G#IineYzsyPFYq*90VauN)fty93ah(iyVg66ReSji>Er;M!_;>7HLv?gLC>Dk ztXR!I-qbx2N`)H(*v>gCSHwcxhOTqtUM{NX6>{JOa*~h%IFR0fiCZge`RlHR_>()U zMZ7@C9RA0N0cM8_^Je6 z>J8BJPsJ~?_TBB2<)evyFy6%BAx|EJ_P?bx>%5jX7T z5imWLvLg`6MhsE(%%X?1hW2 zUsCl_p=~r0YakKna?0WzQVLNdIuz-b1lxF&U5q>E0T%q{GcVy>J8R)p{|%sIT(0gW z72wvffYFr+&Bo8)@O9@_XyFh2yj{sE6cs^@8f;`>G65U)epy*2kncc(GW?b)e%)rT5@hm_veyo8S zp5#Fg=J?I;Al>+#{l*!4RpK&aV?sMz5^D5I%B5%OiLmlzL% zx)NYSoH_GY$ljLhcLxn2EQ{B1aTpakkq*&mFeI5z+TGRI)Tm_Vh=NzB~ny z)Mc=Ka36J0r1n#)q5kyNktabs9qVw?9f1E5FLX1Ls>eo~-!zd~7mYlu$0*R0#ZN7^ zQT9LamyO74HsKfa%oXl3TxznfT#^Yce|2bUI9+xtTci3J@8{hzD89@s|K)17XdkUY z!|;C_Vit%>?PdRrmK8o?z2CIz&MZ(kX;_m7@lLz%9@A4!OjbYDz((qdqJ{$|$V+?m z2i^KjUt`fk)uasYyyNt4Vm_ZiO$}dkJy&|W4N61wzlaJ zJ~qkJf^iD{Hm&0OYVza$*pJj-+{Ie)7!S#dY1I{}2~J}E zqb!^#y_MhbVQsK6?cJC}9zM_~XUidlqM#?L1qe#HS7_M9CdbL{o5%`cSx!|%o?Xc) z%_G@k3QMke{WcXdw0Viu*r!MKLk`Nh%l3ju-FAEnbpp(?82=~QO_pmrmtsu}ErA16 zJ^_fmvlkG86X8WWgxl%Ti@wopi1H8G+>n2;<1x8I7yfQnN@NsvN8Y>(Tz=I3PunfJ zVL>=z%$`GXua~R^@i3CahTKEJ14^Oju(*35MRskSA_5H^KaMLM;ptL9IRP2RA zVSkyO&T74}wDN~`JJ5!B1gtO%Y zE(I)*PMAcLn!@`8HJDeVZDp=MZ(edlD5|Fdsdk&VO$@Iu3mTMw$s)Z`ddc?q+jI&! zyd7`HFkwZ5&XjY8^Lun~^C{TI-}&4h}0E3ulak?H&O1hx>thvrVE}Ik!J+ zI}DAOK7$p|C-1 z0t_U`6nvDXFr>W!L)gx1rom(dL#~(s$4h*0`-an0L;MCPNRvoCuG`(hqdyD&!3$Zy z8oy^6xKt7d%uDSCf9?5hmboO;TipA1a=jpKAu#J^`KI}L-qx&XH!yi;41^htW6S86 zFY6_zCWBW-t*58#g`%k{{!>*wcmzovzbfgN?W~rxiPcFSmNKtPnB9Nvc?* z>IpmptWD|aycqmAL3g~C&plesdjGZF+0rcg=IrE?zwxQ*q_<26+HJ)0ZQ@qunOKiu z%&>?^P1Q3HD%jA(<_2F;V^27UY+JmaTK@Fdj=^;7eA4yosxLdZ5bH%vX4d-P3xRd} zZBzJX-H1pOcM4#!G-xZpI*8Q$9W1(@kKuElIjqA66G=b%u22d~U^xm!6@I9aEdC*< ztCMDNQkN)DwFzXR^13oY^N5J$V$d`BeN^f)dfuuqDbaTZruVU*pAHXMPk^_ zS*veSACkGT^f?e>WNsHE+e4z0i*}lAKiR6HE2aURi~&;&@ni z(A^2V<*u|}nH1Q9-&AwGZQt^GqloviM^zYArG927YTPGmO?lcM6u{iOl42gw;VWMc z{9z~C%3Ym;b&1bpO04u|S@*PAEY;;8D1jx~_KKV0f}`^4GpTN?o;UZvT3X1S1kA7R zQVV>Lw81FB9nvG-Yn%X%3}~H#xo~i9<9Yi+6sr`1xVOY17=s-r>!)kzxPT#u=qIUc zK@`G`@kmLwAf{tJDzdfu?8|q!HH(9fy*1W2 zXkHTQoMeREr)=t*u{}u;-LGJ3ZAAv9P#^I4@d1wj<6-P!H-+MT!!)d#X%j3*@WJrsY&NvLs%o3Gn{0O=9(pU%)A{Ft7;|m^**Rk@;y# zh}ejc7j^%64iU-+afN{ffqC)9KMKs4d2$WWRqVL>!z6dq93^ivMv}s}w&N$iZcp{3r=cdOSEFQ(J^f!}tNSUz1q;K=C6OYdp9d0&B)A-2%JF`f*FljQH=ef0HeI0OX`33VhasB@AC7BJs zLV7n<@q-K7IVtH*2_L3lgUiIW=-VRNRRjbkl*^otS$oh}iRu_GgTES}H%!8S$g>5jl)iNpx381b!84B6 ztTgwTwi__}C91?%kmLd6&y?PW1dyhrX=z!8q7ZM`c@b!zJ$_ybi!dfq4!Z-ZP*e~r zrKvKVm8mm1`b6NG>O{10EdPAobeG5@?dWU|vX<^!3$J^tlgK<9Arny77V4r<+=5VrQH4`6We}j)K!N zF421R_JSpgGT~8^$tH1W890tT={#r0=P1=|8?VYcw-!GU@$><$l!{#aBN3TT9yFcu z4dZJ6m0q+Y1-{$dH<>{Bz!Cv`_CwP{N$iL^_$v_i8Mu-dk3C{T*XO5 z(I?%EpGk#xr_&N{mDAU?C}!HM{xZ;jDUJ;?{V#NaLoQSv3{nTQAtcvVf?K78V7xxd(;9?Lolp9*T{qMTdzGDFa_PWNm|ZqCj-s` zzJgm4`k;IJXUL~X!DM7BDQGhNxe;X{9nul!StB-BJ8!zfNVyl}`VLYWuE<^E>y5G( zH*i(0K*)$SbzvtPQnPZ?KkI{v!w#D9HFO+}z^ZSnF;Iftcllm6XQ2LdX(_vG$NGs#uAGO?gl z+df*hqV#hr^q#_}=RN3)-Y>{Lv)r+lF`F9GvGmI>!ZNL*;58G*OvW`R&T&rGk42m> zc8!IGS)jR)k9{Nwm}omMh*&Q%pXcdDZ%@0#)JZFwGhZdBKy({p98mE_rfsI89R$kz zg7L%#-T1C;`-=RuqoP>tW~=@3n`fv`)amst%4M=|OB1MT2N{>U^Z58XewkvS(mhk- zd04YOgKZ8QD}?L|^cZ#|7q>A7?d7MDvDm#Jgu4c=>)Mv7=A@M;jYl_n6+2po~K>yls`s#XCPM+~B?xR7y-Bl`Sv9 zEMH0>O(3PX63EXe8>n&|Ce_R^nhq%Qj(PKDa6K(2JQ(FhqSUP)j2Q|k#bBJ2BRgG! zYP>~R$-9xBf3RG*;lYEn&@y~arX0?T3^ycw3`?E%8~I#_{kPa}?x4l{*0wt;H@7(p zy(V*ZpPY^SAn9Bo9WM}Jc6$?$AZJgaH1pKxGfbFF?f>#iNnbyxrcbsUf98-BV~|&n zl3-lG^qs@GlD?b}r>gq$Z2F3<`a9-e<{LhvM$wNrq}-g1%5f4!Y4FIbe2x6kuRt7# ze_lJzj$VJ@5^_PfXt*daS`ViZiMU#`o66gMXYu?8%%$^7Ky$o~?Z%s~X?w2#B_*E4 zJpLceUW-JdFq`C@85T7XQjbO$6-pb!Q!4$Et87>74lW!ofs}eFVB%-nGhwDE0;=)G zbB}!7DtR=WPKCfb)Kx1Fs;z5_{?MCjlDbpdxnx@;TgA_nl>}n^?Vy3&3z* zQM1rrlfWET@uCGT;QD?DnGoIy=|k%EJ|4)-3Du-lF!h_fA%lP>`Me)!_X--xus z1G{o;>|0*s*HcvZhZ~m>_YpDzJDrF3>}AJ-bm@(2a8v5hvxl-KINrO%dxeD)L7d7U zNOqqA99FFpk{_eAsDEgJ;uEfuYo_dA_=;`N5NyWZDkR(}Z1MNF;KC`%n_rj)>#mY$ z;=TTtLZhl&(AOMT4b5UyBW@!VMAD`WK96z&UxZ?|N`-t8#v6{4kmoQfb=^rO>+-+Xx2Zn#&n!y^_MZ@1URp;*L)C zx;Zs{RCx{ZvEO+{z_1Api03B}3iy&3F1?E{#r(Q(fqgbV2mBY48L*^S_bYBM*)YhfUjxBtxsVu_nTwlOhr3zil*`l{(eE85BYvH56(%$;c{ND}oRZ%5_1 zpDB95c3@+!V9bQK6Z)(i3rs-h>(9jIfY?Vf`{AcE&lsq0Xmzn(B=6VB-2sfBw?*rg!s$YBJUzay%8LagFj+)hz9@r za!l}+W?LN~Qoyt_#Zo|PK*QRdl59TNyx9~0d_U4)g{=XcXE)yu-)MEEp1u2fR(L(3 zGbp&qQ9o}_VEGF~%mCiD&+=bZj^l2~MJjdacp9d_|8ScB-NRhy2T?NDwrRwcDt8Sn z^GJ;kYVwzeFX1&9!ymM^?Qf~;^0tQkBieTq@xMGP76P@i4DJ?d~}CzFq}A;Ma!yl#^t4~+2BS|y&ik1 zWAQ&+on>6pZ`k(fZWI`ebO?-&0U|9Wf=JisZbqk41Ed=i5KwX;og;>{fOIpuLrTJD z{_p30UOcZE`>^r5&iEe3d0thVBU#j7$%D>j(+N-56p*y`hp}Qq&o8Jw+B9`FF?mlDn@?E8QtKvL3ULr|^dZ_t@ zEMCWmL=tn#5SzRh`8GQV;UpDBBgfCT?Pwh-mBMQEoT*&dT-(b%N*3UCOq3`(UT=y(o&un<>Pynxw4_jl?qHRtYfJq|^)Xl1&>nQw!p z;YNVV2nCAhe4QlZ#|6o>=Q$~f3ajl?3tGD}U@M&1_YJRH9gyd`lIA4rsO~L4bD+Ng8mx2;nydx>7AgqIl8yjpZqS&(+&~sLSt{s_l%uf4UO`$H~ zgM@>RMQqO6{d@LiDOZRu+rJFCf>1IuaTFA%cxkHk&Li-;XWNIOLM48*DiIcpUyiM` zOi;x!RZp%!ir%0kM>$w7jIpm!&Y+&tsv1?r+ThbD4DIT!{0*=VrrHPh7Zukmu@v}X%P)&E-h&w0mhu_X-Mv(X~I0rK0BB)Lb z=u1z@*B_N;7a`1%4IGSazr)9xxU_EVn@QbkS()dXbFEdWU52|d&6N3N!-o4v4lJ(E z#M~J9(_}v1CoixaIIsQdzO18<^bwF9fB?8XCMPohVX47JVUi2{oaD0^0C$b-plBPN z!#;d^2n16jRzwZ~>HTBLzEw9bst||E!|MhM!uQQ(udw~``9CI&!4lQUy~5)G925uV zj_J_zUkHD)GDM-=*P=we?cXeXg_JVZKiFposfS#;axR!!hG$3-clj>=Fjo+bin1ws~#{Y;QNT#Rgfg zkNn}6()%2BA-_o)iNE}IkWYAY*MU6*l&{FyZhD%hbEH@#UgQzx#d}o4TL@Za>vvO( z7%*m7SD@$MmA7j0UcB0*maGv(NChYf$ysvY%jykj%YrJIv^Q$6^vS; z`dBVp+PUPgd=Ex%jghrlix&ROGqO`4oHzDo`Jda*iM+P%<&an4DelfV7}}|Kg>kaP zp%;L92T&-f$2VQ>O{K{pOL1qDm{hm*hfer0+tr^s;vH4yT)F~{{)j_qyYflT1&^;{ zY5`-`1Pjb+oA6%81Xu7r#%3B*^;RffAtH%jo6dx94*WXOAV;|i!)Jp{P6u+dv4zw9^M$SHDRE7lSx1XSaL~-H1kv2FrAJ;x=d$CxCAA7d8t}|fN zkr^_s0Fjw7Dpce3O45*~!kdrrM!9ekGiV9^r{+R;%P1}0=?o;9K|7CO8RbeFSKDWT0W*hXR z;M-52?TxNk)i_J1JN-L7?nnWC9#|-SRIL@x$MdZ}T&Kv8$8ClQ3BKnB`1fqtYq2-2 zZjgG5mg6)S5#I6@R2xNdnm$NWW+i{Hwh;}Q`qcBuTPIcq_=_cOc z8p#fSAs+xum`bl}xtHf3;r-P0Uf2iK2CgxTaaPUPE|olS%MWqAGS zZP@g6NXY*R1`!_@P{Z_u8YV;|eNqFf&$}(LggmP%(CB;URq_?{8wzUk01MBYUfMV_*c0n54o=T#t%<|Z^B-g5W%7t573NIfRJPt%OhCc&_9DK zaddt?4G9kQ`|Lkp%n=d+-Yc>)Ue-1N0(%R}ZxJ0de|4>PHYnPB%fS)MB^nGC&kAD4 zvNkPKV)3!y{ni#m7FKM<1urFBy~`NpsF$xOH>d7K-xq4Guf#u4;IffeYukqAX~+eA zHTY8bJETB)b7#~2Xuds!e9&Ehx}DBL((>r&O;1Y&=3LAi$DGs8XRKR_ozY*Z6oILD zcW?YiSbVvkC?28v4$U1|X#X0qc9VivZ(92HW2*oo<@YEOxVhH;!ns5}ihFJvHGkS# zc8E&{*z+#ORpy_OoHlBoj-fy+u7d34Ag$)B*f;QK{AWkKG{fQhiN20nHk}qF7pMgC z-PgS%_8QrOjSPO#0~IIh5<{|mYeA2{zAY=N!@s&y6+dWOn( zL7BtTW+qOjvTL+G65LAmFCQyo%Tg2Vx{RFzarV9Be`u=G)^ADRzR$I2l(bdPQy7OW z@Z@5g0+V4Fy*!$@Ns7>Enb#>Cd{-wYbrF6Kv{GD$Z zF=Nm;lN$GS==|I`=g`+$JKlv{!KChlbb z{75mk`>749yPnqrRKlJuC?@b5e<;lJCFa0Zw>TB`Ma7B}mX0eD6q$tPcX?6A{fR-x zOmaL#$bDjf=t=emV-*MAg(yfzbT=yXUtI@mP5NmBwKB~ z;mEgVDWqe9J^GVzFQ{%VnXklEV&ouGVD`e+nd~0SHzFqt`J@jf@eve7PbEXGN-z*< z;s^Fa2PdSatpnl?gwAt2y2tDbWbw-BrHOn?`V#r(Bu!}5(gkK!fSvXm@d=~%kP^Jf zF;6 zJ{lCNXDzy7i2c;e*n|2^nXg@!-QB!F>4BAzO@fRtHglR05WGG+L~*+w|1R+V6C$+y zf{`7(qO!dGvciq(_YWh~Hxup>N&UY|nC6eMy{ksQvo>DZ-_WU@=91RhFb`m$CLx`r zG%-($)=sE14US%Pyc?NULIpnpW#L}>ogpAD%56*mRmT%Lz_K*+V6~LF(TsdYp=K6z zHc1rA9I^_M9&~{UyGF7R#B$5 z*8)Y$B1a=eZJjy#GqQ{4Pi@`RTnG$tkmDjW7LfNPJ~|GdpB|!TS1sm$tup zXAn`NwiI>KNpYVv=i+@u*232r4Q#A8GhrUckB@h`C5xu^qD2vl+-_}N^}`DVhGErz zq+$VDGwJgH`Bc}3xW3NIO787>@3~mLg$;PeP=&7TN7TMXn9hFH504SpzCkG&W!e8y z)`m9QV+DM=n;)QVlEWmBGZ63L`BG!#r>=h0V%}L;pXm!+1X3tOkT>4kuTZt3d`3?| zmIXQW0=;OAUK%Bc5#m$&jCKc5x>-qJ8&0rypN!sw3|*uSY|n4MC){c@>Ak7MLQWwd zUjQc-jpDZ1K!))rk_c7;*7-LD%!`S>c~mQ(G!d4;F1;j{=ok&mhYuDuc@h>5;t`&%yH2P&t7I}>I z7VizohHPvSe}P>RsgG(|l=YTqd#sMJp>rWFYZWIV*HJxQQuVi{)@okLxxDE7u|3zWOM zdcjyeoi(Gs0!F0Mh^sEqKYd;rc1baA1WgsDdm1qC92=X1APfTvgCI7zm@nD{$3+?oo62!>Mo?ER&7&~G zU_8!_y`l*3McZq<87^&=1*B&R+hhTs`bUv*1Hk*39#t+=nq`FTF*Y`p)zA^|$MV_+ zeAF*wPcYk$w09Lr5a(=u_4}Fjfg=`yCBpEb^f4|uk^K;cT*U(si z6)Iqku@uuI>!V%GM~AM&6IkI7Onb7!e>*!Q{-4h&x!0NI{^Y@&FP!yulX}u$3(+F^qf!fwY z7=w6Dpj1+2Tf**Hj6=38sc7HXN(fW2$^^89b#VAX=8%+!jQ`rg6gCF0?T_44ZzCkB z2x`VeJs91;SWqn^QX?X5oiSF>#0D=C`xfybb`zjR(rK85d_wi_0)m|zi7@IejF61n zUV)9^Z*HzP1h9FcIMdn1p0|rATO!++{=W~ZL!8e{kPdihs?F46CZ$a zf+T~b2ej8deNHq^6!>Ox1rb{-Bj(lfB>dtp>(PZ*i1So_l-Y+fmx>{u+O=CD4FaXM zErv7q=+!-|dafTs;BDbiYnqXE*y9q&Y^DCjJ-yWf#a({=WBng8Wx0Bix><|iiTM){`v2d%nr01}y z3wvd_F!0`?nZhFyAU?@%Tq$ml?{M#kZ?+$@^1NnZIHsbtt3WD-Sw$JdlmB0AX%x%BB1`#Tjw#Dven$!#V1daNvHbY@s`8{}0=M0cTX_gd(kIsd_-k%L zC?w*&x*CWdD}b)7L|UPuqmbn)w1M&^+*&tAqTovh^*FwD7;2I*GY^)aj5@YUy?y?^o}695n%)S#zNSge*tLgFYu-qtVK!w(?!+fmt>>VZfa zN8Q%Mte8E5G*>Xv4iqHoD(ij@GWe1gIj?atktW63M|xpVzel?&FTgFE?E;5QNUq2x zBWGh#6kC8Mh^jkYX6(lND?N{j#*yww%xCY|a{`1r5TPW*FWOAh{GnD3vUVMj8J0MWrt#NB$MmYRmJ2-A*iJB{MC09o1nW=*v`V>cu;QfgL{Yg zj4>VEhS8pIJTlGbT2}j-yFq#4HXuu6jjv{=w;Ka4L`W=QPCEp#vieihuIz`rl|n!$ z3yo08MB*2)pNOQea-xLfOmHKT24j*Yz3fdFlkmO4>#9NmPgLCy`LAv$s#GS;xxuky zP}S6gKF+Hgp1vM<>b0+@=j2H62#4m9XHrz_F5o>vS2TUYxI!spX~awE%=+r~r(U3{ zx^u!CaHJfrD|!xgmpdYfj_%fnPbnc5b@z0aNxuWq3ujjSo)#InOz1dV@H*sK=J1;h zM3hI(ODoK%_t-Tbf1dLch(?Gq&XknF#GN>=rO!V4X$TwejvwG~19ku--89iOQ*Q1b z$XueVCOG;+pdAsWV{>s}!Yb!i?DKi~R@x>}WCpK`3Dy>6?-LTaKfb4=hV(;0|7F*q zUYgLMvm~EML&WzJs>OnE=yTgmkCQi=<3k(VYe9+csJPlcS)G9@=zp$ReTX{W3P3{| z)8E}tl)Qf?9k5A_B(Z1B#2&uXg_08H$@8SxG4|ZBBgS)Rzs7R5D|4Xm+_dSiJo7BT zPwtJgHi?f0kd)xfV_)^cy%rY2B6bB8^wdGCpcUy`1TinEz+ z?O&UXvE$vDzr#h!{0k`!2?NBhcDcv!qpWCDW-r}R*IexGNnroTg-7Le3|ovjwk$^g zi9OMb01qs_Rj%`&!i1XJT`4hEiUzW$=$^;$i7T_nsaLk1?F=l zbMx$zEmKioJ?9YHfW&j@%*Q9-&&@kJGyd2pymJ(p@<&k%sfe|GnJCy_lGvTmv-U5y zE{ylbiX~R4z`-?CTrLw`R4MY_0bEHav~v&rZdml<^%}~*7}CfO_ePh828qz(pYPg2 zIY63NE#8FT=%Qqe6Ehd-J{7|lW*2+3bGrWO)mX-Wp#K~J5$1+#ccw*4xvdYQvF;GbDV|IxK zsW9vMZ=&~#D-Kxe%X(fK=>b2yr@9$mPK=Xaf9~^zGrsiPcC~QR%8~hpc?vgFk|Y&k z5TAGjA3N*jI;BwVM517|Ma>bl_=^z}esJ-|^wg)4b&6<9eSU<7UI%8OK$lN|tKukS|8UqN5Zo>r7Pvk3wkmj_x zH)^13{|!EauY=yF(Gsrd&FQbL{m5>f77a;%OH{Fk2=P_E^>oTHEGcsG@^H{Q6wegQ zKvz|ol{msFPIsWP5Rrgrq9_3EMP*L*zyYBfOi!6C`2#Po+IwSCl}rX0Fq$7R4FG6h z=oiK@Zz{H+2(~1?tNVsB%6RWZ(b6r38tQpF0eot*aW zfObuZUDEB$rO~4t8M{~bPkwURQW281Lir{r+APb#aR317WkD}>4uWwgi9(*Ax$6pd zNhIH&p3?@?jblI$!7^e)a>2qbL0nW31^!FAUm`%r4o?%C4aeAuXZUp8RI!=(-~$1A zo4~WEN+dOrY>RzC6`*|=td;T4`LZw3m1$k?*ZVmi$EgE01~(EAYh|lps_<8x_cXOe zuFy}d+)qdx;;f=1@H z`!h5y>>{O3=5w$YJuMao#m0G1WF-QFWU^sql7-dbG#)GHYTYWZzH4V7&-5Q{zM?PX zl+h&<-t6g!9h9(Dd~=ok+obIT%@^#fa3}_wR>+TZc~v_dU$tXhe_{O|)wKNKFCzN! z=7%mkmO-LZf;G1v_B~+Ji=N`(iItOEtPjd4@F(|r%;d!G(PbuE+$2})VlQ>HEMC(8 ze=QENKGLVYs8=dbx-lNKR<#=yCf^kKBy{Ks8ENq4W%o8A!TqP7o!^(P7e9139U)Dz z=4pSk2#XIOz(*H0!*5*^LzVLVvl-XjD={7e`MxpD|7Nc{1}`6$7cGNbVR8C3YT(tir{ZCc`#k0=8!$4xM37?$>LWJqx&umQxynoG$ zK5?J3W+VIvJ0~fC&c4!?>qulZU3~FQ`1I>C<4VqLo88##^54f%+&NDntwL1R;PWJB zD5J9LF5{QsHWkdz#UQV^?{Nkb=%` zfL4T2_NAdQ0qY1#-QvsGuc!{jJ+FXjT2}*;V@g-ZK-=J8VZtApIJOwc(!gIcLC|;P zZOnO5Ab>I`KJ2_`H`f>$q^Rl&#=aqhGO^Pa(v~CWfxSuRTRfsja=1ZXc(#C$N6GZc z0DXR);{$1A+z>^s%r6*JWayiZ9HJ{nFmt;|<+$!rfkAg6z2Cu9l04zWCUe9=|hhtU%+bA#P=O$^H5)4e>{W5UcQ+#xFUCjli!a-!@zwP#8BF zCE*jE3A!`Xj?n$JSI&>+Elwo#!l(43#^g6jd&Q!!R{3#mhXMju1Wgs;r|r?~6pbAZ zz0h-~=P0g!y#u@=t7QVWffnsmOK!9c8*uxD7X%asEMmd^&1FJEV$8Gi{ppf$Z za)aXT56asplqN76il;14VAoVIa&b~I`DN_Pckw18xunAvwtq*n6 z?c`d31^s6U_XOw;Sw$*Box^jIg?!(1#VZz2Ph9%dPRF@hHMh*HHW$k{Y*urbB0(Dn z{H^$}JBRK&*gCNMGeo^9uPM!U<12@=O$kncXT8YQ0XU-Q>i3DBJ5K}!!rzJ=9_Qw7=pyE$k^kJZ!v?@Yn)KnP_As~8|Jp$#K%}BQK!!NrlVriXLh?(V$n<&3l z#+1b?4M#-Ti>TCVPi@rM%ciDE4rLrD3x_D*v@vma%SpM!k|6pA8-T2_xQ?QwRSBMb zcF#r7b^~*@h1<^g7gKI`P>fBw+NQ3L2r$(S6J}Hx7=>G(7uZSO{X^~RJn|v6uOxBnv$ejd z0BuTX_Jf|m-1^Ahr#ooZ3(FELVLOW=*ROm-P9NG_?p_BKfXS=M{{HQLZVPfP2#q5w z)fU*AmNIwGg@e}gBhu^=6w`&j*>0XL7Ms!uRK7j;HWjxcco2G-Gxsp)&VA3LH;ghQ&&y;F;%B|Q;uPIe#06;lIk(QB*S zqYe=Xkwp}(mPUpResH|Y$t z^3F@bjg9_Z`m`xN&Si=@v^@*GsNTUs#4kNrQE{@vA!?!Y_yC?CfrqLhYD;0P^|qlR zl8R|}u*M`ZD+iwuwSU2_WFdQ9MmG#VlNt`7&<)F`smD7Y&ptR2k+-kIE@!2v13RlJ zm?pxG+WH&IYOZ-IW?m6`dE|S)sz_iUQ?D4;L$${0cg;U}b1;cT!I=~#jgqK2g`hAJP6bGpP+z|LxCAHo` zVD~`4CIE~0^T1rx&E1gyRlWRQci_ON&W!AK%2&#SD}P}zUpJyum&#jL*pcDu;u_U^ z_Vt^eYRY07OIX{`Et;ZbC=ruT!ux>OO5q)1yl1qyg}OCIF}2kh*uMfGyAu?FHe_;E z8XBAznGSJYCU%IU7x?loS^zgXQlm{;*Uj5BlGM~w(|x7HunqykpzGjDxgn?DNgR)* zi;tPfL|yiXRm9|evO1~GHZxw;@VAEXmx;lgwk4Zt7zft(7nRgEmhED45EQklRu`@s zm#lR+$wpPno%yeEVa0(YnL=JxRh1_djZN*!$-4Rj2Xr`O9DkGJ&I^g-YKAQ5Qk@jah1|;yy45zMB z^Cu&>Ya?@F)<;_88B z?i}fnQ{Rf6A*N*qO$91z4Nh3)A2u%IuaX%>7&ln!J)5g3i8cLd`lxK4RL8UImgqJ( zXH~nx4`HDOGHwU*3h-H z&skVSs@Jmc#y271$h|MlE&M{rReXFfXX4!KuaUIWy^jFlc2o|M9=QNVKn|=SsBq#c zn~&1bO#aymHZmhHB6~S#fjJ%a2>TH{q+m|IJv`!GqaZ-i=u~7pAbAJbzat!tYU#~w z?$PYA#Ihk%e(Di05jwl}zQh~15ZiwWQ+JJ^S=!BQC4C4bHAkL5%9Ds|7W7=}5h|IF zY9EBVGi~@xOq|VW_90qPci%)NBpZjD-8^6qyNZQ!sDZ>-F|#L!POcjn$$WVgfd6Y8D1N_XC_<(svK!Ioco zWxRwdk(6R0tv7u_Ys0U9TGiqflNg-zRX9L$+35Z$ZCo|*lbV^O?_6R?Tj(_l2W6a{ zcH1PXzXEeKZ=+azFC-lYkbr6 zCLAlRtWoUG_u${*8YxCq4cehD)B20vu!a6cU!7cHM<Ew0LRPX7DrtPunL9 zOHHAjppei!e5?@yHQSV>nu8qmypg=yu{>d~v6k`R(BpIhTzI9JfrAw>;@by4{qX|( z+}7PA2`$yS2--&uiCOBhu>waozbkbSEyTo}q=Y2-fIE9+S;A>Z5Aw6+VaqBB=Mr90 z^vsVr77usNzp{CPSR#TDUcmyO!Lzdn46{7ZQ8DkUK#zb@z%(soxRW3veP?0*Yx!qL zauIKn@FXZPZNOknl~6)RFj3<}597>@0X!hGiOg;NjLJ%K_z_* zV_lJV(Ki4STq3^l27`CMQr>+XfzJoAk*`ylb#sPOk`GML*xO*)&z4|1PFB})lL`cd%ID(M#NYMFUFHRQbPxvDo;Az5GSU@=(P zGszsA{sAR=#BIi)aX1x-P3gV!7=OG^q}D(9-VMode^E)=W~+8R(ygc%SP*(5Ut~Q@ z)tOvP`6!VupkMr#{S$_hf17<#xO>sBli8W`z^1}uhLlwDB$71)Z73x@FO8k$CtWbp z{Ako{MsauS_g~7cB3ZRB^i)lD7WV#p09<%yWx}~Ai}}{@-luvc7QGj=5T3!_U_jMI zdEdR>!(YR%jr_9(zZ)%q$*XyDo&O$hG;RGR_fL-_lKQwFC$!MV1z(To)ue|XyZ9TV zmK|d0tF}c};zw46*3BY)lUWGK5K?P9m>90w1HLR}UR!T@yioUN_9L5LKvn4N216vG zW)mo*Qgvx9bG4NT;~kj~56QZ^>jsk3#$YCcp4aeG8s6WatOX!Up3xuOGA4`Gfn00GOri-HGVY$ z`Tg4`Bh>Ri;m&RO_fszEcu{j(wM_##)v8F^wnA#OxK_I!a4-XN^W6b|WW4OJL@KSH zdFUW(MAHyzbB$lScv&Fo17C!NLr*Qz04l1`K5$wr>yyT_B&+eT5iCoZZ35`qZbu6x zi%Q|<;a?jDgoU-le~IDRO}{+LoT4>55C_-i5=)W5aE~a%x+CU1Xn=?&hc{(qllyWF znm)lwW9`ww#|$%t9`QNb(*s4h5ab^+>17whGvdTw7ycOMz%fAs)$Wlxhek*9OhXB6 zrngZ{xCn2`2lB1iGz zu5Weao0&!~+$Ppv0Vh}4VhUBciH6Yrh6I^`8T7W0VOE;IR7;yzNG&PuIHzV(4~rP3 zA0D#{e=_cy`9*aRgN9je*l<+CDNeI`R#jTuF~xlKRQ0A0NN_ zceJxLUU!!fjeUfDdloIw<`wtL%W|6GHO=e|S~c!@m>*jRQ^K2L+m~K>zlOWCF95K_Uird4gDVs8yf`?uWJS>xX_>A8;@;y zk@i)&3%XQ48Tz7c$g{D1vh5i+T7bJ?-GjvUdcG`ecvljLPElU+8xT*(*DM3Z6Cm$=H&91FJJt> zR`-^e|8ARVz9M;_uUG~3@{T!9A^I-^F4nN%t?j=*Pq*uIHC-FH1h;$5Mhz`sARERd)N?i%SVnAOGSLLd~ z@E<+jJnnB3u+DO|nKl9lp#e$d$Fl-#XF&ry#D^G|{NHw~qO=?1Z~I3+?Oe3(WEte! zL%b>2W^CXtKM?kH12o3b8f1wh0L=~LDcB#9Onko!Lh;O}eNt&j}-!PYneVvE+qW|1{HHjqM?6M{U!D zEeu|annrru#jJc~JtBuSC+c_m zjW+A8Gs8)FJgfTQvUkP1hBj=n7Ui5DngpBA@O(+1RI}!lSonXWUz(FpTPG>}yCga4 zxOmrkI~|v;~Ugx;=cuIRe(RZS9iOh8&26Y_P4Vw{0tYsa4s}Vl~om?)u zbv?{&KkB1G194HFomI{nAG3lb^DjJR-Holduf9Ex?I9EOL#L}dG?8Z!Nc=n9An2(d z2*VlEEEzJfrUX~_+4v$|W_UEhLwxy+p3{Q}afVYUa;5{fNI4?r@Wn!O$&_EM7Z%q; zxR(|D?f53wcC}<9frf(Ff;axWf=u87rL5T_7e)p>k$0F+Y}!Fu#C;ApW#l;3ig>tt zphG}X4x~gR`kkrDX!R^jh!p~MPLp|G9USM5_M4-xGUi5MP{cT6*GItgRbWPRmc6A31ZNn~q9CR;#sWA=Yi#gzfi--Tkn86<^ zCLdbJK`ZK5r6Z<`Rt}=4@W~1~JxE?f3z3wpkUUd?ceNyO zRCu-cubJ~j1X_?^=c=E7@@{S{;p6FQ!a5lRc>ZD)Jko>jW^A0OD8mTAnJzf%nB=~~ zXm%Oivod=^CkV+d^y=+zTL`0z)a*I(87$Y}iQ_ctaZ%q>$0UinZ4u`OBJtof zgc2A?_cgp8!GrbhtX_jXt0@8S6Cuj`!^R7jV&fAnI|n!47v}-nE)kz~ka;Qefi9tD z;{R2NF)XeWMC71#rQ7??-+}0m=4+iwkg=(3Dg%Sdas)sBWsFl2YVhZ6n!eh^e zVWD4I3rYhfJ6-MmhW}oixZ93(8JD#*AG|OtroI|IEnaW$NshY9KNKstZpDU2BV-yR zA&cP=*iu^folMUrvbEm}C2$>+kPR#JFU%N>oAB+Wq<~HgQrY&O7r>) zmbOY!WsQ@CuH4*Qs+7c*z%K*!S~P1l@sfoSxE-r9-jWy!9Qob2nY#n zY>)4oa?>(0HmU-y%)clV9@fR59{Vlt5s=E>Fb~hV48`?d3R9S{EI$3d!jE&g4Q%5Z zaGkqz8;or?SyUBYSQYzNWS5@2AFgA%Hxt{~P_9h<=hWa?YKxM`!;m&~OXo=^nK_ihK-DeSJkAXpHf>_e% z_bOK0jD7*NB9`qE+xQs`B9hmY4vpw@XrQ`TCmTkInAGQMFF~bQ5@x3!q@7K5iGLy- zWjK*5-4J_k4)w|B?NTj&|Ja=?KfX-34D!UehXS*4ipjCwhp1`zCDSui2#V_s!vb2iL zXh_f1W*)g}9#F_TU^ez%qiF+MOV^{NrHLP|dl@@~MZcJL*y~XHYxVPV4XB=kp>fT6 z;ylBy^ekgMHFxW`0z%BQzgT7X1!(+I&*JZ-JP#*fCz^kQd1v-~7XB1uOXTZEd`pGX z*k2ovF&VI)g(wDP%d_G_Wl9PUW)}!WX0=78yHttkrTH*W+*yNv$E(DWy_ zxGs9OYI)K%$~D#!Q}>H5k#cT3r{nhu!rdcR4`WV`?wdnsmaY?A$U~zK27am^Eepua zAHziab5ogS-&F6y$Pn7{*OWcR~(%r z+Y;OQp9nwZn^zeZX{H$md-Ec&OD}B z?PB8l4=v^%tG8y=?^jc(Q^e8EkvXnMgcW1wMuTtu*9#yRzSg7Kjg38>bEI@j?zQB* z>0N!*cs5pGFCD(RH9l)aXt3EeaP*>bn9x~i(0Y*wl-Yjt8C9y)7O+z2BtEmKd@n!k zqIpk`EeK8#@C1wgDa%}I8$9?OwwQVS6cznW;fvZCp_hlGmxW`YFH-r2B7FG}>Wo74 z{AUB{J|@)h2P*L3)w$y_mMLuq2X5!UP$#A84!ri}>s5jLiev!bsBI<}#2JI}ZdT>i zs8YG>iu!){$o|N&X(j(*GWjs9&Lr@63T?2EF5jsVD6~`dEwF#V`LCne`BHgFvw;n- z?4YTwNeNEIfTOqRrbWnVa>&A9V>;sE$oyXb@R2DzRpJ*UK6@$`*?Qm1h{&S8{JQUC zS*f*{@=(2^x?+?TT8N{32Nc4SAfkEN?Jg{&Qs4uyXvxerWmy>&ck+bhy zgj9aWAB;_&)Fz#uy;S!>&#%I~iwe$2PL_A&H*uGr?bH%?8n3j{;%vP(iy06uuekeJ zXrgM!OF*?Nacja`C}7#npVjguLwebQVPH>6nCffcj&KAPICsQXiV8?2u@Eg!hNF(= zX2sVKHXre&;B3Ft$c#=XD!Fq!-gbm%7={tn(~PJv@)vrflfVIgfd*y<#a%tAYB8=Kp*f`D(*q=)@8mGe6X!wf>chXzeauUOSHM5Jv; z)G(j6_^O07G(s5tZ0&^W?5jJo##mZ1f9<06Wz#Tp)`{1@QV3r~3oZZApv2%`eW!^s z#Afh?qmFjpw*~{m-knf?DZI@_($~yx`u8-h2phQ#mX+R`2Mv1ku*8UkwNTWb*K30N zG;=q3%=CStvKXc#(#4l=0-elcStET#x0Zql|?&=Cbwl6Sh2DX>|maqi#VGEBMn z*mY#;{V1#SUzc; zdYZv!7@=ROMgwAotgh)s2!}_Kqbp;6oE~}xg0EL~d~l-Mlf7HOc~kqkH*L-HuM9tW zz!F|Z`>RVP2wAU#MU+1gkVdOJrW+i?eIE+PvxpHO!5mo=mJPyzQO?D{Ci-XrPMDBU zi-aCSQ-lge5(zD;v#+74j>u>(7UfaaGEpuSTqs4$Jd`@j7Xl40nBFK!xe z)NMd9H!XI2sN3Y;?U-0gOCf{VaRD;v?ZLQ%ao=tfpY;%p-&C%7uZd_Y>K|GM@>Q#h zK<1*AjKwdUTQ57lWmym7V-~vcqRQ1+uGFxL)0;TX5Iw=dY59ij>;cS%T*EoTLa<$% zPmv2d5mhKwGw^?qDL0uNATRQ!I#!{sex4%!zyn?!qe4P9e(#zS+-&!GiaRB8Ike#2 z*IZnZ&91N-!xx$%#5MjN53<7Xa_qCF3%sKZUzEo8zgu9g>PqM!y+4%~qegB%3~=>T zeC00|ZUOt^2K;RpxW5zmS@*--aNsX_BlX*L58M7HfkEaOJDuWVo%Tn88SlR0xnryu zOPHI}lw;zIfiDUyOWO{S>pd;#OnLLnOE-yNj;p%PsEFq(d7mo30|c}!#z*Pp zI<#L6&w5rSwdj|1((uL+nQiC39FRrFj{s000iBB^9o)i8i_%bCwu@pT<*CSlR}$yj zgqMf)xrTD5YG!5V&*Fz}mA$H8OQS!naE#s6Sd5X>wW7mxuT?Wd$L!9$hJFY^LAK@9 zkAJ)K((n1@cmEWz7>C3Gpqis*Ciq z>)?8a>RS0>|3 znj8c5BIEptP3SZw`~9D$U9`Y{+r4+gbf*R(R$oMBwg_7s1**OL`{5k(d`mZ7@{XgD za=Oc5`+of6S~B3A^MQH)ujAV?!ZkF>mG|)f$sULJTCo`sb~!PLW$Z<|G_tLJhUKnq zI()t0k+$38lRSuVxM$~*L|a0=Sx1So{URLIqwCNd; z;DXs{_48}*o0VVGN?3`JIZA5_PDCVG`+g zx6M|Jw(!85HNmNC7?4I0E|eY(k_>v*fyWf^DL7TMFnqkXF`*s5pbXB(cS0QI9IWjX ze8=_6L~tu`P%7!~tvn{W7;d*ou$Mih3GA?N-{-*r!ed>Gv=FF%{#^m9(Lb z1c(C~SlY10Wur|5>W1;jxmP>FvzsDcIWpy7wxBbn#058duI(D(xRwE5!aMxul(Vre zx@z#*vU7*%oDy(+y_=wGPX@gikweb1XrdMvAd?|?2ow4Q>}i%uAnij>G}~{@xz@C_ zu$0andaklwG6ltN@uh{ETqwkVzaCztV?|Fe{C3N}23$^*r-AC+QvR<~%i^T9tp#JY z(nX}J2gkv`>EPDB5xfhenN}{5tSUIL7?Y0maDP3MXqxhhX}#gr+b)|ZKGp$=q8u(N zv9zJT0S1iASJt!hKf7paOiK{Z$E!OM`MYQZC;Dwv9%L?u-&=Ksl&Cez6K-?*w2%?8 zUa`>Y8#Re>JZy=Iik*_WRtH%BbsWjOWLUE3>mBdOO_koH{>LYSLtG!Kg(f$FNHt4V zc{j4SokkTkg8`h2zo^L2Dzb1`4j+~Ewghd=Mlofd#IJ({xYirZDR1|uDxJ)Tvb*p! zcs`TE-nHw04Ixqsfp+T+2xNfcVA?G5hvwjGE;9fR;TiuqYtJFyp_vNd9s6!X%|bMH zojWK+82^#gMwn<0Put+~@r?a9m^cG$?%cm3*78LSLpu51k!QySCw|oIRKx@yRT&7l7g<9X-xg#_};d zg}GhTW=O=Ws|d3Fe=Vvug@OsDJeLMp+z}oBP`HR6__KI7Q})#F8bLPD zJAqY#z~IJZf2tBI$Q!M=wDgb4no(=A7Q7V?|8JiStS~ha%#ZK}-RwX?#43mmKp)P| zraHYKIc4wC(Yhm`#v$-vRw;Y_?LcSQF)de++1gH<6-M;MaKyP*Yx^V5y7_2&ex>p9 zf`zbH5Mh-QcV=bR+uZy5Sfz{Z$dXA<>Fvv65ak(Zz18Pl>j%}9zFd&8Dc%LC3Q(Od?LskQIEWD#d^@PVij;k)TUiG>kReF%}e3pkf=t8a9(&b zQc>E!o`l}V6|0CD^vOQ-Qk2OKXIwt3Yx*vW0;5J20oPEnypnU7o83JSu7)TflrN2f z0o~u6t2b!2f62IgIn^ZUbG7YrzS)p>T5L;J;zifi>~3k0cN-(8y?CjxNm5ol2F~`w zjLV@&JmLnTmvAylg+sx2Svh!Uh|X8vn7^$Fwj(y{d(p0&ao%ClFkug-5d>c%BB_E1 zP06Kb!w6BSNJAu03A@R{HeuJRS!%M(EBVaCOq+;Mf?8laSFSxpu=c9r!ccbsAOGil zbz*wNNL0j#X=uaeb*bL$CVDRKV`dn?&S*Dg{z3&2KL3o!ecUe9>=fFf#yNxre)aNQ-CjNnKNY4y4O562 z>JNaWDK$$!=R^954Rld?*V1GDz1uV;LL3d z>{L?$JDQF3fII?*OZ}lb}(}{gp>sdRs@2~pIKLT`TI`<>LP)P zeatp!Vf$-qnEXrkcUi~Oz27~;*J2)nDVpQU=q)h!-wyP2%a5GqwEdgtO$;0pP-t06 zOH*d&cF2KD=SJr`e0sovR3zB z89dvSA0P22sSU{Ym20GJ3o0M88}gkUG@ME{s}y;n!_xA?;+6IQoZQ*R8O;W{hT zTLgS~oF2>wZR(59vJ!7=pYuk6NPEWg>ySHlgbP`ON`9CbMo>C*7qp6r=%Ll+54&gQxrIubJKIWG?F_~Y-9n*%hxygea;$7oweh|2 zjh_(~>i|u7pgwEg+zauVYv7DhEY<7tvv6<0?x_e*IUoHImkj6F=6(bhCq6_kW&{+MN%-E?@_e@7^Pj5046hNLOS~r4Zih}nyi@f8*dwf=$->bsMeIk9;bA?Ev3FVqj_M5vhNuo)5dL-YG34MN$@Wa$L&q=M~}V@9>_6DobT$E z28|V0^)n|Lruc9xOU;V=JR@;3Ng9bN=EgiH$&XHpJ+)09)9{*hQw&RSzXZjk@jDsPLuSv$!>;aDj(K>*3PBj~3; z=DLC|n$!ucs!>!3WA-&>M_oH(-UwjZljNgTmk;dQwEcF@!@0pBk-hniG?l_NpI;Hk z2c3uszZh``3Y$o8hT_x_qY}hGh1rJ>u=c`OlZH3q{AM&O425(pj_RDj*$<+?mf_VV zqArrE&Kynu30cdoC#{}{zg9C*u9Q9acJQ0U@KPAGWNGk)lN*o!B8D^hn)XmMW_*VS8N2gfg&D1ptCUttGO7 zur^I0mj7n7@9%}YA64D@k}qYxrtpLGo+H2#lK^X^jY%vFi z2Znb)1y)zin1n^v(4ZrnC10xG6e=oWuWmozL~Gi$ndJBNE9QkB;=VKHUR$R@_3AbQ zx=rqmgfPHCeP~2PF95-2m}(7w=i)v7zKnirp=fC6N=s?eJo2NZqU1N04_fnX1>W0u zc};9()g3MJ=n)*w^7QB( zNQYlF?QZrPfh_sLH)rE}Lp4Q|+uMB;(JL!bdCIp@Ma}1`se+O^lU{816UaDNdxjkb>N?J%=#B;34N91`6 zb`URU1l!`$)G9X1JzIn5mKIWz*-P}bXIkfn`n-1*f808r2B@+wu;kqgV}DY}NRkNs z(lb-_&qFHIf(RejOTyZRz`%o5A@g&qgapPB9nyEALQghEE(d|iDxbweb?b<`ci~>h z4{>s^y7jr2v~V?!g=35##PKqug!%&VDim=YuOH5JV!P*-%&4qXnp%RezyAO_=_-zd z)J#9ub1XSVo}9IWT(%Nia6s;7m$G68u!!D^4ZB2yUwVpup4m1JkQh1S0vZmu@gYoK zH-@*pe<^hy3W`OWh&f4?A3FgxLq$K~N^jYwVNa(j>Fz#cp6cJ78CTuppZx&W+$<}I zOZWwPKs0^;hS0&O6bAh^rtd3NFQo}5Cm|MHFlUwS7-!b721zK@PfL5LUuO1j#DQ$N zr|5oKo*TJ5N+fnLr$m%%#2Dxar$Rbpf`biW2m`hrChqgk^;wfixa(G^4%~&7W=c|b z{%e+5WWj4RC>~<$vy(f*x*_y6$EV2nl1l5L{XspkdAC|9!5snlshx?%!BMq87A>X~(I$g(hSR2mH&Q3Q6 zJqS%(i^(o)WQb);cu{5FNUVRm`>A`oUF`ML)-1h55}84 zmV3)CWz_&jC=nXFct`L(VgJ8~3U)^iCXByrbn)cY9!0Q(vRVzA)YddzG>kfom=qor z8F8ztTltR!g3g*cax$7Vj^TwIbGR!-*&jy9x-iuD>U+VRMDK~N4$*lQm^)UMcD@n>v zxMzh;3Bwm4E=uKgHVQ^X+*9drtc(*)xyIjm8Euz)ei<;O@Y66+(hE# zW5REh&NXI&t*S~PQ`c$)_1^|h>vmM+9H4{=?E&MluUY=LH%O6x$0fop^5R;@Kt(}A zws3V#{Vs1TC`}=$C67)@d?pdtKA9XuT|*&qwc|aw3C**gviDoRtg78Zp4?~M*&@YZ zV;@{c1j$OzFs{=5(2HT2XLbD9&`cr8kF915*w2uwcI0TH_~!Q{>4@QRX@VQ*^kpF~ z*#XFDfq5Uk7?MF?U<36%;9qX0ZM3qEmj8(e{rVo?Xuo|jD`UE6WW|5ZyrE{?`6NsO zvU#IeBy=ZTZs*jl;uZHQyuc?|rU^h|MK?6%8Eviwa#(T&;MeDMqoUauOJ@}~L*>aN z-c>8RDX}4Ka)~+{a5gpc0H}l#_>XHftPlrfH?+70ObjNF3&IdKlcC=cBLtGj+w<#~4SNGyK?a?9_^J3aM(APqp|hsU)cdWHWtP5a&cv0D z+_@4_E*8-~ABn;XblK@kbXpVccPadcD=k1hIdb-;impeZw5I%X-azzynqk%q0s13; z#XfD!HD@tw35-Y}aZHW$QHC~<=U5_+;rjq;qX}DC%|JkiBmFqE9xzd}n1OvAIAUkl z#wn5|1dlS|e0s?4<@o!PG5cUO6LWS_7#u%7J!!%}oPn)Nh=xdUm;Jp8?v{Ie+~st(n!Q1++o0&gpPZ*< zU;!QhIwg1JvFKn4@Zwb!v;hS4`n`j?^Ct@$konZFt<%^qFb@u1)l&*?V!+cV&u9Rm z276euTO~g`qorLYn#!D!%!dD(HWv)w` zz7bSKRSfgrxpkdtk#%dvt_PzP8q(WY@B!^+?N!QdVxY0?~akXudTV5 zth{Dhr9+~5=wz44R7Ur(_y1Z2oG5WFMtNF?@7sj%ArwZ=B9P3 zsTQeuD)O5#Z^K7!3~lQni<)pcy08JQ>NyQ13U^H%G&P?CNYa(Mi8kV;A3n2I8=s=K z3grZAu{fVheu1j*=wev*uCGR`Hqm~iI-VzChZF$MS6?uIuk6^zNYRK827>NB?o{K#Rr-awe zzjI7QPY6sPB0Ugq4wW~N?tpp7c`iL|s@YD*+p}-f6U`RNs{6pg^T1IS2U^Z$L|e99 zqXJjd4U=~SPig7~c%F*d(MQ19)4xjk%TdaCKaop7Swc-HO|Eu^c6c9CW^iaTbr^>v zvu@H7QP80N5cd{|>EGaM1?5CqShC`Xf@+P1Z7~)F-c>F&hk7K#mS?A?AM*eHJ!!nk zn*F@>?+NMXk)|6S6_ZEgP0%=Jc>FtUcrg5}S9qsYdwZ7k+%YdKV#4pqp$IExmm&}_ zG0-r*+%bbwDCM>la-R18_jd$mi?c1^-%bG?9W;gZKPi>7bc;IwqvdS%nt}%|B8V&P z&s~5t|6@=Z=fJ}Pq>PZGP3iT&UVzS?%4Sx`RTR)_(H>{^&dMYkPVpNdQvwl^^l*4C z3+K+o8HcwD&;DU;>4*h)H*|W;k{VdO2E7^Dly6+lS8AAUZ~kQL-}(G48jJq|o35Wb zF!LYp5jTJR=X+hS8F=k@z!etbJxI)^1wJ_M7Na#^MKL?e^?K^~cQh6OX)~%7NB!WF5E@V#36KqZGkJ2MF0F&=fe?ro%|R zeNbcH?<4xY1BIJqy%jY8yp(z-ig%aCRdD*B^o)dtUh@^YMs@vMI0pr2>@N3jo948e z!Wi?ao%nPTM_0Ui`0%m1OOE>&asPYY87u5WQ|3L5^3vxJqGGSs4sj;-|NlWyVACuMQGc|W?(G&fE)!D=QMP3 zbLXcRw7vO02&;>0Nw&|Oce z&t0g8BU-o|&VY<>t;em=1K}d1`<;&J=0VCZWD55C`nU>{ZK-;M;46^=S^NJV&VT>m zT_07ZMIL=@YWxC!n4IqR-7f7vcyVn=Ix+^~ioo_{{ZZ(-+!)^j=#*pOVTX6H>+AtM zD4_r4x^iA7W0vY#yRD%^$KIq3*@=w0IK61_As?`?6})ZV@2R8%1M6yvxgh(us^_Uep9(UXI{Z+W6lDhr$OJRvH;0ZteECDfT% z0Yw_VN~5%YEIrY?TXN0kzh}b3lL>nM6`IYxmT$IX|stHv-l6(X*=p4C_kqtHFY2#9B+K+70VsjCc3_9TRK>pU}B;V z4tl_R4?@Vj1-6Jz>6ads*WWE>Y-~-727FBOGcDYXOod9NccjB??(mG=ax$eJt_$f) z5D8NBGAArUsfZhLYXp|n;3Dy7Jt!4W^c+@04QpiT7P(-yOgwy%iCfD!@?HjJj^3mn z5NeCpTY2%we)>E=I@)=!fTcXDC%WQaMXnxR%c>f3A*;@JsnaWAEAINni|fMmY{il# z*%JY^zUpCWz;Z&+uob3IFJbQpVrGs(;bj};2TNn*atB_!Owg!tsZHu8*pcCHYyGGB z_9qwlu+>}|njRKoE62lC_J!Q#yG6s(qQk{pUG61*SiUime-1lu8Vs#S*_rdZ2+oxb zjIru6zxwfBi(w9aKTE~vbf9^+cHYT1* znRADhItES;%|NjkVU;xcSo}LRqK*M31ej(y#mF)8WngA+hH7p2qpSHuGCJ}A?F9BW z*eD;}nu$Hg8H3iO8(XQqI5MY5&WcPRt5|gIlMD_`WV}x9kzz_V7`YDg`e$u?LYU~; zQ!ia4f;V3Cv43dqj%tUv5Bd<}%j|(xQkGX*BYt#QTF9IGD z`}_~lyqr{El>QJOU+BGWXlN_=uD8K9u{Z6C3ZE{vu-@&OKOIBgN|85mRpI78q@kaE z)GnMgD9_Vw(QDCubmUIkLwtRWyZCsm6>PNUp5 z3|Erv&K0|IUElVb(|#QTw-w-xK&{PILvmJ|7p}}Q=NAQ|a-VdY54v2nD5i3~vu6$G z4%>&{&RVFtdT<<8Y#zZ=HixVEO(U+dc~N&q)o-qc1uXF$J}XuWr7a+Y!+NxnnS-M{ zk}^mRNb&IHv8a5;(?dRO#_$3Ze1N>~@`Y$M=g505sDpp*>AKx{MJerE#_AC1w2sVh zCidQAq)k#~feeH|raRqz6yyI~m4ncHldjQo?&>ww6?-)DlH&Hu8>tv3XHM<}XbI)R zhxkSsWQJ(M(vEog(E*HwztDi31DJ;%uP?hxoAx}7W1MNiK)en;3wNqizoS$}8O+!R zhecArnL4@i>jN&RKX?Szv$D@qn8^23@Ocs*LpDo~{Ob4OMwWOr-Km#9&`jM`CDv0G z$68S|^Ic>;!0y~9Kq7fMA!SI#eUXc2{=jxqgo%wl_GS-U1OlH@*z}r}+$Pl?O)o?E z#N8ds-eON9Tz@mT^0)Y}T`I`k9Mv8bv=MLqi{r5&7%x9(wo{jIKvv~;E5Q+GZqtuVDe$ouDYD z=3>}r(Fo4$E*YNf82%kq9(S~_<28$15k4?njuZIoOv>;}S%R>alX))c^FM#-nZ0(i zRtP=2a9N*^+>YY}vj5UO7RV95)-W(}6|ZDzsj5EOTwdS18H$!ZtmL^@U!z)BQCC@9 zIBsuP4An0=tg5(EnPO`Z8z}?spjc56%qapgrYf&?30=X981`1=SK=wwi8_b#$;0QH z`@jg54k<9LGu*L%h^D=x zIs@#t8te#V%zer46q`3h;Uh)j;IlgeK}2~V;cPKQmiPqB194en_9PRYM$dmW% zcwGJJ&W06#i)07r9WonSlk$m-shv62`& zo9sO2xfZ`(-`Ef_P8on+!7K51G0;z;#w&g@Z$9UpNvz6`(2Ba)6yM6VVDr}EhpUKA z!3j*F-V<1gqQQDx=HOfI*jw<)IX`!7Z~fXBOmfWoWUsvZtI1AHE(Q*9<7OqbPG_;8 z=sARgW_5GFLujPJLny_+Thi*$*9*?4|H} zIft=o)bZh*+^O}`w|%E?#4H8I)}`Or24*OjjSL~xGAmCHl)%E3Yn9Yxes{rw09*?; zd^=0g>GL(;QG(SgZ?sxVa7QYfw{C=!c>nlVG7+Mj8=I5dCMES*10$mW*HI6Ygg8ez zLTc~WkyCkZ5w!tdHA}|l79GBrnMajFlVNff6~hjEP&7Ca zO*`TOeq1OvrGDA5BPsvq{>pBFpY4;#b-1K;4^hAv1@~>5@9|&m?i2~nLw%Z1?LRhR zNjYX~E>x=!Pb%XPzA*0f^~g&}_5&qaeQh59M6r6!bN)khLEL(bbZ44?i^6!OjX5D* z{g{nn6_=tHu3zOnbFGY-SQYMEW;EbQk#9nwKPj>pt2GX+NY<&d4s(?S54p9LGHw4Z z$oFLM<&UWe=)?D8y;dRT_0!bZrn$>^4wtokA}=#4qCkdklMKxZrSX>io`-TwFkb2{ zv1EQreF#nNECCg=>`D)t9dZT6o5pG_m#!PYdW~j|rxYa)oRUqONI;Jqgp$MgP97=yb8XQ$*C4?s5>)u$J`+wt)G$%=hj(exIQvR+ z?Nl3O#*8As0~Ngr3zXI~$Z_xf0mf&u2JY9MbO zdq)u3S@@AAF(SN|hcdNx%1>`*nKsl1+J4zhi8#;f=U3d=alY!_wYA=}_kpTZiuTBI zx2T%^)EYIV-w0ltNB%v;PBb3M?s>26{lNC^69;rw^1?RmH}wcdz2$h-5a;xo;U`7l z8vuWlR;e=?5RdjDXgRj3Z(SMz_g37d)YB+zk)XoK$w^SaeodY7?g0@+`{7$b@4fo1 z?zgaIB$Nis+`Q5agN%*!=gU<}od{~ZK5ES98d0e{fL3%`uRGXvm&-lMow8tiP~>jI z-I25zn9q+aC!lJVUVpLK%u2Ct%_F-E7RaWs2wT?ikS@3f@!RVWA4EG+H=OxZ!fP25 zE|mE>H8UQ-+^>i%so^Y$)ak4XYQLSN#b!9kg`N!I?N=KW5x_BAgEtk`#Dkr{g5w*! z1wF`!J;E>Ci7zjy$MguZfxXISW`j{F{Vo)u+o-O=taP!F>q`>33Pc zYkr6yb3ucbqE<8ny_oDPki=jBFWvyFwsl>N98K<~P$}i=$HpDu6@vQNF2YjfP6>9{ zC7e`wI$!=e^#y9}&w0*JD@~>z&T@6fiiCg|*EkVbAKg|>0ZLX1MoR@HX*&{@J#h}u zSjfImJ>GBR%6FwUvqW)2k@(qxPB68DLEBE>$fR$;K_k+hos*W=O4oGz6_@Z*&wE+;vw zP^4Ak&LdmM9$#GgupDMFqMh22OI9wZzEkXdWc6qNxxO&8WBIiy9}}_ZP?5+azqd@d zw*-^*TPz|(7~L*)Ce5lVLM{ZN=`~_~Ao!^b>fAR8QlWhq5@dRY!^n)K+y%-%A;DkI zFAzNm1s!sJMmYLO#t_bZ<5NHeGrxocu6)4pqnN1Pg3yVmCZ4o~25KK>A(s`)62IeBqleyDQYBVq&cm%<^GLg6Nr zHpB1vb&~#vEn;ou#gcIv^_MhnO=P}Yq+bWY$ z(P%RG51lqxe(_I6d0lC5*7Tm1j&I|~p}Z3$N=Nx-NjC>$>Q(gO@KO3eueL7=e7@~2 zMnm#-0Y(mr!<)>3dsnLGm-V?(fd|WMSB&eK^?lm(v&f4lH?S6bZ>mj_)RO6?>r0U6 zK?~c*3ooq2N(0842aEU38+#g0cHt{Yw!Wbc-Mm_3!A*8I!R}lvtb2)0(me|rOpqs# zHaD-vnEFD+O<^*_rA+9#9@iVquk!qTW-s4LyR?}!2w^?aaMrcfH+4M!sG-v>t+n!> z^!RqC*!-`uCh(MGzH;Znt3hCm)Lob3Aj0k&{#@i@iL^yCL)3rIX;d z9OG8RvuHjRAjX?qI)=8^Np;_Vd}iUN-CtL3Joa-9nm2}#2ObpOlA~YjE3L$r?`OAp z%s3un)4Ed>H$Vl)$yIX2`onSfBRX3@oQ-L6@~SCHOnnN@3q$$HeFay%%nBM6ziFFq zOVR(GU~98wh_MJx`>{e!!B%;hu$T~VO%YD6P;B@|vrBxzheX9c0YjWKTk+al-C;M^ zAdQS>f#&n+-!Wc495My^mqbqgEK)SQD;>dt8Dw94PSb_-xR`XJB6RWQTaDc)UVxh z&3SMf%>y!^1@Q*P!hdB8Z;ACd>|lasi089sVG7e>YQ|WqqkkHbk=dMwtK#b(+i9AoQJsS3m^D$oLBr%W9#7P&@PX$)Vw%({{ zc8v!TNfa@b3hn-hQGb8%2)0Q)Y10Fd6ylRY5wozB0Lq)b5g)E!dRYE*pIaSJoRoVw zm{xxJtS&6I|2QrWDazcypi91Ah<@hslJ)l7lUr&Y`Gyl_KWD(iLeO#~1s$EYg5OhP zvk*;Ou{&))va)mGjimZ6oYtj# G0^>hD(ESd+B)WX3`G7)+%pcX=dscJF%i{)5?Fs%)7M6k z!}n6II-H`Xv7(zRk+e_{3QjJ0730UWdT?ot82LQye+a+lK6k4(e|pkw7``LHh{ zw9(0=DOu%>dV!?5{|r*#-Yw`(`?N-%Vt1YM6k3n75W2-^4BJf+cLZKD{8ep4E9Sq# zk6-=sQpJv@eK~9elN_nZ)~shJprrnLnOB@Wol$seoqH@fr|M)R^(0n$aD8KG{CZ}D zI1sHQ^>;-5!!eSdvY7Y0Hlx~wyXtq$CWlSy;3N_WA>q_dcC1>YkAxsMx9#0!{+fR_ zq!<4?JL$rX>h!y5X`z|*vE%%RbqY-Xri$p>3WAU8GfS6Q#mKtqU7uFIeqh(y$_gUP zL#cv9XC90Ja*JdTuM!<0xD>G>wfX1}O%oe14j6(4p&)+}HO3$FatM*nzdQd-5SG2= zMRjE~3x)Yp5S-qz;>7(4z}{hiVmA1xLFMrXQg8lv-}RB<#dW2(Y&fw3EHb~5;nz7z zFt0?i!x1Xi{+3jAJo$U#fy$6#j2GChAV)8p3uGi=ft)MB6d#g_VeFV*#t;>>~hQcQG1~reVhI?u& z&s)~{O9l?k+uoZ|*>;S-xgT>A&S~ode)!snep`a^!9%~`R>Zr5{>_h*B-GNA2wwuNlF7aoZgXD+SXU{}5vs@zk{~{X@ zFZar2eo5w##bq@5W%Kd}Ly5tE{%;~h=_aC%|4O2r?1WD^3I)cDf*g*b^1cr<&>6a? z-~A2AzgFUhBlmr`1jHEGs8X18)}z!Zl#u{hg~qqNPLlj;rCOuZun<9H$l$w^_(e^x zLivj*RF7?`IgX_qjuf<$e-^n0Z!b*He1uwle-KQMwhmS8T|}(?xVKz%{l_hw!dz-s zR zJktD^AANK7Kbq3M#L4}=>Ti)HKAB!@7?*7|dUT}+7khVNUiL%kiAo5(mMF*8H#`-s zMnQT$84gP(Kdcg`8@Rl}{^ks|HCqKJx=1}$mL?I{2^=!yKpu*bB~avCjck|**0}ZS z=`lS3#f~QDnss_1ZgQ$~AcFa>(H}k6Q8oqDsHLRSzQ_DZJieuKv%o!vFd7TK8%7b% zKY#piO7n^!Pw6@ZaDNekm8yHW`^>sqEn;JsdNTp}lP;{vdj9PvcPqIc>K9tJJq#`W z$*0-0#FIz=MYCkkb*8`I-%-t+!Fa0{iDIk#IbLIb3cVV2mfe)KeM4o8(0fWa&LwR@6wlj;*avoD2jEyV$E?sj#2(}( zTcBS?l>08_actW?M=~bTWU!pd<2tW?HjV2hQ@Q|iZ1~GCdBeb*n|CA5CcX*3q|`@= zv<>faS3v$1n>RR$tR1^>1+Xl+C=P5p>yQ< zai3mZrY|N?+?Ki?e;hMP9&g*vnVD(7p)6KP?b!{chy{X-OHSGWef#hO$TH%BM6+9W zzJLd?lSCvy!?=0B{0#ewoy>KH!Tw&x!-}6n*a4DRXo>>b*TikE zo%#X$Kv?MWeKc6Dz{uvWI|*}o!~4vSZc5SOdpa*LSqyf1P0e+m{LhL&OU3@(olu=n zt4Nnk;I1xT`H*;)Y}$Sd)o~Hax(@mRmG7eE_*t;{7;Ob>VXqPSFfoTw(DW`!^;^Xx z0o?uJ8G~GlZZu>HcV2OB$^|=Ps~+8miR?AsHbQBhk_0D5A~btGRzLk};95+J7RR0c z`{e?;W}>~XQy^KCe}S8Bo|6YjV1w)MxQcD3>Fsl^>B2%qqq%c}1@Z>I1&8ER%t%{d zf;(AxJq1!u$z~V5l>Ig$ zRItHiN_&yo+AiaSkC~_@&cY0z*62Q~>~jnvh5WvBC^U4LQEU_O3G4DVEdNGh?lyjyKmS3GoCkmh=ge+KZS5nOZeR8<%)YOlWsy&M1zmkmJR$4-D z8$c`E+;f0)xNTuPeDTtq@SLS6Vepo0lS8YY-f8{vQ&fdNbn#de9D$14Kt(zmY7}Y9 z?21gfE2FbSYy2t%Id7s8h;U9v6nSYjV|}NLu!uV+nyE1{sZq@}Xj7fASaj@~in9rM z=V|&eI=9QW`(+UzctvHOv>>uKSo*D+TLSr7AV!v*IYoXi{kr#W=m6o+u9@rI9rKk> z5h|F3CJrock`BOVWNJJ;+s|K!{xMUiPn_JbuOLv1t)ok_aKAkM`TKBl8!zc>6Z0>M zN5NT1Z-`t!o^lUXYhAI7Rq2o}<3g|BowD!%mSK49Qv|l&vE@YI%>F*znP?SHznWp` zxKiqn%T~l9SzTh*RiDJs(I9|7@;A-t5i0@Rp`Lm0@dJA<(hV0Z6qo5jnX0vgd;XHh zy3T5~g-n;hKB6(gTfz9psg$eM4fnmw%l&Z6^{t2g=sW!a&d(nO05$P}YTs(O1sRsZ zcjEYwx@>c#V=F}hf7>U=arc;q_tE$*`J^*a18%45Zp`=gQnC;;*G%}Ug4SlfLgW=-;a`{guC69)7H^sy37W5RMP?DqftmriVbDhkzM} z;HsBRd~2Rvg|-c)U}C@m6vLJiwIt#m@`@!O5jLPP$}dcGkua>dOQtxxYgGq?S7J10$6Mouk=Uc$h4iRzY}=H8m=q*X9`$!swsgVn*M1)Rfit zUf-8UR`eg3qGK6v3_->7ydN`)#tFK^nmOFDhyr689UX1As|~2gMjhqunW(5O@4w+X+qOM%`65UUft&}W~G_|yWhZjQA=~jZU)TuxOCrswT+Wd ztCE{D@7BCeqc|myz~|gY;RAUyzWRPZct}EqEm-~0uad>miS>yT<5%O66`rySsbx(% z8(dvVxu5}pEB>uZ>_+ns1^#2`LqtuhmEudq=3IUHj?(9#!*CW+?y6*Sl;q}}=zXvH zvSt|xOMU4eIa>j1i&q0Lp?N2`H)K*xfapK6qGoWso!t9?MzQ*F-TvIH#LSl3%uBfi z?qGET=%UPIJ#Y1A?fYDmwUP$L{H1zp6uFx$B|L+0`46=3{fbVYrV(3gn-E)uO()T0 zcvlUWXl8Ie1}#Jn!t;0J+08^B1r3cOA)?3#>2DtQQTo_XKeb9`y=(0OSHB3&dnOlk zOTJ;Wy6Q&zo8=AZQvWKbJWd}{*wO;klMx$Uo_-x(yEu{E9KI0tV}PD^3avQbSR7%= zFI^8FINJY2&W77FMW=*UPw$#1Zk^(s(jPBk3AUVq@8V4B&Wr#a!f3JJ;1uVKAUrh_ z?WxSSmc@dXT?>>(_#sS#vC+Bv=Lwlg2#wyym@ExJjjbyhg*KtQmBJyjE&#41-v17x_Dp#KL?#wezhI~F5ZH^)G0^x8qqMdG9M_pSeS7wBW|1EuPWO`()!AN2 zqk@EG*U@PC5aH~lexoBV3o2FmHX?A~qb(SFysW^N4d0BCbV2Fpf)aZ9IYlnE`uE#} zwQ205Jk^qj0ct}+2!;9wGJlT#wAbcB%rOfQ27=do%d=Q25W;9!@SbZJ%uO}$^eAv_#)u;a#3YIc5pKZ zu}YnJ*s_b>-!i>j|1q z?KQ%pp@O2FLGu0|>}}D7chqT9HTvMDJmsAV1A#NufHc}FnWc#Su@Eh2gmK#{C5LEG z&BVA@gRVO*KJ*OCKG16A9M?0g!Fjh0K3=qqgwfm{Yc4VMvun0X{|>E3`SUrt8p<`_ zwM;5)UPb%*uwG=|Qwk)ElcnGqs29Sn=1?2e+6{aRUQYTuVat5p7lBT}h%NsuYvr0F zHXVKJwbB$S^v^%JUdc@yZSl4h-Yrz}PnfY0B0q{PreOEkZ8$HM>|VBzk9~T)k_1Uh ze36OuSCo` zJ(bn7ni?85K7uAFGdd^AVo+kj+x6L0LS?9v%*9RVJtQYV|niNAkn zi!oqc>lLnlEo0GZnB+|4ZBJEN8*#OoKLAzkh9M~U(H+3e=OrM4Dd4tK;@23%LGPx> zU$U;LERx3ZlTdf~rdT&C5xxbO%T;a2E*HAAB)Jfm6673%`;lVoH*2tGq67UJ&x}+jvQ?vpAjvDb zrBZ2lX;kHb^rn_dFrIkig?aH7ulBguR>T|DLlLtI;Ms2gLc9u#a~-vZHwXQ)`s(yW zqvTG+_fu%Hbb9mvM4=Z+?gryMNq=D%e@~ZPx9hWQYafm)r21P3@jRZ}4a>=FzoP5; zQs>C*s7L;YBIX~cV&Jr^b^qzygY|Ej2n#!q3n)GO%ejl(Gtr(H;>Uxha#v9~E_c^* z!*`qZiwU*PRuf4^XeNvT8WuS^i^Za7!;%gFnrMp1&eiY9ILY#bHZOL7FZJt2GZAWG z9dE(8cF{7{G`=UtI6t0$=zoH`3@wLU0&)+&1yZ>&v4a_7K?5H92OG(U)iyR_(yD9A z?;*|a4VJ5t9;kad&Ho=$XBib&v}|i=++Blf<4$mwV8Pwpo#5_H5y%D#+#uY6|hy2Fji&d@yn!tRXny;KRlP`h$UC#;LChcqny)LS1;wg5X<)pqJ`rBCZ4dGP^panm|7ho_vT- z5!zo-v!!CiBE|HAS~ohMUp|I?#^9UJo2xs-C|qnh6sSuJNDC?#5S93l*TtQ0YuBP4 zw&}^#<2oS4{bj-g&WW3~OzU`Im=pV;KmnT$o!<2vt^UFVsB!K-(h)F02O0zQ|= z#JB()T!@Y?nc3^g^i>63S`EitPVe^<3PzjSQE;sXLpELS&d%D)ApMCrP_046_-hk2!QYj}63U@T@Q43Ge3?}F<5JVk;r@R7 z6@yQ16ZhWYK|AJxjtv)c2p?BZXKJfH9C-uH6JdZk%21zdd(KCkdwJ^&9!5;R-v2l} zeb2i<8@8~t4$Nwv+->wF4xpz3%JyNP`X!EZ&glu+F3H|dBS$OzU?2`N9bRx!lZ5Dt zSxypTcP|$=Xmy^Vd6~}E(jiVfcm>2HfPJfH>vVqderclC9=baHwoz?&`+BN)E@v9{ zJ3{AH8^eD_b09G<@=cmN>a9wPEC6l_2nGTe4zaiFwAeF0_GPW7rFegkk~ zrb$SsgjG5z44$hg4wac+#r*V};)Ry}y6!sLaxQ>);Pjd*B&(NbGhy}q_7rSKI%qst z&-A{mIXatEYY7=I&o zRIh6GP-%7RWOhiS4Y-)A0+_#%5eb5*T2^0R`}`o+?7>1c@m3v2N5sql&F1 z5roqHJ<6;^nFj-tzd@tB>TN$)r}xxJm&isRteRF>DZ{w3hs^sceLpdwYQ~gk8Z+C@ z%=)oPZ?77JE&>LX9K892RIo?XFOq1RmR7N|D~c1}y(Yv*xSEw$rMaRA8{r(aG|E1) zr0P^{r>7*Vcza)^wWWaY%{l(idrW8AVro;!;#{P0o zq)KM0;wkR)? zCIo-l^Wih5@zJN>E_AKLyZ>?SncQV67-N=GpZb;(&tk!`Vb>uC;09lYtYg=7QnPDb ze8ZSTB*SsD3(oY-&Wqy9?5VHM4O13f$rFv~NrE)fpX95?i)*KdtM@`vU}z!O)ZJzE zeA}dx1Vs|yX;PVXz-b^zQS`YiG}E^EC!8(-$h9tkHj;tD$k+Lm107EZJ|zCTDoY;lQZVKxD|wjweOuvyYjY74mk_@2L_y^pQ>dq4C<#7eJAz0e)R2?)**Bv52a4+RW5HdT{4h zXPnVylBrj;XXWL@e(5Xv1?4O!h5U?{#!cj3{vM2B0w{Cc7%WN08qxAPi_Q*XXlhnux%TC0+Lo2T(= z;+o7^h?5qHIpd@LsJLb0$fO`I1VmW%qMwP<#j|Lu#`<*Qf69W$WkN%>n;Z(?PE%a|er0<+tNOezUSVbmYYV3#`Y07u zQGcb?S|xHvH%1$|D!tpedM0m?%q^RCrnyj(>tL3G|0ZvvWP(w1RJTo%93v=K;+-Py zuFCi4%$qlxp5hqN3=CKE(Ux#0rX)Mva$0Q!R_gNj#_z29g)@f@T z@V8cZ_&io5B8(>plDsc14(A&|UDu38;fEy# zbSQVa8y&F(di}E>hs5yhFedbFlqdXo_ItcZ?1IV9L^3>V$>*l8XOc_HJSk^>u@!&#q5Jw*7B<0i%Y1QZ3bgrI*zF4g=gRh?Rz}y<< z$)xV9HV>TUWc+&Y(ll;_A2oQYgL`P62j7TT4B-gD1fMz$&TIU|$C{!!b`BW$Vkk4m z(QE(8h>G>p#$PS#Dke`UNi0(O1}P7eK`IfV`*#9T*8{JO;C~%$u;LrWoev{1cgF8e zSQw}nX^2FyM8QrieVm~(5aQu^caYWOCrai>7e9Jz5%m$*ac|1RNpV{!77~Nl<rrIq)Fn>(~@(@HAWrBya=8+Z?>?i&R#q^dH=Cd3@Y+7i4P zL`?6NZ`Zu`&Sg-&L=s5cBzbVA-@%s+QyuO)=Npyh{h4QMQKAH`@vpSUxy3SInMk$K zN~v4J=u(<1%WRQg=Mfy#8(kuJ_)}mIlq%<%@pP})@ z_WZ}ttPKOb!1JJHl`;G6k}AkEcp`}bMdN+nT%fU{)G4co3fqd^;$lQg%My2pDSRLf zbO$#3Fa%Mo&JTAjw#2&aWWEvD43wdSHMV(;w$syT(c2w2rTcwi9^ zEm}4e3okhv8XKVp0va@chX#rVfiMkC*Tj8MM9{>l!C9YxLXEiW#%PA$jVTXaFn;z~ z@i;!_us5%{AtC$U5_Zd$#`66>r#O94N{Fm&Nm$eV9}3zv<0vQO=0#pGh* zlVj=|;Q5dzv2D;;vep>`hq&$c0VSxN=%KpJ{Z)3|j-aJPpLWPZue6WJG1`)DQ`(bp zt*n?+eH1FH&!);uK_N+)$BD~Hs_N`N7FpQ-k;sAjX3mgY;D%hd-y{onY^c$Fq~+@Z z`cC(_&PqLbYw>8Z3V2|=2p7!>Z@#e^(40gXWK!gw0nxO#k8%^kiOA9K7KpV4Q8u11 zV#uA~+IEi_UbPq8C^U)oeAm5v$EYokIbpMD5#pXm>i~>{+(4X<(nJ#_?6xSmt_PWS zOIjs^ryvjOtD;F$Ix^n@WfjD9`nHB3%(nOH&U9XhMMEy&F6bbNKb%&3IIF|e_X8Fj zHQ)V6+)I%uZa@_I8`~S^N%BxR0ul~{E3d&Lk)&c2j0of;>MmD4 zahPf-Hb5i*2}h(^EEPuIL1>=qfw)kPsg10QlJA%K^2y(bv#4K!KcmAv0o6yT04$pz}+2j*3 zFkg(0EXI?ch1_I&2j_g;;G8?$JA8x3=HuNG_#xY}(fR*EhJccvGO zA~{Y&;KB-?aEO{Pa>ZdiOKs8k5#QDckhXc{c!nG~FqL6R-Ev2ixdB^F)#xf)=nlK> zKd04b-ix77%wF4vK|jY!zD^eOE!5S0MF4Hu0Ch5;Yv_Tt_Ky{=r$E(#MYR@ge6!2h z693vfF_Q5@;{Pd*fwmb!Vz95?4pQ_!gxvGfVP(`|0ir!c1J~59hXFGYloKBPJd?ws zZ3TV|bXQp)X@BJt*l8ET{KZ?q9{up{xB_y4(P1&B62Dk`%nR{;ncoXAE8atRaB7ZH z3T6EL;6U)&zk=I2++^i$q{@^3McVF9TN|JAOHFC1N;b0etzME35Ckk5YU2e=VEbsg z<5=+#L8P$I8I}N0AO^_CVWChF%vL9|Q-l2_ z$+$`QoqIrFT=S!S_CF_b_>nF?TvA`gsiu2^J2DOJI zrnj}|PwN0+r5?wyYj;A2IbDt1797KISP}X0mW52pqbb%(v1NdbTO)m9#@}HWMA-J0&1j~Bnbdc69vdFK_jQjr9q*|j#Tm&>&F4WlkqK}|0qhxYpSp-xt&M~l<#SBHV{2B#v)(PLh00 z?Kw=QS%&{NWj|$zHS}@f6rte-iu1_ttT={%oH}{j_)H+Gsm3fD zaE8TygZ5^&S&Zs@g=R9YJ4HtpQ6erPlh>fO5=Bp|5JRU1_i?Ikl#8L?r}aSg586FP z15HSL=b#k_qts`Q<^f4p4+b|nKx__0y~Db}Br(@6t*;I{@b{bn?crwW(L^={^(ztm z_P5n0Au;e~z5NtmKW|@OU(1|=@DC8)q+{OC^utXRG09s29%DfLkzCX(Ndy4BuYid^ zLdYZ+EX70^@xLAMmUiH$^X-~Kne_DqjuAy^6#nZ0%tU>l8B<1NO1U^!u)bTQ8PVLJ zF=Am=NIrt!!zF^Qa(Z1og3gvaQZcRu3)*1RC;5Mgq&tB*fxuqIEyPXYb4mlByGmY; zE73qi&}%_7;k;XtqQ`@gKbJ)*RvZy!a)$5+4dD!(`>J9G9LAqG8;@s&`1Kz&St*4% zLVe^^AGO~6;teb(Wwb6o!eAvDOoiKEWrA;P z_cQgyM_i!OW^u_UNN42isEm;T2#0!L0n1Y(D|hAfVae$>=I4#sE!jmD>`B8aGmEB$ zi;FP9!vZrvH|Jm$Na7yuAk@%Q^d=n9VSAh_v~K%p_`PXV#;es>37!iUk@NQKE%R>s zQLab6@GYX3t~!yx;?peTP|7EwK3r!{4dWPUfmNm6dV?5j%RV5477w2CF`)0-s5_uY zHyyrGrUX5~id^dJ$@RiZ^A z*|tyFfVvC~p+S3$(4&A)(FxD3QsOqg5M!UWkGhA2&%_S6??pm+m+^?p$LhY1J<-c` zNLmOL0A~a%3q@S;=5iCwSgL6om^fRKKQ;nFFBPv$^Juh}%n-6_g*%29=>HD--@W~XD+fu3jZ#$6yI;V6PqDO`d>NrQ>5!o)I1vRp35Ld zq01z@xz}g}hNk*ox(dO`1?@c+!CZacY(n1aEBUPMc^>H0u+$-)OiA6d{nrWpl6N;z z0(=~)Y=*IDK(+OmMAJh9Kka|L0BUkHEAj%rr*;3u*G;zD*FM1ED=5EZJFrOKxhvX8wz#zjC`28a#aA>!AEM$mqsM z8K7JYWjCq=51L^7epqQ_4Nkt}phW5g{ilZU3k#QU0!Ok^Z}w58M5+g;}S zX-m8(RSA75q7KeH0Z|{GO>ViM297$sj@Xz~4Ea!v+ydeGcix8>1NA#CR3B^;9Wl)r z2*Dso?{%*yATN;C^2j7r>`wwO14_zOZJ!xYPa~`)``mQXE$AXl*~F9kgD3+D2GWoR zK4wHZT3xcER!7z-kW=(AfQY$-`2q-}i3O$?Gp^v*8yPB1!~1%EI{JVA2sA@KxYeCH zag4Q=ao*^@c;qn#mqs08hGhhHM_--Csb4j0auXnn1MktQX)P3I#?OX0HSg6l{Kx#; zWcRBE3;kiKEeN#T$Ck}^52AL_|Y3c&^W<6tOUlG&b6m9 z;6%>1S5~8F5p?tKK2t#u@$LL>&TQD%MY*TUM)zCNM$JBGmz$yM;C9KS!gz*2rjsFy z=9FLRzr{VQ1J|q4Jf(h5raNFHTLm(}_+ulx81Uq8+LR@IqBpJtMk9Vp+&+t} zf5+8t_w5qMI9#LTcDWy~f5?Y#R`G-a;zFh6}lgpnSqJ zis_rfwW}q{PJg2c_^>gJ0q_YKI&zGzvN7@=7RHRQ^k}J{->Z>T{w13qVvmuJF$}Dw zVy!&#s(D1lKSX$2C~lwji_SVf>G|q}RwD8TG8^TH$?t-&puniVEPDfoJYrd-;dNw{ zl5@4>C3!#ZVgP$om?6+57)NuTF>%@x=pK(b(ICQ?cjPEE;K?IB~m=x(n>v~L#IXWK$ zV`ho~+iIuxfa*q(ytSRYZsA?#)(}q?z;T#wr1$Nv(kFFVB@2Hg@^YWtB<%KGxxCmP z8s(Tbrs;DFwT9<#<`LbN-_i$b2%kx*00T|LT6WUQvM=k)%(%KS&&xj+6E~8DW1N21 z;WFLkE1Ywcbx0eP6D&@Vf~tkqO?#c=T`GE>)p<0+fSG30Pdu`C7=9$4xJwl^g(W${ z$T_=T<@B6)J(qUtaS9__KiB9O70}eNJaJ zUgId&wDl%9wl!YGRFl_EBLo$a^@!tLGJF0iW%xIE#Z#>(q{&SI<`l3hsE@nbUM9?( zNvEwjw4cDJh& zqSya%!na;f*i0|z;a&Q|9nuDx@0+JC$x>BcfBvO{r{s=la(s>HJ+lF^5UPf*u20b7 zy~+Puy#KR?AI0>ubcn}z!S{bCy8f#38ShAJFyRg(bm%h1_iSe&MwDEjHdlL4D6LdG ze5?*eB+HGC`*l1uvjN*tbrIbc(_;u@fDhhpO{T5)vpx-*r?^65UGMn!%5p1L=d&REkO2b!JD3j+Hm3>@9gT1EJ3+!ia8^ zuv;Tdl%fJAMKPBW&9faFl)K{khVN`sH^07r=VUNg~lDGxf}G(}w@jxo>+P>(Udui9m# zW~nq)XHr(vM%R-tZm$@Skys7 z3-rPYU}o;PkK$bbM3JLWDAGw{Veo}sDyeBG$uV4DN%HewO@%tE2|Xr$hynW*Qm=8p zgzn*7N$}*qAA_4S0b(6T1M!pFaLB}Tn6V3SMOk8fuD{ewbQu-<$8_qX@0C(S){T5SK%9SWLl z*3qC`L{%jkWoS)Fu}K7ecQ%KEcKw~wbt?%F~S-WxgdoB8_Cly!hnvsuipRn~+rqlhz; z;O&)oq0cBYB8ldCGF6z3B1(@b}=P3pk30cf5&tn1*%m9_j&pG?rB& zI_`74h=h{C+WgG&3xn0ZziE<&Jj~&Z+S`&y@hZkb(R)2tLH_EE1MM0|c z?jCs1V#uSs-hlUyKDRIzWebYSO_(B3kf=H0J@pYaGkCeQgO2-=y@uF0VkoSde?Ct& z%ufSiFwc;<2zki5mmE!FIGWD_u{FdPk0pL_Z zyx~K&yt(M%O{g2xMmjRL72K>sznitTK>g9KX9xBmwNgsh8r#kD%N6AMS@K|tuBy(wX z67i@Wi=;1c#3V6W7o=Wt6jS(R#Pge-yYTx!1}N&)Sy>|VUwOz1=ZV&bt$xVhZR=W2 z{$a`v&$zt64y7l4N5x>w%~-5$2~`&a8GYAV+jIU}V~iXR%D!KP@7FCcwG}V4gKR>_ z1HFIT63#DumH;SPYh^bq~Y?80>qDiGV0^ISAfDh2Q z&?$`mW0yb-HL%u{uLYKq7(R4ty)W}$U(lD^z6UG_9hgx;p^I2RW5Ce<*3fON#G%&e zJhhMMY&OuP`l_MpxVrkbvJv0lap=T9Eg4+dIgh()%YcZWa zY3N&oKPC42)J@K2OP*91+a(Rs(~vESkgDE9uh+b{M9pk$a*TyegrB_!JW`@xgG(vy z1DF)YmmTw<-qp4NfA>R7bsh7w>1X^2H5fEVv`Ov41WBD1+!E-w7T&3;RxX_#0reP* zWscXiS)siJ?YoB)YQE}{(CQCs+RByXuCA@E)5F>v)HZ70C`szDyQ}re|F#CGeM?{`$21Q%3XVeP@r3XCD5^b#MO6z|i(#4=QS7{CS~KG=9DtTN=XmgS z?@wNx4yCG7;@~5zRBf;0T=sFi8c`!<8-s{Kv`7#i*i1X3c3pyah?}5MA18O}`<{g5 z9j2t+Jk#<+0V8l0-RO5}xfG!ymqwGLPWkP#jOTVb?WaJrMJvy%DE`lJb`Np^AAwK& z`{+x$=H2W)wv(I^|FvUkC)aL?CTo zZbu>{mKd{rqE=x?eZV`WMhNp@&;c(bTlih;Gu{7utH-{^F;wtLh3^95pf;UFv890YyYEnCR8&`2@? z?tV=IbU3Y~0~Mnu#tNw}I)C3enpf>$EHS>WUNrIkGCR7db-mf>)l=T)VA%olBGL7W z+C{2a=yAf&DdDdrEsDEQ7jQ-bL;U3yE3RAAgsy!a0cfg4l>2IzI}ztjhaT zbgwR?{`sl>owdvH0>jAJ5Pc!==z@zz~X z(QH=J7eVEuq$DK}TFG$;mW9M+s7?(P?S03^_UPQ*f|u=bkTPAjk`KL-RzUssaYH~PE7sQtFM%J8exFrlqp(?# zcNKb|qpbK)T+18B2fVexCMX}A?J(^Q5%TIy$*}`UQM%(tn8uS~iM*h9!FRSxS?e*NDCT#1N700p5 za!JAsp%ghqBhuj8{Fch4MgnSlYJzXJu@rDv)UxKt>}(^!A``vnh<}?fx|mTVVrNA{ zB3>gyXtI+{JMI}POY%N*>0rrRhkBfZh`g-u5_Xn&WJ^g}$@>s`keCI0hIGY5AhC_E zfj@%E5@b>5IBkvId!iabV<@}5FLP->_pDY=$tFj38trhbd>aRTj;hYYA5OikEfa#h z$N&s{QL-uj0qRmyUR=sGh zIP5Wyxu+!vLNL7WA7Lrcrx;@kuJT3_312LoOF}i=W>!n(( zXs4Mt8b;@tAL*Z5O}`kqW`~mI?$$@5umpWm%lYRy-8~7b;}PvV$hJ%%v$SNDoHtz&C+R^)@al)gKYnP z@HEbam-!;S_LO2iCWvotWvd*AI#4<38U*qQU>%}!_q@#J5hQaUHfXQbP%B^A3Yfc) zmyFxjoNN##Iwiu@x1OHXt(rFR_1R#r)N*SST$z+h+4~}IWlA(d`pYJ@I1N6Q-Sj6O zmcG)`Ur>}YY={7Qg1Ds8FPrvWZWfzWL|v>xcfC+eAIgh>zTJv-Up9Vcy+H`<@}@05 z!I{m|5f`^UF;{|bJF6T4IqhNv7xG+bG%Y;?)IAYYE*V6l(KeOCTDI9=Tq=}98)K@C z#2p`>`WmAYr>hrO1Ye-1O>wx|`uh()|Kyr!ud0Wxx!6~41BNUqdk$n}Tg(mOy7*`! z2B8Xb6+JsO!wqw?+EuXhe-H!{L{7{4cAB)>z%Za_6kWHx7X%~sbONrvedW%XHsoJMZSVN8`RGT!&xr>vQ6C}ZkcSY)W*sZmoMlvEwL`jlH{){MPRH_k7=+pl401pw{z^&7?zr z$Bu|n#fOg7*nf8QsohK4`)ex$=a`p;NylW&HOdf#qzs1f)3foe;d6VG_ETiE4a&C` zwV~B4=Xil)!X)cKyr*_+?ayTUmA@m+GU;Z(sUsZgyfiYgR{_tT13ogzrNn=WCF}}q zxo;}BU;h`qh)nanXgsHR9Al#+RavEskj0TNrPxHL#D%0dnPRy&bfBCf$sDUBe?^)` zL-zRRaQr`I-a^x0^L`w|1R3}xz+yAiu2c{H}t z=A$kCD;`Hh6&~KJ;%WG z3l5hzz|rKcucw;Y{lZVPGz$`B)_9wBy7l!O%K28^*GzqVt_LUFc2Yn7J`6sKlw4R` ztoOeCdzLMgviq~CDP?4V>1T1*@p&*pqzX|#1|>3c%7YmdD$e*G+YgjGcy7<>xqZ(T z>cLkJx89?)&hBbO8(UlF5GfI|XeE=OpOKduTmA6#WiWlFR6$Zk)iA*eEEvZ6*lz~S zIrGx>0d>gf1BC)QCyxh;&Ed0CFMErANxP>HS zEArw4pQMQum^|PRijNm6O;?*7jvmdAjCU?Q2MC)wD(dJc*}@^jnb5NZ7klAcp>en{ zDT0&%8%fMXaIb2x^yFn7gZXA35|h_YQ?uvf#EhpWZ@|4IN7pag!8Q=f5m;{SD}?Fj z7q5a3cX@(i=Q0#Sl08bd(;E_J$Md5S04Zv5+l+pn{QLy(#(rqx`n?d>lYfGiJ24gG zoHUCaWv9tVL+-#aWz0^Sp?AA0>!pcRxUw5q`XgA)H@x7+tox+9CV*YHg6U73oN+e4 zrIw^@AGVo^pDE*%%9F*~t1l%V=$dzm8~M@Bk>x4nQ9B#x2Jn;Qm2*?H4KqFXT+^f2 z*qA8AD<4uO?a;9glfeWLQ3sn`_nu#2e~^cmVq*g~#0`dpGs32ahnI{eJM0Gqt&$;z zh7NSA{k}jgYmDk?vLE0HTyp#cF2I-pd;Z??z~OqzA5g`pB`uJVQe~9!d%`B zlbu#F-29@D4`cxe$;O>XIkUCMC5wxwPmppdaOr08rNP#p<#BvBjI>np&@(~gjBvJ{ zmin`oe@2y*3i!pI2-rb$#E72>DdjtQV|BcyP$X%kO^~@!qhuUWq3=NC){0q=A`^tt zSzdox|3ZJU`0b@E9cmAQ(Bw`<(_s{}HibkdGX!Gug&PbuQN188z(#t43x=pQF^YxB z&n<-RMuTMC&1kT;ObqejvPrQbgMYALEm3`N<-xQ5THMQf2lXt-$unaW4`nSKQdr_> zm0Mfi6Iqe9;sM@h`S$XihJd<3iiGe$WW@HmhxAVp~+#RTt2CVhm4i6^P2cu#>1 z!cZ*O1tR8Iy5$ZWd67&?=O*4M(T?#gRT7H9K~8nXMLt&nrppR~X{qhjAOkH*qVDFI z!F)m>Do#@q%%V6Sf3rW0jV9EA5B258Y33f5zF4DbY0uYbmiq2{W(B&48GGDbBdi*_ z9M8}^3Z6n7a+h$AfBKleGHpuLl_1r%at5jg5_Hd2NF$AfsQo}n>Z>28>HnTVR zfH?TU)b7JQ*@yNIU%QQh9sw}`VFB9Y$#y-%iDeh9#&%t5ve#X3Kc^WsF=Xr-W8WPd zo7kk+WGE8MJj039dd^LoMTun5Ml3JM%ihyr&;m?uQCwbL0`pn^PgZL>4z}MmxE*26 zzdd*lc-H1iZN~6)&7@x(iBNUWY^J&9_!C53Ne(1%4?i}y&OgnzNI$NN$jxdC^xFi5 z_4F;vVbjrV3-ltxaX@=W>}W|gW`i^kHR8wjriXXBk*mk=9kq*ch}}A-w_Rs>=u?h8EYyHp(tYc}{~SD6e{$B! zaFgcsw&+8Wu2~SE%Q@%2l4}1j$hgYm*eXP}yWutebe!+fUdfUWz&U{*XVq%2F&*D% zALH%@mLj$^v(TkOFMzc%7f7mgoKRlPw0OOwVl}hBWBetk+YOYhqw5`u1f=)bANhu1 zx0*e=c4!cN?}Us&lOTk^UBYcgVm!Q z7S%34z8xo2Juv)7R4`@k5vg8g(wJfn@eF_^=)R_IgpB`OCq&0pgxpS6#h(_^)%K35 z66i<59kK5Sl&Qr(_&KOO#ipGdg(tw!K=vEEwZaZwolAJ@yDz zwZl0&N;DEI)G?jThB_Nb!{J_Py$Q+aV$f90b6Kia2Fe+Ja0`~pbnYThg~oD1mc%xZ zK(}yjnKX^ZmZYrf3QEi@xTXGAUm9W;&jP#jxOTG54^YJ-u!j>Qk+}qwsG!H83y8aq zz&eZ5SmYEi3XaWWua0%wm|a2aQpC>)^?kxBhL_SpSJbgkLc~_?S29BXT2+$bNO8ep zW=94G#wVNGml?6*o`JW6c9%P0U#f!7z-XM(I@eihxX`ivJ2-dFy<96G7rtE1X{E%0 zho2eZoWeUL5(_oPinx3Eiwc>jjxM)%fZKMX9j}G)nK8?A;<-TT=QS@SMN#Nmbrd4v z?^xCXY~@dxS{6R$3(d&d6=ZQSX3t-NpL#+)#=<~$o(qoLPdwhmmMZx3a}JqZTHZSR z5q?wR)d7(O{5w~ z*L61keFW+~xv{kF2GLccGznKWOW8y!N}zBb9~oIR2;$3wI&5V(nmwXj;V;Np9isxs zCAbsp6K-J3JXrUPB}w$-CVmu0ZY?c!hk~aoy>%7o{H>MiG)! zGTx2&MzzVWL-BYV6iq0IBrivU@AKT)bo*&_s(j{MMlUUv{q>HZsk#1Cs0KJuk1ZSY z#(t+-KL806jr=8BX~j&HoE}W)lF)@euqS_uKl$l0S`pHAG`MZys2bfPCsK!EdS7# zKriQ=ns33##NrM>h6r+=UN*fhU#s8KHw7Rqv_Q=+i&=K|{gN?4y{iy@YT^xhkV)Nb zstO7}?c8kQ{^Y$`*}T#Ar+|U8jBd0LchAI#&_tjCHsBBXfVUf34r(?_VXaw-%nv&; z%#`>L#R50XYniVRP9NmLYspJ-|IBIeAqWwiu;9Q!kM29I?r+_z5j|r6RMp}O`ctdc z{Wtdx{>P0wK0Bn(nS+&3)lQkAc8k+?@B~YJDp*BjA_JxB@cgtF% z;C%A6o1@e}uAbbU_6acRKJly?u5SKW@6dU>&l2#RPpG4j>5bJS(*oHHOhBw8_|o`x=yeey_?Gnp z8XQfs9kQYJvbEHZx}ViHKb2pIe^>*RHs40q(BW zJXgIut6A@0w!7vaLOk>JULO~;Ily-Np) z$OcOu?F6XHQ@dEiQEb;`G*0dHqEf1i;4TiL1jc#fQi+RZEfV^S;8RcBzuaOLL~^vj z9z0nP0rD%`P*5Ch8_%_q0q5V|avA(Y2iX;dFA=t0dtf=`U_rwqripvAn0pP-p|zF;9AAE_;!?6yedRQKOZUEfdBqCTf}O7IR2 z+Hvjr9C0FnqW7T*a@bJ5ql66p(hX~_gN@slSvMvdwziQI(ucL_Q^m*2*saTw z%dtL}RRe8pFQT~d@1h~$rcBRh^$LddlckQm+`{ey_TC-(a~n~pCj;(P{X2e+Ad8_^ zfQGm9E>UHs;#%_apx`I4AuEIa%sOP7qNnl%)~4oGuLT}ZyLRNRL?BYKFu!tLLeW;~ zV~j_<%#z${K8|V{M?ozWNe7X5HpWQr&~~8!0c!P?;^$7pqez<=PyA;N=lH047)z)F zOlVlquYYbTLK=CpIXtI`Y!#_4CwB7~b{0IPj4R!TxBA_Uw&PI04>dutj4UnrS7EXJ z{oeYM(wPK8N8XnOV|P(n#}Eqt!c>APoTii5$IE^MFPl zuTXwUZrVJz>+d2L&%#QDoVX zs~<-ehI0R+O50q6EPQm@Vi~Y_>HOft@UzccNBSI^%Kp!^=Q(C< zpK}?2>wnoYow_X2t*$G6x>}MpF^CglaW(}Q+d|g#7d5AXIQ&~GP>xRcg2{(dd#ueq zxtL9BIPZ%j9fAvPA6UFWMc)q&$2L}H+aUVdU?clFYs2ZYduWN7j`q3px3^-0`uLP| zTiEL{naEkx{5%6yvO5W^+%tN8FGuXjkltP6k`wH@A?wxnCtmHAmaoQE{%y zoL;bZV`W{J{8A&?_995_$&)=bB(aNWl zInl0UYl6vH&HAc-H+Z}bfo2ModsuS^a+Rb$KlfBAr8b_Ds^I(VEk~N_|GrGS7C1^2 zX#S@lF$`6x;9wJ^#cBG2h?nk)6Kp;FWc}&;*m_3y}Ya3I809p;~);PwME)OV3Xn*NT3BlQoR@@v5yy$pIrp zGnSNlPdUqH-48aAng*%>!6f_28VhSK9$Sjigmwoes+&OI*RK%{`-9qRA-8K`-J?T( za0c?^?NZ7Hp4v<@ovBK>Ek@r5bj(+?P!kd9iMX>X2fc2oT#)@NludFE(YDe)s7HFn(cSB?eiDti_V zPXWHYOw$|=3ts;T7(e}9bjAR9p=#)HCMmDMue$KHeOq2rOhO`WTdyKPWQ$g(*YP)N zMF=LZy6`4`WfR(6^lIbhb_y=&;cT&Lz3*FVntze|mbLMY=v) zOqX>jq!;fsed=!nfR!PY z6>+K;ZWc+}mt6cWA8Qc(7M*y^U$IwahFr)i=FV`tg5=dds*b z|2J%y?(UJ&NRQ4T-5}DP(oz!`DV+l(Bm_nZDBYkmI6^`i$-xNel9KS*?|(n{^Ss=P z?Q`wgwex!(ah?aEHlVHh@XkO8b}0d00O=|^7RAZ2d_Xc$rp6S6L_VPm)yfNn?>GnB zyLEo060iNW0xJT=Pamngt=r!BhXkv?J1g(+q@B25+?KxzikEm7JDJ&GS~}XVu#RGC z?!OWbYvp=EzNyT2$btOWI5=NR2burJI13org#zfDwqzT{Hck(RiX*jl9_e%Rn#oX|!P;uUS6o$ThN|J>V(St_3GKw7Jtxzhj21@ln&nQh zn>D;C5}v2Fh;YUr|LM&C@c1&;SZ;Hwl(X5#x%8Jx^1vIs_E95iV%o)z6d^=b+N)AWo%-WQsa{_s4k`TTf$D%J}b zKeL#~%)H-oB+-1za{X*O=opo!Pvc=^V$Ud|;?8BkJ!4G2HrU;XJ|&qEhp?k=M$DV;gx9Ejq#$?_^X$ z98)Q=lY;GgeKZnim%9|AItc$xt3}5kCa@Mmh0X#IzM^ex85Ajb?$c5S=NyTCeZy|0 z5!tC&8NnIXQTR+8Fnun($x)wNAF$;nR)2uQ|CmhuZTAIhiZ+srSanK%hn7!Qe@Cj6 zJ;86nX*|>D{B>ayVVwvCmrgE~l)I9pF+8Yy^vd<=UQcS2=C1LfTEBkeuzcuIo8O_Z z$O%f&edG5)kt=|dz*P{R&LE+XyBHtwW*^UYVcU?!K@R?lW$VVNw1XPi8J0^2+ft1W zi(E%niI)9RP9`U~V{W27usDu+Io>`G@|oM=a(&vDty0MFF0RCTBo9P4MZ3wnT`e`g z*70WaIPtSiItN61L~vto$o}lBPn);N>sCoGWrenj&5{{Ly7d_$_%URK@oWAk)<&WD zD9OJDFopE{=(?Ak7L9+HCA3z1AlZ*0`bW)S3RyvE7T>v*6}7OzANsLkpDz<0D>J0O zhxWBXW%fR6GdMDh_e0Vs4`)-q`T_%(s#!u&&vFj+d)g`1-dd?ZILT;>EzOf4PCNMl z$u3=gXV$c@uxs34%(s=^`$mV9e*UmtK-=HP+0pp z(VQ7-R!%?vHk$$NomM%4!t%XU354SvLw0e9S5cj-0Z?3GlaG+9o=Dy3v5r0p9ZBCh zyD#iI%T0rrY{Xrpo`u$Z5<@u2XB{_P8d=M}pLjKfm!fWqQ1!hvwGBTR zPtL7jLT>RomW3yjBnRD_^|vhy-JOh&U?>{1_J!i>R<(*vE2!v1Zp@xozuAxvW3)l# zJZAj6A8_a@D~AngH#A8 zz#fg~ehVa=qRmET4MjW8NlBQPH*lDOHBeck^l$420)! z3bJ+F)aRbN$i2HJXEqD{aAmmQG3ATW9GS=M#YTTF+Upp>Pp2F0oCqEA0j+sJbVu$j z%P9Tbou=R1IhKyY>W7XPzSCG|{V2OfS#SO<<#_dU2xoTgd7P@~8{Hg*cB`Tf=dD?L zw&6jok6#z*c~DZugUwcK6LWLtPIbC zcB*07i)Am3x5>&2=ShC`w4I**R`DGNACu6BA7am6hb}`q`)Cj$`&Qvk$v=)`M(c9_ zKL>$dF`faRnOkZI;Y`i%y5k;{2$U@ewA|W=1V_Af4(*gZMJ7(B{1BU$2BD2}^Q;G^ z4Gnx3y)(4ECA-fI`f()z=*7v{y{l9;wWOWrODpnW{);AT<-7jV5@TZRQ>ldl(D9%& z@4Bt+owq=?qMcz2Wf>@CaFIlYx@>ZE^E|qn{D!_^pR#FehuEa13H6MnYGb3~j|rB&%RjhQsN*Eln9f(JS@zu7WX}iivTVorR&htKXM%& zfF_!8aU_W}CKbXIQe%@dvK{^cOHw3$RLa>zF%AW~4eJ-Z#yb+d%~JwqpMLLREk5Io z%7Vb^0KiZ0tVqmstPBP94Z2E+E4AtEr|HWQzqz3aX$?|SL{ z1oY?E!?z)fDBuGexwe=1AAkRx_tW^N=a+Dw=uNJ%E=MRO@->^b$goS%r;PLkmN-|Mor`Whc#l7IKF8U`$xC=Qg<~u#L zpwq+BTnmQ(e)Xl%pJp*7>vX(RFQFpQ>CVthml{TP9U?=rqO3(lg=rdZwPclOz)F`H zLuCA=R_9GTZ6Ncz|LTE+?0UjEjgVmTGm;LxCC9B{loK=x2D%}VTyXWo>ft|EjFKLh zC#-KV4LOATM^#XxVSf%y(lm(S>Emf>n3B}jG%NpvRfbhY#qz*Ux8?fyZry;ypAN@H ztvL~=Ul5mJ2Ijvn$LzH{_^95*fMP|;t8$xltf0O?AM$>BD5eD9A=scZ>`6*c`_NY_ zDR+NUO|%Z1Ld45bZWa{KbJ>`qGo^ z0}r-C2?FwdiX(}rlwgavETL2am=G=H_h28#5%1n2mHOU;{kq9=kMRwypzd3%nmXRGVr$;|6W0#)gQXy7RkRlvD61Er=Wt16xcyAzN`%r zfSua<_VX(4(V?ReaFQrI4`=~PryC?66pka4J5Icx zL!&8h3#x7!NQb?mts!msjmG3Qy6V4vN-ztK zU5>>W2#){2gNvt9C3E!|zkGzjQ*j=c96KnC80*~jTOs?2{PSolQ7!7BB_cwFSMeAu zO7I-StlUj;5;A^I*ib1TH$`V0TCl4@%YM%TA5tCJ_EZC%X&$ETVw zq@3*X>*&c#Kg7auM~;%XViYJ2&6Lf2#?2@K^lKn7ORn;Vf1U2^%AF9B3&Ka<)1d9e zbUsyc!rq@}iC(|WqFv*vgb0^hzqsvY|C*s~wJ4D$(S ztDsB=9slGt`As2rLtmq}BN9@~>Bo|YdILAq7Qd&rV-+;Naf~wKR-hxID_pLpH z;df7-6~_ms0mK~t`Fat2biL|2^}Owu-_G(RG2Ug~4oqVJ_}u>}4hdm>KpnFSF!#Xh z#iswBL)vp^1kPTEVkBh4JHl1~=0B2d(P@Oe&sg_%V zJNsW#xX92&1I-x4i#6@f9NAODaJ~&-*AP=2mZk2IR0KU;bwNV9{`)U$MDay3key<6 z*>O5htHBbhf$KzKgv>thSKh0#h!|>){2T7LO3DKAl(V>&|AbsQb|)er4~N+}C}V^_ zB1a=usfjp2-nokxq6$l)v2S*eduK<=pa(~LI6-y(MUW9jTMMyS=HIR>3*n={m7x&) zzxn=LCw{3L`~_}8f8HFX6{1XIQW%+~siQb9xj@axsw*BSYt+mnRvK#!36q>9F`evd zPk#r)Wytq_8p5bA?c9M4?|zc`ZAovlxUrHUT$3Zw)UC;|QXLJ*mI>IuVVF!96EL$ z)N=gILTctRd;{-P8I`aOydseVLXN>a9~!Jc=crpPJdC2G-(Sswo^A78x7#?n;_;

    TS>@5kUqmhib`jO>SPC{eiqbFx`1337#!oK7|N~Xn1-(!XySM~Vj#i>HmMsD%? z{mmT6d)j_$h4dT;wDTK!jTw?nIX376m+j(2>y)hU>`-CgKl*;)X%hLVeU8VV#mXhd zaY#^n1G{2NC40LN2gM7*@Fgote5Ubb^qJtMFV>d9RDrBDd7=Of(Q) zT&g)87SpwGk_nl+^GKQn-Jd$+dzf3GOVz3m?2obHs5q1Y{h7u&ajXL(cp!ePh#`-4~AmD;C%qA1n8d*Ks5{Ond; z!Giw@YTzMNoIvxBLhFA?LOz#0#%(RwVqOsUe8~I}n8wurbop>$Rd7fIA}p{!;|3^H zeN74h8s7Jno)FlzQ}#}|7E=->=k6zC?XE$}hrj$mVc`l9ARe-yC=h zV1JjL*=n&JZ%TQbM~yr43_fwQOU;ZbouC%yZ(7j$2pkp3Saxv2+Xk>KLo8a_ss|Pe zyY8b`ut-QM!TCF9X#LRQK=_F_c=CAT2BoDn9)9CHv;NQE_&hxB90X8+lI$233Pi;@ zuohuF;V*e??Fo(rhA2IVQb|jjI>hx8LA3{hevv?XS(!zU{i>$tDiuQCUg!B)`q35X zfdOY~l$DP527-sh!WzPhRk#5JHvN$Gptg~7UWa@}OSt@aYNqwi9=;ewtA7MKUwGTY znBItb=fOuBspvL`WW5Vtr`@QoI13qs8~8r+(>wF;!A5Q?M}2Uv@w_h}GP1xdd!=I# zUhLsJ0Tygn~Fjww{x2=7H zxF+td{NMj!df^jZhgJ4nc1N1bmGh08*Wpi|;}c@t2B2@ax!P?ea>3~SE(^Z#_=Y)w zL)yN4vPND&lHpp9)1&dME2uqMs2dg~u~+lTraabTqRJ>6``+dMdI5ZNZ82y-LIvt0JTGapx-;SQQ}eVXy^ z#k>waf$Y_Q)>>H@7!SM58@(s;yj=Ude{$hpaP-fqJ0c%Ttya6?9GGSQ@cUro$3&6}G?ZaFbz*k=YkPXN-fTOe04M50^)TNEMVjns|( zj8o-u`W-w%OiRNRCp0+!*>pZrxmf-*wRVrpT^Gh+xz+BY7iAVZe`%Ub8b4~a_^j>? zOHRI)ufBIe8_G#DPmkf5aeIM+UWKT>%5>iqN*XJrE(5d?UM@B&qyg4%9>b=)6dsfpv zn2b5;3eUU{9s-m_0*NAWvvisnXl+3Z>?q5Ra%ZTXW=+LvC=jKD7-O|rpUlJS%jzDW8-OJEK!io^Z zC_}Fc5%W2WduuE2q)xxJxv>r{&S?QeY?9&ptC6b6=D*^t+J%e!(Pz{jmhjI;?g#V! zNe>P^z;cuuK<^)UD<(Xyk_S-6RtCm>bjgL1lO++hv3E_qIp)^1Q&hAO?xMV(h2v08 zeZ|wSkoPESXsZqzAQtC^235Ea^as*ti|&%cj%oviks*>uTk37h$GxXVqbrw^sy3io zUcvj+tqu|CXL(DypRe}X8m-jZUaKgnQE13&K!l^KpaqNDopkQ`vz0H({nG%J%PVth z*6sP=BE3YFpy(jMGdMO*4%tu%vx?k@ynmJ-dyTpWCH((=VV-=rfBTj3GzS>p2eNR4 z4-_z-{LWMg%vgKN^2v={bI0&VMG%IeSfWCL6*coh^EQMv{z5$|l1J@1o3n70ZjU}W z8$Fy?&COQ$8(73QEG3~Fa7Ex}Nl!IYSt-nsCW?tIP0K@8$lqtUT_TL39C}X|wn_bm zzRtR6rra*&w{hjasrCHf;h+yL|2FRBL^A};li!SL7f2D}e5s^irbP1t-~JJx z#oC_^9lHSUueARl%yJ;e8qhX%b&K9<`0yQFtHDt_QIQ`XOCth<#0lJWnjE10F=+DY z$rqNc)?^aWBHaUG32T|S7$0vg0G}NGT|c^pPvSkP!wqBqVAi^ud^+4E5Uq>pssDj@ zh+mtqv3*^S$L!{Y49pCASd`pvGOO7FERBOXc8YMD)ncQu2L~!XFtVuOvxXGF)h0Ud z)BArn3NN0RjNG?SJRGW%#}ku~JxGS|Ph3|;g~eJ_e)gDiiIg-SGLF7{IfXSZ>F zXWa4ByKI-Pl=|Ljy~)x+n-zTM;@^Z*ld>&YO1noz|U(oN?&6(W$AgabMuiv0vBt z71z}@ADU6K7J&;C!NZ^7w*IEvvxj#^)i5XxOOV$`CDXup{Nbw1+0wq9h?`st9)CUd zy9+;$Yr2i+SvhS#$EE^wD5Qd0j!b)SoCk-q30Y{RWE4n2uk>nOYPkpfLtjnpc+F4T zdSSd+6~q&9RfwcXMpHZQiuWI`HdyUujfrOE z^difqo#Bc>sl1RmoQR6}@e`TU%3WW`*TMLyfiHyBU)3HlecmXiSc~u8i|r?I?EOu- z5;u{J%nvllWF0k;yif$Z!wfC8mp)}WW%TsVw0VAB$fJA}Bhd_s7I))r*&h6hO3^vz zUzf_{;;(N1T`K|-I#0afJL)#6lE#_>< z<+YfjT)Tbeqx0Oo`2G|*OJ;{4ON?BWd;4!k=Lhfpi~YIhCprsXoQ*4jgUW`!MedR7 z#Mq9Mo8@dI2BE61yy+!IBEyC5PtAT8L$1NaUZ3h?fj`$f`YnaN=?*aMp-VDad>XUK z7mj#oPPxSX0wf5Sm*Tg6V01JnLO%dAEf2z`b(!Bxd70k&#r#8Eys2!5u8%zWcE>2x zd-&x6f@Wv}%WO?Z$8(_3m#gpX->et4VcDwLJHJfEMI2zrO^gAMsiv@4IRH=&Gc2Gw z4304ASBzGslZ}+`0|8bd!bI&U-tm4}EA=Qm?;jGDVQZn+!!X_ZngDX&^12KS5*f6l za92v!JAbmzA83A@a0Uy0x_|Az8sZ9{0~jM8}*mU^B_ zx?-%7VdO8YXa`@6KLS9W>?)32tv$Q2zNax@SG=?^_(a~5J+fwRT}TCGc=Bd_k!LAD zN3()04+&-@OV$|pmXOsq4qOT9g8o`JJSwJAPrNb8EmPW}h}On`c}4=&ivlzkq~{Ym zVXsHw6RY5EhJ{f`ap~uPTS|X+TmM8t1xX8c_l;GmDb0(;^FJ+8&+ZqCuIZi*#Jd%a zycn>QsO}o_g(*Edc*U5*g)HWLL0vlIdF!aO*}UI}VFW1qj%YwssleI3PRt@xl31ZX z?$DMQV*)q|Wg;YiblWs-$sy8>XZ991)}u9^6#%)S*10nq0}_zd=ph@yksB3Ho))L?^e!+wIuHv4$u6Fr1+5ul5Qa%NsV@@a!vqnlMhTYj!;#~(a$WC%33?g1+gZVQCrYMrf z&8n<4_(EZK2OND@B%F?IVNuEn(InR)z9Vw?TNEUz{!D`SBHhf5GteB&HM;!B5P?!4 zEwt{<95GH27EJaP*@YeCE7()A#-@%9me_)|C zsC#4qAMS>Itzf*ObpwXak*qGEKa!&d(Hr7r+ZPpT-d^K*OWg7yMEafg?tXvGKQ6(C zFbtQsdz#!GC1`h(fXTL=;?O+{+zdUFSL0(|((| zl=k7O)7(C^p7=PsHfZQ9CdS`>lj8TSo^I8yG+>S3e$2^>nX&k z+C^yFAtNoRRf`5YKJ)x&GW^U^<2A<~wZT$tTTEursi?a1 zx{J&F@Efe5?dm(v)Dv@sc>YLaF*>o{iQw6Hu?Ts^My}Li_fJM%S?$ zwjgnUgUdoI$AV;NJb#*6bJEv2)6O-~>g#O3BtjSC*c|S~0l9AR32HxnhH~qvYJy?j zd8m_|`g$TU7zUziB~6jmJfM#`yl)2J>Fsm9nEGosXXBY>*ZUe0+_awW5_KT?h1YTj zSEtMJ3_Mhnvb!(KG%s-wh7%|@x5P<##ppQggjTg;DJ3;yp(3Il6b#(XY= zz&i{2)B*kqSu~YAD8e!opIg%ALf$P%@U`*{M)5c&lD0l_>hZsdC>P{9V%YmhDjgXy zg0DLtee)bmBs$HNrGe?Twx47O1ojN_>AwsmNOiGrkWKX>o2&vUL11LrzH5h-Z*e<(H~@!T-K- zq`y;y29YOO9PX?!kiUt8M)w_GG?nr}M?I1*U7~DU?-PYkQC)G)>^xJxaiJgo`zjiK5wmCN;tu5K z@OLB*K=c=~9rkV91!)(XrA!HB36D|%A0bw$+&TqkFlmAmR+zF>k+oLGx^o1#a9bYf z{k73N*u?8)7A`BHjbEd6sxIWj#&$3|){3ucrSuTkgZC$QZ^CdNn_jmpk|@rt1(bu} z9NSPAfqb19;kB}4A26%&24&sqhv0)!e~msmQsRc9z51u6dAU5>xv;QaCX)Z1Z#!t- z$LH(pXj#p#nk~KIe4;0M2n}4a;P&TR54v{LP1C0`*mu}*8#xP z54D|B0nEySZnD7Omr=A-ZqmEk;wA~$02ilEnF@~3ik9RptH*2iWO|7^Ek96n{15i)XDMz-eH zVy=@WJ#&#Ynl3TL$hZR;^BHG{xZdwsvJSr|Cfa&B)bi3f&H#$Ty+4RSWebs^Z<=3) zgmkCVK%WK1Si zsID2LU90 zgIh7Ct7Mt6{n~YcLu#(?iv|UeYbX15|5=d_mkR|Zk_VVkq?%m;j|8Y^#(T<%=iI($ z>2E%oZJv|o3cfVc;Kju-(hV=v1k)%aZLE|kIqai5m7fTRF=QSmIU{H%X!Pd6S6#;} zIc?<9g}{Q}iM~h=0nsN2K(Qn&r*=2{HkF5xUpVr2IfL%ugafk|+7#~`KkvmCef<@T zQ(M@b_|t69z^-hlLTQS)GFtEBC2^eoUX$bC#8uQ+qOWK|n@&{bBWc$`f3V-+$Z`Z= zhT!gv`(6F|t0r&_r;g&oOIfLZAs7F|zkqI+Pdrwm6E_^RgQH4KEoW;F^CfnWF1enS zTuiY4Vg2LH&2zbHm8i1IJ1wpe%uA2y=0eV@q-#JH563Q78#>=KN2_W7I0~zAoUV`pXz7>0uV=mdpfO7 zB+thM*de=q$kWJHxD(U$+vb-p;z0W63bGC<74MEvNR27Z@*fjcK63%nB>fvVU*Cm} zu~;tpdJX1(IieX?;!%_T!K?X{zaO8?zjXAbn|gH5Zy6X;Lxd5FUnk-(cQt>s<0OK8 z6Sl$a>MnuzKzP#(+g0BsoPWAxF8!TXKrGLsJBBZSPZT;oBsp35{YxIzi{N`2fg89Q zq6l@}^%cP(lLvX9|Hgl~R=?9uyulBUMy}0%e=pDU9~$jb?6*XH-IK3eZ49A7)+ycZ z=47=^7KbDwY1IHW!fa%kO<&b|puUbr9e?v^y7Jv?y=FeF8+yZ8$Ys2|83k{1&=%b@ ze!eE|UlrR|g(>#8C6|MiMmaShJf?E{#=?}FMBM4w`y`hj!!RB*Rh|m(G};akb>3mGruu&o{(P z<+3%Sb*HMfQqDi;xk(MW7+1~W+}-;XB|-`Ip<>l?D%TlTDv!tlOe%{x876KzCD;Y0 zQrj&8tj0c;jn>f~!A%U$UM5Q(kefv7`IgiC@hovi>B zm1oljEWd0Gex(BMGfz>NDxReP&Mxa1fW-X`p6`H?VQd+e*%tE<^LIHnH`sf}Uhlo7 zBe85vL$^{a0}2Le=W)fXT;OmBuTNGkPkPlj`Y`!xg1s*kDw+;S0J~RA&MOv?UX)z9 zIauEV=#SX@zQ0!EW|hhY{wAm5cE;y;MN{|rQqC%7&w=oLS)nGxzxeLEVfs79;7tn1 z)yowcd^Q!Q%@8dzb19R-oCK$GeyY@0G0%oy+FkK)uKtXkt|mJh$#pf9dUwO~Vs1sA zk=?s2q)YQCP<)gG20RJ|N!&U!d80Bj! zm{u+7WK2!K*5eOA#hlaaarD9eE98S)VGLw;y8u19^*?xfV;rzH3c-DfAyMN z=)^~@miBn^c5yx7A06NCFd1GKhZ8-~VL8r8Aa0c~j{#nVDP)R~Q1|t&nQ+esh`|^ZeI69gB;|CkVF#b`Z4d6IoYccT*Nozn6L@ z#vWPkNQm>E7B#Xa=d^W5F#L4>uuEUm8Jj(8&Onc0^Z05&`luM;f3paTTO>VYA1vP zJUvF7G{$?YPU)fZaQv0JEr3Guviyza_?#pM*=!Ew?!PejgHm*Sr4oD1rOi;EGyieI zpwu$|(bTgftQ{OvjgJW+27P6OYo)V*9Jf+R^s-UTB{xuhI^$7WMuk!mH=# zf5q^{UJb96e{(x1c=EPQDDU6)M}sTHUw#pgCabJ*&29PiHUH+YcOvWU(^-9p6KX5w zem+9LTidmAKF)Q_2iBj@8(Br3uHM4fX-E7t6Vygm)8)?GvOWcINfZOB|LeQI#aoL! zfgk+v(=ga(mdP87(;;I!TQ;*ZGSw#9`_o^QLpUk&t{SzV_Z9`A5l z^ZVBOvpz_q^{Zxm))Mb|9E!c`)!zZSGh79rpj(Zlt>abfI()k20Ax)ObP!=-2UBbw zDtvPs3g*gfzI^to6NmKfMR8_bN;>3rl7590^TpIVq9ak{simb`E`EJT!^u+3!3d-s zs({_Z1u9Iv%Sm+alL3see50g~uqB2J=?hDwx`orqiT-1O$44ed)PF>+=l^lMKN`$5 ztJp67S?u^uS@ZxOy>}Sv-)8dN>Rw%Q_UH8;rRp|=MRZ&2)Xs#(`ftfmOS`BbOG1Ve8y0ux1@#j&UK1KhTf$K!n&_hLg{kr zvx#-t6FQQU_{Z_VY*4`m2C5InO=METRFhNEWFPGs2|Wyx@gwpc{=Nx(^^N?!o*Wkm zh6IYOmw$zwko;f=P+J>VRrNwjZr#5wK}eG%wW$93(mvH*8!P ziJkmk*_#E}(jp#M4w_)DuD5r!q6q5@6VzR7a>l>|}X#9!6Q@?B%Iq*@R z8oi^1P8NSWFPcC0(WO|ZBIjqzLxdeJT<`L&7KEEO?49TzLfm=I0V#=4wXleXQLI;c zS=+X-oIs{9fc=C5p`2jsqaQD8XzaomF)wdDqL*CA?<{E_C!0yL^`;8?>I=2uvC0RP zR_xz@lo;nBGysbX%#!JWc9^ymz@u4{6{kx2uV^P=GrL^!qYx>+|Q_k0aBi<0eZk$n* z+%p_DyF)of1($O9Kuh!ri}ckBss`FyTG$*!jqh+S+eVF;U?v(?mbVg24 zg4ahX`7;_DI14jfr4#TxQRG=InvD*3_;u+Jx46E;b7B2B=`u?)%Z`6XzFk>@N<9tQ zFlO*utv?jIE!|Nh6lY&lXv)?G&KI3o`DWDU%G$<|6Vn;@socofx8+R*2~BT>_&`lYPsRr0hadFlaIrcz z2(=%38_)b-FF=p>RyT0?x^d2uuq0HtmGs`IZXd8+D=>PlQLy8Zi4LRJ_3kyDx+ZUZ z!SpiKcj~R@j5HnefH65DsL`cI`K_X7=PF)M^RR- z8qpD5whkVFMuWB*E*XKtnRLU>H!~uc%~jRyuC>r!pjmSr{OJu!s45kMP664R1ZMgk zoaDo+hbp%C8C?9{K$JLt$)1$S(9Da_@QM{yNthu9gDqNP!S@cLUvO<#GSsZ(xw5wN zocSU*pV#CuN+8`5kF%Y$i33#Nsq1V3R5F$_Lp|rOilsIPsi(G{R;_Bn%e1!G>Rb}w znUm-9vN#YHyR7g zS>J5-BC9kT!+55SWF_6axV}>}XXl+;MZcz);vD~kMuO3s=gH$wLcjK0>s9k}uH9GM zb<|y0zOS1=OG)Q3{ij`0u0Cd^Gem<`S;ON%Q)aN*Ya0_`t&8mEN{?(4eSfcA#}v!- zpMA|d4<{XjQWGx=JE-u*(YDA8hD>KL)(`8BFbX7{^OnvBCnT#_>gxnlgxpppXE2`R zL^5F4TiZHX#(!P=4~1M`u=V>>EashOY=?e}ZU~spOX_MX&Zs)7Dge< zcbUh0bB^_^#sAU99{xTh!Iw)Ho6?Oj!7 z-dB6fg+%~%hsB8nlf|kuOmBCy$yi6})J(L~smKip z{=Mwp<#Feb8?mY@L$oO zed3(tVRpJWGVOT82NcqLO=B5Y;&#M^$@e+tQ9fJ{))#f!bu|7yPO;!>eC5LcSKUr} zx0MVkr9frUA`Uii_3(NQp(%Qv1>@7QB$^M@j!i}oxnvY5Do^by&VimSQm5B9A6EEY zcU1tXElMq7sj(9{(3VU1+A7MoXNV$dI*j?Hms;Z6S7f5x_#)ZSmJG)+?WYldw#|OSn2Um{1M)KK(Wws_?BE9u6{J0a~>?MKlKJ;E);R=B63E ze#vSO2~P6X-Kke)@#9+M+9*V6XTXRc5QYAH+@n@lZ8lJOXMmP+KKtJv7o4E2% zM;VO2Xt>QS*-BJwA^gozkGW|ktIY?+RXgIf#%tL8%%f0~BDK-~3112!XIIi6iVgm* z;oNVA&b$^ottdR(##wPK(Qlww$tFT0x}uU8@6c?ArIrOK4~-cAI`oWXvr31k4+-@D zGpf`c=wxPRlvb-5gCPv!D_c~lSAi?4sR?aL?W?~1c<8}F&MrdHJxLxiok{n$+3$}O z`H$H{C{!|z(21`9);i;8>Qmxfb(Ed^=qVJG-(RGT7T^*A6%D4w_;?qaVC0a6Uovt2 z*%VC4gWbK;h^Eu(OTa(tOC%{)@eJouA!=uZT!(fXUWU5Ob|k?UNFnVp)? zuBe??HKdqXByVfuOS|G|?(9|{`leov0EB?+AwG zE}Yj8FQV)Ua7r~OB3&tFT+h@$san2Q5b zg;`H-Ny%iG>IEahze8`l{FmwSkM(^zoRMx8RdX6==#AZK+_@vbRzx4DOo#6`+%CO) zhi3YvA$>T5J)j=6pDU5N2TzoCRP=(uTt<3mkn}?-FFr+?|ErXKx!Et+; zsFFiK?E?Wi$0jr;(wK|Fhg~^j19)hFAsgsp0y`Z5Dh2#lNk$!WRbB%3z@3mnts3_o zfp)J;ArQxXCpG7loNm|pSpZKIiEJ&jTZ{9qs0*ea81m%BwlI&2o^DEp;k2@|6tiTO zfVgqBXg2@8mYVF?F@x~y7op7I_V_`jl&(*KU`fMk>!j)h8Aq(^%%K1@?~hI$bdyl! zC-HvhDLbs&f`?THz8-XM?RBQ&O)CNK}7DI0* z;*#b%+5>2#l6!fB-6rDJBb&)UMf|Cp=5hBjsq?qdE?SuQfDXp^QEzz6#-;-f2KHC* zCcjYI9$fPOh-R*7vqxgczj>=@_y396LE*3AgD8$dxAL!4V%`;*nm1LW>lY4-Ig+#^_FnGw5|W8}75j_b9TxKFb@e!PJX8ah(a$3uWpUA7VN*S(4=b zD}8uss>*n&&?m&;e$=YG=3E6=3R;{6Z4j5}`NqhZX@a1^<<7aIR^5kh>7N(O|Ni1J zQwwRK z4sZT_gY!pRbVQMCqEX&*sO_^w8dFPn0Od;{qtt5-PLFVuE(k+Z%VUJvJU_8|7yYK_ zjMgvd%bPiFVjGk(z?3*J|3AXPGYPEsC7*lGb0EBl3g?zMc*4~n!eE%fjc_87?;;{m zzE5w61lw+Xb{qZkFkvinwaHqwszH*%2>KLJ9aoI5Xdh)P8rq`QJj#V*5^ee%O}ZI} z6i*^=kKxd(O&&YkoU($$=Q?m5+;0ZT^p%*C-T&+L{)3d_*;`d-{9Lfz;|ZP5iw1df zZfPZ6wb+kbWYPqEkuHGj!Ie0AvE z6kq9Xi35qliCer6Ri^Kjc2e^hQ1srK7sD=c1YmY^)#B&}ElJYxQ1?H1IjTQ}2k}mf z8=8lMtgrJF$(j~1J|(a?dP12t3N)&G9v>~}UGAEs!)>>^k#B5dDdzg9K7xNJA&*&$ zaR}{3YWf;pU=EQddT#S%+t=HN|TE?S3dG|mlmMF}k39e1*rXtjS!z^+Q3GO0; zg~c<*Z~O)-qJ3SDwZXr7luogbv@fjWrAhZ2ph_{p*CxU8S`@j(J}O=!$|dsO1XS%J#cvcn{76(nIeg9d{fqd9IMpa->41_UeG;Hg9g)m)i z;gRj2^KvA+4#wa0wG^p}e9t;P`FKcy6U)rgcw&WZ2zr5??Qzs)b?CU+@#O6ImdPGP zJMscq+eRGI9X1nqZ7$+zC#Pxqsvhv5`)f&%<6!khC`JF%)@}Z@c^I%H9y{%J2MleX ze$pS--S7HzYt;P$i&iPhB4V@G*2qk(;@5tY98I*qQWGS)v{yXWvCAE~G_-;_X^aOG zV^PVDH&f&+BQMjiO2)p=z_yfyWv7Q_{S*t3vA=oqkjtCvfjezA5b&PA*I#-IJWb?L zADm<^Kq!-|b^QR$-| z`Ey|bAudrlY6Y5A+PDnK1nHxONix7(z6jcEm5;rsFc%8=Sz}o0;ZFs zf6afINpIx668ml-P&&%7mEschQd6IONp_$rt!n%4bvPcB9uRvD5GX?~GofJwT_jAT z?ILW6W%0Ych%&?lly`DoJ?eGKS3s!@S=J}9F^`;`qmJKi0Qi=ypY?|maK<9G)BiBP zPLJ-6VuUnS9e7g`M@DRLh9-H%ikIXX_XIIkY=~;&MlTe-rGJX zFyPHLCH@k*slurL>EIprjMGd|g5oauHRnxgqe?vF68~hTg!3N9|3l$dtCW zi;HH-Z_Sii@FFJ_qCG{ENL;p%6p*xuO`bC5H&`7}bLq%OM7FbIK2;f7OM1v>iStrr zLB-zI02hyKOMm!wvWIetn|`v1J9bK5;LT3Yv)dzCJoAK&lvvIoe{V^3mlP4sufJEt z0Px~Be4i2A{~XnH&GRldW~yB5!Pv;#67KF5^!LGu3s$Y2m)4|*76FHN|DFFpEhN`< zW6dw{)(O>$7!v6@{_y5z*BRp5wL@tBF;+I3(VIwOm?f1vqr%JczBE+zXz zF_9t`Gkp=6zm4jcZV<>}qfOuCu352IpZUl84UekDKq$(DI!>9d3dPG?pNx+QJ7%l7 zB)D_^{|9cac?4P~m=CnT9R&`KZ{-|gjbU-Nfg`AKmt0Y))AS@<GOEeKIO_Wg-k*_F_pa3y5tL=~SZYRn&ZE)jXn7VBd}Px@{PiO3cx>{L z$rp~OY@z003xqFi8&_$_bIBFyw-*r0$aKiw$R#ef%~e1N+YsmXjCT`RWjJLxe6&Vs z`F+{EjYbUeqRvH-5&#pN$gcNjU6hr!c9{C4SUwXSthxDojM)eccvctB7RPvej z=Pw@O?DjR+hBi;}P+bA(AQ!@;B{SRKdbpgBpGwmZ2y-@>{uusOTrA!lGPx0=QF5Ay z0^dThYHZijGd^ec1T6GD_EYQ~Gc;4R_O@#zZ7U}M+J2*iW#OFYe{ddr%3@qYz-(UV zP%GYcXK}9LoALpc6fcvshnvUf4AWM3-)nhkH|*|#>bFczOyYuOr|$NpEPnEjxe6Bg8A8JmBGS`S9^8U6W*I{C&33OW4bkw^rlmt#nA}djEaKnR9f-|S!4Fa zuu38>$;qt_>BA6XqCW10tNCjAU@#;83{_+2rotvDzmZ zBFfiD`aYG1uLv)rPNAZ9Gs<@F)A@9T6weuL`zz1*&>&AgC8krukhHD=*-J*S9u$Hx zm8rM88!Q|MIgX03L^DCVZsY0zxE}j1 z9Qv#a_04{YGk^07=k_M>+KKi;33}-sB#oJ$g6<+!j45x<7K+jCU6Zy}3FB#p8<$E} z0&dl}-QQ>W9YitZuLA~hAIakGH3qrbnhB;;9Y22YUF{85CT$@O; zi@52U>UB4SU|(rooZud#eo5Pf{)aB5>|A&BMoPB9c9rd^>+$<34PpO1oKqXqY9_Y0 z3nY1gZZIz%ABDQcapqm+SDCG%%5N9`Obc*K?QI3=os4V_C&= z(7T=%@EI=6?Sf2gi_91`5iQd^t@Nji9oRIq;tX!?OiXT15}mQgn$z;Zw3f!RE3hq& zyx{nLvnl?oOQYI(>R0?GpVE}Q1rx7kP!drQAMiGg*P$toKH>z3DV0*rgmPa_%=2)J z^=MpT_Qx2NnSL}B#Vq0Cdh}w?cipaw#ha?lt`6X;5B+8%9u^>22NzZUVPzrzpf^)T z;0wmR+lKF|{rWC{6uWvO*=^DIcD!NkR!>gg5WMegnb*j3zP7d()fMuHEH-D;kwrdq~5 z=3C}kb}pH9x8@z8dJ~tJX0eMJ_25m~^w#%;oM0j!ZD!Y!62*t|$*6H5P&nC^dh7pZ z|DkPg>Fa%q|L?W)`D|pt7s>-0>VF*)Mc+VY#}_)?R3B|1Y-OfdHo$(2MX|S?xG0@K zy)(o6zLdC}E>k&0tEVx%`tYAMDaF%>Ff$$esqiTfPWHv2Gt*o&``zi69EgPif3@!} zpxD85Ed;D!8lSov;QQYln|46c!lpT6(>on5I3h{ksH5{4vGB(-=rCy1s+7A}3Y}Y< zbaT#6Elka+|Hb<~@O)J?%vx%FFyw31MBN35?A<50Mm=YlB$o3kr44!YVLpF9aL>jP z9<24Z)oX=acI{LU#^pYd(B;y0Ms`@T1g`+@8Fp3dYvQWY_=*tHKhB_o`D=7&F}_ni z?0RAUZjDgwZM=mg{r@oExfzZ zvAnxeGKPQ6AMpq%3!%HJ{$ShWAwN?5h~g`uumh9k3&}&ad7n;|^1srbmAAHZnhqPAPok+1Nh#!bVPkEv-3GPf?`kq8?8FPcRzS%#d~ zi4v+=S^;i7vGz3!)EO3cUy_TQ>2>Qqz{nAM`$O&% zQ%E=Bqayrf&o5vWU0Y1QG`4!VwlEj%0cfAO1+B9a4Jpl^7UfPfXXLgEAo0Q(Xsu z&;KS=I5U9Z(G#*A@>5?Y6q`g6IR8owml-Mli04)$L;SLW1kjrxBy;D*yR7etiwqtq zgWY+>@Mx;^d^7e82ry3Z`}C{)N?orwPpTUY_uq~!<^EkV$V&^{UT%shlDWMbmXkc0n$=8W)U})E8=<%iYCr4l zer(;%eQyCTIis8A{C&hmrX;dGEjSi&{!xKNN4SX8!x$rCacFpfN1MlfaCPEPN+@#a zx}b>eiM#J{Vq4;!Qm2i;G_o<-c_)x5bwyrej0#OkOk>(_?dtN8o{o{lqbQ&t3HRUvNCFB74t(A6QjGcq#gP2#32r zp-Dw>gJ|^lNhgwU)7?vN%Nc<7IMY7EL;W2#SEHAXkwt-b_JXmrHY;{{Tmi{mv;J9f z9tJ?&_ad*PGZYdo-ZS=mOBQhYJ7xyJjC#yqIua6RCk<=>Udhq+aa^pxDVRV1W!Q56 zN7rP_CtUe6LxRn@$7P2=3`B%02h{qFOh zM)}9R3EwO>5yP=4o0z|?Lui$BlO0V6<^w0*H7FVnjKYQqid#yto4V$d+&y887%!xL}O?74G-xl3curzAOEqN2HIY5srG``T*m z(V^3@bUaTIX=B4iRgLJ7H~9}DoTWDtVJ_|8a)ri+@_~Hg?=;2-5wx^~ed14aDO3U^ z*t8REhqf8WSRAk?jfyRXIR^RiW`2g)8L?UOc6y+}Z6H=WKVaYG@lD|ggIN=F77x@S#LU)%{!x8eT+5PO;Pg1Kyi9U<*~t zPftJ@wMt-q39icHF?ex$RbIU}b$gQPgOJ4J*pY+XU(7vf{H{G7rk1N z%)`$HBz#m={j3B)6^as3a}M2ufekg39ikmlP#H6d-zWC1+wX)$g8k2(OyXg9*p{(3 zt7lP1N_hers$>q$7LqAao{VL=1Q;I`Uu=N@1ptfJ^%4K90^3U^t{P!;7%B__t5srp zYuSAQ8lO?deAAM*e}j4F*P`_s0m%Dv;J|lcswajxSSFEJbuOL=J8@Y_Hd|iQS|Yh1 zzSYNQjuUT>KVvwVK_EYRdLZL-G60E#VUR?;fQom7WV26Jb^Ss>U3pA#B}0%UECZA3 zJKyj!3D8dwjeejl(M|f+!z-6HaaIlk(+51u1t;&ZXDw%TOXdJv#$dhyxQBsYeudXc-dH06ZKC^H!WAQ>AQX|+c2AEagx$h)x^mW+Kx1M z_`z~(`?cwI*U~4;yYP0;SElkt=#fUAKnDq{92M2HF`S8^!P&99^8+svAEVc|9<5tY zU3!jxS71wJ!zs5p)f`O}=!%_{OyWkF%22qJg-TB7f)nfhrfKRgQ`A79*MrmOWT zv-FuiRAc=O{M7OONKCuHQ|9*JIk@*)mIBhKuj#jORCn7eni*lwiXaylhG%;<3QLRV z1r-Z+6gg_ZV+-jI0QeEcfJ{4H7=~N_AVgz=2J$WA--^z8X_s$RXIbQ78kpT(j4Ty~ zmo>=E5D?n-~sli{= zAXIkntBq+En3(n3eye)e`N2m97LqAxt_wZl26DjV@DN`8dp0Xml)quLh#P}Q32%I40a>b98 zNW1dnj3x(M9Pw#Qok+3}$z^Ld#qAHE9ws>r`>l7DYHp6iNtMmR>Nl|=Sf+vSD2##g zEU@2`@wbFTw*G1;ZieC~9a9mKDlz;#3O4`T@=Zxp(`lZq{Tz~{;DB!xwp$@kE|!<> zj?7o-)!>oLJa6RTBJx$NZmb|7Zdj2r5(hcw&n}CpFQK?|_ik7ZB>L?H+>l@<-R*C(jUth_S=Na^oW$06Nv2>sCr8(yKuVg8ivEyJZF(G-q3_dyb1)w{m$ zo8rwjfa@`ICxG`)Ki6$L0M=4+CKS-KC+r9~J(A2=Jk_xY6`7_l{P<(S0B6sasA_c( z!<9nXO?az^adw4z46wiD?B}9~U}35WW_^;xP0V{_gr6<9r_DH{p^aYGoM$WYr8U-N+nF#B zgx>`qT8h={pZWbPDr){@1qj05oYxi26fyUt1)W4Z$6QoxvfS<8% zBACUz3XFY+NUvs5n7p}!3es0hn*Y=1l7MqMoXYjY0 zF=!=fsGV{T*-^p8QWg9s%-`TG`=U&vV78#*9;-MO9>NzjZaQKttq1NgId!V z2Bs1FP+P|DIwSjnds@<&tPjoz{&YfFr>p_Af~%~xv7|bU%0Fg&yG?O8DIDGY7UW&g z?A^(sG>>3?xmKPZbI#SA2;~F5IR`<{8q95EC@1&Gw}Z-f!YD~+UY#!U5q0oY-ijO* z*aU%Qcr-~R9k#>U^Uw0R|9UYTIfa{Pe|?kJO2;o9XO!$tJ;Qz{eNML)6j*zUx+q!G zX`0NF*MxSbY)s*+&4j=450|5^&Weog)+1kUX}=ZJfT3gH|e6e6zQ`r>o`myGF_g`aJZ0 zvnn|BR6qS65w5gwzy4o>yiEi~k`X;N0Ngk= z#Uu!W7`FmvsmPaJ5hkeLI)wYozmO(GdiN5RR5Ow3R&X8TygOY(!Bp!^C!k{6oS7vd#=>+U ztCcN^MBYa~_tI0``k;40`Z~n^EIXUZwn2dQECSQ>S^+b9*~cT*-SUW!=pR&zOt_QU zPnoZ{w#;17KYkYM(uwpoh1(Lvaf4HHMv@hp|(mdX*M`^|(Ck;SU`4+sz6nMDhU)!M7@ zr)d+fMR{%P)G*#hWpSTM%QU5DP$k{npX`gfql@m7?x{ip*M(0+p~&44%Q^YPrpmfH zo4?JLG*IeRYSDSuc}6mA8D&qCs;rN@(EUV)L(P1#LxV%iLd>E+wkoMuKixkt-(+6& zW-TQW^<7EzGe=C*ZAY?$=QeN8_!+8_GL&z%JiUqMo`iFV@%ZhGJc2M`U%XNPC= zi<#x`+wzsw!Cy!5>WCFn)K+erG_uxu5shyKmaZLmWzyB2wO`NrNQ9-xiOZN@c~GFc z3iMo2#5W<_xg@j4lA8YnA2}x*_5wjkZ6GXYH@yIN>K!;yS}dB3K&&9 z3LZZuF1zq^RZLQiZS%-;;hR>D3~hI_k=4tU)1N3+f0kB_rE1L2iO~*_|si($~~3hl5h?S zl)At&_BjIwks$$7xePDf$20!^kLM~t|by7;~Q&!yt+@obKF1aU?(J~|agAex)cMX7<-10O%+uo%WEMe%|ja`=X zb&paAqGUP9TX*%wbR(QjBc^R}lG~u`Q9+y*4ipnP4~UhRhoj@f)_48H&62$yiFk5C}Fv=vmsur+iI)|Y|ty^Rp12g~=;i+JnOK`gbL|Mva{gXw0xIcN( zWB2vw>b+Gr!hFKxH5|t0rQvImV1HNbrrZ;ch40M`79Bg!7)OqrF&y;z)v!I;w3Wd{k^Uvh1y} zI2Vg89=q}`n|fj81kPTjtV-nXpZ;VoFZ7$6LoC@2Xj&xzjUF4j{r7i|yxNK$p@C&k z3g$SX`1c?p<;D?)vN=W1_XtbYTi#;qvoW&{rEl!MB1G}b?t)0k=KjL{H3kaW^b3=y z$LH68X{lQtSkr|l%F7+gLY90^=6fJtCfetJ^Hdq}2tzlBE@rIQ{l4(1I*>6gtszTYV(ZyOpY_-X)wYC@Dj6abkuB|~Q&fXpRO z*EHDSpLDWDvd=lXT^6#HMewmyK)Zr0Mf&s3O@Yad6MpIP=eTHMv{(jeE0~~%VBoy46ZdL({z?wE(9YkH2|5w}<5Q6$H7jH^YiLPG zt6Ho`lYdlICQ@t7zZKRIv>ZHU5glAT%h!*lmkv{fHUPWTleM=G=%Otov9b3YF|)hsMZ=KfZ@b8(Fe318NSpEQ%1mHmckkZ>smF z?{)y04yNC>9ayo3EI}#d`v+bPi7tI#?+_*Ym3d|`TDSky_`WfH1L?BvR^O%^FfGPj z#_qP+ZU;EC(SFfWFbZ8DdHP24mp#lHFSE9zRz$FpICcbm20_|9UkVkh4puKA(D54G zG(30#Z#D{uPs~wDR8VSUgMmFq@xOn*4n><7HNb>Xyiqn8zxdmzsMcSZ`GtHb(8y}|{igFzZ)rrQ!OQ*5&reR>IL&Y(jJh)h8y5GL ziMzS6@+s@Dd1qyl;dv>9dlS`GvWRQvKAu3Ce?<)S_}5bDB#3<{!q5gh6;Xy)y{Sd zP7?bU7M+t#?axp1RIww66W0GNi;L$FL7XfLvz}XhdgID(@Bqq3k_#H1bw@WwdtD`@ z2A||mkrDi9RDtDO%}zF-ZZ_Z$e1GPF1@KwEfYq^7Mas?1EiQztv_6Ts(N0Q-xl79Ba@E z)zuy6S2e=kNaz|U^s$sBY67Eo~0}KLk#^x?lNype2KcxWBX}|x=D+Q9tB?? zlMcTc_k0q_0HV5)@lFr30jwl5?!NY-wkQsxpBY>6kiJeJz;xVa^y%F^blj|mMF|3X z+3mouf+9sHH!U9Dq+PaOvPe0mu5X6>gP?#i^q_hD;iNYj_q1XGV;q>^O3VL?0mhFAj4%K=N}D(2GoNV znBT-Id;=1>+DMzc-CI>S-NMT(VJqSU{k) zq~MICOKq!F?4i0iSSzNw$+kwUVmp!+8OUKt>nzT@CNJwy#Cwfmx&b~eE6|WE6vIhr zXAdtuVU=B~m|Id`QaE?}OFz&38=d{w70uyog9@E@jnH%zly8bN+-2?jnyDWNVz(6RuK<@0J| zD=!Ad;p`=Ou-3TG6U(dF63aS9+gAEF2GApT@HReRyzV||;FI|`jlyS;F%V~4a%zN> zQ{26=HxVf`gw|j8O*!tVQ5ip1tw-!dV#(pTij+}L10zPjwWD}uLhC=(6*t6eud1*ya;REia+U9%6 zSN?SzQ>)=T;#Z-lwtI$cC4s^bKL`|CldGFQ>pZMgBE#OUvO=J=9;$by-kt?Mn!NCd zPsBW%PW^l4z*O-@B^sVo)wZDSp^2`cFRU2?8Ss4M@*~M3(zeROrBjfV z11)I;)p2e^l4-Qse#`}l2Nu2csmkZJQ6}{Kn{xmK&_q-dmA=pUH8f;(Cf;VGReO8`vPl= zEozZ0VBOmE0JISI5wv-}Wg8gcMJOpTtC0vreS7HXd;`g1}6GWURFXK2xavvQdtV<{w!GOm1*THTR}KUq1zPQ#HIE)UsjO6ffwA5g-wx={RogI zlIU!b!ath(Aq9w#9Yexh4F6)cfQq#}GUms5(h#ng4MCU!3Wh}_RDm$)TXiP&kRzDT ze{%3PVafET=Uk+Fz7Fy4@Y%0A*-OA=JjpfH6Aq92fE<3w52A;EtA(o4be)wcNb8vTgjIoR&g0 z1lM{L7S`6DNS0e&s)Oyi8}_`vtv`I_p_0r>?0610IT`gcU-Z|+saq-KCjNG2V)H7w zzT{DVbW>Nu@x~nC1p`JA8Hkx5r~cU#)Lwo*F$+H~g-5;HD%mhB+X^;>%G@oiySKxr zyVdv-nETM+vpr4VjL2=&j6xy?T0Io(o7Ei!h7#Z`ve?q$0FIVw2| z`lR}O!Q_sIzZWCOe~sv6&hB&r{@-m0Bo?`vWoYU~g39dYC0d}Sk0|GB-s*RM6;~Rm zli@|LbKDt2NZ=a(=o(d8xs~s?QTGbj&~L`!A$G3SV+gM(|r< z^3^Vvcq!kS4fEy?uE`1)qje~Heke~U%YUJ}V%p7@rkpjV@KPcuE1J6>kBrik>0d>v zF{(^}D7$><0##SR-UrWP;fob1^^>tG@p_uSwXj)NWqBG2N$yT_!R%$QcFDIgnb!&2z2ep;e=zbU(r5>|bKpQs#=@r)Dwn?%B0Rdj#fP9vc>C*9^_36xa98b!S`- z>bOM+f2-U{v5JC4?^uaawXyVY#@rxITf|=+{$1xthv~n?WLd=mabWMRjG=&yShOkN zLm&1muy)riTg9;B7uG>E@?BrVR(1|jx41||pb<0z@>oF*Bp7`g%Dm5M;PTI32KS>Y z9}qlGZddW{E#yx^KMkD->T+7=y!64ks>iIg3d*^(dtwh#`4on|pn|B4V}j6@a)k2w z=`-1MfsagD?*t|6vQyLhad*tVN8$3;eID)=a8{g zW|zlOUjK-_;XbtFgEfQ#a|PL{YOL3xw1?z@Xo}YqqX&#a=u4KrG9GCAe1tY9*eiH_ z)iLAo_!@I9JEi8Xi@z?XOhenH)9oC8A%+6RWF4ip>gG%hzcVkd%A?tzVSq*@chrTOSP;N$@)21pUl}8xV zjj#1=@uycmGd7&Tk77tzP6Xt*ojtmUbC8@qUhs zlTP?WM;ot2wasaUv8W)>@WY281ro&lLr}x73cxrk&|a@*^T&yW=YFHfb__(95IPXd zztz9{e=NXf(oJi{=(A=ygPHuR56(oa=>wTQ%&25>oDc%jUF7-Z>Go*0W-|**ik@8v ze+CbL{p%9g?Czp!43tk+kku;;xynjTDO`VX zc?X_l0w!C*#UrcD5AlKg$%fr``I|ivb)s-iln;%b~$-IFT;85gnx}-tgAfATQiYNc*EZ;)>P(`Yk zS3D@Ta^CVV6Z(TAiqb2!q*bt@t}<~-0Clxtx#XcLFTMY}x4QFqj^rZMr)P~3)L{%P z#KvG;!XW}9@?{iysDy_8xVucFQek@a#g@KK^qUkro8b$4iXvnNirX%5A0_5pKuadl z6p8Ft5hBo)GnzJLo4Vxe%2*1zfG^qL5i`rz%X#@S5mfWH{G~V_>GG51f)_n4H86?HJvmU`K<#wLpCAj5Zj^t(EOoui5ap0tV@OYV` zlSybIHD%JCxL)0A#qT?W#;M5Kq#wUb`l&4n8pk=Gio!oBoQxMG!n3N_Ki!eH0|Z>? z!qh$cr$0;DZ__2K`PaAUTL&JWOznvBa9qCgdu8QMo zaI919qyLEcdkJOB>Fd)%b}5K~AQd6iyn}SW#ecS^d*s786Co+=C5C!dFnR+^EuneZ zK;Wc3QpZ$`f$Qv&r0Lwszzz&o(6m*_nW(QTBu9!jZDSmr(K@}i#}}ab_%J|cN?y7z z88Mi()0&F3ZRorZs`Av!-+is286EwxLrL366gfCx?fqlYY{2U5VgfaX?^@72WDmu# z@*HV%J$~h8TEA$e=E&-z2*-t)1T%Cbw)D3M6(|45!p{Jy*kx9jKdTQGeD2=8nD)hh zqFCZ5cwqEZqT|ChHkzx7WH?Nn*cpdX6W8kLl-KWl;~GQnQKx9u+Z}9{5cIp8&6Fjc zR%%$_4y+QMmb>YRyhSV$Xn%7-IV_bAyS=YDJ3#s#gl-gfXC4)N0octVpN_ItBAV~J8zfZQ9I$C2cl=wm&!KQCf);<(?h_ED z__X;2fF;}G(fslY#0iDO_G)*1VlgY?W1HIgQ_XwCz|a~9Pr>v+`%J^n9ae{q-;S|mOE~PyhS5&$(BLWQb&L1G z*W3NG$6^CtU` zWDoZP4^jOOZZ>J&3X*{u>$XC^~q_(QZth)lM3YEzC65On&M%TFuTlC3;e3Xhw}CFr`w}6f zKMn*Hz3dtv*zyDOk8}=8rc&$J5Z3%zu(>r(_o}0O&WOAAEP7MSrmeP&r7_$4XT3R! zJJE`w?7ZbDaB!q4 zYUTEByBHK4B@lzGb?j*sN&$G+;Ju?zQxX9msE9di5~fa=O|a?A9@j(YHw(({-upUw z5i!)w`#91qy!zZ#5=Js)7KXBILJ!v8)TQPIGpL^*dAVVUD$%rLMSa<$?@msylnhOE zS`e0|yQoB4+PTGc-P#I2&6%go;VO|9-c{k%=FI~%zu_D4ukarsiToKw7h?vtsPft$ z*q8Up8~qu_#}7Zal&K6FA>+{=@`*6W_Y;@O!f1o6)whBeX z1DIVGK~q~`WZtW{q?hj3c4MZ#W|aRwcc{A}qvfgl{ALwM*`IP!w8DiFEiZjHn2x=w z#Z7ZVCW@K%DlI_s-7fR)vXlY+kFq)@ufHCbrtIy%l+sv?2FwNJ;IRZwTVvb)`(QKwK#;6Ev>B}0`}cFdtGrXm#;Gm_&o^aj zTs*5MK$FQfoiZ#8_J{4kcgoR&5%8l3Mp5E4I|)Q(`J zc)sBZpJ3R%m)eYKbPS_E{dA^;v>coo+V1ws*|+%aY49sWa*NMhdguYnQxFJjth{sSejmCIhc{vYR%?V<1peHFn^BeC`>o1BbRZG+s(-eaXuV_DzWD14TC6y!oR%a4gIo$U&B zjcWa6@pyNT1LE0&B8z;KssHKU69ShhxKUiRZZKWwQDk=a&OYxrN&j(7xokX~ojaU- z(4^P^jaLDZ0{yQIxU&3k?y})!+a#OmwtrHD!Lg42{LpjMW+Pmxb=V+3*)wWY8o}-L z(^@dp=1p>lZG#s*!_1PXfcmRduX-n~O11je?6|t4tltU$Yhqz=Jz1%>^@+>v$0jyh z{>~Uaws*#mDNkKVNvv zS~*ME#}{pAF3tSYI%9RJSW5?JdnNz|&ksfpvTL>fM_556_*|MT=yJ4q+mCsdPocw0 z$ZS@0W!@i;5xaBDnw{~tWgV_~w0=@oBYICNYi0uL)jImWPoyOM-UTy*U97MW&-Kvt z-(^&WK@gcGx$zyG84-qa^W8@ik+Vp<{cbwqUp^}cS$)}ZIPegp=6cOI4V;q2=+=Yo2W^;+T zsHPaful}O?-yG^lmwZ$^ps1u)Nm7$6soT&qamKW%zo>hu!GNVtL+!>isCt4eleT|( z1G}BeKAi#c}^N#AHo>XJoml0M#nD9qJqo*?Yt zLq7?KA|BGB!^hq)0FKv2l0hw0x5#ql&*hYT->l^|TskaPO2Pu*&iRNs_;Fn}Q8x{& zTY@nB$)ebsjXkI_gkWwC5l7o8dg+Ie8RU*ig0b>Eq(${_KH<0>v8W^%PDv3rHzJRr z?AYkDe1TaJt2y|&D)}Qgf5RR=jYeS%?TSyz+M;T@+o`6DLbl)W;c5Z=ARHj8XLK5q ziMX)%Jkb{a-G>K_5c#hqRJy+&9oYt%M4>q`{5QgL@$a5zRc7R`b44G6OMVaaAM3DX z4~>d5zSYK4(U?F27!uR%Hn8xXq@jqKS}IpZM`n#}Z)c<2kgk*>OB(%B8D(oCJiZ?N zf(YUaDlrl(R>5@pBj5fm>@T`#S6K32N3)VD6`PilUSI-JzVB5M34{DRv+^kxqdiq& zLb(MqXk^QEpC0TP$hrDx>}mZs96?wF#4(G`Ed~DRG{O8uV7t8NkZ+c;Os~Y*hrGp) zP~!h%>MOY7=%QtDcb5q+!5LfzCpbY9+})kvuE7EX7+ixBAV_d`C%DVt5}4rr=DY9R zwcao2UcFAAy?0gZDtXi*eirFtIX=Q<{F2V1TKQH`=U@Ygq0}JZp{G~_s zF1k`-N~pm06^}CkC>GNFvwN@^+w=U3^FoJ$VM2?Ns}}-QR%$@|yB#ZSW~VmAUGi;G zoZGQk$2?3RiA9GZH|f6AA7J0t$8~mip#WLpc0M_2e7nl&%hhJxGbl%g~SPD6^B?EtAECb(k(MnPPxQ~N2*yfR1 zDm;uIkDForaObUYJXSstvno`&O2;~>#ZlhG{i>}vpRGX~xho?3LpGA!D~uHrqJ`a` zeb|gYR7~R0$OgA-KxBGkL@-#GC zdS+YK_Y#ESWszta^ec!=!Ix%Q@&I#yHrATdt$2VLJyP}UU|ZP+bCKu!zeuEAlx;av zPQ^CB&m1^w7_!$v{s$~T2Pqt$Z_Ol zSsF>?_-f-8s@I_xr!iO#MGDK~#H1h;X*O6+!`WkDxd zP$kOc6;Iv(YMpi(dQ3*{?Hzc7T{$UqP~o>y z%-!89dsH;BX!@KJt#K{d+jyF-5U!yT~@H4|?cKY7CX!o`| z=%grmq9r-Q*!+?2-WQ|Zdq^5LE~jOp-++UtMA}|1r$91>cOi=-i#U#Quca5E<({=q ze8GA9iR=kE4Tpr3l*}w(x;Goi1SxOAy7lGs_e!tZOZb$!V#|m(!pz~_#1R0&S#0J7 znLfmTwC{-kGVR0@G`%gtxV`=da2J2$I}8i{nEcQYZtQdOY4o?T%FY5|1)S}mfDypg zn^wHRIrC-C$9TMwLj)w1kGohFt}Nl~f&VMB%ZDs6;CuQ5Ox@pi|E! z4T^P%3Y&d&0Spvl_vi7X+?yOw+VFFppkSfiU07`{JkFO|m(qmq`@7nFrDv*DUKhD$b(PlIjJXI!?o;gtY5fX*p0jA ze@YlkKlrKdZ0ZoXC4jzQl3)Z`)kW9oh+D&*B-_F;U36#{jI2MmdDMjzhCMvJLs4eW zago3ZurOxHmZvc1O>X>0yP!U{#-4+1l;k5wyKFNdRV!l$TjWN(*kc9#W|>&yM7bTk z$1#UI^8|5I)jpl5`b7gw5KFV6%y%61{&N4GB70ah)jv^~r}k8#)duhQt}AMqT1%0I zM#0ZMPcWr<32*KZl9eLFKO%0Tq@4p$}}F9V1w zH-N;M>W=h(4!2D9MyK-LixI3%KwXu24WifNgJ5#$DZngN%y3@;mx3GSQn(D;Guw5ooOpkM7z>t0TM-0p>|MSuGVe+*HNkL+F ziVyOA+P2Qej$QZX6T^_*GJTk^;Mr|6D`${{>8yscz!an^nXg6^CeHjT3WJcUAJfTC2zG}I`_UIuS6tVg?^KAEK4!Ih|mz{+OhuLV7P=P+MfyGec zo?$aG1o`42^TYFmd7`LoY~diFCb^jLr1Zw|{!Qmh9oAim#o!{o@n((XZ(KQ~zvH%? z@mnL`alky15TtZ95eVxy8p?BFufN@Ocn`{F4ZAi`ID$09yjY*5L+yWEcrXxPhdCpg z7^U%^be63$<}0hXt1}jl73ddH6@T4U{Am_ba4cJc^rkF2W7+$A4X1J3;}62wZ@$(g zPVN?M^@Q2@L-JlV9&)OrHs61qo8#s#4j3}j^K&Pe@fOM3Mogs^0B(qtZ(9nmks>Su z1Z_w+{f;vij8`zw>#?eck^HgXf%Be^{vwuJ2``O=<_AAY>OMF{JSi+`rvT<$upGXe z0Oi?jg{cbt8z1wC$a1@aP6|O^VJ7f#AAS)2h*hh^kq39%iXbu6qM zWAPDpz{?zP(UrC}pod5B>w|=bas7#B3jODWP|^LVQE898f|1*n^cq}dkf_P4L}VI; zkMTl0goPQ@Xor-q@aECs`Y~uZx*(hc)1g42kEp}Ji{zx-dL~#*z>-@XDOwct#Jrk$ zZ_0{Q_HW2M{1nY0lKm2sT27J1Am-;KwracSVAEKf*1UBQ|h-0zKjS)U6DG8>g;F&Zv4kqWBRV9P066EVu z!Teu_IYLH~z>pSF)nwa5nNCd)z?`9xs)x>mXPjO_OX@b)3ai`2v%5gvxPSN|Kg^C+ zZyflV#~l^q_rmk^7p5atZ}X3?Y;W_8CPqD^P-B@es!Z+NT_HLP&QZ*rhb_JACi0H< z@8#H}kf)|@*Nh%hq{5BnA*l#}8NlXd!6o;v7c^(Fu!M_#TRyjS(L~YN_y50Kus2EH z=5hQ#nJ4nZ6%sDnf64*TeD1qkWik_t{NJHFo0$CJ`{;XlZCx}8 zO1()iEr?(bFrb+G(NV4{)=_hOgcazqQu&_gDwl|6Ha0kL!@P9 z&RWD28eiu1Rl7Vtg-kB^n%hpzR8LrT^6@Xy?gwBn<2kge^ol~FX1N+U z8A{=L4in2kU?W^?`SsZc@%a-4c0Sz*H{?>5v7<-B`pXA0dy^UP}H5-K!U7VX{v?EVU+xD37 z`D$p*+4V17jLja^wGdFX-*uy3gZOE}bghX!uiPn6$9XmyTVUkA^G5lMt@x(p(92IB z8e`oSb3tLaC)Vxz_H@1_|0Mibyo7?Sct2o!GShBeq!CssR<fLTjVb{q)Rm@vj`STxxI0yCWMV-9g3sgSa8hXl_vVt+R!N_Av98FtCcb$`uxCi&y zQ{YT`e%?%Iml7_1`qRY7)QKI(2&XUuh1!*oI|@fuZ=w zcxy6YwMiu-g2<8-0g{)_VQxoyrtJg$SNR8{9+ThQSZj>fz8v`-4CNvBM1~*VvqGzJ`22yWw10OvoW`D0^zH|lx-9{3Ha6W@Ub+%QVD zJ_{~@y`eC{M#(gA!`hQ!X-igNKx{`EAuysvwr;s^Xhsd`jdi+v{Vhl|U0hvb%?Gzv z_nMaw7qaZL#qoS?$nBA@6Abf;|CDT#C2VbJs(+SgKZFH{yX>HJ3l$b2?iotE7Hldr zt$@VhH*sd704`fapn*Rr$yx3xUUB13T8g(f_GUjQHn5TZOC@CVIhULx9-KYYOqNg%Uv5 ziFk_`6j>Q63exy{dETO`@no+kD})%&uOKZ$xTDe!hFUalF03yXSI)c?X=JGrLg_t` zAK{oSJE@0-Kl)9_PJR4XVqLT+c@%yfRwatOg-XTF1u-B5W z3P=L^+Tp-Punf6R=ziQHD)T&=M{aNn%$o~ETdG}^A;o{C8}&orZ1!QiU(5+ZNMkz( zgIhK%Qv}XEh*8Wdr!tel-rTON6wStT+9 zQP}ph#`$0k(pikQKmDFIjM*(UrqeX}o=lyT0NM?~7oMm9HgEM9|AzEelj z@Yu)y*Dct2x1d+Nz_2qieK3>_&v@7ZsplA9+Uyd>BYxlmyRoAVD*>X_^7fW}vbBa~ z9P%_`DOv~O#<57S;Rclw(h^VvzwKC11@Vx4%jpBM{!>vJX7*4~!rWqKspQw#Nv&lz zeN{w;%rN-LP?ox$>{fT7g!VDmv)#A!yq{rC*59$gz(zbwt(aDU`P>L1-S={K;~nVF-5PBZH#|LQGTSDm-^kcyfQl6hV85b&G^L_fv5nt<54B_olVhy zcO@yW1Tw#$8_TZhlv^PPliMB+sXmr4qSa5dD1jT7G#$6+J++)$KxK8ooI)7iNOYhj zS}60NdKo)yb8gK~YwmC&fWbSX04~1|788vh%lXiqp=qY$Tgz|8=Sr8+RW0@WMZ={Y?Tm9=7;`Xu+m_GmxA6CCbd+6FPq>^eXVxga8#A^BLB zTHEbBi7nr7JLN8|5qW3N5^BLdC4AOTt($Kq4KklJNRv$G!O+DW$@Xxt*>zt{0-S20 zi;1>w!zt=-Ieo!n_@cS>RZVFdghp$+zdz~h-owH7y&znUHVgdq6`t4q z?4qHqH%g4&adlqeo8iN`@-~s7aY!fLaf~7=G8!#fk(@Jqk#cXeordzp;ihIF`UccM zBz>?xAnH>_`HR`6X{y*Yny~F^IJWbC*q)FYS%8ZJ(g}g@QE03bMUEC+(m&Ugcr&f< zl6ngrajtAK$u3_485DDG0pK87nn|oU1yg2c{kTZ)6HsA3RQ1l;uOyJi26R6WL&x>^ zzb~*m&|x+{U*LJMynXKfw64CLqxumqWx2fz0br`TdaS)rWP?fjtOE4;L= z>$IyA`XNTl9Tao;I@tsg*Ym2tR;z?bdetnSxdwu>b$=f-iGF*1;}_+dw914G^p)Uz zm*yqiKPQ|n?oRgAIMS0qlS^(>H^V9~EA>in%@@wUd^x~-O7WkFL$7=Mz|(PR_|vJx zH+cXXMX6* zkKpJfwbEo+aRpq6KJvFsEQDvMov=5Pe~SF@xR6~xV&zntYbv>m{5-++`*zj!{1a`L zKrs2-JC9DAya5ooN3P9J!OBU39!?;9TV*yqsfIShb}hw!+Jley`N2>g?nV_+AG<3W78#oB z#**~0)Y$z`$lOEtMdCrP-|_eOEOSKsm7ME9e(OtSt=7?7Aj+i2=9d$Kn$Kspd6^JP z`2hpGs!$V#38HHQdgg{Q@ZXy65GH2vc%acxam?~pnJKNSrCxX|@eY7= zq+y+WoWLU-`MM@nti;t8*+>+J!CDt#(#kg10;Awa#WPMyp5XfHpczpSp}Y?5x1zcw zRN7jOV^cjWi6jVzHF|-%r^T5-J*CBO559fb3gpxha!GQzRuDNaD`OE-P#*2N#5f*r zo$(CR^@2BnU8*>LkU;&{2*X8ZDvfPU6p({jopts&o@4->Topy02&?LD)I)d9Cz;)! zV8h6u&DybiN%}%qZRmmLGa0)YmPtCHC-Je@0?HW>7WwR-a~Q%Sg-Y5Bj4cNX++umv z&t3h5+Rdm13p?tpcqaKS&kdV1%`;GKQUV)Rx&^yJcAZ&km`8;erXdTL@! zXsh3u@IgEd!$L2#RaDlY-#GszcK7?V4|Hzq;!epCh9|&~vzdN}eMhKk zl!gj$V^cI|PTdFbZ*9L9z4s-SqU5z#QZei7%8b9Q0zA+i^ueqBU7` z_tIVnAMHrC3V~Am_lFYPDue?CJKHm;Bz>RWv`nqoMc%0Hq9&SgylTJ+>3 zBoC%GF$iYt0QlJEne)FL`jXy4nYnQWV1MldX>=SdcJ$Y+s_3mlRoB3Pe)`IZeV2_BT>N8c6~;}s}JiG`+v3P6D$EP zp1qc)Iv6pY-CwB%2g)Lq$-DX6?nj_i%2uB+;puPtSim$G8Z1!LnDp@$+A(i&L-Jvt zIG}HvlQ6j1F3l6}0C zx)*^;WD?F%)BbdV zNS3^PvjDLcaMR5u-2PYIZ_{;zj@&w(4K`>@@9q2keh5%T7`ck7T^CmO1zOCsYK-{P zr`wy2gB>qz2)f;yDO)?gTNs6N%7YZR7utQVSpA(r#x^eko%%y_ByPv0zgKu6PztVS zvIbW&3Cl_vdL*je76wpq2Pw(sdyU$zyGm!OQ{Jks?3zL4y#)esMIm zN>aTA=APF7G*+YYp0D{O@%}mZzwXDM2SDPuZ0KMDxbYCQ*mEcfK61*}g-V~EqlR!K=UM)$iK=|k0*pXQ}ppiMgD{#nBDwWq;A)sme zYI|jQFaPUY96#>yCyfDWJe28t=p}l5RD5~NQxun`?sCy4ok@N{!E%8-Z{b4@{)7OS zW!5@z!zYi)JZaF=m;SSgCCurVm2mh-sQ^L4ED-~FN0Ma5{VAWLUEY49XT5KH!S2k&i=pfNLF(4A}dD2MZwp^&JXNlVf7r?}6n*^p_akxL!K(wl_YK zNeU;r<;-|G^V#x5N^uHPsCwRz&GFU5nNc z;5x@BKQY;(g_C{a0l=r*>b`ZzMNKek*3DIs!ju~X8zd2?VpM+YSf-Z5AuYm~m#52^ z)G!V3FF2S&Vvig1n`5+VSbX?M904y6$`67cJY(!w(JK8YUMBDU=@xz=V|X?i{U*&* z9dgt+$0*O_Ta!sfOyH3+-7@sYzxn7}{gx^95Y-jvfagxQD>dS$g&qKbx1W@ zJP&{*;^}YUU@&%eJs6IxE2j%!OMMBrr0X>;;7=U2E|?c3xyAWTG(GG0Ayf$k!)Wtc z5Qf*gN!K0NE&5cuV@*hjtb;+70wv8iu~Un`4xdDn4k8jV*}aktu)Ip}wuQ*GiY)=# z8HOF1t%va&Cbd-Exp*x?LHwg%M3!Gp8CNGa@PKHn+uPJhblydI94MI*ZW?%bV+dj$u1O2M&CSFdH8b^?+tn=a{hUy>t3AG1pS0+YBw z>fpCLb=@@ztyGqq(3*C_f>kSPLuH@5&8#ku`K>E~wJ!(xd-rnU1N!D4s9foY#k>)x zEzWqT-3e{Z#C4)%F(Ch4e^5ia^pN2M2gXwR4!{Oe7mM4UcpZcc{F7VJP#5t1=Q5u& z!|Gw?&MEnj6WtCk_Q9@5#O27FK@fPx^g$}RS3I)qvqzh}=9cSbAsP-d-8?W9=f4R} zYlyNMS3H=p_pF@smVfs0r0K1~oed&PXtL5cwke@eYe06|T+s`760B*wN%g{#89d=& z<)|$Z=}wAiL2f~TkoR>4EYm)gqz9Js9+dSP&!yBjY}3GZTxGSy|FBWs6v~1fsj3c} zaPn?NZt>3P0h{R$xr?s#*4a~E5@E=XBsa;c&-eY*yLEF!Rpl%5^M3sZ+$b%ix@%sNaG*sy#Pn7wc+`EP=RALjRBJI@*wPv4;f z`m_-H;L?6sMGqL|c|L8mMyR_rcjU{O z6d`J=!(E66pfEbHf8QiB8KL3dBQqP?b_XAGIFV*f7?7~Ww6Jw#)v0YLULLr(P}3MJ z5}st+S6pE2i)bbxX3alN1fue_wi&F-fsXeikfnVDNb!v&OKHyr2O|$+RsIVi1ti8F zv}6Z96jX0M$p+=tbt}$3T<;V9Cz|e^VISX|%`+G@H|i8e?`ZqExanRx&7b0P_xaOz z@>&5*Q~QCNh#MNF>)bC0qLV(3AZ+O3*$m&(VA>QkZqtKzXkXF9hI*$#{9v#V1U3fx z(Cuw>U+vUBFcH|*%Htd7DM%4E*}|37`y|e&C4FAj`VAB)A3?kgB#)K{p&KfNXqM6B zaw0_7>bPL9HHfC}$RCDf9;*M>F5EL2=Yo31V(>aa>A4Dg#4k&u&I**qqT^T)@LN!E~$qQxtelj8CovBj+u9_9?4 z(Xau&hEG0W`qz8loFO=G38R~f>CE78E*RU1IY&(bnM$p&5ar1NqOjf{YKJK-F#B?X zomBqEpOXwr$!X^AU{F}Iox~76IR^?e)U5M8Uq5FNJlT{hX;hdpbLU%8$T7k^7kc~+|tbuczsk1ccF_w&-LoeE*9q02F1==0$>+WLNL zC-Mf(^#x;QrMhy8kbm+SoAC1(+vy`b5c;LKCAxqGqYEq=+2%0~u*{{{a!Uk&@M! z03%!T_xJ|}0L)O~Yj~2wlyw*4?TU@jr( z9*2-Bc3Tr`!uZ8}8Xz|{F7`+is`hyqP_1{s0)EH88mRkT4OTOr7dfI4)rklQ@sU>Jeu%2{zZRl%A~t1&tGQ9J9_>y zB`g!F+NvhP;=lxcQSDEwqwC8zC#Q!ak3nDZT7T{76D-7j{#7)hl}iJ(*Wh-rlg+u5 zOAA*HS)x-J!m)9D)MGJu8Y0WQb@Gv1V6})PRmMMrS0-+J9j`+&Ulqhmp+9RiW;jE= zr98{1S2H)!OANFruDFUq`RyuE&h|!~oN$Yn z&VuCv_iY1Wv!Je9O#_M2-D^nmc~*ApLtSL%@gdU1mZ5_v(^Jd8;(|nPdiBh*C!f`L zRxW2gh(1>4eJrU2aG6cs8qcHH{1GUm>QOvyIxnzr2^ee1kY@GLG1-ak)@{f}S&=0|XcW#oQB#|Phwv;*$?BCB$`-z(pv9BVqI=oy4@%0DCT;;^o4l$Hx3u1-2>%(D0j-K; zD6MAtCo$(7b zD6(;on|%1@-$6u;^h}G{L$Pd&{#4e{raDhDdS|qkDWiwSHc#$-Onn~1%Y3rm z`3~mlXpy~NF}&fE78X{WQUgI+(0?)Q-nO501hJ=taEI4Q%bzR=Pfxt0FNd=o&Kts? z-)d<~VNXpfdw9-AapreBFa31eZ$`aUfJ^gAwXCb-5bP~dD@;sCeM;$>7QLqO%*3sH zSr^O2nLDH-n5YT*<=y^SH_-rVld~mnM)n!DOSju=rFMCqVL@1o=c;Lm=Pn%RtHjG7 zgE=Z`DN>-RKjuNWv8>el@gKYE&@UvvFI2mrSe;#6CS=JtDI7%EsN_8(1c06_suG5z zT->(qp72>hF&SzIN*ihtrDdZy4U~e^NO`#y`MLz6%F4Z#A&TIM>|!r6A}<6ImvszRSui zw!_es_@@gaF@DB%3s@iyy@($KS{P{?z}gt%{SKKSCzL9Jkux1SA8yKlu}C?L1@to~ z+MOJBfZ?$eynTG684e+H=TXl{8{GJDGJS?*-8ex#B|Tn`6dp-Zv-3jaEaR+&8CtQt zToQ(q(nA&@bvVZiqwZ|vJK8Qu&H574zvU9aG1zU$8%)1=KnT^O zJ-HZM7AazQou?GxGBkfq?(j&BjX?^nY7DGrouM4S#O!Or0l?oQk zwgadlLf`R{5EN8Bn4aSFiVx6|-g2Xc$nf0yx~T)BjqT+=o}M;oUE10uCY2P77y}Uu zrSQaMSY^4rMVI%*+IfY$Br;VKy|5n{2Xxj}-%~mqo;>r@{@c;N%R5fTY8wORtq1!R zwm%@&Aufh=!7mpM5ZlG0MTnV_2^g7(O-@Df`>>;!57P@ce_wl(`-}2QaxaH;Axv1e z^oU}_2o+`U*WFHaa#}}JcYOPnZ$JXa9=G4Xjdo2l$pTBVl~ccXAEL8`mg6E<2HHAg zkI*5Nqv9)EI!e%Pq>6(6@#0q=*}#EUhD(Cb{{yK-iH+0UV*lPcK~9UiVmtv&!~uej zEpFL*%F?rJ3IY5|Sn5Q#Z~IJR+)CU^sT51d4nfihba$_zdSp}h&CVFyF4ewwcc-LpEDCevj(U3J49SwO;t&E z(NL_}p}Qr#&0rg?42!#r&#M*nBBj?kUoafBX4~ZRE0#ibN-Xi}qg|(C(GWQ$WI+2n z?VMoGcoqe#j$K$GHOPW!#wzc(%nvZ41MJ=YeZvX25d$4=lgHX%=Vf!|iR#?mQ08eX z2ISyE?kxtA&`fz=1WUB58Bg=v*D)qkygg5YUMNJNmYl$ldXBm$tb*wL8Ga4(K$1IiP{NPz1(A|(O=y?YF-!_wrjv2_E37J z{{$RMKlUT~-EA75DemYPpV9W`sSrOw;QCvy;VmFR4{J3^fM9}u0jUE=ld~b4bfvf;$B*b(lq>*`NG`v%l^s*s~P6g8( z>YjU!9_4_j7&YgvS)7C$huq0}x8n6shn7Ea*|0su5k~l11OwwK{jdLxgUa;78yGaJ zWcLAk4|`&QD_4V55+vLwo-}^dQ^PlF*Y@PN@EjTglMpk6hGyezZ2RIEWhV3d-#?8} z8DE30Sf8SyK{fSXp>XPDmt(YdA5vnnZ7`^Ly-P_L&6> zNo?qb3*2u+QbI}DHww`cCWID2l6qJfFchry*ln|PeM*Sv^u@VH_obN}+}h6^?I49M zz#J2&txJZ~bcefgUI@5#M?VSF{yJpZC5!5adJ18_S_s}+z@+CyGA%hkECw2K#JB&h ztR8m@Rg3?{@R`go3d;KU@7fqr9YEvw`+mn(1#5BX)FNzc(&M2t`>f{}a3MR8i(NVD zx5-0vY2MP?y!PAPSX;UYbcJP)cNKUfF{Rvfnzd(xkIZy{BEF&~;c|&kp+^Zw1ju&^ z9VGNOm?vU4li-$L-9%UKWiLwgQk{8Da17DGp2BNv*yx+~(x)qNry%9G>BFA7zgD(( z>i^$(N9Mtk*t!WmH9s&%*Ty{{xCVJJ9_VrF=E+Fm$`!~Wro8gOC!h>>*!J1NkVv&u zK!Q=8g-O@ws^*cezWh7K1hWD+y>5Q%I)EAIR(Noc+NQT7>6NBH2BqEK|CeH*Y0=bV zY)libLo!QFe$43+ufHw-J=Lz8u=mgpkVp;+Z=~vzBSIP{LiWd?TBV+l&N@5Hw@z@7 zHd6SZHKxeX=l=*7;A~i=L>zpX|Cp_K?&~JZ#mibpJvBUQ5AajbUI`P4e@d4@LqPPEKPMpx4wjU?VRdXCn!8Z2^%9$+b(#sei?%tyD)aI~R@8ilG<6p~C^gYQQl2 zF0wDXN&g4@^C7g5FZA%4xKG9yO&*)6O)(hK&W%J65RDQ|x0=Dg$H4$fp;>=%rWb3I zzS!QytB~&w>-JKtCFiy(HwGaks$c|LjpNk zVwT(c&_WV>I(aLecg93;Ny&_ROYe}DHxvOJ5jTwx&!(tIk^cB%i;mm#F9PLEm@Xsj zE}e-53!?E*vR&vL|1+6}i_iVzFfdljx)DPJpsiKhMu9jy2}|&q zkv7J%M7|kVkA|qr0mfAhk6Mv#Md#j6=uALYEo+YX%cRddhl;a5uWmjE`!C^4p8Q2? ztp|7*A>^cU;S_%4tMec$51%GzEa-$AC$c||m%9*lPGllfmF2SrsjAlS?O$XFf{Lu% zCfY+pL$4J5c)H@AP_h@uV6@Tf^-5aKp&5%g`YtH)%Duw0f_I8-q=q6C5os=#H1vh( zmd!k$^yy=>yDi-fM(1O(r8w;Z(xJnsCWov0#$+nkfmSCIUYn^wF?{Q(FK~{z&Tbg5 zE)ZGOHAA*tI7^k!Uub7L0vB(t8RU*+L~>5|7fBoRS(QT&V**K z#^mduO&Lv~Rx9I_|JC8Bo-b89NHB0YayJ{-5pL?(lBwDJdF6a&loDm6d+43SPxPm6$iI=Zz;AdpI zr4eEET>Wd9DF%9H+WZEH64##^R{!{KoOWYbqWQ^qG;FLqvXYO|jM@DAH?(H-r-jO3 zEAfYTgjzZ>#<1mZs8F4jxsAW*o7UNL+c`W3C&xZLfdkT3(!kSSBde|K8Nq)9Ul$Ct z^)-5NL*FvZBUBAxRk2p_nfEe@>r?7o1sQ0O-LVV2X|R-R@;lsSV4p|yWFVMgV7 zw+sKsIph$sNI1UQdI_(Z+r|~t5U$D<_kzDxfWLCvd`j6rL>3f+{RMHz!xQ(Vy|;#m zZz3BHcPzR$%Y$uxfrQJSbR51U+<3V7XfnFduZ1X2TtzkLrQT}BdEMya2CQyZweoE8 zZZ>Sez|D3P>dLAnWXOXE*NqSa`Fsjx;W~yI9@pt-Q=9lLU-74+ z1*ufo;tv359{opvY>q2Fhj6izKDrYZbMKnv;D3}wx&)sE2W)430BhQ2SZOAc@6Q&a zPjv6Tr05WC=!Q=sEAiId7j%=Jo~x?gipFR-%BaeZp?|JuXa|u{A1+%1X5oEJ$2uV7 zSk@$oY$o8Gut`n)57g_`xZD{%Kc@two_z-YV}CYB3_>JSOxf`ZlV4i^!QIsnH8u!w zT@KOKUY;87$oZKnQ_WiJHILj`o6!-@eX$}?{UT}0<)ph7%ek?<)@4&kRS#_4XNdf> zc!aY^&i4k!gBtQmFJU{2dvA>4kd8Q*X~OoJ?<$B8ttQ;Y7GFEJRdUYoIH)Sqse6od6t5MnJ?P z%cG?7Jq4|dc-t1Hi8l9y9P<O=_K#|@(({ba@QmVVpbzo!omfz2N&*3f!g9pi zai#-2ajv-;*tdIdWXz%TF-+m~n?Cj2Nd*xynXI?@oFTusF{YDMCO|HRM`GiuhA_AB zUbgvQg#k=`7wkPFAWE%v+n0;b}n;x{`8q)Xdn2{Ov z$VbC&$&z9T7RCVnX|u!SwNx{gp*h_}85;}KvZ!$5&xB;miCh+amj2*OQXF3bkBD16ri}2cpgO_d8!H{5NJackB*j~X3nn;p8ns+vz zEdAtdQa@ZBs2g`FwVa6o0{&zO-~#S`AaBQp5qhvC@@p`)8d3+NUC67$hEkD-qPj>F z&Do0Y>6`jf3g1_pk0gIJ{-J*HN8U`A{PjUc9Q>tRYBYJE&99T{o>Z!p@VAS;m4Vt_ zE1ZDi0-HPj#TVCT(({i2azhd@?jtr?e7NqxG1M0$Fgz@BHhWGV;f0z#AKCnhJp-mY z>cH0hs2hESJd}i+ev#v(frXU$@u-Vo{60dDSuX32eBIRi-1KzO zwB9eS=xZi>?7MN^As(2csm3zB(!3BjTqE&)#?1j9;=gpHJmCBbZ1yu~L&uwA;{AAl zJ3?B6yk}yOXnp00ZtM`a{bz}wU{wuDK$KUzQfQ|k=w!X#X7}S|&60XLiuqF?F#REh zxaZ%dNbRBdwmJJK7tHbjp7&PajDH!DAclW7d9cj8>2)P_CkoH$njE_y;Z?o7Nje1I zCc0U_ga7G~J;MjW6Ru-!C>?U1qo%Jz08@y4-X%wvc+|_-&xE49Br+{J&kau9llDeh z2XF^d8=2a>zJpgd2|Z-IHQ(b-*9%FzMWpbDCO|!{CFWpD?FYicOQCiv>@F|69Nw8(;kK3N^tXdJu$#+``5XVeBj-V?O$u{|e-&$~yy4M* zGEQtOp)@#N?|r2eev+aQ7`{#H1vQSpBeXw%i#oLM5?sNZx^A5wY^gFP^`y*C@yW(K z@UhynWAXFzIdW{-QkAP-DXc7yzKOXrW0wK_-4+#}&%25)$(Y;13xEUt0r)HZI?Gf@ zO+&C|-3YR0x8tnp5V2Gs1B z|ACvQk6)v_Mqw65>43j?kA?QuBlIVHsop9L{_gg{sK!WQWjIC7{oPCDb}q^i+_2?y zb}ZM@!s?sKEfkwL9Lu@P8oyKWm!+%!;fnfi<-fBo{Vm9_ii5H%N_LlhxHW9fZ3V%x zy0xlsGcWAzTjt%0>{3b~kLv{IhrA~xf~$1z0ZIqo)bS?zsYR1lF{H~6N%-DZH4ES* z4%%c=1eH8?8i!B4-sJ+!P4eLToO^%PBlR))otA~<&o8X5O~W=NU%dEKAw~z!p+A#R2)RjjI$%TzGI#bN-{X=rMfA^ZSC9klU9SQ4FoV{O~1&T zm!a??Q4Dzgw4D@QuzchUa&PYGSX?+Y-tK7AZ-=VnvjNjvKPR3}czmL||4mwA^FKr* z@m!*dk0fuv0N~JY3{aT%(r4rxH%#c|*+#(~w^HX}q-y3oHfR|8=IMRbW~Fcn@C+_G@W4Zxg2 ze#l?l@&5tZ-);^Aq&Lc4Usl3lCM9av`a`=pLfPi9?~8MNnbqNc;uRsTiv_Z|q$gJs zoo>)81`?_$vQ21cAPE>D2lgB%_mu|D1R@`KQaP>~6rp=GDl{fW-#QRIxV-A4z@Pbr zl?;PxKhaIg{_bxG7Q+5u4i_kKS<$Bdv_aI8?lm!C1}nc^h+qNM$s;IT;8 z^f1xj$?+SZDJzIRW|ExA4k3{$lWMrLG?FEmrW1DNo(-*Mg#VGDbWH{(|Jax9N?_eP zZ<-uykG%2MF#utJ_m8nbVqKn0OLsg`kYIUfbv}-{(6*6rZ8O=?&-(D@=fDHF$qexE zphL%@K5DJbOn(N`;eA8QVeGOEP)Vx%noNaM%7%FajEw_&$KXeF z9g_PoNAo^M#Oixid9x`+>IYB~ME+kR0c;sgh;f(n9)&qa>>NXb$E{m0`~xYkD@*6VDXx<5PyZj&8E)C;;RE- zXM6S?JT={V{#$cRLNJK(wv~{Wl1jsh^WX&JQ7MSmm7mi~6?+IH#E0U(3dd^jOUlfb zN#)77)!0iI1?aC)XcGpbygV!z@O2jD{63r{{693Eby$<{`~KS))C4YN=j^Fq19mn<@d!FaM@9R8Y*LktL2M*4( z>=Q~YXX4xiV_QK)?(#00Kdhf0bglASpeNLygu1lX z*uC|L5xWDxpP*;d2e;a(q!sPM!5R3~23CfNs{_vune1s~%`g#R>GZlUsnWH~-ilS! z6aUlW%9<)CnfWXK#1Uc|@fKg4Z)Xw;pG23F4?G*!%4_;cP=f^IPM@LL;2d#?=};pl zfA~GgHMpWQ%447)h$D~xr)ECc&KV75)Ek}XcxZM4{RSpf#SXF&Ly5b+XkN6vp>}1h zNm+{zG2Eg4uyW|3sz|)q`@7VYNz6qyWjrNk*{F<^GF5{P0ep*0Z~IiGK-Pp=bsS*fH2o& zQ_1u73AmPLoMjxp!8{s0H^sDSl(dC;*#g;5BJCXf9jnCvae|PjqT_^JE}mO-N%~!^Nu%J zgH+>Z5%AtS6J&{0ZH1-`^{7ikpn`!sY7ubXgzNHB}lVA zTx*vcc>q0vjzSgb-=u+N*260l%x-Rey{0mI<&O=1O;uFcl>2>q#Ds4B9L$RGK0uH{ zP*HZCKhpBbbkBtOrlnbBe%j$q{Od&Au=W;{l?e2}pNg9*TFC zr2jwY=tgJ*@3f^0G?VTOkg`Fc`P$57n<^ui3KHIKFQ4yE*Y+hhX!TtexmHMjf&xuAj#+>)qobZ^o{LzjZdzB42uj9=4zG%Zar1H|s zrh>9%_Xui(LyN&Lf3d#3gwj|QB#*~VD|Or|WhHltsu{*2D86>^quV5_)Q4UWznKy| zGu7YEEE~tz=+U121JaOBZ*lV{*B3LGocu0Mt~}PpFDYOCP1=R{G#pAXB*i_j!xXNq z{9}GsM@chdiEBYhkFio$El4kS1zuZcD7as~`_7Ry1Sw zo(M}>$8rQxeB%uYBMpv1LC&n13p&czO1^NMxWaGRsX~tEZS;Xg_0kD-NwM*r4;%9@ zRBEQN3PgTfe^8>s%u;RpFENOSCoWLqQ!<0A=~rIWNi=^VsP+pUhgc~;1_wItW+O8H zYcvHKoHBoc@@P)$H=?lOO$EClzR{9cd2VSU!-P#DF$#M6Ilajd4f(I))_*95Li1Hk zu5yO7RTwp%q05HBn0UDiz_lU)mo&L~Gxpk#EHKanmu;d&(e=P>Y&~&NKah>Q7t)MI z2obIUIuypy&7t!VbutZ0zgMnarV1d?#D(dqxtJCi3(PnZ#J6*gX8}nwC{o>N=C|Jy zYhr(lrlHszsIUPGySAe-E7l`)l6-|Fx;W^GZg{pBUD`toGlyy~0y_Qx-uem9em7wV z_|fV_m<%`IrHI*~0IBa-@*Gfy2;=4zx5)dFeZgJSM6(=>!I=Fmca=A^)`sunKQ`P0 z3y<2^I1BgmUeJ27AqZ|oiDCunCIArFGTimRs>z%}f#sh-Zdq1o?c3)fFHT#Gg zzMwL`^p^nfflLcNFmR8g?q|@?al7=&V}b+IpF2!aVjYjipwIxZm5#{YY+m%M(*d~f z8Qpur(_OW8NUHnHfA&J?@du!kk$__W9C>}+H+5AyeNIeU%^&j|tclh2wm0Dedc02A zhYh{K89Uxn1=e%oXZBA!oxmIGTKD?psymU!FFuXV47z9b^Eiarw~M0}N2vBIbtcrQ zLW<%3L+aq7sV6JTjH4~eE^d2PuuN%E3Y;9}KBYE3vL7JqwwG`ahBL(#z82;46a1b{ z6o$3<_GZ+QPLN)}P`l~#mr57O7xsK1vK+jK=J;KCc_D=6^jvJkXCorXweDRDRL%Q< z7gEzWuPDAWCT3l~T=y*XhHymRMV@npQrd-Q7s-7=&-s><e|mtmr- zO+~_T=55^^QK*DM!E|6295CZS@RgSkws24a-p{6$@hr6#-`oFWP3{S_vNqg+d^S@=p^a zkM`ns$W4xQzjw`shS!I4d@G;jf&?5E_F;79D1}5_<^+1fb{eL-`atP@bU(HP4$jd0 z@5TTlFc7lwyj;KWt=@^L9wTFH9g+aP77uI@z3@FUcM1R4o(WK~vJ@xHI6n>&QYB} zh_fDAA5YoBXZ+K5H1WLTnG-F5zngNd+2lXGmnEdK5iWKeL+Q#1H^T4-;N)QXPbSU= zU)jVSDA@us^rFfAD!%Mf0Q?>J?*yucDOoJ zJz-7%ceT7)%(sW1^h%-#8UOo{owne5B9G*Eats$d&snhNQN?6F{OstIisC67QpLf?>n{L43gjQI(PB@(xE+!q^TPO z`;$LhPurxtaBmP&SbwR%-R<<}e=aEv>f7}z{sq5?y@-LJ85TO`%ion&NL-m-UJ1No z^cUuEvnQzFt53$5wI3jvOC#9r=0`v5E1X?_ssd?Fo<}lS>Tb@#BjnTkCSM5hTQCYsAF0K zL6X#hZ(WBb?^%C|j~A+V4P&C_HX_eAQYmL|u`>e1m}*1g6nmeIpeo00R^yc~ zcqN8oMXBKQ+>0SB+KSMAE^n_XW*&LW_@7!NJW+Bnuw>Z#d+@O{XW(}rLqCp!PP^K^ zl@1up*U$t3p3vqI3QJT_f7h-dH5I*(w|!oTRzb)exhik+iV(HtL)-l+CFs&bX?TD8 zO-k>N0&tXIAvj1!2Qa;U!=+dHfBwXhdrnw^cE*`j4m|JTSbh$#tXJ&4vc&L78*!eU zHJYHho^Dt&FaFz2G1x;eAF*h{0jH~q5;Z>>=x z1XJi9S)kmEHb-l!t*r3)j~~q0%l9On&wq{*SEn-aQ;|^|Sp!AvxH)m%U&N>fb2?DA z5OMcA;5zB$ggRQGlS%Nn3Ce2ku*Xo^iaWFy0I^V0A0OUVwBT9XnYR3%D@wko(;I={ zMg3A`xgjRKo3h9=AC^%%dAK|P((KqwupkoK%+eH#w65dD8udZcYpQ5Z&atcn0|y{h zhI{F&F7k`WTgFn{^v!XuCj5nPw06xH-TCCgly@qDI1LF*J*j2tN}D#bm5k!-1~(~H zco}bl1Nz#s5u6PQJLoD;pxNceKq{p9bF&9Ct3iLuym8Kv(vL9aP@cNP$i)Bd zpXHdI?_^+x<(VnIi)=w^#Y(sU^AOz&Bm2~Ui7?QV7f6Q^Ks`PB@g#9GYHNRc^ooI- z=#%*|M@+E+zl2EaE6}_eVi^R}%Rsd(N~*VOY&l74hVu-M6P29F?Cf$hPJU+X=aE^X zLzaV94Gwc0T}u$*2ydS#$uU&Z^}PMP1A)F2B5On`^UJj&_4CaC*&?H18&9}9I`<~R zV^5AJs|ZBjU%97iRLYyfs<-yQXi$k<%L@!H>+BC0+FrP-Wj6U3`hHwv-gcJ4ufO>$ zug@>5_Cmktc1sS4vGcck(rEcP=%%K2CsvXrbJ=0ykF+q$4SdZL@6kO+HC|_)gTxs! zeZKerFCzQzTLpCiGn4W&q0|4sGrJG}mXCc5oWu*4(1kI3^c+9h375Yb`Yc6D8-tAF zV2qO2cDyLqGw#~GX1thy+5CpBG=BxXWNk;fWaYhoRj@#9kGRruf^ z#3(lWll}ll!Xg5woF=V>QbiqV-$Bf>3d#t^_`{&ZjO2rj$I<|c;cXdki&vw{DP896exco7| zW<(;+lWc)vem+?=%Bgu+hGDFH#;R96KtP~d1Ke2%g&oxq-i9V_h`Czxbb&xuLMy$&#mIzYUTUOi%WiEU z!4iw7b7GIP@~$rz7IQjbpyKN`>=>s5mOuASBh+!`j@Bw@;QYexLNf@c;S`cp=X@_@ z#}0UUr5Qtt@jwy%MquFP<+-AvOT%ipnmYC%ETqOh_hBiJbw;<=!RTfo#!$Te%V6O# zqOhU1_EzJ86VAv(cu{b~JJA`$E*B!U_IV2HXF-J(`yMc3dzact2iVlIT=se^fk{)3 zX)-~=MV`3=y$W(r4(GP?+%k+=K=A@w2Xw(w^{sCV;Njx0+az9_m=r2Aff)5x@Jfi8 z#zMZ@;gTUe9oKKqsvB4!v~EiLdIxH~8=R6sNH6uTRK^4D2Zw&4%KMw(Bl%10p3++fKH|}1pxK~c}k=%Vl)p7xrt(LuM3wdk8mo7<97CeBIL zft;dMm~}0Gtx+APER~DR;4LZ5GGxsAI|7aTiyY@RWjj}|c1K`#82{w>y!XOc0%DMT zp4^TZV(`hWU@!ayk#00Dy7fbts>AgQsMP+p96}#!pjP`+qPvHwvQYVaXkEXtqee#} z&v8WC>?}7Pp{F!`^OAbkaR&OB9#ei|0A||YiF;m!40}drrF4|Q?uhrbyN{__Xta{^ zv@uVOA4(I=ao$*PVq4ghE4jhVnUHnlB79!3O5<&z1yA0tzV&H32 z0Y~LRJ`rYwNLYUXG;r9gy;qel6Z zglo2R5?V;OQAy2X>ywd7Q1z1QrOQ17!hPt3qFIUJj$EOoCHXrMY6MDQf`J$wIu>65 zzRIHFnqs*oTXG>z)B+{jFBVRYN}O=Q^TY&b_sz))u8By2$TZ@s@|)oWdP+N@Xl4-% zhJNHZEjo9KfBfH&xgNoTkffM;Y?$=sh-fMeh=n|w#K^mui?FYRXCTVlrFglYkA!M7QSP?RZKqG@*V~clPGQEeerOZCPp=fUmT;J27?VB>SO(Cv&8f#@wCu@UxwsFEvr5z1Q+OXyz=nKkh_ z&`VLflUKegF82CQStHDp#C8h&1;Bg1gOp}lAvB|yStVC=hsT_eCPQqFHw!g`;y0`$ z!Vs;LV~fA@M^@YEaG3bHOY6V7V{{?O8J~@-S^~=&-=DsskHjrF2=iLWzZ0KPn$LF; zb~bboF$+wiP9ik^^Nu0*_2D^6nVr&?+OHNyUbkMg$#H)vK%BdNz>7Mfq0Tcu9it&y zct(x_cTI=iu1L`<#1d!LDosy=k-CZD8!V|dh<;qu@@}?s^BimODFC{A2hz`8 zg`mc2uU9gXL2x}L&u0{eGWD&ASCmB-f*9mEx-wJ3ZHbJMj4`?c&_4)~Wde`|*|BFb zW4`^n_jGzsEUJskN2yp(V%hA{jKKo`BA!ENR|q1y>^mauVJz|~KUgVpzEp=iI9&=j z82uei#d6J*`1(f=%_#GekH<^*_q&c_iX?}c_iu+8?sfuM=4$6}H6oYN2&I}@I`vQt z(PCXuAo>Dj%(!RF8fbuXY38ZeeUtJnsap%ba-zemr;9$dofCXG#Rh*-;yXHs()gg$ z9Us5(dJ8AsOqpwO6VzZl5QzB5FwI;|kYsc;5NoZzd zGEEJn$*#`~POHQD=+M44mZTx{_u6`oi588v02n)h4gE)Sh5s6R#$qx0hIq@}SKhl{ z9&i+3ZTAoqX#m%Mc(C?gAP(~5U^(Y1)wv3zpxKmOPi>=SgKz)2BEp28VX?~tHv)p9 z{0^s~)ysyb_aS$*Qog?|v9a${M{osWbXjquxGLy@l7$@;v!|+bI4Ld}uBfA35Kj~3 z*lXbP_B#9Yeued?rqyzp09q4W+NSht8C#XvOkp-Ohu$fz(MTKicS09?{?}wliTm48 zYlV+0{w!k}%Tm_8>WR*|f_`ABVxYolI03|+^fXQlHv@w*O`6_cwyGNz=vj`_-lv$b zHQvGj#vBBxwB0~u7_ZH*r5&$B78c(wUn&5shdsjQoci)szEw;y$FS}mn`|GRJBOK` z<1r+@7a$JgD8im8Zc&n2yy6nFhVwm9k{Bkx_Xk~1MX>#_1#u=AeWmejx9Za9jTOdT zjgR@7s4%Y+kVDq)oXeskxMw34TT>{q{Qeu|1!*akxAr@tENKvNX^IB`HT(g_^n@b{ zGQJ4m+?Hp~tK{{sbRZ6NRb)OD(zhy#$=~dzLpUUQ+Hr5PV9pBPNSx}9H2K~C_;Fa+ zczK*OW|}3fXK9Fvx*<42UE4=DXqA6+u&AeZ#;URTM7Oxm$c0ui zL7yO#`KpxeVQ2peeO{6G(Tj2f(Hck6KZ9Y>witKinxX0!@sS?;$81L)(P+h1$c3g5 zR*L#Fb~Z)z7@N*#dp@$UwxK;+0bh8N-d+*@F4^362f`glQ7&TgqXLPgA}&JyT+n28 zgf2@GIFcN>jJe}>1*W7MbC{Yci1}`5B_bVZcVTxL#PUF`Tt7r`_o?NP&9m<>&wcdA z>k?Ab4AO5m(znj2Ot|9j4QOSJEoJnR^MKH}oku=DJRlaLS(R_!_(Z0FZ^KP?oUoeV zk3@4u=ABfbMBmWo80r!tRTgr!@G59cz~=$u^Pe-n@-{p`3mEwhIR)R-s+W@czqB(Y zwya5;r$Kn!j>5_MrB&YyXG8he5=2e2qSvF*1Pcro$X`(5#u4&(8b%E}3Y?C0t8e+@ z?ILLj<|6)%iY%~5XemZZ>o$Oj1ex8coX|;%Fp9WQ9Iz8t!<5C&xQWewFE3>$pR#Q} zs`30@b&F0VxfQP~=HsqEAv;l(C79NsAp%WY?j=dsAAUfM5l)7ODFsG`ju2Y)F2**G zjx*<;RAT;nNgTAfk)CQS7<%IH+AlQ-hy}#LYsGCa5*BYAIZ^h?EAB#wJ~Ea*A3#TR z>kpGJ!@MC@dFs-2Fc+Ib02-boY|J`sXbXXaMuxL}M>$=N?xO33skhflvX{3TlGL9R zxD_%gsbBiImtaE}&rCxrCgZ?0EA(dmre96$H`f5kWIv5?O0XxXr2%16oJ`u!3C>7J zEBFyf&)$C+9<%)}u0i`TbJg=>(@S;fFaMP7SAv&VJ;@;;BH!kc=Jg&`nEgGDV|8*V z{$g77I_<1|zgi;4uUGigHdGfHL!Mh8RHU`$&#(%d7PjN9(sS;7^Pp(|h+q1YOMuZajpZ>Z&h)L=Y-_c3;(>3xPBa2<(7X?M@|!PF^o!c9C|4yR$F5 zE*zq+($&Q|!m$N@$WT@wxMLpvj@9Mbz}5a2rAeokNdqcv(R!{KJ|I;%Lk+MALW7hF z7*6Qc&aXBl3J(PnPoIO8ZvI|g#n(nW-fAeM0;7io?j~v@)&LC#p~|m2P0Uhlqn!O_ zs(uA6tFinvH6uC+XFz;OGW!zRlj-_p`o7NhhbGz6@&>77!KsgY8r-!_b)%$n=!wLy(OC0yhQz>1il@td-v6DW-8G05XEOKxQn#x6*q5 zyR1~K6O6wxy7(Nay%Z1PE5LXO$h6~v#9uL5$&FXK*7yY*N+m7CZq{dbN=lT8o+f5X z7&r1&=U(IytXuzxpub1myXgzw`h0k>@I)niJTz?+OV1aDNExMvU?Gav&eOeyO@bPh zYq#Q98Z(#{io3vebROs|WM0q28J?VTnH5GmxqVTe3xw4OXc^@im=vONK+ees{RGK= zZWOv^2&C$41-b`JB0t84{D=rJoh{QU{*L%a_}yNE!0qiUgN&6P6EB*T74gefmA$ur zv_5^D;@&F}&iWDJ@gONQbVJB=;E1;E+RHg`ad{vlK|ixi**7=Ds$=b}0T~IRU%yIR ziLQgKeD~0*keP_d5-RvA%Kp>8wJY!?k&TRF4b!zvKQHz9pXCls#0uGyU`hCRGs zEqGr{hwY{;aV2I!o>s>1_8Yq!@f$m9 zd`czoHFdF}G)oBg!RL(MWXCJ-p@RA!VX=9*mb_ebCjl7##&r40)c?NvYigxRY;aCN zwN}PU!WkQ$n)XeVAdzp2*@gwhGD;EXygXZq?e?E_eqi4>3?*|%Wl=HmFmlL}O=CzE zBOzS3+>bW!BLKIbJHmjQ^z!90t#P*BF?wS-ksA$D=g?rLJ+MHP zsYID|iZb*8)aipdZQo^EZ`psMf3ArccjSRKWIXb`6q!S7SQH}mYv_1R!m=K9TA`-C zr`>3Z9Znh4>j-#*)B29E7@8U=q8Q4WT>1yC4V{YyLzkFFVC8z3Qcs;eHd1NU8y)-; zSB(xIqr{P9sLb-~>B2#?GrGu8Yzmr}!Pxm!yZn30*%i1_TEe&=2@?mqmH=H$nskS) z2U-BGz3)r3@^$+6Fh?Aq6Iw_o<@6LKR>iP!{)Q3NBvCT{iJ?@vD-@56Q9tc=&*!+j ztt#P%D4kNi7~KYD5|%el6z`1jZd~X{GQus9tc(5o4pZV1hXvdYbEFGc1EYfco zlP>VMK|!YtlM!=s6aT@38k0JKnn{rS=cXYPJPdTGyauZ9A0hh37Nq`CLeq&qA8jN4 z^&{s|rT4zVZg>j?!k_mQ9|)IlixppWPEh0(P}C4a1ERPdhhW++H~)^3Eo`#?!qe2M zvRK(Y!UPdTX~{MrEKK+bksmf(Ppz1Jj!SIl&%Ira#qC_aNlH2w?<7OR1DZ57b&Xk9 zvxRWppyWgy-R`e4YaqlWk1cu$ZkdRtwEYkW{6)kC>{Uc6A>ulj`2G*U9sh=rJ1Z`) z>b=c+jUhSOn_a2;FO=11bc_rgd_sA0A-znj8tv%eSZO7|pbX@7^9E{~(S|ZnyCT_8 zEJn*yh8YuB8~XA6WbVlIsQgYk!x`?TG8ua?`SDz`b6^4Ql--R6OzmaX2w&h3=*_qt z*{gk#OhWYLS^J^pH3tn8BBj{7mJ%Xa^_kbod$>;t)7^wPp1**qp&}E@ zakDe)WT24!OxZd}lWZM;2zRAEoBO^)U!nRT2`6+L)4sGlPo2phd6Pq*-wF+?_MV-d zH1>}LxYU1T&~4r2pK&-ej$1_>wV-aH1XK!Zo9+PBDR)#IaJbYFlty7j-KPi7r7%Yy z)D+>Y#txs7wg*#?(iR%y^~E3^dvzJ9q861? znhnd1XKQVtU7itQo{I;Q7By&n{bbU*LwsQ0DX~AY6BpG1cPZ-FmA5}4i1+kAb@>ah zf9PCmB8-e%F942KnSJrB0|)n+t=ELdP}frB>zmD<-|~2W=u+Mi1`If9=b2ts1J309ZZ_jq9Dg%%x{L|cWO%jwAQQ_TZ$AUH(=rxa=6%K$RQWBDKK*S}5nU+Si!``fBU(R*~`!zZvqtay8!e z{Jq`a=be8j9j-Wqp>dZmLY##4QTx?Qa4d+S?2PNk0q^|irN!JJ8)DB73Z9JY7N0^Q z8-Z!A|+(2x z8dhd2d~%bWuo_(dh1TGjZr*q9;7`a1sME{JnKb>Pt$VXI^ora-Y?}1K3HN$72~$-? zvETR#T*#YVVeQZ|)E#%eg{&Ih*riZ{BIjzdSoQO&0{U_z4LGMI$3iK7;iNg0VE-(t z8A^ir68}&HRVXAVj7BAlx<=A@raKXFG3(3ueH-eN4)c#qQ;!Uc{@2i+5qOe@=~*Q5 zrTTZswZ+aJs*n&>#IoTh>4SyH#9wbUvrH0Hy^33{#%P}crAxnS>yR79=5`HaUP8OH zze*Xyc$tjS7RUC2%U>6s-im1EsCM;W?GXLJolZ}Xc}HE=o|y2~M1xj*UKYQp8tvnr zdZ0bJtih~vCpr8lBF-_d{|)m-Xr!3n*+ncq zG!psbStT0>^s)lOySH&@Wb#SU2`Fn+?KCdFB5xxrG^4#zI!xAcoA|XEB3m%8g{lS1 zQI!4kR&eNteE6R!0@;{J+p_?J`$4|({=Ch8rFeen5KBIV#W+s=^YBr#-_zv&7Nf@K7KeQhG z?+ci2)z^dOO;PF_N9#l8=TgAh4Kc#7RCP2LrkoJihIT4%IhLW|6aHZFr5Z^CsgH?q zKJuzw;W8e&(2pE#YHY=vi;QsfC;o1;GufayJDOPo;fdLwpiB79D>y&=415Pid<}uU zXr15`v&l?Q=INRG{&zT{Yndv121Ejj5aF&c1556@VSb%V1p*hpiuC+Fe%TXnowq({ z;;hi$M}j~R6lAxfHZ)=4m}Fb8i!C-cy;B%P)|Bx$ZbdUn*FwI9?i5(C(az^;oF-}g z6xqWakAh%{XCq@%D(Ez=>7EtqGoAT~Z^~F1!9Lb50zh}IX73A%Md~7|2JK9pk0*en zZo(SW@hqJJXDf!2d#`3sTzB*u5*`B%l-G6Izquie>F&sRtx<5+nn_Ks`8E~Oitx12 zGiJhZW&uH`M02P$e;O~>*!+0dZzd)S%8nlmxa%atAic7`FCpVmAR}3Fln>^?QdwC2 z>~B7qNI$4tuM&c7|3J@vHNJ=#5ta$!A3B~|SZte%T%oj-DT?vLTlj7ah_Y+O4Dp*2 zSe9EILzRHN^GBw+2b&atMpLxXH!5`IY)PenuEFkuzz)y<8Em8!s*7*3ZmfZ#Z@?rE z-*jsw<*VXq3fDOXel^1tWmm_}Uw-a6y2S-3diYIM{kp2yR|GFH^sn{mQ)8D`&hlO2 z*PZ4RS4@U~n>1!O=H?4966PDOF_hTXxGm18~2g; zsHM98h5gYFuwTgYoh{3(UxNyevQUex%NyJnR}ruZ3iooSoDme->P|gO^jfL?Go)yX z7+uDevf3b%z`V9!Dc(cG?t|lJ=Dnuof6o7RTCp9sXp zjtWVo7(-AzU+#lP0rqD)ZK6R);-Nd#b`o89xEo$;igFoLR&Xo1*JP<7&OzR&--@;U zjUC+++OaB;I}=&;i=Wi(ZTfB8Q15Ma-(jQY;m!XlQkx1%#{0D&9KwnwSQu>*{|P~# z@l&OvmzsYoD*R`0&foGp=x8=l&2d~Hq7QkY^dq@9CAh@m3*jH>Z<0b+n)-KXT z?~281l*w#{jyVnQxOjSapf2bdOzhH!%Lly?_6x2{_pbJ2>;2CqJaq|O%gbe32DQxD zB?pKP`~=lzTcT(qg(n7@aK})=EP2i56?p6sWxG|CcCD@oZVfKEA7Kht~(7t z=LkBDrBv;;Z|eZ?EgDM@?mFa;gP3 zYu^2rb^;Pm=@@NRP4$ow(9dzm+2E&FFF3%K#G-lsOo=2lu#_hZ-=T%*zG=8@ST4gE zv(0~Wf61XCHGy?^UTE30SVWNx@j_V@Zl1jrjf$s0?l9LGRE0hpIt^jYQkH+$BHz8 z1_d~S8SmV{Uh$fZOWezBSS@LgW|t!ol$WSbz@H5lw@M)ePO2jC%?o_Bue%q zXx9X42pQ-Ol_1R={aMueomxG|GLGUrXS_y?FO^+|8tX<49|fEe5SI7*mth%Gz2Qv+ z5hY?m%QS~-K4f4IeAokU+7Fp#b49Fat6*qZ-PnFq+r*2zRTNzDt&An^K%@kv?qF4l zWT>GN6p%l3{KFC&_jxH;E`%~&MH+Dc)7iTxCPxur0(xsLem+8{5Nb)vVDwVt=&OZE6uV)Oi(}^&A5RxsOG1z7bUDN{aTyjDGw}lK1WN|_KuY+rV=|u%stCupuS}m(1X_txHv47lHQF!=PHI5AsnQ88GxReuKsRIs6a7rLQc0{B1R*7sSEP%w!o?{M-QF%o z7A+UsIg`*Gh{67mghDO6y${Fn{yIQk;KEU5s@Fj+%b3?x{qHW5@!jwnPx>cTKT^Mg z+O@%era7%ib?aD!0!|YS$=92YgnrF1>+FCX&$vyFw!GRHa*+8)oTlM9G<(-3PmQ?N zd4;mkoqv(3pGDW`2vdJxm93NZ?~=b;%--WHBowBzHxN~tIhbU8hrxtl`xVF9b%(mR zX*=-{Sbl7q`1#}5yo@mw9aq0`;VR+RfCmuH`;+(I-O(wK?ISJrdTB3)gIk;OMO7JiKBM*( zjOdcrT#tFDR!X@#$ZjOTP}@*>s9h|rXb9v`lj$qeSP%yXBiR7=XZvxKkY3NCh<#t; ztho>EJ=zU8^JcAd;e28)GSe63c#%)?I>d6$8M1^f!nkAFb0t(`a0b3+VD*PP&b;>-?DGzZfazbe&FQuq!F0V-V22%$Mrn1d7*yx`Gdw0*-Fo>y5!Gzwb*Ihc zH1gkZO5$jSD>=m5!Vx09IyO}*=Un#5^196Wt3Bb!H52gbmdsDIl~XD-bozS-9EY*?@2_P8%loWZ0+XXrKQ`Q%|c-H~trfwIE< zyQwcvSoK*qf3@siJg>4^uhc&iMEx0`c@AVyvnQ?@*Nc3zVDM5Mmc#9GJYh|1ceq)C zVj<^6V~{f%UgE=ji0pCO@Glh5^hMDl8=SaS@Z8w5`3F-|o~v`8WCq^f^26>zysY>N z3S5AlJb%Ob;dS?CD8#LDg$9-H z7Md6@o$hz}-r=YEZc00eW?7+Ii{;;+E@s2`(QESecM-SA@&}bp z-}IvhB(j!~@M#$EODcDQ;`i2@lTo6hYjtH9sNzhX2f@yJb&GXJIQrOfd_Db>f#1y! ztLDZ}C0>DU#47Uz9XE1@2J`(!4C;6&?|j-efWgvxAQW_JnyD~ALMux+%SD>zu!?XP ziilTt5zHxo1oZVMD82+FaVmeA!O+`s2Lx%5ukRoJ88e~&6DW|&%pzU6K)W-#OSYqx zt@!u{jGCh99IBXFu@X9v7pu2>XyQCw{XXpQUto|U$(NZ0^Y#B$xw|ewlCfSUAUC^_ z9oy*;h}AGq3CNYs0p8NeDRxXv^}zk*|8uKWM6+8y*Yb`+oxrH0<)|Yq3IwJ*4pE(z zDGU$Kw(Jz&?=X;egJ*Cj-Wz{e_d>a1TAi&wIbKo3RFm4uxnqGz~?? zJF>`56=Xl>l7IcY$QNSf0G4@2?hFz-RM5xU(I>pcgGM#^Jtne?lLU5_S!nY?^C)?A zq!Uk(ri!AXGRhK@n~b&0{2Diq>Du{HDMgjt_BW-w-7! z-leCI*BCLBXZjTL;)plovAqc?egDEC6*RhL;j$$NY7>Me&{Ez@Ey#8nm~L4MBC5)gC%R3|4< z>BXlrY*#0?pZ{K9pLrN--0I2a5ae;%x}*9d`VR$EN$>J0lmH0VIEc_Qhij+kpp*4l zv2{)DH*u{Aq_Rk@oG!FS!Iq7R8VNRhFXf%$PEPUw?O7J>D~yDshoh>@kxy8Bm!k>D0n!`lQ!2O# zeg6rwl*M@<%eh|Df83gSAE||5Oss<4R->uhI(U2+ruNIP%q<4_HwC?Q_lM=<=jH)= zBG>Wy;Iq(KjnC~cdAU}RD5qXJ;`cem(l7=Ap*{cd8M&~jIrcPmpYmU@`!BT8o0zEH zFmg>o<}uDay_9K1;3pYHv_6&)3PgZ0`+C7)*;f7Kkp#{HULy|E7C#^=u7z=ioE5%l z&S0IXtUsphQJt%5U@sHH#O5_98#=Tc^)i+|&*F>)S<75ab3d8*a54T3dex0z!l^dn;+c?C<&hrT_C=0HDr-mhWkNvZ@CGVO z=+xDJW5-M1w?DX8;2lWUTO{NfvH`c95(Q+mci_eo# zK3g)eBD!FB%Riepht$botMNz=-#!;fH`lFa;b2*cOb)sFGcK0V4J)^P+WH?P*#H2TcHY>58W_)R%UyvZ^vPqZ440HPJU3T6XKjI}jpzR}-_;CthS zb6PTjxzqLBSRZjnr}Q7dT8LWi17bW8q6k@7)Hb;t`c~$OiDbaut1Utw;ygoY*$Ww3nzpE*Z9Bk`KoysvxUXWBMNUbr-` zWL?RNn{d(is(cpIL}pfaR6I(=EJRxWS$bnJF?8ti^S}DnczW4s#jE)ns9kk-XthG3 z@joy~v~L{O4knJy0IT=eT=jW}OEU!HM_ zu_8u^0oD*E%IbR=Gkr-$0e=mwoSfVI_zOg%N)S@b=B)88&7h3ZE&F?;xJ_fqbUBMv zQSaU)^&;F+i}@6YVT$zhk8luUyy#r5?vBK79O^<3k^6|=in}NPT(@9vo3lYsBoPr* zYEpYzq0~t;dAV`rADbv)irYh{CgmO9wb5U7ey{-TNW~|Y9BoreGN(KO0U`m1_*b-X@1ke1U*w)+JPfgAA$hC`>U5x&WHABRs3{<+j)i$_g<@bLoL-R zV971l1|=d_4rcwWG(O_2n=f93Flve~}1Xf7m5Q46=SMl+!n546h_fMVF4zV?2YrMmJAgRMaE60G+FV*w^ z^f^s6V+w&^nm~>rrm~kq7cVm^M#|ijyYLc`mxw-6$VWh((_&1jI_B1xYN!s73XPh= zMMXJS=OIsi8=vRf*SK-+RL6`|EkC*nVnZp7{5a&N3AJJs2*`(i%rRaF87XjHbJSu) z;ZQ*s6K@NO4dC#uEa7}d^h_&2ov5{&d~^Fo5sboS^^TbCX%c)%RP~jd zQP_nK#ASlHv+MQVUb2QGKuNnwCa@#AyHee&pIAH4?SY3M<{vdakz-MTsnWG=U65!-r_xl_;WML7Gu8>>P&9*5q&f# z3bdc-AZ9fJdgZ~)XkiF4TyUG*9V4QRup$#p<&c_5s={Oot9+dpH3C^VUu`fTFvQR) zODwq$!%vR=_n*_eDg^ z;k5hbv#Eq+UQ02lou1H?{e8gRg$9H^fCx2>X@s6uwl4?0Vuq9nW`V2NaD; zhN*atojr_VB&7DIpf;j(*Hx(HWjHnBUi#AwC$tw|V>;U4;ykxy5+EgCqvJ~z&Zi$D zkW;lN_pPMHsK7Iq{Trg&oL(bTFh@W$hmweMJE0}aV19u!!v<-wM)}6KKS89G%3k;< z3*%TA;-7gsZ5l$k?NiKT$l916;ZUYl>&%b#EBgL_cB+M!btW-YAo~VcCO-CHTTxbo z|9OP5O2k{OQ&?@0yzkn_zj5O0IJOxUaz#r){~gmHW%H;9TUC@$sf1)0jgu)5U}L#)~bDoME;Y>oLw%= z|0g>G*;L#`U^)7JhW$U9zA~W6_KkOR=LAMcr*wChgmfb{y1PL-M<^g2(jW*3NH>fw zY3UpS0t4yr?ERl}KJ5da#-8WCuj`i-ydi%ad6mBgcFbcTZsRNf{f>r8ik!WkqSndw zIpLN8rXjm9YbGmy>8F0@@{FgGCG~Qw&~PESqQ?2+jgdpv;T;LPW_Hv;Usa!>k@eq_ z)HzZ{&1os{#LGb}qFlInyo0q;85Rk)PghX$1QZ@q_;i!~R}x z$%$a3ScPm^Vq9z^I75GW^EC%SD=R5crN*5lv5%#;SH6C%k6HZZy<~6j34GjuDtgf=6P0Q z`bK1Cd!Zy}aUH*Hk1j0)Rz4>Rd*6^Yjyp66xy9N%8QL)ayKe@*f4~~Nsr24i`n-L= z0|~fJ4nl@+8=+)Xe&3aul0@HfGIBjH8i)1R<{5~Lxbc4jY%;+&74Rl16o&~73)fJ+ z9R7`th_6#eb2^l(w-maD9#q^(foez)y)|nPN#f4Lq`=)3-Us&acA~vr;s=dR)FNk1 z_;uD#ik`5}%}BWMK+mB4;slG=mzfVsW%tj8U-v?1T8R(M;vz7JOiQg_Q@vvlI2EK= z5{B{noJnv%IvUcp)U(<`{-2N+od$(VRsyo8i?{5#rM`CFjZjx#?7rS!Mc(@ZMB427 z4^rKAgajk_M+_)xF}?-&!M^#xn58aUHKEBPWMx_laBbwYfzm-sCzW92EL-_^r@r>b z#(bz5P~SKCmrFx~Rm*$nkE!D6NQ?iI(#F~+ew~EZw6$)e1gNIGk0u zlIsOaLFpChs9N9w1z67GN3Xw6pm4>0p+YU>+keP9B9XMp#rHn0y^6}kQdcg>7TOZ`!2DxouYn3Et zE{;_Tph`0&Vpj-0MEElkJ=KY(#u($gm(>urAT#^^b@b+@VBc3v*ch-6zdz;X6+x>0 z2%krN!r;%?=%wiEO}^MO!5@U`Epc4|LUj1bDcDhlY~iuFb4j#%O5YzUisw{Wa!!WK z>Ss;)gaI>omBnAi{>t%Nz>b?0j2`p*L?U+UccO>4vP8b2vgB8aUvl_C(ctEH&hd{o zsICNmR z*wubPlO3sA?qhD%jP-v=CX~dp?IJVsE9RpyTT~JK>(5|AZDGwapid=C%SyY}^it0_ zTs~`;HMK>ZgdAYnrTjiR<~H6#QlC(Mc|Y5J=XIebfvC|cYfJwn{Becz$U{l_$y_kc zfmh^MzUZkzZq!PRxma{*Af?ShI^7AO8%p)jDU8_pSV5(XRLEXw#D8cMafic=FS19M zFswA2B~tne1FwRuEAJV<3mLM!^VS-S{Pvcij8G{xdgj51&tt{oe7Vhs@=x@0fdR5Z zlj1gYGuBVIxkIl)98O>THzV)ay5g-1qB8k$vFAe%^RoAtn3_1)@BlR(R+V7ws48Ec z8H`yUlA+*s*;28QVxx8d?hY@XM{i@7#j4<|6udNov;w5Ekv<5A%EK7a{?7XuO1ZO# zBYtflld;XN#5R3D8tDUY0ux*s4vVP7EBpu-*fk`^nYzP3IMurImRA_|Lh67fgQunh z4m&Omm?~$RS{3fpXTIel2SCh@nCgV#c^vJ=h^ilnLc(Qq0pZ`mt>)C-Vg-#KpK zWnq!Yry^0!6CbC;%5p~2t)Vrv4>)F#aJ->^lXqTHZ5oPytlg|WvD0WD04IG5*@+IJ zQh$pM$tPQQ>hoFfPWwL}20|xW{31baZ)-UXpPnNm8PJjgzm(cq(Xl9*E^qo39o{gv zuO}eNC)#5?9?)!J90=tJ*Va}A*Snvi*7P!NGJII7e6;qdZ0~sd;aYU8f~@pM-;yu@ z^HEpX>;v~E#51=Dw@%mk{Y~0;fXWOi0AwXSY>deanl)7&HO90{QyG%Z`^Ovg8IF2S zt1gN}$sn6u@dh)5@6CCblF__P^Qe`^_R4`}>+LCgSmMSSx%QoX_lL@HMC4nR=n{ju zGT@^dJI`7Eaazre<=kLI2~up7Vk#gpHr;BD1hTs|p?fc{LrXMc`-t`t*L`3l41?c_ zIbY6#(^1Lli2@tzq;irs`IXI2rCG8Ho?q}XkLF?TFBy#9_=3uBi2e|jsmz*h zs}$f{3gbALW9Z@hK>F7eNV1ie24~T%S1x2%^FZ=wmw1C^(uX_%o0SKFCqx2c*!m`q zQd;nOTTpxXW;_%2_;Mq_c2r3}1-QAt1kwjJF$7|dVPjIDixg;*p;cn$7jhKes8=D# zdt#CcCH`+CSC3v@9Og}aMo0aOSfPFEwC7}e4`i5PT>2u9@uVLC$|L ziR5aS*rk1&5SQNaG?Ejg%7T(&tlFsbq)&pD?O_U+LTuw6OY@ ze@EcgX?B&%;7DQHDK#mB;u4#xgh8tsmRxlyK z8{k0GxSz(YXO9tr&U8z^vl(>C6Smc4Uwu$I`|ODV&BXh9nx%WQZf~^cYS>L~A$0ey zBmP!nd9(k4xm#`5qLhBz{+9b){X48ey{)oGA{+_>_%Ydu(l3Oq<>z3K#n5UK%bbgb zQ%rJhU3}8w$Q!R@ohCs~{oeQf)(Z$PZENyP(}`aV`|1eYcCVX>t%cME?AzM6)Lb|@ z@WXe<k%w%<-1!EJ7>E^&b8(ND&Ia0bU}22z`f}kp&m)? zsgEG3z)Z9&1*i-WQJ?GW&PvBVQP|5TqNu6xahzkUpCkHrLSOQ2Y&1YqUS`J( zOV(Xh5!Y3Y4FoLY*c3n7dQXE{dX#qJ-F^v(4|s$?>7*eA8W&<1^N01ROx z_otDH7;2qCezvve8IIP^vZ^r9V;OUV0~uXxkTk^HUVh{pUCizvuXGGr((Qf%`P^ne z{-DpW0oeGEj}5jo>)({{uWGRW`7K${u2g{(39gHh&Je*_VVU!(sCZ7sZl5MNs-}~E z;@~c`XCxX|kAT)9B*``e=NX<~`xmjT;bq7!&m)H`Y%`m zLTlfrqQc2Q$V&?1uwq_C*ECwPsV*-x-FV;93wwcwc6N4j27T%fG(I=!?pQpo`K2Fx z?jEoOyYD87Uo5Dg@<)46oz)M`-?LY(ykJw%L|Bgu2*ou}EAwd;g4Y-vxVdZGIqc3qtcCnZ3ns zULa{*2v4o-^V{0=Equ4|9RV}sCXFvs%acO00ua6zEt@Crj&6cf&Zw1=?;~#mV60@W zeq$Kf?&yv&a{xE~p9{P$A#AdS8!`dv<;=wV$>Ocm-)a=TUiKTgVjnt1HU>#G%t8<` zRRf`$<9FV31kIGqYRwaoNXy#}s0=h$DW#F%cT^fU&6@TatzL1t8vukmyr3i?pLVjE z8T77@4nkLtA*Ku8nc-~ZWVs5QR9tT|=8VEJ%t}c7hWw4Lc5dL2m0v^8@G2@DZLoHw zD))ieWXfn?hjbk6C}PMO14qCsjEv}Psu6vazF%eIok%O9zRa^^Lp-GeAa^5Gz7)v@ zMrv4rs1X_7HKfM-^O!4*MSkHKIlA|qEnZ6s!$FrHw;W4`^emxc4*aH7$3%$g=jvzo z5A;EG(NOG1omU#SDP*sO{mP(m6QX@qn^o*MghW5X!DHu1FmR{j!sf11Hl17)Ey~lpWV1NDR0#Mt zxWtP5SpADA!48%ER^_v?6{_BSe80Zu`l%ukt|c^#Ta4O=E&i^Pr>l5^d^71CkWaai zY+&wpbO1j886YiVHi)~6!7td*T3E&pDW;Gq%_r4wN z@vB|srx0&C;g3QU*^%s8gWOU)QSEU%>%92ioBRI&PjMZn6>xk3d3Wq7e#+wij!%)f zHHDg2D7C6vDeugCCM?QYvt|9(Y)*8vI{W>o4rHv>>KuE zqfAXy48lRHQDr)82jE%QA?f`A@sh{QNC>R2rT2S?bp{^m4Yr*j_*$6(Ut(dUi^=3Z z`XNFjy^LLBDvhQ0AaOX7xg?q024?MxSQb&rPsYy|BDV>?=lk@+hWWqj{5cldAn4-c^tfiL*GGGXYDcBMvE|2_VHe1HS=L45 z>sSvf=?eeu|&r$GEiZq8SrCZm-q$=HSUJd8g zSF>G*fIPX8xLS=b#*F#hW^`=Y#bIsZgNsB?H)2Xo;}~e2csBs1C}AkY1rF%89PMR! zqWrAWFU~7Cu5Dzfh|tTVw>6CIpV{w_Z!1-0)d|i_ZV5q&t!#kaLViRFm39m?GYd!| zn>DBft%H9Lb|x$oE6`f~4Xvr`Am1b4*helzf1xvfV-I=fwP^6(u>p-iW4LafJh%d> zI85+D6+*mstFZ@IIFNaphb$B7pVz}UT4!O`EA)n@&zSU$f0Zct{y+3E!;3E9zvT}8 zh7^zQyujxjy~YX+va$>3KJ0<8FEc}iJg-?vR{X@yMli!(6q7F0aWn`?2`|;88J3JD z18lgi?Mf-2pX&ncvE!z0KHE`!au8}0SnB2ayppku-1z<;o2UF5wGa(*GrNg4R+E0Y{G z=fY1&Rv94QFY#aO;GxJTQpbO%u6{PYd51`vpr^+UTfZ5bk-ItS8XC}kET8Ma307Y| z%_yR4RQVGXfqo=fCQOKYW0HOzkn&zyy+exIJ&2SN^8?`>t4Cu&EIQvCA@=GVW$&I> z00l?B*J1^-f6J^I%yAg*#~SIBU}3Q*>oym^jn3auE89|CrGSBpgiB{yZvSWvD?F&b zj7@0twM4J)(IK?le!(Nu(^vZ)2RHqvjldLMmR}9l>Q}6nRHK4d*5%&5Frh{Le)0YG z4TuHP(Z9lUFu%2~rZ7PfmPY{=#n^i*sQzjwJ0d2LK*XkjV2>6_Y$27!U8$S=dUM`J zc1FkDieO%*P3e1V0&t+m+I!AiK~v!8t@X|pk;sOlQY%6GXSe%{4XOgJ@+QoU>)8!h z0AY5k6X>hkbK@A;@HDj=>+hNQSDnen6|4f2j|EVn>_kto<>6Qpk9A*0}$4>6K znmF6bA4XSPTnowEN{)f}+{0>45f40FJ{~L&%*SfIH%^bC+;M z#T}=(N6w1t86wpDK3!2%VsP6D&EcK|bw%56D`lJvv(N)t*cjNBDX#Y?_6`Sli`|p0 z)&{fLj!vh(vK)|8a}d;YMy=t_Fd|$Ar4>ExR#_SRF;_}j7;SQrNF-hR5bR~_&k+UkySK?NjQCw{&^HgWJ_oQ75K;Mo|fO&?~~Te zzc^PPq=jc-NpkTReSMN;HeM8Z`2MCTM`C8hs8hZjrCXpfF!umq+BJX~%MkX$JwXptxjKS2Qr)X#up7Mq2 z3e8<<-3B_<=ZuLx1LN`Y!oG>NH~HTLv)Ejv;7$D3lr!EA)~3BHG=v7?wwB=j*wnD( z*r+vMUq;8qs{^D#*R;RZ+Rm1s=6YN`V#S~Hd=eS4b1u4_b2Z`1_Nt>=77ys&c0zWD z3sC2#$KMVZQ;3TUtDlZ+tq6C}a^SI`H7i=ppX1v}g2v}|(IxC*pAt$?Z>&L#;ak%z~9t$-0?S6nH|j5+Vc^?8wCTn1Q{oe8sjdQXYdT z@5WKwrNk**^AodWvVsM7^2s79d2g}_JdT@(z~GYt7&yrDmUM%5#0henH>%d$E3Wd^&t^}7#F6H=|B1^mn&QQL~=U8gvwWY z%TP1m-xT3Z={%sV9JSAfY&Faq*XEak=F%+YTzNE?VM*{0+Ibcr%}NP0a!(TfOwY)_ z8}n&ip=F(fGP8MMmQN4!7m8>u%fxltQGpHP7Qc2G>dc-jxh8`-k4TNjCO2IzMm@g@ z;nrY)*6sx5=QU0H%P>R4G5VfbV|vbpv}fPZVAfa2e&p*cqy1eQ8mFh*Yglh$U>v?2 ze-S?99R&Z%=Pu3rD6Mjksz3^F%NvWjJWR|yg(^PrezrmA1JkZkKRr0WB1f@zs0qXk znM!8%;IY__Q8iD=Zhe2eZAjvjb48N7E`5~zq4%%2gr88oB3L)ld1T=q|M|OYQ~nv8 z(=n3!{!o9TM@Pvc(G=|V2P=H!#*a1yFjMbpEJ+%B``XpAUpgtvnRWVGDk~$*k%M-p zd^6y~6@89IXRhVyH@!8(TszO`G?0<+Wbof*L-y0x!FMk4i>?nGySdjBe;(#TIk-oR znl$QfEr{4ZjsRS6v>aq_z`XYjl zTctB!o6RjvJ*ADfdw#Brh9`9L6&f(n`u^pxm>PXuN}m?=ow?1M;!|h*cldm1B)11LwP=SuKgwLAB^;OGqPKQ?G_)3A*L$1A}}{p+QrD}gI7l?EF^!e z(JAjt5H5TeIMK0oIyWCG0rRSLn~#!Nez5gh_IU}@&l3VY{d_1lkm1_zfQg+h+{a0p3*GlJZB~j=1qvm7qXBefL6>;+6 zKQL9=lP!Naj;vTUY>56k3$FZAP`4~j!$LYZ);g#3`AtdHwVcvmj99oIG9a)p67#YO zLj79mU%Tn5#G;^{+mPaVgeSvXfP6TUOV561$fFC_Zeh)6xM9>{vsOvJY$^Snm|VSS zEpBx3oaHPluXHZnF|X5HS!~oRRytL$viKU-Tz_pdr^eF9GAnB>DDQU!PnAXkV#NUD zL{@cDA={9?NFx)v_1)PbV}3`$S)MG0P1qwZ?D`B#<}LDNfO~`wO<5Tyy~(w(566_k zn8Wd5y0U%1VeUaFN6A~Y-6}9|J- zRgxfZF>*_t+!sZ>bNbGlz9Ya~FHyuQH9mhzCAg^zjL{UF8=7~KH8P+)ulKs}m49k4 z{GG!nhIQp8&4StQm-1y{?hnTAdPM$d5LrPbJslsDiX>?pd-yjNv;|w4Dn=CjB%-8io;qHW7@+8!B{9xI zu&xlr{WDFD0SgaHV0^xICEqF_4ExF;3EAPts?u3K^iH4G;uT%}GiuaeI8H@o5ORYs zY)G4YMr?%N5eo)EN}wZ7jF(_T`OLHbC7c^rLyl+1FdJ_bFI+sgy=eIvJ9UhozC*C$ zj8q~W#0a63O4Lq(svt?u@q9-5fpPF#n3A+vuI&eJDWwV=sjUFZvw(Hy=xxkC!iX5H zA2?@rxxj*@5s5}>*?(2G6UdmS3r%Fx9lmGazq6*A3WGuXxKldrKFBkrbOfc`Q1>qj zduhDm(Aa79G&`cr937t7W+Cq6eJy+!X0okpPdv()B-oi@DBhb!o>|bQ+F!L!@o&G_ zvK82Quu>N-N$J)Iv%3O~_j995ze~Oj97)khsL<}qxNHm_($lZTf?_&MibNj~l`$j0 zr;meGQ;>zoK%t;_RD2BjJgyK@agd^fBq%i6x3Y<6#(s)b>0jNbX|{L|js#ufR=-uh ztUVRQr03Bc?}Mpx^=qNz&-4hb6_N)vB(2cNU4SViM#}c1_avFXE<+kWL|S8RNaFh@ z-oOogiOn|Js0V0TfrMXBBUUBi6&*^wB?uac1bqd`x5KWOCYQP;+<8r*fNP0MI9<(x zsTyR9l$#uzH=9vEkqWf>Mczhg*=D5?{wsywt|I9-Cz;%Tkb^4B_EdCi68Ex8_>9Cq zyU~aO-Os)_hTda6@`x#X7*AOQBZtnhgIC5V4iER-uw=!KN6 z1)_Wv?MVb4vfZ_4(kd181O{%sQZpZD9Wr zRM6MNT$s7yp5mrS_$^19!GRo%J)_{X7%e!Z*V6ehm^HrSv&s`lByxun^kRcAUk1WL zQnA1oq&+i{4P94*P{Ys(6(Q)6WBZS!H(!yE^{R>HvCgOwhmel$;BH97go-h}(XM3z zL=DUCGgEXUYm(G9nk9FCc$20zHx`DTHKIKj?n9yY-`kPVCQ1?9wC+;hUpn4VyfuDn z4=&PooH61`5x9#Vpx9d@xk<*!2Kh<$$o>Sy`;N21WW-C{wBIci>T;`hTS`#eHNojW%(GE<`o^l-J96P+}uuN&D#D560{C4Y3nK|oV& zvj07ZhA(=BWe+P#lAN)mCb6i{1(=sJR1@d(rF@-nWQwTlZ_t46y5gv&AmNQa({>zr z7t-FzN!Ds(dgybi%ltse9lDl2$K_2Enh_pSK1{Or3m~&Q7NF2Jg9lHwR|R*BAy!+a zspKvbq$huz-9OQi7ThWCFU_1UuApw4PpvH41cgZJ4!Hn z6B;hO0W%0}W7|dQ)(3oT;5z6T@T}A6jkrw67Z8i&xd`hV2sJJTas|%_QIl%!$`q`rO*SGng*-BP}R>wlfKeyf1hyv!bsmd-R zyKpSQ+mC|3xOpggwz00RiuAsF z;f=MHQL?~Ms-!Mhub6UHGKQ8W4eM{weX8?xkx2N65L$Q;b7PH$IIo|pkrR!04oq~7 z{>;!I5T4K`^>64C@`n#xlLVR8*FvF4n)8T(<15SMU1#fWuLKLhw)Yo8{E6lv)B(i~ zPbbyU8}+N@UDD&uB$K{55#lnVN)&Vw^o>oGaT_e9##D>@RW8Y@fmeqgJ5!|5`#s&`N`os5Oc1jc&A!5eL~DPD*mB{AdPU>_b&R`_4az_ z9bfJ$;RJur+f^;{>h8aeu6M?2KXn_romv53_`IbO zVz3Z`*6LMRP%}Yz!CT9;MEFKM7=>>K6RWKc4BmhCUOyhDMsI~K|BFbN5)mq>fji_^ zZ+a&%by3U^laq-opYQa=nA(7I$dW^NR{EY3a_UI7rozWa;uID$Av?B5I( z)n^e^xlWxf{w@r46;caR5g5-Eg&pUHrlq02PER_@NU$Hkrs9ERXdUK7L;9uQq4s z*?Nqan7ZrEsoh(0(Rria9MssCWB^gbCk-fFRCq(T)kzzs|C7=em@C$7YUJEZN%d*Y zt&l-#r$J40AHqOJD#BOL9vpc{1JHac@u{wUTyW}u&`C-DOb(pe@X`@I_ZYe3%g7}l zP;n}jS8F_!pp^4t#~(AOcEb`Fj7gO8C`x9$Cd*Vwcv;5pqI5*-dP@s?zpGO&;KnBpazsQtp!lFGJ@YkUeMYT39v1Sifu% z=wwZ3GimZGy`D=Gbcj#R!PZ_|RsjuC5?&Ld;he;ERCPKFm9ig8vk;WNnNE_AzGq}w zuuFPvvl@c)F18(zG0i5k;5>U_#^=a@iI(<2E9-B7nvcbzjIYV5M4j`R_Q*7dNZIog z*cH9vzWaM9;Jbsw)vD>L@Zxo^U7mSCVrHK^G7ixe?+6TI=cVZj){dD{`_j@jd;cP- z<%gubBA;SFnbIjj!I7I$l&|*iLg1neE@k-*Y-y*!el;ep94g94F=uIIKI)Sx>eALT zOZ*ZYq#zZg!0^eao}3^7-=vXw;Mavh^S3>LKcM%~V#)wTO8ID|z)K=R*GAq%jx%M2 zInkhUKG&|&`M4HWO=Kpj=S>g?wSB|%5sf;Vtyt|C)Wq;dFZ-5%W^y}!L|f*`u96op z9cjJfA0BU7@^B1YN)h|kj0<#}y5`4T*BVnu-%uSgPY<31yXQ*6q4Csp*%{UwEb^DgQB}- zd1m$N46NUhKrlY*HC`WhNEdN>-WqgkKvM(`T8e_R5WaYtnF(IRRR2NtshnJR($BS) z*huWFrp-MK`$8o1O1gR_`Eo`}!{x73W+b(lg;I}-VGopb;$_o;O4K!u{fY@naRR!V zWMmymO;#(-8D4V{HeA7QG8S5*u;f+~zyOA9)MQh8~xDC(K2D?}^gb z+YCidVke{$VrxnZ!W9Fh#K~ZiDe|ofbWfZzzU}wcGA_ZQgLX3ucYUOS1}tW~+k6RX zXj!yeA3YPI4B6v%zx(DBD)S;_yW`u6 zwIIj0&t6HY+l7r|aNKopi9w1pYQ6BBIw8KVs$QP9i~tW-+eq=g)oi~O>IAv0%x*d0 zfdRP@%ewmaDbQx;UMzetzVPj*KP2L!pDDGl<*6+6lxNz_icK4}--b$FU1D94$SxJ~ zRr!X0oNl@k*VriUiJILAHR6blMH8V;gwl`=2~)QdQ={nnn8Put=VRuTcb*EEmqr~@ zU`??Aj7Mwhkh7lhn}xR@L|BM)Npi=B-4AGMc`Hgk^P!CTbYu@0(V3OIRh0G{mG&os z6+LZbhSQ0lwncG{pwChS*<{I2SJ1FwXHU9Jw86m&Nu}`Poi~_WDYnan!eW#2#s^0t zzZ7A5Xw8cji{*@6aYP>1p8dk%7&SOgYxe`wf32sO7ayp4x%UVnXeQtv@euU|Ihb6A zZ?&9C(0I3y^*pd<)p>Tun8_C3QL+mw_WR{q`TUPimh~tiKLGG)^Y*b?@op=We&3sl ze$lpciDjGY1qlT1OjeDI+Q)vs^9G!<=VmG4njQ50`K=@b{Y#9CRFLyUeU?T3kS&)^ zHgbn3Fe=wUeH7yA8~?znKpiZFjw(;8?mj}4nzsjgJsIc}p+ue(F@ZT_{0Ux`u+it{ zE>XcA7NEqu%4B-&%jK{5O&<_vXOT7BD`I^ipFjh8nuUyrcLq9D44>P_Z2(3L1LFy2$zom}73Hph?KAe_P)Gz>goHNd8kKnq0xB(MwEfFAw_}; zvZ_Dcu?n*i{7bG9ES(;p_|h*Q6=i}JrO7uOAgo=6d>+~Ec$dq|LtvL9>gOe6Uk+k_ zr04^s+0%Y|PVJoaC{FbVQ?{J_qCNF50xnJXXEisb!NO=4F-^D4N~lc+#3&7kzVFi& zdCea%o)s`nrTHeVh&WAh7$%K3??%0c^pZZz7GqOX{g{V1d-bQ`ntca+QXN*+8`5O; z-iRxmWE+L}A4x!rWl}%O5_i-2)bL3G7Lnq2cb+}wC{rG{#N~TBh&!EME_`%&YX?4d zV*_5c2A`K=Kj!Pl=TqgW?^&)K1Q)2A3G3tLq3&&wVL21Cuo``q1_AjVI8K2V}x4YK5~1FKyK(+g2bUlG<&1+qdAQ6{XC zJi=xCN-jOe5c=maIZyow--84S?vp=!TZz?Mh>IybeIZl>U&DX9|Gi)x^{@t>-?# z^5+PE8?woy2$v>HtQCixkwI_&%J1R9B2zbM>5t2hzTsYbQ!q3Vev1-H zObOgOmui~4$=^;ixc>iIfHQF3Tih8mB*K6J#lcAt|I?wMgBd+uWVYdmxp`F zzBnt*CgOpL97MF|UAlS~MjN^Eo!1i-t%vp6h)t?NF?lhiC_5lv!|QR|r5E=5KhTu? zV)J_9^mx(L1l>h43&MWDlWoPidxYKrmgN~tCgDrxPgzz)xU`U>G|ALz#SQ=JfBkW+ zN<|}xXlwd(XFUyXt?XRl-7sp@)<``w4^}wz`P$WPRs5uVTzzFVwC6w&Jy^#iZ z*9kjZk`)1gTMm0ywm>1=u|6f^C=DE$)mB1)W-4&mwB6tZEQF*|DQ*y^pX8mAI@*>6 z=xC?8%fp*Mq;$c920fnX$x@t-{OJKsA|k-z{TiX}jcrOqMXy_RsOyi-`D3AOz|-@C z?M+tGb-sNN0y5^DzN1VqoVe4QhL6BH97BBb&M=(*yD#6JAbqNPpjgg(5AmTp9L=Yd?R9Hsv{^4cYWn$VLk_ zW+xX_LNbhoXY6$z)(vtKUZK>S(MH8o9|_x2k*Ft%)mDKZAXxjNt-p!!uRB&`=A} zQzr6zPyy+soj!J8bK|-9-7m)Q;ailv1Td}#ZA8>O8rrnL(*Kn(jCjW(bNmx4)@&Fg z&r=ET*x9L3^g_F0io3PGstIjtt0d6I3NG^O9W4^{`4f2@E`G2`bii1`ATdVg zqeuvS;KYB7D0(~j9zO6Kg^QF*XeD+^8L2~M{E*-2}dN;ni&yZfYwfk=MWlGR1pK_2!JUb*-{YoL* z{Su^Mdy<15)uqrRicQ?2-YeT5E?3Z@tVA>u&W|1fP=$q~%YwTMP5_Lt9DOYqxG7-V zu`0QJG&Hiah%ukq^yP^Wp(MYIkRK^Hw;H7h_k1R1v*JCGb9ktgi)P*wMN@4?SAv3> zI-7sC-^DyUNNv9iUFAHwHQ8(Ki_YAP=Gw2SFid{MoQlLjrJkMdbCcVvXW`fhp5GYB zchEEGgg(Yq|BV6YI^xnfNxnJ3wQ>R(myez$U0m7Z%3B6(kad|}*>q9twaj&1i|lIC zco_qo2_n+xX#Ufvw0wp}NL(LQCwJUeSW(xO4kwx56zQiAwCOo3Nft7bU!(iR$5utv zgT34}2&_(jGda8sM(t(}A_>3V@cK*f*Vrh|@9p2*qrtg79kDnC3s=r=`=$>z2wBp+ zA4Nu~C>+69$T&#N0tD^>E^Z#PG7esIDi_QPz{9kdXi4vK&yJyZ82!Yp&*#U{{ofv_ znwq;utQ9^62S=dJ)LMX25RNR(i$qF6{P{!1$mGYFrTRW+>aMp|5;+*SxpQ2aWLDBk zll#S|@C&$VU=4PAe7a-GjaNcvtMkV|E*Uekiq_uvhIbYvvo^L?tMU?!bf_ML;3Aw` z*HVZY{E1#RJ&>wVcb5`maeiiZo3M}96y)+ZdBXu}xzsh9pfT@=>BBsXI#m&u7fpdE zj047RV4c29>J$dFheNHe)|T}_7O}?Y!xCE}x)kh1sq-`k$$H~Xd8@B~P{Q|W6UM81 ziV#>#-OSay{(9i?M^Vc+yD!bT8un#zXCcw+W|TA8dlt)_EnCtXaaUdtBk5pJV|es! z8JnPJsTkgU8go=6`L$=gc3t1FgFw|)$rAY#_CE{C?gowM=TV!NEMhCopBhyW*Lic* z4a&dMk9Z4nO3`e+CB*Q_P?F7 zl9|1~W(4|vO;FlmpE}YsfA2jp85VvXoCbYOjj6}$+tH1t00P_)X}7Ty(*^tH^)T%{ zQhxq5Vt0{!jyyB-D}Z*j#x>;U_8@w1k6VtU$VMFWY~vp?A~Qg`-qh`%$eR%#sp*wb zKyjZFa{gb+*FCfIQz+h6suqpff_TY9pZU=}KKlO3!T#(mH4XW1?%=%U__&9NP%9eB zD+QIYU|Ud-bE1o4cBv4GoLyf;^52wSSeu_xPwM8q@e0l%5`KkDokx^+EU}e~hjenE zT~LLpczR~7=FFMw7!hmz@gZM3i$dd_z<3pZsd))+V!|;8<1ytsEp-9FE40{;v^AWk zZ_tUJ`GPcFMX=)xq<6&~vqJJyJX%?#426}XWjTJ~Wnfy*l_^Hj9x7%zx1fO8Y1h|S-4#zpy~R1=i6Q*2`a z3GO6{wmgy~{g0(G+mnJ@tF$f`NUsEfH8Z^zD%q~z%4JGS4MMB65Vl)^?5b-m9%Y=8 z@#1%12z6r|*n#3gyn;SIfkQz#RgFo2j6Xzwt#B1(SBoKG{6VNu=o>i>b5sS6<656) zPb9mic{8|wu5QlAl>0&xlU0xN0!o2jBerP$sxf-NCG!|*eV9jLeGU8oKPD??ir=^ZvFaeXeI6@;~ouYJN4bN z(d`#klii^Y$Y)4gicgp$D3>Apo8pLr?$+wXk;%4>>HDu} z`OLLZsTCgEtt^EE*dc7mw#X;UILwjgngTMAY_8)v}J@s1D) z_kDakYq%Mciu-Rej5B`KU!LS?=Hd~Nkc3$rgM(#x0{tF`M~HiZfk``$0(zWWarcm6 z3+Dc|Gpmk@;qSWq6q4W1|R@t+EUXDJM@Tp6Q=AmxzK#UY#aY6bu+y^7o0z zE2?($JMH~j#>`KO#ij`}Y~b;qnPlbY64i;Z6Qnm|DZgtXTH@f3v9;eJQshs3oni`d zMucn^hT$x$r51ls)#c(L2Z_Nx^8ch`Fm$uYkyp9#!MiZd*Fk(z6d?{XC*dKB>^8Ey z5xI!e>C9CIN?|4`HxEe`q+98=67`T!eyB#gDW>z0Thuw$54F=t&h1VXUFkcmyv^-x zULcKG>-tMzO>YrqtSb?+c36G(og(=;OE}>5=Z|)W+OyEBM$2_FGX6Q+C z!;QKLo^M>cS{?%DnVPd)q*vxIJaiy*OR!t}-1ftLdU62%HD=syhfcOKMslCEl!s!~ zaQvumj%_Xzb$;X=$D9ssoCQm*1Q*sW{H=L<;GSv8h|=Z*;WB7tR0A%6xq08VRCax>XntegHa%LyuMmYOCk?KL4IBvh6#5 z(CZ5Q0nO5-{!d!;cEBB(28m1X?!l;PdG(dQbXjUJoF$;g4*C`IqJx-7DYcQ`Q$m9B z@hDS#As^QZcW>h)>sQ5ZDK})+9R-h*By#C*nz&j-t=3(05;S^0%~}_dCrbw4l`P^dp=#40Y46W_Pt6 z{ojmY?R_p{SIF!;N6rF;$V0aZ>Vh*nX%^@&pM=xtCZ`1TTEf5bzn9Fm#^YslZ~^%o6Z1e5!XHbzjO7?wHk~?%f+X}g!0Jp zXm~pcxKm;+f5q>cK(P6BF(UKp*EYD1c-sQ?LyuL?vq#OyG*h@qp`UjM6@0?0%YCr! zW_GM=W^wJW{*a>D>jS(d&w~2*ZxHzfxTANoW`Zwb>DK@0k5e>h4KRgZ61|UJNRPFf zH6Nf=CcTqkt|h(32oO^qMc4$8@j`K-YFV$4Co05p<(PNUa-1vlJ}uUF(RZ_LdV4Cm z!(KUAq@EV z$_)!dYNB3zT7wC@@}|vwR1*;-q!fLO@yfifSxN7+bQkmOiKFc9sTQ#$CbI3Yqz+i- zc?meezD!~G8NA{cSYc%pRw1i+0F;s zlGBRBX#>_FH05kFj7ow^Q3_4QwQH2VjlXSXrK3&4fa%M*3Lwp(@J%Coj#wQ@eeC-8FR>Cl0>SRl9S%#I&#c9TlNzhQ_x5576;x}J&usX~Dh=L`b9he^n&#+Zi?%S0ZCCOsA#|u+f(IcFfQxS!6EQl1RBKR_6N={ zYN{&*OgjgK%`7q1L$(~A80~SQX)uz5kJg{T`?}&LS*8yi;!UiGuKgdT-h!>ou8Y>i-QC@bySo)B z?oM#0xLYX%ErsG%pe?S&-GUQni(4SLyUWS@oxQJX|Al8IYpyZIJ?DJL#2PR`Dd|D* z7V=_d1h}DM(78~K(MuXt+JZG?;)p2?{_2B6Cx)+}&foYp6sttI`HX26{+y6p7ct%x zra6(q;#R&=>Wi{5$h)HZur`Mv)QC6m|B zYcMXQM8j2_nu4F8SfPBH^g&zPql!xzOl(4Dv1(F(_@0&R36gBW=c>YlUP|`MWA0hw z%R!eloZ@wK2x-8$%|%`y^GmFq=z|YekoA4!nzioP}>`; z*RM$+{PI(qj=E09+ew}^W-egxPJ_l=BmkixBxub~+;z)CE=%Ci?s`-}RX$bH+4eeQ z6Z`XI+Gu(@-?n0mJYt4&)sYJKAk;`C0O5J; zDR)bLZP;u@%E!^7euL;LF1Q?$VHq*Di!!moTe+2|tFlo`*ze14TCRk3W({7WqB|x% zT2bLscJQfUb$=VeqB|(ez~EW$N7#75ihh=QMKcEl+brHlSx0&A*tN-&H`svDX~?O* zn6KhWF3w8*-X&#&^(xx_X{zV`!5>iyX~U4VN9Y z6v1H7BV^IIU13UC5s@8xT8DNo$w3ey&oEoUbgQGJAGuc{X27&GjW=AYjCMR!&cfk3 za2D~}_&(`qvJDOV&R(BV67^Wt4Y|-;OkDlNSHtl+f6|l1J653f8br*(%{(clG$2Gb z;3qIkBQPoY-CJHFg%qpsLV7=(bwXzjMp&#T25+SWA%mudbAXr_IUfZcQ%@YRMhBRUZnO~6)#YK#xk;JzU6W^bRO1K)hsVMe z|7HRLOt%`cC>7lZq>km1RIpkkR93>yes}+RG6s(vq+b3!&bP5XeFtS!$1o3NnHK|pGVU}y{UP$_AFE3hVI?4p?HF^y zMRxt~c9KhMvvMg~A;kEoGNrew3BUJQKLmd?xAJq?DBR4uS^IvT4O&;l?gSbo`IyXb z!m#yy!_oF@_V2yCvMSTF5#ilpFKv!ZrYMB9{wY=Cmj_08mj@<;6LLf0cUDzn-Uij!SR(lBR#iKjokf-|alZn`ue_zFM;@}9vvI0}-4tI} zPe^j#p83CfoQrxF6}s-oOe>#Fjt#-oEHku7gtJ*j%wojre|fMlVTANTM_H2?ED9Ei zpOSsQW$_>Bt#!vIca1`{|1}T{19-o|U|+|ONyW)Q7{+VjwfWip_Gi0zaeK-)Gd~ks zNyn{QzX|sV*f8oV@6-QCt19HdKaF6{R(BXGZHWU*b!i6gK`>()^>6s3@C(b9z%WA= zIM-XQaSr$5js7&#m@j?IWe3NAHKrOlTx)A%^1kK@ebPtfKMFZwpr)@N{*K_QD`gbV z|A5%Jqj0-C5)vs-1Cw9W#ngbf{#&A!aQ}*KQKPyDX$PMF!xdwnGWZ@=3thxht?1jO zPBaWMkl)+=M?i_M?>&%F!%TjMBpKd7 z(sMw+)t#@;n;Y8E{IRaIm|_^8mQMu{WMN&0R;k3#;hzeee-r5xN*w}s6P5=3XD_NO zFHrrLkB$3`WJ3w@@CezX>uYE^1H5;<`D_S@(IA)CxC@B3V2`TLn**LOcjnI3` zsTZFh5WA9=RmqgD)vq;!_!N7q&gTnAGb^+(TD(ZcBChHGX<=g_!|WYGuk}8IotzQz zjhK^~WU@2GE`wqWXSS5)zeHXc8$m@le<``PjUlwr_VAJgK4_aF4}N8(wd4Wv^ph6(2|mX5Sg%FHTN7#QdU2L>Jun%{lsSXl>oN?9=xPa`9-&rdGZ`p;d?ez z;Z7Em1e6&Wi);pw>b9{%QR)h}$`hhJPzx-n1V-?q;l1P;pDVH@U}tDK(k6am?s?7< z{pH+6o^KBg1lSFlr0VQ4#)2*N5sI#(2(^9Te_A)E*>D>!zv+uNZoV{y<4!1<_dbF{ ztmE}CqUnr@6dT5-bOA}LB+SN<>B8CM#ezHfoccLG-7M70Y2kl#2jK&=m~dEA{CRL( zzhtox*ww+5U)D$ZVKk9StWAy$TDebqWK`!{Vn*Dnv53|> zHK+bmd>~W`OEsW=B&2ZvU^9eO!Xu-O&&!5dnz)NR+D5USrFP@ZJ)@l|KAwQ5vOuTG z`U?)2rxKdml~7NU-Ogtk7?n@2vAy@~|t8!KT0j1Fm=w)ka)Q|e0^ z#FLx-T#JX455gwujOW-}V9jzS6iC$Ymohb9^>00_c_N8?0(EnIN$?qAwOfgFq5<7_ zd#F>UX_Y4L_-rIPa^f^miCf-o$HXm#MUn7(kYTsHKyNTYWUr}>q!|99d>UN4sE60; zV8dp2Pn0eJR%&@O?*|gJkWCig&rNSuVGu+798PW^J~Zd!6^I!(D;|}PSL5PMa#QD zY!%BIAs&35?N2~gG&Z@g^YrN4SGUL4t}TK%-p1EEG4H^PAb4y-C8Is=;X_qpCv5pU zu~qQW@C{VaMnjKG&zW2#m#I(k}v!O08WH9QoNO$as~HqOCeY1mD5M-Z%ylADZA)+ zfe4aA{{-PSFpHH25Qnf-v1SDZ3ow}-?enR|GB*t7GZ?XcW^TO zQ|6~pU;kc}Py$E@81YX!S?s?+YQZmtN5^*T-FO;VHWL?DrTYXMmtUxo`e|m#vB>8( zJg#~E?&{^Be>Z7kr7Vc~Z3P4+H^xTYCSQ*_!|hQVcUsKcHNhAy^CK*>U+$psPe`dYzDRKZArODDBoxuxC;n{x@=0_kt>{-UweYNQi^-lb z&=p^ums_M%MnocIF4R?ARMz0Grq6D>@e-IZl%!^8vNw;pP+s-gYMAW$s0(ra78T~mAK1YUivFG>iU=hp*dw1zPd1HF zPLcz<#Axz|>o}{np5G$UccUgU?$?nwo%Jhb%*I||rAZMYf8cqh2Tx|KPPI7@qoxR8 ziq`+k9|ZJ|P)iF|G0f z(&th@G4CfD7YxzUZ^7N~>fTYKYXnytuh+f_l9~T?FiN?3+p%8yPJo%v^Ru96z?t5w z#TvfE04JCd_rt;NGy^l%o>Lkxq5_lgJeZ92p9r6&Y9XOojEoTnw#?m^QQ6rNCLMmj z%qp7Tw>x9yBqDsx45BYo@#N8IiaLU*k1Arc&1>Ic9bWi6&$kAx>0_|tHL`0I#dc!(A|Xg8@~`K+=u3)9m4RMa0&()UF(1y z(@BCtaT3S@aANPARmd-^3&_n`9(D?01i8kL6L4MI7YXaN^SE@Z!-Xve~}L^5h;% zPBJFGKST(_2{ik_$?woysueWjU^*a^b1}Inc0(T-O2REYjUmLNf8G{yJ7;u$#W<#b z1=jIe=Dm&xt(j%J>XSrOb%5jj#v)4yJQ8-6!#gX%Lct0RD(^Gu@r^x^rr6`1EkA}% zgg9A${IZXi&BceC4Zu0@9N1$Wgx^=VY-U1nM!}a@73HR%Rbk|4rhT9hkPXAgVg=Q) zUt)yTynab?kH4nNO^vzh4cvx;>gP)vNq>gciD771%@PXeg($HQ*-Kp@xya`_yD~KQ zJB?w5&2!;_{kAep3COgUGeKu18iiAsOncKysy;#S>y zh7Jv5DHpcTIb*wBQ$W0Fy^TAG<_BjzLY64nCIs&Gq+Bw9~(ZMrIQdC?4~?*ABRo&gjpAq$(t2$m8Jj z0_elTtNZ^2>2J4ii&%NC(JvPFEi72rOQZ}36(o&~Bxs78ZDq-EO0PeBAe=3vt)BLa zqWH*~YRK8Cl$CQasGlDu>3ZOx zrV%J>7F;#0&VZX^-008{<|D4s~U6+qr zQ*It4t!#%`)<}mVs$H8>HLv-|sUF#5BJy?9YV9UOE}X5!KoSewjd{3xn-j}^O1wR6 zX`{w19%*a*_Iv*P4!(BW%j%QH+!qAqi`PF&yrI4l{yXxtF|OmAY(cX+F~4c+qF49y zwvjEV!e0%kSX!5cvN}TA*gaKg)FBEuZWFmv=Li8b>;sJsk70eKEaAEstGYy~*Oa}v zE@XekvW@MgE+di>{b@(;?M$ckQjwX0<~U+mEr)jiV%C@*mG9e2dsW#yr^k_H0dhe; zPFk-|3A@z_@S${sLr7xvIJ1tRFJ0gL`Wlsu2oa+Zlr!p)G@=mFhG5hMYBcZ>E7Jfx zlrMd?-yh2u!lzqo#*0_1b^0h4zdw$|Sg;i2r#^&*#YtE|qJ8Z^7u`TgSLT~psg2%o z_yp8jlf6AncB#Z~l20>nwlnnNGgRm984QdXQpew;(6=cQ7uB!N>S{O3k$vadWl)Sc zOWbw73Y)ns>!`747G3K@(BbegW?Uoj0^=)SEr6<;4c*5ZexJ%*RrHfcl$K(?U{pawI!W3^aj$hKv!DcUrh1Qdag@U_TK@q+n{%wm}D>4~QWRNRtwP=Zz?9 z=(1>HeqDx*HtnGv#vT!m%0!RLR1Jj-WM85XA-6p_bgh9J=l}h~<-&gai=Ig^BMF6p zD;~tJ@R=paAyIG$*7@e3M9Mx7)gE>bIK=t0jm}s<#2t!tEVK{W*SS4&J3dP;5kY!0 zi&@vdMk!rUyT(!sRzU1lVd$~yP~sYcD?$v{1HGLbY-zD@8ctAz#U-pSnsT(`*|)LJ zJ1I{lY-vC^yMjI%ve5A0cQ4 z7UB68SOZiCK$3TNr6CNf5{RKZu3tN#ib6T2{^=9|VxI(F5egr>N%SUagsg*5}VU;v#|`0Qz#D9gphi6 za~{n0$0lkG-e0c-P@KEAlU!1ItFkkY_w2Yq%Vj5cERE`YLSpU$GGaQFKOT)01pu!= z2*zfRZ%fAfpG4H$kXzK;q=+KDH~>prrY@kpN5-q3;ATIqTT%7a@*gdvM?8P5(T8n; z%E;5HX;(~^iV%$a|hJYZ1iCt_zwl-$PbRTWXT`l z?USj0#+%Y9PLB8LFfw$!?{93XgYR0B8P{aGrNqi^kWqewrK=u>^L4Tdn|+PM@do%i z!^sTAvYbi@sAfmWsH4KA=obWXiE^ko!;`UEaZP7Y=oo*PU9c_Dx?sDM&Kdi0u{&^4 zzZMjZ_dvU+1y;MbEE5yqNVen$LwI3UT&c{C46dKn>pII6B>^rV)a8WXsi{I5eCMg7 z@CIik&^9pCD3o~Os`o+#Rbqw{NYIOp;oXZ&1T{6QzT+JUl@zruqU&W{qr)8i6#N-1 zML!{;fx@7J@EG~>k>0DdeKg1jue0=`jl94fJG->*z#MO0M`8v{NPIE5&L-tkLPf4pq>i8?(@e?7_PxanUEj{d~yXCojo#Sr3Vx-nFW*Xz?XUCwdd z<7DnR<8p2RoLiF$_2HPLf?=uaKWvx#Yx+#a@Uk-Zlrz^V|0;}A@>&*6A(KLsb?y*0 zQn#K6TD5)yU58o1^yFc6OXTO?oCfEA@5i1#DY8_*fQxDLftnG-QW^q}0z^HKK#N(U zB}}%jq4f6toboV-{mW`{e?`fdtvI}iuAPlsP?10TvDXvCb%wGgya|d(N@{N9TjvW* zO9yB0>5DBsswT_+%Y!S3sf{0fY~hyqtz+Tl`9T;;lP!UUY^LoskiHp9F0+x^B` z_wnR#6bcMs=WjzIm5KrDt&C&0U@)Ib6Ky+ilKCy&c#$xcWXTQb0s5!d>$@FsQ)$Nn zUwh1MF0(HyurhAu?Ba20-_ryikj#CexAbIp=O=Nz0f+SkAf4#^rahtxwNJwQmQNPh z@dsN|pfk>HV&x$uNe0inw|1(BcS*q>1;1C?DLlbn`k19vX;%&Mf zk*o~rJ*>X-G^|R#U+L;2(1mArZ zj{i(n(JGtFkla7TLkSclbQ-45=%*WVK~(N*eE8V-{rFvOs!E0AnfZA5hZsI4eCE%S zQJKtQXyQVQ1o0#~^QCNJ(qFJLb0G^(mb7(aJve?RDa3>^N>5edY^q)*H)4^DQ|PpK zU%56$<==Tpr(yDPe*sUCZUz~83GBzANh;dqLFlbl1}MVCmfF3C-8*F2%_6PzjeKtU zWe?w->89bBqUxC{$X7j(&E^(tmBjD~9xCrd>P(0# zxc=)cTD(+BT-8#3t|(I{Y*p7yElL}KeG;F?S|woIp(Hd6Z;3}O?47dx5R^nJfUrm_ zD=CGc#@#{+iJEh7@!?eX!snBMDv~Q&PLH;<9@w@}pVgy1I5K679vU>$_Ud#q%VSbk z`Ptz^!)Pc(AK@xS)L;vX{1?U288sD3BvuaPgi(%>T1eywC#=P1gI(!VZ#<E>WwQlR+4FAr%s6p`j-RZlad5i4(#{RBBx$7Zj9yor2?&shX>^ zOHr_Pb@c*mCB}4TPvk`~g0Vysk{v#X}rdnb(G5 zWBWTlgJl4heK#ATU9;bn-+P|_PBKjpG3sYLcg)vNS}O0WST=16b{1vTZt$=EPmMQ5 z#5h)UgXJo}GhS9d&BoV}9^v{A+>7^WUAp3YPPPvrUZQ;7la>=HQR&G%{?;JE_sIMB zN46E^fSvg|S%jOj)8JQLTQ)x9ijm!(2+}GmG=*y2ACww&?sYox!%Ux0_roti3R$V8 z)t9tg*Ix{o9y*$Tz|9WTM9&oG)k!z;en-p4>*KveE~>skMFyj;pq-hzSrj@ih`2Qa z9~Ll^j927c16zWLl{+;f)SQ3}&4ae-V=rJNg)!bkuC9xUfUcvvK`!0qSoQo2SFwHuJLSTtoHVt<_z zL1Te&tfyx6wZ6{IcLe_NFu8}_%9A!0_EY2HV`i82q5r`l9~R!b8I+R?@zEwsqe%Mf zwpu&ZBl3kD4(%}c*qboq?dsu&dU(Y379cR1-{XTd%n|LC^_n7bw%6VxY6XvOMv^&WD(Ia2;;p6STAa0uEgBIOU} z@{42_B>!TXL%*>(J*+yk$383`b$=)>A@oi)aspPy%`rKr4_S?%xoII9ZmPqN zlyxoc=~B18AY;6>n49yv>-w9cUgsy=@PC9NhAl_G^}7tcV#(d_#Tys8_ClJ-^Y-52 zLsHZkKc(|AdrL-Dz#F>#3q@XM3e@AR{pvbYh$KAPCT7^Mqd4H5m4P*~s7w^iyp~1e-&F;6aFyC{G z4EQae!uZe*{s$*m52Z{PI>4WN#TGN7^MaFJZB@5erp0#ovpMnPPeq6l4LRi=G64@3 zD6yoCtq-$FT*q>71Kmxa%?k8_a+g^d2-$86BIY3*>T}Ph z8hKe+8zpZE7p<iUm)7)?;5A)Ls3tQo6&O%$ z;zo(PchTEq;*-EEjoU?ikvb<7dTg!vg%vuKNSx>Eom4FdZM|TL=OU;|Z+{-~jS2iX zvg%g)5&0A)kKuHv?ZJ-z;6DC;zIBuox0D^T;<*U9`79T$L3kKm3b7o4f~_Dq6S*qQ=F~<2y~}f({#xn#s#2kY!Ei zf8mh6ZNnXc6eQib_ZJgqS;??USSb`(PHHNR28ZmAn)07o0Ou0O5TF!-_l$!$fQ@#^gZWYwpx= zR1o8%@vJ&d^2d84qsUq|@wh0R8RFz=q_+sgECvfbndPa;ej`@vaO(C+^Iw0)53 zRIHUkTRb>YwoH{yPM@%xUKjHp03dvO!zk_z@4P;=0F2ps$;I?#Z(Kkq`1;1J+)-ZY z!@@k9>G|gfzeot`#!$3>xEV3^$r&x<5YVfEXHrEpO3{$PQnFGlp4*r+S2agxjm4rCGYdi<|Qu`1PU0} zK{#XX5cvk)w4%<4)Q+{(uC;zw`13dTCc0oe1+~L?Ky!{jAupQnh|`RVY+ykj4FaN~ z1Lm&%RI9XzY}5D#t`_Q^Em_XnhA~36leFV85T|Y3eKz)e1~5aO+YsY;c=2y@T({Mm zCS~Xu%bXFAxDU1@owvt1&2ua}PJzG@GryqVuYZz6V4)C8Ei5r1MC_V?L4gQB9>abs zTox=EI43+uG)rrcyj&GISD;={0gwVG^A`zzDO1{K*~)4&N>VCXxI~e+m6s)oQ6!}+ zhnw*urmZhm7Q6K+YfDC`Aa26W(nWXlPQr#fIdK$9Hl`=Byvu15Ksn_s zdk*Y~6gA;?`DH!aA^h~mS5hTtn|G87<7gN(M z(Com8z^ybnf=%|haa9kFH?G1LisB-b1Mx!>VHgbca2x0q@jCAg#<@Qj^7-(jaXfJ; z^tAo-HO#>m$NK1t;qS^It`d3Aud!kQDu)YPQ(;22C0*e zu?G9pQ3^`o!ANWgyW?S}6ke4yu{Qh>svOFG$Wzgh!{nIk^S9((1b=8qPy9pf@KC;6 z*}=$2j<_PzxjJw~6P8Zjd2}uN7sU6ujAE5h2D#?&hDn^ql9`C;WM4HTOge3`_T8R( zEQ31FB0SS~u@e?-y4Ht|E*>@DXplTm!@nfZCZWE!Xm}sNanawLDEeY7Y;1pXe^h$0 zHF#1~j#TRaxN#nbb79EaqpqJBH}-OEFBYIpjiQbZzz@W`&*;Yi;xcesd9m&lRY%Z> z|M!R^gNRJ+tr|fVw)d*4Ow24XsZfyH8*(t2#x+ZDh@d!_%o*?>1!j*wBpe$DO7x0T z6oFxJ3l(E8^94NwVTig)!5D*SC$d^D~c5lY;3Ka#t~}a>p$!$R>OOU9&0xtd|?@*1%VE{<#U{${_#Be z_r=SArKblY&Kf7Nv&yy2Ufg9%1+92J5pyMOiVuXKy@I#Lv8jc%j{Q%$9#-bazDs>(vA1pA4tvgB#7R{RMi`4E00^7phbUU`BIn{~P>t z`bB$GhKvLOV<%L~@OPEeoA4cVFG*W7g0sohb+1 zlt*#S-lDSN9qL5WjyLb$=GOP28%dpBXtthM*QRCG@c88QkZ!XIRRa9&c9J?9q+PWx zI8jvNFa7n87p9?>o|AF|gvir3&;@fGe?difu)zFIJAk}BwOky&SVF2)cdu(4Q zzx$g|LWQtR-KYBsMRojKy|{J})8hAOD8;kImdf371sUX_s4k61#VkjORl;m)M0^SN zH1uOVsEVS;;|uf*N3)3p?EO!lVa^X3k`LoH!e=jqo&M@xPwfG(c;6cIbm~UWdVZ7( z%NDA>97M6POWe_rRfZCk5<3&H<$5VA8JaS!t*UL297VDRVWTXotm*-$!S{ji4njt$ z!YOl4m?`$!*DjVp7N=tspSQaE5?y*(O}3J8-lxBZWEieerxE8g5-1+un}j3jZh%sR zV!8u4Fbq9*s}NNr@@T<1W{BIR=p5HhirmL#6x!bJ%QMXcNgnU6s%h$+X(~ZQ7>_Zt@9ZJYr3xS)MgQ!Jq>oqsW}BPPDIID|f1GdIcg2p5 z@N(0~iM7Kg|6dkBpQkYoHXdyZ^z}x~^yt}?N-$SnlK{1xhp1fs-*C0cd{^Dj69>Z$ z85dHn=5LNhJg6Yqsg&AeNZw}#MM8$W4LSiQ(bYl%0NMf)Hl+JB?5CUb)jH6FYN!j9 z&(1EaUD+|IjDCih4gVl5rtFEcUIybmlc5qD&X-I@fCd{gjs=CVnMk{d=MIH8mFQpN zhu3kk1L85+LO@i`=kHg%lyS!v9D$=lGRTWxD6jpmXQilv>am!-D;TmMrujx&MHi6} z>6lKea8tGRs@5!bREan$4B8>*!JknNWNAAag*n08BZ7}# zyqmkuCZje9pN_jdr~PDK`oe+SnAb5d{e5lcRuxN5(~U)e(7xe3&MVNriB7@vw_})+I2OAuHRPZ+*c_x+m)p>9oJ@Eo8FoS5sbGijmY`{b4^!ArUf9eMmEl zWz5}mR%FN+BLThGjpvBq&+pUBc5e6UYAO`dH2s_$T0e-qGVB=5Ubb7ZJwRt zqi8d^=RmU?qQkRs+7!LbAZcx55%tlPB)J|XtQvYlYGOdc*b4gC#Lf)_O2keXdjJ>j zm^xdBd!5*$B+B@IXt~h~3NDjA5j`l=mt<7yuZ#=qPldCZaUU(zNqe|Yzfs!W#Pvxt zNX=>*1z+&_l`J7(d zd{5FHGM=R8@b4HE zyVc(wX<_HaMc^y;%+@15NK@Q9-SNJVUIY*06$jU!m-&suAkxS?xP=<`rU>a(08C`7 zPu)LNJ8!1Wb2dg4jQdEE3&?r=N#>M+97YkFfiXwo_G(B9mD=lb}8+b4$Zp5U-i3?+o-a?3C+sHiCit@3_g!j zA{Pk-nr=ChYh?#gKr6_C7?27-II<;e2PS-Lb+*a9w6PY$VS938-+2qa;JTe`kgOx7 z6tV)hnlu$2}UUnY0NhfuMbSRNi>T15j_+!xD~Ri|sOvox(p{D>0+Ue;+WC z+@BHjX0(MjUcKs%e7&i3ciGNu6gvIeXEb&H3`Cd`|HBr?nX*@F!4A>>(bSR(y&}V3 zr{!eXt}IAS7gO{mvi5BIE=}l_gnShW%K{B3d4xRULu>l&+eRJG+O$B_@ijzkVQa)K zVK97wnpD6nYKh+gFqxwKu4E3Orj1YDmFS9-7kAbLRTy4Kw~=&3)Q(14kAneQvGyzBS$~UFgnPF?C)=$k!8j-@!CPbj zo;KYo-Bo_z&D1AWN@8{dS9*d6&Bev-o2C6A^9z zTS1qcIS~z!+`$7w_aSF*VMKeLs4y>?Xo@oK-GW!UlMLy>8JMEA7wuUCwqX0K5-0XQ zR8pn<=okj@XwL^OiFG<@6zSLt(e?aieLO7{woiQ(3Hhv0gTPWZ{6*$Afxyz$RH0F= zpW|f?CY`TheV7ZsmxlGcyT%m7RG9{pNZPY!=|*R#Skv5N2?A)bD7-nL+9kM=7oUv# zHSu!c(FE218ME{NOQgx>K3=FarvWJ=o%8`joVuFK+YTKAo7pk<%j4K|^)t)XkO#bfPGq2dU)*a)M4%dD!_TSNUu-RpU&*(%Dcgw4 zke_oeJ_}f;Us7{oy8PqR^^c(rq?CvsX#A00PSleA^Fq{J=UxwQ;?B!sA`hU_B){A^Lo{{U7pVkkA zwYxmhNtn({(0KSoA_DQf;FofF2#cjY1uiDJ6X4Jd)rsee#xrpPZvND%^?8$%7vhkxwm^s(LDfR@(k>v(13C;-p3LtDa3ekI zEQUf@8XZI5NQAC&&kyM=)m!R7BVP;1S{YAyp|`7E!ZAOe7YVq{eSS!Zp76LN8PC^d zkw5F7qr!@d&)=6&!dSD3HZP4UCR86uCFa%T;nI+a@3okTk^z#@iND0hClA&U%LuI0 z38W=v#r&F=$5ea6o#9}*@fci8R1ob{!(PEdRY6VdI(rh4 zj+&wL#6^V%+RqKPW5LXtQ|8I{Y=!A79QWG;F0Vl@zM9@h*aq+*^bKevhRw1BCg9dOT#I-~GJ(?b zj{jBeXMS#MFYGM}$WFXmOda8UY9+_A%oWRuh)aPbO7zrJ%IAJ>#*iL8QC{%B)V)kp zvZ%s&2ugtjcKG+v7pBl(ztUGeDC$jO`3AtyY3r^j$<{{fHWS;y4&l@6{cdTFRL*Hs z%XrZds?dWcckoldR^OT2)oO%?*ZSmQoJq#d_N)o$ya$GS@i^y^Sh zn*Z;|cR@+$>c0KugELg;5?JTNSh;6=0RUgR$HrCV+?!@HUQ`jJg2X&I8ctRTK0V%x zBa|%AXeS1G>P}Eq#pgDoYTOMRU${5HIqgaVGyQvmB1BP4Q4Q%+gM7%Brk))#yV7uXiKz3qwGUd#?w>6D#7uk`(5nmjl zid>!2BZGC+*RD!Z1$kLTCAG`^aJsL?qb{^K96SznLf{h-d%7i{GU>YdLfoC&9DH(M z>U&lk)iC{YGTTwuo(?%ify5N7@hdik_XE-l3eG}J19XmXdusVM9`~1D8^L9mfr8)$ z^cG}j6nxFRi>7Sk77ZmF#V z-Ov8%b+jgi*!(4O6iR||a_aI+;MXj?NnSCw)o7bpS4saqJ{7wBI6}lWKCAwfkn-_D zk>Mx5Th(LXjgAVzxN_!hxvvQ=KBs9@N_7tI50mzd6w9!-fc?XJp$% zg4#T`>!4`7Lp4AvKAPX~deL#P2E~%l;?#o!w?^G0Ii(v7K>!h>1v6jOml=X#P67u) z6TIhF(X}K)rCn>m_k!6v$$Jbq*)C0DVQ91xA?FVsxb=ynP5gx|8LXujpN0y_mVDS4 zzlZOz23Z$&2`=^>zVoqb0ZH@N9jI)1L?lrfaT}KbQFJ5#DZ@=3q4X;Bw9b(S0}Uh zWPd>6f7DQo`!dNMD8#&HUCR=+?5eXMRf2-?&yY@4o_CBtkLck~c+4HJaJP&O&$cZ> z4DLImkZDj_@m~l87E+_HdWQ#MxjqkykDEwl*fe-<>eff(GQ0hy zH73UY1A_N$4DQz`OKm6Y zrFrD-;CpPcd=6_{QV-yLY?KCmP!6sWkD>f?N8yW!!ZxG#t&s->CFP$elNoI{sWJR- zGPgA2Fj1CY3!XF8{Rlr1xC|MxXF1PuT>07Tp1N)4tze;5d(}tL03tv7POYma{;%Zp zb`*3ut}&w;xGeXV9bSwvA6EZaTdhC+oODB7cqm(1Z~t_sh>cXrv%!P9{~=kBEToi8 zr})?JqNw0f&&tzQ1@gb?Qzxa92r3H5j+=nXz^hxi5WjKy<(+O4_+1-wPTDJ;!I9b` z#$_%qbtBSNTJ}Yu3DzDPqWrvw5c)Ua zc|n@q9 zT3IY@6q|LbP5IpLD!d#ALNYY<*B&B~6Zl_}L(aqc5gq5S14#sg(S`y8%UYFA>Ak>L z4K%`r8F$26R_jJ+GK?{LBQ72?I>Dc`Ktq6?DVJn}F8Qr*_kI^@%2)>CNM=)QAuLf9 zHf^a_1_YjP>q&Xr-;iYZ7NZyctPSF74Z((45e0EO&N!(h$!jRhI;ch;|o-9 z>Dz)QyX)-zqVbmzARam3fCiEV)0@*UjVi!}gSaYb$n(}BAN7=a>(|m{v4MJOvEm?- zbn^y-nOc4TeQX_=YL7dEWcpQcgYKjgX^?A!&zygH+}V9&hNl$-W^G`{cf?hjn1(HBCA`OUj7Aub(SE*-WHT#w~R zxHrB&k5_AJr*;}vu$UPGB2bnul3tt$j?3n(rm!~YoF_N$fsB}o?!-Rxi=YADT09zF zPBv+5gE}21?tKV*Jwdn{p^&n~#VY}R$ayFJJ8$nPL&(G!o|Q#djUQFb)o6hib}hMw zOMWEc)mS!pn$Y;O@Hscc&6;w{6?ngVSap(>F6CjlpR%=Ft!k1E9EzYr#eL=H`!I%i z*WZ9h;;$C=Aq{2LW|3m;#@0mNJ=$ zP84feH*SU*NT#N=<`rXJ7CFlX)lW3f#caU39UE4@LHexWJG%dEUw9TFQb8J1_zzl0 z+vbd?=h4BmA`apWmkI1vpI{08xgl|uKN;7$JPG0`LR1m*3m ze-^=erMmwK$@`CoiIKeh|Csvfu%_QP>M^=g7%;k|yE_CW1Ox=>?#_|YAp=CDTa-?b zl#Y!UB`wV;3E3nS(0AY8b-ma7{BLg9>pi8m|(dviEab0WDg(~S?0z)?) zt!h6=((gJ@`MkT;EFWNL==)ZZx3{LWkBJB|CqhWxddCaj1YTTa;ljqXmRK)+sB)i1 zG#hMhJ+0w?RBe)yLs3071)6C3-IJ+q|58X!#7Sh7QW|CHDsnt19NDS zWGYepN#RuCht3@t{a`=)2htU(jpCg|CG z&97x=a^^@R9G62LAtkn5qT?SY?Nm}xjSYO}u4-9&g?-!2u?x(%W*MoGSFt=}|MA?G zJX2967xxbi7kf%sw4sw`DtiN@HR5-WEZ~&#l%$zQT;KJbwA#!K-5`daMjiCq$!zTO zHDSsg*TLJXN>50PkMVJ_uI^h@pD@S^cWn$DvgT@hbL%hap0l5TxKI4Bsf7L zEbzO%-F|E6;()PaKx)M zapDdhtBIJ4QD@Tz%xC40Kz0JENN38E3UsuR;)1B|+ZNt6Na~%M+6sT5lOb=JgYsxN z6TMGKBy zWrB=1tNE{qyQfrzH@co06I!u3y;UKP>2oD9OPM})$KzQ8x1PSVQk#HJL0Sh7UQ8tQ z-_m}4Ee0=0|4&Mo@c!V%M_v{2Ow42vHJ6l~gvG~Ipq}VAFf@l?>VR}nZ*?mzSN;bV zzEUc)xZM7E$aop9G<^~I7w4{Y8^8@nfpaAvr$8rj9$}W8S~kNaZGe(##*&Il5$Gwl zVe({pcg0*!d-`SU&Um{8jIivJrq|Im%Va4u;f`m%*yKx{Q@a%NX24EO6Mfd@?QC`80;O_2$>;ZEw)PA1)Aiyee}MNweLmp8LlFomh0@V{0!Vs{FzR z4}4q``erR4V!6o#+2cbU+nOEMNX!+Ci0?M=2Jj=*@p6fo#cu6QQWnK`?)e->1;Z+! z!6~oJI#!gzIx}qAo+MP^h34;3P{l28-#pJ4EFQ?fdF{Ac;X%8`Q+1E4yLXS*NnPPG zWzyruoiEeS`J~SAJ~%{Lct%x|4Mi`Dvtz@*vvjMVlmiI`fdU?PUO7g$z>OS{n?BFh zqcegmrp%b|eotgZyZ&z~kZ;=dF*Oe3AxT_Bgk>a_;}vd3l*9`Q&N^|;|71oFuqM88 zUusM_l%qpODP+9DzE1^~T8CtBNUkmiOZ;y}XxcgIuafz8kl`2lA`fp*3JLZ=dKHD@ zexLnwC#7X&G|{m->7kY%C2UmH614N_Kvo(h>sSc12&kwjVQy!xi#VUq3p3(!40eEsJ# zd%NKHv;0}9`qwD9tsv|>uJZ0fQsH?Rrs*dkX=XxRc+jnu>Rl^fkY1nYx~2A2ex7h> zKGlE1Eh1hPaWvMp3*PI_%Bd*d`k50~*stIzDdd^I%oQW*YTkRW0?(zOuwL=qS)qAr zlXh#l5_qDS7(#Y5;IYMoH}h(US%b+p7}~QE;oSqU$vUU;B(?XD@D?UP59hm&NI&v> zz?)*w?F1stx6dG6`^?mg>=9lY_Te)B*0e850K|@#j=sz=wUl{OXn%}4c8EW6-0+Tp zZ^>P2t%qlg`ZXQ85q^?CihFm>hZC#yU)ne58k|$xNK{t2i$l5Q+j%e5ECh z-jkF5={Bb}K|0ebD!D;?o1v+3$V?ZdEDsNU2@fZh|1&68Ks0em5iw}>-S@GVfK?JW z&{F}>?qreUxcaj0u%`Ap?3~5p?D+U)NF7&DorUJs#bw3I5RDk!85FWgC+{W=A6tvIpgqNDFp~&-x(bi499HTSBiw~Ip;6R+8{o*On9O?v)26H@Sk0q$=ffX z*HF54)8$Enmh?xlAud=P=-#apsMo&O*1Z~u#dz#uT@WW8u@Rbqz6s|g>oi9^{S4P7 zj^eD(Y!yYa(h=*`&S47fSa5^JG&DA)Xz2HLEnu?Be04=cQhgIi>PW`2GiPn5`O~3E zEjmjiK!%=>H)S>c!~_2FTHE2I?hUO3V9vC?TP9nJMxIcNQF5OvV2 z&Bx}nr-bU-MC$dQaBqH z-Xe(QY3Mmb2V?Z&}azQ+Yff?1&i5!}zw#4_$^7wa!N zU_GKQUtgwA(~8_DO7-fN2-{f_-LD>GM=*#tY&3iy0_gNQq+sRcyMom$CH)Aps@BVq|hi*>l-E>Y1QR|LQ*qtG9w}G?R#D;KPZ|Z=st4euTbJ3tU0t z^FPZ>$>@|bUWzjWdRE_way=D{ej6?j#Y}`eP*1L!YH1SM4;3%@q0PH@T>UI@jF*nJ z&Km0t{oTQp7y?&@muUN2EWKQk(oNbPDeW z$h8TTt7p)cwuI7LDnINZL#g3OZZk3lVRG)n9hVFVtY6828Ek*uYgrdP+WFi(_e{uy z#Nmui7!A=V(apf;K_%Y!oTsN+;CB^5egf~!_(Zpc?p@i+XI8=Cm)SGgY_43cba9m{ z{P6_bAi^Q>?6*fPL#xAyx}aGyr1}ReZt6djcj4z*EmD8pc1JfsI?viot}Cb`UW=Pc zpS?t?WTsknYTA%k3Uq#SKf5PD8BvoXAuHig+L=im_lZ~F^EUXmUQ-($&Ec`SrbqPg zmLi9s+uIZ?;q8$o`eD`e*6o58x2*LGpO0LRo^_=kOgsp1oin99f248=2KRH%tcm1M z!bHgBk$%EGad@&skCQG;*8i^-0PsPw=U+jEDOVwR=~(D7eWF%~0~U!MfyhzzlTs3r z@p+rMZ8ImE8+p*XqbKhXbIwVwLBfRAz{V5ugTyfRakAxM=@jNo+15BD?9a3E;ZW)oxD!$r) z1exGJFF>CR*gNNM1t75}P6+5e`ts7MsflcAnZ%AUti=fuO6RS^KKhn z5CWDrJxlgbdQBXGQSK>K`baP?2}IGms~1M;?AlPz;8qO@$r^b`ye-&a)^1z!lUWgW zzofWBwD?H17=K9mM;NgF>3w*sq;FgR%~F*qg+%)+CR)RQ$0ZY+S)We721(+(3`g#H z7B{p8wO6)2$8_%9QfDtQ3G2D9W=Abadj?~#5BfaMwvFQ&o|`_2I^6QHc1nXsqTK4! zcK)P=3lhzvBd}c1C(o7jUYLqaYL8td5-r|u=E{zRq%Y5T;G{0(xGs3 zcSIT354^Y1BmH-F%Kk&x#p^p~$3MY)KHpyYWy*n5+y)_;-tG zsd8Q?u)4nn_+@OD;LSXgb}c17UzRFvc$VXM66~KJx0Q`vi~o4YVt=nwGqxn$w@g-Y zs^bDrs9}e8#sg-5D>YBjf6bx2-Kp%bpdVlIcFCM=*GvH=bu`?#)XLAx*$&p=?kweODy%b!#TSBa)42vO*f7gJHPBM+wYnp!Y zyg6b0H**cF)+}$2d^J+D=plGy?UCp{$S(d|187s$lHosMzQ>QxV%)(aeE$ ze8VuUw&sX0)%O~VH~$^}?gwYio*F$YN12_9&u-Tbx15w^M{n+QOgzrNVF)fJl}+f4 zUI@0`hr5|)^iDvWwghB@)f+Zwg#$xQUHT4z5#v0kx?1G!Zzgh<5s=z?f}c(N8zHe7 zH7HkX0_F2XF?arMu5_6>L9MEkDDVSS%|Kx$N8VH}fVjdioIP4iT6JJ6|ADciYd*0& zv{+2eH}H=bQ%*%|RaW{cFr*)|7ID#(+xmonzcVDs`cpZg8)<881A}7X*3PhB5+8$v zgY5eR2)2t|jY(LVQ#8CTUb-}@XMJy2%LIY?whH!2Dxcq@#&SY_Exd}E9BK2eikjc1#WffRGP3*2AS{4W zWe$*=k}Xk}$ZIO9Af<$4Vzr_*8xk(c@c01JU^bO)$l=9;F=#C} z`g5qZhO5*ESGH(Jk1-Dyp`amAM_w*)Ts#GiPdYHh(=NqMDLSe6X5kR( z#GJ#HGnU6PNLyn2{>VgRsoOC6En*uZ>Vwt0Cia*y4@xN0e$i+B3zkg>4}X*i6A1lS z+L!A-A0+`9w~V(9%YgzcwLncHmg2M-=od8!4kI)GGza|ooGNJ#$gVS-GYSi=z1bztb%wntbd3HX`J(5R6&51JtEY-v)WU$TPi_X*p?nr^%D&Y zq{y94HNF3t(oV{F=v4s$at~(!%7%Np+zKfXgCm`098xf5t9as3HZT{47k?dV@9-86 zO@p4UABAFspe>?^yVZgfh@|L!*q-G_hY^Ktji$*~iiDF6T41{yXt7F^&q z&TkFUO})FmU#DI5NLrZW4mPx&qz=l`ugejkaw(>>62QcQ^jIC5V1IP@6No))kxRWy=JvX%9fI%@eKaIu&l&tqb{;Pg@j@IuG#_0#%fWZ5aC9?;t>11xfYF=7pO_7brC`=%X!?AVSR z4soA07<%Gt$(Jy|8_;7HIQyPD95+J-IXCa-Y`Il=LnR@dHUP&AHlI39x6U0#Io&hc zmgorJP^S@=<%n*_)2QgZVXZA??GuLU7s<%1#av^Ksa?(;@|X+&HuqmcSe3r1a?}Rd zLpQxeOq0+*r4#)x%dJsKf5AxM9+y$CN0YG!Q*~#{`Uk&T%cYdcBEsSe zqcaNUi0>CapZlHUdk=s;(ybmv1&}psh(-(z-2~8oJuggiI(ekl_g9e-lhbf}EP9#~ zvRaNAsLSZ(0PVaOD*C{PHj=$AaLL&JJ>6isb}`>;{Ql#i%c&eu9~$^&$XBcP5wl?L{4XBmf^-eaK&A40i5ccpnE#(cE_y7}8$Uzx zL#>niL{+7wl6m~1x z^vXwZBiBMnY+lpSBeGpz5JY)?p`b7o4?7b|C*EEGEXJv1&GyI!LtA26+6+2lKBh=z;{F*Hire`-52WS_-X2NrV zmUs%938{Q8n#&w)xunSRop3o3-AEo8kID|FKTA2p^-&OpV4-_tzwgVw3jp(e z`m)ttz+of`vkA|o<&oW_Id3qfSdtf0`Jo>z1-+xVDPDZ@+{P(pX!ZVuZzitF)$e#@ zFsPDZ2%i~kZ$rl1<;0aFy*b|FpB|dxP?8k-3lTsISV+coMr7sTbM$Fq>m(8s>~IXE z#?lqZ>@uA_2WLVCx1Y$Se{@POvYE+jIk-9rJ~DAW)jT!ITK3DzNzITFU4 zqEv|$#$8)-d!zRwGBe@UcCb3q>3I1_LG$!;1oZM9jg({ldNI*RGGb-+eS z<^lMjb#A7uTrW4Qb8rMdrVH;T?Dj?DNdMIJoo1W!ltS)AXMCAOI2Tr<&97ZnR6IRC zWzs%mPQi&AKd6q(Td9k+tkz@HtoQVpjqryY_@S(vRredr8kjZvU@$T7?(}P7?)}ui zXjz7iJFYR+21?E>kS;yM?XFsu`r?2~8W_BK$l8hEJ7_ zLy`Us1g4f@UM{UYcRD->wd+>=BJI75$$P}zEyme8^@#pJzoowJ08@PQdhgj%L4&rr zIiy&P;&?H(1Bg4KG$<5j#rHYjgDe8(RbVq6AlMAE{Y391{1eODCAq1e=0F*agG&3k zOqygMY`-Vj`mF-)N6?Z%!5sb+1r8;<0`Cuae&gHhv?4A-w-Z$LQFYEju|lKbTeO<% zstV6_N2Rtf?;%<+9z(2+T&`77p1ae=p1o)0;g|2XW}hv|*d9w$!5p&x64U2}<){R@ z=rpX>ss#||5^j3$G7VS|-2J5UTW_-{+2C1IRAZ+NLn0su zsf_VEB3S%W7ME$i`cfZo@?~aJw|?8q*QlzWfG?rhz30Z(hn~gePp+4c1Jcq>pOuS# zoaGxAbG|E>UX`_D&3SZ*fmQ!%4L!-d`j16^61a(Mp*GpgsJacj!C<}!@%kcvvohrvcGf*1`*(x!u*AK2dzC0?o%nmu+M?wNWOKU`(}#LhIaE|uc&|6& zPWzedcC^>GH_cpL7d7NMd#%)LQAC{ON^ZDSdOVORx~0!-b$|PNIIi$|Qgwq{;sVsU66r0UDso%tOidz;&x`;$hoCd^j z9d^2m3GFKYN33=&0sY&uP;6(ggp6Z4HWL%LM9)6{>K!zwQ<0fOZ+E_LE%TDLMFDEjqVXHmIH^ zZvIHui!?r<1r|FdFB~f~3zeg9NdC=D%PS!+o_XPj^WLc}$qpUXf$@c|V>hRZq<{a0 zb@r@=>Ur?wV=OD70hT+a%WUd5FDs4I-*Z#hd3|qKzlc=*sPJ}n_m_+gwkv-^(G#pz zar1pqI+fvuP1iwjy6REUWd%u48qr-XHv{m3RzorWnMfWU4Bx6G@CkCmRswdF2Yj00 ziZjMAf^OLW@%Cxo`aGiKPZo+DYyqdG9ESRJ1z6Imnr>a}3Z<|dfE59&O8C|EB++M^ z3ZudeU;1hyN?E?wq;f7nkRc@2q&)3LnDa{~5zV3zc==K>m_VS$}Ewo9rJrvc!I68Pq0 ziO(K*rj!qK_sJ4-(KDyFQC08^jk?fHWQI~KK&+im&h$PKXt}}33d4?#ZTfAB50mnL zbm0VU-24&K?hyg{BJmZrw$Dl2abyD){@6x%(;!k~Pj*f^&>s?i>X4fu_Xu-L%8Uq;x-fQF0ohAhCGS)^cn- zvVg=ZC&|Fdz-OL5Hfz?AjE8tu+&ykat>><9v`ix#!#}6MSJ4~bcZY7`WEs-ViW?XG;|wBo8KVvd?89&y ze(Ei3JdRV_r-Pu<4CI97kkS=*wm(q9~DY4lSi~)zp$bQM;n@*zV z2#Uv|#dtMIcP{?cNcTCED1vUF_;=&i`p!7uAS(uP|K8}97-ENMCswscc%mgsK0-1a z(@5+p_H+1&`-(O%LoF;bg=c6D1LNghuS3b#F$b>~pG~+`;a^xv#@K}k*pwn3#f+qj zJuh&{rTeF}c+g7l?>8YTx6pKzr|MT*)d!`8N}H=)r5Dp%_uk=nL-*&aY$amIx{k&# z%K2~lFaEo07CDSVupR|RbOzxMK3?Y=@-$&n* zquf(jU26MT2m^#D0cJ_btR6-pLWK^c(j{yDq%#|xaUF8-sewC$3`vBLUYC;`qDb1u zRL>^nlLN48__}lkC8r_@?Y8$HM=Uwu$~=kO#x#)8`>|&O%AT*BzCI6H%ZLe<5z?^K z=wzlZzd^~E1O$dM7YP}iUU|7!qwiaw%5(}l&>6n^EL{c_y~VD4RZl^N?}F>YWNCN? zKI@gg-O@YYQNP0pol6d5zEZAzGw+jJv!$uP0N+zLvP$eo=Q36YVi=F6dU#cZ(ie69 z{o8JZ5P_!sKh$#;R$G;cJu5E0YX>IRE<6`E(qDdTaWQZ7OnA%XAI=0mF}T~JO#eFL zn%rNKX8Yz!UQ#*;F`1pu16LSSAf^}&#koBJwgN=zV;Ry*PD0D9W}ipP;XWloZ~&}c zbNlskeUU{&ct7c2f#e$y~O|cpcfW`f5{Rg31Q|ec_QY@Dx3dS??W99RwN64)PWl1QB_@+>9Rk?a&1OAk!8bu! zxMttiJ875ME9k3BT_1R^aVO%h(n&rq3;B(JXLcakC>mZZTq_LB=lnK(e7YCI3jI{c z#AGN7c7EH|E;B&^QR;Du&Zp+rict}A(+LK<&^wE2@ zX5XG*q4dL=;iJ)3a(D%VSyjQ6FsU{iMe6iD{J6UAWLPXxch@cFX%Bm+aM7@=ID_af z!z_byb%>Rf6O*FK$T7%zzK)H!h(=P(pLXac)pO4W$Tu$a1HyrW9WfgD?kYe{`f|JK zkg4)c1fvCYIfy7U)-Hp0A+P!w715@VOG&r3fo(e(HN4ftLj-v>s)Z2Ox_JlB^LXz5 zuy6by*hof(uB`<$>ckLZQQV3A6raiPjWF9C#6T7uRpEtE`NtT-hd!`pC@Jcg2q0g`J=Q!DZBX%}}MacG+ z+PL?R{`997IrLFuDDz!#z$4%poh>C*L+wd5$~ll1hdOuno*hR$af?xvxM16%2_i#c zHz8S8!8h=Z^!&-|g@ljXautoiAhO~g3RrR8=g(U2Uf?`&@t}@$rZFTD!FoTN05|=q zua-lcF%#CXq{17g_TMJ@s7oDM@EI+X&V7Lisek91<2vfqg3NCW zeD{m%dg{6l9k}!#QJ1iV=Z#~{f16MJ@7Uk7YoB3FIr}v~HY;7)!N}O}_$A$QAA`7R zItdvq)%-p#L|1@g2BG|MF1d`JE}N~>;a zh8JuBfqbKP@v$j4g=W<7;qVw?EE_qaSihx>@=8n6v?p2)LWnhso~k*4h|#N0n$&5r zno!!8o2RLx4KjXKWkeg8-kc~r)PFv#+&wRP>g1tbF|hDT z#Fc!vyw&zNr4EDXE}v{^gF=*(THv<16JMMd@>{RIH5^}zZ>tSHF?m4H+{(f@4nmF7 zdq2hB^+Vd)W>C)94)`BUt%(0nD33Sd?ya=$yRU_Gcle3f6~5Bvo6i#?Qz>vz_Yf2G zu9Te`^58b&p|%un{QEnvxehPPnW0vG_4{lkxlV+CC~3g-d#|XPrNrVt9D_F8gp)4( zBmp04k1))Xp$^Bu!l8Km;tAk7Q?;S3vV+M}L zXI?lD*ZR8aDGqCBh)q>12EaZfo$e3Hwi2IT6MNaj7Tuqhrj%dPSRL7;czm}N z!tE-HDW5Z(-kUuWIn$TzJ;ukKbYHH#{zQ%_S4j$#Op!(-7ymGs$DtQF?KbmeQe-V$ zG#l1xyts)9P1h#!H*;)Y=KV$>$H}MvR|}xeD&=GC^*Z3ijL*CU<<@mc$3}2NWO!|d za2)~J8qxav#uWZ@+HZlwLQ|7f_msQNxOpQy{!V}0+Vg5>mJkatsb0B99x*3`X)B6& z9lzQBdR4}^F@_u$8C%lpI?DZ4Cb!3#p^rY>l>>KN7M%l<@kkuZ-rDA)6&O;g z)J~NOYZB~4bN`E*FBC*-k&H)qN0Dp|p*ubyrD8)Cq^ z4N`R_jGdiNaMtmmp$dV$4tFg7?XD^PR`aPjQJ}0LY%VKBEx-xyomdUz<@G*%*49VfRh<7;htrsTI zL<)5FMZ}kdXd~gD9q)T(wDBU93dAWQr$^739yURk3&iCzZ-nwZceGIhW4oIh8=S|{ z(govguoXI&;wna$&P#`2nVJ)rRiki_)?$ki$5PrFf*fWaNvFbeG0>RfPR}^BlUqw0 zu%Tn%yN!b@?j8{>FXg8&yXqT+<+guMqPFru)yDa;i2j_5bAfL?DdqGTo6C+(#QpLS z3tKZNe?d{^B>L;S1|Ot;^gk@mpFa;cg!k_pi>UwAD)hU<9t{){IG59rV8XtAm`azbcb{NOYIl0GC;=~S)J>yLJE$3++fz)N#x+o*K`g^w7ZNOgLy(wgQMkBJ zO#A5=NDLQh`I||!ahdez#u;NByQ#eK!-2q3lk_5%Wv{78#W#({RM}kzGWFxI%ARP} zsitapNNjazP=@l)+Rs@^PCEy~md}B5gd+1hrMM2^xwt5os!%y}U`=9UH+!*z6`jw@ zr_cl{>B-x?*s&i*8ygW}OU3F{1}7oMRk2MzublpcT(>d?yID_BT)coQ1PJ)2?<+ag z(5G_I+99;C6jViiEQ^hwSOwSHeta=%>=W-G!bU}=sW@I3Gvt#l&8&@dc(F}Ck_wv9 zQSg9KQWtL?eX;$1Bv2J-o<7|TWNNiqXI4#ULJi`v(UHbTFytp_z_N1 zmw2aZty=v(dG1Jo)L&xEXhuY24J!zz`7bzbn6kvY4$x70+IhUducALmghkF3+tTQ& zIR{le=amJ$K@QsY1ZLx4+SnFbks|(OjvK^9TT%2 z=W!@kmWu%qT#3GyGIM9;8!2>7;2elriOn8Wi8d3{e;BM35#_R{iIooNRPD}9j4}s8 zx$g~HFV0djI|Ttx+xC_!MV(V*{?uoNu9)dx6bi zL*j%Ay^OoyC+iY&S-2h*#*u^3b*NP%Jz;J|{@W=i8pNz8)5nZg042%&0m7v|uTCs9 zCO*=qbFJ#Gz0t#SWFbW`koMypz<%FY604xXhW-}l63mEv(H`EBjHl>~8VM&1_!o{l zHQgBv*ng*Lh*il(ebH7WNi8$Vo1Pdz}o zqr)dQdspwC8^j=lNpol^gD02K!$6*8(ko+vNrHR;9e|!~fvhpAsv5^@%6X_wt~4 zof#JCxh{52CqE6SCF?_GgHHIq3WlHlk$P|mJ;?VnuvaEbLalql4yO3e`t{-Ag^k^Q zRhw@?rSBm8uztgX4Efp=vuR=_K)>W2^%-9dPV&lM~)_(5br4hZe}MkV{5QmCTsm3pZ*Xe;MDp0 z8<|2)nNjEvl!r+nsuHVa`R7Y7ugrsYuIY*kw4;5s94a>iy?MW#EuR4*`yL~kaUaz9 z%cVuGd!*y1N%NmRI)H29&^vIH7>Uj846htF)87%4*WCFk9Hbpqh9RW!isa&~z_42( zqJTFkKOGi5Dk_G{pL5si+A+WK7>?1UHo+i6yXF-lRP;YVMRbamzP^H}%AwY6lg z2RdT`HH{oYNzD|0qdSG;hP_tGF*+|UozA@_kJA?VC}J1KhOZVnD9fX5`w@>Gzw#8* zv6eC5^ak}n6sGX{t8HQc?5B8-m|krpa~Lkqrq89jc2GcPg^5w^VAwNgk=nC<2 z>J^k=uO{yedr5tb)1v3mgZF)o`5UK$Jke!0h@u3eytu#Bmp@xAWxZHSjE(qOb%1SN znEePpUHV-J3Zj;D&sBBR!bW^S6q@rqB)RfP zZ3Ul^&S>8U-qD*f8M?Zk*dZz;_zTVFI5HaPk&0TO&h5B5(}5=U&wL|KDKDRSO5aw> zGV}bW#eF8F44n-)ck@#v|E4{Qka&3yM3-!rk5aNwA0YIk)-OtRo!}nAcGG5JhO7u` z_3Fr?e&RnQ*2dA2XHE5U>K#&~6;c5g1J$J4Bw`nH1 ziaK@Qm`MJ;iwX+wY5q_TTQ(gzahJ;d(h@t0jDWPe$2|X3yVTtXz4%rqpt7z#piVUS zEL=PEr=m&nVYR`02-YEWBmb5>g}+7G^gydMMx841bCcMN2clD>WZAwa=jcar@1G=2W(mk_YEoGE?@*~_^H!7b z`>+ChCRzU3_avD{>6M<|F`3f(6<}O^Qj-(oR|YTA=&rnJ6vCjg{_O{WA3XH)rKK1- zT$qEuVK@6@qfG(XmVMs;JDjX z<>C3d9oCq(^+KoMmjKMh+uH55^!%E5_mZc{x7m?jIM$72p^&bT$>J6@yPgFq7IPrR zdB+Ww#eF>v5fi*{9K6^Iv@u=&4^1dZaB?V@J+PQ{6?n6gdJ*#*FO^0jgjgnrZ5F?W zKp_Ky1;^;ZhSBxVL*oM#rI|srSp?(vz?u>40e%b-%TsyLTk@X-czQ{v+?fNzpl&ql zT>RqNWb6DcyD8XWjEbe-%ITcnp3WyhTl5>rM-O8V@-*=_Qg|JvB?ayJP_nG|eE;iI z+2PXdzCqR?jSRrE5ne{!wLW19@4@t;A%IU9ook14n1wapf8=SRRHU9kYv`xmyFky` zz{T$3KlLdcp4MJI1wXtnI_fF&|I{diGenJRpC{UCBpu2;r(7)m+N?`Rl^^?wh-KPMGY{4 ze?FcgqiQiFmYrm+3otCjAv|a7rhqRJC{z$aJObCUbLUshQ_Okh*>lW25F{_6fQ3^) zD3K)cNAJ;`jWE{clGodUIkp{2D;aI7-d9LjYyr9#VGSB?bJ&4SyG7`Mrw)XSaFK{< zJDK9&5Y)LUaNX`LAjB(eX^1YSDyE8(_03$Kp@gA?mXK1_M?eWvV0k`KjkZjtwaizEJ%=yMc*+#B3hQfIS)w5a>N2 zH-zn%^NJr1Xa4xE#tV4e&Nclh{~ZEf;A85I!!Y2Kh$8$p?}vCQz>8(z`{rXgePO~+ zx*G3_Cy_Bf|GQm@jd_9kaU(o0`0h>}w}y2-X%Zw3%k1zG_=aJ`{kI9w3rbV03_>N@ z#ka+}r=?4?#zIDi;4~!wq5IT4Xve25R+D%(Rt`!_o$4e(k1!FDS&((5c|>vOSolJn z2yRWMy0S2ZYFXiW%pQgS`4SBnlx|ZQ9E-*=&^v3Usbc91riZBtmN>_v>mTuLpR~BY zb>D6~8ku{f>gS};G>Uen?iFii@Ei^JNU{;cYh^@wq+rz+mGoWY8l&K6k;`6Q?bN$c zvh#k0c;-LoTl*eY2w_S~Oj{r-3?#82u!R#2KZfxo_-PR3DNI{(CELHy&nYM1lR1zj zvcu^GS>b?eg4YE-}e(;92815eQrX`1`ABf{#Ajo0J)LG`|PC(*;k9X_6=Xv^DTxQke(mcP%kBz3#08* z3w;qMHZ+-8Fl1)LHc$oF19MvMO=V_P*=jOZ;OXlvf&xC{^&J;57)aHt7P-J!(xU4i zMba2je|qGTm=F)Z?bA#(h)=8 z!XI345=tS?k5jxO^Uy#&Gp3+kTE0F$jd|oG=nScJ(`49Px zn3tGZeS-kdal$-${aR9VaOm=o5j0RrKhht#WmcLt5=xgGzx=F~l-0ETDSJh0f~XQs zT&q%op@)77f@xTUO|f`>xy!K86B^2KvIX=FB)!~TKSf!{<0xfREy)~60*$cbKhS-Wk~pV(n86~63c zS8W|NQXTPhlo_F&6cwBC`0w_&cvk;~F;wpe3W;wIWygCw$L*7$v~<`YV-l&ro*^x4 zYGc8!_n4pJR@&bY>}dGRQoK%<{})rm;s%m1i&of4`K#Yo+D^cJm)nK*npj++bd4PK z&XTm}{I`gbEsi6`9MC$ypH2w5P2m|JW8$G!PC`2RUBV5;pUr89eWq=|3lMNMm70|ZMqrV-61); zqz6g}0@683x*1(6HAiG%gIQFmMCPFjrSu|(YG@pw9c#dN`fLlLe7AwD* zVn@Q_j1|Uo`M9S3$)B!T^mIo7DXrD5Fk9G6m$miqd6hBw8bkqR?fhNN~v3F?JR3g{`f$5Pi!kMibO6ju<hg)6LOZgW0L z8YGolB5;!>P8<>8h@E(9Yd7bg?r8Zk?^pDj3jI$DD45_I&sAV&-%CFf!4Y6Oe{tVN zUXD2%VN%#U4Xk;g4K zc>1(>jETW|?{<~7Eje+n@Dh4%G2P0%7bo@$f_WCK5W1?p$p!6Qa_tP=aF-%j*hx9yj`s>qm7hf+f`!Y7tlFw(P z-#$6gJV!tNp<~OC5Xxqa24>glMz6f*sC`XQ>=+V>9^Rh=I*R5?^59$9{ z{R|YQ$VB}nO`vysAHPi>Kqb~^9j4?$dBs%DY&%f|JSvV(7z_A?Ra;c>l`FLkkwDtW zQBD(<#5R4)5Rxsk_qaqnuLHX)_*}Q1CH4GUYs>w|nU!@nv+MF>%kP7f)iCq(g|LRc zRUiBuZuk&R3&F! zZ0@Cxezn6J-bU7cL8d`vx~8Vy<%dC&0TcC)ry0QqLL#HtC|-Xs7_BTr(d)Pt98qv} zNhKJ;Q%VhTd`T?jXdbI3YcmhRN?f~YLXS(?(QS;q>YeO$0CyaK=^s!aCS(*Phqzy^ zI&Q(rhonrYXlUlXz~Sm!T!B;6dZC#|+oU^m%PU2ns)G!UAA_i1t-Ygez!lr{>qU`D zsTbNU1zF5Aw#qszd?E1&{VYFhZ`S%*(R{zp%gx?mlvYS!ei@HFOtEA?b9AhzN%PKt za}ez{U=>d~;ao*#EwD*+q9ZV3w33boC+QMhAA23m#Cltus$^-PwIIBIsynt87o>qI z1aY5&+*lvYw|i$%Q$KvTN$-;TjMTU2b? zoD6Xdka2lh_PJS6F<&!)R)SvSVd5Zkq}I}*l!FQ7M&U7J z$Gz;1Q8tV;96llQBEC0@2TIahkiM}OUOmWT^55E^`s-E-w@wruQ(&fN(OTfzlr`uV zq{a&fum{>lPq~3|1+eH}-P>L`E!zTJlDk(89SfjGuOZN62_i$=K}OtE6JA@fa_xOp>d1 zy+W3gYvZ#&!iD=Wi-0Fqt+KGq%n1`9`FVDLIkbqzTONfzqrs^+sjWhZZ{sghgE7=^CQ;%+2HNr5|d8B?+eQ;JP*2{~rTxOjW4 zCUPBsccZjK^Vrq-Vf)8~<_-PF&dV5$dn%#Vd5g1;Zx0Ky7CZJts{7}ok$%!w6Syqc z5UuA}k;}&K-*>%Ha#GMa%tDXEyn0KU)|KPM>jsaE%{A~#;lX?Hp zp7QU&L7C6Ad+fD{K3t0VO_PIA2qRn;HKfgjt2>}@fO;m_q8ch|&^`BTRW;;UXTOZ? zJT97IMroDTJG97G|MFshe`s&NYa3)-WAg-j7;mNj)uE|bxm=i__6XA18M|X$U;Xc8 zit`L_v1JB^Q_n!R*s7TA0>;#!L(mE^3r8~kJpRYZKV74GjUPGv9U`Er zeh3GEr4lo@Z^^cXck*uLL<|v9N4wu)((Iz6Lb+WMy36%O2I?+$mcfEN6u%hRTxJ7F zMARX_@so!+p6^_;08eqZpHJ!OC6?c0752*Z{VvORae@l5PGlFm6=E($qb~X8a%vq> zFD+K1WyX91HJEcsKH4O&`{I;i&vM@GzI#nalhyT|CoJ$hdD8j-vv0q}8NX&!< z=qe^~QD{RYLn&3!ho8y}ntbaN4E@~Ye50-gdywB=r2?i<@pOTiylyPP&c-oOKzb|~ zYO1?A;Gt}W8plBAyGZehZ3AJaAfpJ$JThx(lNcUk+HG1|OWd6#-_UYL%5zB~zjnh$ z2RY4(RBP`=N|^Cp{Tp0ECaz4rZT4Hwg6KsnDr2jZFZEwat)^}J{-pWPHa2UJv%E*Q zpFAcDVDtOrVAQ;7(1$`U(BU|id;V??isrpgcSa(_xA0Nv5297 z-p31k?qbG4|XC-Nc zMxi3te|)amfCkIwMf2UA*NB<^Yd;5NxJY629FhGyz#~ax;TvQ!9PGx2OmANTbMdU& zH=`}2{eTp2`4NY4!RL8kKqYi?VexXS)dBCe2h=En<{|`dX4OQ0{tbLyDL{(S^r>9^ zZr*bni7+D5B{~esNcMYFX>R^@JS%L+3e?}0hep1oA{ZMmaoJ_(ZSL848~9P+;xZ&8 z`I`3FH71Cp$18w?8J~C;$r^cWi4mYicZRw8>FQ+PKv_NyXy$2QY7{ZC)km50qjIyFdt)C?=8*{2j^7w zmkQAm#t#|LIK(vAm2*E+v!SZN4+j@#__Jz5zOwI?+kA^|C_Z}ov-KSGGru=5Z#Em| zHMN*FZC5BomiM>0CsxT-HG6 zGLCcCs+BE6ch(>Qr~m2t9(sTWKMTVUGD>0mO4+&hu!&=Z3Y(ofl`lrN`b(2e>kK|A=Mf>Y$Kw@NLf(N~z0if3;&mmJ#EyZl*&gEizWN3(Q=*t$j zwd64*cgW9d9$raYQ3leTYYEdk#RvXaH26w2nV)1Zows09Q4MMW2W~_72~AoJ`6(Ym z9MgX1&98SmB)@(IuR~l9ah@VgMLz`HjtUK1kbuSPRv;#a5+R=rQM97X+`_OH@%1-x z145l3#G&>ue)U%b+_;%zd(2$dM0)$P+sq*#{**)Tft%X+LY}Ye)usQg3BsB1cz+~y zFe1WQI|*Iu@dS3oEg>Hl4#cmg`MFdvt^aH~Fd0xme>H1*G=4j<{NrY9>-GL{V`m=~ zSnfzZVV#atXxlcs@I@gN8v8n9pk+9qPETE?~s(VuC`KZLT<}X9sBBFS4F}+s% z?8n~l)Ad8~qLsVZ(IR7GFV@TCgdrH~vV22r(BK(WWtr#CgtpL-O9 zG?T>9U4v=5i+|#ni7vexPoR2WyCEY~Bzd?Tey$jMt_R*sF6?_stgMtK7~31Ge2@QuxDH7BzqVEX+nW z19Fg;t`vPg%KwPJBn_Hmb2q~>`9A!kr)lQFg*%UrcN#2Tg<;zTy_`;0jqnug$QNKRE+ZY=|O4ZJN#TZ)nzRF_H zz0{$tnBa}B0?Z9M+(FK(gLe5>&>-Kb&@g#SMNSqZ3!<3z>;aaO-$mO?CsWZBp-x~# z{MB1IGuXbvpcpX-FHH~mCxhMcVSwZ))B}ZBGi5gO{VXq%oz4ZVg&qJ(FD%Fz$%ThO z2^Ao;5ZEQfB>NK`*2~ytn<<7Nwo)}t$MEKOTdVQjtdkGql4=k$B!L1b;eiW|S@seL z0ONtY6ALy9CWwj~tg7MX*PG0I0j1yuya{GGK zb_?V%ohTlZW$Xs5L+A3q+z_7>YvP6E1@s3&A4Fk7t&ox=86qq7^8tWO%#xwo*Pu~b zpYyC4;(V*(sBzjesTb{;;+c!GzZI}~8G0FtFpWD?BIPD!1$afu$yf=(l!;5WHtv$c zT`dEJV(i{dF&6zsbl!?aG}$+xnYTA^)rF#1QGXOE5|OO&lB{u82KZIJ?-`wKw#Jwq z%A)J@x3fC==i09;EukhBFe*x1$0Ov9)%f7MjUax?4bgKAD%pzEyDgJNqG0Qy z!=FjT9ZHIgO7LM317YP-hB9M75z5(#4xA&)ilxWJCBQ6jn|k zYaHNK6st+gxF+>pjg|@t*h|$5soWIq%|$X#2y;%oMEQ&zHk~CeV(Ya`=x2C!H7_Wg z)iW=$qU-+}(Vo^i#+>%bjcXgYX(i3^8t)Nl2_P*Wu2tC`?B5@{{2V%B_4>Q?)Axty zX$gB^eY259X+bt$nj|}cEaH*k`rA;11DJz)doJ;uJ_3>ZMPyDAsCX8KggQ$lDL`#5 zVGwj;?-ZTsXcdh5uEwrHE7;h(vZS3CW@LNq=>D*WftBi}=dq+g^x5oSf28l+R1K4Husz)R0a$K$z zy4CRSWaucl@st)LsK^=s^-ur?&oA6{~5Q1ETS>lc;q*vK|=SH*iW6a z_M^1l<_zPD67LaMtfDcFpSnZh7sOcmSDiz0ur_Q1$EV7C)Ncsv6g}}j3|vuP+7RPYFOke7`C6Po zhYOdh#4^PLfve81DZ)Htmx0@}wjWK;s(GH*oeq z4gRrw@k!>1?znDzX1bRdly{MEWUS76O_8#J#%Too3y=;Y9=p~2gPHTM z^(?Qk_gjhmAat}Gw0N?|H3@V0^KW%G_QZ?p>6VF2$v~kMe#q2ju+Ztz>E3zkTg?RF z8;;P%UgF=SLgMSHK>%=8E8q~rtjun|mJed$9%)pWOV(IZjr8(l&x&NL^YgD>fQVgL zbe2Hs)?k1vis&0B2m8(ShURDcNAp-)#|UR?r)oE;l7Nx}J2bdj#gc8qHH9!pslF18*|XJ!hBDn?bukPy z3z!k(WldAD^kY0>JWW#qKz5CzZlxvN*|TB>wzme8TgmdzF&p!uaT*`ofETRKK^+^L z4!sEiryyxeFik&9?32dAj`pL=j4eS(<+(DKGc73jZ!fE$Q1pMFT69ZVJ@q@L7XvWB&HDgamKJyqaI&v#$?5y zoYHC(ZW1*K{MJ%2S%MnXBKaUZEKJqFxlPgmSqm>ZX4VIbxVz+!JX%hBpXDR*hF^c( z&L_+AmN_%Wt5T3w+UzEX9y%Np!7%}EJ3KBE$0%3;kYN&w|DDMQcfG5BzW8V4kL`gY zn~~u%g1|&{*FLIddOFZ!DQ6AVM-A#hfU?i$9v5_KTNLqhoM7=m5o_C_ENvoPjdh+# zG5ZhaeQk^q>9ecS7Bj_Co>Mlmh3197&b|yVwiVV+($39**M(>4o_yY!6_l712ec?n z7L37PiT-IGyFG|DfSf1Al{4V*R49?B*9zczan6Lf$J0*Kk%A%C&o_SyanPu|bwodD z@-uzPVz~8nQcbb|!AKWT?;h!p@pynTXVgXfB1+yr`f{GIgJqB*&Qsv9b?GUvUR#~= zmFE0a?Y-dqM+OQQT1a*!sF>sp!|L}R)3?IGG7r1nVoQpiBB{GHx-QOe3cO&<7S)<* zln`JVSTeW4qh2)AeZkNM@!gls$}5d3vYVN!K!~FH4;>%fF=2|f()Qa0?|64dMz;6M zq90;=)C^$(nxBri)mPv39!UB_x3n~kLq*Yzc(r1ZFg(F2w#?&#Q=jbX&U>6NOT{-~ zrODc2C}XyVt*+#xVWEQdNim^wiDsbC6M1G$fLQNFN?O}1Baa3KAxG6h{pL(+( z51{ol8uApIIq)})22V~cOiY-drHe0P6<#Sa2>P-jpP!}50N^}KIl!Juk?U=y z5g8W8{>6Id?a(OR7kAa32&7^A_uuuj?4}efk_JBRX-Ezl6{8#r-^vrk@-7U1TXLU> zkPfI>y0IP~V(}ah#vcYFZ6PeA5xu>3t5cHnd(vG6*HE(t$8_BCZD7PNRx`VzVk@fG z=DK0+c=WK_e~ew1BQ`hNxAJk6bZAu~?w!!s*|w>DT0!VJ>2??4El5vV4`-myq{jm> zzTsp>D2_{=LDcK>B`E38-ISB|t}^JxDx8tT_>TrP%J1KR^jetoyZy`xhM@Fp_4NmF z!%xWfEW%mmv*9avnu0Cn+sQJWP7WveysXng6jca>*3BPg9D=9A#OTBLuz5R$VIt*;#+vIt`|*CUNLzI-B|P+n&5lpDe=KLap|qJ24%$$rVY-)X;`bC@B~sw$M!}M!PI@7Q zg8NcBgS7fC3+R+D1Xit^RThC)s`;z+1zF9dt$2%E7cQ652UzKg7LLNFMj;U=nZE?d zjp{*LpPSELQ-#>OF~Ja+Hcz&7E;sjN(a0~MioK2q-rF(u@cIcrqb^eT581T`61etW zjLrZ7bS(l`Ex70%Y3rYX@U2F*lf&(oW~X^BZ@nAfQ!u;A<6#@kiL32Hr$(anphVYy zn+Uoyarznos6reC2#&L9y4PB3cP7!ISkv<;n2eymLZ6~0u5Qz?J9uh0XceC7qM!UM zLI@w~p`AkL@{^gY?asKa!Unc3UV&_YfgsXat|$$=*L^n;m2mylf)Aq|>th8OQI6-W zQkY$_Ll;eItG2NIqtxG#Nym!5v)W}v{m>hS6dzA<6R9be8o56Rxg@X2 z`moSmyy8x*@=yEws*+hHeF4dz5~ki^6BG1pwk#B{=~c%|-)x|>fXU|@szd`j={2Ou z;sV|#y~xb^Ul2Iy8V5zERw%^2ZQ!0^vS**7&etfcL?YP^t^7dQ+KEJS_o92Z&Lj<6 zi3mxRVUYz@Gs}EPXKX8b|8DFL)087yTlrMbrj0*G`i82{5r}+o-d%FL!h~h9P6%BM zZ=x?DZxEXE%1m@J@*6rL9#cWH8eJ0i(nRPB8~G=>pB~Gh%4nIpUxwo@g5F3KY6BR& z5L$5_G47vsw&&!6I6OJpfgr%P7-g6VJ>iwnjt#JF_u+3ay8pLX$3g{04lNNeHGCko z=ftN^L{aFTv@G+01#a_`*vjHfD6VyOY)fKcm{EsC zm#0ER_+#K{M@SH3@)n9ESh(^B)y=2SZ`8A`ezPFncBJ+Aan&!kCqt-ku2-D+c za-iefdhS08xZx7UbJ1jPVi{Z+EJDxWk8@kz+ixA{d~z)vBp#5a>-d5?V7IVl-;EyZ zTs;Y!U`fFkod&Cdt@|5{MSbu&i{#yTHpM85#iRWK^GDdtVu2rN4SF=P-{HUh@g=FDyqe~F3U3{%GLQpKr_}7sb2^25;@lrlO=w6{bA0U z4zyO;9Ol)$TrgX+NzqR<0=eN?GSZ+O^E%=eU{-4@;+ASQrAk9}B6ulM6&SR@CvAt( zFr*qFAX!+Q93->v_-p&ddh~qqr^6Rr$_7ng#|_L5Yb%aziMNkE9>Ihx?p52&<({v!|jmt>F|(e3aab`aSAvODD3Phs*`*vfwE_uq#TgV}N zg{Kk%zlI-aST^{$ePMhhE`IFEO-BmA7tnj67KfM$Sci#12mN*`7$?%)tHMUAAKqai z3jG4rU}BX@`r5yI@-t9}0#+ZaXV8RJvemFx8C#a5OW0t0@n6m_OXw~4hHfr#0%_om zKXCp9Ua)rw&0Y_W8_%u2FEH6r7g1MCofdx|apaAB9ll4%$zn7s(#D(9exm)!!fWn1 zYa55Ekar%pq4=MmC7n>*{p`aDjYRXBT)PxyZHo_kOVXLlMa$?-_4tT?!qLMa?tphDOG}dAz63kyi(G zb)~hCcCUrfM9T8RNAPl^w(pSmVZ*_mI%wT4RCJUlpFbk~F|wuaKgbtQ%5D47MPZJ5 zZE;2ThwJc@v#`oPVU5{!)jFN^4(E)Mse7x6|4IP#8n8iLHf`5ibe;z%0o#pcR-LGRb~ zIjT#3ujelt?Yt07Gyt)CW?oN%)>aKUGWu}3QEX4F({}}m3;rzok3ddS zHWygGEc@ZJ=p^%Z`h9t22;uOBf7QsBTh1B`*KlEIoScf}$N4H|z-}t|4Y+MvaCmMJ;wuaX0NM7t+nn z3t1?Lf;J(<>Vd9aq>F18Iduc$IcuQgZOMgWeG;d^eEZq?DEpY}_i@`S!XTwf_r+Dkx7l7WC@lqv3u2*ZpFok(p zoW+oWviqO~9dD|(zOavSEhCAc`sUW0LG~M#!9{0fdF61Z&*tSVIwaX*P|41rlqh%j zXMeA~kX}56vMxz}X(qJ*8eVaDOiV`xSRCzbSv1#hM6fpo6-h33XW9?pJqr?#i?VtUkGku;2MHcc0TZ^N$;ikKW=B|b<$)FE6dxhpcL$`{&q1A2r zX`B}?%r3;M%F*VsA413H|CP(oT(EciM^*|i(;ASTg^G3WP&?C(cO2a64v-PK2*Bri zTyUj%&hqcK?YRg~!DE`$ox4NdX>9nbVQG(s& zc)D;W9?C2uSGB1@&7{Td5j{X--O&qGBcy`;BQgh`|JdSQc|MhCx^(MG2bUq(()($F z>a>>Em0?xAvM&^Z^myCB%JlltV;&QO;$nTRdvSgH+n(<3npa!0qDbHVUkk8@Jjr>6 zx1E7BsRZ%iyckOwllgD^^j@~|sjzHLwX@vo8+1_n5$8-OiXQra5-6e&k^h@Eu(byY z1PK)m1`@RQK5y_Dxq~}z0B})c(~)a!n68W1Y=iHe>2fLyRaB2 zfL6eRI%zgk2fc)b=c~O~(VIegDKr7cY0!yBVqt_H?xqN^4lNrCcvyn=G1eZWZvNKd z-mfkEpud-A?X6rAV;k5a1ldpsF6SWatZN+|JzI3nO+vA`$m(W)LlVw026=z>iFrek zeyks$^74;7=L6A^`_ycnP3-McE0m+su;{EWr9*Ao7q1GX3HMpwl^{e`fA7OkgiEJN z^$7C@#_J}RjG%3|TzLP=98i3KthaYwAD%x7vS^l$f6gCJ{GsFbT^!?s^PC~hDmD*b zyYuq=Aj46Tgc+n^u`D!ggx_F;kbqeQl!Sc?KsxNdz9Vfo*|A zHUQGPbn5g@rWTcL36y|w8Zu1V{%^b1&erCg$`t$C3}Kh*kB7@NC-rcvR!5c>i$%-Qi7pO2U2)A&Ktfi1Ed}6<`IL6G) zJ2PDrEh_%o+B*82LH&2^`}x97;!YncNTO|AcFJkJVK#o_#>&0O6dg+n`3#DtIZFgCcPsYDhx5sB1n20Z1$AQ32vLB*FE+uu4N{+A5J z02T=mcuk0A`=Z=hGeg^aI&yjd>|rVl!*|ctLr?!Hj@;5$crF-bUZ2PI-qw$V9{gm` zF}=3Y#J76mP{-vFts^_0zZq0Bqj*~u&-D_flTHpO8QSUL`a3 z&eiiv=xx`57SltBTXbr!A@-Vl`SX-7=q*u-p&zQ(3uEhX_{YCvSP#nh*DIeQcYSbu zH1D@c-c$ft9(1FwqL?@oO?5>ROCf;IeuCer#(jarfG_vSgwVU-sb{`fh ze0Lu5-w3A_h3CMT~3_ zmGj&$H-CJ8pO!rbBUENS0C#QrmIdZT<|iLG15L1zViQN`n|N3L z5~Bosl(j#eCw-n-rm0A?<<4?m;=1}{2New8FAWA_7oBwe++}+fw-lQW*sptI)z;h3 zu}*=vg;DgG`Ht8zfro ztpVG}s06^OxkrvTVeHD(J8tL+L$tZkyIbha07Q%fJ(HOBo4c8UhF6A2jNr5_xx3Ap zv;EMLG02Z(W{vtkJ0_sNEO+*2u8t_sS0a|GdTu;E zW4=qhAN~(BSZs#7f63psH2I(tK@^r~CBTn%OMez|us7QX(%%2^sAGNc^!FP`JK2<_ z46Hx4`9N<}QJ6RwJ;IgA&p(d{CoZr)MY&oY+hub_1-cy6$?2Q@n0@Q@ zo6+=W!?9CGdcVTHSk7Spmjx6HQ`^&m;tEuuOR5$hlehfj+Rq)?o<{sik@&N3HD6Ix zQZ=x_4}H{XK1MX52slrfp>Fda<><^0;U_{1&}EPj1;#j3oiSJ}LTph1iwS!ogAngy5}!md3YUFVvQ(!EK!=K z&sU^(G)#x-b^OaO`pU`jz9&EMwM60q?~_N*RSgwt6t|UJ80G4wNSfkO?30)IFa9Gqou;>4?Q>c=}p| zV!BJK{W}-8CImmb{D_V>euF(5CH$hGFz>vg`eIzs zu)Sivf^AwucO$`_tn2TC0wK+@?r9!(yexa9*m82qr#{BT%V?clYn6+b#ycqseGGp3 zIFsX%()p}LR*J>pg1*mNPTjrw1pgrE(?{!N#T{c($MRk_*F?(r)^0TvPBiwAKHs>NueAo&Z!az0;$!@_3#9iWETBf}l zbs7hAK))97$nlc4m6o70&QQnAP@+l}O^h)Z&(Ynltzw`|I2b(8`92Fpq_Gt8w_xkN!@A;XYqc5v6JvA# z#p7O+-E*s~!Kz*qwS9rVp3GAw)o{61*tFE`)u`w`$+IXd^G*t<>i_ySC8XtrZ`l5XXcwASBb~8E~ffX~b?g zFM6`%>5q_~jO*Q%RE6U%c_+C$g-iT>)wS5N@4kOUWKoK-m)KOdOIc?~)sP49BSL$P zP*S5q9M*uwK~R{dZi7d1FadbC&Bo`{B*Dgvql8%F#dosG?!2QOzWQ;OJc#W4tj*?z zA>pbOQQo{i*1}^vaFn2j#LX+}irGcY(k-5qpZTBq8n1%zQQEBGvVtnFet3URp6SvE zv9Wiq>{x-$hx;N-AbFUtJv)$Z|6|M#{fwR8Gw^Q*n!psv{RCdQPeyOE`T`G|;@X6T z*7@NS=b$OOu#hHbx9LOj&D=C(+Qm8KM!+7iFb;5xRj=h1L~wds$C& z+ZSE8SLSS;qxA{d_=sl7t3x<#($N<2tqmP%{tCGAy%^F`2UII}CE5`VOs1n=dh{+> ztQv;%Pe=(cyxecDwF%f(Ai1C;bmpl60f^e5byrLr#%a}pH=o-G?U_pWFpOgMq|ir^ zGj}yi021Dm+J;jms8YOHim{^*cdIQEv%IfguLW=vbHlhbNW+DDmfE+4l?GvbHM31!97ml7Pg9tp9_fwn_C={bay+C=Qk64vX%1ox7 z;h7@)jOB%1kUmYttWR{;(!q6D9qAGL0>QwWcbF$PrQaeaVL+0^YkCvtQ3W+b2t2-c zF!0WUmcMyAkV_0g$?pUq+@MJ2aqP`yBB&3QhB#{lI;M-r7P^j(Xd4aQFeONr?aLVQ zNk1`AE$&_6*U)nLG9qHkK@}>Sh;qLO9pyszK)Aib`=7jZI8ir(a7vj3hj|ns$zr>A z>n87bP#z+G>#!^KX7zY>c}OX-2=&zHkfh$v?5}W)P5Fm9`Bs_)Ws(ySs}L`J)_s`qIT0#)vg#Svb#@DQ!i#F#wWjf02F*M?<^=V9A-MVk`-UgnVZU*-T%@Y&Q zj!6T_#C;4VBx(l+cT5-|jZ}74JRhuy04&X!lfWUjf#g}(N+-?b~-Ws9l z(eZomW>E@G+SnIl#W?x!{-1;1;*?DYAyHIh;kiXw?$A%gRTsC;Xfj9Fh7jp(F`?@I z8N{1Xsf-u+8aHxB;J6l|J;GDRpXE(r+@qnfgcQj5Wzjx)@*JQv4{l%`&lIEUX(h+| z1Z~*<5@IVZB!zM?&GeR$ggBJxRsI_nYvJD=eDcEG69dB4$qOr~p&LSCV7KuOcRzBu z-}T5knd+}ZkH{msiKRcDsp*&!fUH^ptwESBnZTJ+5&Gbe7VaL|evq-5N-OKK0|GoU zj-nYA(WZjkBw=NObxTm4ue~75sZWY&vEcXERU*k?ueYeL$i`WcG-5(4P-iAXs$5MIS>iePC zG4R=Wmt7|Iy!@jXJ0?9s#*aszi~aq|z+u;R4Zvg8Jmy0E(yo`~oweyo3b_tsIh~&F z-CT%LBdQh==N)f{@2?APwiaec4ot70Pu0DjoPY&a7;QsoQ`J#UX;EJnV1VM5!cfzE z4J}k?cLG#Usxn9I_p|+^j1sM5#57IO3!(`BF^9yh)gFgd^a0-Z-hG3;?e-ain?{9+nxmCn6XTB|8N9h^IB1 zRjI$p?r+|lyI6$~M5{7Ys&u^0Dx(Fx|rB|rK{PiUG(fHo)h=gAf?SJmMQ>HZrbw{U# zt$(ATjlxEJ3g2sdFgAcq+92Wy4K=%Lq3(M}BvsBJed8_OQKWbFtm%o=R;T#I16_Q8l6IpU=5uC1 z3SR#XQezBlk7-ZUWum*B1gIwpEh1kI^d0&m{mu6go?g0wFgeucoYY;|FYkjyIDv{9 z%47tt2bG>De8uwe7FL6z$Ua%HKMkkcBb-L2dXftfxG$tpz9IfoNuAT16+$4Vp~*8S z21uo8-PO!7sHQTL;7>0Td{^k6;uAv*cBSHH3m~4}i zAiwA@Z>_`T-LWOA#l+2XU8R$UnR#T^@nc_I+(~A!7k}ub6lg80kWLeI0H4ltX5L+4Vh2zwzj{6UIsmy$z7LOP{ex`)6( z=|*xiNcWJs_x+voKlj7!!OqUEUGMAtdF6^3W-&2o35IW@LEWBJQS5%RjF4QfVsyf_ zlFD62kwaBrc%g%>)jCR44BDKuNmF2B`u169*Ze&p^n>O@3RCOEVztqacPF;i=6@_{GZYZD?mD_I3HMD2Zi2R3gw7$BHH@ zG4W%>$5*ig1D}&A*y?Ljd?wV~-Mt0&U+vk6wX=b4SIE5~_Bf(IUR*0zyI;bweONTS zQGLQz@A6no<|m^9tC!Y&p25B5hUVt0&Z;%Pt{RPank%cEPb-(M2~W?0nB*_km7^NI zLCaZzZshXV{Pe4By2r)9QKICkSv);g_ecP|8Ewf*hUkeY07e}6v)e9Kv zE1jS@;(Wqv!L(I&KPuO%@7}WWr}GgiA4)cr{WJ#9-(CjX;++8LHaTK!6Webt#roB% zA)As|Z@2QFKWMDT!f&$QE=662j0$~t|LIrXZ0rc9r*7mk5i^}BZ-}VK*gU;z?)qd*X1&xXyrvqPBcuNCW6~*){qnT@5cw z^;^UK5Y=0^_&U1kKYE3<&XOQzvKfiiu`9)KdSgoz*@)32}a)^#CLU zKo0J5l&G1ACSWb*OT7#Awd8E93(4sova_7$t8LD{0&LO?cg;LqPDy>k-P1Yrk{mBv)ck@e{|2_yD?WW!MDBqh=UQN#;-{3#HiZ=9L zMSjtIyON2GLc*#en0!dB(Cxl!)der?)Wi6Fm;iAZh^=O|e1Q}pNc5${zhC?q|1tzZ z>^`lCx|U>|i$|A_b|SomA23dpv@rNHa##6K_^$z`RJizZKE4E6Fw?|cOj7TNKkaH` zb}g~{?8TRJR*AlMulBsDb8KzJZ|U$8ZKUJ=HEVXr*fc{9J)x`2tWqpnVK2GChPI5c zaQ;iVFBZtir*5p$-T9D(&V^n|G@Fl80 z88{+`N^D~g#*{1c;qMO;L=u@ax`fNwx;$)bh@7_P{GUu0_SRP=s{7HlW8)}$PA7k) znJsV`{glwNX2sK5W>cTky%Fk7eyaXSgk|6nkpJ69Du8qRJ$_{s)+>;^6DMGdU&>pM z_AEZ~p07BUUsCoVwXc(($szdh0-W) zHWP`k%d>ZhlEmTCrWS`qN7YhqMS3L=Y<&(uuZZxJA+lVJ zDIeabOo6KCmg@^r3WK1=&cTel)QNFLGLBLV&LDS#`||S{{#pSrn}yxe8}hK;4eI;x zLW$d{>5d@ZqRL>@{e~Prb^&Vd4(2PHE8LDKD#$H-?9N;Wkul{q$>OnTN+860uaO0% z5$OWcDrp=g*f5|@Du**7H9TFJD+A$uD%?sxAR&y7;m~~*J3H3J0A`W~e>m(Xr~u`a z@S3t=N2*s^Umc#7z!qwpb{3WL-06ZbAO=LGJe4B*hT0xKbvkI#Ugzr^^-@Q%v6@v} z91Eg@zW@Uu%t}##g&h_{EwX?UOZK#ikCjfnC5MKf)mLRzWMW|@bCuTK7a`TZ3?C`) zOs`~yPy0HpoE&9iQbbxs|YQ~tp(exf6I$Nx(zq% zyK(Den;S|^tfRL|mAc-S&7k3(D1TBUP5dyOyyxpcg*RT3t0WfS1RXmH`y$sq3?w5po8l(|NRYDi-|;fgFn*4qP0R(;DSMCp-p zg(tOf zRtk4z=A~g!61&Xl@mAuA$aA{Fh)MUwjuB1M^tI;vI?b+q1=NBtN*>ouA?kL)>BC|85e5=~w3q8~i-C{x2AE;N%N zAIkyg7piXuy?+}ni)QbQECgek2nZ9}n(|g^t-NxaOv4_>Nq&pEXOr{Uc{d(NhGOH4|E%&<+IbkTE+D;P_)Na#^;1{$6x}3M^JolDE>a$=?WL<}F|^=2sH;!P@IA zc=*TlcNi9s1bMddjDyEu(R);R>t8Mvg&R@YzNMfS+7gU==8XBlg_T6}B3zMkFsW4D zKAk_v>&d_hZqTOTQ14Co+LHSm*l%mHOK2&1MBgPzbfh`9!;`=DP9(zeP#$ZYA@d#W zG3{E1=D%zlX}=Nn&Zaw$|3;1q92oW7V4e2(Yf7XSvt6oQw>uZutFj%I;#D}n+}Box zmtjt9uM{CDlbT@i;hN@z#o%Z_?uDsM-af1zzz9K$`Ffwk{tNz+AsttR6&^ zdc-A0qXY(B^lL_**AS-B(QOCd@Mg1K#YgL$x5$GjDYr^N)Phcaf+f_}&ha-wm-6m0 z!dmJ>bzhrx)~`$P^Xow)%oCZF&^GGr+cGSt>o7D6=0&GuY3I*Vb?y2d!doujoSmMo z+_d{_w%T5ON35+w)b#g(TR+M#=+uJI*7HZ39MTQjp-4h>Kgp&c&PC6naPEeo)X zq1SNR=Yq~k+m!eudCmi$?~(gPA?eT2pVlPF#D&=o&AlyN5@ zlP2OBe~|;xZ%g=n?KjDH;C2lZPjUPQ^bc7XFmwXXAhF&%wF~yBzkhxO%0(`S|wMY)oIE|xC-R-4XxA_J= zB%==<>b4x7$REY1wKZ!=iz{Qv4C>7%Ng={_d7XqwA6n-^KfE-~n*&|{xDt=a;_=ou z7;S{|>r@X3X^=RG%6uNeW_<-4MTMfv9_j7c>c@7KLsQ5m>{#+9nD3X^BrSjRo=#6q z{=3GT=!)Z@`AguR8C9S?!f)aK`mhu2Y7YFaL?djJTB;x80w*s_0<_zOx)mJdgIQK4 zI*6o*jPNDW3YwZ9-b1cTidBK&!ei0Is!blbVWZB?X(gZBf|6RBy@jfm zO7+C^jXjj|vb%`INDym`)KOhiB)0Ax58N&G3(CiOLIbh$P9Iq}r7-DSt2|FPMw(Eb?S#_r5}B!IJ)@ zEeh=u^&${ecjVet=ne2nab5Zb6Qt%6tw|+a zQ%apA&>^~1aF^v*e=cmr8zF~%ZVWF-1Jtvl%gYnc9ffk#6if3Uyx(qzT;f)^%p?I<>s7cn^c$EtDhiQB&uPCoy|BiF^QK@AGp2Qm5 zrey|K$m-pe`Q7d-um`Ka!k~5ElD-XCt~C8d{?wPV@U%@rN-$C)BqGvExJbC-aVA3` zp~FunlJ|F&W-dqIQ{YQ;LMaztvV+&o+j!tFzfQ}pZk4QZ6dYBWYnnUe0^N(E+IRd) ze~%>>i1O&hC{wZ46@PIyAF#OVac$`1M`L5sQXf*zb6IkRQ9@$m#&0X_SFHF^=aU8> zf2nI~GQe*)^EdXq&+8fzPn+NF=Z_8740hC%R73_G`+Qz-N}stl!1QOz(}m+k(SN<{ zCRxnFz9Ay6KLle;w4$k{Ku9Q7U$KVdQ>9$|5(X7qh4yv|>C-f{GWJS@XFo%}qF91g zS9P+6ZZ@!(kdGTKUJ~Ye3czuBy+@DpB#}XHiz<~u8>KNirx3#CV;C*nrv8w8sEw?? z->RgkY2}4;6#gr2!7Vws5O~~!7C~o(t)IU(-XBw({{78@w@}aRpNMnAsGuURp@@u^ zR9HQI;DFIPpid(VU%z4B|58#f{l=UPBpFQGK)AT}yKTYhonTA;laN1c;wfC+e8Ju5 ztx4CPzd9QW8$rp`1_;kNiE7Kbvz6?Cm&v!oV9=U?BrC#(*S*f@ZYB6;aMiQ*U!@_p zVBK@iC_E7nY>xgn%d0N#UaLJ{nW`2vv0#r3S2&mXwe**7dGsDDKE&CQ+k*Zp1~z4C#utCb67}F#gMb z-6e<*tqq``3o{nC^;|nFEx*8hOya|fEht46lj^z^wITU&exTl&r-eQVWuH1*mdO{( z)ZX@lU!K4Blt)WgB75a9(FjAd<5Q`JLYOn%=bzW<4C_L&ZP4JAzy{&)LixWbKhcgW zrF#vo|DK{cdt)Y0g}6Qoq4^a?GU6li^`Q4h8$BAz@%kB z66D(-QT^wG$j@Cy>y_25-*n+oG)8}<>5nf>CL<}E3btgWRqOvM)gUnkfvv7z5}&KL6Xep`zX;izdpEf2BOn!Aef6$x`MWe^Gs(?4 zv^##mGsarait4c=H~HT2qL4Ug^gqm(WA*zwZd8 z{E=zNGsPj?_<;up@*kYe?c#DB9)2S$Hd2)DgG0YIyQiFdwmIZFZL-Wy+I!b&5*ClB zAs82*{8=VHg)Lm!%6vu&|7Q1ayCEC8=lMdbdbv6Q^Hj0xB^cd8;+AAH0i$IYd?xd? z4Bxp1%@bz^J-H;OWsyXp+9;FYm@9roUv@K@Q^BIugi5(>d;mKVJ#sli}leK!k7 zblTMCo6*M{4tukRey;JK_+&lYTO+^kzKR7{p<0C4HHUWp6!6$4L#ra~bt2LZB|!}J z6DD?h6)z1zK+0QcR@a5%O>L$&iYK2qILHW!5s!9# zcn@X02Zf5oO1i^87HB2F+-DA=!CuU;bs|FV^@hb%$?W-+k{6WiSTWx$64`d>6zAyD)c9=NgLX85sIR8)&Awy< zs!+uWZB7CuundYpZ95JGO4yBJzKMbT<&e)-U8c#ca7>YjUx}P247S=E&XzKBsrm=y zVCLy5ZVPtbM@m0C@)g3IJo~Pl(yHT3`H=DJcLsshAM+X@QsfD0N^egF-6Sz6G55cM z2t;P*%l23?j3V}@nW5(3 ztEbNLd20EO1Q+`ZF;+xJSc{?fuW590ndCUdzI|&7aRw>SiQjKV&D#r+pcOAfs7K) ztUK|rG`T(j+RDLLp%3l(*wC786fQ7@G82UzE2RSJt4HK?qQp70!A831 z21|)lCZr>Wu=7*!v!ZDjSTm7#+KdAttkW|1Z(5w86HJdOZaF52Iq4cfw9bSaqaszW zCkLey*m&ubT!n01AQEKa2-!Ux;q)ABI)ysU5aO3@ z{L3FWt|^-g@_O`%Xl^4{M;S8E<9;_Z$d1r_%iOtp0AB}<3Gc;YfKvIQ0YV<0YccY| z*cwN$X~YrACt3AUj6OgmwLGfQl0q}n6Z4rkS-$Yr0`dqf*+_dITT%Gu8sw!PnS}fF z&z9r(PjQI5vYHF%{R>aF&B}i3FN@Xx!K^!Gl~DU#Rv)U3g`+P6WxPE$qLyoC+(G|5 z^G71Bj#(cm&tj0X@CUQs=v*uN;qmSqUf0|T6wU=^e2|K|FZQZaJjo?k3F8!oQzhD% z*qz&@38({khHQyEC=57%NG8^GBmNZ&vzGCNki|$E>IWp3JnHZcZ(lY~Tz}g5Mf&CA z=-$@iS*QGu$LDw{P}^Pd>7Lz_v7NDsj7P9LJA)#&se)n5;XkQ~XC4^WmlvJ_R=_n0 z{j>&2s6LstG5p-_i{QL#v;hjeb2M{>YKYY67l-LYnmMUy*c$=gND4rMrTGJ+K@!;I68&V!LZA|&$YqwY!Hrw}>nw;2>+ zkEL#hYs{<^;kYw7Q-K% zlW@$;2Vu^dgpN_PDq}Amy9s($^bxMR1ueME5Au0O0qLQ=+Rywczm}FJ4hi^MN`-E< zAXT91Ci>BhM}HX)c-6(N!;+~!LmZ(AJR5VrBNlaz`uXKY-!-$(3s-rGsu~%5uNrs& zb2$9AOnpW_ta1PwFR*nLMdK`eN(9FVY+RLHG3l^ctZ^MEfc20FwQ(88ad_~a>Vo^U zCCXbjWBa=Njngn(vuv&{$lb?$o_+Y$e?xZ~)@if-HqwiQh&Mp$xK7*tFW?8&c`9Tt z3XEzi;>LZ6Laxi%Z#;!EB!XEg>*&HOpdRo8&BjPDoC>9JYPd0G`jt<=Qm+0OLKB(V z6b}h2*SdIXYkTw_ONZQqbYpwz?*0_{H^^DUcU2}NJXCuYn+!$nO5a#BAZ|H@Sn^nq z#<=%HKD>syU&P{~LR+j|x$?+kxZD$AHxk7HRTtT)p3If?hz(`w(+aY|(tl%^?0?^J{~hn$=WY zM)kU9L-gwJNLvz)K|1sY9Q$65GVnXl{r^I`JJ=uL^zki?A@e>*k@n$v7 z$k=UI|I{Ua@f)Jmw9jwlQb)HQ6ua)iZ>rT;!x4wW}aB z8tr~r;jN?F>GyO-a~5H6`f~P1gcHx9KtB5<#Z4f54}y7%6aI!1P~F((jq3$~&fqJ!EfOo%}YQ_t%SwN=8z4F?)v>M%Mww9#rr2XEMf7mDAzO5nbxOR9yyKS6!>nGF?rfPBS?0~&TW@z&|1 zjs~wC#9A?04JdDzQ9t}0tur#?@|xc=ev>Kcc?ju|da%~02gmj8<_LfvLrVsjAbEP9 z@|=*0A&yMXtKqFO^{;&Msxs1QhgHK&uAe=L`8aI{Xvf7O7lsK+z(|TRXShPdpga<6 zuqh6d(BV2)c>gs%?N^jjwlBi5Gj1>-?ukS{c;Pkq0jcksNjEjvA9q?krRMW)yQ1$M z5qq-edBn2qT{r5KK-I%i-9GSHy8|fiE8yoaA*;=Ig#vNJL(6D^rF(ee;@_Yvsxi%) z{Gml^pS&hA>2dFtxBOUg40WIRrtBeFP3QQOcN}ma(*mWE+Tj9+#5EQ-4)9x6QUV>e zXaBbtl3UU?p4d9tUu#9*zEay*2{j(*Y*5R$UgGHo-|kpU=$`g7smb zOXwqgSd65w<=!d|>yqW;Zr{B7G&N-iFGFFbkEcb7f=2WWMfA%)AGc2%-3kN|ic^Kk zt5}bu=?v)^4Fp@;P3ag=tE2%R@bQsAADA22-k8@i-1sNXm1FbpKRnbJR`tq)4O|nq zpa)8Iv+5w2m4OFSXu4^{hBxek`qHP6}I-wR6%yQ-cp937TVr^fV@EWh^ zq|B9*t~AxS@9)A0`zc@VB-f4_(=xNES{!~l^y}*hf-{drS^S&W(EEV#H!zNw-hO?b+&5usPAdLgKf7ttH00OnhW*~S zKWD^+8ExC*`>71YxVM=nR37JeY|h2vhvR#NyXd}a7=oNCpQ8)(goyOb9t5ZFu+);6 z*~8S}1b^>R(;0Gqp0NzypOck8+m$?+PnEHO{z$(6jk>xR3Of4;F^_d)++kF0?;2gq z);=2z-lnA#{D34Pb0sCsTzBu9jY7}@us_h(N|iFT#+=iUpZ2?a&P!i(jS#2YSrMYI zFF>p0*wTv|IiuaQ9_tQYfL_7=NeS{y>2l32kQK^-6gfr9X!|Lcd!*F)Hf_cTNfhg0 zfacSKM^V8S|A3Itl10A;%G=IlzUKLYnA!VDjDH{RPW4~UpN6tK$DRki{J`>PQ32$< z6D8I=Z3o0BOCX*)P{g!L^JwiL(Sbbu1vdO=8n;4K>))VGzWOqiyo*9wIXo#{-@eYT zl+rDM6Mw+#%uhnTV&oU z&-93J#w!}rko?D&&-4`oKPCi9*lkVbPCH#v3t<_f|E+%9t!R z$q;l15wp{}_MO{lg^~y_aTZZRV517~7WV@Ws(p#DJTBmha&s|#lkLVUQNu!ba z$9;cp9SUr89%D5}U2zch@d)_)?d}B0RZo#hb-(X8@z2%cz7)}@OG&QNe}*IbH5`?n zMt8N5pBL6|+-{v_?%6c4Q&I}VZkla-z(#J~7tCO(%UX<(mpCx(FyE3@uciq{Ssuxn z)#_UYcl7j^9A}C72FOM4i_VhVO5Fn&VEGQ^Ip?)Xbu*E?t?^5PJx?TW5A4_lZ zFufs6WbBh2_=9MT{oKDV4P3O~xwr0tzHYR=oO-u*Mwb`*hU#GjDHORcSXkP}6-_9P zY6wiGIyF5jdf$)gPT1X51dI;JMqc7$a7Q8V-e@P`y_;=``1 zc*e)=|1L$=IT74+U}CdxbOKk(YecQblaq~oKGeeTwWlI)?H6(F{LgF)J&Xvlv$Xj0 zYg^LT3%$9&@6xWXkW<8YnZ(HFM{aVqL^sw1qd&=_ z>h|EQ*}q624;qgHQ2gd(XV8`qt^1!*^Yyh?Ce!JFF=iLLXlSTOy{Mh5)C$Td=2(8H zTMBoqXAL|GYlOtI70OoW7R*hv$HgBy52p@Zd-@DnCdu!%PYXG9%D<0v_+oc>vWeG+ zO)4D&QVyfsqDN9Y_r}KAPfM)k3=O8R`*WKbst8RaJD>jJ0F1pvfw_=k&#i!zw)w+R zqn?2qCgmWiiCJG%3)*=d3}jE#3y7jOjyLN45!Bk~CI8YWelsz}8s%L0gK_lXE)R;hWR;-cmi`ckSz8f@A<1-n)9 z+g~(8vEz!rP*(?gg{?0OwN?x*wbPyp!`%RN>U(z~Q9N1apMrCE=o1Ei(s#%wpu+h7 z$z>Mg>;TOaw)Og4kn#NyB;uITOc(NK%Mnx56wrOu0t^pVisN1Ay$ug7Nr*#+Rb1Ek zIkb0zNMOPf;6vA4;GQiC2mq_0_W(3_V?$(0Ubkory+q*!$l{Xd{-of;5CzRzD6FM3jWC-Il04ou`eYOueu8m% z#$?JYz>{+f>$SzSdNtg~d@S=PMwuVT7|SrM@zE(mwBZ7*{Y4AKf#?qBSMbmdVRZ^F znr`0%bsvp=l?K;?b9y!tj`|lE*%y{!b?%|4RQ;a~ggh1=+WF=rsblo|{CYlTeZ32O zEWADftO;`b0etU1QajD=Dfn1bimr66Iz%N>tDON{TQ13y!kO0v9 znX$$IBZ+aG{3MAl`vC0WU(5~tC(6h@s9P6MdK0PoL-?VVp}uL75|%?E>COHr?&ucn zue~>t{Y9P<$B+oq16K07_LnH4;GCt;UUhwv*yvrxlPgXBjoiw?qSR&dnkx5MLB7I< z-1275Fnj17xcXk1?AB(5&32@L;Hx&w@i2lIEhz)h-Dln6d+lj+R@%M;V9OHGjo69Z zsW@;A=-1vdWkTbjK0?E?C%{pP)3DOOvRp8xJ0Q%IHybtP#D;LXG}KnY6D!DdHLMIq z_Zn2=a>7d*q*PKPCrC3P!l}E=F37Uk$ly^A%q;QOB>`#&&G@mqm!1Y4eJdHVicr3> z;=TfnDZ%Z@6?F4_iuSbF>3?-Z!PNCwC|E>|6HAP;<0K?&DjdrT&PH#(Jk zZg*l;>SUtZ1$RrbI7b3~^q;*3W>E7-6MdV*jnT1Y{u#!4&fSNXo1F@gibV|KaH{m>UMrWE>itshWTz3&YSx54;)`n-ODk&{*qE`cTogC%>A-S zZen`qFDx8u@zr+V|Fi(0+|vlOdN#7zDq`$x!mRUh_;Tz<({mR_%wGqDkZ}XlOem)ezk|mAKR}Fb&k2gNBv7^t1AT=Ynx9j zH_;Bd!Z+{q2;-*;`k3-^$EzCps3j)E++jArGL;-F*vGgsibdz-kcPtcWyoa&h$dKr z$P;R%FuTzl83z}&l&(;5*9?f*=Zl&N_Zbse7!Zwp3$LHnjiUdJ=z*L%!iX!AmGNxt z!qFoFM+HB>uni;`v9W58dn(6xKvLrC5^M{9gG3o^Cz(<(SiMk=NeItO6mJG)-oz?m zbw`%$3fYx?g~6i7Pf}B z$bzPq{QcwjBWAo*o`e%5Sl4H6O$&(Ub|-0V0W9*8mWOZWTp1eZGbNOz_U^Gu(VTY+ z-UvDQgv7pFT9^*xkeFm-T2@1>H-}EIGF}VWM>=FFNJefC-pSyU5&w`c3 zrEWn#<9Ca2CGrgv31)D@)e9J2=(Lwg7@V6>9_qEf-}Yoy;LdcIV|d82Yh%`vB`!RlYng+Z79KJh*x@vj@mLJ}S7Mh2z@lYn(# zwIl&=E4v?);XE-hh%(zkZUlJF@7C#k#m^s{^@2&9_^|1HheozxV`rO8NXhPQ--suU zMWeR_H{a*%X9>>d4{GbwuskFxI*^x4dV_Lx>+P z!OuHDOnfEKyW!9E8*-zT`2={6AK^Ywgmc`t|IJCDSo|MdnR!o`bIQJZdBD+7-3WJZ z&H>cr$aLXc(@?in>`N$p8bGj4oL1GgPs9e$kOXb()4A$JN+&bU;r5zoSX)4(RR2fyuxdj2x?gW)S~S7Aybrc#>`(@b0Y5W=3Hn2Q|29Q5S@F+g(psMhu|;e z=O@XVhmAltd@)|+dDp~}zAmlpH?39(a8edMN380{j*gGqn9L+!v1C(Fj&M{-!1e`+ z2@A;g7>Y=ayXWgM`7{(YG+#Pcn&mS4u20%4<Tmv0(OT~Tnl8-U^ zKDo?P&?l(vZ$NS8@T+mwtu!)^0YZ}{k_l7zJ19tF#iH^DA$-7tuPwCu<=41Bk)I*| z9e2?jW60`;z%P-g#&|#BGl4Be!;DoD?Q8M8e>j0>`8JxO@AABODr>4-0^Z_DeY}-9 zR^9dNG_+ZO)A@59rR^#&c<6@h#h!+7MAR56*X*^J4fNQIeydL>LD+TFN@v_-(_=WGMx9oC&@H-qJ>%Trmi5bJ z>|>Q~<=pu^{b57Phm34&cMP3I#%j%64rC5t|GA4~;Q`SWqabZ3>ILy+dSe~0)2D;_ zy)9YI>mWyU{l9q=1wBfy|Ms`QD0t*to1ya!IYXv%(KX%r^e{xi%#z6ulq#vvrW>v9 zms@!NQR^15-2Y7!Qyp{s`o9Oxq)`DhJw}hUapE{Dp_k$aVF%MzRr)^gjt1=7S-RyE0;1O^qfuqcZO`E+0p}MHLp_-`&c}lBct1sX78G(k@D-e@V$&eXHc_#Ygwwez#QW?c1CcT;z#o7wd~DxB zxXI)rVGh6{pp^afrf;}Z<~uNe?r+5C8=`vsIVwe!h+WRUh6K1DG0cWZJ)DJ~GMfsY ztME-S&12!H*#F^WEI<-FT$HU)wM&JPJ2@eV!pgqh=crvFZ56X;M+ zF&=fsBoER3_=Q@Va0!=FFGsIy<5CB8L6d=tyc-I)$}#!B7^a))qTul+~1Unb&Z-}~53 z-lw?%cUdYWOEgzbHA2i>vfPS|g2r$SI5bh~q4DJVr+eEJCC`1>7fdBG94nQ2;*!Tg z&~VZQJdQnLCe4Rv4G~&O`|(y1QU_QO5FDUN5}NsJ^q*a%U*sFxRz8QPJO}D}8uD(d z-C#V)c4^datX-|HJ;8Ge5SL7YG-hlcjmn0UDParbMnvVu%cbjf-Bl8BDnhIu7=)@6 zSQzAWbJCvjHx&DG4?2xxz6a9e-O32cy)?EA{uX~a7%STfXM!X`V{OKg*HB~p3N&iU zg?_3;qRl20qoK>bhN=kJ>WQYIIh-Yb;PVuu;h3*`3%(g!(b_Jn9{BtEhV%ebyv(#Z zwJ(fKN{N~N^ys^2{sH2fITbY}|D6q$)^udO&Wn5whn(??GHJ~k3WvfMG6pD()yP4E z8?MD4Ya+Il^$*?WZE6#LGQ{IV+5+V)RK(%{LjXou8J0?1wD>rNV!2mj<*&+>2D=a< zB(d8DV;j6_OJH^}c|PvDNB$S}I=0Dpi=D64Q&Z06Oo~>~SOPX|>rF1CcvMB3ey}rV zIm;ZQePr(%_8RRfd{yd#Eelf04~TdmfoTa6#_Q4A2I|^InNmu&fQd9cI%+w1-5Vby z`?zmGVWWX`k=z6M>cLBJ0fF41>b*Z^c7HY{E~h!eV!r9`urg$wJ1Q8Vc%+;w1&^+M zLVN~VCTvEuK(J{Ng!klASTstCO~FCNFRZ>xjHlj-Qb`76mJQ#f3484Y(>gA^-iqlc zZGXBHd&6;#HBd6_rH*SqTWgz9bdnRyg(o^&k5Mnj^?Vq=M7mIVPm5q+LZ2H!N z6f*XnI%fJl%W)c?PBr0Uy=&jCy1o>6iUQLB6%2A%B`cc14h6Aj={-HuephGsh*7<$ z0lNEVn=5RDz<|pbBHQVqQz3ij>Wz=BcI6e)Eur**I%tXaw*uuaV+zRlYq77on%I+h z;eQwbI~Y;J)3h1CHbnn)jd|flbLn`Z7pd?|RHAZC2U{api7v--KmNjD%}){alrdX% z8d_-DLQpq?-O{PQiznBWlvAPYh!_N+Ac@MCvJ!RB#@Mo70ZVF-S=i<<`2LkGn?GN0 zeZw5hiIHWV51Xe^cooqcoDqomK@HgmJ_x958s@OeVHTNt@IeM<`;+rvEWXgcj0QRu zR-7r^?HTatvXJPb!^{d6XQZ)N^qB#~PtRsVEOCexr`-ZP(&4Yn>6X}&){~sZ>H~`2)hni`LNqR z^s~EQ(r2X1uT{`n3*j86E-){0pWiziy+&D_$N0nv&mjDA$^9Uuey%iR(rX!g`eL;F zyHIe4DDWp(qHJeP+hzd5xZS|qM`^`?%mO-XUw|;i$wJm&Oj$_vd!HfBdOsBr4#t^*?*RXKF3g)2m0=pe?$85D?|2>q?00Kl4{W%IF%oL?4eL(BsxAB!C0?3SeQ3 z@gz^#$fKV0SqP3Rm4p+KZ@{Z4Y+|e)eoNC{#S%wYKnm~_CQCq-IT3b?dlHwtEbX5t z>CG@<63iyIEzo{m0WTF4Qn?`5#TM8}&K8PA$o8B1L75h;a-w3E9J2-30b%V(N7qKj zScjfX%H2Qj-?nyUJ|k+`KP*jKP4d&gplf3rOhon_w+;82xS|$6f^DE(IBKI5?gGt= zzO4&?b1QI}WotC-Tl}k-%*iyln-Ot5=0Mzd@NeSqJLef?pCRK}ZED!+r-nf|o#CIZ z4f7j8@FP(&vV}W!;E>P4L(1K#7z{&8Qg;<-cniFb<&?Yn?$wMB!atz$HCcUSAJ(w0 zN)2%gue@7g`Tb`URYbC8%m1C}JJxz#UOkENTZ|pwmoMPE=t-grg&}-3;x469S8TFZA!jQ5B;} z`!QH|qM6Al0h|$r0?~4xa7Tb~lX>63djX>2aZpnfJ zU*Y8Sim)qn>x$2b&+jq;iwjZ70Jie(q`bq$e0D^)T;4hIvahLRf#&G~WHjF4kd(AT zShoVmnAXGjh)1h@e%4alfnn0>B2{Vug!XoLA9VgP4!h`Fg?Cd>1&@S@61_L;f-v9X z+Top(D3zaVWIRoR7XU&-Dhl;B=7q3*%+B7F|E+nQF{FrAIVO$DoS_>p)dP6aY`D7J zYJcZO)@vb;hBr$fS3~rgOE5CyUEY-GPXZJRR{D{A=eC-xzd?K7(NUAA2?mFA<~{m| zaE?T04qg1nW@P?qhVgJrr(JA2l8IyvzxQT_5J?OPJKHE+OZp8gkYna}l%7{dCNVO{ zl1gYx#nIp-edl|x!21=2jK|nY;+A%~e&?v9(7~$rLUM2&|7jLp^>hK?&t7)qeQWY+ z8_0&fmxYYU7F5(45-H0N-wychh9yqgspqyOLk)^c{+#ObSO2>t#!~TwZU_P}&t3eo zVb&oujBR>RD)l0noF7ZS+D4^^m5w0deE)KiL^R3-W@TMIi8CldY4GXf#}sLz7W>sl zJ0|R_H1b?cUTGY^Q{n+mmJ9tx2eFHI?|y zZczItczK*mSXSd(PX}96m7@qK!*C2n0g6W{8BGKlsoOF?v;tNQEInsNY_w`rjs$J7 zH!&Z?*4`|>kH{TG^{tk9SAOb2Z0g_(8~(+rWoQ-mAF(?i68G=Ui10>X3zI2G4u&Lh z-Yn8(!R9F8`G0)r>e;)8v{gC#jNL;eAvQ-}k;Q(zwq=5TUCtH);|JF*;rL^v2E@F3 zw#FPXD^K)-wlxO)Sd3!KHof|bdBzw`3mn=kz+BsUXSz-cOWcPjA7RDb%z60xoV|5})8ytU( z24+wmanF-zAKWc+;rCcbuia*+Aj*FB?VH9P!YrbOELGI#i}qR$J+6hPlXQHO_a`z4 zSXTWX1H4pL{&X^vbnJA@2D4;t%yd+?j0O!GV7)>8sKmr{*Y08r&FHCM(%g}7gSt&C z#2nmpKr67u-bVHuEX9Tx&|rWgL5d&#=NBf0vzvD~@1nqwP#>r;aDtfCMk1J5r9DkhRXJVrv|HF|qAcpGr2F#bP38?S zv3{Z=tN_w1NdBfO?N_XB%lz%BfC!;+Bn^K0na~u2yBM#XFpEQ4;d@q?BJuFma_0F> ze_>H=x6X_FUNO(DYobfBW6qj4%KB#SKm7Y(K*y2Q5lYJJ9J_3y;=rkY!Y|aKp?~a5 z@xy_f1`tPh>UL(DzjV1PYCFFhG;7T0zk40HCSMVf^gsvSx_igL|d#amr3Q( zNNmpIHV4#m1{w(02UJ~^$GiP&t939G^z~fj{cYl2;pn6?ntZ2Bs4xFSLFKg$#T+AiAv-aP>F8 zNtOp7D;rE;I&^?~>JagHpM8a@1WC%J2TZ?ayHq@YuTin4lFMU1i>ZXH?JY5~{ zkDPhz{STU-5H8MRvTP|KET6mtIG+HkfaQENtGt#xkE~XwtbC`@LrwRQL)x+xkw4jj z_WzHjuMTVK0o$gLE`^O$TDn8JrKLMZBi%?(dVmPh0)o;?r*sUI7)W=F&e5a4{oeO` z|2(^{UFR&WbDle%`%cr;_)9H!M+7TK?c>YMp~8BnrEl*Lu0(Vz0WE>ThzB)X%Ny)d zq-~%B^^wF@2{|v6i4H~rO)x=@w5R%l06(Gp`5S4JRn+P(XSq!b>lklCvtYq#)pE1B zsS5Oc^uq-iIOSx{T3vY1Vx}&mu`11SxMu&xZ~Dm8Ab(9N$*&}8X9UTyu?3J>s9g#B zHSg1WI58L*9$CHov89o=WjpQQsFfv@0`0Tg%5W^vBcPfn`)8(e@7mMvFz~|x%hK=H z3*NaaTAQvTI$fU%7b(bPYJG}BL3jZkIt^~kJVTf=y@A)smsi(=AHubSM}ybiFBd;V zRUgh-cQvI;G|VjoSBA+!3ksIy@8Zeh%xB7faDTWk5TtJp>u{4=xjWOHosqh&WbYkI zYI5dp{=H>*G$1D7u}&mv?r=`I$=xK~WX8=Dxr!O4P-6ydEI`SAT$f=H3KlAr?Hq9g zggj`L^y^!DCykTz(uB0#fh+y*@JmuS9^Bpu7Hj)FKVnA82J}6BmHiF;8u+DB!jK8)Beo}B4u)88C!&>5^R)Y7`j{FM?BUMTP=2e_c_b6l6~JN#xO?`!kWA0!}ixW^z!E$ zUP0-Pb05K#D%jz;Az_kd&7*ly+N^H#l_W2viSyV__te&!Q`BVx$SzXNd{Z&H*x@d; z>AzPY2OKXRXW4k_za8D_2m5FJQtq~)+{+juJt8xu#^<0xb@l>R+SinnFfBQv^!uZz z#wj|`1lFQ2^VdX!Hy8685k8hcwNYjV%eX8RTsMQ-DN5VTK*5fG@K?c;Q4pth{5uV= zBfn8lM1CHfeI9th(V}M{s7xkYg07S+v_n{Ot+t?zi$j%?snDpWp!MfvA9|3zpz>D4 znSguQzt4q1LAN{{d!3Z+I*eGcFB@2mkC)cGaNp^lvaZ>*w>ko1?UVij1o(OQm934T z))A3ef*JVMccW#>pegSd?(x|-V~PAA{hSVQN6AwE@2-uN?z0vDuucTvQr&l+f|WLs zH$G+#haK)6%K^-b`I@=@<^L9Yg81R`@kVIXd~n8|0i4nwv3P-$NJ>uzC???A5x&&* z=|C2}7ndEMG7+N%K$9^4FNm|4n>mZRJQB8?qb! zd+SRvu0nFd%rFkL(03^dm$3T3;&fgPa`t%B*fip4n8}j3!qYi`R;0#39|Jf5c zRvXmk_x;-jZIqt1zjA0F?$3>!-PoB(6sx&VrGWkE;gk})s6!j~UB~|Tb>zuJ8Hkw? z@i76C!>{(;A(FQ2FAatdWC`N0=y;nfL1y7is>Q#pM7ya!U~?%>wz-yrKORktY5lqa zYc)UK3)|zPK-u3Rz0+n)KS)J9hjelZNS~!bt%gc*z8{EXXkDc{W`g5L`mgiOzd(KT zQej)^$^gTa9bZPNvXIEf+6lwOE>7d|&XZzWNB$MkgIscfJVf$A*~JMzAVQ@u;zYK| z*!ebHl6zcy!1ZrP6-*Da<=@F$^u8-EwyEm)Frw3Ih2;oFz7LPwSwmU4?iDxd5LVu9 zrTX@a(Ns+HnL4ePFGjx&)nFO0qYeDn2I<{I#J>u1-&9(% zD^AFYQ%>f$Ap^hwlTr%8B)l1;xgRuOIhb zG_lvD+Y*afej61StIHErYmXi>vorq$?E;gN*w8+Mo<}*Q`pf+w%SvK!{OO=?*TAlu zjXr{-hdyE{iOfnU@YQ@>=({%i7F)Ebh7>Kf;`wam#`SvAIWZ={hJ*dX_EPPHb`)u753&iy0tuXm@G4^ zrLg5!$-%`r&Z;mn!TykK=MVHI6kW?bZa|>og|<4>j7Z=z)Is+#uGKfX6VHGa#cAyv}3A1-D^AFvUPIYEFGYVzJS?6T0Uvk z2`UU20kP?3_w!xHH%0>Rcl2Vuk{WMP8gqo}-=USS4`#jR$nWl9(w@Xp4%LFfRnF#_ zC$}miQZO88?!Wf?IX0h#C)<6fr`8ChcU_kEG5u)wk2**i2S?ttS$QbluE%(IL~`Cl zD5W`xi9YQ#LYP0&V3X87pFSj&O}k+s#?@nD4-Qqae=leZiab$Y@~GjUToHc*lK;$=Tu8k>MP*yu-*w?GD&6&+%$V?o4*eb1!}bhvbufw`oOp z3Zfk<1-RZ8?hNg_JL=Z$O8MFB>ShVY#92Ie2@*v%pHFAyVb}&RDpnM5V$8!pbT28_*zy37WP+EI3|ojNI$k z&(RH5WEzm1i7zu;m63ieHv=Z*EH@7@OxQ5dOzdb0oj}ohO&8X!g3}Autk@iWRmV)lHyPb%Zra_Lwq*_(QZmSC{$ zCM{}PqVq~jWrItc*5`%up&$b;l$rHktZ{}F&2~jJy9QMZ!u1^ku>_5-^|O>(!oNMe z3OJaQyTdjw2?+HE0qjaR8Eq?V{GDorevG9Z-2cpmjaA3g6f@-oa8rC^AX+RnB=n%8 zy61v|#ViSi=hTaoK$eCzv3>q59O3ukLj12O*BWc&co$3v zBm=$dbwaFs^luk=G6%X&x=Nwn%OZYqA(ka~29$lWGB}EF_6Rja*rMS<^9 zahZ>;Mubnd7yUYwR@66*B8*CMeRNaMpkIN9GNx&$?(B>6+AewEs6 zja(1Kw(O~j#!@0bJAjQZ0|;+~@Uss69cVA>|8&-R4yMG@9M#=^=ZUWg9LZrGEpO#;F(KOW%_O_QnikG=&vvARpjX*iMutz%R%78Czgk+;$t zLAe$20J`IhNhc&~|1ZnM%qKp}mYxizGiyg6H1t}ifb4;*E@He_Zfnxg=b4!z#q|xL zd&av-%^FIs*o>!^o-F}Oq6@rE)y-iC$xh^l+kX?jdNqAt3Yp?2?eplFc5(*mwE95H z1JrAu*2E#0ti(fsA}u>XK4-T9j}#Y9#dSWUxe;`U5a|L$ z#A*VTmfAx`FpA5Ye79*8(k}1M`0G@lralxI0!0j`=53E-q9h*pUiq&I21lALvjsfF zRE5k!IEz@D?-ty)jVrgUwaOG^B_bN*8j+`_snt9AX=2vUG;-dEYsPWAFd-Vs%Hf0&*O$@8qh~JhXQ_}LD`YdOb3VKa1Y7e=}0>gB4ADCpH3#+BM>Q_z}mEQ!0 zbI@a!)`_fEtn$G@5+ZZrgCDFi)EGKUI9*s~wmhL1SpqA##+&hMq}pgO(!gNlhZQ=> zw%wptf0_=rfbl6OOHSbpWs8emsTTlEg*2map1}Df5_ebE0<}E0YfKw*YV%y z6pw%OnQl|MkD?Y~&g+~?yxkd6!K8sfeUoem;lAlvj~ZUu*yWwR57QImH$>Qvp$X4N z;{vEJnw4gF46T;eo$maj*;YmZxIDcoNWN-oI|8Y!t}SyrM2@hgGCFQ&<5vF|`YfEa zxt&h?$}V z7ggDDc{)+Tf&|z#RdD$b|itOIWt_oCz_R~UyMrokPsBI+P@4~ zO>L3LUBjIX?N$~!(w&(ewZ}2aKCMTK%8i5(UewZXRxlJwspX z#IWojOj8eRr?;Dqs*(NO#gp#in_-8)!;lZ2%|23AmM+(~D6+W1Y8V)NcDahh$V(Zp?b(q-%VBZ8T%=q`%QV62;i?*4 z5fo*gKJpE7BApr#0qCA;cwOdv9u_4mYhzMrSZ^xUD+oKah|8i=e-eMwv#Ws^wACU#ykYK0Z1m;gNhE68+) z&%yk5gEE>Xi5pCqzKhDqj-dO$LQf@nrY36#mPH4t!tBX2B=JOjyWQyK821r=^3<~6m=Q!3~UF*`AO1LUbWV&f-GOtC8GpK#fVzzB`Ir&Azq1*@0 zeyBP*FiEBbrxgW(0#4^+G0vpswT_9LiI4axvhS(MM#`M)vQ`m3tzuy$*K_Ayf8v}A z?gP(D>M@utWM(P&z6X-Xkw$@K1S#ht@~IbgmM4pV#9iAO-yh1>M++$cptIAO1VC-~ zGhzgg2>LPSftz)+@GSdO(=5=(hy(F>-5rPhm@cMWubuVY)|pS!>0X1w!RLM7D;>cx zRSFjDUkyW*5ux4J)K^}L@?9iQ)c11p8CrS<0M5Fx` zqVzYeI2xnXPf0GW7>C(Q-xZc59Dd7`gT-aHSaC^Vjp)(N=LF)#mFpQ9sEkp&cWp6u z)MGneI?Othx5u82+_eO~}nh6JVxw{XO%NYDRTOlr32o83CK0Rl*?6kCU2J>c54tBx7=SaC%HA#c^}Z3;qH`yb7#EH=26n9&Py1ekHk{eO?;k z(Drl{T;M9Th?Ef#v+#il=F3WsX|P|tABW8gVbBVdDKjv+3Mh}jDgjDDwbbyUn4PJS z9xj#;qR;C|*-6&%^FlqSW*4uar9>}Y_hdcUw<=z5SHHd4l=OCb^U3kZ;sTaAyo^GI zCS!}G+2hpi-ae(kfUK5ty@S?fllzj>59-jITupN&Yac;0K&qiYTU^NaeV~La`Xl1J z$&Hv4FhXKMtu0eb-Uk4);@}aQZYsr7rHeC<&?0Ya`EYEZuMB{PA0vNo8Ry|DKd7m_4zOK5x0VXF5Gtc8VSH+wUx)+!C)56 zO1_RqRzj8f$+;x!;1oyxb)^FAb@xnUZ1L&H*!BFR`e{BI>PePM8V)%%T=N0mZ~M_4 zW;>)TqsHzPcb<`TU2r0HwE)sfatDvtztbr40Uf2ee^3{GtVL7Mn!O6;kjk6Xi^~60 zkFl$o)FHKv2EJY8|3?8?nPOgGidDJf`|!RQO_rdT;R(Vp5QybLdL&xCx7YmE%H2E$ zdHK9}I1-mH%zZHUuE)G!bp}Olw0vw`H`YPiNr=v!Xmo+j=`H9XGRX*+bFq`D*3Uy= zPM|lWya;L^xz9L>3_Y@*-7Ydn z0B>v=agJBqP$4!>@vK5f`Vefi-W^T!d|uK>^JJU1Ox@n}r@T>Cp`J2lq)&YN0^~zv zzUlYULqxK{pYJ~>3sux)Q)F`)mmM0u3&WO@R@M02$obey#C}w(Q+m+pj@X1s$FIwh z0@HkE;T^}>=EVa-uw;&nZ?8LFD=2zHa`4l1aziXlalh!Amwz0LC>FmlxLMx4W`e? ze!qM>O-uV8=}1ZD)}mS5-P5Jzw;$=!W?~fQ8Wr(f!@*c>Z zQ@N7yg*v|w*bAs2Hg(}#GVqXasS9_Tq&YiihUI5EJ8TF$hs`5{YyW`yxDdZ&t+H_3 z$RL~`sBjg|106^Y^fl?FUD@o>qu!e78kf2Qv(MI3^-AfCu2xFYq(UK^XfXL)vjkuk zf2XoR==piN2Yc&& ziqbDdBf~NOlt} z|6_Gu0XnfpYyiv|zYdL}q7{<1KIHNyeG(|Zkueg=a;^J0D*ft(leTRMlh#|*Bisg?jCghj2p&ei<^rCFTdpzrLiJiVjZ=238Z&_4kCq{ zK&Z%gIRyS8q*DGl9ZD{HR`q0gG|f#5Sx*Pk0wheV%r}}^bHs87%&1>7?g+P^D2ROu zjyatj8$Md^Ln>1$EjDvXJ`#@&d-Ei3*n*9IxQ=tG#@IVZvUnBrfCcDDmmD{G>dgXu zYe5R-{zv3NU#}NYZc0#9Z%V6~#-YpCwcKK$4!7OB7|R#Q6UwcZRXC(+*yoJ}_aT*Q z5mj1f;Cyy@9joYP&Y?-<_w$eh+rK-;%V?)>4=SnU!oWl5RYc+&o#~4VJpi`PoRMlY z-ml=#SvksO*n+t=4LVtYSVM|k7!#kx?T2)NdUtYs(6dp~>W|9YCjw*u4i%~+!5wYd zDofvVQy0RZT_7j3fs23GJVY0?={nfgeV{lo=wE5y(wnXEJ@8-zc`%%fPesQBY*#w< zd|NxmPCvGm%@3a_7EWKfV!7JkA*gExPJYB6%adRB}9F59OAQrMT68_ zql&!43KtXW-pOcNby~FGaKxp=Az~0Vl^?!Gz}l6~D8&V_#u`vblZJnc?Td`0txTey zjt4;Mmj|X5#e2B7n1p{oZxx)Er5FJusr=Yy&!!30$muBA2~6W(!{C?JM=h^Hb1_&L zxuYoS(+e*A&h8^*Drv@PqEp+fKx`5Gw2vap)jN_OmjH=xUlcpoY7loMZ~JA6M|x2R zE4eu6PggzKSF}xY1xTmJ>kxd%(#@m2Be`pxLQjaT+!iiZ;gIQS_!BfmBx?l|(B-yE)30Kv)v6X)VaK&#>O%}WXvx!2!UCkv9N z2Q%;lG+O^$>Ot z>2un4>ha876n<6T*%OfLS8&sm+t6mXjW761@qPC!o{Ig2Na!-tsrz~7UuuK}Fo5wY zQ=rp(`GXtqIQ)4|(@YnkF%cnkNTpcvuW*K^mZ?xBALnzbDSPg8gQDhiz4)}+V#>ln z#d(b7Xdro*Mg~jpXqh!}dJ|SU^uQKF?SNEW)_MP6F}i|}dXx-P0~F}pE?Wv&QqQpJxqwTvF$^WtalVsJ2SYR3w= z4t`Yr{BT)M9zIR)EMwx$a=w@8U-_GBY!qd3OwIhUv@;xW9+Alplt~EubwdVLAx&XN zyd4Q@FyBs9hz;BiL|8Q)Pd{bEp>R8l=hBt;V5q^q+W%D@9nGO*@^vSdtI4qG%%38A zVR|WEBqwC4KNc}JCI{&vunqtC^aif#?oXi+^6TGUUeR9!nY#ZmBlSZCXfz3- zIdz#EI|1(-V7!-MZu7-IyZuI*@~^|H@u5s{PtGjvEsx$G{8a+kcevz3oFrD07yttYkSb3Chbk1A|ZbNDUpXiZ>4k4Rum;S4#3kCLH zZ*S+^8zBzuZzYx^-?!z#9x5#gsS<;~14}|bY9^RRpI+%Z-OhiiKi4~H z#!WuR700lsH**z$f8|HGQ=C94bR3{0aUm?!0qJY5^};zk2fK}a&11T2j-J+sixE^T zk2uJYROamz!~aMTsNf0^GK_VCW0`w=8wsiYIAo+ADWPRJw`+T_5V~Jwc!TQ1#^w=1 zN&v&_;Gs+HS*sR;eOQpjguIyAH!lKz^(Mk*`5LX8$I(`no-m+t{c`6~-@%mRn{UqK zxxM+)#piV3YXz1z@V8AtyqSQiOk)qI1fsX?H_H|EQhu}d4pHWOQ3Nov5xIcs;Z|<> z+s})^N%o&K?*-|ayLm;kgu?Wj8(@LQ_#XSf)MX>hkkoF?+3IGMkX9K2%_N4B4atb0B(!b_+cs11 z?sPEYYc_u`K|k2jK#AI2zGjvE^EIOH75c!`_pL!22jvnhw%R`qcM1BjabhjZ%z)UZ za3q>??7a3`w1Lv3#S8vav<#+4|FX{!zdy_H0Q%0NRDUoUdA?LLScwo;)S4HFlH@lQ zDb7fCO`9O6EnJba`zh}da}BSi;GM&c-80%M+?v5|hj{@XD1n+gS_Sd7&pg`d;se zIS|MF(JMAs^CU>2^AyY*o6W*E@)3;DRS15;z{Dk=!GiD;S{NCMOXq&4rg{5AC`?nN zG*He@*6-O}-aqDxH=-W92LmU0}e5CGzSac$dSZIDBVQ7LrAGJZC+A#hR-~r+fGb@|jT>Tcij zjS07u8=6rdK<rS768_K@Wo&;mD9ps5-zDl6 zPc7wx?jPXc9vf`#ydxlx2q4y}>ghoDe-0SfRVQ*R_LiNkf#`ryWzAfkk^R^@?QbH< z3Nlf}OcD{*4e=gAu440TMo)&e2gyWNXRZD&2S0B!1s(}JuTaOf@X#c_pH<3cObzC? z(LD)5&Bq37Lj5l7uWK-^cpEm(2Sh+}t{=Jnln8VAX$PJu7XWdKcL~NB zAdba@N5l?4B~59z*5K0EW?)Ch^v}5pLGwzd#d>`6Sy=xGh6m{qBU~mlxFgiHY3Ds^YBA!i z1dA1i9$p47uLHNYL&3#{b zlaQb2^*ztWoybyq&48Q=Z6}w?#EATv17QEaM}77mp|Se;<%!++DEXe?Truy68#{JDguZnZF-IeYIvUCz{ zdqdowzaB~bNT#dB9I4GEmoc(~ik#OJ%E=c@ozX=XJ>XbTAGei#ouZNSvO^yHI)AIK z{9T^!eexPqD!+?;!&f@xXaDoNG$-NxlSZ4gsZIVmoBn4lz-L7;+I->kzE4WT)`T1a z*3dEx1*dDaEM-e*f(Y{1XKNcHWvDYVBQQVNhDd?s7aTu%++{J@b0ozcx@gv)n z(>^V{c=wde{ivHpBNR;E_e9^Hq?s>t`su$s0Z~kSYOw}V_9IktrjRzg zg^>M05I&d^kWp50{tcf{o$$vAZ_aMUMCIE|AZK>fov&E_;F;-Y(qX4Hw8PKyT>EUO zwu-aUzu?VarFqHF7oxTLS6~l(_pt%0l35Ci4(*ODejW%ECG#ZER|d9hI85Vt_D^A-^fnC)>k*^ENn? z&9@paS;_9xxB!Ar`CD*}U*k5LC45a8X3wTM*ZjUTmYT0{K0`F1Jee{N8X144>`}&D zF_=x@)1}+S8~M))U=zqs2uS(zpBv%Ss|l?uxt8*j2qPucM;dx?%5VGZ)B^j8>B_Mt zT%@l@&tTHFI+}m+hKT>?WVWQ%Aer`rHO^bGs@cz81(d&4aKt6q__N!i052$N7AKH9 zQk~f{7BjgUgff(Oa(V@1cs2jr%SAA#$HFS8q+{+7dPUY@){&MrYw9SsC$=1Q(C!-3=Ho zq*Su{TYd%701%=^MrGmd`6y9F%glYPgcfJ@1cm%~E7!^vyk!#XYvauo_T$$DP_Vjv za7$HY@~=*%Qb(W+i8=V%;eix+UU#~;m0ty_9Bp>Ch%+Z0PdBYDN^E!}< z-pCigw?uE&0;=6VKIlk7*t8d{;Q^lpz1`=$qC*||EkPzKC5$Q4)`6j~@m2_zcv?a| zBf6{-#Qk#4&Et`1?w)4CEef9XN{`#OoQHq<=2xbhcQ2~?X=wIYcn4-RVECPM{f|yd zwONCxDltE}ZwlBQYit{!FxGscw-@i#W>6%W=&Le8S7?^XBW~P6Rm?WctFRK(9wXkUwGKh(p@NU$9WtdwIr+W}tp*3hwWYeC zt@Y;<1#t`QDgo3XAO6Qdgc98S_MK5DvG-i=Mx$d3PVHBhGrQh}6}32_jB0;CwGSxG zQndR(c+8cm(dOt`dK73DE?fCDM|OiO-`H)cN|Po2+}aJ9ePziTD2Sk>&GI5`(c4Hy z)5hn4B1;3&d}R>X@1tNA*XXYJ1mY705ecJ#q8k=s-M_K!pLwxGb{TDseWf{igm+Yz z7X9ip*s+Jg2!4t1Mg^HeSIKYgPfgjwE*ySlv7hp+v27yu)e!?5BrKhjYpy|SmH!#o zX;U5~bo7Pta*>%)!;vRBr}2+r(t>o|wfZ^4yzDu4`$@`p4&&p1`j~9lq9U)Z6;u*5 z54h=>BaQj9D$RktyU{rsCaa~^{FAR$i5Ge%42wTA*1Nyp7@^ag+Aco1K^<>V|5n&j z-qwHqi=WUJsI~R?-2{?hFTDg213sMt&01yh(e}0fW8XJgUp)xwzTSKZ?h;$Ftp=65 ziIz)MBhunD#gK)V$mIB3S75>K_0X#|ua$wme@#+vidma-Yk{bULkW~M>n1JqaIwy; z+6X$$8ivPvcKbP=<_`B}5#%Seh;jkq-CO3LLupn#R%Ixwy%?P)c?^PsTTF>d_fl&y z;Uts<3y%}IjTkR^Crmkm`14&Z9AbbCn`t%u`BQVIczDm)V~O9i&+6*MP5gNK2ST2K z->z6HuGk|N{kTL-@dZnReMDfvM%m}DyfFH6Pa0eafVd?ej^)%FLLxM`Cr3p*47arC z=rzsP{L9DD9~n6Wa)4X30)itD@8_?2(#$~Lg@foCmGZqq>%^-!5gU9JivfrmbIDjT?yWjd*9XS#sbdaeugU={Ld(_`-_Z8*u;h zpBOcL6vmU>9IRtNTgsFkWK!k@j0{i;)QnP>j7R1JNrqk#5?>18UcRc+FG~b|73-I( z-w5HR#|7rJbG!Wxvt;;2%wi20OrfLJD{{(-rH0nf7D{7Xu*LaP(iYBtz8WNT+m5KH zqrEbP_Hex@v>>J^sNQXH%9r|BpkC~7@rR&tP!DeUg5TkBfs;SjE-zXPlh<9?`t8Ok zX^WL-%9;*iz`HAc*3GIiOjpbv?_j%oR7_~R4nLBn=YhNf@9*SSwC#cGN%!%8s)5Sse>?lkd6m3H(5>h>VPcWpyW|!9WsV73;zMUaozJ=XTsXmH984&B8G_f7 z6?6^@^sRvb_?|;viLaHCfW{TAjz1kvV4>yI$XfkW7H;69wQiAAzJ#r4Th-sJWtcVo z!3gI$ovs~%g&*UiT%aC;7waAS>?)QX&_(PMzCel2Fb4S$DmXDjqP}~TYONu&u4$!$ z({AarX3e%;(x`|YMchpa95gE!^?(!bcBwVJFvHfJW*}Sx?V}7WU`;!DI%gflYE2;^ zP${$+GrS+$C2rl!FN@|wCu%hAi`Goz?~0I^7~qV_;_d`4Z&Si5tTv4cYhNahbbj5* z5ntJKa8;}-f{#LBqRiB82{M5NC@=A9`|_5RNxdfR%2)HSVS{>?bSXg?Q|HF@#k((f z?Rb(TpN5~2A8oH~+jjC;o6B!ow@@dIyM)UO;@;0Hk{e(IA-ZU)(S%u!Ed{bXhf=0z z(e%E_JOcVgU#TIf|7;!dhw=Q%I^G-9zs| zEC1sriRU$0lVZ(p3oHKm1%Lc6$AlSx{Mj33j-Fi>UDk1fZrhO^H-;YLG&D7sdWei1 z^uwh2uS8XAJvKoah~o`A;0vsvB95I2M^p_@QL+2qf*_^?7v_bo6 zC-9qrIP@{RLXnx#$!=*(S-Q1W_Ax$D(RM{dR=?jCb-^2x9c43*X%>MnI^1?i7bruF zK}hhonolNYc8=_!os6N!#KR_|Hc=SV>oY#RbS#VBG)9bJ1c8DZT5AC)_L!I9&kpJV z-WZeTH${5^@{HLeMRoD;*t+y>zrqh}3=~5x&7q4+u)$B~uR>9{__FHzZ^}KMcz2~> z>}4#&oVjP_&hNg^EJ@qbs~qwds}$kx%Zv)~prmQ-Sunc}ab%Ma%ryH~q%dt~0E4F$ zVTeoyav=y&3__n;LQ#<(Bpzb}IM(1FG2!tNgzjtz2_aGER8&jHy*(P|S~#W2Yq)~Q z2Z|%}oRLWZ7Q;C-Wvt`0fyBr|AEH9S;&GfPmdT-j^F5jmrSQMFDh#ytE0Ne={Li^sa+(lC!dNRl|-+&S-- zpsk<3{R|1)xx3AWLe(H#{0bSd`z@=e0wg7O`aeyoe{ z`fB6T&o}zTG_Y2G^^3W~omJV}J>Fj_abZ0Xtz^zJ;|xikdYs7}hs9*NT{o-EFzL~* za>eu_MU9~;7U8W@A4X*Iic{^(JmBqsAkAm(I9~CnIwfvhyp+|I+!@g7Aky+D^qMMX zGDkDlWA?@nOIxa@*Lp+wBY|TUoaGk9DU7eiIzt6)I*+a0jEhZ<0>w;w|M$ zTZ7!#lzA(1O?`j(xp>@$|EldI0en_?h)ED@=_i%8BzbxJ0)TJ()|Nf8G?t4G;1k1P zYuyxx3|T-FLbkt%($fA?7cDW)=s=rdOLg7#J zf6Ey!Cp%adwq)n%m)@5X;coZ>_WWg1a(jR1g*eXX{+g9cHc*17DPmW!ivAE3wc&=d z280EPYNZ7dZLB|kwcqcgDPHu+57S%NeqCoQQ@Ubh9FPIcW%Rb1;kC+ z(_F)|?z|xHPXA|tSs0zX^iAD;I3CFx+7bV4Wp)KIulB5?rXG7KsdlXmZ}2e9pfWkK zsv)O3ng07f7ju9QPrBE)p6IAVU8235hE@(l+?pI1B{k>>(Q`}(I$6-9j5a1O{_k39 z1&aoYC?Qc1%K&)D=MDEe;+WUK1XHl8qit16ti%J z&BVP215iaNUg|3WRQYyWH1N-9g!9*`wp+@MlJwIPQkfq@8StB&+a-eP+|J^zg5TO( zVZZ<5IZz7#-eSel`I<@UU;CznQ&K#l%X4VoatFo;XfvqqK9*QiT=@Ig{Qsq*sM&Sb zcW=dKUS1I#<3T%AFe$bDl%8U6-d>8YZq}>lIX<8s(7Sns0){1%0)K6yv@o`A#n{`h zv#|}=X8YWI0z*}zRs%kEqip;A96;_k`tya{8T}_Cj$cm%^K6_NFja@QP&qkaB((zu zC=RP$RMhb7pn~Q%Lqh7({Ts6+zV}Lp90H2j@zfWwkbBQ_vi~%zGyKe*)bN-Vh%AjQ zZ8$6@WlyFT^$A+o&?inzV*YU-7`vc;PK#x82dGHDHaZh|ICjW(Acmrru-k9-EmHyf9VzvBt$yI=c)<2TRB-=mRS7F0c2P} zx|;7)eOxI5I;S93$_sTwha1(z}q0Y5Lp;IN4 z+WMtiPH-jQA^7g!=?X&@OR|u-woE}e-+l={Gl3-SVBlKdd2+HMO0(EukzSSaDGcH-%2uDHSClbPMBdA1*Re!ti{$P zu-lxA=y?fFBD0o#Z#uqkr#mcla_=>E#M5Z1tG=)4-36OWQJbDND0QEfy3RW}3%apb zEAE!2c-sAY|8R0HS%IaqOe@Rb&~|!a1z)V#2}v<+Ke4HSP57J#+Lkjon&77 z+96f4+18xsFb#?GLg`bYA*b{EO%6eK%8)q>#c*Dz0{Qg|$tMxrp@np)%J9sAH%W62 z($AW819!XSH}95f+FreByN@#N@JS9hVlRhKbKl zoqa#slHw9U>IpiihV*=R+*fC)S*DO`;?K0}@(X7l;?dVhBp{{AjOis;&$8t4$p#uR z{;EX_TG`$>>I@ugd#X}zZY8%k%t9@;RPjB5gdC%=j=8D@sW# zi|yv?i+@3kqDwsy-xh-V37m;UQ?Sd9-np0*w|VDR@=M!oP(=#jkw%`p0cqkNC@)H~ zgDHE~Zp`rRE~LA^a0|7fN~OyDL_CunRx2H>>7kN6=KWkdSud7DhigrKs*k5kc%bJo zJkH?cJN`eKzACD%whcD8ySo)DPH?vZ#ih7=aJS-8G=#QLtT-*M#kII=vEXh+gH!C} z`_DNSSu0mrE7?2mo_S`TnID_Kw?057&hWzl<}t}X2B$YQqJ@>n>6xN^1_xgV6}1s4 z|LiFEOK5h;>E0eivz*M%WmyeLj#$SdyXr>5y4QpGdCfUhDH@LGlFsy)w+wsAB_y$w;1C;6lrz zWW*@=W%RHaK&FP_ZDtfjUwQ_ou$>Na@8K?;>8lFY5s8Ka#4<_&*#?U66iuPen(T{Gs6T5`Y7 zOtPU#{MWB2NR0U;bTK3oOObbUXt@Wg6>4#Sx@ly8T&DT9sNCj#c^B04sGsM3GsV zjKvpg7Y}6=D%A0C#_Wgu{FD2jz;TL=>z-ARopo@R%k}0_4fh}aT9#&&`-AD5EYV^* zm#Y1p^IyJM3RPpbzXyE~E9>;Nj`L-i%N#bK1chASu!!A-GVw*(;)oV&V?L$~C*Y6-8vM=b^jI zJlkcE9o74d{fF?DIL``1QmhOL-h46W>a=Qj>kZ-NJW#zsRf2nH3ZI7H1Ch*kMH5D` z3!l;~h?m^Z7UdyFj~pr)CO3Zot5paJ!daUUL>)KxCU?Tj%%%LvoYS~!d6{BvFMo-w zw3*tMg)#?p2{9%EV-+j0S#>JNM?cLG<@?_tZ@vlu|0?mn8uKzj-$I=Vsfy@4Srlmy zK8hr@(1Jhr5i$z6T zG>u8n(lP}OiNobt=G^jCb<{O{#iNu)B+Mgq5r9po%|cjHYd9S!&fobk1IA zQ<5Fg-%$Llg3Y5ZXN@rknoLdY0qW$&OjZ~stfK)ZxB6yp;31cY@zSQP;Zt9FzN2JvgwPc2xJ76>6AT4+Ll&$j~FFp5hUAl}1`ko;YA(PeTI zm_5FY4lNUdOc5|@u}GWm49k_?pRc89m|$GZyN-byXps`ABdVhc^SV#Sh{y2a?uS7@ zTx5%cTO_!zmdS~{j@pc--*pv6M0KJiQn{#wW0fZ&3GyF2F2$5^HMeO3u~^C`m_DB7 zf1!||BcB!J-N)~FhvXT1-}&EB({ONKaBXtu_>p0Y@u0;6-DQUhJ8OoNz+?it%|y(D z?%IEBlNR04Q<|(`^pbkjo_wWN^)lo zXvY!4r2Pinbq=^xh+M_(?~frb8fZC|kXw_t%b5=y1d&?Fb>H?;6eTtNYK4NwtTqpV zds}I{e~=vSXHn+9NT1iAMM>{Oh#9U*lcbB)kq^yZcEs$g*tzx(ps>C^ay2A>_ECiul2$bUi(BUQs1L5r;FP4wr2^aQe4jB+yf@h6l?4$the{ zA>r8PJ989EI=*#bOWI>J_hiM&^QOkEQ}Er}Zd)>d1OC5S+Qh&!oFdn9-~WDDmT@Ic z#84EENF0{4vy*KT-OhrYn&c`yU9(=_vVfYXI}C1?lZr4z31o>Mh#OQqhBlRDZ6o0C z1X$?DDHGk4@apTZY$YW`6!S|iL7jmC63LNFDsUPoU9^#hYU}#+(55v>VqLs`|RxjYOKI7DuM4xd7}i~gNVn| z#H>4g(u2b_zZaPm_IdgEo)mfi&1(5g>OLp1IJNTjR*;O)`d}WrzJ^^im(rc6++^`E z)f7@sovnC?A)=1S>x8wqld>e8-bDn3Kojcp1~p3VX)v1a{zXfgot|X2ovAsh46%)* zRhPuI*zKv`Ho^i%5b6h?lg5AD-?yH)J4pkI6kQnR23>`R(#qeOi~JFpfaQZ+Zq>3b zA?;G2DYff>Vjs|2n=J6k?smA&ay~f7vTz9alU*JD!HLC|^GY=<3x6diVQa|yYpv6M zA6~el?aj(+l6QAplXn7^p~tN+Z?@5|x-%O7$VuBc~q1!c84 zDo62~QowUiVa-jeUUX9U%$$_+Xgz}FgyB&$ct znW=o5R9j^|khT>qDXkMNqk3Y>Q*mtcz+w$`=$0b9Jl!51=IBXjGD&3Ip4mr|2PSMS zqMrauD-N|QecbV9Zz8porZX@K3=g2;{82In#NF~`5%trSC*#8emdo#>7pWZ!YZZ|1 z2*a6~dns!z6?cJa*sH{Sj_u;N6hFzv^2P6fc zs@>8%y$?nd4hY1Nh+5^CvGqO|QU|4%y-SuoCNu;rMf=|3P19vDH5#H zF!gK0LEZmu%25PTyTQh86y&&5Qcifa6f^H%_{r^x5oWy&uThPYwg^mF6JM?Y8XLE1 zEZVH%q%upTW%?zh^T%m#XXYY+e<==+b5sBx#W5lj(>eU!1)xBMkZd%V5o zwjCP)%Muf@gK71QK0s3rj+voHXF$FfK(0K1i&0Gw$uwE`9>m!IYW%vd_%hNLRvWE3 zdR3lixf&JjFd7~6a*Eu&pdV#m*P$}%>y`%GBi^*G(nr7jlpR0F&<7II3s>N{ zr31(>h-Ok^;1@Zu+S_DjC$wUWGg`$+h+=0>hvpXnK64xKRvz}oIu~I(Af!oL`)Z)u z5p8R8i;UW`ko15GWq4VR(u-C;dDo~Slr{`e@1fUTdEy}#u2Fw2NvVA~R7@o-GSJep zclxSR&OWntq+GvhvL_`3Q>zi+^Ms@joPQ2zkJPrZLB_Zt?_jrSmY_jDr+$bCam?_a z90V!Nd4jZzfAW{khg-#e+V97{{YKSe#cf55&#XWZn_hB)eNZr(FV<^Yf51)zCiMFW zFT8>#GmTtjYX%xY)@=}U)|&L|QzYsWP&7vLyb+k!tua_L`BqBCQHv37X6}Db zDqc(BRRd;+yHwvH#&x0SQD>}2*FN*5h}XXSs`^%drdzT4k6ZS7*W6gVXp5*0-4!TXy9fmQXFacxaHf&u%*NCg&8ryZ%?#F$d!_tSBLv}4<^bwC4M>pEY_xkzr#@;f%jA&!t??|z z#FhN-5hNMI#K)?FpehDM!l8Fe&zE~%?xrI&-3Pq6UUn}#Jy{<}H)>K+sLuuHl71on zXd^vr_>2~!08w`&*`VX_9x6Cq8=acdGktw~H}go*6+PvTN)q#~?+`E?@DpQ-x$G&BJeo&c=42_rxh)b9cr=0mKS(z$MbhIJ`WcHj}Ag1IR>@o z(Z^?lsNeK^9h{R=xyH-o6mhCR-p1ZX(Y#vPzj9B=L&>nGe$m_`^@k(SA_XmS`Bk|k z({_;PkoUUoF-_yXBffyq@Wi~0!1vOd!byr*i8-Tti7fQTi?o&da zp;f~YZy#kJRUdJsW(ij>AMqJ3&F1pMTK@X*A(&~?CDQHO40Y^(cwmWW8^F{9;#QO!%NUH810&U-m3*Xl^=ZWrk zA9s4kG1!X{q`ch=O$-iPX!KEu5c7F?Ue~<1w1C5REEa z`OXkp{+Tu$BAd#6OY0i9KSg#nn28;tdmfFj?# zkel@TQ6^eEx^2ZXqu-=pYwz@Y)0^jvNo%eM!8HM6> z%XXTA=i^Yv)I6-YxpCVwFKEVkWGZ19GSe_|v#(#W4h3hDwLg?zMO)G@649;5^B%vG zs?L$`Di>e~g8ecWkTIEFNqpOtMBt01w+ zIdA}p#XMdyX24a1GC8M8M9?oa`;GD8=+9?G<)^2cUw?Ui>0g-$K)djZ+(Ls7)mJ*| zXoma_mLd)lTK|bfIn`Y7K*SUpWpmy}Jdj*~s06a9%jB{hYxSi7*Lc?5__FuU{Qt&v z1(;ZiD785>b5udsxr$`BLKBfok(o_l<6Sa`^H9u_UT6#={v?I__7XdMdC^aEpR%xE zbl=w@`*e$ul^d)mOhI4w-STC@Me+Rw+r`gsSS_rEj&RVw1Bc~KP2Nwawd5^t7GP_q zlCRfSAc3$S|KT0skD>#F8g~VuThv4c!=8}-C6a^RN+CW=RkJ;~z(jB5Fy<0e6?&`8l8AXLIole-~qe*1- ztJUb~u}4i4qCb{C*7?F+4SA-dLn>wpwS=@k>U0UszlwJKzj3zN$pne15^oq~X(rEJ z;NcmS%Xt8pbr4bmkRlJ`1{PV=&TL8@w1mCsv{t2^mQZaiMobH4FW|OA8|-77t9_QZ zO^1APTg%VXV_rw*WK)%4Yws9a!Mm%a@S!diq+%)Z{z_feS z=TCWSS<5u_K_E&B`lcyxvg|%L6{8NkxU=s0y@x99ly=<%;@Zf*l3XG=oLcO|2!aEk zp|;akAmx-lIk~Uh1SfWcwgVq?)G10pXvfyS6j?6Kw|Qp;Ltqnq&e|Hy|FJAC=lOP& zjjO?7Nfe)t`Rx*vTsi@m>N3eot~2GN9%DJ`fQBWORR zRnF?6T6BY?PWdJ&lJBSf=&zv#hih5D!o~!j#^PvKhaFa>eEqFYGuhrMo6eBod$~wq}3R8>9~?_a)^xm zxavIP#GEwSLOZ2|6Pk%X7e)^A9lJ^*5r$62)9&!fT-^~RgtXz%%1dk~#j=XaxC;1= zeVjK4d|?_4V|nwLPVq^e|GPWbk6^}jmLZ`m*K=^k4yKDW(Ku1}SxA6TtQZI#wpcQi zHf6G^p>Wl4VU$2VG`6;woY^N@7Q3DClMqOPG`qRazoT_yAXb}X5ReQNbq~IwBZF3- zcs9FDj|a!!*#x8Czmt<+x3^5{4=ItJEYd|$NRj8lD{sxdv_fk}uSQ#DK11n}Sdy7G zV)#KJOhmtOfLJqfPnsK)9D6?h%lBg}by%dK0zl$rW)$VNGoE%4FV^LUPs9I-U`OWFh;9nwtO7CdmR~Qz ziH^HkKC`mUQv2}^#5^7I?IT@9%wnh?;W5zidcG>lASCKnIO&^#N-LwC9uaTeLx2Q{ zD0D*5C>V~!2AU4VzDs@`=ND_M&%-ta@lwvCk2-C@*3iSiG zCajpk0ZCcdqx{h&B`Ir_SgM`r-+KppNe^FQaim;Bg|Ppditd5 zj=q;m=a_ZHkSzQ1)`~+W%gbr4v}=R3#?uu_&k8T#L^KX5{B6)eHbYt}v7ymS3|KF_OmS0+-18OV6ro%&Uj(BAX3C zp;BZbR5&uYI;ifG2JV9AHdYun44|%co-0o^bbyF2v3_BbZKqDx%ZouOm|$Nu*7W z_%2}<`Ac*cY1c)%Hs#xqN(Fm6@t*3|T^ZZ;o82sl_hGrHs>2Q*Q`m)8R+Hu47&qo> z!bLqn_6i=??@RVg@XNSYNPG?^`z`?B0tw~T~d z8Ri`a=#NoOygg`HM$Esa+{BctzoC`uJ1Zhg_VKNA6eyr?-l(|>hWu6tM&9w<#ABHa z1wAP4HQipZ^1l$@+v{bnB$H_!Xv;0`du%pZN#m1oM^?Yf>)n_{nj8=rQZTPw+!T#+ z#mvt_EMN~kbe^EGhcY2{jLa(Lp5DA`Qf~@?!9jY~cSGiT!FUTZ-;|J`LmO1gs}Qzf zI>f*Ljwr2EMr&tOUyoX(AwQm`&o*P_$ANa0cf#;9)nawTBqdrEnM`~~Cw?rB9#c15 z*Wl?r+FJ-B5$>R4Zmo&lO^K20GZ{m7JNE*c%H z%$T%e;qMdeNh_6$cT5&$Eb2`3!a(oQO%)1WEz+~Tp&@cX6-VA7HCZCXqQJklABYxs zL}SqQ@V=oxPGJw)A=XEAtHhSRDFRv1taE91D|5*>jH{Pl*~+#WtQ(>M*e%;O1z?g z5dPsvofAq)Yft|bUnp-YN{FErV9jL-r0krr%tiH9yURrdQlek{ZbhxP6F^8p1!5e` zSs?@v;On!PCO=|4zT%>wTetUo4`>>z;~;PkP!eZ1Bk+NS8Vlwq{o1Dm)Z=`jh}XrL zB+VXpDaLq*!lnr=>EZ6z+&dJ|oTRp+8wVFVY|^3jEYFJcpEzq>cxqZl$z%~1O@Tw{ z{C@coyqN(viTXrb7f_BK6JjzBEy9-< ziPf^0!IMCF;(aU=IHys^k?Fxj68V9Ms*mx*Z*X6?JkY8k$uh0!FG&;+)60Ok2A>GV zl!T~;-?r_in`i1xV${WY`~~XvQUD3Li_!`43I2(4zLpTT-(av@$FDC%!wk(5rS>X4 zyi^$sHpN%tAL3x+0(`SzBgSqA#yER6<#DWAL*5D6dp?_*yAz=ybE2S5=&{$yMBr`i z6Vk0(+VL95=|9lny~^y_82`FHGvM&ccl0u8)Rn`d3-R+mV>v07DB})*3uPIGe$#%B zc1mj5#BI$|*34TqvR{qX124ZWmwBnR*mT3Y?1Cm$bbq3!N?C3gInM2aDtPMsIdAj+ zgP5Vr=fXuOu(4>7acMnDfWuG_dd5GU$eC^Jh_cvOI6!rB+7$(#SDJ#jitdH*rmLKN zRP=H=(6#=mMyR5<@}h_LmGI>bUVX^AxXw(zyeyckS0PF?%{1Nv_0NhBmNxXiCodtC zxyA|S>^G%}-4OP{50C7$Z*ahuH46VWcBtqxuz@2}+zCpb`9`$n7~z$p{ULL*3$?u7 z+p1Lb%wwOQmA^Fk>XpuO}j;=UMXs7^84csB`3)n{*EhUD``W0Uc^fU5ua7o1)70r9pJw={$V#1ANic8XAg(HWx~$w>W64&b+K2ycp7tVCa3ByeKJ?A8q2|p<9iw ztN!Ts%#cuBUZhF-C-bc?c?wiI%x>viW4O?v&uSI+K_Ke`O_y$b3H#X!LRN@C*a-bG zFQ^nVAN0#9<~>sDWyFfT2-rRn24b?x(^t(%ra}+O>Jb~j7bfDPwP6yz7fVf07zS$b zYFFX6FTDpOe+`+0N#1Nleo0^tu7;6czpaemD^e}2wA5NiLIDEd=~3@J-Pi~%L%BPU z9~otK_0lha=@<3CcJ@rArAM*dS)bR4S5n1K`qx{v`%;QX-7M z1G>!Y(rZJ5^a-pBaFCfAQOUgYl&q<>S^7u$uZ9VGhFgi%a8!`Ca@MU7x}_ z@m{mEuczVRm;-?#ZhSD>cvk8s*B;nulx%vM`v*5wVefK6jjO>`gq=o9dv8LkDalx* ztH8BxAxj4^Ne4yGmiTzUY`-5z-BrNZm}8($;KpEUYO9Qg6hd|Y!{fpHdMXqQ%f>>* zI8a%Q<728Y;_8-^PM)q{SH~SVetxvZ-s~g2rMi2++UkU`Axit#cu2KxkFw*SqaQ{Z zUvE2JHGK0E*?S~ZB0*3qP>y@Mdl{`R$1v8i&b^f1Aw3iFt$ayHKgKzB7Cu8VsoB}lUlQJBOBz+Y3{9p<}~9pFC^sE zYIImd)bU;Gcgwq4gq<&5@#kQNDtEY3=ck@2&(y>uOg3H@J%1Yw-}%Fj8?8hyV`DAsnqKTumxxn0ai;p~eRo!3m z?m%@7=V#7q=z2Ap@z6g>Y889Y$0hLb`r-%Z%VqZ2fd$pr;_|%5OlJG>WUG_;l%}x8 z`4Yc&-6SL}Esf9N2d7buv{EpmaH4KR(rUiT9`!jwQZZbzTfv_) z?ES>y)^Nb`Q9@U&=grce8z0rD+w$)x)$z2Gsg{lvFNE-I0=afuH4C=j+dIU?Vb6#1 zho%rUi*xkGA9}*%Pc#TmmpA=aN8-|!Jet=n#R5N7LR_k{%9D;GKG}03Ya~yMVHCtU z5nb4wKa8eJS+=wK)D~5u9|Q>(#BHxd_ZK64$LW&(!??muWBi}x(7iXfpK&ui{9`{J z?->o|w;bgG`^sh;)7S$s;JP|nr$sYSVK72j%FC^>CT_B zFhZ@Cc=jm|rTSf^Cq~%qz{BmeLb7wi2T`RA7y+Osq&r<)+)#XO!czo(XDQ}4coj_0 z9m60cq*eNQx!6S&XOU7-oI`QG2Wci&v?*A>)3 z+{$TGa^*R$G%g&#V-($QISFfLk;3i3cycwKc%_*b-2P9F z*Xu=@yg~tIl1slcm1%hq&nMcUh&mvUCh0H~Fdt*RHWr(XLq%9k6-*U0abat+H2!*r zz$iXTEvi~ZB0#ZAyh(CHI3Hi6SOAl%n-<752*1@Q$b#l5On&+eWS28Xi?A2rJijaK8`10-}(p?>v}Inf2(Dxlfek#V#nd z_XbFbEJ%nGiRz#xteKOqqL`C7agTYRSKs3jkJ@cROhC&tl5fF8k=WY`*jg1Q{l<%l z+-BYrABq@Ilk9PJV+4|7MiR*QjE5@DVHs*qC_a^iVjdMoB&(xj0qmrZl)nsi3iJ}mem8twM+50or6=3Z11so@ zz6QqgTb;4@+mO#B+ulzqY}I?C+B3p%fy0@#OfI;z@hSwpi*!S?n&dXpJudk&;WlKZ z@E6W<2U}*{&}K;F)$W6QdaXRIJH!w8XKtn}RYyJk>;o|ik*!swAa=lCvEIgZ>?gHt zE3gtFRDkko`t3tKg`H8<=K{aeN>yHEiP;Ttor7~V^8j}J)U|h;Hdd* z_Sy>)h?Z2;V=8g=)*4h#@zFdskgnI5honK=Mm(1cS^8^T(sXT}G2qD%8Ky=RPzBd1 z-IY7e-ryp$;80aWL2bpcbFj+tE0!|D5W{nAR6&9EAjnof9ZNrV4BYr_h;6}f6i2F3v;@oi&~{s zMW%Z4q6X@sBPsh=0qIQYUIFR!-fZtLCK<5L;jUOrRLXutd8+%VH!0Ye7vas8X&)d- zJA3y*bg{V^C8Od_t{%^Ziavzc>3*1gnNaqk96&Dglv)Z&!%9T8tRDHQhpmhSsb!>8 zkZ&x1glg7|*Q7kXG;y=ZNp=#opn)kYtXp}Z19cCyt0Tbn&vJ8F6%cd7@DJH_|8Q{D zX3!5@{TyzU+k{|fh^%ma^wS%Z?F!0O$aT~oFxAlz$|wW8cjLEdW2C0mR)sn&W|iJ3 zPC^ik$qKlbqY8V)S`%xVPxZnd8#8BU&ck#eW&v&CxCcjrhc|(3W79Lu$?Gr3bjT|{jc&wx%Lz|s5k^! zz#IUdcxs>l6$0-pjt_+orWpPjW{h!89OPbfjcq3_b9Li0R=h-Ru2Oy2GoZ zQH6KM&KPYq^?S7`OU-EVAi3;IjLq2nfYpgz)}l-cvGI@RoTx)9s4fg92LrwvAj|6p;*;)CWH8+pl6J`pV0jorfydS*2&MH?}}!>6VUax zEQ3S)nIa$m5IUO)O2&?#)3xwq4qSL2*8;LQYx0r=S2(hB9Tq`RUCByZj`LNhuYiu2 z1JbCqbr`ophiY!cZp&(~alsh%6sCFaRk^5NkS2G#&_~UB+1c(!UQ^Z*0yp7WX=rfi zNAeEZCM2`SGxWq`9|%O{z6P$dZHYOuo7o*!svl*j?NfYf^G(tiIe1XtBtpJel_&HU z67;t4XLU#>Rx{(tC7%#W{aMw9a{o0d@psE~E=|%w2i%Bl(o3RY$^g^o5$DRF3Is3i zEk*8-pt%P?5Au2E=2)Uq9PYfMSxE7Bq8S!vNEZLyAbaS2i+otu=%?!Ti*jRTL$wb2 znZctYP=_u`5nCb#T#1mS_wfs|%%sS37?P0j9NmVEp2k#li!CPYj4NX@)+nSy62RL^9<}2 zDX`g8qi;g!2D?P^P`d3<2_Vyl*r62313X!tb@AfC!>T?RpGB8D*;0xsR+S3Y4<|%F zDmiNyHW)Y7|Lyf}{zDunk|EaZA#)R8>Rbj*cKAI-D<0{M9wVJ>iLdjqa)wVY+lUecEx(sS9p|>a-db`{WF3@}2tr@1Iwd#iIGz?|4j*qw`JAZY4GYx_^W|H8 z=|yv-GkksDhhDfn&A%SNBOlYe8o}PYS*W)LiU?EsQ6;t# zHrwy=F03a5JPW~jxWxlhdMO-UU+zq|H?1kih`cH%kl~Qm&P50ct}_~}XNIjR?034G zR4j3CsbE?DtqAugTu?G2)Xdn?zIw_x?JH73d~X{3dp%dR1q*KR)y%sk50j)=luLO} zXHrpYyu*)|p6S`T$&Z!qp#)`h;}7_=8E+lW>Mc6idmm+Z)rJ9U{f70BK7zl zDG-pjNe$GH9hc4CN=o6d3C27=TbqQc0(kGf{&7@X691@-vE@)CI_OG?eMxfVBQ@AT z9ffKaYw{hZgjOy|RR}MAJD>xLPr;gVhW9d(g*A)#Z-+x)xYau}YmPzH?h296zY;a0 zpt0)j{|Wp)Bs!z9k?gdI*5}I>0D}SAj45Ww`8Sp9uWzy$Ghz<}sJ#hF827D^=>Lx1 z47%YW<}121r{+A1HmNU&MCKuvz>+usPqY$FA*5b% zeg!dPyzRsdZv2A{Qqj$VHvvPrB3H2O3AT>(^n&*e8V#&r!h&2DL!a0?xFVYWrOsm1 zMYcv7*$WWXFvkve-Y7-2(%7G%-qPQ)%^{pJk`tbdh~8@1PUQ&K`~NbniPcrD*e~8T z?!mDSjfkhsj`c1CaF$u_=27Vv%c*=kk@7a6hlV(CHEgj$)rKjR27RkfAat1 zvd&);W1~`SB&-Mf*ej{drF#Fbd#ooB&*<=A3`sMy1#c*e`L9e9JVm#4HmQ3X19>hg37nu4(Cnx@jkMhB|NM|li+}Vb69Qb|KFc7a znB{MS*G4$#hJsocG(-rL@En+dVMCN&;&2%|%3iKS{2RGW0YF-<{9hPv={fcMW z>Q!JS`X8N3g_D_`_qw%zixz+R{_EKM^-XxG5$&m3FRbD-mWy!FTB0A(X&r3`l2ZFs z1DQ%gMZ&F%d*DHi|BKomlfmZ+H4I=--OrzU9d*G;dt-a+Enm6ff(+Jee@my;++0;# zu{Qjy`Zxn_hl`I>|G6r4RTqywf^mLQ*PnIu+-m$MM_RM96#HSV|8^>H%|3*wVZiOX zUKDgjaBrp1LJbL)d?z~MDbwIf8;WFlTK4n+TM4rs zI3I(H#OZ$+cZj;Nd&D-+^|=~w;JaY3xnF3$5qGPWxm0}Xsvyv+)i#4DEk9Jm*z(b2 zp`uI7?xT^KrdQpAZ$^wEii|bD95{_HZVFVxqo7x6KzKxUg)e0v%J^i=u+Jd)v|O}6 zI%YC8k3@3!+yB$5=7uNu-2@FS6-A@|KG*qlSHtOh#ly(nPRe+B@cu2GyuvT;NVmEBedHLqp;O-wiE~G+B%^H0WVP z{6^+R>Vl`%z%P?Jkwm5TJbZkS#&KD3xtidKQ%lmq>RZ|2+|?)UdIgnil7vWTOg><^zZm$rMRl+~={=bc= z$AItPL_TiC4kpqrAp*)~i(lxUWS?qH$7WLyggW5s72-i4&UvkGq?wsADc*Bwl7Y-> z&44V|&qbqw_J}{W-vHeJlO7i~J>LmMy^(O{ThZ}{gEXr|$0Zv1v5QcxFma}p(!eyx z@7_jc^V_b0dfl*)$vFu`7RW4`f7MZan29r+Nu?=RK~i5r!dX5+Lyci_-MtX{Qu z#YH@JOaC&z$u0a{iKRZ`-Os{@LrME=oM4nGTz6Bq?Ose}E!G0wK;Q-E;J$)H;DOu< z-xnK;CUb|tdm5s#aC4&9&C#cjx(F}zFXh&9@~DDwG7oQoloz`gT8-Iv0w&?17pR+RUy9Po z2a4~_uV@~8gTgvfB`nrS9X>gvR;!M+13IB0d?9;r*)u@4zLsI zetSe#4Lwlpl;yWRD<7v5~aOgD|QF^w5xbxyL~Q+NG$!ydHf(a%A;urSKjE-s7%Rvh#;< zU&ulRy^N`uV0!6z`!H;g=|z6)TW#=s@T1y2&zR_O_C(mz`PZm{AM9gj{v4f+5Q;Vw4Zn|U8Y5BW~X*nPx{)`G?(Jm@ti zKi#O{T)aYqu0&ePuO=TKvrXoMDjK5z7}2idXDHv*p?u_=5$f6f`X?Aj1Y8U@Hkw~O z2UF~_*>cC?WO(y^(css0+w}A~b}9U9c6K2olM#5k}}4;^7u?Gv6uqmjDf4 z1J$akd7b9`&^*mD_+jlk)#-aKITbh=*d;xnTuD0VD2>qlh|-D53=~7d{!D%HClTqh7_VQ}A@<37Vgqg z`afMNzwPN$1}(>^$wRF+4WJ+4k(RQ@gaB*mfsc^jOkh6w->h$0(^)gqc{7A64dinN z9@RZJ7>AA+c`9lDvLah<8R8{gY7MdD>b|L( z>R3d^MveQL|3*lNq@-lnOI>n^%g9&Xw-SqetR(kXxUMciSlh>)+e)!itP>UmZ3`pW z3W3Vmes8xwP=8#=T3=2MaBB&us)n%Qq3Hv|K2e&m0*lJ?=L%*$dTC*oFzizzw9QH6 z-(qkH`_S@0*~NC7VFzJZcN3(VPW$!M>I zZ$;(U-9kM zgHr_coL;#o>$zTEpSx$NWqEI;mJOj^40u)@`QT*TVnHI`)|oU49KJSfknwLQi#LFa zw+Ad1Uv~d&M>%Nwl+DpCW6{15AYZtF_)NY*tv;{Ii_8yfPB~)=D0=11Lp&b6v^3m_UYeS|T3c&|!-e8Ep{)+1t zFYFE{H%NnSuKRk@7n3)vMS6u48EhHE{U3S+D2DVV4}9`gu;DO02c>D(nn`rZPx#kQ zK8IeJpns0_oTpKs1Po(Zg&e{|*%%Zm^00BO-DLD&q`CsidvKH-TBHJ&TDh2075ic` zd3d`#WlFJ4W{=EDc^(~{RCm(Kj-=+czt^=3ne6ud>FMBfReSZxD{96(Ji(I)@Z}8I zpf{f*>-#-po7~00HyCI5zavl_u9S535{{bi!MIp=AX5r9v@0A8yPn`Zr%nRv7JmZ9P4uEZDhjqqps9D zh%8KQ?4PpFd+#yeNl-;`LzI;FBZl(y2Q^wko`@v}9<y994M)?h7h&sqJ~q4%Wv z{?+U^seJx0^X@;718?eylOH;}a6xsc&EE(Vzi#jqvF_n;1jeHybwB6qd(YEEdhNYX zN%$|jt`D7S0W))8bYb<}Y+Rnpx>I2QUg2_%DGo0QP z8&4h)y7yis&t5E-VDx~>cjxc^(OXc>MNsW_Ccq;5^`nx!v|eS-YCcRY$n#y3C;#gg zYrMXNC-dyx??`ydub?42PZ+jKqhEm75LBy?mpz#vQb7IwVb`&mhR5VNKWDE~B8{9u zbW~?O`-z$AnatmEM$Q~$nJ|Put?^TIHCTf*va5A9zGaDYI(%WD68}g&6M7)zJ_amo zw)1x-wzw}z1pPZaopClvJlE1~9UkcEne*NiZ1(L25=!Gn957jaspnmf2&1EkqvNP$ z=$^9Pg%y1X3YB!Gv-z%KZaHiyKrX$~n3zXhRoA^8`+>8wcSYSa)r<51ss7K{6awB@ zK*lhWtVGB4+n_U0Lq&0x6Q$W&i{k7UFHq4wlW%O3xJPL=Sd+qH#YCGG4i@XXN#iGE zT_6`~1>O5J;!v^Ng~s1$4WOhnMbAH%fkN(;D>}0;jUJ6>q!P`+xsA!bCQjvL#aWR5 z!_!v>Mfpd2!_wWcba!_wosuF*Dj-XDO2>lqQlfMz(ybs3i*%QSba$i#3etJ? zEw;vqC=@9NdecvMyV{`QFPdQYw)2%8`sUooO=-}pa_amKCxDJyQ;U}kH;iPP+&L9P zTV*$_5&O82WNx)Nr-^FDJAQKyWR5u#ecP}G2@diu8QAd!+-+FSo)*0LtG&Um!FH=- z&lf+$ye$=b0>rx_w)vDwx0NzyioEeaR-QdEgaKLAh{wtkxbf_)^KJ__O8T@@^Ky2! z&y3X~CzZUu{#AoKJF4MoP^63Of(tdicLIeq9^~z2QmlM7(B-dH^K5XCvm2LZd05r* zG7mBVX@#o>JqefkiP5AKWjZK^S z9Wb^PZ?-&tW)t3V5is?U6+4@M%?f}Rc%&WtcN1nrdUNpi`p?fg*UdcBT8$FxJ`AFB zLB3x#C4rE|d!|(y7x`&>4uyp$3ipn#g{2$%#<2!^s86e^S^UW)@Y8J!6s>9T3Vp4j z2w+hmW@6T4YJoiVR&0DlN>y8i$+X_EzicE`sG~Nh`f<>>arg2o>fW6X^vWRlHlvF- zxX-2k6-YER@_QON-=I+S=Nlgy;w!iCPWpW-_~D#=an~t&lY*7_S>$r-?cyXyy>|R! zC|{G^E$Du$*6m~EJiYs1qU@rMYK{6f;j7S>3Nge<#Wr$3mM@eRkkk*9tSA2W*g5($qjBDn* z?Fn*Wy<`e}inDwmezIiKy+*hul_gP;OVUw?H^)b%@1yHmA@pZXzlXOzVuc|Ik07bg zh=0`+MMvuN-PzfVitu*hiE*FGfBp4KdI`B0O{TVC z07c1sA&%cdkjFhfn$*a<>O6g6w)M!$ZiwP_`0O!OUg889^i@l77iO2e!5CZ#X)aqB?LRWomQSMbbY8TyuK%7^hhNK*n z6=`D)*N9BEk_mN#WiFNC7*^W3TFhZ*INJ}D4kFQWzXvyeNqGsUC&L_(OVc@UameZa!GUV$2>heb-kt5_rE;D-+*FnvhP|o>`}q zc`e$DemB(0`3Xl0Z>6)Iso1JM%brNw??_Cm1zJYeum&d!=iFuI#QSo3#V-y3kLA#tfz(?CXIdlv;#ZtO?_Q3za(Bd5yCt zeDSJzTZs0ylvpCFbKSq9p_#+D>8#G?yg@@F{~?x6foM@Yc~aR#m9A%%jQS?^;OTlN z+f7z;N_Tf8Q$ON0y*!!mWdu9#lPY-=?dE9o9Z>IKzshLAj^OGs+LA$t&?^NgTF?0_ ztT@rg|LW!JDPM?s?+sHwr#k?DFo)<}RO}|~nZScd*3F1k^KuhC(hNc&@Y8JT)*h5J zUkt-B8Jm5Z+tyUGaeXzj;Cfbsv^wzFa;^_6FtZOgp)3h}3W~*T`KlDqcmnJ+Li(dr zFdgkk;{`q3^mTm2IpO^E1)8ZxvbR1Ur=eF}^GvqTq~oe!kOp&!3nM{nldwJ(7fqX> z#Jr7w|K0EG8vW7>@nz!iY&cEr;F@3$4zuVRKbgZ8X>Y4918!77ulnF@c}m_S5|X`Q zxiS6a=S{S<5AIEe@V?hlto*Oi)!0xo=)PE{?6YNAi!c?d>eb7eowbE3g)@*7j$)ab zu@_E)63hFM$I%p)yLzTy!?xm7cGSV7>rQV8FEY?^AKn+wmq7Q(Nin@&3Tc?OmfnEvSMqu4sQL2VZF!3*_rMh!ByMY7!X`Nl;^q z%cb?<`24+1msS;QudO_<~cGhMu3q(4aGS}3dIL$PDhLzmj2xBm7Tc;cFE#wF!A?QB!r1F`(|sw* zm_Y8AlY4V>I!HJi#k*gy4IL3%=}?)EnQPAdt?xXCHhu8sN({?8DiTSekzeIUqLgua z+{tb>m|UNa_?ZSug+?Bjn%$}iS7UF?xi(MDhK)y(B?u2lN-M~XqmT8>t%a@nN)d1U z?1jpz(AB|mVF&P*zW0N~k-Ix*wkl)k5oP1zemEiR$Ak|8uqezV8_A@+8|FMZg8MrA zszm*DqNlkuX0iW*AHMka91FlIX9lB>27PGmM~R%S%#q%ev+@ZFx4e zChmiZ>^Swz+ob47mNxf-X8DBv-p=b3uy7PzVj;hh4&oDC+YO`*yb$H=+Y|BoW9duE z9}SDwLoDz5x<&!3i2L*%s)Lx$a4XYpm6c7eyXz-#YaW!eV6~N?mlNrcr!v+pk>2I= zdl8KqH-ya(6oDu0d)_ly9-Z5%=;Pv&!;ujy@ds-1cWGR!XHa6m#d6g5PBxzm^bQft z5`*rdF5>V;sUaM>Ej16zflX6Z;4~y{?gJRN;!4py+uPKMhGae&sx1LWX@?Mau~% zBsLU_K1mKxNmiL~xfHrsG#eO}B;}0go2L~EXq$)-f7Sh0V{@Sn51y)g*;x^-T1=@ZDKW|8wNXZ?`8_JFKezuj$^oxfWRTEx%h3!^cF{o5A_S5c3;k(&3N0Je%Fbt z3T~5(KF1v+&9T9E$xmDP{x^fexAch}?Y{>=o z#=X$2ot2Ua2xOix@(-wdF?~pm+cwH1?|~jP;1~-vM2QRjuKX^9FNbe&{@gp1HK`<6 zRqb$rKsZmNO#ujaHf-EjRQ%{PNhL$U9Qxxy<9@i#Ra0AZ#$dYc8&ze%mZL=#Jyj3_ z$lYJq2ixKq%7{ss)*eJwT=Iu!4)6ZSVQ$XNiZW4dL=@-mvH>izO^9D{U1$H>-eH}p zf%(by4``7Bsj4_jwGvVDGkY3;5Ko&EkVN)}lUGljf_dH``f0!VpUw84$Fy}yD(s%Z zoca#8RM7kwHoeeGfJ@vS=O_424d~}J4j`vVu3T<}E@%p3T*9iS1W_b}s_n zfs?--XTK=wt3-{>xI9nmYA1Z3utk6BSid6A{KO9PL6fjAoAAx}wTfOq#Q&5#)`2s0 zg#{Os%yHC(=@d~mb>!!DLzH;iG}%+(dIhu++Gomy7U}Q?1g6}VS?#or{pCdg7mFPx zGGd?i$?tj$ZxHlU8)dO`{s$#y4fz1oqML;`fFBrwuKZNb58KUG8^(p`jGI@fX(Ja4&G5-ef~6Qyl&H7<-tJ0^a{+9L|88@mbZUu<8K z|Bp$yJU@it#o$0N1fQ&SA|CG5{|bp$PhNbysj+=X=a9mElH!IV_5ivpM^BGk&D2(V%nH}wGAbkDXC9xtJ$RcOOzL-J2k2dhg%;Skb3gtM3EGd~3wP}QxF)igA1;qHF^DYx# z)YGB4WE{u>sMg5~hnA?%b{r#S-p1~hjmpXq?jH#E2DxFbg)tN`=yuW!T@quC3|A{T9kF>k_8D7co(&6B$B^ z9AJ7fnA$h%i4ytz!S$FOLW1>GpXToy2C6KI?u60n)ck6CTJqPn0DXv|GWWy>#`ue& zy)LheN0u0`*F@qsj~lfN5j(pb$lng7*OFaIk$4i^Cy;3QS6-rZew5YFIIbUR#a9r* za7`lJ0OQ}NB{p7+_fWGu6OY9HDZ~~UnYJC;_vb`534q^QxqW!$PH15foo<)z+ln(3pok-%bimQtF6TPDvNS zb;Gd~-gI7QnEA8()SoWkQjzkE7}7j@v%-0Edqw|o*SoOk^e6Xm=K5b7GNmRI`Mr*E`4E!wGFw?9l-OjW|6>wm`j=97{ z+w%ii7N`p5v5jtqs`6?fX z@Nvu~>W`zslY^XhkG;X)JgEvVHtW>gFfZ1?%|c(L(Od9%l;iY72J8ozc!%uubSi)e zw!eqRe@u$eNQ!NtOXBBV#7hpvkjJ79A-H_;_Xo%=Xm59R%4oxLZM`)wGT_)>nXR4q zG2W97dk@<09kP=O7r(;$83|O@DLqh2va=6bj?PxIfmt_W4F|;DLyTU`J#^fSLu6|{ zVV^y@YH zL9BKyof%p6x$idi9cn4OgKLbXVsf!bd4!Z)t-XmuLZ2AjOD?_crz~Xe3KE#hdap}) zsSrlS*S23{i*d7xjUZk0t zXN^Ag`2gc%S|)0lI>+aEJUM?Jg;5ig3~mm@Ltbz`>l1OvkW_WL6 zY3EJSkhgYkkbd=rC>m=nlY^L8VqVzYhtg!oE0OI;{8&mTiT>V3UA5DJVSEN}i!Fe3 zk6G$M(C_FEP}rL2ESO9ELM_EcsUhA`+?O^R(y-R#gS><=R8^@bHTHt&uSsw+9N$`gFXQ!$Y91Oar_3-0t@I*Fa~B%baohh&~x)(SGSj??i>qT?7%2 zjy=2DQn5!LyTAIT!nsm-(YIw3#sfzZE|PZ?QEh1I@#IUh0%KEj;$#V43F4y8(+*sV z7+ch97!4xaY3XUB4fm?>n>O2eM5+EMnPb2uxCs42S&}7~y*CaV@xq#S>{E?R2v6vm zr%Xt=d~^m;vBegC>Gdrwd$YDW(xiTt?y#~)Lv!bkjpgZtSUlVoPHl()kkv$fpHRD; z5`)}8St5p2k8P-6{0$+l;@L9;Rtr$xnrZh|(>Tf)?6fCafQ|ten0RFx#d>HkKh<9X z8ONd<@~ozJ`LU*3We_Ymh5Awu{ijgZ$Q&|4Ii))dw-@Cw$V4UivcgqkCWL(De;fO` zlO6XVIKKJIFBlc_`EBve#dXz9(>H*ttaavItm+^rN+RMQL- z{1LJILMgNiUJ2Gm*@&*DB7%8nQ^|1cE;t0b0X9Zr0?H-izFld5H zW$G$^V=|Nr;=2K&iP0ivgKj(QaC_4B(LA)?u#+|2+ABRFT4dAs*}XQ*xy%~5Tq}3C z4>gH4$1|8-VS(d5_f6leWuuezWZs|GZRx~PK#qZ+bZTleT~f<xYP*^fU_xUAii}%Z0Uv2V$oLx^@hS(e=Ld*LKRF8q{>(TrsloE`GE8>Eh}b)*T*Alw`cMPQ~#s zu>X(PbIYLy*r^6VBRuHnp3}lg!tneOAMMZy=rxvm>>d7l_F3wvUo$nED8kiudHw;1 z$!VBrc>VjD?>}AXRTmy(cGaEGxtwIVoiGj#{Jwv*GpRSVh;a|WGZzm*Xi~DA|60oT zOaHJ#@ZmqLo^U=kqW6^Q@angLzP2c>W_ee+T6JVagZ9QVLg;wB{9o)qReSIsi9cc( zn~k_X!->D&J9-}bC~3MUQdn)tG@9G2(#ESMq>)!oo>B${?7xwA_$SFY>Eame7gAbe zH|MpOT6qSQ27i9a28#1$+m+Ca9`l(NT@M&X)&>1})4Ff(djGNk@z1$~b5j5mM@~o9 z#py5}Xu51b6{*^9C=u}p&Rmn~3BnSN9<2u?p;*)b8hP87%qb6l(%}VL<(dWr`X36^ zZt(RKvKV`CZr=9;O5cO_{&7eakP45CU68PbUeIEXQC3f9Qa{=u8NvnNyn(7S?op8Y zPYd1XRnN&oEB6WSbqh&Yzw*A)}v*FO_F~ZwG8k1W&nEWuT>h*!5>j5+r@Vds97$D*eY_!*=J2X*rQrr&n|ID5H8y+1K6WD>{W*|_9G$NE zAIvDcIlXy2enIjK-UmIou)tce>#1%?Cu}z2Wj1QAc`{^;iz0z$XW;wWlpyr~1i{W8 zL{gIC%rywvmHLd!y))KLe=QI0xbfY+Xhn7H&@W}%XL#q&L7nTg!i(=$t(kTk!mvPr zS+lL{baRJQNmFh6=QPtpVeBG#ugbz|09G04uLT9zceo%TzV9V4ro~ZR0-+%OP&G*W zq2(3FaDgB$6e;Izk!%4Vcr`M{I9#n&%EMi8TM~;Ur6hP?^ENTn286IEBBoj5=MbWv zZxpOhhN&xI;^!vft7JN+ybvlznjX1k?T*LeLOOg)#?YYb8-CdE`dEpXih~1{8UW-2 zsD&5InE60q{nY*oAwcvl0tpcpSiRN^q3fQ$HDQaJH;V)gmTOz9|O$!$^I%{c_qC z$T;p$Cof3-!G>bgKBb$Od)Jp5Kg%Jl6i3YRlL3rT8bxIthN>KehopSKNR~oSqFhC@ z(|M0Kv>$XRTB!fkVuGSTI*9}4>Fwa&%Wsw;bd+5RTsv*O9f+kzPco{7pCn03#TDxD zFrvu>!_f}FI>{W?ke$8c(y)w(Mu+$ZnwoSXz;B!bLZ822Bjn(dVVZ-pt*!kp1@h?f ze^B~`AVJQ`n%=}Qgs>0p&O7V;S1(-Xc^O#4Siwk8`(Im@^jHCaBSSI+%su%nRH>MY ztVvc3#yz+b4*kmMuUX1DD_o=OKjK>TFBSHEUAXTjL9iz}BH z;6+FQ96=uIs%f@^U|3gbSM3--yAv`90+|3IcGf^?8Nl;u34v(efI#Z=2Cc(w|f&Mf| zWA7(lBpJPoZYG$=vKxII8vF>PaC#V3IAl z<}&9v_dCcY0LlmRlmkZj8U)_ob_OJk5D7CQ;=4haIlnz>FM^b3mF^WRf zSo27Ge3XR!L?W$UQN=1hfEY08bep=>Pyu-(>I!AJ&fW=AuM3XG#a`zHA#ByA3t#Akk0$8jy7Diya85U8bh6;2SetyInTa^a?3Ru)^-LI@DAp#5aSySF6 z3-&(Tl14o(3G)qX6V@APKarg0D?Q1%$H#V#C-76;`xjX`X6$(JiQj~+ah*Tgv~lfC|}@9D-$5Y-x9I#^b+T8$9KI>6^s6X}f#+i}E=rEs3@VUpRp2 zg6imH_~PpmecKD=NvAY(l6EEBqSf&+r9rq6up=J>B}o{$oB=hLm>%64qB6X*K+7!A zhEauf_f7a8l_1a=~NOBcYiT{?hRWa z9Q$D>Nk*cT6nl>PDlKRXhDr_v1w;vCa9E=B36Y)CXdx{3!dVBsUYn8iyuzn)BM;I? z8e!u`yk`I=)p0of&Y4Qhrx1b*(*Rd00kID{kXwvb%`}0iPyu+HXh`7=D(u}ZPNW!MWTTEOedwR4yW3h2r(Cjf#llM*4 z;Et-v4^|z~4BB_^>#g6 z$uFF@9kTi=agQc(U=32Gvt6=O+^_;j^T`OHM3YBALZQ!;X;rvTWkoG&Z->KR=OGMo z!{sRO^lOtfG?)-wMqoUIvYe7JT`#L&v;`=lxsthai;n#K+IEPsRx|IuG!NrMs8DY7 zt&VW#Tt4Y~f&&e}_0=O7n$JY{5uxZWriD(F?|!^4qn@)5ko=1U>_oE`a_zl&fZW9< zt(Lvm2C#2ok&57o*pn-PYu=q#h98su5jzaYlbm&eldlw|^17!5Y4`n!`2mNk)4mki z#EQ*Fk`sfcg3eOSb{Eo^C(|6gB9cAgn#;PJZ<|8J@=(g5$5JDHsv8tSc?u7Jd8=C1 z@jpTT+*`NY26Ix7B&s0t)A%QqjnMX4h5U0P4yW9aLBk!9u6^Vc9zS7xYB|~VDhhFz zU}Cse7YXBLY_7Dw=QrD)|2_#TvgJ_?ngFqN=x^+7d);282!&Ra6{D0ry5?G@+`=wl zW~jQT@Jpd3v8;v{pL5b2P9H2Tm0USQ(H=@fYWu2~-W_Q;bp>!cRij3(MalB|RaXd! z@x5rX>YF`yI*`9Tn``Cr;Y0XaGNQ)?y{RfGDn-G^Q_VluOT{$4QyZRl(8z-OY?@+6 zSFfp`L52dCbLD9W``r0V-v4<40vPQEoJ{%E-r#Eyx7qjk5)ov0JWpN2&x|iDJ}*c? zE3_Y|@H0cOj1!s)jVk}lwVWY@sheaE(X-($zZzwkGn9ze$|rwj29wO=&#%E>+Sh*f zvBsb)i$g+|aQTq3A<-lMOjp|j-Hq+5dGwn*onove_l=p_v5kZh;xIFomAE8UBy%x8 zgAF}2y3w9O_Sy5TjLVddye-*{+@3{feCbVu7AW^0fY%yJW_)M4rY^zSq6q|uKDx3h z63FE)l#)7{!J5H|C>d^oIOS0J;5@K!Eh0#!oQDS)CC(O}_dEwJhSV-1D#AG0rV+v+ z;HBnU<49FTUNsrb+L5PS^sa5I+iAfJ(XFNcSH(Af7kM31fS2>K{vjRk3q;Kw_%xez zfgJ+A1(^w&=9@*lPD)5buWSi!c!I6@9v)_j(#^%T&DPK1xvV?36ZyprET+G;NrEb5 zt7;!RUG%fbes|8xm7H}cLmiVF+tho|rUVqgSRNp<2uzU1Wm%MV-S$sRtX!@*Ig zwkQ);>eG&Kg7@B8=x@;@a1TME&!S_wL#ReU?;$QCN1@#2+=VQRe%QB=8O-yKS`a?n zs!SGShpBjGOjEg-|&nC4cwAP5bLf{N=sU z%~rosSuX;dCidB|@u7_UitnTo@~DZukHZ7Kr1oZiaRqP9Fve@c2a@niMNP6v-n3x* z$sqHeIQLp)XN1t>H=%^ct$d~fn6j{C6Cr#cy}G<-rJm+kkhgL8-H9nW09u~}@2%V% zpzsPUl$&L&OTl1O4D2(|e7{rSyqO~RQWUR5w^CozO^&{PKuur=FbRDPn>##casrv# z{c{eQ_Xm(ylQl#vxRsK*1+UKZ;tNGr9EfA3osaYUZNe zYkNcU9coIuO%(?O#EVVYMgU9x1dnrk&3MB@&G2U7L&;;~1R3*q)1c_Azf9stp)nNZ z&;I7)t2FUwm2)+}Ga1j+U^OU*tg;AAtTpsQz9_G->qoe>d}nMY0a}LuF?0CU>pNj# z@|ii|!1}w0TkcQVh)KqPQ?bo-7QWuDap>ZTGo@UdT9>|$q;Va4t+Ec7GXHKIf8cb>!#ht>$n7Q0HO)hHXn2T;TBkyM z>{ez+dUSx~KqUNB`3XBUII{3cT%Agv2DE|EirgWVZk5>{|DF3AL8Jl?yhv8+s<@RW z!U2PJb^VBbx!|!L?DBD_RIm3)`y($F45CnhPqN}kc<>ebdjg6adMLdq3~#~(-xUix zhtZ=gRt*b;hs(K#jv< zoV36tW&O@UWn&x`MY9qv(G8vU$WTrNvN{lUL`G~4QI5t~My%ZqUC(@6oBr$-@-6v7 z<4aJ9teCIA`p)je?=EzVA^JR!`nQ0Yt>Pqxp@sUsOVmaVDavwX4vQGq{Gx(~Y@ zo>n!0Y*uqoa5PgZFCxw&j8U%kU_QlDDn3c6@}o-`opGUiwATn}L7GRQz5;nJoYo;w zn&W#_bADAcHhx=3Q85`*-xK_^i?ffgpnH%;gU9LE1RhNLHplr44ab@3ud`d`ZalEvR%?YIETB(df~*u! zV+5;93#%hT^7%8L`#D3QPsLMsA>O^fR(yj9P0V=f$!e|jUPuy@_D=#W)7IMKonk8d zvbOdGF*P7nCys7*hQn`c32D&t!-_b-`p17A~SaE-l>Y#Eya61FZKPDV# zLW%~+L2?9&z z!vu#rNa3ebq_q)9?rBp^H57#u^F`L`R0Z5|6r+1O?h2>+Q@K`RVkHUS(k+XhS9 zsdSzKIG$J*5v!CxO?8tRSdOQZj6g@pP1w$D%=vM7wVElsyFpcXhtzV~aeo&O5b*Q> zroW#jW-;>LMj+OHc>#si{eJVAG4a_{FN`ofG8_M4a(^4up7!2yMjGAh;!!M9U zmPlz|ckRB4ot)2AaQ(`zn72*%1Crq>Bp_Lw|GI9+eZt{P;>TaV-mP&kC3YeH#^<&H zZZ!B%*N!iO65e5yLR(q&|J77xZ9MaLcxTa;|*R`nB{lgM0u|?SX$a z9f=J2eC%HD9=@dXy^0aXv`?)-+vF7DaF1AQIS>2ULEn%e(0mp2;m!IcRTCKd(J;jAal&PaB zgtx+%aFu$zZH%BD0Nft-Kj!{X!Q5>2?lfV{fjUg-O5eak7|Q1~Z}{v*Qi|?4e>5Cy^Omib+=)%11hVt;1RBm*QpL9x$ zsmPdSDGCt-QQrw|Mez^D((5-HnVWiR<<2NTmgEw`vx(djg)6osG#-_~N{jc;U2`vF z+dqI+s*dMR zU!q-ttuw8?T6?(YCbAi+RP<$%NceIVYC zmAHQ`bP%$ekRNs5qUD;P=STj?$^LvtJbY1}1! zVazc?tsGh{5Q?AEXK8^NNck3RUgvC=blxCiAPwyBb^zkNNu|xNGA1aY+41w#Iq2UHq@@J1ht&L@f$MI19D8Wj5d3GYO0Y=t$n63xp*o|T&1|3hS%$(j z5d$zB(b%GyQokv{L_W7!P-YQSf}#*Bq^Tv3p*^|XhqvMMD320|-bKWf2-@F`=R4I4h zF+czht@zW)O3>~f%aLZA>fq3N*+%pVI%--6o zRU^hcQro_9zPfpnX(-wVA|k>^bNKW3#lrO0*QQLHN{G)R=8~mly+L3VPLj|j=RDfb zHQ%HT1U^z@>A+qR^O6y#cJ=rSweeIw+a@R)wg_{8a|E`bUk4_ zjB52Z9kItC-<N3|%b4BfrP@2lQUei|O>T z{FeLoyj02y6YE!eZ12nmxcHayQ1SQT1xAA=@3PURb9?34JKSqxxoVdL4!ZYPi3Oqq zuv)Z1?3{ z9_%-@I(Q~>MjU^Ug+s_P&_S*nS8pnt5W%^i%Ec!8&nwKENoU|YC6au(eT<-UW1tr; z0-nt3vYsHF{IhL|he>rUvvqvb-puYdWgP$7AeES7p$xY`pceilpFqb2v$BD`R2V&j zx#3#s@a{r+o$H+X?~ulocPVlhE8I=O%CfRky(#gh6VEoM%bQ!}Ll>*3t?w^c_q|K9 zS>6Cx-k_#%#3*2)@-rmk$84}B4kcqPGhz=(6mIT~z#pIieT9jeBNFC}w6NhdR39kg z3yi|aoUk{z#w$o%ZMz+`>jip0 zfE`Qc7iAJ<_DF#Z*5ic?Dr}C9WchoLo)1UciHY~y@h>Rq*l4p8f85qZFD!y`L7`y) z=e-ilMJQM%s23=Aweeorj+7{qAb(ETuB7nSYs*=c##kK+%NK#?^2w;md18}jnD6Kq zm`lB?cZIlk*cple?!}lx2`D{iY-67{vDWl(V8uaz3Laz-#cyykO{3&{Q-GT8!lE`n7(;-*0A`HT%>{dqA|#99kW@8M*itUS zIDI2QpSsbZA2!F7MvMfR!74T7Amz{2<0M)s3Yzps)95Qx<%P^;)G2nITavDwB3`|< zo;ZU898kzL+jxV&u5%*Iz6Wuujo-O-PMsOi%*r&YAQyIRxkOYsX8Cr^sD2?5LmUk> z&7HV#M1T_p8!i2T6kKi?=4iw%f5J_IM&I2cFniL1@9w*_YqNs*>!>@R? zpH*o{>7S5zx|@OQyn|WY!>OYv^(x{_V*M+qwhe0QR0}SB)u>JF%a%z{{8*Q?FA+3m zOnXB+d*2<+Q3t#y$bs+^?3U2Ah)qn2SRU@zC5@YilE?NSmzK8+ zPDA=SA6^F>*QDgfHrJAm$rtt$NxWVABA*iQFxKl0i0Mm##S>m@R64osc6~w5KGN)c zJRF!#zN#3V3?o?EqpLgF@)uUcqM|WiCmaok(BsM&{e2QT{%r@#p>s;n7xfcJ)tHVZ z*t_T~APn^g8f%QKxR*N41%OVlUiYaZ_BC0Dtz)9o+y3H7#=%ijA0*fCLrfJ5;gC~%rj9F2RkRknoHHS4!_n6=#8C4d5htYo=IqPF0we;xTr}@ab=n1z_liC?l zhB=}48DwF#kAT`5E4zSahZeQn&0A>K>+lBjd>4oMqI;*2oY&>=O%exJ)2|5{Wg&Sl zLG$UHALc)Yt;z^c6_N|0dw|@<`of6gNM1_*twfRStW9BUTnae+^YKX_`0hdofnZGA z1AL6sjOHllCHzlL@tz`)^x`Bj-7Ea_u8G7cY2qbT*8IBaY;!m~c#ySL?%U>zkQf)^ z5ce5poKEtJa*H_Qh{MewtMs&FRXp$Mbn!m2?0QZu+n{T<`*VrMG*`m@!G_A(yYLr- zFFvgPiujOofMIikyh?!5R`Z49y+~p(bvr42>hBmQ43>iSt-F+@TM4Pu&ELr0bcEFw z-Y&q>D+;fOr}gOeuIP(!g$fSYIeOd{`n7koT`)%xRWd5#)CL~aMnJ8E9dhy!oCBgA z=rzF3vKf>!v}vvE;LMK9p@}U3X7D0Bv&Xy+X7vZizM&H2Ug{=r4SeKgXQqCy1|2YQ z)FHbgpu;JCr=i94Q6e|Oz4N_nGy4MaY4qb@Hqkwj+ZZrRO%`xI_{d>kM0L4S$Zq^TO)k4|2}(vUO() zL0-r!UFI-M+OzsKah)Z4X}bCLc(ugeeusUnGs#tJB4`Yk4zCC%wyd$QFM_+{nDc;~ zlJWP`h@+9z;`a->NIp^<%HtClrHFC=$c5(qZS@DZ@Ng%o@r_I1^^a_#!s0-YNz#oh z&zyt|KwF&q@d{*~pA$i`edY!TL9BH)l6*(QaWndaByr=`~Ti zu>kt0;mgxPce%PIOLS@suka1yK4bkSy3Esaq!eY^MDUg*j>MuR@t4&`YIrzwcXVFM zBVR%guKm*pl>XX}W(Pd=qzm6v(lhgPOCs*h)=;*YY}+#jd}a{0xf($9uP5|yINux1fiV^HL;>%>RBhk0Gsh(C4$zt`OpH&GpxIJP1 zEcPp=ukESr`UDy{PD1(KbqHaA66;oiZh~(z?xO(%EA4$RRcG;q^&5OD&99ltLXwREi$liiYIW?I_6oo$S7`c{UhQ|8MheL`=ah&IE ze{YViTXBBVt%D7{H9y*!FtC)Gy%PR{ty^QS3qyMl~vyQ-**ul-;LDpoErZJC{ zoODXhmjuB(4!L#HO6mTdO+EJ5Uojm)zcVP=!JzfKK&{E2pjt9NBEP&X+0R#1%=0vA zpil{LOej{CoW)5qj%3Y15bMQguWFY@#Am&zKn;^X?{lHo#~u%#yGkI_Xv4U&t5fy_ zY315#sR3PO{ER&}i+FT|l_KEn7oF=VuVy^It${&C!+z9XI)AFw4godWJgz%n(f>|& z)wZJWO4=4~4w^Gc8gp7{_AIl@l%I&>ER)KmPYx?M06^6FA=xfNdm|6u@5PyX*8Nt6 zv3|7&b-=P;BUKAiafTq--_RNsD0d4)j${Wmi#1CPTAH$7)STPMYYE9@Qzkn7-B7z@ip2-Ikwsu`#5+vy_*@W zYQZ<&OPF@eem72+82o8QKlt6u@P+N}&1V~l5SH+RxS2M^Re_A}mQn3Rzg;*F_w>Cg zI#`;l-xaohLA>X-Kfzw+fZwL6Qd^XZi8LN?37>ql^ALgjVa8*6A6#Kh(d83;C<8G^; z4X!@X^k`FtB643Xzzo-j)xFY}ZS7zmHVhN$@?~Eh=U1Z=@Crpj?UITRCBD9MoK5^R z_*C3m?laS7v0=M5^C9+cjZL4|u6ipwy({b4f%u?@$KS`!#N@VXc1}`XWl6(j&juH6 z5B+DR-%I7-5kK9JenCXFZ#Vh{dE%I!n)uHeV$ma+R$j1;eac_~zfnBf6B^(oJwB>= z$;uLj4wJW|n*~Sy+LetQYhRxOB6hx~kw^!YH^1)3TtOcZY68R%UW1oxfFTkz_j3+^ zX%kJ@Y?0X+#D+Y?^IFNpJWspGzY`P@M>KSz$cD{-fH(XUbCoo`<9*T9uS0VBR$w{= zfQW(zDEUR6a-O%9g>5I_o zYKi_;y6Ugl-Brcg0j)p_ls@byhjrWz;rYY4qt8@EncKENde)2d&exfnnkc*z`K^i; zX-(COe!VGSbmpyEJ~Kq=Ox46~GRSALu6};_mJepvApVio3f63B^mX6o+7iA^{4tP`K$i z-*=yT|G-Z6PTsX=&CFT@Uk&@0jp**UA0nZO5QmLVw{Woyi#ao_aa8XDq)&^xggMxJ z57fz;BF;q-(j{yXN+{OY%%=U znTsdCBa5%#V5n~_*(m+A$v`;?5do=x3tgCT^kZz9&Qm`yA2+;#C(+d>(F~715dztFif`|IMxcbQyccQKTa5w`?b8UuC7Hi4vmnhfv>BjRKZV+o@+ZB&)HXv+T zsE9U=(NVl~RU$*!gtd*&#N}@ZJGtHLJET6)KbJ-Qns_xuw$pxEJd~(6Wqq*xATv7$Tz8=OB$fK18s9_UCX_Ae^E=6?{+SZ>%y^u;~Cnhk%ZtFb6#a&KV{RiAu>1lk; z{mJS4^f?t>|8GVBKPZ)o-kXbHYx~A^SCLHTQmT_w_CUyS`IXX44Zlv#W#n&Ue0Ncl zu_C~x`XdQjKqzCW1BRevd}Yxn6xpRN&Z#fbrPc$T9u47YBy9PB%rs%s~c5eaZ9*`?nIjC6i=intzi z9wRK!2lKPFHz4;lFaw~h5$vN)etQw+7#u#*kV`ote@xWenM{pM)2s5%OHXQjqi_GF zM9zRysfZ6%D_)EepCpEljg_K;R!b;-F$ip{&j7ZgRy!dw#JQsE%=@~q8Q+?B^|(<> zZ|tYzW`~CHW;L~hRNYV9>nAXtpHJFIqkF-Ygdp@WR_@+u1Qmtc@A-zQ`9498Y?AO# zwA{V0jfB2lvquaF$bfQ-TH}jLDC$cNHA7Uvb|l7lDoDciwk0M3KTW`5tzD3R^enOg z4bHugQnS2=0mUc`arQf6^3>QSCu)qIR~QWtf{Wzd@uzuCAcz5xnlc6yLy)k`9c`O9 ziN`u6J~hh%vOqD2n?ma~tuT}?ndZZXG^xu>7_-k)TD`T1Vylu|-X}yxakPFH zaiaDQlx;f$;{kX_Hw#vkvsJiN5|cTOv)Ms7ujhYb3FHO@w)-*0BH(ownytKk*d0}R z^3 zxjCi+X9CGFJA7R|WjS7FVcuCic_fWuv5xA_DST<6wacc&m8#Nj@W6W2fqh`dPJ+5U<`G*WE1}en z(yj{_fE1v~gx;|WU2+zZ#m3ZD0|&W-;Wh8KJuS}N13uhp6+jdpOmg{MLoukqW4&Ig z*NtRSVu54uxRZP-tLK`vj0V#PJv%lljiZ!BTwRj37+;;=2#D!&vP7R;X$bDfWH+AdAzg*vbT%eF>Q^A(xuM7W@ zN^S>V#A2sG-TXdKC>q~s_L3pF!2R_|wbdvD2(bmHZr==0@Hn|oskr9i`mx{_+snS7RD0>@xJ+M%@QuS**?ZC~gu2hmoeg?IR zF;Dq{1z;c%kV)k26ZXUR&uBr`pI72=m4zCY-xYA?O{NFF=4O6Ul6noMLCQejAh=hi zxS&$K(l?1;hxq}aX|;nsr6N=f_h8iVKJ?X+Ael(`=HlmHGlC$B%h7z40hE(W;{<4R zfrnwXtHlhv>q&M-u#dbxJ7up>TuwS8CsmD=omM zc0p#qO5Nv+69-nsS{NH}SV};+^Os!&$+uv-Oy}qGMsc^dG6vQUx5vT;MrBxNy zr!cgjr13EJ*Q=*RejaF9l=c$svNE*#)mygJVlFVSNU6A-kv-lVUfXNXOu&h16HFd+c z@sryy-h3r5nFYk*EN@S7ig4G8Mjmh9d!DI6!z;sBJR~Ec6f)8vJCN7g_mt`XI<=mp zcgSA996n!NGX|qUEh*}!Coiw+gKL?IVA5q6qIy^PL@x}`N3OKHW28YDjZs2#Mf&~SXZ%9A_dPXci8{n!jVbvr)U2Wb zJ$1DP$COWo`wj5|=URhSAN$o=ro6enVi(J?Cj4%4=m{4cUCUj&g29zTtk}pWw*)*qrm~B-b;0pXN?}Mf;}6<1*pKgOH#%g5n!nZ) z?4ZGe-HEUqAzaEnFaI!CQxe-?O3FesGO|VX*K_N^dpC%c4Q$|}s~fdIqV|Irt}!u% z6|2MEuN5`HKM?FdB$mR8MHWc$v$e{PP+VjUL{WTEHjBvNtItok6!GM-I%C$+QjbO~ zDCFM8hP3%xH=Tgb(>$Re+zjHCpB$8{Nw~I_ZLIe!xDfVYph$-M*_-E~#28ZBcn z*{PXg)cL-2ki1nOAQ+MrRcd88Zh7cDGd__2^QQMpJI&}X2P?kfakmGmk*D$tyoHZE z_df+s^&mpLq*{a2zrwB8q+YK*CR$L1s{d3OxiyK)8#9Yq6q6(oWyg569v%6(Cz9iT zrEvUvGq9=SO!U{X77cd8`svx?eE1Cz_cjC;^7q}VOBx{RdQ-$Nh#jvx<;$<{6F0Pj zyXWl~HzsI1sIUuq-v!4%8Cy-KLv)2ET^3cPp2FgZJ(2G44;u?v(*FNC&Ji(@_L zc3(oH8w3KTmsFxo><_=EfAB|`EmGUlh-pH;%N}#qvd-@Zn9t6eGpX8WP)u&W^nL5Q zTk8U`^NIIi!Z3EzMkpz)jDt`b8EkN23LJiJhEG^u?XPBvp;a5rEiAal(t6GTldPw{ zwlTi?N_<2mcJjpzF&X4!6hhwWu@s%$vrhU`I)^d8l^xc#UO#!Lj~+H}DYs`ze*?_E z(ZvrH0eieLLj?Rl?wWzP+YC8kmAaEIuF?Vems;2-^VM@%)1BYLv3kL{9Lp2?h+?Ez zIrPViwEvk@Hw~NdFShF9(IqXJtz+08AtALKGr&$xCQcUq}tIAUM5a6Ibwbi=C2!cB2G7zgpbjq=EP7ERY>U<@Z|!2 z*AoTbRGPkFj>a+kx+B^|r_xctkXl^=*uCJl>yB^L)xiG6eK4s{gdN_^Sk@(C+T-Cl z5=$*Ms_~uTAnXLs5bsr~PLjiIoZOnXGg$Te0iGN;pV^n-t0__LuCIY!j8RS|067*% zb#4TPSQZ9e-&b1pQ$5@iJVm|s#bjMr3godLm=vfE6UF0w`Qsna?E6IanBI?7gV9vo zb4MY(LX~`2N{BgAVzfnjgDKc3n3K#Fl7IS)CyvnBLsmn=3_af)e8IyC=l-CvO~COq zpWb>Ey2%t|xF3v2-nS*z7PIyFN@FtMx3%^$^#V~lTv*ifQzD=#A>di@+wZsaNo<#u znhNck1r|7(vw45Au1`KZGTx?X^|A7PIx?hDNE!~Wbg23(lUSdIVGrd}*&bPu4d>Hm zX*xKr6c(VsDC|~+Lb)yZVM6hbWBR%+pCL)!JQxq{gC%H*;+Kqg$iFbq^`%B8s&#w1 z;(9zV*)^kZ>>-e$5)Ea<6j5^_&jQU1nlqHh?v}+Ni_^Q$h24fEy(PuPqct$~TQ7M$ zUVnDG>g4KZ4O(G|$@Xi>GmhW{P0N%|mfn}!;Jm0`!eM-1Q~n5*3oAP;p7;p8#ZcwP z{rnysSHlx3QcsB=0;{^(cuQ*W4(A;pKl_*es3>UZYDd=)xI-|XRxKQ7t8L-2V_4K-( zDBEA|oA4H|Em3Zh##ArPwc|&tQXIb<=UQtM-^eB-wjz?r-)h!FDCxBnIRB+0FIs=K{sij3vYPTCRCaw;>>K{aKc)n=KYB4Hfl=v7v@~%R z=G+RSCMY4)VKx`YP}v7fPWf`CV-OM%CT+DMqx*Yr)?-012cjS@>5Y~HQLs!bB@D9x zh^hz=wn*8QRg8yeC0~h!db_rSAI07?d@+kONL9d)yC)_wac00U6Yt4JKHb88U&bQ6 zIWM{rt@-!OVd-#^@4)dKGWt&{jNsJ%C?Ue(^j#x~jo_Z;zu>AI@i`xJ_bcJ}E>qpu z_VLi%&45aG$Z-*qtBV6=`h7vZVvnH|;uHSEl&nkp^!jk2;b{l!BnjWZ#;&~lrhHVv z$$J=ni~9cdUBGJEoB2_%6}T1^STe8JCL%)AT}wOR4a zJLBRvL?G)BT#r>4{M+`&=p&Y?Z+#Qu#f309%roJfO|B?GU8B*|*-IXd`Z@mt)djl^ zcCPnl;UKWF(nHNeZjNI)?qMNUsb1=8J<&*{;j5x0CxK)#v@qTXf>r6UWG&>Gtn`=y zSiRXlWqb!y8DE%f-Sqdp9J1zsOA73BX7wqX!rPu#Y`Zxz4ydX2#h&GFugS+fXJHmQ zQzeH}buon(i*JbF%sl}anTCGX>xhh2ROt2xUX|d_ehT$fZ)Y=M((>1*0{jsv$4&p( z?Anb$R+m0yA}+^1YBCl;(;8CF$p0h!D6w82%aSvYQVf`5MqL;Uz;3+l7LH)22n-e z?HczHfBdBns&*bvX7oQ<3Dr*Dp!lKgbC0A(guhbfc#R-}Fc*YWP;}H)F}YjN%@#H{@54?r4bal$VfxCFW0e$(v?`~lHbpI=^p`79v20vIb&txPlJ#hN>3wuw&QDwbucXdPbS(O3h z($>TO63W|pVII7+^TwbG~iuE<{&-Th#Td(<2S?W!v}WH-@TZ=V>A zK#8h2Sf21-8TR^zgvPV*tB&&}v}PQr{(U$BeI0XZ+D zqXlwIT6z9d7szYB-^Sf^Hc!11s=1?irRKsjoq}b znrXcpD1LFHY=!{oU$wnzE7e}YtOa~IMRL>x8T_7*<~`)AsqxzUGg603hE1<1;lI#ugm6FiwnRIr!lDI6LA3#2S$|SgaM=j*#T?{>u5 zbK_U8wt1uXHd8^8TULPVWXuMDtVWqdBBG{*AW77+%_21PFJbmmaCULF zIRKIBtJMU#>qop{^h6HSTpUxy;duKQT}1UWBouWy7lbB@AhW)CFD;D?vd) zTI^$`yC2FzX9j(LvwU(iaUj`bR|rYaM_$O7Qwy|C;^i=Jt-&LB176h1BWrG-Ezdl+ z!rkq7wSSbyIN#SJ8~&aB(Jb-eYh`7WQ9#<=@bNKY2V(HQSSJ{jC5b z${a12rYXBf5$|e~ohV@X+<@!!`~h)=PKoX5NEa<05~m(Su_X&!d|e@N{WIOBIawHJ zkt96MO@CMQ7jTS-zYgbdn*z>b%(G=HkS$UmMFhPysdqh?GP+P~wECk^L5or?3Uibv z%PY@w_a|${S)DnH^4jY#DyaExy*J5?GP@)npUWRggk0F~ton!U=Ra|5f}!`U=>qUb zvDx_vV4!UnHQ)N1L69?IQbabjfu=rNR5^cKy#lf*LDY8)$rV)e99l8LZR%Ds{*ah^ z)EZ6ecN%NC{(4=UzejIVxv2?_e?=31Ru*pv(OaRA3F-4#cSS!kLF2;mPRaNUs0LHf z=wPRO5v?%Q&KvnWNvR*qw=S0!Q!6jEXWl$PuA%kd_oDP_@ZQr;WgOWKU&YTPiU=%Q zeEYE<-~{@~0498pv7tfHd5EL_|l`FVv z?Ptb2l~gJD&`Y(L_QiHQu1A#x6jZBV>txH=xn_d64E*j6BBo4*WZe*BhtNorTtjy) zrWwD^F&+^FpGt7#H+T(8zanoHWiD`e4(oNQ@~)-0!M|jjMcOIH?&gHEn6$YS5^q#* zUS|%h&S0!1C`aWG25N;wJ)(+V@&@)E%{(|eq%S2*Gl~h3QR%lw36nc&Zr!900djbXmT+s7M_F&oem%6Mcn z^&u6RxXAG?eFtw_+gHZ1@W)Vyo0^~a-k^6K1&dm-3&=Q}aL?Ec>Dd`f#}`peeP7Ez zj&|kOhihx#T?#rwfyYvR0Rwn24Naojw$a^^=(mN6T5^2qbKX;U zRjR!zc1mAkm`9su36nvU#F31G0l=~D62U<|mRbKlC(Tn?dl@YlnZsWsF1kcodDU>5l_HG(E2Y)lwt7ft2^h#wz(nVY>VGxU0~I z*!!mlT_LRt*X^saI~oBtA&D#A2_{|#OeIp2@pebISt=_QW>T!3X+32^WbwetbiMRp zG!N9f{D-QUtIM%HaY^{M=JDed3xKaH#wK#YoNoc#mtqIoRcXXb@;x8y@&(i0r%!sq z?GCwjM96a{m4DPlE_41FTHu5@+K1y+v!)IfwXLDH^nrgsIzjxjy%aUC9F&aOTw3;y zVOEE9PC+<-vFtgmydV8Y^tF>TImu66y6dx4o2B{8;>Y}wXSY#U#vBXYP(zU=JrhtM=Qa_JsIT4z7xYn_mV5AsjuC9ntFN=IkIlN<5uunZOrOB(8!NZ_VcVGwF;Ue6^>8M_YD-d$4iU<`4rkQ`_uy4 z(%S8O7Ze6+bpHSi5Dz%(ksVmx$7F*5{ix*4HWMj z(icXiVzLNWg6%S6vj#<{cJ1XqN*jn=NnTNdnS)COf=DOZ2^S9dC5=u^fn$}u9D-W= zsc>pr{Xf)pqTvao0kSXU*?X?~=>Lz~wqo+na!0*1|LUBowpH5pkKO)I#orL(1vjw` zBan3quA?aQZk0zFkRjFL9d(AgdwzEA8LcZa>%`PntFRDX-r#oKIrWt*+NcXej}Twi zlhTdRdDOkZ498o52_B(RA^yf|9!|+>Tmn!b*ZT}XvY~^`sVysW1P-=&a7(5 zZgK%#1#yiUM-%&>55gCL4B*+#TPqlkUp8O`<|%nNY!aqrMX70OX#1n5tA0a^h2QF% zH9o^rP=U~c3&WLP+#uWyT@*E)Au5*=a{a(Q2|OJ5;)`&FN@rC)WV z$pHGbXDJv&s^IYFzTNaTtB^83y`!o7*L!W16kn#LVsqoGtEpqR#W7Z*q2Num2VBQW z3Kz@z{xdpJ&EzmY!#Q*mDE#oC zWDH*Bh*wsSh)bT0_Cf=d@n}jv93Rm#6%EXW#cwi^8SSK|C1N@xx(q zj$}~H)P1ZDChDjT%^^8SV%!D*Q8m*m+J&g%+qij38AJv2opm&1@+%SIn%TQO!zgP# zn z;pW6h%Gm(8!d(DY!Gtv`#t6n|JSqjLZI z!ELgn1AGj62Uhc z^AZ9i9e%Cg%m|H9b-xxTh8bZsw{-sNj|5#mD5W(*vEb={fqqnUV#}@u|HLL2X-=58 z{D&J6t}&y>SVNZKl}WzbuGtnmn(2r{)%LuTadi|Uq&0GLd4MGM{eEHrXCPfI@&dB> zlgX|fxhs=&N6R9u6yYN+J4tlui|N(Mo$zz;XE3z!O8tp1;n#eSE{2!5Dt5v(m4GxNwG-F~ff(B_1?1C79G!~; z{zISSNoa$6f8vpwxZ?+Y6fzA$wCSZAbQ>$3* zdy7?*WGCK`sTq}m`DwEh(aj9J{e{7E8DJdOp3g_{hERu_K2vR;ts*8LgAHAplmKoJ zCGRe(#;ib8+x1cWdXL;>VVuBzqhG+F3#h8Jd%@ltM3Ll$|dI_Q{Pt`jE>!B}Rsw&9|?Y z_LXDTOGnX$Vp{~g{`lttEYYPUdMHk#(gXck=hgK9*buqm+kInbGt^dO{WVW*7PXIQ z9eaIlG2QvT1&zVgHc_tITEsSQM*C7~^0g(-z;sN3XH+-Hjz5AbcvTw|-fiiak@u7J z3B~oor-T7Y7lrpq*e1-q<9K6CN`xm`DV+QP?yh`zt5(sO+hY<7pTwXP>dMuchL7{~ zj3*{;7+1ebb5Ztm3JWAL_?~3+rA0k=%~oGU{aPCeM16y!9Z!x%opoDaE5GwC3viF( zh)_l~D}ZUeRlfGx54ZTfXg;#b;rjLmS&j{S-1l^)zW*-Zc&6YwuaoyITD0z4a}~Pm{N-)d>QD?}y1fu+a!c3?mvWMU zpY2bCE;D}3J6liwBh>c-0c;5JSU!#isTFgrR3Bwa%$!qDXG0H!t5tXj_i_f?2RA569X?+*_sf{7JY*(SGR+8OBg5nmnEBp=Vt;?vH=S{zl zET9R{)CSq}vOrFE74giX$VwpcyvN^DP7ss{mqpjsMiff1yR-!2Xms-NM^aP)g9Cd#>2)us}Oe{VwH$8e@GKpyt%aUwpa2^%%cjo9t>a)Bd_*1vB(w zXAmod!x5H)yA-rUR8AUDqY|~8w1l2;HmOIB;ZJY*3PGDexUf~H<@;`YdOpjaGX?W* zd7&Iz?kkvmsLX9C4{c)t`9E>9KS!XL4+UzV^w7*pTf;c6SSs%}0+27$M5MkjKy_kTn_6PcH*rIKW`y+!(2_}#O3=zw##F0*$TMqz6JHJ3bOL;M z5R|9T?8D)7QGjM!Fo&4fJd>=8D3UiSxL~A~_z%NI6bpXF%qVR3@IkK;_TUAqB|Q#? z8#6E%mfvr-d7%!I&)dzlp;kqc?-n|rOg?oX+`StqJZim^Rhbvx8$LsmEIDf887Q91 ze+TctG(4@%6~}vuodyKJQ{*fQqR07V_%hNI-puLA#8h=;%P0f(Ee1B5?P*_!A@r>) zz`TLh#?jUS&90pC4-9IxQ$~oaLovLeZ0aD^i0)P%nC&%T{s zDu@f3K((HdojWPaJKzcw)=_3tWksN4R-%dbGW|cLi3&N>8V~I%CfWgU$nz>5z7)JmPD|RBm#e2Nn)M zE1s_yr88KF<0TV}i)6v8o!vJZ{oAg85w+3-w&0=+Z4<+j1|uN$;@a!jD?S5P=_dEb zt@*g%ajz_xDr$`ofPOwAEa8JS+AwqUzLn-l=-=ku`K)^5 zVBX`ae_r&I9_pS=pc<1VBcRi;=%G?_Sn{_VEe)=UbF7ZHZ404jkr?Hb{tS5zGx|*C zA)^X};1vXUS3wBOikKf6*;4nOms6ZqTnDi?VP4Q1@+Of<+wH%s@R*pm?Q5cA@&OX~ za))$nw_fteh4lcR7cbzFAkT_DeUr+_3K?Qaj1^*_e{e(yBbGbStH&MdFl?M5F1G?uM8n#Z55<0-4jVd(jB(JDbV6ThO85bBH?eZzZcrw!T$>JXj)PvZw2l` z3cClMFsxOf#6`EvLf?P1evC}aMy7yO5M=RFJ| z*-Sv}IiiP52`(gHx?*J$+~>3=x}x(Y+3EdDc(%E7 zm#F@_w2N4@u`%r?!8gnaKB3WR_q#5+NF(e*+nS$21724~hiAnI$%p`oo{X{~*H@$h ztNA@5D8xdIU+0*m*Z5=Ylt!hbQ2fd2>-%_?*C)b1-u#tqE79TE@l7{Z8a#_X&#Flr zS}^e(u#(yERT>OwW;tzKyORWV4t-rI-OV43P+H31%fc4WnfU_XypQ)KTPDLTop!E3 zk6L{UUnLXVR>t(&Mfk;)0@`=%*;eewRJ?X15F4ir<~PJ9@p-jFM0oH@b3R$UjlhXC z^M1nd4eJPND{>>Yf#R`gTn(!@9nPo|{}?f?1d<-Y zt3+(3+uyg8e7buhW2P)JzxpSoZw_5GrHqX`11^3dMQ-oh)c!GxwA!FMc}%ss9Go9o z9~}PmXT>f9_Dy1YL1t@ckt`Y)&vGib1R%;4oe?;brEuWoxBEk|RgZvXM3|@q6XlQl zJ8C@HmhV7Fna2LiNGXJGP0V(}zP=qH%2@Se`5!s4Gr?h(pOWtZo)|HS+qwB)orZZP zd~6UeT(I_Cr6$8s1+(;9fJ~Usw9lE>3+_KX=qBs~Z*xTV&1TQ8YG~8)IVBJ-hhYL= z)G@b*Jt?I5zWJIK=KYYQenAULM2X#7;K~Orpl^5c5zxdp@;hn->pgzmjn>2;1 zR3y5c>M}|_!x~FT0X@NzkR(5sI_{+dMx1r5(GoZO$=1`HlHt~TxcF-hyBQ<`r)GT# z9d?S`koY=;i(J3G_Kf>^rQRq|N!x zjp(VlHjOBT#p=;~6(WLAm8-UTI=Yw>Q#f~(RMInQJZtm4$;Mr zGOn&s$aK84_JVh&T{E8b*ITJjc5$rTGFP;8jq~kxpKGd5%4H<|J(<;yITwGCsS!Ltw-$-iheI^${yc`kV3M_-iG0i z6UW6UaD4L!6+=>Z`wAn=o_Y51*R(6YfYW@ikk;ILXI8B>R-s z{9o60DJWJ*ou0dBB)1mNE^0eZH=2LTvU&Pu^Srv4P4*Sm-pN;xN$p_2SmMuzuXWJ0#h~;yHj$s$7o_zbQ!Td9yhnC{CKL_ogiEe(6SVQQo$A zd=+V)4$#&8^-lykA{yEkFO>eb;+lzg9tKzi*9hmLEwZJvcX@1RpB6iY)q4+nk&+~2 z47)F*KYt1g-N3hV_28`42!HoHQQ1||qxxY~-Vjj4k@9mo_p*6#Q&=mu(3hNK+Dcgk z=(EQKR{7aKT8p-7+o18*3aRz(ZJsY378`hp#OV8< z+-AJgPO53v@KnsqjQYI!@H$NL z_U4)|II>Wxz^Ttw+F_WlB;2R2HE8NEVBFWILAJqJ%R9x7QIa%_fQQ!HfuL%kZ`AT+ zN|=cZ<(E;GTg+D()e-KRPa~)-{66~z!x`jL%o|=Jovv~~t^olF?HK<9vEydHwZNcwlvH3(Xe^1U? z)l-u^ciJmMaz%%(F0A3|lGA}*-A6tsm+b&eMk`bQ$2)G1#+8<%D78^UQ@tpH5!_f7 zWPiDlO+OxI9ZT-+chq!wu#Y3&BeUpXfsP;CfBfjGu+ zv|3);j2yK#h`cMnv*_n*MWTxgVb~-v!qcS9@BNPzN=m-;9KKN?lrfzM$ZPfB zhy479MeLO)UJFH#MayE??3xl$v&7^XA0$Yg+pJ9t=B}q(ua%!~p<};g(jYJ+hn^}R zOldAr|AqGa$DO^{dtO}V8V=5_#JA&bZT3@{l>+t-DhZhT2w}rJ8tXVc+bHO9U1)^eL$!_p_%qu;!f2`8eZ>mgR73^C=m4ib8T$ z>r@d8#U@fh`?yR(=)V8u`1^J(wUf8(0&QgYbp$cR^qM#W?F_Q&so=D&x#Lv?NOYI@ zsn?O_iV>WJT3<-t(C7JSaH%3~&S#u(dTI#C+*+F~v3ZueEyp2Mke~LLxr~@cBnq@rkwhIt0w8*@9`bl{F- z-ADu1I(n`Q9gp|-gdkcwHgH=IusW1KzoSRBH~#PM7K(oG3!J7Olzn=aD)d!oi6v@CM~6IVG-*+U`;VxdHU8HHig1*0 zKGgjz`$zgeGc0O%I4`KXvF97=E<$$Q))`vAssMBcn?O9?APw*g^C`gwZvcV>!Nvi^ zre(>xI<>u1<)@o)fWHyp_^k_$&?K?^cQ$+xWA=O}9okdjy+nJaPIKI_`CWEvE-x() zV1dO4^pEVSE`GHjEBZO?lHjz#aM3eW_QF;X48$IpZ?i~={TJ!leX`BdH8q@VmjP?S z?S2H7lHM#=3f2g`gP*=^pYIv^r%3)cl0LxQx(T#$Mnphu*DbbH_Np;a%imuFTL&n92rsYi%3^n1 zu2bK4O4^ycDcE+my%c0%E3iS7CSZHb2Umjp@LLwCmsV!K=d3~MN@Ri&e|IcqvU0w#ANbsZ03`t)J3KMiO45l~A|xRb ztGZ*hY!GvFG9zhOH~BASB69vz?!LC)_{R9=&3QJF*a=5qSzKM`xyj=jtuObm4Wf|? z?Z?&cx!D6N{$1@QCf{<8QeD_d^CbV2sP(BDZmse+O0AVTm`bBj`-D$5pMSZ2gzcyD zMo5nQs8s6&o$sy@iumc9(;!RoKdN%zHhT(B_0;*aah-e-H)R0oz*mmm-|4ru++8QT zz$f6G3d!DD06%ijB+yMp7JQ~Bo0I}!{dnK7S;S`c`9o_IPkuhaPeE8}vFJ5E5-?4>%v$^-^@@p4(6Az!Hyms*{w(tJK!)wTT-h`NcJ<(`SG*dd=2*^#THNRn`TbmOEEo9U2eZ zl8l=I9pa#f8(lCr*YFB6SD^+9Fw>lrIpBa1PEvj|9vKa-hV*r<^VvmvWO_G)6ef># z*0Y8y+j>ul77l&h@LkzF1^cHZi@gc%=|7la!V=otSAP%P=Uu&{9@vd!+5c|O=kH10 zjFD<=L|z^Yz!puOMZ6P6`Z(TehRlI&xQ8_=xSwQPY=uk|bzKNHx`#REQB*A#N)Pl-Uqk?U+xoFm(vfhtp#_oHb)qy7Gzd?w$A~Ue z$2z}g&(^FMCpROmAv9Zu@%RuAt2u0HxuP&)gRP4}L(kK+<7dg2yuCqh4i5)%lVM+$ zNL{TvlFvxI1i;AfZXCc{-+dVWnP|d*om~IR$g5G=LWS=g>SA?h0 zU0Tu>U#DGA+%%pA?CQsbV;iGeS5TH`Y66wQt(VdGPJO9=X#_9Rxo!UH3Z^7Z<(K3} zEwFn({^|w=fQI753HG|l{27NGN{)6nMWsS$1BGxxGM)9>&?SpJLo-_Dpj7vtLKK@dYIxKCBvW#*1Ng;?+?>ZlzcD)jFIZfu#&qG-* zS+wT=3J$fBV^VRXqhv0JqFa%FKbwdj{#7q(w);d-^(8;^{X3+WY@Ks!OSxjE^WLGt zF5}-Hn417q^i4tx%=u`WGW2;U-|Z|W^M$P@-=wJ>^w2^Hv-OcdGqoQBz{UAGd2@{y z)Ds5NG{#@1xG?of(|9BiRN}!X^(C#$M5(%+iX6Y;@u=d~0j}|ja0KLcclTk;))5)o zldn_|@#N!erqZ~hHP$?t5CgRtq1)@kIflG8?xjhj&_cgocr-taL{M~Z8Ex<<{e$3Jo~^Th zGWfjJJ}F%1v*P#D^)~dj^wQ*aI6x*;f4R86>Etfqcu#23Cpa!s`13VTOFEYGf(gR> z2MG!L&zG4dv|S{EbQ1WC|2?v8K8DTD5tcW|597eq3Cl-Fx|aQVycX>i#?MhmI)vGd z455D(;v!w{nKzE>>z30x1DfxtkkfEmNN&H;o}%TluQmecj1!Uj9^@}s91pz1@^2&h zD5QglOo*pMBO`6RZ>OcBThWePnnqq-SrIy>(*4=~|*57G3R)`c4ec*{*cssi}RI=dY z!vDn8*~f}MEWkjSRGXvN)lSzyYvpW~y2@x``Yw-t_y zK9I()M7M%Lr?0Fv1i{l|8uJ?3ZL&+VHRwq5&$%i70Zi~3JcU??T<@E979sR~`{xhg zUxG`d95U6(zEA{cG*$_8v_(`0@HDpTO`(+!t%c^nbcI{Qe9<#P@c_pJqwC(! zp;nC`P-;PjtRXNYDO`-wSxtv`7nQgB*YRInB!P{ijY zDykg&4ZuVAjfEvuGBwOO!wYVAaQ=S@$G0$XY>orKCb}t=Z5hW5ioD zca`b(p6{Py;j0!Jxx(DrmhUDzf70GlH?~M%eL;ahK|(Lw@@N7HW``5ZiQl8->U^B( zwBMTNXsYNoOm-93lFy6IDkJKhkMko%Vqy#85=o3xW55?Z`AFckvr6#I1Z2<@tUN-D zyzftscv2WKsACo8$<7KABt1%pb;CW4s3hQrEVNKxcAvk&qC4{$xM=Xm$rqD1bv(g0^tVV^y?BLKb^S2K5%Un)UbJe#Wa`bhHBSZlV~#x3_=nU`?@2ozL7B z7#dmSWr>+g8^_k(!0UA)Ix4GJe@;7!u#&l{ttAH@4n9O9Kf!&~m@`%RoLzN)PSFNa zT`|$f(Oru_%#wSOK5`K-;v9E|*PGNSM(aVa>Tku`U!~$yuw_vC2;{%6> zfnoY5t79IXe6I5d{LXEVL9>~}am%&unp{}MvmV%j;ja$@iyv*Cgl@7Ycz#~vBe!QA zC)&7-o+qjtn2!)--9$@qO|t3Cad-90FDs-iMdeNrkC zPy>_F2%`NWcI-&KF$k%tbvEzZf2AX87#v}yl}4?QEQ)+;N#I8Idi)ng2kclufgln2 zF50;xNc`9tpkmDDM%4ty-`M5h1=fgZ+ZJkEJ6jSW@MEd}__4h0$S(I7O~w2MLh@o6 zqE6u6uU=p={@nwYI;CJ?pdRY?4BO@LAt~U)ehW)$ZeYQS=&Uhn#GO6!Yj@NdukE@f zI&Q(NMWKT4ed43ZXhhIz_~^*+twf-vheLeDs~@4vk#2uftSK6K+c>_&5y2bml*Qn>D#j*!qm~#4aW5{w>x{U6u!B~Uq1ZY^fAnPO+ zJn<1&u?+$4Mu7@TbQIE{iZbi#AoXnk_Hk0LR74Brp*YeRZ6ztew@Uy55FpW5Xj?;17LV92Pm|;b8J=73B=gj7a=1jqhXm zx>d&>LBv-dpE0cC1Cz3+%yP9C3pbN%QLo~ykvggxl6RYIzsV+>aBRVU|)ZiU&m!#P4}sGsz>?hseiNBL3gPLEj<-hZoE5b7s*Uy z#0^h^lRmMSpn9g3yGqlE&!z|c*rzB-e+{Ymn^2DwrK7nAQ<#qQSl7B8RxY%yBjB(! z^Oye+UsdYC{U^4JDOxqR=e8;O=U%4u^g}R{JN@;IcvjwB02Dn!EsoUA`@iDA!=W3T z#?h$Ys$VVjSk6z;@Bf7Pvr1-#c0bY9#lO1&Ji=f+@oCmu{CK=PQ$Gt}hG-|I$!ZKW z>WE9N^Nl5y4Gi+1sB;bia8_E`EmecuW+}6C-^EP19 znD%SvT_-3Qt{?oA5Z`;`G&_oLYBu5tjq6l1)7gyG2!WgCM0rG`af8?6orVi?%;`7h zTM8yQKUNsFK55{u{dH$=Fa3}fiL=Er-v3=^9P=M3mMJ=~P^M|m3G&oMtz9 z20U(?T3%dE#{sQJgT3!(EO8FBC@A7e4=edYc6(EJ(;c=j7nzW%atMjedz`;M%3X@# z!*ZPX4>8Y(9_SIwz|vfB0M`w+dSeOcye8|ssg;h{Q`#BzJ;dbS^*x=aPgwS*+*Yzk@Ks5_F*83_QjB&(JU|u#w5gP}X$8r;2|F$IrejDB~|C(8E5Y4L3I$KW} z|Js?xiy@wh*+A}bTRkhsBiYo=`7iaIhmECGaH6v*Oh>&R?bfRyCKSy>C-RVBQibSSiVe!gDq3vY7WRd4>7ukD`6NK`_92_ zCA%Nm38GOZFs$=?-C&-UHOy}l07BqxFRgv0KsQL+1{oIai zi|r{gli9@!{8YA>?lSsi@|S$2&^#A3@A^-y^sUIc#~SxmDUP=7)b);PQHe5>NGtZd z_4?<`xPa0oN%QqUEJL~(U@2Lgbz+rnvnsl^`?v^{@AYe8DnT0|ONjM5m_6x)_+Uc= z$D*V84N*f0Zxuy(2aX_{1J-L6?z*p~PCPkNwC0$%jDD7I@}<U^N zT;VINx`~Y0zqpp>N-4|pU0C!VXz*VNAR))n$~FO3vr#$%2TJ+mqpjHn@yS?-DF;aC zVRc(BTR6bE3QY~!A5ZO|S^BWAbx*g+k-rcMiIbxq#ps&M{KL1L)2zd(f);|Nf$(Er zzq0;}7nhpzI94*Wj9f`u3Lhkj97o<%*Ujm*<=0CFOE3cKCzz;*EHnPO>u(G=PcV5a z8xY=L`}(TL`$`UfmAl*4&f;Xu1y0|c3j!V^q7ZCR)>BGpy7^bk$z3%WIM%Ar_2t0! zs;{aBRRo0pVNI|+y^qq6`=ybp#!=k}>rL?2+1%=M{;4qL^vmD)+J%wH`6H-4BZEhP zh5dznWn*upOEP;o?;>5oG5V>}(BZ^)*ow#3`Y{)vw|VQ>2l|PeCJbjOx)Wni)fgzl9Vempp4coUO36; zih*UbUtO#Hey;VRY(mYT>n4`$ulbtiKMGJGLjwby3{_Ma1$(mJvupiI@)OVnRkg)s zOro8nmJk)Q3-XBy4*4_f@xy<>vQ!Q@c`{omksG9KLBdsAyh*Rvd5z(9r0&+tT8eqh z;-tv8kyfC(5(Of#C3!7T-HN3-$}W9nf8G6+nW$Yi^0}TtF%-HUaW&q0B0=3J2UCv&! z?xf$pJAeKn5L~Sk1ZpJ_{AOW;V9G7JJq#w_&##_$;YEHy9-jt)*KAV}x{*Pd_W!b{ zdbz4*CB%7-2Cp8R9M-yDa<3OO8=;%Cl}Qc$mCvIInJr7nhETR&P?eJe*LErdDfn*( zVCSOE|Aj}Rh>}?qLqrd7=YKG;?nHt+mA53B4lmq;=>KXX{ck1BFLQv34h%8HXkfd; zrdm*LEU>!fWV!KQeCjQJ zGxcq>WXT?H#Ah#AI^;w1;eF$=GwM`3(r7LO(9C3P1Dp^#xIdQ^$DAxMa5=!;Q`St@ zJS-KBFerj_3n)46zu+`crWxgzx1lU+vVLZLPpuade1C^{AT+>6(8A+!D#Z_QUk|}s zzgz&6%gHihweS_Y+mnzzq_%KKdoUe-prZwg`lg;)sp>;GJt2XZdnMdmi#`(R7x%jd z$5Q+TPb55R!u6R`-+a_OA2bruJT$Ke$))wF-*CfowN>NKS!0qU8y@*O4Ju657i_Jl z9}4+7J@$X8BzFLAwPJQ8xvLG>n5K?+`<7My)2Zt*=dN(!{(j(GzmrP4Y<+}}ZC|$7 z`Zq=4{{b_f>AMfU7_0~&13`s@ejmZ(_DNp9ov*ExELI1;F!v3gC=6VFxaCLSUhRBZ zLzkSTbE0s1Ux!*pbBuLFCDAcSzm-@(gg2V%A4Qof$9hcI;kBy^>B=`N_5WqPq4J>> zEt?jLA3H+QQmZjXrG9umpOZ8_F*~dkgmn5S$iG2VD@nDHQ;kP-sP_0Xs&Uf#MtbMa zg2~r+=#jl_O0yQge;bMLS3~`WJSv(Ix9)_AXjQ(4DwP2JQ&Qe9ph{W%*nLfO4Wkc5 zZw~I-(0$!s_9(`D5LdtVm3y{M7HJiQOOvYoDxoL-6^9+;o2dHO@}99Pc$Wyr=GxWR z@7U7RuI@N1lBJtt)V4Pa7;}qU)i0ktC~!pK)(-%&#uh!S@FmsscQL%=e5NI+@NM## zE<1wQ!EI{rKfHeG z7vHq~R^u1|t;9hm${97o@;X(9wxz^wW=-(WtmeCVgj)uW1gNo2tWDFyQg>|)U(WSfN_xg)N{8NQU2oX)5+dTOnd0< zYtn+KP~(V zra2ipL9{m*1#Icnima8YR7)8%Z{y?SnD3vm7MABUKcvra+1+dkT@KEZz^~uDj=K3p zyLw1u>}{&>S0hdTp~8`92wY9D7Wj)3 zNIzRe3?%0ZZXSmlD_yi)h^+lc|M_=byi!b87~r==^>;O?UjUkfhs1Zj^zk_2HFADr zk2>HjwBwVxcQ4o;Q_Ea_#-)-Mo<)-Q{;HT#Bp|L- z1Gn^~cq_C%cRu^YU@WR<^Ak6|f@0fZsC2y59F@tX;!8BmSObS?V9D&V)}xJR!!4(m z@=79)Je(n-n|4NR#;aM#wY`~X+)*{C#3TN$uA+H*`B7@8pWx~>-h>v7_pKIC2-H*h zDFbF>nk}QYs)DR(HAbOg14GqUXcC~7R~pT2fR>9jK;Gt}mx4l-0GX8YcHz~W$ z6czBF$A@i&ZCPJS2OgHrjwk%S0M4()N;)e?H@cNb@aitHXw>OYT;A91yFxw#aVuFX z4-7Y+jxR-*L2UE9@f9yi7#@6UbRra`5_J=AM|tyjPGh&-2lIcJGy2nkal|@ONedoY zSTk~E&wOvImD`yK;WH~Ent^L;ZETYIc+#mBd~ z6QG$Xh}O2QLJq1Zl|(BVc6V@EW*lIOb+C%#!SVo@WSoB>+I{*+MZRRoq}b!8?`~{CK$%;Kd4a{mVc~$?}}=HkvYHsA=)wvRcXTW-8c$C z;~;UPLJaq~N49K zcrQxFUyi1k#xXKX>?g8TB8%>w|NYXOEyPaSiaef-+9 z1G}){oUu1B4E1-aW{)GN2JasCb{eyTHsR>Sf#qze-f?cV%`a<0n5cUvnhPR3OtAVG zg&S72hx;p4M2gL#XpN+PyV#*!)#S!@8ufgj_C6c+xhcjH*BL3|v10?-TJ!HVI`RhAbDdwWN$Ld|eAsH6?%T zugIk&3}f%Fnfnfb#L7IjKObM1&s>5u(n1wO_xo;hS*4zUISKGVrS9ElgxLH#t|&3k zBf0!Q?ABUUG_?8HNK$~NL`5b1Qm7A>5=%Y`;s%p3Sq4hW%8TZh_t5$2uA27bf*$I_ zS^(B2^me(mc!hT1L;lrJss^Bs(FW0hVvIPDxqv7l?w|8$(b@m~T;AQ|BQYY6w2f~F z>jx9#qw2H&-GTZyJ-L0%$xg#@uQlos5267>nr*N__jqrVb#bbpN{a!|WVz^j;5ue^ zq|8jmQ4$B9NioERk{{lr>+j0AKi+py&BMe3unxoDZA1%3EA^z=F7z&JhCEk~V=d;zCeqyMY?o!`um+vDi3N9!hj)20@QKc^1bC5kPRtIDw7$k@}I*%$6w1q2zZIcn#qS zK`#xvj~<$1Q5VCVuXdaAu@=$mep+%S1(BDb6x)j98?ivcX_B!~rRetvJmyp8RPPqs z=NA|<#?&3p^w!WRm3#~gU3s6S&fM$ufc<)Z+@;ttiksnDy-94w>w0Bub6HYUWjvJ( zl$sx~7?hafxL1b!`vQ;tpv0}+2v=0k@G0O$68pKhAei&xeXq8?=K5()kV~GZg}ox{ z63S8-F;S@Ix)r%TrQt6K_u@DJQfaTnU^OV35r;!gx{pS`#+V0^rFX|SvB*q~ z{ke>vJ2S0*B%mkAi;>|AdF_^MOAWx=Im9>;E~s|PlG$Iio#(b>Og12nbM+#dt4-l3 z?T^jIn}iJ4K+t|i$3L$%f*|2(+~04Tp_R(F=tlfT3~+y0i7(AIpE!)=6XS9rN_`+I z?A&*)lWV69@q1f9`}49=t~yA)(ojlCba2dBq^_`lve|R0*(27|_+dJh&b6U z$*QK>J|J=2`-oWxR9v#`Au#;H@d||S4NoDv+?4EE$f*khUVS3IKYu!{Ps8dy!M_pn zClJR|USCV!JTkc|Eoo00xT{~kkG*XvFi*dpFykG2d2Gwj{q*9c1du-MFqIsaJ1{Dw+=zsutq6u#{YR%P4m|bI1j6XzqFjF|X%R%(`re@W zbUF@jF6UAoJ)yC{G*DkMmKeyq@M@QQ4isT5iW8;lK6z92`%VCmxN5iXQZDIMb>t_} zh1JmJv3_yUx14$Q`A!#|?K-HlC|1zdF0TSozjJ^CAAf4>Eex0nnHi6CAubu>#QO>4 z&0$r5a`J3{#eq7ND@naa?Er`imTPFzV+*;eZ?{ouVw$6 zJq3s`b(s2+gZD{p3Ek^Fm!ur)mlyQ*)u{o)VLXT$iIf*`LoA%!{oeOuF^3wl|8}@Y z-l)Q!#cO63&8?$)cj-BA<}Xp>eRf5Tcjb%P@`_^NjyoX1*yP6t*e{ymKbVZ1WbszG z?>_cW(dUvnjv3|h6~Dft;^DKAIMPx|(cCM)Opp5?qKSfroLvBsJXsho$kA$%GQ5cs zDmO17JejPb(S!eEd=Q_r#gb2nPu-jJt6S1$2s}n3C}@`A<~h&oBCXZv%sVTyC6%K# zOgi?rqu?4Vx~B5jYqcQGVPwIkxM5M40b=lxg6RwLF%&9RKBOK+i_SUDFivaT(iyyk z*I~O$CxP+A=YqmBpg+H{H{l*9!8BtH$NUUxG3PbXn-*7XgC&zb(Zkkxl<;o!=n+bJ ziAG$=gG_&dD-QqOJi>%ocu(F^ZK9Ak&ML85 z{Tryi_Jc7`V!D|w5U%>3h zZa&D-9#7*f`N56@N3aYLx~1Ej5c|YVdUk0PdT9==x%4tMeQ8qM8~YuTd@OmJcyP;2 zP;oR-(RhBct_zsaXp%h{ia^i^ni}k*K(x(QRCRl*i*k~E`w2f?Cm035?s_OpPX~|S zLGR%%kXhAH&!o16qG@bSQVYj*jYvp;*I>>b-NP#1RZK6BWk#g_;KuPw*F;D^?v>KeEeh-7OND!Bqkhq8BV??7hD$1dKg>?oPc_ zY2BEjDwYXK^XcW+48}xSpRZ$*DC+BX&Pu()UErpepoH}_R zUr$v!S+=~u;;^!k_E*xO^Zs#lx_+VGdK}7rl7-7*eau_mZ$n?z-=0A}iVq=!jR#*% zq-5yZ4^OGp-x&T&i5sl>PsPFU&DD(tbH<+L0E(+Apx9|Ze_1oD1dIQ#7huDb{CP3z zAO=Dx?$fwC!MX!nho*m2T-ll{B!X+on$kUJpuZ|M0Mb12Ma4-3>d4$ISzHiS6%KX8 zXvX{jWK+>=4uw^nhR#A#%@);wstyFV)Sz<|U=c+fWu`<9k9eepc;jx#r68=%56CcW; zV_7R6cBAL*q{g15u0dhu)+yS6Z~2cSD>r=)M$pu}caN%NXD^fOZJia}_g|7V)PQ3`mFeX2&&&5X z@WCOm;*V99L9n1WH1bF{0%ZckVQ~zZ;`PU%hZefYRx$C_gm_wV)PHt+M2b*W)l~_f zTnCucP9*(`vvW^JqXCn=bhNwjfKA}No9uMb%SV1sK|rLH#zKgV$H->AD|%o0SC0G^ zFb*o-wpqsqbD#5%rwT-^rv;KQWgItjxp(E2Z~fVBqTPZ&m+yj?wZBk(`AvtM(k2begp)DgAj+L+uK+jPDk1Dmao zj?X68w~e2|bDS~bGx(=aFkz&5T0PsSFffwf0&}4oiZ~^69KFIu&B8>a_qdODrtM|8 z1enIe*pxN}(Oeb43SCwa-S+>EMJbo+<p66eSBRx9EJ2$Ub{p}g&(4ay1LlCwNIUTyqn?|vrYB@ETMa7yEw}4XTavN zsQkMd=x3o|KmvjiB2w7*UQm@O!cSIS1qrF&h)4BEM!SJ>3GbyywCy5>N*lH0Se0=R ze4ej-8dZ$|<%s<9(xryH{_jPXY@J!4?JPrvKIG8~ja89W_=1tVFNG;imzhlthpT4@ zTc|iJEQqF`AcWu+)erF}OaH1PCp1wpyuaJvS9<}PqO3CNecQc!W3a2G;7t^u-6r>wX`)&(jm}VUTed}ydKr2h_B)3 zXhn+wl^Z9{G9h1_>EGUzr;}E-vE&$pOm3A;y-(>RT-qZ&AxtYH%`BjhmhRPr4>sZy&u`o^W3A00J=Dwo)-oYtcMjDR zy<0auCj(gF;@ea#@<=qvz4zo>6NYbqn0gYPWTBsqWy?8|@dgSPxcoxP2YG8qu8IH2 zj>)ED=z~Il6t*eMe>@2DHn7%SIr611K(I$d^ybkgy61RySh$b(i8IQ@9O#S1q2VY) zdc#w#uUo6e+S)p1CH01#7GvFbf z#L=_Sc&34dwN|Q|jCJ&PkJZ#)e78He?w^RraTk@6{CGbT`6bn^N3A4|QA4nl_BmGg z+V7W-sw+6e62TvFEwI*XZ20T5P0D+SGO3Vs7?j~r6A}_^bL1{Yz+Gru)jELX5ail} z49WS~{f?b)h`zSIz(mIq(nPg@hcb2>_AHn4k%S2K<$VT^`-2-TVR4fn&fkNVA4utJ zE5U-Lujw!(rfea#nwLfsMNdO{v3>IdCzls=IyHOehOsSG!hp= zEGq3#j#6QS9MKHSq%loV0}2|* z0UmuM*(qh!(C3(`e;tYn!uwkclFYd-ywM{1hoyvXE-X!wCzq+S7Q-)vgk!`4r>~iN z`9)~SdtR;SUCkd-_S`+|Ih>MF=2e$^Us;j~VfYQ=4nnaY`CEwP9jheaPIdXYE*4Oo znXf+g>R)w@g#sM=E%2}M)itQlgQ5cBFep1LxhfHT0zVT?JwjalpmXH@XEC93c^9!`H1s7?CF*dwsi?ZBGC$$EoSb8Zja3GWCZ7U%SKpsA0Nj0B`7jnYaSNbn2 zxH&>F&%}_`#%a!W+AZaCtP556G_*Zy%;WMBSgcqhpuezivPgEU4^R^8kCq?(-z+oV zI-AA~njXi=62>}bKUi4j(wL6jKJ~`iC;^j8l=UAiYp!jP=U3OAXvA5ykd_}4Nnh%Pmfl`j>2qD&OQ8jzyj>+M?>;_Mz z3fe;J_xC21eIMO0I(kHNq;BX4+p9~lImMsN`+VY4yc8UV_5mGXe=t*0Yh_@1y;h?0g2VPgy+|j@Ak-{GMvzb*Sh{G zRkHA%BtPI_bi~8rdS1a}!sT_aN8?0KRlip2UZ_W%s1;_RJr85R(q_)YL`*R!mu?HN zjwk|Ejz%b~;Ry$8b#E&P4vDt)s7SHPtc~g9^u7j%nqPp(efB+(P9nHWJMW$OlfL}d zRg-}262qGI$6#-&JYV{8ePoy2S=u4z8RReTMbgE5Xf7J9P&3qt7*3Q>fBw*Ld2p=z)A#=2^e$%@lLhsaVjHd> za)+=AuepieLw8|CWA3dtIBwzXoR8ps^PThM;+{+Ue)D2r%RcL~ip6Te#e@i!Nv^7h zA~X+tG@g;=K!pgB)X}Z;8>DA60XJ7vR8Ew?EaNFN3uG&3d^E>XHtX`{I_a<&EU2t! z*v%xSUoJFp4E{J|$zkOLVQM{ez^hN6`AbbkzBN|MZNAXON27}KQBdTHvG!-2>EVYr z6QA3S^FNiCaN>u&J$eJ-`Q>qK?Thhc*|@aB7xoiWrhH07hp|eNGFTHBM3!jNqVE~! z8$^E$R;Wu63&UooYLsM@nRPcl?x$Use&FLG?T9)~{JgwWxP5nITJe-?^Xd(SjYY~3 zQe8#_Mfk(St?RRbxbE`oH>cCfpMBZL@*fDU(%0;d4esm2CI&NJ?K;u;e&8a1DtYWl zBPaVZ$Na5Aeax{Ij9dc)3*E9&O*+yjO9O9QWcJqjTjxstpf_JS-^&z<5bonLy9tYe zzY*|>*}shj#~)~>H?>++l59=YBn;T!X0v8%sFtW}t{A28Km94;QZ>a)jbwyBC0|`y zhIcdU-c?_rQof&9&Ar05Os09*)Ut9hq)r302QF!9f20CAwY3=rLBf3pxgU{{ErRFJ zcyR`vkP{*}G1a8_t^$FUM$!k9kc-=rI5f(b?)#O`95}9DUoT4Um?7G zlV6_x(?J96KrskwNa+?K6%umk6)3svysNs+8r(;>`c(Y;$3Cfh=ar|6IR`%8(Ti`N zE+n{;Mv)SWUzM#i-oNTlHM9;|So`&t_F`HVH^g81Wq44Kpd<&-$h9GHM4#l_57K zASSj{!}wEN;V=dH9y?3QS}c6Djkf9i4X@^FBQDcw`Uk8BcBEshie~y~C!*PRuuF10 zT*;Gei#$F}{#DTMN3Gf}b!*L}aMh_Bnuu(d>|Q9Dr*$L{9Eh)&C0kVY;)oO?%jZtX zGJYb`3$>g1(^KR%PDiEBW1!PRNi~~aMmAe;Nh{3_#C@(V%Pcp02Q6#r^Njj-@F53J zKQDIEUq<_a#pb@a7C@u4g=S!%IFwakLP%-YWNhz?#6(KQ;$h2n*m)0xOmGlxuuVUYBEEHeNK|0LT&o)2)kRcR9W81|BbIK6JCFcKI{k&z82qKCbGY<_2e3ewEl z{9%6QcSh^+NZxiw0H4RT17iTXP?>df@P<)xO^eRS`|)&S1O?c;o-2a%4^KsSMyx$_ zeL-SwUj4AS)AX(P3oW`Vd;v&n-Vqmy54tvML3&-|Prpq+`1p8;YT2OmE7UT4yYXDB zigxREfOK7*9kKPZqaCF%Q_OyTo7T$;Vcc_Ka=3UdDKqFEE+#->X89W;kxUY3LJUO4 zmP+&H+i(1^_XqQ8J92W9zl_k9I=+;zrv469&W(r)5Z}M!CAd&$cl-0vA?dpVNylHf z39&Y=0ax;Qr%aO2j_VTMEgMVbi5S^xp4hag&w1B>M}O&_G$3wR;OUkZV^4taZw!@n z#TOMv`X4TUJf#l@q7llk4@UoK>X!Zk$o_?KchN?yJCTOTwMf5 z;UHoqgor*Ks4YVh$}Gz0#X`y~2(oysOKtxhx>(Jg1iOwX;DhQt2{}f81k$)nKk5bN z(b+C3fS5YamhhK+#p{rdN1iyj`YaUt9qwP(f_r(uS73CtAbr<4xoR0kbN2*`WW5iM zsLA{zu7gnVv!Z98LTAGqm`7xu|2};Ebj?9X`*~$XG|QdCUnkhYn8;3UmgPrl0wJ)D zu0Vc*$1VXD&q#5@QOiu;x4wR-W=030FPFNxV|^3jUpVP4I^(cBpAPA+&ME|l>lP-m zhzo6Y7chV6!kNdrb?wuggvJlsOYoI8(N-GBGH1U0Avrns0PBUL$b8E& z4V=$Y14T=gxh%Scut4N$|K8y1LB6fj)WWPr$(NUH=y(#GsA&WU?xFHk`%m&5?D$B~ zF59H9c_GGb{atF$Ud&VQ!Bq)t7x!>kp!bme*6zS7^K8@6KU0AH#J{oc%{XL6N-GPr z1K$>p_6N`R1#fy030OB%&!cwm%pa_YShkD3_AX!;KYlBnwJ%ey>Y8~rnRfTQGpDjr z(v!Q~pvrQ$gT^55;D1cX+D{fA!~vw+YJVD_)WaCGgHN(?+zpRlZ7H`RSBu1(w(D%?n@Cm9jLLUKXz6sWWbu>lND_o zGh?nVPH&6;DN-A9a)-!c3MAuWQnLxfM~NeGhV?Z;-Y1pr2wECP^0vxt7?%L|nU`Bb z#QeQJ%_$VI?5o+JZys!Be4n>&lK451w+`K-QXMy8hA{TqE8T1JY2!k|c=4w#f-^mL z?slYq8X;jaJ!r7&eoy0>pQx4tO|<)D8X2vr%>LqOL{sj9jNSI1JEt;k#>g-`IkLmE zaW&X5Qe06PF&Q=4{q_nR_kT8u3cmxss#(;IC0>XF{RSf$_4G3E{s%)*ud1qB7D04#G=^5UtSuQecej!i+P;sP zN0Th>?WlZ2Xr5U9&9`sF?v5D8y;TL0wX0_U);uN<4j65y`z47Jv_rbPVf6dsc;M`G-wu+yH$dz~g;yJWD9Y=Ef$R)!;Yu&v zmsR;a#JqO%zTZ6l>l7=a;xM&{gm5)GGp@-&STLDmtxx!Qtn^Mju1d`3RuesbcIB3} z)^h6){QD#ODr9Mbs1_)%A;{GjnSrGPg0=t3tpK%}8GEZxYDgYFyyz4f%+B?iw@!3g z>B{(9rmFZk$x#O^FwZ_>Z9P3u6K$T|$hP)Hl75@DzP5}CFc7iX^kc2u{w2H(_3fVj zYwpzEt0f5NCp2{n^tt)S0SUv!gMQ~Cr*JLJKY;70of5K7xBPQvop$-n`eM%!GR163 zHSp@|>|uOtV=jk6P6sf@ z>t#tQRTsZBP zM5f;+UEZgyV=z&^&4SWfOYbXv%MH_vx&q8>-V-+z>H)1G@{)7hk>E+_a%=!2vHTEezf5Gfq~9ZMmFbSka(7 z7BHZbv9avs(3|PBGtR^6jBCHc$Nv~fmSv1BcP5#>tZEN0_xFd5MLF&qe+ERPGmfpU zTne??KJKNt{JQ(j^j;8yS*Ba0M1v!xgsf{J_-$+`H;NchBfC&{<|^_xUx zwHan>FnGUHaq(~28`etoX7*^WI&ThBsQ| z?u2`Tc8@EMiv(61K9?afyfV{8mIP72G`=lONBL07QA&NDmXBe&J^q^!>Azr}qvD3v z4rh&`3VU-La4b(JRrYzD%EM85`I8kJTm&0}p;hqRsSW$S!VdZ+`{^f8y@cqEov5vc zT!mD2r_ptD^5i)91;XJp<^2a$t>vzZ6^{9L;rN%gcUZ)za${r2HuB?@U&bShx}k>> z5-hUoYs!(A_|gayxTo;SQ!Wis%}Y-B+lypIbmE3>j9RJqg(Xccin>M17BO0lr>c9+ zszUsI6SB&kO_M@FG=zg5H3DB>6-J;E!2Gc|;PRdX=^zK8A8`4@zV7&t{-WD;QMXhFVsc1?nDr>u{R*&GKV{}qtCODpXlUumE4VyzMt9ci*HvR&J=mwi@_Jvd4)4%+4HB)apEsh{- zW{{9Z!CtX%&$}|8bkaWuBDH=+UNAoa4He=3Q+><8u~p2>>@iQn)YH7jdQbhxAC2RA{*a?u*-TdZYfC*6;3j%?U=%;9`p*D@r8vHLq# zG2`goz{tcKyCQmOfA=m3hiaa7AoI2X>=FCaDknA7>CO9<%uUp*JY`K;n~oKRO)3@z z9Oh&Z+K7iNnH6`n2@S(bW!Y~vSTWiqdUvTJGz?x;#ts@!=Gvf{51>jox6@xa$E~7W zdUMS0sdAOiE`apHcv+1P#TDFsQ1zy1@uk)A`S48G-aIu|(Ji%phu*qGX2y>M@~oTb zKWZV0{TP=8@3Xm~siuxkrLiEL*|tIqsvtg6zDDuOiTt-U-siIFU%gUjT6oSjw7^K* z!!|+2t%nuOs2O8cn!fMCA=0kj?$igned*QN2cDNB<4T;q^k=gUz3Y=Xd__d`Z+qyO z8n)fu=?^Cb-Iu2zSXYlIP4b|nZePPj7{!n-lU$CN$%oj1iw68Fp8N2UId{c^9C3P`$iCAVJ)9_;yTt4NHieLZ_wqe0})5pxhE{7^*n@CFu%!!=5FSeyG1NXJrdFa)JmCU4X7J*xf5Pd}R+?&-YzrdOCdOMKs~`%b4OGluweXFybw$iuAH~xP=GrH$)qrJlvIZBH+w92B+nVvaWL=~0YTGZ;a4Gb8e0J0* zn&IGq$TKZxf>@g9vK~5j?BFLJdWs8e@)nSFGR!bF0--^**p%2bTY`Eatx?h;%<$K| z%DIYsco^K`PW?ohyw8r-NUa1WRPo-^5|Ty8fU5j1@Ghk01)+k~hr5j3GB%5)r2Yvw8B`knO{5jdGfTuIY3?rLHumNqNEz^Li5C0|ChWj#V+^}Lp`Y*F8D zGE?R^++Sb0JfIa|ch3t^4^X0M zq&dKxqOo%HhfOD`Z}SPwP&=5egxm}$?9bWPbr1cVCR{Sh^ytlAl^Z?Wo5k8^Mra_d zAs{z(@xp7~bHD}!&dk_kLN%hqhh|8j9^r9@$EKbN{8m9pvBv8;*8 z(fz_q$)xcf>dgKj0RmOiCbP-ln=%BuRAgHfuih-kBow_E_;>dEYzfqFOCSbSWM`C1 zJGv(1tUTp>!wPS62G{-U7p1-re!^(K`(9jXx=l84k=1-B(KePYY0C^M32X~o40yr@ z#YJ4Zt>!qmg~LJ2oID+k({epe?JQ zGsf47eh-ibV!FVgp_m--Q8UR0#bv3(jYKMNJ{ppB}PcAk0NmbSnA&hf+B8Iv45QDIjSaVCy5=Wy>cNg-s;)$VI}t{Vo9)eZItlR_DoeW zgg=QyeQJ4Yd^7POg_b9qcLv(LRN(+d%-rxqD2Ai##O`dp{81vu8e;-mD2IlZfZDuaxZ9Zba*%lWSdUsdmYLkU!WmAC{3Fl%bFLFo7#|pPqfSaEJGiIAijF};+E11JO2%_%()yS?8v;ze* zKvF0+DBGjURP^WB%W!{JcgzDIceXhq8a=<;joOe0=2FcBk1` z(@I`##|g_D<+cQX2NI5bl;ZA(NNXuwOx<~>4(Kn@l_3L{`=Cf6cs`w|onC&Luo{*Wo(cvll{}JOZZiZyuPM=piK$Wc^#F{*Q zn8y9DxdHuYnu$U-VNM{F6v`3CZ3)i7x?&U^^WIBff+%J6ICO4E)@{-Au{=Pn=&sm) z19R@Rd|ws5yVW>Zmd4--=L5G9Fs;M_a_S)N2I6NUOU*CxFcuLBY z+w+AJay-|SF8nOQ#U`l;-rEk2%p{>!coU=0P2csD{YY2+)HZ|Z5pyQNNEQ|@0|YO) zYB|QYTq#$FgjBj9P3E(3tQY2qS*N*e1x#L|xk-8p%b(Y@W80BmgaF?xhJ=j#*dk0+ zD1*fmibTl@AEqC@?vGUyLQU9m|MntdvVCm8^W{8%cQCT^FA(u~o5z5na2D+<<|XKC z^lY)3U&;^&c8bi5LO@W%B0a8l2^?ezCfbPihUJQn`uY9zGX}zQp|L*8yLbG-MidMu zAO1+OWn(hp!=+heH3$WZ$6F3cX)tBJONgxpTzhIhF|>Vo_K93NhZf2w&2SVjVqJ+| z9rX@Q8hRJER=A_<6r$hSp+-O_k5QV1j8+M+Sq@I9I{tc?X;OiKf_8h&%T6CeO<53` z(!Il7!aop2+T?2*jJz2FxWSi<#(5C-!%Oi0!a`>N(u7~gTsjAZTZ%NE}2)ERy&%0*Btk$j<#z}<42G#1OqQC2|2RgR8 zBKRJNwq18qe`AyKrEn#8L6o|!j6GN4{g*6vg2dO#iW3)Th^X&wR-Vmh>&giYqacna zf8^=Y=+|IBmRp{$E)V+u=b_x*)O49p^!Yd~-23g^38kmJ4pu%H3=np8mAbG2NMN%I zpi&3@`1RVz=j^d z@kSf@>V9nOu4?)aAMYmBnl=`A`gjX<(fX=UW>j}y=%~_YMLMxV1QnWH#pmmx#*Q`C_n4P?T0DYyTaFM1WxM$!qB_Wy(tGnQZtkI$wYNCb#~rk5ZbH!vE}qhwxIe#KUa3 z$MQDV{CI&Qc^73>#8g&LY2f@%#P*#?Qj__~m+_7AH#O9md=urd5{%th*jDPKjcvTh z7)3X0x%eMNo*GD&V1ihOnOFzWH8~UWV@5mqd-Y(Y8tyVHWDbS*!45*bLRdPhJPKne0EXBrDT5*DFNq4}Dx_!YIvZ^lZNtYz ziCq0RT)yf6pa4Qr%v?Bf1EIFvx)?BL=%;fHU6)~!gu0_yOKH40c-~=CDLDm-osUn~ z=jqAc(TVr~a>96ukBzBLu3|EHw)tf3u@d0~PiH)sKxyyavg;APYTS=F;N!>Sgp$tg zKVHzvy}u|L4ZrOEkJ3VHzZqq;418h|+Qw z6a!L-`A$#zWH$8AhiR|eNoXVb7itmEOs?~ZTEue{FwiG})>DL2v8~V9dAOv#sW1Ip z?18-`0rveN^*R0?9-S4~0M%XFhm~J1cM1QiG(6T(wbDgdcf=th6|2Ol98a68csN7M zl}C&nJmc5wyPLP%*Q&>25`_~UKntai8Y0a(FN40g0lnfS?`Yb(qPo&)-no57*U!l7 z2_J>3-flAev(3pBy5XjXS;^4yC@wRN%7JmGXa3YFN4pQqLO=nDy;YUx z6OcZqOoK|TfftoS|5@9A$a>2>=GZT&k|?m|>5ecZ;uaG>c*aD2IP4sc=KMp1J#}J! z_>0q-)SfXiaO1@c*d>D^Vr7$YPZwy(%GP|9P@Rd=wPv`jzy11PMcS2_zw4hgHmaf? zZ4NwobM0v6(ZVtOHBhLZrK0@-V>}sVvt~q!m^m4_j>PKxPp5i;O}4tnj}W%+C8lMY ztf*Oy_buHrHd%oQeA@mkb${srHny%0#5?{mjXR?(8)Szt=rT}RH(yQ56h*hh7LZ2P z(F;(JOIoiS2S}!3>+co;r8sjJ(O5IrquM$5^-GC6LEg-Ml7=~>i&J-k#lKtjeinB%g zo4tZp7fMY>R&{mJk~O0~lAcjMR-Z^cH}UXE^(EmWYg}}_Un?owU78!TB1VwRz3L+< zJfOZK?ZAT0#P-wXm}k3x@C0yL+Q8ORL&M}G@=fr*?g+=2$F{ZGxc}}Q@zL-o7A@O0 z=H+N^*A%49^Z}H|(wm~^ay!oXzL?xTS})~(ye$O?4w;TY8tYGb8AqX0bTx=Ik$`q| z-gKbiYZ=S@lgi!B9z%oU8FMuhbAd&%@N!m7Lk#Fee@rfN@!MIBsm*WZ(ru%PLh~qD zGwqji+L{fSc#h$Y?5fA>^;uc4X4PklS&UUIc8!~r*kj*5nNfg1OFG=q5ATM;hEoTf zUlP3ensg>E)Q;BcuynYHGW8%@N!)~ImQm_7gHAftV%b32`N-a--HX#exBU!k+8l}< zMnNrf4@6!DRmhuT-o?q$=*d@cE+W&t;`oDYBx>E&Y`gBWlivOI=ZmW&tM)-;8n!q7 zIyVkugp27%jZfmHXcJPJaiNR`D{}+yN?UAvtdc96-zTBj)G~Po=$-TwYrbg%Zh9VI zSEf*}*Gu6lDt!Re|IUIb{BuyV--WAMD;k%LIjeth5OE80eH7#-m7pq8No8V}D`XO; ztfdKWU5Nj={d_r>{7qbiZ+zD~W-(U#rMbh6gB}BmlHn~Bm1jD(-HH52{wtTM$&5sR zNdbH#^Ef-hSHhbgi`z_wS?_=K7D3Ze~KROfVq!lHlAzOpgz6A8_khT zSP-gd{)dB9<@`#4!d~|^cxdBUD^mlAJ~1fNoGv(J{V^|Ps5Vu!k7B4UD|lEuYKQwR zap-eszDgmbq;|-+VY!$fC1i6@c-EisNOpAvqqJq%TqesHd&>8Nv&eU3qeg$lsqyQ2 zT9@RCc3Au72X{1n`;JBJu&+<9%8Ul^9qi{S4==8#;@F@g@E9;cW+*y@0V!#*dd;F& z9zE0d2a~~j;O1zO+n~wmCTA`~3JU$6bq!Qj{u_{7soN{k+M=Qq9JDf#L1V{^DDo{T z3+uy)_ZL5Xqn~$ts39_o{1Hnsn*ZvZ%+zeUfN4;_wHgQgMm{7@hC&cQ_8I>>R@bI> zr&M=Pzm(#O14^-iKl|CZh^|`f@zKY#b3Wzo3U8D3{J{t*2w?$S2tm3s`+L&(0+WtN zOv8@Q8L{wtcy1{*g|aAI?0<=yvKE3*nGcr=8I#sw+<(^P&0z|CAeFSI`ObL(LL>y6 zT2n`Lq`Mj8B&G~Zm1Vg2q_0ulvUu8}Z=$odzStFmh*yeCR>>QKlJ~O9rBieS z4b)~8v~!Xk?;n@7@M*?zr(4ct3U7jrY$Xt+QTsEVN;Yz$!-)(<~A- zW;;bkyD>EG5ZkNkx2va_?)!uvTfzuhq)a!U$-G57^czwG>Z$u6v=+j>R=6COf*h@+ zt2e(@f%b@3dF=4x?e2}pvyE568NZ)r=^pVj+q$wy z80cKn+qcX+f|0SmXMT_WJ{QdLV~4dydJvUsYRmEaNB!eDeu#7dpHO4}DRfzUdX@%4 zY0uIB2w_PY!h!p$1<%WTKP+_%kk#oFkgYV0C@8}_{UYdx>Ry!hH-;9ilZaBakaVjg z{_VJVTq>#dcKnORoLt<+ct57}$Q*A}9vww4FhnWK>FfhS^K$_Y4v*}ObFa`H zNB%~R$>bZBxJ%(;{ifK`Pu7MbtBPKsYPVsaPKj$`j-3DGU5E~*dt%&uE2a!*v;WE) zhTs~XrVXS8Dui$sn)hV=35h=}TCP12oLJt!{pC`!HUFqc0T9ZaTi?kl8U&O5mb>Y| zS6BUEk6!nt;KB7oW2S1fLKEqA%MkH0eBmf3b3ml%>PHfd6-iKxfy{6d&D z=vQI&YNOn^edO~y6(5qIX3Mp%DNrz=dE&~xMa+;`q;<~4>F@}_OTow%^Le!!I`Z*X zEVlaNX|DOIc+ft5YO#Hf8Tn~!PFNXfl4L(bwjpZ^Ze&s}cl(Hjjsmd6iAx)}2D93- zFHk;WrCTSG%s?agjwSk{Vda-G7w|SLE@b_&`nwVp5J7h&8^3^c8G?Hi9SQp+ zMtgU|r?Jb}ATvhLXalq}QP?crnW_gTC2!zQV7FraEji%VZX24i{F89^Y30GNoedm; z-0-AlBelp~ccA?p;DsC>cp;U#6xs{>pho*2w{;cbh3U`Aq9GriWt!}BbdJJ7JLBIM z8vTI5?r*{YatWB8m?GODl(h2Zc25KFb+Go5gwkZQ;|xqma{|9I-8L)wH@Px+Oaww% zVEAFvPGe|#6~h_~)%=8UsAdasrxUn&aE}b5JCK$nIalhRyoyMo*hF|RQ_;%&S(nL4 zODsvLWKZPm&LV8(Lt6gO@XIRM*I;MK0&Cjmb)nL*JvG>wBbk=Z!==_;_54HKO|6z2 z{zG|W<3GV*=4WCP?AQocqo{1zu?Q3;|FlfFq=9#^%DOSj9`X#_W398O_)=1VmAYd> ziF}(?f|NB)TZ4E>rS6~9OrPcR2kkApovJKpidOg3Gd@zL<89AFB22bc?a-JZ$;rg(pe!T}{K%{L+xuX>(A?AuAFlL73i>`m&Y5udJz<%T% zXR}aVp?y6)0dnMc@9x=y^n%p174u}SRYhPzx09eb9MZWWMiy0<1b28N)me6zzRv<% zQkC1NJ8#3AyAC_CkNrA$Y${PM#|E|Xg<;xpf@z-S3mQ!I{Hwid~njG1$r`11*T6`0031rnxRgduL|X@w>6MW(sRC$W0v zF~re4SVG8!j|NS`4u3!J+nqU$;%*?^94ho zgyv1M5AQ8kP*b%eSRHggdYh3h`^Y&9N@|(wu{(R9XXHQ^dWLR-OrIRJWS_1ClYwAJ z+?^|T1XaR^%5OPIJb5-|X!^M*Lrb}i<5#y?0Pb}?k?h(D4a2z%M8@mrXg!QZ^^^3+ zxMw!EJ2B&!LLK~i{o(+a7C=X4DHuZUvQ_;QU!lY8Lunx711xt(x5?&-w)BIap(^Zm z2Hu9NBtXSX=i&C^#r_qroyjJFxH(mNI6L&f@etZBChSP#UJr_^rG@EsmwqL$Dm6i&Ie+bal=W-Jq?*!x*Wtsq2kf^ zGw1cmi?txwDs9k}Mx5H`2q2FWb8hBg=?HH#JR7x<6{ghZ&(t^)JIoML&SRoS;$|QgvBb66Jd)_gYtd=@&3r zB{y$T@iZe(nE1?OFfa=erC;m1B6=aImhex@)by5tKBDr6!-w`b$zx-|j z4NJTU^c+EMFuxBUOL!c9vHg784HE~P;QI7EADjY606xaL-m9HHQ^QK<52FqftC<-3 zI8CKWCDT~k^116?Le#5=X1R;k=7kG|jI5H?=^+x{d1d-^R(6P=j#gYB2wVl>Lv(aR z7NnBq&^AhI4>frhy-GosrnQ9dKlK(~m0m$TmXWTliFP?ZkptWdmURhl(yPec0dZ_# zGQ;C%3a9MmExXAWLwxUcUJ_!SBza2ga|uniLN z2QR?944E+`BAe@gR+uDU!VzFWJ?d^YMdF<;94`CM`d&Y-X$4-V-7|_X36q4FiFOl(b z2-N{J96XgHuhO+qkFg6Pf`Z^5pU=G6y1nsCQP5-SQ7aS z%^mgq$}@&GaKwLEjsLILnl3CZj^<+PP1BA6y?K)J%QP0U2AUnToh&cCq2M;flW?|; z&wcE@2!yPwL{3%~a6|IVJgYCQST@Le*#@(wzu*mUN0hM@AkIwmxhKq9HR?y3wNF-` zW+1Olz0WjEZ#avcw=f9$177{rK=}MbA4eO9j;H#MZ(b$(eDgQu@(_RtLt0_@Ac|tq zV&UR45e#3P3O3Vh^ZdnV-!|rgjWO=6Hj16J%VdJ2HCxHovMNfyo$s_1`P)(@a&uQ4 zhi~+s7Xde1JI^T*9&?7LvN>@ zsoHZ6ckUzyyG_aOT|LX!o;%$TBXibxd!KjCgPbP$W!%|%6>)+<3lETg9z@Xr#*vUTo&ULX)I$!?7}^X`#uothVIOWe^iqf#7p znEcyXG5@m!o_pvuBChIYgJF`r^Stj5L0-^APuY!Y9{KIkJ!!5x&dObVba%%#lmNOI z-!w9vEVwsV#{ArteK=Md@S0OndFI0`2^~ohO9Y7~c?E1ffP*o0!8^-UF#V)C%OK5N z6i_!33Wo~co}u_PH5Jhy_WCOSERAyX4)RJY_%t4nonIDco?5X(>Y~Q)9J=4G)PuB7Zs71(j_DVh zM^K|ig|fyzNnD9>7#P=nzGx03LX5_PSs^cuOn7cjRTN>g6L6rCZoCTEk}Yy+_McF& zA+oca6Oogx+>w%}KdILJf7w>P8ZN1B8u#~m{9x-_=?D2(t*<@my2igsM%yPUAeFK6 zV#t^NX|3&KS$`v`n!ac3DdaRUMCwBbL%2I}a({eU6fR|#uqi@p{mz-WxBVyGfs7yr z<&o2Q=NRZfOJdI$l3V8>Y4~UK?o+`7jg(DkR|5PC0YRDgc z`l_1wUv0~iM-f4R^=|zrK-djJOZ;>=&;TgWR?%U8`0Nt>0jIDokT&Wjr7NB&@)&XE z==!%H!K?o)uUorcy5d{<>i_iuIF}SR(>jyMr~z!0j*55vB#43#p#f8d^?{TFQ|??M z6$(j51TO5XSW#GZT~NT-&C(?R$NIB0NQ)jJg%Gq| z7EYC~giVuzQZn_@0&M{A5H_|I`jRVxNI|~W7<2}yy4hpw$>adqP24QBC$Z;hFALowhYF9vxB&xEzC z?^r#>YM&t(NeR?8k^PCca0swJCAD?ut*{(=9v$2HjrB=OsTza)LgZD->swMzJ=QF5 z&T=DmAIkhw2OcRGvp*B zyZRVR>88c_Fd-3!t23RsvS5jp3eKu2LHi)77DLe)9-QDq-@0z zw=p)RBehOa^=<#@M(WoI3Ov%`IYwPRlxAjWIY_ox#ZHgVcd~|`e>@0bx1&~6%Rbd; zE9!V5`lOrhctX?Vx`wEr{Lc=6hx=cJja(2NPKla42?|+FzYMEpm14YOKylWp7YS{n zwq8sh4!&tRbZ-8S{<;*2!cctloeZf>arx3>BAE4O2Z_WmOkgbE-DhgKbVCyWOsQ)G z#O|qckaZ_M$(zlU@{3s9Aq#4^V7xZm5nRi+HRTWM}LNvb5p>fNpwNF-2 zIxjdgfPCT zk`;4qWIEvCy3U{X{W?MmBFF!uRyI&M{#h2C_nG5io>zKrez@pntuRl&yd1q2y+>mF z)5$r8-n|(NYF%BK)K|d~M-K*Wt<4i~H~lUlFs&<%rsL8pWc9Jp2w<^bQt%1DapJ(QovFO31SD?g; z^SO4cSOq5yt=dJ>Pv&8hDu2ux%{5xp?e6+9ueV4B>gdq2oipGhAjfs`sG=`bof|l! z48OXNkDdLgA98ICl3L=9!Ar8X8z$M}?_=W>iS^((noj>OV@0?YB$FwzK^{Adr@60J z+qI?{!IojW`(k#X6yhF4!o)4ofr)$tV~4?GeDL9n5d3`{6{Ep~NKkSDyBI4hL9)tq zVCWxlghP|uh#-YiE;4ibyXx<^|G4ek!1Ej{?zM`wT|j>sqEYPEWhpAwlFHdxkNAHH zst0G$o4y~uz}UXAOYjgKHMC!af&$-YZ!+@xH`z`Lis3f6Rl!!^MJ+h>^QvK3!*iTj zd^rv0OKu7RFWxNag!JXfCOHk9N&bA|Q(UkG!hwQ8S_5Me7XBBVnw7NFk4A;i?>X$y zr@C=jeIaq4WcROmp7!X2VU4hwmGX$__IdxKGhR47gZ%H$EOv4}NxeJUqu&A(UmDj_ z^Q<;_*HJie(jK!Bfb1rZ6>mOp7rnnE?M{q=iyF`7CsMQh{EAk(wFMT-Uta?R_|hmt zP;o1Gh^DyBDUGH$^!K-Z3=#BPHfzCt0(R?UNU8_K*lG4rN*}dxd%xxX>03ld)A&jWiM;<#r;=F?{S9r&cq6Qgul$o=%ETq zB09uR@-xEizT|NXl{VY_t{-?Hd7g3mRT7_QyA1oGfOYc2<)wR6Jp zrKF8@$vVr1vbUA?iS7vVj8zs*Lbwyzem>MsiCKW??^6G)i|FTbtZBY=qkvL~m6r2` zaK2!B^n|%Tt|#87W_*MWlR)rtv%&9~%Nip^?eJ_aFx~hTywF38nFE5P*Us;9>~iF= z)>L&JQhYP6l(O6sw=1{j948h%VPc2JoLM^wbHdVZQkS_7VOYz1YYpdc;}u+>FFt{Z zLI~}@iK{&attKVjt9c0pS%gR6M2|>tN`yj<5zJ@wX~@zDOcnaq!o-^w9(t1b*3=m9 zIO%{nPM7+8<-gEj_uqrsZ(rEdXzNLCr5TIyP`}H|�Udl?ZtX-Ut%>>0P_mKKZ@# zYbNkFD)>s^on0Tsb?Vvo5Xt;D;D34EQtDfYHFsrUZ*HaXe_&!Z%iQf_JIRcf+q^>3 zCiDyQxNTF6h=F;EHLe|;VUS`LF&mAjdH_x+OJKE+KuAUBN!tKEb0a-%`7$ zm?!??;DKMg#hTDRpRgM%^u<`q>ZgMBzkHTWDz_dH%X&=rLO4uIvzI}5ug!4Bwx0T2 zuFs{-j&LljB2ax<$xBJGuNnFQ(isAip`c(r4K>R{Dtt|6^fNg;6{T@(noIcMX%wudoOGK8*3kh>>MBCy-e%L-d|};B;b087AWj7XPJvAB@z=SJtuxH8L(2mYORlZ&O@47t&Z%WzF5xaQKaE0> zINhw73s+nVlXBLh)YU#+QkHz0&F+&&HFJKUc$?3E$A$h#ABp7a#Gg`C$i`NnVwwf7 zZMR`7;OniudhSJcT^AtJ@WnJLR!oi!`FPC_gXt43>Ul`Y&(*8QC%cQHGCnUm+1ix^ z>5f%ybPz+D*fPOlh=ab0h5^{)m~jCc+a$lHks^!7YJ9v16#FMqWHkBe4^ldMU*m(| zC!YiNNa27g5^O zzdu zL(Oa+i&N(6a!Tow+A^IxqTBP$9oX$Jj=D-xe_6pbTtXd$ti8kR&?sqck&nRO7ULZ6 z=#wSCPcWD}eK#{?85zp^-v$JhCuZpS~g-;gbkKcHWeN_>SasH z3%j4La|@S}o;DUuJ57hrxz#dnndg$yjctPlyS|Pa?4VU7GVcgr;C+2<~gM%F!yn5l+f1trn#1YNsFhck{K*G!|jXFOA*#FMNbV;OjHH8HC$u5R3Z{ znfIjPHEB?LRhs?lJ*bsQ#c$vx;P7Jf6s^TZwO>|BSQ=Obq{pcd71fFsvd~8vrm#dg z`a<;$Y5zu$)RdqvAmN61wvUbt5#El!+sIYV6go|Ai^3;4<0z1xw1K?7~GL^6%H0oYkfFtTsirQLuGG$DW>RZ&TUV4S4 zMX}@~qOa{t680yu9yf*cVUnA+Kb@+5qMn&O9DuQ{6`!gu`l#-69{kYD4aXa`0_ssH z`&Ph(lJmL=+_b0FDM!Y5dKA8yZTHE}%R=1%M3RS$ zKA?S5@PsF}YI|-^#`ieRZ657Fp8A>T(Bbz2%h4|iK{ygvK{ogd60`5g9@C{|%4n6B zWa$!qgwgF3Sf-S6#REBX63q_3Zb z#%&za=O7zRyS)}>(D@?izyQ-7s3-CkvWh$Ur2i^|ht0ic+DC|hNw!1p2icT!Nbo1| z^~C+Rl<&%ZaV_ba(npKB5}ou4V@j*7V7T%u zAX_C_KeLtMSlv%TJMY~=-$jiX9$U_>r24!##>`>B4I*X&d$R$?g1;fgdHnaFu>D|D;uNfReR zyS&D1w9>nVSZa1EqfDa3^m1UwGpLzQ&V4xaQ_Ne*0)NGhL&ZT_hKNWB;qZuO2 zSF;8Jb6pEX+Q+}pJh~^|Xkqs_(1xw8MafYo8|%rI6GX|UxeaxFy)HZ|H!Pq-VH^8{}A%8(G|LQzTTD1(3f{qwIq_Y@4Bh3~?12BqkGg1L&YqC}g^MTTKG&d5g z4&@~r3! z%ULI260Z@4Q5X}Bydja07)VSp&ZtlhQI4!gpjRblAN)Pz@7LA?OvOm556SoI4 zM^O+Z_%cKm62cfdFp(KyH@w0RN0G;lognb8nh-Dl+ zOBz0|&HU#_pjQ?6^_XzFt$P2hu?`D`BWPI5P5y3vS+vwX zonKQ@%>HKa^y;Ev#b!~@x04uSbM3TQ;pUMNmflew3+wEx}mT13L;M(%_I>*Luf;pq(ktKO~v zm10W3$lu?nta4KQ5iIt;_-|;IWR_cVuM6B(=B!ORFRWJ9Zob-Ay)Q|Ti3Lx`))gcM z3M_>uqUrwn0ODT1pYOq(Z(C@7GmU{m1sHHl$B(~8QSrpJ~upSAY^#HE=g3LsQorbVSqOs_)jL*=N zLvjqvzZ;)q#r_=a5BO2zeWh)-`<5j`D~LgZiJ=EsGur=UkX`TrDQsA6U&pMfkKhtR zZX~pjSxI;a^)kwBA36tw8PSTv?RR2iD9zD8%-|)$2;whd+nllYH3N#Dl&txP6zC#3 zV}4)ttk2?{t*p-p|6Ifx2qY)lZh&nl7}?^mh2yi6D?CN`(MTiLVE&Ig3z-t_pb@MH zB(qyIB1x`sSKvJnjS8hIt8+h^@+KLGOplAcD=@E&^}S$3B!8vUas)2PKNIeAv$BY1 ztH48Aps-5xl3drKF?(9gzKK{-Y=yzQdU42I^O_6X=7ks}EuU4+Fcso`bnsP5Eu*l% zdDGKkD%==2E+%||*&)y`TcsJYFnd*g_oZd_l|!0CUF_g?7E6|WK|F->+(b&zz8^0k z-$r~6pAzo~r_;PHsJ-eSmFUmQmm)uIqy#6|xMFdOCT0BCKZZS&L+`<{AQT@sVND=M z@g!RnYd}x-Q&*2^L{<2x8)ExTrmXo*L-k)lMo!@kcBXD9*?8)&rAVje$ zit5CwB*wBUJ;o4dM8|7s^_SNgNgSMG4Gj^s*V)>)*@!IrO zrJl!{g_a)74hTGf5QoHf`T=6H-#YzDPOf3f#3q}W{LohfnpOIkdf&xi(g)Y|T z!WQ=@1U&PirC5x@Peg2!JA z!>V`(tAjpDVg8IP7VuA)Hr^})?vs@xoL)oNB)PEQNYssIey?q>GYlLlqdi-#<3X|h z0h5aM&4GF=KD|n7?8Yb_abD>AJNof_ec-Axs_8#hbJ6aj2Qu zxkJBb!%53t_PS+vq=sTfBA638bIGqqz0kY{=sm6|sWq4O=nJs`eo03rsC46Np7-9X zKFIAjIoi)z()9_(68d5NpICBbcf}89$XdGT(RQ{MohSIDx~o3i*Re9NBTwa*c3t03 ztJerCCHHl;Zu;j~u3f0d>t-wUjjKwtEr~X3fEeu6w)Zm9O1mNo=b|PHjz2etLst)O z{{hsodMZmS;}|e$yu~@f%5-zx-o0v~pWLRelOHvktPAy)FgX5LD{g@as;6N!(zUX~ z2VuHUF=EPr)AfE)lYlgK*c2smX<8rrb2A7+p08`aBDO&kD;_GYGm~2^w>3YRvaVnk zE~&Q^=~W!waT^|H3=~}OORNoE`xM*OUM$5|d4c(gpxo{0?BbQrYr9as@KLe2!|%|; zkq1O($7ZDzr~OhV)9FXl+l|DaxHYtOQQTawR(9km(>M=iU;S+E*UD%19&sNs9MZ(q zhJ=B>LLWjkT38BL%l=!J1i^UxkD!soNUss}US?PX&b2K4oAut`cK zfPS@h@_Z8>faRIA;)GrCWm-UaBcowR95ZvUWjd7{tzv-5xU z8)&B%x*6?n&;@6D^$8gy-{$#BV*2XcJ_Eo(q#2N*<^8mmi% zT$n7LA==c;?sE}gU}Uc$+V(T!#dFo^tl;vBg$bbhV>lwX141a-0_r+w8hxasA1cna zut6h^Ua11x0xiM$(ofjY*wRFMM1F4#k8PcX;6A55A|Vs@Q~Yat*a|MhR?C530jBt{ zfTlD0DJoKFcE5TsUAdFkHrF;f_6fhedi>mnMfqD}|C*Ud6*;q<<`mmMxvvl~!k%u1 zUQ^*cnHjQ(%FN99-*Q%m4AZg|B2wN#dMDUxPdmX~5S(X|oFOZWIvVK>S_f}4vtwgi zWJkbWzH0pe`ho^+7_D*0uU$Oz7?B71ab0LWV0Tjqs%>)HBe%}sPJ&JXa)C-tNT3Hz z2+yzADVJ#h@ChZmH(Ir0G(54;pm~|V`m*+Y0D7qvj1K@?`Y5_SUve8nmuy8&+H~g6FD<=%)exe8lB9Q&Abx?UJ)s+Q{(C|plT>YPJO20l?FEmf-)btM zJQVlEp=-Y)9BH^{7xvVHS)heRfY?hI+r@D5Cu&dEXIM%!yXZ*ZDJ-kEmsg zGwyZtc96c0ej>2!;C0qzn&uLI5X|a0V5lvke8Fu`b|TK7(-HB{#2~ zyrSqhMF?=nj+a&=0|U}e;4X8&*?z6v)l9MeDw%w|1{+m1Lf@u{i9p6N~;r z!ix&XI3iF9;}>zmyCNrg^#&7`7+4r7f*2YvG1VGu>&30d8M~_QNNXIvJ|IEWpsC&` zAaR7(7M-IE8`6Zk&$!Ix{e%r=4}lyDQWLfq#uG}3!08q+)*9RL0J%<}bq+H$T zQ(QuBK*)wL^1{M|saa60ym<4G$!u10>iI^vD$mft?{=%5Bg!4AYELXqCBm3IjZm1Q z6mcS^oI5wNHCB{?mN(RecI8}zkkw!$g*F%)x$I1-e7)#fEp7tH2*z~NDfW%Rj;IL} z*BtCQWht{|EfC3(!9X9@oN3&X5`iht#sFaO%0ChN>^0j>)OtkI;;`%w!?w@=35F>i z828jCr8M`Dbst{3FUc)^NiJU=3ku_`jZ==)8K6PI`Cb>+wsf_!AxouLi%E=*{_gG7 zPA0%_GYXKwvD$%2Gv;}W7fkQC8Wa$Fy?V55I|5IB*Or5}tVw?HTg_Hj?Zphjr|dQD zk1wV@FSJ7yrJ5fR^yBC2k|z>0{xFzp!G^Q#e#uSgr+bG4UlS&aT1VVcI8n-?Y(hK_ z+g9(Ei8e0W4+-X`7@tdw>y^h54QW5wje-#p#3ttwqn$Wv&BXN9)?LqvPaL7 zA~=*|x*(A^TRe`fXsxKJ5l;~ANMue zQ?8yev^;(GC*<$*JV-X^3s3b1PwutYh>nRo+uMkkgpT=sGTgrt+C5=l`fVw_Qpl7| zSh%`^y#L_wsy{HVHOZOazVNlas@B`kpoVXs3UtRczy8}Z>-hKQfra89>GnmrRl^uL z5b^IFX;12U5pU}MhEe76hgd1|CA|Xk2INTcf1)^$X13OelvwxW8i8-jDfKpvK!aZ; z@MnDSw?B$nAU!E~M(c*pE)B*8Kkrr8LsKiz;V{v`n%n1(cmaR+GP-x4yr%5<15h^8 zO2Irz&Rh=3E@frLSN4iW_aFZ+y~iXH@n3q+96Y|aS|3zJuFH|dOJLv|m8U|h768sC z!b#-JPbKy3?e{tZH#$WW9<_6rOy#VJMO-k6c6mpN7u$p1A&!xB+ zC&Uxj@$&e2$>bRJN$Oe;)pnnD%ub)~%|Z*>mynKtk6~W~YK*+XyvPI>xPC3#P6H z*4LIWZG~6don;(3U`6mmN^Om{B#q#z5}KJ9nM_|`7!GWiJdluftiM$^FXD%c``dS- zo}$YMBpWzPSJ$x0_HM`s*J!n&StZ(smO{2M~q2kMszwxRGFh0?=;nyHxUrgIIYUdLz6Cz%UegGaK%z3a;#Hcn$fRvSY4P!dr`X5ShbmRyi+7O*^Yi@_ z{FbJ#Ubdv<=a1(nFS;eKI7-IP#xZ}trCrSx(Ccr)q3)M#F2^a^i)1WY2OmgBUN?qD z(nL_+NJM29x-gdo2?pC3p&c`bY}n>?NIP>8YaO_RL}Nb3u9GJLfJzb9Aj%;{lj^jP zBFw1Q0Ykx)g+rVTNb|81*D7Llq-*+R(%eeZ{@qfICdDn*Gp z5vFsh0mIDn(DVw2jL(VTnOYMEc!IBhF&_PdIa?Aq^r_uX6N?!V*;L@-N8oXmkE#fH z_NRATiwG4U^UidP&T$sTegKtux`AfB?uk3^ke}Pc6}d2)-2`e2J>^#g=BR0|jXpg$ znf@$8Y!Wh(@}k3MFf~V~mzwl(ByF73n%(hp@Pv1r z|MNUIRX&dVk2xu|Hr`0bQ`KunTk(}F8=m^cktmEio8-<*CDCYI&TZslMl*+ih?8%s z$A||0S-cipa5|KA80f&k=m|~ZOK|Afc2}tXxh7Uv_iXJXO%!({bsQl>SG4LSA=U<2 zni1xiB7dq{u0a~xlze5g5S$=5*InTrV8T>l6pnVuL=B{luE$`wb9|wfjXz=Z&wSe` z`Ar(gXLi!hQ;RLXeMVbr%FT~%m+G^{7unvO65i>_O2eBEynY45LDVXC5G4rnIN$Sw zow77ypNRw_PeuY__~oqwKwwIq-dk>SqCMUFw*vk0F0v`Qr?5?U5x5PSyVphTmoY)M z$oN_`Z$qqnzHwCLf3oVlMjW=5n?KTC&m!HL&9JbC!2a9Se&LoM=ckLvj_Z5szJGI# z5eUDrr#|2JZ@N)=w_OixRWn@AY9~3Wd|w@1??+Or%{Th$BU>|X$j`e6UgCXkS7ddy zuS;Gs%gBR#;h;hGKQhAJk2zS{ZsNu_{M_U1c99!k6%+~9wc1*gvL(7$bYl?9;(VRu z?6!OMDp`E8!+3Lv5}KnMwbNtYq^_c{i5p9Z&W6E7{3v2N``mtLJpSX;T}W4vxusql zQ=M2HXVo#QOJ6;6(>Z=LUdUaxx!3h>i7~@!sW^e6s$q%6d?a-fDWfaXAKBC>mJ<9b62R9N4ysCQhgVlfj>e$xndMFCpy497&mQ4+7PihoUTGlEI-i_mX>dZhw$o~tA3WXw{@6bQQzU6 zq))T=Ek;D`y*m}B>c_K0o6SK+I#ua9h5{~6_X*gap2pu^8ZUL#H8P=PN~Ob8@g&Nu z8a-vhN=ex1l<{)JB_ExiQ;j@Y%_<}+rZJ>_5wnBiD5XG{CKKi{RL8|$#y=uI;TU~~ ztaxS%Zi0~)ANfj5M?C1RK!uXt14|^g874)8^t7@b+zNS-;?j-Mgi8d-v{m3f7}mUimxV{&`oc&*{{4HSW}gTSzp-=%hUZ_j*2B%;SjT z2?$v_hjLE6@?GHurh^tltzlD~ zsR3}+?T)X*sc{Qj>dw@kbefKW1pD_V&hOXea`{GmaGdP+K4E^YY47Xq=Ri=O<7{L# z%tMh;F-chOn&4Gvps5vo;}KPDkA||Msu!_(B^m+O;AjZ@t+PBke=t*&862rLq=*3Cx=G0Yv^w|lkC|Zpc#NB9 z`l?o89^S5fhkBxx=WS!NE*qloq?x259pNM(yiLArz9!Y%klql@9Pwp84>qR2P#`RQ zIt@9=d5y-OH;s*?=_XoWd47KRt^5B}-gj!70kA5Q%*C!59vh_l^IpB-chnSI8xMQ_ zvK?o{iZ-|aF}k=wimAN!I+3CU-*Ke#ZqaWibBP#VVE?%Y-hO^_r|j^DDub0*yTYV= z+!mnz<@tkiI`z*TZ?>_DvZ3qr)V4_0A`*oOS()+do;?tvwFEQ~s%B7Jh(j-)8A`~y z6^gGx!O2s5#c%tkC}(to3VG1C+pSy84N20L5enA=px>dmze2?+W*j1ZscgI*){Ry* z&TN*k*wMB_juMILwi{57YbFUQ7b==VXGw4It9RraF^LL|W~5Bllxnh*k&WyRH$vL? z`mtyzb^q7+wPaZ{B-`ZymSO9bKweVxlZ#&9J~p1njEwpBuz}4~zob{%peO6ytw_kc zCMr1jpW-wfs537iR?_hP9@| z0`=xq97gkeydsBEmaGko!VfW@Pt08bo>%Rioelda8N>4%yjMehEBIEsMpHl7^qV!Z z%K?o@(zRFMcH(BWrcXb+`6vj@v`%szr#$@G-nszOl{c&R!4IP@>$GFiofi+F;2de6 zHIX{{-$z-wZ?i{_(QKZvQX|VNIicK96rJrWAlO(X_TcJnXD_Hh^1FW|(*0doqv=qw zE2L^4^TpfX-^bBjq{(+ij#Vu@rDVZ)tL2@YE`fHa2!Ks9FF4_*%Nb(a8l*9Cd4O#^ zhfz~rw+;+*?sl-Ypqe4Y|4n;`!6xf(%E(D(%c4sh5o#%>=DsR;!M#3h@Xr8vUfJ-* zODRM+{Cwu{fLw{RNf%D6lra{>yWj+uCYi4{1({qv{M`1FSiLRhy-3TBD*9sT)7BTDuP&Y;5H-;#Sny>R>3LIzioT}1~rE$Pcj+39B`UojGg)w>foGi%` z3l8v1$gRl^z_kF>qIDJkat4%DNRG}8CRBaDFMRD|$&r%dNer2H6od@2-_ zR(}7Se#_eTk@H1Q#uSDokOo+*DJ2=Nb8XVzH|2YJUzltAXv&m|`mK|4sbJZZjI>s_As4_e776iQrqAV zD*HHgW2Hb@o9)*^?NUHNKXbcR=o)PouiICi`Svab!-zdr`Yxy%r3IC@)XtE;|cFIRy1F}CMvQ0X*ryLbAlZBNo%e4 zC@gyJV{_}?eZHM9qI1ORB%-$?*Kb|R=w2UY$xjcIEliQZs>=xa3Ape^WV(>|)bI7f zPE~u97e*}@glLmNTuh6L>*tR-8tDbj=?G%5tEwBxXx4z3#4d(8ajG9_cDXMek_W6b z3}2UvH!Ko?A3OxQF#!}A3lBC^ARwER=Gy)p#eW%3{2ZNz%OLOtly%AvvKKSu&E&Dx~+nut&FuUuJYu?(qI zW*B+1yv1Qs5;We*DljveCPh0uI60|5uie3PnH!CBJS|dQ3w`!6OGfcNMDukML=-DD z{|bs99ATTdmOlr&`j9%J+aMu@jvfrd@D<=1(vh9NuErom{XT6g4)p_3z&!}@^^>Ll z#4h-DdHi(o@^{1Nec`MgTZ^O)ucPBHJ^0-AF&kNQT?L4XL^>=^7(sk#qg%mCG^!+C z%?XRVyl%hkX7|aPvd5i#8#00)4Z0}5i97lq>UP9@FQ7x)2xi;c%%rp{aDUSs>iTMb z*wZPhHXTLRPHL$r`gscdyq?LI3hQw=l=QghHTHM?L_D2>1@?tQNY}Gn!)z`salr~O z9hImf+22cbpeIsRYiyr;D~X?QC``K*B&n*O9FKXl@JRm)e=W?BwHc6f;~16?Dqcdb zldsbsrU{~J{{9g(eI^k4iLJk1w5?U8DBF~vhgvy|5q}ezGZUvfQVD~_1iLYvs1=@; ztwm++{(bm{VLitFx3KhRJgSO=oCa21!V3ei>ktk6Q58se!EZ>0}`;pBWdLX0Bnx_TQ1|5D za|)9K&e%tcFk)wvhmy{mXIM*OH(`56{?s|nPr?en z5P;T*-dOei&`mVp@r2;@(VvUQrw(kJSBj`d8-GAIF3~27V4=K}Hr+w?M2l!>=<1}g zX5p-TN{11=J~17g0(D{_MDQn5L>BkP$hmZ(*%K*6{-6%eW~Ors3_~bPHm-H6n1oJ= zV$VZ+2iDuE#*$Tje2`G%fwQ;ytS0L&p2}Fy5tg&m8hNB0Yu=r$8k4`kcRW#72H1|% z;))OYGaf|!^nSLFh-pNkJ_)xW;h&VNP|a*~cD>)?e3G#%`RD?L6^V$R>*g>VL>E`Q z7B(z=e8Wy5b+D11owYa<-fJCRt=vXk=!|&(*IU6kN;n0DONZil0GUy4dPzvyKk(?s zu@UzwE=VRXvy~P}cn*C%-Y)~9#qUh;G>odT{me0j#BsQRo33;fZfjA-; z2@CG0uHkS*#E(~9~_rb*h4$l+8HmD%TNtRYZ zJ8&k22wluQm!{`;M}ho0v)lrJr65AOIB>7cgU;fKjX3#k3ZL(lD3ZFn76~({Y}ed= zD*WzI1jV17^+U{5HS>o?(C!W}s5aaiCm%;gj#F%xbjT2tS!WPT4ImOZc=anngazE) zRd5{O?sii=zx0HS$k7WKDfr{GB;hhhK$o}&#;aQcy!}C*L zQq7Q0#BPxW`Mdpd5ZqxW?EXE&ogkyaO-QA1_7AFT|J!aSuwt1O5hK5Kp@EYn8~6hz zkpb!;m^LD-wJV;aDw_BVAZ{{X<>{>6W}SAm45oVMeU0O5GfLEGD;3+kRu%LR8n^)K zv)&~vO}nq7#IS>i>Te1bk``v81zW8>&@FVF7fj9E{=2rlEKF+mR&S$2H~)~mNHIB7 zxig#ktu|BEPps?*Xd|sB=wEOYjemT45k}J?ZVsD#xSbe&IOyr685iG-sD%VLg(-nxHU?Q4WE?C|<3N8yAP zcRKA<2$@ts^5|ULTid?TjfFK|1D?qp^nTwHj3IOg!Rxa2{Bg3V9t;qpzskNsHR$(@ z&Fb^8YcE&9!|!8yM|8LQ!0+_85HSp8hT7UCi?gahFjW}dj362tfY0J~WZ0q*BncA> z2O~Pqp3OvY3Q&Xm0>k`Vc5dHq9H)z(4@HYi`LcE$<7BmN1Ea}iye#)iW|Pz%wO%FS zsCxTIo$z`oeD^>lpkpLr=FXpA{Ui9>$0Jb4|C?C<%!Ug+yqXQR9Zr{UJ4m=%(Rs%T zTW3}|EtBcol}1A93aqVFlr&ToJ`hDM$niGm=ILgT&ZTEBo)EN|e#$yNsFxTiaK%-@ z0!87{H_HK#>J5*LKx}*uEK9}q{71>ngj)9IdvedvdYB#yMY%myUdxv}9t@UeQ zj*@D9(*(|u?yqc8-jFC1EWbq->Vwx6*08GJrPDFF=}rG!S9Nmgu)!3I@h@ybK1=wm zxXC<1bQ-sB&2c8&Kj$^ChJHp}CQ<+FICSxJwwk@Qx5VX5_QkEhB1McEfY2BVwQA!x z!aal*%806jsD-|?RPm(46LuFZoLUGL3977L)eio)f`0?9QGt7a99Vj~%v(-y(ugs6 zD$mday_6sJ-`Snzgnl{mJ8Q7Ig#9L18=n&|=#(hlUlpoi4$Az|AIa53nv$pQaB4Zw z$@#1h>3rn>i}krHd8kG<{31Cn*XdO5cDL~kyTf~Bo>+99#Rkhe?*MaydjA2Mv9ZIo zKI`oK5ED(~15aQC;gi==dvtK|b?@*0Ly^_8wOxDTvlImbJGvnJzcPh_=7xNAr1%gw z+YXl@^o_1a3O)@SV5*g?xr6D-+ z!d?NUP)Ynt8}qw)ER2q@yI=vqbSb8)NS)|?rJ?<04ABAvU1Irc?8{8|&gJsx^CD8> z&_=BUB0iWUBI5>kB}~w3nRuc<;oUYY z6&oD0j+`Cb9Yu!RX`Qg{hB)AA`P7WPE`^#amSJynSDX7EM2X5PD|s#QRdu!#b4v>6O$A8(hN$~o1+Mpcc~CQR35qwe*Sr=#`lSUNM%>N!ck>SU2*f4`3jexsf{pT9e_&5N$9TJ_ zG~TR_wD!hZ{>fPFUFkd2lY|;*eH;G;N5X@@xqnDg*^};iJ~@9Of}Wqt&0j|mS4;`E z%cA5VuP7VK@qRQs`>=qKFpJgsgIUI}A7-0IiUZ7YR_7^dy)>Z05K+V?WT710v0%}e z3BP4>g0!dq2R^i0h*qa)hy%HJ)qn4`A?Mc=!c~`Bq}?-Rlrry9qY2dICv1*tD)1lB zfOQSCM=a(s6sFw>bZ`~&RSTYegwWe(P*j$x2)-|D6dSc7K@d;nB7XG*(9yDY=8Li2 zz1Xk@VZ#w5gmuuVsTNzhk5!o-pm#CiwEP47Ret(CYCGZmI(CS~D3tD47xePzrBzrf z>JPa;hOpKbe6N4rL?pdb#fpneOa^lfI6*%-WEz!S&w3QPhRLr z(p--S2kI>=X>tQD>WcvV@ZAWL z>!L7ujd$`pS>U!&`hJn3vWFC=pGuILQTwkQaMSvwabrhn zcz8ISJ=~lM(Nc?pzx6&*`rbXv*o>onmkE-=o+?FZpNXr%Gaj2|N6Wwe_aTU8fhTC_ zsj!Q++F2|h>(=on;I%G0z2>jlv;AzCsJsVJ)IBQ*9-<0EKefx;n6WwrBkQp5!weeC zD&=9Sh<)NoN{%TtDkh#Dk@p$&-GhHJ1}sk3Z8vyewuaa35JjDyED}$3KtOQM90mUp zQVEa0-X@_Bz0g4~Kl%*QutBfxHeA8pFN(eyAY3B7n_fg)pM1q8EcY8rFAa%pkyARr zp}fAXR$0t)^J%%wQ@3J8+Y21cNf;Ng%g$2s9c7;k8h&9NWnTNn9uOUPhlSpRSp@SI z&C~lK?U&X{%3SVJQ}s8JU~D^fyN}|@rAmrQX!u z5saO4P$;C^BhFe>4Iy3KX;fp^@+p|V43vMfxzI6O-ljsc;$e}N*!@EJ%vg6>(OwJnr zcNFs*9V(lO1Hy5Y!YH@=)(SoLo1(n1H#5O`AqF{!Z)qK3Ez|mxqvhcOt0G?AdOM6y zIO)4BR|9ScY}SOB8n4o~bx$Rbr@U8b|1a6E;NHK=)c=;ft&nM-aww2vN(_K>qI01e zwsn~OE2a|kf_e6>FOi)jV8B?*{N`@?LLSBR0%>8VTeM-|Ja?L3tlZ|j0z@<|qm!R@ zZEIZoA;Yd`CH#=&9ZBB*vH*uHi$CVH^k(;3_!W3O4!6}qGsr|4*KlTOW<$%?Di(4Q zKTiF8(_3XgAXV_>nAHBCE0J_J{9nlF^M4sUa+B97q>p`W(MFdS zU0buENE!48KYPzds0Zf{r_+Lt_X<^sjvB>Z-!9Kld@Ky<2at;57e?+0}*pL zm~P$Q@z#95$rO0YN51(gueS@CxVdqoVgKHZtoKY&t;182(npI^^cW~N<}9Kw9Njc3 zK5A~Cn@_F;{;B~FinY|9S8FT4$Vh06h%W|gAufrX1247)=E6%2Uu?25MFesFUMV%l zpL%WEC0aQKrHl2hq|vIHsavsw6C}|R(M>cD8O-uo$boGrD7VS{t|U^&bp`Oim1yk2 zeh!yQ31g@3*(e7*|!HJQWC8+QYMT}$FEa3QL8(Xqq&=1|SvaABI{ zAgA+gmou`QbiueN8$)ypsPc02g2BakyrBw6xCbA~g&4x}C7wra-&7^$+X#{`q{vVg zk?HwP9eURNAI1C)U+kOqoe2Lsy~9T_yX|tci0K({^-~ji$~Tot6n?S~g2uhF{C%I{ zCS+z(H(P8^_c*p8BUq?YasBV=sHtn*0ht+nC6%fBrDGY?N2LxU9blSPs|h6y%P@R2 zU_Ft*Hv_6BNih`wCm@==Pz;DXWDtm9i(zX2UT-{%7z2jtWi*BDKSX`91gg0-0EA!C!a-#v@*Sc#1wt?LS4ISEe8$ zawI8o3`rxPCj0=q1fjHc3A92(wbaFjrj|$ z++ksIFt1$$m9L)PI#Ab+Tpt*W5%}>LfgK>zc|gorrI$s_^wf|5-@pIii-@-C@kVbo za~Q-1k{pg4FiS1Pb!urrBRla|Y2A74Isz^3_C8L$DQZ57{$*jx$jzx9`LDX`K1aA+ z9V40h<4}&^-FnW0IDUJL=*QvF8y-wighJ9TazE_}&1)|A33k!rnzoQK&aDNMObPGx z><`N+CjZO{J?2_hbiPdh**G}I*+&JJA!i?hI?&iPLN%V1K+AEQMV#MFM^!0*S0YFV zgD9G`G*}o_@#QpoO$gj>Wc8^SQ`CmUYP=V(!#u)zkTD)C>O^Sm36XPtRdC|QXuxbR zy3Ua}F2MNmMFuaP`?g1cTT(VX9Ly5Y`$?yr=8pD+0OCn=_bb;S0MxpiwHE?HZb4@? zvj>uYZTSv~$Mx=tms9`Sq_cqnw#3#;EeJaQ>p~5;kSd|?_|AiY4#z-s24W&C z1~LkO5mIZH691yHSJkd^H-wrfz>jLsd1cI7K0M?4+E%tV|1S7cxrz)JgX=^)CN>I% zvo6b~-E?it&8m>l^q46mSqp=d00X&F+5&_3XtnmE&Ab7py>GtCz!%c^?AVa zY~ppVnvhsl_H3K8O;ED8|C)K23{x5_XIhJp%gKdkbP-aU5f_FqFGyO zMj0tWXGGAoaS@v6UN3hRj!6Jr8)%u6Fr_3*6sn8@+eCo>?t>NsW(Pm(7}#;xaOY@` z!JTmAL-I2&^T-Pf7YZP@?=b3La$9^t+ae80oMN7f$dm^@vD9BIBE z;lWcfv>V6FFNQHd;W?GqIE99F;@C1e>H=`1R4Pd*TXHXs?&g9;K21`Gk#?#jA~cxn zI+8zPha~KuX5cc-(0$)f3Gxjgd(jf*JV9WY()IJ$w@&hS4Sj-=Z{voFSWczj&?>N~ z?c)55slhqDWcC(Y4lpn*NIdi665vRT{0JLm+OLh2VTNb=B7jWHT?NN38m1kio)`iX z#Ijf(*=byJa8fy=OfZ;R&O)T0r?Kz!2z9N>i5>G`oNpCjKPa7y_-9?psJbiEvQE+2778$5lh^Hf~VY}`tKNRdVR6UGTuKCBxzb-N*sg`2Ge)Hc}Q!2 za<@m)*9Sl_>%%nSPs6@t@GJ65#^{=WGL;9QxPyVRqJLbRqF7@U<17p@L|nC~6EY~A zB_a!ldgsI6neFq&dN$U#s;V5ZcfSaK_5tc2?v#x-PYfRyiMa{Rt`3ueX)+aznHtra z{<7DwiViKq;#oE(=iyfE0aNA*ViYNuc-m)LVY)C4)hZ+2-^pVO6w7(XP8)rHPe0k!BEB43g z>X;X^Bmf{;v=zjfN^62w9zd}mO@8L^`ZLGc0?ZRF5)(iY=4e&nPBZRXE9$J^#5<#f zs&%BC)PnLd+X=aJoNVVsb+Z!|>hL@Zm4F!AyF{7q04h@MEnfz)T?is^$okM17{K+F z&iC-@PY=-Yyk1q5^Ee-YzT!4l6n7ZGEa;J;fMS3jWcF$PZ{Hf4LOp@;f-rPFNlvUO!o>_iY$3#y$$ES@4$ z%8QlPuybyK(Nuyp4#W<-sEh-zAz@G4bq-8(@_G@R^-}=g9*jH<;ThwpG%ew#E#oTV zBT)3|r9Am z{~owI3ZP57|E?8dc!hOaDI-b``^W@_YDT;vUuF9zg~~kiC7}W=o zTMW7ox}_|(>Ck&wmN%2;2J7J@ViCIcQ=&$ZDTzjce^4q==uEL5E;t6@m?7Q zCLwmjc&C7|W$NBiM`Ay7wt_r3Mq7ks%^b4koY}|dziBzx&gE1X<^9EmuNR6B&AJgd z8$W$(7fKM(-EA*W-Ow`qLLH5-6k*;e*MM6R-sIaZ zQYG`~dHX}ZCPVn7J%QwCsDYYs_Rlh!ta;QIIHUPw_7f0s5?_p#0-z{bUWFf)7bPjN zI;aX%D=4BNlrOG${x5y;MqeV|yAk;sys-$j!O*)GgT+TsoWuci34T)b2A*Ly#i8I^ zD+Qj)^(Rr#Htl|O2=EX~1J=S09#T2K1(u+!ZTu5@>+gDaj)DD?MyH2yfeDcs1QDg{ zE`V#P1!zVu^qzX-CCTCo^huJ#<~Wowm(M3U7P+G8W`1Ef=Bpl(A2LUg2eOV#j&g~M zk*5cizcQ*_DSe5YCzlamp_CX&3lCDaONgZn3aING%YC!o+x;9Jl1}{7a1^=0>R>A0 z@!Ts4g>Lm@&v}{#tcX-ggCx#=#4yGQztA6^ewJ}~z1v*}-Y}sFuMbl>{>*GM5LA`K z$0`+he!UvdafL9RbE%=~Cx6kPsXzldRy@@C#namNSkQ=5*_*9wR{v0ntw3yvJ&>b5<0znl=0-LlDuP zU4KDq(Rg4XbN%pjB2_;hkoLNA*v2WvjaQeeNIxgICQ28*9R+`2p30us>LOs9S%-f$ z$t*T%(4PdJrN}W;KYJ&M#q&qyer~e+=`{6=4&=maB&UDLOj)GZ!#$ctCiX`&>+`wm z+UpMgN0k@b;%i_p$zMTh+KHh6a<@Rc1c0QEWbh^4)xuY<2&S*bvO_~8kJyKTrvtg$ zm*4bgM@@}FP}?E#JMWSbey#|2F^rYyVFW*R!TzusH<)?Y&^KI}H*4SUs#6u{qsIBa zxE`l(T2Mu$&OuWnc~K1oKgz|+RAUUajY0DZH1Si7f9@$x1{n;}tjJOZx%M}GPf6Vh zp#)aOD(p&WhO@$WUb}8ldv2FeMrtOi$`&46x13_o1JseH&(~8t?%&{}rnn<<5L;=p zYTe{Q1*PODn%d`(lw?vI4~$0}2OTMzz!m&A)WFgODit${b zvKj92uEkYEqy8j)%Z)jwoSVY*yL0~iqEjW zZx*(du-pf{G0_X}NuKdv<}DP(g`Y<#D6$qVzgVBwZl-KBg^X0`8rTR#-=$gNdZA*G zYw9tiY|Iy;LBa%aPu_X==x>xhs@{;^RGt9X?ACx*>Xl!iTM!P)_%pIxV6@kts-aIA z#BU`^-s0>5w$!BUP)$lR)xjN&zx$LUDgHSA@+>^MO$?}@J8;$&^p)a+ZbH((A?w4u zp6k!?eYloO=StnazkU5oeX_j~EiG*@M1hcABxRGXcX8#12XAm};^IyBlZzj_+ zPOAa5cpD}A5)&E{I~MO>+rMj0Zsr&Gs3wXpg?)&5nHxm9ke7Jsc=T$2bkO^}1RTC0#xs6a zb*s1Mvr-4okq5VB-7^9;fS2AepBJcnLbenzmJlV&jMC+5^}fH$0R6*kP#Tl$hhhef z%JLoe$uHUL{J@cJXG`5%i={xpBG5JBUvSFQDnf|H077xv-r@wLm~ zT5wsc%K7Xq&4U@fedV9H8CCoxx#hoML zSfxlebW^Cp zx=Dhwp$!}3;P>}mbhu$uqW7m&VYITd_3sS>F z=B?u$^(~^yhX^dUapLv6O`lr&tk_~MHgF{#+;N+-;`<95sQOjsvAb(vJ_@re+5PiQ zm(n>1(uwqw$W{3#LFppqe}Sc~M#eAr!M-wqiuD_&AhTmGkQ9u?XamMtZR;ZHn^DE~ z?@qvuT6ZK>?eSiaPoYrl7%0&aPyp1{ELH}EOTJ*;$p!Pmg%dlm&R_nH2+6NRcjgyM z^wuj3fy9zLOKgs8y2vgoQT^;<@Dlbasal4r{+HoFu>VjM@ytuX+1dK`Qz%=VY?`X< zkTw80DK!9?#zqPli>Ye)##!53&K=1vm=$m2^ugHuXGY?Wwyc0%=XRFbx=-I+rPw7O zDSJvKQZfe4+OmvApOn{iTa8X6=3Nq1f2U(kxNYll#@xo!w`a}0;0z6SD1;k63NJnV z;l9u2Z}b*=hG{glxzpsbh(v5JZ4V(L#{uHtT~mMb3C`O8DP=@(c4)ZYndX1s_rkZG z%#;)Qi)k-iv^CMZqmqyH>W;Zd4NgpoT$H%1#YUz>u1x5ua5xx*zrfSX_HO8i&7&Pr z7Jy>rkT26>CP>1+d@EEeY&nmq*_@JGrbG0eJGXRe5&n_AW--N)Mf~rzRjXshLxYY{ zTk;EX9}A3z2QtR#jbO+H`7X_CkM^Hj!K+zQAIF2q+5cwYJttTC>Vk(IjvW^l?+7ZQ zy6sswhJ>#zI2GQ%=K3>CMC)j5Qv7N#pT#W3G#^W>>)l%r7BNT(&Wp!Te81LGtJou8 zj<8<3zTf~cdg;LpgMKzzcub|K$`FyWYob2rbUHU*X`U&D;72V204M7EVk&&wdFELUp8ix&Xonj*;rE46g% zFsYEWv3#{Xp{HYW0&;jn<8XbPnEW`zaifZaFK9{^7kA;^*VBP#BCqXuxwCeS1=n7~ z>xl<|>ik$YIB-0jyYf5C0Gp$0%G6sM)HVFs@rdaDv0-39xsf5${GH6vyImZ4ARKRC zy{>JUku+oFqMI zN9XzPD((Kq<9ItZV>Qo|1jykX6STO$spM9Sp$_Tka zR(Le;>`-&C&(~cj?JvMG>&_SUZ1zC7Wm1k`dT6zDw~E4~C6fwiA**~wFg3UW&^7yy zZO(I8%J6-m_++!G9b?+-lgvDD2nKC3x{{u2UHTG#*X`R3_I+8bD4ktcj?O5(TA0F# z#R2D^6vcCwv^ry%3WYPMC*%5lt}}0_wqKsEP$T2``T_8g6JHJgFg44|i#s|y#8T7+ zwDlMG44M|i2Iq!h;>~*;2V3;dYiZ?YPxGo#lKsj_E~5l0Z{}M2u0@=4^-RC#7-&RF z_wf#dpg_d@08ZZ?gpX@@CZ*SjBuzo7Bwl*T?p*7=KK3t9nQxCxM?LAAsB32cRO1B| zlz<|%NtI3-t2etOPMEZliMJ?slYuJgKLkfWHJISDzH#?walZ%yWT0~+=0;Vo9i&`K zslCZRYA1I=%ZQ-7@!o(@KP4(uJ+aur-CY1E_gY=>VHEZ`<=ZE{#9o@D5GqHjU0v>=t z^-Fa$#Eo_8yZSgN#EwAI%H8b@$HnS@EG;gxwB6VSt zQ-itb+2JE7uwfLu9 zn8O6^=TPP)egh5pH~*sO%g60?NRulDZ}mB}@7j#mqNBQGcx_PB<#L6i& z%~8>8o~)MSvl$~tj97kQbGV}_={QO%KTU-~T{bDUt}%xv;!3*(F`)apn0()^_dukA zstW%-wL5|&k@o!Za0$D+nXYB`$jB-615z3Mai-iEN0KkhwawMYGVN?rf@ZH|8g=m_q{f+X74>HKvV5#$BcEqx{9YrWRpe~Yz-H4zK$%{iq;HDdI+CdLo9H7qjBO+ zPnAKEb_qTU!0!tg27X76&m!^_5C4}1IH5?S0B_EuuR7emxnhUEG4?d7)@_rpwzAOZ0J<#2=DxGfDeMs6BFyo|y;pa=Pi8?32bC`65E(}9Xl67k|V zxUD|5H>aoHpjV#ds~CN96zN!0CxqYYC9UP3jk0$o)2Pa?ul=*6M3CM=gR+C(pZ*U`qOQWRAC2zFax+ou@t88epF*x9L|_i(a+2@O3j!28+S67 z4l$k1xGxDM3z`pRsV?o$0{JWYb`o7~yUu^7z38jI^fhsx^lv~a80NNNV2-r4_O~=C1IMnjlhhxI z8{4dKYgQ@rXf_P={*dX>FwoYdf=l0Lg2*Jm)cj_plu+llRfTWgl*=o;l#eo%MAPzn z8LlY(tkxqafL_mCennn@mVuLrkXUsKs=twHc}|8x8q&s0g^H((%EmI;K{?vHn@CzE z1rQc1r)1ky(Hz9SFRhY3M%zWCwevdF7sT{{R$gz)l%ATM*i0^XiAQB?O{3=t14n%| z8}BzpP&k6{k=dG2rPEE2?2`#U)UN;DOY0oxVFXkNdEACjC6Z9F5D)jxLiR{lET7}M zpc8QAkAeq)u|sre65it*&OgNRe{Y$3L%@q2>fdW5?xU&tdmVF(AORLwWn|o(m>iO@4EF^@b40RC?@U?qPs7%>d4h?>uUt zJfuv%G4@QnQ{Jtjxf4WQ|~U#=IxuMmCBdnH)sr4Cf=9luVY^jOl^ z&3_7Ltc*NJ_9O{uo8FJzIjd?}c{d#Ormy)f{WYD3=FMC#EK^|{%&lf;3i6llza60A zh9~AM?EiW;kVIDgO?;9|M@yYG!~S#ZVob1$@7ki@F2mpab87tQdn`Mlo#Z#~zU9%g z_rDY_(hBzoI-6iuL+!(8;X&z9jC8d+DDIm@zjlBJ({J4Dom`z`5G{TEJ2j^iih&~e z`2ieIf^5Hk(f@@QCmRny4Y4WtewE4et@OUoml+IaBV3j@)#(L`GBBQ!R%wC7CC zW4QRv!2Y)ZW*x&Yzm4cAKETGTWt;%waquamyV_)8xDm}8Mh*(EI{kC{5DvhrSu4g# z0<1Z~w$1`Jtl|KzMS?LZ*^1TsJe-$>uMImNTrLEw@BV`PD1F)k?G80qgS?wMsh_HR zf%u%WSIi^aY~RB9C%KrQwpqj;88d|+m<80E-rmk&ma(dov4{ozgi2HUsxBjAg#6;o=mye=${MJ&r!)LC{_(UH`7*<=&O8UIh_4#0 zJPuU5wau*hJ~i#veds$r-0=yZr ze(wRE^(@d|0mOnozz?ykjKSJmpE=ei1=mMRi?QvruiWWY^*)LS?r&F*#-MwCOPb#V zjF&64&gHeu4#kp_v^c(txf{9u|9CpfxG2M|>(kv0(%mpL(%s!ig9AwS5YmzZC?MTP zx1cl(0s}}(O2g2Nq~trEbDsAzAMW|hTwM3s|F!nshp>R9Tm*c#c~{~EN{bXPHG;~Uawp}R*W~<>%(tpWhevZ72NfDfp z^x4j$?3@32o_>vNDS<3xw&*MK} zgT;1t?}Dx$^{x^Q;1p8D--p-kA!A3B>=!>Fd51`N)OJoT#gx7`!>wK0YoIIAx@{Nq zZ^v*|$a{)He6p z3b#MN+sK%T_qz;pFP3Fd&n@F8|Dm*-+r0n!sC3Dk#Dz%Zj0HocbVu7Y|B@2Q#|U4k zZsFxpmG@Wx7F2oq5s0{Y@zLf$CiQ@e0?PBZE0A0)Yu6g30iDi3`nX^S|gk#=rWI8U`vS!phnA-GOBJ1RE?vqiX! z-8~799yfiGOxB$H`TG5^O=903Db`zQL~79s58jCv+M1@4&y)Mwm$O*@KQBK`7l>LW z{YQ9C&J1u41ts&VzS3k(N^v}eO{+bDQc_zmks-i&&!4N;=uhI+M5oEsa6a&!Ro6sx~^^W+b~Y_gRzAqVq-aAWHBE!0@N)YWe<4 z8)pYlS3A>>W{vV3dLr=b#0^mvluL0pwCaSJ)5(c-)_*`qR39hre26EwU1qu%60@=l zM!&_mb+m*RyCcj;;SV^^U0bNnLEP7`Y7VdL<9Gc=>)y32r>b?}WC`O;k$11!%yacL zWH(WW=E5g`h_8-EKY~pSqkFJHa~r~76CzA2ni2Vx(dk2;jtGh&0h{JE7CvbX;EHcsIQ?Hx4s$;bLnZ zTONQOB+WQz=~~S4N%v-Y6};W)pLGpFr&V&<;6rfaH?Fk=%1|fYwhsic(3~#$X$S3* zwP7EJ9$N*w6x{}HU}}x=?BESx!5hPvp`SQh&=;t!G61T-l2%Zd)CtO)ViK4OaCM#s#bvDvDVD_LB6g}QEn+e$s+tU2td zwsC@JJhaJTrPB`>kta^AvzPK+FOpO4n`~CAFGJJyv+t+ZP@TXkVTs{O2xY|1uM)&9 zjOy&t65DzTpC)P1)Z+GjEfm8c=Coqgsci@K48QtzHkxJtZ=@DF#+2l z00Kh1J%vgWLZg~o_<0KzHBWe{N37{@Pba_po~>eE%QB;6pv1i}I*v^vhjTFBfjxTk zwI;SYvd*mlMhk_OJ&RROP_s1K#jE^$Zd%O(g$}~FSeEJAE1GC2HC0N-vOi$S&Mi!< z4nw*%h19xdL_s2&vA99@A@)H7)*($cpfbT?cJ!qn;3S(?Og=n7m?;@yT)=!soGkG& zgDB6Banqgz7lZOpgp3!_``+no>_#58Oxm

    (4BwswYzz$yU*ToX@e~B8*7VS|nn% zzx^}`p>!QxU25fWM?KiNZOx^zW59xbHM)7d9WqCCVOfWUU^K3eQhx@!=lGCVH1b}) zy5#9@s^Tir@LPU~-_sB`W&ZLD`JEA1i}|levOKSdh!%PX{%Bq+9C4>&lH{l8<=Ja$ zQlx3Zh5T2Wl6W<&rXr5$vjgUMwTUcldm=mitJ{(2XC`ULa=r+xcED_d+tw|BY?u_@ z+LY`~1dD}`NvZ&ra3)54jN9|HAqSUiPMvvDr}anvHUy#8_KM^f>t(qkz&N!&QzMVd zxV80O409{x;WLiY>nm&u+E4g-SB_}2}`l^ zyv8T~gEdJh$p^||UZ-*5D~Bg0{37%V`+Wy|CCkXblki}f zQroAY;}DrMkkR2`COUHdsnz7{%DciCr^6 z4QE>^^ga1w_U8W5c}8&PB`oxFLI$nD$j=-%B-E`;t7AK=nJTS%tv+uXK#LwaM`>hj z4%A8U&;8mV0FQo|z4iO>)5r&4K*n@YFRe;D~D>Otv<{Y(~+j|wy{=t+2Get}#&`(c8 z)iE$poFh>}(+u%135*Xcu>>mo=3_n-DqLG1$yLUD*u^8}hh!X1`opfWi%FM-e*2x< z$|F7q2ohO6LI#K(mq72BBfM)`t7iiQ*87moOgBgn>5@==`vU-_W_B`-lRs8$3j=T1 z6yKL4kwZJ-C7mfI84FD!PQ7T8Y9GXbaMd1y85!S4JMao(HDKlUHJ~zKH8{!oiHZ*# zV6@pb`ExM*?g3pd&9s!wyYon zV$Y|KrmGGmzr}Nir?Lc-`n%I~OyFdRD1;Q$J5V_G7qgHqp>3o(sRMN=3|$&^R^u@Y zvx$cdx>892V&GpcLefLi>@ShW*hHlPS|Fri@b%koo3qo>RNAzt=+{&3Nwrk4?UvJ1 zSZ=sXj_@uj#jqaKSI-#sNk#v?$q&Z~WdsQUmsAKKNo2#w+jNXe=@4N z1^RN81NWY{|>r;X?q-&eeY>{7X?i6rfTH_`3#wpW)tHmw^h zQTap?A=1k#oVy)CY0?}p%qU?}zVqDQ-Gem-XQ7d&-GxfN3S~&(mBnm4!W%WKR|%k# zYR9WY=0K!U$Up@=O#RZav_K7yf_$;gyx5u0-c1?|oOG&MxXz4ZEAz(v)gZTz4y1|7 zFmPOynTPI=8o`5h`xJ>?rml_f06|^wB-sYs3eRjRUi?%zIhrkmeuQj%f%v1#J7u65 z?Tt^GD~$-~n*&#CAaXi+ znEY|E&q~f7h0!Gy-at#7BvwMPH*Ub3Wy7y$7b%AbHN1}*@h8~otzZNVH<1W^jpcCkb?1@eIlo_0?|k8u zj;ci~p7UGUv|a8{f9Q?5|Mo8@IW+>N7&|ZcsCWd5jDjDYfZ@etknf52L+jPcYOkIWDu67gX~3pQe(h%`CB#!| zZDbTV0+|k;PWACBzs96WvYWlaEjuL8v!>TZs>t`6z&_i^i}k0@@Ko8 zhYnTr(PSNQ0Hd9S#dA{zcR0OPOmFPt&nOFia62ZLex(IKV82QuSgyj~W4 z+Z)m1$r4^G8v`SP)V+q!Kyp=?d+v+$K)qeNF1krS0kHJO@WJk&)UFBKe1tbpq-)am zGG#{k?u!(JP@-~}W^&(4A^D3Br$CQq12_vcCSReAk+%)AzsVbd3*+kqA6lJY>+_Az zxmTfJnU+S67s0;0<%#pTzTI7XjE~2svA=MQ^b0S;5k|ffQ&S(@hd0&Fwh>%vw(o~r zq3GVCCLS#{r+a-BrMB4OP7c@%T(l{+DHVTSSduttCzP4OSvVXwKirffzC}*M{T>Js z$W6(dbK2j0&GV@;^@5&3WtsF?b#aWzq#1Gt9=MCfJfOA*#P}R z+0F&}@!7!iS7WK{DR$}acNX*LNgFT$zdkn-QP!CmqG>i4XtUkE7i_klft|s)E;AA{3d=`KRW43;XSEo>#OVj z>@Tztcpiz6!v8UuLd`$p8WCv!wX-BCvGe~MTFEh8#0LFRM=Z=Rke)2%h$65amr!-3}QjN=H;gp;}GYR%>9=kAtfo34Z@=(cqA%j_e6%? zFA5zh6F&yTBYpN|e^xsGQt$9W$gVq5oylCY_S5xDp@enob)R2!la0u#nnPV&x9R@F z&hH9};P-gJ4YQy8=wYaA1tG`0%c6=Z;y}Z0B_H?IccR0RTd4NJVPi%=;~`Fu(mQ7c{w=xMz>UX0DzHu zt}ueww#aOxZEGb_yKo*?HunB>h3s-msBmVVZff0sV6GK`rOEPcN#N1)P41y1CymU# zG0ao-rb8rqgPDii6WbK(&zlRK0Ts+G>i#Q{6F3AXEd=Z1?HJyoH50z2*tyaKk$O^0 zgT2^Mzllt9!vWP}$3UXjWR!w1)W~BtQW3l^qKBI&axthVU3exXV)E}dCuz2f^zL(w z_ogPD#|_U`*k9I%^`NMfZk-!Uh_Q$fU1@k?qR_87Jj8ce zL3WK^1(hJ-&(yBaK)xjd&-g3G`AyZUm*bh7Uxa&B^47lp<%DZnAxs8{s_waKbf(ZQ-Q}KAWYC;tk=$7Den2H z4#(Xaq6|AkyQB+udB9Ip8$QATD%tZ+2#R2+{fWTC>HarK!Io-mmk4XM*Y58hwSzDJ z(_A5m@`zac@hF!J<}pNd{ud4~GtxFBAW6W-rJT1ng{7FaJL?*_ z2!nsK!a5(s)tTr`ovY6WzzG=V0;LNEDMVXQT5-l;R?0d&^RB(dl<6FjSOFI8wm+2J z%aYc}tP=J+Am3YB{ur7qfdi$m6At2EYv=rXiw}!5{vExyflj4lofN`xoC7|<$BP{G zhv{MJx5iP^aQ6s^WnW00i0cm4q$cRv8BhcJgQ)}68(YLIQIt{sg?sBCo;@R<;c3q9 zICJ9l`e8>U|8Y^t1lb=tTvr$CkhWdMqCgph@)Zj!I>WIq`Mm>oXB4?U8^ulUz8k}n zw?7!E^6!4+>=+9!olx?1pp3nyaYaRj)YhdT!$?d1z>~XWOi-dd(_>q;mgGRTRnPgv zu|w^ATOHPcsM7CYQ+=@xA#n(!Iz;mpFFOO@{fCRP zJRQeFD(SL_n>%}5iTR|@#vb$fXI05t1A&o_;b*YlXLj7WizyvzNF<)T4Bt;8(E5&8 z{YMs)7Tuurn#ctBq_tsPw;mj(7UUmOcqu$6b>$|#ief(z^-;8=!VmQh(};y&=y4K! z!7VVU)Z2!#dM?*5cHlKVI&AaXsB3>&fzQ9>#84K@roaTnSag>?gl#VsXsi{7evFQ1 zb1d3K=LH%39rlNLJc=^&-yM0Ot)|eAgZAl;ebEzq_OrFWF9ZX zpHv#UMHuDzc=IBq2y~~T?4D$DJe{`n9|$y$z0x((v$DXS$e&~)&Zl`3N6FUB3k6C`_MHW6OZi8k zRsyt7t1|@wn=g)MtNlk^hZ5_P9^G$5-(>K0EM}ZdtZE~%pdv;83Xi8rg?}I_CxK)) z-*9KN^89RRsfr4a9Xf>U|FQrRdEy^#vL~)QUr!B)Fle@m>0)TRiUYDV+F<&s#{-yN zuD>(fEV)O&)-8uF+&(s~nJg`3gnVMr@V>bXygKG_ww`}D{kHyX-s35>(4%cVC?<{A zmR5Ahyw~bp@Z*DYLs+dUR>v>NTGYJGpitGUe-=MRe}^^^$7W z7?<#)F|Rtw1ylZq?wE+jZ+Lx)XnZ4}=|HQ23pb++;*dcWWjO+d zLVxeo>{+vYrj4k&iq7+X>rPerfdO{K!7N^jpTT;9LnI~JDgJXO8wnoaqT`Tl(qWJ+ z(C;&p`ylrL?2WyiizSa|Ccb%FoGf)qou`}!*;mX%(uVExiydsX5LckEq0*pLuxQ)* zDwilwY7Z6|l)cZpU$M-iNDP^{KH9 z{CZtLg@jS?qkOXPNNS)hA3srI!BM|g$;gY)B|?WFJT=XGJ*f6uP%fDYB3cN1E9f+>u*KnU66F#LwOn0QeVpXop?;&jt@x4Q+cy&Pkh z0O4tWx&C4LE-ujYSyEIuNqqsQJKAF486eZEy>EvLGd`Qexv!jXs4^U|i(l4ULE_dK zTMEJi^h*m0jN~w^-_=S03Y|YY36?5Ny_*7-j7uyr>TnSb1qC@B9G1Kl=yy31;i}Hl zE{ip5(yPi+x5>c%cwi>LNoW);KF6)`BK=WfiZ4o7S$=SXKtO z)QHl2Pewtb82I?-5NScC~&dO{Cid=AMY!m%D&J% zer%z0#-p1JkG1rG#*IADWrRQ2e>4#pacCz^_{xWp2d2GWpFm)XDRoKbj<9U8Z0!ETKucHiG&&gZDtKWku6-9Vh0D7bpzw zK9ez@zq@oT8%~u~A=L0z77pOdLx#6os85KIeL--+9>K!Kcx85pnQPuY zGHfQ8tVYe~xidE5AW#o@QgrqLPYEx zPBQWv)D(B~kpNcx5}Q?^5~)GTxB|T+MACc(=R%6ye+=&7n}7mwJad&(O>Zv7(Es zrDJoCyh@z;(I`D2M;VOcpW8GUe3PE>r{TkooaVmI+T6rl83>lqD0f=}ynXJD$AKW0 z;Fyl&-Rrqq!g)z_2g&5cuZ_`XmgM|`r-Vfm^rsu-$ifdYy4BlRRODID(Dxd!F-Q^u1MAxpaFP9Vw8zQilqT2`_ zH>eiYu@r!I4}$w?dm{Flv;vj{?dNtQv8dwj7e1(YpAk%bM%^Zjr)p6@9*?cZNY+)H z8LTg!Kbdm9zsmyaAhE(ef$y#cWs~O541wz$Kt};?=32Ksd?er4zvetqiO}USr&K4D z90zLul4(T)>zH!J(u#(ZHAeet$(cC#&|Mrkc$PQLnPP?+_(kdaL{`j?_0-5nXPkod zJ#`e>7d4E*Z)6G1I#hZ3StjMZg&AURJ%9C$P-v?VR@e=VXp*xncZxkNqStcW4j#2S zsauRmq+VYKM|>r*kTNUQ!*@3tIl%d>%|K|0iBKX_u=%j5eu)`_Y+KGCAJ(E<#5DaD zs%KL;Ks&&fNZp&P4hk$8mpT-wsV#}j9Rs=9oqGy;3Nip;s1@8RFQm}*fr3J5?}`(; z1?7}9<1<6&+5X#z1Nc-~1J9GFH%8t|7jheXIQ68iN#Nd4P}vhGo1=;DBIU~z%TTVlIXv6gW|)bZ3R z%R0X#SsN)v=H2(!5yOxlb(0^g>s)@Kw^nbrG>JtHO2-fK6C|2xviE4tB`l_3Ur-Dn z3gTV871y=Ugejc0B>TPb<034~0Oj`K4HUYy&4l{=O*x*cxt91WzS8dpSg~u=Y+Tte zjxk?7dDR1DFJQeFm59nx$T)utW!1o2Lgyk~rWth=EWquqdrYfS{dE z%XRRP;Erxl#@QE>aXj@2GQ1=yNlEikb+1S+UE)*RI%Y)V_cgRExqm7bH@@-ILc;Ej zL8$kJ(^R>QGLjYM$2 zMxAkQ2t5#u3BV{)eWo7h(3B4Q9vL$FSoH7JOVj~5UZPvtNa3d@_LvXUS}d2}KLbMu z+G3}k=_o?_C3?iOcbnlSN39k1j_!s(1FK%JEeXNt6~BH&Cg6tt2J=SDJ^;UqUvJD~ zA`RP{CMt11c9pHu^bYEv3%^EYfc$Ul}U^sN+evzbVvi03bLEBoOuzS zK<~P-cVhz23pryD20uos7LVIh4+wjwOEjsRN5`XCE86dQ;b{R?HLJhry!#}ty+8x3 zrO(3dK@y^H<>TFyfDu~PE!S>klNv%f@}LIJh!zG~NKJss^vbX2mJJS0VnDi*8R~JO z2TZiWx=5g7%TFi2Ddh}fy6M;HgmPFjX#2b+D2H-CvJ}5KB=0LW>GPNAz3WpY z<|{Y-n#o`va~UF^Y)$X4Vax3e#i5Mx%zzsxkgpYpS$fycPV%nXhU|8TM9PWQbw=wSWR#eQMTc9RPrA99U?4n>%k;;k{Uo&M)QxEGPP z!W&;YBCV)_G$D@GlAhrWDmhUASHOhtM|maB|)i|MZ8Nr5`iO z{j5r$Qoyvxv%CJ2-iOMT=G$F6;_kKm=BcwhN+q1$*abPb^-K?m)>a)k!}4VC$nz}l z_sRQMx;mJ*&r|#)57TPD6pq^Q=GNGKX9BQUTS^pjfJ%EDdo^~-6durY34B_>Kydl) z{EZTyGNcT~OxM2H5_;9BUmCb1y;II+IqHa}aH!}%j%E)KGjyEgJ^`YuG~N@1M)$e~Gq zJJ}}wmitqdBa|Ba`;Xyf7VvPL=|VR1Lk~IZ9F#|0Ml>jL1t>pcfs`!+CJ1hNBp&2` zAv&x&L*qlITEyNa6T|0h1#7nxX=nP*&`xg7Dq6)#wi&ThFg-6yhQ&AOZdv2@;KSEa zdyQpgDGVEArC!d`{>bta8~NsxDt3&7aPiTH`Xn-n_^qWlrBJ$8bbPjScUT0JFk^*{ z?UqGgiDzr7eN2C{!f*N8KtG#SEvg-5icJVmU{DQePPbN_KvX(`^yR)zR&Z-npr_6G z^HWgQvdL79hRZ9VQSj}kPniC~6z_%KhQ{6~IggX8VXN8O8BS2*2hbDNMt~~#YdB3L zO+MS-KG2ZGyogfuAJmWs{ zE$t854hrFZ&iq)DB2}DiIcWIytD(8#=UDYX&U`(NN|93a5~6##pPzBuT<2Xpt!U|Q@zc=#{CTl8H_rWEM&U-}hEo_u`_{xdCcmz0iV|mZ zUpc5-q`N`Ngz47OJ6gWKNhP5#mGUe5-l#UWoy3&SCMLqFn;41Jq4?gn^PSx!qc~ad zc_{*_8g_4aMGC2qgc!4z7|%q%*HjTlviJ&iEbn*E0QiNd+}$OJ=+cePuJkxdodO@V zd99BfLAO$!S`f!#1|O-ak#EX5WJILFBg^w^E6-gX>0y-Ofm_V!Y!rHIK>5H+>ZCVy zSM%)5GX@Oo6+a~KU?$0tbl+-9*7mnJMfrYTAxty5LhD4%~l#!R6DeO_(Dc_K^yfzn(%@@a_1j6rI4J8!L&tbRxshjQ-xGumVW;Xsp8E3JC5vEBPCEAcVXmIh5Ak$OUp6MdQjx3V z$V9!V!Z_zULGr&W(6_`dRHHI9W&>eSWChDuuCH(}WBitVo58{m zIznijb#@cw-BQfwo1Y)Ll>hUpYZ|u8$lW9JSh3p_o7o=lm+yNyZ3!E`JmTvbHCJ9b zEjH{mGWi=PqaQvEFUwI=#6ev!W*O;)p!(3x`r87T)C&frFZ+SSxy^(xSHmoRff4Qwzqr(?!V$V~)L3vXX(j z!28s=KM3c0@bK<<6Ra1!8&KA33PAM6|Ag>fSlne*@g&;b=}aetma(V#e2AI`>zCz= z2I*j(ra=s)1M(QvkkBQ(H;mOTNA%~o0dJ-1#DQU-pdClSNn+E}tXJrR99krt{+uVoD@S@+_L}K_f~f{e@Q@oUN>``4jt7{^(>3&YHAfl! z>7qT7$smS!V8CF_USkDqS$kHv@Bz!XIY&v>s*=Hfm;?5br;ip!X+nqt7@m{6h2gy!7r!U)o_z%d)6dq6f0l69Y1anbX)jB!os5{A-pR&2Oge0Y zcA)EyZd~9^0F*zzApu1Uvj6+yr7tkfwTWN+o+s~mS(RR>;cax&={<3S6HNn1Q$g{# z;kD!d1X;9w{!+byCkm_cAi-TM|JOq=O}3~qx%(FtBjv?7@naVq%)3Og3XRx{EKM#g zI5mI9N71sIqVFb&(Egalh&F+px(Ea-zAaw|$MHb$bqculM;7t zMriE$U{ihTLPQY5x0yY?#-)u&O>vtAlCh=ju-@YEkpz&Hca~Otc{&rQL_S3-#|TZh zi-`>@U`Nw%DbVLBcspTwXxnbUzdV-Bu^dmAB*dag*HGV?xMpa+?ad(aAJ7&&w!GwT0%~jDNS7 zjg|4mU++YApleQ$2~ZII(#CpC@SuMeLH@uf<_-1nY@xqCqPjBf!)L7IfdFh)(}F4l zTxAW_Lq@?0$_*9ZtAl#gLI}BUViUIv3nQ!i4!D*U?|_ys(5b_Z$rYo`-mMS z(Hs7XSHNevoB(H;)-)FFA4&uyeanvR*IF$NG&cPMPd|F0Bl?F?!5(&hyBEYyZu`29@e7mtAg>WwBJYH10Mq9<$(}7M#)#s09Y}8FABb*fRZTR-g#Op zXA7#Q`Gwx~q7_u+4dvi=#VBUmZ-m|lL~a7xJf0eUzbs`|7NB^Z@PB2s`>`fVMaPb) z4j4daBt^>VME7Eia4H0p8f+=r2?hNE8-G}|iIud>kp1?6xLmT_elAM9>c#rEx1#fl z=t|+f?)1^3b>wsyg#eR0HnqA>5y<l^%I#GiA`89kgnC?R0;*>_Ob;3BQ`>$b zMZbPB8$-BiO|wCI{!00<9cTs}CA<6;Y3=E$4~=DcvjC}Z2vLW=bROVIi))4&{l3cP zHXdVaM)+dfW~rGqGcVAXvVct8__3zR+7{oVFrZ5xsbPD_n-|egIJWs=E{@&^JJG3U zv5BR1RY1MFg4-=PXk7Ti3+7MDVXl0wMSEWK@?iVwD6piGLYTs@lz0jlPRTNoMaSp! z{C)M5NyW_g)9tJV!Vm)Xv_*=(mmgxp5=-w1hZ@o)4;ki3IArUL83F>t?X2FV=9NDC zDRrnQBAIGj%Eykf!H3`9x-HBSRWbm-D;cU8CWgX(A8uEO?A?YS_zA+BbIBr|2MCJ> z71LsYbY9#tI&ZmK{A)tdhkDUZSs?r}bV?!5`j7>a)cJ-?m#)vPY=6I&|d|9HqwN-Q{KL+6=LE7A>HX4swou9ScSg-A~!0v;?^kNr`RY2z*(_v zWa8a9P;qZ1&g``Ocd=2_CzEZCJjJKnNw$L!4mo(kUDdiFXYX1?8o!AX0|dT` zh9}M*NPP`Y8YROwY-!y*c4N;S=5v{PbnI}8cL1b zzU@Ql`e#?Ix1xAnY`j52Gp?J?n=;v-dT$$J;X(m%!uE^H-ya=yaFGXBdWnV+GC}~j zK-0mgTP_b60hJ7A37YwM|3?L~mi!+gOuVQ|;yQVuKKo80^xAx;NJa=`c-~JtiLT7m z+FEpBf@o~1E5~G59Hu2{skYD%301y+V>ow|^=7;BS~*EBDYjkYBY{co%C1M`HDM}F z4rYA(_^uNfH9!YD+5R`TiXe;7WLQkbj~Ejt7aYG5}+bP&nwj{neKZoA;JTjAo|HM%@AxH;@Kn)EWGE? z(Q5f}FZY2|T(+z^fw%wZFAhn^7j?6SNl~Bt*}S!Dj=IP3=?OG+28) z_tkNV6ML!Hb)D1Nyu+&hj$^&r_#-)K0if+L_oA=V;`RBKo7f^2-X?+uKB8b3aaZUH zzv$}2j@x@r$Oqr?32}(LN%}6`WkkvX9iM0#BSx5{=v7elpFrZXI~JLw75_(gJ|WG{ zFnbJ0QFySzH@9YhB58Zt5AbV!nBA(EYn|?W*LJ1ogkbNZzpNJKUT6`&p|yJ3$#)}s z^h!uHWi2*4!bL~#V!^P6{qht$GT@-azoo-zS;&TL zw+8*6e|BX`M2T_2oUp!UII)n>H$VVywjOAuuZKAwHh08&{uN29$?c!?m`aTiL6WgH z^alO17xtkc6|n@%&hmY-tl9RWT!{WE1-m62LY6;Y13su+kr-sK0`1dt^fFi-k;_A7}xO2kw?P zQ!(dVXWS^l+!6C`1kPUuSsr1EZ!Yo6zAYO%CiAI>^e$iajkHwte3wHXzl+7?I+=m3 zW_&vQ&!-!gbY!?WBk}>r@f6>cXCOv3Jp+D#c>|LXRK}*cy~Jqf^1OsZk~w#&_U}fSN{k+FOc>(_2u*?3?SX^Pe+ACWNtCGCZ87odVh>LejIP=4&|A8 zNz38LSCr%$;zjT5cAPZ4NSy2$4T6@|xzH{Mshhq-RBRuR)aYtr1~gjykZtm$^F#oB zK=73e-wTg@(mpPH@yYr1)FG^M5HLPt1NG_24OZ?5<#qb+BgW4ew=`azwaCy+C#rsT zm#ATRMvE1^EB`^woAj^>f$XhEiAfrQzn4Zy5mT!7_~-T{0o-7mo$tGr^{4)R_Nep) z@Vj`2tE9cpQ=bSmarRfmdm0B!k-{#_?SjkceAft>8UMH!gyC z&;DX2)6s{1Jb*ctVy2kF4aTWgpeV+*q&D=nPY4&w?pyJuu5@m&o@v8(+B}o16lZGQ zjyG8#Fpl-|xpr_U_j)fK#hF=-V^((XIQ}}%BJxP6&SKiK)C!f?Q&2lp^bc@D8k_Zl zQYogHz~W^aT*MBAR`g*uFd97C-q1^ zd@&v8LVuNg#GVq3GgT6pLkVA|`Ub&#oHe}UCN+yC`$AI%{pEFbebV)^-+S(x;ih*p zG&i%LR>!V%?DFk@NeQr-OASiRr#deIwQGuc+k!wm4)B|ZSzKK_1Q z(4adLKF3V`;j{2~)%vOxv%lVJVh00Ni(-0qc?XwcvSXf5oKN9Z zlFg}7-DV@S2i!m0Lg_A1=*@#q-2`H&MKwZiH%0Q9aL{exmNEw<-IbEGKIPA%9?*`8 ze>Ku}(lF|PV&~3AKd&X2)0Rgc(J%|3glLoLkuI)Ec2jK6r&?_)fHQ&oxv$EhU?zFm zwE(zLB#IYU3V_|!9hH}LC(e))FRTCYkw#vLy)Y$w9C64UorhO=ZE@z*%{$p?V=OLU z1UaEB7ib>CMywP{r8%}PZ_@zfpL2V3>x3jJFTU7}3?J8$94l}u+ytq*)^~%tk{iI1 zIML@&rh>2v>shyTjl4w0E`?B-%lWSUFAH$)o2v3_OTXEd{11T9>6B-8Uvao*{C8B( ztGjO-XJi@YJMu3WK{hoRN>FqXZz{4++v7^_A7>P9O^@!r*B6x!1+FN>5w_TbOxnbLbzKK#(oh`v&$=1^ZOQI3e&00@ zb^&CVR(5A6q7`)_nKg=2IaqueTS(>-t|!pqjkn*17ISY+ea@)x0Rf_n?}g z!~Q9n+-f7{E5OykqoFx~V`Ho@D2$!;)_tQ#$SI%ybF*K0m{ig8wfu{D-*3qJnA1qY z_Y$im+K!=#+Vv_;d(l?7+0cjt%Ktz;N{8v6)nwmK^Ee7>`1`MT%H|jwgO2$YPq>!1 zH}}naIjZ%X01`ZBScjpFh-*xkP(?`n>y^$*D=Qt}YR zYPJNH8UZRS6f24r2Cwu`5~?8bh5Ey`1XL| zcDjAv67cFIjid1Ee^ug015%iiT{S{Y0fqT;kq+{$tHs;V|8FFx{!b--!+y4#;e2@f zM*=krzP4U+MD?cs4@>O4koty_+RUMn3dxh+FAU6l_I=`X%47MhQdrWFf>;^HvTOQGA4@U6w$DNK2l< z3CnXtYu-5)0ZA>**Hb94i7%4rk1uFwIpTHHXP`s(9p1TVc}jzIa_GxNKIhp9u!>qE zf+cd0l?)j>tMd}G$gYr z@{2VZt_jZYl$!M(=izben+m0HXU0XRj)cANnlmB^5S2c8T{ zoq=v)kOjk0y=xze4PbLgfNgJc2=@m22KhmY8X`u}FDHr4CXl|NK6QWXjcz@OL~Vj> zk_+QR654*Z@h<-Bc5y{`CJ%{WuU(@~K|dM5WJ_dYH5v(8XeYTVWz8GnPhL(EzC%6A zoWY5}lDR|Dbj^UbOVW5kcs%hTF69?; zgdWMvc<~*kQ_Ue+!TYYeWWnza8*iBMd*LT}Y||Y+)ASbkmS8u6kEw^pe)I=XsMr<~ z&B(mepk4f1heS6o%SpCYL79v5)(V_K~tM$9k-v{145<2d__Ab^KQ$zWg}m zcPNTYVeF-(MI4b#O{MSudFyB@Ql_bO4|u}AY2R58`iu)M7qOydQN7EJCBQ*AC&oVC;oxgmJ;Wz?n#mXAW$Y{uZuFDT`SlUa)~i1zOkSd zA@7XjQ0cIb^uciNgLN(vN->=PeTS#-UKHAE9Zy$oQ4+ev>O=M|)&X2dQsmpX+{Vyz zA9P#GSzt+&O|=nxrR7^tbCF~vR{z!JC))KTx9a{oba}nu9Jom9y!Dvw(!?B%M}E}W zV*PQKl@l(66g&nZy9jYT)&m5y$;+Loek+%|eI*%rHwBeAsp*$;hkI7gco~2mzHioD zh~C(G*r~fqFL=D$scyOY&CVT}CwD@d<5!ZE+SPK8-05$&pWl0SEqja4%B-;v)UA|s zN>fS^8&x)weM_xt{H4ufncbeUOp&}N{JI($b1gRFu+Zo-?rA1>Wq z+h50ISi|Qf%gl*ev;N`T)Y_3u))#5J#^qPR1f7hF*XQat;DC#rL8t4q92m6*Hwir- zVg~!b9vPwC%fa0mHnky9uEs7mU8>lj{i&tohdnHWgz32)wD+?caG-fa+df**owXP0 zkZX08^n%ufdRNhd^YT1RI-l{H zQ}p?x&8Zo#q~q2rvq@3jo27zxrm{Bsf(I6zL^4EGLQ4m#)YsYq22en&jO2uL4_GJUf7LHNdjhOUehYWKRjbjwTgA#0r ziy)QUf6mkv<5EzNGY#j>r_=XPPwXuo;0iR{_7`CvFPncLEL)RKribVc+k(hGI?)ik z2=Rm0FipRf(8d$MIkgoDD0cCHS9Gq;-`24r!D^kjxT;tzTrC!|aHYWvkKRq`?)5|n5&zBw$@4mq?B1(c=y7(xf1KWb4 z0jS=a)FpAhi;`!FZP)lI9aWq6?0!}uTtXv(MGPPaQEmf=b4YP@4>c( z1Eq|j#Y`z>Kd9iqaYO6x&($Hq3DIX?GAlX=buvQAXWatdDvGI>a=-nn4B>TLpOFA= zrM>iNs@$zBoyN*1d!cO~M^Ra_N-}btlL3qhIIPlhP@Vj|$49#-t_i$9=BncUKeFC3 zsLinJ7RKE*I20|#-P;0%;@;vC+zIaP1ZZ)WQrxY$hu~Idp*RHhK+!@u>GQnr_syL1 zFEg=8?)%!Z*4lefr1qc`#o_&-P!LM;=5j~$8FH?`e8|QNL%P7nElKA;cD*B|N5+1b zl%0fvWRH9%I`TnjBUFE#&t!n#(w_OVZ#5O=B5wMOn=tn(uf=aurLVIQz^!T@4fUuv z{kU#fedJK;mhmD2fB5y`O!zLjKQWeJ>uwS%=?nZ)t283_zjW$rs1cTpwpkJ#P5oEe zi*UByhpBy9FSavuPU6=ucU;Yag96LPy8_yOpe*^IyQ!pzia5A!AapEWnaenJOp)d!ErA!mAI~v)xW&5$$g=w3wxADNFt-OWv)<`{Hg5rqIy^bLHvi{l>^i$Ljc_5Od9&UrQ&Kez`G_ni<8 z@PC+C)=C5u%eRJr?h}Szf_+?#?Tw&a(&&lC2n>$g_KqFgmJL5gM5h>p90@(K7s2Tw z6ko+SPmbG%%ALXFLLEY*N)M|_L043G>Y*M^^!scd_FQN+AmO#)bxsIg!r&eH6`#XY z^X!l@?G-oKn;$uinn00=;tuY9VsJ?;u!sWG3g!{)bu6g&^t?`mt?q6Vt{0<;W z?j7qtuB$WAVVLQ&D&GiL*;QAZ!6otQd%UX2ib>?_vLp26NxO8rAvfROt{WgI zPCcAKU(riGtDDCc{iM3w-X}3Tez~t=7JLkehN;OTzJTiIgqON;0*HH?deacan2UQ` z!usM13S@^BlCbVO7ndng*93ztKEUS?ih)zY1`li^)IXscjHbkC26xZ7 zVI1hS6Y!^p-2K3v zvn}`-CMsj)7DLr|D-{R-F^w3StTOK`3TI1^xrwy7vAI*()Ck=ezaz~3fY@l}dy3$# zEB;^!XOrxac(e`l02YC?a@{P%xms%Pv+BkJ9;k}4H8*GD?U>QC(B8aFh!c5X2$M0S ze9HUQi1Ei5?W^R*EOvA#Eg|_zaco&-4=w#+;CWbWmB>iG&8l=o)*u`Ws8SYxUP$;m zMHb*6|1v>J&^pau!@!UcR2P0u7Kxt*Is?XqU7?uZy=hpPI=Gz8_ekQw3hrr$-NQ8q zs1MfmFoqB5KMA14BCDtl%VEFM= zp2x|cP48-V31!lIn~=VDKA3;qS)vd@gT6++buqSHO!6^ei$7{Re$Ws6f#P)87XW{S ziykP9vlwgcNfm#;CjdA@p8edvWEhPK7aP%9oM?Q7JSmi+O!E0J+8wT})N!90{4rTa zllUFi?}8{m0v-iB{Ai)2L1N!pf(c@=BW?w?0HgX6U=w(Ge;3Q%yY0B(jj+ant>ZI8H`SlJpBvn&nr{QAA6Ea|2Jm2N>Nd5m_#yi`z&Hck zR5z-NKp*SuFNpY#OYx#>Zf~c^1{YjAXQvWUhozhmN)8);1DJ{G(AHayZOGYF{Ejl5}|}GYfPpt zN8%t}*se^!E{ySuJU>0@E~jUPFcT2h>BWGAsD$pbh8o2#N4vyCsJ2Pu?A0PZ0HpAB z)pvp_|33{#*@Y72_#rzZ$X=gMq~*h zSOrm7ob#DIiN|GROkvz>|cu-!Tpl)$UU+&0->3u3e}8#ZTI!9&lg0o9Eh%*o9DfOjdyPr5K8k zZ`DAHCl@J%!t^*&zFB;E(t{R;l*H!ekF{3@fULjwz_!d>y?vn)t&TMOJN*WP(_i*o zbPg{XA=>m^=Gq$x;(FSY*NIHz>wzgmu(ul&(jjWML`k+cxoIGP5>;H|`8oSV*-J%bk zCLcp(0xgK~9?)b^}GSXFFj)pbh1S*Sh+t^}O$|mwu zHt-TD`$dj`pqOv3-)iS+=eupv{+Q6Gep?vHU$}CVW&x>8KA>rD5qJ?t70pMwa`_^f_m|&LQ^`5FWmDy3q+#yciz(WT^ICF&3K69 zuBGyy32NhqGw$yQ=VXaPXr1V7N8&TX>jf0?de_ZC?HRo&7)nM6D=_Ji?1- ztI#NKKr+F=iGfFX)r04_clP&uFIik78~@{fRePKVvbvjuYN`mJ4OWlH>?D+PF2L(( z$hosdb8=(2pQlo89%$Xu0oPBVfv-6M9KG8EaohHbDSueMJdgsPXSow zb0TpfMN=q%a<%`A%W!+Qh|f{HYav^8!0n_RM-SLVDWVE}YaFpl#sPT265mFIqn(>l z$Q)RL4&gwq17Kz z8qF~;^x3xIAFqVry{9>bdlkP69O4|P(%Gue(y^C1*7~08 zjwy-$AfkWoh*j4%pp$Qi*EHPyIC|<0>`t<1;*7%n zrx`XNXxPQTNJ+s=Yz>#5UXsp!!(CF0km1{d4ea#+ZWeQ2}>m2kPL}e`86UGXH2y99~ zT5XJ9fuvDG!KRySHYbQ1f7*90fwJjcw{IO}@!#N9Pu#|sQbWiq%@o9tg?B|}^kZ+U zf4NON{kmF`c=RUrrpkS2214y=R~2H23(I<@xw9P52<=;K8TU@Q`6D%3v?zYZ;>L?? zcy-UQeKonGdQ0r^<%NwRFp2PLn)+?xTk8-l<*b35fKEQY9?(!bkN<}`CoqR_Hp+eQ z!JoRgg1OIEZM`S>Aw{9DsD+f@`puQQT}% z5Q$$JwHxb17#_Zf4q4~0IhVU#%KmqSj*6EP9B7-R7Z|JPbaD4S)zt&Y<|h`F+z~L( zu1z<8T%r>MUPAW00Nyfnk6mj!^#_yj=c45*!KTiixJRV z+Aa1uzUAMTSOwz$j(!2dr~Gc_5g-4Iikx;Sj9KXCn|?}ve3K;4uu*w=M&Ao;7=+}+ z6^ypoYw=ZpT}|1CF99*9Bo4jTpM;{V#KYyMaD?=Nb$nWHf<@NgYQ z6VpxY8$uI)JW1*rr0u>&DMU)jhCfd}W79+@q#~%1|4NI#kO7?=-ZX@o^L2&}96yO{ ze%dUeO7tbLpuH@Bz7W$ziGdDTIZeTG6!_~wJp7gytKlG(?>91=tmc#rD!`A0u#c(a zd15~ed(`TEF4T|)DDx~SfW!lyF8rt<#8w$%#2O<7k3Z71LShHz&%P%{su;Du%0#o_ z%x~Aq^llQj=-VEYra)AG2O-ZGC!%*(h)EfEqr=B1UcEHwfpCk^fsV#srjTMX`5dVA zRHLg9@*YC-W*e^I6|hJ7FjsA~A7-#9faDvkM9|!e2nh+6rV;xJRHDeD#M?QCxAoXd z_$S0CN#M1h;S;I}-#;;JRbL=*j0p1B6+Tmq&n`koM}t8L-}d7J`T-Y#lVhprFkE4J zT9D+%ByAk}UZqz9(#RuPOHZh|mG;CNFqCw&r&J&>E(l`-^&3hbcf7c-IO9=Ct*4s6 z3pZmRBwFPs%S%2Ug9KF@vD+wzDV@$Csg;sgDpm1N`|>Y)WH$}3TSg%vk3au%*f-<%=;DrQg3HorVs{==^}=`cboq~&jgP&iRV1lt zZMj;>zPwDPkM9Kkf`*g>tPy&6#7FyyHwysEzy^Tk%@c+WG$C#qKM=8W{oV{Fc#(iZ~?T?5=pfrTe5=)sQKi?`AZBH0#)jlILSL+Y$@H_O`Rr zccTzYg%=v;(H?DH4g7W90!z3qN^LWAG_V;Lie+*hT| z_TJ5L>0gB{K@BbEDS@O%N+olsWRnnmGp`~c5&`D0j+{a83N0v@Z2iOJt-t#?qRsP{ z8Mp_j_Cst#bs~f4lINnz*)iMc;LpvsXImhX>z>>FHXF}o7L_KJ4cA7w&`9m&Hytd} zpHh|xl!|6Mqfo;jB4uNL%G%2FzG?jF^>QuW|307bot{9+35CoqKSS0zPzf&>7aP&) zzl=jwI$6r_YUKGj_06Su@%G8`lsge>Y4nX%<=gG8-`dwPm^)cSf|LA94@4>Zv`=s$Z}gyvH%x2xA`DtK9*65p^4OVEsN+e z4&m20G1an@0~KVtRJxEdQd`vQeW1QaVN_4kDEK4lP`In)!8H&<#e;!tbD=vv=*I&z z4PetW>4nlPu_;htv%Hcagqt29@l~LZ8tsP5ZoE zvL4$Xr6^~jNIi100nc3_^;OXr_srl8vcN@fva_l4j2hIDlHZ%>TU%o+-`TDsS!7^Y zE5z#5v1X+*mp^!MQ$6B5;7&e-!7OXcV-ZNbXf~7YI6Hc{7%wfpOr`eg_t*t9&XrJ-n@sqBg3d2)Q-4)e3 z;UlM;^fn_jvwJ_G&@c0}@a)C}Um5rVrxE@GE#h-TxHOe7&Pc-NkzJE=6hKG2maKGn zJ+C5K1jSDg6uc6g;YI^uix%c(D+GkK~WWox`8)-6?m0Y>h^RwyFptGpP3nsl;n zChOT5;Q>prEp9Eg^MaG#Vfzt69cO5}01Z9NS>oah)0{!%$!p@!`JPx)+MZbYBGGB1 zlQ=cc&ipy&0(w`^WUE6{INDk!OzNbd-aZ%#zw(3DW9L1@2owm-kOIsK$83^Qivw<| zGKi^7JK@aaD+b4~|3bG8;q6C~LneS}gM`xF(2@c0;FL_q!R%(|j3zsV2 z%L(edtnq(nwP9Au>^-#qs|8RFB=K#6_&%3bSZfFeDO>!g)HW&l{#W?QlQq$-QhWC}LQ<%!CJkd^ zjiM`XYkWYt%Qkz=kSDvcA>^1kRZZVk@d z!#ZPm!}^gp{=S!W$rKp)(&VDRNa?K+vfZJRQp_;P4wI4yo|2JTB+B*Ac@jIRHL8+; zui(9E><1&P$B%d=eELMFoEiKd?1aE#%El~mciQ#?vL~L z>vv$~g)uKvV^_BbVJx!q&cD@jv zqL3Bc^?H`$7vz!wvTf!_KU-$x_=Wz%#!pOw5|$&Q)2fX}r@y;?F znGVE7dM{)cjd3M(=f-uFVu?ac29)xESypoS##sR0iw-o@ti`DViQ;@bhiClqBSe)} z-)E)1PFRAOC-2_$BxHjNx#TQoW_iw$|WOO|LLMLq*I2%Wj@l z`?K&(8fUAfmDg*_ckLN_?vG(q$6=I2Ax-z*0l#HUk5$>g`+Pij`~VOi15h?2;+J6# z&tBd}n~9ekl}iIsiMmTY6NJv6cxJ4TuyKZJ=A*onC>_%2gaM6@{adtT)aFTFTbWrG zn27M5cE*+g+lat``@G#`$V=EQkN>3I<#q#=B3=$l(tFy^u!|;b!+L1z)`Q6d?M0FW ztTie$0U-8l7W%w`Vs}1cB2B1qE7p3(&+S=|jsq`GSFibGSqh2w?Zqg@YC{)`1YwD# z5el9k!$#%nDM7|1zrY)QzO6wH@dU4akQX%rxC)4EOzgtN=M%kB@9GEe<1KRm^|nrh z!Xfz0W*32#a0Z>mzP7XKs_C>#k@I#ccwuNE>iCph#=en_)YewqUzvigrKf`~pXw&E zU}XJ>cDi|oIV1k^*x#*wufxt%d;(I{?Cn!Y0m!N-+<#AV*p-gwRw| z*x3K_OxQj9Red?h=reZLFhGrR=a#$aVf5kZIvYsR49ca}9qh)UfCR)`NwkWI zL>fWvXwi{RZCX@>n3J~b_%(7xmx;J#h8o|ueATQf^6K*Hild_j-h4f2RleD(7aZ~1 z%gRcHFW_c~jR>3@&<+9jhd*s|qL7vPa!mmELCOleUsj4t22^)H#Sqwf`p@mkFS;f1 ze0;Yk50q}yn%_W;fv@)5o7_Ys$eg|W9@A#8rG(9Za)wDk6DYSmpvsJJJ-Xj9fCYf+ zARI_b3Kj((FA0d~A_j+)5T1dwq$>P2GP1wm}8xKFZSDmfCTY1 zv=%$34nSb1d)8hywNdPCYXKM{oV@B1!*-bm+UJQr%h3Xroi{|d$HjM_gZN3m%Zm>d zs98mS3=OlkJTTny*}#3^LaOPM^3)f*rCXo3Na7(i5$F^|?5WDjvkmhwc0{ZktH!#b zWv)?5M&h;TCL5{@p&dvrC+Y35$XsW>`$*;EWZ*2x``b(8>^ln8qHm)yVr-upA-TEQ zWCg#?#~@d&B|xr!-yII(gNYI0yO}q66eG_6yP=wfJ~3Tobe`3j7^eV@cPNA38bWk= zN(Na&VyIF2yI09JmvN#weo)-BjE5Rf^v|$HZm94pW1F9K*Mg`^j4& z3aK8mS*Ka`tgaT;<2V+x6-8R3ztYR))ZlOSsmAk09jI_c1a-|0dc2*gc3#o#J-@e; zjV9g~=uFy=vlYnVw}UGjezDo}+h%H0M&~jOuS7jaBa0gbOGLr5y-mJ~G7NOa4Q*^nlGTvFd7Hujg%@-N> z1(<%=er^9u4hR)lU7D+8#5}ekqjKwapfFa^x_UU3;cF;gXc1Zoq)19++Ykb{@L>s7 zS4mMR1kjpR@*U0Pp=#M;yGcNr_F?*wwx8cR=dFBD2@clJ@<`U#my0$&H}BTLLe^No zv<$T`!ko+RFAc)e6j4m}^XHPAc`r}6`+E{{y#4PQ)O>}CJM2^lmq1@QOls{*3paum zw86(0T!~x#2J&d~@a3wkXtW-Rh_WdZUFx}42VQX4`hn7!%I~VQ^`^I-`_gjfKah}3 zZ?h;2A!^}9Q|;O2Lb<2~J!IENnX!gxsO#F7FM!#2X!cO-KX4jQ?nMc!)|UZr#XDtA zWk}5H4r*ZK$1ZJsuPR;2ik6Tm#1snbBjR!Ozlb}i^_pbv6M5n~%4R2#=hTuj!7!nFl;# zoMc;qhtJagvwfD05NtI0vNu;Vc8!i*v2BlX8O(O7-Wc&aXhlyn&H5!UJ7RZT-vLMr z1wv%OQQ(-$e8zq*!+emgf(KrK^JVd=+Pq1ucgJx-PnDNk_X@%w?feDHh;$;{jts70 zzkRw>*>EvI>t(|=?2#H%$lsoUbbpGePW-bBKhLyX*dp_8r%O8h)4<^Zs-&*>c%yvr zdq*WasF^H>sRQ&Jyo?3NsmhFBoAsj5;mG2z$eC4o|NjJexhiX*Y#xOn|Bfa^YNq3R_1J z{kS9=RF9ZRlz|Z3{bShwLoR?6Xmg?GOPs6qLJ3vFY5e+@A~YhLHB_j9*%z{OR>+%MgS2`pN{5 z&a%RJ`}f;ww#GcW)r3h~UCLd&lU}F#{;_+z&-qQmJ7n#y-Qi1Yz~r4T-s&Se__@)q zRa!Lr9QEB^kzYeJX!DZ?dAPdU-|Va!`J}TkQ?t6Ys`x5uYNEs>q@x>!2!t0~$uEut zfA#fR{jFhh<9=-l%6uOqjR}5^W$ckU#-n0so8kCvKE9o&_R{{M6s&$dFCD5E4`|444eUZ0Egiy0{EV zUfNO~G4D$`)-Mtm42VT#%+y$)uFw`t0W%3`CK+V$Q8R6evM+V8p*ab_Fy&pc3?pk4ej#{vi0P`u%3( zy4_mSxFOrqW|;xaja`BJBibEgPxwX=iN@Qm5xmiV2e3H1+IaYLzpzV`YjCTlXUnNy z8A}dWjMZxR={{J?`FHUPpCfJ`15czu{Yoh}hUM_#CtM)tv}br#G#f=iB>`HTqgN;x-(Y z#H}BCu?Ua?BY+JTjYzJk9=R@#Xg$P6IV&j z+G1Q2H~ypIy2}%@A!w6F*zCoi(~Hv-s?AKZaA$5TCO`x@8=p zJ|0N|#qM9}yCId;{LHKvGE7Lv~ zP!AQ>U3XneK$3wvUtP)mK1prO4_|Ig+c{7A!Qjz8Px+70u|r0)pUXaRjdT^)bP~vQ8A_t()U>uUeB@vzFqkC zQHtX}-Lnkl@`FL+itm$X-NvcTiMnSXZEk^ckx1K*O-P$R0a-@;U>YEw&t-ds8+c8F z9+Oiua06;iQgV@60u4mk>Upba%Q7}icaRu z=VYpu;rp>ulBtYhlcb-2VJ*{L7n?vrKhM{p`3Ci zcOfy29#QJaiZ-NXNARuX5%!A*s%rDj%=>#YFakk|Vm%&(W5xq&VTfW@;MGHGKYPn@Gp2l?RL0 zD^y@ECBY9;w7u1Dsqft9I_s+>Boid!#AUv$)8fa&v~0F)@eK3j?y^^TMb2rF{n5Ay z2z=+n9lpS*29cA%afW_Xp@xDPBLPJ!0M|4he*zbQ`Wd$!_ou*A-&Tg=b%^Xl(?a;$ z1r&3hFUS=`T2bXVB`J;V{-2lzS6A}?5+LE>K3GP?2Zz61i*zTmO)>BT{uR_!ez)a6 zjxJXg|Jbc|Nk1W&kR!KspTG+6-ZHkvc1#?VO;TwFQ{o4|AV*AT58;v3jp?A1_gA_y zpWyF?+9Ld4HEd`%^6U{7pUxlG8u%sMC#S?Hh8tt7o^+D46akdgWZRv)6c1|HwiDNQ zjm5OUQLxVCZ`gsz9P@$u?A8_sa_?)LTpsSy+Z`n}prl40R$Ntmj1b^s`jN7Z#B){_0w`j5zuM)OXd;Oy357w3kp>^26pEPm86sZO z=bnj_b_)GJkfK`VbcSyb^{Rbfc)zhaCU_8Cw!lUk=zytX>}6SFQtB79?{P)yJgcAwLN9Y-(HGe5`mXLhn25` zZg0?~NB+Y@pO3)lGg)CYF!Af@eVp=IBnzB^mw;`!4Ycj6GKPgY56SVU23Uz8f3!6} zj&Q8;>Rj<Aol! z^wmvL^hhdhBK{x`6`t1Ll3vV846n)L`_Mvya|IrXWyXk+qIFMV=Gk_;#m|5q5&)2`q*HeL_gz}+4(y%0aaEKsENg#LY}aWyC(FL!>Qvu8_t&Idc??|u-D6x*2qXfXF$ zLUj^U{BE>aOI=sX42F`@vz_qFh+mNs;UeFB1}EqDBa`w@h`m8-q7_x7BVGiqenl#O ziJ64mYkLt1N$t(E1y}_`@ANjABL}zHsGj5Z=eXNeNHe$fbxI`|5UqnS34IWil7NtdxR(uq~$l$jmP@oH5mGUI8 zFf}yVDUDWQWI_JGhrtf*>(YcW`Dea(9zoVr}8sH)G}6wW`UJUylSA<^4&Y zxsG}Fh2OfXx#2{IC{I2E546Jk_ZfC1itlyBX2&TiA}JNkKb)jq7da*a#E+# zp}Lz)+;uGKZv}^{tyx0PQIoqYOxtN+AL|MlQ6e?duZ84Q@*U%b=}%mpSWWdTp3dR8 zuY%jhz`5A)*K)KFM2*U>D&@zIK}yqR|Dg_?o8PXt{b92lnfI=aG&x`?)ptrcf$`gw(%9FlU2==IU^C*? z#72}Q*X=o4sY`_JO5l%8qXQySI3~o=x~PiJVa=h;*CB&pU@-l9#<|sS}$~fd2$pP?@SQ**zXf z&{^0{1onPM+#H&Wmt*6XQ-({>6I_n4;Kn%^YPY>|__OEP0&|KF`|uycE*D-qdbL{v zqmufukEFi8VMFP6AM3VuOzfF^z{czH3beZW4;d#GG- z+^%5yuR9O9Aeam3Z&J=Xw#Ju=p}M>Ih5qrm?y_09`A7M!5ec*Ga?vC(QqYf;E~ zzDm9G4&&j-Z0(D&Bt?%~Z~oZ&%i;r+jrJAG2Z+bdLZFi>H41^b1%pgj=Y8z{W#Zd1 zqhlY(>VXya(ry9(SLZje#buxPVlPL8s=%KDS6N_kLVPc~kt6y@&$77h-Rvj+D%L9E z=BbJcg{UYQ?UtFbS+wHs#L=0Wk26Vdk7z6y+82g7%$A(F-H6IfWJ2ye`)R7|s6fPS<%vSa<{wJn(c)h+FLfGT!Xsy7@cOhak5q83h{cRy zwfNU=Qb5=SvoXUrg{0T{6~D}T|6$7~NcihoghHL>oI3UV2cA8+Ze1ARbFMw=qTB!` z5p0nXl`o`r?5pR42mJ^A9(an1hR<&HEeNRmo4`-xK5Q=X6Quu=7<*-Ex&O|PzepP( zFzZw5DO!MPAkX~h$M3<}N80uX8iaTiyGB@FjxXq;t@#Iv34Uj+M2}!?Dzu(GQH0U) z%UfWj_=opaVHBhr8E|Px?_Cfj@y#pBVbJn$WOvx3urB5-mzcwB8pJ+dEG0s2VnSRZ z)dP}pMdx?a1ni|!vF5r2S}1HS*Eg6}K(bgZGyFKW1FHp*%OWBv@v`}ypr53k!d<{T zvUG;H7VED!hgMxzAKV4@{!mtXndx~=^LKTp9lf8VnDibXsxsuG(Q;1uwXS0+;((`@ ze=7*M%eyzuXE_PGC6?6Tz3{`|D_O%z%Eem!NTQDw~8=%ZufyInFt}?i#%E3p}1D5oh~V!T+hl zn$rKb4m%nO&^1dbG1=}ha%l_6J-hj;oX+_pz0C73KmR{;&KY`5SpUuEUyYV;M0le4 z>*WXoDg$P33e}b+A|mI{uhr>hs=us}(5u4LUGB3%tc-@g(yN+K`xpE8W0q5Bz0?=p zWnbtNEI)=9EirX{u(%R?9aom+A4h7((m8byM=JcVbI|&!eb#Yy{~cjc!6a4?XGz)cxk7_d6g2@A0>4TC$V9-D_v+Q?0_SrBon^~rk z`4o8=z~vOP`G6A1JZfNqZR<7P} z&>!LgC6$8s1K&%KX>*=jHiV{_Z6nz;V(t$a^(ASXNpLM7|IPpIAGpw(&XwF$ zBZMC6h0^p5i9rqL?*sO1hMW!F`%P94ng7)SAcWp1amQGT*~oFWXdA+Jy@C(1zNtQe zp%*4HXpcHj-yQ9UEA3K=OqqwQ^-bwM{J>Dn(FgOoyuNJDyD+O`?<@69Q7$s}C(VmR z1hTQc+a&X=MX7FAVQ-Y5J+pNBa<715M)Jz_ML|OJMgqA6!%SZs%BUA!ugF~L{~*sZ z8Mpe+QS?I(YySC=T8uX3?jf*pL&_Sbb#Z(YN}B@(^I;=x4aF*f&P@81OWkQgrdCK2aPV}!7JdtG|+9vkDDmmCp?j}*>U4& zGoK4B-iQ3VG;m+Os@UVO-IGfXK_h-F*N_R}h7GT(Pwpi`!SI*TZ32O4HP5eQsFViy zIL47aBR$ey1mu3aY7<264Xi|L=MoV1u#2_uPgF;A-Me;awslljMEHQj$gHjThi=POt^eeQT;$@Axvmma`+#lf`NHoMdga* zve6CgmHct;ck7~O!<;b;?m&WgKj4aY{ zgMDRjzBSma=i3^Xbe*U;ND!(95FO^h^Z-3hbu}*KC2sIeCp(fuMHH|$N=WxOKHCysgui8rMrLEo zn49@gWH!rU=T5O_!y`gJ09wFz_hmC}vlN3r^I0-q+&2lF^`!-@?xP4IdvwDMBWTdB zOqQzYbz{A(LX9|y z4)rYwFF`lvxGh;e_EpNys33^{#XBsyiTy~H>n@74zxes zB+7GB(5sm1f!6n(ik88@z8?Vm*se(!^~yuvMpzI=5WH}`17Ms?x~=N~6{s|oMpts^ zBI0n;U5|Y8K7CwPTmL)G@!N>@R-p|7wBYTbq2@wzPVImYA-n&G$GtMVy!7dwlb}-w`G>k_ zMu&*NrZ5-+5pcPefa$FemRHJ(kW7phQ+e*+q&imgTF8YA*|W^hcJ9C8)Z#dgE7smDugB{jc@gCMPiy#rk+b`^$b}4JmxPtS^r{eX>Za-^KEkevuHQk>-87KS zS4eX3wZ`qTZIkCeH4S>_qXG+s1($VTx4Uu8#_-iID|H5Z&<@c3 zJC6cFER)Dkylh>OQZ9j0v_n0(>_GrEW~a6i%F@D}{9M756_|!QK5cF+#2Lm_Ll_;q zSWUu?=MVA>n1O>47FxQqImC+5!|?dnb&WOqHJuQOct^y^7;DiI)>Y4E`0`!6Dz8LY zre=OB$}520sZ%|E@f>C`Z(Fqy`H5kz9w2a9w3tB8MJRB3=#gYvv?#|=5R4fl_MoD0 zkbR5SLz*v14(M5r5d)W~s;YcNQO|!StfO>QV^uNi^SAqZN*SNS2Ts>eP@8+Z@&y=yWE;gOP; z_wb+3&qy^wFduqTXF_$KTx}D7#JhDXc{J^xbNo6}p!Ep-pvW*|;qrTAcRF^31q22o2rNBb50;^14b9fz@m_7e2*;E#TaeO#Ym>g5+7=b;S6GWgE{N;g>HoZts};= zhC++6+U7jU=t&p0GXt4A-v>xLEL+MJeqfpMg7Rf;ZfY$)ZJad@f(OQ{~k` zw$fs5;!FjLPaaedQT@-(){h7ZM<6rxKMWr*1+^U4rPm)he zy`A_|2y}I#T*UTn+CxU@5gar%>B_;swIH6M{Cs8rT71|NV}C1@Jl(WwAFU;2>*65(mz zRERN;IoJF2BkhBNe8V%^K5L*f9~d6;g*N2RDBVwyU+1mCF~JxkuEa>cruxf)p=;!l zu40s*hWCfx;NaL(=54XEV^|R*n9&6Cp9nryRSn-25cP2=1V!0We}Nv%&b_@Mx?vG> zwQ={ir)qpRi+Na7qX+!ZzSbJKU2Uin3x|wo(`>{KSgQ{Yf0X73t(!s=aczX}bftMP zOf7#~(XKHQOQ+3ybo|aHbe;e5o#ewE5=9p@jvQw;#}Uh;6Rl=e?M@v{kh^h2QpUa@ zlXJNEDlSZ_LC#uyrl#2aNI;yEsQE<+6wC?X60GVj#~9%vB?oc2PyjOqoX`(Ox%@a` zGhP(?NahLQQzP^ASOTN>7afKD^SmV^vSwzH`>)0?nBR8czT3(#32KYHiF<<^?A*4u zCv`h<=Y>$ZXVkz#OdRZ-`Gb6uk5t?rUtLHD2H$V}xJf*8(fNWedCf$X`{$veSDW$D zc0M}azYrV~Y8g)GWMDaiIC?gn^h?D}$adgWj?vD!x0ZNL_TT}vYXm539G@HIg(IPc zFw#>fzx70-+dEL+RAVL1?;u{DX#;rAvvrh-Ua0_{$@MwmvA2(Nx|6n-16gQGi;4Y? zSeE|0+v5L+tg{M;vJJa6-AKa>AYIbU07I9cl+xWGB|}Je!w`Z@=tP_pn=dYBgIWgQQ)>UDG`&H?FbPRSa;(8hTX~n}Z37d0WSbhk zIGzEG{R_p+-Nj5(9gurXG_;Hw@PF5?hTkY{?2=B~u98X~``Kk2WmR4GSvj9|0^+ZU8iAoF7lS9lx)lCVOI?92cXkA!ws4e@K}ktf?Q+q$R|cYn_M zJORL4)MNSBCOAz;h)u{&ZJZU!OU^6LYakdo6|0kI6|~F&a&G8|k;oBI<$=%U*)FO2 zRRev|+t8^Z9A7@^?s@^jb{K_dgvtH=G=r;%?!#GIcHX4+b#< zwtUsioz&scu7#RVhL~7%Q)qQjMgG8HeKVW#o=Oz%G2=k7o{oGPKLt~kLhN0!dXv!p z6k(42{M_vFD5`yzBupkk=1*{tm((WD0mGbPV!L{B?m6*?xW!6 z6O=dnQGT~y8osOWW}tQlcUV;pcnW;XNlFyE%oci4@*>$WZ|^-|a85vN3InZlybv60c+3%b0Ea1PR0$x-6uZmzYgvp5bR1zkh*#W4(2sGUg@jxiXXQrh zNvQFMASvSB-*BO%B1yrKuy_SLk7F*n{uTGEUumanM(nI2&p0nU7g50u-A##65z9h# zhv7_<|JdL@n^Wt7X>!k_-VaFd#YWd*zjvF!{CshXslHHGjA?im*$FdrECusFp(a}j z=bx3133S#F{=Vb+-HyH``pa)Xw}~2kdZ*5Yw@pncTM7>WGU=6CTYdTcfW-3XkLA1m zCmHz@uTEeX{svj?TJT(t2g(8!*m)R+kCN+?iUzZg&C7!#h*RTv?!UibF!4Okkx)BJ@||xMK@=IiN>}0H{`9 zi{?7fKHDDs9CO2|%BA#KkL|#h*P?v)y3MaHV~a?NE3*Q0BGwJ)2k=fXi$-^hgKQ;) z!T>Kl8yda#K!%0gM(nC@aoR9^(HAkxiF)~#Y~cm5hR8qFV`d@3dT4)oqrbGugd>3G z4?3sa+c)^^A9%J}7PoTKf#0pZGdWY8QMyd3qVEpFfxKC*{=nyUHGb>#EYSDGb%x&l zr6RWU>8LQTdosVjl=;Uxr>H6W_0K$F3ICya|IoeG|3&vKYF8??ZM)saX}jKZuB81V z`wUCI-HyPTQEn3n7{w_3S@UjV*N3?jMH==CIe35U||BA+e^x#bmz^^|KYwM8_ozw{Lv4xNB_$z!0d7HrJdYJ9oyd6 zKYoCFh}-{I6wxEkDrEExY#FroBoOkSW&5A_td3?_&)iSmhZEFWpZRl+c(N03#>!ej zqa;2YC(+!+W@h6v_)*c%^Hui=lnQCo7KPL~85o2arr9lFl?2h%8hS?j`X5T+9N?RM zgO&~|3-X9{$c(ek=0#VLXr~0SWc1_|A@--De ztRXrOHU~)giro9Czd(L{un0nk`B@|)O|Zi*T>vj$$vB_d4x~&jkvv4j(J+Q&KAjBh zyT7h-_DGe;g0R9h$={|-yF`I_ZTl$hx0YzOZ`Sm}cKDTVqrcvs0^&2K+WG4RNr;$v zV@8Rri{t1(`>^s-BGXqzK~>o$|6oARksgO2Gn?K4i+J4oyW2C=E~Wp;B`k(nV!ni< zjObA6WD3JBepGt|Wi930Z?73NWTmL?3Bo@=`tm?GlF>~u-snp7bdPBV74N%AN*V`6k17#!`J_c+MTHr_g(^fSF{By?!?H!u$byn$! zQeo^Gx!QVUoAF6B{fJ!^7j&Xw5G=<7(KP#>zbE>J1a z>(zj=_M3s3B}@A+6KtQ5u%hA`xg_-seTB*ID4qXFb4b?Ro9y2haB~8b`I@j#`fmdezmHe!@uTxp1HS?T7L=9P;aBO8=wf%VD&QA$$3%4;y~F&vl3rjE!v%*ivL& zW(^pJ@Oo0RDPu?)pqZv%)QZqcuFKRWrMOg1H)z2Fta>+e2P{Jzl7d5r+=GobeVV{> zVpL_NnO&P9i>P&Yv5QNE)c1u+E8jO>81D>w(pcGyV~_IzocJ7FLk{tECWjgUpX}+y zK%(giCYAhesRnCCjwteQC+^a6c{N&p34MHFMzSh@Hs{BO??IT1XMt9r)Xg;FHAE(0 zHtHiRj@OOvhjQt#>N(M#qH3mWtxu0xYcg)jCNw z3FRv#Ft_6(0opmpD9^*SpxCFftWo@rhg?tWWe*<0d2yRsMDwRR_X~QseU(wq({y)rVty8f`O%wc zrrD0`mq`?Oj_7G7?y6MD#y9cPv5DD%cAnj{LvnonITPEBnO^+cwV{k?k3OIwMgzYs zR_ATF{2YIBpZa(9Yg*;dT9KTy>yCfzTl8_-H52{dNW$p6)?Yf~T`?XS}U%!u>E z;Bwu(<)c0`O4w=N0=_ZW*~{6x^BB_Vv4A(}!VXYCeu!v;w$-M_)!&}MH93!3dLI01 zIz;F>mJSlN77+~>OF$a=sxFV_p9;*`Wq!+jC@uW8r`*OY#C0jf0*!aTslOt#q6ICX zR$K_RewAo&oOELf?F07*PMl8i$3D{If_jCG53n#1Ednh#>6t7xNI%63Vm6HuD;HcT z`?sJofz1Ae6oL;@e{V)9=|VK47v#!vPak+@@{kXWvCNXxQnq!m9Y`a|X{d_DL=#$3 z!HD0@5)<+PuT)dD$$#0S8Kj--D|#PiYZx&*@L%YxcmRru-_{M9SX(r@>lmr=GC{GU z&kaZhf^u1>lGg&YN0je;%(ndHPIu*-=t<0;Ajg!`Aw8{DXWt`d zWB2p~H9__T6d)Y-m~aI0lB1F6j~`1s!KO=TJb`h0A<2q3A%Y`JIokFxCKbRT%@B9h8uIyd+>3c!F z6sFk^RqBVU3od;m;*gJc4iJ3LZfs_dHzAll!FG@f?X{cS8fRO7$5bE?kk zhvSKF-^mHE`NoH+fd2L+U2xLk-u-4U=*)O3=`j>z1ukMFMsFcdU+UQF!k92Y7Md;y z4>maE%w`7*TOM?sSJuYrKP5h605T?>SKf#9kp)>#b39&Y(CwCY3b$N-sVcQTmUl&8 z)83Q*J4J)A7U$7Eqx-1ki(C z2^K&$*?`IBhqRW+-j_Q-c9+|E4(G4)zp@*aaFse7at~#nfmNB^+m!6!lk$pMM`)@k zD8oA4%K1Apgc|a7!2hJ(YBK^@f1|K0uy7h6ewEmCb5Ao2es=d%^~G#ZK*>4Z?4JL~ zUeI#ffiivM*sUWxjKnr-)=O{*tzh7GA}~i|PAH)IJV?e|i9sJM;G`4dKvx#;MET&J ztO`y9n?)k#Bl*_zX8y264SHu2>Ew@M+EyHE!B&8J}45^ z^=5zh`}o99)G_D{vyy`Yx_dqwS2R|NdfH}1QHy()2u=E^NLlbO_Bg(LSrE%=`#UP7 zwnRc1fmRRy-WL0MZn_-5@^})o6KqtAFs-J>boqq@ zG3z9RTi5JW`G$-yPDNH*B-vqis0lm?&=ldqm`bNa=ZQIscBvbOqB6-Zy{)~`e}X#m z%3ZkBGP!?ungwt7+_#9PTZ`FfD%7AGWE(lcod=vTW;y}lOC)(XQyArByB>Lpc|)M1 zvplis-?zf-S(9#sd-SY! z(5q*Fn0#?W@V?NBvOqQp#EPgGILEJm)7&g#Dff8wS!}beu|ZfpN`Vp@H8_F@D9j6I zedwkR=G7&E{HDm$dkaH2kLiEWEl3is6GPxoECv|89S|)S?U3L^1YxaTZ33Yubj^1P z7Tsp}SEwsR8Gz|RA@XUzHl_gG;lO#vj~Mk#w8l&fOJ2&G$Z>S08_3+po~k!*h-@bl z(Pl--;DwVP;(hT1ZSk~8;Qo;Yj45*X!%8v?jno7QU6Zr=VXj-FPe{@x{TfA%7WvU5 zMD-8Lg2;4!n@RH%vqbbtyN!{jRZ1E5Jlac5%CZ5wpRsyt z<2R+c-YbM)-pBw$JCA{ne}XUtTMzZWFFjw_Fl1PDEzF&6HRJ#3D=#tXr)(W^*MKYW zgJ!o&vl3oqCTB@2%@?ozQKXdjc(Kd=dv5zwR3;*oCe-%S)8>hht5nB%9QXGrAMAE~ zLJw!C1o_=E_>={Hz9Y#!($w28$NyYD(N3DAageUsMt*d^B-r2q3~x^b5V@n{$Wm(n zXSvmKQ=EEM1z zg<2%F)ObWdYXRIMYa$Z}n?=C~supp+9@Z9zBkGZ!=1t z;$F(J$@<4m|HpL|U^1TCuNv6KKgQ5vy3=HWUmEm;6#Kas5HbZ!_J!Vy_`CX^+* zKw&dHT+|IlXGopU7eM>Vf^>rwOWnj)F8IoY=!|=QneaEbN81f1JjEH5wV2?7*|BAE zi*w5=39f?NHeDMTY(2P7K&Fzg?D1X()*r3)p6OIeM6Pf@mxs(y4Acw~GkqR3Opv2d zJ^B>0XB_e?46h@r-Xw$h zJVi(PzmwTE00i6cqHi?1*VBz&NZQ^o6h+Po`Qt(!F=mQEQyAXuHj_W)Z67x+& zMv=B15(~f@(WDx_I+if1L}IU4ypbCy&=C)@G`9vih%k0B6(7(3y^458|6M=>+!)xT ziSsMZ(A>_+QHzL@=0bTixw+XtD=XNi9M1JZ~0UJC_QUoUXtO~Z3HM-K3UgXrKAq}ngQ z2i1~|sXK1h^m^t=whb_rcvQKyLAy3zBif>c@}48LEicQ&C5=eP(^{H#CeYiNWC%J0 zebzmh&>}Ch{HKap91Q#8jBL7>%c8aY)a7hyb&+IY`C7-R&ghYoAPVl^C#EINp?t}? zPrTo={G8{kq%BQ}07vWA}?)gh{Oh8CGQ^i}|+i+{|?&9Zyf5W|3+44L2Yv4nD zi@xYIWmb00d;lbJ;8F#0>B5|>qD^WjF(M=}am`6fK^6Ha(MyXW)msRf2e>dGViO3@ z(H9Y)lA+21&t^d^9&#fjyRS#-*W@wM%fHru^Q2<*?TPaSeQp&My0@T&>D#T;O5gbH z!TMU#eN|;<$@99f{j{Y86RXd_YIXy`cMppSU~04}0xikJk?xs&YPdcDJDukp znCUf5*cBfTWZ#-F&6>_qbPs0h^dd8#FS%EgFmIZD>xw#{Kfkxfo+dDJB`4oB9#5E1 zG$3af{^Kt~FwehY@b+_EDw9+k{Q*;qoG?SL=w=sI`9*6()7RI0Xk6*?1AJ&2z&PTs_9|1eHwPTL>R{!bzVa?A8l7u1zK{+me+ z%Z^bmbAr-mth8P;lnSNb$p}@E{mF_kd8VKjGQVyJY$^Q)$02Ua*V^TU7!RRk+qXi{o6#AS@s_xhkP^!aOE3(iDyz zNyx#E_H-?JQOk@=+3Xa1`KKUFSw!s5K1=-`vhgteCm+>o;uKcK^BOb?>;XJ@V?Hgz zf9Ysa@;TX<@~QGtel6?*UJ;f6hs7u}*zjo_QaM*q`r7W~To0DL*I7yD$ zyQg5wv^Z93M&_9ec*nOVyg8^e8@;E67U}7Y`IG$T)aYH@6xjPMbg$rd$oj3mSYyPmO?)8dC>wK7%3hvf-ld>x-1p=rsq{Z_wa@@1tVJ+cXE#3 z2O`V7YK&c*qGQp1l_4xARUSw&2Yx?Sc&wQnYMsgs661Y4ol$Py?`KC*;H z?gHE5(?`Z-G-6#?68T$1=~rxC1g%TR1w2pW0ZVN9FBR#K;!YS@qwlwVY}kEG<6(mSDU=}k zBpkvbptY^6rXLf4@W3L zH|cVq)zz2zpTt3|i2~@+<>9Fwie^?awuC9Tx?#&7A{gU~;eQHV8=9e)+O3eB{MqtrtUd;Vki$dbEyZDfjC-EmB1Q0rBLC+&|C0+2H zA6S@%Xz{|%?MZ7sN)sHbkf^<_69H`QCRm9DKGBdZocIIwItfI; zMpA@}o40u=fNZCXnS=@G0_`Z{aK2vPY-ag->Ttfgm6VH`&Z)CU3AHvr@q4OUVb0KP zzsYbiAR#_b^fEf0Gb4hbM6(CfxG`rr)Aj< zX?ZM;qVG$`pk<0T{@>;69`4+mqOZSyxLqRKbInuwPBl_0ZncWn&2|$pFm5CWnxffj zBr+F&zG#+Zcf8E*dsd4=eDmY3Df*)eB@iMc?v04dzC97Q3WN~l%p+UQdo zk^_d5epO}tb6y#Jji^6u+U^1i>*qqY{@5M|%MCdTWT ztm43%;3{f4W^?0B)cBGqbL_x#W{Z%GiJq_?`)OI~G#g}qeizwHvfCk;zgqmNC=i2K zYZD9BzhU#`9&4j+Y(pMDOK3G+aUHaQ05GY_6GqlXGp1Gmew( zR|A??SMh7Fom0tESSe8JqvO2hQD2HSo(ahE#GHX(CyQDe0TFBlxsOHetg1P7OJ?=0 zboV*yoXAUhHrO^U@fm>wI|E>lE9;a1(P5&Tu{wGsA|DNfYBI!5QB1|67coNWmc08Z ziEubX7@lu?*d!^Ve3CXh_DO}}q{fK3#TGkR z5IU5@+cvL1ZnjTQ!g(X3d~lmmb8qYYu0|l8TAP2;sy8Q;+KdRNs!7x1`!UY_gxAuk2j4ml>U`A6F~l)HR?8UOM<>gVZ|@2cKV zl#E+DIT)M{-rbJeZT${g03w0z@Bk*#f6Qx@Yo zbRoYo7v>t6)Qf9)(P!hqJ$fbo6m$5XZ>4Z1fF%UKJtbA!m+~gU-j8dN_=Ok^_t=|9 z(qh?dQ*v#C!F6Is0LzrQugWRf*;2j1r`MQ?`^gquzpTWI!fco$X>cu!Umv zI#!)%Pgza4E$nppc6O2cDNwCEWzT!k`{hUJEPx_0U6O%1UxA5$326&X%Z`(>C|XNI z=MBAv{9L?(9$yJV=@^H5XbBr*Ey*5dffD8)oM4ESmOxZz7hCzbWB_5w^suC5G)7NL z%Z0_5k5i^8qs*saD#GS;F&dVQq7`3p%V@F+Ay8P}SBwOF@wH2D=;i*l^8TI6g; zsx$ImuK1rdUAbfOEY!)GJ6eCbuvM-y#rnZoe0;Nd>_*_<52@3>AxFM1cUabQgF?1o z+QC=+_g6uv(!-gn$N-W}?eKts@+;R?fe94X$VdMl*XU4j@nGWDnRAEY8ee_BLrGr1 znj%ygkZHkP#O#)GDLpaAJ{5tbDb^)*n)^O+4p?+prD3epK5dc+vj;M3LQ-PLjL$;H z>2o<6G1mpm_qz)Zd245X!KK|-T{3;O4LzhT}_9XaW+)qP`Hhv9KK z>@;pMFUo7fE@?o;IZ4^om`N%2@&nhLI@iS>FTWE+7ED6}qNLByR_T7l|Eq?Q_O-aR z0NYWGEx1|c8Th!l{nU=_H(yNg=o}E3PYt;Xm#zsk@ZG^$Zh3LMW!gRr?FzSK3VW(G z>PIwPdeA#8;aCk4pZ6P9|8bHyF#i^FnZ1_?-0di$ZOPYP^g~Z_sU;0&Roc-E$iZ5m zN$Ahv3ZJ5>Owl3w;Z}UpKqp~>g)ej{g?<(9PDa4Or@gq$-I%VRRfexgTX-mqEm~QU zKtcGsKqqahC;BwFoEW`#!i@);#*JPQr+CJT3cWdhVg!B|YD20hCA42SD!(W6k%q{6CN7{DT4h-IWzqf0LleoXbQ7*Kl3j>A-2- znAy?uzmK~Xl&=;SK_jyDtjBP7}C#zV0bGgEQ zv0=yB7J>e2(pj2BgETagU@zJ$EUAMXSJLmG!1|S*A0ZB^xNp(-*Z!C|C(GdEYCg0b zGlclo75h}~SdIlL6|{jyVzCx!6sqsBYN>5-Wbg!rjN{%nlip=|7F9qXuQjaV&%9qL zxcn4!tlMJg|2Ic0jGrYC7`&+Q;0KQsO;AMzem%RS?hGd^Z@;35-j@WKg z9*+XzKW_bROemc1(f@F6TnmQSq8c%WZr!JY{`*#mo+bhqQ>=rJ`kSyy<8Yv2QHZ{T zh66$xyphM60aGl_uxSpDF`h|}V^8OM1sUs-vw_KXBSEgAc6`rbx{|`9GGa4)F-D%- z1Si;rR>qrG87~A4)TlvmM-=ZVHhxue(Nb`QS*~ohTyf#>@L_x;hhIp-o&nW}3$9N~ z0i8eIs!p=?uWdu~De$b3Pv4P(SRsRwkHBfUUw*T6ZU?<%KgKp23c)pZ#mw&5YYcMk zEN1I!LXT@3E^9Y;!&!tM!nQt|hQayRvjpl>2VF3%+<}P2u>0_Hfa7O0Nu@kgX`ufE z%fc^zic{($0?5nc5wiPzu%+cFqWb>H9uCPhDMNMKVxZl__VMIZ>9=cbQCuJD4I0G4 zjhHa5oArZax|3Z}aAV7(-6}0GA6w1Qynt}-N1OEZ8}(x0EaSk2Z-Y{^RX2Y19C;)z z0BP;(sHGvv4QNEi<(tTJaz~btj=b^~h33gi)oD;LP|sz|?p9Wd3vS4kGhl z$xe;pJf#2i7hrwH&E(JAoAldGfe|!#3R)r7!jiqPT(_Q^^rxh{{v*_OLSNFm+a`de z1ZXR1WOvZpe&w}^J%NkaFdRGTW>#+8j~3~QH68MfLd_A;t|eXWDC&5(PPUU!_6p0UTHm+PjHNS{InQpP`#xXjiVWH^BEUBf7Pm~(DS3XyP0h9O> ztN@_^zO7LojSHz+9yL@UBTPPAu>W+>7~4T|>#3EVw6;&o&ZR8y9@rC}Fh8^f- z2K8y};HaP#(yy2 z$dUUTeEPeqwh7QIlbL$76*V z-~!Em{-rNgdF7S^Xl zbUfkOBQwA8I%y)ZwaBM0Y@Q`=e{{r7zGPTn{g`XpqNq7Z4u?0(UmyVTM8GXk+BP3~ zRUJoWMyEl^cvx7tAU7VzR|{*|Z{fS$OfFB@@~~~wG@u009oobtPfEi*4&jp$o86`E z!$KU<9qyd$8*hq+Xa;ZaXN4$dZ%;W6Rywp>q6w-pihq#kIs%;&XKREdW{l_5+)TNw{!IozC3-zaK?z_K- z_pYffc8UXwA|JhvkY|-#+NbX#SEv?%M1D^|Y@qMy+b)@ee((N<==&JHDh%g16U{1J zqpG-ueF>@%DYdXB?)m|~6yE3U*Eb2fd*2ru=xh9J>+o`z=|%xc4<{|ilRP8m@R%C) z(|z;nj!51|je^!z*rZ0t))QLiw_T2J^yZ5}2}>_d0Ywle;%31LCLs}$-^%mGBJaP6 z5j8rt=%DIqsQ=Z~JfNKJU~H>vhrsp!HNXu}26&~m63+U(d?X zp$&}n&l4dR38`LzEbmT3#0>NsVQ0L$T*t;+;6!^~YF_c^b!%RBwoSe=Q8IywbhO&% zRtp2Q=B4V#@wS0!s}`@-9Wj#luuW+?=IXHwGT4^tt%Dk8ntv^1gKG*Rf*ca4_=Z z0pOJ5j`3ch%%kjNS%0HTOw5{bfD7Rl_<+gV8WGhZl>=blgY+cmXc(U+EUwlfFQJGS z;a!&?(qwMs&;C#G-Rd%u#{XcCSsERHDB@+sh60l>y*)NP6>i@hrAY^iyd6Ae0QO;Z z$CTV#wdO{OXv(jl%=!zj+QjxL;G%|Eq8~Bb2kR6ci}hn>7|p~Da{=R+(3Yb0tgwJZ zEK+LlPe+2_I~nu``P1$J61IZt`Jhl{RHq9yq?p)bqS&l%U_$PJafE-dP{_y{Y2SM*>{CfTrvQ znA6NxRS^Qm9Y2#N7v3EQYDff3mxqy{A92X0*YBiIf4j`#M%^P+k}kUk=-Wp9cnVAf z#mVnJm-dU`OoI^FxW`-3iBHQjshe%}a&=$V2?pYPA?4yHVD1m%#EyZ+FU-8ea9XytoM$;fD7Ht4j-A# zfD!k3d@~Cg%MfWH(s@ehp~npirXG(idCIwfCvH^}Efg(Efl*XhK8u_aL{H6N4r7i9tN-Qyou$|J83#|HpBWz}ndX#J8cAvu zmW`OOp>WP~qA08E0T(hVRDzUyiQ*3c6U*uA7X=Gz*VlrnOu~W!!c(YC308X96?5NJ zzV!gIDu(@J`9Dl>Pb}iFcM{)u5OJU}(nmtx|4xmS1g>&nD1O*GeOiSGq}R{ zIhbgRUACKa_f@5Xq3IR3vk@$S$3uy1>tGTJ$6Usmmb!UQQ!n9%3)h969QKYg_K;e;yEDHS$flI(TaT_&1VB@Gb9{38S~jX}tBEAa63 zRvvJ7`%OAz0gveb%fyLnciU;4$U|I+s(p1iM7|H>LFg2>OJXIoAkmGV@}Kqahs>9J z;`^E!m!KRkvVYn6v6Gixv$6KxxM1wda-e~VJ8e842ecB)AUcXH@BN(3B5j@XW*>%MRy?DLLu+39RWzFmgSNgTw@ zz2+2>8l(MoGU|Xt(d+^bPIgX@96|-$#7lT_Uys66K#nvP=9V_bcM*B6YS2iMH}?`)K39?HDi8t<}G{R`R2e{ zOzn?oHlde{NDjfw)|qJF2;BrE9lV&UYpYt10cGLTWvq`(!8C$-Wb+T^1ZGAXDQEJA z@oxPVr6~|XNpy}VpTIt5>V*)09=WLTT3A4wmEJen6oe|&EDfQBU3;Mql4Cm9^^~irK8clJCQMzEBD_T-Rz-U`B2*tB;>^B}zo?6m<({?0!`?7C+ub-r za)loJihhnLwTeDDkASEHK*C{7?O{!|_S!y~yT}67s>c`A8Wrm_=mZTd;No=u0_ZMV zDq2Yhb0sK?&p$)nqj0ImRr-@Uz)p7M<}jfOKB;iH0teIclgeku5)`c1MN;UpUsY|8 z^Z2U`c!x$x7zVjgs&c9Xs-dNzeNu{}fl>H1tciTr46TlsoF#Qg-cEH(=6&?i+fQiz z)$g#YGVncI2OHkT6{hEX#Mi`ohEo{pC9DQ=R8U3+e~w9|Y51`DfG4CJw*NSqXv;7D zc(u8-Z82V`u~PVbMDURw(fTv@(B*UJdWZH4y#Y^P^(Huv^slhNux+Fm@+84_SqA3M zBwq~!(%1TFVLIl6#27n3BJ+U$P}I!3*$qd=XpaHjynJGdVO)kMFJpdQ{`9^DXT&z* zl0)_sJKGONBt|f&MWirz z#V=qd{aE-+VMXPiqu*#4(Et%%d;#Cth7u->Y}y~QrVooS(Kj(*CMNyh!AJbevgO#J?X9YLlzDJXVJOFK3vKk8DEZsZK-rg`c9k<3$=8lT!&u%j{s{cA>4!}9R= z{41-Ak<%OZ%?Esn9*YaLWNUnZewF78YGFEtU{OgdLZ}Y$iOQ^_hIiHnfZ`^=iS|2$VH_17nFy74tz{9HaZ|()!3_E z5$v`07=_I>+3RKg?=YKzigfeo{qyH%{~2GdpPnKQx=tFWCwv3{YhQHMmwL=HS$VQQ z#KG{@p|Y2J!KKdNrU4DpV5DyycZS@hZ(Q>{Un?1>z(%xIyi*I z{cQ7r2NO;FI5@SO^8INM%hnhbHy;Mn2gb=c^AVq}^A3Oi+A3vi4v%m35#sh@JcNPR zkbXW?mIZvH-#Hl!$30?PG|f0iTu2wm?;c%%PhE)clj*wIP;s-&bEXQB1~a$|KIsA0 z-4ACEN@Va``i$LsU3NLY(|6JmbZ!NevM3K&#DDE*g8{Y8MSc37sCTQ%k68{zJmpsl zbHV#^dVu$bodd_NnH$=G!)AxBvFwU22)213!_?72cjUz}9T^@f=ki$Qev^L^{NDLj zCCu&@4SrE#DF=hk<}chedx1&#yH?ps;`d0%hAq~Y{#~rln-0x)&f>Ci^V_q@N+xv} za`pwef@?9z)|-$*u^Ud5c8#c>3n-wI05moA+aFT`@Kx%9SKm|W3*;q?o z6>#IW05tLaCYeq!J&wR|$OaVlj6zOuMCfg^CQYZuy28(+VZ*TXWfUMiqIXi5e7s&? z6+$DQ*uM;T-ln>#@9=vrbu#41OssG@f!9f6XjaD6(Og!E7r;w#z=Ne|17hfxes1B@;0|E;* zY~*U=ArU+Yi=%UrrcAISTyK&uxQOtUX^+1dXf(N%o5~l`M6z6d0y9?d#qA#l!=;6R znLVD*3j6+q6<~a{YwGq_=Sxb*5FC=!asDXu8=`IFHTTq(mu=W%j1jf9F0koO7fOA7 z>5bABF7+EbDQV5T`7Fnc=4Q!;TF6RUV0i2d0(JKsj`ce({PTw{|D^xL1_R&%-a^hU zEh^bX%4x1-lwN?RXe{_XWB7|aLdC0jOk@j#N$srWgKcH}cGP*mvjL{2&s$A*c)J&p zie_DtU`I$ZbrCD#8JA51%o)50SPes}s*a%L_X|b*nmY%mQ6V2X-=2E@7HdEaSwETT zB@%a6HVss*9o)#*g+_dPcB4nVrlj|UKIR%lG{9iwZ+RO?M~unkz8;lEMEf5~N?N=t zpz+AVv>^M(PujN&y5<$~uy$9X0cm&ohim?vtd^T_+q_;-%<`gwa?tF|P72L{0i?q_ zwNXp*Ub9}3#OeJ!ltiY%VUBfzOI)Rcs0x^ZvVL^Q* zsB)yCuMxID_?h2f3%!x1;IN4jz?aYQFt1&W*&v7kyj`XacyZa zLNPUEZ^)9q&ZPq6*^y5YiF-LDRmYIe2#1qwf5pFdm#}6)npkOjcEbU`ag5%!asRHP z{p3~L@7RWVc>qV0$lJ1RPJYTf9GlTVg8m<;igojMT^&ryx6O0j6Jv<;?k`7#W4~8F z^FVO{uVt6nE!|kRJ~KxE4|?lg6GeKytY^S!jc&m9jY2QMu5zNG5v%sXEHh4;aah_L z(Gv%H`4K2O<4(MJ6u?zLwH_RtFv{E=y`(b*21-_Kk*Vs>E(f6zrPNJluAOLzA!&nk zEi!$Haz;FeFqACX0c=o7J8W)>8Af#Q285L!xu=!SNR#zU*W0$ z-6Y&3lACce>^=5#a~!qESZ+d(&nAl9b-FCVG<|BKTo0%|TD{?-SmZ&lv0BPN#GYV1X6E(q7W?Xw!3>40;}fKfH z$F+0k`9FWDIX8FZKX_W@gW8>TEuW8wJ~1S*La#$yv<`!|jg!B%8!;k};Y85-*}g7}peUP5U{s0LtO+L{L9ieH zl1y9L3#D81Wk1ctOb#63U}rQT#LWn%$ZR9mWvc06nT!m5zb=5^!;0n4Y$zfMWDvT1 zMgF)>5sXWu+13G<# z*H3~zNc8-$HyD&LN#xXDt~Pzfg|FI;{+IbT)Y1E2 z>OUK;foG!7Gq4{$3E4>dUtwy~KVhoZf2g@UG<@>sx6gETt*Y&Ydh9mdJL2e%a?^IN z5ogAEd`Twtni7v|_g6=jmOsb*`~KzZGR?e2XX6Mx9hp!Mf3fxM*M$avE61vUPnqd# zj97_@1@!WmvW|#_X=ObRm8s&_3Q5=n*om2L3uX(TGMpME(o%eLxlHT_>U)#@=Ez9C0z;vBwE zVP~l9BP9+L2GlCn2ih_x*$Q3`rH*S*f8ptJly`HtFS!x2_c7|NYaJT5uxL+BCKmr9 zs-q@eb(YHZY}WklBjCGN>g@~c2{YoovZqnl`oD5;7M|J0s!;Ldn_+a)yok@Bj5!C= zo|P9YdR9-|5W@vhO<^)$y=s9vhwMrxyw2Yp{#n=3{(9_2 zQx2XZY(99^ZM&e+bK>WV#s7fdEVY^x$T)B!xSe`<0Ke+o%8ASZhs{-N5k#`@%S6%_=*&@AGZMo?No_5{o_Ji zUg%dy#w-LG<&t??P81^|E!&Vx$J30`1dmLcbLc-CdSX3 zMp(Oof_wzXRbKAuuqog!1RLtCb>nd7Cw_v&mv+occVJb7soR;R%pEN zlf#nM5gLJwX+$VRdh1#{QeNAqvBSCNGnM|cU7QN=&F6%&Ke`FeVrQPR}z$3k6N&}p<#aBFg^1g;l$!&#$*Q*b0ni;Li<1DP~Qhhw=~ zN2xScIi!P>R$4-I=u48k-BXGGkSxDR3uW8HvM#y&cQc=WkR;G8q7?jnEru*p7%0I^ zG`xJVgeY0Cvw6r8;*``tOyh;QmWkQg^XLGx*HLs^ODszUHP3Ac4zqOg%z6J`BOq8Z zyn8t95GlO}|0YMrczyOFZOOG`8u)sMm0SnLD)Xp8yOF)IXtmHsUG%7GIwR1voKv}T zo;u;1bB7Va+E}CLy3Z2y6vLmv!FwwuloZJT`gZx_il!e{Tl;pADBoD6l( zudgOcsIw8f4ibOL5%>ub|JIaaA=Vwbp+FbOgK>BPut5vr7muH;;+wCJ4gCPhAFEcV zcU=cvUwyKXeb|WB-ynXA zYT6q+M0}C1TT=&^1#5)z{KDC>!4(k&&-{|kcr!(d=1jMs;in1YRhag@K>nA?b%)$O zG*M8v@<;sEJ3vX6lU@LZcqWe15Vq{`lNOhozh5G*MSGfm&0JqM*_cEP{#Y^8DtuOg zE!qQ^!wHNs!0OMu}K^(L^wpQ(mskO{cpjuUWxKDfW2IIpB$T@=!?$D@E#f zmXJdnJ_0*6^D%`SS!>&gP^V?opy}~th0@CU*X7!uriY(?7WQrLzg4gOdGfBm!L;eV z$v0~Il_%iry?;MG`6Yklx=hrjwsqWQbo%n4`dhk=bXR~D-cUC+sAIR+A znzjQZK_IM^41EQbfFLm9Y<<(bKfJr-&fG+2)0|~xSxu`p?Kyu37bK(VNyQw#)!k6xCYyS`kBo${Pj5^C25b|K}YbfrNGy+a+D0ls~b%hmqB$l zcqY<{W0oQ-y9ZaTq-`r=2SF3GEh<5jGlyOzNO+uLl^KR&l;x{cF<_^3MY@qkT3*p~ zRjsMq)sJmJgs398Dao$1SBrHJn zG*BoTEfUc+tNZd;OQi$p!7*bYBql4g)pcfbkSbF~L!}L%{v+6nuVlyj$Y2{N`0YiV z6G?Fq=s3}@O4L`HDA0qzJvA&F{_fO8ZYM&3ffs7( z_hSJgna1$24y6CRFuW<^!+MDDb=$Y80)f@#M)?Qnu9FDszh4=o6grl-S~tgk87|%5 zUWT9kW`dT*{WTDOxUbywsV}_k4rq$}-ulzJM_B*&jb&JG>0Zl!9ubTR-;eI3GAwOU zW1wCqn*|EZ9YAL-bheguppaqDv{TrPWI`r3{f}6Cm@1oj?t=U>tcM|vKT)+9U9z)A zRt@msmkiK`xcyd1a(xd1C*v4}LcRf?Xv;bQ$E7PK(OunXG~A}_oX$NL72}^p*?S4O zdO1x^q==nosc~(XO_#+P=2vGVn9G`RV=;#Hy?Yq~Fa#AyUx$)W^%;nxLkitLBG+;0I<;&PR-|Cf~{!v8THhOC14bR_V!}FO8}^qz^z#P? zx7jMjKI4>Rmwe*BC^3|bPu`fUn1!W2E6pbT0>h`zUl63r`@Pj_e6ry!n|IrKn_fe? zQ()=)FT=rGYu<2Im@DRm2d*JwS-~SZbf{-*3J0!w`92W7=s%yE#7Zy6vRJB_D;M_+ zw~L(q$6zW7rG?XG^H0?TDf;v{NeH*)1tvbXB)i$@0v>0U?05-2D@a}_aW8Xr22MSS zyUn@PcazK&Im);lc}64G^Ln4c9-%~V$1)@k$04TJvmoDkSVfp(BxytdIHd>7S+M#- zY0ntj5{ElR66u(q&a9;_QdaX|5F1l_m4Mj%^A|oxd{z_5;@JB!CT;0|QCKJa;ns)2 zZt9wM_16!D?6(f`JCf&juc0h#un9d)c}qX}_qWe)*T>}lqF+{L=lSylJInzr6ld1; zaZjdt%Ze9b`CW*@tIS#osp<1@=qg4F+YC?5kXdX!SxgG*b4AnDtc$`L*QXEtnk(W< zin$B9(w0KC%W{@FK_xhV4`G%d**Q;U!quNeYDzQf>o5bOc|=z0pq)x-AA0 zA2*|uXugVHIUE=upNW2ay;O8=%z$xD`SEQ~#;`9|%kT{mETSdfOOLdNw2oVdK!L9@ z<2;~?(Tn_${44C%HE0!-4vYn`j!4t33Pmx83&lbojNiQ_{=Zs)U0+bNws7MxJDtJJcg)dJoi1XOS0KJxlYH0*rjkybyQ z<+k^=EdS`?ezSO_tUR;^%EB7ES07hTZYMsz9g6gw8$YuL!8L-NN-T=^Be};tA~(lw z6MmJ8j-QK>zNB9L+(@pDD-+fedxKtTZ~HSpI`>T@o@1RpR{Yig6ak`BU-DKUL%ZRa z*!AJZrv%8J`6@GrNQEMF3%GHiQLZ1Cmt=A=+eP~#ikU95bH%R|-@55R`<-%w1+*t; zXF*WEQ*x`(Vsw?B$fa`Duq5?#t^PLl`t*xur~N5){VnMmD;LF7lqp@z!i!%ldtjcA zpVMPd($3aDq|y;4fMLE%2bC(Ec3suRA&ub-^*h{VSfrhu$(l4 zq`xVr8N6knT-hmIPBFsN_cGrUbQV8Hx&CEf+2340{dL6nF)Jy~%k8`79@g#rSqwuk09~bSy{!S|m9%OF%A|hpNxv3#``+btUE#yfs_pwh=FDU2Q8xQn=gJy>0!B zmpwS}mMD;7$umGP;KeZ24jEf?W#gQHaduK6;r(Dtz0R{3YZj@RZnuW}gI8OpZ$g+B zJf)uKy=bLt(||)L%RrI@l9s7L4NmXa;x*bh=(Dvw4T5AkhYy)9~|U#)E+V&KMdy zYt7MSt!g@~7X6PM>!bI$zBmJ%D3`#-7BTK0?6BlcnUk=oVyt~(H{YctEAbwxzMS(E2?)=2{_4E=vh<7IgD+~E#X^ABac_-Rs{qs538=OLRqv&egb-!X$u~&Ui(HE^LA)D@kS;YY= zNRd7}=!a>MtW`ugKIWEBRu5H6XH)Uq0k!)9l6i}B-7#3Zk!vWY{g3z7W#LI^q#1qOCXGZ@Kff*GpBAFMidn4N-bk4G>`zZ}H;LwSe@Dx>)5g8of`{}~mV#J}HF7rbRO?UzT77j{_8TkXry zVLjPg|2}PY{f-*%>2#`m7^(V&Fuk4pu2@)Xc46)fQNcag0;>fz zjHWLIR&n@Q>;&}8mhS%h{e^m`(Z)7LI47<&RR=hDvDvf~%v(_nB>lGr!7gKQk~%3+ zxHE{?C$H}<_QK~yL7WfO2 zrwHx1(-`USY{t(5-j~L?Y0G<7{QW)LwLU1g`dgRFx-y+XdlS&7oyCBE-QxD4I~*uo zszQh{>RxEB1^7{p^PVPh6cP4FBplUrNH2pXEE6}be|#kOl|mj51t;RBW{1s>D+bjo zbiLURHGif-DfPO7fy_#<{FVkrB0*N6l0fS$&yvwlDTTt^g%&(DsaALF2REY@o?%$G zZ$UE&1C4{*k68VzU#&8Zlh<=*?MSCd3(rqN=F^Ha`@%atH*6(3I|J+Kl+wEs{A}*H zcgX|gf0~~ECdzW)`sm9N5_L`HaJiu$;i2sk`gD>46VI()TT$y3=C*1Wj@d)?adP?>7Brl(o z>kfKx%Ar*zXA*t#C4^qn3`<8Q(M!#W^c&DB#ZqmhdDj3EFJU7jS?Y?1S(^RGr9c0aq+5>y3sM^ z=XpMznto%qSe2CgcaG{ylH3gXxr>C53 z4~#s;pUMl@juB;B2NE@CL5E~i+(2#W@hSSURta53-{P3QI9X_if)=)Z&%}$F>lYTi zO~y7EK6r<*L=-nq_L}>T=$t;0XiJ=in>}M}`dMwFW~rD?oQA-XcXf3aj(Qoo(p+vw z?lakHIEi$rQ(hnztTH1RpU|UfpxUAdf}bv7w3 zQ3`=d1J6ZG1i_)<<&&Ppcbe#HjOMzje^YJWl)O|Jk{fX=7^#P$i(m14*F&blbfo>! zS4R=S-*FlroLH2yPz*zt6fEpJtETiFdxm_|Zq8@-(>Oi4(6|7s@j@bP)R0Q2u1*`X zx)dQdq2f1>Rk+u@Eat(!_mIcLd?i`AI6Jo3kjm}M0d={Ux}D|TMaoIXz;w*>z~F7C z^>0iebek^lGA?>@z3Ch0;q$hyA?xQwNa=sWbH_yc(Ehb|XNXPKYU9dB7L(Q2P6_RR z%XHR_%)~oC+>7;z&9IN&a6Z^1|G~b-`}r?R8OYaM7Ya8tx;Di2-v*-o7!8M@2b`9H zZg79E$-JnVBhm78LWxaqqiCA64^8z7hCaH)ZviFI1f_UQM&-LN3T+h8hW+P@~Dh@koLg?;1H z-1JEFc?WB7a$bEkDVb}!efWmR;-d?va!5J1qU(Zh#e-&Cbc3k5U*q{M1S*7`kd00$ zYx8_YuC0i$0NX0}A)xyMi$kkj+5ri4QUtbMXO{6E#yl85?}DK%06Wk;xOoVC-fy?T zvNGKSd$iMSv3o1jXlI?+%OvKXo~S}eodoQC%U$;dZ+SYXdCf7Ne$9p2JsdZ@_dfPR zcfJ)>EO{6FTs{pYlYm7%U#}RM(jPid`Sc}1WI((Ihg_RI+YV5`9a2-bW90tV*n{LM&(}F)1p~7Eu5S}@9}6`s=FVLt&ac7 zti~z$={H4}?)^wKH963(8dGb}uJaTAR$of3_}AW9Iz+w$)?4!&Y&n-ZEkyb2O+sSi zad(1-Z@!T7XDx2}KKJw%@G9#t5SLV|?*QtH`L{1eV?4=yT#<<)5>efBWknW{=Y(TA z|B>{KuVK)NEbB*Kzdpm=-`|s6P9inOrs!5IlYAHzfM2;K30F$m7BhUxY+6jS&pi-S ze$bpU>61)b+5iup^7@c>BPcjYd8u#Z(SzQP<*jqBglom_<*mUBH!CN6Q7+Gi0amP^{x#vC?< z$-Ov4x9^x>m*$No?qE#6(wtkbHv6ZmniJnU$W|0Oe-BxbkX@aP$1Zkn%i_sqVggMZ zKg&S+f#SfcibcoVMd$R~v6VNoUf*oo`i;uU-g;4iKh9aq-T~G;m-oEj1YQ#oL;OVC zA=_f1g?@5I{mmLrddNK4=x3MmlmC4GfL*H4IC4y%McQKRo7O*$#2^lBoahQl*i^YURaPu@IvPB*|QGv>gix16&Q}L#1ib>p- zhBbX3dutm-WP+=|ynT#AGVFRzb6oD$WEk8$5-}xQ4RxDgT;k1&d2E|cF&b<9N^OEj zny8;(n2K@*hLlp6#{^ zR4cOnFZL*4ra#AGSu*9YTx55Byn0C?Qhc+6ciK8HjIOf$fAHh;qotx)k)to3gWa3s z0iA~f;~kR>eTN&8s$O+7WbymXZvf2y0@%X5X8;2k9YA06e3b81ZZI(wv6K4^k$`U zqluGLP59wh+WtQIH3;(}NFUyjW{?E$cx(PzCKH&OR3`vV?sr>f7qoIzg{Nwjn5I=v zVH*j-LwhS01(;~eHaHDzfo%& zHfU8#Z-d3us(M0J=e3K62d5M}Vz-0T{sdX}O9gs=gJuEO%z9S1g#91{{ zxg0u>TBIGu_DE!SUfO0`nl{ZpWPq@WrzNq)9^gU=@z`!&xMbP6Kfb=dz2JXz%DEYy zy4q!YWFy%9r}10~T_Hlyd`V!{*F8*UMa8;hgMe+Of`u&`m=sVHb?S5mW^N8!iTb;GV{LB416jH-BPy& zs0s@`VBFdpGk=HLUhtUw;S<%cl0ssr%S$jn8hCKt38q;uI~yVkblBn;!iK*YZl!er zYcqr0Q%|k1;JB)h&Z+tB=W=c(O`oxfp6N>WtsNq>?*Evi*MU!GOoIN9k)ZM}|9Im0D; zw-02)+C-5l@3IGT7l!(aAsapWh9tk{=6ED2Oe>e-S-HoRN5v_>3PH=gBA;zE7`n-A zn>wkT(W^Rz;oQ(7JP;Pp{V9T&^IWUO81ns2=YMnksL>rmf=!~t&S?>UpNQ{KCO1Js zqiW-?0{gjwuQTsXz*tGs%w7%WLCD0t8w{KTv^?d!7$Z{pjp%c{mmqx&Izb>-EjRAp zgOq0%0p+K}RMY4E%vXR>QfA}sESzFPYykt7U(#SRx1rC(6_!Lsy~f;5{yL$wyFSoW ztK!iLDtSxc^L>_{4Ro%vmv!m~rRJ^@6v1#A%ep6C5fV68d;F-OX<-5$pxMRc{T=|a z%RYd&(Xt^+00JQ0LTR~-?ZN} z$ZqLC`mR#m98GTWaJv{3bJLVb(&sevLq#RJZ#hpQyE z`TI|?yDDEeNZUfDGUFN0`~)_pOAMHPek}Gy(xJUVYa6~k2{|-@F!9bkMt;z@6s2d& z2nM-lsid)`v6(ryz7Xv&X3cmOQ4kb#=9y+i>_gs1?%tTJ!AVV8Ay9v|l>N5fqOpFc z^mBVMVCeXHtEod@(73#xYqWs^1k>8^!m*qarjkI;Ecac3LnDqLOmIZQx3D`6AYPue zT0{;`MVxc*rCh2=n7_^{nU6%A{w)6MIn#9#sV((7>$ZUf99n>w9cnRC5|&1x!Qu%Q zg(2DX--)vP)Y0S6mqY3d^r7}|TeMEY)fh6KY+=YNi;CPsVJFT)F=1`NESIcswDlF@ zrP7GXA|VJ0JIHZ+8F&%8h=fWI>f3U_?A{K|_>qqUo~#?}IL&I&jf+73I`xs2al&wMfBnYT!;Fb)}TV8>Ewc zdr?JgAYM~|F9POum+V^2dfHmT_~dJEG0t3PJaD);eP7;n_`qSUYIpSVmFn8+9AeSQ zReKujEqs?nNo{@evSTPQp>3CQseYVpAm0!651vS`@3DRj#;moX+Ded=qHVpFL~L*= zo(69*=^qHBhGy%CMqvK^T_5P@ZT(s%xlybVeEl3cv(X;zFDXjx35}=irX6Dy;8)y z;BPFsEtbHRBe`JHty64l8iyZP`AqzXY(4JnjBj@>APKJcDR}T)=!`_#Hc^#ukf&yL zbVD)dW7Lm;ic`m6v?NhPZE+LHggfX3e@%O8Ljd|#izcM_J44QlQtdE(sP3qDqaJ;A zuroh#n(h<}I(4!9>(p*W>aN8 zx}Q9L?ul-&L%lfq8uMho*j<>$L#zf%uS^iuJr{34SV1$g&Z_)+H2jr9^CQdMCMy*|uH5xA7uD9w8NvOh@ z{rlUxk(i$uuA^N7`tC3?((9@$`qLhkkz2c7)?Du`4{&zEWCfdIo>g#zZOO0O>;zDr zM3o_x(0%Q@3`)CmNvn^!CBiN(d6{g0_LBQ3F^;+;#r7CVmD^pwN@e#Evk$sgQs8-VrH!Lg@WFFeY#h0z{ZLhtQ$xen50N=!$}dlw?}nC9Q8D!OPp@?PZyt6-a? z^wuI>Jz;X*$U$$KlI?OIE zAa`Cc#766XSbX%L`@7&g#k4NK{PO#1R@9%6AzyAU^T1lL;(ti~T7hh(J@;^QaPO~r>)t$yrLq~)e>E5?aO%||K^9exh!G65EV-y2!c+w_K3;>EHLMSn5zvQ zD_eeb=PouJ>8^C_)6lkYC*S?P5W#HpSf<+P(}CYYTs>IQF$fqmaUkACkNi%tt?TZi z5j%-L^bW5MBAN;EsUR3mq@#|L%8ApEX2g-NHQ$uBV|)3=^QP+E4i@OCNqdUmP;=CX z@+c>knd}=LJhS~?!vcwDnKqRLj#+UjA2IX89a&7Z5NZhoeiCF(1I_2~L7qT7nNtiz zYgm(H{xYV3hP(rZ+y#S}IH)#BouJNtvqgs*S)WslSMfvTK&BLBt zbbg;OYu>~#t8N#Ta{BF?re@aQK1c#uu=X@bi2Pe0juVk15ypYMmADTvQYI7R4S!w5 zyLe(>4$R?H`m^cI+3B{25kRTk?vPs`h?Ys=?IP2D7fI^L+S*s0SQeA< zYE0b{e@#NNFtn4q!nS?kpz%!MsKIAzvNICxHn*}a`6zlqa|d91xMvtfhpaF&?Y=$l zmpqD8E$iRk*4XrgBwR-t?_LXkFP`tb3rAF0^6-Rp(n$@^92X?sw@~8Fha+WRO9b-w z!y92fTsBgLn*Zf0w_!J7!%or<$B(Uis#_i>ZIS?vPc_Q{Af7c{K?&m1k<(X)OWN zdpOcS_@T1Ow`WuLmXPM-ZtN>XPYFteu>lxDCGoTaDJf$jivftvQ-GhkB^ zr@s9vSt33XX3IBdlZ4?hoj3npSvq;|mbPgBAzA+Wwu7q0$0;i0i?++yAJ=f#3{>xA zSve%mQse1n$!C@!Ky(HsE%DQ=G89Q|B#9G@F(GtH8sZ0yaC(RNI0;l&w1n@zVOt<8 z+pWI4N^rW(;*q```L>wSM$_bRbM2XkNtG8>KrP`=f-q5_V-elU;8+OR3QdA2Ru8jt zv%|K1;k5X8l@#s_*j!jt)IWKcXi~{rsY=Lnj{rIuP_p4!jfSb-o$YRp?R5UH79cd% zl!mZzY>A}tvK=uMoZ1QW!apprS+(O80)7Ym1R{@3@QHs zk_eTY{dmq+ZZ=b}v+3naCC|RpV#ZXod^la=z_ofI(f3EwE_=2(q~HgLHZY)q*)CW~ zwOEpTZ^?5u&WK!jC4?x8V~a;xB^SxzCS59(ERy*gz30_>t9l!Xe(r_i%a~$nKdVub z3Uqo0ibt(!Ab59QBY3m&<^pGA!drr{KEBj@Q)BJw^rF=O&EnHDGLV&#txl}DV|eGN zj5))L<@3b&xpQh#>%SZ|_C!oUmniD-PaW*~UcS$n{?VXZDbHi1zMVwRwUVG)He1Z| zxm0lGE~dh3R&-Y!?oq{3!?Ng$0r~2i6oh0Mix(ww#>M&+P9_Je!0QgS^%)$$x{>u)c^3K$ciiI+E%p?^ z&YYr`#;Gn=$WFPk`8mKgnS9C(kMA85BJ`}+}*GAu#CYqHJ*8+^(8a0b!V@%K} zanJ&mh$goLwJ+9wo>Tu^PV2)G%U zi8Xc~o<;IT`pmIsX3$b|sV(Hh41G|1(SN-p zC;Rf?7f8vCT(+qv=ZA3njrqOTjJR5rc-z$i7}4-6XioKOwVs>9k`5PcvvI+B0qnGpY0$qDwu?sM7`RTPkhJ)};Yy=7FVR{oC86uK@0N7yZFbvnH(>}SY;fjR zu?KsuQyn}0`*K4=+UR@BJP#aXId_I@w^(UoR*#4Y zN@U+RC!%n&g^p6OF#-1##t*f`719|ZYf^5k`qk#z*PwLtd`exTPj-w;^47iL3o`L} z0w%=mLq$eJd8T>dbn=Zn!1c-FK3AdVLgJjo?_2BWsI_~})}-P2@>ryGRKy9%Oxg}m z-p129e6KzN$~0u&Hl<`?Ho860;q8K$7M-SN;x}`Jd@+b4iyr6K3J-{fk01 z(>U#Wl2sazc9lgna&;AUnelyz%0x2A7}U7pM=??P3y`xT`-xRHKK!M>WrYEw8#dM+ zooRPnQC^|}o>M{Mk7Nzp#-v{bp$gj%e3yuX9;TfSajn;(3s5WyJv83CZM{`f&hml8 z4XX=G_Q52s-9@~I-%rv+X4eyO7kA^0^j^uUP{lRrK8iAPmNk()t@;8OC#vGi1d$488ZzxX&1vj zXToI3hu`2(b{fD~s|OT6=ccOk08sOYPqq1rAmHu6vE&D@qRqv!uuPa0zSE6P;ygkI zL4Zi}K(?D{L3@pRLk62QNYd;&Tt+QS>DMd_L}7pC!+XLPw}U* zd?e(A;}G&ZS8ZM@h~7A4SQ8s$#wtE3@`#cw7dxFRW4?xi@-I*%o~(f!d_r>{u+#n*G-SK;an9Q;73R*lv&dO$6F>(emafAEyRPL^+{!aQepETXWZ<2q;DKGEE2|#$2Y`a^#RTeW=ztcS zrs0tRUF=$w{3GJKYAcyG3dHMwikGFV!(qjo=x{Nn`xVdscX2T$p>u!dVYZ zSsbSh=C&#$o46NCF0vI`^IzH5GV*&se1lgfdNJ;-wr?TAwZ1@+maxuvFM_V0=d=r2 zi56HX#H7>G+Ea^;BW+4OUv*8CViGeho;HS{LjWa<*(YR&5WNnrJ`G9u7nHGSQ9vF7 z5@Zx%&TCuf0F|yu0wO@@W%M6Vrxe#FH_8+tIU>!3`LGVFpS`)j>soKmh#ElOSQd3q zl(>V$o2j7`H~l;0ifx9oXhUiFR6e|i!7vsB2C-d-7N?~X9 z)>WOh;r8l>PW&T`2CnFxYPln{TR^)=Rq4KXogq^Xt0DiaE~)e-?Z#^&arPBnWh2>l zh&QuaOB7|3nkf1{pt}ezH4g7%*FFhNcQJ;S9&4GiJDUA04##{INSr$V*#7k3Pi zv}bo!lo635ibbDNiAdg2=t$cp@4M3JK_&ts5~Etu_SfPU8v$gBf0KuD>|}HRDqy{@BTv78zUGSsHAhaNBMfF!e7ZQ!@9)sp@+<0x&xl#> zXs@NBo67>nhxhjmoxd@KxN63Dg6jC1(w;0yshf$%c$ol7LS)8(7rseDi-WQZ!jhekH|FfgeNL(bNNS*GxxM4{S4rE`q<4dQ z%dtE%lCn3X@*>%wEm!Et8f)or30hfL=r*F-xM7YJ?#UT>O4B|r)kQwA74A>I-6W%f z@;{aqoA{BG?#GPw1H9#nrU@0<`FQ`}Iv+C)H4PBz7n?BO{qYWiC%EL`mvB7o-bmhv z>^ocpi$qyOF;9^U`1!kEC5qK*Q|hsWu)xC;x#Qm%()ET`JYHvwV~d&Q8RlNCaOfq4 z7mk-;`DplFsXQAyqvE%@T0qZ3GUYrX)U;v=H;P(sP~g+HVRcN;_)*s2r%q0JqPsun zO;2t*Ot8r4oNjIwq)HSPUm+V4ExFeFa{vJg7#V1OE>s)$_4|y)Y+OT1-z0?M!&7Um z3A5%rb0e(cD`kE*Foma+Lyh3#DRh8XSqRw?_6OZ|=ck#q)U3VTy%;e-az_g~^?h?5 zv|oPSFsMf-zHdlIWxx>pRg`8bKk(R`HIfUUV);DVM!RAFOKdV4a!0? z&wZY)cZ&#qWs^0FQzJm#60{4)&zV6Kg6qPW2fnLnFSDDcgvzuZo)|!5UhK0F5Affl zsK&)KR+Meszv-PKkec>ymv50mM&Kis2}COV&s<nB`L8gH)}m_MxBooNN-Wx=Ial z_d6J)gd6?q@h>TaXs#G(z03}GHut^yZ)@rTVl-vcJ}P>^vGfq-Gmsg4ZK!INtU!BAwfGYq)h{mNj;hE4){8R)!K}@}@5G{skc!~A1_|7ECYlos z*oe@Hw@?5jum*ROf)e}eCI?F328{p#cSg~Ls4qc#_JSpjuW6okp|{rDRev@33Hsk| z_c7<1o8JAInz!Ma)#i~x8K_wT?Wzbixm0q9LGzQOW&S|_3FzbRgeg;K92Vho?L z?OXhpX$jp%p5luOweup&(F%_$v*EMv-E`xeSu)bO$-tT}{hf)EkIy2veauF8r26ac62%&Tc@`s6W_9=ygzB z=aMSmA+Wjn=Q5x)KJFT442{$<>DGM#J-&$%xJ;28M^5&HMU z>i8^x#j5%HD%xtMZa4nb_O6`H7k5DT#y3ffMP{`;xYi4;>%j>_WJN|5mpm-XQ}I+lC_E|nzm_tg?#@MH%9f+0%< zy_ef2?XM1J9<02_&EIjNwHuPM?@jH zj-~H;gov_DLM&2ce7(n~>gC$P0&&+of%MB7EPbkP`20_`bn>!IUCQU2%%3`cG!yes z;b>D5GaxTY6pW)3pXMKt^TK1+weugo+0D9})*=_x?J6-<)?-GEF$`iFdOfC<1??Y) z{%sglUs0FKWpGWVOQdseA`H%i(($~(n9hFBy8x}P&)Q{To^5{bS%9{5AiHEo4hv)j&73uIe_-iZZTKen-MqU*!>;2Xly_SS`ms)aI?k?E+U;ZgpOKlJ~#$omg}ecFirF5&&i zxIPT=nlt1bdTAW?uLT#lzGC%6^Y6U-M2RXW?R^{r1(QtS%)^gur@tk zk=Z3^Q1B_OGq@x+}q+p`kTATkk?&m(eJn`Wa6e_Y@RtbD$4H(zn8r~HcwXRAtE`u#^; zF-`^cW}X?YW?_)74Hm5qfIG`2&)G9j0}6e2)-L3$to_lz5NyB+w>FV`nK`|)s5Gs5&o%Fx|+(e~$}HZlZ?{T9s3HLB?_tAh3c6h_`NNxAA! zw<=AhDjXM6n1QrI&qF{HH(&$y0^u&s49Kzzggv_DTXtef< z<{@2Jkr$)8ns7eR-YfT~KtXG-$$u7C1k8p zYxMXtegc$h<`*zCB}2jmb#4(30oWQC+zMw5BI5$?x~~8|AR`xo73dYS+~YnF;BIDD zbJ%Xb0FFw!0_auP`lGNgfn*4ZNgTR}CSfiK-j0I(b{l^BSnWV40hH&= zeg15CT9CIMb&lUXjxA>>{O~Z|Y3uNJe0u=}MyCO6ZK~vyW~Ao}RDL8d0GayW9EA7p zxMqR@PwF?>J!#d4_{O>>e}5wDKVx7!;nBwUI&g-uFc$whC>IA@FZZcdWiVZFf?7JE zckUeeW?FLPZXtHmBIQ#jt%uonpQB?r{g%&&jGR-^1xQeq1<8)) z$^o7xac>f4N(-i|Jev~P)hn(#ro;La@fwri&k(M744(xw1(=@&d-DYcp&RJa|1R;T zAmnw7D7D|azFGX6D9UftxT^4%;2yH$j4)&;8kgv=(f&P>R&p8w(^xp##uRM?oUXB! z;2Ib2CIpo^jO+^xucSDV{F0naxiH9sdZg6UF-(ix*LI0(o5qP3cx=4nYjVjZ)NBAp z5ifW`jda<#WM>s{R1YVu5bR5%#P}=e6b!q+#6i1j*!3-Fj;pH!!ejJ8r>m1z1z4E~FGowlQGrV3)dt`A-j0BOv{I70SUg?`k+WA1YF2A`^OHlN_e!PQ~?NmJ_1ikHj?PeLtu^r(+%E&1kpY zB3)(9)*CI_O75~X>v!;Ok4>0bC$7Qz{b$+DcjSmBSj9%%Yt`X&n4SebJLe(WlX%kA zcP0#o&$#D|L~AUxOgs3k@oa$!g3QId!I8Rxk6Kjt(I#;nt51USb%SRrKRvr!E!rEM zIpmx?qUHJRLWu8XjwkPBRM{Yxe=&1y?9MU#lqXao(KBPrkh{oCg&w(Q8}h?u5VfQY z18D}HsFJOJGc%)~-CTw^#E{TxZwXFL$T|Fezl9*Aoumi6aEHgX)z6%~xDNDD^7iD6 zqNmtdy172{**+H&-uc7rm>Fix%ToDwE&qM`aJAIpi=lNr`WTp<&~&*JYlJXxzMA*| z_cv^>g@1+7ao`v#HbWC)vo){LT+}mzB)JrvM{klRigsSr@uyCH4k-Ft<4H} zqW5Fu2=69NIAmAgupjC0f8S#rb`n-yhpGN3HtS7oc^bK~Qw3)3WS3e>hhYd%tNMOS zfu!5Br;mA@x>?<0n_-+qg|FCNm0!9T6CS;&$SSzc3?WifNxlB?$@?MqC;!*Hl!`BB z*S^mJfbg$f)-1>EGtu2dQf0h5ww$cBclrxP*{slClx98U@a9c;ow%dG7)={0bZ2zH z<)@kSmseki*UHlLRU7GDK|{7rzA#q7v@9f!Kd1q;1w;i{qg<-22VKRW9Kadcnfou# z`0+IK`!WqA?`)>Ao)4vg-q@W{mwczIdGG(m_DlWLf+8~UeBk-8_ol0&`AO>#o;9P6 zv$XCEjTwe4>$&5}2=hyi!+z^;P8YiyrXQy{8(HWQkYkRY z07*w)Nc|IVC(7)`3+a6#o&xIGqIKnHP-Bf^s28jz7J%#3O^`6|tVBg1pQ|k4M#f1!+mMJK5ta0BWVPLhQFNrRlOb;CJNds{H{s4IA zK^S_qyuN<&y_%YVrn08LcwHdvCG{8Fxk5m(2~`J79i(h!l!_{&!mHH&82}{d1{8N@rh=xl4DN$((ER3~_hG;~PV79wZT{mEufC zMtwZ7cY{zWcEhb=V1v)|Jo+Q``{KO+yrg`lzR#;G!797m-|s{Pn<43wTiIlZv0_Z8q++JwA0>0VLP6o#I_iF|jTuQF$rf z^Xk67LSKlot+MM3rD^{BKGW1rov-k$^uNDmr|lbC{Iw>^IHIkygFy&G2$g$6YB?eR zW@ocgti(szBBEr^Kfwi)L>WQSWWhq@_=f+!F}>Q5rkC&N4UBvVM#u8U z`YVXF2|mR|$IP#!=DyD(dw=!HAPV=0b23ZXP>5rf+`Spcqi2`278SQ?^`&37G>mD7 z5Wx#END0h)H%OhYfYUdtU9JBPKXo`gpDQX|Qss+Y0S~L{aB*jG$ZIyMWOSCXE=LPy zR!W*g^Mfbjr|D+KL+K%FDrnZ){ij;v8Fk;#b7n4*VGUGXRwE#+SR6V*Of>*$Xc zG^yA`BS_Xqarx80|A2(XCa%RNnR(G) z*P5hlU+a^30WHBf1L6;hQNYzjjlUAtp})6)j&iMCh*@+efQf?MP*Jdx_%$a|m&Ei+ zyxsF;5q@cq&c#*t__A#t(S!00Rj7Y4`k`$m=&je&X%E2%LKr@LaZOUBcA?*WH*N{f zX`66$mbih5PWU=&>Wm22zPILe3_*ly#E6&(u~|X}Zf@PaUPW2eD1AM^hWY|2R`mng zuqx)TUQCp`f3?0B-=l&^gGxC%Ul}DrN^+JHPBKz$9L?zxRTy`5qTa zN#ERG<$3qyQk(r=OKK0t3wv?$JkK$M)d^FA`|Grf5fnRYh+3|#Xei9CIG?Fw_7%VR zL847$bo+A*W6Ja)?S1qr%Yz@UWdfY!fTtp?snMu6kzd>poYLJ2xU;wKu)gSa7n50< z)fyGv8`ZTbCL^=9`p;v(X3y{@>b=iNFj z=EwEPNF2b|_(KsHMFkZ84O8LxWp&8!l8-n68juvdgC6#-h;7tdY}zODAEt#%Su*_c zmiFQ)-bY*2#`;-~>B}^hR?k$F(jsz2rDV?l+Eoh0^^TK>|wMS%K z81?_BGDSyQp>k~G5vsf(W5>?9XLDtMrsZCXh__0CzX(zVRwe&#@5{zd@7JN|>x zjOKwRSk#3oDHSa-c4RCfz*+CPUBuB7msO9@6ONXw9BmoLB1M1)H52wTip~)OB}Tv? zPFy`I1T6^VoX7;YzTE;T4&g724|ZztH($}cwXWIKlxZN7bOnkX$=;6}S5r+rbxTUx zFe^`WOSWGsrNu+%cTgme@vk1=Q$j~5?HX^Hn6O;OybtNU*)ZX)Pot;e+8Dy=DMeUw z_75m&_eKfuH4=|>@iE)ny7rV^eULXiTiT^v;Thw?5KV)>9X5U*=64hUP9S9oVGR@Z zdcNkC^ioqEca7yYiALLLYXv5T*4*=FsTh`V@wmOI;Cw7}lRqt?=UPHOWw-ZyNV(05 z@IS^+yi4fi?im=_#L@jUPrW*Kl#sAe%fO2uSo3R(N(4Q&i7G#@*hiO@OEe-Ag4NBs zf*e0-NgmvyDwZ{K4&-AvJn;!^dcWljaj3% z*_v;bjV2F_@3%oqe@AYQJD!Z6#-5>>yuGTg7S}Vthkjsk4F#s_V6jq2Wqf`)(Rl}m zrd%axrAmJ5oF0Egm!_!^>X2d6rI|ZATk(^9?Up{WX5IN31U?&glqbukL#SCC!uT0C zFi}Aze%jgA#5)v-2ILk83ohAw^B@Jswq!y{Y8&O6&`|jmi;of1tHi|w&nLOWx~W+B zQERUd-U9qk1%87F|jBiOk@8kw~;S_EQXYBPmWt= zEAgt^*MNP-x-H4sG+2Uny*DfYQZL{6wtlBItnVP~+zMs8A)hI_;a=7t4vTSP9jz_M zY|1P&!j7?h3Y@#jr(bj+lAe|_CQx*v=!HY@#wIbh`RnJ5d;==)Igch$U8jsX+X3c5 zE6P%6N?QyD^Q7OU_+y~Q_D9f(^mB=d(GUqk8p>`l0pxD}RFt7#8qJ>*!Y|Ra>hGH- z?u<}3Z*AAu_DJc;Y}xnc$?+|AAg)g=QC8g*qF6B&cJ>jD#^dW{aOeUVE{cgyem{ub zT3wvIookw@drb8N-)D#UM8}Ejn0;VzUoBn^+*kp=z=aas2WYLsW-Yj<#OudL^c7^EGd*` z6MZL&`O-R+Qk1b7*Y~AEXr>(5a94ru5|=P$K7DZfXhfvjlbb0fq?iTP+DPi@M^SZs z#vN4ahWjXj-7BomCC}8eZ)9o`0p{Ya<}={pt*qcMCC;!0*oO1L6IrUBSQOgSzMUP_ zt%M|h%c=B<<#AD6roBo!D9=&HTzXlWmH2jM0vHe>n%ru}8%KHEX@^{6_PBmuXt8VPwV_i?v?c-{?AzqZmV@g07a>srMk@!v^dX-N#u zPWFOxX5+m1#@Te%?(*=rWFoV>0eQcr1t_i5fZC)9qnI|qX2b&P&>p(m%zSNR#&C_Y zJReeY*sTCq;kaus(@wUpW(9wa%<62xWhm(9KgNFeeM)zCx#d%S^>p^uDAGiES6IDL z*S=B6hrq}359#VmM)9vueWq^rXIR8L)!qXh!W!0aL>J!c+EL+Fp^2cPY1s@aN${Tq zgy+fL-~-QY?`{OcgNRI!FIS#kE7!8=Qg4-pb|`DSCW51@HbfIstP4TKJevBcs-A>w zQi?n>R;<7FE4g+!WFno~m=}cUuKb6zGs19vC#{RPG{fT#ccl3*2K&SfW*pO)cgO?f zZbxQxf66!fMn_}|aRb?t6#AaVm9O{Ht}s^?Kzi9rD0;)NY;L8sdHiEAavNV71?&on z&1x~EaD8o4nEE-{cVP(&_x1!V5;zhcN*@-7a?li!+8y)BbD(<>1$zr!PHkLq!!^>EHzGb)c13sSuRazKkEi z^|#2%q3eBvz-P1hC=enuV@=ocp86C;qVB9~cND*_@+{!^pltKbkgRiG<&J*JkUyYr zl@QWScz>0g_}IkVcy8|DQRp`vWvbepS^EkoF(0KzWG|GjyY^ruccR5*it=xT@_?Kz zI$Ll!aaTJ6!020~=$5c=c&V!JB#2al3K=Thfu1WPimNMNC=ju4mrZzT$077M(%JFNqgUjvI+* zOV6|6@5qU#S^AlMN}D!8FRTAoZiL260ZtUHcgvEVt+!75!IWL{ky%#uz!_WvT>$nB z5zjZVF^KboQs7i6u<^2Lx{D9J;|uKv0jb^+`5;Dic0Ie$(3A!EKg1MwTYe1U@ROWo25Y2x64h`e0UIrTuSN9+eFcvWl zRqUS`ogZO9+N_dO&+%Iki8$24vZUUWroKH^nJHp+>-h2=t7Sy2?30n!oMA$*87|Iq z_bdUf%0OK^w9S2R$T!vVf0v^rlR>dt#bhkF@EJgB@J=RTB8ceGQ@(*al~l={*kX)j zLmg5`(OJ2H0q80QZ;)^c5hBtAn8rZ!kG?3o6fF@XyFm6f$drfpY)gx>GAVuTu-9%d zTUS4D-LZR)&TW83KXr(gbUWiSm>p2?lu^x)mlyZL`zrE89Y!lgLu~d=CxsxX)kQ3I z@9R%c^wH{Q;!>0o41L!?p*>Qx72e%TwtQCb#Bb|8;Pw*L=kjccbn!x#WdL%%t3!fx z!eh*!9OLM^_n3`7e9p{3s~d({oW@(3Tqz?lMW3f!C({7pJTYzIS#Xzg(dMfkEMm$o zf+}Aadc+mTvbV3BQT|GfQE0{9rE(8~RN{psOj+rv6a|#hvX&%yvg6MbGQ17A4-du$ z*@v7dw-fO&JKhneq!}>O!u=c2+aerDWJJQQtr6BLegyq#J_PkO!VAmHO3lx`-#!tA zE!k&h2rSE8n<$W&_QNqYG?lN{C0h>fE$=h=Uf-z|H(7p8-V3b=&Yzd1$tDb8CCX|v z`&Lk;Fex`@ct|dkF%e^vV)MyLY2Moycg67aMkp;3gd}G)6)*!T z+z<>_{Dp%^y^3M?WypAdcc6crr2>4k@8Z6CS6`W$ zCOg$a^!6O2kvwthX6uu+la6zq(7+rQDw_)`RQU!A^C@J{pfY$PaEvq5%5_fAf;7FM_{#6^Nv$r^I}WibZ!dt=_=?^!m*-UuQ2+ zwVCmggIPg#*zkOi{8>QX33-6%8&X+a-^cSdh3R>;ETvuKZucaC`>QHjDtT0dXjFsC z@KJEnqCwmww{_-UgwC?4027rXN&fcSwq!>PY>D=T_pf}vv#%nBCU_FgDt!Id>Je?h z*qLWeC-V+t6)3#*8|UTsWlTT))0XGy*9mp)CN{f+2jh%QJ5E~)fjN*ybd;B0na1|< z`<@V=%P?NRpilKj4z~kR$fqYTCr$Yu&;-y|9ARD>J&YXI>h^hD((?j338R5uzW`;B z)VHaX@`0fMnPb*XnQwLhIuh+a^kyYF*`I@wGz+>5rh-ds#b*psGNa690MXgfiCX>c zHHu2vr1EZrsT{Jr3a*T&yXpK(VLAS7zM6V-Zk!~YIZ`w6Tr$mHiSHU4i87f}`FL7B z(5gmT2SuiGagx2C8^Vz7c+)N3^I8n-O$C_5%zZU(RR<%-Sve>UldPS%HpU;qCc}~O zBh8(Z>g6jDFd7i>yIORp%^us7nFhQuZ4TIGbl~<5;NRZ61UwJK4e7`19}&yGI59eG zd~5A5cX3;qOu3`|zNdiV%2kp-Lu}A8UW_G+RsTA84) zm9Yl>;z|QVv1AoJ`n;r^lE!AY24j_`9REP{(x_SGL%}%~I9J})PQhwp*I8{^xar`X zV^Woa9?p^{hvf3P&kj6`N|dHGCN2ex+3tXZkebS7La1DOlK#`x&cg&(J+rDDik*y# zb&Sq8i29p_cNFM*9Y>^uVr-&2=qK;35*M*>10_FYC!a-An)V;^uxx2t>v-YVc&ItnZc=Or+-cMqj70< z(f3nQ1vf21Ox+~a4lW7-KFv`5(uk($p`~4e38**(n;z{%GE5H6q9_HRdsi(zKS>RI z?eM!ceS%XV;bm0!onwu2CgwhObH(RCCW}EcC1gQYC=o-hEt$61Ew1z#Q09EPI7z&S zRV_M}e>|{8sCHq&SB@vk_)z8$^8qt&o;Q_m^ZML(*>R;Yy}#xpG~GDTgG(LWP!CD~`Y1b)`x|_5TNmqff zmS}7jsFLH1`~f3!c^>?QuW#^ylzuuS?~b5Fl9?l0V#dQ0UczPq%6mNu(?VHQ zDElq({(79mY`fLU#-j>&DjUFc6j(GOM#Y%B(@NCvm9)sK-mQHZIfClm>|cqbR{wxz zJQL9aggGIrfnzAFDfFNvrEg^Pl^Op7zT%lgD3DqDP8EMpz>MWKN*v4NaD)y!M`M}j zwDd;(h8Fvoq9yv)GBc;U=V?CZkq{0!Em+NOGI^-gWM3ifd{8gx z5k6Pqa};dUbVj+%lID^UuYW4qg8%H&UOsoP7*08EpDfflZ%q050Q1S}>K{Sr93CY_ zkWQxTa~3>%okbp!xF5n@JXtNT3_@;JE^^xykbGz-KrGdJ^QN?wQsJu=50yug(?yK@ z&yrV%)nj~DOLufr1h{^<3SI=KhOd!qs^t68@dUr0Y*>~1C!Z)Dwt)0Ty27XX@NZo4 zvW9|uSxm6*eK}!KfUX0Dve@WNGA!}PV94)Y&t}DTa3x=t_!ALK~U*1UWQoPg|xCBqy)4V2NhXWGef9H_4c+?WUK=dQ>h7LHk;CB~!M_ z>JNw5^XNLQTGvx^4~nSTMplEjg^Nvb9Y20+x>;E>>P|CFIOO3r^yLm=18nfVa3QOC z%J4~Xav&izxFmBfM zrqy6%iW~jRurROL5d@s>Jl$V1#uQqTapbo1G{PaQ{5bgvew~EXVEPHQWzVaLdbB*{ zJ@FoEJE`q3*%NScR_-@cS;A@!;?K_N3qJbw;BBuw5T%i4x>2|3u6crBn|ka#?>2;PdO}zO>Dgh2cFTM zs@syS3|sW4pZd<(SY$*xxB}rsWy}Z)hhQs1A6nu#YI2HbQEqB4YJ9jD^Tti)*_iF1 z#-${MT$9Zvw029bh$<`cRjxar#iRGmf%F$8zWgG$bdfI;cVRT3R}WW0NFHFOLW(SN zG5cxuGl~SlNC=)qz5F`UFe1o9pP^+i9WLb!Pimw$rPeCMeM(Z#X+8U%X*XV%85s*yIdfOf2(U;n>D5g4s|^R^5FpvKsx0I zC;53Z84I~_>-EeoH?dJ)fnEF)$s@{&JRVlh0XP`AyN6RLt^|5c+I^Erj4)}Bh6l$r zcq?UB>czBj1io)`sp%>Y6;@9JJbWO9f2W&F8p`v}nc40=oB4F}H#)R+{l#mjg)@}H zZTSUULfyB^7$@dUvRI3yl(L<gB6W_1RkbOsaskL9Bp2$eX^d=Oi zr`Vuh-ev)F7AlWk^aF=(v@=x^A<+Xv+yVNQ(fk?^B4lIcP>wT}n#KT(O)!>5H#^-4 zl4FZJR%OGA6RG~y zCqzcPPbHptZR?1rHW2b@l%eW>-PFd z;MP#Ly`qoSD^OYj0)E8xQ12m?tss?fz#jtr_WoFbG;uD!(5%xp+45>&c%)eNDmU^j zj1t*tiaY;P5$>+BPQ)Kmgt>gDg*8_G_V1MJd%NHFpAn|OZ1jMKQ@ZE%3;iA(5~#&; zn5Y|eHfl^ETi2w0+&Xn^`A`>Ip2wAM-)iJY&seG*75E^^ei&9Mi*E)E2LaPdFNyaB z(Y~8~hA_isB3;0*yaz|wZ{kwYFT2?YD*dSTa3;kcBJlG1ke_~bUnZI1B+}_f2Q+sS{xH8J^J8h8Y9zE@+z> z{Wtlgx8mxe6loP$6_v@8Tpy z4WXzc6|ekvLl>;Anx^|CCd3=PrcLf7Pga%f@^twYPk^cR$gOTEDFAAR9eN!o^!1lf z>W74~6g>WcwcS)-#I{{DH|Q4&fYrdC_Qf!J?-@~O&8Jy}FqVFdPx}kAW$C9fD#BOk zDK9rdUC1nWUi*!Z=CNW2c`@=)6J=;}f4PB4k_U$9V=_x|59hem1q(Q(w@sXZP?jIH z=mXkHpRdz7Ou|0RatkgW_Q13RT67Lx{D-6P4`aTaS|uu16*imJRriuCUbKX+MjyOr zUo_D>+OYk{bMWCPCi%cUgH89drFG|l`neR{+3=bqN+!8^I`eJW_e~ZL?nyjKx%n0= zC+Tbg`4Awhs~yF=LN#eN8;C3F&hr1k%zP&Q>c;*^D{w4JFaQnCavIzlvJE%$4Z^Oh zli&L|Q;#aW^=zkVe8_EjV0+Egk1{*UH<# zDA2YJ7%476@kvBBzIY?T-u(uQ!3>ne#aLPy;5^}gjPYks{6j-r59mjXV5H^fNwy8OOoJpJS8;OIx?R*rI?0}_EAY!dLk{oC zW_F{+DXcGI_IqI|fLo`mHds_-AM}x?%*QJey(=cia|fvU_q$5?L8Zatf4BfV)f3|N zxFQlTE{lX-D@1v4G-a+)QaV75EO5X&(2WG@N4a}7p5m4Hl&FsF&T&B&CXkSE|YPRbNK`S`Hq=hYG7t=B+u=_YN8<{@W6T`NSmIW^Hj5f~I zwgKJ<51p4z`_-)0Lk5(Xjh7P znB#Q4f?P)?;h|lc3dh}2XxZ1cX|D57u1+@qS6;D8Kc@G-NIfGOJ?pK9n!fncqtkxC z_=_7gf2srivL5qp--M_ifA4zh475j8pV;=^CUR_;e=F&X;txDsr3#G2$sPb>A1^zMm7$P}vP*yYN=4`gu4`+n`5H6TfO={z%-r6vCaZz2 zIMcCHEw`0CvcWd~Au8P2i7!ZNu-6IuX^nE9q_ zQq2=5n+!IxFBnm7#2_U~Wh=sfs1quzYyTdNx2D5sAe=a&HP!+^@SafNyfB;>vj<;S zfhSGY9wBB!w0>eJBQ8|j37w&;*+aNmvA<6`CD-_xQf*NTCE3#m!kRg5{45fTdHDgJ zI6zws~x zY&0Rn@~l2BE-nAt{|APpFbuyz?c3(3rLyrRP@^X^Dxff&KxxkG%WRYhLY30d7gxGU zwG%5s_2)S!8oKlgMunezu+B&z(O(_=Ewo;X5z!R3o?m-z5Y)OeS3I%?QoCZmztG^KvIY>WfPU@kT7rJ&w%qIPA>xl-=B7M+`G8GTf$Yd!yKZrfzip#ghC1fGqN4S_pOn_` z8Gc6)h*c;YVwiNv!2j|)lWsg)F95T(iKTVwbDeP;vL`9bsikFMiN0RiMP!lk^|;6` zX`fpSKXC=4HgQssl|Rm}to&4wqMIBn$b(jw8p!gqGvqa0RB)vjoOFYJROV+fy}T5`>8s+|Nsi(N)qFllWg#Bgt|j z(09@<2x$lKh&GwonfdZpyXjnCj&CBYa(>#!SjqTlF_bZ8>_h8^%7v)uDAG)2RY?)a ztNrmq=JX*Ez)X9vjy!#`<{Pp|T>NLN+oA5OTsnED3udA8|Eluozg6EVO zq6p<6CviuR(?~oFI3Vz zT`^XiIx^RY9Sy{J-_2CG-s49dEY6KK)YJJ2^00R5 zcsCy<`CvKI;U?cJJkvJq>tChBIyY3ll41nmCNjzHQdCLwCSW1 zB$7JrA1w*bJsl5egzJ8LdP0W@w`P-1!IZ5SO*PzSMC@gSw(X~TKf$}efrScq52F?H zL-we(`FEdON%km#JS>p|ko`Uz$K?1@O+$+FwGQCD;Hlvv{m$&n7nez8gU?UJkR9FE z4&B~YIsM4%Uv~3CNB?HTmrI!UXkDReHcV2#tGyOplwDT0k=LDsHv21m4&hbW%*yw# z@Dxe?K!K4p8qbcni+sseT_FNNlc_c2&p%?E8m~vT`jTmEZY}s%a3%l7))Qg1p3p`oiETy+VsZUz zM9GH{jk7bseINw6B|yG5!cX&}l00@@fK1AVwA=6@tdU5V3GZMmb#xGdIC5s(X1*m%wM=$e1T*m z;p;wuG6p(AGdO6aib!}YpEMtfSq@!QyU_`kIW2Pg(HEQ9u0s9-?F~V(Nd94;wf;un z{@)y}aN&5}m}C3lL581d?p8N!VG_3@>ldWwxlNdMzrC-0M9q(;ZO?s|E^Ju0%UnaN zZD-7I1Q`0g$X&tg(|qH99%^j0q{bhV#Sb@{*geYrb-DSTe#c;H3|bJ)(unCo z1JwBIFHPq{if8tIbfs+chDNa0<_kcuWlFR#mC@0SUBX{&m|xHMy{*vf&O zFQ58{``XR~D%J%kU_$SN*#Y&dO$Q=>i?!$H=#HaqBw0(ZjS(f^O-GK%dRI7njWW@< zvn|?>pK#JabU!5hcnej?Wc%J<)byz%s!kse-IV`-xzS(#mm9s;De#L2{l71`ncX4R;0p<`u=PbSZ25T zwFs-MIqxH{R`j{u(O#cWz(2|gf$*Q76R7@*HL^|ck~B~UrC&qbA?3Yy4R{@$Y>qg% zT!lA`BNl_KdN)8<=pVe{vHrewv1ji&xsnH;eEp7AQYQ9I$NY^Bc@l-JWtfIO$s0>x zB3f^8AHqXgox9ufiAFeHv_ATwPsKhxKsFV><}}AcvItWwh>d(VWnDdf4$7123Jetb zOwB9~VvlmMMlg(~^w~(6kNdJhhwBRvY7GMZjH*Zi&O5&+ zWB$({viXdLqTMGfo!h*9+A!nl5ErA^bHYHAnq`?DYplkKX@KBIP@I4bzm3JXZeY18 z{_QiFs;9D2<~HRbUp|}yFABudhr|txs9(+o&^cyxRav?q$R$ywW<0cN*$4worbT8$ zZCNfaCf?4m^;_VDx`B;ax->!&e@MUzwY#1$(*kb3z(ZKQO0|S>>#k$5w5p!wV^uN< zDZYqsF|`}Cu3&}!L9w^TGA&^hkvx%ehv*o#c32IU7TWf=%PKa`#Zwr-)1~kUCucR1 z)pvRGcdd}y1kxQos@w{#JE@B8cMz{90ZRzu(Cv6e#5r7v1X`DNQ^*`E7P|rcG}6H& z9G=3)mfzPcTpI&GFAnJF!GL?^K&`h>GmTdsN$VKGt&eG^uxQUT`r3O1S9s@BUYBw9 z2$msJoFBvj5<_4^D5Nnj#`FDzV3fnp%O7OTa*KbflF8wF%gVOb0g71o^6?VC*7(=3 z6wz|U^gw$tIOjH?N9ii41-kWCAsg0x)u$#b{DnIAZD3Ncp87KT818QVXDc5>iK4?MHij3 zWa|^SrJ>+PJF@;ZP$iHsI{IwUj$)zl^YVu`qUjrw%Pr=Gj?L?ssRx~%yZ7~qr-2dI?wZ!g>FUbult(ht%Y041y=5FRQE zy-22PS3f>mqh+$S_NZvsc3$F$kP{NhJ00vN&(@>!G>e-N$(9_1D} z^OasDjpN6x%IZlNh=yvC7Ix0QJWqUK``Bi?` zGH_#q8Q*9W)T+~7@iVj}d#o(R?i-zK;oz7fU1M{%_a3z8*%Ig2bNu#o^nzn7nX;qx zoktI-so;j&D7@?kq&9hDN97++phkbG6LEJ4K3(TiJ6eML@1BE7-HqGoiBi<$=BcA{KQpne)l^yJScmggsZW81$>Sft`%Jj;ikzT zJ(GtzbvH(yrita!Z-}Ec)~K)D4y|{H;PHRwzC2*Z|uZ7$Cf_|Y-!04VkTx-aSQwm;$Y>oI`nze zba0L-!kOLgc9F%1do@@}xMDsw?Q{Qc(3H42p;Rf{o;}PKU2$uXB<#}T$=NYQr$?)R zT+>9hBoN%6w5+`QicYjA91-j2wEmO|@9W$Lqvythyj{G#i$RWE;vpT_?F?r(y`WOI znEr{6C{W!qjMjsw%jikSce!{#yIqCA3%;-E0{3Veq0}3Wk_S1ZZH4x`-GBbWvaS}6 zzI#gHrvCM2*J`^mhtxdBIjDp)29lQ7owyVB;{UMq)nQG(@w+fOr5W8I&FJoCfD+O< zQW~TiL~4|Xq=0mH=MWemEg;<~AstGc`Td=9uJgzF_q|rvw&!{8=dMrBD*SW6_&;}E zeIoa#r_h@@5Z!shaKmN$l ziRiBfxlD&iGtL!yi`39+Md2aTe634=lQW>L701lzfQv6xm?D)<9G8z%Mm zX2x4;ndN(%=R8NjNii$9_DajllfxuoLR3zIqA)u5O`!F>lZjx_Z{d>Pb9pk0*P^!M zQyBrLQk3}m%4wjI;S4l5A!HE976bC95kp5zx#9Waq?N~n=C;o2?!Nt=!n@dCtno^k z-zq#nkhLKv_Kk9P3v3{f;V_B&EE|@zyCrejHPYiDd_P-l&UaFfdx|#u8>DQ6Re{Hu zr1{e>=9;U#^me^++&>LbQjHq;d%-r;vwl?XZTVX8t6Kam5s*2~gZbRupY=t@As(Oh zi8rS`7AE}L_BIb(=94RF7*G9QM3xMAd=`0FPI@#J_wb-xbVIvh3S?#IwXFh{B(F*F z)3xAfkwij~gaD%o6ai|Ov93)Wr*!ul82d$=+`u-fI)rj$NXq)0FwR~qUrfWcdIS9< zN(-$Q9ZSr4<``IaU0m6iq0qK~CYa_G4`C#s1m6OZ;u87?!ktS^QpQXUz2R~mi_m3a zNk1P@h@rU353Ri-rnay1lG6C09CtzHCh|ak@iKK#betT?ED^$`nkwldKtBw|{eIA2 z#?l|v{HZ=XvWSWV!~k+sCWch-?Stv}S@~EX!Z7(`VPR4Mqck7qA2n@8#y{VyW8%_( zhy<0OeiUB6-Mk9H#n4RJIFGUl82W*uxrua+&PTdJV9lRaX+_KVMZMlTT3h9CvWb15 zxC95QY|Tp%vIvkPg>$seTQCb4SqcJ4Ed}NCM&zc^g;s)E7=gdW)Odt^IIOiaWD6?G z@JGUY34e;&PLY8%n!qs_yDP#|bMFXPx!_6C_`V)MGzlXlTt(iSx)^GAZn% zcX%-qnB?FP5`GF2;qO9j6K?+cf`K*;&c>1bXS9(f)O=#;KHtZ1;u^baVg>hN&ad}C zgD8(rlzPx2$BC&wy{cy&PZmeXLFGC$NGuu1SBG{Yi#Bs{ooI&q#m+!aR*1s|P2g zmJ>A8(>U}iW(8_L%Di)|c&{%bAnq=^S%12THQ=@ulKOZt$fI4ZQ>-p!pm!q^aP&Fy zFLsYB@JvipfYu3oQDE;xdlWVGyHk&fVvidrgZF@Rrcc}}#r9irhO$Mcn5RkI(7Rm6 zzWm~E$JINrIg8?dZ+F;U-W`3-=yYi};0irOI|N3v{60F}?ti|%7VbV&R!=i7yjicr z^G~2tJVp<}w17Rv#CCdl%wxE4hEy9&V~Q9y-=E za!^cufe&#-$U)O?baisMKxt=XdTu>+zR#5SHoy9T1L534ky&xf?{QdC+~4eED74{{ z?ZhWZp3jrhjRQ&nW7gE^9y%#T0*TqvxLbx2_7yUPHNtG8QJv{+%z?L&LB8$|*URUY z=czC$yC7!gE#6#C97hSYDRy>U{28N<$?do`jkL1kA5q6#MV(WE{D%^5b_Cjc_Z0#Y z%R((bguh7x?H<=bPhu*WTUZ?~?MPp7f;b?ktc!f9#C4L|jG-fPA=H^BB- z>HuP8vt)f}qo=Lx10GOfc} zn?|3jcZIkjRT=>{4Kt)O*z~tqD|S=_?qY; zAU?*;G6?yuYk-{pE@*8he*a@m8yO35YZCdH?JSDG?-s+gY0`Xnz3bJ|ZJ0UxHs6^N z_Zb`~_;^AI@k7aE@0aq0;74a_r+^bXq*(<#8D#>NHE%Yzl3HnJM++75(M1&sywrhz zqAR5by`6+pQ;t6?1QB_-sLP`fY^k{Qj{G*Cl)eF^UmY^B$u3_zE!ZSdNrAae=c{H_ zq}S|QzMDS^8bY4wL|m{4TTC{hSk0m5`~x^)mVBJ&hJv)?&_a+W2Wlc= zc@0(=BJvPAUiZEx_)PJ6cLU&{qFt01oAMd0K*_Tml+Ij$CNFrAtlKY#j+WCISC;&m z;fH;}N1`rl)x1cCpBTS5KUOZ4yPZA;VfgV{g4rLn3(T1HSuo!=h9Qy29$SM6bgbWW zY6@I|beX}sjRQd$RG<)wHsh^{SG(!1oqdTl+jqIINBgp)D3<*J*0pFbEOI~$O~!!} zf4W8A)t^MpW3htzCBd{CBqq5lLMb_mf)5tDM#yw2KsAr%zO6Pipx)VJ7BI1H)sg^6 zcD497;m}xAF9aF1oCdUDKG&w)c|FTrbR@v?hjge$^%!SrI6?C6eEd?ju#HxGj6YQR z>$82Kxr+ixcI2&s9m2Ua8St(?@$kba_dLbdH!+{XS;ABjzaC7@heXB!g3-!sj2>5y zL?$_WbQg!uo6RQ!U;J9nyj$!_s?5WytG=!v7xXLckxvqC_63h`%M*V5Rft(-bBsKk z97`Q-B1m{bGXLhU1)%`P7*jxb8q!Yz*t^%a48{%kT>5sHG1FExM($0n7J|YVY*a6{ zynnyF{!Ky)$wNN019Nt3huu;D1VoEUT=|G;RzPX7YS6_D0W;zRmq_pzm*aesCnk!<|1y+`8dqD0Ix0)S7<*sOnK4 zLW}}x_LW*{`rQF37Ikh7XtCAUD4~UjchfY^B0%q0#>@N?szIB=5!prrxiVpx3v%^$ z^CBVJ{5x1^U~xQaOp6v~yfu4?ks(UA|3|)zii48qeLy$g5g6Rs9kT8U=Ok$(J10`g zwf`x$58y)nMdc@XGCF-{%%?a(2H<7A06;l^_}UQ;VM%g(Ft#~vafLsTZWygTmR@I# z3)(iJ*jyaVqPEA1T}t=qk>IptzGjW4v`1#Pa^wLCFs1f4a(I#$D$^5`vmU%tW=2ev z^ZR+hzqc!`VBC2dk~@d=LYwfC51_uerQU0K1J3`8DbF*z-21-hR1O4J|NKH*@y z&l+>N$4%Y0&hNODTXjfLFhg@P+DUTj90_@FZuQS%?%bunCG-04+a&4Z!lA4tVTuY^7ZBteCKZcmv@ji|-y zv2wi-O_=^TY2UfBhOB%50HC_N*w7BDzr-z7##P?A7mVnCqw=Gpc*X{vqlj|qB!tVlgVZ~Mdf}A8qOd)z=nmN) zp{Aq|+{-^VRjcUS4GCroPuid#XkF`>dHQ9YUOrpkDpr=j|MVp`kMQ9O^tO5k_ey7` zMrQcPgmGsWgNYyl$lKU!cd7b98C-F$?)W zUVv(E_yLNY^Jno(4X4*0UE~CfWEpC82TB>-Ttz~)GoC2j9hMBhM#YkX^x%&+HA}*j zM)7vHz&#jpRN?xd!`hJh`@Waxv53eDb2R=7Dkv*tcoV4~*zehPWhl;uW)t8Z6-Q}>qkfSTdi*TR!>M=W@ zDRM>}eslscipcM;-TgwdzgcQRt-pxdNO?4TfI3(+oU9|6lkdXVDYP*VWd^U6SmXU0 zCRSXEtipXruIZOhOR!NYj3=6!9n!)^b;ynX`!FwSQ}5(fFi+?Fq#pR-c~sP{^LIz1 z9&4wj&9`;tirMoFH6q)1Fr4$JiG3SMn-uL?PyFO(ZpSYyY@gCEt zB|sTu5=hyWms$H;jg95QzgqTGgU>n^#h1Y*A75-dlI2&P0*<~Ym}JNGB=(xWck_Mz zG9f8F1=>&xP4AF4$k0b})M{&VF$vPNuh#wd?DA)epc+WbFB!@8dD90AqtgHIb(Fyf zU5B9lw~9Q9lVI6ef$duBon02*0zCw_&J|00Oj_&M&0kBZFLgSx5nS+H=DFWc;$C1W zFu^}G2@i(RO4>i?L!U3Yv^@_@eb8t;=_e?p+Y(7Qq=0{(%+p30DhIPay5#7z8`EB_6 zE{zTHY!??jhL%hN$r+gIRljrR>V9)o|H)0{J>=oH;z^2C^JT~M)5mwj)NkGqnQ7}U zfem+N2dIfBmG?)aRAwzQAzrx7{Ph$I5%os!5`smN1O#o((vqd%E%NIMEm4dw(vYuz zC!PUADhbLiX|&Ib&-R_D&g1|AtZ&z7X zlaZRach%W0U+=c!Hr{&pVm@r%`!10ia8yERUOS6;6!-a17+}}%MGIThSLHOqwnbfoBvv9POcWd*B+s7^eE^%@=72s0 z+a#IkyN$4KBE8v~Mrq^q<0Y2Pan@d#&aZ8Bk&XFHPzg4!jcXOh96OHcXkQSQTE8x( zC|zbkxFN{W}lyPjb@wSvYCpCN!c2-wVYi z8*|c`YEt}C`bI(KgVyrp3hf(&8<#P)Xxk|Pk-WK+!jj0zZW!ix4*`XJyi!z}kQ=%m zt-D*39>B4QW#7f}c(W3LUx?jn$b2+Z@xi+GneA0Um{jX&!#Y~qZhnZ`7WvqaWec{m z^D2%g;{V-D_|&repm0_p;j_5^vm>GTuv|L0Hp3swX5O$T9m81PS(w36tGw3( zPp;Re(HLeE{`vbeu?3B78~w z)fUW@XD_}!!cvZ+@vB-RWoEsc@qS^_#l*c3e}=Bp3%(y|3&L+x-o8)SdKemZaL-tE zC&vvGoYU{0PKf?{W^>IEGBN)t=5xNvrD#rJ)cX85Du^3aCqOh_v;8J1MG}=YCGzA` z{ubH>k8(-*kGK6c!^4xP8%qdE#wyoMWZO8_3D?{;+@SO*gz{VrjaFGQr>}pfOWbZH z@h(`%-@-!Kwp%vM73rrxIx*}mWDYPE@Yl~9zjvNhJo$VV^0UTp$(Z=r&HvRr@t?}M zF+xPdaqf>e6Dbf+Y+LaIH(${~GWVZ)&x1Dr-(*?ZUv3Ih$o^IDs>s}lW0e6=Fk8%b zK(YyvQnD3U`EVIo32( zHD&Gm{zoOdt7{^ zgIEK4VQLgfTLii7sAArcSV>;v`=onSn%&cuzrkTMyLI0Rew#BH22*v9+iF!}5NLlu zg&w1^OOitxG>kYiT`jLL>RAGE+)eC`U)gj5Ot>4w5|G7%G27dRsqr`7mde;+x$CFB zL7lkOK`j^yAN|!K_z;|}YND*WmgJOabrDjKS?q+U=4Fof<5%sM0h{=?VEq~^g4JKj zF8n2-uK#-nLOyCyMSj_cFlHOZ0VG9!oQzoMSZw7qf!onfVag~{hccU%H8N<@bc0|_ z@JyjrrBVrJFxX7JzR70G8~P3SIv+Ofd)$OEG4HnGsVc*JURn7i&_DZXC?@)>eV!p6 zsfi41x>XNSTR7G00v!Vgwh#^k6uAu+bqg%`37LF7Dd$Syo z&a9dJ6xOpp{32my!uEDiu?HNF*NEG>4B)gQI9;muZh0+G(3w=Y;yYQqv+y5Dw$FP~ zonXZo(GGIbDXf&1G(-NvQwGF(uHA~uhR8Jma@0!R_oW%lvAJ>;GahO%} zQ1Umm*RgJ(%y75?c?dg!@u^?$9^m#@b3hb7q=BeCKj?7T;fl1<$>ZWEM}SHO&(D(k zN-zyduZ1|9>CiB}KcZ&A9S9`CeqqTm!HTHmS7W9ym6`0odWh!9FC+VL{(suvo}w&4 z;GqgZ)Z0Tm*X;-b=HEhpV3vu$V-c`pe5mzZ89tRUxo2yYE;AS$?nMj1wJ)M;KsZP7cpVI}9#*NFzfTnz{t>1%4a zxt07XyUM|LpVb_t;@ZUwi80vs$ug7_{l`@NRs_kpGP0pOmNx!HU(gyzRH}{X4c-ZC zPl&TBAV-W1IY@28p4uCQXwZ@Z<7_^?zkSZ*D;82W^Vr0!-q;hxul2_C%>}D+I(AWW zCvQT2#QpK8K~}xW>@RlW=TKChu~!~1V@J$Lzf|z1?pU?Vq;Py&xrCrH6cmL~cu~yb zlGbH#9?}>?vwzwO;n`i}h*g4WS#=*%ZZg9>{&7uvxNj^!3HN7Go#AruvnGY&ZNf7k zeRzBrpbxR-c~-cL%6!UWK+_S-f}@}rET0I?!}&EbL+G^Th)jXf75;~6tE zyQZIbai;Mr@4oM=8ncJ2!fQKC`C|z+mO+HwhzCMT-^; z6LF_}=Z`SFJL5FWATm)dQOUWD?Mb*dXK^l-xVvK7kZ~8BQHK5wd866y%Na|b)j-}* zNMcSr*6eQCKQfSNbJ@m}w+;E6_xu_p5Ho2V#JKwWA`RWUSlw*xFl`2XpRU6!sO4@= zed=UFn5?&z=pEJ1Rz&~)A>QiEy7|L8;`)`0H*%9fn5)A4?VI_n< zlr;P!ro9>TFQR!g)9McGl@Vl-OtxSDN#}7^yxC_20iG7XQ+^zJ^^-gLN>}msfpPD} zyTZQ9ywUULe*n|*f-KhL{O*F7)pZi3HPpRS%BOzRphBz?S#J~3TjI~&JY=b!B{vt=F z<1*pq3W3)f^%1bjq?#G*=iU}@7g7q~UDqIr3%ivM0&*5h6@8|t80%2G68wHZxBVE$0bu|aPaF6ft!Sbgti5i# zj42wCrPQOv`9}SHVDrK>8rIpi9uj~k2-#w#S5mE_(QS1q%GJD!{XK6pMW3(5wsi*6~9w#7Ro&oP>w@V)GJA8*s{0!K}R;4$(6F;l#+sBo*4-fTw zraGQ(l#(u1|0jtIWAYB@0IL14&UE@(GuJUTycZ3^d98xfQg|`W2jA{!*sB*vrQ%b+ z@_T4LPQCNq$Qxe>T-FM_dpMpGC^eC(NH6;~M4*yQ>iRH+=W}75{tLY1`|1VqdN+2J znDt7)y;dhm*BTwgo+i2s)3$|WQ(!pIc9`+HE04UI4cT>F?$K9lI3K&r5!V89JJW=A z3WM*){X?)e?6)vJ(Ou^VdaaqG-1mP1TFpq?Nca>?IWxPL*>W^PN!gYLN%Qvd3|lFq z1jqBsU&E(0Il)vrEL=0$TBd7YrVYyVoTcC@D;D}ZrnzhGKpR#xXOJ$ODf2uDJE(Yd z?}(I1`&Cvwsy|SnCzR%8S!*`LEXh18V)oRxFuOxeis!dMfBx5D#V}?31TML~ig5U! z4|Zf~ssh#uwqZSOFw0{3gkg6<4!K-v9w2VGF>+U(O-a-+(W?ZThsXg{)%Cu6AEgUF z(o>}x=gB&q3 z9hFUlbRfz60Y{v(RenkF|W0llg_x+mDZ1W*X+^aNQ(R?Uwtg6qRv zCdzm*BQ#~l*LdL!kv*o)vRFXc2SXN^AFD`tCG(Vi0_q4RvuNbH1QXU@v5CK@+2ZDT zn$}IQzD;C1r3l&k^Uk%0r@OEX$5rz_zvLRn2wj@)C06thv__{;<0Jv8JO~ zK$v~w-fTM+@S9KT^n9*h=T!=-L{=l<^EMwPgM3`@O*Wf|>#NhFW)`~Ix!tqLfVa_I z6Iw0=O81HprMt72c;K5uj2u#TSHk3;;Nr)$Ryu(Takdgt>a=%w`e?yeZ8J$<@RfyP zCQy9qj<8jJ_Q@y{M;n{`<&NIQj90dUqc?Fd7qNBGM8g!jq#d#_W8%UruTnPD%JC@i z`Iz0j(x1(7L}Rnu;%)3% z04{tu+22Gov5N+euS}Nv%TdM7b!{x=Ph{vV|CC8hj6#8Z>a?sB&AQl%B1CI#ZI*b< zk>^@zPe($xb+%>!y(9w?$=J^-jM?(C4y_&!L(WZ&ew6bp&_m4GmPkarJbOBsifXL5 zqYH`4HU=SQuzny8DmhU3f+cPdt=09_H6_+zb{zS$Hw7_S`OsAk6>&2*aXR+9E|dFb zaN#20t0S~52`b#*S4J|gpwjz0w^BI+U4=_Xd46~t2%_@`=v_wSZ9tF5n&X55U~{;+R^v! zQ{<&B*aq&*V^_vE=gMz9y1*{-^3fId0L_QyqiI;9MMIeuEUS zp3!?nH}WsH+oL@lsMvUtYFW#Kl1gc8rCR6XouLC4zU#Hze#^Zqqiu{^c6l)_cFx4k zYM@z8(e7vdNYS|L5Sk&mNo|uIzkugY6hi{rcc;fqkfWv30=HGPL7u;Ja$Smb8e6A$ z%AlH}RyCO7(y43AWhzW}^^&?9Y-^yKwGT9C0cvyneP%A4zPkP9*R-ta|ECLjz)wr6 zf%hp~H||ONE+mIv)SK1)k{jb16D~*be5(%mard#RFb=uhT&~{F&D+$Vjz|hD z1*g9)WO}gg(?;oCayaXiq8cCIHCPQ$b&K1Y58JnTkO>xgnrTEk?pSgDv1IyU1-naY z>xlnJ6qv`XbK)rKh)Zf|cDe9jsOVEzNw_rjLix14`uTM;yqLzaY6EF|;uS~2?oSDx zOCehGUT&m}dV)C$uV(jrPn=hABhi*k1wma(?@|K&hzr znmUy+*Btnc1MNw;r)3a-uP^xb-)V|>vry|xihck0jy@`Vq8!CoH7 zcE;9r^!A?1^t$QUj*AFE$3mjPYT^JV*!iV(I_U2;xlT}djK%k(oW2QaOUh`7UaFPK z+}SOW0`u8Ba>)QG+1n_RQd8BVlRXdOMKL7*JWkcIC}@5TtMZ3wW`65%O`>I6DC#h2 zCf~NryT)(e0&7}{mt*en?UmOVcjA~!<0bDWi3gBUr?++R7~Au$%;~g>+m-|!rM_Bz z&FKA>!M%5jZ5e24=_AXPlVQ6jpRnw^UhMqtlY!bwvNgeabY7>>5WRX@$HG#eAuqO= z$S}jG8*Io`8}g9WXVonB?w;x-o4hk8{o}tw={f5QN4F~nXo$Lhe-=vyWy>A)N9Tdqv-`dR6%&}v2D7l?KsoP)mh8*f!>{m2=@ za?tYZj?on?me~K#gn~f&`Us?tQ;UK@LVHh3i}JLNAR~Kw7k1hIQR(|1zdxzCo%C9) zf5hm?THE7)8mEysY2|tQl_x^{GBbRYbuD)PAr!pzXmER(;%RDps59qCy0ojen8vrM zL$0%X?fvVQXGQOS_8PtNw5!~E!L_kAlf zSV!6abugKlfd3;|)eA#Q#lfTDH>1Fhyoz)x&dES#K1G|zSn1IP`m$$w8J27x?q*(Sb3OGe*`;Vlflv%Q1rk(cb5Tv=?LHR23 zB&#&jgxv(UHDj{Rm9+B)+C+AOc2L}!c=L8c(v3@R)(SVjqr+K*_fpQ2KPKwKY82EZ z-vAmHh+t;5fe>Wvn6m9y0&lM=Eh*LwZ;`Iag2D~j!GD_08Ky|~`J346 zapDF#lqb2ZJOxX}A84+|sK{X+V8kvv)hZ^{DJp?RH2*B&Xd#PY8S9vDfdj$Yzd@^!H4SgAHt-bB*+6yI+bToL zW%kU0rOM&U#;2_CbH%+4Lv&^H3upGO&HA4tv7E@MPe@?pd=hnpdvJAsNM+T6Z%h`U zJ}vw5doYY+{s+6go$H0Oms7?w>(%N80okOB@9QZpgZmkFO%A^JiG}x5X>pvyLy1|n ztf|StsE}_^-TJ}zOF13e+`@AZ38$aGJ3ry!)z|AF5fceAeBjBDC$9=!EF=e85fc5p zo?;ZOaxMSe01eX`)=YPGF+LSXS5UfCfsJU|jlpn8vQ`QGvM(eh?uBAb4)TAguO-uto55wu?{m z`T}CzHVC(Fj)eENFkGDeM3HVMY1&8brWcS#2itM4ojr*x$0A65^Nwp|GxCI9qka`M z`fUqdi)4=@m1`oj5YuoILWwixQ!Ogzsl=4^o^88(5hw2Xr^uyT3EW^5_p2K-pF!i^ z&Nr)`uR6o-e}U||MLOzj{+=hXO3QDoExYcV^5{`zlG!Def6G{c+QNY;ps~%Lobok; z4uFv=)MWO*qp5y?05D&;^gtWMa#$Sw3pjBMujPXRNgh^8FTRObfHbs!%_|RXq7U~3 znIC5ZAQ!>Z0$r!PAiEx3rLExlUe58}IS)%O1wZ+2Ii|P(Onl9Rclq;A&!~FUlnH+* z6Ru&lyiK1`q~nUdGFp{&zUYxuD^n%lAd2j`-^TjB^aWG!Jr!cc86j1jcV8*;-mYvx z$w+uLRveJP1*d5TX?_J-rkWeV!1mEWMsLs!ky47q@MW- z)?B31DZHaFF=}Zp#&9*_xTtW02v27Ba@5qm(REn(hHivU3^;X~k&h|?ZMW&K3I2^} zs-uEOqDgpP*SA(1mztFG6Cf|3hty9RA7c`fh^(TS0~3t`v0(UKiPx?|s=q-Us`szn zWwa$#?*Bw16p7aPLe{DV%D%+=y7Ww;-&jiVo%5=d6PG0a9N%&c7|)0bsX~(c2rDtW z9U)Lo8!kip%UnaAqdu>J?EG@$!bu-lG1G2ZvL<0($se%Ek?Doy9X62qIcy>3Gd1%x zl#iIG%ZkOJU*dFL^|Qc=1*FXdmyiO-S~1+pD-7<=PXtuE=g*;qnAJubEKdGuvf!o{ znf`3`OS9Al}2+eFY$=AujAc>FPSk2wo6x2kc=jlBj; z%vboX)ux0aBEE~%37T#G|DzPT^jXDaldL!cqWhAV%YJzZ83`&ot63^@S+-nk3x~b# zTdruHotD~M`6AAS{QL8q2r(xGnGIag*UYO0E{0I=?Dclpl}CUHnYU&{8y||&#li*DT?TF=Rb`EUMbao<)h&%d&zH&KS%lbwH%ZY znrtm;%x0sZxT0u(PTQijO79PSg>IB}go)1DJ2W|J%=1U=8#Ryw&4t4MERZFAKDB+I zDtzpy7F+p4e+N1MS23v+-^V3@ED2BAg@T({C>~cCBH3)A;4t!-rXi>Rk66Lv9p1D> zo2rbRpTS!%vtTLTRB z?}16TO6Px>_N%8rq=bhlEY*K?1u;(knQo^1{JUGFKbRt|D`~UkHG9~v>DuWkzUn@p z5YxcHB(PAlEC@`ffv)s<4D&Vex9f$rdeIuAk+ITrM(NM-Tv=0EI#>4N_njqLq0W>J z#glt>V=8yW1QZ6REm{!{J)uLfD@o^;mEXP^Pxz{?MBZ{6-Df8xfHkn%?rl zl$?Hhel><(qGGqG_!&_-LMG6{&_cK%j~IsrDm8Q^BR)4gK%|N7B=M+4@(TU1MP0>) zmf;E4^gbxjnA%80{1$kN)k;uxeW z0hL66tXxViIA+E`&7b{Sf}^i0iB1L1vzA>OLJ?K;#XLD77v^S0)t(|}*aB<8%Ubu_ zh?|T~P4|m~VzN8$f$@m@va{OLw!WU0wUaIcIucay?)jc zGw>@~DpY8{MUO;id>H#b-BD^Pf~wLtAHPAHYtNBjinBl7AZn`|&f37|4%SUO9=}S^ z$gGQ8)ZyI%LQh!B( z8*htuYzfRE+Ib+dpP7n*nwYbE5sYLB$*}}Ve1#o}?UB2nz3Xqzoe*i9yA~13Sw5}J zy-W)c|EgnCJkCkB;mY(y1rS@~%GuZDE*}=_aNh@k@hc{Oc+CNDJTtsq@ryA;%0@{riG)xzoDOAi{}2}*Nd_r_={LOa zqtr}tf7e4`B060GJu$CKFUT*+1O~ezm9ns!r2O@RvVB;Q0)XJNX)jzwn`1w4h-^P$|Vc)k>I0 z@F9i__Z`?{rRFbl=(BU}_J6K%PaTnWRG%YS4I*6obh%YSBYe?*+4vM;NiR}=nkp_QdK0|ae4B6Xb_N=4 zE3qN^^q&j9vf;VD!Bwn?nB5|n(aB@Z%hAk=yzy6Q7&%fB65aO=h0}FgZL^ghX&lWR z|6gW**0|}O2M-GMjAV5C=I4amjP^UN?KII$QjaHq!&}<>9{|$#>l|1PI|_4*#2^Tz zCT76OvddHoUGbyNQMXZhS^tSu##0#x{rERseLL;43E#Po zP{>L@qc`%IB4`?RmR%u{&eoc4U&POO{ZrIIwZPFrkln?N!@xm z{JC0Uu@R42z(Vwy1YcH^)nj(d3Uiuar&?WW3`GHJsjiTX8TRbUvQJ3h{?GECm3S-O z{47u*oYcTxStqvVY>cuIAkaWT;Il#0O`r&*a^rBKdm}$wC2Ue72n5^5 z3fipDz8G()=J4kE7vDIazX*y=m)}1p+8FffBt;tYlgBd03(`NEqwn#g95!wUe&Ja; zP`mlq)Q#Z4nq|{?DNZDc$kl^z9d^Vd=CQvAur{A2OLLtoR7s7PM}!6r@!TiuK8qrB zI<~B1qGOG7MwXY^3>PoW|MX>_qC7Nd^g^Yt_+EZ zYr|zratlJ%#ugKpr-{S+`3jk7lIcuGpa!`{E(izTm7n^6FUqh^_R~RsD(m0Lx<51b z=xDNED?{s0jhE+CL=9e@Af$5Y3h18byO(c(^()A0efRH~%H2d6K}68{gXCd=q~N#j zE^mqHB!t~xc@!Rj9MLeBZ%3>areGNb-}I-9XCEdo%7F`$YK9IV&z? z-^)1>6J5m!{^lR36I%)5Lw&0h#3(2E0o#vG7Ws&?hggk%Q^_k6fJAK=DldI;PRUwA zT<1yapwUDerWj!dFc3z|lTHg7DI#{2dzoHG*y=P#HY-fgCuUC65J&; z(JrLe(jIZLGL>lfY-I945y!xH>V&aj?Xe$i_bOZ#lfOE4ksk%&Za6(hiDozLyU!N9 zuX@PAJt!a}8uZ3Bn-(F3A<|dwvR#b$)cB0d8OP`V6w%>Ax;A`~#0nhrvC~ayXEeTP zYsvGm+waCQzQRPW!_jmjY6DDb89>N6FD*r-mTPE{b}m7*rkdR~)pKLt-n5s%)6KM< zqByvV{Om`mb+S#YLV)gLab@%sc6v%3K7lSKf*_H^zKaQ9qd;BwrLmX>Zg$J%!p3;KPu>AY#7YnqWi&GOf{UMmkOQxXC5m?Eo}yFkc9 zoKM-?S99XT_WBu)JQFm2Br*-=knzUU$cYsKg{Cow_{4Uz<$(x*<_Z`hy(fq@mf=7N z9=XRAKo_{^sOK@H-zR}{2^|_`EBj`5NS6CNcP}MV1miqH4LsixqQ~Nn9;o1M+aaSw zFkC+ULgYKlA|KHsJ#}ZSsFkIxr%LtdE%#K!D(WcDAv8Zc7*>l39S9vbi7>CSvu~T3 zBxyG)ffg|?wB_j1t&cMgC*dgeFK+({=PD*$-x=qrg4_V1rm-lgGSTPk#CfjvL4PNx zPB=MTN+I$L4TwZW8Y`JVk}dniCGb>re$99ZPX_(W*AX!rs0<5TbJhlTv4CPQpyt_; zY)HqIZ`xLsfsSbhJpnkPV5xH$0WS3~d3nfMG~0>=f3GAjh`$BuqjR3W>-@(tcz>!c zy^+daH`oZZE>}|o-IyUsV^N#pH!lXhlA+k}`Ezcr+XZ8+?LJ|Z?mm@sO-Nbi6L}Jy zId`E9GIjT3DVspB8VLz!E@Gzf9@R=UgKhYELm7g1CIbrClBQAG&l6e_EjNX_hdNVF zfz9F26aOeqF8k~srm=lKeWWm9ufm_zTwi+MZqc`}9Uy;o?K>Z1@NDK9rz#1V^|2h{ zPrks{iXQg0rbpN2$n42_X#Nv4@-LwT_Oe2-9#z6atfVFBd-=Zz9*yco23Q4zod_jY zM`i5*qTwDNZ6x1D$vJKmF|yg@U~VyQ&F%=Y1&&*+dAvT7t=J#m3lOu-x-n=+&n6xQf$D zyYC(;nm^;Fjl{-+qVSx4yV_}46Mr-w_Y?@|AR?QOAIYeW>tSuGR<2|H3Q(Q(6iF}= zQf||7xN0B5O3#j}p38T~n>u*FE{XTCTW2t%V!9u{!+Kcy)BkEyWP(EV;}{LuTU@;* z+yQ9)#N)1ut4GxkPMHS=|A`k6;)m;m1Qd8aMxSv0Z0x{KGfDwP=d)MVwMO+Ig_Bug zZ{tL0qup7Hx6B|@wo~Dbm%)p&!1`WxJa!lN;V9TDy`%d!#`gLGaskfl3wVK$>Jx}5MbT~IlxZkG(efxWnoH@Ls@F`imspYC;8&*VT@c$nk8{< z;n~@9$Z>Z_Bg~{AV!-&frUt2@Z}}jn$fhjK7S#s=YZ3VEmQ&R4{e~Cj3-m{!DA-z;8szRQ_}NTSQR0Bxyba zrQ2ejR3->}n;1P>Q}QbOi=@ul{r{vg<(;bkUqYQzu2o|BAi}#AY4wBa*^SNtA~P(J zcZlwG`@yxJ=3%G4IO3y#oETALju=bxXheQ8uw=rI>;o_Kuw5}R2!cVm1 z+grnUMz&EMaXLgy{qzHxB$)k>^rCw)w{2LdtLmR8y0CUL5bGHKte<`4;fVh?i>EJE zX{b**QvcKQad+S+n|b}cKg;`YruC$NgV(AJ%v1y!eR%xBEx4{C4eH;1W<-zTxKk;r z@j$vVjAmxWDc{`UQUZSphJv+k`Ouj(zTu67we_i>8lUxa^;raN;b*^3B)45rEYVAZ=QlRC}wt5l~`CY zKAM(je$t&TW%~l0QT!fJZhjHhFR6@MVguEcwd&4y;J%wzZ$2Pr8@vLdjNqVtYO$}v zpENVW--`81NkHZHGE|lzb!qs8NKHjLk{#Y5aEl7sn9J zi;V%BY_zVI3?KAn>ljB$c&0UB$ADKGFdCR8VIgr8mz0~b1XnMU2Ams8DaK_34Ae338FyM$KTifT6H^!u#d$`)7wz zAuW5l?%NPe#EilO_#4akUFUk3vz}Y%nCz0Mx#SrW_6l%=uC$=p&1A<36(41K0BUIxF$SiGdx#q7 zzY>bhvB{w|tz?4qF=_xcV?W4U7H!E!H`}7KM1;B$K!}L>s+%^???SN{5O;Y z%s)|=;C03L<-#sO`wnvsK8$e`CXotNG@p-^F--)|WDcZqZM_}7@gs72m}V=L7%{mb zpxP;vH**DL345~>N;>NwU?-J%m+7_VtHOAuWs_c4;QIy5pd^Fr{_xh#|Haf<2DRBn z-5PiI;9gvUyVDjc?i$?Po!|s0?o!;P6!+rpQrxAK;suJG^gZ7<=gefDKbgrSnJ2mT zUi;c>t>j|a6Fg_ZZ-n~=8YGy26S4(q_icH4Xde9KdiYT6JMYiQ0SRxBYY-=qk|eh{ zo%j19p(`-;Qm2%47BCi=qH29Lh@Zmy@REXQeBvP6?9GqOabw+nGXotgGrlOJlWnKJ z^SmAcS}SMI3+AgweRA>9H{82OmK(Nwp6T;gg!VJAPLjP23P=NB_B$^z9npkeSnsRX zP@cQ{U+y;?db{TC9c5c33O|81VrS&wE+PFR48JE@ZnByHBON!N6=v9)$|)Z1%SGfx z(!3-}C>W8w<@Wu+XQw6;2`H3257|3s0MQn0+^zf<(zs$JFFFkd?$S|=(2wN&q7mF# z5Q4IKau+lKxokKqsETdUw46J3EF&&nBXiM0t%i<;UiH2r2R{5~1S*Qq9R`tf*553W z^gM(JC7ju%x@tsv&=83k`Wdk$!DS&OQ;UF=E_Ol(D1mG1a8*%HH)tKcLl`Qfx_0iw zSv?<#i8#I~-aU4EkWi`wq814|mj3CldzBaEA7^uT?5@+8!O5u-{Cf+@)kweZ0$gSQw9uX>pJ zgzRJ-LXX~XK^T1{FHZ*HAJnx?t!i!;js79pzz+MVm45b=UvV~#2}=2GHv8r``j|U8}&~Z3~RO_T*j*x3Gh8O zzC+h)J=0?Ke&9#tSu`w(N;+Y+No1Qb8(JdnH7nHbWVS2~Hc2grM{)Zt$xSvC!q&o6 z+cynm<`#+^Rx;U5^1UriU!v&{t#A!63cw4A%(a^ILwE<~VMB|r3^y0~WP^s`rr{@6 zR)nVXg3ngK(7d>HJG(KOaz5Ewu1duh=>>9vWyWGBA@vVO5lM`ym`NnvGo&dai|^we z+DyqgDJjzYBC(2(Ue+t%7@&kP!B<+knvl_a^`9~^zNkE@9#83{1nmL#kvAV;n4Ep?Jh6YNF`z+FKf4;(Q{N7sppnbxX2OtXEDA3zB zbm1kTn@c=w+{;cFMbPNaOm(d_Rm91FNkNreNo#aSO28OH@%oF?aknHO_fRx=JgJ*} z_s5%uAke%6%DD^)D}=}k6dTJ@=ek&JBO6b#? zH1`GKVJE(S{aGRuWzk8s7tDQiR$2W+l`}=$oQlh~A?5p?sTiQwe@5kLcBdEVxP?Rj zWeY+@g*li(;Dd3s>UXpDg##n-Qhdrw@z*FmxgQQep5&s4t{7G?#D_>w+J(zwRFA%x zqc_NVj0SM#khbdN^eSWnYL8Dz+!Wf8>sJF8Kb*_C-^>+97taZ1_oK7>m>u$2=RG_h zDp-A~uHkktzdMtIdi6FB!-(eeCoNGA_)}_S(J7^HQ}9?7)o&~1km=5_^tXdElUm(} z|L)hF*N9WupdZybe?GORI1L_J%Lm+adv-(G)iX*DfnVsWzNIILS+X)UWU!KsiaFVDzFI81GKIi*hB}6Q8pmX0yyW}tdgHr9FOHmJ z3f;X6E96%VGao1_G+XA8u+O}=<&!lMmvDsP1Kh!2b}X`jcJH_PpNE!bHeGw`RCk1FZAwK+ zUx5z(M3GY8H573Z>{C&J!EiW+I8APrBlm6=CpgXi(E~>B(1qxCPO3sqK6qD;=^t)@ zcW(&~KykOj=U?-X(#ZR#kEXDHlR`N|}CiEUOI%x`}aw1aw8AXZMD!>%5_@XVl zuE$ljR_NSoAexH??)s04X)@lwrHgglRZ1#XJW{{Xp?JUmNpRTJF-iL&^UUnNMauQ+ zGw;ibm@SrBf%bM^5MJUvfjp=@wt!H`*~vaIs3`sMyNB8_PkM!URG zw~F}_X=R}a@c#F8EL(bmBW-|$a|2J{@H@m{pC#glxcDQ%?u(G&cfy+2cyyb1#U4yi zebBbo3Erv@myVuC^=?H$eG4RXh(Q=g{LnUo1p17~))8$_P^O%thI%w-Mokwb0sGih>%c#hj>EeTHQMC zdnSIC&mHm1L$jCc>ALV;S%)zR+CztX99Xfj&VYvgf9z`vj;4?V_FAd>>QhYMu+XrU zi616eX#~6~;xwR78yN2@N0VKeKOkR;Urb;m?rM3imwV`G??oZ~`GLJ-fBOjy3luQz zCLTB=@+;@Kz4Cujp*+>9Mz!ERw`X$t*6mv<&`pdi zQxtbH#mqisuyD4fz4-jN-MoWzNYF0ceP2r6ed{weFDgd-RlR=r^JnZ*s{MT6%0MUB&JCC z6j+G>sM4>R^oFZ{`*n(SC*8k1OF6Q8{;<3>-a*=_Fy-7!yy(v2G<5L&AcLuOQi64U zxcCFp?7K{!B4%Pe`X|ovSNnfP`%o|bY0YD_e8EN4>QnH&ZA+f3d6-f+I`Txo=Aby- z)5Vr;V%{-h&o5q=gf})UnE?IachSE(f8xIWbQq9}>JV(kLr97R%WJ^u)-%~OP@fQR zMRN}_g{qMcHqnGcNeK|*%XVcdmK1xUzxqvqyM6_ja zbj}9uRlllg4I^iGvL9^XK ze8+#KR{kzgoIPFWO;rZ~E&y3En+uaH^uzvMPz&Nj z_L|&V`C{9j>I+&X2o#*w?~S{pt<>*er#GDrD;@Fq(k$~l9~h3Puvk0A3wX;M{bb$+ z(8YU3Y^YDYvgRE79%Io;bt(PgG}bR0J4qmSnv24iy*miH{lWKV0`9hNnJ>l{tj~Ld z+YHmpbR=`>4|hY9m6)`)N83C_e}YZQlj(!)0gJ8F;>FgM@uva0{rsntI1fXFGv&uI?eLUHzg#LDTz}(T@lZ*BR+^*#FA{ z^q>=UG`Q6D9mp7Utu^bUjj9O>pV;s_Q}F!+eqZRH^25A`)30D-*iPYp(5fJJ$?i+0Z><9ZgAr83g!q51(5q6-|32gUBC~8cM>EtNQdwjti8*Qu;cIwhhaY$3D*XG;eYijylr>$J#j&wTUG+jdI!7KibmP?GTnywbh(*x?CM5EM* zraWj7a*pTBb;TF?^6QkBx2jNg+#eCiA*)~w}| zCJv(Lt68;K8+fAD9yGRs3Y>@t zwv*?8cYSSm9x+=V^e+6Z@Iobj9N-YZ(NJsyzN>MNWg678%E(%TivA5GbDsGMIW%QM z&5mWGJ%XDY>T@m3Ld>6{Q+9uN41=R6)E*pKEHma<=$XX_=`7eujz|f*m|?*}N(ARh z`&U^K0R)AcSIyLwh}FK$!Spu1yz0NSDnHKzJ7%GrmQu!fHih&Z&7@$Smb5sjIMKtK zda%u_6~^lh$7ANmMq`1U#-%LcPB$E~8bgA&MPp4v@v!`=@BsZJ15-@zxXP52>^=Lu z;d@&s;<5gSTJ7m#1Uc{NP6}EX8BdOr8^n?uIJ5h#7+bCnXX*p1zKoL?F;0d4)__-S z1h5u9MKnrT2;V;awk3Dt&7w}$dVXLo)GkjZPUwhHfc;iQ{8S4=O4#S^-f#edBVCEj z^kTGYpDR0X87t*i41V5kafzJ~|L9M-?6FKsP{?wIm&^?7J01Q=QsgioUNOR4KnK^x9-@6L`mmJ^qy&pbR78yPHhx$`qd(&l#EGbgAPX zj3R2-LSzgE<{O6>!R@tsO8X06%|pQ%qCujui_;vBI^OdQP*88$(iGpCPuE*X&X1pO zCgVbXMkJijJKvO2zD#}tLW5-4t@VeMe%_ZeL@5&oFPNCHQPx|M8-04R6c5cg{@7>R zpBv-b{voj@VwNG8Wx_AvYc>a<|K zlU(P@Sq7T!t@aM$4l16cev%Ma9@qb)J!L#?kF2RUNjyw^joi!p`^xTQcT2BxEqp0v`0`w=G|A@)zB z)1bK}+A>dm9K8E_X$_Y3noAu9oYABU$M6z&M$w$u}3m%O~FN0;C zdYFzl7uv2q!oH*ACEI`?NlD-MY&6ldXPL(G#PS9w-QVQpqh{XquOF>6cCAW;amb5B zbAjEB0uc%pZL_bVyYOY~>Iqy+JoMM?UO(pFq9K`yR4hmu z@QuHiMSHl+gN(L5bbX6AaVLxRibW^xm4i>rnw~>O_h-|ce7FCl^xN-70ysq)>mVU( z-whk5!JXXcjwR>O^_QL1ejLc0vkJGS7ye2J#w-KW~!k1a2TZ!f?A zK_vNc%sD1j!lcLJzMJaHt6F^L-*#@k5_BU@Lbq@lC7C=KoguzBmXqx6DR+>*b~Pq~ zlUn<1wxxgxS7cvlVu*=jG!PAcmHPU$7@W{|ZO8Q&?yIGIzJCIqQAIo_{)~Umj$)10 zPtF85Y|~$zU%$h9_e^yhx5peCb^c+=$v>j{xMAZ`yz|}#KK30VGA7m$o#=C8>yKw< z0sckRW2p;~!mF=7DYdY=BM-Uhj}z#QqORi2Pc-KZxnu|e*;hn6{+HZ;w-p1HcTATL zXZ;#y{%?I8N%}LboR;&;L#Lxs<7-- zElyG1_1~TFOgfBAIoMlB3A8Ny+pan$idGoie3x&hL3JgpPUQtY# zZn@s!3gKI9SKnPWCg|47u}vF|p0uEi<0_S8Xj}NpWW2-cWX!fd#E3;QrEaFI#s&-{ zUV)n07L8hPemo!m78BCpMq$H#!wcvz?};ZzLA}MFcL#jl{e8{QRbeR;@%$0-fFu>> z(+ga67ZYzvV`d-g#HsQowea;!?fyqL3UUWcZW}pHNfu~{L(Y$L_43ipfhuv9&%27V z+>v-_>=3~m-kdyn|0N6jEe-*|a7p~Nr#Jw%P2sIT@u{phmCd|zl)2l>IHEJa&ynEk zs~2*L>Gh7B4U~c*K(uaXJjh6+zK2_-6FO)?KKmG<#8TMyE-Y^)GAxEDltGp;lZ#U( zo998Ew+D}Qn&*Dy$7`A=KrX@dqQ#v=T^_kw}@4sZ5zgG$t-pIzfaS4o}F%yM2o2g75vz!S=%=@Bz=z z{BPub6e5bS&l6Ik1Y8Kn03w%gDb?@eLCo_}IRXbm{_L{&#bB9%YXr!ct6(raP)?p% z3h-Ah0yGK7;0sM^BsKlIlqxPT9{1=Dezfrj6J*pKt}rN}_+m!eDw%rE*^iN;*7yOH z8x*N-qB#_rW=^7UyL*|&m))oYmxukGC6;yr=Oq|?ENL})7}~CT^pHi=QHyk_@0*a5 zX>|C!HN6&*TOIt)eEQ({!fxC4qsMz-kbaU#hz^aoW$1SM6C+lBmFdm242#&po*m+A z4$fl_%C`BX-Huje?U1Y5$kS1}EH7tN&3OL@{Ih`a2oF~37sM_Q2ZCMfX(pwQL+B%% zE;lTC@6G=5+5;!g;!wpuWlDRP&!~;DZwYCec=sKS2oC$-o#5S&>;aNba8V4sh*yi! zVCQrH#KW_IMWL1aD89VoU&uY5_9(2;*n=wX<`RQ$V-wPXt=oC|=BF9ug-aWgwE4xq zmR=pW?zT_z!TM+<=iA&ei=gEho%((Kwc{AOM>6+ZX+Yh*LFn0eV zTIKd9ccwN2SSFLDN-!xq5N%wNyhlX{#_KmDLuE%-o8(=@hyt3LT z3pdvqO{d157AJ(ln2Us<{jec~>=r|W6>BH2``reC6HA0LK3k4xEK}z|m-$i}Ylha2 z4l}`_ptL3FF44%JufsEY3_27%RFl7kC|c;+X0fuF+voGJLR0nV5n6Bo@WTtve56A* zEp~)Zmc~xFi%3tIF*SNez`>#X1QFXg7m|uDDGIax5_Rtb6%O z{ECm3Y#bEDz_~9)z(cR26+L?%N5Gep0ThG@e5I+(5B4a8>PeM@5P%hkO_~n@NVuZO zO-Q{EvtmkBerJAIj&1}m@yG4&Rqv~CC|NA?&=Cu27hn3a*z*zh(vL-Nnk3|2ab)cn z_;F>r=Vm9CE9ISPM#`is#I*q5rpr{QAjFA$c4^{N5*2eg59eIG4q9c28!m8e3jP@I<*7J<6=xk{ca8 z>|(xgbo`9Z;PSs?+tgOs8ark4tXcob;w-lopKw^4>m*|B`$fj#aM@9UaQo(|x0d4` z=0Xs>EDrnJyyMJvDS&eZ^4k3r<;9{TObGuid-qicN6$63EK`k^2e zm>BnWLwwo>JOC16jA32{1D~t96@%j!?4QlJJ*4qeui(5tqrwGZi^3iIQZMN{1rdEY z;(jTCr_hnWVcmD7`gyAoy(6GjWjN7_-i}F`>oL{gWh%g&C<{+h+7zxJMJJ>x#tk-~ zj~u7q+L|SNQAcEzmn2o4jUHoTdU#TCXevB;Of?@4fEE2`<DF%Q#gG|Is{F7e>rCD`5&pCCB>-toBlMJ{0~UX z-aP|sECPPC8>|?Rn{0_klx5#Mw2Hi^YcA7iW)O8|B%AnKSPlU@>9^v{i~g=5ZHT~* zeSRELRLx*P#Y8Jq@>%y_r$d;FW?&h&ng2o_Hq%>t>~F!0ZGk}@zk5P4fMu4CMDj4r zz&6w~l=>)S9PmkTUjhjf8`?8=V3k%r=E9YDKZLTm^XSnpYD`dKoZFcCx4Q3iq?)^; z)aMAOuv3np1a+RYTtqag+&-@1f0sUoF-r* zitwUZY^FJu?~jkBf^R`F=GtFCLU#Ar!S-6?IquAp!EDa{Em|_)y4K|c)9_mC6J&+m zU_2(&rgn3x6Xti^<%8bSYaEfN)*}t)cTD(tgQFnvUuF~Z(mnspzFxjH{?1&i7OfcJ z&A+b@(*HnnYaR_F2Cgev+KcHvM%oe}F<{#wJ{ciJF4&hvxi<~?`RxXKWv;Nj;H{e$ zyWt*!v=O-B0rI~D#&^F$^Xx< zAI)1g|0)8y;kQs%k$fUtmz1nGj~VtqP2l>?mqO#HD}2VS2r}Ab9BkbkeAld}D643h z?hW2>Eo{C;TRWcsBOgDZJCpw%deq&<-P?B}I>CA|=#*hxAwmMtes$h6`a{QRt`!-H zzq>Sc4V?Foqc?av3zco-Lf%;c^(oy#^vd;n5E{jRgFzL#TliyI{1A25zG?WXxyJc zjFb_28VZ*aGQjp#nYT8Axa1oyZZSA|2XVa8jT2d#<>!P;)HMzr0G3UCC`nkWYqX3l zFCE^$*Yv`|#S5Ep6aIq?kCeh%G*&2v8q|m5kd2j2o{E+2U33h5ncNu0ShNof15FVL zpb^qCD9a-Mi;&|E?c!vhH6&#IMqZxENA%%AiC4F8m6VB=RLMsV=m&Gfm`-g3Uv~v| zaU7(Te;4cKBB+8$5`!z99{bUV4$94#cCsGAgq)vtHe;-ziUNC7p2%)tzcnNH)aA5( z;V|i{U~c%JH1t!ICko6qZj*4d$U#vaG#yV%|Flz{d77G~_M6%sVhi9QdZElz2{{9R zPZ6{@O;?P+d4HwlN*qv~AfUFcFcYP@BE(P3X~g;BGz^#I2iwxchJ~NP= za791+J-q^U)-%i?hnw}T=U9Kl3k>(mXyeIQob$~etGF%~0!K-K7cB^^>?25GSHL;C z)x)m|=Mb!@u#`8zs&x0syw^&HAbeevP-*C=Jw}MNgQtk81GJO39Vv-M(IC1<`=c_I z2U#xlOheKSjza+GZa9MhA^Uiow?XDMAJ`a8<>};!6d8ynD2_f=qiBC!$L6ZW<5~V= zPK4~LvO98~x;x^^Wfl9j&|6^TII2eWDS;Jjh72hY|1ldx zQ}sUAvh+*WNfCiEeVBXtJES`-^Ulu0$vez3<(NH~v()nnV+mraLmy!hgVb(I zYm6|uZ3Q3EB;Rh1$v~ouN1jjcYZ1_avY+;z$)Qm`_HZ-a3dk@gVdSDHSj7Wp2If7A zXdKkI=v}c-GTx`HCv$Rf!oC-W6P@2W&47o*zIDQfN`L3CQPX$U`RtpXD@OHcw@bAK zt?C>FUh#KwwZtX?+(*8zInbIN`M2R2A9U)-mj0jx=#9)7A`q#D5BQaz<2Yk?vHtSe z3+K@oyaKmUzV7L>ts@iA9MX)qZ{JM%W+^zb)df|sS{xyjE!>ub!$l-Tl5sz+i8LAr`jELLs!+*@0(S8>k_TjRkm-laA;$$O9%WUi;0Zp2+ zOliHxAGQ0Msgny@A)=1+4XA6pUNauX*}778edO#G5Qsmx3yV-X{{*|A9XjRmx8 z7>2Xu-&EV5(#2lZloGTwo^iM`7eJOX} ztb2#Afp4e}xQIc1JS)W_7n;!EC-Dppj6o!*d!7dYjp7bDI>NIdjXdKd6WzEj9Jp*H z3SnApFl=TQM=aAia^8@Uuwit!P$QR;tNgRy=Uw;2naybOF!Il|+$7N6d5CaQBHvn{xA0utd(_#Xm7dV9{SM7}2d`30TG*=1j-9mLaIGR6q(*>|4R zX9x;%Wj+Km-AHT&7U#i~yv|06-^M$xw;1_99%eX~0Aw6h-zSjou3ohdC|*2x_i{cs zxx-v|w#{u?Ew^n2&rEsUx7!}FswThe!8=ThJJ4B^fjW19U`2w}gq&W-5oJ9u7hsz+ z?o}AM-*%s~Bbsjafa3efc)Qlp^>NQKESE({G2VOJ8FO+zSEXUKK{de4giRXFOax9! zHEemDF84dKj=E*CN8!jBx#N(1B68qnr`%7(6FvD!k#N-_yHMsh=2yy0=%Gh=b>H7y z(!9L%vl5eUP&AYjE6AzD-e5vD2ZDuLgpzK?Naa6r;(m=_lFKV99?BhIQoN$y%07uk z)VFfsGI|>jMnu$bDhJk{Jk^a6nN)>5Q-)#*Wyvxi05=e9hta6Z5;=!2xo0$mt%m1c zDwn@?+V--Q*!#gFn{Xi75H-S)hqasbQ2t2O#b}@|j+w&{xn9a|BO`!H;) zI5smL;1MN+p?^A-*-~eLws%TCw~yLC5j_u2=RVM~ zAv&%+tich1h%_~o!3JnG*e>akz`~w<-+OdByq1PFrEN+tU2VuXA(9$qQ;{m!=HzrC z{~N^8-@$_}2F?~AjJWNpm-__Jp!24G+)K{QX8wONy-pE_=IgGJ_hxgwer=DxmDN#z zz#+rR{5)Q>emr)-4!r#< zK^r};J?nyt6N;VKKlRVtphEd@&XjJ#-VC_07op%`RKP1A3a`W1y@^7e0+ps*Z+Dx*^DvM)MzF7 zGeX3)smwkm;=XcCa!ndS8AKAD!sI^lrRZ&UV2QbgoHLRUUmSK(uTC#W_Caez*2(yD zsU}qP*_qhY`hM{FhUF}y&J(WANxrDb*B*!qKax>J5bAtk2fkp&z+ICf_h|CMjxNY|>vd&Xx=z z9rY<8{Zfm?#DALcEqdTI@kA@_Kp5^gAlMb-X2FGBH1}IG6-@HW9t&g9A1#tOxuP>C zND|r%kB?fp26)A%Pd>fJFFS%*R%9zy(=;-u&nb?BOnrf((GN?xki5N5Jza@FlCvjUc>gQASCfkV z2nRRHhmA$JLX6-gNi8vmV2{I(wU}|(kOr%R5W^SUt`G?sk-7+@a%4khPuq#7gQy7v9iK}k^1w466pFr(U>+g=Gg#22se{<<)xmTS1 zcT*1$o!)D2-YqSG99n%<&TYF$jEve}A;y5elh)!3`uh5RSE|2PF?7C2ZN*<*;60ok z*vCGMi?yzv{YTr^wT|A+wQcR(&7P4ZqEMnkckx!juI>_lADj{U?fque`zMfjpqn#f zmQ7e#L5{JiGL>(dKwUiX8+}Yh1@CKMKr)2f%)MR-4cs@m`fy!D=10qYg0@0gQ-Vr! zQcSf7p;a{Lbi4;vyc4Mv$TkR#0W0gZUi0rhwmiWGaUi_v#OS~VlkVh`lM-dJ!_={k zqznlvaf!erunnhSjfvhpoXIkkG(s|Y%umDHbGZdzBAIC950MyB;0t`2gX%C7JoDwq z8C`Vu8UUX@k|*q4F3|;?<&s_GzK0S?6m4Z@2jd4%=A{7lFvU;&Wf-Q6VE} zX{(?v%_8+dZoCj-_%cF3MkA&aC{>4v}P1g73aBDem zuTBtvA9;!uLQH3d5s1X2?lcdHDP<~xJ6Dnw!e}*DP3A(Jl-0wkt}{jbbI_QMQDLg- zTIkMq7x(=MG6kDY;jy7s5|`7F)qa|TGY7|ggur6~V8p%L78o_BLJ|x4^npw2pw}PP zu^YN8XN^AUBo>{8QA7^RLl-7Gp%xy4sfwTbYy%+2E~2C$cr1dHnob@jby%{cx+Qp5 zFP>h5ny2RH7@;TBmswPoo7^!xhYKqQ9Shb5285O!#>fTOvV)g3pN`*&6;uVa$sr!q zfz!6n7LMdx%L*%#aQrRwb6f%=CwuNsDt~bj%Oxr0Flax|si|nm3y_3$#cXF zZNHpz8c86935$T9SBmGuN|4b%GQ%u2ir{fqBM{P_WUY8vUsrRz3nIV&f*p85CgT0O z>(8=*^X7>Tl^y(AZ?FV17P-&$0M+Yd^*#Bl=jP~pl;?`a2OF6cd9Zf)+v!%$`F8&P zk@4a`D*8NqRc-JZljGgj{csX-LzV4sx8XwRkNV5pUG?^*o}^i7xCk){Tv6D2P_6gO zwY#mizbTB)_LVOYI`mUyL+n#PkW&I3@rEwkoVp*S7A~L)3R?pdf6gl)y%VB6l0>nP z(xg?&2Fv>Qo$}u2hZ^Vl)biybG0P{`8}VuE-hDNNwh0MHn>Ghf*jm01A&Mb^Z1Q%Q zLeOlhGd-XeYtlUh)qMTguhRj<{oU;dY0wD?mj5)C2=1w@D7w)0yZPwXB9^RS%MJM!AMT zw`~ak1N__e*!firrFVUH@~{WQ<_HS0;W)|d&B@&9_i}^-$G)>UHxWE};$!O-uNY|a zhKp|n%YZ9S;jzEYN|Ji`-Q1U1Hs`shZ(U1fL}z66eMliSSvk1M^fnRKkg8^z4ERG8 z`H_wTW_~|7L;5=-DN5^8a31t=D9@75xlbzaX5@c^&%+Yy1pK^Lcld2&=G))qOgcfy z)pcH!&3rBaa7>?$B{_d1^&FTJiTgtrzVvPsUYzu}vVR7Fr3@h{`#@p~9{?*fRBK8w<{a zA6d~~CFCv0@#c}~!JXmx9vcBj>+4b&hybj~0ILo4A2WbM;0voCHhh#`d(|)Q)->0V z8Pub>Z>8g{NrbL5)p#7)Mn=#x$@KYL{Qf5UCcLK{Qb*xMgob=vmR$_gdIT z4Co9@0ZO8(QXx%~@mz~O_!i|(e;AQEf1ksvU3a|g^?~jOuyy>w7o4NfDZ%_O;O~8X zJaE_kWjg(z3d}Rnr8WGC^qIav=F$XHT;*W@{<-bt{LyLu5sK53=H>1ofyu7cv3CNO zGD5&%;5$Tdp2;!5PwA!K;12$SjZD)C0l20x;>m|^{Zc!-(9>%7W^)={3W{$EQSLu6 zI1zLW?XW+PyvX&_Ar+)O7}|;?8Y(qL{4W;*g{LF+348Kxu<+k>LM}vdF3;tykCS5D24RI)bAtpY=nc;?8T3wv9=xZEdofgf@dD zB|;y3ci}k5uakFwK@^Fg>$LDNTs;ja6P& z{(Ehx9=`Z*S?Vjlv(7=DRTp|2!Bq*|J?;UFChP1j=nWG)=Yo=V z=p;`!eFXu(82z9BD`ds6&#FX^-(hYsLl<4onO@0P-^WQ9p{A1ARm6S#|LG7;q+o^N zceqcA>kqd>sa*c+H1QCAk|{-qha#kE>O(rWo$3_+W%iypS2~)|2!2U9OqKFSi!V$F z`2BboN`WMLgi(uFMDQvuZn)2theO7W)cO)JUl5sKmFZQvIs`@OK1JjKIcZ1KzgV;U zW!rU~C|Y$zNTOkZM+D`l!A8Pz_OZlP9d#4MiH6$YerveZpHua7L|HsgO^jAo15xq6 z504!Bwu#qHI|mnADLAoqP*oxq%aLaak>3{{B%5l3U1brpy7WX3kV_h2#?voMriLaw z7L!XaJOu(iSm9dwN}WWR1?+jBm@^&Cm=oODJqJYIb+56nk* zL!^Gb1^2&>SCzN`wK-^++CA*LbSoF_5SOX@D7cPU#T?Kq&_tz7j?|3D1X*4$MYUJl*)c zcZs2R4AN5_B2kPO(ufAAASt6Dn-R7O37vqpE?>$<4MT+BZpO1x=E&pOIMYsXNQ6)u zjvL}?n37fc;;7B54>j>htO-`7O%b>gWH#S1h1knSR+I%bojCK;(S*+pB|dV@a=&%2 zAK}EP@cul#DgxA^j3~3|4;wb>et%=m%)AXh`ei0@qBUSQ@Y7EyM2{))R}5PZrWfIwSWTiNxB45@)(!F9b2A! z1T61$(Yr?P>p^*9?QN)*DNmsb%!{kUD072u1n@M5_ztATph7<4Hvt*(P6}b()p;kh zgvgPf7{Mb)XX`>hTc%Q>a!A>9aWcf7!!e}6D4G#mc69f9q9 z+x_o6$pfyixUpklxAB+wL#j`y;@AgUL+KFmKrt0F91xg|5 zRs9~}jR<=r;a0WY6!3m4r=Xf2DmYbTLO$kkfR!uR3Q0s~#QRpK(HDflf1#!#_s zZrm_9fRSjyyWoP;i8zjki6D!QskpK51LuTp6;a&?7He@)6WPq&l(Z4Zlnq~k(TDHS z4F9b?tRpj18X5~(m+XoTQB*4NS)r+x*C+~gd~7R7EP{l6;MAo;YN8d8(nm{@gR7R! zAFe<2;v$_3_1YIS@)pHD;Ep%v9>&PV!xvQTVTfAh#oY&fMaUGsxUiAO6{|bR8gTTB zCKST(W9V41LRc=)5`_WAoKrClRkv=m?l zo^(X?xd#O+5A#H8>1iEiUq*gk^1_hEE3LgTLT##`Voc&AjK8R>GQ;j+u7sguB)$p# zT0U>Wbiq!LoNb9TRPgqbLW3(EU2-W;x8t#9{<_9^l$_{{PBv6U(-O195=^$qfgf9^ zQI(IffJP06)7~^%>ybvJVbKeW(pk{VDimI$@|3_D`jXb%>AGcnAf8e5 z;`Xx|)XnnqHD)O}u=wCo!H5H%gKQ-jVpZCaWRh=f_nG-;$)-aNTJ~4(xr9$uC`sgf z*i^NL%*r$0qfqge4a-AnXPzek;fWl& zN2u3r3@$vJJzCJtB@_`q0|=*zyF~#}O19?kMe%D$XHQzXXv1#6KBFP?hk4o5FSpMV zSFYRiX;*tNTtR5L`QelKgFu;xXFxMd37Q&6>E@QnA=JJ`($*|eZ>2pWw z+OB-#RuAEZk1K;%;xWzy(ssy|2+ehOyqdT{{7gZu-xJ;1!qj8-&U-3BQ|xmue=ljW z@3=6u{x>JoJNb>A(Q0t!vb{vbnbYJ>I0RW=CF$h#QL)zPx#~VFK%BX4MjvQDe}tx| zE@BoSSO2a>3Zf#_dfUDF<7;m-uJ=+{qU_ZoV!#7tgLyN&NXXvu zm9%iENQy>aHT%;!S)>wMiMbvN#f+V3vbaS32LgghPKG8}CV|vRLS+yBzH`4#cg=d@ zE;64Uz?*mHfl1Jbwt?V+H3!kAuQZ)+PAk)8Qy(Vqb#>CN#$m^7R9{<&!TrblJ; z2E`18XmgO{)5^H4eiToP1bVr84RA^bW>BMNFh28O_{LWGL-VUV=|PpBB%Rb3?i<%; zA(-|bGxv|=K?(4QWJomn*)zn{UorQp(Z6uqJ~e5nV?>NFEctkhCGQ#%EV*~vI|=?D zzTPsbt#Ioah2ZWI2*uq4#kFXW;uI(n+#Omd8eD?A6nCdM#T|-Ep*V%&T8i73p7Xu; zy?^clr=^M*vDHJHbn!O1M%d% zM%;F*AT|1V*Fx>Ydri31y0^bRUAS$k!fD`Dy<^!BG@qd}$Fv0BYJ;a`^ou9d+J2lM z3Fd7)Z2z<8r|Y{lr){T$bJI{}mTN; zdK9&|E=dD72tLrH9{3o~)`jPfX&*jo>@&Z!F>C5q4)$UkV!yu;6$`zv9Wb}@ zz3*E5Lk)kN)do#=3l%z*y4BxR)4&1yjhD(&O|M9P^tCur$@-9YiDR#aVF5NIS|}Fy zju}!>!3DM; zaU>Dx@ zbXp*I(|aYmhLAN9M!vc`bRZ4Hv8$zRd?^mP#9`3>&-Mn%ET z1R&G0K&^vLp?FtZnjwiD+^}eIsuGAs8IO`Z;TvfJ%s=?#C$H<&zp9bk3bBk6mGfFnHz%9~cCso~@1cU{s&>8N=Q^*EJUX;-(zC=2v-OpZdJl5c_q z!*IHD{>;a6$;Zl!6oBg12YTgtA2V%=&eoLzC=s$3dwYLBI8$-}IWU%Yrz3<1=nAMd zfup@xLHh1Xr*3Qp+01osEShG_o!DzGvO+NvP6s`u&e(+~cCv&6eP{BR!&y8n{*Fga zveWp51z#EL;$Ov_UPZ`YSrarcsA~|rTj4I3A;^KljrLF)#P!kxL#t!ouY0I$6NzVb z_IM@mE#tq}ta}giQBKFiP0r#qSAu6iso-Y}kf)G0^hC%FS@2KTu+7p;EAmu2j_Qor zl=k^^`+D|#1&ohI8(ORWB@8Sg0$d(A8R+DNnmD(C#MYA&!XxC&2V}K|%Di1KSQuZDh zFRg=BI}g%_8iL+ZsO&ytXUMAzAvX)4HLAgFjO2WO=#DXc#Yczos+1~)Za>o^@}->v zo){zVEG+66>WMpSytw#umFht-6n6M(kP1I0r*ty6#?vjY(E?F7Y6r%)=|J2@Ku?Zv zuH!m<(KAhP=4s98xr%T`s8M^#Nqbhs^|N^81=yx0_NF6Olf4axh?%0O{T;gfb?^V@ zwD2Cd`NDsZb0pa>`ia8hk^=Ul)~Sy}AauXW>Z z<-o5ZaU=q2h6tMMzSR03YBWWS=q;veLKupc-Z;(kv62sy^QNatRx13S+Lr&E)5PP% ze-V_-lcjpG!~d#O^^5IG%DuWnKv&Aa3vK5|q0G1``3t>ILq9T2{{~uPcX4bpB$RTT zw+?Jz<=9-`*1CoiSIMw^P)TJ}<$HM-1!HPengeJJAltm##_ZJ&==HInI0~MV*D}=f zTRh+d-4F8b>M8MRe8cpA-rP%>VX*et;s0!R-mi>DY}dwg!2?N8b?sp-~+9 z9sC0(iRbd3n!Q;M>KkCOH|1vxOgKxMMS6dO?L_Q5I$+I9ih_kKl01%5&mc%+GrVc8 zB+dNEhY1sH2_=x+HXJi**fxrHb*VgP#v1j3!GK{71e3pi^7?#=EF2**3~zWQY|{sC zyG`R_^tsQ}nwQn|B9pG<%)pSKep>I8wLl`IGL@puH@8A!W!TT5pUVjnkZIF2^i+l{ zx*~{S5MI-un6T9db~P!6+1s})K-w=^R*2(z8b!gBpLEVS(ENpw9fkek?vk+#UeCbU z3Q(Z;bD1^Jn?qlxNG^{7Y~|#irmVt}7!Didm;VxJwhF_5rP3uKW`Yg8x-+x-Yk~mH z_KVflA@kj&EqnKRug1hVGvYySx;N0^dTfEh}eCbZ3cOq8N=<8hnRSODLhbK`CVg>2N$Bdl>`%Gj216xu%43n2?}H# zqMyJBh|agDVNV?%(p$#i+3gMI7ZDj-$6vA^S|493?NI?&WF{;T4Zy_Kf12Z}thl3I zHoek$M&ISPNYwouKc22-@dMyKlioC9$Zg&Hgzat(a5KRbxsA_E@@dOSBr{#LNg(^) znvm#>okBaBamrC>T}M;z-0+~%)1JpxigiZm{nr}rxcjbzY`*UBB&EM1&TmWn%zH|3 z{R+d#{v5#W4TVt#l96|)pT`7M-rv2=rPdf*DK)tWd%#^%_;?bXUHW6EjVda@QF2%u zxnOAG<28k0rxQ`=DtQ_Biv7Z?J%5bBY}@d*qJ!Fa;9*G^GHMpYM`?wq^|s%)W7FHh zoGqrZM0nwmz!%2DTo1`{HpFnso_Wiw5~-1ik60jM$H(U;Czu{0aocwPNu)Z{*+)mh z`bWZk<`jF%3}R9Ss~?%5umf@-!5YNuSj9WtZW2i_NMG9NIz85X1@wn%qFaqA+#r*& z$LUgG!?6yg1E`@HX@TZ^_wdSb*EI*!LjVGMc@mQCIG3OThS6h28YN zm47E5*4LVL7Eq0C4`Np`fe?$I=5G@duGN~f!+^h{O>a3%I{11cg@|Y8?Xl_M7|Js zK)5gm6FV~Q9zCacC|(7JzZw%8D#4OdeA?r2+486hHJyHQ)pf{Mio}^s`n8Ur^9%Afhlg83tlBbQtziUi*K}9bGGc806&s`h#aRX`5voxe#CE^di@E3 zWBPTsTKsRnKCxk`dW5Pfu zR`lcZZ=Nu}BMraG0eDywwn^G^OONx1Nwl+XKfBt$RabgKS&#|;#|zMAv-bJ#;HlUF%fffs%~#=VQq@W05$ z@y8GL{{@%-u-vlk!ejp0qFVNJNUEQ4TjpFtPeJ^(KVo_$TYzu%X@21W>ROq_u} z12f=^bU@l+hvq-5deZn`sEP+!_>?oP_+yLbT(YF?hHnx1_Vbh4YCw-u8^T1j&QZbq z{~umGGMoJncld#RHMSLL`?pu`GBwIJI*_`Y3}bQm9hI-*&m9JCdKaD^JS9UkF|O^x z2>Lq`-#_bTjqCb?+V)!Q4`tVwPQ$$mwS$P|0kIb@`hUJrcT9ABU2&|^Ir8;bbX|j> zd?H`vx;4(@xozAeKzZfA*>t_*)KdRrS6evfz0)RTTi|u6*_7OCneH9-zB zD&j9SuJ{`j<5)gaIY&}ZyS{E&58iQ*#0q2LD0Fi!;(|Y+9+_h#dONg#Rw)T7i9>x% z+Ljg?HRQVaj)$Ct#S8k9ibb_(3q|g&iGl&8{Cax7ll=A8DDSCbd-pCdDK@g>Z!<{| z;B0(1d7{T8rSEchd2n5H<I9Foyt!NY>iJ8l<04j_1j>%$W-pMneHOA-{!JzdtOeCWz zGyLRfGI3c#==O$YfDcGx>8t0;x9>1z7eQV|6a$JPsZhfLQ-9~28uAYMaPS1(yD>yL z#}0^(0K;?>+qoy3$^`5unCF|&@aPGPlsLS^XlbdiSce6Tj+1l8V6bPT@)8Yn*}yVf zQ{?2$HYo=UwprK&CRQp`XiJd;UKLFo)RwxG!;!sqM|~NYx*L6u37{eBQY) z%jyb>)JnR(A(9J!o1(&It(gD>B#~y&@UZfR3S(z^tWl_ZC#zKb^)$m^9Ztki>fRQ@ zi^oB)i#|?IdVym7{Wj>UC5(hFdMv%vVsPMV=D478YO3j7?^AQfU4z$_#|`fq)QcLQ zXWjqB|Ka@I>Di_X#h2CZuZdR!ks@mnTH#^KJy`lHaIIJkCcgc zq-?Sc=vWyd9;+hsZC%9TI|3aqF8V)v5@J`OdEk6zJw4T@ zVMDaQiDE&k+6?3mAQ>Tv?6qM;cl^E~kA)^D=+aPBGKuO93_34K&)K|qLHPat>C*#E zIqpeJ@EOxloTSC`@wgUf_3cy?oe)Sl0%FU7ZaZEt$0!7%RUZ;UHyj7CWk3w94IP*T znOSG`>ey#q7xwJ4&0;~p(0w|mS8(}UfLBo+g1)=miolE#mEdy8&~52G#U3%ny3Q~2uUu~k*;9>6-#`f^Q>PR< zdH{I(Y?>^Cnmnly$*J`)y_h$o=oqM0aD-ae*pnPdlRyCCVd1r#j&h@CgOvyib&VyB zBdEg3`)!ddf)x8u{&kg&N*)`9m($`r^RNh~bxZ#zxeiGiy6~DTUN$s&D~zuFk*_1j zxX8}G5Dp;n+f_HuOcn+4{R>q9Nu9t_WWTX-#8n-!Pp5zCKU>C<&Sbu_nSQTN%^+vD zILMHpF{Y41^0-3is|n^P0+Eylj?ffcoR(}lje5tWz7kuGe z;~By-?}PK%FnA!Ap@hI1eR|m+ZW&ZnqFW(P3hI`e1CcL-rUl=bQpeN#C+btjhwCnb zLTOUzI4C(->WUIm;GN1mqI#}%gfcd&6;Q7NFA+DjIF)yc^%wg1*VYZIF4NzU_ z`bF%g$EW9~2j?==g_TNEy{nA%8?CsC1y*lqhjS*mQ>OFmL+A48UukEOke8LomfPd| za)kwh$)DC{&Ky6}fDZ+(I)UtkuA!0af$TUr^wf*TO+N1eLd`ZH#Z2 zpR0kNSu=(T44M|rm>ga@h@BA8iT_c-{c6Xja@F}TKr453D7V4>{&##%xh14|q1ewY zG*lUJ$LmJJuWz#)4xJ@ePMWpbkLWWUEd8si1k&rqrwUVG#TNkq??`!5d(*{?spI77 zKV4R*%Kh1wm(P2l74%Nb{wj?eq&^0V3 zCxVXAO>Xp#tdWAye7YA01YDcyl6s$LuQU59lb#ocx%;bEb);O99lJ7&S{XC@k)vWf zk?AlVE2l}g(cV5zNrkclVcQN=alY^uyAt+;(n@cPY$yJnF<@+W?{)KE*CM>R@S$>1 zVPm!W50>>hy28;BS&~KmCCORsB--|`XDJW@H-*0~H1@u6+Mi~eX8am8O!j3ne$NSA z3`sq?O5l94I3l&!TW@1>Xw%x+koq|rO}E)j=&35f;uF>O!?;k$t^cO&W^l3B2AXsI z@TWGYk%ADmW+`$P#tV0xfY@&s9mXs_5v{o(Z#A$$ZJZ0)(uT$ALc;8I&DS+ zdF!Kk79;Qi>Z9yvl3&qgS%yl2ZXEXw{C7Rn&VRsH{KD+2#nY-Sieh{XXUY;mahzQ( z@HBB<(HUW%tJbP~QgFWFAG)g_qJCYqY`Sm*np0+w2)W&zs4+*2x8ddjH&BKRH`y6s zixkUz(-ZyXu7N{T)09+ETN|wgpD^){zlC45QPus0d3yyr?j~eqaTDw21+=Zmau-m-+zw-pC7rQz(o3)c&u#7pL-ZQ z$nL=jHJWwuy%jNGu`E5}k_E0ii$&u^uZcb&7)6>VoGnyab}io7x&e##^MQ#dRWu2k zBEjEry&=N+GYs|kGJ<{Y z=(&^`vKR|q(_g(i^5ft#~BLmkZzA`Lw;>g z2ODJBwQacVIdXI@bj(%#jfs_nJFVz4lwhJ4OKDi^ zKw^wX5ci)L>OLLgvN^4m{#e9?xRj*9(GW%rJc|fZgHSnpcG+ zwk;$sxSIcNaWZ!j#U$A9HGIev_m>%p1Kar{g)go_vhwNqMG(GZeEZm34Br@L<5JD& z)sA+pE-||@ChW1C`>r~ii%zKO<_tYF`BkCtkwypyApxOs1AJ1$;9a74M@Fcsfsm|M zA1ttVa2i7_8NpH5>D4c+ycphKm0yM;<$BV_nqsGagbL^ePYtW=FtlT2D!(v)`Al}i zSE&}mD}b6^^Byf2B1^&=$XjrC%UhBza3Ug|DXj}_Z`txWLr?Nn5NN;1c`Q)$apTFQ zL=)Z@VsddwfN3P>;B@jov*WW9euecxB$$#b?m9I)B{I5F8M;vMWf{(O0?AoNZJVZ)w#?$K+Sz>H2UH>r1_roymZk-H&2(D8w zf;CAf(u08}ay#9{ypP1VZaKZRxfxdv8&Zs2OWiS)o#UhXnR-g7t z9SJ1T!vJ@;^IvW-j!>zV8S~Q}%u2lOnPqGH9{GwM9fZ!r5(+~ssY&t#AQ2~ch=;<` zf||}EAq?hcOJv@I4kg81cEZo-8}7jI4oJyBI%`1wg6+2XOHrhy7bX@XiX<^vcL~rl zq8YsxCZT>ZpiXb%d@3EE2*2O%ln|xVSy8(qQg$x8Z*%?l!)@u|l#S>+w6idI8F=Ha&1lS%yaQyGAG=2) z2}I0dRp}cAba!hgsgTs~yR?di&-~hFvg_ZTPv^}dYy8H!OnFtgSI{C^Al`|}$CgnK z6PLB3JANB~CLRO~7H9qR741yT+NEb#o+-?zH(MCu`Hsih>FaA|b5h>4zzTP;RWR=d zax8C1{z&@ErfPFL)rLK@=RV$RDy-*FSgy#h>Nwi=a3=NB=*B+?T07BG5%5<-HOAtR zKOtZ}Zf~(dkThcz!)BA!#k&=CdzrTGktC>6<+y(-IQ`wl`0{fzp!42~mJL#(74tZ5 zI{lq#`46uKH_+$0|55u`I4ZbOO)&Rs;&a=@HqDKG-m^QZ_l86m5+Acr|08sZW`utd zz$i1ykC))Kth(A^^_Rm{0dIeF<@cTb(MwmDlqM*NXyl^R{W00RqaIFx-NYcj z4IJ~F0{!SO667Ir@U%5S4-Q_NcY(UWH3@bSL^72yWL2^bq6@a(wW#CoNz#_KSF5up3wM|ZLyQM+xbXwb;N##=CXo>*`=PSV=nPN z+(Lu|CXo8P+x917ikmZ?Ab4NSYslC4C$BkFF$4C2tY9YQbfhgPK&Wz8p6IrjC%2ok zFrWrVUkr5g&W^VJ{2Maog=YyuH_r8jBShry!w|g*M+#?zuPY;YoUXdgbCd zU}EZP;Nt5Fl`NO0aakO`qT}nL^df;zO}M=9oiQQz#k|!{y*RLL(0}(oun~@=QtY0m z2g{X#x_-PzIfeHQAyZ$JzYN^pmCa?u^%>v`7PU?CpRtb~}6E?}2C=hM`;z}&(L+AEQLy6PtZU&jI4#V?c{hh0e5NvZn21_+!nNr}y+A>EB@Oa6j+T`0O(L;gQ-^ak>dpbOKA(Xta$cSK z)UD5CR*#6#xYZkqhX7NmRaTx?S;iKbawW-z^&}Yyrv0a@sKUMZWh5Z1Jb*>7L7l)* zQE|a%y17)EUNeM4CTPb6;8aU$ZI6SV?W+Z%N^%4VkXG6)ts0=j7$Mv3n4k#3!yvRL z*b2;U`&-M#gsbGVON+=tj^H&+Oq;SCOA}BV8HVy_f0)(W+Hh!*JyB|_Jib|R6Km@{ z`b_~(cv#CtL5K}cxCR?jS#y2zCb^ODV<8nx9)>Tg22E5{p2iLYJ-%k*HASR{k0vRS zlP5-xQpw~sn;wWRR`4LD(E^NI&Gtp1drU+_eYAUUUIH+Z50;M@pHq=iK~gzeC=32S z=*=-a9D~BVFS;0e%m%sjA{33h{A8GjA- z2x5>TJ)-sI(&aRU2pD$X$_lt7S%1Oug>lT};r(>1#$C7nuZiy;2C}8Bo;Kr%Rw;)t zpfZi8E7o8+{*94hEkrMX z`B$?;E!ecvM@PobF2?Cp9l{|Xe{Ro-v+u@#FINZm0bh^-hN_#{0%j;^rW{F|`MY(; zp&(#g>TqcUgg7` zCym~O!GJ=tttaoz#WTMcKiAu{|7@mCK0dt9{d_q6?bQoc4jI@Ot_K3R!53zL4Z^{u zU3F;`v@9eYvj!Cwn>Yg;Jo3%^#kJ9KbeULeu)_+5)BEcaB?H7IhQ<+d0y8Ad6OeLD zZ>0G9W?fyD8y(QgFrQ_jm@SH0T^zG{rC?zakqeNUu6Y6FBa`&tPd}b#%r621d{zke z1+H4$&efQqE#JVHS{qAfFqFriEp}#d2|B^W$mzU8Ow@v3GdD67zA zR;ZY+Mpz8MW+H|MgItLwJYEDK5W6M}9fSiweY)AGr8IMoQb6x#3ly&=1fp)|I@q1w z7(kymdN;4h301Z*y51&%urNQ71fao_!(7P8_lLZ-Vk3S;=O+Xv`MR;LTc>w_!Uhwq zestu*^*sF(Ch{QhnNP=;?TZvvNYr|q@JzacsB=v+8BOncF|wfA<`yR8bQ`6xa=*@f zbyM!oV9Cim^~duU?zhRbd4xFvf|7@CIfw`wHDrmHgISd5t$tM&UqO?fjv9!+W=nXr zw99|bPMD@oub-vN2WpMyc#fp_)G$%V8zRx?HcRKO3QAH^l=e<9DaU7}qf(UP<>m)5 zwi8I_EQ{tha$feuSbbibhkOIBpuu5UsTk}|>gBN(^DO$;^pw(wO*AgQ*oGg2gJ4~# z#O&%ZPO{WvBx_Elp?G*Rwx{wP4ch$!ABWxfBiyG-Bp=MV`({TtQ)d+VlXY)CvM*>a z`!iT+Cr^+A$m{jYq3|@gl5zK(?I5jA1%l@x`mX?54z2AX#KjeC!9YdXcPG7@0 zc^^+Ey(=T?#b}Q6%7{f*Qk$2bKlF1>m+|V}OSD{z!Hxnug{J)p1%K&vZ?JJ2{Js`g zc7}pxsgbCN7Q~EtY#5T-L4qz~Yd37;&{1*W9${2vb(?N7N+}unOYF8S{~9Xg5|Q98 zVL{=?OO;_9My>BsYKQ&J6BQRxlom9C_~R|{r68#yInk@p2ET~EB9}q)agF)Z4OO@| z%(Ox_?SQx3ldgZvf+cXKyuZ}YG*dV$jJTg=eE@TyUZVy~@-x)*3=;$Yw0;?z9w65! zGL>?feyqnik&+q=N-?$OMor!!h12p6mbm#AEV<=O*y0-9?| z@Y19d)b)z2p})zYuoPm^_b%3aXxZFIg}l%m&cPHVd4}GHXm-oTvRM1Yf!}h?x1|IUG9XNKd5|H-$O` z8U>*zZlyT$IR^bcTq@>0R4cjItR>1gqUJvPlv?3f^syQk9YXl}bMTX~&E}=p>? z*6hHEbh1a&VoC$_KG$|K(T2EuNSGFQn8`-lfnl6Th`fOcgLr@7XM7g z7}GbsJ%(T=^Nxra9RDYIMwuLoC`v}9;94Yn7JjdfP^8@OMSuj+Rx#5$%!ch;YJGDf zwbFwUXj0=QMP{B4hjxqXywBFbE919f=UIh}FYRHW5~7|{yqyg4xEUAbQmhxEi0kef zoY%P@zd7y|$^?{$m0)Vyu&_CIi2l$tvQ9S zYL#3L-~SrIK{*$;YyE73My)BpHyCZ%@#a?wJaTNx5`8D;V##ilIoHt-^8bQ@SsMR1 zM4kSM787Uj3g?*fJMz1Ayj8p0)st&O4w3ihE!9Z2x$Gf6pN7oyTr-IGB;0tELn@=$t0WRH~&exYyAN8*GByNNy zURGu3FB#wSyI;$hoAA`UF{E9x{)GvAV5kw;w(F>|4{Lfl`*sS~2OgaK;tZNTYL$A} zq|HGp!{FNT+l9r&!P4*LFaI%f!eQd;|3_?|9=Ji8BJrJAqHdA+A1}Zr`A|RBCFt8y z)Uut?a{Hxuy9oS+8lVi!ItMgLCf%}}&!9Qgcdx9G8cX~KZ8Hl)pwv>UvB3u~%L57= z+x_rj`E&)Bo#F6Mqsb=6;E;hTnQ#R9wUR=b2ZXG z^?)7l`L=Gb!O14=wIM{zP)`i|M=VB;9F5*6e-()}%SF}v7& zMsc$^rYD9{slX9xlOP}uJ4E`%PX6;N=&yDr3mou4H#y~WM@L}DByUI9gAL8Jp{t~FF;i`r^gfM@Ba?X@@Le5!DgPr10q(+$1#j9o|z+=Q@Y~uIA;0a2o9MDd1Nf! zwHqGkyy6i>0Lr@(^L08Q4<;y!8_<*;;?^LsZ{)`Ej;v7OZJHGSzB~bkddZWv@9<%c z9Yc=-pEMf9?s(IxVtf~3*`e=b+PV8_-YG45yX+ziu7r!Tl|=;8rCl5~J3=*MFHZ@1 zB6A|~^CFYl{9STh3z|7# zdBgNoaYJm7c19?k2#w=?Zv9_T0E~Sa6t={Gu4yH&#f$htWoBPzMZ14JLWp36zn5S} zH!L|DaQmU}9j=BG7tMUh@>!m^XxC-F(P@p?zGgxETYx)@jpuX0qdxm3xfZzw?jh^! zLjhx+HQ+~vESzz+Snfj%oB=3f&df8N;T$(3M9Q)G?1q4r!?Jz6oW94!&q1 z!>qa%a0)z>{2&bW&LwZ*O+r0|5~=(Ou3ken^U>h$x5EB#lCJwN!M81o z5GGypKS87Fi1p#{d;(s=!i^(x96mHOdFl^%!?QkbqkVtpIdcCByvX0XkI<(cG0L!l z%FI_ThQ%%7nD#!@@nzaM>XS{#9Aa0PVG-)!-dL7xdOb;*9Ss>1P$RKlg?FuOKBa?l zsAl~y-6P&(V*O>24hHG>(jdF4FtIW-f%(27V>o4g5q%mX8 z;!FKg{n6w8Oj`0Z)eN3FDZsq%$T=%i71Cv^K=b=*vN;m7y?lf)Cp;^(>uv-rFL=dj zblDb20=gHC+mk1&C=eBfbXyC%=PS1m=u5Qq{kf}Y`N{FOjUxk|kHrCI>wYyvY-0&^ zjnoj9ZN-44XYIV+sedjLqs}UZ?+D<@5qMs*l8wR>;&v4bS6%c-F!} zD|zCffVP5R)m`D6Fo2$L*tlND_tuCl6|eE0Ii#q_8J$8cbqw> z-KZ+|Qw>1+AX^;ZH}d1k8XPro-eSyGC%cR|k)+c+rZXc!1e(S)3QxjH+7k)dVMvGt z_h+Tf&EUWu6N9hBRu9mMU1wzcg{hao8%jCJUhAp~z?W~Mn%tc&*79hK`|f#Pa`dTW zS60g^(LB({D~s3*t${{#Q+lIcg^M1K*fMlzbnDrqxT31I&7Fl_?7d4p7d6%#&h2|* z2&rvQ{h$3FPVB#})$sl6=HTvxtpvWHzzuWe$m@Ra9~b51dR-sD7r;^7Hklz&9AmCq zZqzgTrq<lcbOT@KRrv>LbrNXtSXw7-#zv*Y!i=kK%mf%chLSP!H) zCzJsf;r;)$^4USC&plz10zx%G=KmDHx|NeE9sACIyc#x;Tdo7p3cSVj6UVCu1`2v)9H|cTuLqq)ov%rEXr61X`X1PB^1{?u|LFNM2DHt|hy72x$UnIex8hEQ ztkh2L>iVdr@cwl$bw_}t;JiD2TK7jlU-gyy@E-cs`Y(eJ*TjP>0ei3N-p_>xU-ZHe zvO-;QZ8?Jk3%XzBcVrfeytv!imHvwJi9JjUe0hsxe$4gD6iDs0o_jgkaDfaz{+`#$ z%6ju}cQ-f${;YZ(n#exR!tIIl%b;mer*u{9{}TgwR(}B9yFuh!0A51PxBGCFqwSw; z`CZ{(&6?*IWOw@ptVOCR0ep=5XT$sYZp10>2lOBSq4m`*TBJFt7sJZ%%)Q=X`}|d^ zf~Pr;aook{&F*35sMx^~1xAT$=!cUdxSnkQw~=BS#tq?7c908U_=2{#>J!!GdrJ6@ zrU{HR1iX;WgL^7ni+V6NZ@$9^mU?CR{Z`49Tzu=VCpyzj^lrsEdq+^-5_T;uJA}N< zJ6(Ts|vzUlc?X zv~=v?{T3}FP_`w;h>mm(b~sAzyS}Z%M5H!y5jCZ~IzXoLU00&bLu9eC3yYb^FgQE_ z1&bIv(9nu5oiG9oe241R;iwOApiBrfbt@b6W}L$@tCGqtNTwdl5f;l=iC5~+$KV`T z_Ylh=7%!11jqhhB0nPvHkg1JjT8C`7_bbBXBZ zNbQj}8-+O$yGIS+-vT!UHW#x{x(%Wx|M{1#V!!9pQyew7a>e1+r@Fp&5g&?Sa{AeK z!MSrDON8uyMg7wMklPVocep3{awqnDyItC`UgMY(J&6i$TuS#xZ&gb;m|N>6TpQ+ToroVGWp> z83KupTV82FvEDDn=`$Kd3J?@DHLk4-CGLn)UQ+X-G~jo+p+%WdHmDAXukZ~@aV5<4 z>!PW!fY&Yzf0$}E-~6*HYb@e-{UPX2{Vv}@JwP2ZXB_@lt|^S^MBakb4Q9Bbovx7s zY_QeQKV_7YB9xb_kgHM1Ad5G$yIm(-st0qMCPKAl>jTCrOFbl@8GJ^t`pp&j{i zgpMqftipp3p70XvM8^3wu%6tM(XT5@P6fCIP6T3LV{igENnrYUP+ljqIG5WdZw?;S zs7^t3GCe7d&A>H@9TB6J7mqoG;eAE1bd>cE8EakJRA;vj)qNG5jE0j}XOx}Y8zY>) zPNgm17S4F9Fm*d0WxDSYeN#-5UGY{dzwXx$xJ)-(c%DLxt9^z)_Bn{}F-@^DZ|>u{lM}@S5wYlXDCx0s)u2nwh-e@LODa!!gSVaHQ)6r$QIT>ogmK$Z-<% zdRkG2EMR(hmMBDog~&qyeg=69elrVrq#Q%9-hDSxTZ}IFV!Rw%h2u91)jh?Ig19-v z*u1FYV^D_yHQ0VHHF!f82gvxhmZT%M=Kh#%@ywZd?9z1Mj%)TTc_>|Oj8=EZZ^XT1 z4SS4`g0+it_PXK(Up(9>o%$vbdZ2=2lYTW}Ex-7?d{HK=Wuwuq`kgby!AW_|wvr>| zy?%iz`J+Pt)$7|fXJVmgOc}}VdKfa23VO|oi>p%LVZBIs>g*atL!wAo-T9)lG+1(h zoCRa;cnqk5O6PZ?As+HJA0f3Y67m)yF=g?85SUzQ`3fBhV7wHvESEY1{S?6VZQyk66d(=;JLCRUcx_*cYF`& z9Q%&5x1Ts8^;*<21u?zYJHg_bF|HT0P?CD7UzIv#w_HRItN@U!PcOC?z9KVGb2W_A zOF_z6gy)$6r;1WjlgHCIQ>&Hf$t7toQ2Ex$+8^Jf-bZh=uUT=g_WE2OPV;uQhJ2#M zr2q+f?fus%|824;7_VGdcrXq@()#>OZ()RqKir?+u;%ok8mm@RGT(WU?i11tLJ~Q3 zLhB6_>7#GU%14Rz2lIPWus?DuOxXN&A7;~DOE|Gqiy5*s&Yw{0wy+PAva z!H=K%wt!lJmiprQDU9`Et?vUl-rRV6*XU|A!K)?z1qu~`ii8khoRU1L=bMB)$6nq> zzKwuI%3pShWU;+VlTtB4%T{vHIZwu<9JH2Un|M0GviP2}$KTZERsBO(_*oZ#_#_rG zhkp9-jA)89CQl#$x@1v1RTVHN4>SGu8FCqy!HLGcuXO=u182JenU6%96W}(H{7>$&=7|7LR@aeS zzNc5H9{AtW3FDo>5Jh>!Zk1?|k4xjfs^G_1&7sI+pR0_c^?2yJIW0?5eLHNg;`HW1 z4sUwyM@d?@7gK2ge?AAI#4pEPwG0VAsgwmIiJR3X#bzeZpQ7Rix{E-Ztqq03B9{>P z= zqlZZaRo7c9Mp(bois!-|6I#U}nxEcv!5_+xu+NCqd1gE$M2I`-Cq?Imy_e~XHHxe1 zwEmGoQt9-BNfF6n`wFgXAT9}8S7^uElx6i+qDZ6)*>pyzm=MWWy4{=d9HeYE+fXH6 z5N?7Lf;yvg_$Lh)x*~r3LzF}WGIY_Q3s&=aQI2>EbXH0H8F@2voZoL}go;x;AouEt zWLdTJhQox^uIWZ`iqouzQ7DO~i!X{6gsMOXG=p@Bvnvk4m%ff5S3`%@H>)U%r33wR z_jVQe0}RPj4-__-A4B`%Y2OID36+;Zi!4}(#k})FET`Xpq=!!H1M)p4Q8og22=inY ziu^1USQ^;G>hRuF(JbxGvGD1XsZ)Et2@TV%R}V~Jiq9;MDp~gi9#*M-%KodJ1Gl@bLqx1 zw)MYAaCk!BjPT_!jlYX8z))D4yq3aI4|a(N1H00hBp3M89L%J%Fm!*%2T{wSb1?8q z2&eBRA!Jkq)qP0LMm0M|)cF`$X9SU=s*MJ3_Qq<*E-us~ZN0`w^zi@v;2?8tq)Vlw zuD%6I*21?{+-rqkg`Zp^{0e3c2K~WYC}MG(}}0UvJA_ z6xaF(N4!!IqisPi;!+C=uF|{_=a1wg-fyJSkhgKm=_a>Ax6ulgH+@gT_d4=okYy-9 z)N%OfD96cCZ-mgb?Rfm<7~ayyM|@LH6s8aZ)YG!mhN8$cM{h>fA>|sT*9qkX#Z4hd zZ-r8AeOjf6S_68h+d~zZ{T^J?{zZCx%K_6Z>cM0_9%hR&!_oGv@>A=M_R=k+n z3nsFRRn)WXqnD$B&%gsYU-VH&7;Qpuzqw9yhT_PE2oJ0@NK>{lbq5T}6&fUOX1*z- z!I%72cET8oX;MZk*=HLQbwykVKt?YPvWPV3@{-oos0dV z%iusrU(iCjF`UtH@-zQd89%z2qLe z$-o`-sJESm#CXH%ER(oVs&YX;q}GL!HjM|ee5D8W&NUt>g8mOxZy6O=um+1F!3K8; z7M#I@yF0;MLvVNZ;O_43?gR@qNCLq_&_RQ{+Z}Swx$nNU_%mzmS)1wI{Z)Nc)xA}j z8h+gBEac3CaxWaN{B2+Tr!XZZKUQ%H`wAgYM69LXjihD?%YPH~FC0iT;WJtV&FlL* zm^s|h@qPk_-)cC6pUKfb&HATwqCR%PRepCnd{w)fQB=gH0XsyEMBp!TkWQ;ldgm^Di zl_VTE1dnS7S|6gC0=LFm&+Vq2`8mcOhEJSPcbgCsxm+HbVCGoAUFareW#~))YFE8W+M7NOJm2!N)tmk+WZ9A@w-DZMkNPJ}aZo&uP7hJ{q3HXwqmoI| z?#9UfAfF|g}ZkcVUJ6N(E9>e#3 z>wx*(8*SKdtV7?jez&}pYhqCm?c6883HtFGR0heC)_#RdEZf6}I3F7o!C zEXX{DrB-+W@T$SAyfb*011o^=RDC+@2BPqy2A|zzD`=u)gJBO`=m&KA<$ROfcKM-!)O1F=8~fa%jWB;=}MVkF-mO6Qdd^)L8hTGkQY z2K+A(LZ6R?dDi^UPzMR#D?o_Ze;J}^sY{~(dJF7vdi{cUxGJM2=$_8Vaa@aC=Q$D} zSar3cGL<|_T{y?X6GL@`Q;PYw!hK~SX&x0&J-jE(hc^~ICMD1r8M(i#`*8KMDu=A@ zP_e3`mbdy@@$cA9hr{p}FM6;es>xgn_b3_Sl(D?#e#{@UR6W`bP@-YbnB!j#&-bDHv`TZo`FgP}yf=b&jD+fTVa>*xkuE&Aq|QxgrOImeCqx z#*`km@^OyBTwAGwor7%Hb^PG}s+e7?A3JK5sg06hBbgFM3g4|8{G7ID#lS09`*GuE z?nz%YWPv6^C&>#Cp<-dJQ#T94kpQu)SVO5-NXbSjM}B0d8Onw$A&wwJ%uU#Uc9P_g zBElCMMA~MMM8A^$L^XkI_^3E7gD5G=O7PPNCfohHWTBX-x!}n5s=R7aH3khE3cG?# zCggaH*GtvpJ6Eh^`4kkERGFb#IxqT9XNIK>_Fq-x^DgjZ?QX>AaOpo`@hEfPoLl}j zRzX^oEu0&S9^wR_=HbsGdJ-XmpMN`?zWXJjO)W;?B8rie1W8G$cRG zXTAs}c?WZ@GZv=$yI>HybTh&414f$&xi3>v-JY2Q>kneCEW2W2n0k#J$aw(Qw?Y>j zI4S;Gta`);QoaUJ*pBgnuQ98n8y=_QN!rADo~Y00039hMG*h6*dl5yhrY zE7@n%OCW0N6BCxcjAOFiEHgl`ROuFCM=21GF8_e+QR<9#Q?z*RXK-1%61Y}Ybfe_jOSsck9;ECn?VAz2 zs(VzR)4%#w$!c&{lwiR9)L`TfxT*OtCOC2~zhF=GBA6OWjje#gY@hEKsJ zt^x%`eslx8Z53$;Foc21F@^&1i^I6DM}t&rqBRH7pl||ud-!&Cc2B;b-aL zlg(59rC~Shq)Mu_xaozmlbzX%W7M#!%Bx^8VozRkb%2XR<#^}W?_;M79`j8$wNRqH zigQ16DOE*U;!SZ4y5`)%cc9A#KjqL}WcLzko-mo;dC`FP619mUUA6aHZZ8QyADd3n zAJt$>Oe~VSo{Rrw0mkKm%`~K~6EZ`j ztBZ~QDIQw)u}sbvO)z0ymUs0ocLs-BrAe%FIrQho4n{Oh2q zjE&Pbl%mxsJMNgLC0Q~bFGBz%^0Zrk!k2&hvg_tMdOfxM_~^#GN&a8MDn zTs^~A?CosV|PWYB1aoQu$7athtx8cUk$ z?yDUd4?|COGKzX`HZh#x-*UB|t)koglLOX4`LCPY7F&EWs*5fy$v-e!;;3?@S4Q7< ztbu3dX-isrlR73CQA{M5_h++!+7*sL?U}Fr9mVzDSJUj1S>7Ss$$f@E29J%eQZCq}B z{K3iU8P($g8wPhd7((fOx}mX~F3-wv=yf&8TFG&XtSE#3`OC<;8xMyg{fqLDOawVT zBf}c&Bzn=>u9ocTcI8+`-t5EP8d(8NF4{#9d=QCHw+~BaB`(DqpApmf{|Z0GG4G8Bmf8ay40<%H-Ai~t^n1lEh%K!v zQ>QITTG3N}oz|rKY)0;2#=aX zR+S?1y6HOvws9G)A_uzC!7Z$6LFSI9rl=BDpA1k3+lQ|NBmf7mo`;P0VfyoH(#+rx zY{k*OIADVGpd3S{^q@RLDhL#9m>$PJBXEl|`=TxpaF7wLS4FZo@ba93b@WIZQa>0( zy)~2^#j)E1qhn^$zf97E%!bwL=#|EU2XPVkln>~&gG6k6Z z>Q)y{Lexz06|(KwseOR*7d31x-zo~*!>4T=G&O!ioFovEQ-C4D2S$fA9g5I(@kjN@ zY~pra`}%(Qy8GmQh!NmwraCY-Gxht}4 zxT(2+jOMPYFs1V>vmT4;3KMa?DBlgyjE<}C1C9}KaMgCvy*zo#A2jeO1`UE7>r_XA zJ8O=AHN5Ixp<{3F<Z30<41!zPen2=2%O^Kx z68Q@_4$y~6?P%?S@mY}q5^#w4981hr0f3$qbZde%2t7Cgy?Ym0Oh}SNX`!`pB1rU1 zRaChGOD-dqC>ybjCBTVvaw$VhJA=^hIAOvTICG&hVxh;XWeuW??nWWCL_;5E{PLl% zClJ3!r+0pmE8QB-PshzZbxL#I0MQzG39h02CL22M3JARHKks^POgadh^k&m*2^lmeFPqK|d%Y3gyZen_SmzE2_4w0~;41Tr?$lz#8s5l!tX5SJRKETy-W zsKhB06SP*x2(d<``Xd^SoUfa>VHg9P)Iy6ltz_oe)!-*j@tnfJ5T;Ae4BGG=hKLAE z)Z5Xg9R*{$81|IL)lMj<0e9osycZ?UShXq1a?+=zB`RbAeJof9Gfq-jy{=x<7SoS+ zd!@6nS0v*qe6N1ypCJn3Z$GZ3j~Wt|c~KwT?iy3;!;9mfSBo-1%m0m^|(5TCa*BVTgxp>-vHoGYtoz6`-n4Zglf-Z_QX1^ zjmk6Y^cxK=P|+^@Qt(y98Rhx%Dt{zt@R{5Y*J1Bi$g?uZ8Bq644-nOrIJ5gd433idN)Y$Rs zXXxja?5JfQEzNOd)G4i8YW;!VfzyGJ0sh>B&ZLp*dzyCtu_iFf_=q9><`BG398Epi zu3r&^vMH-#fAJsXTo%Mb+G2ifsgzl+Oe;poyH;@q7(kb}>)8E!sLwb>OHyt;WYw!> zp*Fk^<0i8DIU#wsg#xdS*DQN3t`sBf+?P5Jx@2MmuWkojC!Gd zLDJ6^8g~dOydVdj(PbQ8BMNR+C9gvywB9&CUnE3F!Y?0(_H0)ha!TtjKgP#2x6~<2 zxHWYB2CG1az7K-UUsz^S%@`l3(kAQm^M`vrwF_@SfZIKz=FfjIJx1d0fr1dqd$4aJ z-R#=b$V$RWwUASA^dzmuUR}F3?xgN=`xYtOR>67T-Kc$m&%Sr9JM0f}ORSwQm_n)h zTX4toH9VSAR~^DDQnAkkJ+fS|3_+>2f_$^p+xnl89Aoo0`I1B4C+8~5JWAXxwzX&} z$?#9AmCA11eCMc?`Nd3sa;Qx%ti)qF7!ehQ!jBG9OSfq5eXZkG!*%ZL)y0B^{u|@P z&s9fLNz*KHU_J6I@sq`w98I-O$jKbobXh66u;<4N>rHeWG8JfFnlm?)d@!|PdFyg#wZd*nN|%wW4a zxC~~uUgM~Wq~Q+@&cZ<@V$NVB>H85rJR5h_WtxNuPbET?0i;Y`TaFE7!%micA;|Uc zkL6g)`%1K1$iQCSJ;XrZfq2Gw^BAT4Cvu*W#!cf)f&e9aFMTU~wv+t(v1NhW26ZTY z;CIIsQ4RRbOYz?-R4uNay%*)11xqAjYLZK#8_^~{RG)r&ZO>S>J(j|-#A|JeFQk?p4Y+rUsr;0^wU8G1U3yvanqm`yhi>8_;{>Y1) zXgd{r28)AHs0@g~ zbM=4EU?slzvrCX6E zziw4%Q}7W0;xZqkjFz}+w1Ylw6KJ}c`1n3QBrxC-hR>cj#`TQrPsqkkfZ+*i&L-sZ zw-j!Q1Zxkkc&4_zWY6y>FHKEm&SPjZYkJ}C7&gd~;>-q$fx&*Rz;2Zgk2dbHyyy~w z$4?V{g0g~|g~Z1pmk#ym^Rgfg1ItP4)iUT_K(|IJKaeEb8b{Y20ZS@Icrx>e8 zI2HN5zYz}Lj{Ftyqga4niPF*e9L*@q}O6&HDjw}8a5uSCfP z2qxAb3W^6i85qLUT$RLcd{~~0Es4xWSpIVr@L$*3H$kMkn>TshFvOl=Lpe`-xs}OU zx_|@v);rrvFnNBSPEce1YVD)ZI5Gvw7Wu3pOCOYw_qp!#Q49{5`i^x_`9~c;v5*^m zYKG(!9s?y z^Lw*U3TMx!#1EuEt1g`{d2xogJ{VaHkof=?nFRQHu~(E+#~N}L(l2k8wxfTvRECZl zl60D)T1iyRL+U4t0MNKAk>j*YY|zIEKN3Y@E|EMJD_=G4&;MYHx#KbPP8J}fYB)e8 zROQI?Xz~}!@OI-h=lbb5p5b9uMTyMB2%D{FC=oVyN?Qr}Y(dz3QP5A}@DYL7NCWKm zvB|bk;46i1I%eCxs=5ra`e}6F)NLi!8Fec{W(tgMf^elYkrr`uuzn?#{Acn$H>BQ? z5Dl2T2R7bx69{SZlORqd8siQX^&L_7-y;6zGVb2a(o~yBmuM9|#jM{@ck}R`p1)P1 zTO;IX=dx$Co%m?9RO+RB#^f7H?9*y|jj`UcFX8p6dqGQU<+3Z^sa6LXSY1Q21MpH= ztY}DjsvRRZ>zC+R;om_$L8fl$us?6YhbN~u<3ue9;aL2$)vszHan*|l^t0z(tu}?W zqo&ugN*%;^(}uJeWv)h4!K_Djwu>ZN{g8RY_l2glIMaMoWlQVC=TXs_X9>Z|jW{$b zvCd(9({VG_o=|f0!Wr+N2V+Ewy{Orp0tXWs2WUXYgD>hU)tUD-Q+*>W8hi^ERO^F1 z9fttCQ~cd_%XaJJFGN}zDtKeYM}PrNomSlQb&rf$iM!tTuJTj)HwtUVTSpc=;y7}C{yH({$wJ$=$mnkGv?N~^+=f*MWkQ`@GHIp+h zKfk59QJ&|lYY{Av?y4{w1YusT<-UZT_yZnlq^EX9RDH61b6tuG@v}%=s~Tp~PLVNHcms;TdxIN}9aW zV$|jKqAbWl!7%EgBBVKRQRA;xsagMC-k83txsjz_{XRYduVgA;P*)K2BwBQqFx(Y` zzS`F1sH<gd0$}UzNWvE3^EQPOnO02PA<^Q#8jEU6;e3XAy zx#}934YI~q1*(ePGm5YX>)&Gztl|!|qe}(-Z9GWs5WXZn?g%rEVHz}@FZwI7|BDr` zLO8WImTkJ>*yc;3uzzLL7y~M#PMJ8nK)fnAZKN9gCOL~Ab!N*7&dgQMl#DNiZ=@;I3x)kk#yUYQ4H)sqaR0URe~B4VP)6_k@{jzFeh-1b zYQl|21N_kpw-fG|^UX=`B~j5|{=-L0IrL)1bbGL5=UkW8WlCh~W^R1LJ&*vA{J@9z zvpH>C=Rvdsea4$R6@jq7?3Qi4Hjg7pd%VTuIs!MI+;2C?VSnoQLFolZeGMUb{u6Yw zYnV$L7hmD*VjVbT(bNSKug8x+aVZP3I-;fUKKyIygRS|a{Y`z7J2y*_$LLZE)}LOZ z%1(}}PDv9oC=hy$+u-l8G^)pBx4FVntyxKT!i86{SLzFTC80*on_u(4ury)%bd~{( zBy49)OAkbc)?cW1P}=Db4Mt1$NnMF7BDr>+{vJ2YN`nl(7P(E*@IKAqWrX{~0UCzL zGTBS21lY-EUj3H!!Zb(MQN{{dAD1vy&!XT)NzY7D>fN|TSGTaVV|tJZ z%V8ly%@TwRopyVWDSkGEwpRRgSuM<_s!77uj$q{OLs8PaQRT%#i8!GH&KirO5|-pQ z8tk7v-a?K{v*DNLiibY}ep#K&w?}Ou(~&`u;(&8W zt}i5JoKj83fVDXW6A0YjIq4i=7dA2$z48>=DPU)_7HUY3zn5lj48qVB2oxsBl6`Nd zEry~>o*$IB3w+Qgk_&k)84rNUtb^y$6=pOE&~B1bQ;DN;G^P`NEk^W1Ty$6!GtyRf z9H04rluW2*mAq@%F$ewu*j&_$@{%o%7{p|?)7)Ku!9?Oq<=rUOso-|XZ3(Y`l4Vc* z6Zz4t>HnO>cSA@YF{29J4`MzVpk?5Dxby;~edMHP8s9E}L(_Z||4_Rzpe~{$g5&!+ zcVN{Y_cqpTJ-_k~?KEr5G`qegY95vVUEYz#+OP$NvHOe@ff^3k6mL}$+8|v)+;NfP zFnUENTpKM({J%wNB7Q5`g!~u%Rc@zkf+DC0+uNDR}E>e zVg}Lohg#jl)j{)tcC6B^Q~c%NJ}{UN`HS;ZTbhtxGjLD7p^m>a%K^eipqJZY#}pz9 zp0gl7S;d(nblEF>Z#r{-9)#(g1G;rEV(gRS`Z7p|$I@OmyXBh?uaQOd+x*)A4BD!= zxUYv<@)PsECoK^J-ndIYWb53|+r#&go&Db*IkW?gAzgaKnP2*DZycW&FW52GN@h`P z3CgykMk(HH+_@kW=an{j{!!U}-*!XvFwmMx^7n2Z$87m3UArglQwwi({*iTpAC^Eo zKFM_xbF-AvEKaq+os+y~{fT7){|#3zz-PgNzPChMi)}RA-Y$hL`D!>>RFMZ9LZ43T zES)O=%K^nWVVzsP5_p!b+WSR-Z@_Ud<0K?0@J9aOs!nbPxS>`Foz{AFu=p(6`vq>8 z29E^Q*~O*)g%rHbo%8H*2Vcwy!B52QPuq>6BWF0_)dYGMZLJZ@$bbVs?-zGz6a$WUz5G8kiQuvCc zazm}3`w2NhsxZy|@0jxsw(|LuV%6o{_`eIst5O`*GSt{BwYv$#v?O!+^w$EH{|36srLUd8tP2NKMjBtkYE7a}ssDs<8Wqj0zmOyYZBpD~#>$Eg3x6PK zLAhOz;r%B0sV0w6$|a^y(>{vfxM{0&>ij30{+x&y zTeXrP=Oj-j%~@E_R=Ho5Y!PXRCMuLsoMaRqp2aSvSXrzYr0sy>_vapAn1FtctMNR(7sk2+1~MQLsEYhW~6U$hyzwY1@VvA~{CLv`_}lvX(Y(2Sq>;?9RI?=a2| z+L#0qTp6)bA^uV=;yOZJCLs<9=SW7Hke$X3&4!9w4vEk#CmL4zmDQ(G=TwAzJhN&< zE&C-g3+*RAvFVw5>5oG@Kwli0d<0`^7lPi!U>cgj<6%oZjjX)6U`R4vd48msm)3 zn=N?qB-&JK<~%kG;)Su~OzQMgf9wwr%!E1gv#hMz_G$l-ek=>JR1o^8BZ#uI!s>C< zL&r%WKtFC*azClgOy~8#wsacOmO_M46)xZkmDnp={6)!XF*gkWzkdD?5VU?Gs~CGG z0?A<0e`m!mcFUbScln_KX2jg>;Tc`8`UvZZWJY;5MPbWRmQlDX{EnC91gg6`l(FA|q9@tivK!bbwIh_hw~rLTj~J5OYiZ@F0TpaE=BA6-bX+0eBiM`(9=BYNUHKfcTK6*DI~gi zd8b2DoxjwT8jwu~6MRP0$OOrSldohFZB*_WJ}WPZd9|$E=?>$C!SJ{C)36MeGT@D( zqnXD{3EmRZ<~WK?Kk}RpCC)fOUNa<+ET@3fo>&iK)Z<;daN_tB9Xx?!UUl}=fnZ9I zoWL4%{IEcJdhn~fHdvtV>D}}AUlzdQ%ddIzL%oM9;?UOlv;Oc$ z*K_WJop@OgXC9=hWNR?Zspo>e`$a2@UE&6fh(q|4r7<*`YtK;cR-R~g3y9tS}Y$%lR zJP_Q-PKQ8F@~6Pgz6i(0dSB2*`*^cyYFQP@I`nSI#!5X)QV<06a{sNO9-r)H9g?r)-4d%BI-$WHV$l!uu2bP zY(jc6A28#=P&qCS+3&E6pDD#XJ%;{?uD-=)5E=Leob>7J7DgI+3d$&jgMsg0d#7ZJ zorX-_=Q@NVr(X2s}G#tjxWhbaLj@7)7# z-8pdSv!r2cq?mjkX{C6#-i8722ZAEJZ&1007b0k{TaI)|4f>{1!913<-fB1UqgIGl z9%u{^?XDE~9ULp0U`(VIu|O&~AkQwG;+}{8LlmhbS#HWn}wfpLfYyWfM!;{8(I%TeRYFWR(j zSM-?#t$Y)nuyk+`*3k&y^ElBr|CzTB9}7rU#6(@=5qk)_rZrK*v-L&)c*fh@6}ndhMk4Ro2%FH&#|!F%D*N z5HpIpDJh}*`T0$)`Ck4E5ZYzuMlo4IG)of3-ARcH{kTgqPeYX1>J5y`uW(+FfqO0E zXX^3Bj>FSfn_VJ*&2$w|i%e_v4g+|6n2T_fmF}sL=PRp})64F{SK2#OzY}m|bYwpp zj{MDCTdK5PI4&LZiX?#GyIQ@;g&nVm{-z-yq!+bN z_(Q{tloj2RU6k}@7HEr;kBS=?UZ#in`HkAWu{%Z6CU1f>tcDhdLoK-P858(6Ijc8t zLtVOvO#Nog6{K|EaOXQRfZLUGw2$gvgQfC$4EPB`LHIYSb5WfkR}EP?IGhSyj8Y0a zj?djsIdW z4{2)U;%I`TaC_NVp)w8qhzq4teY)_*S+F5HgKnair;^JNlScYHt@=m}*@k!vQTl$m z_(A~3i}0nbR=}1*k5X2Q*I@3Xi{?msoxokY%cI;x%SDsyUDquAiJcL-9u}(SSCtui zlC~FXo28|k`Rm^g>?4T{us3p_&E)fY2XC!#!Og)|FO8jAeN5xreE4I@5V1soY~V2P zFnz6l-Gy}hER>AvcAsfJ^=V6jUbFd2WB1%b*)>bv7_G+rW*NJs^~vHy*TMGE6VLbF zR-+(kUhD9ooV>&yC=4<$k)5CDBbhaR%*0f z%Ih5@owiz!Jm`Zw3*Q$tRRXU~C3O5w@}vxZ976NPYo@pUsW{3Fu4AZx7z0p`=k{Myz^ry%Xcl`CE%JuJmrT&c}`$`qA z-)eV3eng6^zFKOUp+Sr69mSaz%=$R}Vx2bK6g7z!W>r#WzLc*}>A3y|Qs}OoUMGXE zyMu!9K=-613==6Mj3MmFl^@@UHb*BQ*YFM2WM;QFu%@>3H#jwVky~6j8!$1yv9jG{ zHWb_ogwX77`Sr8)BUhOYpD)$w{mqWLk9@0U^q_Az2RSB}?@Q%O@#}(=7t_8rC|mxarEFkN9dj4>13Tkz zu#j%~9jUa=f9z!wh~&Vq@AU}g@z?zdlnzLA zWgMBKOrEc&?{2OZ-GyM7iULjbEflTY>bTLexaq$oE!X)U1LE2Wrx4SV^6aCduv|P^ z(s7qa8#QqmTPPhCaBwM5+zX{pT6JadUw7KBykfbEDVXZSZ;=xeyxSgx^xE~KTM zg9wF$d3^_g9#H%^3;cy3dckAVi|~*^ju?SA18cqfyH?h_187k%;zB)=RfD~;)8shF zVcR;zAo(nBy?_ykf;VpM_kz|Tm--6*|Eq*CRv}d!w@#7$sQsE7QIqgvG$fii3i&V8 z<8m9d{pI|JomPx|A?@w$`88F-x%?i?&E`M(&O~TGpbI~p_177EtJCZC_0od~NF%O$ zO|1{^=|!kJu!!->gw0x;_cB-?)9fV z1T$!ewEG^S+{B+I zo&Xu0j;QFcQ@FOGDPyN0 z_Lec-Uf6vbK2&QzyGT5+y1eM>De9Wf<`&9ACc#4op<6t}fbKo+gXCY~U6njr8*Jfy zZPemUBPA-3KuRaY94rV{{9S0=1147)F?u^o0@Iij-wUHbv2^K7H?|q`xIl;pOlm(F z23LVCj&bnu)PK1bo8P}JsQmua1LKfLp6Sdv0i5pQzEd9Pve$70A^>7Eb!<&X{f z_pIx6#srU2U9N%hmtA{7r%p0h(6RL6_8|u)kn+R`3!@>6V2om68Nt8+ywkB`T7+5r z4{#Y1U_*A8m?8Xvy$Z=KRMaR%D@6kHs}76EYjV@ojBMpi4qy1ru)R;tuH*B<>%i=2 zgdAe0cHm@CrgbT{W2fiU@kl|az_TqoHqPgT`xm}zOUy`R65;>ZfC>>VYcp8tX^ESR zW3v7WUT+c8Ah;@yO6O#RcJro(61r-qE7u&5QkiZ!rit@(uZSTOL`6?>*}xy#3$ygO zPSNmSOtQd2^BBNv6SsRN#QxggqQ?JgZKnM6%uhGyeGi~_WueyVVM0kSpr-t>{wyBoOFawv(x=4kF*i|G zV!{roQw#$)dy?tb`};+{@SX+K)z3w~4>zF~#U)$Wb#KCgQIF=-I`lfsiOv3eG(X<> zZBm>~_g`JQ__nKqpZ&2+&wticXjy0>i)-3H3&pI-8$oU&N#gQ(0r%v2wWF&j%ED(~XF?w}?6|x*C9O3K@ z61%U5G%-;UaL4NRfdj=9Ijbrx=(HqSIlDe?ZR*n~zQjCO9n0S(-~3%Hw4Xeq`fmwR zz+UvPDo17rsrk6$;`2yx{|Vw0G5m`tOy3}BoEKT&mtvE|?hMx$6WM=ps8RZ=IixvM6vs9ZfG5^pt&Wju)4{0wCjNcx z*!@osX1JdFUG_hGE1wty#UEH6_zm~rxoW?&CoSUJ9yD#?T|W!wXsP{eYPc3-%3f0J z+m!@?k{o32IypEGe&yM2g78gCiI2N<4WkRk3A0rVvx<#CSR3Inr2j3`lxZj z+y1jRdcItR7-D8+?{7h7$3Hk~MU#_C8k!3FZ}EE5G**xncbD~rRt->XIi|hYN)M+{ zSy^zj(Dee|#DqcjI%8rSzJnd4&tCFq8eUF}&&CPuq8_i>R%`Fz`- zXD5fzcOlkxke9T{n2S*XH=^|Lb#3Hv8?B>tzXFglAD><_3WZBLlD7FXa~9q19_;G6n<5o+W;-aZny!?D3#cS&FpL%7ClIhzzaQ0VG++h?8<%Qo^9 zP}N=0P<}`ZtH_J&S;9*()e)DZM3ltGoctm30+cxZ`log47~i16gl?A>u~|KnqC9l zq*Yk^&pib7%s}Orug-uo%#>@Gcsl+1@r&z2FV_wx+SMXce;6^|aft^4&@0P{B86|Y zC-#JWRoWs6h;sxoNNgk9g_hx(QB!b5KN?O^z34vIg+tt8WJyC2%G&BcNU-WZnsw zFF(c-qM*u>WYTXsZ%}NAB00JXp>A+extSWV3FGX@SFP+J@L1TF3OtIw3dhFAB2*uc zjZaJv3VL6ONc{9c7dR7{3PXKgC-ivKy!AGyZ{q?$uT$Y62DcM}XV5RREFPpG0|)P4 zHgN4DIHYxHTsZhSqRh3ZzlSbgep^RnMkKoQ${y3*5-=wF@39aHS?jqD{hlT+8%RWy zhL(mwfR+4iFs35*tYXzoD+=27Zr&E*`bBO+2nfO67UwuxiuenXhR`1|yC;o#|(Z$S!YFi=| z0w1ath##ak=BW0iN#K-k{gIQsc1v)lS%k!qr-A6MHNDX5#`HdV*3o>l!fqPV%%oB| z-x||;G%felAe2h(BTw98xT@2mPo-W78LDSaLN-Dj#W%!VjSy;>-2Tn7gr`*}1@<3y zD*gI}tfHS`8iEIegQVfoB7b%6i3?;Zo)hi;MZU+oHh~&r!pmzBHjLOW)H+CE;fdi+sPEfZJmt zleKg^A+I8OKR9qzp%8}ldR=(cnX3p-0~=KUWMSZ>Y0H(vHe(ypyX6jd!)jD2u^ENZ zQ{=4SBn{V55<+fi{x{0~z~3+|%7YQBZW~Er&P`E`psd_Yoh_$(zW>gp$~8jza1@0^ zQ=s$NT91R(oiTh%t#~PEt~ihzw@cuIRq0ik@( zWjfse`9fsvUt2D>wHhQIG;U~;Ovq6_Zg74BQ zW(a;~emm|NL21z;@%9`kS7{1w58#^Fi}HO~!?BsA#2~^%+Y;YyZn9>m<}x2uPSuWL z$ACOHg`Jxi=lhiifjyq3hLmg@8S{Zmeu%T z#r)2n>MZc|yzgh~1^QwmV9d*aud6)#GDu!R8{OAo>PyxZHl#kb{WLGTl3~#+@}n8Q zL|k+{SMP(93ijwi&u19^b-FJ?$j>%j9oaHM1n|GDxpS|lW zAKf%gpmw>#b?n*4cAtM+bFsq2yvuu<^7WA+^~i1PQ&2jrpxEIF0yMo6(+^0c>;Q5H zThA7^)5A*Qj*y*85O-j35qGL$pbVw7qnh+X%m&YoWLv~N(ouE}*hEvDHxT>9bwW+a z@Kw^L&>EdP1iAiG?K6&(_1?7;-|3ZwjIKmBO}o)tt{2hQVrZirnaa}$XIRQ*!^J6v z@C@~`zc*2M$yh2w@FI<`ayD?0=so6};&1%VgY>bz9K)91#}<*MU|c8K7I?OnDnC)5 z1L>wjNl2Wyz0G9HZ;F`4V43_GUm!oL!(xM2^hcXaVcVUo}{-02k6(79GLGv z>A$Qhf#Z{xv+8py>IUQN9KZ@vRFdTi+o4|MjfIY2n(3jIp}XxOhVcz5 z1=Joi_OHFJt@2u}mTDovw!V59sgX*_$OZaj(TwHmTX2L{8;9au*P2Dqp(5g%qU&>7 z_+n|QTfwVBz>38b8M_X~5DT1BmcZzgYtvkNNuRSyoK|;xxvs0znyT@heQs#$pvMuV z99E0+sB&C?eGj0A!gcrM*c&jATUCPye{T!Hq&>b_k;gCDX{p{%hQ?kl+LNxi7Qal9 zyIvIBcMo9}oglRc#ct1S|8MMjUj2~bQD$F3M4oqa@C$`c#uHx-1W9+5^wLFh177X} zkVC~F^L*;xJXcw-Gg3A-^x!TPFIB$`jw-zp{p?1;nD3EGZ8X?ele@#4%5a}F33cAW-X=#ul4fL!^8BDKOIo+i# zQj1sLTTL|#BnqnRFAt0rK@e*~)I~OnG=Yq$jW@4CDj*0DiXHSNMFWt#Ih{ps-iWJA zm_BJYPx2T=cbkeGh&?Jq8y(mOEsuFJ3nib;V46Bx5M0wH3Co}26lgxtMGKV=eFMV< z-KS>UdB=!+HO;BMHV7emZzSWsviH;N|6%I8hwAHbzSdu-5-N^F03u76V0}I zXp4oT=p3!q#s(H~PpVF)HnGToMM&{ZS%_S*hmE(fL+cRu5Vwm%#?E$t+`B!f2NMtK zKwg2ryrI_FwxPFSplt4tMQ(~qNi?Je`>^rsLkEg~T|CM@drP3G26WY7f0kn!!dBXT z3bl{@EMH==Q!($dSalUXUG74Eol7njqbFZSnJO{43pBa!V07NIA*@js{lLRLa1dwv z7E5os>KrGsPhmp+sYf0CvMww!du*2a&0_PAF#(vkqWXip&3b2y)>2C{FxgK9zIHFj z%*^eGJ`PICt4H*4sDu%QMeU_Q+z8yXlI3jXQnVDD)HjbU>&peYAxKSs_6C)>1&5J4OgY6!xL{_opX4w)D$Ccz!-n!Rx+p`K3*_Nz6poI z@83o??w6(=xSdAG+-q8G-;r<=Drb53@^rh^(9msgq_%nDezLRW zl;1bzPl9#A(g$WWn6O^$eUt(k#kxrD2hem7GR2PUIG&7V@-;8|N{R^sTyMzQ{Tt~+ z*+GCqkys`!8P((m8I<_EvI(fnFvd9UL;U-^K1B1TdR-P$4-rzJ{hU@-X=t>wa1$6{ z6l49xuE3quP2?*4K-a&kd-+H{L4mtehcFW-7VC=4htKB-x7p7!vTalR9mA9Zr*C{d z8&8SwN2-SgDC^qwKYzg#>l)L_XnJP(y6vazmNojx#x64NrvT{Cw0rO_b@`ctc1mZ{knMLsAI4Qr3cJP`Y*#wid6^%du_W^QC5ex*TdurpRDn;Uy}(FZ$ea=;(_b? z80l{1`F7 zHXbv>DuM}5xO4N(*N^x0&$ng#H)nlWwVmj|yn54g3#W)$|FX- z|Ae{^DWv(IEWrK`s!L0Oa{cPdNW52mKVBQLyphnJr#tbUV_jVKG?fZE+V*+&H`sP? z$=PW<-d^sij3vjt3PDqK@Tbwq^shGJ?Qimf-~Q&o(*fo&MG_qS@(?xSPCo$DV!v@Ln1xS7>)~&Q@6{kPNg3Q(`7~x9J-+1ZH$kS`t=F&^oh0WhA1Rp| z*qj+Ha9ozGi^xbViV@Ni$`y|AjmTcv7*cmRRscwL5ChWF(AsCizmc7AE(kMb;kW}d zR%7(xLc9WZE+R%4Q<~rl#&AikX70GrPKG|$<A7c}0;LwW0_F_n(ALA?Uo@YBJG{CGZSPp(jU%MCjPYAF;DPV*93Lcw51;3GZWf?nB)Lx z{RaN&3!+7wY@>MMYlbHTBqYdnW0NLt!ug3A`j&V3@7hDeYcSY|n?D{#B0pm3XLQw0 zfSQ}AG46E`y}(3$S5esnRVVNsF@zbX8G#Z;izPixli=@1hn`;yKTqH%W-*68SO)Ku zZxa7zp6HhsBfc!to8y59zGKW|PNhuyf&z4q@?Bc|1mEvzx?z zYvUn1N=ktmD9$#58+$w&{oP6eC&BgNA$QrLoV!J&m{!|23CTQpZUxiLz%72 zgtbJgywi_qH8%X>;?Pu)@-_zkRn9m7&JeyCT76uGfT#>Q>* zKWxb*0N6PWXf%(x>MqLx+O_TVl2(v-D_C^*#+O{V=Lyt#<18-v1lOhBu4$0tJZxLb z7X-P`XM3GUg0oRWy2{Nu2;KNtHc=-0+I6GfG?&@t-m&c1k;&EqkgUwDC}GXRq0-eX`f9mVgvej9Fc_mk~DRH0`SOET-^K1#y3=07YKKMdx>UKfBO9Ri;fVzlPkZ& zYV$<|ZXf!+n5AXbl}veMe(%r`u7`-Cq&-n+{92m$?C^Ma-gM{u&}(V59V+d{reGy0 zFx4)~VED48qBL^(6~T zo#L~n@*0sco9~Z3tST&Xrb1u=I?2gf(^T)zlUdEHF679}N#<$3eUf=CQ9I>Xk*5uN z#B5MtPRR6p&kUilZ-1``%`1o3{dNv7C{EPxDz*vvq33a4QY z;0r4Hkx3Q`-3#3Q5Z& z%}J=^aOSeRlf{3w6oL!>Nx($f0)>BdPISGELziV^fY3Jg$M~>`MOt&|tm8(9i_{l1 z_7pSzkIi$LxtrZPs@coHBIo^Z)|Cb9f#)k}MT)L6BRd~A%C<4(s-dQGrfLp9=^rY8 zz|+SdWvv4t1=ATw_IcivSV* z6FH#rlJA1%WZ9DZpgh&N zeY3Zfp}ao~KbtYjm?^pw#6pf$eMrPJOx~A)eOQ;zn*|xc3HFNWQ`?XtgMKz!FTCkd=C{vyQ14SWo{$5-f@|b3V>c`g9o0^;J=;6lT z3dlKK+B+~r@OpA9^x_Q>t7q;kHN%jiPFJCH)zZFXKX)DDAA~?ZbE`r;YXUODe{NHm z!75S6U2K2!nB}VslJ5%dew;f)UBr;pqCd+0aEMtb9V-~|HL_u(wEbNL^|z*}8sp>r zkgg8BTNGHLL|NGhoX9S?fD13qwNkg{L@JDHPvjxI*8*|t@X!`koF$vixJu-ISkdK3 zt3$enGg3Ti6_jnMyTpYDX-zp_Kjg3@zPPvDLHzJ>vscLE=o<4~S&e6p)weJi>{SSK5PzN{4yxc}`|(z5iOf&Guy z%Af!p#$7#Q%0KC&#$3<5vs_AI8n$pKJIFI3Bc%$9>IQvDRo)+;z3RJ-*MU)i89KV4 zRUlX|DDcqcIw?veCQ@r1q4Q&(2m5j7J zrt%vse?w=nKF{)7h_q@0RU>#6*NfS|W@7S_ByQ!ZN4t-^SNE&%c*59%Xg|(j8XHt* z21UTq&&O$|`3wIill!zmK66W}9pqVKuPOosv==6#-LKbhswb_>aIuP~bdPw6O*gd0 zUEWA2jhkV*c@UpY<8c&0d4`f6corSyTVrF24Esq8Ks|2tS7&hCVErU_Dde~0DoF7lf(s=Z&nxi$X*+(rZ*+pD zU)E>W9B(t<-tTNi80#3fv5jzhJYz_&b+w+zdDU`4EE>DNGDQCRc>`35c1|v3i4tf{ z&GVtD-v+FU!=OMV>dShFp;%e3nWD6QpcX!A63>l#y4l`lu& zB6HH_-b^F>fKZGdKNu=aOa_+VvfH&VsHrMVilSy?^T^@zqYjw2kHTLx1I>-E;H&ACCL~c#?Llhn-V*%rd1E|HD$^{Dt`ET{I9!HaQND$NK6iO+&CRpm(#6;LNko zt5xXizEPX=eMR6G1hsprG6tye2Q*4D>|vw~ou^JLN6&2fgR2W85sBbe+t1a%m8Hp! z3@8Ht^R%YcVx)-c32ws%arNCe*_u4uU4y!=9L;ka>o6k&N= zN8-vxLBTxLZ~avY9R?3>#Qr~pBJW+5#W5j4BZeCGZ$R-^md{!ztR69&#tkPURp1X7 zSLVJZ*LL{|g_-<1+lcjOM%qzc<@QgmXgEb{BNV1*H2?9e|$lbMX)caeL#aVsxi>65Ns)K4d9E^6@gP3ch zOu2n97x)Tg+A5JRkt){IdlgDi_%W9(DdO76hv*-j3-Hm=UL1rMB{v2>W(W{~1n6?? z;R-Ey2XEiHT(`gFB)-g-dJm60XQ+O{jF$-qLUQasDzGp;jF0)pLb(4<7W-PkLP;{? zMv4@yT;jfnp=ZbKl(D;5e!z!~+!8pgQYc*Kzc7$La=C8R0HJk{4t`)+;q?xarxtQT zx5jip9U}es%R89qvj{W}+13~+-Xp4Lm+#*Rwg--TrBwMa573le0X6#Bpyrl8xsYml zbS+-|F7DGG4NCF}F5vTNdFIjywKt+EdfEVPH^lVTS6VQVC`m92`I( zZ2Gtxj5QiQXxz$lI5`7;$7=!#U1?@}QJwt$%j{leoTj>KM^R)^3wT|Rq-Fe&?tC>{ z&$8E9Di^lY=g!k-Eb9ds>F>NqAQH*N^Cxc7icmqb6sBPk&*rh1j4vs>R&?J!as3m2 z%-&8`)T5o{VHZ6}SeyLQKOe(gAP;*N8!pvhobF<#MWS0BKwU#zcA=AXYTRMf5Z zXp2ew`M<&-q!{aFSR~QGTjhC|nCRDiXaRg1PcI>&txoep@BIImZEGi+The&aeNlm4PM{jvOg#4dqBfxvOH#=1e@WtBH3kZHwd z3VmV7TiG6y+fdpW$J8!QaBtnthCQQ#ZiJULY1h2si{|k5pQ!GpTrG|7H;R^Yqi$fe zP=;12bb^0Mx#}SOf(rcVUxZB%j7utPB{S2Fc2=x0YY$TvTZfwD(M^5sQ*G&G$mMlY!3<+@R z-La*&q`^>ZP2~C~bD6_90LM{f0(3Se$FeMds!KKvp${z@fti7!!u(v`ykbuxa-E`M ziYf6am^(*+g!)o;%upxZpElVy0p@UO@^88b)#!xGe>`5w*TR(XCp(!rjsPJ}$&*aZ za^_yq9(u>`?<-mq3ayMz95@78NgQ(F0BZ+@Nl{Ur0^(CtqoN-e4SBDkf=*0qSdqr~ zRx9LG$9PEsfYWKPJgZ`C>7Dfz{k6Ky++yOuA&u_P;iAA(z-uG(A$S)O?_G+7DJ5Jv0)5d+m4piD6?r`)1je>P zC*13{A^{f(6WJdk0bD)4cT~UvUrBSIzn-nPlXRTn`f%L@CO}Ryj9J|1Z2|l}2pW#s|Q)I2m2+Dp&j+2x9781ZT!J-6=OSlxjcu7B%W#d-I_r zu~aCYkV11e;>cK$NTJy(DwPujk9<42d~;VWRqTQe3-Zqer2dtSsbAU{14ey|uBHIt z4^h3KG#+6}x!pV@Hu8w~QhJY0J5BTsXC*p{HR#ds`q8HCmy~ro@V>cT_+5?)6_XvW z`@inuPO{YJ2eYSo7ea_HIMyVLzVI2%G=Rg-nrn`ui3S0j-5d)U82r?KJ zXt75_H65fn?pUld@Lf*{@x-jC^9O!XsdGy6=vG_+AAt8EMRkQ-UVRC1*SG(=Ino`1 zx`7a*V8IMcD0w#tEhAQztNOlaE1kXFl_3V_i2R&Cc+;xi;&=4ey6j3&-&f6t`1#0( zSQ^1;tn;6kyGyqx+8X^+@r<6V8utzL8q`e2#ujtl?A}jYNt-LYcC$ejF8pN=DW52y z;gach-0+2st;iNLuxz&YL@nKqo8Fc?2isYsu{c+_0!H?w1Oq*(d!KatJ2!5V@_+d9 zELj;=s*}d%fhBCXoP#XD8Za}iH~iUIXF0$nc?#fK!Y&?H_PL^39I(F?@R8oy(?2fNO@ez$w^ zIZ`iHhpXz)`IR1wLDP5Vj#viKH||MOLU2QQluSd$ZYA4G61bjq|MTTzbY9Y>HqS_s#htaffqsq(y$2Gm?nXIcy=! zh=N6@u>M{As@CLw3z$Ftvt>o zC(h|b6FR(cF7B%EGuDG#xHE{^jkxGRkFSE*p9#UScs#6mjLf2b*TCiyw9fs`-8?M)NIS(_wue zsQuBj?%4I-zxE5W;f6V5pZWf9D~Znd(t@ca)S#;wA|Oom6Z=Z3A??f)#91D%# zbr2l8yu=Xu5_&bS0cdmp(oHD!cbiqipU-VpVu>wkH81(JUzX@$#$p=ge~4CVZKTqO z@`8`uq4wzH+RIgPVMAINCfMR>{GTvOZS^oN~gmwv2${yMjh*pSKoQhZ{eSh*`DLnhQ{zWBOZbMeP zqYP~i_3l^j0UWkZGaUffXH$vGbO_d-a>OvR(^e2h~W1gQ~Yg|)r7-U`hUY*u}Frmr}eVMA0 zjx?@6Ws^j~yxas`Eu++fS2Ve)BD={Hngm@{uhyMo0Sy`S-Jyjmf5L zDp1YeU4NlH8JZ5_?Sg)$!zSm4>Xsf^l?k8p&L|N<6l4bW&fY31%|jE5z=0^{i%La! z{CrJ?A_Z9hy^z*W!^k^fmk0Gu6ZEz(YTc;yS@E|&Nxmu#50QJLjr$RR?eh3#e>rE> zbi821yzg)aM&sJ~qXc797o8nyc94?WZ5_e}&0Y$=8`QrV%o~Yw4Qq&W2sPDYNd1+Q zX{|%qL#MyW*p>V^IDw)yV>ya=NOj_ibo{&Q|5qSoYy)Wy>zHJE!`eC|Mm^!T zSvA}H6=?u-NKM&4RQj8(ptIjhAUj*t%Wlr0Q@NK*V6?6wSr@`cyY;PuL|;BFyH)Kx zk;o4xLgrtB`MU<%C`O3rM&Kdz;iO2V$bhfxJN3`Cv1b;O-rLGB-xu+7m|iA<=viM4=1#d5b%B$+)^u2M4}2*$wM`z&pPOe0Z0 z>ISb(#lKz|Pd&bZPS}pon~z8mEKy*D%$m;%c8T6qEY8Z1`bXhOB;KpGG~&ouCD*|f zC_@|AyM3==x@*zj$;Pb*d_Ew-@|`L1S<6sT_2&4QAgtroJ%uSCG6G{BAcCDXA?AhF zH!%h$+o>e&3xG7&iEs+4iDWY)C%NcW>PLz#;b$Hhe zZS`62dDr+CA6OD}H>n+nVyTStp|;0?v_SD_2e>$ICG*41*p_!Vfg_uMq6|<{f!#i9 z`a$_Fm%?2vZoUsh!IR(P(GUt4TXcaX*h1J(X$s#Duj7033=G5-(8L0%a-08$6c$hU ze&pKA`4w6HXU^&y?hGf`{esaigTMM_!x2Fp7tBo(Km}|@KYZoMwXRGOrbxSiQc5!X z`nvN5m7e2fjAZy_04k0zAZn7!UE~A~=Pg1&jPbgD2@9L2s{A^{15Qb|8PT2s05FG0}sb>sVG%0QRu?nu&iVAd6@TvLpz{r!mC_ zSAJfDd~sa#Np1JM6&0gXC46rQr`Fql0V_UV;5gELtJNese)=1po-)*L075lk`y7I@ zTi>KUspA`0!&knR@+WMOJ_;q5aiofe7g(Oe4G=PurDZyQCGT9{MD|@AVb3 zZ^w2C2h}6&b3R6kc|786zX`%I`WB8Nkz6Tb>tPu;Y?^y~X~mk*-j7|0S~}r2);rxb z6jb}gBwGZ!NcOGJeI*X%0pr8rqkhP7p0&rDtDij8&a!;3wa>O;`X8EFhmPGsI$3ii z7!=ma40@?dcn&_l0VrJ?2@MfVM$87y6>rxiR#u1tv-hq2%&p8G*LbjUz!NgDN+yzx zfv7pH$CaJ-I|!pmc>A%TxyckE=Hu;IzxR@_b7St)^8ktc{H<7JRo6E=g7=h~k825p zZ}=z9uN$0SSS!S$RqmS_1Zi;hHp+%r>s=(trtrn$fGEep_oBwfcZc{jUdCSNv_!foge{RX9_UO|} zD)wbUoG&wlQn})>Fz?7@yiwTp7 zuE|^nXrp|0!lKV3iLba!wDkj`njF=oZIu5jkg1F7)EFnrOu&mqn9yG_VplTKE_%h- z;f|Y-Ki(DH31nthBoRPH(HZY_2GDqi00?71ZN$$=m8In_=D+N+>}=Ii2-{J_@Ic(E@?loros zhVc(YaR|&EuxB&5J2L!3ay&$txgH!fxA&N>Sz&7>`&lxu{oB(sAcJYu?gH@E&CyFF&kdW?EjD{bio?h9M#-%4e`fmJ zvoo%!U8X+}-6lI^w>emrs2IubsMn-?`G&b{p3Q@p3MDxj5JJ`tB;o!EjM z!)-FK+A-e_a@&7NS%S7H{>;qk-9_JDE!v94@R4kSKA-7;?;7aTiKJdZ7YUqTq_Q82 zCRBz;K)Y$kQ8N#y4~#Y-o?K_{IKwiE_|EO2$RVKCG9;SjRoIqA1T3jRlgK|=0c@XU z>w&&#S+w-s6U*~e2OVW2*^NDet_aOmA*7ROo!``wPDQT ziIYZ)y(rVm`5~s*PE?E?q8P*H?P}A|_q8aqLSZty*A8~1b5g9x$i+Y~Ch{)E23FV+ zek-JeHpe-lK;_#{{^S0?w!05k3Mz&#Tic~E({RqV(c5%x^R68hE*)dpbHY9n5*0Senx!#Av&wp*lFEVioHTu+ z$A`~^!(Y?V2ro;CHGi+Bt5#U*qq{R8e;jhzkvhioC2w+VYtXvXX#!cI^iVfXJ^2CW zdYU%dsm#SoB4&sg%<1MUV(hXXvMCDOdDPJqIC0odbLApN;zlUC3Vjve2*H7pf7vllZ94>qhCC6ewg6zHh%o zk;|TUVXa##_e=V%NYA@=Kf&^$D}3gJnb>VFYpHD>bAEZ^mU}IhZItm<*%rp{Puxp62n$9O zPZTf|K8_fEp(*3Igw1);#^G6OmFj^X4&+`bh684| zt|Ys_LC8+ckInYIsja9DWID&T0ZJiP)!XSYB&B%%g?ReA2E%s8VS5f?wFvE3Y(!tn zCM0l7Y>%IO4JwV>urHg(x)?t$H8u%+3lniM$Qg_4X^Pgi^kFY1wKv zWKfM$20-h(4zchtI!SO&Iu^VG|LWQ6#lTaB9x9{@#!%>S4RsnB&r&1;Tqc&*CE}(c z!+j$$`r6&+moO7IvRZ!U2PwMZ>A$u4ellDwB&WBf#h-0FrK-b3Co9w94yC_oWYBMu zDILCFRR`^?F#Zq7fpvw*H_ct2%)<8*w={Q)WQ)cP9>bQ2N$)k!_-4yXG(LzQ`ie?Y zl<1otu|+-tw-fBR-4v7V(tUkPj)AZrR#mrM{+9Mqv1>(}&p;9f^>jMmDD_lVelp4z z8QvYz|115^omRf0s6+1EN~?59{gIYx!5U2*C&A#oblf(~3LWE2-eG-yqfJUU1}pv=c5$M);s?&^ z_|FYX9!}uRNq7q*-e(OCW&8#fIpK^4pW@-#)b2!&uIpLpRYa2 zuV`&TI61*9E4Y{=3(h)`+bqlB8!b%>^tPh9lSG0E!DV69Sh##DZ8&!;ZYQ~+g)Yq^ z|LI!iFb{(#_&q90URR-C#7fHY&(z5C582TIGj~u#K_G68N0W9QY5Lo%wd#qaiIrEO zQO~kfn`1EiUN`5wuCM>mIs`1z9{RdF5?Zotw^O6BK6Cz!#ePaKUrliw@|HHG&lWhG zBy^Ugy${IlS@F_AFtMJ{1`zq(Ch7OC5_2d(pVO>`*xlnR1uAuncnr@-e1^;yr<(}w=*m+6;P@nVY5k^8faZ0e;$qyrV2~dhM!kb@lNm#yiQ&rRkeQ?nJ`g)69hOlZ6(LX`4ngr=2TCHhve=D~o zoAbbG(o^32yac-+))b)fy!zdiqc#dE&yk=k2&MN|N`4|9VeCGw)RX4wrkX@XkU(~??>&<=bQXt^<8TTjk$}Ml{p!|A-J4szmYxKInx*)(^2AeCGh7_4|wfK1&|-X}%_KJJ?a^_zYE z=C`0+xya#=oE(RNQ+(UlnVj#f6|zNjIy-vtBBWgVT~`DW#(Lq4IjlS0ALIwcunWsz z+O*5so1RaVqg_3-dfycX=*o*>r1F^)Ws-nlFW7G}*ZM7?G%5@I9mT{AKKoXrvXww7 znlK<3ARmHTLFWHqQY-0~yZ&3vr@nP86I8jfB@^-&m;dVz?^HKw$slLTn9y$rX~YKL#b~b7 z@t+qwTHB?*-YI>xX%5f99zGM6%Fe+5Xi5grDquY`FUQ{x>1W%};uC40oG!DdEu z_;Q{ygOzJMJ*78@kw;cJ@>2LS#HA=nsF%6;7YY2Xw4D$KK@F zT=0~63S;mnl9(3HzHUoBNE6moej?F-`or6>=zDdA(*!mVaT>dl)~3n8qJi;?u@QMSNZ)Cq=h#;vmBqPGt*n)w=ofTEkUF6+>{_1n<(R{stSfgA5ur zY7}p;d~%didc#dz7LOAM$JgDVbJ{&@n)3|eCvBK8kf%EOX2wkhDb*nEwn@dS-p7_H8QWg> zuC|y5@iYY&Uhot=+`WlW@U z1yD`7x7bk>m3K4(E!GDOOTEq>MLt3hhbf1pQtnW_JjeV&`WY-rW%g{xSVZ|6@X|sI zrOCgj1wiHB>b|`Qo~6@D&Z??=yDcSE6}8IMG;w^|M34k$Cg9ge!Mk7A-?4RMXkh|Vd}|= z0ywW!PQM=sbz}?;@OFz_66^^gh~Q1Tza`8*Ima>(J*D~ia?b>2i5n_DzixPQ^Se|s z|KZCpHL5OSn1dt&+6r)!k$pxSkqmMyT@ zW^sOWjLhqB+-@2=4K*Jx!r$5Eh6rP)kuecnzz`016%Sr2OwAmSiRn1!2ihq~6BiQL z-{=eS=nm`TznIc*I8zET;$cn?jkmQjk*U81Vj>PD<)(#>(ZeXD>k|EvAIJR6dY!m_ z%2N7eIbWGR?i7?vZGvuK(PI4p4?v%zMziwE`MCEUU*9Pqs=LVqR!oPndxwccNT8Ezk)*7w6$1t4r5L(gdfGCYJ>@wYQ;DfxsX{R0@Ga@Sl~B;JTUvF6 z&jd=(l5~XP?>Z(3F#CJYXfzIc&DF>?eK)jZ#vy{!QO@ehsyHR)`E(R2J-GLpAR6b^Z%B3DHmVCrTnczl?bW1O?>yhwkJvKa<(8N@30VpT zAAf!ud>pJl0mU9~4kjXBVRXu|C$q#w=`P0|k9SjPKFIr#EQfY8HbK6@eW-mYx-cgB z1SxY$2Xb}Yy+S3(P4V4fA0?c9@Sdgo*S6DnKo78Rj$~iz)5Ve{*T3lhJ97k=j8MT z20a1j&GJD)RB#y%bHY`&d13*EB(-u2+naUkWwvK`tW3UBBmzaewy|s_P@3?ntl#KG z*OS=ICYGIJPu8&1Zt6Rle|G^zHasiAE-KTz>q>8RhB5$`S(tC20o6LUFf(cnnNGwH zYqGJ?k!&5p)0rviZp$*~>6#A1>C(!YJN>L9STd+GUGH=ihrxwpLZpYqkAMgXlM*@z?l^h>p#@@U> zUO1Y#gV663su}Gs{U1g8W0hlfqTFJTh{uh+SR#JTkNN89a;wt$54>Tz?a-ypTkH%d zK<`T{VY@TGU6nSRA<5twgA|jd-e?K@`5VN`Ve^O>I5SddiPp>=#A~o!v6f+&K+I)lh>rLH2+VAf)Nz@W8C7i3p*alT-(aQNzYLa5KvjvYe{ zv=5UCbzn$#ESC`D#PNYAoBj4tTfyA&gD#`w_;M+1!RpC>8SA21i_Y19Zk7xgG+|2P zqMkSIte~Hcc`~5aG3a5OF zj>~0>4$B4+ObUsWg|^EjLKv?&?metuyw{WF<7FR1yGG0!6!mCxT8Cxe=+UMHpV{F_ zm~h>qe3ucNHo{)H6i1qA+zZjFT2e{g|GMg+&8qa-uvetZO(n1LEjjFsepIZ~}#$6gA{0?r9M5UP2wxgL%*_-d6ABItS z5gB3K@CON)oh}!p?K3kK5MpXeicHg6O5Gd*L-{Sc^fU0$smu70TcIu7B>V-Cx=&Ytrf3 z@TY0W`9E3`j%uO(y11+>(Dk_#cPQDc54BVk`aRo%NJ z56yC&%^QS6#^M&C*P^H0bD(#?BDG7sxI8%fFNuh~&zi=E{6UU<>07}yk7uPZwqi{z z#}^y1E_a$}>r!gKyc-{}dZ+3jZ973$y{79}1_ayMwq@h{f@xkeLYN**`_!_8(Yz%STv=<&7)Z~8p>{3)U9lpUs%nh_oOH=Tw) z@!b<;Hi5#TfM$n`Gu1$z9I+wp-VN&9)9|8hL{sA+_hg-kTb>i*+2W4GT$k_0HN_ zn3yVS{AFIHvz&o6UTO#%CiS)7r$bBk4mGfb&EG7+S`mEU!qSYmg->orBu{rE3eIGf zcogk46{hXH;A@#_abNUVFs~>G`vkyD>Arvkw(K5IbgioEOre*Q8Quco^`%2W;S2;W z$=_r;hUnUqBMXS)ajmzWC&+Dz?}btT-GkEFuq?ruV~?@MtAxg2_eR{N4AOKdPF>v@ ztOP(ND^1IR7)Li1We0AL3C{yG@@UD6h7Z0HR>?78ug9J*a-LikVY`j9rmEx>wIv;N zi)k_(T&;cTu3QS%B(pz?qa_cy*)X}ov`46tC$NPw)`Q5v2SY7?-_<2OnTh?|4+CwSGMY8QSX$$9=t7#!yx2r2E2(PhTEiZ%kqsUI<^`_zoo-yCjP#CA zWnh50QAyuA+|AV5|E}(3lRSpF8#`t7F!`Bm++$G#KpyVXctNpx3Zbby@3*cp_NkTd z`xdu<^}4R+s89 zkuUUxAlTDG^rOha0cY=l4HflHQh=g3(WZVhHui8go(Y&Xfs?7T<{Wvp1#fA z&D6`SNPKYV#@R{FH579N^29giM}bhKW|k(blUx0M9PFXCoxhLFeakJM_qvr;5dHB| zwP@b<$a-uAtKa0LoZ=mHAwci&;wej)W$0$VLiD51a&fH{;4Ax2_upLaNrH=QBywFD zpq-`bpM7GB&Bv;9&sY`3x@wW^DqBN|meULt1ZsyWkz`A7+kYOMsUAb5gF_e&6i&_gixJLlt@* zy`vv#CB+>b7?<~Bwzq5ctqt$A!vK!*db$sz>3Fek)@KuXDSlc2P*>dFUupl71rUJA zQP3{mHDDkW#|ysV&l2(T%bHz6= zNJy*Nzsf#+dW1gWfFE=BJAy?^OPrL1rIar|0qB%o6CY5PEyHe5I^=3%gZ-XD3c8oO z29Fw39~5t8?i!&FigeI& zU-#|%U)052ihexY9#4_Q6LkHYGQ*?96>28m=X!~PgdTmbesy0yw(%m^o zBV9^6N()j__jmC6{nzunbuEN}v-keg+2@(yj{2aEP)))B(zi^zD#eM9)NvO0=<}Mv zWvlWQy8pO#hH~TCmUaPRDPthv=T(0-&ToKp#vGs|$%sRVObQg)!NpeX_H{1GlJ$@T z4p+0*=pTejM#>JY132KOL=JLw&|(yV=J3!l%=|F!EvkjJ0%QAwD<1MlX ze!td(72e%f%NvXFsw(~~hI#=9E1LG{8eo+z8exK${Jn)zKpbt9Fj=J5Wht~1KIeJ7 zlt2Du8Ck&D3RZfoUC~`+@s0I0TB|GY6`JKDRe_S{?CoD=(ZJHYJ%}6pxHWQi@KY?5=o|gW)#g5c4M&_*Gp`j#e*dan z*WA5~1xfxv1<=I^_zlcHGkIA?xW}hn+0+37(hn~#`6Sz-=wL4Cm8iKwD2*jg`CRLX z83xru<5fG5Uq-Pjr}~?5)l*T_RG^JR_hV&3rdEy2a~P!iiGq;2KhDO@6^<{}vXT)V zluqcV{I^Dr<4I$_r1*iftWuUp0h=H1y-dNPu7RJ(lGU!K@9y+{hRUB*%&Bd7Uh;$# z1D7ZI@H)P*y})OR^41*+l93o*mck*!!2^uv0K-oxmRew+t=?&H> zbnBz{ZxUs2G=_{LRQkEIh?|HrOe`dQg7&e31SG^f@}{UHr>+xKmc^B_v)zaU{~2K8 zp^{A%RJi0+@dw|IY2;v0$0|Qu8b()onqPdD@ENl=i*(3(+nhg2TUqoyN}S$}ZLo3r zc(?|czS1F_;Qj4JIXkCrM#fZKW|fYJe%KV;yQRoI2cRO#4;KGYDg)^y9DY0~shFPF z#S~JriYThm$)y;4=yf|9ED(kW&g7xWUZ(d?inEbVE`@*c-1U_+A+N^6q#Ury9#E-r znpY1ddn73ZmFlNB9!ywe19OK-`{>bUi?~2HC0qMOpN8fMBDl_aVem(dO`Jsm6@w!tV}AVVkO*sM(MiXC#K#T=p*%oU?xjcO`p-siG<2ZcA%Z^{VB| zZ${aiPR1WpqGZsG5v7j-&a-+r1NN)!Cdy=!(Nnr^jd<#Q=3t^M=FwwZJ6$`Sc({#3^3Grr1JdzIb>jiFxXFb-&FCH~?%RgqI|Nqff2PJo$PRa4#N4Y$pE!U?U2!$*DRdK;Br(e&t;-n!4awyC_ZyaQCmY%S{Ul zlmK>(?7bnRV3KPAIu$D!4`jKC-)?kgB8rv!$ZC9AU-V{;60kF16_*YrOT z8Su;i3QnlqpDBu0KHaN?5CI#AM;llF10%n6eWC=Q*Ie9y{VwFDMnhu_=mDWsI>4>{ zF8nf{Fq&sQvt11U`FCa!4ExCQK``|obE5I{w+4^E9tRsX=n#TxVdLUKxQAt9R|Ci` zePM=|B*>;$0ix~oN+y67ZPl8^l9l~FJYDM6yDYsU`v?%;kVxNCK;94fFe%|=AmhQ* z!M#Ez5pM6}i${XmB5}LV`tp$ufDHyGwk1>0X!SY$NzVl9Va-3))rh#@Vl6L4pYm6Y zVR!MeRL!7=>BB_=_?B$yhFQp)>w5jr{z;KVL1;7bLMjv8KV|QsTK2_KjA~cy|E&-lBT$;;QboJ_#tdbk8v)RE~O$PDGH0`7na4J*+T1!6}6%WSu*y47r zKUKBIrHYOt+A!o`?ZIFrGL_B{O$iEN+jv(-{bKB$q370DaDzJ|tk?6<(=ufa1g>Qs z$pQkT*47hj?)%B86uHPlB|nFErHlOl$MKnS=LSgqTkX$+jM@ew(iCxLi+>B8ymDXX zKF_l-Y2=si+5jHf7M$+|4)n72Z5ab(A$|N5;PG-iEPsQ;Msf4lJtfq#pg5r<{u`cV zzH;Lh;&&aTZzNlfBO~Wk6WzaP0Q!z^lfYC#P`IqS1T*0q-c^%w@Tx+AUk09i{Uxg& zVail3^)cIa#djEg#Q4h0xAA5L#|D2R&h3?1VFDymg#Pmry+kcRn*3$j41BVZoIrX} z1V8RTW9tvctv?NkqO>F6XTa&ecl4^|C?jS;BLKL-MmIIM4T7KhF|9dP*Mls+ATm>! zT5%uHwry_iLa8=UPgPj4QG^@r*x`NlyTAT3(eiUMP!u~vYQ_pIL&#v5xHlr;!<*2I z+dXap<{k}MzBCY-sU5U{yXVGzV)>D~*lIuBBt*nEh+dFkW!?mbm0a3{cTwzH#e~l^ z2@*xaA1K17HAUTRyd-OPJ=1+Ifn75g}*p2#i+YY72G7XQYq>#oMtEiSUe?dJ*?HW z&_V5zhu{JjT_m9i_I>ik!(ymTAH(((pwmau`K=%mPEsX6axYYXF34V$psB^60a!<$ zw=IK2w@}Qgk&lbslJ-Q28A#+m3(o2QN}C&{Nuipt>;zhkFE}E!L1Y@do&HAi+l_~b%5&Ax7xO0ne+#o5`WdptamR@c+;yH6 z{ba`n1)}PpHwa5>JzU9CRmHx=gOhS{qC0{Uc@@zI_HbBL9{O)8fqM-z;%IdXyU6vR zpX%{Dg^wLZUn_jV!~J0^5Xp4+4ilBR?^YjnHB--k&zyZX~*dpIlh@ z)+47B20WBhpq?6zQF`9K``+&}pc?-P5Um~e>X((v z)2v+Y&84;1-f{V!-Zmu>9t4+Cj<*B%dzf8^EsF`*K<8QTY$ykzyw`f~X7AvAYma{- zZ7;~1e>Zo0u~`xiH1NZ|@lg%iTX5;4KOxLMV;H7cHItzyrnM*C)C=^oe=vp-khLW} zRLmp$9~fTs&VFAU^L-upzk4=_EzVgN_bStB+y2^g)Jjx7tjAA5-e#YXej`%)EI4ae ze)qq+Y92(yptJ{W;I#l@F%au@fN1l-Ap#h5^XmjTCg{LZdFWE=S z`8h0abEQzF$nUt9F(JViGxWW&ll}Q6eClcqy39{W(09H6j@u0HAzG{@KI2s_haZy{ zvM)$MU{LB`JR${t;y7z1w+;P}{^gmHN^0E|Y<$IRaO0xx5*t%$Iq;^y50U?`v~7;V zUh`D=xf|iPq0JXZ!26%n`KJ+}P9n0xdf@5AG`2Uz;Ct)YnjLrYUZ#2kTbL1^5zdxi zx4~vb;IjN?Gzi5HwqQU=ao3$?9l{te|wS79ZwyH?bbSu4or{Au2 zyxAih2t^f)4~hRv`Pouvw;j+j-GlhY2viA^AG|e{M92u0`}VI&#@&2H$P92&mUBTW zmOy53{O|`=65=9lP+xUHmdi=Q8$7>S!7?7;$u{g-tT9PoabT3$Js3U1O)C&yj)o>3xI{o-RorP%$c|&>-}-GR zuTMku9DX=hHy}T$@Pl}Fr*`?xAPd}R^!b}pHJ8ce&5KZ$mbVsyqMJ~U9X>vrO2XbF z_xPAe_ZJfU_$P++$~gk$Gg`y`G*J!fS4}~xu(mKWm2Oy~6P%Zw<^M8n@@X!2RU1)f z6A=l*JA&ChPd{3I7Ur?jY7-lx#ujdJo{HvcuU>W6L;oVa8D*ke*fym<@RPYH6g=O2 zjC1PZ<%BPGNF}31iC(Zwx`};5DC-en*VXT;F1TP>%@XBTJ)Y_-)xX=l0GXso3jZF^ zPc3dlDLQC7G-W+^%v1z?gL^zB004pw{X)eEaAX=0uwgaI{ZhE073g|-S09VAuS}RPmwF-doVwgUa#z!g(EudJR`8>S9s~?Tt z?hV}sg4ObYx+8z;$!LfBP?6vmvaz$e5w7)KB>Hs`{S-s`vhUnyEW^Hw<+z`f8w z6)K}b>N-KP@W+b&p%P4ko7-lfSqbHWc!;3g?MRV5dGDPe<17ldp~T77%G8}N=~-vL zOt=jWb6Y7>8C{huof$8Cpq9-fP6Lx@IrJs;P*jW)X47&jadmb9TI~L6j|j zS-zxx#o(Wa0^k)0AlLDn%T}%SFa+YUz|wa@E;neg!19Ly@C@?jw;5E(Cgz9lKF%{h zDL}0bw*DqM0nI>-zTi^fFWYB$7o%oKo&wy{aj*1k`5=eugtM=ESqfY=^O;lb^RvAO zn#X&jsb@&s(tVa(AY4Bl0M>VntejY2bSgOESLw3I$kZI=W)6+NOmih@CCCxL>P-NpONLJAaxHjMggA9O6oyTGHKsl2i z7~-j6OB3^5m;?jx!sF*CCH(?Wu-04^lTQZKjjPy!GN4@6H>!fts7@d8u<5@zWov%R zgvl(mPG1M%h0ChcLNwrVknc6OMb!=91-RF{gMr)4y#Y+spp50BWRZAYZB}Q7R6h{s z!XqyDyTcEqY{7&y=$x+LaVQ3`UW8VmLb9}{|AN8fGjU z8GM$Oy$kYJ^W}jPV`!XcW9(NF@fU1DtXL3m!=Z%CaHL#h+437yYVtC%{H_d`4=Q`? zfVm#)PSqX!EMb0_lp(A7jK2vusF~k|5zz9f^y40x-OBOzF!KOHbBTlZ8m|~3c<^z# zR46qgl?20CTU|sMK;QyyH1#jqhpulg2RVIKodvlFfikIm;xyIWCh4z|3aL_JHaO5V zcp&eu6p!gwzNB2;63hnDnPpH|B$TfB!UZ7?DJ}Z!_;11eqI+{QSD*IGRX9FX_m0ox zm*(yH=WJ#reZT#xmXXf4sum`r>@T*l_#!|@`VZscuw%-nX;SB?G>TWgyy1F?u5_k+ z_+Dv0w;d(SswDEV6YtAQy9;x9l_2~pC-=?pVqeU9f_7@0Bx0aiB($qdmR+11&1x0h8n7=ieIB1$T$l6nw7`UB0Q6VWLx62XqQf7v==Aq&_~&g8$i4 zqc5(U6JU?Knq`dHLPAq zB#kHK3tBB#)}J%i>%An;0NaH7?@)KR-03p>s#Znt=);ELl;hVoJutiSkMGvCLr&qb z;N8RG02c#e(a{rnECC2LtMPwPXZij}7zrO#c>>LtIrEr!C9paWo$aeWABxbpEj;9B z1-K6WmJsarpU#4N;2JX!Sk|rV2!ZB&yjlTr+)(WZzeDZMyJ1B4Ev^{g@kHWxMmiYS zE{oDT>N)EZvRnc4K7hSfJ9xaR*6X}c1-(#mpM_vaJ-<%`#G;9mw5$IxsDlgf3Y8>* z!O3L`?0d%}!{6r6Zv8v7Vi9QwP5vZf*4od*zw_oYNrJEKiZH?jM(Bo1SeA%76j8we z@6A(=kMt9Urz2P(PYAZ*Ho<@WwL3NN=^H7!xSi}THEYM|LZ|74AyXT>XTiuw?)>f$ zZcA;;I_wT%P1vrf5V5K5hwP=6Hj`EbLL9ZeRWprl`~3I=(x?|p)>9|2KU%G5?D#7= zyf3g7(>xWcI(~h4NJmbLyL4QvEb3ey-zKU1w9_C(=scp~K3#J^ANUgmYcE#eO6e7; zQH)ts(Jg0QMLkcL{3n_Y?gI((4{M8K$H2iH^b!VsYs{``SFbl^_+?V11tguHg*=wr zN$0uZ3y%)nZ3Z(N8t9eE=5nahQjjeh#FCg`1U&pDUKw?ei1Hp(5gWFL2~C-wLL(AD zplYuTUo#&T-Ii};fw#QLm5KN=XfP449JPuKHsYA6>>RidB&~63%3np#^cDt-G<#-5 zC+h|(4Iub0X-=Cy4+i@GlS3Ybj2?QcMav|S< zfCJIiDC~B#lP`h(x1!y}Vr?_UHg-pOHIsL_W8qrn*DU>+OdFic@pbE59|M7FMJS^F zCMgbPkqmu5$M%1`HMYW!vlkeDg0a+U=Na8KT-9U9W`uTa|9E}4e3&v=5%J{yT%;Q* zE-%rBB6aw1YDV1sCe)YFXKj&sE>Gyww<)6b@rL%y_vgw<=VmC1gS#A2>ok;prv`>xb~va^RiA&edhb z1wUkCooaQ1E^Y=bL$ZGr#}@XKb9YsZnX7?0t*q3ytOwgm3zFk0VjDkR1!=aEl8A^L zOyKb<)mbtwEJ~6)DDQWQMQNeEvRm*mdeYLV3o(~=;<(vdYY$*K5T3p)o5<3-i6^Ab zB8()AzVPL+T<3)xu zST?u^!{CkHoc#v39^b)rgpaZy1^YAsUN#2?;Mu_zFBZ_kPsJ!WDJ}>YpJuODQ8v8F zL7J4w!3ql@z+G;0-Q^XdvEFJgk(Uk!Ur$vaq#d!d9?#Tu?N4RJ{w4>_2h#^Xjp3bp zvQ2tUV^~>VG7*aAbl~X1C*6&I`d=2{ZoC4;!oRv~JkCQU zMTc;uMQDndiSb5lyrAkkc^WTVH#6sr>5qajo~(}VMivO%G+Z8kY(`f`MteQ9?A5Tn zzw~_9TJZNxzlji9)dNM_2~V9o5&~>BBAYj{=HCn3?|Ew4rDhYqm=WW!-hlnSZW?lx zt4HoZE;uM)NfDh8YG?QeZfEKaCvfCPf^E#CoHriHyz-X0%B88#=Y=sB7Qn|<6&G*Q zH=dqI5I>t!T8Fw%abEX42&&nG72sGu3(Szk2|vMdNuba z-qwc$${r%Ag~mg+(ju`|d{uT6PSZH>jvw;*x9# zrP?iBbFezOLIOnJZh^XhZxPWGb8Qg8LBJ_GnRoWCY9P3yT$tVtO)491jnjUKCC?== zj`O+1KyBv)pQxrf=%xqwN%)ah00Uf7XV`2+alL)B?(*B=SgwaLPIM+nGk9fMBXqWX zRgvy45Bd%8-Tlp!QZitaVB%=n2Kr-pLKe*<{5Ji_vq6U#9?Na1i?4b8`RNt#APOrp z2+={1`Xjpdw_h4ZO0Ob67I%KIa;c6OZspPhlZN7K;cvAOVjLUVpC1MRRvyV{<)i)Twpnwa38~v>M_$hUw3YZ)B=F_$q_(Al79@yX0-~ zuvZ8KCBv9+aY;7UUX?~eknFcK@Diab-3PM0-^B+PPL2z!Ii9uUZy7)Lf>w}jHbb~K zFF#%DcTnED!kKdaZpqT9juxCZ1b&}b96#W99d@tofb$$_gmUeHYw4(Pybbh5z7?%n z-CmQepUaG8k4QU|10XJ5g=XhBg`2D&LyWU&bq5_gpB?NF>t&yajL)?zg7QmqT3kNrb z{R1wE#I2cMz?W~jwJA5CS=f77XOzCPJG9j|mU$;zL!f*_75Ed}dox2JzRShCq6-aT zqK~d{X@P4QR(lQgLiZ4BKP~SMpQc6bvu4r}b8G$(N%9e<(0h@e z*%@z)7f<7)MyJ#!RdBjj%~%UU{#NDQ>C)0cm;d11L=NR495!&|FcI)1!7@>$UhX=#5q-Ut9vu*Dx9N-bQ@vyq@H|4S(g2k(t^J66FYQf4!1MtCivmhBi>lk z4PnHTuT!f-NPdnVv@F+C(d{c#$Bccz;{4b`_{pYuL23U(pct_cQ`XxGI8h6B`fJbI z*w}2^M_2WYlX$`Wb*_%nQ;RJniN#j$-u2B>LpqmbztmA%WtyPa*b$!{p+$E;)&r+$ zfn`mba_(kvf8rae1gv{*g57nKm3-|)jnd&KxIQ~q2<}56Hni&Zj<-ak(%05A=QcO< zVH21WEpXjroi_-iUX6AHI{|acitjZhY%3+%N$1tQhEO(W_)v-5T|XJsG>U@<*xxQ% zKQkS2K)7&cn+&}V*UhrNDk-jfto7&!G0+BjW4UR;*R2wz{*n>R9HV+%IKm+i$ zSZfSwlLYbG2?*(TZC?>RdKRQ4 zoJJXa1voP;yT&ZSeLJfQ%L`dQ;|`w^HcKPW{fk{O2gRc$pvdT~FW0K=_(wWsUXs%Z z#k;e~yy^X2{rG`@qMPm&Ho_!4Q!sT9en`HvBV_5ZK7wz>OXTdsa%N%fNJH-JhCo8h zyNLsQ65d!8gp|y77=FU{3NqA`7?Gc?FU`6z-8urCi0By2&PhH`Ac94BXs@&ueD12o zWsY;FcWIiANRzje3JMM#m6(+sFO~c#4{H7^tmSV6%?|m;>jLiS76-Yn80#3zFu69m z?6O42?ad%m2|{)k@tkGLsd}CZK1J+M3|50wTl;DKx@dYg$MY;p1d=>vGL)m7{vB_) zYF00^P3)bIYqaNdM{Z|nO{YiC`A}bj(M}IAyndbX;XwEfQ)b)OV@WWL-;`pJx4)xG zTrdu~>TI8i1#ry6$cD}_i4)|;n7}q3)bHx-&n9c0(bToQ1%TLEY2j*f&Yoe>bs?hn3`;eW%)nn?t zBs>(HuQ3(=_DE`N0`bj+X; z((L9jF!Pmu^-m`>A&l5eQgk((`^4gdSWINZZYEV7Vx=-;;}gHJ_kNXnLy@MX+C*PG z4f#$v#+1fkx+B|9EfFDrR=$2(6xUMDMA8zNF zKzUGg5c=7J9{sWo&_k)>2s+NKvm7WdKgz!OUHDipQC_4^|3weYzl+z!GzQxIU6*X9 z+HL&4P?~7{FuG=_)*a}TCT&sVxEvFwoQ-=wjOBjnQ5OK_0p(Fn0o7SD? z0ufTud5LJq*B}b^Gz9933Nlr}#3IZLd}0VQQ$ve7n5eKBBcd)H|crDIJIq-LRfkuzXdhC_DSZ${F0u8+vRSvv-F5{LvQ+XL@j9MjzaMaRNuy%gqrQGm9dl2hK zb7$bAW2a@%8syg%bvU+b%L7@pR3G(pJzDJ0VUWRtze9O+02_l?ekEAPC>~=0pHTjJ z+F_^vrVO?3cMH9vb)no^TEp?O{Sw?oTd>JsYFmwHAjG2Oc*tOcnp|@LPX$ndb`UfM@Q`a{vZjaRGFUgCq*0f zIAlF!vC2iP(T(+b?D*1ABc+fp>tEWF`wk2IFqh6#d6pVqYD*oOpzKO0lV8v21fT8NzkwCkmBYK6l`nPUJ^mtMhi1NS7QSvchuk z(VrzI{50G?g@pIFHy3fqSmnhlRqvlPX6f^@mO^^FzBRaW+t@68)Dpv1#o#dp-Vv6dPSRxpT8{>ahL< z{93b8{XAZp&H?}6A5D^Pdenrq5z1Q_u`hV%y8|CSr^)?#KdeE)!qLN)E_tl=wPwQl zepbp|x$^TzAVQS2UKL>ZO8E7S5x})#1mis)rhpo43J{|A7RU(z?phSUtVF+Gh^h3O zsYYB}9eN|C;0?Abj*4KfGitGQdiOLz~S?w?2eU1Ys?JS%|#Ak2GIv z$SwS%of36EoS+pH*C#v#3XVL!Fz$RT|3^j>oqQff#Cy#;q7G#-w+S}i?)z$57hg^9 zHQ~FvJ6G~Z<=Va*&rW6Eg@pX}a`$665cVsoF=;5Gs)hey;a}7`d{8vKV92!mTI>Q2 zEvOFG5YhB=%=)D|B-#Kv*J@!zQH5QL48W=Y+`X=7>PeJR;Cdm3fSK%Wtk=I7Q@*08 z4k7*t@|WOI>o6J`N5D+NduXHi-i;LQhBAVS!#hQ3rhOZom24OhcaH zQX8i0>pOV*@54C+pS~z^eTyafXm1rLvuws~1Ltxz7Hz3s^U|0)Xy`XOy&{_AD)nwgk}+P}hnf@=%Ym&Q>gOQ^gHBcFv2nAPQIE{(S| z`=eUi?*bNlfD=8sVJ*mnoEem11*U2Atf5^7CZ}Iwg73>ebLp;O{ z+ViwoxN4S@i3QG;>dvaC;WoTj6{4c z*zwi$)OQ9z+yoIhw3bZl`25qcfe||{Tn2E(`w5G}N6W?Vrusdo(Gi-GUq%SYVa|hS zc65c{hyy%*o;08+?3F*}jbQztUQ)R%OrEaG5)!eS#H8js)B(LPf zn{e011D~jpI2uEP1us?s41~g)`y!1yb?&jhjAJ+x?Wi|&l2)dcFzm>PO^&-)6F=du zT+_KLE7-R}VJ8W4(1huC!R*RYJHM{v7H&8C)8&3C4I4KQo*u_ogF5C$KLy_?D_0r= z3W!MJYfv51G%rVW*+Ley*v6BYcyAhrPO10&eo^|{vcKfg(PmuX4E}|qOQgizE*3@( z0i>WR)z;~X3!vUK%Hf_cl)&v@x5OM2jw%6UXcbymK0eCbHeS(5D5-mM{bo+4^I>AOeTWW|Y66chLr#O4nbuE_PUY~BRk7r-PauEluC0?J~ zn~J-+%K9|@$Wnh5<8Eb2O6ToDv8Hd~41OQ=6=dmcOu@T?O-us6f*s-XC*+xZU6vS+ zSI@x8z^tP$`TDf1=dLnhumpMHaSk<>h9JSJ$}_hGl^z?)^Gr6rQir^CHMZ6`9V4VS z{Bpx?Xy)Ni%Rmh;jMb^oy-k$bs!WHEQI(D zK_hjw4k_D<+uJ8>K2=g|KTj$0qBtDVnYW5MX-YF23f}1 zIqJc5A@jRj?b~}wGiB!uR_J&eH@2;zHS;*uGQ{^HgZvFy7RYh4y;Z)#_F^mhZV70^ zMZQ@gx86@ZK(|%R2TQ??D@{`QiCF^!?rkgyfocnVrx>u24qyI3?u?P*i3f`?_hX+N z-raVMD|Ai*SoR5)yhKsn>m|{^d1rg-l}9tI{o}Eq0qo0(8-6$b)jMy+AX?X!g`-9~ z{9X(Ht^g9<+W@0$9h$65+E`V9btP0Z9jQ>2(tQ}~n>2~D*y!F1wEWW+T?$^CmW3+E z%Ep4gXKR`9-axXCx@J(noIim@U8 zayb8MHV$I|_HV~w&f~45&I@P5g-oL-H9)~HqRQiTSA1@FWDro(xwT*hyRJ#Du^gE* z*elZQet?OwsIc$hkj*^tW1HC?)M~ojbR{ZY5z=v1dL}o-d0{6ezBxeOM9KN zN!dO>e0jXy?p%+7cqNNA#&t@xY0%DFU<>vfLbnW)_X{cpO}Cu-K2`c_>@em(r~0)(qP5+sztGe z&oY!9nx#!_CSoqVA zY!hW-BUX@;9tBEVtL1(PM;S<%Cx}ShfGfDX+KkkPjkcQl3q$C(Mosdza!4wE@E)GQ z^jgWlt%S9g@lJmVb+=TK*0?}emcQp^n;NaQU3;x=>njqK(i`4BXpv*&nI}R3#dLC2 za5tO&mL*v1UBON+)mIp;p7$j9nn*>;u+AI}-(w6qO;0|Ie*XBCP=apjCtud*YB_s< zWKSg{7}CjUuhJk>tcdfm-dd_kAMsBV??cPO#mk3lIyLT`*`yEOF=csm#GX>a#dh<( zcL2vC^3dvhbKC|c0u@gdVN{VIK$r}?1w&#%iT187Emy9Jh<_$lZD+<@&i^a-`pV&e zao@kL{K)DqZCtr1lUrWBVX#pw?&!SnLn;@N%jCL*5Nn8$hxRG+*`v(#)i^PkxmVL7 z+RJSJF-v*h>=0dAJiWC3+@FK(iGJIMR`!##e;`KF(+kLR{v^1WJ=P;?gsPP&aYVGME}{XH&&;gh>8~BT*j^1t-o^ni5|p$qt%`BOdKxlkFvUcb5CAh z&+8Hx&zsv-BOm@0G|vKFg;h%A#~=(@iEV(>D-03>%}dN%Uq)k)fWtOmwS~l<#Au5X z6C#F|8rLSGkm8c-*QUA zcJ{n~_B*&BAV39+#z?d5?rR+;`y{C9s=)0C3vLO{Xsut+P=^3c9hSB>>LYh>G1m@_ zSvS!xEf`jMZ)qH3DZ=9OaKLF#yz+tO?sK0Yt$bvnbCaEW`=SAEp)F;^+Z z9GijgZn@#UTu51quHfqEt$SwaWSlE%xNT^~fOzWX=n=CBWsEq*2$sxU5+`nrB-L{t z%coXIpW$rulu!KtA0rfuyQrqL*=Z#d>RE6Ckp#js)E(H^RKjWt*mu{F%38Iy#&ab_ zlrkt_r2@Pa@|$9brr5GqZjdA#KY^VL7c6MgSjCJR>%U>8@3Q5?6c^fgf!K^#Pl>+D zuT}GpjICp+;IsI)2?}`f?JveF)^OYXnuJUr#vHr8ko5`}o(`cLmIfigIrk^A@1?`r z!@C7?{nK|OI9BVD0qGKZmdb8*Y5E&Rlap+TgmHX@-CQB+4Kgr}sm`d}gk*-kz-9HI z7rJ)-XOU;HwdV$@q7N${0;d8W!PIsrP)e1T^li9g(J*O3oZ7ht+jF@bc14Wn(uy>?@=qT-qc>>tn|_*ELQ39fxg8CThev{Sw$XZtcQ%o)(h&G;FGqBZ^b(Pmj!^5&+*-lz24&PJ{n$Wxgvz~rix0hH9FNS8i=L_ zFhzN1(HH>Yi5W|-K>E5tZl^l*x2R#d%w=os zm~!)c$f|3mJ4FUu!2ORm7SOU2Uu-P}dzd;Vv0v9XjoSm2!$P3Kc9s4G5gK46A zpl+@aMtyhLa9*^aqidDZ!uL$LY3USLatcG8?ypktu%CEnmk8XYmNCZDf0=1|KXPz` zNpe7dK~A>s-pKXF8OM3O_3Kjp@=CE<=7OK(?xb3d`D(`nN6_R7g?su|9{bQYz_rRR zo<8``Yj>5Fj`{wojOZ2NXoN-VK!X)T_&YF!C;I7PN0C?M`io0^+Pym;I64=mJI-x* zGThakqY#R&OsWn}W;H0=U0$@_%22r{VA*A9oF49!$}i#f=~;^hP)z}9@xbdG&ve6; zs#n9%Ve{mdSY0_(7o}uQ%s{!PXcc?};4B;%#2XPEvK?ksq?rKF37Y8tR z!CQJnqj00ZvyFa`yer`D*BL)}7uE@Nq%1M~zR(n11Uh|dRT*8sGR!H-C~;bHu96(u zZ&4CeGh3CW2STyejFMT76o&;J7@?8mY1x81>+22)A1I>H7yrl*n4f4hEL$ZTKT1`$ zP&zjf#uYuE#5aQu|CXtiy)~oHk!fx3BqT&a_&60p5Spf!wFCvJz*h~A116EqFkYxY ze`JvVfJZ^$eES%d$;YK?=|5^tGC4;QOl%}IFPbyHYH+3AacBZ2;&qi#?GPuCXv*u_ zJcMovcdq&p)@i1vylat;q-+DTFe2T>6g{tnOkah63L+~`w_QE3eABTm-+o3WcM4z^ zhE%1y!B3J#K@9{qI?ho%GP%`!v`KeNkC?TR>NN%+@_4|F#?7o z%0Aff-T;(WFl~QgKe^R?T0%sph9Qx)f16(v-6!g;$7R0_3cP!1H*I4SMStb(&x+jD zld<_|SCocFkHnmKR{S+KSt7U+-4c++7N=qy_g*5R0S(Dki%G>9p1G1R&{*+)u5F#CpIK%JPXzi`f!)D!3`+E%v;ghqQAXvHNHsod1 z+xX~|@ASWeStFYtHQnfE#gW<;a$VPprdM)*v^vPm4%EQZV&~ATSk@QLcQT0%Ra-06~3nE>}K_ zbY9O`d*(wP)6%Zbey~~WFuxhIo5hJEdBObF3ki}UWsbFoGM~LQ`=uB5c0k#jc>Q^= z&m&%>kH%h$_(Aa8r1s}2`QK`QTLuv4bL?jK!}sS5@NYoA=SgY2qYg=Q6lm&uLg$Bg zpU#!8)lq{pD9oCN83r;oz@yiR0W-?fdAydM47}M5L=CHOyhuXtCnIa1jpkZMi|#Tn zHe`miN;qv}XFW^xUMkBXP*dIs zY1GQBd%$jhFchU9nc~eAMJ@(GqdKfJ5R7@L+ytSHI|gL}OhSv$t;#y4`ss5wv86V) zM|rvfx(n2R!q^`As2JoK6bRD>(-(C-^Xh|})gPcjn7*hnKl@g&fdlR91+>U=f4zS8 zC$CS6p#kyV1FBAoWs^Bb*aGt5ZD8k$gI+e+pXMZ`1Tup#=O z$2E2GNif@U+N&+vCbuA{j%pmc+Unlcc*CH0deIO^zGnh3|G`LL*_UZ6a}`|2Dni4*O<3~y@fw=q1=1@#jYPAO4MxZ zN;MX7E^0?r?ZO8_^I-{llVnU}I9AXPSWDXaZ%TU;YSZV;gFDU0zD(LXJBD>{&NlAz>8OUevnqf!M1oPXiDIlD8eWa6TeQ{=NlN z$Jz?d%QC2sK*#=Vct6Aw$mL~)a4$YPUb&~Av+@@*(EUdnxkRQ2O^;M**8{ZEhg@x7 zc7yw1l?gHYZ1s4t>*R5jiDhF|DOl*M9Y!t z>0*GqPmIj}W9qHLqWZq}VY<7Kl9cWS0qO2;qy!O$?ilGty1P3>8ioOhp&O)21e6p3 zL3z*k`98nv{gVrZGc)I`weH$`e{kRjqB2K_=g9LAxr47~{HPmkesO&y?{t9@fy*rq zzHkp*e8{Gp(w8M!=?sryz$IQ`&-U$7uteur4r0!qIM# z-DGzb3|F1;feamQd_VbooCW;;D6{MrXh|Isv6%@zl+)9`uva03UebGO=YpGSL zvX9ZJ1v2@cmDYG`4nS3?WD*`fb)-8J$WHlJ5gPi}!c4?MmcZ`)bLJ2_3M~iO!d3J_ z>X@Mx_@_LjZDM;O0U~#ZSOj@|hB+-Bylx(#r!N?CW0M;W^=Xr(-jHgQTRs7?SkF5Q1~M>ixdN@vW;VrxJX^{S^o)c^R$jv)X<=0PQc3XmGe zHaL%Pz-fB~OZuHu0Q@d)N9)D7Hv-`%`C@|AH+y)f8?l{$^B$TkT6?Mp518!B%5o1= zDEPd*7I`1l-T9KlTPn-o!y@H-aqG}x=Yu|Ti4=U@KHz!eK{tN`Y$=LTtZ|VxgmrJf zM53ltFay`){M%U25w}xB)lyR3Z%T>Gr~q6GXL-8{oFwK9`><}J9^n)9p0qd1uM?cG zL|a^I|FFRelA*?M_|q5N2bo0^^Cz7`T{imrmpaS+dF|7BVZKMSAycM~jtNVapv4ZR zTtU434wPQ1KV~KFnHZSHjQav`UzA75>wFge_?_;ES&vOywYh*jp6k50izEN+n=G&D z$Z!%iw7Ud#rl+mpYHyiirrH3~LfuHqz2gh~XtxJd_s!&OT`(4!514m-v1~#WpMZ`p z!K~Yjce%@Jryd%(S-4P2c<==y>A&J50x!c}yQrIG#EPY8o`%!J)xO*&kE@CU$`&&r- zwz+A>I}LUNo9Ts!4$6m*+YM~t_PR8qb()P>cY7?s5lV))%?j2h@Qm7t>Qddz1wJv1IQo6)^h$_{w6JIY2Z{Bp?-J z{FQJN1b|xepKy$kvTHrTi^gaA8aSdSl_Jtzl;EK7H$yY!Du#=U%croZU7rvm-~M;; z>;v%L^ScnRRHn#@-*2#B*rR7eBh1*;Q-9BUP94Nwf$SU8Nhv^}2j2Z3Hl+nNRBdYj zjFy-C|C`Si!im&MJ_WpiM8PstrCez5qBkaN!=1wG;-{H4*q;%B&_FC8vbBLcf5<*$ z6Y|obzMie6iXq{cfuE=11Ne>?PAk{EQ`i4lE#DQ&gXMs6ZAk0L3XdedCq~4f#VHYT zsP|(Y+WaTWw{@TK0dZry1Z-RfL`LunURS}+n#$oXrPCs-T!4Q{LlcC2CkRR&esQY$ z;}Vz=ALZMoKX+1RBf9X}+B`q0-T!6&FHRuAoa@aE!X05sV4*a^k9(~(&aN9|07^`F zi_fv+8T{i~=ImuB?kfM4W#z9G?~JQ*2g*lw#w25N=TJbbKV65D#gRMA5kUdxx2pB8 zwL%8qn>PSd=@-GpC|KAUc|>uTU7D%JjYG>hX;8NHn#bSm>gS8M`#yF&!ycPVKq8b# znwL@Wm!n|R9LWU8|3)wn5V?`30NZDLecAx)jvqSqM;(F^F)19vsFG7o3|hTyW8GChwFY1Zrk@F9i>yQ>s0aa;TP}2)`$v-2Bxv^bV37P z{;^X<_lcW9Dncw2*k3p6&^^sd+wOUg5_*ET1tfY*5sse2#aWu%sYowYQ-Xy5z#XI3i|H=fH02Yl9SJ@PA!CPM9I4`RpsL|4;9+`z zi%H&1jSm;hic|@MqJ$J!b_Aj6E$&B%Nqj9K&Aor&iGZL0zy&StRVd?}asv~hwV}bZ zCwt2^v4*vHS+ZMVD6DGOJ`KnhOx$pFEfmv|xzxt5Pr_Gj{Qd;DHgUv|M0H0#T%4>B z+D%yb^d~=I0#-y|`kyLPmrOsH2#|yYG$eQg+Xuu>?}+4hfJJ+YSSVs!u~SH3c$B;o zvW>xemkva(?m#RYW~MJQTx#sTBrKH}lMzqgo2Z$EaxJ;LO#!9JE~xoU*ZSo%Kk2o^ zn{@(wY~kz{ol?Lh_5C4u8YB3T>H?l7oc^Jn>Rvf)(v_$c=^$ChYi6F!GNrF9)Fxd6foKp zOVvj{+o2~FWxAiraHD?X`O32ZEGclFusnSNou|~H54D>EgF_kJ+?ki0HMJ9W|Hzwp zV>gtpz!O>J|HkY@F*DBHyfte>qw=wAtoShOJr4OFm#97p@5;un%-*^Pb@o9$jl+$x z;xiJ!NjX5m0XV}ONFOvQ7L49#0Ct@zYd_~cHbP8L0&Y9A&!gF&m%#GgVDUBF1g9Ne zyZD-QrZ3{iw8pxxd2WY8<4;52xvs;ow;Ge^TUX`I2%|g+>ru1`U%TV&Vo3%VC03Zi zg(J-^jhx?>CJE0@X*sK-IrC|@yExq}0ZA3p#V)kGu7+o+D}&dtt-w$Yz|V0As;(S9 z`#$c{cn*k_G$TXp?rQP{sKuo!(d;{~V)IT^e-P^&`AdAQ5@aM%;}t#}x?jmywJMul z+=QoB+>l4977u`?HT*Qa$yT>wsW6li*_r-*R|p^b?~A51s#>@-eiSGHCy^n!JlXDD z!`Kc%`+%+7>vHv@3()Q45{SaD?bVTgA=C19e%|>Cex!W;|8sU{9TdGg3#^s^=E{&H zQv81^e|7>NrjGir^R4Um?PwfRZzv}Z7gIK0JhNlP`>Z}OO*cYt`&!U6VHc& zg*qT_y1>JiDp-bOtB+xe1dKD1kzG6KAp}XsW_psmsnvv4Y6>cRwgY#oCok8FPB>#g zdED9=$?deD^e)`u?J$W(A2AJIYG)2wT><5v4!|3RBDGf3zJ0GWuy)B$`l4||uMn9Q zm3DCT`Tp)Zo)#Nk8txxJYI4gjl9 z$8N~(jgG+bg(Ug-STUiBU-AFSxC#(`a01Dr&&g(uF@lVSKkmn* z2O0V=2j+vk;wp?-sP?P!TsXWv#-OBypVRJekL}aTlio&OeL$Hl@6sOOY^6FZBojoT z7g^*`Qsftilsojr3bT9CL&$PjdnfV024!6QuCE0DhWA`RX^`6mLWp1@;0zL|I5@e zaVli)3-hWe4hyAn;um=t%u;3jY8@!iI|C+n`teE6KY#sLC_Zqd9E__s-kxTVBNpb| zYqE?>P6UUZXFAjxZ9FF&5cnlB*E+rqK1XgU*)Yv#4!xEzax>O#R5{07iA`w&;a>1- zA9Sa4=5ah-NdWumcxC0Q7BGXzL9sFhDE+ORdcwa8>Rxb}HjsC7bAW|0K^9gVFURW^ z*GWUzWF2&(>Mtc`TE=jXZ?&&-^C;W)(44L%l8?6@RV)0LTW2GJ!x zNhtH(2<|Z9>8jJxLG{-evuSNisR^iR? zq1xvh$u~#)0a~xX;u75UA26g1?2X(r6K*B+Leq>&iVSyeEqZfGJJ~t8$I~lb5>5Uz zxjzhW7`DlS=BKLHTuJAh^{tM(C@K*;ZayQ~vp6p(^`xkNs zjq+@s8BN@I95*3HC%D)X-tYHQ@Hdcfi0*-w7h#DpAK} z&3t$laujbQ678k^o?m0fV+V_n+rS=SYvl7W~827@FukR`Ak``wt&uE98Iht93r#B|TFBZ!cW25gi@MOdgpAZ*Hab2-kv1ew(z zspGZCp!6HCnubWw{dO6ZJ;%gLUSIj&Q8f#BShYf{6gEHU1K39(f8C!4hM^VHuFlWt z?0&qIoisP%9r;; z+EP<+5RNb;kW!rP{fRYFTq{x8B~|iQps_@>)Hx(I@;^+l^Z5eH02X?yKM~M`Ng>l) z^j<;Y5negTRFjq{rhoY>HCHMPtC<&k0p*M|Va<_I_0pBikTG~Zb^={%T{+LM^d-@M zd$DvYx`N5O1|G*qGZ3Q_rSDc@Y&OZ5LYfhWekD}twHqa^d_ir;KSSzA9xW}HgTCwb zIp->Kz)8bxtZw$2@UO-$+72h7Pt8>d)XFs19}07SDC}i_sj=S0(5*azV~sRdWK(*$ z6mAY2rr0%q;->2iO|02#}J z{Ug@j1;UtcH*q1#LIuF-tFy=i@FBBaZIu}A*NKuptR(dQep$OL2 zUTq{g@8?3bP~|hiFp#y+TwQkuzHfLxeK4!pHtY=cB4Ydv^`FaE{nH2uWmD%GPj~z? z?J4NWzOrZ+{e;{a)GQzslXF3{>^0L5srKbxxmQ4?QK`!^a)2&|8K)^$)}olmht!bWRkE{=Jmx>UA!FMbC) zaA@n~vvu4TR8=XElRj}kKZ6mn$fh$D2Lvc>r8q+q@!Z$NR!CW}5|pxIM6%xDSgts5 zT)byB(_h7r)QUKYZ_4-)@)f@6&2RoESZx_uy`NOA-9XLl+^s2+!Fits>N?p8*dX|$42dI3iH zenz4uO6oCd5#gs8wLbAhr!X$&w(`N5NfxQY`sH0Bn{M&RZy)d8WA~P;;>tG2`)zR3 zjt(HR@M)oMA<@1vp6ks@=`*^~xX%#hES-$WG@3!2M%W_uBdS;?buRt9|LgbX>hMRG ze#~^ndW?Me3JvSCmtq+K;gBZ;HZ0V#v^#Gr*0EzQ>{=nQ=H&ait27f}b!_Xe=L)w| zsUm--9TWIA>8o@dF&{-hAE1m7fV>3N*JY-^oqxcK#1cW=W}Qx_yDz92dbcFr*`9$b zqvt8m_PRx%wL{k^j<=juuJKAjE!xbj??z$8d*)I?Nz#-0s3P#Z?^e!!5WCj9dSRrX zbR)^PpLv%+Bw1dX2psH(P4o^$cu$vHG~)=r{k&;Q?DJ92sXs;NM?4C3ri(eZiH>&-(SkzU?{vX>wNy|k7073NKi!WLDXuktiMXs#vDhoKSdXP zAJU;tgujIs~>Lr;{YGGBXt#%FY2kh@N8XCN7TtW{pxy~8qbSfz@ubsLw z0?1O(4-j5pO4h2{cw&df&g~x&gC&4-q1a(OL*tJ@_v-%ZM{j~nfjZXJ&1Qj0_P+nx zb~(~$#86K`VdLG)=TsSFwb4&zjhhBrQr1aI>ZBwNA}tONtMjLEqm-s7JycSs|Rs1Hda ze$)zf<0WFM+S*hK-q*#I-uzz{;1?78b1yUi;H0xH5nIsIvH_NXRJE5eD^(@i(7A{L z)hD0M5_z0{8=z#FQK%@oK}7>Ys9I#L`3)Y`J6Y|= zxWec@JZ7q0{+*YR&ejSZM4|Un>i(nW314?SY6TN{1+**UQ&1C-wn&ZZw3%g>#@Z!q z<7+-w0%dxD#P_=H#j&mD7Lx{LM@H4&8Hv5VUkb5zj!YwIVpOa5s*gNRDqU zhn!1VWSG_D$e=>Y_i&DhQIk5hLmnp5STt1Cw6ty|RLyJa>TIvSPT}5ec+TV?prW1# zY96*B`C^x!pc7N#t3LnE-i{X(V#j}DVM1abs`Jglckp6&^jRqcGXqMrg2z)4oKr}CY2_MS3hNm(s5_x1rEOkkefDL#LT z2)gf^YVMNBEo0nEGA9IIy9Ynpho+MngaKAF`ZbOOS|6+_)% zzkd%TB5?oF8s0w`5^qm${SU=;X{0b8B`j?`7%$LY$d1pywXYjE-W&Zu zCP`lHkujP%l@WSR-L5rOH@~pKOUW=PmxGI=;G|tmRIRF72^}%IYqC|hJbLZy-l?2{ z=(q3RF;|n_T@l$$Dl+!)w=xMIn|5vi`4u-=mY0z-c{U;r>eefNLzNv(1bXhu$;V$A5x#(9~Ps8o~ro&5!%f=eO~ z1LF3ZNjs}V_4@lxZ64V_W9=>-_fc>JeEW^qeu;+6;7t?<2_hy&2btrT)gJ&U0eB@YZA_Nb z6?Iy{xC-XB$)uV!lO7y$B+$nrQcfp#FL3dBPyId;Xd8TAl>rcyA|CT$&yRVTJAu@O zlN+dMgrP7QuWQ5J!L~%KM2vO!wKGw{+Ii7g`_ZPaz#gVrz||A@Mh~B-iLoH#sUq)X zgvROi0KCSpNXAYwnl(L0$-014H5U&)jM|c~siQHu)k(6vBCx@)WKisTux^rcS6WPe z#CZ2wZ;Mn)Y*5d?!sJd<$Zq77+wriDfl7m`P@MH^-Z|~o^y@l1bQ_&9iYp=qneU`Q z>>&@e`l1))FO>b^ozYj(^9?}dWFa<{z?S5yJ9ax$H*@cEM5)O|EKz5?%*ji1>3zVl5{c_b|r@ ztGa6GD$5p??dvV{iluGTX{Eb1;;(s^#z6oz^)$FchJ8he*4oIUfBGpwEMr-*)p(&s z$RE#dm$>cUEpOl<*UO}8uag%u*rdfoGT^&wt%r6K%szbC-c7Vq8FfuW`U;Xq(-{qJ|DjNgf) z@FEMj>u4o@)k$8f>uPNbh((ZFMbzk(R87?Wcv=1QZTB_`8TjzwtX1TW;|W`Sy>e`< z+K!|8v}i2MQC$}u*LKN8{z*(d`p7jk8>m4h85LYyoUzew{os^u+0YfeKS^ZzS14Nd zqh#Ue!j^6&BN5RZCrE-(@o}gU0fVWXk_Q4kqs^A1IB~4Gij}PR;#^d#nyTLpEWpU zWXk7}72opyi3wqPPWa}PKY+8fPpEAsw)$L>qJt~?i-BR>V=AT;d0acW6W%0EV_Oau zCv*Iy(Jl_ zJuvWKhQ5wWMm$FdmA%`qZeLtQJ^9Prp*w)|h_IV>X*lbea2$Fi@<#TKOVd5w=7A>; zV+b`$!RT0$O8JLZ+Dn;mSz?&$ai`4Q><*R&bDLA^U!ne1yQfoPEL@^F z;UoOQl1$V+#S(HQ68dDV_mrYn;iMU1g4L$oh^C3OrEUB|n^D$aj#~K3-$L*k#Qs!n z?&A|)M0*BaT2PpSHI=1}bpbTfS|ShYXo4!lLAZq{G@Rw*z_}g>+dl^PE2%0Ec zhHldP?&N=^SU!kT`B9l&$%-59ruo4SFF!}jD18*7hcXKL_Z}TY2&$zQAv1!DSeP%< z{+iDB0_D^NYmgD1MU#9k>#h^Ecux)Nf|;cDPhdJsV-GU2riK=V&0)jMd+gTR5sz_qc7_Y6A+ z2jj=DZcQI8AFeZi-8A3tF??i1nfsIW9AD#&+t$QRW9GiGPW3ULq2cBL@PeS$R_BGy zfR=jk0o`Z?Yl#%Ie74)$pZheLK;x*mcp5&eE$wQZp5at#Z8q0(r=~^VHnMkD$>hA1 z0KP`NiJ5aEvq1b`$a58TagsEiLTmqVaQIr8YH=HpxU<)U~Ym zawJboD!L%{<41$e4jyWrTjn{BM>dEzgLxH<$(mFCj{WzL&|RLKI4kDY8V|-4 z=J$2n95m7B2TZb&dgYtv2`#m7FuUG~kaf&%UIOZZ)cEbcT*i8QxpxKZoZOda@CZTN zzjr{E(|JZxi&C4KTJx=G1^thYT27KOjt3ZuDypv7g`qsO?s%64RZMq85k^Z-j5HBk z?VNBeWyf9y8A1+UlX8RR(#vUQ4V8JOVLZ&pdtoFA(FtIv__vkstXpxyF)i4-81 zr)Hia9f|YZ$UyJ*;ALYJvvAb6GrEr28(DqB7yLDMZ4G5Army%o~(-!P%>XSvv<;C zaG0!B#8G#aVpOxju~D~E92ERBAoH_r?Dc!4pFgcrP$7<`$jv_NkC@TYnUf!IrA7t% zm_*8NF*p+-llGLYTj!Dh(oG|4nkR<7ic+#RuF8110HVahkrPF3O2MSL8$~vFtB47ZUqEtkd_1%b%~91UjWC;FJUnb(LK_!hXDur9mPfEVYNXCQvSe0Nv&SV5?ImUdxCntO?+d zra*y%A^@X|WZN$3m?mBXTXSBFhD{VidLG&jw0UR2@nHlnK9U}alvz3($De60vvxe! zclO~JO+Pj#gj&4*GW@>TsJXaLRW~{Dr3LPsiM_pjgltJv;91wvKW?b@YhOfnceM`ZiN1CL7u4KT04gxrH1Jbu^}WYI5N`1X@wCJjUGIn2D+=e88h=)mC#u-Int!fEW$_m8-_ zJAdOn4SHWYqjQT|OPVt_tH3p8W~hLVMQGRb(q!$tOb zj_LH!yS!!i+#I1G#{QMX0|kL?9s-HILMd-B3xv0k=a8H$O3I`GfrrbjVQ&%?5g2X6r1bOy#NTWW21d*@7G9kUOuCcwtB+;h z2}%Y5*=%*bg-4%X?O9MT61*FTRZE!};%;HtfDQYx9;+bN44fvp^jd&}QFRdYQ!Ht}`R2paUqzNvBufo`^JrEi#bJ;efvbO+J>fgN*`9K(p%M-;hWtd zjy29Ko+P?Hn|`~X-dp66*K$gOh^oS%ms|a|eXJZHRt{K-coE}B#)c|zk{Lg+oUa?& zp~l}SU5K7Ws{$vpoeJrBVI@dQm)gy*6OOmVfs>~qegFJOepde6679hu%lWl4`v59g z+|_0&C)caB()cq&U%}3b>)X^1*?x|r}m(xz$ zRIwLnhbyqRz^r!#x?`lgtIQbTd4Mxxvw6g!0_9cQ_I*-L?LkB*TBn>fZL`Ym+0OXm z;52q%>5=%?+SJI~FUa+zCDd70rJVlLGeLdKJ^JY7cs7PV#g|9Hh!5n}xL2d4CRg3t zl(rhv&NSSFm32cnI+e(2i0FV={Hlhu#NoiSuqCoe8sw>r&dj#{3UVobT4-m-$*ZTJb2+E zgxeDO@O!03cV%9-Ad&7rKs!Rs3P7+N2^ipmw< zN~H0P{8Rv*a|-@!n`d@7+_w6Z;2~ulMUDgl3e5az^anAU9id1?bf4N*wMa!BA2GZh z)AiNAe;;}sUI+rcDSOKo{!MqPlhM;Ck8*HHg=-=YDpV6z_za6%HpenwasaePPLHw) z>Sf@7V6=z3>W_a&8SyN_lp|ayy0zFeE&QFjyqMLlWcoD$%MJ})n6GPtWyFz1RsfRZ zc|;9QE{8;L!n@bnuiDXk+dZcLZX3aVeuGUD?l2pi-x?sCxV-AVYyO8hu64dLs-r@& zl4Gwx&&O(^YxCa#((3g~>rIpi!z2RBPJu`OS#@i0;%ZB|dD@nDC$&w#U)tYj#HMQP zsEN3_Q~&uSn(k3(N)l0)TU<(A^PEnJ=fcvNd zYDSz`$M%f?7tqVH9}AFfgJWFrFF?_nXgA2Ett)?b?n)w!%%!!pU-}cDVKDlFqfU6U zAq!UPDfhdGb^9$o|JQz#D+ev9<&pz~W2a|doxoX&EFTPb^`IdKqN%+eG&Okm2w6y0 zY|}egE!}>WUYZbwUR1>BTJ4C7vQ)9w^>dd^E}rt^Mzwy7B19qrTC_8|3}pqYKb8{D z;4>l>mWX79$WpwxcTu({Rv))?K5+(=KeDcF4sD;}HD7PbOSk9xb*=1d>L#IVE~3D4 zVkT(OUQ2d=RgfJunmO3$7YSOSK?zv}H^mNLkJOXRzeg+r+W;7nYJE)>465OPS-2#{ zY=`Y}+dEw`_K)d+xVQ2%J9Iu(%M~D-nP&xvCQKzRJ$hWXB36wIL2ye@v-T(zmKivU+NQ3~#goy+{`va%#}0T+O200x@0Qc7 z*m{1U_grCjI@2NKKQG@%Ya&>FR5=9)uuDxK*6C=&W|&e)q!avh(SVC}8IPwKEN>%= z(D+G~3Yfpba7*futV$Hd>#ZV30iapsq0J}%BZDr4UkJEZ8mv7ErA0%oJ<4`K75*$t zdiB7%pyLoTq)>~4kgFr?n@)!Q#n?>LYU@Ix=~xV%EnN}_B4iF?>36|w0SkU0D9QPE zGu*%P7Mn0&!BYSBQT5!o*Rw1T9ExxQbix4K<_fz^!MkT0!|BM|Jp`3I7G7?;)x_00 z70WESpZouzM4v{*YkTr z4sIcgPyp3*02jt9E0!rJSjbM82r{}80bfF>0QofzOlbJz-1zZ#fxt3X{bD@QMcKD@ z7{3v#aV8tppXtL6GnkjWEK(6F8KUFf54|n&H&v@iMu~haZ$h2guV^AZ)N;On6kKXo zwpYsvnC~V-us>iFUG#9WHt9Z<^Xi#%$5rTF^r|-K*?YQYa$X2TXBgbppRv|S85)u} z2P6PL@faG?6xG*%@#?T-t+Rv&JH%Y{c1u!my2`3(k3et{-~hKaOb6`4eOz}`51=cv zj0bQBO*B>3^aqU)M{%-$Gc+~Y2$Wwd>#lu&4pn!$k}&gy!^6*q4$tvL<3+`Ja;<8H zptAj}@!%2>vkTz|8U3e?B@~#lcn{3EZ5}H(4qoBTOXIpG1|ShvQJxT0%q7caO}= zp=beW)2bTuv1&AKL7xHk5(buOgXsBTS1x@N)H}U}dIoF28`4ueThdTQtvRAO9uAr% zYOQ>AoV?%S$ihuNKoh8QVQYlSN^sh8k|-p~*FFAM*A7q+-QT?2Urs6f!eai7mAr-@ zHT%7hht@|<*YG+Qnbp}7UB}2D|53%CdbO!^dp|J}bnPSjJ}=lRP&B~a^zO%`No>C6 zX{NF7fz+MM#!UFEl;{k(+y?f3;2XKC0d6{t9^m}~GQ3LfufD^qV~BFf5=L1p$p5mv zb@N<(#7n}U%bs+Im>ADgF_;BpTGfzO`Z5}~RIvJ@wbMl}xwOiZ z0$U;Nk7+gAkzic8e)!AZc?=Y*s!t9fxK2JBvwXi{*pTNU0_$|q-a>`Nj8La&Ki4*; zO;?ZU0~YBtS+-R^o7O!LzOdcX0lu=B-f56G1+XJy1R+-0g_NTFlOzqOR3tX$B9}d} z_Pa+!L1XI>m?feBOJi#4d+VzfxXg3QUcJ22XgIB7)6Fh$krY0IT5e1KqF6JdJCm$1 zZY4f{B<~_-0_T!t%^Xi1Nq(0Z?9Ffg5qG#>^Pc0(kd1d2C7&FU=wQ4oNYMpJt?Kdbf4hD3+sI*?`kjiz)nJ zMel?f@T2g9V;OpzVEZ!mG8m)|WAPzJf=WE5mch(WQb-2SwnjXWlIt$~iW8sZ*==O18|#&T-Hv1+3V6By6O~qhr6KB6~Ri!@T1OV)S=MAbqy@s#F zmBJlPN^!Gd`hz0#bqd$}Hwm#q@LY)<2Dbh^8K{p(Oh)G)|C1_uKnZL97M;{;IC%+Q~j z@fccY`O~&f^3`m)LyCFmw>D}pq2u6aHT^E#2oBOp#PACkJuNydHmd=gU>B8*RD7=c z8L^B&te_nIhwcagu^4qVPUKTP@W}W?JD$M<6l&Db`phE3Ijm_4o!XJuI>2s>N*${$ z1KD3}!aH4>-;?}fg|@$w;s5Cu$~;LFHqMZJC-xBaRCr3sZRwCBAmw!a$JMf^d2PgJ9>DY#7~lx*xW0$8YBM;ARU@1at(RfIo5t^DgHI zQj4Ir=1_g*&Vv7|1I+eMB02D&ZuH1F-fI{s!0AP;M_)$NLfu*WD{jn9wrSW9Znl0$ z3^PC~VuPh;ggEk#WdDW3>gH%0Li==9Mho93SPdhgVoXQwiIX3;l9wOVD(d$n%la=B zbFyz^FHFrMXvT-`9Ct~aZVy!`fp5m$`c*rgw`tBEtAIJZg|#?v$Ran4#k*RrCJiHb z9oBxy0faMR<+H&en2ziq%oLqmW@f|;K3WFXf+gv-Qb`%^B*yUN*B4Oiu(sF z^5RJE-+Fni9tN08u~=gI%kT1`!=NxmIBx}1p4$HxD$HQDvdU%FdMK#l0o*>s8n#Jd zdaK=M#VV2Lo4g8e>+qk*)A)_G0j<9QhRIISWfRi*XzD+8?lQ{Wp{q5_0R-S+TnZ*v zcnW3q(CFX25@)wE7G38_>vUR$XQ1AheaM4&?mDe&&wg;?>%Mw% zvVPy51^0n1K1;*Rv?dYiNAH)5!M=|V?gK1Je)(lYfK&SNk7rPG(Jo%}gP8P}cjAtc zx$p4We}LDikMBpX0_A*a@RT(U>99h9Tm#R|ur0NUYh(!S?gIuL$8-w6G(WW_U|~f) z50w|wO8*ReG>HKLZ-c7TlO`lKc9PNG?$_Xd*(6sqkFYcpTJPPznGS~aov*fTCAKfe zOlsIP`HKt>eRhI+TQ_8@61PdGvu+=!SJvV8Qbaup<64_PO#iUq4e`KqVKjwr%_m(d+q#QFrjgG={=JBpFlGB zwU19pi1Mh?P7iC5tZ@@;MUB7W%ei?7ynVyxr<)86r`Moo=5t`fw&GeTo;RM0 zyTyr_X?6S!`28hZ8&7=bREjVMOT_UX(!xVl31Xe_{s&6gC8SUs{mdQPIQ*;+AsU|aSBs$wDzPpf2bnL~{^PCNd?v5bkG;}WWz%E}WD?oiUHPdp0gqQoNto||fO(l5 zp-NulUOBeCTk0}9K^>T?O)q-|qtdZrWPUjPCvyM$4>nZZ9WpcoN4_(M@1pEca zEWP{57D1eS24D#mBQ3;KQR~+iWAcUV^Y{HP zfQr@6j^?+D5R<9J$RjlrYd-nWSKo0BvLNSb_$vjfk;#CH#0ea-0dtx(o_5at+0Hhp zE3l(oJLHKu>i*j8Xq>iaA4o~)oU%3;Rv;)Fl&oT2gd1~#;SWL9Xv@`mdGH9wv z_d~C0pXDw+c%xL^*jTJe z*NxB^@6pk{^0Bmo?n$}yJ_Pr1C>FF2PbL7VroBw|mu&QtKOjWUF?UzM!XbwLNRXND z7%;J8L1h>s`x)M@q&7Jm8%FSnL4T}_~3 z{TBRC2WU^!S(tk?$mPhy7gAay90uEHi-=|fC&bo$bPt}FXO$ir8bs6N^cF(D1A;Cd z%5d+{w@$UIR4saj1a2M2ditaOouvmP(5W~|g-5biKNwY10gJ~W*i%z>pZD|QnGbV+ z77i7Ky&bmqnKL&z@@26_aIIS&{Lzr`ilUC&iM^aHpDiWo_5<~%7u^Nc>~q!dbsg0o zvjlI-N~F0L-@-cl=EzOQIbPt9Yv4M!%vUX=FnxA<39C&$JKpzko1xjVL^YzeRLte0=T%F^ z|K>rT$_hZ%kzOF5m%0GDWpyIc)$O6c=b|V+PwoFFI)|NJkOc=5@9G#Bb^+t0$z%m^ zLCi_}6FUYh=%HGGOsfO0bok$E*b6r!bkd$b3y#FVk03U&Kg1cyHvRw?`(ihuuI!(i z>=?a!72>na>AwIBe})cOH@Q1hSojpz!JQBpV~1?$`wKd5bt^d29-Afo7umn)#h_H6 zY#m9)X)!k3v`|4Z4WouL~YM?U`LOM$<2qSCJC!^xeS`y z;ZryJrRb-D!aK3ElRv&jCO30ZPkvl=Nt&x6n0E^Bl?grPPs%_7Tb%H3J@i(M|6qD6 zTrD61h@ffz&p)&%dHW;TGf&{ZP5k~M%~*a$A2N& zY)T^=4wa-;1J=5nX7bZ~NKrII?wn&ydVC^PqUgi98)}Tj8#UUNo@ZSi&3AFp7)t3&ABm! z%)K?<6o<)_65G=*^-}xcp{ZsA?@!2=lQnLT@!+^cCIb8!kUcItvSOcy%1It=2 zf_q=_WF%d@lpwgPhKEPQ!0xUQDh%e;FedQzrRD`>o>%xmB5 zR^}2*Hn@yh?CMnM^027&#tjF9kP;t~9q7oa&8|3Sd` zXLwO=f)}Ka!GS7V`siiH&+$F~0KF91w8>zX46I&^yGyw9S0`3~bp-}Ef$%=v(6E6Q zgsF@ag89fvM!p0v)TP>bgipk~`yt%}emeepBP z>b8r}1M~L-`W~!Jysbj|k}K@xm;G7g9r2=+!c3_%aRhmuxpHF~P{*RNf}`BXTwR3CSmv^)-DsWD)YC zhFO)B4RI5He)tnm2$8=TQD@pu%zGoVS`K4TT01~n{m1I_{97yzxomD~s8J3*F3S6`=AF#;ex;S1!~W)#Mf zSp_ofVL(dMs{>e`bjxZ-b`D3ruzXU{fiG(kA;z1S~i(Q$L-nX57*FJsk5oAz^5KJ0%0Tpd4x~M1^EF^Q)SNhmEgB_N{r_X?tD~a&!mjCVq`Q?I zIt7uImhKoDY3c47Kt#Ghx*Md10S6ESl^Bp_P^3X5B)^Nl_kGv57JmSXVeY+i&VKgZ z&pzh}{gq`(3$)Whm>1`|3i*6KyA4}g<6UPP5o79JyWh&@77CF-s85nlI#XF%#J7Ac zc`o=VwA<^x{n9xlS+NIIkWR2_g`LKinvOJoazWxG(DM8`H&nqUSDDp)*cf9O*N(;I zhjFwq1HsvPd#qexMCPoQ!xVvr zUzbEfI?TbQN}1M6?>{fkAub4$=Xa8Y7`r0WGe|dQ3vK2sdK%g$UY~pCx5d6JKD=s+ zHRuZ8pTe-~Qp;@KZCsvTw3iD0J8~+i{>ITCF`G-W*C_MzuT0uZ!=8Dx;k4ns$yxco zzsp|jb(<)hxIWe2bFos%?(&zzt2_MUw$jnx%T`Y-bszZc#8+ab)p0frR@>`s=I@S} zk?rDNt&)p1@UJ|d*)2Va8}Vx4gN9C=?sKjDU2xQE*Ft;>n1_5Cjvo)-bx*$dd8N&D z61+{i-bR+zDRtL3NbsJ|xJr^b+}RVmneI|vCOSOuRih|JZ|A93cy1-8r$93`wYo&h zHMu-g+mOHg>OCcbkZkbu9_KOZ{)_k-9JZE^H?|2pUM<;Zkr0;< z@zvXM?xHD=(EP<7=e@ne zoEP21aunTpp3kEU*9jpm_|@s(+)2A}Pmq&?7tFlSUWAe?7fIqlcNc#;dG)@%clKtm)XN+B5 z`YKE8eKz`V3QH~U+IyVf7e7sTaka;Rm+oQ3?)^c56KgDIB>go^<`HH629p}8IFaa* z^Na7#+Ry8|v-hgN>X9H%NJm2G(KsmV6yk7#1F4E&cgoo-0B`D#Ws)tMw#Z zxPPww+zNxypOthsU#%avj}?zz+iNt9P~1CBo9Jece}lt%V$}o&I&h*Y(gQW z;lW%p$#p&A?Cl(=Ja)Fwh>^n>Ake^CMGfO_@&1Uml)1e7@X+ePPNK&O>r7eOi`e50 z^{13ZE;{dXE1*oM_u#;yr^`#Cj~eDQy=9Uwdw<~XhhLmu^|B7??+nMajE8U>nfiD%Tx;M>yv9C${KZyzsMS1}b5XP~(=K+eM{l!P}=5U-i+ zfi|DpOr}5H%U*Sl&#-Xx=;<<7m>Ky@ovaZ;+l_IlbL{F^f1ZI6|ALz$v?+HSZ}{Ez zmr^VJrT4vL1_~du27dQ{%P#mST7WkaX#tp>begY%M6zk+;#yp#&dXo?iS0=}z7%G^ z8m89AcPY?)Dlz4EZ+T$(x8enpAcSWVG=p>9nwyj4^<-mP30MkSKwb7ir_jAGZ#P3B z;9-n!2U>=w19yu>9(}92?OImvPCOC@EeD_jh5JDt%xqg%&Yl@A3m&!nJy&jZ{e4x$;rebaPg%=M zS(`ON3OijPXIeNlV=+ZDA=C|Z)?v0N=L_45gZC+YPv3B6oIPNYK*#$KW8Zw(S)L}; z3Oz824?3J7cIq?8=6`o+QfCv*W-brSq|R11k4r~4SMK&%`59r|6)nfn)m1*G6BMIQxpw$s$tvC}a z90=xj;%-+|BD5nGB3pW$1>GJ-FDT@eRAS-n)ZOS$Qz~VQe@|*nx6i=YW&IPme2FcP zK-*9xjwk436&u&JC$;>ukzV6GPHQi!lDh*jk%wvsJCG8&pf7-xDRh*e6MTY}fg$Pr z*?lhk`d{a(84{eUX#UJRr?#~yr1msLLUxDaYXW!OrHi(H_p?6%&_yWc2ZWBp9mAcS zKsJp$E})P3Br2MZ99vgU2w|(nw;)}9^OA6C(yo%GjqoR~JLWgi4(j|H6vSNvP?#?A zau|ubj_9q$Y~m|8VV(8cf<^O;G_s-9dM=V+IFIu2#87SV!56MvjJ ztIt2K>4r3cHHfucP7&$;7VnB zt7-lCmapBk73MvFdUGH3&51`zoocaVmAAB6BOL8U*mLx^4A0(YUw?xksn8{efReJ$ z$v2bv@A-RL9nHH_v$MI|vy0ooVzTuguF=AK>nio;JS+3QOV1#EXEWc-2=lGwKAW53 z_5a{o44jj)HC)^Kqkk!#xbEC$&MjN|x6RzGbp40A3rW2dM>E+uSS|jiKWhYx@SGkQ zM5jLjS)|Dt)BW-b=yA06S?rrPn}oEC$tT1PkH9jStDlUnu13N?nq^YDt|w!K<7$w~ zxTOwS$*ze3guo}$$#u%;|7TK|oq~&Jg-!AE+~rST2dE*aCnn6?EmE782>h8R>T_aW zuDM0H8#1+Vf99s+n``ufei}osMkyDT)cD&FGVO*mOfXGSa3f?1hYL;2y3RUu=B>#-}{dG_p~V?-BvdqI0>y$2#n_`>iJ|n0-Qig(DWJjc0cWsD~upvv~bMU^e;JF!eb@h-7 z2~3x>rhjV=WD)aEmZHiK=0(#C zVdRO?vz=b?mfmXfH5&SDtK0p>?Zfd{KMb-+4F=xES!QXi)MQT@*3rZX3`wCwv9Y1C z1azezQv5A+unhSIYyahz>vDy@)7h2zZxh;e+GgpFnSU$t#9mQ{gEvpgyjPeK02paA zdTWvY03&i7Sm}e=5`|wwDQGiE!R95PSz2)YNGzq8lO@`6%orA&nU_d04;cTSpM}~| zcB4P*$EOn~&Xd5I{rGXHT>?9szcr3Axb+{yP)a-+-yPZUiooXfmG{9H)&NfW!$+o( zhL=-6%GzNl!8;LxPml(TV<(-3Cl0kyB$B^b5OA?KT+VR@sc(isl4rh^G;0t-d7|8~ znsNd@+P9T=4F~t#@tq7@7b4x=GDe>;k6PzJYM`vqP3nqqglvZ0TEUamgb-TnIr(RV ze0`gAgL+oBbVi(7D39t9805ly)|~KHkYEgjRkzBHW(|)w0mZp3C&xCOgnx!UgsQOy zgn>8z96xmxe0H|b`g>j`zv`Q+rOuCcDp9q!HdfLmnw`8~B z!R}j>^nW?;Sc%rS&8q;=OKSi9UM_Ao(9-Huu`v|m=CuEZ={!K}hhRcyXU5eGVjwW-uoO;^&{{+8s?i9dt#^C2O>{qDDbZ?TjG5@J$m9Q6Y~jwviu}LDia7VVBP5JkOFEFz2fuZ2htYrRc_6H zd_9_yUqHH zN__FQ^7kWAc8KMw81nBHaWHEa$H^cg4Hbf6CsfPf1#V+!(jqIdw8F5LJ8i*E4MKVJ z+1R$VLn4xutd%T{&m~GQk(#lgM%*BmN2Ng@W$HBj4r<<8_j4K-Jb~KL=n*ywA-NOr zQOT|edm{=HMlt3b`ux5+xZFC%{$noy&eT5u?>CsS59DKxH7G6uml_=D1q~R=2|x#b z`xe2hp(%n?7?NE_frrr;B%nhr9cObFs8U**nzT88JpdJ9?4D?TgaLF=U;^n1e73z5 zjdQOh!*J+@E@K{bxRPu<#$Q&nlEL4dPgb_&)k!H6q7@*y( z0#}ai;#)6dPI;;#XWca2|DVcYZnL9$!;4AriDe2wzs!_St|h~Y3=R$RH0MsQcVeJ| zZ?q<`sl>?7V`Y;TDRUgsV6Sozv^HY;<+qr5`Kf%Xwg~EF(E29)iyUv>HS6PFe)wl- zhBF)yUf_zIVUhjt5acE5%y~b>bdSBjFw+L5Q?yHK2i&nTHw+qq3G~g#3N5K< zBC3*T)b3;bYn|IjjzRr&(&27yBH)FgP!@Jq$Y9ia}Hk)*pqxi%pKD*vjta|B4O>1!<#by zmq2A)&Clf*oVG4nzd%u;ex%FN;_wY$W?N20?r_3B&t{XyVHsU9qN)ISFDtdy2~_q0 zCqSGknRV-JGFqcD3(u?FXnd|eCx07IgrIt=Q-hzE|Ad{Off4TyfDdHk3DD_CFNY8t zlg6hrW_$dW4J;=jMdAqzvao^?46)EL0-XQb7vQB$?mS8~pqKhq&5xpqWxJ)t#l;=J zmMIllR)U|szMd%TKhT(X?eNs`Lt|UoTJGr1D~77Jpfi_G6BDlCm%~h!^EH?s(qUke zrNus)#t*f669wEi-3Q)|9?~;Hg(lOvjeDtiQf3OHKO(gnF3c^X4}(^w^}$9(*Cv|9 ztCMCPxBc>J+f=(ULo3kmFR^(q&-#}Z&(43H6Rnw9fgT^+JTK&Wyzx!_J}KL3>es$d zsB>`fL1&xW^n16ZLg|gld>|m}8MWb_S-U3R?_2EC&tFqav2wYh^OE)AP_rHzPK=v# zavM7zGLW`NgSjWNC>a(j@rBGjtToz%e6TzWV>#}`DTrrne**P!;?OT*nh;V62l#J^ zkZ}9Pet<}RZ~^#nhw@(tGgFR=#Ch4IVoh?3%MPn_))v{cI-t^WbC(NpW{;AeiRpkh zpZt%+>V+S^`%hwFg87f1tYb0b>E{P1r#iBxeu@-|tF$ot)u$-E*Z>8Uq=I-$U?Y`x zw4m^T?^m_sg6g)EAp9I0oCUsxs0EkQ20oq4oL5t>RktH+iJnKDoeSroeYNbhsf-o1 z0!(##_zxmuhqO{6M;ZDEQiprZtI0|~{2gN-#Sf>JR5}W0Nlr@9ExcH#wCQn;{%h?5 zwUIHw98SSG8c9@hR}iOHmqH9!#1*GYp+VS%h{2|6jp#p(RfGs-G_8ZAl|j61`>dnL z!1WYyx@p=mx{jz+sJRT39_)f~raD~ZUmq1=pDUF#ibh|Ata$=tr>XZ* z^7>G#V?Pxp^aJ%C^;M$dao|0}cew|vVP3?0Wc;=U1ul)>#3n--D&MP=M{+$`?Y5NW zBE6Pn&}KVupgz@h@}RJ$_n5F=0TOFdC?#ze5z&N3bRy6oIBQh96MN^;dnXqtF!s^>l+gUX8?Ty5O_*k!V+3W`Vg6WlJ$AFM zPCSBRomku>7arb3oSo;20{n<8KcdAOqF_e{QGg7myV=sijS~e!WEP}|=rMN5v9XBp zi1J#Ps=FeBqOWqm_wn)0#|*Im`RrSL4bapHP@^cY-+Kl~FrKS;nta1HXd$ekEBPTwf*=oGU2xFo)Q3dm;RpJx^P zPVP31Xon(T7MsV<(3LCXW6A4o*-5zoXD&fi*a|HRC4)47E5OdFp!n~_QO$pb9TW9( z%E=QLG{&1;&PUgf_}v>az_Lxdqctte5wWYFDMq~udN5tg_AL9fvK1jzk!!ru9D_}F z`~ti)3{aQECp?r3jjN_dJuwCf)CsSaroDYoY1b zJKck2>R;J-iraKJu|}w5e{~e)G2u0l^tbaYgsDkyZ@J`2k{(OIG_yeNU{g{TH{U9> zn0z3sNg6y}-g9o=x+|ISmaNC$<0lb$cr9r5ukX4FAH4OBa{WX1OEz=iVyxeUKheov zp%l3gU4G2KKTv(EE+c^cq~t>=wU6!dNl7TPA|ISnSPX7s5l-+@j_Pkk5&_fH*#WFZ z4wnG?9DL))9Ir=J|B`dZ9MMSpT?0m9&GuFK*MpIlPFZC2VT|^zsVCE{U=Ho2B5R*G z(SDf)$X5iee*1KPkc-0O%Q5r%?`ImqIovr8w%l-zn1gvfXg>8Er4C#5xy{%L4?wKg z;=Ghd1`Z`-2AwO(!uSc)mK#W8n+8oTvmbZx{4{a6SanqdJFJwJYB;Mc@$tHlAHX~@RF@2pqk4Jm_ni0i000R&&p~!M2 zEz>_f{pB?9&c(zc*8Yn2IL$%kr*aGXT#*&`n1DghPaI`wK}%FgYI2;5Do$!h_SjI4 zqQsDEK6yqkM%lbP1AoEtu=U!BgvXx?F};66t8c&>8gJ0`U`I@ppj=9UD3MgCH^@)s z!7Pg%frAfsn44>!#5Rg)&N6BTY~lL?#_Sql2#Y9WfbLQE((k`YZQlDwB3+Kui1l}) zesbQ?!HZF+M&z!)xBzbAuC{J0WJsFT)_)A9SVbl6(Y2G`QO=dW% zBD(TZIBH_FmI(FiXv(d`ZW?3R5O!P;0Ie$xZY9sIK{`H@sv(XYXdYkOk0-vC>;E06 ze5p4Sr1{KzdtEAV4--LSj;a_z90>?v&QAPVzLbNBpNo-Oh6fdSuqxk{Z#f!J{gFq) zl_W%#w3*!#q}EkKT8V{Ny_>e%@l3xf*Nn76t8kl(FzvqBe2c}=f10PRX+@|@HmQkE*BJqYIu0J*Z8~U|#?AFc`SP0C=uXn7 zKWg%^G~sQ$h`Ryt`9%W`4)3GYk^BTJUMuVHRkOXPi00kZFPS>O25RNv3@+mMv8{tb z)tLzE4hhkJ_b;go*9I%R@HmpCHC&;48PvuvS`qZj z_XLYD?c=y;H+eVu7@DO>z$c{umz{%7u5k{(WIvlpACLpv&lwhoBxQ40N&EJ4o8hof z+49!rGAojD-C-TAgsA$_jg;rj)q~yW&2wP!;NiuB29KBAO-$}Et7cmy|5+=@iXZ&VA?}NHpMOkp(-^L+y&O1aars3QDJgl(~U75A}M)X4IpD8OkcnjBvoq9f@A z0sKd^FALaa#K3{J&#@tn&@V*Orph$lxKt!;-BIoV#jwg|L@D#f@T_Iv7_dj1JLT^)c33L_z#Zib{Uwunp_W4I3hhJ#kFaM(wcA% zOW!J`^Hi8!AR~JXvO}(Lk4Xu$iQx9g= zIyZh=lZ8frxg=I!?1FP@p*)m7xw&nwMc9BV>GU};HY%|i_ercn(KkG5h7%5$@SCUF z+=+=!rnG@^NQ@?18bKGSJ=QHK2olG7CB8t=M@<~Cu}QU<`=anO*4zIr`}onHczn>Cg?Z#qDfI1gEGEN@YeMpzUhCcUpp4>bJ>#|@h;$qTv# zNUT~xA*Hm)mH3A7y8%E^<5F}lWKk$&mijv!;$mX@oA zw{w+&P9r8~n61tpYe;7oS}QO_wC!)m;f`6`-*;Dy9gQd&XT${uNS%McR`YJ)@xU?< zCc{t{*~jh0r#5rr{N?_Cn|JN9zX}7sdh3Mh)0N|ue{MiBA2c#q%*V`wUR{72p^@ml z-T@(?D24o?}fE)ZastWx?$BJMc=$MX6FoJY3M%aNfTyAE*nJ?w;f0yDRT@Rt+ z0(J(Z)L}?z1}3hbL=Qz#F-*uJwM7-xKkq~h=J#uxAgo40&MYjxKVzS^SKVG^1U*<(4 zL6|agrGz#DH7*en|S9KM+JxLTdjDxrH&)&8TDDh2NWW-v(IHy z_izA?Pp|mK@jm^n9J&{~Ja3h`W*X$fY@z~RHRtm=GVSmfZyS3VF<>v|e6$zr77cWe5M0R=G| zC%fz1HyqXCPO2h`Op5exzFMQ6{gj|i(_``#X@>{izhx1*jIIFw%j(X%cVh>=xjfMk zI}(-ZlgtD(^tc$%{Df?fWfs^>WWA#z&@g+sw!f(Lp}4VW_@vgLYWUc?pddJ5N~pBD z64Yb7H+2z4|8?RID++F2Ryd~Gm3_>O%i&H3gZKp3kD>s-A=0!Y4y4mRPa{g@&^&Q; zUs?IkC|&6;iZG#WBN4_O{>-ou(ZfBYuJvm83wy=)&UMj0gD2O+O_c4X4)J&zhcG(9gb6FdZ+1Va9zB%D!eE3w|R z%3?$!!b<<@}y3-u}?Y^y1mP!1Ter&J#nM&Z~Zh%>8j% zqjh#d|9>t}%+i%1Y<-UUI0>Sez@2>hsum-o`19rq!WXWaw33zh4$Kausg5tuiPZIT zTjn5qEfEa^7U%CDdfzJEEgy3oP=%vCVXNmhpKJ!7sANX(GMB)$zhCzzi95aIoysKQ zoXAPaVa=Iuyk8`R9ZelX6($^vEDGw}sRX~g9ta0g3X%!*!j&%ww3hkyJ?v*$T|QS6 zqPgUKtdm9g$BAX8>3;o>mQTX4`=}kq?2tQ#N4Al`*@`o5rFd!9+pk1ijIvDT8daXY#;=2p? zNOS3&cU(UnCUDVqp)fEcaFY>xcwBcQL$_p1Xgph&tAO?bRDR$}Ie1-<^-VdSH5XPN zkv?f$tv+2}yUet#s>@f4H@|*e&?GjY`rr&Bn7F0}ue2135R$;~fH1|&Sx zO&;Va8H`Y!WG|7Tp~Pp6)bxzs6;V7x9tXW@{Hx1RgkVxT|KSVaB(*$%2)Yf;<2f2J zPK;acb$afl(nbc!N6VupW(>*G5E88#6<|ry=AjW?!QFue>~SJxv1u&@e{KC?hyaEq z8xgc_FjD8x7kA>qTj(Np%;`(fFgL>dNuSCy#kzK#Hu^~c0bv++wHg6yZI(L->&aLo{Yl4xJ6%6RDhC zwoMc4JeJd2#!$^E*a2^MTyyjtHqf$8c6gOIy6}5}p;N90vuXgqqSqvo2G9_iQ=E&P zyvS_~3M>khRGqWg6-sUI8nu@0m(gXKA!48bI}ou1!OckGD3gV?*;@-ME5klhh0UGi zxUnh)PhXj-@XLFT>C?A-q^7sb$AqxZbf&YpFS}6&pI%2_8YL=0tpujq;)8<9z~tR~803mBlF8O=E4^f8bYFw#L5PCpL4IFK8d&;X9DCU?jn^Hts+S zPo4IbS{L5IARZGfo*zTZ);`bOrj~hAsNawvt5k^eE+4vNGkg2h*8M-FPZ$#GB90vG zj>SWt-1IbSWTPuVvvJVH5#uNQ6kTnlau{e-nS0-!E!!VE!x9ORQG`&vuQ+vAKF`h` z`hJNZZO}BNH=-rMRC1o#km)JRJBAX>K>ASHEN>2U;i?szu&37GRL-CePD!)tQ>{ zTU|6@1c!4Jy-}q5g=c2;I35>0Q(pHHHk7}_)E1kxQ+?m~AxP8o`|fC9?gNNy!+RUh z2`~r`dm{?}ww>n$%SgV^Dkwk!zQ?($ns%aWCBylzz5+A!=|eL$Rb4FTzH+ougG1&7U7zFhD z46`vw!}tYJPhx=(j?q6TX_#S}2*9Y$Li)(k9li%57!=7ur7I&${{_5Aw5|k6RXw_l zg*Q&NLIH4C*e+>w`%N4j8mTM3BYB<;$PUQ%|A5FDz$I5Ot@sc*#!z%2MvOSr`^XdG z2_LuMR@c)HR)G0lMAriwBA}n)a3Jv`p~D4K6+_?Sljqj21|*`5)PI`p^AhL3R@!^r zU@Zt|B4sQIH#|Ptfpg2Drz5NYO5{LdUp--+ketCmokSfqHbSknWDk~5u8d`{ibrL4 zc){T%iDn+5I!vvxz`|RYQTRJZo!$w5$A$Hkh_oF%o@^8(t4NQQN)y5^5ham?WJ60G zcY5cgkBYsS8pQM*NR$DtG8RA?WEwO;Dp`tI={X%VoR0;|h5a@^)a%JiCgv8{iN zkqBrGcvyf>m5sw(oYGA}o!{M~^eT6IMti>h?1_ipmgJ0ez9&VfkBe&dki!8r7}t%dTq~Sbx_Rl``Ew~sM-w= zj)S>nv0?Lz+^i`E>SA$lsp5x`wy8@2Dx0(a8ux!>Jl1!`OXuEFWStVOn?W;FQjasM z4m*)gdp?!nr5Hf?pi{|0#tVq6%148L_%1Fk|A5Z`$Dmbi}57!V~c zK!(H8Upnn54(9uTu$%yyKjCvA{ZwZ~?JY&-iMY@m*D)~S{yKPc{h$P@q|Xfl>srZk zc=1_g3psIv0bCF{_|#pt!_ z+!QNIFyQblf}gly#GZ+`e+;ov>x}r@^Xw3TjY&qXs=S|o%7FjVn3`YK+><2WD=cDH zQzh-UZ8*_}Y<^k?o%f~)Cg?v?F>m3I6TfK9Dse?96NA(MqgyBo?7X8ENB^&^St-yj zC3V|qeJ}@ul5oEgvvn5#TKcceP?h%ajEaHl-RPLS1{*;|D*K_KqYgvD_p~$Oe8&zo z-u|^u4_=)rCmGu)jpTvl1w9OL8#Q8)PkJ<7-J&R0{cQGX;J*?dXvrO1@{&sABTc!) zqV8BKHbiXH2@P%wp@fKmMNq*YxTp7hk0$k2(#!P(A_l54c0R{L8UmoFdO`$;*^<+LJBFS_~lSO>mZ@ohs zi-9PWr8MT=A7^1h+P(&f;{U{5-Uq-xA@t^xd9}$xvnCgmGpPE*FYjE621t^H><2d` zD$0)MKCd=f)+&@M+WB|=;?00E^*IJ+M#$D>)Q}aL9%;U(Okaqs>kX0Lt{LESOXRr2 zHKOS-i}o?_{|3bMl}zLVphl-aLh-VA{XpLv?)~lT^_gICzdgE^FMA@lD<-%)>mB*HO@haj3t#|9!mS zmSA{HBgUOrG@SxU63z11%Zyq|{5_a3aeIv!2A4qFwHL_&S{*7P z7|PMfEpoCk=nw8eTVEy6fG*pdqlGamW1|9klT#TR?j)>?x`+j4SC%jPDqA4<-8Ueo zJVsav!M3U*GUf!T9<4TdhJGBG{5wo!{q}4_WyfUCZ{3Sd6xz(6{Zm7G|> zuB=3iECiShETnj}ZuU#xl;+<|=Jgk4Sk;bwA>C3O5gD`D=N-)K0;27N-(M?hq0AI~CoIG7K=H8EXLG?6ovPN-c0{E8{2o7Ezp}^p zP_Pk`Tg;^OOzf$>WLoXm3~1hLwtL@X>eL-R1EQTy6sA9y_A?qptn& zOY6QzZa+B&i@)9%u)eY;@_h2lYym}wLzjZUwoa~d!3U4~9dZ+h%_}SuK~Mm{e!e71 z!Zn+(y&niscdZO+iDST-(Ei3muFhfIllt8JdC+BVC-!Fk1);p+X^K_0P;(Qf_pOv6 z25D1WZsUz#Px~Tk24f7VvUZ5p)k-+g!oSQ6>ix^pr$nh3ZY?5$y)CxOs?D3w1o$U9 z%8D$riGe*BW$VAItI5^}Sp%G@W<1^?c;$e8kSnYT$i#4sv+wVjo zcQoPl9iZ5D4&K74A>_pzGDSTqWs~%-sq~e7Rz!Kk3Uf`kutchD)Go4f$JG>F8=Vb$ zx+~X9zaeh>w?ipflPm<)ckCP8$x@J%#{~A4V#V1neR;q3|DesI1TlcK$lL6eQOr?u zXpYogiGq_cUv)grzuxOStUnKJ0ZxM#_sqi$qbU6zkEU?ql0sBwo&tVBa&D4m3m4HE za94?7aCoJ%4{EU}3u5jJ_SFYckSz-4c3zd~zqG+1LL{wLYPqDwLQ~~@)Cl`Yswo1N zT9LeOOg3?p{a}$FjwYLdkldhwEII?xMw(W_*j(RztI=?i%rF}(9xM2xZOYufF(Oj8|MsL(y`W3qag zpcrgD=a*2$C7UOnEi_6%)o~ne%&AQy{@;B8c0z#e_D2)Eu|8*60j&Z#h&IluB@sJNIwE>Q)60u0$J>3 zR068~5n~VA(Bu=>dxe=j$Uny?gAk%mT_*Jn6XGH*Ky7dPXyZqx-cM)7#&nSR70Cu_ zI{CIHJsw0Mp&UyElu8>C|-1nz@<>m||sQT?2&xa$_!!RP@?6}r8ziWpR2Iy0tALe#E~ak!0QL{4-U+d0jn>q<$~4djuNmI8PTu+fOw zt8zVU@HRZMl@(Ly4cyiYsN5amkKQkfw})1>kBvQeHtZf7 zIJ^>R8Nc^9hX95|9PxHgVj$M3Rtz|XTw0%6U$Ly7$!XLj>655%#I?p2IZ;xL;K@5k zxLJ{-2WRiVKs}J$eX6x3Ue1NtureIe<~`=GH!S=~g>HL=uNl7s(^tM~NT@))+(}BDqUw%Q?Tn zPSHa*SIp-%8@IMDD=9}TgA!mVKAi`i5mg}5AV^yP)aS0p*iL0b+C@kJD&>bM z99eB`ts&`SeyLt~)Y13~61Z#eiv{!o-&O^MX)DP8l8>szNKZ(lO0Xll6Oj(|Z*fR$ zm`ss5C5tqu8^JW>nkSE|2wi;n+DTaW5(?=38AOCdXgT^1TIH3^37mWBNz>Q2wqBx) zQQK^s(zt+lajvf%^1M(%kG)n%u%p?PtqHKONK>z63)$LJZi%#+zPR^wL6jXuu#~~< zjCXD+-!3m@g6|2^b^gyA4LEA?CBbrCB%ZKR+n=`$2>fiqi+)B1eGYOIasSWEP9Gj{MBfGx+5iy7nct`&_k>fhPgHM=5l>UwCm+9qC< z%#CyOf%lDwXo@2u{9BOE)A{t0TIHH2m?5Z01a69HGRENR&G@IGH@|}Yjm;WICBFAK zCUbMt+AV82NqN4|!I#O?Ix&VI6xGaH=q{E=zI zZ$1$6*HiX0rn-d%LsQ@H7w-0RYgd%--a-D%sKA8>FM>nqC4V>AWE;rc9DBZ!{cY2; z$4~8U;_G!HetF)7y$wXXGtT`k;o{ca_H!rFzhD~*VdC|{=2Z5-t1&Apg8uG%eo{5^ z_?B7oC=K0F7}!jz=c6T4<2J3TZ-@C_)n7dLy(UT2jeXk5!BJDY9^1*y5q!n0!@L>G ziwlH{6pTK~x_es;nO9D%EBP&H)*_eU+y&!4wgaKEZa3l zk>o!GH!C!+Kn^Mfw_?9u<@M1Sh`!Lw{q!SYnmUBvnV<*d*T?GNHict+VLt+YaHYBD zy@O`JjBaj}eUvt?taGU!dof9H1A39d{wJtU+OmtLB*QVt`@-+@O97*GW0y^CNF4`1 z*Vfp;lK`54p>-u;%ba%`bNHecB_B*1cV^yIFl1l7snb=HFwBezA{!Gcj$3h<&DUL< zQMip|EdIM|XdyGChiV>$Y-Oj~^M*OP*tD98+cphZ(g$xXIyU>iT?j5M@?pxVrLCyc za!3{bncsq9{EXzK5ej~!kK83@d>feyM43EAh?Z9Y8Qt}b(ua~YU6q|IQIWMgy~%y< zV+Q?9u<)d6vaLty;Tp%;eFBZcqz;Lewm3L$tDytUWfq4V;xh-S81Y=r(3CCO=jxOVNX1ozb>KIAv5V_gl1u#8F@s zE0}Am#t8v20jWSsAOo(w9{cqr0j*^5tMw-{6R#_t_~nv#1~sjdZ`{ypP_e8(!kB>z z4tbG}@)k^th9-f3)BDn-)}$fn2JBYYdYaNV%7I~YEA`@92;gt3`V!#MlBi}oa`xaz z&UHd^k7vd*BCq}17JXl{FCtetjXIW zO5s#BdNw*8%F!uNF;HrLteMf+3BFR}BVe@jRMskIRBG8LTIVM6U>cF(%{Z{vy~aDI z-p>l)!|dhzT=bZk{$79Xv8X*BK2V>KJ2=&1 zpZyX(kt^IswoNxmWFY!UfY&+~;>s=?>qS`lQ+tMHKBkPo7+*vzW%5CvB$x$R``F|r+VWb3*dU^psh;^hwVR=TlK6v z_ce9CV#U@MWOs)*QE!& zcw-vlo-yFDaO8D7&jlN)^R36oT+O3m8qHHr*REaEL^`p0yKzrSm1W@A!KT0?Dni7$ zoX8AMNgK`0<<8>If~9LHIx#Qf&h}F-ycET_csUwB6JI+K!M;|POXS9a-xfOX?e17C z9Q(>$wNZ%?o6?aUL6|RN+A6wq>4qJSDzlWaIl<=D-{zkE`zqCw3w}gr?r^+z62g}4 zBRd{4TZk96I}zDWM*Kti?l3abPr?WpBwp(x;{556JBlI41Z#-JVB%Wrk+SKfQmBTx`INIkL% z+_wdK&>5kyjdiNV_^Q$TgddF!dD*|s6Tvky6QC?ION2;iq=L_$?pZP_-zg>E@jCw zlMnZ~Mnc_rN%ewv^^|X~4Cd3@TDEg~#p)z5DP)ymYX%QlNjavq49Qvi?VISEBm*>y zLiH8$SBcp{5Hvnt{UNDHBHBHPGPm?2c0p9`C@T+E0oWa z=qXp7Zct*P+J5>qDIwL{EAi;`CmYkdUDJyE;2b1GXhMgxTmv+%NTW={BIo-(BK|dc zLzH2(7O-sH^Z-iygG&M~UBjmu z^^J2QvowbwaN%>(OD}6-csZ5*f**^Yd-5MWgL3_iN0bxYTJk8jlGd`NbSvsYetC{6 zMab=PzMAua6z*L$pN63hyx(u?aH+naTnnDB*NiSCgSDHG9ba|mr7Vq4bMTfG9aJ9? zztiM-Enb+K!>{|wuW@PTwe@Dn=Rc(HOSZEViGm&>e@RL@C4rxKO%9!axg;pL64{PE zB061zxQ98k^ii_ysN|K%`XZPUTsrDYrlRWkXHH5)2p?6VQuPm4e!v}UNu#6J>&!)?&xRd92RTxUr9PhE%flYfl5MEpOtei! zUkco^ju%Loud8-{X4AFa@!mLu7|w_owaou`x8P}glQE`3^{I^nTsrbRd)bz^BwVYN zoCDK!-il;vx>?|pDw~3uLCSCZN?jKkZc=ru!VLV3xggR82a%w!PHKW2&a~poBX=in z-}#j40MB$tF$n!p}R{&ML|kHx}`y+o1v5jk(S@)e9w8__kS*~+3{KHuC?~mfJai`B;mI6 z4-!@M0lg++v|+(asTw6$^1B2fNpvsF7L0SwcX>C$0enrUCxSz>jv`khU|{&NxtBCT z9ifAA)v4CY?f!%D*M_51{X^*pg4M$C$gT7 z^q}&|euuivK)p2=yE92pIS1}ITg_{DB~0K3>Ze7&x*#iF=`9nd3pu6$=6(f8;rL=^ z)zh1Gc7}MjC<2E4(e;-h$`R;0g`d7I#~-0+sh{yjS27L&jout|iIJR@)9F=K9(#1i zUjMvbBiwBM^N@pwOks-o0b54e#)~d`Cj*<1g1wXf+IMs&aLnf<3I(jZ*?M@1R&CFF zPNWBqhOk1(h5okk6uG=uh4m~Du;xIGBix8eny#@pk^D2&^|R4ueya)74P2gfS9XN$ zxj#%j)o;;`?{vjn*yk6Vo^uJ~8E+xRH8h2g$Ml5JX?S~0ZAr1ez44Rb_ zrbcQs{w)5ttwVvig9Lx20;qS9co(wsHJWU&3x8YJDr zPxtC-KOuF~hdmFe=tA7ls(5G!maivr&14vKAoF~5fHpok*ChLZ6@hatWU2b6p-5oV z?`=+YCba=S4ix___ei6rnAKO$DrcdPiA?|9>N`1H2vnR&T>1DB#A5^2?=}Jyax#^f z)z|FG-geB$1mGRe0!(!wJz`z7v()IvHj!7zeJ=xk`LFYFlS;0b_0;wLFm(wdq=baG z;YAbQka%2B?z}xmCP!wrQ@^H?U_VdPnFZkv-jIwdHcX`+8UBWR90f{Tm`J6RAu=JEDwmytXime$W$c_FKBT!3UgzaDJ-G3MxB^JuL5uG+}SIE zhIabgmRMS|PIII)TV8*L2uc=QO%9?aq`+TL5?gOM!gdu;c}lMg5keMI#tb5#UJGLl zykh?Ge^tKpqrXygUfpmXJU{$nzWMHhu0#J5&7Y%X6NvX<9g@-sOi%GXj#Q3X*N)`ZJ5v*e+%6Mr zt76C2t|QU|*WV$`Nz7#jw{S$r;nGJ=Pzfp?s-uTI>=VP6LXFdaUW6zdvo~1c5A&bA z$xVxpD}MWU%UspXZW{p8el>kduuoceS0$|bo3Efd9$P-FYgT%`D!qWi6N`R{*LcES zxk9>NbMjEHKFP;W4`3GfI#%m$K(l7OPL#xI zX{(T39yk-U;JA1wLV-+Tgc~PYolFdUSEnbEU5B3h{QXDqHCmbOq zPV{1$6L)=c8Ph17X7l9MYg=;^HN_X^E#?6iYTk)Em=V*{?z~0YMo?$0;0y*+ScY#m zghp>_o|NXGRjkrcM6f!B-1HW@MrbZtI%%GU7-iQvJv#{`e8QBnbT<9ztGL+`!L6*o zlYYe@nZTO|O3pXX;GH&?gTDc(WUpoMY* z$W^s^U!)klsr@+q`I+_m54wNT-+xs4h|#VZ8-HuUHR=N#INqM~)+1#m`DWU8LQNRQ z;RkH(SzO!nDpR*hxd%qDpxd~$m-xX^3^IqkbA017?Xq7sul;{VxbN6%<*YUJv${KU zop&m&C9g?D(2`0Gq;~oN@b}7!C!?wGulV<^$lC})`2vua`wyGbtG=dh1hUMqz54p7_l0}S*Tf5##~M5!9V+7b?%W?qq$@wy+GAzwyP1` z`%lOEiyazwIo>-g_4jI1245oH8d&{X?nuE70MdP53`}vp zv&v^K+ca^YivO8)W$QOft*l4fY`aIPr)<|hY50c>3+b}-?WwK_@9bZ&?YYEuYDq7U zrSf1a$8C^eeGI;nCB|-#(^smLPt#HQ@dkDvqcQb!3WAtzA;B)nc#_8X6S^%vV9dXr zogHr_TKZgIv6w7ddd;FO(r=eyPj1{uFc&%zS8=|+xUZV%%}ENL`nX)G5$b|^k2}XY z;NsHM=e^}?K%WyJ`ctTAyROqNjjb|1R4=v&Rqh#)&LaBT2N+0-a?S&{>;m!wEKI*F z$L=Ah;*R~g@Urj-ZAhQE!eyf(RSZuL2|O{aLLB0;&ip^#%S0&&K)G(9>DUB;ouLLO zORBq6-q>^Snw}m#zbU_9Vb+(*?mfSZ$iLFbI=b=}I$9gs2tcon?redW4O2fJooS$N zdBe76XGF^D1KS~S0B!q zr&>Nkl4~uvop;73e`KK@t5l_Iz08AIa`dQ#= zgR6Q3Z<%nd$y7B(t+)g-lE1xtWc-^?XHiRZHyvB3ZMT*M+XgNU5~kkM}%}xu*~tp+$}p|*pBAux6D&i zHw&5o-6G#h6J)_?Xss#dvl??_dv`y+h(<)5>jI%~QiY%aSI9ncFB!C`t;eV znI_2k4N&cayM)#2`c&0WzAGpwRuAv$tVzeihAEgNb~`5zpD^1~w*ZV8w8o^^6-4vm zN8Uj9$51&5dP-84w~FpJ;Aqzk7rZaV9rT)M^DfKlp)E$Lvf&-zB*e5ou7A-@(K8z%e;Ed zsawuaZK|DpKOgBE*sW9;ySjIz<<+nh=GfFvVHy>u4VE-VvjGfY&^By0hv0wGO-V(Ms#>=j+6^&fpV7**e zR&2XV>R#Zz=K5UHn019TxvjU2Z?`I)kT7D-yi~K*jLI8AtPet1of`7?Qlw9b1 z2)tUa|BmLm4!LD@(W6kR-5UCc-P?#$pTC&pTK1046YB4%pQv}jJ@)9mj_*xUF;Z^z zPqVF=E$$SzC5BXN~4OwPG$CsjKh7}mbP*F$(%zcEN=&=VcOpl(G$!s5= z8)?aUL{~xrQLUO|9Pug8=;oMfKvs4Obsl$4Gs$}=!Ni9PA1yt26nR7p;@rsPwev9( zQO9$9_4_?m&h`zm@~qD|cobPJ2Sc}qhj+&te-i&lm^Ik$GzMThoE6Poor3t+hJwc{ zD<4tkBgFNICuAkzwW;Fw;uiF5C_|$K$=!|`(MIQ^pDu0Y7f~FyGCm{4z2;+~w{N1* zb!T5+@9~arMdH79*3RuG5UZhwZoO7f<^($8qz#7z|NY*rl}r)Cbc|23Zkdv5fl7dM z|Gz~eB?)0|c7rpOZoE6r!nE)wf3i2zrWGt~W=_@xwYe7Pv^ zxPy~B;K2uM1hFt|QQOMgPGSiL!30j&%g2v)JB}*hQ@sBR^f-LRm~% ztdvIFUcPCW7pZmT8GvL-DfhL7<|cSRPFy| z0a$MMle3cyl4FnR!fK(N!HB!ZpwFwtgEU%Wlh`7Wqk(;r@hL8jW zBOeAIt1!$XQsO;D#H`J};(l7qIE~AuP8nxmL|GBgL>2>@Sdh)61J8QNW6RNS3s=#- z(fEgbF-{!Jaa4tc&2y0yW^LN4>&k3vSi`19HbM}R_rnj#@YRIl6 zOfP!c51my~b;LDc`f6C>^&?NE1x+skIGTMbZU4l+uw6=QikjGO(EYp&q2V9;?DXb| zYKp4$Eufg(zSlG4J)sXZ>?8`43xZ{|rBn)jnlG)EK%&6yct)#Zd*$OJ>?>uWxBgdYz@eKg@h1%R(s6Jwi_WlJ3Tw(p-uwNr zmuSoP_j<;RWcv6;J97R*Ur?dcNE2EUp}5oM!JZ`l1g++=6!plJmjOs4U|~iRVYXtd zlpNmekAPrFa3S5Ohtc4bSHq4m^S3Q@U8lI@Mt!^E{I&PDvW5R>ixp_W^fL#~Ovf21 zT7)&Uc%B$Xxv{P{$h*$1vG!^_E;#k|?!k2&Id~^0>Eom?_?accGNqTPyY-ey;Sj+* zGI@mc=TWuA{`u#CXR<8=5w{KinEgqN7Z|4@$fszWi_KXp=*!%@_KM&Sj_H8!vUGsk zzTYuLZhz&(AIC)z8M(C0iJn0CRp#c8yqd?B&uSg$T_3@orK$kP;Io{SaK?S=7d-jS zl#IL<)1g*fTY*)CkWzDZ^K(p1P5ld7&u>#KWqrjMlN%6Tx?Hx+DPg)5GexZz32fw= zR%3obzb-O^e5mS)(slF7YWRzyRh;Xq@(=!_m)4q30c`0j^Q4EffQ}=dO}&Cy!WQ`b z1wYMgP3b&XZE1jYi)9nVA0in__!!0QYk#9)h3OZYDAN?8i7yZsksPq=e5b(ZNSPe^ zWu!F{5HEC;&7K`ow$vrHxC@|f&!`rRVI zBjRt5W#z)faUor995;<(i9;S7Nb%G?ajSparw2u01z!7WGSb?|#jfTEX|zU-s3fRj zVd?%&+)K&-&36(`sS{v&-R0yhRAH64nJ<#`J~S{>Vt|w=172()vEKSqv7SR!%sX## zSLXcp@%LzcL!YXFzq(B>WpVyz9M7W_G}a$&a;8U(L-lsUS$p!^8kZLEa(rL8r{U`m zm)PXHk?K^BBeiA~bqaTWOg4&x*f*I|mL9}OT@sIg0K>IsBVyyIJS-cic%jXa=uX%| zdlZ-$^s1A&6udQQwk)Jzu74>)dIbk_+=woVuJu#v(r+!Um76XIrtn>Vin}61pl6g- zAhem6Y+L-fZbJfaC4~~Tiv~`BXAEU-T70+aj|Z5`UudgG?Q)4sK<>{J$;Q?U&c_=56gsg!TuCd?3H_c9LrO3*ZFdsB1=L2 zT%8Ae49?7eC|(A=thOHGyJ_~4?Adc0^YMJBBHf(Exj0dOHPACKi&)5vyVquC-o1=l zwrUm+mQFUVe35DaPAq5R!gxtNqN)EA-L!!?#&23N=xf%?Xd_}$u+ay{3}^rN;i*KM za2s1=Rs&2j_R4w&)9#bhE)BjOygiq4x7H!t=rk{#4?Jn>n25az2|tle$4&1_ZF+C89nb&%7kXh;Sn?^tocXhT4_5%^fFk4^xab#8JMBiBXbt3vxAH}O z)jtbnYz*wVe943mK>=FK{J|mJOd!fk?2=ib=KE?3e#qZt{)Kj9#LnR-Bfb-&$3`1s zqDu}^(bp0)&eQi{mm0kVM9U5#az7UDKQFbtSk1gl@BnBQR@OW^pBFE#fqS)G_IG6m$0l=M=6<68{1lpOLIE(5=m5I;a=bQ@tC4Tig>^qs$jri4AH--N-KpGaKSowT^ z^mzr`qLW`7Twj<(AHDB*0MWqQLV5AMXlfEi*itxGXQL{y|2FVXqKf<+AX=Y&sSxI^#O&}uyuA`7NMVfxRBC( z=u+`~Yg=&fJc0sFA)f}~l}*Y#L_&OjbI+tz27wb;2vBx#w{t3ZNR%?v(CoAgz8Zj+C>q$WsY4sLdP71{ld5iWFRgy(=1lA)S8Xmcz z6u|c6m2@LBC8}d1EZ4jcZ1dK7jEQG{+nUu?+kX+O9<&`*>kNGSd7-9V7^}UpJ8{cg zj43541}IVM`rrw>A!#A&r02W~3lGek(3b6Pop#v>_c)_uL{@xk@W*DQQ2x z<5;`mid&Xq%xT1BO%HSP_0<6WOrO!(|5bEP5}WC={0A&DR;#+<;9_j!O71FBQdWiy zhXK0ab}t>|<`(?tNy%6g&?QbQG~be1ktC`EPJ)|+D`&EfxQ`Kfbl6n2>2+ zE$KUnx|_n@-{D2K+5(yR%U3ES7!$tSQm zH>Mkx?cGyO$xlgDY3vdtaz_B8HDIu}t$!*@R;{+9_G$R1j=J>AUS+1bKcy+c3Cjca ziA8>tggaw7$y9JU#?lge&wpxRaPj7?|2V7Z^Xzv5 zDp5)pC67b+?#|A!NC-Mrk|x&eXkyT%q(PLs~B22#cvHs z3X))YZxAVTFH92t)pP)F)y%%aU2LP~!EES6mp$k`r<%1e&Kl8ykV@NqRB?f=MvVz|iXC9r+=QQS3{g4!VNtJp4GON15J!?c^8iK*;;VxBX_SFf$4Q8Ath1V?BM0>?{WO~f-&+{MnEB9Kk zg!8Ivyc5lkQ-}d6$?6_v$DcK>0G=!>FyZ0C2OX)Cba=?!+NVEqfCuv5xl!49h-I{2 zI;~xxxb)M@`r@t9;=XqQpmLO6^K^VQ8aK|U=lv@ex{w<;kA}+1EhE{U3`{cy><@A} z-&iHXFLC;jotZKE^Cw9y^z`W>i_bTtxp8XuGtjTjoXyL6`wyLib1LU7jaJqQ1%ZFkPS6-QpUgwq|S3JU)$O#jn`VkFn@t-u2B2SZOscY ztF@ozy9}vLYTO<(Bq0xCtiaKM$4J26v_>XRnF_2i0;_*WJ*nzj=>8ylPL9@E3w^{* z%k%lwWg}qY+u=4zloJ3A&Ytyks zj4uYOK*70pO1bpSlVh7OpZ}@3N=y=KfUzklmBN%&@{Ri&PThBVaUZEsp7#;ReAlnX zw4&_dFVAMwn1Cb4ouc`QslZ#gLdf&&sd%QghxE4H6J-#9Y~2zMcxgk1)ZIkYcjf)LLp*{~;453{f_(?@HIt+xs9@1m)({jp$x2#jQUkQx& z1~M;U#Q}wZYyw}{s(vlvC8|yxNQ-^t4f70*vNGO<^YjSaNj3f<2A`rd=YW|@Qxq?~ z@LNNZ%HLu5Q&1UA9f`NY*?i-kI~;#3qq{uG{w|wK-VK}cFN3={@e;(K=xVnt-O@g| zk2mVUpMagyvUqNx%0vV|EvW~djj;bGu)>uL&$Dfo)42BbkX(?Lc?MhtLL7bvkKHG~ zP|of3I=b(3-?5Gg&Tn^@f7So_rO{w_ibv1@(X`aFg&F@-$6ZQ2S$H2>CSQozOJi4T zA4!+W)*;udF>R6Bxu0;K?M(#Dz@V^~(V5@XARpT&uifjV z04)#oKbPZ>k4SUan$w_--oi4W0YO#07kL_r2#JRti{phQzn5FfSAPJKMwk zNo3Xva=>zCROD0m3ZoGv3x%DfP@gYV8)FUha;$x4|>E4LIFc857TSF!KWGXv98# z?oXi_e*BL>YM)8NlXdw9T*Rm<9uT%eq66M%NGc$z`mD$-(|%F5I<67+ z3_66_d&P+Tl?dCYwwcwmUUKq#R%wE?(Lm+p1(0({B`V+M5VUe;!se1sXHwtI^08T! zLL~&(Yt-jVV%7&t=Hez`5^ic0OW^(*+j+=nXy~P?p|9=?wksxfODohx^Asdww}XC) zss9}V1kU1rwK0TFDw|*wSa&m(TDV$?ui(~6U1>_qiP~FR@=iOSJ&%qf7c;RaO)EgM zZ4$tBH>W=#Iuh0?Zqe30_mMe6PZ4&RkU9ceCR=9Pbq?hbM&khrkH22})!-P`1>zW2 z07DqVCT7;9vBv*Q%DNH8l)ZzJg8lwsW}!j|Kf-OsA&j#@Nw)4*)0x>Hc)-OVV1FWC z?Z8e7Gv|7_g_eNR7UF=?$bQoQDr}1Ce#-80{2?Q-vyF-+j!`R%LgXQ!u1Q94Nh_8X zY^R$ES%5_jw#&gO7S0qfzM{RQ%lhsJ4A{M1?{C_olyij$h&z&4{G$~jLmqs_Gcxam zjtt)<|L~XCAYCI>2zU1WzOKr2?B5gEbUu-M1d9b>0@9H5Gm}cs0D9J-p!9VPAA#}s zXL$0luif`wUx(=V0q$L>d<&eyIF*CjXmo1DD{f|PR1~04Z2uD1uG&41FisVcLb$Ew zvs0HNP;vNQh8OIv)NaaXq)GWYq{*t1%Qwlc>299hK5oA!s}07n>B50L8%ix8dGC}P za*Qh+y>qoJ0YW@5pm#^s;7=sNQYJ0cy0QTtkcksie|vB+lT&#Yi;#YZ^KI(QP?F;B zY%u{CHFeIieqsJr`pGob~Z1>3)!+Ixbx81h~veS6Q@Wfj==)s)8C~39=(jeTU zq|z^`o}*?^X@tgOKbg`(Ke?>zbe8y|If863;E?e*tkYs;%gnQDhG-CHL^kERwQII( ze-7Xo6mpNV_L1q@dQUdXT&2M>gBK>dMvgF3mrffx{_WENyK$FUDls1w&B)#nUGp}_ zD3Kq-qso(h9e9S`vaxe<<8h(S`^Z`QjYcDC8c49)JL2HI@Zv)b!d+$zp!}l$ltmsh zVO`!Pqt7@4MXv!HFJV*saOJ}msT>)ZIMPh6>3bpMgH!cld24%_wDU0>f&8lCTr(Tv zut=ZT(zvS;PTztbKQMeD)49O@n_l2=+jrv}yc5%Z<&{lj&4VjJdogtBWL}DhIbDB6 zFNWoRE^6{i`UR#Bszxa08dm28y^)Pe;M~FTLs+)_lEsz4HGy*0@Z021)W2#^^W1M= zAL_MAKXd;D1dQ2qEOMaEkC*V59%s|6M$CoR9Biru%ceG`JcvP(J?=aydOhyNsGUHd zKoVLwYCV^dwcb2Q%KfTQ!%uR^MyN`aWi_KS1AVd@ZAIb7uy0?N^N}xxuU8N6OyRH_ z(LMnOK6AmOa5jGB2k2S z{(^ZXiuM08-oDwt3A~Q#E_fV+0YCOT`T0O;w=UNoVQrQPo#dI!6eXNc9EM%tQ>z2gf}EESbc;hUI}K7M@m6WYX=MFi;1@pn zmGHy|SHcFS1+~dSAtNa%2`UfOal40z1U~EU8shE~?UgiEOb>B6A9Tz%Ia<%P?x63& zZ}IFCEbIRT_z+t$=Gre_vd7?3IlF6 zUwgJ?@!Xc+fOH*8oS-^{jC;f;gLs8G!jUy#R2%_J;xH64Q(<9X2_^!5ZjYa<_*YS; zlp4TEGahaj5j8N+S<6V~U>It3- z%+0aBg!G@YRsHE_k&YR0GbluWr$T?`htSzdWSXE4eES z!FYj2akoxyZB#5`EP;hEz?kuHeo$^sWKsGP?9r1Gm)wqJ> zj|&8?jFaZd5yf3#0zO5LoxJ*f>l)w`nHmCbmZuOq^Y$Q=lB0$=Fgwk2l7|(Y>kLbJ zUtBHq6ZpWF@SFG=A|j|%hDcJqaQo@)N&;YJgk7YW0JYodyNb5wb#m=q{EhgZg2ny) ze~OzBp~OpHpJ2Cf1!>mERX;R5qH%_WQ5c!$P zF0oUfIDfN#U7X)YiS$ARqLE4gU!H1CFzT@T)%(y__|;P$C@U9E=Lt(?s9ar2CGNb&V%n+kj(@Ah<0hXQ&@9eA#;c|8H@qeS zKKK3Qwm(SKva?eo$9A`q2r#p7J2m}&b9u`kk-L*D?R0Eho~6{cZarH21Degin7{!L z7qDl`w0u6)^lU>tf_s<$*qIG`&@AHwcVij|=EB{QFKm}7Mh9c}!p4E^?U(3`{hs(p zFi6Kr`T#PX_##Xt^IxQdVSg@%MS*8LmEwvdIog}UbUQ%}I_O8CU_BFqw_5NMv>@iBg3%wM928)mo(v#m3pF|K; z`d&wj-RT1$`*SEzl~OLr`b8qISnQN(j(IHE`^UBO*ZNZ8$bmn2VbICmio}G|0Q0Jv z7>Q~>a%)5~EEiQrJ^m?}R2riOggcpi==RPr#ba)$IQomH{ zKASHibJx!}2lV(KN2NfTiBy2Wl;@?0$$psH>XQ@A1wK zR)%}<*ae`gsS#q8rm$4^KoWwkgr(ifytXVuqT|mJ)5^Y?6Bd#dLF$wejk^~yOkIXc zEIVsXl~v~TAc(7zod-oZT)|dca3`NdHXuJOkhxoM{4}xI0e;zX=NUaauyF$@whs_! zQ{iE(XhI2hTE#;0Nl7@z=cmdgpr~+#)F-7AhD}<(KI8h?iG6z&8LbPXL7-oW|B;+- zLvMs6-8{>06bJwz_9sFDky4`!h!}bmf{Ng{Q7Bs0w~7)fD`lot9_>uOO$Gsq%4l0R2HEd zk+o`#QfyDYLLYqtTXBWbo=ExL9)FR%**E^c;h&_;1Pzt$^;><0X}XbKj8isWJf)P? zWq7okL0mcj_9IOj5j3>SES~FqjhO#ETVpMO3(?N>?!H)K1Us=U@Mr}D=g!nDMGE~N z`Nb#F)u&xw`II})4b1F3wv-+G6m@8N_A`s*f*AKW?+rtpC~P!Ve+M?Kxz-8HZRJ1? zlvz~rLB4)~#LuProPw0}X$7G{0|>^FhhCoiPRtba8@SEZ0+nL+U&=Y$`i-T}Tt~W~ z|$7p3e-~z3U=1!Wfv&5x1Xl#0=&6q5PM}h!rUVb9U3D)0^4*-U+?HCg*5)AP~x6odT_Jeh#x;##FattP3%E^ z7hC-WK@i8ez?8)HMh+m-wjAi0!aSHB>Dqrr zw_+?!4JJ|KFP%mxyZn%vJ9vn}JTNy1(S5kh=iUV{o(vCda_jc;|IxdkP% zluoRSIC0&qAl@C>(Lw{)`>_Y>#XIwfP?cV?0Y5voHvVL64d@-zO64cNp9K&706=?% znDs4}HW1_NJ0s4Q_wxZ4YfWQk+GlpM9}%nxdMe{pbd{9v2^LTO>|xvkLe=d66g=^TQ}JQ~_$ zY2KdftfU(lKEj6#aE*(LMY;B=$7rZttSC=!3qR;pw1mk9Y5Nq(?zFDn$nvY?`#N}r z+qK`nXsQ3c*Sv7GZ6P9w^awAo-Dgs@Vk7u#>iPpwmUK{y~!4a ziMq39-W1Lv)$U5xF3xP~L#R&Sbb-%wtb|+qy?bqO{%!n~MKZJ>21kxxz+*zCLPLa+ zi_Op4FM`K(Ebvw*NQyu{nWPCqULLiFBVI2b8$5ZSNRjrPHs~Ebzi>*5qZsvEMAY) z=QZ=?XQj3)b+Km{&0oL;D`#BLR@Y;0(VFjzpR=)&K1dYVrNI+Cx{2ptuFQ;I43c%@ zkJ}`z-e00ja*7wIi7#J6OlH*s{Vy0Z^j}UzZ)5zR+QZl@sL?Gg_-sZ=g*9fCpHVT~ zeeqlC$hQuE#dx&#q_4FsQu15yY@L8k05#RNkX9dof9qsG`GyGh=%FIlCsU0y$S0~% zKr{-NM!=X6W?xW8ANx(}DHf{djvpd|`TcpYTm91~TuRwrsvpHL{`DvaZVkDk158Ju z=jPnk$gMtaE)=G-wafcNCkONE$Zo2*3Nf{p;n(VIjh}H1FaLc|+{5h^F9@EGk32nq zOvB5RgHt>u$u()7$4d-)TBv6l?32YmnZj)hk`%M*jn{>gZG*l1l+*Cb6s-_dnU@MI zrw>nLFjqvF4NN^U#Q;kwn^aQdDspDTmZ6E??(>zOF`qzuG=FUQ$Z7)qvG-A8um^so z=2YV|2{Pb??9nM%dFm&cTO)6&$W^zZ6syrF6v8Kf=80xP;XcvA&>N|l&#$)Io@rT6 zkGb-G=FaKO)ab~pEjd&nR%U#*v8M^_NN!mxmNUoDi4YUiW?D(M$i%Iln)|cm@N`DyaEV+6*u~{=M*{ERM>=R+-d;pj=Q zf8%{M@%=a)kHQXo%F8^x8juo+nC;Kfskh#zl=UMV{2T-v^0z_l0v`;s*Is02ZlKD~ zH3`fQQ(^QITfN`(Uov0nX^J?3AYN{QZ~kOaC72`tLo3D}6$su&hNP?aG{mE9Lq^5a~%cWMK5{H5|!4>wxObRnwZ18ccx9Y83F(I-Gt!2Nuy4StKPie2f7jt)3_~K)v z`0MecAE_+)XmsMP)pu9!9e*=6!Xj{ksI+xG>CxF)q-z2_gDcXvsy2n3R zC5}wG@1wzLuNy85sU8kEj&)Aokp*9Xmk2%zB3X~FQotcz=9F?B#*m689M*n9yzg5{ zr0C5OYhK@No!AOr9rpX&NTvVGT`wb*!tf#Q+qlM%O^GT^V=T6N zFSz0;-`#qXoVvi3>pr0byIzK&chxEsD$xL+zFaJ2Tbqh>I?&GzKo-wp*{dW;%X}!_ z>0!8C?l7y`Wbio232B$856xI@Ira<=_sz~x+G#=38;9K{`6OhK=|Xiy>I+h5hl;zs7x`*PnDeF z#S}kTG!Dha&t$c>l2KwIZPuS#Eg89ruTQ}_r0u#EZg1{Vkba-w+OBJkE3UIJqG|C< z9l_@}rmGP0`?xjZg0sMM|A^!G%Z~4gU{tn94^ke-wvbf*8L>99Nw-iGfw_j6>D^|+ z(EA%JOdg~tREw!dWoS;Uqo4SiDH_H=;~4f|rA+zePHZ!sLNroH|GtmZs9@68G6Es0 zB*i%Rb`)_QpW4xn&9ry+I0=4+aYb6XDlKD`hTl7;NgqsiII%EqFX}&+?j61O?zy#- z{N_Y=Ym;N#^Uy>$!bvOKf(>FBsNa~`SEbd94u`9Z`CLFYFqEZ}_*jbv{#Br$q7>of zYZR1B7k$IX(cT0?rqYt)4OsXobCj^_^;}UECn_<`;sr=P?;#Um9c(=|lFcxsjGV>W znwgIM<@u;K?h3W2PcvJPPmu5@*_&Cb&L*DND!lGJ&t!LL!G4c^Uq2jV&7=;?>AI~> z%utR^kn%^Jz8)vK8AA?p2emZK+_3MZ6CNtZ0qi(f%;En)r6D(vMWCJSJ0GA8xlAoE89X<2+LwLv=55@o z)6Zyb6<{BdKX@v{Y!IIfU#?2O!_GF**6zyNLO%criVWLfNR3_!tp|RhM}i~Dv~Q0m z13vkb&w4b}9c8NrX6pDgv6F{|kP2X|PwB!dW_^PxXe5EA=3{vT`ih4n!f!`!<+$_# zA#eMp+uuGwmW=6JID8fDZ|g@yOtn(rWf;2`=or7$qrb+Hb@LSwWRg+oCM@6pI()bA zGR_6^A_&0N*0(zmE&CTQ{e%8{N%0cEYk=P1iOsMlNR;5+h{CUn8Q{WOA$vUnB^QN+u$(z~5r+(irod zl$_XOb2@Cx^vkIE1t2=gZoVeTqdjo(0 zA`B#Rr)c<^J*Mwy@34?*>WQUuG-bzy&0ah8-l;cmqrVSHF7S?fll8yE{{q@*dGWI& z0i{Afax|tUWBU8rIWOvtLYdJeHX}d%_voA_NJWdl@yQ(St&C{_y4%qnhY@SonWc+ zWNPdkrEu{vh>#ZtIbLK4hTm8GJbRa ze3Q(@#XWC6kyy6ei^;z*I+-~4IF_7p_H^Va8Gql@R)Q?_E1uibeB{c}L467NeDOtu zH4&slAM9XUXvFVOpo@IMTiOp62{)2Ykmpqnt$eg)lggI>~ZCQaIiDQ^FW3u-Of{tiM%QJ6xF#c?4 z!owoHO8l4-z(T}&jywT>xK1A@sz=nKQCpo@rZ#W1;-evJ`0==?lNQV`IFpf z7RxZTe%Snc;$|K8Q=wXyjuX7I&w!3FL=S8`x+?lr83-^%;Q% zHi3p{tw4(9V0WFtBXZ7vp4^_n0MDoG?+VH~mHb}|*leqrA(e5QkUW2~b~|Ps-KA_F z#Oq6N(24(gkH*Q-6sgdj(+H*Q7}y+06o~ee2o_yVhq$LxXeJcIQutqkL76Yr`PV%zRyR8&g?-QjF-}`Qpp42(U&yPU}@3*y4Cv+qYU$f z?DGbwi`Ick8{SZ7%Gd1J)*ir&xyH7y{6;y;dbv*v-^{B=m$SC0uQQb^*hj>3#yx~Mw|cFlK7};Tc)j`+dU8jN>8o9o*K4*sr_=S(Gw1kqqpz+>-|gKKe*PJJNxi6q2tmoem?c z0|=+`srHN&@`}lIDiNaH2DjJsIevO4b=V@pGU|C*$e*chV{i}ceEx{4X^I=u|$D6n4FtU->3vfcUs6!i3nE|j~XPaq{Y5e3A09U)L7f{5e>&{XW_n|8ZTpiIrQ^r z#i@+DM&{p|I*WT#sDJ*kB2GF3=lK=>i%gxq@1;ZX0SVcPu86BM5nUJItVE#5PL4OKuy_!M~ysX-03 z4A~U&;s*$7IJLrokwv?>vXME0xRQpoS6PKsnT2gMTVVv-J(B^)Bl#@Zr|^{ZSBql~ zrFItYiP4$YvbtlFqSnQ`t&{CUpqQC@ielNI!{oK>uCq=#mOAN>Phy7upIk7@ z4`{W9B0v#{`{iJSKeHt>YQJHjM@?)mIBA*aMXJSv|5^ux-nZQOXo9(HRXPGQh$@1` zdYLTZ1odyv03hj@=&4mkct?24S3+mdK9M>_F76pz7J!AyR9sC7c5 zJOPqntRuZt(ojcfKPr_gkUNER(aQ~7)Z}VnW9g&BT0VJ{iV|sL5&>3)x$HH#%I6 z_kB+RC7$fBezK|EFRH-bNYNHe7Zny#zodUo_2W9C*-lewWroW3f`hB_hw5j$l;Etl*+z#_6F_#1iz+9X|Y_Zw2LJeBaWlY z*^_USIF^xhR6ED{8F_g{1&}g!iXVLRtJ0k6Q)>s9W!_)=_?x{Il9AkC5fGpYX$1lZ`Oh*-lWaOS{q#o0nSHR_*Lki`t zi?z6)UHwT4EBeT9bupdk%)cGReqP(_fpt`OZy{lJp?3hc!KTcXJf zaI&zb`q4$>50^t#Z`!A@$7HRK?c~WB=cOZG&qs2UkRE~#vf&Ac<3AU4rA2DiSpp(~ z_IYhpvyT*L^dgsQT+@Gp(re#muiC!&NNcAZU8ZP6LGAQ~f|?IcjOYM#P_ZE8*bocm z81zDY_cOCL8&YxYJu|O01QyyR;O3*Zz_auVKJF7^n%Y2(q+lg*o(90Sqbr}_ z1l4wr^ssE_6eWkW=ansNR-wJz?S(80W z3lVmhO=!v-32ND(z2$E{JT19F1$)9HDv&<1jXaP!mXCrn*e3Kl!gvEQYUjnfVh&h1 ze%H$Ltiu@`c^-vbL_)oD2!`KG%;kP&u_+Ug$RF5<8Gal2@iYM7gt9sFk^6$K;n=z$*zst%G05 z!?+eZ{D{!rCw{?(aEJjBQi^f}T={5CmP-z8)t5q{s5L(j?Q~FHMQ2?YT_JJV*MR(G zJm=d%ELTHxGB`*QE1TOhOk5(S&4Zakyl#(VkQPrmj*pu;)oiJKhB7A@(!b0hrkRu@ z8%{!G$uj~;VfW9?`>|=IK%>;-(%Z@k=6rQ{lyk1N?|zl}zj_dm!H5X~*1{@!{&jY) zrg`-6w>-3AphOpoA^TJ? z74L;lYAntA&7<-Nlv(*0i>);23an7ZNJROGy>Z25-Z0W>JabciDNO=GPZZ%E${s%DO8y>Y0hMqMHoJ{t$YD?CzX)E5x@-uIWM zsV7s=XfW+1Zo+}WCjhs;R4W3AsX5VWuY8IX^K&vS)a^8LY924GZVy=W7dAG8Z{(vH zSQb+WQrOcMMa*_-Aiu;Rx6ZgHUaY>)fD8amh9xhw1`A2lB~pP{v+ zb&I*#T`JvMb2XQz0)F-%mvm?bncHj22?li(Rdnde@+4Mml0W5ARq)l&$I;A73PhkL z5`2D~ryyoj?60cSKp-{Nk8Fam^oCWWQ>Nfm$&sNSSYrSj*Dgep~1i7`m5 zw{jks!re=S0Sah2x8^T=x24#37rmOB()ZO{1Ja{Sbn;M@OqdT z6z_&E{beKcAuFubLOnT~Wn^fYgD>d2Dt&XTghj)~`J-gMx1=-v>J_|W#F&o;^B?9V zbTrpnDkjjmFJLxf+-QfGISMu%Hgam8V`#3-F#_8O(xY7*jC{Y=rLM0(6E2v?xcd-2 z)TBiZlRxY+jMM$xV9-?vXm|5ko2UOR@oHZHO!sWM@q~#{!a}8g?l)01uSinSi#<=L zH3y{U1M{9+)9%}F$>Ar2b+{wjfdlU58eB7cg#{x_A(+N`zlGXEJ(x7S8K(ZcVM!_v zd3@yDZ0y-zcDescSIGN$i!N%G{R;uvshR<}+4Oz5zE@<;_}x>JL4*U0#wKbV=w_hq zV5}xU<;U-eRwhqc2C*X0B)lGog782)HVxWd+JV23+9k)-5{#qmk7aEd5awmUEcF5 zh#P7GmHl~6=QTne6H3LoVbh`5Z+Y!5&RKf&n6{ygusk0TNz(8ak`a>CIMcJMS(x~0HY>$6QL?_)Zka>hr{E%z%^^M>_;*hM zJ?wr?i9%~_zDVQ=ieq`5FNoJ1`|BWKDl<)8e!+IwcoW)aC zhN2AFFRbdQJpkz3iY$Mh2{4^Q;}LL90J8|{mrJQ^3&%~*=651tD&2pM&NZ>4Eg)>L z4t9_-XS@p16nr^H3Jw>{ehA)+YgygE)a|S(vcDvBNPtU;SMke_Qh~i=%^4F`6xhQ5 z&G6IM5l@GdmSdR(y7+npkqAkQ>oHtG9Dp8!B+0_LCCTLZ-# zHEL@|?UH;<+K|W#(=mD?6Ip#G^Gn4gm}+pe{xV1~z~lq{l+3*U89JjG4Zvl<1y4SM62fR7~O? zqtEWduu!Ki_{E-94O%Je#7e9*#qAkk%|T`=4~0TD45%_PNGrV7MJntM7#<+_&gQ$? zfgyA0cJ0Z5L+dV@B^0GYM7GN9rveXB5ZV_pi3nn-xqDi_2j(4k-h;rjcYUmD%Av%y!x zBT1@AL(#FD1y$6teI}g6X(0UcX4OY`N4Esl z0SM-4$dOM67!k8p00!4P1~7Qc6|7a1A9>cjS6vdPm+{{dyzTSAS6ie5QVjQm6!>Ky zO}G&yy4SDK%X1*A*5ysEg+=rqlR-tE%%BT|*g)raU}|me7dJkxQ9uU!<2$X;8IPAb zR_O9Rx(Pe(KU0%se#yK16uS3FgxQ`VGI5ywu%TlP?pD;BiI+>S zCY)>5HdK=4@)d8FfWCt0eQ0A>%PtraI9Ac$;)e zLIR(bh!j(`OV(^2WJ!L79Kvl5Xw!!tF-~|XvNs>Ck-;rq`@8PU0r_zFFx>35G*ql- zCVDXR2NBd?2S_?1gtOR!D6&Mex`wMk;@|%9z9X5G1HRIN^`_KeJ{Zk@TCOjRn`C?NE; zF+0i2PSgvS&noHI_>k^c5^^^&@gEmk&+i^U_nD?=DUOv}&2LrRq_iT4TgyL6w}i_P zT0vMKKZz{`SkhDqF5SY(IrbyK{4jCsFO=wn1;%bV>Gp6eV7%ZmgYXNhET8M|>VFT_kDPm%|0nL4EO>vu^-;jNCD~W z&o^vxC_N8dw$#u@SfE<2rp&07ag)Ty*S50}96%zG07;nQ8c}mmLyWnMjhObq4n|D+ z(tJ+`b=`rutH{v(%7MrIZHgFS`bRcJBYMRXTvdAqo%C#DB}vh)%x4j&D1Px~TxKV6 zYhVqh%iPO9;n3;m3hq%qLRHxI>4Vt0dDj9nUteHY8 zT&|9dn3j83B%G`htrb8Kz;`HYe{c|W<@ZT^cn^{s=b#h)C_jq-iU8yAH_lf^I_ZxD zsIFE%ef{jB?3gK%fUd}r*pbKs+3aNM@|PE)(T+5VkX3L)8b@<&5=zS*D_oH=EW0|> z9oB(hY$q#uJbHIFc&x_TJqau zv;N)=V}Y`qIhC>>DIN)SAO(b6fyX7qy@wCHAqQKlm9&4C;7bv0!nddqn){P;b7&XC+Ooq4Dw!0%hJ>9@cs`+vS#> zX4IDpIA7j9iPTtOaGTj$rxPu4jJcB1``~s27LSZ*W!oLm>H%y20}Nc9d=ox^K22{U zzj|0r`0WxU7ig9#{cd!xo_6>xW%2j+?o>V%M2oJh$k{N z8_&SYiOa)=FiT(GR+BB@g^VKvn3s9sF{|{cHROL%9+E~h3`WD(Tdq>pE6i_Xjmig^ zXVQIBx`1mp1|K;}b?UO%7x3gQ>74U5z78LX4m$NcMc)k$^F3WNe``$z49lKAywd#bC=^h6MPMPKJ50_PwE z$h~aQbwT~~tgrMP2>J46i6qBLp5BoqgEX-iB8Mx_i8&H+orbu8TI|Q@2yo;EANbvc z*Qwxe2I*^AtS3+10AaNYAPV9wkBWTN1V6EqsMWw#slCIM zQxq|K5AuPWu2-O2CDkPjv3qZRLf%{(?34u60MCCa{m;_s_e+z2)Fq$l6{2>k^dibh zk8o=Xs01YNu9e9nBh8n{qr}j)htZPV@?(>R`0D^)%%+3e-zV-kCv-zX+S1NNjllS@ zhuARXvQpNUd#tv`lK(!O+^j%nN&`pDUHSKq2*V=9PTvoXZJS)B^rMPwHs9Yae} zI~-jJvm`zHs|B|dzg6Xx#uFpgXG`bMH7d_Bk208oz`-iR%N)T=L3n}v!tIb}%)kj0 z(P1+$s^;1g8rONITuVkAy3~AXIx3q$ARbEDMGq%)HML(+bRis+2=QrOL^UDVDwv7x zH{|egLkY;G_r*ac<&q{K{c|0&DY%YCMoIt!6M{(_6My062!iW*5FHp6kL!VIo0v2| z(ZRTgXOxKbt)fxFc{X!|I8dq~l1Rn;pEy3RmPUY8rqEQof{)=BCtd}xj&Ud` zX7MBc^?Co7S*e^OvAQiHx-kbHkPSxG`$T?1e~(U`N9bHvhqxeP-Nu$oc+n5>&+FiZ z6*8@XX#WS;PyWDuL!mrtSV{jyl|sIA^%=78pKm@j$7ct&59I zEiLu^x>RK~{Hb|z;;gHYvm7!CM5S067VL=; zt+ddw?2@1_&pl-qnJZx5j2B?cVeK8dolx4=uPwf`J8Fsf`2=uZMcY>%&#>W~CpCLz zpv`p%&{o}zsQXOB?WkHVS9{9#fHVU5>Sls z2ubI?D1c{#M;skrXkQKPc#2Q2b^PtJ#WyBbZ9(FBeRJVZA4F!;(SmC4{y7QrTpwNN zW3HD4fsoA}CtgCHKlH8k39lGUZ^$A~4}|7x$Gr}{5>5dUoSp0*ZCUy0PK9WLZ=tJZ z(`oG9LAt)tO&7q6BODsmu1)T}YLA<{pxkndU6-G&Jt+ResyM7(0JiBme`T_pI$>v+ z2OK}e4QqpI!w&1KHhzc5!$C~A2irOaq`tS6&DBlA~grN)*zQw8VY&PA^OV(VZ^ zvv&hzhr-PUn|)PF-hed=iyI3J>bXZihS8B9?>@^k~-k!#$))(mHTrQ@^2mPkm#u{h16F;8gR z5W|{)u3Sjn&+&lf&9Z?hVGU+a#NNy*1!t5n2B+aH%RRpGc6^i2>iWzqZ8$FI*fh17 zeEIMHD_)0n+Z|p-24Mcr% zWIO;_F_3YspgU1+Z~0kF9l1mCRYG@?=ahS^j4Fiz{uharuQ(dhmp4-25b{HjoAZjL zfxjIr5p11R)z}$Vq80Bu&`GLx;d#PkhYf~FO#pWp;1_~aQ?Qd#|Z0-SF$5U zvk@U{x$b|!XNmHI-z-VkO1Q}0)sldpilwo94Deg992do@FqZ@DYOtL6uB{16dI@!E zH3vIEDyc$55`-EOlGp+<YxEm3#l*9KlG_+3dC!eYrWeYsdfG7^9sj)@Kq*y4t73| zMqxiMH38JWD@tzxO~B3l^W`oxc6Qpd6T13eYGr#%LE;1jPk*qw8h`)&A(0YJn2?IuxT( z3~C@>wck2T?WWY5HmJS}m+Ws!PX)c*!H zH?ly87vb%#6aXX)m zKP2xujhQ%dd7*cCX$3wGgv4_LIHf)a7xL==NxVr zs(S}d=EJ~|vJH;{ibQo)A2(x@2k6eFE$7M5Q@AY?FxCkX&I}*QFM0Q-UJaJo_N6`Y zeb#RSOxC(U%&!y-pOnVm_Z`TQ`sj1+0KDZM^cS5`%(->TL@;1*_e0x!BZMP5Zjsp! z=Lm6pn5JWrN~^3cD}J7_SK$MgAD_K^FvU)S`1&#I13K2wXhK~{dRP$~C)qK$X&B8d zDG>A~4@*dq|1pu-0Z>wLCvdL!T-=N^UZOFfR%CfGroq<#M;&IG7q6azJMNKUTwP8SY)Vbw@6DGuaZ-l(PPUhFalq4VQrY>g{jmqECh zXWOu!P_g5Wab8de+drctTK8AmgCNwXNqvT{X0HdkTy*I%kZD-Eoqf_6?rLsb?>25p z>h?Uv-4Oyz7xT~NtnRPmO4d#Ek7aNDLPjw5D(CgW$K9KST_m5$-na{A2-`K^I{aS` z^@`TNbo9ZagDgYLL+-#r93k6c<@+>~_K9e}AREEU(|~R3a$?wXJBdSXyj)_sdd9SM zDf(274u5{({-nPQz7OV|z6#!FLSL<$DNigFZ4h(NrF*iEa=qlE-t52MnUzH)$^nO7`@Rth{xGeXNGlMq!Q4^t{A6k4 zFdOPK$GnV)13h`rY^%QIQu6$$7-x_S6${Pm1=_0_GLyI%G!dwap3k{9PNg&aeAE!a z2Ga8gT+fv8Kh5tC&)cpu-o%_!-|J@Ei`g`oGg#}>+7e5KVP4^(`=E%u?87;8Ak`1wnLMZ;+n$t!tg;brkkkIlTS><$m{bsq<_O`tr4nhh{1vvnDi zdn8j%ZgK}URgVOgoK)#xoxLvJN}~Kt_O_9Ki(NU5okThBe0T=z_T08uJB4AOo;L+q z8wZYlkMdBeT>~tUh7EYKAg6WDqMD2Q_m+Gdb7R#~>VJts8Dn~24kFN?we&!hJ^2zKMw;-Qd)s$nD!)^eF(szxF9>vFsi~FC zrSpn{^h%EiL_WtX`}AAHOVq4WcR9BK zJ1nFc+oNwDi4P=%RpAJYx;gi7B;QMBqG~=O;$Xhxu|T@YH)HUkb6lenp{TehUKqY| zGo@w*V@fRdiY3_V!G|(4O{O{95V0NjG1D|es<9r}Jcd;qN!hq)cG9^N$l6aE^uZ}B zmd{kx)u&uDe(ot~?juRx5l;5a3%HV4X-K--<6(KM*M%za_QmCS61+)dRYa0wVE){U zZc~FN$Lk+r-Y^b@xDe)yNai_y9*lKZt9PCrmHX6w+V$XZ7X)B6cQ=VJfA55m9pRz} zxUKvG7ntV8ewZuxihj;GdC*V4JcL;5c01X~zM<7g&_@2eS{qaRIp(rL9;wXo>r$mq z()%SZ3jNyO%~u}FL6)q{ct@5C>fS<_%~I%aT3}S7Z!3H}+0_A&Er7P2eFD_wEZ!}-UOQ)YZ#;(!aGH7nt7pBM>;`nJ^F?q8S) zKMR%=nR#f;(TSf&zvK5S_H7rqTW#f>DrY?<2Wqgid!l>j!P^$)fy(vr>*DQOHmm)Z zD_y^P^MkL#PNlaQ>Xy$ryZw~6QhY^!<5IkswzyTlKAn5!?)5#MZjpE4{x#6XQu_Zn zOF*6D-4Bg6jMR7hSgF6LOkb$I2wG-yFe}`gUIR>jx&K@FpBn}UhbNV-f-QUY z_}*djGgQkn?mXZ@skCW;!$Z>s7(t>g6OmxGNTGy{IN{h6@$ zA|S0LuGkwWYH%IAY}!Bn!5jnDmERuNc zsr!7B{;a2b9{vRX`zZHQ@*UO4_&w`u&d?UYg@#taXJ!Ou>^%j@vF!$T)}#5R8?z~k z^x0rf-`6f@3ln)%nzNi}f)3MP4_oLv(BN3`V;2Vd)EGzs$+|X{+59&7+(gZ{*;%*~ z-Ojr<4no@6OtSKkb|tf&C@?)whxP!32PU=z;=)ouA!Nw4(-Bv2fvg%gI!IU5e z2Ro#(tmS0js$THQ*Uh6X(z)?8t%)n&j`6 zyi-RB4M{XfO0xBcnyfDfe45XTaM)8t^0}XmJ_b71+G&)qiF!wk4 z39^rD$XG~|%Ks;&{YwLTq}fHUK(22Du9D^Y+0h5U4w^09p<e#6c$);-bmNda7Xdf_mIe(ITA1`dP3Q3k^_qlpJy6-I8svBbbR^K?0hPD7= zolZd39z4tjaS@1dUUk@3sfuUNZ88EzR&`s~uV{6xlIVn^Tm#B*W;tZ>nmp!eTFOjN zJ?`&n$bzeblwt5D)4K;Bqn!8JS{ z?-IqhYQq+9l_$r9p3X?rG3Mh6cXeeMOvG3t?y$sbZ4euw{6Kd6D^Wd43t}=zoOI8h zQBkXXJ0(d|{Vh*_)S$2>T^Qn|Yp(~c-u;L_{1k+3!Oy_?>6P>o2Jc>t&t$bEM{VY8 zM8elam#MYC8NRec8gOY>_oj@*@wwK;6VQVnGp$B|`sOr{EFrJcg3w;?ZyW6SUJ` z*f+jt_NR=~D>`_7FR7dM!}fW%Jnofb0s!`_czps=d;B#667m(rL+0Rl$G+&f;Pu?V z)pLEX4-xVnDeqdYMMbVPua_xY(`h-knW0T6H~re|W-lnz&s!d?6Wn)KW>n7C$2D(D z3m#S6b-?v?_+HfOceDN%ukic9x<3d&k?kCdForwU)^3D=jK}19}#`WH>8~Fsq9dUKReBXL^V~TI0YM{^Y0K65m zfW-knQlxcycUx4sF`F9t;%F(-PvXUk3SP)5wQnp=CR%Exf_R!Ox~TT%$}YvHzM8u5 z7v!aTA4!lJjW6c<&n7mu+^%-bM=w|G<8auWMvNHCknJ|mGr1l54udlSBhKAgf-k;o z?!IMd=Utr&>93PG9PjL2CfNLHJ^y+iEsZ7kH)m}kDI~G|6HJ{UeUO6D7E!N9$kQ&> z8fyXqMzntB+JtYK_I2zI7T^CV++wc+Qyb=m5ZJ;KAqosB@nFMZl@m;>?bKZaez-09 zGDxiIHG3lWGELVnZ9})Y8W(7|EiCn(+=08a(1&Zf<9a`y;gBL=#Q1RaZ2U1e8Wy>8 z`Y4c1$A;m`s*C{z=WuOj!bDAn#P&>@UbY~yMgaplfAQa)Av51Exan){jM4LPmP)yVR+0OVPh>scLA zxKMkXq}izdRS&DkGR4|l7z?yIdsFiv`jwkH)uo-6 zz}7$D0&h!03~f(RHlR%I!>jOg>l+Q!I%6VyG`O(@;fP`sHR0p;e#Fn%F+#De_T=A4 zlx<}0Nez%GhG;(HHB)=8(5FhB6$qQ7kRQvgvu5i|&HNwc{`bd$l?@L~gdJVqyUzTj zGy5ga`Th(TR>l9&l@A(0YinD)YEkt;6As1jYU$J<`nnCKQ2#UD9cl9C`%Q(Xs!K%s z@}fiH0HJ$=MvQi8Uy)<)m!_ngtuVPPDU))U(}VN;j&or1fiRP>tB$Ts0JW-9`01zh ziFcS4hfWuQ!;QTofAK3T>;`!gJM)wC-Bboj`|}s_lk<{`-W9XGyNsDHJ8^pM`0%7Q z9I$1Ur?^9Tk4>~rQgV<#PF%q)Ow5?Y?rbxAZ%+(PX!<5kUr5SIX9UnpG!@?Tk&Ah~ zR*p2}$9lXIDE1uL;EP&M1ABpN5PP2EgGN>*U$B(OXedHbDYYkE;d>nw?r&&|+Yhzw zDkGyk!tDp!q&#~T`gb}2Px-e(;xnWcpL9%OXCgXBiuf_3d?N3%Ln~BB8^#wtKtmzu zq+qjT9~du0#uKpixu|%+e`)zfMB9_Cd1q#YnZo}|(l?@S5m>TI9~`r&bw6IH@V@;J z{!PB%E!QmFAr`T&E!6DE!Vj@(4seByX*dk`Yxp<4x0!IsR1g)pp>vf^E(xo3O zDRAVax^s#LU?c%YCPV3I3|0{orN^+%DflKJOv>BrROuX(?vT zWoAJgGo${)Vg)7RADa73?Tm`8w3+exGyse}@$``C{fT*_jv1Xwzfg+n<$ox#esOH; zF*Vm%=??JFHZ0MetMwkO?ssNzWvZr#<@1bNT+TW8VQ)1PLY0pKUV@7$% zwr6^t-tbq9n<%pTtt7^sjK=ZXsWa!sqOSpm+o!LB_Nz|AX-l^p8T1}EUF?|c3OT!d z{coYUhaN6mdiTBMx?wp7+>9&CAYe?*P?h9iDLYgV2~EXOp)hTrKZJGY_gxeSi(Y;e zu^p-2eNz&XQ(Bnw!KC?z@HZD!7b2I`p)z(9tzc)9)C#H}BCGJ2Vj9NgQ)X?CqnbLM zzI666zWMH}o2g<7R)z-m*X7>8%bGtedxqQ-e!6H_9pc$yV<0M)o7&9(q9*vT#3NYN zMPM6#{5|y?ZLTp%aH=qRv5ZqJ{L{|lkc`VquA#H}ql+#7inR<5D@>L|oc%abeJ1MNM>);#3Skp?1)&KU5YGL1 z2`2DU`dil6dD!(B(*{?*Ue2$YkP#=mKa~Elk-x*@AlOB@Pe~zKxt&~OHjcHP<*B0? zp-P=f%6cg{eEEC(a{a_6s^~u~Zmpm-Lt^I!caD3Zmi|;nC0O?j|MWU&jZHj%+oW=8 zUV$d+kFFAYT351imm9g*o;MBCta!R)5J3!MWe6u1ZH__t_Glic*6E0qZZgi57r zgA{k=TqvigZ1B%~Rb162Z&a*djdcQF%o(yvd|8uLuie)co}7E0TH zSZjJt`&R#*veD<*Qf{-8-!EaC9jst0Z_55h0n}yNLVjJxS1GGMe zL^~4EyJ6C7Dq*DkA?AI@FU}&P_=}6A*Amxb2RxjlFYmbDG7~?+!gT>hsyJ~`fy;KHhj?w@eL5$sDn_+n zrf&JrnosC!_(g1%4aXxSS!_gNL_D%6U3^4RRmxH;cR1?LO;_pU&90l`p0k5RG^GT0 z;L4c)&+)QP(qUBA=E~W{*eo1$66$fXgNJGWfK<*O zHFa;@Hndp&0MjB&KD#PA>&U;=F*w$ux)&|0?cdv-? z!Yew~!xY2av=Mi$>z_7BniZmYh$%f4fAE+PfukWi+~vHQ%Z!BW{?oK&Q;EivkEdC< zB+NxBw2V`T{|+Yi(~YN3j^-2LsAXTgt{?_pUxYHa4J_B0NhYx-ekl9#vnU;yjwo-% zF|c*Vq0;f3#xN|`QkqzWK#koxE-cJJhsnF73*BV<5`a9rpD9}^k?v>7_TE&+6Hj(X z0cYFrnZB?cR^l54gH--R)Il5u$Y3d*!rgG`)XsB(RQGrQ*e}Ro1g-iBNNO>H1UuY% zZJ3S*SEy?dfCYe`1{1C$`c{7^7+aXG+i-z8q#gYk){Dna%bW(2q07%hoZ(b2`4e!`k5U)hGV>e-CDVlSPw|ZlYkh|JeQtxV?`}*$VAb!}u z7HjF&vfhnQCY{SwEpqB>&D^@nmdPzGT$JP{1L-+-mv>&LtbLcRe&V&DXm$hSjW)f8 z56$at55@MMr(Q-&7)X!7yTi1(|5*p8TZhNh-uE?)mXCMX5Mt2HF)kb8Y+JP#Mc`m+ zPT2Teo>Y=k`_A*WfJwwo@k#cZGzfOV0DIH%g@nxtBM z6m)05ECyi5S=@xC_ie$%ZigP3d(Xt4{csJ?m0xyW2S{8zFP2bHb;a+(n>}ddp8X>2fa{F??@|&DCN0%zcUw zHQ2JuUI#K|JAGindubg|GM*VEP6Zlh0;iJp9=4{S=GmL85hX=aC0VLa1(Oay*Th$bLciI?Hb2BGJ{_D=}C%8_rlYwQojvoP$R540UIBm-R>X2|Z_@ce7Nx)Yk;kr$&ow2Y8rGh^BoDWq z(l9PQD+!HMb}N3oNfq++kkYX5o&jCS%Jm?nJh)uO{8feba8FmbqFL5c)Eqgv0e23e zZWH=Z5TyD~wolG*+WYG(()_uSwXpxodjG?sgP6=Ne4C%D$FtzU`n+4~auIwpCW-e{ep zHY_Mfg9ai-2b2^2iY1IC!RCt?u!aTr8p6|9W&8~KRXAm(7b05nZDebGG$mpF`+1Q9 zl{Ht-|1z{R(U4Utde5duZVJ^lUD$$x1<>o`T@vdz5rOQsOGL($4 zgC^zhhx%Wu{#c=JxP7WhlqMO)vjQq4hO@cF8?O>{Y{!}Mlr$m=O}F_!5S3gjIE1Oh z;MndRs(NFy}HhWX{b#^Q;eQ%S8VrBF#*$72j_v^g{8{ce|+MK=44bh8o~ z`(G(8l7wyhU8c!w{lb2e90QrpPG6<9p(^ zb9w9rlvJ)|cZR0>0Y(Ah?(L|a#(ve(El7vxlRE+~tEKt6$M;u_d}*(MIIJb*h3pvT zy8BGO2%the#}(q+z}9LXTajzjX2-%oUVxJjZP#!+!@6!OcDbWi>@VHW$MGs`ce!|$ zQC1+-DEi-Xy&q6+PmF;vNe^%tFG3nkcLw~suIZgnt}PNyu_M}JLi0K+$Q&^vhP$Vx z5TFC6F$1gLy@|?~z12+yq_*efdN{DGgJGP*OQ+0nA^xpw_MBtHqLKU8C?*=rN>+rOFFIghmCNnW`LYJX5CRTz%WwN z`jjt-y(7KTHi5Qd+IS*}mW%1Tht(QOMvAH$jOD1Kpru1+;!wY)^EO?*dE1CC;JFeU zGmwCG4Gfu}M!WpXU_B@IM+YSr4a#6@f)Id7bI~J#!NN)kzbQ%AEfF`pwi9h(O?v9f z8&)jkZ8BTF##5IH+@Ek+36)Z~2~M^AmIwR?c{|v;aP1~LikuP2iBgC}7>i;Ohk)tF z_omNIxhi$)OxV1%MG zX@O25-LBXVAT$AK#u>(Dv5T;3@5v{wGo)t)?& zD=|6|r0^>7s7ngUq1ATsyXW#hp?*eZD&SB2AKIMIq2TXA{V)#L=cJ8Rro~Or2|2F8 zXR;IKo+tJAK(jO(B7>iT(-v4&ntvwLJYYaAerBmDFzZ+%fDzcR$`BL@lS;a+X7hE(-4N?fya z9%mFqtHXiQ(h}))WFMeg7j`eDpXAGq7QJa_9}31B0s^2PB0=wi?L2m;4tQ6RG5y8+ zR}Da$jQ0kA5N&@ca!e?SDaEkGTha(%;xV$3ne7t2EhZwN{&qI|2FJgr2O={Ksr+1R zU5M4<3m4a*26YFk1`w=w^pN(w|+YpDl=c@#$UK;5uW))PYxZ<_6Q8&H*GvRNa= zF|5yoUN)E;Gi&4QplA#SX01rawx#$qi|WWM-k*q$6`$S9E&Ee;HfTP{>i061D%SOV ztMoUsXL|AM!g@yAkHiS`O|*HNIaKxaL9La1Ty@96N*U8T?{@gO(2K6d%;pj~xbg!@t%1;}Rhj z(RTh`xoTB5d-_YJJ_CaEXG?>@oR}gP20|V|HfqmCvxbjH8R|mrfT(?UqSFqEFe`@z zY>9K?sQ5mwB}jLZl4yw}^s{Ko{DGSU8wxV6qxKW4{A;vCJ%$~^pMt|#&PP%|BSP|o zV|^L2PyuCeP}AyHOIGCQ{u0{bG&3|~Sj^nY!53jslpRDruz;#HE6##SO=C{>r!l=9{5?_6 z9?PCBht>)RC(y1xw#QBtIe0xtDP(##_C+;G64 zmw?jc6?=+Dz|vyju<3FpSU)bR-5p-YRgSoREgZNGc@~j;c#g@v|Jcyx$k{iB;cg7B z%HCaI8aGmXJmU$F-`}OYh8LDWFVVb`h7?+#h!WqR9gwbF4&T|_@$uozrqj;KS{;M2h$Q$D^tK{j^zp* zvZNg)Zku_H^wTA1_;kRqr0CcXus*O#VtYGWIvFtS+AuCL_lQkDh8WhyvCs20yV4wZq6ux%n*{wWX zokfCc^c|86+KmgU9M7-hbNNb|Jx^<{;@8N|umB^gJu_g|n**0CNT!99y+wedz=je^ zP7III(M<7G!BB3~)WoR70r~+BL%vTCM_$?EupMkm;A#B1G+Zz2Mwyip`0 zGRKSm5}nXoamh_0ZJ5#N5h?4Kr=5;(B;FxAGCyP*Y7xr!tG1dim}|)8pq=i;Y6(9B zD3WUcZqU=d#$_YrA{Kv8wecm~sOoM;N+V-OjEHz}5e@F;4`pKR z5ImY0;%+P35tP6~{Oxj}C@@a=U8G|6#GDNAgh@vkjTJOV*+1FDG(A5W>PzgadE=p?>h=VOzMKwmORP3g%1)5oi9K3qEd==?;3)=qP}pi#Dc?9?v_{P{Rrg$dGV z$`T}d$M5pqmO#jEos26VPub5JN4_@)gnTiE|0{VJl?M@OmqL_p> zIsxL{_n;1EIAh?x4zssJJx7j7Ivu&@6^gD14zosMr~heMk}y_$P%0Esw3bzkmg{AU0;kN^2a%-4a{e zEYFHNVYkNG*?2G<1%K*A?o=fQv<$6pL|ml|6NmO zz%}v_wgK1H-vJU30$>;}JzKs$E>Lh&V?c{Y_8iK^abIoJd5l@q^66(?N}KxvASG}U z6q!Q8D$UcIViUvwVh$&HlwJjFn?xQjoWED-5;ELZU;0)#I_K!Gqz23^J6#LsjFxW^ zz*OS+B^sn`!P4C;n|7@AY|v}7d^7ZJ)^4wgCImkB&avrgbzB_#wl3?cU^gu$cw0Ak zDp3~w-u{8$dOuG(O9Dw9PDk^P3uQwNJTLfNcRbDb4U&6P!gd<8j?AEk#sB##`Tn;g zF02yuEg-W>HM!wx3}se~$%KT4Lw#u4OQ|nW8>jzIK?KpLhm-YCW4mVeQ}rP~)Z?r^ zqh6YLM3wY%eizLgvLWX^?peJSR_t@(qrXp%`kVu0{a32A-y?{XengN`;zX1X4YHK;=xf6FW{1!OX-`&fu3KGPdpNJPer=JeNSLMybg0hlYw=j<5|rO{cNHJ zI_7(bJ7-G&KPBbZVRA&njJ z;c(SQ=%ajR1sg-k0pj!HFBj9c$NWe9_i$|5JQuv{m)h|BJ*D&ZQZT>9am%rrpntV} z*Y(A)wa2l9Yx9t%@GP3fOWWRmn^=){J+sX*%-)_5z`nfLtiq^f?Xy^yKGwQG z@rXlY^r_PB~%RRU_}lnXZ5Ifgx*ayBL#Gs!A4W~ zN~)Gmj9mC0RR_X%^o#&K_N5hWfpXQ<&{_S7syCz2a|YQr?VdA895(|J{!aD>YbLRT zo+RzDhN-7J6p;u`{P@$N*)0rh|5UavtjAhk|WZ?d4+5Xl}+2tkYNXHoj zr0q@wd1)-T89||AVqzROzA)P$*Ba=jn@pR4AgD71XrpNI483Fb_+4$Dj?Ye=EkTp_ zVp&pj1V)63hwq^AvO8P!TKtGFXAe4HK!6|?UnNEuV%b@Ji!p*p#-|;>VXqD0%rKBe zPKVhxMq3d887BLN`5xtK4CEj^)CX)t4@i&PHj2#JAPYvy$gzsgUP?Xtj~rp~-$^?7 zngJ8#Y{#2M(w`-L)DQY$e!!#A2s6Q}FKdTH31GVy_x*rSE*KUSN6D2{VBu}D4;irx z_hu=3i0V-yn!yydJMop8kg3+-E*;CQOMZhQvoF6{fNq!KvCW!qcyL5^K4=fAy$&SF zAky^Db}`H_cgDp}#z-z6Om-iF|BwZvTu<3n$ZlqT-L^`Y6zLOM{2Rve(F@pQfTvxu`fbP{-L z=4cYgB3LARw7hOQkp4ATx$`OvXF>-$i-^k=Kn#BDo3Ossm>v7$RWT?PdZx&J09B$h zldkUGR>U6#%@5o(&Zh36QesYi{pf5^47wwh>(56F@A&mopCdhpeQm}{&yQV;dpiQL z)t{*I3glvS`vzLY4t(+4OSi*>;`bYx-ODufKu>$oEHr+nqv!nohl1$Y$3e$0F?HtB zUv+4H=wyFxmcda&kxlTl18MJT;MNe00E&!W7Ys$skVRs-sq-~Kc-S+s|B-rFTo8LM zoNZd}Wr12*?1J&q6st;^9iAzzkE{fB9y)B5n{9}gZ} zwnDjR;8yBH?%__|Yrw1ez3wKz?MZg6xe?Qj(cW$KlOO~4h3lppGU{_v3_c1&UN3fD zVH_`K_AZQeb*~x{vshqgpzEbxl3op=IpS#*&&DNODokDs0`Do)3j9w^2s;ccCPaqH zd}~dI2-by!+ukeCLsZP`O&CKvQUv}fno@lx&ojFV^M7z=A_@H?>ZAW%>{OoE_ffGW z)-*bxG6b_rJb-kkv+E^6$tsw*M0qlA+vb9Z{?KOE-yKdnsUY0YW}(9br*dosoE9EY z$`LMRLUiQEKd2`9la)KqRRFhVDOQK!s7%fEwshSGT5zuvl47SJtklH zTkO0q5Oi_saxVYGrT^E30I(3%Ph|bX*4RKRGigH4DM1uGCECuWw|#Gkf~+wsf$EY# z4<1rORiKtu&=fYU!vOif?Vea|p4-Iua1WX!@B=|TE1 z`AZ}0=#@#P-h3e|^o4c;$VQ`Ql9fik+_3GKFpTFlB_q-Q|Kd9yHIFm9kXA%S#)awC z;(XshFRn<8g7RM|uQ3X2&-}H_ntNrt=m;l6VA~)ll zB;lwTez^I32ZeG=_w#l@{Bwt4xCT8`vPzb~B1w24Ja+8dk<&=BTDb&%OeZDJ84|)3e1)Sw`7*2iV@1jl1?;Fg?{(Y%p zGUi91fmpPgF-p12CK){r^WlL?F=S2jG{hQeMv>SFY7xb8c3ZSdCU^~qIF=g-nN934 zdifftWBNWdw~q0c&tiOy_JxJzQ}IKK`qDvgz)?uNw%cCqWDqDDxv&MfOJ|w5w6?ve zL16_f&?%;qC1QC7Rm9AgTLd5f!l5o6QW+JpOeTt?%XtzwFc2rE#CzKXw*Cp7p98#z zg!Dt;)e}#q#rdu?+tq;Faqr3Ow?S)8aSbkHr_1kr3I^x6X{?;G-0x|MniqX)`h5O* zVXZQCKOn2rZ7v=s&Ogrkl1c_8&P?5JMRAT5X2pER9EfKP_0gwoUFv_U1NM`)BkGn; z{M1s_xUB06!qpp%(=e8H zZ;Qp$oR?4`pqkIvM3N!+FbKYx5|XTP^vjVBaDFv3=|h@f$8WB!9&-L{ie(fp-A0g#ghnv zR36?6oFiRTCv@Ut{~r1Z35{Ybji=0Uj(B@jA#b*-TiPX+b&Qk0Pw)~`@fi{gKu$^G zmkd`b;zAPhkM|uvdWhD%uWveq`5+Q60LT4=(*k1L$lN{&X>LKJ_n>p16M#Ev^q(+jS z1;YbmU2~$89lJ6hl=|7r>P%AL!;$oN4$9u?=qY6&&t5Yl`qbfdls9 zHy?6+4@qa#dH)iAa1aNMpvh`PGbcIn$*U<;*?iRd@HO*&HQA2sj=?R`I~i?s(Z7rV zh5nE>E?F%*Luy0>SZBdTY`JP@5~Y<#GG{F=KhY<1E7|f8s^@sTtc4^I^12c49N+*v zw;9koRR>aRURE_>%cpOVGYRJYNe9(0-VmaeQx1Lfvgr#O2#bbKpvK*+4~Uyrk_&Gu zN^iS_D85&JmmORrGWNyJB!Aa-#%4@)Ea%IJKsNd&0$E)^1QFReH;)FSs!)-~(C5+f zk3OB8@v>$n@UedO7YLiODU`ucwKu_Djqc)Oy?H-2h3pf(ScY)yzJGq}Oke?DZ@yVJ zSifd2iHPoh7N09Y9&W2QgRF|A<%OPo$*BXEtv~h}s4FBzy`RzMZv?6s@!>vLa$Fh^NjUMJh@_pX^JnwvK(RuD&R8KkKvMWN)hT z$_2gUL_^=#`$+bdkmEXMrKw}!Q{LcCsZLHY&41(Fco>jkbEaq#{}pZ3SM zqRp~7IZ}7l@N@AbCnB-U*CXtxG!=s!C3apf$u>d@Byw+x>OkI?1a*1ju>~N?33`H# z0(2$`_qg*_eX^mIioM`h3;X!&_(3T`u;iQ`7EDiu)3ZcsXR`T>okI;m0|vN^&Y{(v zp(eVx#=QhFN!;{~cvtGlY>TYhxs)gAqxL=A`-H#(0QRGtjj!}1(m?ei@k90d1{TXa z+41PlYuQ)|-10xy+4^P+z_0i@L9&CVJD@6|$*9TdzLBTp&Yk?Nd1uJC3HDZo3C1yg zDh^eChJe_tx!DBChCaW%Pc4F;sSK;)MybDD zy;ArA<|w+Zyeo6M4plb&fuOy`>`OeSez>y5KIpmqdT$m#g^WHu9u0-30gq-QWpI(2 z)b&xJ3Qe(NV#Nt7b7X%QV`fRu}IhuiJM40Ddo)7Nk}%HUT{RI7oH z3P^M3%emocenRJyA5KfK|D^c!iFF0l@6C0 zhQps6|nF?}8|ev5EMf^98z$w>FTrtsmpbzs1bH zzqCsuauQ&+nzyOf?L%^)UQVZ{d&V*a&VISn>%sYTj3xzXkin@&#$Y2*f8HxDQr@k_ z9m}2Ki_g_LwQYf$A-2aegfv5+#z$DE7lQr4Pe5(D=Ay@AE2;Ck^<_P;{L2&Nnm9R> zatOJfy!SB6N@BT?2CrRLuIMQYC%hH<7 z<|Ct$4lM2zH_&PTY(c^jp)I83fg++m`;<3VfG7I&LtiG?fW!91XSUBl_J3Y1=e#(L zEwYfTzI*H#-O@}$T=CMNvU&k24}FHG3w~I8TT3`9eh{n3;UR_&(6voY$m#2q{YVp$ z8}{V9SqKPPgcBDRkJDO4Gd?$lM+LXd)F#w@FO+pqGO00# ztY0cWR8%7P56A`b$S#mh?w4Uat~;| z5Ma%L8Wp;T@E+8hbKR@vTnrp0qrEDz7>1XIRVo5?1PWBsq< z;?bU?`q*Oi=qQz@L6hcX z!iwy6wG^e`^03kVYr8d`N=}$a=`Am(EM0VIU_aS_JJS%=9_@`zw~#;aA=yq*(eXOp z&5l3Gs;GYUc_0eQ+#nL6d}A9)R4Qlrl%H6Ay5Vn^DV;gSNffn*4?#E6k92{ErWYk_6bJ>j#<~>w5VW^ea`s%0%B4q7BqdwxN5B+GE zZx(Y(u(9hWC5~i0%P9?`P2!AJvdO`5k-Z^(A(3}c6EES!?r<)#g>g5PS zZb&FPzMZWJo%!2xE@|g255=JjHQFfp%XJUyQpuG)ufNwB=*hVHJ44#z&Y!@AB6C+S z!+QJ!fZ*sk61bV|@*D3uInzH&#CZ4)F1ooTxd@dWy3~9;`OKgP32&w81{~Uu)481BmcU0+3aDaKkITbrtjrt zf2%Nf8bWn=yg}qin^dxcPNGx)ye&KijYhK(O@F+VvDJJd1}x&Ql(UY8$1ppUZq6kt z3V>dCtm6#`GMO$Y@OFIn?)x-mZwTF;2pwA7=D7dP;27F9alcfzN{bm5{F$*>iIx*f zZ#28g|1;{Eq`Ne>ejcR@$u9k0TQI8!>Z^A{U)Bu>H~oT%N@e>m&S}NeGFk?c#l3xy4*tutt46af#K)5d`Y$*)~H)S-~8?PvNK7C05WFD%5z|SI>l4PWz>X#O^Q> zF7vi-4;s6DOzdn7UK_L!!QlKS`Mj>0}U0KIDT-nPyV=l|~*;zAnIA>Ld2B zGPuJC-a^Z`%-R>Q)lcUe*!)s&-3L`jl!4R57qS|wBf`umN*w(KNUlK6p(y>~qU z1lAt{)4sbIwX`?IzjX+ba^QVOefd5QXIW##lsV1M9pI~Xo%5;- zC6Q&B%+7dZ(xsalm)x1D|DXKNpXVS4HoWhoMRXyF5eMynL=10Qp$Px@+-Sqe98g0< z30Js4;un}ng}4DjH(n9UtNBbf+#nGPGtl@WbK8esKC4Pw+RT#uzerVIlXGmLRbaG5 zZ=DboCVxn&E2P?u=uY~z<*g)I(zH(1mG(48$1al&V$q#l7iPyd3en4~$rW&cR$lS~ zRoaWvfZWwIyaTE&4g<7M08{v;-bP!s`LcY=p>AJ$q&L4I9H_6dWKUH&47F@arj?F& zWnWyG(t!p9N7~lN9s1xr4ouvTYcRoN;znkd=&Sa_L9T82{Vw*b!^vk{WaP5qkN*#h5romn3VJ=s58FSf;4qkGZbM;(Pjv zb1-~AVU+k#y-=zmK-SJxc)U}I*VfXMPk2~vjEZ*vGMCS?!jNE3j-@fYvtd&)`RT)L z-~l1p0iA+!iHqFMN}XSi{AND8<#=Ci&G#mvDyoS^&7R+OJ(Zudqpkcivj>jh+H3RV z<->Y?uZkE89jJ@VL!6F-nEv{4sD^}|+tB?pY?zfT?JDu1F{)`s z>lS#<##n*Zh!D<;prTk+-93~$Su*%BM@Nt&zMd4T0dR(b2sm&x6}Y|^f7em6HBR%x z1I92i@pto^ty^044tm|T`UY)O?o@1;7)1LfayF75*4Ii)kJU1 z{KosDZSxqqbFBNy;9r^>dxvRP60Zb=Lew{4;S3x@35-KI_pdiO~E*ud4BimN8{yO-RF!r=_{}EB}*4KXl2=8 zn1l?3K~MY`)+uGty77X(4HOL@Cne>(eT+emABfy8ulXabd8^MJ5>3c*<)Xh{IBaQF9D*Nb3dG<9Ql%e}5 z>JIhUxGo0jz03w`QRw%=uAeP_f7$L31X{2F=w*9>P4_*L0 z`2S7JZ3swJ&%^od&?iU6>XNKp9NFz$ znX-3Z-e&mx?yl;TJ{p^A3`2aO!1UaN_=iMH#_dK?!O$@`mXwpKnlSrOrNPN^Y9-NA z$mP^jCWqyWw&QgS(ABBgwlt#Jx9w3ok2TcwM8I@<$b)BWF1ycw@ zYP^(u-0an~KF~YLwgx_hv5540PV(Ki=aWn9+ot^JAi9+H*3>a5qS6I=y|Nt_NVJ20 z3v%|5inYRzPL#+>*q!$a`DpLekzw9W;6+$rYe92dLUOnZ9IE@X_S<}YaavJt6*pf8^Z~Z_!Bv8IIsRSwas~ z#9wa=L|127xa(2r>{tEy3OSQlh1F-n=VMLg$wDHai@B^TvqB&4#6J)mSe~?^_oU-f z`D+3gv|#Jcr_M`-jlNo)gG1@1GSc+f!X>sbiW0&v%BjSxP`)vJC5J86VYFjg3%KQTGFHP7{L6#N z)Px?QOj|oUlq~X|0bwGM;V&tl_s2d%2!(kzvH_r}@}zhs;Nr_IfqRTPQM%p*py0AT zRPyB~n4|61UH(*JkNIF=&+n@}iE$s#KV-nkuyS6jTqNZvjt5d(r5)XkJvp_Vv84AV z3{F(^oY{^9F7{hdT+}{$B|p}tc6DGlc>P5l(3tY8b@;EVpo8Og!BUC|eIs_!%sN*V z!-do&gskiCrCrs3Evx;XuoTW(@h`>NKsg@H{sEzTyKBQcqp%}H?)e3ndOt%X6cOXO zsalB(lrN5SnUZUo8EpPl*`=c5Va7-rwe)()_>KDO3ql%7ll}pHoU~2*6sc+G08hl8 zKc~Iax4m!m*zB+`p6h5zQe^x)SN?9JoSzmH>))eN# z*?Fz%B!*?Erpmr;-2{!>RYl8CVO^;Vy2!W1l)xjv%WlX-jM*Y*dAxw7Uyil=Nr_TJ z*l06sv0z`TT72bSCZ@7B!~l7)n@E$5oT97~ll5C&>gEMRJ%HKv1hHq-&;Vi|tBDhzlS0#(g{1Yzl{fP%P6`zTCiymT%bx;Hya_6+ftLJx+n2`4 zqt1V&wXnl{hyzKNKn?k0LSuArDl&g^GAJh|Uh;;x{l+t>Mf@u?ZRNIS^vc zX^n}EML_QvTe?4E^F;G*cUNwSVU@w{16&!DsX*zB3NqX{q1vq}jD=h^-`L$v-LdNS z)`*jB_~CZ$4$GcQs(1&|$QxX=We9~MdBl@=lai$FMms(Ot?%tMZ7G&9H|s%fy}{K1 zcKA&fF<#F!GDmLuWI%r+n)R(m?T8R;Gka+1ITjkt*^qUN8i_ObNp>xk!>;XZ7N}c0 z=nv1LT_J-G`Sy6!~B-w zmC+A5RO%S_dU_59=FnGtpgcXNXf+=_3-XZfykL)Cee>U5fF+p~8;O)01jr5GdL$GT z49J}Ow7ENSb&)7*hgco5(PUl00-R$?z6ITW1&2O^fcf7I$hOf9uTPu(5I7COziJ&g zRM$98abr6T-LdHsqcB5X^Z&l{KQ?S$l-<1f6jetaDsRVi84CuHC_t`-Y-%& z8d%OV0Jf-V7>FrG`&n50_^$-YOUd}jiUPSI@HJ&o3T%gb zV1y>jT3vDdS=`cEJ^0l2_RU5K6{1UAEBciGp3XGbd{c8cBMS|2#<8avaU%HT*CEM` zi$Q+2^VcAj1HBrcgI zS^F2g-J0+TV^SIgpfYS#IZ;N6o6=ELk_$RuRqZXFJj0OsO0U;a0>j{03|N?{?P~BioT{r(LJIix-`Wd zzh9WL!p{WB)yJ%4J6(3O<}r*m1fE8S;R1jUVRAzlNTn_nw)yMdl_qv+IZcD z9h@?>oMSe*61!>8ANg6pY_0KUJ1Hez7Mp*yj8Pr4XI4x+G~%tsO`Q2`pE6R;ae89s)h&3PBsuDf2y@d2|2yt_iF!@H;uYTc0PNa<_NYdnQsEm%G2|9j)#uAv)?v zE;uf)U@~MD>&+Lk9yz<{;$J9P#wBKL#&j(#ZU`>pqONvXb#@^|hoORB=gV>_G(Y7- zT@~{qJN`;r^Ry z9LJjQ-FWT{J|&pc@_`;zAt`S&pJgrJ+7jx0*tP>EqvDApbF1{5s-kI=uk>N4)hfJ0 zV?wsP+;?5qo4kUHpvS)>m=d#!JEA0RrL3r8`i#~?#|T?sjnNG+ z)QvO2s9@@hN}~v5)v{{P2HNyF-jx<+F0iD~)+8a)YUfLTFijA zr?D8QE2xKJj?HyONUyr3t#D`Y@s1fE<$ybetYqL-@V3(;gvi+h`+~F&bIbPx zKJtsE}E^~s8-9g%imgc z+yldC$v7klfxBk#;+unKmwPl}Lm#cTLy)Gxw*!IPu3AldNz7uDMNU2)HO6q?;^r($ zf?enYaTNR|h>w_|!7&w85T^+mK~$*OxdH=X4q0mO^$r2OlRKG}3}gYK`}*w8F4Scu zL~>l@e=Jw{1d8-@L@Owv6K}K4>00 zhuU&tix1z5u&TiyU}uvN2+7GF)0`@t<1-2o1ofDo{d^cY_t+3j6-Y6#R_FeS-F_e< zmzq316qj1iR%3>hT#e*Du;2sUuuMsOQljuIE{0&PkrWhF103F$t1t(aOT)FU-H|py zP`-<8^qA6mnu}y>N=FNxxpZ5?3BeWM@_9~k6sr-rZ?R}!9pp)nJjQ`mNP9+HL%f;S zP#k}p5ZMVN;_6D2%qA^lh#eXTl3hq_$s4R20Na9S)24WnnPf^0Xk}$CPiH%Ooc=T6 zZTY`QDLv(>^}F%@I$ar34sm5XAScu>LW!v-YiO*_T0qqxqoj;VL7JTB-TbE~p)|QK zlYxW3NYXRsp0g78l5P<_k8n5FEjACW5_a8Xj@hv%N>BUg7t{T^Mf`q8`4_vt>DmmH z#-W+HYpTGmN7hOH!fR;$<(LxD-xBlLh)Q34D>=)MAgNoEh-2R_y24bI6^wRD6A}}C zLkuVJS;7Ly%WjNHrbQ3AG4t9Tq1^6?cAC1ZD3o}kI^7VHfl6#pGEaQ9FJW9}#@1z> zk@{;~(v9bB(IqiyayyEHVD&dG&risx1naPu;@<97$i(IH=Yps<6V|>?7@$<&9Vi3) z)GwWarQfgy{^5<~Axp+dUiW_n(+)~CM1^6Ud^iEU>eXGthVI5y^eR&6=Oaoa_z0v& z)j|Fp^Tr$S>lyt<0wfrs&jP7KK^(~{$AR^ATjfhvAMlLP_=uwSdj&0Xz%~+m*Wm3l zlVypriE+|nV(hmY;)fZo-)+WtxQHEOFH&PMlS*jbvRl@(n*Q}#`gM3b zsy-MuU#V`;Z>&kmKLc(GHa`rY44{Bf(Ns^mpYv~`BkQU$;BleTPHRHM{Jg)OyD?Q# ztKKMZ{RvMXoz>lm0bQjy{Wzplg*03WJ9*T2S2&qOEH%L= zv!tvcs8LS_Ap+#NjqgzGloShdIC0u_zYS_IXO+lpWI^{xP)2=rEeSM8MtAL6!~+Z@ zS%BQz{#i7t^p*&W@&4o9yw;2360}f{W+Lw!tqC-6P>u&|+lZ`kdN=`sKBE zD!PLwQu%p3^omLh{3PGvgoLW2O%jEnLL$9{{Y{>+Sc zkxvr^%Whfl_euG*7p=>F++rJ)0$3ps=#dO5q)$%r>q?Zr9g$eX7SK&8d0~iawaE`f zkXzVPUUPy)flWuISG=7q=fh4+{OPXmLq+sf6v!>7F>)o z|MuhMf(h-S2Jq}wezrCKKNe=<_yHQ_bX|@|5hTrT)Z=eHxBe_-R8ch7c11}XIX1*% zVBm?43O1#0OmaaX-VQnyG#~K(t=KPQHOqx%uH*4RgWb_Bwgl1<{f0N}WT1LHVem~f zD|IigjIx(NOf>HzPL5@)9R)Fp@!ml`jzM%5hB}uWFsDRt3?%Zw*jR^Ez<~EdTO<~u z>-F{pV4>6H?Z?50T$l8$?+TvCPxOYg9&Yh|5MU=c3dypYlK7lh(rMZAda361re#+x zKi(w;EWUJ~j&nZ+o*__`s>fCtzX_BROl7>WbTB)h^iZOh?fFUq$4+ zr?;mo17G?2%u0>v)+gGug$1_a!`qO}49-ip8y!43?A=;Gii=-oZG8TzG?G@cfCllM zF!VlvB|hXm#2ac!n)9fP6LyN* z=&x4JzG{4js>+6on;!efn`TR5w|~iR(e#(zrz|^yrA+oi4ffE=ez#V+`AcCmJRw`G z`pcMj19__g^a0#vr!+{bzl;`TFb*igo2mj-G^4PT+UiI}aZ03b3}rj?>zXZFsF(_@ zAP;)HhuGhhH^zT5wABkC#pVp4}?{y*} z`o7a=P?o6up0)P1&PaXq8fH^nXa&8giPQ17F8a-)`>)A4ezeD&N0i_PO`_aSo$Q-r z9Nm0Z%|fQg9mPRqyuGiZ{PX8L=$rFlW2b(ksj^C`K$`W={hMAM!dV-eA+f@T)~e35 z(E^oDU5Q}BgZ|JV7~uozk@&_#-*HdpQB<%4|HQ+Lnq>4bO;ileM997B&BiPY;H{Zx zP;@wQwMxi<88QRV>OLasKK@;E#1FWY#wi(q*Y>j*l?Bf=?ApzLtDPP4E~BV zfBf9dTAtBP>Dcf{%2?b-pW^()Y<@Un7!{Wi>bN`mlBk9>BfuK1&Z2Besd5N3y!O?j zTF2rWz&~>;tc=@gFBG}$bxq!tF~xKhpYYE1v}$qrr+AY*rY27UsBo$iMuSLS2J8f- z%JM|O5FsHS8CP+4}lZp`F z;Xy{~-%x}JY=2t(=!IQI5UE4MlSOC1&Z6mGUfV?RB2khd+Ott@ejKak0%7^^2 zD1PJ6P1qU$eDQ^8=QRleXYY-DQ}j4i;kuivfE*8d$l105KbFZ{csCL2+R3`e*i`%P7;Po>Dd*6mUiZ{W~H_<3>@3u$yq0C4f*_k2wxlie888pr7JXi`$Y$^)_JOfuTS`+$8aP z_^@Y*(P*<3bTmcq>LRG=L1DCHcCIGwe`F$XKDQf=J7M7 zFm7U0>vn{0PsNSCm(=za^eh8IRm_UTp9K5i-)<1)~R+14hYAn`ejQ7!1CIu&xKH-)d+-G^w9@BE`i@ijrHFmA z7=u7iE=K2LMT5I1(MGR|0W~znsmHk_H4>m={F+rb;!!-lm|Jio!-pVV9*D02Zfy20 zp%xs;l(Z-AjMbO^uH<(+Q5bZB?gFkYLUM1HF=tsNZM|MB64Ti=BKIDY#R@Q%#@O{G z-jRP?x*VQ7mF2dDK*S-goKZS49mPszL(wW{_LoJH{*Vb8O)8Z+#T=r=2x zqLsU`R=UA_!zrDwV6Dhtm7>4sr@6=e&SU=S?)GD zmV%61WmSY^%Qc;;^4(oD8T-LfMB~;SheR9S#Bjb@?X}dWIBid4s&uA3`dM^sfz;c) zZIkon!zEx7Fx#Ho07EtZVDJd>&xv)PaJ~E+&gLBU5(ii2yo-%?|7sT38N1fPom*te zE)`yoJAt|s?^k1=`~S%L%CNS!Ze8466Wrb1t!S}QDDLhSv{=z10g4ot;!r5=4h_Mr zP~4s3Ql!{T_x<)c=brm3&&r=9D{IboyfVi0z`Qp#;A_*nnfvs-7q~F4eyDo2u`F03 zz49ex?>#|Gz@+wmqexd2HrW5?@X99xigyYYUUm7r<%2o3au_D4wy{s(@F?SQRlah2 zx+`ObF&A#nhbDa|q}c7MzY?#BY)w=S46bs0E33Ngb4CO zR1X`}6V7hKa*HPws5osI4fv}pWZ}9<5BY`Go@KBY+b_HoFC^WCD!z?HR`vTWSGrAc zREL~eHJ+AMm~6%GW^y|)@&6)!XUkdSh)BZm-M>yCt(^QFzpdn~`WSf93>{koYtO^F zZup(nzLD%$W>Iym$=XEQQS>K%DVZwX3J`W7sE8gwYY3p4=IiGzy>lV;HXh(*By{16 zYO`ue<<5ib{x6;+zm=D4{qsL>x@k#y=w4mrRVgF<&Z{c)kQQg-4g`Dr_P`pI?fwE+H@V_+$& z?@9C$vS{4}pIXIaW|8=`cZMK-ZpiNijaISmjd{-~$_aA)FW169!xr7|KDi zGwr%dBe9F#hDH{)C4pJ}OHDXR`}Cv7V@P0!F%comc4e?)*fZ==T4Ny30xhYEM&x59 zJ06mq3+;8MUpdQfdcp+js)bq9X_$2EY%AbujO1eH$8E^OP~>1CG5D_w4S&{K<4e#vz?EUKGA938r{3qpT`)=|gSw`)xxUm)f%>n?% z(9#N#0>dD z`fAeBq;CVD7RbO^tv=fD?XXu&2^rf5X$Yd4ch%K!qtTUNsMJvp`%{<;_HL3HeX`>9_3cy?pNQ`e`2166wh4JFUsP#?HQN z?|U#xM=Y;htmn>b2#x?Wrrbz#x@g}h_bXpboDsD={oU>#B-k#b_^F5`Y&X5BnU1AV zZ68ZEI-<`qE@FWpqE(lxv*%9ynj!B7&m|ns0p}v;ESrCb3V6;0`6mLliBZ>Y^7Nt- zq*bw*31f2auSee-Z_R(ugxe1dk=nlhc48f0ra5YIXYjlPCcJzk1ebmIxz$c5%*;bQ*&wmY$xcSTD6tZCq*M$|5B?NIM_9a=CKJ&e#u60j_3F! zYb2I5B<#geH}3}2uM{Lr*In?DVka;a9@9Hd46yEaq$8_?3uHBEyN%P!jiS>@FHbVn zCy7S^qaK|;i*cB?#zL^9c4PaS5JPWEfto;rV}xhU4G*fr z- z6C|?vaL8&pSZ7hoH0k)*=`>-#rSDst_WN+9#?O(?gM0Dl!aZ9Nt3`}ytseO5zSWNz z8~9H?>aFt4C5Cnp#>{rKlLSKf;%;;wkkSwMOpPu z7{K7+Mdxw$H~dFG3I3{s3T!aQk7XOn9Nd*1i&6g-O)}hb!?_jf83}x(ko!Ut-}Q(n8>d8z30WD7%i~+rkQlBSTU!hrF#THQ?mP~QYS8) zGz~Y+`W^)G_(yh=lceaa9VwiYTj{-Z&|$O4*^q3~KSN0k?)U&~;5|#0)4-Gw(MUj^ z0)Q?pPDhC2N&C0?*wMd8ax5@#X_H9mnb%jXn2s-*+T)WaX;B2ge^waZ#2#$J-tL^L z-6%-Iu8rYHe@l;w6lA9b*A;#Z95NXSDjuRlb{GAM!;EmCLw-B42eWa}nUU6r!1(k|PRs=1nW z4wHMY^kND?n*jNt+ml_(@BZ!9SW3{ZpdF#Y&o(>%5K^nBzgf4xV%&edK*DK;zy4<) zA*Q)M-PqjBIMknDV=^Pq?z;qv_&p+F_DIrXKn6OSm_|W z!`wPHiW$X-O*koH@uZXwUEGThi&t2u#7uOtqQ&pWG&n9jiGSxGWuQnpIi+_s2<_Pe5HG$N#xAodydI63sLE&Sf48 zTvoLXa!GGIf*f0R7v+*5U9$FT+C!v5&`UJTmN=_cR-yW6WPICe=y-^6V9tU&mqaz* z>si$6wS&5G7>?kK@$_ifH1k;+67RwO(!oZ5TjVPeXdQOAf6Sp@LL;0S`Is_?r5fSf zOCfNk<#nNO5$U`tyO8oP1(kC#*~cHv?o_kdc(yev*M+Hpk|db|$U!z$dhe?eB%Vk^ z`oucA+_p}>!yv@0vUYu!;v5=mM$sd)>{B;v7&`^y&k-J-TJw}-~*OYgVdLnc_xv6Gl`yKuMtYs z`ATUV#QMhTDwy2Sry&adsaxwbWBM@Kq7lcgLI=A2r>rg&$wN*0trbHL_=vBB-gCI! zTi^#&E!vX0_Dl^hNrCm_*lZXQ8JY18HaX^xx?OwhafVw@c8(<_ZHtHwj`@kijwJ+m z^n;6#E|&V!?5g4Pu((*A#r3wDK|lSu-foVR_m>1LmCM#^_CP!+68-#;w(*%YFsNva z6L?wqT*x|q4fyZ-5&IEO;*Q^Kw(s}rUfeUA=@#Lf4O|g=!m!RXMk$n<_V`xf{OgAJ z#9hKhN7_{^Mab{|6rb(9AZUxo3y z9q*>L*>vKF-vp!vZz3gl`Q4q}?$&~4PjSx?M!A$C)o2?~&Mma$ zud$@?xOd3yIKg)OePN&C0iU^ZI|72g@ue>~(*IBaY`{+z0l3%LM>GQBlkwn|u;ekt zmVGz&flUFT9qrrx=Xn~^ZU7u z?>9v>QT2itt5#!S{bkzfd5TF?XJS?HEaJo{#R0yri_wP?%Fbn$SV1Xj9T^YNh07OD z%VYjy>sz2#u(Qq{T>}PgdGprMu%+VK;&Y{yawZR8tx0C;9Rx8CfY7J9_ zWW0gKYFe(-4c#iqeLa~sO`SCTq`B=~nAf*qd9HOL0h3fUQUpgg0e1Q<`l9=4hb$G{ zEMwZX*X!cm|TOsf>Ubu>flnA>n(ogb?Y zNGUjJT@J!tvE^ET#ibn{y#fL+Z3JyUraXRro|RuR-gzQzA>KmS9!x`?RFIUpud~-S z9g{~fQMQ3^P(h5mgNVjm5U5|`7T}F*m|BMp2hN=Av7EjJ+Yu97(n#h%)|4c}EoGp6 zVMYJ43xg!NXezfGbkX<9exz9u$d+9Qy>~5CfYH3|tEI0S@PYZi9gqvWr0r7oIthJ8 z{!{wPB5N}`r*KibwP2cxFvA=xF6Xk6Kl#8frW9t-OCPOIc2KNVCIOF{5gbGvUf$?8f7kbN9YW`p7 zf?X|$|CffDclg-@U<9-Rc_M0ZoHR1W5!>>b<@!rU4Z?1P(*!Ny&ZIaP?u zFc%}^b@!foE9d5Eo%j;?m?@h>G?~$a#0>!eb z6RY!3Aez^uea@w5acjYAK&PdpBo{^)!PZ5l2PY84X~4>1y;L$J;L(6Sl!IbB7qEE% zhRq@>7b`|SZ%dr+SL@)Kmi%Izk#~TzoX=-36i2i=P9oGJHxQL9S1AY>v;G2X8KIGc<2;*cdaEn+&;R`cj z0Gf+(s$Gx%By`Q+OF5^onpK%??C2>@#&}wn=Y_h13CvYJ zz?HJtSSj=sMqy>RbDlPJ269Xjc+{`j!nm*1InPOI`|D_%#HF!`(YE2z;K_u3Dt7`# z0_)If0$U)r4e;@mGgs;I-cL(i-w_carY&x9WVm`o8}7#k*xBol%2KBI+WTX`owu4Iv)?$%sb55(`JqD+3`&FD6Fh)lDdv(&x;4HhCT#NRGBHqiQTTuV= zf$5DI3lT=7udwD*o={W25AkBffClkGg5_XXT*8duPQs7h68W~!8&-u~rVTlD{y#$s z*?^#p(q!kQji?=jUvpq`y=O|{GiJrDVJAa$?TOu6i{LS?5fX9UyLE=i35DsU`IAaUx0F)n(X&xr$?Fy#jbprT`eHpJQni0Ozvjb>R087U6 z9{J^HQ)-pbvDC-ch3S7kU<|z`Q%oF+eQTivCJx8;&j&H8xIT)pQXP3ksJem*j#k@P z#`h_4wL`n4o`a-6O{!1;r8=Yx$aa!HmagKeU$EQ^F zMtfSAk^LUQyP_^G3SZkA1qT`6Vx32MAX&1cMJ`a35B28!160-?r9fJAp8fu@C=L+q zNMl>4TXw^)u|{Z6#vrX2~;OUJXvMNeG2FZ;e)9(9mMC54?-vYrF zoYtJ{cDF;f_om|)caMTD_B-3ZN{5JDiN)px$w>m2%`>(vm$&8iqYeZc?xf2y+5>06 z*ksFGF@-_Tw%wd#+rNH5RoC;km!()7zZeLNGw#M&0ZLuqY@u>+l5V$f5M@?ww!vS5 zH*I(_+b)IDksevTGI4j(KTf*X2Jr!3v5rP_ zIxQn}HR~u|by=<^AbkuOU^oLApv*e-BLhXG-05aqL}0r%O7^_CP3%2iCWqg7F+_&5 zkm>lFyzRH%KIuQj@n_ptu&;ae_LS(+_w7dh@a`u&tUsf2Lmf8w$NQnJcIemQ1YB{Q z+8@@980R_u{;*A1kF47JMxX2l%mwL62J*G24^I!Aei!#nOA9rJ&0o?V3bP?OC{HW`=0UvwK zpEG-T`o|ESa=t8QdFYReunl9KNlY+kT{3ijXbx#?e=3^NS-P zzLE(bzTpw7|9L^QB0oRTLgg~}ru!-P;TpfZ9M9#d7?K7&^0b&FD`cMLH%e0m9uG%q zx)qQ9zRs($>I}U=Nt#FNoE94-zhyrPlD>j8e4U$bTfmSYV(0pp^>JtGVl-M6i7TrW z?4hznH`>pQzQ*%H-KFtLp6h}P>a9@Sf-s-y{uI|^J-?nNe9yHRW7pK~pYSo0DXEFk zKp@zN%VZgztAPU5BO-Z7jG@h&z%V;s*faskKKY1Hvod;j_jkV()XTUyc+@wx4`LkN zkQ%AiaUxA`>Y^CHRJC-v3vR)jp${&^2_(A6xWAId2t>$bC ze0+|kPO~;@eXsuQO!MBo{Qj0FcqAFJ1kQK9R(GX&M%vcwlODu)w)XACEcv9r`PBap zKKy)iAq*iu+kcTdpVwT_2@5elmv$!yZnOQ<@iOn@ERLQW^Ie#I)_e-$JG}qmgM1i z{k;}XKC`>54}r}nz>*?UHONSdwf*~o0QbTyk)hd+F8*O4NBD&!kv4wz6D&|T-nrS?~l9PudbG|SSD!_ueq(LlP^53QaPb&iVfPG&XSx8E%)uYT_lB! zR_^-hvvfY(_k(^-&^Z+m%dxBIRt}}ff1dlK$F8NYXSr|6hQdeMx_4&_c2VFcrkjsW z=xYyrmco=0#{Z_+L-)z_7A&BUg=ma)@>bW%k;}qmq)>@~5afTPj9t)Zjt4G3xKu~J zxsYQi!poQy{5ZGCQuA}(@^QedK0H8VPi`}4v@C!A4>Wbc%Z3&ar%Bbf0Z$}Xdya!+ z0yB(LUN8|pj6{Wn@>n;fD|JFi<(b{;d!X^$?#{(^?$9=nQ~?oy71*vF9+!KvVCBG( z<2GTX{KLu-qd?o)pxgf~crj4gaLtDbly*bje;HiABT5O;^4)5|ofqX$n8k$U)wB2! z;y|-Oko;=UrSbJi>-ycy?t=CP*OunTl4za(-pv2q+BFJ?zGD8n%ioHQZ}d52pXghB zdyfy7g(!`VRH@x-$N%PyGaKqLP;y7*!|T3W8D@YuUzj{|Yj2f}B0E=@d7b_vDL%&&Uy~m%wdQg60m?p+JbD1DGuxG8iRfA86v)*Vx5tdr$g^D8yB0TPy zHLarl*(CW3P3KG=EhoYp(AT&$TJRZ(6{l$_%b<`i;j- zN>bJwIxN#Z!pyVRYo1$n+h+l{Lixj|l+uX|@)g_-W)Zz^RQbWCN1P&dhG_zumZhLx zQKRUr%Uy{U3}Sls6owV$!fX@cH4uNCFwr7*EqVN^?!f8shgG}htdrebiHj;R(m8!; z#|C^@io;an2QHV-8Nosh^Zs`nt|C)m%^zoE*N{%?_3sa7*$k|Yl+r|2;7@&6;ed)U zw6Fxq2a_Qi>40cjC|#E4HzfvJ9@GS7uX{ln_`0FMuT{;gJ zJSi_1Ef*#inM8zHbAqHKMs>F8Ky|jqE3UR+M2}SnHgKN4GvPuppg*2YruB1K&sRY< zs%j(S<}6jdYKF`^R4l63mPey^FXnj>&d>t78n_zs&ZyBMGty4Fi}%E>Qi5w}A3K*M zs8_J_AF_OGIjd*S-Fc`!yW$&3_j}4+bDbloSi5j7KhqYv5R>!%;J?EJNXOi<1WzEk zopoad>YYn&boAYsR^6@96LWt?z&W4onIfi>&V9iR%jdnA0Z1pry|Il>AM>LfhP>#X za~gJ@kA;lHm2Bv3b`6o{Y5Nl0k)!k^Va(-l*t-u;E;4@lfJK| z_p%1j>!%+!Vg8>V%*SmF-D@fHjg(9)0)l_!xq{`B)*U4wA=-aV|2`-;SJ!$?irG|( zZWvuOK6uL{3o%k=jk%UMJ|A4Z56s-(uy&l3jaEadGcf~*7n@|vrc1JUr*NARA6{iY zZ!mS>ezhNVK`O)@ZS{# z!!$ay`SGPQfwbmqqvvzrdTs{7gDu5QSQsDEp+4>pV;yPqxf^W7FcktT&7FZArRfa3 zgF)8qDVtd_>xHF_17RuKhubTE5{xrssStH?CGBQI%SxY$r?ePKgzO5Q^7VaW(w3NO zG-ulPcNCXGWpTu)hd%}tz6Hts!9)aiLwe=SpstK4GqKOHfEBy0!;ta6G>bYBt^6p+szoU<*UoePwS%*Bkn71OJ!_`Nh_ z^*eFNSzke1@oQR*1HHcHHoEq8-Ax@xjYP6Wp9?L^`ns)Glulop<;1Fj0&&JtYxcM6 zws=Cywwei*8#okE7HjRLfHpuXSwz4|`FH@1enbRK>N%H9<#^WvA!101Si4W37_~t0 zqyn>K@-0IbTJBjaofj9;8n^OITTQ?+A9mFsPOhVxDyJK1VT;1M&s#h;`n9tp{=BUT zK+cjJ{%}(w+G431OV~j}h|?rh*$3uS0XA_NkcO$-SLPX>BR3y1Gh1Nd4(R!b2D^NitlF>=j}ChKp*|TiI~n(*zc=f!F`Php$x-8F>HK+kSfIuo8A^h*8@+ zeLNGj){^kOu0Mj+SlDrtzPMZqA6EvNw>iK39C}qTLl;&5Tb`L%ASd`8;i|n3$)Tke z9#fCBxemZZo~NgW(_*iv5|wjqqQ6B9z1-1%Lpwf60fW%omP;TDPP>oc1B2paFUw|3 zt5y;#&s%G`4KypqBoiscXxr`%R;;bIA4@WIrii`-uP}H5r~H61ACu4Xn;@ z7>)fMQS<_IVEFpYZE;xu=D}DDQaD2=5J9lkj)(BL3;~`#Mui6l$tshX-9xRMm7B%g z911a)|I6@NAXQ`y!dSCCS1ROEpKx3M;W#ZHm}?vYyd%`XoZc1vsn}sHgO?FlnnI=w z@XfnnpVJ^PUa3e;zAKck%#H2>O5Q*z49Zs_3uvXVjmY>!5R1GGhswv)8fX)>fGPD1 zDBgb`(u>U3px7a$I!qOjN&}#OXw2N(sj>Kycg!!T&g81{K1e*qj{tGC0&fVV<#nQ_ zRnn)Evy&ZpXRBKst=75#!_CBnJzEu@j)1&Bk}igEpt`L<8_Z1aSz`?EiLnx`TCYV3 z3t#?v21k!J)`jt{N^`FGSiz3Zbw;Q@dg8}xao~L^g)?#$#~+AXXu9K(s^kQeUxKpq ze*yY4Sou`fS3O?iQEsRhgmXx!(CupXjDD_LPDOp(D?1=Pbb4hO$Q%lk0AI+ua=!M8 z>%_Y7{Gey8GIT1}kY02#LhoYA-EX=7>s{p83k7Zy0`9;DofDlNQ7eTp$1@KXxTF8u zegypnwlT$XR?HFp8qfB-4eYp1e0I}xKbMf+-|J5{;yXgdU8QrQ{MEBtuXL}X!MK@s zU%=FeQb>V#q+{?ZRh*`LcLf_ty+_f8Qi*Lbs?*XD7x*LuJ*?+J#p5VHH#`v`aq|i8ym7D9PmZ z*_`N_-x6`wfIIn*3ha zT@C-XhC;gOw4K^`3=1)!{&ae2Qm@XAq$xJ*DXFPr4MSs+FhBvzq+p$u*E-R2F1u4v z3^ivT_WBPMFu6HQ_*+$nujM#$-98fj!PKI<;_0)QAiNKV-m?O#*0>aJkwJ~wOgwI{ ze3&WMkhHQV&8X0s_6ANBdy^n|`488E$|BL0hQJOjHSBi442#@5i?8@lu_?z`xI9TfHW9Nu3LfFn#T@U>p2(dH#{96rT&2f34OW* zYHodx$u=`(x#Az=N2z!q2Soz7*$T6Y>pQoqSXG7Vc|W*8-y-{0Q>-e?@xzyh_I|=N z5PQACSPuDW+9@rFGGAvYi$I)lg8**GkLJ+fhfV{&b=9B(O}J2O$PYr-6T#t;H39!O6P!Ci}!Bf=JJJuR`?_c^PN)U<^q)&5$GvC)?Td%-Iu&a z>)$;{G0q&i&vV)v4tj3C$C}y`X8gdReVWi7E0vAoSQQZBS*oKAu+>^vcq_4=9Jo*~ z@n`2swc(9=0%{v6RE8@fdt0nb#`J2UE_cT3S(aBtc;+4rADf9_8sQc28(IoYAscio z!%#t(^eBd>ekjTjI%kP6OF*ez)N1jk^YWy$7ub6qCUxaY%SOpgC6SnYF_@h%9xpeO zsh$dTluA1lq;d*=#!UvUQD3L44@8i)Jg_Fh1yV?^`SEQd&}tM7%Z!Hk5rLQ4gvS(ITngxWeuPQU)3y~4u917U*ZvrZ}dN;(^Yc)OFS?l zQO5`;zqZ$=B@-_-G82=}WHr6h&yP`;BY^gc63SX?vtIOWgvGq366j>5&p_?1F5XA- zch5jwi4_E6Xxck&!<%wSEEZ7q7LGO=b&L9>%YALw9OD(1M_2 z$lzpGu_u=k)IPhx;CcS_6KbX<$irt{A~fU!J|nIxHWlRk2hIucw4Eh`-uYBVf&rPjSS(7c8sgKe^_4XeWKjZMs&KndE^=Bkg%we|NZ|<;D>>U*1>}!`DgcwGg zN{AYHVa@HH+%w_5d415(R!-Y;X2-}}X>D->5W$0dO4jv!$iuYI*MJ#MLDG4tE^@r? z3nV5G9nQH-SgCjo>9^FzA}=tmGbhk^<;)cy8WaeCv~_<9Ncsj;a9Y+^t78a?>rgl5u@`D!hN+uXG~HLIa12ITaGbnmHD$>OE$c3@!+KUdeRYlYshBY-^20Y)%gWH6tKGqq5Xs*n!Djiq+p2I(w$pcy z{E5qMxxaa&t~#HYV|tvXV3t59nUmD-&zg%b0dqmbuq78jFf4WJ-CX9Z5|%#GcF9u65iU>X8dpf&`S)<7WG)_YTo%Q z^(ilNdAM;u=-wvDN1G-vGiBc{O@7HAtBGMc3ivv#Ovc9Y=f)-rm(d2@R`UJArZGWJ z707voDKLIDtfd-5WiC({V8}+3r1Z;INx+OeZV%amjwbsIMRn^)S8UIyq>?U6Ycjq9 zB^C)(H{UhD>bDtZko=l@E9{Up^hp3$s$rKN2<92xkWKR!<)`{22- zEk(QVixH5Ac@yRebaxnqTE}BjH^|$;sbSq*u25Kh;FUeLaY!&XheiyUqEXCkl@o+7 zWlULet9Hk(RK98T&Fd`vJRwEi@UGcej=NvC+?a>bxV^~m<+@F@CiY@rIp{}tF5f3TNdxD}Lg4urYlD56(x^sSgRZr8-iYjQOX$h6f z(KAX`LS6T*M4^3|C0-B5AHqi4OwKmy`zHJT9V_f$Nt82=D#JVvJdtX*Z`#z zGjN=8$@b7F9jQTDp$I7a9PxnwBQ$B?*#M%%kqF4gV zX0*wtDGBQEL~Nyas}ZXPs0qjKrX2;@UrM9x)&$xHDXW>9SJd%j$+FcyFk zD3OPp7VZmRZpK@`;x~S`piY3KjNny99iZ#Xk<|xF2I|-#BFPb3K#|Ccn0`gg9){8a z&CV4}=pOdOBHIyiYRI)AIUeX)1rbjQt88L7(4rtQd*myEE|3|0&SHb#^ zJ>g5IplkBq2y~|HX-?7G`khTM+eL)gijjr2??T^y|$yowVps&d0hC7 z7}fJI+Kg5TBauowSB9&WHglGO(OgMQfJ5^tt47ZHX=S+!Bw_rwg@<%)oW&8%93!Sk z_Y;J>WGbY$Y(Kq#dvyLmDAxF|(rgoXm`F0^0S5YL&2H&KrLpiy`n&Scia%c64yEw? z8a?g-ZhimfwonnZfDI7X?Ns(e^M(-PkZuSG{3T*g?HMjtoaA;Z=nivQ`8BshWm&Mf z_>)hi^RLoh23rt5B`~Up+Q1vWD9Ix}(SWV~cc-uastp_KACV zu8P;Nca^b>jY>2lskz|p-16NEvqpox|xV;&Fq)@Tn|s6Qbo(tfyVGB^4J;=V{4ksVa6HlJV> z2T2>`;Vqz9N>ccihQL6u2K+hYNY}$)b`?$Vvs6n(Owe0T3K)M(sbgm}kbkBu4Q_6; zcUHU}WWWJgRK1xg8*e0QxYc+*m3mTdYMY2$5^+nyoc3esRoHx~v^Q36fz5`HeSVR6 z?h#9E#W5!Bq=I+@=doSQjZxR&T)*0qdT8^zN-6iPbR^9bZxtVbfO)EA(nH_2hv^}s z))n5#afmf&KI3NrqGUD4zx_EU5rg)~#Xfp4%1hxPro+aA?+}FIzBWdYLNhjeFS$Jg zsRq+`4jGHL=eURy4YyYh~$?# z;O1a{E}1Y|Mb904NciZFk4LoTD)sQOy%;FHQ&s3_6{``bLAh}>&6xj!zxHu#`2=42 z8HPN26@ym~?QGj;n^#^hPyG3{FS}}k$boz0fAo6IG%QD9GaiIpZ?pa?ZLajU!dDW* zx$$VqPvI ziULCA_T&=9SxRWesS85-Df+_cQ(nlQSHJ1}f&YZ5L@s~-UYqj`kF94+VJ1yj3Eey= zCQ{oNN3StWkn|u2&Ffi*97$ekZOxSON)n1J(!gAJ)H3vJ_^t$B^jZl>KS{nEWK~Tqvwpt6|kB-=iqH5#tQ$uPR1% z-}+EnNV*iE+x4l{*25_w9iFDvVd`yhr2pe+C*C)F%j+f#OeyA?=t!N2V3kj|A4Ii}ETL{)}W1o4gRlnAn&5jpE%%RKu)D%cG^PGZ?odgj}e= zWacM*aZO#W7muDoQmV@~w1_vh-{cRsvyTS{T<+sZW4toSh})W<$r9QdpcRYOC6Q&H z(juArj$t{_yW{ldn}E;a#`7RY+j#ZGMe;Z%HZTp!_S}k@&pxUU-5H%YC_c(KNMes4 zWbA@x)5yCN$0qINeYtWNzSG*ec&5EACElz~ZwgPwiy1#yV)fu0t!$y9C>Ana66EOr z(DtSAg3Lf?X~k~UaU~s6a&H?G1ET<$X8syRMu(5$rWf7zf~6&Mg_`W#a?J-1?~}TD zxb-FVEd+LsaRn3J}lU9}z5R;RuRSWJ%BRv`RT zI4dA3!E0prpa9k7vO?50wAWJWb8>T+Cy3xBB{k>VL$|=O8`l5k9{<|d1#emr{~xG` z^hMG%ow@miR;eIp^t;zvUB7}&)3(A%2v+pBa3-7V^@VCxMKWZ5u5+j*i;q1(uj;c| zs$^~RUM2Z)%o%~tV@WWDVhEdDnug?ld$sn~)14|p364K{nsL>Zr3;EkSymRYfymkw zg(^6K*8~)-O;3y`+Q>-I(|?u5sVSDfelu9FY=?zu(7Y%SO#socq#7&Vh>_MahFLy=Q=Uz7o8udplNI7|Rq?Q1kW?LQg=U7YZEqTAJ0{S@!@T7O zzobMYgB*mQr9jTYQIXyK*qoIa)zBG(CEptOse50FB<78}J5Fjc3c>Jv{GhhSUgXal z49h4FfSFQ}Wpko%}a+9dh`rI$pc9c4D8= z&2iu<2Ytv$P9O3#@fUZSQ-1$iftRkzz;$#0C2y)D7iZHnV)06d6hPzqoADsg*gSHAs2qyOD?n$2JrEQzdHdlcnt+E)Z(3lSEYsQTDvJ+3_uspab z*Ed9%R}IOM;6>Y5+yqJxJl4?7e6^G&y|9ll5VUnO<_{Q*)@6KHnP1FnUeq0L21+6~ z6VG^CiASHHb(uRe^Xh7HeO~SB31KDoFfYeJ z%$}yk0j{_qod1=U?4Za^ZT8cQ^L!Il#xgnSt!O#?+Z0^MqLagKe+O+axzj(LkYn-Q z6fWQKXSE+%IZ*W4w>J!evxAIqUMZo z+nK~PI9=QNG&F5Q+t;RmwlBBKt`5xU`yR%=V(R4^caD1D`PZ{G3FhDRIU|v}!p^M( ze=KZ`Ze?k$>Qx{l<>3NKqz2QIhGKF|QjhoAY}vx5Rmc*=WVhlEU}LVJxfdm@*pIhf zU{Dwv@AC0e4Ja((jy`fHvERKsz7m*NwH?D#nvV2!p;uvr1H*59?7hX~Hh=7e;9>`h z#6O<1=hy44KWbj&4(@lC<~n3672N^D^Pzr3u)z^p%Aij?vX4Vx(n7yJW0dDGWK(-h z{{l1*3^!!Wr|#!a;EUBSa?8TV)q>XIe9UKnH1!ihUb!^WR3CCK!6PZkx>6w3wj0J0 ziY@fzu_SSMy=(PU`l_=V>^A~ge}VZrzYNwUe>ypKc|oSY#NZGSiu2ppq2f0zo!YG_ z)>%-$U7@XU%p57GlmR3M3RL|uZWVN~u(ua(9QOb-n-iRbj)aymoCy~vw)Md-kmhsV z>K`s(m(k@MQ|ro*Q3a{A&!ody8--Qqg$V5^tM*ku2@VgbUQyXebN>F1RpZ+0BlX3Y3cS_L3x`sBXFCCl zI$Ki+RtkCKSc;yZNiNW|xdQ+Pc2Ofydr` zkz4%m#@;WZhiB5yPIXX%m>aph#N-~xotfA;_w1I+0Yfc4t_Go{arCfz@6qSIrmBko z1>t9^?6ZkUhvr4No_p3mCFMq&U66lF^;yPo`a0cr*9cxlrp^|~<|z9dD!DdZLGzZbSoxryCp_bSX^z36ywihjByOKl!P0{CaL@4q%!<;=xMu)mv)ZZ zn(3A`OxF>G4+q)2 zs2)yRI?yz#BA^;Z{D&XVZAYmdd~*y{+0v_d)1~~hmVDH_(xCl~na-N_p9?qoVST?5 z70;AJ^)~x1+iDz8H_FGO-Zh3F5EwKlm#5J1M{~Bh|CrQFB7t#p%Vp!#womRTb9jAk zlWUE$Op=gt;T9gd1BmVH>WM;fOT1KgoVmK$sc=$28)3 ze(bf#C5V=Ljpg_(<)YZb|EdWPa*H zzJ-RrgX|N5nQ40{`BO%rm`^j?RmnoO(WcR}uqh_Z_{*va`kGx*P(I6ulvbKotot2_ z#Scn?A5@Le*Lry~bMLcHh9gWXJrC0rNKLlaKT<)36el4Q#zcETom6qwzqi5X-9O*( zVDUs3x-<#A`nN-N%6=Fl=NI9 zYavfhDYgx0UHMbmht0Uylw|Favg8!(-$$sqR5Mzmc{VHgd<%#)}!MYtv{6 zYu@nUnM=al-|f%UC8%lQ722~3vLc+ud0uQu3A7W8KWV@U*yobYLSO5Vd}9sfB~nAg zO5Hhuv@HZpcG~}hqtB`%k5s$H{$-EVFl54`J0R->wGiAcCl+Zn@|ffdJBo5Y6G}b; z<>b71UvECS(3NX^mT9)}`8IrPC&upGw;E8LqX(@@6}R1e$3|z&m96n7RjkRf(WSao zv={6ZycHe~L?h#L56aeXt)`1AiPIgRQ}@#^YKF&<;-6!5ZKJmzPo|> zIX$4#+pErC-L0$*y?ps7j|tw7R43AiZ(5V|4!_7DVotCMaB7)d3L+A{~)0fuSMUZ4;xeb zCos-Jo{qNZr^{7aPKSx~1VOWu>6n*{VdAu9f)zEdU{QX8)u&x&|7R=HPLZh=V3Qb@ z4!=oey;-qDWWRX$WRSWzeH}@ARTD(lq``vNiDXe36y=08M>c>s$K$p=hRI!BCORA7o4RQEL9Pa6$(8DUd&(Y{{$c1#{p^ItR zIoH;q^qU$oLMBeNZ#u1@*WyUjAtP3#o%*)1dT_m+%H?!vdyTwBpZ^#Zhh;fk?IVYn za#3J>8K5{0G=U(PI7o%~^bkm#w_Q_QZ6hl@!Ce{l8e1>1ObiEV%(wjZH?b356%H{4 z$7RIWu7rcTFl@EP?EN3*%WT(6)jo!bP5Q!OHNQyM8+3o|Yb?@?EoYh%h04^5 z4eX(a(GExoT;bRgEv0q3IWTCLBUNBNV_I;&zSPT#&_M8S~%DewI#==p!>`U;@7+I3yrix+oym*DQM z#a)YQDJ`xk!2$#d6f5rTUI-2?#fm${-RA_p6lK zfBaVl>OWJu;v`=x+yCDeZ*fJ+Du`xXX9?CScsZMN!3KKzE*UnePY4_w14hR0_izen z40^iD{)SaMxLRFW{qa*nxA{dt=yL%XYsnUjYAfydQB_~~so#oXqG*xm>v#%>c)lnd zTOWt?H*iCP6*&RXWw6=uTZVM^u@r&!0Gl=%#zDbdJzee7EWw_7v~j-#%r^6a7Aw2B z$d9UJ1Go-!%0(GKfB`oMdidl z@KB+$rhT1gi9@=3?$hfjnQ&J)WcgX2kQ?V++x2w24^H5?=jSNgp0*9Uxu-}Qd_}S~ zji$t`w?u153*RS3=p`!befng}HLi$hE%aiV^_AI-eqksBpS=I5mO`NB>eE}SaJ&Wq zo)ux7W}FG6*kBXA8>xFy*dIPmG4Xul#b@UD6 zfE9lF@g2kHB3@LcIXYiCqXS}BrhN~{LqFX|F5-)@j`T+=M<##(54}pAc-W^ex2Mdz zvd162sDPwDg{VI@_6}h~9_Y$ar^+M0t{DFG#&7djRbnCDPwLF20XqS%_frZhiLl-r zw2^fD@@SEk!k~rm|F07nkzC&ajMa0i^F6`6XE25MU^h(sqXs)WL36Rq7$~PeZH}YX zKG~w1ioT1(N)5cr`2;SSXU02!(a&Y*W*VtU*=|q7bcz0z_(|$ZaO_cq&6?Fr&U8=X z|o-zHPnH}#;am8?_%tP)eE_tD@h~$)wlw>Sp2~6gVftV zGGim50fmca0gDqgd4vcvaj0&%GZEo10F5VsM|JC3qK|_)VNNhc-_@Va8o`wIr-+I- z=Pq3*NB1X|uEZ_7^OdpicPEP8E3nY>so$SpFjk6RoGoU+bP~SE{^6W-jSWAs(qCu4Rb{0(Hcyq|Qp^fw*N?fjZ$E11vYO^vN@hp>DMhy)*@5=rB+!jJ6;G>h!bfmN-^?0h)Ke`*^@l+Aw(_xztd3~a`7YrMN zy8Y18=?}3DDZBLv@v^V~^ql|W6xR8&`WSRkRgxS0VCwPX5C#qe0h`8E?yj}gltOY7 z*vT5mLQ!!=6PWi`;7(6|HP}u@Z|bcc8k;I%p<8ZXdJM{^UvWRMCP)+)_-&Q#w4l|X zE;b&!Q46Pr+d<3PKGsJm0+=+?tg%q&&=AhaCUhBqZToxrk?76W=0xs`$8p;>f}QvH zF|@TMne+%L`padS?2^2|Z|pMjpah_1qyYgXshiJ+CL?$3eKC}CZ?q%+S{4u?-Cl=N z#M?f6iTDzF5h-J#qH#$Pwlv(3mh)k8tAr;NkJFnVD`XFXG#x7e{9}wfZQWl;N%}U- zH~(ysaf$$z**UCLwB!6jdASMi67VbXjnCIBMK(Yu(V&Uwe23HG)NPwahaO0gnp-FU z4hz;u15h4BM&ZLAkHf_tCvg}NfKr78s~rtxKL25Rw7k!_K0SjiT6+ICud(&Z#5ej! z0?I8B`a1_>8E$csd#fCuNy!x|vMz6Hlh%ud0)0p;7KCb9!j0tuT8zGXR9|~|-Xarf z(og9jVByyNk__h+tiu^YKJuwU4qf;8T1QGx&-;c};*=22;$UgEDXHn{BPVYKRFc}# z#&R`xyI*MHQ4`F&6q#cX7wivfJgIAa%Q?7M#9Z9e)T#0vE-1nj`4HM{bAbPteOyk| zGj{WI-Fc>d*1-$R;gHbMCwW^7wn6csZm#&rqR%pZ()IJ$G#t#c+9@TOYYX9xYHR%X zJ~~z&M9;aoR!pK~kq$+kxO-SZy9}WG$eSLa5AgkRN(>B!c$(NbgyBK^Djf`?2v3Rs zROo)TxB}!y7}Yg4&w$<_0Mznfyh=NO`x0i6ep5Kz6585!6G9uDDDh7VxiZe?kIUtK1yVtYGuy3tB=m{YO})yhUL|n> z_{m#6gZgD!t`j6aMFECAt1Y3sb<7;ZI%Tf3;2hE)xTSLOi+UmPUK2-^QKSDAUjA=M z4+ht#n*UJ+`^CbUb7l{s1aWTMm`?Q@6mUI3l}sX(4wd+Np0#yk-g%yK?j3~E%L}Wn zb=1JwpUTjzh%~jB&rV=I7g(i2&)Wsh=~nC&5Oop}`-l z<99c=nQ`Ou$dlu7YH!ttj&5JLgRr?)eSm_#uCxq81DQ??lwEBUec+=&9Tw0J1QZifrOfaY8Wu#JyY%aJKXRBh+!7QP3a(#ptY_XFSKDKYx| z(#T$ovmE{6gdK8)1UwI!BKTf-O3Y@))LsN*&MdM8Dtj?jBe*?hJL&mf~jZA}h`9=5xipN5avl(4#Yj&R3 z<%7&Q22Bm4lZ9iNZ~vfkov$RwP=CYErklRtyUc}8kYt& z3e+JyoZNn?NJR7r5sJUp^>&RP+v?@HJom)>?xv{pQ&0-F$JCsLs{npv;%}v8f$!X> zzp*{@Z{T>*c(l8x7ODn9ho#L?8ou;>(mC?K&NPuK7qQd=SRzl30dnn6VSEmN6BoDM zd4Fw+H2;s#7Z%b?ZxxQm7_MN5?!&t&3Pq8uKJcUXdwn0XfD zcmE3(#$M5MdUfA}E#|d0f9N~`Hixi+&Cbv^@kkRh;-LI;>x_N369MSwU|_obIe2}r zOR|QN+eDiM?(=z^)KKf#i{JeOU?6Qjd@T9PJwoSFs$3iWM$cb`BuXxKmOy! zcSW6)Wnwo%p^>O~|FZ&tm8H%ZT|8`lYzuo^y~bH07fM?RL$0@PD@$YrmUyRsEMPH=G}nFo(q`9p<qRY|*QLk@cAhI`~PN|PXA-(+s{?lb$WXM{=?pm3dFWX3=+?ki(ORyg^ z1%xgws=p&<%JMhVH8<@Ko2g*~lWo+nzpaHmx$U5td^=;V)F0(RB*QmCx_xyVDXR`2 z&CeO?TV1sn!WySMD6A-k?WZ3}Q12-IzyWx?Sh$=0L%p<7qcdxTD*$)LiA#TlYHo9w ziK9{fX*hhK82X&^)&9>4*hpyVJN&P`!ntW7H`i`M@mwuUpEe1&!Dx=D78fEXS0aeV zq>BXFxldr5f{xD&ZsB5QEPr7EaQ{W&*OfjGZC8nTNUP4c$XhKq?$2RhmYTLieL{0V z9ZE}=N#wV1syb00P&7#G9NJ}>sj_}}yjZ|xdJ&UGaEUTa;*^Ct2V2PHtmch*ZFJX_ zwFX#Rwg@tF1?PT+ifR?hj@6MlR6?Pb)9n)|%v0Pw#^VXZRwF%wGgA{12P~XH*wBc0 z=PbrLekL1!LsckkFcmJ3#-U380ibwk2!+ zG{!-Ehfe5zp+rfFuh&zMT>HKIe`EAuUta zR1m)f)GRK;_B(ac-$;|_)6ePS?8aDemG`d3^^VFKb&X!B;EZrH?@vkiWsCS*iuJbI zX2b0h$jepG;Nm_sRb5G7SsRBHrxaHhDJ8+TkJH~9%A)RYBCt(VAKvcjn;VwCS68WNa4HDi++zC5yl|5Z$u|5-?m9tcNM%p?kbXPg+KJjAE;K@O7|ikgC{2?7d>kZp8D=CWaTW}XfSy3yU^ z8sZMmU+=y_xiZG^!iijdwh$a-LkUSrG}n;;7#6*bUr5-s$s5O`n(!hRn8q5tfFH=y ztE+~MG`6AyJ60ZANydt%g;mf?N5T6H_+lC+=@fm1tpySHas*hl?$b?#>M&oq}T;O*hDd!o1 zSbs7}BcTDL5f};IGT|UzGKNjWFmR(}_d;mAhc|qu+H%`ZuBU#OblepA&x(|kbd-F$ zd+xQ)U2M8tthjMoxp@ep^DZ5RITNA`$vFcmk}+w8EvH6|#_C{m<}mMvWqdQlJz7ty zL1P|G_WkR#t?Vu*zYNs}e)7v+2oit7n6D%bZ#0oesolk_-L8STP@EE3n6;*|-!uW+ zS7nT5UpN=HwJKPWwYwTLLxg$X&8mDmoAd^sCZcFy0K~29SVKNKxKr_CD9uojn8Q~HkVMf zF52rCd^5n|NCqy{`k@-$L(A^7&V&i2CVvv>7jt-0;CYc6=y2$4Axw<%p$d6^cf4y% znX)%=8vO42A*JLXcnYqD{Il*Rf8QNwz>!B%&<7!G?(Kvp6W ziDji3w60~a6WWsA3?)R{p+S9GTB@%g?@I%+>jpikZjP>te&Gj=(Nq(**3Vc5yL(m* zzYQBR@+=ogNA)~MwQT$Yd3G%VI}`IFdjgYJ$|u)|ml@-VsF6sNV9m;J`*Mof-3@YA z_Q~%mUSx zRWa*i)-^JWW!V7_i%9tgG$JdK5c17Pp7d?V)}QewV>Y=RY&AdBe7tq(u_+1K7fZOj zI3xEsj3kFz4_M%dOoP3!%0Bav7_TeWYT1FjIx(ha(UNdC03@~wHw}OQr0YinQ$WA=3HN6bVh$mbHo{s z{#MBQOeJ$+fzs}+=#)6|PCy}EBXb)1rMR=MfZZ#ydDyF|YVP)X&XwWgz6$@(hTQAU z`OP7N@UH2h62|aOoVX|ISusN*V-ql=@Zl%CD!YRWJod5%I%L*bM+R-7hY!CW(dbx0 zgyfjMXi{&*mPkx-Aq#&k{=)Zr8Rv~iK&w4(rb zrZP)iFmr1d-z3O5HM`)fd4h<%>TV5{zy1`6Id;0c!`F77u+Me|oEGb^@Yd#?HLtqF zt|WDw6@x>0x1EPRQLhm%y;$`Djy?`B{?R$r<>e)J3y|=ikL6tAeFMKCFN*(q?8z0d z{*Ji8yqXyK@QcT0tLQq~s$-Aw0a1;+^LO%*4iI{=)?`JT1i<*{ouRv^p)yD{DtnrZ zeGIhKvg|egohEEa2U&O@LTncX31gk%{;3wJt);D?m|AKXEW8V0c;npvjd!d+O0{1C zGfdZJ9)XFssnCxkgZIm|oe+cn#Cz5j8lzGLoGorpX|SI2F<6HQPwI2&*@@$Ci5l7;ACs9wr(j*XoTC=No55f2 zHyw>6Y%vT722wmvXkNQAt$yQs7oQ%C2sNb=IH`B4^grmVzBsGyW=(~$&LU;ph?tW( z^Qpfhsxi_MpQ;bbxLgqX)5#inYSEF;3+xivprGl!_B2sDG%wzS{R#s2E2r-p$NT&q z7?SrZt)z$?PJY! zYGaexqdELlt6lpxf4!Oa=yJZSYP(CiJ8tpg`O185%SshV2VAj*bgrrRn!8ZIk3OmM zta$f;g-jJ&dA;64wHSj7!l|RcA8gm_fI~9k7G$SyFsU@?5__(ZOVTpe>jraiR z>^8e_=9lC=XGM_m*!&%?MfxOuhJIk%EU>l0^0Ew~{(7eqDTTT!(@B82y7Kk>dm{L3 z$;jpymSS-%9K^=vcpR$2FM*?v-~rX2E;qzFFl5M}cx!Cr60z%YkU7+E=O z$_PR_F`is02uLv!WU+Cj$zrIIM{6W>$)C3qY~}F)EetU^;0GNhl;13q96SaPWhKU6 zzFa-U@?39QWz{3RWY(jHeOuRE>!-G}a$EL`zr8%%HipzHPxU)nS&3Z(T=B^J9If@s zskmz%4&l(^trjMDTjV7YmT^{@ijpZ^C59&=`L(!&y3-B` zBgLv8@G7RbtFL=>x+W17K`Zw5duvrV<3a7?Ir{LRyt};u9SV13t~wdzP@4&uDt@$x zTI6#OL@?d!v=~@GGs;CeAGK7R!N@k3k{Y%>uREs#`XTg|Nd6%_YPYiybH-Y8NEM40 zmulbGtP-wzo{WV7JmQRu8~iS!dIYq?3Ntz%Z^n+3MIM8%f$fm&^jjDS8|K%ETJc~L zo%ss6XD(8kA@AqX670{qX(J-TCf6^AzdyfXIi>1(DqM3pcbu5^L_i+Y40jwFmNDbK z)g~V5WAo2f$vmrDF~HuGJ|c@)f%t=98FR&iVn6eTrXbjIuIxXH3=Hs|j?N0Y@lXG) z0BJ>W2bp%%oXn;Ww-X3t@wpr29$7)T>Rvc(g$25&QgESg#r`G-t}b($9U}K1(jZMt z561;i$BJ9zcyz+4=xT~U#$C7Vk}gdj?>xL%!e1F=>c~-~eO5%anH1LAxGZH-ICfaL zKIJMs(4^SPOk7tidfZWy8_oqk*CbKsJ%?PJT@oe_|V=ZxKL%1>@YEL|R_A8riVT^X8y;Bgk9ExaT2`nK>1<%b)l0b?>>l*<H5E#S*qY&p6F(WL@9l zXd6-^pgLr%8zm<*@-6~k!NnwdHh986V|^wV5tIYk&P(~T;M`xARBq|{Y&NL4X_cNu zG6Hh=Mc`Nl1UxyW(TvD>JbN88lMlGy^}^l-=UK1$HfXD?8Nxf`%+E{#QoU{USE6dQ zTD)8lUirfY6y8mdm)f3P8b7aeHa3>XIzLTVvwqp(QsULc8c0@3N+LJl4w*U{X33GJSzu~vf%MLR#~s3X-TB2U&CI;P_AP0&UE=-zmFE~2yUMa)nHCGODBio#YiTtZt!f*vum!7kd9MNPyDw(WF+LM* zo$Z?kup77rr&hsW&k{?7mWQdHcrdw7IXRJ3oTgT5Jx$vi7f}hHdaTdmh7f?JBHHBw zIXo(JZEyPg%95|Ymz%r@mmcc`3Ex)m(jlbDpurfBwd#v)>#^X~jhx}8MnY6O&d#?= zD$)=u>>gQ?PfWAA3MUlUizalvKvA>Vr!cdh^{*YaSGSqxSLI@DrNC*s`!TgNJ0~HM zaJgI>E}ce?ZOj8gX67x<)1*aZPxG>2CE2&O1#P3jCe-Zlc1X-lr4s0V^+oHlbqz|r z7vV!>DiqqE)-^UD8|P)h$K+@FA`dbKnGqw)Br~eWcVV&qydbodDFi`l@hY3esPy8F z+r7gpr1e&0BcdIw4aj~ry-dFLp~k}uVmqdE=X!c zqyvK2GP8ZYwwxb?Y^kzj|MVIU%j{(8&bQK>K;mg?T!01O_x`GA}16M!Ve$Nx~U1(q%@}wxkZn zR=?=6_{ZQw=|9Ey4mA`HEb3A^;rifI6uqqCX*(oe#vTO023mo1x;!Ef1%H6A%$T*3 z)fRgiSUpcwbCzxcm;txtxit^V$>KH0C+?~%vk-9tqit#ads}9s0KGG8{jjU@DJpH) zc-xZPlgId-*dO-vxM7fNLciK%!=LC8c<~q2rh8?uyWT^h#322+dubs}UM*WYJ*ui* zUF$5i{LL9hX+*+L)(Vi%u&hG`BkGeb@)voJ^&-1_9_-+U!gM7mEwbpTBVW+VJa7%ubY(L;Lvo|yrarXIP0Hd zT3Pj*en4fEwZ&K4#Gg%(N&C}K`2GK80Tf&(-h$?~-Da}4SuubMD~dc7Oo2i~niGpD z@wOwKeiph++zsMh%zLZ|!ZwVS3}da1AD?x2{0msv?^^}{m{zJ4c5BGCbhgNlfk54Z z#Ylz+X47|L9&dw6BAWNJsm?dz>>uP;wJh(x&6}rqeu!FAxvAyhji)mzJ*5VcfQ)KJ z0mUjK{1HF1Qx)OLsK|M2-^unF(Z~v-Pgnu*3JxAE!-5Ei@=|%!2)2OQCYiBo*}jHS z#I72>KZR*uowcV48GWbHXH#a8cm+-_n|!_pUKkVI3FM;lJE^x5r4voJ>kN|-OwWAH zql9(N?_01(xoX#t?~cdR1uKfHm3@cR+)Ljwrld84N;k$&4o6&w9WoRqR(W7Vgc>%L z>;&cMVp&hS+7x@QPlfG|*ebDh_&>}(2uv4x^3xPsaow0%qT#l5hb7quGNx&ZsT`{g z;M;O-We)cbWcR-1Ay5zZq8hYUCK#yE_cW1T<=%J>%YY;|c=ygqbHv2ycL(b;2fad< z$Z%8>+@QQ+TYM^P)K(Pfn|;#RxPXK+)zBXqk=CefRV^jM?hw%v_dgm8BViB+d2~U$ zeMpo{6p-?0wV<&4rIU(-aX$Z@UqgA$aw++TqCXXIED~W_hVWY6c_~W5W)J1vA1=AefVyNz7JPV6V~N??oT2!cyr zV%Ue_aM%HJ%NMXYWv+j}u~C2UcqwB)8*!vFou1;bjzqde@~5dcqTF(J z9bSY-b$o1M!2rARXOfX5&2`EO6J6!l^p(1XeX&)Wf(6fc64Jy>z|u`={la{PD)kCcO-b4kVXm#Ftm-SMh)A642D-uE?nMF3KGNAAT1d4c(oTypWCTNz=ucW*O|Ms|j=KG1SYJ0CJy`rCRDbmd z?mNwmJlQG7IAPCBQ)C{T^Z}5er@&28#>pFeDY)B0v2HW%^Rx zm`JSIk-5nfc<3#87>sy$_57nrXUyz-YaK%@W2}n$^D8_{EhO*O1UFoVrQS6`g5~)} zHCs5*#=UIHapuphK2%c~9!WLsjZQ7e*rIJ*+i9uCa*+g=Srv7l-LTD&5L(W@7_|iW zFUS4ygpvo@RPKpLbi($hsHW<)#!^}_Gq+_zlHwT*-L-dmtEMbAMD@!&e8YYW9H>uU z$|JT%TG17MQG`tO<;gjr(6AaQlN{H*!hdUr=vpPt)hFek=9`cV0t$PB)r?fWw4g3( z4wZRS-WF!XI1b#bFPVm4-hePynE~9cm_L`^bbp?L>q>NQJ(ISC!KI+(eOUCMmPwdQ z2DuX1>?xt~pI}tZ^58udSS;Czom{R#w97pyu<{w30t&QYo0oM`E2!w@xE^W}ol?bL zxm+E`g^i4;S>dZUk8z&yX+NFxMWm_>hs-Tm_=hXbfcLI)ewAA+zp<+MIjN*~Rtf9E z7NuUfbwmlvlDaGKi*Wp(@Ouj|m6W)u_WJLl(UbbwS$=;_M>4T9=8Bpx? zK%Nsx9p@3+3UKioPzBET=gN`R%6HZ!Lq}O%ll$0&yAJlqI8Rsed-V_AA2R>0K71=2 z8I2JSsdiQ$pK6p}l|DssUmq`Jp2CduV+v7HZLr4pm z5?5nCuFh#JDqo9mSe!qcS7FOz{pIKbb0NV(3Z5wV6uvpQnjt|}X}HQ)Nm;u{PNA-MpEE3J*G8*8HZliH3Bx z3KnPO9A~ICVZRXx)@*=(64OpP$*8ly>1}hW&V47M43ZnMl%&YSqr$kh1n(5Wyl#+( z(9V50GSt9!X|5gKq5ejKsg;Lp-pf&!HgqOOIYWVg^H+%VH(;DJ$D+;a3B%`53l+#e zs6Fs`e`)dgF0|`Dwnv}vh+`oC?PqZaXdEE4#h~U!rA&cw6X8XY;^c{Sgh#UT@SBB6 z=M=js;7kaN%`DUiQ2l*@Tt;+OIk;GsgL~P7psLmui_fU2f^nk*9S$cPrbn?Q9poUf zC;SCsN8fRqs?3pp?UvCmx6fwfQ<6un#%N8jAw?hnviGUWxf}6tA`rudA(7X@t$tc1 zI1YhH0c39gEJPGey|kVb^r#N|Qb5%3AXqjGak|M{8K32dKEWO~;F0EVre;Y!tjx-t z2XB1Bh>qyKb>a<*4hQFUpkX`H7mg+h@Ih+Ky%}Y4bvARdxk0$1c6EAT;3R&A5q>x$ zX+*4U`C4S}$G4%%HmtTugSIMM)Bq+v6bqg8;nZ~UPx4R+k3D_AZ;!*>YF4zoE&3rH zllPs_0L!yhTq(|!yenQPj>glV=5|TQoxM-EcN;xp zr|8|c@s^Dt{%gnPhCv}Y@`lf_|36MhSWiL#%NFsM;gIud%X%@7)8$-MHVrE?jz63Y zETX6vfwdZJlvdgHK{&Wu96O)V9D3xXR9HBfNc2)8r}2tWO3cfy*l;7f*ci`!t+OX% z)MJtV>m5UNuWvlyOkB#!ZC+KznzSJ$3jed(__|R1Iv!_dARs8r&Sf@;Hh!|6de6 zyw-KR(RN``MZ7ur(;3{ zh5zlWw6Xt7oqmWp5NAd7FwMgyHk9K)-a4{KB0GQv;!wfSqtR0H!y@I~u0sN@%x0Kk zjMm0dmU$7Sw^Sd~T`LJh{g9iMXs)d0RJh?x+&8kT)=w01b)^T(cXH|wF<0f0LTfQL z7xUOlkG?S0nazDjoNciAv9Kia9yC~N`}@tq41V=(!bHD%T~IuU+4f8N!R6vz6)5W` zwphA>Tp!^c#Dc z{2!N|#;3nkqG&NWgkGb&c($mx)Jl3)E#5SbxEKUZpu0+>%&)r>EYOTxxu>8?Xtk%T z9_$=&oN9(vXggk*I=Jb=!~!RtLv=fDBt*<{@8EJIsB_D>@>)K_B#U?OF4L~@oH$Bs zQz-(d&R#|UIgZ2_Nk;&AGTeSx7Cz#c#8t{f|{gR|BZy>|nRo`t8RY>9yW zFeNA@>hgKCh&L+|VU8YM>&o1g8wo{?@qFu`#jpUiVqiMj`0|sSZ&Q?FvOzR&2)2ey z3;3_k&*iCx0g%03?YHB%!j#6csTp?8{-a$P(Iy}|Ms#P>_HT9=@7`k)a&e&Z(kFjJ z8*dEu=vGo%m`>wjX^dLU*CN4h1fJy0k{+-6s#)D&{#QA zR0xB|N~lCoHl_oFVSOHcmqeI1?UbKD*!T;jy*iH_-e7M%je&3d=g+Lx@El}6I3$+b zzA)v_GC7Yj4T7EGpNsnzSzS;ea-$%|#|#3}i9 zqsa<3#oPrFIhV^YV%;(H7|qZUj1z#fl?+reG9jWrMc%?gPDDu_%Ds~cxYEH+xDX2| z=n>+)lY-}|W_%%6csUHYQ22DpwbW7h@UpCA_`LI~QImDPB>xhu6#n5Ro_nF#|L+u* z<%=yP*Xwn(Jg<*3O#+Z)TYJ0Tim6pM4=dS4S1gDM z7ruhbyOvRh;&um#l}$ zftQ|^I=YTwi#KSDJLY5-dG*Ny!AvOwCR@Eh5S|i?1zvhz>`2XRl$P$e5!ezc9>4t3 zZhi#JqOUsdTR5RgtINb^28A8J{AAFQJaP3YHQF1rl6Tr;99u^8nw{?~X(6AU?VA>@cP!fTa?ad?0+r9A<>kD$CVaIP0Y`=G|8cn&K1a^(TDK!t73__aVd;N&QWQh}- zui3jl!^~IF!xTLUXz?chaBW=nW?8eC63+TZ_Y}v>bvawWJX?IIjWD3S6+0hqyhE=U zrIkwa@KnO6`G3&2VSu}wo9?3<@t@bk;VmDUzr4F$Ou>a0umf-#HF!Etwz34u3)*lu zGYcDz;lwwO!%0I`{tlxN@>cRYX~>Zo(8(^RWZke2ZhuypL;V5N9A62?t`ECmt{^eY6?9n=O}Ml< zU-CGVp2r%)i&3++@=2(oVeu{?jNAyr!i1_2_N}+-mw*icgQR3$YvhHC@jqwMAb`GqR=H#}}IqicLa5r0WA4 zbf7_{Lm9n{YYDRp;lg!kz9co6l!9Ffy&sIbgmp3hfWcLbX8t>S!PifmoKkCV@ygW8 z`W@6$?c9)Sd5mJ8#H=BQD`CB|jEEq*C0;}oeG$+;$s3jMB)WO}o71xn4`uwyhUljQ z5JP?^t#^vOLpq9DoS79C?_}B{`h2*I6H-xZSWy~?P8}0~7N%l6n+(?Wv*Y=qas=DV z%T}c7U0%258^zdsV{B=9buFf%-zZ=Ieyc_|pzC7jwb;IFr$K(Jg21~48lD01_t~!Z z)18t&+2I9H3>a8vLlBwdi@k;)*Pc4vI6Bz>G5yG}12|JVO^_rF6)l>2D^REtHw_4C zY&tPuU3P%VrVe?qsTAGLA>P^WdI=vDEfp(z4K;D{&~M5~rcmM-~QcuV)?Vu3l?V2klx>1iOaMd+)r;|SX zw1e0YQ8FqY)Znav`He2TI875~igbY3EdNIgGZOXG(J8__IPJjT5;(Yi8!J~ES7^7D zlb@JxEQyiwv=&&LO&UYh8b$sDe|vL~u4&^kcP4P=ao!lBx^qmyJGQd{@_k~)_fgwf z0nZeJM5H6jDF+%GbkmZS&|+zkqv-H>vC2;BS!o7>5P#0jE3w5C$LjGjvFq3~mSCyN zZ40Qel!&y#Y+OUI3a=YP@4EE)sbIVN>uzW$o0e&!gyt)ETAGk!Z$jZt6UjJ^=vJwl9NIvZ56%4g6QQa%?`FR*CE zr8BC_!=NkWhU6epYHrrFk(ZkBRR`IJ^)1U=APPU-X~nM?RAa7{v}1cDVp?tO=A|M& zcdXsE#1DQT`f(0Ey@5(vjq#uu;X1oK?L?2r)IFC0i-uEUo4!zmzX@vc4!Z6U`f&*L zR~!IHE5fyS%!Xf4GK}cE}eV1@M~!9L7OKMd#(>_SRg^wvC|rWR*5`l3X; zVv0%`sRLlf(1BP6O&85ku8CR_Rt_Hb*y(5npe7O;lxLdg&=ef;u6{}eGEXeR%|}Zb z!68Dq`@`C|riB6Era|a|Hpu&fZNDrKN~OV_zs&hvV_t8XWH5TY!$eBR&;%@rd9Aw7 zd{vmss8l5T7|1X(jBJ%01?K2v1X~tao5?tS>K))C8jld&%wYJ+4qw2_eG$aOyFYr% zNdwGfxp^wS!BN4VcdIZ0FS(g2G3tnAd#n)iWO(Wrz22Kt5wzY%a4*h@i)f}4gHn21 zjp|Lmpr(ORhFi-&RYqpl)(j_OU@ODZV&mB&JQk;A_}KA)N$id1wV}hQxr7 z?=fd(|F!{1eg{bk*Vp1f?*Hi6m>JvU_cp19Gs5qPGcc|c5EArhDo^!&MXpqbe-j;R z%>pR2%TU<-^ot}~zxV|I4;~hqN}dd!f(+Xh8|e}Y3GG-qY9Zh7INE3kJNoFC=tgew z^m-=ahiM;PewL%~y=mZq&!oEh{0uw=aHjRl3u#`k4^ii`i3UijBOXW&JjiOJFx%#nMZkOmWH&y@ zJjAD^jwtbC0w0;hGB_o+xtg<~FYPh_*Jlt2=;n=;18u`Fb-!IsBV3ZSC2VpOy66`1 zVzcIcSIy31oR2|?AyJB*-^bfaK4>fHWrcP8mnFYy?Ciph>oXud1x?JYMyza$ob!`Q zaNp;9t?LgHcQrymHTp4kzh(MPpMR~@zE(Uwqox`3oI}Z<{^UOY;a@sY`5gjrb_W~0 z&V9JP#Cz!`?fK!R`w_3_T+RPB6kS5!e%@wS1#}eI8)mg;RX7ani|x%>XNhA@EWh#K z(X7YqSyjw7vMMA599AQgk;{+{_kER*jmE&E!@A(--)`1uc&>Y|R~ddLpzuqp1@zgX zP?v4KG;OSk`HoZ%-Ts%ibC|KZJyblMm|u74`}pw`9jZRbuD?7#K!L46kF-Gvzxo7v zg+)z|QYcMjyTAgslKD$Kba_U4)_hkyM0MHPM#br}C?w3S(1m_TL%;S!W31pAp zBO_+Aqb)bA=?PXQu>(Az$Bg8++s7(olrK$2La4s1G|1yl zMXZX=-61^DCh76S##f!?!oz4)j)go$r&2%p&+VmI^Tq<Gg9^|H5v&*)Caq%UDL^>;-NTHIG*uHamcrylI)_0j66khu7=lm+-}XfmZgR z0NW5AqZ-6iR?kI~pZ1~4Lyd+p6^jKyOUl_lrJ85NqFoeY>sqFYg#qC<7~ZYTYcE14 zBz_6McY7z5KDS=asu@)%-Jqw_UnSI4B6F68Klnm8e+AM+-~#3!7Uti4^P&YRpdHE- zeg~M6hlC$Cjf8d>BPxCVg-Y_i0^xtvDf6nh? zFXys^@-3atb?eTAJ&wpWKvNi0$R{a2yY+j$gEI*Y8?EhNU$uT zo^@PJf5AI?DK*c0uVf9T+)KfiM*W2! z8)*@ch4BxS3ZF2&`Qdyh2M>QhCBwdHhL;8g9W6m3JlgUAgThy`RKv53;Yz}|{Bsse z5f7W~asiYG2J6l~65?cnK6Uy6Rmr;1@_<>k^Y0{sz7({&NL!&CaRf)!Se!iicDPmy zBrJT|7y-$J@%ua=&XL9#zVJS5Ix8$5l(tHA$Y`SMHdupw-zPbNuFB-=j`#9RDYkw{ zX;+TH*t?>4=DY9WGT+q+<_x|Uzg1`7xJl4$V`wl;lVehk-nn|*sfcEEYg_c29>H1!>uh69+{k-O)o7g_g@@uutM9fm!M8l_ zjXyd#0;FOOt+yYzWaq4oJU$ui1db8gZpT@^=$V_Y-^Pi&uFQwbQmsI4-1MjS9BEUl z0}S^iIsZvDQcz#8BXu*KpNqu--#lLA9tg`>DXFmZpn`Zb8T`iqwZnK}UK}48k^F5T zQ&~HCaJ76PWXCR_XPKPl7-ZYivyP+YdcJ)+NI0sZ()wts*R?cz@dnl58uYzkG6-vG z;z}xSdm(Ze8xD>Dpdv4$zX%p5t?!kZpWLgza^=TM8*Nc=A5&M}b4iYPV1RdJFv=Ug z9_Y$$Kp@$3oTSQvZHBxTv*zxnS$V#U$m3O(G-?7~7l9)nz5L9@%`vM-Ow`6S`#7cS zmT!z3S5B3!H9w9JLGpD}8@5Qp;?Tw?HNrn)BlC$<0au0d@<0sTIv)T`Z5O--^law1 zTTkke(I!;$ohaihHsx!C@68f<;V`2eu!vyuJPqbA3W(@2ehGIi7pJ+uVx>!0 z_L0xpE5B8*rNRt@^qP(&Eb%LzW1c7(j5~M!S1;Ec)zsGP=~XF$0!E}arAQT}OHr_Z z(yJg+1VTWXK|&x3f`DSEN(U(lAp%k(geFo%t|Fm?02-RKAR&YRNglrY?x*+r?!D{% z@z&e_oSD7XIeXUGd-lxv&CJnYJIHxwVRkOGsy={ZSwG1%B4V*n?{?l+Paf&~TibEF zA&MO2^VE~zD&4lrc)m~yPX z>nRH->|?sk^r`)v`xomY1Yi8NV1O8!iDPb_P~y=YU8H7s>XLI?7HQz&aMl4<>eXk- z`265|HpsD4-rgQv1irf%4#R6IQ}XB7v`zGYEZCzqWd;mu2j&4zfSjG_q++yQ6VUJ+ z;Dmq$#3%=LZEK5nAtuis(s{;mp{Tq-H){l;role5S6A(DhF#k?@#*+yLLT$l>&&2NaGxLva%9Gw{*ZmYR9`pG=|YK6g2 z|Lt+wUCC7>V#}AyvoT<|xY**tyOsszBnPR>GJ#5|Z(pw|-s0$Vdx>99e|kR#?43!B zF4@=5-s7bx(w(}@tYh_FXRP#WdgC&u_ zr#HDmP}}1{XxoX8eqn8JtDF&%hhguh#jFj{=bDV$1IDG#6&cObCCp714oTGwk{Xpb zY1~ZE1tfJDL=&E;4=w1E&+zc9+1FFVYnOZ!nxZkgG#VLgaMvEW_Yr-Eltl*u*11)d zsX-@)7WJPL+3H!1Gv;nd$vCzt%&XPICowtpnyPi-xDxc>It$vUFttDa1kx``$esyx zqUkc+ynKvzFw&z$tCX}C9^t3roVUUJq#sWMVXzzwvua6Yp~}zcm8JbJs?$DPcHTKD z;I+a(>1f$5Qo3gfpKZvTj?YMrk_pL_&$;GxvBNKNsQg7EPm?kBd;Ufa(T^|WRI2Cr zvmnb)OK$sRnS(679S!T&wzdE-FoJKFY z)G8ztXt9jf+oldF1DJVInXD13=g)p^c6|9ttvkO7zbLPxFHX(1l zF!$^ii@f>nKXO!;srhLT*&i_4>f_KqJD$Jzp$l{Fc~AVNeVZ5g za~}($cU@C5gOhZ1)v+E~uN(v2_BhJ0?B2Yd*NOe!vZ4Q zSI@ozeiFVX?%8OW?3u9=p$-6+WX^)eFScq9A@b(Xt6mMCqxfz*n|_uW&U-vab2S+W zVkeUHPA|6dZq!!CMadB3ws`$rcoA>&!Zy$^FTq;jAz|QwH<_DDgX*)CJOWlyqJcaQyKx%-~Z7+G-U)t0xWsk;9rRX{g?Sx0+Zgvm0b%j=lAw=`(H(g2T^TdwWWXE{*ynY| z0&9C?u1|kwegScPaYY-jpEnUIM_F@iIxfH_W+-lu?OD^5qtRr}$!yK_C`1f4_AzrN zJSVjVu(H)wt*m<6J%ZzQV?0iB0rzSo4~7jpt;RNndsNyTIJ1RM9Y}KCAC3aQ;Z&PZ4QNHy(xt-`t?c4K$gTxrR|AP^*_l~* zqgfZX-6~>`II#!uO%DS!b!b5g?)d@tqSIKw83s*{8f4m^HSu^5$yg={hLv=e@f$?) zoLtk+jt>w|{wsC+AM^Qv8su32pSBdQ{UPKlZ=0`rLz3|c7q_*jiXYiI;4lJhKkwPcUFguD1Q_v3`1>dmPw}nQXr?gv-9zm<@(miyr|HjE?14goDVqmC&f!wI`@D%8nI|_<5k|$iVy)~SEA)@p%WO>uPvfw_}1Or*d$>pKc++6k+BNsB{ zGB4@d?=UG(emTBm@!a}aeUMv>?brFsD6QvhnlJCR6xvL}Vf_3{M@vTGl~B)a_@yzp z@ag#|kOjK`N<}`Zo}T5K1G5dd@G7$1R04}(yD-$8;?*d*qz3|OVPu}~p{x_&Smxmb zzP0t)TP#--ols{FvBfGvrnUgm@hKZoY1ttUyq^@hKv(*{mAwz>H>%5ZJgfvcZj15@t`b0?W#?_cA#pQeh}TCo zcpKQvJMzerHnqRZ?=4Jn5B%K0v{r*o1U_K{O%^nH=TtRX zh*g)|S$G6)CfzZ2kFA?Ji;0XBdSzE#CD3eBQZ<%61%!RQ6pXqc5>vZh*wZMsJ9mFP zn#-vsqf&whf^@7w4*rMZ_sjPEFm!gmdik%dPx;&Zl%`xcBBZ)nPH0-Aj<2QaserO=j;(r8@h zAltCnQ^HY;(c6rI*qg0jO6oyIQA~8I$Kdq1nht2fbebId@x&e2E9co=M$`l8x}rO4 zX+ThyFE_-)m>ecg|GVN z!~^)$>fedzEL4H6hH^dYbn_pGtK^V@R4Lif3WCEMbK9CYGKI@cEP|m5Yux976W4`Z z^pH5GnQMCFS%Fek@ehi+iSgjPY?!ESy}#yl^(@PidUbLFCy@<8!?)XK+pw(r(PqN* z7BsZ$$MUUy^89yH>lf!@e`uk!%WLHC&%6DcO;b!MQMm}3xIIW%LJ6Zov%*-pV#T_9 zr)lrdzVy@Wqi7llif=RPwa~yFzVgFbT3(i=77O%`ZvdcOZLCqtr>8KSA+)rjZ5@7E zzw7XJkIDp^exPpgpEl;dL~8u{Z^ZzAl0Ww`16ML|nM-^-%Wflr{vA11po^exnZH17 zEEODXqkwgoX?)vVXp$aPMgVQyZZE03{fapMznU5QHz)n?qJ20Y!%#*;(p-87u5RlF zZ%Absmi|!Co9|}GilgxMNG#cadoN98>^cLTVVfPgYe^!c_dvbZ#TZL44<)08DItHY zb$?#2T-m=>&;Ld!ImGc|5;SIp#CLCFrVVuF#M($@m-T0>>MKkzWa>V658|pbP>kIY zqr#~nGX~My4Q%^0e?p!e)66tIaTEORke>0sUiCi_!yW&$O|-=rAD*ETZ?r=lc_?&j zvu8TTjZ<9hDqln0{5mibI(Jx3s<``0j5%OAuy?sUl)uD?s~zC>mr1D5DZDs2NDk{O zNIlQ9t_*rSFx)VWwb|Lzr!P%fMxb*blk_O>;hjb@t^aLt6;tbJdmmCSuVNnPxA4c%k86zdnF`TgJATqJk?FR~KiOX> zjZ2Q2zpy_^!><3!TUK6$|9mv;I*NykSIGh@JjE`{?+O`OHnPm{gy0hy53$$j;9I literal 0 HcmV?d00001 diff --git a/doc/html/_me_mega_pi_8h_source.html b/doc/html/_me_mega_pi_8h_source.html new file mode 100644 index 00000000..c6af4936 --- /dev/null +++ b/doc/html/_me_mega_pi_8h_source.html @@ -0,0 +1,241 @@ + + + + + + + +MakeBlock Drive Updated: src/MeMegaPi.h Source File + + + + + + + + + + + + + +

    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeMegaPi.h
    +
    +
    +Go to the documentation of this file.
    1
    +
    36#ifndef MeMegaPi_H
    +
    37#define MeMegaPi_H
    +
    38
    +
    39#include <Arduino.h>
    +
    40#include "MeConfig.h"
    +
    41
    +
    42// Supported Modules drive needs to be added here
    +
    43#include "Me7SegmentDisplay.h"
    +
    44#include "MeUltrasonicSensor.h"
    +
    45#include "MeDCMotor.h"
    +
    46#include "MeRGBLed.h"
    +
    47#include "Me4Button.h"
    +
    48#include "MePotentiometer.h"
    +
    49#include "MeJoystick.h"
    +
    50#include "MePIRMotionSensor.h"
    +
    51#include "MeShutter.h"
    +
    52#include "MeLineFollower.h"
    +
    53#include "MeSoundSensor.h"
    +
    54#include "MeLimitSwitch.h"
    +
    55#include "MeLightSensor.h"
    +
    56#include "MeSerial.h"
    +
    57#include "MeBluetooth.h"
    +
    58#include "MeWifi.h"
    +
    59#include "MeTemperature.h"
    +
    60#include "MeGyro.h"
    +
    61#include "MeInfraredReceiver.h"
    +
    62#include "MeCompass.h"
    +
    63#include "MeUSBHost.h"
    +
    64#include "MeTouchSensor.h"
    +
    65#include "MeStepper.h"
    +
    66#include "MeStepperOnBoard.h"
    +
    67#include "MeEncoderMotor.h"
    +
    68#include "MeEncoderNew.h"
    +
    69#include "MeBuzzer.h"
    +
    70#include "MeLEDMatrix.h"
    +
    71#include "MeHumitureSensor.h"
    +
    72#include "MeFlameSensor.h"
    +
    73#include "MeGasSensor.h"
    +
    74#include "MeEncoderOnBoard.h"
    +
    75#include "MeMegaPiDCMotor.h"
    +
    76#include "MePressureSensor.h"
    +
    77#include "MePS2.h"
    +
    78#include "MeColorSensor.h"
    +
    79/********************* MegaPi Board GPIO Map *********************************/
    +
    80// struct defined in MeMegaPi.h
    +
    81#define PORT1A PORT_1
    +
    82#define PORT1B PORT_9
    +
    83#define PORT2A PORT_2
    +
    84#define PORT2B PORT_10
    +
    85#define PORT3A PORT_3
    +
    86#define PORT3B PORT_11
    +
    87#define PORT4A PORT_4
    +
    88#define PORT4B PORT_12
    +
    89
    +
    90 MePort_Sig mePort[17] =
    +
    91 {
    +
    92 { NC, NC }, { NC, NC }, { NC, NC }, { NC, NC }, { NC, NC },
    +
    93 { 16, 17 }, { A8, A9 }, { A10, A11 }, { A13, A12 }, { NC, NC },
    +
    94 { NC, NC }, { NC, NC }, { NC, NC }, { NC, NC }, { NC, NC },
    +
    95 { NC, NC },{ NC, NC },
    +
    96 };
    +
    97
    +
    98Encoder_port_type encoder_Port[6] =
    +
    99{
    +
    100 { NC, NC, NC, NC, NC},
    +
    101 //NET2 NET1 PWM DIR1 DIR2
    +
    102 { 18, 31, 12, 34, 35},
    +
    103 //ENB A ENB B PWMB DIR B1 DIR B2
    +
    104 { 19, 38, 8, 37, 36},
    +
    105 { 3, 49, 9, 43, 42},
    +
    106 { 2, A1, 5, A4, A5},
    +
    107 { NC, NC, NC, NC, NC},
    +
    108};
    +
    109
    +
    110megapi_dc_type megapi_dc_Port[14] =
    +
    111{
    +
    112 {NC,NC,NC}, {33,32,11}, {40,41, 7}, {47,48, 6}, {A3,A2, 4},
    +
    113 {NC,NC,NC}, {NC,NC,NC}, {NC,NC,NC}, {NC,NC,NC}, {35,34,12},
    +
    114 {36,37, 8}, {42,43, 9}, {A5,A4, 5},
    +
    115};
    +
    116
    +
    117megaPi_slot_type megaPi_slots[4] =
    +
    118{
    +
    119 {35, 34, 33, 32, 31, 18, 12, 11},
    +
    120 {36, 37, 40, 41, 38, 19, 8, 7},
    +
    121 {42, 43, 47, 48, 49, 3, 9, 6},
    +
    122 {A5, A4, A3, A2, A1, 2, 5, 4}, // for megapi
    +
    123};
    +
    124//for step motor on board
    +
    125#endif // MeMegaPi_H
    +
    Header for Me4Button.cpp module.
    +
    Header file for Me7SegmentDisplay.cpp.
    +
    Header for MeBluetooth.cpp module.
    +
    Header for MeBuzzer.cpp module.
    +
    Header for MeColorSensor.cpp module.
    +
    Header for MeCompass.cpp module.
    +
    Configuration file of library.
    +
    Header for MeDCMotor.cpp module.
    +
    Header for MeEncoderMotor.cpp module.
    +
    Header for MeEncoderNew.cpp module.
    +
    Header for MeEncoderOnBoard.cpp module.
    +
    Header for MeFlameSensor.cpp module.
    +
    Header for MeGasSensor.cpp module.
    +
    Header for MeGyro.cpp module.
    +
    Header for for MeHumitureSensor.cpp module.
    +
    Header for for MeInfraredReceiver.cpp module.
    +
    Header for MeJoystick.cpp module.
    +
    Header for MeLEDMatrix.cpp module.
    +
    Header file for Me-Light Sensor.cpp.
    +
    Header for MeLimitSwitch.cpp.
    +
    Header for for MeLineFollower.cpp module.
    +
    Header for MeMegaPiDCMotor.cpp module.
    +
    Header for MePIRMotionSensor.cpp.
    +
    Header for MePS2.cpp module.
    +
    Header for MePotentiometer.cpp.
    +
    Header for MeRGBLed.cpp module.
    +
    Header for for MeSerial.cpp module.
    +
    Header for MeShutter.cpp module.
    +
    Header for MeStepper.cpp module.
    +
    Header for MeStepperOnBoard.cpp module.
    +
    Header for MeTemperature.cpp module.
    +
    Header for for MeTouchSensor.cpp module.
    +
    Header for MeUSBHost.cpp module.
    +
    Header for for MeUltrasonicSensor.cpp module.
    +
    Header for for MeWifi.cpp module.
    +
    Definition MeEncoderOnBoard.h:122
    +
    Definition MePort.h:71
    +
    Definition MeStepperOnBoard.h:77
    +
    Definition MeMegaPiDCMotor.h:50
    +
    +
    + + + + diff --git a/doc/html/_me_mega_pi_d_c_motor_8cpp.html b/doc/html/_me_mega_pi_d_c_motor_8cpp.html new file mode 100644 index 00000000..4296adc2 --- /dev/null +++ b/doc/html/_me_mega_pi_d_c_motor_8cpp.html @@ -0,0 +1,179 @@ + + + + + + + +MakeBlock Drive Updated: src/MeMegaPiDCMotor.cpp File Reference + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeMegaPiDCMotor.cpp File Reference
    +
    +
    + +

    Driver for Me Megapi DC motor device. +More...

    +
    #include "MeMegaPiDCMotor.h"
    +
    +Include dependency graph for MeMegaPiDCMotor.cpp:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +

    Detailed Description

    +

    Driver for Me Megapi DC motor device.

    +
    Author
    MakeBlock
    +
    Version
    V1.0.2
    +
    Date
    2017/05/22
    +
    Copyright
    This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    This file is a drive for Me Megapi DC mtor device.
    +
    Method List:
    +
      +
    1. void MeMegaPiDCMotor::setpin(uint8_t dc_dir_h1,uint8_t dc_dir_h2,uint8_t pwm_pin)
    2. +
    3. void MeMegaPiDCMotor::run(int16_t speed)
    4. +
    5. void MeMegaPiDCMotor::stop(void)
    6. +
    7. void MeMegaPiDCMotor::reset(uint8_t port)
    8. +
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    +Mark Yan         2016/02/20     1.0.0            Rebuild the new.
    +Mark Yan         2016/04/07     1.0.1            fix motor reset issue.
    +Zzipeng          2017/05/18     1.0.2            set all timer frequency at 970HZ
    +
    o
    +
    +
    + + + + diff --git a/doc/html/_me_mega_pi_d_c_motor_8cpp__incl.map b/doc/html/_me_mega_pi_d_c_motor_8cpp__incl.map new file mode 100644 index 00000000..9189b79c --- /dev/null +++ b/doc/html/_me_mega_pi_d_c_motor_8cpp__incl.map @@ -0,0 +1,36 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_mega_pi_d_c_motor_8cpp__incl.md5 b/doc/html/_me_mega_pi_d_c_motor_8cpp__incl.md5 new file mode 100644 index 00000000..870bbd7c --- /dev/null +++ b/doc/html/_me_mega_pi_d_c_motor_8cpp__incl.md5 @@ -0,0 +1 @@ +8678d925e76b8a3568a121e731ed7dc5 \ No newline at end of file diff --git a/doc/html/_me_mega_pi_d_c_motor_8cpp__incl.png b/doc/html/_me_mega_pi_d_c_motor_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..9f503bdfa072d9b291b4a62e4f6413449c650ebe GIT binary patch literal 27186 zcmdSBcT`i+*DXpBP^yU1i-3wCy?0c)C4NatJAX20krT0$g5I}8 z)V<^{Nj_>lDC>O^kriL%p}GnQ2z;$I_SGh~zdw293L?G#UTCfV1Y*0||667aGIT=1 z_J4ZBYEXl5*|cU>hceAbUPm^P$1wWYw0|Tp(WGHzTh@Ek-&0XRK_SPHbL(?NM1;z;*3<(^O3Ik3Two~RVWVcDr|@e2Y%Q~`tBt)h5#+ZF zvMU*sySaQ37*=GF0}lV-S7F0G@t95PgYaNkMEtjdA-T+F<;`xx=OY3OwB>)Njy44t(ft5&foyuWxXe2bP()tp@T)UWuMC4G2;ea&I6X zvJr@lt{+~v*|~4Xu!#K5N)Nsn>ORgEe0Swoe_Zf4YZB|B_Rlm39KWM$vguBoN6EOon;jqRHncFGvS3@#W~ z{O^s!V|_H;P5|)-HnxTzfVEMD^8 zKL554X^FW~-sqDamz<_AEWLi=BaCL^%%KqT{rNs2Qe~y0faGq>=<#1z;3dpC@B;0H z#_m0D?w<$CF{4_dDVmH*%fSAvbcP6iz6!2bpfIv5!diZg7I2XNFAt$9i2POGa=G7EV%8?RA*kSH*%?Nr znfQ=RA_wb__rewjHc{o7MHQ)L@Ci?<4jGLkYU#>LPP3b#C{2|1PXE?)fy3RH*u|T)9y-C4O<)l!g>N%W0H37fH2S}BT42t-2_0pCQ%A(}g#Q0#0God& z)Tqd8sS@;L?CunG=7?0&frwBmx%7gU)t}Si&G!zO4(lCyTx?pG*q!?P)~c6U z^Rlr$1<>L?pVi;JFX3juuh@N2bdXQU#9#bQ5>;V`Cq@ltql_8N2KHYorz``s>7upT z!Y+8JMxnmeK?fI&?NCs76#?vy3Z?t9ozqWvJ((qa=nI8MQvZhHPDAhoi^1zhrYd%H zoFenEV`X8-`bj-lL1sI9+XLU+qdP6LZm9NXME41s7X3d<7~e)6s&nJAPOutNxvB!b zB#&L&uWiFlH#|X_Y&wU0b#uj^kAcOJ{#zVMy3_ZMOv(F8>y5^90YAFu|NgUz=KBvH&V!pYq8g(usnrA4a?Ize}hNMD{_d7+CporVg!Qi7FsjZ4mC#mfk?eX0E4PFW+&qsV0LutI%a}%#`0fzi# z3#?g7I8P&UFipZei&y^D_-L-$`o_lRMp8;n!N%uru;=gp%9mqeZA34d#o2j=z*1H= zwjtM~I-M$;OEG7|ZURv~RF@ z8;Ncnw#gXD*8+e*>R}C-k+l9IHTs&I`YZVNI|Z&NVDI8<+VN&xl%Iu5=4KXqo-fGi z`>}(iXkV4R{2+?!Ee!Lkfq@H-!etX?{}Ypa>bpf}x@E`Rx!44$ zC98l5mEVl?{QZ<|TswxEbZMgyo>H_6CH856%uYKwOZO=%D9K|%*z)&A&FO#O*PD&) z3=6*x*!6-1_2yWzzB>Wo(|$bag+gzKxxaF_(7UOA9VzxG|5OKj2j+oLyDOC5UFsOO zY<9rxl!Rez#)q3sQ|dQ1A*EvDRh6{fH|@+CWz6oPATmZOar8Eq`4^Q|AUvw{(66&q zIP%@=(~-(H5FNi!_FEX4b5-to?Gpp0=W0M@Az{oWWjc}v(Eut~)BIpG6- z#DH~diJTz7iH)&y`?sahz%f#p-s9AExW{?Z%0NMcOR?+57x>-@&cD&9@JJH-8ZFU| zJLsRJvJnUN8roM|i_L&Pmd|-lVHQ0oC^XP13nD`m83hgxVmjUep*yCE@&cW5Bo~Q3 zT>WNxlo+-3Eo_~3jK{i>pdZ#XwJ{y#!J&2isDfU9dvL>rtr&ZrG*NtP4f(Ea3OP@W zUD^pWa>mwWvdXNuA-%j)&jN9g-mZpk2`qfKP8L4CxEoR-NMVe$tmG)KU-~RVWHedR zTkL0Qxqw4XZqeA@j=)7sB9x%Y{XRI$!NRj%I;Ap3!%K>f_^>|o`K5-&P<}9{CQ5*7 zH@U&@T&6qSHqKK#LN2G3>hhSTjaf}dc3CZoIh9}H&v`Ee(nw3+uZM=a#WlUOJ_p3`)P$%x7`(f-7P^XPQ9j$`|h#Uwe((4yFc^Z^Tw13 z$@6DgzSx^v$FK4o;LES|iRa_OmLSjQ*4C1u&W9bd`ZU@bDA)R}(@n(YXXvG_-ibN6 zh_~=KsUgv(k0tZ_ICR1pt&twkY?o- zE1N^6F^@0-P-hN1*FOEu!3MRf^oa>+;!8HVx;*2FWR){K40|Ol5j@R&=y%cFtI3KE zFZKb-7r!o;q7mXa1%%hc(ioTgPLuM|<&ootgy?!>%5`M`#H?=}G+q9xasSb-N`8|3 zH{H6Fhe;!KV1QZrARr;Na`V$2#=~X0W5coykl}{W$-C+qjPvHCYg&ii&II4z(!AHJ zUxy`Tq3prg!AwE50=e%nJwq}((8GBC=nB{{TFnd+gxk2K_~G7kBZP(dUh}!f)}w#c(Odp zK!4KQ7~M3pHj@{j_Mq@7)`#(hJG~4Ad6mo#q!@{&;f> zZtS#7_3Vm=L2SRGGjrxcVc%xgo1MwwEI02dk2<+}WP+YI7cS)=E^wfbn;)1ei9khjfyU_c#L^bE~;<@%$+w+f9+mSDw&6L*uV=#eEd3C{T zYHymoluoAL%5lFxuQJ|iD4XP~Z~`zA^Ld29t?dq@Z3P<$vQlJtq0?H2ZXPYpnEN@m zI^J9r&7M_H-)8?!FW+p5`61kiN%@09(CBFW?8%+6ar$w*?yt#9-el^D3`~+6&jf{m zxXS5A#+i8s(ua8)@?aI>^CDg5UBNboRsiQ-Pm-&OTIp5mTQpNn^a&0HzMML8TTOF< zby>(cSEFR+C(+9V#()zdQ_=j+McW01qHSwGkqt@3&!N~5#NnmJz5M89>t}(v#mS_D zsFz{JK?jnTQx7qs&^+tX+6Qjv5c@xepXhkVYeB9?lwcXbfCEW?LmfoPaPk;K0NI)z z?e^TgtvC zYUyEQyHYeV$!gFZF^I^V)BjxUfx0t00&thCGVMnTSpUj73N=nE$0ri^(Ep`(AV9GD z{*l%-Cnm68qP2E#C!#8${ZYc1=BHVUy@ttp6K1eXtQi(N{2nPMxmQVX;QL8l^6)1# zx-U0^xlxK=w92r9J`xf0+uOQ0yNyHzw=hat;?nRX*|bGB!p}GthN8k}&(sB-79tum zeh7Po*2=nt%oZLfN@{F0*t%N zK&ncwj zyKib0zPp6W(q7mteovod_TvaMIwSsLdAuan!|q%~|2D!vS1spK!JKo@phvQacf+@8;_E()w#F(grKC0$ z81b__0Eh#P5_5Qi9&0TKZN!AdFA*%vP$qK3ieM-C>gwf=UXVQkydI=RJy^xT&I@|G z#(U(YYZpe>BtTbpril_Vj53+u7%cp+IH6zyyPt?PdAe`7JHKbPmv}X^zCN)Xe@+#a zlxVKgxbYFr6BrXg*y-wSzSP&S9v%Ce5H|OTxw&u-nu666HHtiS=`KNYlF`prTaowD zS8XXW{Nw;Q6m_Amh-&X0)<4~NcA4d0RtjrWiV4Op{^>a1-xSaj_po-oV3XiYOI9=I zWKbZq5gr5heIKFOrsnxGfT&v1)Fr`3Wi?uZVm?Q%_2+%uNl{W`D|5D+GSfRJ6L{7QS*&p%q~jyd%n+i-%XA-G157>g;y zS$w}64@AuUyaHZ9%jY%fxN7on>Q z{L+{KQS~^d;9n)O&!btcM{4<|==y+9y;eUd#kJo-m3 zyj?LYb1>kJph1t zWwSY+#c}Y=7IOcO>ssUY&n)l^^R_RIqMRl`6cywp6T1)<4c5T9!5zm*#9w%W+|C@) z74?jaUvM1kDg__wFM!^t`GOUYlyulkAU-8RNcYd;b z9P@NDZhy39Ha};qA77SeYhxJq64vV2qmRw;l7NZd+L4%JK=lI$e>SyD2Wba~E6bXJ*CH(D13`b~-P>M>OR+0W3_+>?Go@I)W#4?cY3 zRvHl5o#)uuLvDr;?_Ks5Z%mZ>ZmJUUmbITP~RSCD6wOcGZychTy5z8_~G?g z3oE0=%{gStGrRX?KuSsV0UJ-*ZDCJehxfusBO%&km@uNjt5R1fE?`?PMN0POR1OT> z>4Ss^KkhIG=zpdfQ?USS_O8IE4+7Kw^+21&e9|Sj&g|C}-K$v-Y&Sqd7VH(Q_7Pq`Z?qfAa~;q}1TNO4Jz_Igi$_`k37tcZ1w%?4+sJGkR`+M?6d%Ui7DSlbWCnkbUa}2$-yxHo zF|QI|DJ9K7#nl(tWpA*{SfJx0F%+t`S`J+o%mXxvrwG)Yka zM3|hH!ex7Peqtw-Aq{Ds-v9(J!4rm@rp};lnzB z)57qNUl8kQB-L&41Ld9L~>^wMmEdD7js9#Y> zJ>tNe8!1cN*r_&Y;Kz;hV`Bcf&QL5dM`h)i6B-HqUOSnGk{;!_rq#PiZ9w30g zS8n+|*=T(AqVLY}Ya^a+a|mvBYX5<^+c-GV8elT-1P3j|?Qp`op&ay*SG~vw*T)48 zakGW>?BZ-IWk4bjcBh129NPaB&;FdqbXnwO1_y@1T7B+j8pBEA-Pn|p-|K2yvk0-w zZL{fAy0+Ns_DC6{$#~xu*_fv#va1{D%#A!EZ_-FZ9Lr@`lq;IVslfk5NQy!Ce7Y&Z zdWih5IxY+7UpJtrqNOyrzOPDUF0kk1mC+&eViNz_kyWGID`S-CB;lS(z~@e=s{Qpc zHd)>9ePuGnRZf00sK_b}(9kw$BXi6MHdw!LX~pa*V#vbFcO`=-SLr6Hz#u_U;wCLh zLqo%vxvQFj&4?L5sLxD1fvBnV8G8ke#dqdD1nK;2t_bYx-#X08%X{45{<~}el zedPYA=*e>pAAc{GlQ9}@{jUe8H=oCRm|Cswx=^~{?tSW9LodPEHX5xD!_x0*=cK(( z77Vo?%TqK_dNf&P(l@3dmwvL%=z_rYSx_qUI~-9yXpK5MSX=XF_+|^#n*afyz;nX! zLTax;p*Qf;Umo`au{?;PDpYxFnTtC@X6kWD+H!l-A+8BR>; zNg?t3YqN9q=+iCTGV9rEiX`;ZN_WG-!V5$>L*wP=im-B>84>c_SJ^<_AtD0nS5BGd zI7AY{OKFtoUo2FdH;z~LV2UQGq#6KsQc!qAGB7|5?*ff{Vm=ntzXfsLw`TsZwbuzC zT38++{;>f$v0j=rUmbG$Kw#N_r+EwaMAYN_TV%X5zzFxT3M=ri8U|>Gb8+>ufVx07 zxwl}<{*b6x)4mSn$QM@Z5ad0EMvXmFMEW?8o9WI5cdXt~uo;ULi-D4utD&(&ImhyG zF29hU4VW9bp^zWAo5q`Y9}N1YZlU*x;vBY?T3qS>3=GAz|6V?0D!Llsex_*KIV2=F zy5Byzd(o5o7oNK5s}SadD?+o9K!n8Vr zokQdMlW$+RaKAv!iQW9>GADP`%b5}pGfFC{epdR~pOM+qPLXZpiwCZeFhJTBtY^>h z>;oG}o7r*;0B$s;Yj;G;f!~b}6Z1ST)I{mn0~dt}fM#k2h3)7*XVV>f>Nr%c?<$8)kNJGb!Bv>Vs{Z4}0nH^VvTRuq?M6V%pG`^bIYCeYI`4M>X>3TEz zeh{INSA}SGi*sS`%7N7Q{tvjoXw}HL=|*|yduUy1hsw!rTeGu)nLaa@H!LqL|C zjl^zh1}-VJkVfT7PJzd);o<8)4%Wd7HHqQ2L7#Z$994lhP$xW|%RT`lSIzOuo5ONA z-t_hC@K1BYj-e;7RAvBaUFBZyazT}!P@(_zw&nPx(8Tbi2?UfhDZJ(3R2Tl+dYm+?UtR3_Koesj0Nl0ARB z0!3XqLRb_ld9*kv`jtE~kp;k|_(yANbHKoglk{8(3|N zD27k!VE&6hM-$PE7`* z^72?+??A<>SMDy@Bo|v-Qh23hh6-(EVJiLRHY(bu+f^h^yBrXXW{_%WXqf(nMn2a_ z0ZJ<+BT!OStq+C($BL~MXFAPdppgZ%&7r1=1;F^ZfH46W$k9*s5p=r2hajL{dODR{ zBP-nsCc2!Ofbh*}0Vo=2sKpE5*f;Nm+{lV;_$oY-i*@zmmjM(OB3CB|m9w?1vch-o zg$aQ&4?xttwpHB=+ARK1>u9sL{koe<-a@I7`3wcyAn6wmR>V ze!cilu>e1K7HU#RTi(1+43j;7KW-B*BGYCi=A7%yfJS&g+Lgh#K$q_W zGZ`q}6f7>X3{{{A;R1oz5FBbCFf>?fZr|~ey}dadBm>qk-8@NA<+tHFK3Q0EW{}z; zE0_KP@|8IO?RpWH_!Igq3f%T{n{QPq<0+^v%OjWLhPqmjGQaXTrvo$(o{h%OF@&7= zDLE@NN)GEBrx3xmufqrA{Nfs-mk7cqf~#lnb&a4zMt~?b4VMA*l`cH>PKl`3df~OS zi5w2wOU=@>m@V>5>5+OeD>p}?V`qtzCdq`Jl?QHgRan6)KHl!~ai?L8F#4Bm0jJ) zXx3xq<>$mE5f9fN?T^Xj07A<$w06-t{%=MqW)*KbJ)rB&lB-)=(1oCj11mldcONsSN+%ZwOHzopf)XBV71f{h zT_X6cAG>sq-x(Jhs%QpRft-#p$tUiQT%zghaNysLe&WRu^lJ>K)UwK26vlY0ks4WuVZlO6V3)#fvOPk+IuK|u zOUH#Toup#+xBJBhj1SWXCD&3E@+5Ao)jY~qk?U0SQI&ouB1cXhPBu;`Bw@gUC>#7vB`kK{j&(> z7!d2*g7}hMJsnC-SbStm0*KY6kY4)|OFvyw8X>#DL58t!qfwjP2isR}5NMver9zmj=dk%kfQH*=@uJ zFWqn|gIYjAda3|A&~D9?I&vDvztH-PTc?rL$KYZ(cV=mne)Vv}mk`hmIGA{amg7om zJr&1~AdQ_I&6HNu$=59$sWG1Q1p3DP<<;@!3i&9j%YICw$&;@IIsR{f8@`$`Z-*~* zSveEKJymEu-sV+PECtUg176VPxyW0Sz(Gm=!?S?zo zm!pE@zOM5%%%o40xAul;l9kN!VFn3~aWmYPX+G8LoTP>K!C!v{~)*jL2`1UYnzcYv&BgXJjeQ?F` zQy0KH6h4pMZ9l$iju%3D@(rd*sZ`8|2}7kdNaT2sbEB2-(6ZW9*ApP5G42WQmKLQ};I|XX=gR9pq>MeBn z4OX;j!ChU#_rl{7=UK@U@l(02bvGUTc!B#X0{15_s_gXoJGJ`O?_u(f*7>=n)5jP} z45bjjc)?W(a@0oVTQn|1w~lXRxGv{uQPlebbz6U@S=?C>Fkb!xzs#j}K){~*&1w8a zs1LfVmg~IL{H+yK5ko=X65aV1Avf26t8ctcg|D(B;(5x;TtQlJCyGvQVy0RX6;A-X}B14DmAx)Gpwf~i$ z>mdKskMh9Xb77QD2Z2(o8CGU`f!IcT+HtatH^S%ukfmvFxTEds>s?MaHaCqjZ{y)* z^gD>SU94vBof?39;wY%sC%1y+>jRG0nRjAaDY}7VN`I`As9e0q6u=&1?8`^(o$%pD zK~?}O2Ap14_ef0|K45K2n??e;b(>K)sro6LU92#$9ICTxhuD4|MFgpcU*N#UuKMeF zBP(W$WQ*uEhY&OY*TI#U4^Bym%rZl4r|#6U;W=gI<+jQ%j63Gbc))Yroti3YQq`NX+1iHiDr$3{IZ0l{@M__pzC|CZQ4lC|xfm^^bGgrkG?No{L> zZif~)(DMQ53UQpy%}hVk3T9Oj30k^#qYbI#!`yqzf>56I;TX)6#w5HVsrTPVJk{0C z8>W-Iz+mejKp`s+;_y$M^upC}7F5><@=#^KQI4X2_>%L(`e`O75KH=EdWoHW2K(g} z$-9oMUO1_Z#p0eLuP>CxMWVt1eUol;p)KJx%_slh6Fd<_vGqq#&v7}E>P?UXwyyXM zaA#ql-gT%pd%IaKh=LcOCjja_B};Ejr1QdqftUpIhsTs@dV{W8^6_-Y`vweZfX=Mw z51ubL$y)44c95r=Pm&CJ%}5`3D)#=oedS<=6k=yRJSz8J!@n%cc|!ba^gC{y*Q?2z z>YVYg%--<-H|r?<+?e+=wXL6mRNjebCrvW=T#Hf7TX=A1uZIdx9e0ClBM6M(A^$S- zq2bMypACOxd>c`HH%6?yWcjDo)kmPuP|FffZ;tY4rlqKtpNHeSkP9w9#FPf%2mbW_ z^i^3JgR-E2aZ8U})4NXlh&;qh;!FJqlB)0DvgEN%OIO$Sns96akTPo&=;BDKWIXK} zCrZ+bHoGPqLwlVGW2~&7fPDz-MVY=DV>u37l2eqd@A7URM8H_`2zQXP>m(AeF(p>H zt36`8D@1-f3O}Sjl;a|9J*=V!Q%BzBxs3WG-SLDOBsFas)wuJr0NdaPUyPU!lA`e@ zYQat9Dsz@;51;`@bv=#Q-^I@qTOD~&nn9wK0n&MqD?*- z{$TD(>-L5d8p;zof|XasG>dkr054+`cq#Tt&m~|Jw;11Bn$&!{F#o0yyYsacDWvlL^-vR z-LB7%YiNW-No=zk8{J{Q{rjbSubkZ;{&!Bgx=G-UqLJ~L_}sTz)1c^F%0#Nd^T(|d zzd_mR0f2JMh;N^!S)L;m zpnq97D4M`WTz@t)wax-w&L^j->)JK~T3Wa0n=aYBc-!B!O+6QTFR8(5#aJ;;8NpQl%runa9g<&G58( zv*2hYV5cL||2&QYzwv3BYTmPMdiNPWOJfsamaMK4ffWv^%UO(asp|z~{3!l&nEDNz z?k3vZwrX%DyDWc-^v{CdlZx8*-n-OZ3}W&7-X*c=KF|Cu9ofBb(0Lp#r`U$fjg&B; zSyK>-Ew?&BE6v(e>GJUXa0LjH<9`%|hl5$W_pp`S`3QkNpmAim^N^(8>5>~;aBf7p zef@K|Ea24sUTt!Q1GwY(Bgrcw+Dwn-c(~yvv@yd{1Zd=dg3PhR)eu95N!(a4x=z7n zQUL^)0UNh$X%6%!055tDBrU#A2Fem_+Xm+DV(tp+UEnvH?|Hv3;XF~L+yB9biKW9o zkw@G=SJHH$uIq=(DH&TD*aI@4jJX8zjrQ)E)r>~>L-!*11M$v>^YnF1*}R2Q>DWq@ z>H#H%1kLhOjD%PKrBIn6e_sF-*gw`Ul3Xq#sA<67p|pBP!DQ&|eb3w_;n^+pEvjiD zkK;`g+2TWUhwnt*c+0LNLjI1$i+UR{QQv=Mi6`oR$m%)po!c8&tP1r;=0(S@?}MXq zi+pnRWa={H4eikQ_=!Mvb}?IzU+=JSOa0kuHcwX>kQF`ASTsyCuw`5@bSNe&8=G1T z->rI3d?@W)=-RL=PmwQ`7E;O3a^*K>A7Ho>H~TIHsV+AW;#BpMQ12+*s5JQ5B z8P&G~Kl{%MF0fO(iS3~eZ>bm6xF#L^z?RZ8`rjaaSp2HIvRiievo9H9cGu0cYOw4} zMSqrvxo2l}FbLp|>Og01fOMznmqsPJHe|fnmP@5P2q<$X0elvavPI{G>G2p}*}m2t zo~rc`GDaK)9m5TdA>$$msS3R;uFF9V)f!pm&uI0=3wl94P!p(N=#gA#wq*1sqoaR5 z$d8y`6}OHbknc$c)BW2RKJ7p#mm%izZzzPyuzaTCXO)L%xJCx8i&RBv_$7=^?h#_I ze?c?EYP?*`4^WovkoLeX!GxF3?mD@wX!`@!v!sBJ_gPq@CLQJSmghKBP)tXeu)rv>wz_hmf zT9k%Wq6WpHvHKt%yt82ek2>_fGK*Bvdz=g8^}M7KMrPNX&6m+$gS}t&plbpq)vYbp9o-@5*OgkrRBMwOg=*<5Zv9 zAZ^fXcNoya>g8aJ%w^u+mA{@4Zj{N%Egh8A8J_7KUtJ^?y7JQyWlsm)%p-Z*5a}%V z8sV(f7iRCChK_vQ7Y)(wPntJ$2#juI4mIg1{$Cxkgcp)qb}qLnWJ3By^DJ83?5+jn z_&uDE(~JLOL{x6mP_QV%g1#ILtV>UF!oSnm0en$Ov-o#%S;jgBwe240&Nz| zGQFACWlE}y_v-C3{(R0a6Jq0s71igj*Cq+-PL0HL1vrA-8Ka4=H51k|Z+?uFsMW-&| z93n1Z-OMjis<;WC*?W?{G z{nwv9nVU$1!S<5V*QMx}n)mx(yk-;X%Y=3c5ef9XoV0L!H0EzToW0Rf)L1ORa;k1o zR7~1p#!QX-#aEe0Vl3?z((WFonU%T}t{kYeR!$6jy0hL7W+Hr-Ooi{Ho^#pMW5_#B z2kX!m?-cECn;5!nRpKjy^a>tQGJr*I^(OWIcj&hFKrLP(@pXyzylJa!V-MbrFKltO z=Sx94HU(Pk2J>eTkiHY|B#Dkzxwpncxt(FRmL^_vj8zXS5?pq@WZ z9=T*k1=&W0#rXXvp=rZ4`_p1yFnn#?cY2WyR@4daaH9Jo({fgOc&jxY_Tu-&N%>Kbzw0sn@egN9 z!l8cQJbRDq38`RY6ygH%wOW*XeO?SguOB^PIyS%u?yWr)$+BZfAlK)Q5bEY%AloO zx*%T((23gty-?CGWmpD#sq-L{TYE>aDYhd!Ok#G7x~@8_;DtqIaC06Elz>F^+u4Z((RBk2n%g6~dImrXy}c$r%;Kf4&G{|~u**$1H9Lo~mJ z6{g$07w%FCH4|P2_dlFZN&4~WklZD(g|7SSo#*U*#t08rL8rvkI?0}I3cXUn;z8~E z{FpvawWH2Yn;sl&PM~)125NvqZUS=sqHLm<`)9j%Pb`gddcIqTs;WkJ8^Q6#9$xM? zabffOHHnWipm~&iMe9!SP`)W{mb|)`iPIXYd6hSKf-`8voE=>uHhjI=QQ3N3>ztDG z;>tly+cKHOhP7=k5G+6!)g9|9^>9s5bx;I+Hg9hiMRyX)YDVvv^q7;EEIq*E?jDm@ zG?eZFK0dPxh~)Q#^DeE!Q$=Aac$g#t=Rt`dR8t8=w|64J2aDK}&X0{!1)$Su(?bM? zqru@&$YU**DYktpDk`ceX*wp9>pA@Q&PgpC?({bbz-6Isk+6(E_`c<`D~IHa{R+?SBWLw7Y;Q`5=0 zag*x$Pa;Au`I5DhSlLgyg@p#ock=uzo^7oSW!@~eoDQ$(L|I zCFMiXq@$ygm2 zS9d6RbNSi}T`dLK*A-}e`D-nGeoP=?B2?KvJYz8|R`L`RBId08h(@>6u3%MrLiGF$cW^|$Tl5Tq;NY8AAA&$fSiG8c; z>c@`ez9-LBSz9)LnLHt!T^VeXdgrrRG#Vwo&b^cFxrTuxKE+ngskhxhGJ}b;5OD?uUOZs*ysivk%XP`%* zcBs}d`qmfV_4gB!$5v<-XQu%|T{j3P+Ha5m;Bp+zaq?q6lSi26h>6%N27905*ji6L zwv{&Gs6hOUg9aY3)l(rJ_pQfF6Tn+vV=V2EfvJBN^T-!uGSS$|BJkWtbZ!_!&{}6u z7{n7Lnn3xaxFc-P5{dU7esnxU_6SWbmz;GY-4^t;QnQ$O1O0e2J%l>v!a?o@Dc0Vh0iX-hzF@iRJATRK#mYj#p%a0J-(ctuU<{_0$Qus~Olf4geb6S-F0r6XQ(2?j$qpVJfUeuG` zEQU_~m#-K6bL!W@v0AzQb#C_$9Aw^s9#ehddMB`}-H=eS!iwRvJZn9CZM8WT_$rc6jKxp)b` z81QE9Hb>JBTvho)X1uxsGlNftP!1W}SK&r&#%8+(*MvubrQsKNLZgzoIrok^p3V=! zj3f3%NTd9M@adh7LHi>CsvcHJpiR zKAHTsJbSHB3MhKb)p|_Xv8HA>TK&h#TqPvIW-J5hC|wS|$s8#Y(x+walWg!UVV~2e zN`wu;{_c=ywuV`xGzArzTL#z$^F&rK)ViHcnnY)v5=y4{v!cP_Qn6wQSLzoIfBTLc zcvtLm_@!OaTNiSh$&Suq2ClVAs59ON5?uco965V$CRAYaBi=K~O>~}}x?w&*lvOm< zQ_1gU5eir0ghE8K?_b!Z zg#z#9_P60yHtM$GK0&pn1fI=$h5KFI|3F+$E1QqBET}f?oG800=6?mw?4|L_;I{&> zEIqCQ-A2*#*12eeD?x4?pT#JbN#t1`>iDM4YwfS=H=CPoIaD$?$bK}zpGMJIoASkR zDR;W6y}_p-eWTH2;h@i(%lmuUP*_$0EGy#e%xgo#yKlZcr;1I6-+ex9?Yh=Z#-+&p z<#yq)ZSuj@Rm`0*VbyBj?exjByQt#kU;V#l^#&W((l%$;ObL;KQv!55-ce%F*Jx(d zo4FXI_bouT10W~@E= zR#F+t?b$Me*@e%t3&qfW&VHG6Z(11ao6B~n)#sSD9YR`6q1{qu(MR6V?s>983H3-{ zQ@Wm^P%g8Lag~6;nxn@oupf}?PXcER*;7>Bym4sWBq!47WpUt3-F08S8RzT%l*kyG zHv;#A|G;*aTiu__a4ER@4>z#al1ukYkFZ`oe8sQ%-hMlkkYLO9$M@6Uh#iQ@?0(Ny zf{DKsH&KO4O{(WLNY<9}l<#q2@TF{h(F8GDlK;6ym%{`>0-k7JQpP%{$r|O#*bRL3 z5XofNw0YA3d5^M7Be~kI>$)?{ymZQX01*5Y@Q7h6nd5&Rr89qoRBaUoS z|D%bt_=D4B*umw&&{__+-TRxYpeTOM%vw_C_WmsxO3Ad%5FFz|BM5ptOO8l-c<+>&}TPXap>z1lI@<@1uu*2}y) zQ3=GpF8Q<7SCHHx@F4t`sKQ2F9kh_T(E_d=V=DTTNuM1t{6Y5*_`EZGPNRoW)y{o=; z)+$r8`ND4oshnB4P4T>M{0Xr?L@8vl@V6ckjps*Grq)pzPcZMm|x~atmcH zGuWa#lV{;n&F8*8Lrk6d1ZLf*B9;NtmUJx^Zi1VmIiB15$si=7IrUrIOVg~b5F>`7 zt-6MYY|j=?ZHg0|$NNds;(bVPIQ5%9#34gqI=^yK^d=qg80T9N&KY1U)hBiXNeMO8!1I!yaj83a*RdtJ~yfMRR2~r z0@V=x1X3mJ@E|q@X)Po~;1d00*F7DWum^9}ICFI^^si057GryJYEARKQPt+bw-Q`( zJ^^*pdvK^+N^6OtP@`I*k};dN+#Uy2-7#W+MF-A0w({m3cpxQ~%j&_BHRjU$=e=nz z2a96zztRDqz4fq&tEWaQ;tg?5m2KqSli>t?Y{v@20uncxV`ZwQ931BTBCg~We0zdQ zO$uuHLrj2R`MfdJntf!O%3;h6%D!wdzf7;1mg4z_0=#ecU4Xfg?-r9r-Z*@{MKFL$ zkbKaCc{O&frqT9|>bKZi$7+#O)yYA;ul~GcS;f~h=LqqG=o^d@SDDyy|0oXb`|axTgwILcX`&3}v|-DMOcpFdvv#coildPz)M!scXz5Is zbWwj&$Zh;@h`8s~3Vp4xJ#+sSf*CJ?RKT(&I^oNIKSd^!>3BLnsoTDvHzVr*66y6) zHk=!HHxQX*#%ulfaYi%Y;<#R9HOL*fBz7)fW76J`OHt}A<;S=L1@7X`=;G9Ox)M?R z{F(E*pZ`Z)UmX@@`*kZIARVJLC@md>fRxhWP)ZHbgOqfqG}0kRcSuPiIdr~sH$x5G zLrZxc-rsk=>zwO+=b!m&uDNU9Yp=ETp63x_^2RN(DycH~T)hudOB|(Rd-rI9*>qzU zWpd53bIC$yRah0ho}TMP_p0 znc4a-nwy9M8>+O87NCR*Nl%PC5Dofy$QPflzj@haj0zdT17;b*d}hDGfeJZ@eZV(Y zUnh=^yNod|`}bwnoq2IJc)mexM*ao(2?ZY)f8Q!D{0OJO)o5H^`jj;w)X~sF+!HH; zZ4aj`cole%p__0Jp{E4T4{p4ohh=n)E5u#xpM$Ntzy-p|YKXkPXYn+dhZ)C`hPLhD zSPC-Ljqg4;{$vF?#BZZ_&7aXnq^hl@m+hrus4nCa^+UPry|^+t!!sAE}< zuNUa}se>T~*nCFPdudI*2i0^zN;K*dXf9?N`cBsMIgC zH4@P`6ALbVhr}?PW>EceH+GHT{SC0SWtnk(lg5TEg;^iekQhx6QgR}eAP{KHpcp7t zVlD+HIDAB>!McStcM?Y@d(E^~>=yqOTqvBjI%KI~(tx4`@A7KWb93d74gM)<(O+`x zb*S&!**V1NO|E=~^3D1QPo3h}oL>%za%6Hy-@XWCc4D@3m&d*-Yiz51h?UlEQW0D? z=vq?`J6wF*tp}L7nty&zh+gu)$4&9dbw@m#_>zGxm0=jSs@q1g`huNngK<<8@uZpS z1;_hHlkm<9n5sP{Gs1aAbHyw>y{Ip^C_4v7ZR&wHR4Y~5eX?9I91-rz z_7y=R1-FxzVEQ_znL24gI)gTIbjq8F@4@7fxyur-p?P9yC@lu74v6aA(Ewm4TY1-S z#E3~MM{prPg|#Y0@IY&gZ-Cs9VEEB{KZ9iR_S^;|GL@&h$mtg#gpjfM#1KDWr2PJ| zZsNgu0Ss!MW83rHN>LPxdye+|8S+H4O9e?nwmAUw%&u$t~U-{+vGodK%fOnUjPjc3&Dj zJG9#l+rXrIgSjT}!)m$(RKW(M2#Lx-I<$;X`F&~0p4IheDFbtcgh^OeHUKtBkp}>p zJRP6#66m}7WIWqK5%t;8yk+*V9~)^^`Z!aqD~J-?44i<7zm^NloOVTD%dUs7Lzb zzdhv~RfsIZz7igLDLSnVq0mNf6FwWSH>xG!I%kJ&rx#Z^+?%ZVe`CMV7VNj{JEV|_ zYh3Ii8m#}Vdi{vI5popU8*HMBzmF|OSn^nN)ADZyR7w;#h2Y}S=%Ok_oWx0yFqL9HLz` zD9mk^=P&>PrswIN>r}Kx;PPK($(Y^ zf5)`#CRYrsy}H+~xE*~(tgX`=OVg!E&a#E+$ym+&1PCV-mq)gqSZ6!O(mC&s7(Qo& zyp_o)>M3*Imzk<}Yw$KKFS0Ix5&0ATipkS@k@mn~_*dxZddx4rrX&v4vIa!)&76pj z1uZ$|{juUDu`aAi1+H@6^Pt*M86bsYnhDA6uUN&e#v<(BMSI`=F!QprnEeEt=Wig* zrW`qDdyyH^5Q$+glAdT&efG(mcNT%N#kQHA;*dLJ{)S4;U_9sCTV0{voNe`wDoC1K z{E28LhD_j+LFVpIRnUb*9LJAzJ#rQcq!lhe&(HguAF@dYrF^NE2g zP=j-)Ug0B{pyiCKmCYqU0@>zk?~Ek5ajSheMz?olN)@vaR4QpTzx!h)g9S956=;8u zzG~|}iz@M6j9@k~xfM4(r-C-hs7D%%l+_N|2vdZz2|uMmJDk z=fa_>#e8Ip`mb{H>0xh(MDo3A4Vzuq4>l*AE(5E5E$-l~KlTT|f{daL57_c#$Y0Fo zg9fi&+c}BBTJc5bSbd)MOMwz=%;mIjcofvlzkPf!z5lps&ixQV}HhZ8b@W~iuuPLoh4OP&|6(Trd5+D zvY25ij|1T=V-I64VKzmKagTi@T^nXLo3%s>PEN#qHHI0&{7iN+<~^zwmPy-5nJxu= zz>hCk{B)JtbDX`*aLSK}ysEJG(-ci_KBuW$m9p$KK(_G6sP-e={t?r3>fl0JYyVQ( zHukqP(XBg@_G+ZqlF^$jmKKXPp!RA6P7YTjLyEs#BYvaDb+E7#sxdvpT=v(o{QqQ} zXWTC*IH9e!uP@2g7Uvt({{eEqMk%`w0;wJFyqodj%>%SWdl{JLlxeGd{Mi(8WmQWa z=Fn$@^^-`Kbe4x%Sy$hL+CPeI0?Wx!7~2g4$_V94up!*p@M*PJ^Pws(k)Y<=3WrK* zVI=k;SES%sSj;J-J6Mta4q$G8RYqkQ<9@pCaU_Is_f)=3Z0C8*l}%j7^SU#GK%__N z!*-}mrg>_MMNc;^?SA6O9XNe)U@M4ad?K$Dw|!|&|KlRCO$l@{lZ5JlD|s*|$opkw zpo;*~D|Ep363s^d1^UAoo@wDjedzit^=XP`pR>QL{{R(Zt$@%6Y}T*fGfxnap!%G= ze-vw`hLDAW39|v31S_gKmX4bv%%r>*P$_X7?62vJ%R(LfzWOHmKF-nBW1Mgz^#Dg>;EuxN?STw2{bk(eMYV9_;m+#}3z?T`P(b7h?!u4OFT8y-kx zU=rqFLEW?6Wm2WK{vP(5Zux~*HI5v0Ml`I#b$qZr48qr2FzZhN_A5^_FYoPYov~ZD8C-<3jl9~ z|1d9;rTnX6N^pW^dC2w3b*oZkD+8Bs7Ky|F!j_DoBOI>h5tR7_3?n^4yAR=`i@GZYmM$x>d2|^pA{>QJqP9?e3(W zXgrTBNrpD!%m+4TWO#jPu5|i{TSn)T66X&3VR`%7<>=Ri~V+Xk9F-^*j#Uic( zkeK7+Z^@4}RziRDb`O}%Wd=lX=)hcetTm-({~tE!8Tbhq5%8Ub(Bf<~ZRbhQZGE zN*4^`w70i0#o{buow{p`BQ6(W##DyJiv*p_veH#DQWuxB&|5{rWrRdoq;l|9obAEK z9(5|54-tk8=kRT2&$m~Iv3GJgq0bVV9O7zVpQzd2d}mb})yo5 zu1num4?1#kwZw!!3J0oK1^s4G=iDQ3>CK?G;ca zXHn5@`rS`QAd+8MZ1d54USKJBM3>TWTTl7MSrTq0aCuhI!-b$K2~7f|U5!PgySiZD z!H+XsOY#(yg^Yz5?1)fAf)yITB~Y2A?HT{$*jY?a;M>8k{Ka1pSJBljST7ude$ zAK&n1zP=IbKx@$Dnqr2dg)lqw!IHbk0jo&V)?KY?_S1c@ioJD*_^E`kU!1PUa3h3OJmYAlI36NKeq779d}`usCXPejVb8Xt1GR2sK1BBI(4L9Bu| zohlFMwPXsT<&GbmOC|MFd2R;As90V(A}f z_-x6VDRd>KO1MZ8J=^fG>|!`d_?a}zbe>lkp}PQMOX6N~h;9{ijFZ$A2AKOGRiO1> z!rnkRFrMD$EpHCH_QWze$%XNwB$zK{2zu1W`nW(ayBgD#;#Nz#tL0{Mk9$m9Y7Oikj{ot@ zr3mdU3}PIwgu^Swsseal0Vhy`CYDTG@HN(mZHWB-LGnvL&x6~%cbGy0~VY$FE}-DRTUZyoQuYYwMo#56h4ugN!UonAHkTP|4LSODq|w>VQLz~ZRgx{ za)#6{){C$Y1s39L!xx4vD+1t*#Cl3|U^t$+m*9m5JMEB^439hOa_ww0 zg4SQ2n$bnwZj69iTz)^-&8yKqp%k%s=bSP<(OEZCh@n{=7yYcGgMCT~S3}*dGHqw-ZvZG3Ia1J(ql=>kwlw z9`H5p&H#M%ZH0yfnuAAdIkoC`tK0K*;&{e+*=)w^fMM&imOyqV@iG{x9-)3M(n9b& z3QAVV+M}k)nN91r+DLuD(%fU5R~SB0YYhVzAz{urtv%ecEgfl|5-wuJG!Qb%KUxrqIFJDcE1F`h5O>;y)dt6 zdaM!j+ygT$Qy7h`Y4~nm5g@6abV$dA`Y4}>G{A?^DCM*NisfLxZKB~{f-}MXK6&}O zO$L-=AxHYsC@F9TV!tvDK2Uj$Kh%eT7dPL#Qpb`{bR)Ss00mI`8Ip}BWz-0(Q-zJ~ z<0i_EHBjr@!8z(jojCKt-;g-29k#cz{4OSK=+8|l*7U+j2S4@e=WWk3HF$jq4Lu$8Jg>|F_0fA(hL zKA|Q{{GL8Dam+4}`H=^4@2IFSkDYVrd}}W>fzHnGOc^9pE||@VNsa+We}$?j#TTBe zE40<>tJZnVf)HP&@en4yDv0o8`T~(!obw?xXZ4X?a4K05#)1dEa#0SYGVI{$1d`tc z^dtET8{?#JB^jiq>%5$-Dx7!=J(rQsY=0m<*VcW*G5+ z7TwnwZtfNfcB~9z`8~Yy^qXY~iPpNuZ`YO(7N??6>TeB=THTBZ{}{bfrVA~b%1D6G z_MqX%9`_T&tc|-EkZi2e`O&aj-}aUQIij_(69?0cFW&BTx^|BqTy#KmPy`dkZKDT% z9xQ2q9QA42N%LlwUmTfM9$-I0A%IQY;x1n0O0`z$VZ7*$BD^3CM7im&HS(jpIJ2Jt zNFwiX8XM#P=j`VJFGB1voaIL|(}W^{hNf+gEEdqq0cn!rS04O?pBv*5YFlZYgV!wI z+M5Md3$+o*KK;n%Z3|OB6$dH~qfjY>keVIxqL2D*P@`s!Bt1%8RIOY5!7@dyilCfT zGsFo`#i=w(KsfzCJYJyXL+YrRBS^#BB4QR6P~P$4;7f;4LjoeS#6CgXAYtusdu~td z3=Qa;uvOE>lM96rEdDItMb^gVZV|r_W~ZlX)D#7%%(2jb9p$?Hsdetgy0F@vw*jod zN-k(PgSiVUgWoDj2Q<8L?X|;Aof1EC*|XURAIpQ@?D%caGt#?hwUSM@gm>3nx+if| zy+*spsqx4>awM++FGS^Ny5hhe&;5Osq8=X#r`SxRm&U?F8o@0}HuB8euUgKz>CIG_J&A|u5?}y z!HJYUOVxXl+uOx6(2uj_(X9%Ay48n|y?-Q@JA~V_%wjabyp7Up){+E`z}|@3u}JG0 z4sL%qdi%XK3DsQ1uSwQ1UN=@FLYhex5bnE!kIL(8BQL>m2J@tb({ox)aRZw6S6%d> zj$EGyL)Gto^c{Hf1CL5Td3v$eId(F(Q}Yw*lhsD%a+!UQ3I=KtDCPT8@of^XGCtVy z(aqvdg@bu!2Gc=F8DHELg)HqHlVy1~-b9X5;f4=zW$YUX9}3f2Kf3c_;_Amp9gv0K zxAw`I0nbBo?=XAiW#{fJ5Ym#s2+qEJl_vH=``}XxbLI%at)_bq3etJ80u`c#Y)h`p zdh?vWpkvFFVG6lzV}`pkJP7q=Ihv?u=Q52f9Xn^^uChUA-O9iybUM?DMwk=cd&R|Y zdnGS2u0Q;aUFNz=#V0~yDSm23$3;-yMy1<6JU-7p$_pz^V?HvBS6@AKa|R-Q`9nYF zH7aEHTPy|(hpp;NytoSlo)9eEHB4bo-^{uwOF9D!T;lK0zuH7Of}Wom5yG^~3(Frp z!s&c?M*w$^y{VO~*b8&M%mpgIc{RSqNcShPoG7K(;>)6YpEtPu*!zhWAilNGad?R| zgo;XX`~^pZ6;v6*SvVg~i8&#h_ zT3}IZF_Wjt$}_$oC7fonqM?%301)mWQ^gvEslF|bwqsrs!?w1hHFLG*m4SeoZQOOq z_szf7n!ec8QCg~v3XUfr&R$fd@-pDR`j%A=#;_8ohm4MowTmYwoh`EA1L@$6$*sj( zaYag}7iH(~>wAXs`Rd(Ei_`W|j_2GlYsr;O^j0;Jy&LO^^LfLGSA5M|Mg~0ukw!P` z&{_=xo}&iiZFO6ueDumHHzTQf4xY_!Wzz&j<@x!!$bLg^gKCdPNL?RqK>tU+=g_oY z&>RH~dS&$OJ($rkdHZE!L_7y$yT+m-`&@rR3!n32SMQ%#U@s(jWgr;(T*s1~em4Bi*iO5&e<0-^vf2&yyAsfu#XL5cro4lO zb4~^;Jiu=pRNm4mukPWXmUp7q_+xnV1(3xvA|de9j8z2xg2--)^QYnndE%o-F8CrW ztbc*hmUD^H-wr5-B46fZw6hMiL|a+5llM;Nh>)wD>FBcBOjT;{?t(^DWjJQr46!Fn zta(J5CMNtoGsd-RR6Fy6v>Xnu}ogJ?HhNNdNZ74wk4^1fzBOn6!Y0St1osM)gascRuY)$V=7 zhh!x%N_~@XlGahnTl7_GZO5r~!i=wF9z`XzwNUK;rwp*n2euL^fQ;ed@Zf*20hEJf z+9+_1WWj=S0Xmsabk)PN;W)DC17_WpA=jQqO09l;I55CBcuC@GP#>!z*LbsPzojVSX zKv97SF{j^`a2%~>JlN7b@Exes(c=`~OMdmg+wINMW9`bnxGSs+s_er)S*Mo8+ZTua z(qB-F`-Ndl4%tP7SRzS8Up;95ntx$z{0sBo7h!}x#lew0NCfy3Pp|24U+}}kQ~AQl zc_gM!n?^oYN7%fVN@YC~H}2)4)*m)~{fOtluI&(9dwZ}!+RDM<`2D)&Z!?6aS-=xd zFk-ApQ$zDQP(L$JD^{PZfk`%*NVMs$+jBE$@Qp6n$)m>7lF315GEM9^1VuY4()_IG|#~m&5FWURsVNpmTH$vy*5@#VeZRjUlUEQhm$JD6? zG1DtOhd$a|FPJ@Q%&mTJ& zf6~&@5{iJaOe-6tm}YWXV9D}G-+#i;U8^zbBI&qoRr=})%M-3m7J__q< zs4*EJ)AzJKwl4dOvBS=)(xCCOl3(}@BV*Iu_Dg4Xk0w%(`Iy1%UMlR}(@ z$+yx22t`7Q)Cx?SX|_raTmRl4a_O9`S-AH!SPuVlu4jpbOu%#bxADn746siBhn}Z~ z|J@nI_KADW`G5K|--`v?H-c8P6+^A}*bC{8aTmT3P|KY)`1Q`wx)wkq&qP;+hiA_> z$mg08o{qcDF~c8v!ZgqI+|mafZl>(zdVq9Uc(nd%*0?oWpSl>YOZDh{c^K${43*k( zA<4^*LfG{>)gvWR4laCrIFAT=Xiq~eDm?fXUz=212H!M?e!>Pf7zEERT`W-_-ttX0 z{G+FayI|MrTsT5_;h0}0E!~~e*SL~^M>yIhkB@OQdb9NW%H!`0R?D05ORO8KzZ6&; zu6caI($rS11Y*O|w3lNxt}B0|H=DZ^Nm_8+1okwef+9fLdH_SV~EVY=K> zp5ZRuN&Dwz%29%$)V7>Kg{l{OZe@6fDY32Je)%LXnW`@Ai~!!>_sXR{{KOa0Tiioz zgwj)f_vBM8nY3oShhnj`$xG#jpH|LVKTus=%SiOXKMTE0F7}ePHm;Dz9_|8;J z^E+W}4KvPtkGxAMBKuTOLEuutdVM(!^a=AzYix(=kA=6Zel0g#@2&g0rJHUiXK9#D zS*CpPb%|MfAu;k!Bt=u-mHQ=O=Tx|#$_WeA4B%8`voE*xi=^O+RrqKvdm@Xr5B=k* za}T`0y_7)zXnzzoo!g6TVwU2QER281T!(-o+cynK7Js5k;Y1U}(A + + + + + + +MakeBlock Drive Updated: src/MeMegaPiDCMotor.h File Reference + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    + +
    MeMegaPiDCMotor.h File Reference
    +
    +
    + +

    Header for MeMegaPiDCMotor.cpp module. +More...

    +
    #include <stdint.h>
    +#include <stdbool.h>
    +#include <Arduino.h>
    +#include "MeConfig.h"
    +
    +Include dependency graph for MeMegaPiDCMotor.h:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +
    +This graph shows which files directly or indirectly include this file:
    +
    +
    + + + + + + + + + +
    +
    +

    Go to the source code of this file.

    + + + + + + + +

    +Classes

    struct  megapi_dc_type
     
    class  MeMegaPiDCMotor
     Driver for Me Megapi DC motor device. More...
     
    + + + +

    +Variables

    +megapi_dc_type megapi_dc_Port [14]
     
    +

    Detailed Description

    +

    Header for MeMegaPiDCMotor.cpp module.

    +
    Author
    MakeBlock
    +
    Version
    V1.0.1
    +
    Date
    2016/04/07
    +
    Copyright
    This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    This file is a drive for Me Megapi DC motor device.
    +
    Method List:
    +
      +
    1. void MeMegaPiDCMotor::setpin(uint8_t dc_dir_h1,uint8_t dc_dir_h2,uint8_t pwm_pin)
    2. +
    3. void MeMegaPiDCMotor::run(int16_t speed)
    4. +
    5. void MeMegaPiDCMotor::stop(void)
    6. +
    7. void MeMegaPiDCMotor::reset(uint8_t port)
    8. +
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    +Mark Yan         2016/02/20     1.0.0            Rebuild the new.
    +Mark Yan         2016/04/07     1.0.1            fix motor reset issue.
    +
    +
    +
    + + + + diff --git a/doc/html/_me_mega_pi_d_c_motor_8h.js b/doc/html/_me_mega_pi_d_c_motor_8h.js new file mode 100644 index 00000000..ad642ce1 --- /dev/null +++ b/doc/html/_me_mega_pi_d_c_motor_8h.js @@ -0,0 +1,5 @@ +var _me_mega_pi_d_c_motor_8h = +[ + [ "megapi_dc_type", "structmegapi__dc__type.html", null ], + [ "MeMegaPiDCMotor", "class_me_mega_pi_d_c_motor.html", "class_me_mega_pi_d_c_motor" ] +]; \ No newline at end of file diff --git a/doc/html/_me_mega_pi_d_c_motor_8h__dep__incl.map b/doc/html/_me_mega_pi_d_c_motor_8h__dep__incl.map new file mode 100644 index 00000000..b2563145 --- /dev/null +++ b/doc/html/_me_mega_pi_d_c_motor_8h__dep__incl.map @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/doc/html/_me_mega_pi_d_c_motor_8h__dep__incl.md5 b/doc/html/_me_mega_pi_d_c_motor_8h__dep__incl.md5 new file mode 100644 index 00000000..a4e8c06a --- /dev/null +++ b/doc/html/_me_mega_pi_d_c_motor_8h__dep__incl.md5 @@ -0,0 +1 @@ +5bbcfe4a75735cf45ac5750d3a618b61 \ No newline at end of file diff --git a/doc/html/_me_mega_pi_d_c_motor_8h__dep__incl.png b/doc/html/_me_mega_pi_d_c_motor_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..31461a73c09bc773801ee5608ce6c7b8df3caa64 GIT binary patch literal 4790 zcmZ`-c{r5q_g9KiC}nTxwG|rM$gbW*jJ3v^F-Td)J~YNUcqL@ZHpmRg4B3~ljI1R~ zh_b~P*Pwzj!-}jI2{an}cJlA!f``qU~=X1_|&WXEgs?W(G#KFSC!U;9d zg|V<4V*vlYr`UiuMDywp@L_W@(${4<`t!VODN18u;qid#-m(b9Gp0g(?OcPpH`d6d z@HvCH#%N`MtH_8~>8DXtr1T^AIo+D5NEQ`n0_c7!DNC7aU4KcmMU4{^)G)Wdp@LHk!Q_K(Bw){NUxRj^YZcdTSqN0M1c%S8u)I|3Vs8(9ojq-J?=*+mD4f7mlm#BU`}adZ1#HWt{bTZt<(sJV(X63bZL0goKO4O?|B z%C>D@(+o3!H4Z@!rmb83WdAZ2lc$Ge?%VgN*X4@}44oR$mWwkl$x+!yXUR=nb$YF< z-WaZ5eL%VREd0h&%mH?@MXtWwb|0_XOTyJl*cWe-qZfHKB3v8z`2C+(TBvV2^M(*) zr)O&1B})xk*QzGr{h=wruK-$8Z+=fZ_60+9gIq1%X+`>8oU)Xp7nCURnA6%lCu7+v zIqFT0UaH>Ie5zVJ^zMTuuT26RVPKpgQ#4XHoPiVeS7+_7$+XttFP5vTl|=O}i6ocE zw!jwnWUqwSw=QsegvZjhjR-69wZ=B2-rkl%t<`|-+qZ-W|Jph-G7_+xSNPY7i3uUh zHE7Wj3&a&uyra822d2%lI|*dg1xhv$SQg=ri>r|3OYtiXv6GO33QEe0)!l}|CGHrG zh{3qf$^X-|Y_Fi-TwGjU`g5qA#DCU2%1F71apda-*TrKiW>_ zGzUQ;<#d(dQ2Vq7{IKz6s*7!=a#7On??K_rV*V15kwzo98g|QKv_Z2QKH#x9wA=ET zHf097srMY^V%Dz^BICI8sLRE)Uq@=@XSJaCg`Zn}WK^dRu1PdrlP#s{vA!}=jr9Wd z9-DVJrJcYPMdC8zlvDWb>&A||8+bI{x~dr(JgHI|Y+mm3ZmoSBLUq1bwo^~vUfUgw zte!Ltzw^MD6(S%%XUrOYo$A#jcJ?08yO;##q<=qi3AyITI-uvD=6ORiWW#cbFqlwY z6P}>d$}=`kjBJaQjYzSq_t`uap3H9SbPZk9_+F;`Z`pyMza5Xol$@C-#u^drk(Xa6V=psB8;@uGx7TM_% zG5rW;7dBnDV{v`HuL$$bS|D_@{{;Pejf#DPSG1(dMZ{Ym8-lq zd-2Fai9+8WLX3LGiO>^S)%Z;s7gDL2|L3JDIncU8*oDKXL#U`g;QPTuNyii+A`y%( zr$2AlHvQSvdip3=bJ|4E`gop}vz=CbFB|Gmdf%cRwELU>J!FzUl?c0h6{3fue@=5PPP?2bRu zZysyY8W`7ek9^ZjlH0ztZZv!>tlh=&bXN!SY%+TC?drk}RL@{e?xJct54-Ba(EDc& zpvwWwsWnlB@f=ql?Of!-=x%vcn&J~nizDJuy=Iz#PZv^YzAHs;-;n92?Xdf$XqeW& zw6?@EgMvJT+Xk*Pd3Ru=to%?lNv~qz$@-vW{_vjth)K>0$h^WaaY1?oVDJf@m2K0# z0RQ^q;i}Y52Pdmwiy&SA@RbylHXf~A+q9X|IOa9y`Rj!|0qIoP;Y??C4q}lcE8H+}qe& z!_s4o{<7<)jvNAcNT)}kByG|ARbtowhQi&g05LH1fEl(KXVoq!In0xEAi*4$A^E)X z@e6#}W8&yCgtXTTO&nb~Ak*Q~E@kXP0?8DJ)>x-%>X^6~jMI<`GY{Sk4k<|#Cfhzp z&QZi`bh37MtOn9HEN$1GtQoz%ZvP$EQRGuUWWKih!@g}$a{%hkI`FcCw>>$MaI4*> z+FVp@`wk$B&Kfp6M=&Si*o<95jQRR65MsxMR;}mU_a$`67@|*$*Akz3JapLQ)_{O_ zesUVUxzxux?l#aJxv8*IvJFnufx>w_7~Wi9A)KbK@C!C^>ERr60C zpq-*|*x51LYl1&(F0Fk0)v}6Y3uFEknCBHQfe5w+PNR23M-vs)*`y8_f<^4#=eHhO zaW_Jm%MvT4mVRibbi#&k@4rv2tyN!yqi%fj9dUH+YTRwL+#ypQ8a-=09X^ED7BBUL z)2bytd+j%GQ#K+S$96~CDV!n9V1dJ*oy$1glNf1X?2}C806WxjU)aV^Bl$ zJSG%cKm^&3aRvlOd>PmsCpz@CopnHVid+;=wE-@P_(*8@{xwg8*MD^l{BQO^k3rpygqjT5MGN+r;FbogY7j((vG8o{XIJH?5EEE+^Ykc^bd69>V#m z-X=`a8hd7Pyh9&s*|ruMJ?<^Q1vvLl{|KnqKKN_K858i3rak6$Ggk9PiVko@A?BFo zhf#m_&Xq`d#6DVmVD2i?+J0=5BiJoYA~&_(Vx+wQi#@kq-8dQF${I+UJ!4WiYb5lW z9B4@WtUkQ=G|?q=gdm7%#TzPW4LK)wgYr%R=}NTci*?z4L41?`nD3V!nf+bL z!_q5;)KNu@>YKXuyuBrlg`xIb+NnT+-&!ah3j?wI?VyK~)a}>$E}sfw0@@wZi@2 zw8J-ot`~gItV>1td~b#`0Onx_`@cDJowTb?28s_n#5vg|7i0hlvGDuf?KKw9IGK1q zx-8Rkx{+Eqmt^wJe5gWHy#?`wRlbo7$MB>(rPr?54F2U~WI`U8F>haBGjlv^(!q~G zPxPU>uPgxMX09T(b7vi!qZ?yzZVnlChE()xdW6FZF2GUE<8k=LjVLzUsFoyS4>!Db zc-eP|Am5}|OPP|R!@XV9#B$@xx!mWoXYa^4oKJ7{KT`Jd;O9mL+DQg zqvzfaV_mNio+nP+s2{@eU_5z1l8i3g_NP>E`$Bv8@!cX<0g(N}!Oly$7Llm|oJ&(H zjA9k<$8@V1LO-V!lrR@Ldp$sl`BNg;kg6nKx*c}mQ&|j7nGM+BQ`7XcOP7=*iyHs@ z?8Q*5ex^1b#uJ7BLR%@OvSGM)TY6mK=o61)?ZkMHPbMf%^G5MCNyZb~rpaLtolM1- zb6K;Rv5G@X5)vwF>44+U0i{Q$CzZZtKpO9%f#X12S&#}vx$WCf%?AT^m8Tny^LsdE zKQbS}DFkx`!S^IQ{6uYao`&41BhUqzKZPA0Rk2n#0d3m-RAtwCa^2@6g>(B zFqCxb=vJFT)~rvz4fo6dzamp)rC#(sC`Td(h#2qMZ?s9I6>=A`Q_j&}3Wwhu^NInG z^h{G0$<4)ec<$=jS}#}0hp7hij2NP^{ogoO4QuJ(!u z2-vJJS6*F(``J~`g0Ndf`i!FKJv1#}`8eiiq^GAxUKZgEOCsaEmBKeg9WFL6P5D$i zgslngZ#)^mTrp^!4=`uy+&Xs+LQb|vb@GnJmz~!>vUGEnCit{yEt_a>yuWbbRuy}! z1d^2i6cwV()m39Xi&nhi$;#vQbz027m#IL_nEm3#@o_c_E##FIwSAsTnk@8Xh_{;V`mrVHY_O+ns(OL@9v+OarF2m%v1bNM+~=rHwdHK3Ie&3p6j4* zgT?=MG0AuSeDQfhDo}b}7fXRo_STd#CJ9_z*^rKcpca z;6CJvSmi58WY-RUbGQ-5^JU0%k6r3Rfks+hQ{HGz59SkWrE$Y8uNc8=L?yiu=Rg~! zr>?z(t$wk~_mj0W-PsCV0N2J#_G@G?TjO$;jknNJ2?}w|_+11ugmc(L*k#IZaa4u@ z8J%+F+i!G{caY{?5|JNWz#V89@7i5dw0MQ5wH1tGvnb26);0gGcaNUSyXpIHP0B?k zgjV)tTYJDXhD~Y1@XN+Z%f{sxVO1UmS1`};kdPy1=uwQi+y6}^*z6RrZcXVQ=>~zSfCQtD2 zjSE@J$rC+%vV-`0m{p#5}@TQ+`- zmRb!aEm|&b%DPVYjd4QS?05J--AL1vUk)ow-KM~{6;P_y(3(4pq?BlL!g=ZBo$NWD zaN%KzxRO5Ta^`Y^K~U}BMc_`6vb-#v2{05Q!J9vSZ;~~hn*RezAlcK^CEoe3w#Yr- z%TxgE*XN%L?XHps>q`b=)Ajcg(pSoe3}*5%(fGgk;y%%Kg)ApRB8p%4^2Zqg9U92J p^wRmVC+8PX0K@-3h(m|m6c$glr!uY9KqHC;s%NTOq2u_^e*i66k_G?( literal 0 HcmV?d00001 diff --git a/doc/html/_me_mega_pi_d_c_motor_8h__incl.map b/doc/html/_me_mega_pi_d_c_motor_8h__incl.map new file mode 100644 index 00000000..13ad7c40 --- /dev/null +++ b/doc/html/_me_mega_pi_d_c_motor_8h__incl.map @@ -0,0 +1,34 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_mega_pi_d_c_motor_8h__incl.md5 b/doc/html/_me_mega_pi_d_c_motor_8h__incl.md5 new file mode 100644 index 00000000..54756b2b --- /dev/null +++ b/doc/html/_me_mega_pi_d_c_motor_8h__incl.md5 @@ -0,0 +1 @@ +5ba62bca2449c01f2cf99e3745dd1338 \ No newline at end of file diff --git a/doc/html/_me_mega_pi_d_c_motor_8h__incl.png b/doc/html/_me_mega_pi_d_c_motor_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..18ecd2931ea8cc57aa73ef6ab677f92e126de316 GIT binary patch literal 25476 zcmZs?1yq!6)HO_}5|Yw_bcb|Fh;(;@fOK~YND3$*4Fb|I^w2Pbv>+0L42?r~H~&38 z@3+?bf9qSibQWv4?kmo9&OUqZJ61zY;VBLU4iXa5Q^mJ(T1ZGJ?MO(-=vWxQPu7*W zDS-bltdtexkRB0#zIB$SAR*BqDayUp@ypp;^bgX3|9L!~@Mgm0Li1%uZ!)@k8Z}$& zP>jMKyQcR67ySi4T2oVeuu*W(yrjR;t#XaoB=rg@bpTL``yXK8NkkJc2y>{_3y`-zzSPz-?y`K_i}M& z`P?qJRsCe*mQ9y(fINlO=N*(>yOzVi`w$Fsxt*R|K0v9b7I`&5i~>wEBWDV>eXUcv z9XMqgw!8h_rov}xM(t#x-La;oTiDq^xWiP1rz3xMqZZ4H7Zp8XL%$r?(moKOFyCl>HGWKd25KozfT}|mU7vo3{ zD==dcCH|gKvon?mUe@&`%e7(uTYP$X;20Xwx=3!lHw5BkD)o}kJa_ZGx53V2waGY39B~2PckV^l0iO!4$Rl!gM;)PaQN2E)zSc8X`8zF`K%sP zB>Z;12HnYeOgaXN4xA5^G2P^(x$|=AHf*&oI?z;Uyn!y=)V2Fw@UY`_+_8BnU^mZ~2LrNenTs0Y5r@+gzT33>iC1D7m$`6*BNI-^54We-WDT!3ObD zAPR^%{{JDPojQFyT#UaB`WIRp?b1KVQ#22|A0>^OUC!GQ#-1VT)>QJ`*E+)l=g!0G z_Zjcl$tTaTl8VF&MjU*xDmN0-oXw!`6BO|gXPn?}>N`1GZLC1*GDk9rIvApde@x32 z>R`Z1Y5qqbS?}z$H0fJVsfXe1$})!WXBzj}@W$XdrW(n+Sqm7OSD|b7Iu;>W;vhU8 z>yf#a$D9)8K;QNzH4Tz)Rcqx^+;QODIgk-vM>3tjTav$H)b#hKbC7D}Bl3lU;R^ez z!udM<=L7f^Lj?mh+>m5L=mu^aQO!AB*sW`sg*7O61wV{%t|=>1dM^@PF-oSHNG5Ey z`hE@bM=4dk>1{hWGmKY;$Y6+R*i%U$%17wjmI)5yeuI5R}qJ>-y zau;R%@sC!!q0{X$5{owtGzY?W&sRUznulb7d{j-GRuGd{_$%(@+^zU~Fl$p*j2XRK z3f4O1-AS}pv+Kipz22g~F(tF`$S{_8{ssu&E6Z$^#nx@gB z1eWvZQ-c&Qx3`?4emO-sOf|IWar#?}6$OtB<5-7tql%%1Vt!@kIAmG1yp^_6u{8iL zF>&X3GVa~mGzs0zT^1?(vM-J5%Op;dhFC&&j()E<-LMI{9FLTPOK$l)E6vKfEc?id zM}))OaY|8aSZY`~$P7TRSb;oF;||bFhKvQUXzfNW*V&V5NiHTDk4p{sMIv5^xNG4Z z1JS*|_o_h&S0w*7@2d*2G&W|O1cnE1Dgs%<*jj@~I78mrcAKcX1lLSP$2-J0UJhit ziFI1GD9e~W`f#71JM(oke=+Ug01-w5rV?TPOd^L_LJ-e*xI0?{>IH@%3V!^_uL~_B zr=bYmU_@kU3zWR^F6CoHGr`s=BjC~mRpJlbs9f%!Tj6h;b@aZAtx$2@cspp>frY%b z9vsZV-oILqi1&4FGQc_jaeUfGUt|t+A-|kHnuKMQ>BZHfT^R|}`Pvpu9H1FDQmoSG zj@wtIVs=*aJu%t0TIAIm*xvCd!Lmc?3m4Lf#o^$lm5Hz3vmIkbBunC|Q6uk7u;2$s zD5_ZbuPq<9{RRGavS0@+PH1OSgqFXQtH6XdI6^8f2WrtH*_z0%-d?iCLk*LVBRO}&z$W&JyYIrfJP5N zhM6Q9YcOUv{0a4arqHU7x~l+M@oL{HcZNGmb1Q-9hf#;UDin|GTf^wCx@dc2 z-SO`bc^pW$HCQ+K)?PFdw>-Zx6sCJTDa^Bw>&7=($0;2<9#!IY*ivJuDAM)UN~0Cf z8=2??4Sruf)1zK%bm!}p(;P>>Kwr{XMK;NzKoz&FY|XT?1hzEg64=r-X>2!7Lrmzh zM@h$_u4*d{i|4DD>@h5P@5Ws|#YjcSX1Gvzpl)k3F9Zj-t0ehft*K`HX~f&Vs6BT5D=R*F4)T&t1#(kmTpg_E8Tm)KYzWQb5EQD zYD_XofBJE=Ua6rZBF(ZdY_eP?8Vnb;`hD!p=&D6v7k?m;i9vicT}GOcaj)CmBA~ct z84KDCCiuyCOociOLD+uAQGvm|Ie&=$KCjv3FOlNdqpGoF(I@D-fqUKf($$J}Jq-ue(3x5{9NeTSAy5+ZGy`WZzFvuX!#<&XQ)jr{ z3~Hz1`fs#xM$N@a(^ixgsw;x4;+kB_UFH!5n)I()JcUrCWfJ(+MoV9oCHvj3G#F>7{tTO9)`@s6FX3vs5T+a30Jc#oG?O~{Q0|oMi(GW8GDnNQv&I;1W2F$rV|!X^Z`k|iu;TSSwd<{r)@MT zw+>%-+}z7CxG)mYmyixFTE{>&U%LH`b9oV^geHq{<}=D8qY~#4*U{+D?DC1|WEd;? zWV^hue|wTO&I>BDo8*JG&PY2s15>Qk#drEZsGDXmjYL5XAVpZ7!7%%gbAEvmH$-f{ zGu`J~Z0>`%$0pyZuY5ERY5qyg4(k9_OMT!J#a-Qy5!+uD;gF3SrMS~N1orQ78ua`3 zTp*eT7X}lGG0A~j>P-;Ul*>srB0gu)(zim4dPxe$Py~^>M+TE|qe5TnZ=(Cwk(=iP zeiTOx5UT1rW2yw^H%uE1X9%C6pH5G6-~4F}Uj_~rCm%7&fU4`{J$3Zq%jgAaQumtCp~3k;ElyJ>A<3YKs$rn9=++2Nd=FrV^op z#u9P#E-vHW-oaBOspx0e`XgSz5MMRqT=mP&dU(%~4T1eC;Xw!X^s0pz3x$N`a&_Hz z75gL-+LU>R2v+|0vGGkH6fTs93b(~B_(EpQi)N+@?F-KJyuUZQJJW`~D1<9v&Rm1= zwJ$$1`4E+hwKDviLEkOFG`A(Ud8Wx>I2$I?O`hnHz1PxVI4bpQTx%7E!i=oWe%JO6 z|DgT_o-G~X!eKbs$|bq2Dy_Y^w29hncCvjv^)A-m6eg`|3~EmYpQ=ad^1|<0(@sRC zRpUd{BlFvOSv~LSf3Nd3a1qZ;R*1(QNm+K^p{!Zg2lq;_SkEi}sU+BVF4$UJBCk#y zefTX0v!ij^G$~yb*sPOi#AbD)7X`c=xr~io=w`X&SeA7u%_>tPO!ud6!EvTX z3)lZ&34D^hCnkipWq?HOxaR@%%qNo1`?$PMK&;J?kMX!?=h+%rV_Jm=vzx4SamSv! zJrh2n1f3ab4dtSAlpUSQV7KOe;B4dJ<?cJ#^4}{=4I*I z3iA0Tn|e#Z1`kS77C?7VYS7zT;n808u!v;4TwlK#z^)(JomV*kdNP&I00^=nk;RT; zhi@z$hy};ez}Z)$SyJTudUQkT4si}x8dv_o%%eGkMO4zDh^etr5$CQWRZoU zMnDZ93`+^h?u}*)tgZZ1F7QX=A1ZavV_B9ZXQ(wv+wDy|sRg28!P*j-H7HxF)-unu9=#AxV6vv#d~XyTFTHx76%v77;oXX|^lw2th~ zoeth2!^<;~h4PUWvn5_|(Vd_P>+-0U{XmcmPoX*SDx2;&hM6ARjxn$vGA>A7df5*2 zP4ee5=hcquJ}Xq;(0Z7AMG8nIDCnlEn1Q9#L8e$R3vy^LJe^v!vT!7}P+kt~l;E`y z5cTL<%5R$mC0EyX=(Lg1mer#4$Zv1IHO%bwmsoI7c@u?tQi{=?v*{^f5M@KZKmi-7 z1On(^I&YI)rxvSsRH=)}j{{-aB6TH&ay6nRRi0R`39M*iK|kKt&lM?2Xu_&62dK>U zSGlMQJ0jdHWu<9GjVwj1-smLxnjDZ?MwXBdAQ5;9wa$KG?aE(; zW()E*+t)i?wh5+~0)2Ic)i<`D;syF+vfyQA*CJw@DuyRymNLS0%p}IY&||KJaj(wk z$>VV8MkH)xg&WBuxFA&BRSO+aeWt6VYYjX>4rBGw(d!;>E-Lvqrh4s$D4!y?PLoL1 z^wR5wXlwSc`+RS{n)_^Ojgwn3%>nlMdhbJsUPY)@faB+J#Tlz?B)4(woXZ`AE`iz!Z+K#ld!#%P?qSG`pEQ9@JJoy zsC+@^WF3Hu$lo|7Kn+G+E=uqACDB>gsx>zoQnP7g;Pu@MR4m;T8)W9b?D>I6Zo1B` z4sRL`wy&_(`826@1nNRrdCjrgVL19s`affK-eQ7eunX^GsY4nMwHI`C_^XJY1AVay za;5#GG;T94Ybs78i*!b7}QVyHH&|Z3jPK!Zmb!^=- zoiJ$BFKLvYsaPb$5LhzQbd@d&UN~mzi!y-;z+qi6EQ2s0&uM>?A-pfg(*K>#FMK>T zQP_L^iZkHtM&+o;v3tq!ajRnxmqH}!Np@jIxK%O*D&NGWMKROM<&uUJ>;JK_iWIC?2}PDFbt zQEFV5#i2He}@N?Ci~S z1ANg~-HU27PNgx|-grbxoA0G8AQdjF3H^9}t*ULLdweI~qZw?rBLNfch!0yM*-NoR? zr<8n4gTPpPOA2*$n~lPZ9|P{08chy;VApk6Li#!ylnFZ|mfhkz-oYiVPJ$Q+3MYd` zAR)zfDc>_=s|KltGas0f&zmB?Rl%=6HjX3d5wj*H_BJPm+8x4CyEum`j}sClTw zzB8$4AXh!RE&kA+QE)0ph^H5zq-o&#v>bfn)9MVXR2^Bz*N8PA1iA6 zOBB_<-V4Lb`Xn(%5aV55s@wNUakk#zo|vUzMV-r&wni&N>7?1~ete(}WqjngUItz6 zgFYS5z|sW+E6NGJuV3#2Grrjxbq=oXB=90rYR9d~l{%bo`v7wO9uTy7Y3i!{;D6F> z3fnyZAH1`QiQ<*8Cucqs!1zl~QV~WppGM|Df1_Ko%f@rji#0X--*4+$U3ey3 z!TISj3wXoGJTsb$PSeT5gY$mo>rLpo^{oI)Q7(%Fk2GNAMk@+PgnE;R0<6;aU;fje zWHtTGXMrK7+9kHeJS7 zesKnWTOMU)-KH;PCiqHkgd^NjLk&Iesr)&+8B{k0NV6#)qH4zKH-#>}@NBkrw;%q} z!Sdr5_Hb1XxwBv0W)&I4gpD7BYK-r!+wb${sy!{qW z$0K|Aky~y%C`7wyN}IOxeA$%x2gvc;zH>$0!;)l1KpS{}rp4MCqcEh<35{t+&MON` z=*N=H!dY>^%qa z2Vz$`e%&Fj*&WeGbbAATs~^UmSgLeonzBx6t&*?ky8DaI6*hE$SZV*~E)Q!q-@x-N zr9xIh30?4-wy3p>+ESq2a3TadsEvfUO%hvYs2!j_@)Trx3cR6n`UKyo`y)9)+Z{am0$0QKFM0~P*^syn4=`l6fqC_?Q7PI@(;Xw8)5#y!%$&OWx#^R z?m$oB@MK5^n4>phj!c6y95buW)|GeM>RS>*9K{A%_vmWT(>JGAu~V0C^cK4?T?V;3 zK|uc`0(1pHs*>1eh&IPwpmv(%c3SGyRZU^s@OEw;=>@S;PzpL(^nHA4mah4$aIy@_ z__tF-N2-*|nqZ)e?@i=n%M;o6L~z4MsaB=V_4NscycIaWyou3@d2Wmi$M87n{eHzE zc98h>Aj~O%y&)=IdYIt-a#pLPl5bd|b8>k6q}L_t`h=!}@jOhBY0;(Xi{MJVgku#(9MJC4im)26m&9y@{?CM$cSTR+*RBDCrw}(vu0X!t`#zkv zVlVO6i(X}%N{x_1NWRouZ-Z)zO`!UI#ZC(3x^03t&|@WC{g>r!9wa#q^}O$s`YpY_ zdH(S7u*CkY_IIl*cLDS3VEg5-7Yr&!qWuc+CaI~Pt~KsPHRj3V;KeW0%4ezUJMvWd zPX3$fRiPWa{`SMT{owZDOJ(uyfxiiE(i@oB=jc>4F+Z+6opmNEE=SEfKa zMo*Xg-VRRVnb%bFVWe>ipLpqFmUJXMLR3-3wQZq#FLzxgwGZW*3by7QmoI-KjD3aV zhgD#I%2e2i4)4JNZ{ZV!BoN@-7V~P~Ps@47v7E|XX-1fbWQ~KlgWvi(a~B(#mN4dZ zpR+B*D{EU9i|37ZB`7v$6^ojf9AM&UWh{^bu{B;pS+5E7D~*imi)PAMNS%4i#f^? zYF6iy7R9Dd`ZjekvewdFtGd*{GNT|u;hufShF_{fN}G4M)F|ylcyw32R)Td8&^KUL zW-074oB;xOKOx;Qnll=V&-1=8`XUxc+*z)Y2^V zg^%9PY?j9%IqFs_H?f(v)C0=a58K1q`8K%~XhqZUJdC789%^agU-qBb%6We; zGC`Y0!bIhct^dVoW412r&j~vxPjL!}KRCqVL=lTg8u@s9@&)?JzX!;lC1ukbzYEkv ziii^#LK-iG*A$$BUnb7AWnne*>P1Z?3-K9Ect}W#X3UvFs14sJFB)tQy?eap^(;^H zFnvH0=c~`zF)6DKD7ax`GeFX*=-d88^e#=mX)Ixj(BuMW^iYO z8b8#bOog2y<@b7MZd_md4L1>%ag9^9D*5P-V^^etuRpQ~+$UAUv7^8EQH7P;bAg)L zWQGP)yCw%VT5va~b{P3_7iQF0*Jk$75sy=SkJ3WQW_-IDY6C@Zud; zqgcKTXH$jT4Irt%^Q0B{!Rb!=7YebV4=U>6ZuT?P1|ukvzq!Pxb3SU9=aM7w`B-2Y z>TPA5mK37%&f?x+miT6;l2^2|_4!}}DPyA%YehJCt82n|R})~I%S!r+u+wOTLKoyzm6{KnkMbb~~$@`B&O{ub)ZPQ{lI8sosMADynmD?Uc^{Xj7<4 zRX{Q?cXMbf(Hi}3Kk9w?8;=Hgek(U1gbsLH0ou*G0+F$+HrFL6d%}b*3HhBvV$3rI8I}lx7$3Y-N-F) zd`juZotr4dIHPiz&HlLY^{sDXSh)&F@3U|`iCrAeJpCoR)XviYB(E~7%dN8v>JuLF z7SW5+gw(~>NIdhsZfC1RpDjz8VRWt z;vVkM%eImSB^B%o^4^;hzJXlCbf61DX zEu$%6o_1X^_Q#hoePb%K^x+@xUj{(23Q7^-H$e~c{o>%Fu-q`bl^QI^AD@yMysfJ; z5OSx9Pcx3liqAjdi$oj=(2LcwwHdhsOsAw(%_}gkO=!?(2S!9Z4-Ecnc&i4dk+VxE zS{PYnbqIyGTj8y?68$9s6oV)R@=5-%K$3&y<{bOhpt?P2M7H^^dXj)uLB-{U)=U14 zY7VbMDadKfL02!`tF|PhFzB!SWanF)7BXZ^WY@CVvSbvO(w(TCO7a0y79u&}&K~Z{ zPLO>qkjNTwLeXd_4afCQk3Wgq2OSDn&^}uaRE}ytv7~Am4vy6&q}4EJwBgr2U0wV0 zZ|TpI5%nx}k|i2d;b<6lQ1aCb6f^r;xvL|L34MVTkbI!JezgRs2ZL*spI;%7VWCl= zoMb>5i2x=>qy6YC*>NGh;NP}|lKeea9ATT)Wk0)xdlP&_`xtsp3cFqRRWZ2X5MN;@$0m!aLXr z;x+z2*ok+=or>F+_WQ55M5fkMp|7GQ_{cPSMT42ui$K zJ`!iObOEW%*m;<%#^8;|IY8jr0cP zsj-`WAk4)XLkHnu{tZYP9d65t2{B&5_y!Dsc*OVZYSI4YPqDGbogpg>E3YFeaWpK6H{lp++nABzf+scHlPg z_HRmpfhIl!Uf3-&{iW~g!(gBO7upCgP0|O>6Qe~blJ#jw>)>uc{R^PN$z^=!ngTAw zG9W?b^VnUW`48;gs2nJAa0aDF*S?_h>;TyzB!Lu6E(8EPb(i~nH9y&(UVM&htdXZ} zz}_2QQRNd|%a+gdi?$57f|R1EL`2BGd`HipA*Vk(uqWr{_BXW#DVjKU8WaE|#_~}c zP0ftl85znl+W1qudI)eAA*;Mh3 zrwch=D@ZaSX={!X7Rau?uy_EZTc>VTv!=>M0q|#e2w4ufc~f=fc%oncVh~-8VdB%1cWrmd9X>FwNJXgf$ZDL zbo?en%B=&n^e5hsQH|rtJi;fmU#!DCaG8fzrN3&X>yl5D{0h+J>T3XQft=k&WMoNe zMDdz0Hy0>Pzqi&cv3QJD+&*E#4(w#Zni7xJoTRu(r+6as3?QoA^R^N^8%JfmyZgOp z*&b|7J5g;tK`5Aq#+f)Yd$c>D2bJBCv^F z9qDntBXjCx6_Nlv4THsB6GIn|Y^{$l?1i-05zg_-R0ubXyN4r86q{d&-E>$u7=V$%E5i2_A+n2li zT_I0+L%z=v%}#~8m)D}K$uW|QP20^ounCdCC4aNYfirSy76PE1n-sZh>e~lPk>*+GxXNcfi+BIM!2j33W_KHqoV1VHjAiuKR(WB?even{Cq9SV~TR{2Qtp0{z9Os+4Ha?_5{Diam<&WJ|G8mRjVgoT)ZHl z;H$3A5faaUx5!VuPm~?~bNve8O?4jQDrQxT?q@)0p z)+AdaN>UQXW~H}vF#~{X_41S@D;%W_Jt|0eck^8d3%>yJ|){AwiVO+1(}FlSM(2 zdNFR=5$0Whl06LUTZcx2PV_oc$>rKQFF3d1MNn8h*i#UV@?)}y1iA?=M-~21K#e1Z zS5J%?eh?-Ly7YUpbUczE96JGwcde!9q_zDso60evLoAH;l;0Kz@P>5FX48|Ntrv2m z*dj%<-2KozsN=oA2FwugVPXX1xVLa*AbtQx*591J_Fd1`9S4!}6&LQd<)1qh7nwzU z-CaV>l`L0=NRZ7T+n~#6a|}p$P9#6wuAcq=Pc3h)QXs#HrA*Bbb@H_eDn_UyI%Ylp z)RH8uRL8p~zX#DCO!dYk7ft(ZZ)_17xg{GjefW1wQ3$jo%8p93eN_tpLcD8ke6Ilj1C^fpl#0Z!gU{{HeHiUl5 zCLn^xeN?)3o{eYcF$GdOW-1E@kyg3*YqWY#ezpF@OsUEOX znQ3P6?v$y=oq%dC&eHxK-S`Y8QcU;S!Mb?i(1w%L=jXQ|hoEW?;p5@Gg6wNYyIX%= zDD>C3FW@R+bpLD3l1ugr32R?6TB13f4&Y&8-Izw6OZ(eFI7trbZEQTXc?#J{-YCa0 z#G` z+;Q}GO6!>VqCaBr`LP9cMySoEjjKKoR%0@?_VNP6?0BUp#~x`6KveiIr-^5lKgSXs zgtk%S6TWa?ojZo)#kL1oJzq4y3W((dTGg(z%Tx2@VLh*SOx6^c&vZf;8AJw%E*AdmI*;Ig3bBeroQeT z6!RYR!q3z@hkUh6sFrl$w=N?1d+o85LyR@WvC;7{MkbW915}s15u*vjFdf?5J+CCrk>|~Fo;<_U~W+KW+ z7$?gFYZb|=yslomtbvU}qKC4T=y%K*^%?E?^;{y^=X>&!p$MmyaL2`QGE(+0(45H()Cg*3mERMm@ZJbk)?lcdbSMz5l7k_=$JHA?z2ho!lruud|nji^NgjTIz2WZhz9G&%S9H&`W@*)3c^5=G$QEykF zff(<9VEO7JS68c-MDp$#+Clvkldt)xz-bU ziz7_YjRCjD@$~U%owns2uCmbSjyU005V7|uz7sLN4`JII&k^ygfBQHPoOPx-b80t{ z*U5AIX<9CmZKQ^PZELia2#)9OH%2nsQrwX&-sQ6~mZ?hbGbz`lT}ph+`1B_yt8DJ$ z9>p4a#CO;XE3&!a@BQMVCC6Hc&dRJ=DAaDR?-cR&0vXgBe^}?XRZ00H9d)aa+>(1v zx+|dd%koe9yy(P)?_7+^=ldNh^9LS|CU$jT{^#bU!SDeHmo31{`Z?;iR&;45znyJS zXv({by+5>%QUJ9s*D7z>i1WKIPH|Xg5=3(>;kYzn9&YHgTPoHfo_us5?9T z)y}gTW0w2I&SNMpBTnA#tbGR=yw>%T-HLpH7fxQ65kA;&yb{^Si11tH2fyLgno=jC zYkgca_4)GyT&>uy5^aijTLadWjXGOnK5;rBm46)KWK5Ri6ln@9vg!d?r2g>o2g3VL zz3PCoR^pt<#u`Hz^(`-L>2U(A?$t*gg|y5H6K1z=oKWO1gM{8lFab$bpL#x$uH;UK zfA8?z*kzBZhl34RAG1F_IPKI?t;5b{zy1mFC-!UHbuO@_UKOQ63tA$?>xC0U_7Pq% zNT$WbjJg|g&m(mBk|a`{;SG!U*%x=VH_z_vOY}{eYO@t60Bp9x`R rnmP_)h!Cc z3>kj!3~o~u!guuj?LU)%*nn_-2$c&P%VwmPq#=F`$2KX}l)yKbN*4_n zodK~NCCJf1rzZC>9iM+D{nMZSUPdz9Y+Io3#e?%OrraYaTf}4xg#eVS3xBQ4HS|u( z5Wk)N_wFO+yi0{(!0olg?Ll?E)#qX7?7K&h`Monc8FnwSUh@9bOLCk3L&e3MZAF&KM17~TShEeZ<{`54L6V6G<2KOC=GOHQ4(oEn z7>~dFb^!K!xi*(g*SZo@9cl zYw{GBlUQbu&8^Gv5ZpPp0vv=b^Mft@vfK->bc3-Q=~TvaXzj7v%kk2Dg;c&Zt0xBg ztF%2zx9_sgY)5o~^;x*-uWOy#yXd})GG+uBR|Evyb~R7QM*MNTISKTF>Z_MF+>Bl< z9>9(~miOl$r7tFQaBKoM`@rLv64WFI@iKq%>7*{oRU$2Gzy)kcNX$TEV9qo@vGsXz z{OM%=Q@-TE@5U#zzR)Sm&V4jgk&&FFjyZ7dguQxbLOEF9V;Qx&s5!Wx=JuyWNYcU0 z&cyo7&F!Bqv8zF^;Ghz)zd7yl)IF|uVBk4TYDab84bl`W_(YL+Pd&N4hIV@eE=cT0 zRaQ2aS;RjXV)n%PZOB@C*NX4G3n+M~>52nx0opS4<4x5lsy@2=bPD_6my`9nC2Z!1ybRB4C(vPrXVcHe$H%2c0 z<$YQHPVld_bxFN;+1C#CzaP@$%>3SK9xj0pWL14(_LKv^ zrkMM6mM`ItsM`%v=V!%-;dd^bGwJFc_AtB+9k|>w^zT@nN$}i%$7BjUMTt!NgK% z*%!6hWC}jIr;a#Jr+mTAs$KQL&33=B)qCo8UKN$txmAyCFOUU6r)6xHa z!>zbO+Iglz_fJ*dyJ1Y)APd;+_Zi2U&aY`9OCh(;Fkepy%(Xi=4anBnUiFtmchGJ)VvtigKXq`@^2a8TX^m8g+RqF){IL@La%1j z&zENBZC_OWD6W&07waBy7JQcfkMtwc5Omd6GY4LVnVNJ_l^etsK)OX{C)sF&FG%=S z1tlk5s4hnq-jL|hAkko9zB3Yq;k`L$W=U^MciZZ4KQR-93APppRzwe^!sLZBT=D!E4QF&fD_55W>5Z$6U$CpHFEg7NRh&9p3hH>+g%3T2VY5 z3k5a+Q>~=X{t4Mo(gPi{%p;C%0_Uz5I`9$UAu1BB1L>Yxg{%jW#%=wn;2^a0ugaPC zYVPJ7n2>+ZzP|!|b`~#TD=3>CNY#Z9n5fl$%Wil0x{D0_WEL<0*L?ETF%0v_VCg2Z zR1v1jpV0dyuREIyISjK$Nx`J_LhfG`Tp7w@DSg@|nQ{qmx9+LMEZv~WsShJ=#;K;r z{V(=0G2(BA{x5xYm(%$_rceY=MOT>G0Dmk=BytnzF@FC^56>dak`ytTe|GyzzY(?No&4>$;hs0z6x z3e}?&pyia;oaU7asZtX0;{aZTY0RXe$Ru5FC5d6Q97M@Z{e0UlmZl1itlW*aR;t!0 zGQgM8_Z9G>8{ecIFZP==r4^$UyVWq0w5W%#@wMpv&OK&?_c#gLjnL9 z$Nj_H42K9kAPE33Zf9WSVDH79WQmGL*87dx(wv{kDq=)%NwZXJR@O@cJ;vS1r5D)w z1ZYq#Ek4xb%I+{L%@4K&yx=`MvV_{yi0GcUh{C|N+3#$1)IHLQQMzgCK0MD9rN=sU zH+9W}=%bY&o1;@j{-~H1y78YIusu(yn3lV4g*20NO#)&}!{k0-+e)5*i$p!TJQ=EK zm@HMSQ7&xLZ`Z=lDIVGTg4dIX?6eHAHV_S|#mfnpbg$-yiHM@$@8gh1Y3)4K|xxaJ6Ire-A0T-+; zDZ2pR<)i$w)!>tf=V>~wpKgx@SSe6QuS{&A0P?HXl$ESRG_J5RvJCp(Mud0c=K~R0 zWpHI@Zr_G#YUsNLSAOAwGBqtY>B@59*n7ZRA7H9or$m$Y%?%7GfCOTNYQSGK=U{ps z&@XeKEvgm7JZP+nb@{xRi{?co_}85!Kf^nDx22ZF7?MA{8b+0O0Os8DVIZIJ)W{+L z0X$dqpFOcg75pi3GSsPX2~7lzZDX^5c-z%i&~X^EDc*a~fb|lkRCGk&PG3m?_DY9) znwst72}*B1Ab8Wk?z0~%O-uSjMXxfknjk^W>$`#pEVm_`&_!j~wUU)zuOX!N?U+5W=Re_>-t`#Sr29&Vv>bX;Bxg2M5Ve?m&ESCVcAk+!6s|DU6BC|Yn zlV+P*1V=3r|Bv!@u}1tFu=GEzwx}9JU$5A`OX`-i`@%$=U9|gp9Ky{}dM6R^iHn-k)C6yZ_?_Fh%uyt)btOZ;_ojt7qxVPKTYD2~I|T zJ)$c2867?RtF8gzJpI|1G5IY z;hYd|bY;^_+1Vfa^Nz+bf(b=qcDB1uj45?EaKGT(z8UEsn+@2-V#Bk8X6f0tUH6Bx zC2aW3&3{O==h)WHJ9>fCAJNJOf)Slxc-0c(z5YzJNHf{^^+jT=!d{D2<7R4CNh&G% z-O#0o&+(H$zAe8u3|YS;_-2`UFIt0KVT|n&F~w)kd!E_`mArBi!XOz0=22Ohh0$M% zc8EHQ+?;W|UUyR~19fzdIKh6Oa>GAXp$~*s*LK?l_6Xd$g*e*+;x=pbXA9K2X z4yNDoL!$WVXtF5R3o)rLVsu6E#rn!b4`y09!YQ#&Q{&0UTWQrG<0l&j>wicrZ+@?& zkEHMae5v7m$vy9u-$2`d+RR7rZ7TG<)AAFWu znsm676spjknTC}#Ze$o(Nk)UmYsG6K4pJ-MYuP8vUtzh`u7p1Q z9V6(>pc}V5Nyz$Hj?4p<+Ped(f1U7FNyA;ZxOjmq3y8U=J*`n0vB)O%VqSkDOxcgH zBi@$JD*yN`x-2g$-J3Gk!)qg-&h?^;-@@0(-ag2W4G<|54C*s)lb`U`yxjH!rI z^edSuYmc;dbot!T#saOZIwh{h{&t2ELE0Nu zmENgshH=L(-)w#xf!L!Tv?`2@{&osST`C0$>*u-EKQ|`0#GP+%`~Uj-?x-fda9cV* z2p~leP(VaLia?}AsuV#$KtUkVdnfc>q)3ydbO{|P5kZ3Vj$lHsQbTBwqSS!Y2;Sj$ z*S+_>yWVLbUjTRSVr^5hTYzG`2Sht+I8wah24 z?+a!4_nx@|1uyM~Na#q+-#)qd34!2!$hZDSWL&ioXsO8%q*l@zP05j?j zn1FVF00gdW*+mDvTa&FnnHPxd!w`h#)bgSBUuLbXfTi-e#KQF48DeoQ8B~`vMortD`*WKv>K#yfLb}ogKkv&8==^I~NRoMp-aoiGLmEB)u zY`k~>?mv>Br+c5qw1&&Cc^Ws%uV7~p^J6Ub@Nr?_=`w9=yL-J!31t}fsKhF(X4I7S zGC%9ao%PHC8rGhvi97BW8Vj-eI0gksS!(nhCrzjP?rRag3PUEhkV|A7`VTh+bh{iH zYD*gTNToo#$B9z9b@vlzEuxae>FwSEfyQ?vhT_68z?po6b$;G!jOHtL!cw(8@B8^1 z2z%;bw|Qy(VfjaWA0h3gFt*>!TVve^*`&fmbo@r^^uO+yZzI~*%jyXbBqL-hF{LiX z%@>RrZCqfgO|cI7czxZe`Z`kboZt5geKs#Hw$-6&HHNK0atbN zmtdm0_f}$E6RL+8&H5DL{=}eV61jN4`q_=)A*CgzEIDyyzU-@<%W(m{`2sIwMdpU1 z*6BF%@l7`Ztl(g`m$Qri$drxeOcu4Ur+Bw*JG(iMyvjgM?3LBilmF1J^m)s#$H>%1 zv!ZGI)=DS#m$Urk%_eb93fMcy@OjV+Ek92aCLAK@X zPLr*)ZcggCgZM6SnDnB9A1{{9)T2B(9Zmi~gp7|gg=8??4jjzP%YRpe<1v$5zG2eVZj^HV;U$g2e(mNf0I*DKXG22=CC% ze(1PV_pVMWlHxfkUc|Mt^)xpgWU{rBS%~x0RPPs+cz3ZYUjVP)TmsFdYxx~Ib_;TB z5Ef_`#1Szu%1g(h4Vf%~TRN*WQGs3R#Meq_p$$$v96}>shCCXZZzE0!YLxq~M$F<_ zVY8R{drex8B}ygjxA%5>@UVvPqW4$*jgt{)vHYZJnw|psW1Q4!!R8oHt*>4qef-+27I#*jevPrs3qT`(P=4;6w`kBPH1+e(k-q~=(ooR_CH zT%3fbOejmH+Kic6#dGt7yidjU@9c{g`d0W#kAE2HZPNA_-GW0t=Nbjve1kHOx%1;N zxVw|@&hZ5>oWA1*GUNrkU8+ns>ZdVPO6cq9F>BP?*cpR|7kI~aXFSlU zhz9Ouu|ciqyDdbAvOX;vc#HhguHv9z$Ywz9#Pb1=cJD-s;i?Tjj>B-X!L-(dNLwIu zw$N-WCvMguD!F_tXELaK?~sb^FhV66wNHMlvi3G#TTriqI5g3pU`tyhgJOqu1r6Vio%vg1y_$jvjj84$ci zp=XOf%*c6xSQC&>4iGkXPf|j!rf2GzUDYY^F40v6f?g5Es~;AjIw?bmBsukyv$mj; z$+zA#Ten1^iO6;sK}=S=zur4YWllJd%?zHda9`UO&5$|A7R0R0SHVbhE#+>d%<@Mj zmw#8)KM!B#r=WcA8Te3y?*V)00Fwe)cmRFLecL}1Rn%FO%-Nd&Q#5d|5nMFaq)K9H z%a7*kT%vyX zQP;37VPS2p;g7q*(NiiO8?`&G{lJisH#f6%5}CSr=%O5r|0Qh(j!AhRj~cu_+G$0M zkSCLwcWB+|{{Pt~Hs{+Asu&1a))GHcv3KH1kL==s4<8F^Ilh-<`kri+xD3q^nRAke%+A){d#}uKbq#mK|LbtL2yQK>*?Y z-t*z=pMdr%fJR%N`IH~ewnST4hIB1|nvT1muJw+}!Gq%yB5>j5+JDMJSkMmhpl&s@ zTjS}~MAZim+R9T|##!Gi445bI>PX>-lRkSNJt?aeGN2u-$Gn!&=>`bDsU_pS^zCTJ zNh!VfFFQx!J-2S6o)lvM;UO9!k7JOP--PB)=u?BVRnuC?Q~L2W+5(1fk-7WDj(STy zr-_N)DCMg4Hp%&N85LRU+KuO(jx84rohNH*?dv4ZE#0G9L!pLK-v;#HH^d6Od_Sh# zF@G~-0$}%z^1s9;OP*7MkDr&C+iYmJJ*l0<%us#u<3djPDy@053gV$bdo_qNaxRWMX~f=MEV_`J>H@T25+*WKY_25N9mF5 za?y0nx7)I!L3}DUFmiNEc#k)U)R;08@`L>;3Kly0m(0z~BbIFzs68R0+J8$cr znjcX5*4DZPM4St>`WaRgru1}lYIxgcjbm#}gK`hWvv&Sgb2p++qDF~x<=xP`9QZ%2 z-H8>wU|aRROk-v(K{w+(M?EdEkxz(~3NG#XR}$3|4Cd0(@6l|LPVsS7R5GaXe=9nZ zbrf6DT2RppKpe4Cxrty*RElOBZ2%iI+OZNKj$;cGI+v1*2-3`_z{rXq-keg5pgjJ>!^Mb;MxHqgVd&hO}BqzK;v3% z$c4rqihz4S*$$}#zYv+DebnQXR9Oi;n}5+U`m?>9*h#Z;aoI3r9lf=qNJ``V2q^rK zSytvQ?Pl{Q^$Q2D{B!WHH$43m)Oc;2IQDwvm^-sJ~E1S}!$|bVe|CBeJezBVm-7M7f!Z5ci^O(Vl{JK0IgQJYrdvbT}51 zZrC1gSa@^%`sc>hH@8;f>gxJ}J*oG;0epAxu;bdSa1%y+KBOd6xO&sj*;?a%8eXH9 zPqg>v6`MwT6=P-*@+v0H^i9gB2)>X-nM|VFW85x?k3SF>xn^+q^sXez?%*sZg3O@Z zd{M^fKJIW_z1Yd^(bMg-RvKFdx0Hu25E%U-?%Tv0hJS5B#b%Ga5 z$BI&vXUy*`LX9Wy8m?UmMmf6lvY=DXKP0~HzE3$rf8U2n?UM@SpbZ^8>7r8gQ1^+3 zaK63oSb=gCVtUpJb zYxZq$fE;GOlsE}B_VwTVo#r42m;L8d7S-6${Z)Ah@7)jUx-u)o!yHh=agE1uBsd!y z3avq!5~c1u9Zi$u-dv@Aa-MH&!i>}8o`4pqEZJ}W9ZYV^7oSh~c17dTt3aHIVp8v{ zoQw8GT5P2)$J0ArHVSI831p}q5NGb_WNdkn}?3O0)#uN_0_ zh?n*fpb;|jROHvg_{M3>UQBJ0qoy>G`%~k=PUZu{r9bJ58*G&f!Qj~wv0x!D9mIEc zi;1F~VN}n9#eS1`ROZu|Yp<1uh()rR>OaC0u51|+8ejfq=GXsA2$U?v=H;eNIGeka`W#;`Y9tZ%b=lrYe~J;?Un(bz)OG=Z4(ZYv{3 zE~V1A=Q!zkeTE6d`fZ~vjT9VW^SoVNE~g>JdQ9k1dHCIgQs13N@gm_$jlCNQH=%!X zxSrQ1x(8avKF62>QzXvD>Bx<3+E(Q-w>~#AS24g@sKIQf5%F^mI8(}gKanUMy;AxV z=NDQsFQT$3L!2(+7cPJ5>^!f4-ca9`&Rl^mpHPsdDBQ%_=RzwWFb(j>)d-kV~#J)`XrW3_HrED2AE>$SO>kSWQ!`?saeF}-w zdv_El3>4ae>)fdL)+k)g^}nm$Sm=Y@27Hk!_}3)9mpsIaKzm4*9F`fP zU{N#odo)Vx*r8epZNB_o55#5?A3pjAkStP8xB3_D=*B;=|G;}Q#cZN*x<2|Aeau)u zHV4xRr$OKmq6%C|>cabJ{t~6{AKkp*lKw#m@y62-G!^Ds0E?*AlC9XUNk~buYTRmi z*fr{9lTxswA(66w^VJV+DA^AH|81`+!afsyF&b)mWg-449mXDCip|dub2*=&=qc17f_7%G}(9Xr6Ih#DWGM-Cm=}{3P z3by_XFogaZhUoypiRV9G=TdVVl}To`V@mt!t01{)2ml-?XwMQHW|sgZXS4({RnQ7g zwA>I9KBypgzufdA;Fymxf=X?K^>t+=oCsy;Hq}nz_5!nJ_Lv zKgFs(qy3|@$E^g6=-+DG50~q({u-3(JeW*26yqAG4503tp0OEr*a8ew0+#V$dXW5P z2D1`h6Dq=hl+37^jr+o**i-teGlZK*rK=zur6GBXJ!SS9${8T|VC>}`oXTmNPPKx5 zc%aCfZ!P2GjwtRyu3$hwtP;x#VJ<^U-G)$@#fDXIljIgURj#V z)I8;lsXlCIvdGB_mxCnvBXa5<4Jc>|O| z(A`(x*0ywP?Y!Zr8-n?~;yWj1Q@8jFEGD;>d2k<;>mO!AjUE2!7`mY@GQ+; z+L-!fWqr*^fnVF^?ufhy;d-&>gz;iV-0XyxnSDF`Dnqau_t&oJ{J^&1q-~k@1<0T|2D?GS z*2w*5;k%7lz%BU!ZLV~}UzmmK@uw!qmeA%LEaP?UEi7M0wd;kIbaN29_=qbl2K(*J z)yQzCC>|$nQZ>BvQ<$Y>SmNlHYbd=pU6l3%TsOYC{Rgc}KqW>P(hbJ0tG~crP|v`d z?n!G8f$%|a(~9GB@lF*&Ad1VYe!e|zOe9h8_1#NLwOGsHEqIeZMAE$Zu>p*1B#ZXJ z9#1&bepQ`Pu~!9lRF34&oVY=@M4@c&qxFLLnso?|LY`lv>EW`qleUV_J(HZH0(_9H z;%0X4#Kgp%y>Cos9een>1#Eo-fDiWm1~2q+(gWL?@erMBL1M0jCX+hht5(4zkaFOr zM-9zVS2o>pf>3xdZ>z!n@WN!9!kC>k8>eF5HzV+$?H|A8!oLGHC%HS1>CKPM>1?XUB8~ijR5`t?uk_A zm2*`SxjprF8S!Q|2A?$@WFni|kb5vai!gRuv1k;v<+%i8y=pu5hKHkFiKJ^~iNb#lqw)pW)z>G^?YEa;w1+IZp)J(sRGN{$r)u z!GV07$Z-X+mGmO0@eQp%^p4UvL22KGzO}Nqxi?dw{X^KD^!%%vK#o}ZZP`@25ctGL zX?)t#7;$x3S>28+Lz3mbu}{s1G|(I>A-LnOyvawt?ZafF-Cbc@St8v%i&ut6)3l=P zp}44&*ZYTInAxGQcFXR_8;9-Kl`Cg;p1vHn!5M6M1Y(L}-9idI^b6NqIU8qow@&1oe&w4? zE1v0oRy@l6o|k3Pd&1GQeEG{6#wUBSQ-gTZ!^G8~xWSW&{K$$%ggmIMwwsGw1N?sY6@A;E*z%LTBro81r zgysx(9kWW$$TAO#M{~W(osKh;Pd}0N`zTeHf&XZ&`%0)aR(YGRLgi2U7&4jJ1`jbv z#El4)=YHi3zV4dg=|FU{7`!(<44042LLmbe3s;eX;Kpo zlB^#B%Lk6$0=9DNX4{#6_s|F^PztV&p*;mNwfs2#-OGKmcJ&AU^;K!hG=AO1pSlR4 zSXQmar6GnH2YViolasM(^I4``+ZMbbA{qPc_Z~-IRx?|7GJh1kQiZ@z*3UKymVWB) z>5JTqw)*AGnfbe8P0wq=rW5b`PSRo{cb(CTDy z3BYtxlBfK92_w+{{t}^inSm+qult0z0t^bQ+- zbXQiM!|NW0TZL?x(cTu}+(RZ^mOg3diDF~^CGo|pvqPj}48|fCX;pZk04=x$W0anU z4m@uTsV;da+T^YIll{}*wP3iCTe-A!t%Vd{##va!7(z<;?vh+bp9@Qeh{O^H?O$xq7$@v>GNQ^$0?3ho>|qH<_DKYrhRZaYdaORaZ_J~fRM zAJ|GJ&#{g2wDa*}s-px?j?cP6heUdo3&uZ+=A-RB-S{WfM6d&^jbGF(vLR1gQrki{ZHa|M5RqKBkNge*djrj%V5*>V)gI39I0dynildnW-1|Nm`d cxW7bqand=O)!w1NYc+^89_y%9D_chX2Q^dXlmGw# literal 0 HcmV?d00001 diff --git a/doc/html/_me_mega_pi_d_c_motor_8h_source.html b/doc/html/_me_mega_pi_d_c_motor_8h_source.html new file mode 100644 index 00000000..8457045f --- /dev/null +++ b/doc/html/_me_mega_pi_d_c_motor_8h_source.html @@ -0,0 +1,165 @@ + + + + + + + +MakeBlock Drive Updated: src/MeMegaPiDCMotor.h Source File + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeMegaPiDCMotor.h
    +
    +
    +Go to the documentation of this file.
    1
    +
    41#ifndef MeMegaPiDCMotor_H
    +
    42#define MeMegaPiDCMotor_H
    +
    43
    +
    44#include <stdint.h>
    +
    45#include <stdbool.h>
    +
    46#include <Arduino.h>
    +
    47#include "MeConfig.h"
    +
    48
    +
    +
    49typedef struct
    +
    50{
    +
    51 uint8_t dc_dir_h1;
    +
    52 uint8_t dc_dir_h2;
    +
    53 uint8_t pwm_pin; //PWM
    + +
    +
    55
    +
    56extern megapi_dc_type megapi_dc_Port[14]; // megapi_dc_Port[0] is nonsense
    +
    57
    +
    + +
    64{
    +
    65public:
    +
    72 MeMegaPiDCMotor(void);
    +
    73
    +
    79 MeMegaPiDCMotor(uint8_t port);
    +
    80
    +
    91 MeMegaPiDCMotor(uint8_t dc_dir_h1,uint8_t dc_dir_h2,uint8_t pwm_pin);
    +
    92
    +
    107 void reset(uint8_t port);
    +
    108
    +
    127 void setpin(uint8_t dc_dir_h1,uint8_t dc_dir_h2,uint8_t pwm_pin);
    +
    128
    +
    143 void run(int16_t speed);
    +
    144
    +
    157 void stop(void);
    +
    158private:
    +
    159 volatile uint8_t _dc_dir_h1;
    +
    160 volatile uint8_t _dc_dir_h2;
    +
    161 volatile uint8_t _dc_pwm_pin;
    +
    162 volatile int16_t last_speed;
    +
    163};
    +
    +
    164#endif //MeMegaPiDCMotor_H
    +
    165
    +
    Configuration file of library.
    +
    Driver for Me Megapi DC motor device.
    Definition MeMegaPiDCMotor.h:64
    +
    void reset(uint8_t port)
    Definition MeMegaPiDCMotor.cpp:207
    +
    void stop(void)
    Definition MeMegaPiDCMotor.cpp:309
    +
    MeMegaPiDCMotor(void)
    Definition MeMegaPiDCMotor.cpp:51
    +
    void setpin(uint8_t dc_dir_h1, uint8_t dc_dir_h2, uint8_t pwm_pin)
    Definition MeMegaPiDCMotor.cpp:236
    +
    void run(int16_t speed)
    Definition MeMegaPiDCMotor.cpp:261
    +
    Definition MeMegaPiDCMotor.h:50
    +
    +
    + + + + diff --git a/doc/html/_me_mega_pi_d_c_motor_test_8ino-example.html b/doc/html/_me_mega_pi_d_c_motor_test_8ino-example.html new file mode 100644 index 00000000..79711146 --- /dev/null +++ b/doc/html/_me_mega_pi_d_c_motor_test_8ino-example.html @@ -0,0 +1,105 @@ + + + + + + + +MakeBlock Drive Updated: MeMegaPiDCMotorTest.ino + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeMegaPiDCMotorTest.ino
    +
    +
    +
    +
    + + + + diff --git a/doc/html/_me_mega_pi_pro4_dc_motor_8cpp.html b/doc/html/_me_mega_pi_pro4_dc_motor_8cpp.html new file mode 100644 index 00000000..9f361f52 --- /dev/null +++ b/doc/html/_me_mega_pi_pro4_dc_motor_8cpp.html @@ -0,0 +1,190 @@ + + + + + + + +MakeBlock Drive Updated: src/MeMegaPiPro4DcMotor.cpp File Reference + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeMegaPiPro4DcMotor.cpp File Reference
    +
    +
    + +

    Driver for Me DC motor device. +More...

    +
    +Include dependency graph for MeMegaPiPro4DcMotor.cpp:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +

    Detailed Description

    +

    Driver for Me DC motor device.

    +
    Author
    MakeBlock
    +
    Version
    V1.0.0
    +
    Date
    2017/03/14
    +
    Copyright
    This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    This file is a drive for Me DC motor device.
    +
    Method List:
    +
      +
    1. void MeMegaPiPro4DcMotor::setpin(uint8_t dir_pin,uint8_t pwm_pin)
    2. +
    3. void MeMegaPiPro4DcMotor::run(int16_t speed)
    4. +
    5. void MeMegaPiPro4DcMotor::stop(void)
    6. +
    7. void MeMegaPiPro4DcMotor::reset(uint8_t port)
    8. +
    9. void MeMegaPiPro4DcMotor::reset(uint8_t port, uint8_t slot)
    10. +
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    +Zzipeng          2017/03/14          1.0.0            build the new
    +
    +
    +
    + + + + diff --git a/doc/html/_me_mega_pi_pro4_dc_motor_8cpp__incl.map b/doc/html/_me_mega_pi_pro4_dc_motor_8cpp__incl.map new file mode 100644 index 00000000..32b54a21 --- /dev/null +++ b/doc/html/_me_mega_pi_pro4_dc_motor_8cpp__incl.map @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_mega_pi_pro4_dc_motor_8cpp__incl.md5 b/doc/html/_me_mega_pi_pro4_dc_motor_8cpp__incl.md5 new file mode 100644 index 00000000..1fa48106 --- /dev/null +++ b/doc/html/_me_mega_pi_pro4_dc_motor_8cpp__incl.md5 @@ -0,0 +1 @@ +7c77c996b85e51c3d2a88297840d29b8 \ No newline at end of file diff --git a/doc/html/_me_mega_pi_pro4_dc_motor_8cpp__incl.png b/doc/html/_me_mega_pi_pro4_dc_motor_8cpp__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..bc21ecae34775604392285ff2994dae1018fe5c6 GIT binary patch literal 48221 zcmeEt^;cD47be}IC|yc-igc(T4Fb~L-5`x1sg!h=beD8pKrelfj!Rr5u5?M)9Kdhp zn;&M)`~h=Vz*>iU&ilSQpZ)C3=XXldxL9OZ2nYzcvNDpY2nZ-X2ndMj7-+zq_v{&i zz%Mitd1*<6+q zOaHq~7xv#D7xLBz?$cqjYgGr3J2V+z#t64mHLl>gW!&gg8@);%@yMt%#cgl?_^jS7 z%j4ORZW7N`F&Q6c5z*9~WH*L<(1En7QzT(W==63Jdf-0c`7 z@hK|W_(ycZ^k4e?KN~3rZjp6)>!3GMKFS#<(wDBHv!j>sm8UP&T5NyJr~61rn*A9a zxKn2=&Y!`Tm0fd(iIvVifSBqlcei$R7;siE_w;NvMIF#C+wH6JOrK3c1%=TSguU(I zw;Jv3cftyi(hs;ZmxfgFk2e&&m&XarYTr1_`^dkPY2{n`3H~grA|oevK2;;)(9@dU zdnGAp7WO?#{!VveZ*_fvU*C%C_3msn?&X`c32tC7%MS(`o}Y-6wcU{CuS!G1^Vga@ z8Cd4-lEG7%p}l(mxZ>VCJ$bkr9=`f0MD*b<4UM2AZkiPE?u(67%dF2WD0fHnczA3~ z`qiUy{GR>jX~U1Ao2vOwpw^9__F)_7Xv&qo5dPa%`c3cEg-_44sNHb^XMud%SyZQ;ZFmJYe)O zV?r@e9Qkb39#@$k#63D}!KVSl&}6?st{Z9H#9l&0A zq#pKRR$&%rc!_tTwDp!P(pkFDhT!qz&ksKMxL+s2a#lQ09C6|Jw`|%`?;Pog3I8~F-CN!My>&`gWU?XUK-h>J0o;({+8Za>AUHPw7&4FY!_%w5j~sgXmHlF=yX_w* z(*et2{#)(|IL3$`(SA53iXTi^&GI`Ac#0wAp`(xO8!43t^ZSw%ezyqWNmor^6qs<)~@r# z;82Ti$4UmJ?VsUmEYTazI1*O zy}K8)7%JnJ$w;|ZfkXxvIH&yzU|5eI&mww^Xkh>v=Xv+AiCP8Ct~bi8vUAiyd`i9W zRiDUvGLg|8`#il&eGeBWt3r=b}We%P^#Rtr*` zo4pDd)_;ZRMO#qzj>dF#??}I-+!Vq`cF36P!!MDU03}I7+-2(;(hQIEUglC zyWmyowbfskUZ__f={sF&o~ral#y#~s8xdZ11cyM!_$z_!MgBA4rptB^GvExeRI9xL4mWNm zf>*8`8};is%etB$+zmZvETey4k9QLJcux}E{Bfk(-8t*`i7aGO<7GA_kYtKD?PrVSr$gA5wfc4!${NHW7(ti)%6Y^ct#fkxh&J zA78_^E@kjJAvn&NHbql#QpZQQ_bON!Z@C5mPgl!MapM{olfo?HoL!#FnHPlkrP-#0 zh-Rv@9gD_!DY&OtynXD1u;0+-hgUYFrLJ!lbxql67qTZkLv-VY5g3i|w#dOt6GM{9 z*0yMN&dvAZ|1xf~cNz6V9t&x`QlN9tIB44T3;XE8^+E7Q!X~Vy^1>O8-I0tQ(d~_L zyF_J-I0e^~P+m$BY>_R9T#z~{t@h1e$;p%iT+lXkZ;rs!5EDKPnO(Afe=m_n!N`oD>=qeUtc_wNj>)AVhjJJ!|EKpE8FaX?QhIZ zj5ACyu#xT38%RZUkxyco=pHqD2J9`S5~kDBYD_r3!vy?iaaEeb)|jAW^7F5}h^DVM zlW@PI2HHRWTKAGG?X)wy_p+rFKw>v<9x_6{qIP$YHgq#1XrZa2wL@fwg;i9`gJL@M zac^-kbM0Ko<=dTR$LuNwjjiW@-~KA&4!^eDz?G^4OZW z;^=Wm$UI7h9fY_{e!CI5;*GKLZHDe1sw2AZkBn53x`3cSejJS^m2CXMD$ZI>wASb^ ziDC>mUWPsx!Q6zqe_5=w25(S)4m(cTAINhM z#QL1;8#%c+X7%&s>6d#ZPQ=r0 zQz#n0OGbENrm=Y~hH3c{92S5}!n&Y6MR0hz7#fhO+B|n;F!LkW3}hDhd8z@)%4Cz9 z03*=ST9~S%Kes>bMa-vl!=dj#F3I-17F(ZcmaWm!g!X3Mql+I2I-e-t(^C33X&J2yi7f4Up!gcurlb5!F;y7 zuV+g|&#zcFjaFdv^aO{HP~IHOc4Fu7qyA;=$CIg zy0daEcWtQ2zwgWDd>1`))7v!AzI*0kMlaLk;+0snk6F*#e zDang}4sWN~F~;Z}#~S$i=I`1DQ`Ww=1)H;_RBgbBrAa{$@amm%^A1~isyb_I|1SY% zKKs120ZSH_nA(69FBz`EsA9syin!9)@&zYJTC|^k4bM-1$f3)T>K#4?aeFDQc#t4G z_;k`t_NB1Fxy$V*a(=S;n=GW?iE0&mna3Zbjg?Qr0apx*mq8V`_#O(O4xoodF3szi zIZErBwz!GVbf{stF+D=i4J;B4lekt8DmFRBa|c^Db=ZEZ6N0<8<8V(md zf+g&ua!(Z(4$ALUZ8C6H%*~TAUoQB z<`%?AdD^`SN?mmlsP@=Qnm%YSkgzDplJFAI5gj&&u61}!D)J94>H!gqiEWh)c4^T@ zDs-!_`(t=xW>-ZAPK(v+gbiWj7Bf^c>r{Tze_dG3c$x_W+H{j41f|~d1X9^BbI|b0 z+iDTDVNl(xS*)d)ud*QHx6qjH*8&XggAo$(uhcMx1!C6LM)mj>UP`Lhh3EeVz7jd^ z&j#y7)!^?(d_wY1sa&aGO}Z#H6YE4&`XSg{_~Yhlv@`l^K$KvxJ`GtY8?qZ6+n-q`l4)3@GHv7pzJ|FSURcGHnsX zE~?#!iMXJ3`l}R#N+hvQ&gd1sc@{~c*_8+I%9ENJcD9}r5;9(5!db&{z7q+iZPJeQ zr5$ue(+mqIA*W~imXVt?8c9s~e?l5MbkWHaJ_rnD_5}8WB#lshVTptsqzJ}@LQE}0 zgm(R>);F!KX=eZNdUz!=XB`zv1*Fb7+*}YtEwj@?*XTp_j>g6@gzXS+Q>M(X0J^x( z?IP6t0zHu<&2__>hRx1B-%Na-ZC=zWuGx&}CY!aCSM-p#%^_>#i>qVwu6C|1aAw1eC!+mWFvIh=2ggz;axHKY zrV!Dw%sXoheV^jY@~B5^Q%T+a@yB0S34c>t=X%j}1w^*Zi6 zo^#4*yeadGPv?-Loh=!22rVE$N53Gxr8e(dtw&D8;A~S}X3BwEq^fG^3zHj{TM2@J;WH#IB)A9Ot(vaM$LN-Z z@ zoi2^+J||?|A)^XZ1s*s?cf&KLU|O6LxrIZX{qP=IftcolaN=KWo~8DmYaL>9CGW9h z-#fU&0ZMjH6VA+d#-OhB;ds}Lk=hijD6Ot9XI=EvRp})~Re7~ET4{Tu@*}4fVcmr$ zZk%Qt=g*?V?)E(k+JnB+NhI;ZDPtXkI4f30Prv@~T8vr;S-V+bMXq1(!4K@t>g4Gb z{>5WsbJi;@c^5t~Ca9vHj+i6M{FY+dYw(GGbk9g&_T^xW{IOB z!Z|aH@y$(kJ-a!P{E_tZ)a;VYO&~YLdOKcQI%oQ@$iy|Ls0CxB8X ztXXGH)ViF=9`NfN7DMyv2f;o9LX$N8ks$FI(Y|At<1`Ueku-IFVSwx`waW|7a*_zz z9XTY7a1gwN=o^}KYp_MqS;1U8VqVPFuX5lmJ{QG1EP!j}4%hTT)Kn*&eWEhW&^~_f zp34Y}>vKbP49XpHesFW|$ig}0{c;Ug*@g!*;(2;i#5pn&Aj&hDT%>QE*^7l;f~4ds z(B3e!$-})Tk;s0k{A8c}h%!_(yM(!R$+DcQ-`Z94az+c=5D9_~CcP5p_c!1TGRH!# zRlb9;`h7n@g7Z;5l+iemJ@d2T?t``oMpjjX>$XF4i&9FdkM__*)$V*Gn?H&At0Tc6ZE+6{L(2WKJPHzS@9IL#6u0ZM@xM4 z4Rqt~|4P#ZQ1G)H0X5v5@d~!(aU6{gUNt*Q(?ydBGt@lV@i>MDt=9-6E4J%D0`tiu zxH&2^jXB@yr{iR)ZM9c}1ip>4 zb^WOXQTFE^*WuA0m~ZvV)`~TwCf^Byv4OEd}-8buf(q#fkD>d<9 z{#{Ey_|M-ZkH~!WU{@Fd!^ms z&S@fs&}!#_kH#n;Bpd|$i?-DKY?a(W52d`fneI!62<5QhE;UA!H*eZY#`Dz*UVGDo z<9uD;X7Mm*iOXrcE!zkI3F>_FVrJc4MiV_VCxZRzp2QXGrV5wR`a9LKA8q<6V+-&E z&<4^{L?bYaHhghr{S|zK0S+?md(-g*pEJwGQBvnS4(5Zj$BJvmg4}yu)4B>I5S=!P zzn10w85~yuI03Tx4X2TG^3?bU(dWN0Z=X9o|B7$-6JS32Iw+mBX%<*?mwVG(pF=DI z>(RvVPGCfoP!7=&pgvmeOp(z&bIm7}7NkIhUM7iRi&*V{CC3lhf5%}ro!Id&Ju%z~ zv$qKguH|7PjpBQGLE}Te*)ouH$vAw*w-2468XBI&k6UB)`^ISPa4QthLqw#jmcaM< z?^}`OJ>(9|47@AkGiN(|hoQ-(G9G~ejWhpX1)dZf1zAx%RHV6>V0^0|);N)cnQ!uphkbBYjX1MNX- z612bmD6RCxiu?r_AdQyw7{)8r3}!s|AG(&Ihca?ZIrHMMyyskF!p}?S3**%whz~Sk z^JV9E@m7EEAzJ55W;Oybuwa48H0>BQ;eGl1Q-X9K3!*G7$fx3no;d&Ru1>aE{z|97 zowCX`3-i3G!`%kzR**HtA8R8Z45 z&Ja+$<{wU~>_*1p)`PQ)3MmH)F`m-}9L@*B_kNzWe`uD zQ2|CFw?=hVeB_|Iw`7J)@@Lbnb93&ivC??IJ>tlz{Lhv-vNi8Zp0SXV4iR>Cz0g>E zy%&`Mw!m=( zS@8@*A0)ei>mK$-ldTfCWZ znIM9Wt4!0;q&8OnxIy!60}^yV_D>U$r^;s)R8G!2I6mB)7iMRqx_!CNwB;y* zG;yYl@*lG;_T-F z(izKbz9_brxH-Xwl%a?yLO)d1lZ*s|dCzsd3T+zN=lpd`Umb0vRtPoTC&^gjvUW~< z_N&N-PGbER{^57jmwz{77z8VW*t8;H!tD&ZHXO&XB)-{!t>OsU8)@wD=L!^`L8^Rq z8fLS^-7jiE0;wml67dQy=J<7AB>i9*#qGA3k~5?qF9G<5iJyq_h*BtEq*1 zjiTX;@wB|k3jW`?{rlB&LNIrzcITan@&OQmZ{fMb*{J zTq(qMtI;7rK$HvRCHJi=wtez>E)bn+W^DxB^r}OT9OHhqxN#Ou9|Nx-O}pWhJqbal zQE(K6fv(vguvp^&fj=6AAZ*k5^q|0QuX$A8X>3~J=fcwQA4jGXWCw& z40~`$(arR*Y``CWjNqdN}?S#r_ znz%&Bnt&N6s|{-c{Gok6h5QsyX|O*>PgmJ-GBIJ-?}99VR%E{*aN|+r zAg+>&RuZv`%cO!2!)D6`OV)lwK(>)@dtqPYmzFFyYs0{mU1+xLZOai>dbFWOTW4d7 zkDum|du2({!G&5x-#gbW1t^A|fJX>tWQd+A_%?~&H#$3W}dL%$?h4tpfc2uF2@ptV- z`90)urhLR7u1P%mt=RUD2f(+xPsKG{G-`5Trv;K6=U3B!mDckQ2u%(@CU916& z0Rm3T;3(f`A<@pzdlsL0RbSxN@>~+8lyg+)$X8xU#8k}^lD2QjV>7! zY!=44&{SOg6@8FEjBm3=@*=M>P*(G_z}8*S5f|*MGkcd1wC_-VT$KyozCVAZqwL|% z#8hy(+I^|mjC@v1T2~ffZ$7~%RZ#@)$1;>0tFmdZN9s^h+2e0O)3e_XI}BdRz-czR zBU~nqKf4wAp(^)Qh4DU^Um^?H)vtV4L9Rh#QZL_HfYgapGQV(8g`!PhB6fwPH5Ty{TWKwXxDjuZ_9d z`&vwum-SK!mz*tAd2mxXCbOf>znYxuvbWRA``ofD+RZYv%bPb#xuLr9MD4^vhmkww<@}cIy;_YGA@G-u>)EqZHgXPH0zFg!lYk$^v8oqD z{X^$W!K-^^^5;n>kgbpw(AoT~yW8@f6&7u^lhz%H3SYEz-dC`FU)3Mj{s4k7^FU`+ z#aK~tcl`}6&gEXZ%-|l^3a^Cu7sCb-Eexc3uX-9Qb()-vDM9m-Vmvan)D;RCk(j~T z#N8c;6q^tQe(;mHMV-A9EYjXk|Z(K^-3Ell@#@^oJKO8~J^23FrIN#p*3}g|r{n0dvi{us0ppQ@C z93Et|1O5Djw&WvD@pBioFONNwfw;B96MFp#XiXs)QGh)?!02EF53q5hdzh9yaam9# zoZYNKc!a^@w|2;@IERQYcA`$IzRk%dSG5Hp@dM;--&$mfFuvfR-s3*AzT$@#PP#@1 zdYe6X_O5@RCv;8^^g+<%DKvs<&#!(H9JhY;kgv$n%J#l0DD%04_%%r2FsGcJCIqk- z$TNf1S?PnRc;quev}GM}JP#f5x$V*o{m$|Jn9xnVvb=fA?x$_e@1Gny-@GaM#eO=`sAo8TH2< zi!{L}dm_j8!9h-Rac$n4bLKb2BXEil_!a0C2qnlG^eVT8m79r;E|T#I6{c-eL8|-) zN{ivy0yOITel^l*mwKnQ<0OE|eP2S3L8b?2;;n^!{?zXFG(Cy;-G|Q;ZQj{WQS<`U zf}N#p`@a9AKhc|TFVNNQ9&tOP=C7;(IHr_>(_+S0r8^QJfKe^R&Ac=@#V`Xk4fLIpyTj*|Fxb>yJU~dN%v5o7nGBnlfrX}@NKfW*j%UvN`Ncwd2ge2xj2e!Oq|AT3&T>FXp=Qs=X z-no~sl8F^cAaO57qzi(gPMhmdUm5F?xP1{s4*`eAq8$WxqKE_@yj_vwW}F zv&K~po2wdr_4*z8GCuzu5WhViDVFckA-W&#u?r;bihkVU%kggn`i;_hqytIzA5{++t1nW` zukgS3og4CBSdkFk`>cG%H08z^?B}SmYTEl|i)gz-)7#_L;R$Rhn~^m~7zpU_bnBAsAWvPJD`foo6dLsQ5PLOS&dvJyU?>H3z_RY4rax)RCcNUSF0!+S5Xc=d6^Y>V2C$9 zB!D?HvP{Uk>uj0YRon5`@-yRA(5`P!r1FXgHFk=+x|yHcyY6ovaYT1SnoZSFR-x1A18RXn&BY#S6!XQMd6IKI{W?=CA>ca}?XPw=iUo z2Y6v*O|bc!npyZm&mpJ~C=(il5-omEQiYSk+1YA+@+xh)?)moft0`EI0OK@3;Q${^J~Y;%i6QzSnuw8_)dSanr<4J835v2)i#}k zz$iJh8T2UgT0qkt&+W=i184`1wmKuo;ypL}M*4&suO}5FQg-2_Rv4fvSAcnvH}PbW zmJj6LNHeGaQ#b2`Szp=$E>WZ*)5ir)zxKkmrsq>UjIgeKTPwPL*Y72KgqL!~C$<$F2;W)%`sfC8fAl08ms$~r1azeGv#Sb2%sK;X#}766@blQFH|DCl^<#+p(IT)&}i+q$uTRhw-vvQ`u^%>zt?Ge#zKjl8$HZSS<+NcPZWrW?<>50xhIM z+wIB(VETkD|7p?Fl^%<>N8OGX+Nwaik7}sdRpqBD^_rK05}7ojG#SM!s3{H%q%)_K z=7X~GI4CU4hq^!^0_YrjMnaKRtUNlj?-NwKOv6KEcMXI}VM3xqLKuNjkJARg=-Tk9 zA$f`rnSKBW0InHV4Gr)8m?r{rnbswyqvB{NZURJpzK9wVPr+eRijuqSbm2AoB%Hc@auRMO-C9XSE zb{d0<=wW;%*pN8ZwOuu~q4jqb)BzeK`RHP){fbq7d{UxG-@E{QOWBABLJx9=rgMxK zX$y((XX)&P&?0LfU8Wt>1eO;w+3vdzH|H15oXBeWWdaILb(qH!Aqe%g07|53qv7Mq zW^!LS49gT(EPK%!vcUACC@63HH#W`0g^fJYu2>6&E&(D-Ec@Ob^zYYMwm-CkY8ckb zOIR9`X*dMo`Tj8rIOXVKMeo$|Ki;ErnW_TsZ+fV{Bu(^a#JIiq!oY-y{k|=JGj9W< zWxh{{^kvPT;GqvIbTE=C0Q%ase`x((F(^i(okQQXNr}VdEX(XdDy8oPH0X% zTmwe#82mA8u*RO;=iUsN?QuD7b+C zS3!jk7=0r>*raKt-At3Ljk@=(*<9YFiyJR5-`+?Um?M$PqLJ^}2%0&rf2m*uj?JR0 zI6QyLEnBJg+Xwq7YE}+29I7qd1XU5!_$JQFCONE8~HE3*5!NReu!@WJXlb z2j)qUDeHWjZ|9@(0D^+nnyE(mZoJ9~#iPj;2V8P3YT=(Fx8+;ZJ({r!CPkC7_%6hT z>=3=9MDs*8&OPT0@mvZ+Y6{nvXP4%Yy zbu<@u^>R*C@=qW1)5vl^DFPpxN`~WxIpQ_~gJM&gEkB!B z7o`0>3cf8aLCIEF5r;hB?5_UJeA$M7kLk)gn1J!dJnZwRuFubXO;l<`fq9d`9)5-r8X5nd3{WJe9th$KBCoswZSBq@&gS{qyCfwDmr#;bz<60dS0hFItA`MX?L9;#>s=5i8=GVKAas6SUFiBT2912C7OJLr?`R2Eh>0;KEdYMLxX3{<_?k>XH=A-6i zx8Hd(A0OP@Bc*d*{86_$2_r%yL%iNhwrRC%XzNe%CW^Dt9_{*{4b_dD!>hp7YuYzl z`lLvx(a0$MZ`R*B==1c(rKa3c_d3UuXM>r5rnGp0>(yZ}zfgHOb3??qpo8O&Ck8lI zSn!&wfDxR6L~?*yn9Wq>?~sIQ{`0VvfKgC7+DG>$ z;wDG=zV@JIdtUMarJYvPlyyjIJ$-`!-~*vN_rwX(_v5wx5jZ2r8blowP{j_64oK;1 zCdh4xXlTh0I;Hh&)c@3&9=}$hh*%^qu~*CHZz2(xSayJ=0i<1G4b6N7Ti5Xvkw6A8 zX7Jff`LXhuw?}0udkyQj=!dFx$Ne6s-EL@hW%QFM$Yq66` z(@|qo$k=09je<+SndK;L#YQ3>o9Y<%x42e|QpH5EJR+)KIvIzcv+Zsg-Iq+RFREuV z4gnxazq4{WMq1{3dZn?85Y2aX3;fTer=IyS=wPoo9yg!4?AbewS4{GOpV(+rnTP4@ zUxA+Hf6wO~M;KuEa;dx$`YAl1FAkz$%bLR+@#`h;IMFAJ+8HcVT?sSWS5H~oV(ACx zk1lDSgme42!XYkVBk}0a`DXZE$Z(3_Q3pKZ3GRTX|Jqn~L|XmT0z&*dn?PO!Y2#+5 zBYyk!EWMd88s#*D?v{-~BN!RQT+i!pt0>o;DRfYDfDTk_$oQ&gr|YpiU4dmOfwWgK z+pxBOJD4nfuzbcek{kTA4FB@*3TNh3LN>9FVHO9k>P0M1a_b|p&pin;t=w%$aKB&P*fk%ic#s<>ln#0*FRp+tF0wv<89i>hu5@mUz zTc3Wm=<8xSe&%A^*(QQ;6(kO1|`-ag!(b<`FR{R z)s)WOym@ieC-9+t$)qjF90W7<)8PR~D+gIi%Hn5^F67P6lQ~hJ5~}ri;xA-F3^6E>=UM3Ws4|&u4~47rzA}@sA)Yu>d~#*zkJpb%yd;aL zw5MAs8nEbe9cepn#yLaUCv#GJ1{(HvxWy>?8^*MRVgdf-lCJ5zspc)A%sP_cB6R;>Hd*h9m{$jieK#9}%^1G!9q9 z@&nuVWg2H{dmBu)LvhLhqGcLpc|mLwD4sDPA7J~w$v8&(%!Rw$j;ByuW1AaHVv02z z=I2$3#uAwAu;a4BX`4T}H*rOzw0XkB$gJ>G0M(c{7%#!%ankqtnjckE{MY9u5f0;X zawNdmn0~Hc&Xti;{nhN=d`qwz+3U|pOW~+%rR6^qHbX!jrmxPeUjD{a7bt<2)xHZ> zrWp!X@87$ISPR&szu+p3!$jf@91o~K(b3cT#WCNUBe!@UEPa$q%6u(D>Z_q&D1aBQ zKC8Hl8~AkK+w1g0LfH+ty7sfz-PS7^;F812B|*{^V%8H9!1PgVG~{AFBp4z{BR3{t z8MZgeE$$0*cK+of(qHyU5S8-exTbotp2`>yp4uU}&**T!lz&b{Ia=`4;(JRI%ZpQF5+ta6TF zq15H6+WQpdcc|ZK*${~$nQ3EfSf~eK4J_u>?Sk_(* z!(TLN0Vey!34h(Zt!3KT_m^l^U&c@8=Vm7+|1$*`1;yHHl}*Bzf&+>ydeqnhy8iGfHKr0vj4Prh zF`|SjGu{sZ1^i`${s%UK%<0ZywBt?ZXbHmn_6!LTrwi|f^(uuE3IyNiThLITw-pRz zfjn*2rZY0}fm} z{6!S7BZa^}n}d1X(}DF&OUw-&B6s2L#4kD)68q;#Ag!b)_1bcl>F66wQ7K^T%>(sA zK4i}VEP8C!a)sp7Q>gf2-NyJ?+=Ln-QK^$!n;b{~hbt%5Jq=Gzs)V{aN*@6lW>M`# zhG5Ha$_xz|T(=&1H)W&@)Zl>Yz~sOsLF?Zk)h_vs9V9ycnFV;n_uZ<$}gr zsy9s4JCN#*4@f+p8f>C`pN zWwwlo&b%KclZQ{lf8$T1M!2`05TregCN#JBuCse6%*grTMRDDURW!0i_&%zUZG!Yq zPMTe&A?cvs9w%W11S4^ZGj_ z;Qmv>yK9~W+RSxn5KiD4r8P%7zjoG%FlSY8(w5j**ZV+btn5Np)bX#q-@@WA++mCu zh7s!hlLm0nuNP7+rY#9vPMDe3!D&d{gy&<1G-Ktx#XYJ<8!0Z3!@B2=0ww9{%`Xht zxjS7*05`^cuW@J!vjwTwuymw4>RN<;tCV6zvd_R7k`N?xB20?l`8aN|OFA@Cdmx>! z9pjAb`znDqFf*|CeUo~Eu4_%q4ElTe+5}eh^U`kfgB-mr4>_>sKbN4|7)^!~N}p|J zuxM|47|`0UyDa2>&m3Vi>7*>kf@ijUmVTvwfg7$rnk#9>X4(>XOCnz z7CH1-t^MTxu)0rVO^l;iHq4IraJW%ed(065pjI|sC3lb4|A#N zIHq}=TIJCCB(BLoQY=P9@_?UMM=R>{ntf7Lz8ZkQRiG|$`GVxjI63cOR3Xi#ROZ%| zc2PSUL7&9+5?NV=qYl12q+^j^6`UjL5~NORg^E|--iaZOu+@o|L$&@s*|-v2lQn8) zi8%F)6vu_*N?J@xJ{8an-WX+RHVq!9{_a#q72T5@$ceBOur(L_=M#%pZ&gNUp2KG< z0*qfsSM>T2<|Br_OaJwF?epVLdA=@p8DvDS;XPeRwnozv&q+e1OkMh|D+seLPdth; zaY~63O0`l*EB$brR+PxHhkv1mq1~wcoKDFkBy>I-$>2>&5#laeu*lBq{TQL%6&L!me}^Qh|n1GnQer zdcWZ{#I^~IkEmTvBl>;YP|>glYotdo^Q^-MJ!rmp9*dy7&}B76@IAaJHB)(cL?W9S zJNFUcCb#1Knw;8#lj;bXf4lV)!jQv4cDI=5Zy8V&hA%wAI_#YX!i?g+zh-80H4^Fq zcT}ieX^~jLr@$q(i+dEqx25)Dpg(ejOunBX)0f1k4yq~XtnGf?vbabd$k_b$CK|bI zA4tZ3{*(DVSU3?gR9_~?;>7gjBTAt6hx1V&M@ey3J#$_`IUkYf#btE&$swIlODMIf z7vUS@z949kmX;NK4l4sm2QEF=OB@Li3XrMWt;EAeA|Dhw+g4OtweNJ@B#`^FMx#f9 zJ&@%O=ZW)v=|FYFw8XN`&Umj!M26f6q#|T`tigZ~`ki?d9MR}Q6{g&5Czw1-2J7n* zmQLp}J<+?Iyf@ENhD410V$T5b*H_QpTEXz4G*}I%^7E1lq>f~UYo7ldw2Z0wQ-pwy zw8!*apqpmr+2oSe-&eibxdncFD3!{ay?W0J2AE*0c2Q`Ry5Cw81Tw0+=_MpWnz1zD ziX(*TCARCZ#ljXT0MnVjSqamZ{-f&NsmJ=tmyLC2M)T0?u;aU3Uzb}f^gCN2%8gr#0Yj+H-Lmb-T~X@&FFIWhyqYt;l_q zsTs58rg@$QQjv(r(-SPxQT1O-u#W7IOnl$3lwprbt%mWSuKz*STZTpXy-}ldOM@V# zAl)I|2uKexbUM;CbeDiADc#-Ooq~eoAV^CyAl+T(!QcOV&$+Ji#ZUOuzGJO*uf6B0 z#G&-yImrLdRI>cagpicpzK8MsHiYda9Rm-?mhA>#me9KvYv$FR%mgJ>WvotaeQr6n zlKKO|-<;$5_K2>s1ARbAYIGxrJq<6CeTq-C9ORYG&i-B%Bp0WpEcA`&T3Ps z{+#-Cw3;AJJCy$`$9L|~up@!lVoAx8_Y`(+NI;;llT2KtNk)S=#1c?<2Xjd=A-JG=(u>K2XxAzYuyx%@3_dw9aDH@Mm)Z(X^<_<^2%pv#c&OCfj@Tr?c7 zD?014kq6QkP}s6zL(~dsz;??s#PL-Qfo+_i6hJj*UKu_wk1M|)`(c}!1?omD3!JOX zVMD;6cgvI1_(lMS)xI3qI298jq-CZ$>{V7DLvcsbM#5GMU2v?56Yy1qx$=tS$`^*x zC~o=rWw-b;>eIzoh{S-TW1i>gg}~dBxksCj(|j%du__A`a|Ww>a(a9#%j~Rjr5E}Q z8&mw!RVOk*2uFQ}drzqBhS*eOg&v%Q$%dCu({TJ@E@i)?7xO+^Iv4{HA;cZn7Uxa~ ze{e;eMC+`R1Jg2B5zq^bUj!*vf2jvwv(!{e*RP*IB$gsQU&W0tmqK4;8XO@IOC~&H z@#RU@dHaND4#@OnQ^_ln7VgIwDS!%tme+%2O1y%=A=f zEAWp!Na0w8VYI)>;bJtVH`%%IXDTJ4T73b=1+5klh8^Chb8V{_MQ96FQf6CM>|N`g znQgY%=Oi||cIEDKJnJ~`8Xj=0j8zF1(kUXp7)7d=y^?8ARNdQec>=n)$(&`-S2fSZ zHwv!RIh13`ncXlKSrIs23W{|zt{}x)fi`cx&gXo%Y3yKtO7k%VoQY)HVHNX*ILBky zmuVr;Be0aT*uB%KfpuWkecR%5QG9}-LgCCTBg7?yxiV(lH7{$B2XoJCFzL@opZoJv z>l54$HvUiOzS&71SBXqU@9}Tmo1VRwK`SlhxUMR$_p~FaFcQ4Blj~B}gT|Xbau-5|%7btTUbqK@ST$+ShY)&)V|ZZw0sX!2 zQ8xSU!_*gQ(PwP%hrlK~@qe}c_-o>N5w4qm1ZVe?;qv)%P>tx|VHV~Ix_B`Ju`D>F zD;%oD(3BNIoyES2=|zsN`RVlT;?3%S*Db7i;3G1#L5F-?!hP1^f zv9;5l4y*9Y2Wh$g-c)JZyf()$8Qu`lI|6T$u|}6b*#XY$$+fd*e^%()#&jxs<l`K(+@AC?i?3XxtIGjj~xmp zz5#f{$|Y%W))l@;nLnO_Bzf;A&57A}JHb)`+PCAzI@x#6Lrs9!F@tqi+fURDssEAM zLaEJij0Ue_2GIq|zisut9Jun!y|lq#JQKlK&QG4wSZpW<(Q}EJ}>}18^f2A zG$HeDj6S`W`PnKV^382jmrNq#npAX?JyWoNNGW=$MtN_mE9s9Jgi~a$Zf>S(WFSas zhn5zrI`i&0#-&<75q7qKRTc_UO^VEF{Sm}kyR|G}b>tI0u`w%L%bz_#86c`jMwdjPvtPVq?_6dQ60c1KOt=7Ot=al8v4@y9_ zLP^R?z*%ed0@D*$CwVPdYU{pu@mtS_Z(tR~I^=39k{}Q4T{eQJcZwFsgjhBNm(~uR zC^nt4qy1Aw6RQy<5U9~D%pr+tOu5MsQ2JgrTVIEh|4D;p;jbIy%+yU-z1tK3X{15F zipC~VIezFGBj2aO#)(7&&_fz+*@TC*LLl30T$MX7BB(RJo19#0-a|DUQEj#>izCN_ zK4NtLfLj7mX4%%Oe==_&xnT5zPEE(MaqmIsY;v(cZb263P_=h!fJh)A!2x>LrU&F8 zC`7Xj!Mt4;RCJZ8)bymvrfu38(qcfs)r7_E2ygsS92}?L+Q+M7FzI11`LCl?9|a6>%;f4Qn^DwZmh<$b($u`eHmj;iiRS+8z8 zu%;mx665nDMeRWSeBb=xW6%UO!2FqHKC> z5V^qrc;zcB&R=3qy03bh{OmAyCgdy~QxGyy(;WfDc}j9ChHsaf*y=-+HZ2j7?%Prz%8*a4(UwO#`LX1RM*8=PJi3 z?&S!*+jgO0OcQQKByrJ4nT95VlbV91FvRBmk0;0g9M!asN0S5dNSTrzc?p|%gy3QS z;NXy-r})iIq+b^Qo&HS<1PoGtpU!_=7*vFkwmN*a-zFFGaIVZjF~S%N=wFe*{^4KtPP*YWMmo9jBI&nHzs|k#PO5q#ST4jI2+_C=yf!(~ zYBCW?ZwcpfaPg2KXe?(RnjAWGNrn8jY0V=0zml_~bR32~Dq1m}Y%W=(R7#Y<^i zgsayjL$h#m67jOT_cOIEA~(9}o|pDDw^b(DAVx={7YZ+9iIKOLo}?`+T-gH>)Ie~Z zC~3m>KK&k+A(rT~oXk*5c}fSVDe=8Uq%~*UOtD@x@upMD3I{EEyeYYP?8isv9?&{G7^;zsJb<9izIt=@*2{@2 zrre~+r^Wg}XSR9k5=Ge16MNMyXa>c2W~^F((sR-6+EN~!6Bw(Y8i;;=eLjhWS2lc) z>nj2v#+%GZsJXUdXD-xPlxY|MX3w8;fF+|`k*X$MlIcZ4tN&JF49|k?^4n7Uu!c4i zv|shl5P}4Vi-6T{neiemf2Vk<4Hq}f-{rA(i0aq|SBz^cf(@w=jhE)lC!PfGa@~HM z5I*K3JFZV$xc8rdGg_`U(_`Ey84t7C&kYXScMTSN?~b?~#k?Q2 zsVLC>qKud^MK6EtOd1tbe7E;&|Lzx{DSMOIJmcVUbvR*uXIqfYX%cXMo=8GM@-0@h zcqVJ%cq47-Lcru|wx2PZB3HAjs=C@lOnU1@+#IIZ5D7J2i*HA*obeG|*tegdx38nt zJDL{N!yH&{XIF2#TlboHE;HW;xCn3D^4BTjxr($j?80ax4=QIh=a0v5qZex3VBH>X z7cM+^Ym4lcO?LGN^1e>Z%m_SlRW_2o#Om?GI4qo0&JfUh*anNcDV=?l43t1pdJoQs zhXvy+o9$G?0s&bPIdHcv`OD9(`>{U96W#TIdm)6E1{bYgP=?<1aU&Jy+U;U3gx6(a zEtCy6t<_KsMd$66^fqB6mf6wKR6WGjX)qvm`fD5tj+vLGdB7HN5AQOmmaav5Msn{i z*yhI&A3H7s9v*Hdqpz0U!KaO6Wq*)??=zooT?{=qy5q)@fAgSUM)zgDCQI6j$cBEtQ#8oiY^5yGZ=Bx;}=wJZ`OWoQ5GRQ~{rPFtU z3=d;<-1g&u~T8CQN$0vD_45xhizqb*2 z_G|~i=V{2MEb)HIIUmEt2;TIQM{K-Y@JTrV3sMQb|83>J38sXg4gV9IBDon3J8l%* zQHSg)lDREjQkffKh^`m4+IrV(dy_CyCxB@~WLudMey1A$;I`oUPdFfhoW%4kAy830 z_2M(fB^0k^5^>I&K5g9YGahXKgcd`idZLW0Uh`PI{MWA6F=HRlO>oZcm!c1EUMLuN zFU5{AF7G$a7l!4P4(DUTVF2Oj;%T zyVY5}%R9Tf`Qv;vbjuD{5M&FM5e&w2J5EUA-cNy`Vm=kkd)meMVcq_-|8xM+Nu5_8 z1VgF8_bavqSZrc2TQvRzlUWo0YdC>~WiG`*BiUXf2UF%~s)@A~{>-7)iIn)g=%zGo zYr)nz(@^#$0U@@c#;V*(e_O}_9GuZlR|v>4Y^F1=RT&Tz>8QOy<)Om#0O!1FJi8lxS zd!|cVIGY*4es*0aJ2w|35J8xdILQ1^+IVhq#*Zgu0O$NJxD(xHINws4)0u1!g8j?1 zTHf)dT`st@`;!X|E@QS`g!Zsz-W>{D{(Q8pI=NPS4Y2%q5ja!=BVpryo+6QdOy^kZ z66u{uxp!S`aB>X$nZHD^Up)7?lR;f$&evx8$lvFq{k5&Mr=P3^usrv?O<+ow0z+ch ztTN1Pk-txuPDSV1E>DiT&h-Oe*U;)2$xD#Q<=VT=mBgs@RwU0_8LPKb^=dZ$dUTbl zY4vZ(cB{51fNUr#ChR8S0&q-Ekv=>wE4yuTp7ZbZSk)nhXRsI)!zu?FA@)@yD%^!0 zkGBr(wu5x%v>Te%Fsf+%Jt(YCDV03f#D~Oo?8CJIQ|>asYVoRt5oLKSV@J5T@_$3x zK};DVs`VL`-1ppn?8z;ldp8cLxM7`zr`@Oqd)xLt2_}0FY|6o2#xC39XT5(|ynvZg zI;bjRslsDfpDw*4ym0_x*nU8!+V{%1TUuhyv!KC;WSFeR-Vk``x*S{98Pf>fMV)J$ z!om9I;Z8r)bMJYwZTD`XKX(R={!?02UsHH5@fwx)-FVj@m?Jv9J~X-2BNH;X$-rx3 z)KWuUjJVFJ2tGs#at=H6CNIvFG6d7o`sP8zl6}a58znwXIh`e8AIBu~r^9aU*$0ca zS|iM4e@QMxwmrU=(1_x1&*oiT7Q}f?G1FXq`h27jd?AJ90mi$#bjjZT)O5cXEVDm2 zX|g2t807~Cab4O=ptWiDwW8f;y41jSp@)6G-eV4Fw2onMHvvd9VT8hrfNv z7Tn(}ZaETLbez?W0W-y*s!EJoI?szwY&tlXTOV?6t(2%mW+~CU_dwK|OqctTpIkEA zpTj>nkFiGyeD(Di<9B?oYEHiu(f6k3gBrwsGi^w5O!5mq-(RO^&(^%jVZ@vZ{pLV{ zKLbS?G)E5d-sS^>`s+yUP%{9BMnK6GRbJ;ZdQ-7xTJUrE@BbP(<4O8I18?uY^KDb- zV5V}nNM;nE)PJtw>^=40daumA0MwfkoAznRJg{?jk26WtnKQ9S572Y@r1LQ(GM6e6 zfn@pdU&&YI)H)C5geV_)URzy&%vs&+&DF$N6Og31eXilj*au#&R9%>qZ+uFd4O$UE z4|q(a7)Q@wkkq^n|76C;!dzJ;+TpXFcZx8a;{bb+G16KC`O;iklPc;y9*miW*1`$HN>P)Wf zPdF`it9*;ZA%Qvu6e?!%r=F8SJ3gLAU)^|usYA{R{mL5o+}uuo799a@uRdMU*N4m3 z#$l@{e5JIm<@Mb3Vs8$cT;hSto&djj^xg2lU}I>)V*-JE+U6+dX-oK4g4U!V0V z^9O`}?+dj)&!Ac?bWF-QwDu2j?>g9PS{9@yr2gJNDRx2KFy}dZD!x^RI4j%}_phNy++4<#s zi`;dIsI>AJ)c)vr^$;N7;EhNh;I>Hz!W{jbe$JJNGlX(@t4 zmb`b_VedDBrsl9*)$5bGS@%l4fapAk&)Asrv#oBYgALCdcM0N3fX%n}3cY7D6iy0~ zYk}DXOU7^cKVws3*-x=bJ@;4&fb+@Xc?R}{rnvhFE^4!m{75hv`d)(2hFj27RSlZC zIfAys?Du-?Vg>I4=MrGPHNi!mf|P+{7g|SXMgTQnV+x=t)mbiJ(R+()%+F@6UCDy zb93A)9&X)z3YhVl-YI4yQO9U2eBag04auVIJ(Lw<(`Q%nqJj~N|Lcuv(n@YR>izkV z@IDd|bOhXSw7bl)DPdL;?egKW);A|b&s#?TI>@0cl^PDMz^G)xV`U>v7Ri5eQuf@b z{cYThbtr>rK8heafce+WJD?if*uF+eg5M+jWgAuWwS~epWlMAfF+CAKqs@PrLwN=H z#2Gii3%(wm=2*C^lheN+8z9r1rDg6!xbiXx*+)u17+f3arwE6#fqxUT7lU!v`7t4{e+Q9XWds`@5{VHQ>|BwY&Z@ZwSY-6w-y zDe_KGCBXr>kefOIZruN-2$*!u=kz{*FLfQV+zJ@HOn{;!Y&0aiQl<;4IukYqh|8VB@*JY<1jwx~LMHn~ zhq{a(vjB$(Fv`|rJSx`(`L6(#Er6uV;v5ap$eD){NIELnlN_B}ZIQ`Ybm|1!Sylrz)d*M@&0y5SAs z1xDS6v3rA7;W1C;qKF1)U>)wnG#*s_uOelH`07z@VI!{`5z7OM@v{hZ8|l|ao3%LX zVLM7dKWytg1e6X!)yq7~F;hS%|Fz9$i%Rz7(F`qi^e`SkaR&z1Z#J(j@!$p~(Ht zrUzT6gvH?V7Zu{Aih@6W^h_~%Gzh(|YYeTFNWDL9E_IfED*mkhrf^{q>f-1f`HJx@ zGk}%wjX(T@GRL5A+d~D0yj=N*!sTnA!^tz1)}vN&?wZcnRiNN9o=brrNUD?ct0Aeq z=1)vbeJ3r1o@0H=jBQBDR}j;dZpeg0JEBG|F>xPPZA02DPpQfQwln&(;l(@1?r4c9>3-jg~%S8S=Nq;$l5Vnw>BS26NbPAo6Q9T5dzv4=`@b;?#Wr3lW z%3j)>qm!Bfg0&1}Sq1be3?o^-d;^HF(0F0w&utv-K5xEE{Z}%u^#4**!L@1vVy1-G z1MPXjI;v`TX0&(D67Ux4ZwOU)27=myj6h>gt;>Jwx2ETp1BJluJVWyGB%13?JXeQT zhCVpiB)QaZ*Oh0c{x5r?q8Nwuf$22Eg0#YYlH_aB1V2DCCDZf;+9}B_9chA^50$N) zqJ##nBa0zfd0flP@qYuIB2(AOX(@6g%g6X*-xhsKqM^yw4*lZdj=8LY?tLgL{huyuMj?s11n^igQyRVE4g&Mm5 zq?~Bfw>0CZo(2wiU#NfJeBNw%URo~!n<1`}Y_Xq|+i~e!JxbxJ@@q`wY=QEY5jk)B zTUW$B4|M#^zwN;)@5GW>?stG$>={%bhrIv&Me&e#_bFe$=8zPVP&3asnIlu7;c8*XD#~ZS;a1m!-`;SZLOmZRSuRrD&men zo)nQ?+JcMXg73X<0995#d^o@C?b;L%?9lf{GkXGgLXirDXBP#nW{H|3!?sm!ntROw zQRV<9aJW!UHYRxhb2eyskRc6a9QXXn5l5)i?eDebY&EL@@e@R z=d~tR1_P8iQ-T+U(43G=G~6tm%k76*e6}*8{iknDN)PTK4wMe!f08l@MvW!^%~oi9 z+taqL1Ws?NVPfhh=seigrM=s-f?+3jo$gL5LAteWlet7Za#7*`;i8Tcq-%u4_(pqp z*MEzTa{s83N3hVS^+n3IhdA;e+kO__NKAoi$F2rvFG*$P9aqBm0)az=zyQM`a~RS- zU^k9jE(KC{X7iaSNN;d6n(s}|sPO=id9C8XBgcE^_(}j-dKLkB5r!yYfy1_&eWt_SH7O&R%uxrDva}mq)Nj;Dev-Em@ z6x+}9C58SohJ^8Kz_yzYb}o5pJ>h^`v|HW@5O2a~YJu?;QwFn`H)~2FPjBPX-qL=N)EYe%A;r&l`=ztX1VFB%yjPH#8kz4Ku+HV zcts?$Lu|ryxwA@J234m+hGDm|eDP!lJ=B|z>C%(@f6GB02h1{{^Fq3YxI}OeNk8H` zl>8afkkVQWR&r>MW^`RyZQ66}%Adaq$(k(B=@WiCF?k5#!mY1H0LD6Um?5Wuz@gli z#&gAg#NK^MUgg;+iXsX?9l-T2s1t(y_Ve2~?{1bT2un-5*+HATzd5mXc#)cc4rtVX($pvWCbkQ8(t$EF{Ze-Ts>d<$iyZN>GiJmAX zBqHjzni0V`G8n8SPREko{{b5F$kjRxqKQsn?FU8|ox)ZU*osER=MuMHhn zD{BX)^aA@_6c~sL*bOC6KRd#R2zVBMtD|!cL|?#LGDKYqKOPrmJnTyDWk-%PTJ~-BvIXA z3>s(%@mnW?%W?ue^Szi)B(teslps1Km_PhP$4z&;$9KkjbaS+VZCXK0tl6^FXrVrY zc*xBh{-ai`oO9JeOmrXm93K>>2G~Zix?P5n0QkHOk`BPVbKRuv^mx$n8U^A|-@7gb&y{65YJDTQ4mS?#$I|a;qKH|_$p z(t_7&td69YZ#)AYsOiZYUl&&l_M$arZ}i`af0l~$moG>us4vJe&|qlz3yI6>+3d$qfzl_q!R3ZTZKOs7xK9?}*P?~QrXsY@c_dB18ZSgKYM7pXHW&>0EA ziU5G#p!(BxAbr+sXkslA`uPOk^*_2)M3&Bgm!txFk@W>8lQZZ}Yi`d&d`=rEJpV&^1~NMTp}cT6?2_YYfU>3Ro`fKy!!U z3@8T_kxOpHAN*oK3+mB_vV9~X5x*?0&?&X@Sr-)jL?R-$nd2tV1H0wRU$2>GfTTHz zR)=eIB9D2Znc1GCoS6S1fSG*jlhu|zgq+^pvI^IP&}lxezjof!Kif+5hL_!1q!PKH zQz`OS+A_f{z(g@34?F^#x?F|Z3}gcxMNEQwx68>Sph>B%41GeopPPqVu}O8V4x-Wl!de0{|Tw>imCs_JN0ZYtjD?9=^XN ze-jJ_3~ED){IrIY01|yd@XBhd1*&MIsPorW>soq;;0%xk48H}UEL7NJGmVo31UdOf z@iYb+%)L0FjesrAH1Es(<#utN$?LL{_kL8MUj5o{}(| ziSs5?jRUYo0d|`IZ($r6HVIcT18THsLNQfX-b6 zk2P7Es})JWo-qwdV)F8gdW^obpZ~7L$||HOd_@A<2fmHfDxWnnDH8Vo_;Obk2mE$5 zVX0gZ@-#voo!DRjN8?*9)F9g4*hda3JTb#Q1;4S-bp%+r*bCGA77$WCBI`wp)Dwg( z)5tc>#trLxD~OZqgt0zheSwb%UUD@}?4@h@li{uhZsLWJ`eaAPeweJUD}UNdQ2D1| z2uIz&;TCe&qn-V1vDbQnRPnDDttgq|PJ<^Xt*uMICH6pDd*}@nJj3?cw1|2CgnxdO zEJcQP(HG~^o;s*T_CLyO5o$P@i5ymbqE%#N70KPY!<|6aiSv?!0->Sr<|5@={rebZ z7C^^nQlUo|=`~w(PQeO`eQ!9QtMRgO=#;jCaFyY?_N$6;wYY$*OpjMPK+AiayI?yU z0aTnVzXR!6c`BRtfHh@V2wo2$7h+W#t(7)x(%rgDof@Y_ZeM~H4YOTIkr`yX+e}N2 zLE`RBud>-^t&5Hj%|h{3uM(G4{RNfTd4H6s{cvw5P{HcT8#1#a z`t(*U{J6F0X#8JPv8)oCXkKxT|7I95=K6(|P6yv_wx$pZmw1(tJ07%xfPtbVh zW8Umg?k`+p%F$9uM*J^ceh|*n7qCHV$4HG_!4Lte>sg(m14YO2{ z5m#TXAacGhSinbGDFFcD3NX&vNPK#!bPGHMkE-8;%6-CE$(g)Qbaz6Xl%>KwWBQ#aNrxkm`E{{)!^0ov)=!>I$Pe3OUnUN+``1@rCU&kCL zlZZp9y{mWy!}kTab|&XrgwC)`kBpm=YqDgZi)@Qz$h+62m*o?JMIYPk_v}_(5+L~e z`xi|7ug1yZCtn1gcng;98imOmmCdf-N%(kB)94u82i&>koHdbJE9UkaU;E^vuA|;C`rNEn;Bx{8q(lDrOfRQ(j^bARH`1#jD^H|wj z>mZ9%AOC=nf{?Fbye^hPumQRld0v;TCEiW}kIk+_ODSL7S;(jUUh4Q-4u|R5{e5L< zq5=l}nnqo26dkG@awdytcFMEe84O#${ffF$-$_`TrPpDc9QzGO7o#OmEirRZ`k?Et zRA)|Q)RRzvw94bvv##ONAF96C+6NaV+06TnU_uiSZ8H8d2z&L~bvhZFbTlCVSw}}_ zmlHS&Zx93ALnF{|?9P-I;V14;mddb;US9=zTOBF%r{1cqH0wP{{|8j2VN=ijkAtm_y9H{I)kxCJ_9TYG1VSC=yG4k?`xYEYehn z;Vkv4)n9?Xh_6UpQX)ge`jT2^O)x7eY<}NEaIphT+4>)~ z3*7ZKfU7EH62A;|fGvCdoS^dD4gX-Scar>v7nUrO?9LIWMq%rB;@~}XCn_%n$!Ht9 zJ>^CZ#CYaCU~0;{BU)u;-fdfyLPTnDeeJi%V5v6?(I~QsBK_M=NgSb;sUHVK3DmG3 zi91v$s4?$%iA=9Zxsn9qxE=3&eKSeH z`gfV4db|eWXH{!=gyB2eU$$+VV`I?2-q$oH?zh1dFTNb;rTxu9wGBc8-plJFK__TM z?#2d;gyEXkF=gDd8c{qH0IY;Drd*@)+T?tUv;=j5kW>&=*n<58jw)?V79Erv`nm>J z7uWEnG?e7`>P@G%Q)?sTsA!^!er2!MY9Qr`8#^FElL5<8Ssit$m7=c0qB3Y4z?G+o zs*NBrdx^=bOM0>K`Gj6SrKTR$_%t1tM7e<&#h*{KX%_2~^nug>ll(F=@-#Nv%Q1e*chDL>=WdoR zoco#j<#-MhVbNfW<>d$#`iE4@AMn(nlB5<6aI_3){rIfdfQPjTNM;Axlq#4SuVC(H z{x2ul^E^VZU3~xx*GLoGa}Hf<{Bq_a`&Ex}uvGsUDLr-qC&_Jn2r>8b7)n*N_7WGTB+5Yb!m`sB3bRv+&PXb)9de zfcJd=VF8<_p<=phJ+4`KLz$Fo*yu!uHw}x85oMagky36!ECl=ysKVf5Iy;S)NvBr2 z%yW1?RMNPkMK8wM){c})$Yij7jC`I6$jsubhtswR8o+S=B4PLdc1 ztc=9lW|XhC=r~mp{Mk8j_lT}q2?(uM-l%4WS{1WFPFOU$JnZ=Ig&U3T(G#A{*|;mAz)MM}jD(*Tym>WZ`0eu;Q3=71 z;+4bvXC^@`G;Pv@?1guWZIr=5bXf|2yBoFsqe%$S`%F>oxf0Dv`uxkXB;HqOB3FiX(|i!+CNDkH zY^@4iGs;;{v8PHpDE(YuclLt)u3FePEQS-d02U(D6&~LW28xv-1D5i~O2{51j$oM` zF+6(**qo`G*a%5rbVzw+U+OKv;8mvm_ewXC>$?F7PRbI-x}UgsT@Is<)|FXeUjPR|47+8v{3hzA(9vj=!?uYgO_!yk(vnSbA;``u ztV%X#mYl^4dy}Xl+}Wg@r63bpgvXJAVwaTZIrJ~6J{zkGa?9>gSC6OVxusK@o2ikO zR%u(_A7{)og__Vs?mp0Kuie%a+@8Rde(Q9I`6#h1X)tn+UURqjGSvP|$727&%}{kA zHQcK)Js%q2US>DJ+5i3zrX6f$V0~wtto{q$2b(&{kpbXGLkN9l!Je~01|ktH9>0ja zmKS!EJ=`YEy`Y8E%v5{`MCVk|2w6vMRlfL!-}n;zzQFGO{_NTMjs$j>zOprcYdM9s zQN3L<>6_NOrB2;w`kO4?{;d}{^i;Fq#t7vh^MB8ugdux2`>Z!AkFxON+1*;%agYZi zI-U2cp;%hVSG{KQgZz?VShliWilNyeLz|Mq2=ETxK&45ymcw!p!dL z&1%3;Mp}6RZjxnU5I5iVOgQdoVuIi|Aw+^&zNe$*ZT{Ia zIqlDHTJ=L+Ui*jDJqD`IMh;J6!NO~_6O&ZZtxB`$XpErWP)$6HE<+N!G2@LzRLEee zMDF7s?XkX_Y-pMUsrlt&eb-qT(D|Ehs+D^afd#!2cfz{gIlXoA#f@HmZW2^Bc~*%g z?(6t=z3u5-dr@-7VgWE1JX5xlRjMB_J$oBsgN%xbilR89^EK}~ zk2EghrE7^@$K{BuY`?+ZhnCsvlHX>f<)Y5lm;2SeS#^^}Uz9s)1v&QZ2sGA@T2xaM zeDFmZiP_1Du3K`uUSsFo;2bO&CWA~A)+tDo_fFzcwsF0LF}N&#`z+2eWCHXiS)LhN z=Y`^r$TM!2#If};!aGcyJA<}r;@7XMcBhfchm!yDulFCnSwUwZ&iNTAg}2gc-JCEO z+$p}*#%R}le_?spe%Lk0vFKT~(DH{{ocf130yncHRkt7!p6JvssjiZ+%jJOVWMjqs z*LJ9=sKxs&>(RISZM#*>i>jNpVN@Q7?#C4$1(to|J(lM>k2C*|7r^h5{v~~o@>l@c zKA7i-$E)bp(u8GN;tbZMYRYRDV8t>tC^UG715MyW0%oJ9o*LQ!(X!rXI;|rPqM#`d zDm9Ct+uLMuWN^u3xI8DPHU!pjyQ1&t_|Xf9oPM|fRy#7+6@jbpcQ{7QObxo}vfpK+ zpKYAYXxbZQJRbx_Ma2{`ANQeV$j!|7xFp{Tm23As(L{-f+Uos!PPe!_@*}U6FE>Ib z>UB?d-qrxH0+#Gqx0Q3TNi~r7!6)Rk04n^9_5#*du+YW0U&t}QEQ)!jwAM_92(m(N zIwN^_-M>HhYhm@DDcu|^TfXL7Z4~$19(zz`d~2^xw3%g348$yk`~^jh&}7Hm(an*^ z*rWMO^;1V$r@J^fbNb4J{)+N7m%16!aTjIYM`6Ww>0Cj|U8CctOLEHybgO$1rsM#) zI&#pMwxhCFRl%q@W)T5|?K3j2I~%`RR{W0fsQSB_=H=GEg^myctx86rOQDwy2f>vZ zYW$-kt!j*(jG-y61Yz+AGlxedGmU_K7TU^j_&NSh%>d(Gak$95xy(}-WrvFCvHdE( zPyPOM)B!|UoA9cmXY$SDcZ&+%{txU2C zV&Qo`fz-&5mX7?iKS^R`d*}uJ{KWAt0J8q~LRqDTrP=C$+^_9z6aoC<=Of(L0((v& z_n+~$%|^Z!i0u)?B0h@!IlpL(4x*;nZbF||?Rp3A+J89Al8`adVc08#ymH zaqhBlG~mZIKL~)A(A=3!^12Eti7s?Jh4glLuj$~Bi_aKkG%%8-`{hNqfQ~KOxZ3-N z>C_5)c)IK1LYJ|~ted+DN9w>VDC*4b?8Cs}xcNe@?I&0SEazK?d&@A+=KYyrQS&A5 z>_8i}0L}34Q+fVu2yqco%o3k0zt6un4(SoW8k?=P!|ULkI0p-q2gp$PgzF1%@VW~9 ziYnh7R@N!uO_)g;vA7-lz$)T?D$j7Z+hs#Bv{k6ktt?)oAuWgsN30$OsD3Qr+>4{v zg{(6aG_?XN^1vsSNlvIKt}g2Bbc^4q{&H<<62He;(rI5_y*U|dWKsoeB>&{Mu&}tj z)b`djpsLy%?Zz)>^O#P^0qs=WdqF#3^g3)PdU0uH6<)jGa@!{)ejCSnD?)MM#{ZWc z;f3PgudD+^9|pJ+!?}J&`02Jv;~`!^sk95+`ha6Gkk%kX2;$-Kwc_Va7&+oJkI9ke zsdsS`4u;5X*^1M)ah10h=#!NGHPxf^#(N7{&uL}0yT)A>`br@=5VM+r(RWMoCf#^$ ztwBrKRPA&DDvs5M4?b$ai(B_by7R3&@f|lfJGM0Ee) zWjT7-jH*x=MvLNR2yMckAx01LL+n~e40=;B<3AJ>qAfsZ=3poCIdz8P3-3L`3zK!j0_ zmZxF3EgX>eh9QNXdIkODL0%zl3$?OmjkX~QF$e7K6Xr|>XTOph&5$&oQ35wL?w76-vpq zR9iDZ7H=T_PHtAys4}`2W#H*TdPEmEO{Fd-!xxuVppBDcj%pn9<)ZRWLD7k;4Nc@< zRy&rWr+zB|F|z!i)ZaRSqr#9;{3*X0p`?3$|4K2&POKG z44*cO;=#oB&`n5_qe@d9L?B?ci+|8!fVhN*NLT%dO#b`Ebt%YQu~l!^7h8Zz(3eDF z7E?B=9A9p?oMvY};P6o6XCKGD98-Ei-}Vd|{(k)&aM)@TM?+f@0BL~8?4$lHMD8VP z@6+*Sz%%52e+8%zc<#qe>w@HDi*r&Cta9LCtG~O3u>17e4f~hbWjo-PlzM{q=;H8rSci?(mWOR0O>-`27y3aXyY5hKlJvW3(3Ge>I zk^M2=ME-6q=gWio->b#g$1W6dF0%D_HSyH!Thbl{$^!?>lbL-Q)J%i8ZsVs-IJJdJ z$#t&V8jjfHZ>XE>&YC{qtejrIFI|#j8PgPY@c7*Liso#({Pp8s_uH3;oojC7*0D3$ ze$=Ju9F7Q%2+xdSz&AVM2KwdD22dcnw6`bEs_7gG3P)L*1P|=m2{cMary- zX4{MPd`GRIp}?T#$FiqBB_G7;1&S#C?ew-7{1_R{{+JjR;1%q9wY*{2O5?tHe9&dm zk}=lgk*VS+y3=*{mu_r0z^f1@y!QCWyec@>2*AZ+oBLE{D*3a7!+Si{Z&r*anYM9l z2l-ps1wNE-Pz2 zA9r3W?-&T~`AiresBZy3Y@ot9n69?SskV4dR_iVRU)T@!yMTwuYHr+v-l|FJ85%Go zONt^mH$h7<=#l7+5Wm7Mw-J68SCnG@OgHYv1LjjP*xUqIVYfGBXjD|eUuf^xQr%MT z=!~C#RbZhw_jJ3e$8fY|tncH6PkpHHkb28ls!;_TQWw<2+G8Ycrmj*tn`2;&AGw1k zd)-Bs(N&`rH!u2{_}6|AxTnZ{6}vfU2z}77``DN%FBz$u5Iz=_t_zZo7e8rZm~7v% zaRYw*?*oAaq9r0aLUjpLg5%srtUrHhYE7@?S28L==0>jsm7uGc$ z`O2FWfqm)9%s%BZ6guw~zz1>E8d^AE*`w1aJ>cQ)oPt4LbG~J|R{ygrtWKLsAEfU) z9#_>(4v8d>1if`c?+-zCzJVHdzbuP4f)kwA2P|rNF%QC1Mc1BCXUBhH&}OCD zr>aPlh?8M-90*XR015%t3~XNk%CF^}RfE3z*M#RJ&s~sk;du$j?MQ%p1x}hq^+X{! zy#0027g1BJWUh7Tw#uW<5`;_g5D0b4qlo5KAPWBr3u;}}xS-lu-e`>yu6lQ6M}s(i z%LMbMMPMp;JI4#2^Nwd#IsnNC81gnjxe?x;un#!#U?Y=X~Gy@`u+2Zic;|XFqG* z>$mP_Z%W?yU6$AJ-!H2YUlQyRgH#!%o@~g+1sZ}ZqZMm4WOu=5a9+mM`-jI-!H_nz zq_pK>m9+A*d_sUJh&a&#kG16J`DBlA#SS(ls+o;{e<+uTA1!APrm>6s?b>_an~i+B zA4(2r5@re3wr}GfQw*OgXi32x*b7Zx7=*f+*Qq$E9iOP!u^`=NF&qx=KKWZ*fV3@*7bavkghOD8-pu3j`DM0xU15upNauZ)i5#}b zJ(Pa*0Pi=Bn^$8Vw?N;h#wB#=$xxW$qSiZ?`x>}aSy$PmbubKfWf| zK_u}oD}6cl(3Y}#P7Jm>liV6evZ<-)Eo9(*%yz& zP9wrKwaHi3Iow-RIgu+q83Va!?CxeB$d+i+DxF&UL&4;;AL@WdOo(yx(t}a!ZIydY zWtz&v$Td|a9os7c3oV=p`r=#gYrpiu42HgNHV5mOHW@X?Ui~dkr?>3V(5e%Lzkyyc zvH9&lRW5dCiBwI7Lm~0LU(Oz*_i!Qq2(XF(3Y^jQI7^44O1x)Rr%sCY^NkNAx!V{3 zbTVPNOk1W#oP53zb<@J+u^S&6QY4P_qDvg-G-$gus-sKKK{MAX`k>>1U{3#Z;Ya=? zRuU%cJ#-)^Z9nTtnl zRMu&b6<*Y)k~d>I4#R!nb#kUF+J$03Jxul*l7yrpuxDwv1;(0*tn+S1Y00gHnJlW8 z3cq*xUa5T#MMTi+hdo<6s{)}HL;MM=BXcS>p^^|zy$zeSc_wmRG(0doRt@oBAWp9d z(Qlb%Cc6tdLE!&fZA4hXeei>bVld?~=vwjJ@q>PA78?l3)p!|J@po!x!Vzs&;5wCN zsb!SBJ5LXA`x}3WoKguWFSGg31G8PIv#=xj#f*_>LBKQ8wC{>+l?clYLh01uz%Gyi z=gF|@TqE`@!Qe}sb8ASF@g`If6wh@;^l_h^=mG3t#gAZ7K$ATSZT?d$Qa@VowpZc{ z(MA{%4Jj7JHMGH4q#O^PNwdruaabEojI1nL(@l@dh!Ds^D;g$xRAc^NZ^ck;JLQ${Wbrl!AAsf; zS>#%7Yjxr1h38^Xl1uO~lsNZ4QZ8bERp@z^g4kXet|x)blPVoNUex+xMf4fg;HM@; zSI6V)_koXlQfWlWTRZ6$KmKn?R#;f;-MaNPFA7M+^j0$%WI4f^j38++~vhCfs1 zUaDR=hB{w}Pe{VLsJQ_Q;MnC_R-{6fxQzE0JvMkdSZ&@Li6xyZJYYKp(kIg02coV1o%KOPnMRyUg>Gb~!mOS%&ppS~Vxjb~#3471t@W>GeplFl`k~Xb6Ia+zR*_OqURH81b#k$w zO?fl-sc}>p^u?c^9c8ICPvaddLa|{5Ss4doJ8%(4SdvVnQ^V)Z#e7Y6z}aun9_#68u0MSs4@_w3wyF zdgGMPxC&K0XCxbXD+>p&JWBt>2Yl>D6I5KuOX3+5^M@L|Paf=L7t6y3!p7g3bgz`< z_X1kXDX!g*7@=XsHqVP%S*`8+Ty27~{#pujU&*8Pzp}rz>s_WV-Rzccssf2qPdwf~ zVnb&%eO6>=-P>R?ZXc}}ZGOtTjcaq?%6h&7+E3ArCMIz^C4dYSC{VHrWhmT}AxF&F zlf!J6tob9+u8Dr5xTq_kxr@e2T)BL}wJ~w0riP zCf4MiZBp4pskjC7m&E=r;u|)5mZuAf2X2>%R)#>=-V$I*3_e z8&=Zn6z>QNayI3?R?HKsvsVi*D&WVa!rl3RfQD9!)2Nx{v72fqa_;5eqa5v4PA&91rtTD3fkmby#Zm*8^`NYYi?rjMKA4>!p{*ZMi) z$R8`wVO9sBsHavTvhz>ytvpU!yzesRv`|Jt>?d<|&v;E9%@wVA+BiL8#3{7wNwQNy z;wP~1x;N)&L~lT~;PO-8UQ@W8i^?#W$5PkosDVcvEti2zph)OJM^@5-vpT*os{&@S z`#ao$2sbasBnd${O7`d(I&9mZ!zoF$sI1!rxHJuL_71~aTTo||i=AUZl^0~hB`jfm z_DmFFme!`(YR~yQMA;uWe;&H0I@}`=KPg>|O@#)P-Z1Oi@f+^L$ui0rx-_l+kf8c0pfM?D}DZ2a;RsT4V4_&x^Bf82CDq+&!w> zSij4>3a`30r~2l@m@Yg+1K%sJ_yLXr1{x*MviA4{r9Om`72sM3P)tBdlQq~DIH7j(=|xTEe@_Md1{OE-7}OR1A4#;(T9nf?YdV@{Af#?< zi?eH0i{VH^$C)gVA%p{%P{4>0+y9cdiR>(%-P7rJ$2*`0@&%ZjZ~tpHMQC0aOdKjw z$U|4vU{T;R&LpPf>1nmc4JdeH@qnp$0kj=awfi)|QF7<5yvL^M z#u+KrO`4tRqWmAn{vTO1szvEDJdK65JD3Rk4oQQ4B5nIaY=-3 z2LD};Qbzr&9u=C=pBQODd{5DA#-|NGz$MTN&#xTi6%bT#si)`RRnJg)0PDs8=H=_H ztw{Ulf+Tvzy&%Gg4+rY_LD9ixvV5dJLXI<_VRP8YXlW-%m?PN zl8J!9x?hwt%i4(R**)Vl3xfm?S-1KQH{; zPY9GMWvnsH(aabca;)Bnzx=S(1X%o4ZK$_Eev6QtdV)*@ofG$?E#$oLObGKu>? zQs=6@JzPV!Rxc4N4qpYR(u;^U6s8J)<$Ma0l+i0!A$&{Q%-NlfOAm-4v5E+oy)p6AktrJCaVD(u2882->&W&BT%y|eoH^njn4l8WUurfH z=Q<295mY1;`2pNXUFWWJ!G1S>wlz9z_+ypRbBtO_Q#W2NvzFso;eJMN|sA3_8buD z_4EFQ+;W(~H&{{_zav~!>vXQyUEcujde7cj7H!OGtKCpq!7kn8Pbx(k{4K5J&-4Yc z5GWK>JQ!4KjIzcb%u?#5T!{c$p2@Xf8o@FRSy)tAbBzw?r4hnD(j&QkFz0KSq=_~_ zfSl3w3S4BQYP1snQDUBqN9kv3XQ+mmc~N_=+E;e=e7JtGa9>lcm?zc-(C7B#y~omB zD*+1Z4`G526S_$OU1k>nG6Tv=+15k)viq3%cGDgOKW~F2dn-Cn^i{DW*9XK<7_e3$hRKt8- z3QD_$2PwWb5M>kL>~Ani29osaBm~mzzekV((~l=yy<1^Fr4Zg-hTt# zbFVHTvLWSQ(+IcKPE~F=;2!aYXbXV#iYl)~S)-odi{gudyue|XE(LR&{Pg{`;{m|k zoHmO0bmNPtF@Yb|1jrc0JNjoy?CIn?RiAj=_^Hl-@zl{A89=ByK8p!~SY@@c=mADF z;6)Se=mR4>psA{e1mnvcGXZTN|A|x$y%zxNQOEu~6p?mBE1t~+9;HAJC9hIG))eqm zJ^2^GU1ZN+k#g6bh8C zLpmWF7od)l@FFnbUaX5WVjoE#JNFL*>Snqu$Q`{5qX|>`S}m=wi~o_T9azpCMcMes zMaxn8dJ5$RtY4Zo`-PxBRU3cS8{m!(zU7LJMs*nG)I@kV%LJwNO1W67KG9qfm{$M~ zaz3hc(Bs0T?a};$x21B`emQQOW{nicO4rj5c5$rJXLqGFEu)Jz}Z!g+HGG3l!1Uw z?Rsv@KN)ZG?h#J%QHN@>{@7d2{z%rDE@FC8bJb0GHM$<1WFsSm)^nyltj?_BmvB$W z&d=)gd>PHZcs)#U`0ZA1Z}|q&$#~<#o8UZ2Br{aIXu{{ABNgY1MTIXEy70sv6Yr%E zL@Ux}1GTAJ6ZqRYC+h{s{?zqQ&HGC-Ap2h`sdtmJn4OJXq2PjvLl1l=|L z9`n;(F)svNp?ZB(-)qGWy3NW^G2Eo8;@+U0papR4rF3?gTygfuht3tYt1h~6xTx84 zUEW_ob|o$VKFM~he>39KvDLFS_|Da(miM#%l?O^pb%v#Tgj4Lh$V*Qk=+mt1;SOr* zblmPA>2IHr|D;Q5gB}n@zC2Mi8c+PUppBf}3NVjnZ0_F*oU>f!l(=pR4)T8S!j@oC z8DdF=P(v_%B)RLaERKT!@lECTKuSlQnU$@ekAR-{*o9sgJNa9`2Z&-rM0(N1CGhrZ z-?m&gk8eFaM*qQ;rM)rh5Kz+731D-I@H&;~Rd=u&biaVeBlMGw7|QTC(Rff9KO;LB zLZS{7DhJh-J)H*ppzo~y(xDvgm)v?9I8$f}nHig|#Ns5qP`I0sC?j~ibYhtX-?u{A zN+-Xd0`s4Y*%=xrH6*)7k6I~Hap)(Bv<2lVhN_X9?1^Dc#E88955CM|@B9BNrVVBk zo=Lr)bd;8k@Amz;Xu3IFhqi#Osk1-`MZ4z%v3CB4VP9g3Bc&QJ$`AgncjB4+mp~By zs48^pLkbsIL>m}?{fn5|f`6yKqeXeC1QBI3gw~!W*q(c^T19RR3DrJ2BNh% zI_9#b<9L-sZ+L>wr8MHa;27*g3w$x{Z=Q}=W{0m(#gYJ_;&Ce?A|DXd_58ZiHvZQD zp1+B33k&dbqD>r(Sj0)wtsA%gAXH#!uATtb2LQKm0y-8!-wyRiCJ>nlE8d?aVn7#y zLM3>rD1hif+UAe}%EYi@-lHJ4h9CTJk)~H4tKs`sQO+cBTa;ILQ*ZtgUB}H3naC!g zi{io$h`0S%Np~x-nJ<)sok4s~t{nCL@2g%mhUtB2-$vIa=Y`|{wD_b<7k9f%+5TOj zyA?l8`p42?4)-MQJgJ-rFK6;7dlTA39Jz+ZY0RV)|FS6iN-b>juv}RIuIY^O@)Vh4 zOVhAma?q`_tLk;WHNDcu+o~AevZ}g$gVqn>&mXsTbd03q26c2TNjeXH`wf`I9gKH& zHzN&Skg6ZogyQ42C1+g~3p0x36{^Ly0J(wbPEDn%>h5qHPXx2JTOBV zi+trw=RKRuQ|H_r4WcF0qb2L;4xAr{nO6eFta>>m3D`4D89|i|kdzi2V2`n}UJu5k z5UbV?0m-)2CD+!4Skva$xZnk?fT}B1sIddZS$_CN8YIp8&i&@K8stx@xfahTyHCY<_^bo z3`e5@gCu@SN{soR;;wQ?@VS5@t}{r|4G+?Ni}P5tk*%RwKK1M<_A_6JTu|0kU5!fN zhzUwyhK3;@zfW5f@83%30n{H*%oh2d^hWrj+OOdBtJ(>i(c$W$wi$JJJWwk)hr&%t zA#j25FVnFVQOiwNBAGfIE9x@dhf94r{^vklIvt&J`QzOOHLYCZFtLu7#wHBeih5{b z_xH*1E{uD4 zE--a{p^2mn&g3fk1&uB%-TwRMdWCjC=Y>0X8q2Q<)7Ge-Hx?kS_S)bsjnFJ=9r(7R z14&qTSDlKwTvXyMk2CJ$BThjE`9aG{i*Ak9t||}BAG$o;mp%rQ@3iLzly-RuX}9Ub z&H(#6CS7QqA8nl#u!Y@JIV}qci@N+N0NQuuo}!R2F3gx0-k9M~)s89mqS&BqMBi4bOa-r81N@I9*bCccXKv5hLQ9B$! zXys^uUG|Wn%KgElnShZ+TiD3@WIs8Pm(laI^%4;nfMFm#k%Ha>fF++S()Mvro5^Wf z2K(;0-`47JP{d)jPfB(%eP0FBZ=+|am5n<}@oRZ+rS{Wjf`Dx-MZjCgM=aTPPMV7} z*vky!>Z`4W6St<`X-ewF8Bv|>)?ln4-95f+Dgzx&{6=^gPZMeeEhTXa5uRymDHw_QvZ%e+!pP`#O6MoItGjL{Uf2o!c=5>l%OeMHc+`h;*XrF_1ZgPNeOL3yq?R+@)6?u5{2CyV-?6i?pgc3(_s(hs$?lXs*=K!LrGE%PdO zb!pKpa{Q4VTbf%S8{2gkzG2YkljSMQkrEVlfq zA20uBA$0YIo*zlGErIq$grcUQ^{x7GVBBLwFI`N#g&F4z5`3=?ulKc_A3#sMpC=s~ z-*s~LnTfA)erz+p(ggnk{-AGc{dOkYVRQ+?@QL6_wY$V#aK1u=pA!qPwF>C7PCaa1 z6~B@udmNy5Kg>fDK?v(6zZDd^KRF_TR^821EKG$#fg44~3H$|QcEfr^Cp#Aqa~TMS z?=LGGUtNHY{<4hj+l9FZ^5o<%C_>faz&=p zPLS2~*1=Khuz>r|tt^-el#3-VjWn-^BtcXDPdAHuy?t(Xedwc=`2GG^L~82_v3^G2 ze5x<;rX}ZSJy4 zG6&A5*>%aw!2FYxb6BgOfjC4}sVR=Qtmm`zTSb}CXu|7~7S z^?P!B$B^Raf%dVSSk9)WX5RcN&&Q#^dA@8)BWc;9cYQ~Vyl$C?CzhFj;-y${05@Z+ zXsvyoMIN!kU1}&WUh2w2<2k#A$)!7RT--+&I%_EBS^yc8*N|uVtX8wjacNa#L+iy{ zpmJ)VyC}gSKreT6Mu`D&5fuDX~+*og-E6SA&*tymhYJ!qJT?J zVrh(z)|kvm2QR#tcU}ncqh}-=V^pF%dv4|?(0oHJr~?c_#;x!tBp1~wtZ2Y>Y<&a- z7q`M%$V~AyYRVfDUyl3SVdm#C(3zARn?8OCSOPh(d|JO(G$>Zp_{_K_Hn|`r;wz@U z9g&452ZfNS(eLPs%8*B|=>(HUn2LaEJ7}GZgdirb7KQV0N3$J7LNjnc=`OES3nXC0 zhS7=%gSSGIkN9=V9oF*c+r!K@#Kxqxq5yj+OkhofA)GWAHbE9aAzF!NWCo*CN>;4U z0>Ce&MI5lmX)}stnTtBUx;fcl6OO5jUOL-Ns*a`9vM?+gfrGh&W!b|sbnpg^2!oNC zB;mkwQFON0ox(nY9J%JC?z@og?Wd>$}t5D6nf4Sjpq~z;sK%EW^Oc=?3c6F8~rmFI3N}cpU z;S0xkM-?@O^nkYJFXJ8?%^ov!vqwjTDuJ+dHoaf#>WbI#$nmrmu92K92>l~PfqXhe zw>&8}NzXx8HJawf85h33=qb;N7>w?Qv#&H>H~!QoIXIFdpZO%&N6Hjs4vs&^swEzo zA0ADI6Ranh)O)W^sGdp=93333ZdDh*MswNYZC>UKVHo6?TPKc{T1cjUy3Vh7YVUk< zLSsh>^0{NyUeE%L?g?NjGC;h!TSm~u8 zw0w=0cAZK?JMp2GQ1T$%)GxE5Nm$!;`s=eq941Kbi$^}dh*+bc4$o6z*njAh5op! zdk>6Fy*@yr=c=Qlqo6qCXL8lWUzRi7FE9(W0VD&?U{bkh1L>a=>zh&RASvc`G_3oe zFrQUykKyPWGb zuxHiNPKv&eK%BFoBax@7*pmp(k(kPIuPd8VxsyxV8Ar_*I)hK>AIQ3(e2xk6tcmf5*ngR)VoLd^aP^fvXdvgMcr_tc}={ z0j_M1e(;eX#dc$*=`gX4kJHG=)tRcN)HY=>)9W&v+XFx24Xj5eE&lduRv%VWY@u#h zH<{fEoVQiVL<{S*GQK?|NJn&CW$@4-bp*jOdBe9fmEevN`ztftnDgxGPGZX;RLv;( zY{LHbP|*4wblhOOaioeTUoOc>(WgDdsdqibZ^rwq6!}c-%_Y6EL5VI~4l@qj)6c&5 zPwsw4YaxfCf88lpy;l87^M-(W5bd)Bw(s446(mws7a4Sc;)q3Td4s-u`Qi__2I(!f z$mPyUA`c{k80Bo|z*4EY>`0?I5 z%P-FO`1oHE>=8B_bf7`CQ7LTD0XzT^_s5mro2)7FJ3R=5)Oh|G^WdE@K1h0>e?nX1 zIHWG)&6N3W7zF*H?s#2V22}0~toK(1nXYHaMiscJ%fR`yH=ET9_}imz8N$Cg=dj{y zjZ7OVbT7?PQdCWN!&#;s23KwQKs_1Y8|oT|!OfhQf_4j*t}N}}8Dgv7@*fM|Dkk9=~I0$%yN&9w!qComr7%|Jb z@N_@&4IjwIAnx^&ZdZ$<18m9KG9pP5OXK-uDO)*vH-}w?ZLRTJ?-Ulna*KE@l3_?ibc0_GFFg;ZM=4@iH+{&3vd3)d^2&n zzm89(NBe&YM?NZkAe3f2YKq|<>mI|L&g59d46-e8-D^1akI~b7c>iSCSnD2_1Ko>} z2bxlvHnfAmOwPkUT^0KW(cTU6VMq(T@aGjHwQ936o?zp?_m%dLZ_CGu!{@IsuR^l) z7opl!-AiTvbB_=aSL^e#=Z_FVQ{13sNRcs0f{Tt_z#8~?{Wd!_7uT;QhtTWe3a78k zIEgsSJ0It$pQ50Hm##hVx63cI#CUD}k5QUE?=03WXa`$}Nr{kBCQWp-jKTzp3kHA!AzuURFj|s3VD^sB$Z}51)^MSvjK_SrHS;?66fBfyc6Zl{L asX775%X{U8#`xp6M<~jv$s%5wz5746q|ylh literal 0 HcmV?d00001 diff --git a/doc/html/_me_mega_pi_pro4_dc_motor_8h.html b/doc/html/_me_mega_pi_pro4_dc_motor_8h.html new file mode 100644 index 00000000..42cf7dd2 --- /dev/null +++ b/doc/html/_me_mega_pi_pro4_dc_motor_8h.html @@ -0,0 +1,213 @@ + + + + + + + +MakeBlock Drive Updated: src/MeMegaPiPro4DcMotor.h File Reference + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    + +
    MeMegaPiPro4DcMotor.h File Reference
    +
    +
    + +

    Header for MeMegaPiPro4DcMotor.cpp module. +More...

    +
    #include <stdint.h>
    +#include <stdbool.h>
    +#include <Arduino.h>
    +#include "MeConfig.h"
    +#include "MePort.h"
    +
    +Include dependency graph for MeMegaPiPro4DcMotor.h:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +
    +This graph shows which files directly or indirectly include this file:
    +
    +
    + + + + + +
    +
    +

    Go to the source code of this file.

    + + + + + +

    +Classes

    class  MeMegaPiPro4DcMotor
     Driver for Me DC motor device. More...
     
    +

    Detailed Description

    +

    Header for MeMegaPiPro4DcMotor.cpp module.

    +
    Author
    MakeBlock
    +
    Version
    V1.0.0
    +
    Date
    2017/03/02
    +
    Copyright
    This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    This file is a drive for Me 4DC motor device.
    +
    Method List:
    +
      +
    1. void MeMegaPiPro4DcMotor::setpin(uint8_t dir_pin,uint8_t pwm_pin)
    2. +
    3. void MeMegaPiPro4DcMotor::run(int16_t speed)
    4. +
    5. void MeMegaPiPro4DcMotor::stop(void)
    6. +
    7. void MeMegaPiPro4DcMotor::reset(uint8_t port)
    8. +
    9. void MeMegaPiPro4DcMotor::reset(uint8_t port, uint8_t slot)
    10. +
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    +Zzipeng          2017/03/02          1.0.0            build the new
    +
    +
    +
    + + + + diff --git a/doc/html/_me_mega_pi_pro4_dc_motor_8h.js b/doc/html/_me_mega_pi_pro4_dc_motor_8h.js new file mode 100644 index 00000000..d3e7ed6b --- /dev/null +++ b/doc/html/_me_mega_pi_pro4_dc_motor_8h.js @@ -0,0 +1,4 @@ +var _me_mega_pi_pro4_dc_motor_8h = +[ + [ "MeMegaPiPro4DcMotor", "class_me_mega_pi_pro4_dc_motor.html", "class_me_mega_pi_pro4_dc_motor" ] +]; \ No newline at end of file diff --git a/doc/html/_me_mega_pi_pro4_dc_motor_8h__dep__incl.map b/doc/html/_me_mega_pi_pro4_dc_motor_8h__dep__incl.map new file mode 100644 index 00000000..8c352b11 --- /dev/null +++ b/doc/html/_me_mega_pi_pro4_dc_motor_8h__dep__incl.map @@ -0,0 +1,5 @@ + + + + + diff --git a/doc/html/_me_mega_pi_pro4_dc_motor_8h__dep__incl.md5 b/doc/html/_me_mega_pi_pro4_dc_motor_8h__dep__incl.md5 new file mode 100644 index 00000000..722ea248 --- /dev/null +++ b/doc/html/_me_mega_pi_pro4_dc_motor_8h__dep__incl.md5 @@ -0,0 +1 @@ +d7dfc3ac07f8c2692b9137e15e4bcea5 \ No newline at end of file diff --git a/doc/html/_me_mega_pi_pro4_dc_motor_8h__dep__incl.png b/doc/html/_me_mega_pi_pro4_dc_motor_8h__dep__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..1acccaec3255faec55437651d661d0221938a178 GIT binary patch literal 1792 zcmcJQYg7{07RSk%94yTtZ$UccmAu_a3m+poI)jlcFg5 z&=A4Of_Kx7869X}@!&wA4bl5y;o>M{Z=KDle?pCQ$We035BoZ;u7V#jz<${G#gBg} zG{!cccYn;YK8bS@>`bnVbIN>P;V2xgc%~|~qyLbwT(MAF5iWNO_!g=?9+1U`Fb2H5 zyeP(aU*f(myf1N-&qYmGQyw>b{p}E&CyE21%#yDDB|$ zm(`WXTYCUIv-SN>4+0|pg81!zP5G$ZuUeA|xJfLvLe|h^=VRFcz7gEqcZbFZ84}16 zs@VejGQ2O0;7! z+UfSGpNUOqx7>_Mu}_Hn83!{mOS(Z8ZAw(BFW5QXgRita4HbjYTkmx1Quc1@2i?uc zqwQljtn~D~9-ZQ7eg{{~JH89JBGml;(rx}?U$h<^zBqw;v6L>zroL_0U-h(K54^|B zxwRGd0FKDvaZJqic&P_G7`q!&K|>5WVpbKb!6nb)7CH7o~N zk+SM4VML$fZVJguR9rZ^i$`-?T+?WqWUAW*_APZE3m+=VZN8K&jTs)ZvSPpoLKjTQ z-26Z0pxp`ul`XEtg@sWy^#7D@{+Ku%QK<`sm1;<6o9l027Bg;xI?$lI{fVHzKT=I> z`ebjWOX9(YldHReZ<-sn9_!+;*|*S!6W@Hl-sn93%DAh5{<$!~+K~rq8OPzr04~i> zkIao$s!t+)g@8 zcn7|bGMx6hsMsf)X5&6Aw}`FEJ~|s{{iZz2lp=ZZRn_Vl0{jXr@|bN_X{nhsw0x$OfdEUgw&Lh-QN%lt@2mpCOng600&1zjcaM}iz<3PbHN ztl-0$GJ9@o!hB9xXR0`mCAEf$2}Z5mQPU&H3>0z-cOp^)={nT;BM2*>Kms8Ca~(UvqvHP$GnWefoa!0en*LkR<gF|6ST2<0V42%;6h3W#f~FtG()=h zEFEF0-h?#GuW$rhqFS~!*>G+wZZ|x~f@DiqxQqBa2eh*uZ7St|#o^MJvj>fMfxMJ< zB4@8Tfe)@O^D|uu+lo%Bk(b|x)tL4np61kAa75OLF0hUPfnP_`;m42k;%DoGJJH?1 z3Bj`|-*x65~U#AVn-3-ZlM0o7F3^~<@DD#oTXRk3@NjR qLoRwCpBMV=woYyP^m&E=pev?8SY(37ljAF&Lr-^KB+K>u<^KZ126Zg} literal 0 HcmV?d00001 diff --git a/doc/html/_me_mega_pi_pro4_dc_motor_8h__incl.map b/doc/html/_me_mega_pi_pro4_dc_motor_8h__incl.map new file mode 100644 index 00000000..07d2daeb --- /dev/null +++ b/doc/html/_me_mega_pi_pro4_dc_motor_8h__incl.map @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_mega_pi_pro4_dc_motor_8h__incl.md5 b/doc/html/_me_mega_pi_pro4_dc_motor_8h__incl.md5 new file mode 100644 index 00000000..b5ee00f4 --- /dev/null +++ b/doc/html/_me_mega_pi_pro4_dc_motor_8h__incl.md5 @@ -0,0 +1 @@ +0461504cdb82475d8da2f0e8d64d253f \ No newline at end of file diff --git a/doc/html/_me_mega_pi_pro4_dc_motor_8h__incl.png b/doc/html/_me_mega_pi_pro4_dc_motor_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..d674938bca076d6d87efa017da3c47b4fac11e9e GIT binary patch literal 46667 zcma&NWn7f)7d1*FjWkk%ba$5m0#ef5DGfvCAR-M4(kb03Eiix#4bm;mNO#wJBhUXm z=i52M2l&BoU$w8b*IsK+_N1;XrWx34B8_ zQ;?O0dwBfHZY_+5gL?@lFa27>D}8s-+b`X+>EUSPOfj*Bm-S;=h?=gx1q(Xkb#7?A z?%YQjrlR-rimB-27SCB_Wj^*`NfW(Jr1{yB=w`NwR6?@S8g z7MVL2J&K&)ehhKPGYnkZ`D`RuZKm9`SIPKpwzn1?0el>UHuuB4OvtTSPD_a;J z6eo12piyED`~4crJo$6W06;_~Sd%*s!oL zIqWDZ3Gr<_X_{)+js7A9+~=g{AB!+>pFh36?yAnbqIr68e`4JI@7K>s-w>Pw|NZZU zNsaFNzv+I)4H5hA?KDzhF-F9|KaiSj4yJS|2`rx8!`KX`7mu!mm7RuCcnSyRMMh?u zKJObWCF${JHgKFs-_2ov6OxgpZFzb+rfHhbT3fLs?eyB|RKezcqyO4XgPXsTn}GE8 zmguaP1L1FA1=e#=I$%uhPk)sHPldHK!^6U)W&SO$7mm|F`zpeEIHe@)TQ1LNz zsGN3oqH*>`;mMw1^zA`r_71t2^ z3aX*aiXly`SrTiIzq{+%&t`o)cG$?7-MnUCL1sW}Q_~MUMQMw}r~TrFxD`GqYF{{P zD|y2>vpJj=YWb95)xv?TLShb|7BY5P^aJa=Vhrvn&+C&DTK17(av%SX?^Ozr81gyY|HxPqh7e;L;4r^CsY*oR>9?1LkUB`|BJI1yph23)*-bc;$-eJ@tX~c5RgJ z&z~3PAAXyU2yrjCWEt-5P3zxgOzVGiudKh+=V(B35!e zLlw5F6d($}@kz0h1o7wIVJM_2RCK>M!$RfEZLptSA_lAyIxH9*3`Puk zp3-9McFA&>*I~S+Q1KPdj= zxWFtWwwiyxLuY9Ux*jsVn~795slQ2b6D(-bPdA0QUOw+p~-=hSwZC2&&S_kKX4Jke4vlNg;kvoZ=1GZXVPiA?q<$@h&SA@^Uh&(lTv+l-O`a2Au%6a$g%@T ze`)@T@Z3$MC$aK(iWMhXFDfN`VpFX}<-=N#!6){|;pUD>2~@BZWw zdJ&l?glz4Z1dZNmVFViTE~?E|$VyujsXYO=zn0-%hk`69wZl@9+IhC%`q+)g=~$hM z$ZUbX1gz`7sFhb$2rD7FncBPZLpM(q%0fIxm@;AYw3gTDHEeQ(7`Vqe5r5vDmwCqf z;u#nV!jmEO62q&a6|CuxhAJcdnfWP>#uyTm0@BH};Za-E4~83BYUvpNtb;f!P%Eg; zaA6kabm5(uZKZOT--A@Ql}QhoAVCuFo(1V5#NXyH?lcExqm3HHO_n&v3FZ)?t5Jy9 zaAuNZ!?pscSXx57sL+x+yAMXZi+^@1g=M5sUi>#Ci{{0pQ8B?1qOyR_ROad}viffL zz9@g@VG{%=Xkh2vZjSwAUKK+N_k0C?3kcyoian0#Dl~&@ZP+`0ZE(D5tQ*p3 zVpPqxH5I(bmboqq3BiUg)uju zW@lLZeQ}&fRH4Va$nOR_N~v1*;aNqgwNtPUsJGLY84t8#@Jkoja8yKwB0fMbGei_@ zHUwJ5RN072l6?OtFrC*BtT{uQd7vibP*Vth%777{4&jR-__DEgFQ1bRK1FFSktVI* z#|}-1j_0Ol1BXiJF$%{_MOYezGA~S_F5g3zeOqG&KRQLhzx`!5j8oj&nYSwQw0gh2 zFVe+&h*qD>JvvRTdcu=I(Fyexg{rBVx_tOpd0Q)bfex4fC5~Z0Ydtwx&t|@P zM)tnXd)g4VFoCNh5^V(3CLW2(45vxOTE5m7JB~|fBnm;dI=y+R+`jxRlO9T@Bg@WE zyru7au^;k+v&?wrq+p(qoaZ46E_X=2BHJ%&P4Q)a#Uf%OA($W@4nnDaQ{o(HxYvb@ zYH`p6r#vM_Q^!rUC5}zM_FN7X=JoU|%c+I=qmsA)lYU+FA6}64>%Q|?*2ETF-~_UC zquXkc{W?s94|SKtLc38KqL^uC(=;s+7opVeZK4FMS)n$~=s^ftK2e%yJtv}8ln!S! z+$2w%MOrYdvnpcWYtHV>ewa>XT**;i&=#eea(cAS3qR7Zp<3^p)A}{RtVJGJmR8fC z=l6_w3T5iW-#6}2#-d8?V?3;vC+Oahf_9<+x_&|o%DS}e#p-CoCs~^>BuUphjn+@^K_DKE%FdC zsh)qCfCIi3j7Wa}La+gOc<8Q<%{jZMxu*d`>U@s|=|y~#1=}GeS*RrbUen(aqOXkq zak00|c;Z}~6>cy|0moj9OJ(2!%ul;mGx(QC1&j2RODRWhuTujuiLO?rg<(cnldF(`W7@TO{6-7kIgL5csn7H_Omo z{6~fnYY)!vxyguqz(-oZU@iMTpUP@M6; zz?@@+F!ZNfU^!d$)Y~smKUTcS#>M8kwAqZq36VsGt_cv$x6`m0NY}i5;>);G#T+Bv zkXp!+K#t56~FGu zUAz(1EOQS?H@OlCP*LH{7llYjFro$xj=7b24ja2lUM`3KhvAVGw$Hb)o*-Q6y{s{% zXPfM`TUOcW#un=%bjN}RwjZH8dY%~F_j6(Y+of^DHp%Apk?#<7$cVYa1QyJ}XpyhB zPZsvo2-$*jI4agx80iIk9vB8@05iB`Mj?w<`@)Z4cE^uNe@6drAVrx@h8G6Ny9dzd z+3kT7anDGGM)I{Ch_^ePhtd>uAD}~OvwvmrbH_5&!J?o5tcj^aXQv645tOuu{I(XM zH5VwtnjESmDq@Hv+2O@SY-p%v(5Pr-vQ_Ia&8YgnWXmnB!FvU7b&Hg|TJ=eExbOUf z=mr)g3-jt*lh33)wvl`F_AyJ^=)QSU-5KI>Z^Wq}TiEzP?P(_i8j_2*X8IKF{=u40 zNI@lRjs*>YUb0c(IC0$@h>YHoepsRDih8=Zuh}yXDHa=lrSo7>s)VFVv=8nNodaVT zak|nrB&%*h`_8(jzU>KJ14W)&{xPLQueu*{7@`OXt7oCr#Iu0ha=F>jD=)98qm=j# zapmh%-oG~J6jj_{O;b6LKID}E@w|xY6dSk3f03S7qU9BEiBh|8CH~v$?b%%2gk>#| z9meC^l-f@0f^!#B^o(sUEPZ3_-_N{C19{{Ux7nqeyiMpjf|NprtQIu%?MGw{m)=jf za3_tujF#XW;qoX z+4Kk_KQ^n8W~Se~+wR}}YA_g&1?*=FbLuTz@H+u35?g=JP0g}MLs1`f7*MC4I{Rn^P0Uy;9OWQ;< zhJMa_Mt94>i8S&wwN2b7mNwPAHjO>i`0tWMF{h6pR;H=Py9V$BlrXlrZDoD;Er%a5 z6c3;iZ+}yb_)#V_tt;_Rdcx3nGGBJDA?qKlpW*NB^+phpX8(7u5i)L$;bKYCwe`&c z`!~{g()`>8b+*5_njf3k*p^nwUgtcLagP%4I}`n=7SZ*RYc*fa?YYmj(KqnAyti*e-<9C{B$rb^{gVNUo69jTr;kFFcm3ey9!Ny zcIbqX}LSMNBU^KN{k5I~sB7Cb>cxUa0_3hn)N6)k7mlraOcCjXU-;{w`k zaem0L%=ljGeR4wsGyXjcH-`7s;`?bXR32wcRA&YbFkv0td7oTl!s~Lg;seUOBG)z6 z>}PArQFhz(^LMJ#^!oMT>K)jq^(bnB9L=NTf-DqT$Zt>nOQWjO>|A>wP zZ>Bc$VO_yk!Sv}Y+4P=xaje3Q6#;LNqlAtsL%PgE5N5^UDVliNnB(xYox)z>omMiY zE=5lRzO(r7DC8ZF?Nr6aW)NjeKWf4wcZ}I}V1fdti$fC0gDr^r4D1dWm*m+h_bU}$ zukNTR*ZeH-1Z>ZDCX!%k%M?89izlybZ%!Ec0Un-8c7kPl;TKkmGN4k+Qy9|v<~mw8 zX~8*4Y=>c9g5Nz_&Iv%O>L8c;E?7_?*{!`44K9tzEW4uYE007{*%yKI}K~lKn&rzHP678lF-KcqW>Ls1` zwj8Iv6lhr(x4$!*&hpRK?lUFGR^=-p#isbCu^qc}cxg*Z?tO=#P1mLRx&%RI@v1_p zSMW(wD)ofGVK=G%Sw@~Gu3mbJ^*uIcoH;u>Hbk4_~3wk#)Cu2-bi)7A|i_5mAiz>D<+7}Jh5hhs;&j|-JmQhXC;GqA;?EBf& zf_{k!-TMJD{f4ElqH@iTJnRHk!R6$O+cOv92GA+2t_EeMV2xkkkA6d9?BAgun6#SF z_tobl#yo}n-|3tkdsSS9u+;a4itOTp)&`=Dcxhr|(?D`0uF1&cA5UDyme$lDJSedt zhsho04i2Kt&Z(`Bu>^iXu)dm-PX|-`8fni_wNRkmClPx=jCR82;RjXJS#Q(*$s=|Y zcB>h8`a=5imUf4kB*owAFW=f4g%5=_vwyA7U_Dzzgc*2lS~xayEnW6Scb`|vVZ_6i zHqQkUi+A@Ni-PcyLC>6@aSDU_b|ATsSDT{mC}S)9;|uF7oxPsQ^fOV-9u+`+qdHADMqw@Bv*OFu zhTzwek+E>)?JKf0IYqt|T|$_7U^f$pKa{QhA6kl;Se9h8uhW=BG5o|cnUI<&9d&zn zTJ0EWf;`p1uqLFMq@f3ay(qIH(DMfEM*m2{N+wt?!B z1}FH7VX^*MZ-)x@Et`VcgexcR0_gdeDTDr4BN}aT!dSH>wvH8$tyhv6tN8L?Mg=}8Ku;Xdx1p+h0CIS`mX7@5G zAKkg_L|xx+AYh%S%3vl6PIudvf^cE*JI<7zI+ky1MOdcG%`H8(E41kE2t7RnY;dBJ zh1{$8?+dL`%llT;@t*j=shoGPlcvV6X|NN#laQb9OMn-b(X8NO?z=U58e)v2c6!tV ztT`Uh1{SewHU^#g(v0apGQXNIbcMi?+2^op9g(E1p_+9y?_gqk<6i+3^AJ`GQRoU} zN>b#IcS~Hdlry!90LS5{&kx(`gKz!TYlQg@5TE5$KwVHj`MdBR>`*-Ef*X+GO@mSK zk5p{QCOf(8<+c5vvi=^jfC4CX2g@F5f;I@y@?puGm?I;Tm#u_Ed(}$6kNd%P;xCXo z5(F0A#=*LGbioRRdxn#e&z%il1C#6Z*y5NR5IacF!j>Zq)$KL4BA+V8!4(`a6^%Fv z>*(5po^!zx+0{^cTo6*Z+Vliw_m?g|k~#f6N`CnaWuct|QIq7ecEDMw@g1a{;|Zbb zv(1XBJ}^~41yLI55?09&kMhzZK8?f{NV6A`;!y@% znl9XZ^FG<+lQxXRbSz}>PeUjiTS-IFho7#*x$1D9Enz|&d8`kYIYHPUK}^AqF>A{i z1aHeqdxY{Z5kLX*;>ML3HV?avl?4S>%`HpyI~6VGJ?bPAM!tJ|gS+2KN=k5UZ{mnG zUq8ydh>KC(ZL&s`OVwZAMMEHfGz87 zXfFSmpuz=GCt`uV2m=)Veor;zw(Nu{B9zj{hFyUQ&&aoYCrb?Z&L9*J&3nPxbu$ey z41SIQ;(>g*zf83Z!<9&iUaN?%fQFi&%bm?}_gFsCv@iJL?Hvrm4e{*EF`a9Ll86aM z$pIPBWf~hhd;)-8B~S6Uo*wu@SJ?9}44Rq~dRXx9Qx>!ZPoL8D*0SRfJ%`H1IHrO9 zu!>p;`FmqC3?P~m_O((DOTh=`8dHfgDmm=((%0HUy!z_KX2d$Z0sFVuYs5#iu_MaY z69BZYlrpchz>7F-39DQj%z{TZxBOOLhAxTK4g7FbbdfQ(Ap=~SuxDGj{p#{S9K2}k zK5nc6J%ED>e41e8%I|le#6yC0^)rsK&GgU1l^s%AF$Ys7|4t)ul}K5;Sav4mo9y4> z`3i1dTX@Nn${uH(;7Yxe@tN0>{Wxw5wSAN6y0!(E$p>rt?Zsb@&p~;5xH{5u)A#(F zxW&Ij^3}AwX7u6|O!dh*wS$U0rii1uC#S*=^oSHm0?sT@3!G#vf!V~jhVfyTm?r~e zq{&9J>pe{_x^RKv40lP?emvv)K)s*-isIhk@TX9q`Q5&YJzgVaZ{mK~T1lr#PTyi_z)%)t5Q7 z8^nECZT1ZeN>^QzTfWRg7JiZ>>r~Om^}(Vy_YFQD4e{J5x>EQ%06V7l@HneYRHf<2 z{SEt)@cMEG?&&Z5Hgh|c0kF#^xwdghwyZRN*PvbG-ucWh`7=L!!9s|4GxwI}2G*Yq zml>Mb-&fLX;h+DdcT)aUvw~tQA_bR*KeLS#XBLo&02H?BPevidnCPU=bb%N(h;(t+s#d7&UBB2%R_+xty|}gG2E5qOZ+F7!p>WEiVaPXz^a zZx5=JaptfU-5q1PZ&3Sa{}G=Q?cXh1yT6lM72Gg6&ut6@_BOzTA#^ts(*$gZ{r_x<*L{aKA8w%VzY7q){}FFHnO-Dq zDV&bPMB$UwBXd^jRx`GsmOyZfWbljW7Hsi|6C-r@r&;9lIkhqJS_#4Nzw5-{us?2# zF?Mn+Q@U$rxH!u@&lGh8{iu1=e?NcHm8T+9xqO4;1xasEX9Dg_olr2>-*ADeV#iye z%d?_4ZJY!Rnr=pmznj z1=JIH0?lN}ZtjNsor#&f-G2WPgvEOi;Mg?yz1^2ZvB*O}?;OIF`cLyn+*XyuQP+r; z3siBqK#f$!ElmyvhI}?eU)xfQtuFR;ABX593$b>@xi9S=r`HT`5~oGKs}{@^l1b+;F*Duwi&UE;fQ25 zoNV5M<(o}At3P`U-3S%jYv&R4?HMGn36=UlX~V4Ef>RH&$@h5)k9IouUkzHn&h1>? z5AR{ahNivnfMzwDjpehzmU%b;rV>tN!(2w*5sn#i z)t!!CVmlQjB3fl{TPZdpQ&fB!E4eGUAi5N=F>I@v0o5;KvO~tTsO?u`lECH4e6&Rc zSrQSUOaCr?77xI*@Z23}D1_@>-0z!fhgtmj+dRzEURZ-b_8;ymwtMOR)sfuG8IKld zRVD^Gd#5)wXTcClJ)P?Gq&7flstlhCh@{&LpU$bZyxLB6by$PTFEn=AI^Q>%o)-4O zN4g5iHx{_WmK0stak)2zg0L&!Tu*;LF~BscS!uv|D3;0HeC2R8S8DGex z)`B8F8OKjUJx{GQQ6iK=7{xwx{>*=A1-kIG9*nM>9h+{=|EDXUl*P1(mX{mEe8n-~ zp1C=8E7IH5FFd}g>#D|92i!Z|2|jtp?nDDY2KO;doUvgN6Hguwj0~{neJXd-pl*epazTzkT|E+LfQ9R&Eb0 zX|@%pMQI+sKTRR8Kks4M7WOWzQQnu}P7V!6#R&$hx|MUfpo>Ha^O+zSR|t4AT4=FPCXm$)J2SeOp40%SX|%>zg84}&H0b;qJgj-)%?D?DOsROzQ6sR_G}YGm162j`(3En z4KZhKO<&;7VePF4Wu=^trGGV_jA2@@^OJo=Cx}sF(J~fT@^=FWmlUO zIZ`^fx>O|Z7;OzLuy2`E*q=mnT&uShgMQ{Z!1oRJ@l=ylzI3Jea%T3kFk*Z505Nhl9LC~l^0UlB^O zhx<#fMd!H%uWyv5?_v*zEs2;YVDPmEacI-u3G6TEEE8zc-?9KQU*Timus=1eSX>JJ zEA3;OAWaaEqn|$`$5B?sX)!j|K5YZG5Z}0yp_$@vpseK7O5Jb^G@m%Oq-yBMt z{*n=dnpo1^=APWs_Pv_QSrQIakX-WG{ASS7iA>tupFqb*XTIvwo~YNc*l`>$N`Um>9|FZzL#PB2 zboJ#+Rh~Yh?Z&p68dnvb8;zvkZgd2R-EX;m4PDCF&g;p`E5-)BCxL#&19k!(7!53k z;Y-(4dP`T zTmq6(HKtT`WKki4dQtRc#{`9xyugovwwhDVkMFVj`c7J|)`!@SdKeY9RCeI?) zT8{)=AvVZpMghzU6NeBji-bhG8I(;Xu#W6kXcbo;-CSW%qIgZZZvcb3pT!Fi^Tak6 zD5X61*C_HO|2@-eXZ#p_*2_4c$8V zxHitI{tX9IP#qg6wIJ~n5$I0x{+^LL`ConYH673=5IHM2lK~kVum)3Wz6VZt0VP}z z6@1cU!VFLu)K&vgsLmXVhK(N#X4>C{{~2?H8f+O)K(e-e|7ZxYVOWe(4;JQ^MXCX|PC z%lZH<(RJ#X)3F@u3FYicR|gw{6CguZ(DIb=s86SfBU2=6AHmiCx^%EZ5k#!nz40GZ z;MS{{d)LC}!p}z-cM{o3AC22e*u0}3nGS-6h0kr69MRJn%OV*3WS7Yx-jEW`^`BRk z9!|e3H!@qg@eN{J+DNS@i1d{v=w1s8&N_-;`D>4SVTJN@e zfI2`b0yJ2R^apv{%vs3^AveZHmdK^HBOHZJ?89GS^Xh}IStA2MM_b5$>W9TB|4K*SaapeFw4cVC5t>U}_Fu6P~QXQkMk@@yAQ^k7&FWx&jv zb#F(jSr<)$MowVv9`6v(S*a}An{T}AA|rYnULl&)7(0XMjIRDC15Ty=vDAXsUDXp2&E+Q;WhvgA(xhJDZQM#>u`1*8r4OPc}dH=rJ^0C$C z&+uzU@?F5%(v(~S1APU*qfU~$)=*-*=e)}R4J-VI&G&7}CH90>`elpdh#6&rGKmA4 z*(Wk{{itDKRiK=M)}T`a#MUv+l*fRuZL%)s$dx-79iJ;`Xus)7_56oxS%>r(m27e~ zB`hG+(u%c|tv{#&PrLC_@R4^XUqqs?I<)F-zha$0@^_9 zSU>!Co+%RpppStBXE(8lwv~|8gl@PWqEn|C!GJnn>@D?JqLD0sj~Y9Y03-LR$PSNm z_a76HtJI{sgM0%ab9S4ed8eyOjAlkQSKPY-Xv_4h32}|lvtTM|&i{_@A~8lrh0uBA zBU-&U83=HBI(li8`I0fnEe=Hl0`#=)BWt*+01sHVs(`I?8W5McO`3|JVOyjAZpyymebP+{c7tT0SN0o>jD^(P)K1 zq48xGfnhSoJEH%$<=X74r{Q#Vs&i_82~dUTXUWJ0aDD`hY~X>-gqafiVfB>51Cc>K z*dt@Fn_i=B?au(beEU%Qsp)?>G2Mu^##^({=&itASdgLI+%w`R$y3FNg5f()C4ay6 z2qhvW2AJ6Hf&?(Rs4lPr_zYr>&El-31Bpni6XheXFFJ2{%%;p)cJip{5;h-J@BsV0 zHTNH1ZZ20h&OAVLu+peBR9JMr8Mz#6@t@X-LaLJbVm9`Z>D-Ndv+un6@1kbH;o=+X z7%~_fm%t_}Q-FcK6^FHNMgJ$`U1z5En%ZV{{-i8_)*phOSF%+5*J>C|pU~ctFTcxf z%MYo2Ea;ljD{KE%dJ!t{g=sF#Rcyn-L{*2a1nn=_=NWFK9(`wyRR}>;4~Y}?8W&(9 z(l4U^MHATXdDNtRMSrPJP7=K}IREmyx_lt2{YL|6`yjsV|w1E z{-|0YMn8+kPOnQqFYOJ(DH1}C`2p!LfAbdIOLXb-4M9)A$Rm=IB_pNBfM{@qS$V8Y z2ZZ-`M{sQ$A93j32^vBzYep_F3@7}_?bTm*D^YS`7O(^=HO@NCOA2-?jvlQ;n{5BX=s}WNKfFxH*%`dHw;g(GXKez;@uD^O0>qF z&dI6VdwyO|Ia#yNfTJe_&nUo%JOv*~K{Q2tBEsh}oB`xhk|wcGTvrPd@~z>oc`674 zh+1n4PKVhY!Sy_`B@ZeWmi2MNsLF6{i&^>%GAJVdD$%k0|HsCKk1RKijG)%+JGWu^;lTnB*h|v};|x#% z@i`E=@XyNXHQvqZDX7wA#%5V5TitjK-)7>V&L$O;+>xDUj5F-VAO57_f~O7_uzJkV zhhA-dJOnRtitLZq78>y{ z)fF%{A`9ky7ya!4zk#nNOvO{2h{9`RIjD>>@{iJ^jHs_4jtGO#C4aGa`RCT`ru{y- zoqLO+1;la~+>F;kn`YjVb}Npfqibvrvj8oy^`&ch4;t;^Ynw^ zgPc&7KH%vB1yir&lhgl)Sml~Gy>xJ9F(b=|WvLSA(v>mP{>EJ?AKc}1?6JzSIQy}B zwEAy;UfN%A7`%crkrV!Lp@HMq?SAd}`_c0+Jd1*4jBc<*on95!NrPq<;E=GbzjnCS z(Rmn6^{8C(V4uwzuuXJbjlc&W-2TiD;X%oi-1)SnLM+%d|M%x^sP#AEe`eOnUK{45o zZG>);hQc>(-?LKRSjJ~y+&LYpOO(-Zg%vkp%G-{Up#5)yGuFo z9^tm%RP#%Zd>#H?mg-~;6VQu9ru*yD;JdtduxO|+SjGWbStmpP0t&_oScoeqaXRtvm-BwdW8uK$9Dof-G5=Z@9+!jrZ#kq;@!v^3-oI9UUaPfm zY&WBP1l*yGL-pkzfC`R6FFajXeK5VgkyAzfG5lxw2|<#;#9%vpy`rr?q93eN$Hw~$ z(V+RFhg=$BeT{xHztS9iz=F0J%a1ZH zekVi>I{g)8dH?m+g9tv0Q?R`L*M3xU0b3t$+Wp7SLC7V+VF_6SevKTp^C^HPUK=*p zu505dht_yi{yi7pV=^V~W)WF!YvaZF+#KO48$^{U!&tVYbN+QYS|o@6U(5cnxhF4B z&kxxddsvsKYE`NyN8};2+Uw<=^xb1-WmqN%js&_KU$8C9y2tO`GwwtPT(2PAVmAT} ztQ$=Rblm@_sZ<_`p+L9M;H0RS>SJYTyI~v5Gj!$XP^>9ysP5T)aNZj3!u%e7SH;JD z#-SM8j2ypr@Rf)`@_J-?;J_u144;!8E(@g|#faC&HJ7VCXbI?H^?b$7SICSPP}Je% z(y0UamTGom_n7UF{$-8N;g96i%3y2Qn#-{;0|T``Z8a$SQHgxjG>IU7Fl-DCp82bD zdZv7w$ZZ$iJcSLgQIBE*o*<_$;!{`rkw;x~^5+^q5?))zQ>{V|T(lhb(!cC{o=AB+ z=UMlo%AG)elD`meDE4m$O-GxFRuRkF*!t{sMJX=Pt5|+xvMT0ZUOgt@ACvNrEzcxE zaVlnt{EV;skBv*aT1h-%`8H)twbr>6Jj7Of*Tb(N84!5WUip)O-9G>k3{QR3#lBKk z0Q_vi2-3ZozH#V0DClWaEr#oEh}dxh97MOH#tVC#A1`kEOm#_WyaH1AWDQ}^$2fVp zEDBnc?2ks?BWv_q;q|54o?E`lBwMyRZ_!rf!{;)I+@ zk3N)VG%^W83VtP9oiPBda^L<@SWMN7>tjD+8<$Hhe=Y%>PY$xG+csV=gvT-I5nc^? zk3@sPP5KR>HA#O&Uf*IWqR;6#e$Tx~8@Y(qpsDip{HtRCHea?uS|O1kA&PAQA6plx zP5_r%e}52YM7g^*Z~K$nG;t9b!irMQwFU}qYUm%_5T~gRl80>NsbphNB&O7I*7LMS z*9bNF={%CB`IxR}DVtlF=CW`Hq@v4Jw7mOa+rJ=Xt_}T2NsUJt9rf;NwDV7se@%9= z!Nj`mdv{jgn=SPCiH+tUG)nHtC_EF6Wvr;Bv=cbz<}OO??lZb`onIRs#s9Y{W^kpy z75!>MQiSOPP`e=yQw0fN%n99pE1P!H1w88!46aD9J*~|)bxt2p zk=%rd{43wwAI55VU`OYP$P|O+5zDvifh_N2+(nGVj)V1!=sws~h(&s_A5 zz>LOZJyrf5#Ph^vq<$R1J9 z3h0i1mYsmq{Wfr9Q9lJbG!5_h;|Hf*6`$juxLLG^hsO_XYMf189*s1`E3v@K?4U$U zMZ95QuFs#+QnjF8RwI5NNi&G4syZR=P**4Jpr^kx)t$A9#~t*MrHC-d0_FFqcXLtf zFN(PmcX+lrGfNlhzCp2e2`e-6!Qq94ls@lvqo3a_HZ$Wz1iA)O4uqCQOB7X2g`MH5 zl)upl-qzDIR$gUfUHvFwcAp9iseGAE?JT_2vxoI9)FAW*hPol&4%&@QaSCR#xC3b>;~hqML@>&c_)+wpX=bse zUEiVpm2|7ym&YJ31`3z5Hx6IBI6(fEQ&A`sY7@V5(Koi8?f0awLaDr^SDT5vUJ}Jo z-8^rv%s~@VO}Ke}pZLyIk9yxRf$1fAbQghY8}jbwW5LciNeoX||3UWE4`6cKaMq0J zXylkb5f<=q_lJ_$hOH-d!oXE{blKhMIwG%)&O{i@uY(DFqqv~Sq6xFM*H+85ISb!d z*P4;nEL)bmz3EbaBZBb>>9ZA)P%b?5Pj%0(>9mW8SGr@>(&I1&uC2=^MnwAQax@V1 zrJJNe9;TNZ-urWvD-S48XkqLosI^sRzcIRCNs=>o2svKU30c_G#`aGjwY>{_wo!37 zG#6e2JxKq_U8t-efyw#Y65SaE_q`4>E0gU?(02TWRF*n##E8gN({SG9Nq%hF|imm{lE;SKg-dm4ZqvvC`k864A0liTQf&$%DiceyJn| z#6VO>r36>&HiBK|q^;p%vu&Bn^!U}8ZTVx*cGqIt-#J)Hyy4DTO7AHTSz;+%MqL-{ z^255(d*Ht6$n77AFjQ(*jCJ%86e6f2y~%@#iG8fH@IpIl;s-C})#(?zV{>XOa}g6c z%=hE9XX%UZI|-Gh~p-c=)Z+z=%ga^H8MHe%nUh z?VI+bsZf8-NaO8yj`#>4@mUbbr_ zr%Iz8xy(>65IcB~7OcWWc?b|~)b$elJs1@~7o`jvFItkbai%g`-Ts)46Sl*&7|)PE>`mxhAqX`=eXQ8cLqcBE1dgpv+WN>7$l_e zg{MNca?+7^(RdLeBSL%+p7l%kE04HIYtpb>3HKxCp^7*m+p72P1q`3rmX^HBz*=i0 z42w7{_j7pQE%@IS|1R^ni^FJtd&%tV$=pqN)vPcQf_7&gIZ&N72kdqZD~o(}^IrYm zS-kL_1PBLGn>K!&vDM9`AzI}WqP$BAqw2EMOCoUEiFf_jx9%4t8pAX}>d0^SsIP*T zgz6%Go#8FZR)6uEIxwgyu2Ggqa`i$YS!G-rOju2&;+|ge3fh8vfG8tiv9mI>Y0{jV1wTkq3{3hpL;S}gIr z>0;;B`!}E7v(n05W+>E$ByGQZ*CcE5k+F6c>w}fm#7kv0(`L!{pYl3gO;k-7UD~Z& zQ-&??4KE9ri4l9yME5$+=If8MmrnX=&{~N$&`qpZX(Mk3yOZr}o{|CL+~7vji_3=2 z!0FEx-K)gT6bjyf<}0=NY(_utO}tFcJuIL5 zBAQ&DoS~NB{1G2KfTWC&sd_mSkiQVG(t;MEy%Q9-{wI-!o-O_5LBMUa+jnbrTzKW! z5Q`8ec@LVn-!hCX&^NAeOHE$i@0K@LRGc-fYYPh|KU^)wTi88V{mqgy@WfwHbWe$K z<~_`0#(|5pmAWm)wMrvQ)nz$zp5AEh{hs4RTOoni7KywMP_Vfw#AIvNk$JYIN) zNw|@8#hFy-nzEnHy7|{*J}28C`I{kp7qxL^k&pEp*5HweF^+L8UaFFtH_nzp%ED<2~&au_W(zfg;x? zX6q@f-d6#z*{^a2R8n3{MBgy(hPxHMHogsNDiKxtwtjo=6k}aJ(X~i`Q_xS+V)E1e zoJna(qhjn%jcFL(3gK0d0Qg2D#aN#@@I*jl+=#XUmD-PZ!_OqL)7_ED^YZM#nD+a0 zwn6^8y!tmpmtTXqW-YoY0Su-eVArc?sV4xLD7}Bt(riduVXSpo2N7I$WLov*!(Yz` zcvm|Ogk%8Cd-O8IM5eMo^$8CS?PE}kub;$2T#*nM+oO@ghwsI*KG?3BF3V}s`!)?s z{t#y4041aO5nr-8w*d^0nxRcu^Q;I+C7d2* zPnY$9j{M2XDkVZOF%=&fW|khEY-V6;i~n$R-SBK$P%7m>R>X+6LPGnpjnGe#y6P!p zWl|i9sbpr|cle=hypb>U3cDs&^p*`YU*O)C^3#r7eQ`{paaqLL_%vt&1iWAs+V|Hc z?jRl(qD)q&Gi&A1#>|rbE(fEIMs%*AF7TZU+LT7`iI|v?Uj-T_J4J#}^ z!JK%{e%ze5%LtYL6!PrU>uaMj3MGPB^_Ri@U5`;8F~yJr1Z%{D2v_Txs3n4TX^I=% zi$a>6`ixR@0fsNPI&Tn+BSO{*+mCmKWd_`*H)-zo7{7ZH#vO`e-E+6R_5@Pc>Ce(bU75Gcj%-zl92cQue<~Ey6Mn~^`=<-H zXX0aMZZI!$q^yV1d_vA7HXZ(%ecL1f3Y*x8ewHNExpnff=BI=?Sv=cQzOJE-`)%jk zgx;b0y4wp=J?EbD zJiofMfr`%cWORBr_9(0~M!BdYu zTeo~m6xn+a^eP4+M?0X%em8#vHQu=^UbfZ1jMiDNr&***Nob5BzR#zv6|s;<-2A^y zk3statN8nTAV(wbI%UW>qAC0lCsDVbyvF0)tPs%L%}&g^ccecHG7nx}Jpz5{YoI7# znK0ZUtt#L)7vEQyHp?9sKLZQjbUlp^ZzAPh=x7W=480m5w3ohu&MoM))My;&l66=x z^~%a$b0;9iVq+}-n~lO@e1kl@9eT1d_8F-gGcX9!>i*cy{lZ=qh~|8=^eL1)-;Y)> zmXQjmOfhjQ<(@NzzNm3d*_!`$ENk~o7&H)qc-VQNTh?@inZkl*iny$^Mgs~Im84hq za?f|}8haVFmWUvTWajFj@i^a;i35~qHNu}%X;Ejz=IX9?LDglI0DycDI>HkIrJ6ZJ z+)wUj3|J=r2ZtyK;`hDf^($^qJCmPY5~NECLnB1n_oxAuKydVi6tzSt>A>Yq@eJH@ z6X0reL9KDL)%*vHHh3wmx$W6-yD6EH(#s-1s5Lv}Vnws~g8DXk_Kgv!)i6c4cZXn4 z=kMHofmmh}6)mdVo(DSg;o?AGZADpG_`dn{tb5ky@@*@aj&_k8V~8_w=V!jv%r5ib z+EZ}upAtCqudA**QdBdGWR2@0hN IT-%f`b;pqmW+rd{LSf^g$VpxzYq%zgc6LR z(aIbnBbuIbwrgqKHWe>5LN`L^2(%zi#P9_P%DjG);{G93G5Qk^ z2ppQ_nELzbht3A#H>dJ}JDLj{_K}HLS|GHMP_)67(}}_g%9%Tqy!ps@K})>t=^f{; zSu00z zJW%k3dR4>gTw-6txi8xiF^ulj7*le>s3b7}CBzGt*UT#(ZPS|=!5_xz%U@;9-q`p^ z%61VO0@s857D1BY5$UyWK&>^ujX^=Qh*?VVI@vknurhdn?|%k z5_f3j930K3f0|k#$!x>(is1zzJ50TwDuO}h(W9Y*9p^dh&PioEUVj@n+KFjhx)55^ zu+j0*Swk`GW!kij9S?21sz-QgkNKktn8{ikAwBV)8f>!vph9(@6FNs0n8Ab3S%#hd z>1gG^m(#e;3juXn_s0w1rkeun7i>~1FN9u*T-q9&%@k5@@rG<>Q4iRWLj`Zb$<1Fu zhq5GAq*2Ee5o$4B03*$P1|8>d)$du>7bEaDO}H$qP>Sl_&dJ0Gx35^Ck~Sj# zcY`n9cvoO2;Ze#9k+l04BP*f*-9KRxu6~^_^+9h>b`XO5CEHU+1y8V83==7&E5s`} zm6e{qANEZCyZ(N1)!JgEI4JX$F?U|5!=UHe*%Vmamclp}A=9S-&^GhzNro}x-s86G)TsOC+ujKWA#E>rK}39h zf-#7;iLjx-6rWvcYVT|3h&jg>uH4S_q>Gp_Ecn6gzuqi{IT)KSg%Gr zGH-Zx>D=GyhYicrCT37=W=h{}N|4Xyi=2ebyi1pEEE&H!#tmFrTHRETu6uJsBkni4 zK`Tau0mC&=lC*|+e(}u{Wb3Ck*>p+1e+Sg8g~1D72E18oP(@u$A{BsLOo5VT@I)B@ zHY47(7L5U2VIP+4p1r=EM36t+uiNRbl{q1!1vB+^o|+Ms*!cwjKk$x#hN@|ejB?Uq zxpN#Vv5(2bNOjQzpY+BFo?6W-E=8^l(nh-W{ZoPG1};jL)k=}RVasu0sf2}4TVlG} z66nJRJw^_sgZU^%I(nUDfa*+HslLY+ji^yI3)ds`ztUZIn5*FR|=h;I><( z4;S*3071L zt~kg@d;=2&P?pMwX)kXP!|fDtHhzty4YI6)A_Ne|EBhK9F~+aARoy^gL=HCVq6m`1 zI$Z5J@JIzQA`=?g1&vAo32lOI^}YoK9;WfsF&QZU_dn##)(C#ai(Oh{s~=y!Iz{6D zornmc?ZgkhWciKu-7ZY)cvO9>XLs0rWgQPJqnXmCHF9|~Q9J!<1Y7(VBS#lMsWfmW z*$!HDDODb^>oDJGY#iS}5pk;kuvi}oNYC<0IztFOpNQRS0Z~r8S!U-*w4TZrFha_~ zEKERx*_cl>-iNST+`|4tVmNa9m*j+wpDtE6-mcydh_%EH&l@o+YMUmIMeo01U1Wo4 z2DJJq7evrRT%i=XrXHm$)l03#KPdTpE?3^FdiC|ssMV21`U~_YyuYZ}POSI%TNJ2* z?J!A`-+#XeE*tQIB+hQFhXmGIA9V`E;AZtAEdg!gAZp}l!%mJ=TbpM5E?0d_D>d`d zzt1Hjq(Pls_Va`;!d2w6^rwg;;6yQEtmIYGnSWugBF@HS~w5(>xb%q?Im1*T3pZr7H zmu%(^jDrunvJu~UIVqM@Q&WUmnfqB)_UsvyJUlM(K%*UlW2tcQR!-X07@V!W$+Ke9 z)6>PEOF6Fi!_*XQ>E6-30ei`|)liJe2A|$Mn16e>f5-4@2h)(Qr0bt(<90PIt?&Ya zhX7tKRe4iXmFnMmMa+7A$EUse#g%I^n6Qvs}>m6fz5^4 z8-hyt;{_9eWlN$HIN%aQ8E~Qbp0%X1YGKr7g2vuj!6lf6CEY~xgAnv(1PyuzigEk> zrt8V-w>T0W+U$y*kE7YI&j-kyyeX|We|$W zFF%D@sNnol5mXW|NqNJIUj8*HL;hSXReP@!KDCCu!{{n3t_5{+hthzIQ*>P4Qw*tV)qW^1H`KA z>3iszT}U?QbM(OFKDhsR{n7T5_DV3oq!)ZfH_`u7{RT2ROR`Ma09p3I?l-=_e7FcP zWk%-28n{1NHSM*IFoh6Hds0L;vnCJ3NQB{f8QWCz4@Z_3Os!g=7 z2JWw{Nt8rb(cH?ifugvRJ^d%K0H4T>P1~>SO$@F9#5wmh0AdBg*7#S0&s>i#cy-z7 zTM&3a@2vrh#brS{Me)BE*4Pz=2sJodV0L#Dw^X;jzA;c7s{eS{! z{rnli|NRWzuET5-#Cql~H3{2KxFgcMA2ion>HgZM|QWlW(;KG{jTZF+g>54kwkO zH>}(7B^=DC{cj$vMcBeGN+*gdsh);(LrNc9RIh!{Lmw_@O~-F}FicFx<= zgBXnEO+=RSFspBaB+2=*LU0SwRmya4 zb|(4(H264-q$$DQ;V#Q5Nm=2$omyUnN z-%EI=$m`X2h^U#m{ZRmeTXO%5Zp>%rw^h0Qn%kJ4TJX5OUf!O{fA^*WIW1NL(5#0$ zW3&TOz9JcyRWv*mxH?_{6^`OR2V~{YCR^9*+Uf3L=D3L{R)kILk}-XGSz`9%4}adp z+w#i@pZ)TF2T1`(zlFR`^FKp8e!eUIThlj(>~Bpe({svMdmkef2d3vdekR{tT>TaA zLJ@@(2dHql{@D${&{Q9nmv0x57w_u6b)~psppryF7=gcf!GA8pwV|V))KhFs%`Mug z#pFvmoYDLrxYKsPpw6w?+f5+v>~ty|zuVo-jyrN}p{qfTSWHW-IbWb^871V~`;Gs* zEiqO+SDe#fg}H^R`l9SlQq5r3gUjvy{P5uZjGc-2c7V9)l8H>NN$lLnH@0aenC~iU z%CY?31saz{KkKGMI4XIm=i4ysQ{FV5nwWdFUZ4!XFHEzhe|`ETFbgi&5f$wb9di+a zD`;(XjulT74U2JOz)3a{4=~2KIi-3;YN??b6sBDa-J8WdJ($Xt;%iLqug2ncqi` zdg`%!4th5iRzDhvQPyLMrTuvF?GEmbT2<<;AD%r0(e%fO$1GbDikZ1=4=#+Txz4~t zFB(733!dX$mCsl09Yp8fI-}33S$R-v^Op)byh*DVnXeIXqLn=WpnV2RPjkbwV{<%D z?B2fczN=+r<&*zBl^=CA^Iq-f=R=G;d#rhTzY+hSjfvbxp`Kid9*wb@c7Mt>NYD9+ z*1}+S59++92iBD*qq?3?%M+>SaG^%+Lan=3?X4?zyNH!K)oeF7^5!aoA-1hjXee`3 z^&YO1;y1gTakb)%7K|%c8Q7XAg8wSjsjNJ5=JI`4$HwKwok{=h!PA{@XWnKemoMLD zBU8)a`zSjvL~zHQpTybOy{AVY`t~9^YSl@~imi7|T@TZeiM*)mO5XOwQh=XZerTIx z$7K5XVl(q>w#AW6=h5bZMYD5gCz;}(@!)*<{fnzC#j`TK`uB`KL_f6#8kv0?X`LCv z8JYt3^CD(9xsU>l;}G-v42Q+p$hV@1E?}CbdYT>0YgwJ_f~&gX2{BxWPnbfCG@6Jh z2JrvWYvyeomfk;TGgo=Uu^@eFJwm|*MW)}6^=E|G1J%H1wsty|LA#W6&6@cWpnqKO zXGFC-xAnF#!iJ>nj@@0mQ zQl@PZcjhQ%z5ftvcBTJ!z4dKQH_t%una}E0NW)<}Pg&5k%H}tP&>kf6TBNaS{uv}6 zCat>Jij%$*rH|8UDM8+(I$9-ZCmqOgobSVFD7w$muyX}(pvkY1{`E8Q z)desx-?7j0%{cz-Hk8MOnLzlV`tqcu&O)3W){YIDg_>rW&`Wrm#m>~8t1InO05dgO zjlRMO3=P?z)-yd!7orNdz;)^o=UzAwbXs2IauIZx|9*Gev%*#H8ol2h5{OetUab_+ zGdLO=;+wmf_1Nl&dUo#Ed^vmWZ4^?tm^?2FlKP9yJvginbk8eiV<)`7H-J?nXHC^f zI%V{4=wf)l(4%;XAOrwvaEoG%?-fi*CzydBCY)i6^|o3=^6`>?r&~Mu&P#68`l)*u z{{A5Z^uw>tdW~r}=jaA`Gb{*tN7*%l`zA7wa&Ge*G&m`DQbtW0{Df$~l<}}}J(ye%5M_aF08QZvYAXKKl0lnI|h^5TY@$A%%SFjV&@Z(5CU2i#lbg#8Y){l1@dJ ztN}E-PBeUQ1%5xnQF~mzq~aq}_Fz09vb3|m7198np>kYlh*;ssWF4K0vlx*gG$_2o zU-cl5k5)~QyvYS%pEHPaDp$MT{^i<0R)O)3N2iT+PaO;=81Ws=P0Q@5%39;I>i+k0 z<(t@<^55!OyP@$Sanht%vJPqZlLOGi-EkZa>3Hht^f!2{U=0wH=3ECX=#{R9(CK&4~1F63O& z3^3c?j$Q=Zqv{thyE%YOO5v;7L@;~wYWVS4#+@1p)xH*n&W&kce+Fi~Gfv@pE^%$j5)#1WZSzqfL3a7OyVmndsc2NjXG)rowI^`-d=2`s~V zX9<~mb`$xd>SCPnoY8j?raI6PDjGVOdw=fXLt=^R7qXh9aXb<4v46{~RnI5#ds8(2 z$L4e+vO5jmAZd`!c4>1{WME<9d#j}GtwHW<-*?h?#n`D7#tdAFqOW|6uypEi;~606 z9(fP#u?FXh{qgB+eMD=u-`D*B+!`t$igAK}gN$eSA1g@TITqD9j0V=5^-fM%n^-=*KtM_h<#KNJz_dpqYJ)D`yqQ~t*ju10@)ru! z4#PJQx`wW_kyxO77XrmryIN5S@NlG2mOzL*8vQ1BpM#OO2NYeclFp6JSXhfUW{ zf;zD3oWU9i*I&}|+LY}C;Y192j^y2K71}wKFMK-PA0Hg^Z~cH-~2t z*+*C%fodR>e196f@`~0)94!g~w}9Ndf_1v-4dr1SdEAg5Kz|iicl8y-mMDOBYzUc` z*MmbHls=1@J*9OCkP2V23w6zztyeMsw@xplwq9|lIlfEjHD`{biPI#ZJDD3%eS{ao z5o3b6?VUhR@E-T%tJG@0T6(G!PxHt zNWYYWH3gVprk(ND=;_b36nG}VYCjGc7EA>6qo(yTqk1jHJVS1S=Wqf?S)Wb-HVIKv}@W*bSL>8jlr6i1l(kJyoU)ZMdZ1Tt>%`*?A8o&@)mNB8{Ys9 zV96lp^h-B%{9CzsK&S_<`ZxjS18>KNZfup92>K%rG3|`!_RPZkY>7zp2PVDy+8TE_ zq^9pkYUc`RQuDj{nKzyJujVG*5yazWnBXVf1n&IGRFEbv_HQ#F$yKhhvEu)eD22a+ z=oUQw$>6XNf)Q(Pqzlv)z!={8qOZ_>^lwc74Z9K7(T3>iAYt~!r&fuNC*JJL#C{aR z1ZA{6_}l{--Fr4oW7(tRESb|Htex~wLrtQJ&F%NO@&1+K4+sQN|C0q!mT(+z=OkWe z6ydWgr95KvQ7HVO+09cYop&Z$UR#o6{0i+$t?Ui1bLq;>S3_>FAmVF1&@RXRpi3uO zYUKzA*G~DTR?e4eV_AS`;FUMvtwvf36X}`a9>7$oZTODs$Qh9weAgAv1fxSY*Ws#P z5>Yk%4WqPB8QXu?GzMRiKPb^;XuTl#>KrmH)7@g}#tCUJ>i7aRZVrwFGD&fPU@ zjz`fqdQOK4AA*Okud2s%o&yPtfhfimN|%8U;~aHKc`MYoCr#$1=F~dhu8o2CEFd`) z1|!8WX5=RQjmGX8(RLoz@NMTJZYawp7h5|L3vF;9^sFav$0Ck2qsS$UkI&eBMXk{Z0;NUsZ)PUkWb3U5Ih^W~Vnj6-i?edxkyUwZP_q`4Y|uD_Ka?&Dhqx z1Xf0}!TbA{6FEvQzTL+pgwgxs!OHy*9iWU%9sB!QsO6>wGUw1rmqL+N848+9qq3e| zhMsf2GOnT*58bSd7Bq9?$Hs9yh(`3a>Xm2q4iUzy&-Y|pYpd4ET!GVp()=t8%SLd( z67=k}!1P^6tFVhT-j-{Tvxa_dFi2@aw?j_*{8K+=bN4wI*K*M`p0R($*lC!Y7ybFk07HNt&= z;@NnrtYme07-KU6oV)sX8ARxAeSz44mxL&7rw*zxB&Qf=Z-$w9xRAZ-cvmv98Kz)t zDy2_^0Rsi@yo)3K4Q0DzcJWb4;SnHQ_rVpxoBfFJdOCbF9X!Yz(GRrBjM@sNzna(u z5j@y&n&z0huVYay9Z#KBg;#yTcaZax)4q6q^PW308lxmrI5f!3>{hwv;9P@GnJgOl zT#**!B>2m#DPq8AQuGmC;2jsZ zz6GG2Rj@LSS|G+&8ekqk_nm<{AZHVU45@r>mi2<179)c|{;1w@eU%_ij%1&?nE%^a z?-3fay^f80N(8zch51q^^*##pWH#hCP#2xMDCwYhDK)jjtYr5{Ph5z%#lLD| z7J}wAgR~_8tb0bh+4EqZkR?(bKpy%F%+rAEv!mMuG_&2yZB&37U*i?xM5_;5kO@Ey1Gf)RfmXg4hr;2O z)v9WSf-IC@E;`v-EB$+l6!u#>u+iZE1B#9X)y8~nOj#3TI>J0eNpt`sCb576Qcymb zeT*r)_2_Nm!}^~H+a=+_dRu>_?OHSe^(SlncI@A& zMUnKe_Y#m}Re>T|=bVXl?PT-Lg1$D^*!<{U{!g9n%jaPdyEWc{%_KmjpRtjCs(y(i z#&Lxi6oW-JFd5z#5=`i)k}wCfjWeBnq8;Yq;K>rbeSjcbKNEz#i9fxDvyi1`2mX2T z_^-9|jR?@6djCu$2s?Ss()}os6<%0g%ZbPfF#tX zWfu;F6gqZLX}jQ$VnlOr`l%^>?Gr*E5ysHy^Y-JZfx0|Y^v=~Mk{@_f13ME>Uk5+Q zt}`Bj9tjA@jDrB;Wsrg0+%tV(?89xv99=B&usKT#5#((@0SE?hw#uvHy+QJN`+4BH6g_XyQzL#YkN7(P3%M$w z$|MgW(3zm2@fUX%?G_FVqwY;?<~3YZcV`1y6#r{n?JdmJ$oiMB^-o^{;;pNdG?#OV zr2PJ6PDnHI1xIqp3w;Fk=-Qt$Cg~V*ZS6veAo{{#or+qlq4z!K{1I~G1FWt5=Q+>4 zR>i17D-Vr-Ey11NX z!M~FG>=@cXjEs7v#GOp>DI8o3%WR?%{`K5p%DRA?1Go2%rtRmj&}4X^sfiUJNxFdt zcq00BuShoPp9^^AW~@UbW6#{kCv;Jougsn7yVD{)Z}jyr)#saI#4QdD<_OhnkYP)e zoq1aEh8i?=ce&b}w?DRExd=HqtlPxB>^5+iR`c_x#@Lp=T5~jBRZD23Dul8H+sU=fDry-7H2DAVGHhels?&aX zL~Je%1hCIV^No4`1*nCnG7$aaN8aai80lNetgAZ7t+#8gmSrX0|NOsmBRwwP=4PG# zEz{H5Y5mv!9GX{uD1nh(*DfGzkxZfHVykXz%OsOc7iuC_*NBJA9t^cPRf`Xcu9b=? zC>g-zAQ)3%3|&f;r@W?hF+nF!Vui#JI!M+4^yG3w2pq1IG8OCMz^^9w>zDzJ+yD)p*dmJoIz&M{>vHSulBU!0_ z#&%n2mFd}j<>edDMXX}mX!k-dLu>@y0QtUz3N7)@xRp62v8l{;ym;BkpY-FmfFCp9 zPEVAi2e7;a#THi|-2+WXELsW@2_^s!FQNciHT2o|IS&(uFreT&@rPvfM9?Uw2VSiF zg!;tz({ST7VdwiQkA^;%S9g=)c?Nu+P!EL>DrFjQTLWS5x@xb0j!r?#;HD9_hyt>x0%~*OFc} zDU1_dVAEIG+cbCq6^MbV#oC1UWtwhewK&^8@41ihmLceUvxCK0QpL{$FT=a;M&Zz?W@`*Q@JF&BXvZlRVr!U>+nf|l$k^u<~2 z$_?ogkgQB&?Ww3qBm<(eBo-pcb6?k%Ym7)Yr{5x_R=M}+#Jn~(Uj#B(yKwiE>u*bfa6x8?v;!4M_G&FUWB{-8b;97np&XGf z@`taB5y!^+^Jq2TAKK)Sne+NTejfT`P}KY*^4p|9?WT_xNlzZn&}*T2^3OD$(iD%~ z_?anxAx?!Wo(B6W?Y+$~Q7s$S&Q333byE2LTX=#BW7}Fy{t&7XiS^ z{7@kPc$7tdw)Cfqka{W+=*Z2?Q8hwrWy&Ia|FY^X^)#i1c7*Da??Wou;7qt>^}h|} z1#JDd;UIxGZP3__@z1lk@M{9{H)oybKCoDlvJ-%(CTm04Jg6o|dM(YXnTu`KdsPh1 z#8W)>zP#GHh2uZELkb$QKeqEV_Y6BqBA1ud}s$RscnN_UJnYr~smS4;Iwv|)i z93@4sOLP7(Qa>S!cZ=oWBZU-MDty0Me*Z>=HpLHOPKEje8zkB=#hMTUgje_{`ze9qIKL`k%mj8L5 ztIzjl`E*U5TU@8@ZS0blu<@GOvv8R~>8ly8+$GX#1>UHL4fx^kyru`-{sW;Z;q{eq zcqF;=-}MVr3Xr!Ts@I!bdZqRKYoysjtMH)c>P^?x+Yz#<(h{?JiE{d5YJR7RqRCuK`w=EwSQQa*4C=`$x&%(K8zKSOCKoYD)8$WtD zR5tQ{Y`S;v-}6Dcz4oAP;*a|ll{z?F8(uYR7!3UkXo}&qs~TGTx{U799uqNBZLCev zfOeo$|K{0o z9xkG*PC$zpxjI!f2OjI#O|C@Y@U4pe!7tKL%R4cxGRCD&4$b88~?V7+Zjmdzt0ce$pik#{Fhv7Ig$!-gHjfME~1p| zTbd?#Hh_1T)v`)=fFx?U9RoG&9~C4s{t4v9a3gRi*4>MN)2XqET3d_riR?$SNUAMB zy-i1#v7o7Vw$b8taRDLt@5?o)zD8j7VPE9_B>`?)nbMpsK!EcOH?pCY4#vo4fHZqd zu=?Ihbk=*alIL0AceE<0igR4r_LsqzhZCjyhYSU)O=+qz_|LsBhZO8 Sf`i~MY5n($3D}PF=#2st7A_`k5B-h8Wxf{A6zWQ2 zaP|w?6Qw@@c=(4d#HXB*dAbqrwun_37v(&E{e5h!KNgwb0@t=`T6*yDh~os+Yk^ZD zjpc8nr43jelcX}hx`S_V$ujE$4)vrI7}hDo{yAWj}A zGF^`Vj#wk%ORylzyxhQoHJV2gicaTW{RXTI}uJ-LWf5M-LV03tnSI<4TIc5nup zvk(HaA})40aetn=gB!L*w)wFN$gH@`tIx2kq(!(zu=@UG#ViZ$FV>W%rQ8Zc+ArGF zLtIsC_6)iblW;A=O!+<9Nz1`(rMusnt_3h~<_p|{egRG=ptKEQz8c|Z)j^1_^6xwD zM0rKbiK{RcZ#>{zDG}be8ZJ$C}H(a<%+&%_HU0GI`D$=H|WS zf0wHAFC{FgNkglI{xU_SE0Rv6UH#5stRKP-U2FA6QKk!8|NVu{e)cQ%zpXNHw z|9;+cJKf0NQ4xHJKxC{$*iuRO733mQGaX|I)%yCXo|S-?hLgkdbcXZ#YIbpXUU%Q2 z&bJ0VGgvE~aXv6G62cMBcQ3@1OJ>+onjJZuD&bGBPbt=FWgF>7i(NU$U zqvd&Joi(k@hVpV=qU~A})PmkncoVGQjA3Wl$5kH?UMN2-etBHNeWb@#LtvjvhG*4@ z874!cBmAJCZehf-I#I~Us!?*1`gypoG2OPmW@_u>$Xf?Eg6`_j(Il(5Avv;;fSqHM&z8&cyr+NtI-sLv^2LpV2L+ULcL%0(xl&h8xwOHXV|HN;DBT+bjaaQZ zRo-K*v6!ax+@y`J(7keaGR~5IP3eLob_pl^D=3dB{V@J7Og0B^*5yN#P(O9oG%;NN z$L8U)W03OTVAw0bM21G#W=~oHhXfM(^H!;S`-#t)$u8H=a66uw080zYi*fJR{S z?J^6Qj=vGvTm3}t{d4W?`}&)YRcUp2xp!JyMX{V&f6_2THI(Jk+GOOhQyZ2dg&=*f z#dR8p+GHYcORGIe_fKAb28f!AZG{MfO#jj;?vs}Z9R=0AzMi5|zwqkMX_4x#+-teN zZv!G0Q)5~I&tCg|)+LgMH-9DhmsTyXB4jQkQR4H-HA;`aXzEth{Z&PpIIU|@)cs_v z873TG$lKsOB5|Enk(8lejQlLs3Q?DEClA@bQ|lECZFkwgt5!R-WXBW(ehesgf5d?f zpnCZ@Sj*v}#=s_uw7vu9%|Jfa5yU9<>ctSHMiZo_MAvP4(jJCkF*pq66%`fj7f=5A zw#zE1_rv0K|07OgVu^2gNyPY$AG{Df1!QMmSYg=@7x*W;?MI=UHt%z!EHLZQ!*%Ge zqu@uTwqKT8ch~;Vqn++FGuwHew^i`wxaZ1K4JC$rYmMMLz*b2KHNmIwa`mKbU`3Zx z3vzQv%rL)C?VzLa>lJ@D#trUXIbsu}@9poSw928S2$fQywvCdiQI!qinnmSPlk!wu zZlVMJ>z(j*ZJvjQM4ZMMP<@F}7jjbwgkh>&U47qEWd%q9ycHrps_Oq;Fem)k*>XL{ za;N)3aZ6Zgbr^k|<7C)~g=K=og4gDhV7b;{$Ww2M_ugwp_pN^GsJUM)vpY}lhk|cSQpd0gkdS57x$4W|8$7C7ruRUvQO_#bn zTt_s6pNgbG1Ji>2{l490VCKX;%(2K{F_pDoEP|nT11*0|4W`j9OslhB@Xi9wR372YG5vRo|TulD|U~`FAarlIhwn!RnWog1|@>*H7Zx z53*sr6kAde9I@)jH33`>BTT^Ot@p|m49jYt^YL+t#JJr>P(<(`&_cu3+B?~xlNIdR z7G1BwYLLt_?%x^D!5v_jd~UjSq)^2@*PhvW5{nV)F6GL>gOD%{<*SUxVQ=6N@Z0-q zso}$lxNb1jLG#_bTA{*D_u=jFk>mph8`;&AnWX%614@Un;Js>R3Wmq)RCJ%9az9h1 z`SGReYqPZ7?orEqkm>Nn<;~&W$wqsjKzbw7q`5TW7|#<3=)-4=A;2Va#9uQpQ`gb< zG$UM-3QyMp<*|_4s$aSH1Zzx(4|@cNrxH`phE`q~TB-A7E<=1*JdcKf?^pD^@XB>3 zIoSC#w&(P;Ww<1OxYIApJlTEJy%fTk{OA0lNu}s^Ha|RJdddW{e@d60z*DJ$@L2y@ z+Wth-LPgCj#Va@o!;mDek{2W_mHM%Qb(|o+^Ur`lV)oxL4;9bG2TRw~=_Tl=(YyBY z->xjU8c_{xYNcVl^qRUp6p_Fh(WRehh~$kF*VbIlA#8umjalz#T=t}ubg)}d;audX z6(BCGVwJ07TEIB3t3Fzu%)w>KS>$HE;@LxeRG}<8d+i%jUbk}ho>DTyH+f`7;cLxu z*70bQe5L!g=n#uhH@WliU}0>lqkH9{NvD58n_{mj=h41# zN=ibW*FyFJn2N_C_a%xS_3W8vDk~_Bb$)D(T+w*a(S~7IB?rsvuM{2{ZhuMc3I$>| zb9y)7ATzRvb+2O1Z7ae7S0YUXjbsRJ#RRUTmY33-2v>A6D{wfL$M0uNj|rWMmAgZI zGRs2+@VME+)DDSFSL1EggI3qLYT#ZqlSz=TQQ5gy@`|rWAicI}!!LUIw()&xpgRzz zsch5rdN2qKQHGo%jF%O$YkLFRFPyx~8zu@~f%7`VOFKxulO1Nd6GqWGz9lOjigQ15 zvk-xZ+&J*k(v{DX2yoV_*P^hhw#D@euj%??a!N&>y z-G9!Mg039O-uhJ7ryn+td_@r|XM&bOfEFTarz(U3>leA%!_) zLOVS_1a^IkGzThA5)Qo3BRcG>pj~WPCD}a@c?ndYLL6-#sYavkYjARD2Rw)=4e(ih zet?T}Jaq3zy>Or|He~NdonKS;*HuyQaKW-e{qoY6_pVLSqg3*;tnT{OuuSrjbI!Zw zXj^UR@YpUIJU;l4%W>z+eJ2bW#-y(eq0~#d5!Zt#=PFq}JkF%s|BeKG6p>x6svU;d zu4M2GSk9m-pj&O=4IoBgF6sSG7T}l*=r&e#&}aid%DR=8E6*O>MF*v@q%!EOC%G*Qr(#`sZp9rc|J@bz%d`oR%teQ4ANd z+(-O$EEeWLg3mb$|BeG0$hd!Lv!-B1g_`C^0cf`+Ss0q1zFihn7?k?K7f-jlWWMc5=G!_ zDrljytVJsnrhL`P4PJfd*M_)NLU|(wfwJ?jv-NIrEg2t%Jz)4)>;HfEE?jv z&}^q};bfOh4rHY0r(r*`*N$HU?6ltR&(x64jkSC1d!MUjf9blf@+nijxkwUAG zMxM|`Bq~XWB6?k_e(lzKte%V$9JwwDrz7xw=!YwIJQNAlYOM$@z4c^Cm1%;=X0m+R zoB}37Ro#e`$itZ4#;HkaIZT=2@^0fYajlpiY|XJZ}@=)pDT==a;b?LfKkPhe!~~+hxDwQ{bo64&Oi( zCs#~YX;|6kww74S@F*|xaO_Pv1$DymUjl-&3)bDK$;tYQ(bp@Bvs0Gi6HCgA8=NA# zg6vDw$M+in#|Wo+Q6=X>sb_A9aT2Y@gLz*PI#dMq11p^tM0e7c&UuwAj@I#^6!0T2ttcSplKtndpl zvj``C>wO~ZXebgnW7IHGxFInNk0H3Z`E0z*jbZOp9w;6XFJv{8P}&1caz(ONmC?LP zcsaGb(YFf0D>|hj-?`-e(m?CNl5ehcE*NkC&yKkWWlL=JycYxAt8zFuwk%4uG@WLe z!?yvgO18DOTe|i~YJ;lhXWL1xN@pDENoG?cG0@|Yhf0~XhsR#0rx;U=GZApCRM0A6 ziexeS3$;(>ogYu8wjyZ+L$ZKFPR}oi*%@Dt+rFsDGm!njtC$&(S0j@*x zGdKI6bUxItj{&|JZ|4fI2L)BqnkwSQ39yx~-0^KD&tDS3k9K2Qab$2(l~x}3&`{JV zr9#=m5ks(w_~rZ;o4p%KzBWbQ$g1k&IHw9AsDEwdrK3By~y^Ih0_tt4-9^I8N@UA z#jt$jW!H$^SXQkCNa1;f+kKfO;}_z3CQwUdU($!6cZkU)KafWa!P_TMQhpuIN)5#6 zh`4CGK?ssW=I?<4rq>>3U}~mHWv~UCR%)%x4EXzn=9p|(&+wM#CgYYB=P-R?I;9uE z9^PZ4x4xzGOFh`tnf}bsH!Q5airTxzjI-eka^@Xw6jroyRW6XDf|^@=k+#Ar%b~=R zl1J$HL=C^0R_}Rgd**^J5y~@gQNdUpq?LYUR_bp-y{{K}X_yj?6)4O(U7rbkHdt38&hUTmI*#uu{2oIuM@h~c%ULvvhW(GgMLSwke>GJ!zO$T?Wv zq&n5E+(Ao4Omz1eX0J|ON34A0*t%+;qF;v?Gqy}Gms=ETf^i{+ z0j2!q?e~>$FF&&HU}$DgbE{cQ5#^)#qeQ`tPcgv%ni*&>bA$L*ZUE^vso3S%zUC0d zW<(kjL^0Bf;ZhdtQ34X>s|(uY&IjyOop6jWLRWQ>me)N7%93Y1!h!g1MBK7wO&H4a zCP!@!F<;Bv?rs=g&SYzFI+J&IIyc;N;4j3r@VAV?oe0J~W^dRuqSIIOcLXc~fkdL9`pnwF?Xqplg1;uY+ep zp5|zNl{ZF|44Dd;KYU`9v~k#K%(Q1P=+YXD8Zdlng(8JS_cG(r2glHgWx|f`1~Q-o zXtuFXBdoxRqvQ6bVRxIa8P{@|+NLamQjMepz~BliH3R5AoQo26bHK*;*-ANO7AUkN zLKS=2Q%HlWzM$Ley*z4;JzVbRVyz?i>)U0TX63rjsJHuh9nFqlnQL!Vr^9)KA|%xp zkJAg$Dc0F4Aj1Aaq)Zyrp&~CIlZl}7LIuS*B$6Oa8P{uj;kV*k2CyFSXAq75)-uCW z7eP7D^bFE1rl>*^Yf&l3J}^zcz>{KvD-L0tKp%R27-L90H{)%<0 zD6np!sGP3aHKM+PQt3MZrScU$utu9I7Yn|W)TGAp-RM-FR|wW;Q%auDICDuSI}sEj z4=Tu)y&FOn;JEc5%nCk6eQ>QI=K1yE5<_zfHyreBXyhvoSA*%jXkZr<=9!LB&0w;P ztotYMuaLG`7PNxay%qK#rQO})II?Z2UOs>4F3S%iUqye%LHDYEux@WWG02-NbI3E7 zZx}5{>p1=CTqIAnohdkYV|^o7P7@3=4=b*YRY!etp5Qw6p=jh`6h)T4Er70&-Jcyk z)*4L}d9aRP-){A~f44%9W$?Q-2gmBRLa8+KTvCA}wm*6CQS=>vL@McFb9=mGYqF~W zX2{ao`+`|hJX1QH6)*OYK$J*FXt$6&AV}^oQzwMYCU*lWGYrpstTL*R%bveMt|$9l zb#2n8zPI=NQlwTImx{_kL0&g%1ETUB_;ZM?_?PEw9kqPpSx%5wGykH9z&(GMq zeb{2)Ug(kYEYmq>RHB`w`u3JypLLnEC-gVLQZDT*+3BQdmeo(JFeeBbx`ee0~lTKoYs z3^UJj-}}1ub?v?HXEeKqM%&b~EXvb6ZeG)A)Kk|jc&7Lu# zq!U!YM3jub-=_>z5Epf9R;?K{UUm9rtekZNl7oD$VI=_1_=mITedvG^nzlJ zI@Ox{=b)mdQP3E3W?8pTh)jr{jy`ONGwSBJ0De?xbhCW%M4gCpqoA*NP`AorhsgH( z5-qrB+4*qzZPgkNkGt*`fjEs)=<3CV=u18o@5<6LtJ_pQW1K1JnzHKOB256E9y)>5@!4$QOYMHgV=vq3_>mZRk|3DL^W*X+6mx zyjlA66wQnwA6IxXTDwwjNU*k-i0|f?Q|{r}ryxik3yHY>0Cply^6s;ohx`AjM|zn8 zWvSwP__4{rPrFSm_tbC~+G;6iQAFGviCQvgYb^I9jC@j0JX7L1r4saM?cN*SpnU%n zwqjW-reAB~e+h)ftD-w$W+l^)4K{QI)k*2(Uwy#0p~ut7%S4Tq@-?7JCVh+OSzPx6 z0vwQ^>6y2q{stG0YB*`HfGCyi5^_^MRBH4O~c9LL^LZ372C4KjoT49%hk z`3^sP5>!I0Z4s3FnW}yym}Xsq3XB8mYGc#x(Kn(eN@oR3TH97}d@Vr{J`fTkW6WeK zAvfC=TN*!tgK%OT;_Q5+!BtfSMYP7U(){F_$o)>JDqo6XjnorTENj5U)xe#}_RXL2 zjp|&>y1`?&C-?49{47A0L7MObKR}rV!U5od3HSxc2X9D2&IXyw_ zRx;8R$}*BOwkQIJLVfDe%vhX?2I!3ljSngrY9ME`a;-&ZLr#=Xg0&zP6imaj{2y#^ zA{hNOEuHk^yrKTGK6=lUztvaD8jm_p{fG-tj$O+9jQ)r~f3G_MoW9ryDo@IrXYW=+ zu&={S1`?w$9xwECX1@8YXDQdZ{>s=+NJMSJ(Zhw6E>Rt{Rt-IQa|vb zv&a~{AOHEi%eX-`MW{8F2fl6(EX0(q%wRSbj-ei5FmdLH8)7UadzI60Nqs}_andnG z)!HB0uv0m5em9V$_gnl#q0)yV~XZEg{VyPr=WU3_)$adbJ32!;=B5r8)1% z{zh)|1s{P=WqZbZ3s&GcXN%U^DF2}7`xhehN^`PAW=Q@8c4{~;std6$vInQA3XBbM)7aysqGGkiQD=Pd%mtlVQ=dz2-foThv1&WB ze>2SKdm=#)%M0R*mhNEEm|w8~=t1B$X+KMyzK3855#d_6e?4^(EH#1ku&yXA5K2N& z#LXy%_>z%$`~8ndDjeCA?MmX4E#bIfCsi!mnCw=n3s2hPB3)N3 z`|3cTpL@NsrW|UAQ~Ys!h3yC)G^)d?Q z6&l|CBi+9^sw@WeQYxp+X@W;S(JQN4Wp?_6S%ebi5N{j+L_FK5N20thglAi)PVxK) zRtCCi>G|+IW8K&TucDG`ecl~@N_;%vF<^@WVf6oz1F#*Sog5pC45lhy9%wrAusUO- z(jnY%@Jx$wp+6L_M#(Mpq!?A%RQws$xH{UchngQqm04}p>~KUMtNmAaXra5#!duSS zpJUt+!I%$-x{D(8a@(GmnqV#N5bS7_#Ag zs?epMYMOUx5mGe#go>Oe**$9;!}1Gvvy>aweMl=u^U&PvF7Oj69xOp1!cptv?S2@B zztdW0t+G%I|6GA=M$#SHiJ_5BFYct|S(fo{PQ#F7IAF&$4e?nhrCAHjpaO`d zz3jDY$GVycRx2+u{BQiUX->+z~eyF6gGdG*+tVUz; zkh3n~jj5;DVcFp9Du}X1_3+wXLd7^{CR#3djzu~zS*qy4n+UU&ciYFGfKa9erkoOc ze)zHZ#t0x~2cDwVhkmb-sIYfmy+eyP>YoL;)j$@8V>ASX(~q?~7$A)DyuU4;ubVfIGV)}@?Ycz@2+ic2D;`ibGmICHd=#M@ zt8UlbrN^xUbm?foqR8CQ@uSsff3EoWFqfsnoBqa`3x6tG4JLEt9;)Pxbv&h3w>e#!cC8?e{j>X$T6!;QJz>{KmRaD1GAW<`{}%7 z)E(IhDJ*kRo%P(0N=>lLZYuES3bk1b_`OHbfUtioiI#b`Q zT-?=T4OxX&FNV2=b`L%dG60s!3`@19TK9(2^4^8y2t`{g>%;?nf6b#6!WKFh!hRUv z?Z&#QN>Rts08o3gUqbfV5IjEgJF1IT>AE#Ht6L(2HBX1|q9QqNtrfj?ytBGw-6E}b zXyd@?fwYPaPqsc|=iot#cR#?_noy&G;Gi zRW}JitXtm#9@oRI2_XD0Y#scP%r^tnMZDM2D;_I~R7MYa=Z5kRtvL?Zzsul!VDBbl z?vhI5+`rpm2P_-*v1ykZF941K)zg_?WMUPyj4klYu0sBfDro_v!0+ZWOw~GVCSHZ?y0i ze)6uuXTbS?wgN%X3MCDt$Sa(8c;8>7Mq5x9g2A~u{z2im7JigEpO}L_Uen8TgXE)R zZft{6(lhY9K{X*582H5_R*JX1mM2P94y8G%2M0K0AK-ajW{$qKd9d{iXcw(YrIsDS zX3fIq0mf)j(xx`>$~Y+YSOtk-(Pd>{`ZGy0Q#oeIG1;MyJv$$cFV5UdnTNIpW(+-L z@r&XvZf}1oEzl_LwvP@>y9A{l*(ii0tZ2$H%(1@a#$qt*XGWcL93TyGb~~75um};$ zH=Xs{0fQK8HWGcxvTQ=-|0b_Y!3?jFRFK3eg8fs_;wh{~^H`57Q;x_{fr1o!EI2y* zdO9`f$5DoBQ5WZN?i3p?kd`eFVK}u5nR>rzU!>u{V*;TE#L{Kql`x|dO9I_U7i0dR zHxIzNi3~xhf>moL83ANMp~_+uI@W>h;t0g+6A(4`h(WIWMF0o-M_FNZnqu6l|3?Oz zv(F#tLshIm17sxM03+7>Qx7n!8-u8{`t?e>9C7U+V)|IBRp%Q$^N?`H-nRlHI9fa? zTIQMBZZ4LG5)yHbML7Sj{6Ul&hA}UVw?K}9FUF}$^5r8>gxG=4%GY-A%B!i|*n)~L~TeDjN>#E}qr6|SV!aRG` zC?8%1q$7q^7Q;FsMyD+H?~-^2fbeDBY}vHGxNp(g+kd}(^D=rmaEuE($2N?aL@jAF z3&Y`f>L1F<+`WE<(^OTwfnsj_&JB=!m@Rq5|9F<+zrs&@OO9pzS-Wm?1Mzx8-a!E9em$_tL$|S~7sxJ+kAG!m0=fNcAUHCe zq)k1%4;IZ0RbWzfO06@L2hq6u@M6O? zz~}gcB@ZmhKxCJY2DB{C@W(8Ofa)>AgCe0L9=!%E2aS}J-T_=3dc}&h9-8fCg@FMg zC_0OG$zcmdM|l-Cf)QwzQY5Rp;Gfw!-F$I53WO1k#r2y%a=yF7|k_1GO zN%WXgQ`Z~9YVSFbLaoJcAP2}xNG6zfHV}2^x`jS8!xN7%9kvqGZ;eCe1ZRK@Z$D|_ zHuGRYum#jW(8hJ4Hfvg)1B8;q4%H+fMOry>@aF*pNV%wT#2+^j{de(lUP}t-7E=>W z8$snsb%z|PRt3X*fJ;&Nzr^LrYu*Pf$NS8pp4d%k|Ki|f>_kt(~{a!O?yMc~}?Hh>1$M=-_GYWlOQ6t`$t zUcg*TW<`w!7$iqt4mI_mvQc|0?YHqHC7U_@4evk5??^CKUKJlh9VToBDB&IjsjQMo zlITx}eO{Y45xLsjGWgCR$W+d-!cIg`;4DO^wfYP+h7B7D>DAQB-QIH8NE*Z>&%rud z*t5V6Ql_euV#UY{!N0)T2sJBIJ_WjoG+}GqlazbIbl>`UM&IYD(y|QED zY2QzcC>PJGWuXU!h*w2*p6E3h&i_;02GwUceKo(8*7ij+Pbw?-fM!H^V!DRFfebZh zMmW(Z;P6O9w()EG8#vSb(N*BzGPhfyfUa5iJ|vD0y@)lFO&U@*kI%oMRmPj>2c%Ss z;xx`rt{0gK-qG)BZAD^m_YP>MqJoj5QT{{p76LAFK2E4lE%Pf^WK2lQPdkdTOb6=bEf#qUy|%cbTF35OnG4G^{rI?G-9!_me!rw-#BT1ogy ziLnquu6B}s;wk5{NhQy}pyE=d+#A1;Gf|X@DCz`i${-{5-*NOVo)7U=x=jJ7=tNt9 z8~Rd`K+#^F2XhgmaJS)FA~IPqm8Y`TiXOcm0J#3kIUIvOcc~r>iv$*%vSEiX;Bbvl zVl0)4Ioq**5{F#Z(se_r4uk}z(na;j6wy+$+b4=UQXG)ay zerJ3=k%6Rj#-ZbB*pfg@F`0*Z2FoSb%UdGjY8^n___DxW)fKLRG&~Q<14kW}<(MuG zTRQan6apFQt7LZkWW`WHXfY=;bP0rMx$lZB<@$+Xzp?7^)kaHc^e9=i zrP>&F*r^NDN>Upt(S&!;M7|U!4PooT=m4)eLbI{LPL;uT^KC_}vQ!s(L~Nvhl%U+N z?VlYR^XesgP+d?0mUE-axmi(5<=dYL%A+L2G@Tb-Z%{va0fk`^ZhC=*nc0#034r4U zk95J#_Aqdj6JGKxC0-E@fB875X>ORzpYMN32;DB?BShA`+)t+7LeWp+cL`GU4pQXO zVuu3^AN*}5UY#Tw1&-|+)s^OYT_?nzxs*zj$p;xuan)}dm6@UO?U=h+y?GLkt~Pc& z27nRrFkojihsyveHWQK+K#&|AH?o_~I=_45vI&?Q3J6~I7x(oav8rBBix{2r@7I06 zV>LJi$~%BkBnpSt_CTC20lop?dqOsQ2@);!qm6G&PYjzRMFG_7ED zjhe7t`0t3*fgqjmLfHI|YzFNdx#0Itfd95M;rpZV@wSbzEe76!Re4-&0+zp(63y~U z_7kk^o+U54@PfvgPqw~V(9+YSV-HZhSc5?aefMSy{-ec|2XN2+>%T<_hk9y0{UZ`* zBigR;oN)q9bG3}p=hxZ|TZ5}E&xYWkdLalSBZF~|N{54H@Iw+Gh*{P6;+0vx?4=?X zUJeZnyOUBJE(>i5+x?U}YsV5NnslAa(^JW+(hNX2<^y*nrPd;2%U*;KEDxHYGy90?g9Bhw z@Ygp#$&t{B)rs5Z)al?hFIv@RX8cgC=_s)ro)ogKuGRM?ZiHt|l|9%k*sa*R=;iw? zd2CcFXPXs2pHDJIA3mEj!Ssy52`FCV7AgRJxC4xt&C{p)`7T5YiCT(8E2p-s@RH&jLn&8=z(xq{f$$MP*fhqF`*T{$@rE%cc7{_I0njoDRZKE&ryu(@n2e{(Pc$)9VK`jdcqpuF9Ti6XmY-STPe>qn{Gp~zHG^1brf$( z*@_TRJJ|PS!$>q9Anr@V+!Ln0hBDcgw8AJQ}+ zI02X!*=kfG;dmNZaZtC~uZsfPfYe0!Ac%iR`5liXe=>W|H)UuYRqw9e^T=-4GCCVA zmk_Ilz`P^u0GFy!c*jM?ADV5AD3=p4^6%szutw?8pq8^`BiU~(m0koSt8>W^wIbu_ z$GWUw%JTRR+5<#b2#-(-otX?1LzNXb57<-HTb>4ka~DbzS=NKK*H6(av9C7d-vjL| zBx1T$cjZG_0ST7TEH^n_-1n&JEy|ErO2SlyIH^+Q*{A<5M!=+i@C>Hc84d^RIna6W z;D_MM&DHb3{2OQ!7hownF0A<&8!ar^h=lbSR&gn*GM3`Pvg@}n9iWavgR2Pfv%ALK z2RM7<)3)n*G%LeHk&3|>X&xYuWOiR%G@57Ad9_`N0;Z&+V|kssy!GUVlRAxybt#ut zoj4-*##htxjz@SZoZU4i6X%IlL3lf7^`1o(d}oxZDA%L2+}j9)3ao0HU8Tf z#%J(h7t~=dC!tvyDztOhET5{)i%ZMH+r(DZ>ca$vfx|qSG*ChKCndGjd#LT7ciQ29 zJ7L2_I}FK(GmMwT<8&_WfNY@Ev~UM3yf?1Grv3`b{c@3kABJ*FrBP>7VQAf8rfvap zit71>;g%s#7~#XuS)2c7UT;prz7bCwSb_}aiV)}ML;v~F0)T2uss&EIv( znh^oZ?Ef})@Gpy!Vr^T$5ksb3gbi@!$EjR-AAzuFu!$lQU(DLZvZ@AzEOy0 z15*5oQ~X4vgt;}1gl@H&a#5Z28*pZhlMr`y1X30165f@ST#(TR`M4(J8K z0k`L6InbdN!RD_1tF&i-m9TJ_HXDV2^scIl+jP_xe7+rF3vCG1j98jx*U+dW&%0sE z#z-y0+vcPX$Zv4+?8JjQ;_v}w8s9y7H74?kVTb-u8SmJQ{6-YgDZL@8?P+VZ9bNnH zMR5k)-E<3AtlqJMYkBjS9A|r7Vz{xNVndzmonFUzEmISm?dPLw5H*T!rPyOOb6Wf; z1j?@*XS-Tho`+UkC)YwoM?SRxrtRaByoRHlH+jA3Cu+F5L$}*;<@c+6{f>-YZDa&K z9xcOP9QOPiqi1x^(Vn<~0|L5PhRWC+T%evu+sibn=kKe5dzuipFao?3N@K!w$juVq zAUzI^zX~OJ(?(w3;_?xYSJQy#B&yz`8}(QCZ4mdv~Xhwma=K$RNGc2PWfJ z(;35};pu|r6!Yrh`)cWrwxzeKO8ir=xIs^;?x|0Pb+#k^6p+=wS5mJeV$oso3hS8C z`>S+&+C&Y-{8k8Dxx*XcA&Z{fC`yOdwWqPK+!rIQqHj-pr$@AHRehYQzlsRGQhXU$ zJtx3Kg<{@@yrCIRL4I@W2zV91z`gQo5EsSM7;f8<$L=$SCSxY?o_B%aLsfjh4`fV>wbLA`F zhOaTV4_y}moPN1DN+DF0!|QTd1;qxBV-zTq&eqe?b(%>DxU>sNR^l&)Gx7>46G{oL zQRxD4gf*eeI*kmZ{S0Ig=_I$!2$vMw`l{c2093 zI=H$Bh6VWM7?Z~U*bG$aWfM?{Bv zH-gUtGY@`FMj||w`%`}^#UrI71qj}qabeR64W-LztuNd;S&S))O>Z8HzJncSHiI*{ zvE%=CoM<*`%?fX*X`lQ!K!OW*8{o2AHUaWJiWRUn1ck~6qLjX3ZDND9fC3=Jb3uE< zlPI>ZCqa~%BNa0*lKh&{x@WO6QBO7pWeIAMS=35gykLa1kt0T>^37auR?%^w90REB z^B~6BHty65nUmGmG^Imm8U)?&2_R>u=+{l-p=qyS)?GY?HeV2`s&J2B>;A=A8a-S}&0Slnq_}*HcMSQ8Vsp%opn|^A}4enpAhIF=*XVlnxv|dw7La^#~ z*w^E-FqY(0^sD+e@~;$2e}hOYl&w8gkV<=mp+}vK7jrE@8QDrr2HX1Q#Ub1;TfUu+ zM~J#<;Y4XZ0yoPl`itK|X$Gf%WXrw3RSkeX#a<8IROVsm*-UA-Rn)ZNo zZ4Xcnd}Bl~14jsB?DXUKZ{*tZQ(wQ|ZR-qKx(f;j!M6pysZbeF`4S*B*0Yy4N(M zag>@}VDt=Kcj=Mr6p zJl}@Gn)>>B9!`oEFTc5FK9hmqiMdQyo0~v*vC=Lpi)Jxt0y^b^0lBhcvY}JanPrJz^-}JO3Vt8)d*Z6&Dd|2*KJ0A*%T~l*hzI37yw?`iHW#gmJ zEue|A)}(c^&~tVm>f!B9Ed%?6yx_7 z^uFV>q%bx_niNDxX+TJ?^+%;7mu2+~OsS?QX7g|OiTN7IwMxXrLQ4Pn3$jEMjTPJQ z^?rJ-j|2gEU|ptG?TI{6dcl!$9#nInKkJ{D-X_QxYs*hzr0R>;t?8fB^xNNJv zeN`+ZX>pwBxyJkVJ0MFW!5KjABUIXg_L^!z8>k?gM0eP&)0a;@aT6av`EPLS@iKncU#d?C^)DC>#E~wkm@2kZDCY zjAV&c-``ya?=a78NJr1mo8IYO9>0uMV4&IY77xHkY#qB58^3ir?ITNM{}Gs}G;lN? zTf;;QM1i%lrQl!_-;E@-TMseG=`Q+)w&Njo1x|RN#9WXNFxw@?@*D8q5~Dx|Nk4pz z9R@TKEB=0ykEA!l3wWBkcgi0gzXx8c7-$b56qwlG{+iVsa(ZF{cOy(niUx0c{VL2l zGj_iI(r~+&?bgyR5r0lt6X;Z{k_VcfJL39&9hd}%`?m#RUb~Ofueq7Ow)(8{C2JBG zjZL?;cQZRt8yTcFDd4HbGs`pe2>N(DbFEoOY4@(6^7rk2m3Lsp_4QzTitS7#55ufe zEl+9|<5i32(l@ca^Sk7^+ofCIDv7xl{p`0DJ%OBwLu;i}DJt}(m38k~=XQXj88R5% z9p~pxo!RQ`;iLUZQ?<EZ)L~PhgZ6;64^VvCs;%Bg_@{DWquj+PE5cv+G91Me-|37OP- z7MV_w-ksNrjK_Au2ALNS?#@doV;k3sizmfNae>*&!G-x_Caro-Jco&pW_i&fMa<@Klt5QqT}#Ty6=zWf`_((>Jl89P>rW{ z*=9N{*zStj7|}3WV)xt=D>Oa92*hdoB4YdYj}zIw~X|0 zNcC};EO+O8Ma;kDEW_YZMAeQanDJ3Km#x`Ro30khznUtqjRr37_r{R1k&qst()!#p mv0swC&&6*2LWA^QUk-jUtYlLj_+&y44=Kp0%2rC7z573?KvX3F literal 0 HcmV?d00001 diff --git a/doc/html/_me_mega_pi_pro4_dc_motor_8h_source.html b/doc/html/_me_mega_pi_pro4_dc_motor_8h_source.html new file mode 100644 index 00000000..57618a6b --- /dev/null +++ b/doc/html/_me_mega_pi_pro4_dc_motor_8h_source.html @@ -0,0 +1,166 @@ + + + + + + + +MakeBlock Drive Updated: src/MeMegaPiPro4DcMotor.h Source File + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeMegaPiPro4DcMotor.h
    +
    +
    +Go to the documentation of this file.
    1
    +
    41#ifndef MeMegaPiPro4DcMotor_H
    +
    42#define MeMegaPiPro4DcMotor_H
    +
    43
    +
    44#include <stdint.h>
    +
    45#include <stdbool.h>
    +
    46#include <Arduino.h>
    +
    47#include "MeConfig.h"
    +
    48
    +
    49#ifdef ME_PORT_DEFINED
    +
    50#include "MePort.h"
    +
    51#endif
    +
    52
    +
    58#ifndef ME_PORT_DEFINED
    + +
    60#else // !ME_PORT_DEFINED
    +
    + +
    62#endif // !ME_PORT_DEFINED
    +
    63{
    +
    64public:
    +
    65#ifdef ME_PORT_DEFINED
    + +
    73
    +
    79 MeMegaPiPro4DcMotor(uint8_t port);
    +
    80#else // ME_PORT_DEFINED
    +
    89 MeMegaPiPro4DcMotor(uint8_t dir_pin,uint8_t pwm_pin);
    +
    90#endif // ME_PORT_DEFINED
    +
    107 void setpin(uint8_t dir_pin,uint8_t pwm_pin);
    +
    108
    +
    123 void reset(uint8_t port);
    +
    124
    +
    141 void reset(uint8_t port, uint8_t slot);
    +
    142
    +
    157 void run(int16_t speed);
    +
    158
    +
    171 void stop(void);
    +
    172private:
    +
    173 volatile uint8_t dc_dir_pin;
    +
    174 volatile uint8_t dc_pwm_pin;
    +
    175 int16_t last_speed;
    +
    176};
    +
    +
    177#endif
    +
    178
    +
    179
    +
    180
    +
    Configuration file of library.
    +
    Header for MePort.cpp module.
    +
    Driver for Me DC motor device.
    Definition MeMegaPiPro4DcMotor.h:63
    +
    void reset(uint8_t port)
    Definition MeMegaPiPro4DcMotor.cpp:174
    +
    MeMegaPiPro4DcMotor(void)
    Definition MeMegaPiPro4DcMotor.cpp:51
    +
    void run(int16_t speed)
    Definition MeMegaPiPro4DcMotor.cpp:216
    +
    void stop(void)
    Definition MeMegaPiPro4DcMotor.cpp:264
    +
    Port Mapping for RJ25.
    Definition MePort.h:128
    +
    +
    + + + + diff --git a/doc/html/_me_mega_pi_pro_8h.html b/doc/html/_me_mega_pi_pro_8h.html new file mode 100644 index 00000000..ce98990c --- /dev/null +++ b/doc/html/_me_mega_pi_pro_8h.html @@ -0,0 +1,619 @@ + + + + + + + +MakeBlock Drive Updated: src/MeMegaPiPro.h File Reference + + + + + + + + + + + + + +
    +
    + + + + + + +
    +
    MakeBlock Drive Updated +
    +
    Updated library for MakeBlock Ranger
    +
    +
    + + + + + + + +
    +
    + +
    +
    +
    + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    + +
    MeMegaPiPro.h File Reference
    +
    +
    + +

    Driver for MegaPiPro board. +More...

    +
    #include <Arduino.h>
    +#include "MeConfig.h"
    +#include "Me7SegmentDisplay.h"
    +#include "MeUltrasonicSensor.h"
    +#include "MeDCMotor.h"
    +#include "MeRGBLed.h"
    +#include "Me4Button.h"
    +#include "MePotentiometer.h"
    +#include "MeJoystick.h"
    +#include "MePIRMotionSensor.h"
    +#include "MeShutter.h"
    +#include "MeLineFollower.h"
    +#include "MeSoundSensor.h"
    +#include "MeLimitSwitch.h"
    +#include "MeLightSensor.h"
    +#include "MeSerial.h"
    +#include "MeBluetooth.h"
    +#include "MeWifi.h"
    +#include "MeTemperature.h"
    +#include "MeGyro.h"
    +#include "MeInfraredReceiver.h"
    +#include "MeCompass.h"
    +#include "MeUSBHost.h"
    +#include "MeTouchSensor.h"
    +#include "MeStepper.h"
    +#include "MeStepperOnBoard.h"
    +#include "MeEncoderMotor.h"
    +#include "MeEncoderNew.h"
    +#include "MeBuzzer.h"
    +#include "MeLEDMatrix.h"
    +#include "MeHumitureSensor.h"
    +#include "MeFlameSensor.h"
    +#include "MeGasSensor.h"
    +#include "MeEncoderOnBoard.h"
    +#include "MeMegaPiDCMotor.h"
    +#include "MePressureSensor.h"
    +#include "MePS2.h"
    +#include "MeSmartServo.h"
    +#include "MeMegaPiProESCMotor.h"
    +#include "MeColorSensor.h"
    +
    +Include dependency graph for MeMegaPiPro.h:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +
    +

    Go to the source code of this file.

    + + + + + + + + + + + + + + + + + + + + + + + + + + +

    +Macros

    +#define PORT1A   PORT_1
     
    +#define PORT1B   PORT_9
     
    +#define PORT2A   PORT_2
     
    +#define PORT2B   PORT_10
     
    +#define PORT3A   PORT_3
     
    +#define PORT3B   PORT_11
     
    +#define PORT4A   PORT_4
     
    +#define PORT4B   PORT_12
     
    +#define M9   (0X01)
     
    +#define M10   (0X02)
     
    +#define M11   (0X03)
     
    +#define M12   (0X04)
     
    + + + + + + + + + + + +

    +Variables

    MePort_Sig mePort [17]
     
    megapi_dc_type megapi_dc_Port [14]
     
    Encoder_port_type encoder_Port [6]
     
    megaPi_slot_type megaPi_slots [4]
     
    megapipro_esc_type megapi_esc_Port [5]
     
    +

    Detailed Description

    +

    Driver for MegaPiPro board.

    +
    Copyright (C), 2012-2017, MakeBlock
    +
    Author
    MakeBlock
    +
    Version
    V1.0.3
    +
    Date
    2017/05/22
    +

    Driver for MegaPiPro board.

    +
    Copyright
    This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    This file is the driver for MegaPiPro board by MakeBlock.
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    +Zzipeng          2017/02/27          1.0.0            build the new
    +Zzipeng          2017/03/14          1.0.1            add MeSmartServo.h.
    +Zzipeng          2017/02/20          1.0.2            put the array megaPi_slots[4] to MegaPipro.h
    +Zzipeng          2017/05/20          1.0.3            add MeMegaPiProESCMotor.h
    +Zzipeng          2017/05/22          1.0.4            add MeColorSensor.h
    +
    +

    Variable Documentation

    + +

    ◆ encoder_Port

    + +
    +
    + + + + +
    Encoder_port_type encoder_Port[6]
    +
    +Initial value:
    =
    +
    {
    +
    { NC, NC, NC, NC, NC},
    +
    +
    { 18, 31, 12, 34, 35},
    +
    +
    { 19, 38, 8, 37, 36},
    +
    +
    { 3, 49, 9, 43, 42},
    +
    +
    { 2, 26, 5, 29, 39},
    +
    { NC, NC, NC, NC, NC},
    +
    }
    +
    +
    +
    + +

    ◆ megapi_dc_Port

    + +
    +
    + + + + +
    megapi_dc_type megapi_dc_Port[14]
    +
    +Initial value:
    =
    +
    {
    +
    { NC, NC }, {33,32,11}, {40,41, 7}, {47,48, 6}, {28,27, 4},
    +
    { NC, NC }, { NC, NC }, { NC, NC }, { NC, NC }, {35,34,12},
    +
    {36,37, 8}, {42,43, 9}, {39,29, 5},
    +
    }
    +
    +
    +
    + +

    ◆ megapi_esc_Port

    + +
    +
    + + + + +
    megapipro_esc_type megapi_esc_Port[5]
    +
    +Initial value:
    =
    +
    {
    +
    { NC}, {12}, {8}, {9}, {5},
    +
    }
    +
    +
    +
    + +

    ◆ megaPi_slots

    + +
    +
    + + + + +
    megaPi_slot_type megaPi_slots[4]
    +
    +Initial value:
    =
    +
    {
    +
    {35, 34, 33, 32, 31, 18, 12, 11},
    +
    {36, 37, 40, 41, 38, 19, 8, 7},
    +
    {42, 43, 47, 48, 49, 3, 9, 6},
    +
    +
    {39, 29, 28, 27, 26, 2, 5, 4}
    +
    }
    +
    +
    +
    + +

    ◆ mePort

    + +
    +
    + + + + +
    MePort_Sig mePort[17]
    +
    +Initial value:
    =
    +
    {
    +
    { NC, NC },{ 46, 23 }, { 45, 22 }, { 44, 25 }, { 10, 24 },
    +
    { 16, 17 },{ A9, A4 }, { A10, A11}, { A15, A14}, { A13, A12 },
    +
    { A7, A8 },{ A6, A5 }, { A1, A2 }, { NC, NC }, { NC, NC },
    +
    { NC, NC }, { NC, NC },
    +
    }
    +
    +
    +
    +
    +
    + + + + diff --git a/doc/html/_me_mega_pi_pro_8h__incl.map b/doc/html/_me_mega_pi_pro_8h__incl.map new file mode 100644 index 00000000..bac911f3 --- /dev/null +++ b/doc/html/_me_mega_pi_pro_8h__incl.map @@ -0,0 +1,273 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/doc/html/_me_mega_pi_pro_8h__incl.md5 b/doc/html/_me_mega_pi_pro_8h__incl.md5 new file mode 100644 index 00000000..7e249661 --- /dev/null +++ b/doc/html/_me_mega_pi_pro_8h__incl.md5 @@ -0,0 +1 @@ +48796399be66e773a75c348e4ac7e790 \ No newline at end of file diff --git a/doc/html/_me_mega_pi_pro_8h__incl.png b/doc/html/_me_mega_pi_pro_8h__incl.png new file mode 100644 index 0000000000000000000000000000000000000000..42330224e0744436a658ade9eac99cad040b0c95 GIT binary patch literal 920513 zcmdSAhgVZi*EWnu6ObZBO6W=vkSe{3G(nIiK{}BpozSa*NDm-NkpPMaD7}T=Awg*Z zQbP|U^w0x@z~}Qk@4ME0zt8Xf1HL(Hoipn?XU)u>GqY#*wf7`EH_*OK$wo;;M08tM z=ZP^95%W0_(T#NqvcHIrm#O~W2bqJO_7kG(|GGZ6mt+tTaTDo2Q8x{O?kwmfOV0+E z;4sSR(=FzKb(8m$Y`m4SS$_#@RA-UheMbVhJxex_B0(g2V}aXlukE0GBhO<-_y%7Z zG0BZ+GVx{>ig7x=0kZZ311k0ac5!NIyI$t|wX^=izbyNL+vNl#`S|$i4$G=KEOFNY z&#gaxWMwtWVfB$bOv1d0|NmneXdPTUru?Ut4VE+L;jQ&qj{Bs5L z!Rm=&N&nQ>{|Rg3{^!p4-`(?n5SujKrT@^{e}=_MamD6p|5V-@T|wC4E!E2vTJ!7h zoshVPSjVg*)4!N5W_=j%UfIht9XWdv{IRp@pIbk0H|3w(ayT-}RJ6#{6EQg${KFb& zZM%4N4w}CE&wZ9YE%2ZIV{r20secxV_Yh{ZX8BJ-+2k0ioWDBhJY65Y-fQ*D;=0<8 z%NyLGjKW&(fkjJ#gQpK^2<AUUM;f+lHLC9zSG%g0ZRj!1wcO!d$ns_QcdS^c{X5wl2A$fsC zc^xJ;$amLsCbtQDcNM@&y>$G#?E#N?1@!NHNG&-Ws10$EjKob{wPsj5a{gwV#%-6Od@tfLx8r>)LHG zuPI#QRXXlEgS&f%y^st5^TO_J^KZh*1cj_RY=GE>Y%r2< zezNf@*DwO3dbJWc)+X{M(7ktor-Dh}21e1aoOj&m06=QXKY9s^a=c}>-VTaMC z-Amr>y2wuMD#R@71G`%eX9p;+a&rM*O^qQaDGU$#`h9Ka1%+@^Euoyh`wT zzj1dxpZ0$b*3l=|YcKxaS(3l--~ZhAPe+)Fo&F4s6ha=MSy0F8NtUFC`SY01X9I8} zmUKkP6K1neZ3hj}uUS8NCO9;;y((0w)UydfZm*8K=_=*;K?DCSd)@xbUMotfM@A}{ z4DG#UPz8}`jrz9j0WUTwl@Hp1JhJ3gVgsGtTn+6|bpm>;ksqaX?cJzBXC=&kD(U>z zYk#1JJTr9DoUx{AIPq@_M?sLl?aox|NK7h?C<}(2^P;i-Zqpw7!NaUv%?@|;w31|h zPo~p{iwr}RV7~M%Ov`AANC`nv)!h5C;*kQr6g+)Sjl8&P(|6bPdYoPzH|!-7VOcj) zeF36r)eIL!whUX+>)v(E?wz<<>p>T!Rd< z-MrtfTrtgxlMJ47U|TO+kzs;lw) zlxR-I)a@hq$HcYJ)UJdMPN34dicdA6dS}8eTf!T2=E$Gw zi@MaU8g01YeJKh0fMHn-TK>jACKm97}ACi}dyFIA^KUa7Y%t0kR#8X~5+0@3t_}1#{rVgjY+sYz6 zqoP5iBeX5TvJJ$F-j4Ud^XK`XILwMB!(kDN4e^t{ma6k-FxH$!rVon@@QAYBq0w&y z#fbE1sP0-#Sf&xHsl?-%@P!R6R|sZ5$Q`4oteNqvUgv?-e4fj2buPog%Wj!oQR5JT zr1XQ-R?suFspki>x{Hn(YN9FRkMR^;sWdJ=!tZ!otCV!fz31}BJ!mi0d*zMRoUE0Z zc|EV&H-HdYX0@nqyV^j@&zD}7ipUmiMdV!!hX0pL_+uA>z`3eC^2YlGuX{3d7dJ;(X}nZvswMHBC;pafLD(oeOP!<8(3z7mC=3V^>!66jDC zdsC;;m}kk3&!RHs^8UsVcu-V+_Bwq5cl4eiTG{tVKD94BkRwzAWxs@98jh`Z7(Vq) zcR{K!o}N9B1Jm3dDWN!7fIDh=V`)ywK`s7mpY>jCs8LinVl6)o%pca?4l%&J3T*h* z+(<~j;48Bo9U1RkIfw)oXToyh^leS)r|>t4QjaMBf!4EpN55wb*peM~I=EVmq0c(|}~s&)(AtYoNda_dPsdj$9^s5y(=dUS&w3h)h+G8}Jez|Q(ylhf*YOb1ln z@9I9dh$!fFetfnQ8+}YpI?IuXCMTQSC5_&R0H!V2_vCx@cT|Th(&z^e088xEfprT! z0dev^qa9sM+kg_Hm2~b-`MMvCq13avzLr3o3_<2O;b-Gc^_%wpXaCez*D)Z#n(*&v zn0+`Np>nnCB1Kb64M21|0lvjU8)8OlIF>0$%3d1Lef5H|>L-fVD?GiOEfoOLr}1K; z_AQcZ0>2ijZ)x!|9Qy;F0T!fx8`0u&eq+Rv&F<8ZSe%kOSnB1al{yn2Q1NxbzptTV z_y^A3PuuuGz+L}xzVqh+j@(KF-ZJED0CYg6s>4U!9NNOs1e@}hn_g;KxbbOhv-0=T zou*C*%VMi5ik1MMS`~k%D58Ss@oL@KNe|EYdDi!y)y2Z!}CgzsO@DtV<4^=4~VyFo+Dn2=>rn1dGxp1r?&Y z(iH{1a4%E8QRip_I|C+g8oZh`_|!rZI#wXJUGi{EHvf%{8`^6g&7@>;e#Z#S|vMc$dk`=jL1DTKy2z;*4hYFR;s(CR|d*u~GiJSqK}Zdt4>Xs5wX;T?H*T7%?sf!8i>h0ssx z$>*$GhlApsl|zcrZK2q~gEWoT`Hx$jwlS)~wMoZ!e&I8+Pb2ejK2AKbguJlezLuV@ zO&TsP`3rQVt9flxaLO=FWC683bJjeK%n!5eXelwjdtJ5lJ74kRqn;odrVh%0%pwWr zflia3Es;R94~W9m;r8f?k;pSj)i1>546j}-Qbb`MeP>p5}P9|0Jo$P8Nvs;U9+c<86SE*L?f<1e3`-IBpLTa=>)*P=(T#bHjo;&Hz3se%ELS3e-iB+iDXI#|d5I^Fj3sftpo$_!=BIg& za&Y8&*>-M+`z=Cj0Dk3S?O7~%2nGW|TKxg#-`sOxaSsQCEQLrAEKf+s#*n!&l06TuU=kVj^et;DV$C@dqIf&NMm830 zj@L>BnADF@`7<*&;tDvMfue9AoP+1}cujXkP#1#}R%V)YhiVX;^b^U4-r-usdJXPNI%7%#WTOni%A>qS3o`v?eTlSuB zS)`D2l!Au8^{J)=W!RmAxLoOZaM4gBg7|*= z19Fz>npjRL-fSOC2ZxJy(=8ZBPdo%!$^B%8p=O35okmzBtEy>SjFD)RVQ zsE8lG*k@LO%HBTMa+`DVQ@O)v6o6ahVRCwJ{6G!+%{Y5{IrwJiE47Q3QXG|hCh}-t zW?ZJjODmmkMp>_WW7(jSM(5L*Kyej_PsCM`pDXD04~17OCXQw2P*GXl2SR?bEjyK)5 zCn!)-F%z0tW6yV@kOg6gfVdmBHB09vsvPK<@jm&jl!>5k<`VJ2?kff>3 zt*8kFk@b;mK=5nGvmpwJN`Xyr6!fI;u7G^df`E9k1S#L`3pBKksK{kgH~&M=<4fA2jxXA~%hxgUsUQ+ZG2a1J~iaSZ(ylHV^jZ_|a?=9Jp#q(TL!6|v);SI9O{)&v1$LvuLv844R@+I?lj}fM4 zB@x*xA_q#dF;b8CLLf+Vb!5GC{x0ZPSE4Gaaz9WH*XH%K>X;I=tYx2mIWV{L_sYEJhFP?_cr`=}O?)@x6x-2H$0OYHg~wfatEI#!(7rX}_I#?3x+9kTk`QrE zIqL=X*^rDwfGj8YtwOnmf9%0>F!dxfj9&!!R_zf`{3VOoSR#?Ez&volw%f=H?g~Ck zDZaBP1p~$B^DnSDB+o=x-@g5hQ&7Z{Gw|Se9?)d}<)H28_@%YBv`4r*A6vK^95B%# zLGtyk#}NzUTT{S_k8-Bx)eJPh1Oq?yd4J(Q(Z5lnxP1MG`{1r_(YcL3hhCL{ur8KX z1Tj9nbxRZWcz1SO;o&I#6{(iH%EQdYiF3K`9w?njQzuQC#znAlvs#}xRhf9?5c1N+ zpIYkoQDO&a=9+G}%nSI&ghaRLmBlByE?I%e!5>;f;S}uCuAO&TSEzMSHI!Xj&xAN&J_L<@zyWdb;&LAz87YM zt9>=Z`UT<+ji0w*C*%)T7y*5dh$zzS4CoM8=ujvDT+QmzVvfh$SZ{LL#&H6w%L9Mk z=ysiH$(b!N%8XY+qqXn=mHNNx2fPi4)t z1q*)!+Zsx~+RQ$fa$87_%jPeZUp!%}k?w|f+!XIs>b43bnV0t$0EURo<$ITC1HEV$ z*fJ2`ke=aWtu-zf2L#EZw8h4~#VIz#4i{d@{}3X(o4L0bigSZ!Pvk2-vR*u&n>i2h zF2n~w=X*kW;wlO(+>CQi!u=vL(KYx$w~kQ{QI|VCrVM(*^JYj0CL`O6Cg5!yeJ)M*V#-1z~=b&IE3{aI?Y?`B)l zPKM(w@J}{zxjuYU$6!HwCf&mUK@v!q6jZr~H5m1FZy69Q{AR^_oLadB

    W7Jkl)8 zAMIj>i83Jz~f*OLl55*(~<^xxWdb3bd;*kp)b=;rVhreyIiZ z7BEWkI8nijj0#E`HEvPxdrw@pscx9ufjK4A0rmC_Qu;eT`}Yf-QYr3wVZa~y+gr(` z{!r5;Dy7TCM)$=UgTwm=3kB!>LD6Q)T1j2HM!v=*4-3bVMjUBKPklPxd-=Zhw$d!8 zuySCOkd#Krk;@?VsC`68;6=Yh_L7G;`-$Yf0`R@c{lt7i(A{7#qAbO+WWcIr^p{e5 zfU@TP)^zJlsla*aQT3Ks_Pyty>IS+O96L^}!!4zp3?N{ZkKJZ8ArBX_@8m3t+#E_! z>f@ZaXy9O@*NtnwyDg|A^+5H%xjv6bI*jNzwcqds6qsIcmr6@B9dVn9kgXxTD?tYj z=2-m6@S2)vo@LS=;MJEmB!ke|gOa{5I(7Q(q{C7BbnK^7+xGdY)Ml`8dSQiGJMDq= zVImoNd*6*PPrGT}ed$^iCoQkRLG~24dor_k-_}`ZH5V?r8Jzui224&1|5(D*)W~?V zFL~6VsP-68c~ftAf4I-RA+qDAI)XyT1(cHgL6I~(9v&ozP#Q15$&JwN4-h*WP+o(e zmTbKc@rOD{D4(psA+qsw1`h;M(gc8_0^)s@cbJL^@Tm5>PqRO4sC5CN#9mAi9_Z+Fn- zKdx0=%4hkI&-9imnHY#PTR5^rn2`uSJkl%L-7G@vXSZA>;V7#@XNPVb+(R^I#Pwk)CSRn-s=1dwY ztf`kySC6gf0|FD5HIwDvu?LYnCZWvS%U0xJiPBlwR5lppZFi!0sPNSe5KQ?sRVfw= z*%GX0*Dyr>{Bm#{?@QB_B|np^uw~Du(imY5g_ZGWC0@z~j`s>;ck4E#|l3OT0I5SM$=-Av+E|sEkb>HktK6xcdWr)0p{g#lmHw+B=G=G0rk-b}P z6g6_GSP{MEInQ*i3@&YYNFHQ$2VrIdml%w^c!p$u9fl0QbdE3u;@rGdwm7km1bk=j z$ft1l%slsYcf=h!bO)O+*FVLk!@Fg0=X=TCWNSEs6t3It2Xl2w2heXzRpD)w&f>7$ zY6Y6F03R>*we3b*lWjFTI-qUIXF>Mo_9421FpT`XJ@Y*Njgdk{P$9;npvKRZD^QXT z9x~p5UehaYtjL7;h#pW8qHh0oXe-K zAcXm$&jVRnye>s57fnhMC_mvdfB6PUVnbhyTIgk%1=|G7VN0qOWKgHt<+irlx`N}6 zPg4lC(#4m>(o2>e*F%AqLjg-8JY=x1g+zN#9^*y>`gM3TwP#g|ZoBIj*0iMl_TiE+ z_Kyt->^JhzPHqZ^ewz}`VO|gTY>IgH?K>gZHtT2n@6daTib9O(S2J zxKqlr9j17vV9{kaStaySS`|JxpTB3D=0~p*7j`KE`$>f%`#nDj+0w4fpUID&i?||j z%Fnm7M(x;4%l%0<(w|;BYm+2-=Sl4&zH|ogwM)SV2p%~zhGQWWfrcS=iUJ?RgTfS# zKZ$+;zkjnQF}!y$)X)IupkZ(qey)ORI)^rJ49?R(_u?F^#5xl?LK{Arj={1lKpmqO;AZy*s$Xw*$>t8%-uYSf9IF;5tam6`hWNSzE(Ypit8k#oalaIz?90`6#U`% zaq@H9Gg-+KS{m*tueBSc?g9nC58j)?Tok$_Uvyi zn{ow=ZgR1c(}pump_ zf+2g*iG;#g7g%u5J^j6w)qsg~DXX?n%t6`YD4!m2ColQHkWj+BbfHp{&t&ooL{l(v z-@WF8!S=AmHW{edW&x_@|Yd=WR2sXT@|PI=E1%VsWU+>lKzb1O=8vC zF79Hr_1JIwlg*?dMQXoh?BDpj5}JFiUHPu)x#p;^={R33`^}raR%LGh>IO*HI?Pq0 zmVuuyouX#-f+%^bG0~S__F_Z8sTEsUblIT2gS-oK3X*POTHZK!HD+JWkViNbzC+Qhi=cT449zMIJ>9Fo3x=y?Y&_6_)VW?sc$=O4*9_vNuXtij}d>_}JR!r~4N+hb-I=H>@0-w=)(tDry!|{Wh7&cyXU^Fq;A_q} zZyseS+}zQ=ekHI}6Yv4eeZ6T&5N_{^V+xBucm%C_`_uWln6OS8ft$YWUNTv0?G-2p ztG&1wWI21scph;UcvW{DLwmJYp&hXoH9FiZ;Nga5F=I-&kw}E_OrB@SJ&Nj$L$_h! z-@2RG@8*q7G7dpb`n1M`THr##8C%<4IIRulqTRKjftt{!q-tvKT!D=o;OAecVhbH4 zxh#bf<5)s0!`HDYT#8dN$HSY+Z1|pfT77&cPTqYEHCEcY_V3e$=ESQ0om?cY{M-~M1hNW(6t zu_O~G8_PwaP3Z)9SeA1Xt`Vk0+KJC&i>4^e4hQ@;|Z~? zQ#3?jpGN#Ag8soch-n`9Qdw7@Gb>~c1BA4G zFMwE37i^#1l7@UNf3fYztQBkYKANESS4pX&i#m0svyBn^M@6zuB83=Wu0%sNQoLhOnMU#Qt!29dm3`7z|zhEs@w}GmH~|HjI;cwu_T#K!-w$ z(fGV#bZ9}!dRK5fl4o@CtvFJPlhsmjXYa3Tdkr_U4XS~6P5DgN5JFDtpY36`f#JD; z*H~FkuXCAjT1%WOOK;;nyFEY6+*ZjESC6G)mP=-E@z^*C=i(X1P^mX3(P)Nlaqpc5sg_H%YOX zHc^v{K3i=KbU>M~+nFNP#NJTA)m24clKrdW`%l+-v7fjuhe9J2H)kpz)eA)L9g;%2 zu+&}b)VCC22b*VIBb_;lcSBVcDwb3O7B)L>DK9pZ;%{;wQSMP#ic(pAbNBCD+m>!` zD>y<L!KS)w*Y&jCa3xPK)luymAswtXSg$sWPR8?3HH0}COkXb=JPPHDoV+%8)yY1U z5jV*n>hQ)V96w2ko1Fbll{iFoiUf341!{LyUV2|$?wo% z0B8H>#!kI2br9)|Edb*x6S;wte9wwgkY8rz-t_RnpFJG`sh5e5SiT#|q|(LEE4?>3 zk#;Jo+U_*D7h4!oR2sCN&RfnP7+bQTnQmApGoDbdsY2>IV>5eq?fb`^Z$uw<<7>yzuCgaqGOsA_Fcp*7WvTRgcDkdV*e4 zmvM3>^MbHoBZU&pehF^_j!b_8QSs#TuXIx@T1m;`7h~r3RXp(Dd3GZM#4oUxqNL>b z8HLh?c)xb)(J$@-{VoeB=vM(M^i1?ONy?J)qvJu;a|rS>spx*r*yP z-z6u7fIBEI}F z<(cg8$~{WYf%1e*57`T7s6@4ANk6pJ^xPK2*^eSGEd~u$Vk~)-=>021}%?6^#llaQML5zg!qN)t6H1RVgI*frx)^8 zkESccD}QvE?Hrw#&Ao`YbiV4YUGD8U`<+sC!`27GC#CW?4^34fMA+I(9X66g=r%M7 zU9GF0$1R<;Mrx;fZT@$VpFrfb>Lu5iY{z*dd)Oo&mqQro*#l(y*U)7zK!p8fWF%^z zYMg{am3E)1tjUs7VtZ8R0cM;y>tuTpIymVzc}^F!M2ua5f}p#};K}rTMl^LOziGUh zqgKvWBTs{YjL_X=@f-<%3?~M{Xw}x+EY;NCbi@enkU+`wZ!@0*;Uu6-6Uq185LUTPRzUjo|`7bR~{f%i5tn$ES z8d&AV`{5=$&^n`_%_XSa6(Rx7wtST?u=^>4b5ybl$=hiQY^n3^O*)3!wwTbf5INE~ za;)?zolg;g?9z19dPG0kCI%&vQiIn)YE%iUtBL{E}kr>cg)tMSQohaCqH~P zQ^Vaq$>$n&*COs%&p25GEjUl&O-%Je2?pjT;Z)-2Y#ltP6=IU2CVAt-A2M3UPB zzjQ3~6`*tkT&59OZ;B@$1RYh1$Dbts)IrP5eUx@xDEtcJFdy6X(jPT$XGPi3@^ z0nNe8`4C4Bt@|cvVN7m*0wleMPejXp`{zR+t;H^)bxrpZZA!%gIS&u_2e>0cV!q+7 z2HQBx1WQYPI-rBkL1kPYk7q|j#K3&UZgA;hA2a-6PKl3;;_FsvSQXcVM5na62Uy;< zr=1h2Zt|uZUQ>LsR4uRmbmA7${!DiB(=Jg9DmUHG&bAa*3n6MLNmzvuZ!lZ*{molw z|51MSdlItXWu3XC?QX*i6YI@+Tg{}O_o4sPaW~<)?MV$Ey{mU4mXNeSe;Vt9?%k_- zX9k#sj2?q7WErh9tkk%H4f%56q1~+-yEKTM__8`L;uL9m^hi^P_`@)Bs|EQQ4m^Xi zfAUv790~U$Bs(k;mY`*OGZ0k__HC7}*(}Ppqh>={j-T-;IC7H1xQ@nqPT%t8!;|)4 zG~Je;j#Z>9rA84GGFR_T*2FCb^;5k! zF{d01h1ni^tqTcnr)GLBucvNOM6u&i4tC%`ncVWi^OM3=^joof2vq~$R-h)Iv6q%v z?68mFQ8vjNj=IZ|rTSf6yMJ8)UzId&aasObctD#6%`L@;e0ST^47lqDvb$U%X3J6b z-Ui?q7nWpozY8<~biO8q8UQKCkM(GMP7ixb5RY6CAoU&k+(;Q!oUyu&T=!c91J|Xjp{U?uiGK&etgZCY_A(UxBDl0w-s67$U*gkY7XBnxG zU(G;GWwRoKv6bs8yj}CDVRya!8`20S2L*cHTe4HgWZ4hiV5PsLkwthPAvK~`rk8^E z@Wt7Gg$QJW6MSs69tz3rb_cIRL;6{x_^6;p68q6f%f}0Ut(aB$Lh?RFazP#ZRETln z4Iwpi!+S<+3_nG$aX$|u_@6NnF$o#8>6i74i^MhL-8a~TOBXTx;3}-67Rs0Fw+LF6 zF%?e54ESOsn#v)%KS3Wg%{SVvg+NnTw?4AZU zXirohiV};l|A^8WelBCrQ5Wy3YK3((=OK$Z%H|{W7w_R?79o{(prrX@pX7hZBU%PY z_lLu69!ov+i^F7KJeY*YrUb6N^473cn9mzpfPsmo5{SB}hEDpIjiyIEnl|1VL-=;U z)pt9&__I6lq**tetF3(RkOA1CK}8ri3uZn!s=Ha6j9HFMYmAkYC74n*1+3$d{na^q z>y}Q~BZF`z-tFh(Lr@(y#UXJ0Nj~FV<;~A}A_QyESTpCMCd{KKR-r9Z`Jn`PPp&2i z#FAq?ppDb~k53U&?L=Uywqkz*xtvB9D8+~;=Gg;p&~!;F>BYDHUG+F86l`p?A9fNz zTm?4X7Ed0QwLyZ73oDkrwga1oIuZCC$eW!Ma9lRu!thCoRXao+2kQ8*k2?_N7Ke|h ztk}Xn4oo|s+?LB&uGx^C*G&6hs4#Kl?mqbFa_Jax~->De|;2r*_d>_ zi@3gIUpjloyEMKzVW^rn>Qr~VrLB4~Mmwj9zcLJ$+dPP%Z!R}J#=8ZF9-A$@8AOcq zOuwO>RqBu+SBX1r^E(S(%y(C|y*^RtJnNRNxI{#*AbJz^#G3X8Vo4wRJe+S5_X=xY zRB0o(3Ynt~fZRI7Pd-S+Kej@qNVw>sr`0^fXin--aYSG3V&Gv zC6*g^l{!YT^RnfI^P7QIA)oI_)~J1q(E@*_eBLMhZZED&srYAr!;SWAh?G^3zWQ;< zWGEf6O(B0~Ni-PLEe;-4*{%Mn5=2xPd@b@-HeeF=PYt7bo(Gj%wMJdVZJbmC|!X&|O|etg>B z9k0N~7eh`ZUypqPcK8Sn*6waH1m7PE6nLr5WI|Epym_`VFu@W?H{KU5AVJ8BX20p6 zlJCaoR0ev}z4D4lT@OJKDnIj*h>*sgC-K=9fbI6ugH@aq8UT1-)TalUmoY~cj(uqkcGL3AVa`kp+Y$%&kCydA zM#R(+lTYkIYt3dZ0pGtXTd=qraF5md=-+cQ5UKHLZd5UG2z97IOU?~?7(5xX@pKVw zl#ti7Yrp2Iqe-hIe(yF8^dP7Mt=SC|`^s1P(r~=ahwGeW9DaD19g2e4hl@14Fw^&_4z^Hqr`(^tS@+j} zE<;?-d)PnqsG}^n;Hq##rMUXQrd{J$Iivb~?{jN+S~XuKO>E$^ArmoJC~sa^7SxZl z`Nrd`Hao<{PI6f*SRF^mTlu@w+J(-$yM^J4*KZLu3JmBl#D0q`BYuI{nLzXo0iqj- zw`m+H{+eRpO5Mrh+oOyVOJxJoshJQB_p93}J#&%MenWecU}kpwy0pbhaHKp=x})r| zLcT;5uAe#nV-RA_|b^gikyM*+d2BXzCK<$a?>@~nUg8(L8bjHmTqZPnM zZ$NSqV4<~-)nZvL?j0FTNv1&?7mAwtLcWy2m!wC@ni)vmU<0igF|PBeT|gE_h;YQq zlQE0NI&7z@-OKai5>+Ng7ZnWOemW}98p}v%mIbj1XWrQRD!~)`aFDLaLb;f!z`Xa^ z{}E=({ipRTqGA<|yQZJcZir#zJtRHd<-(sGCMN;C>Gd8aayp}-ADNt4N}Qm}P&w$^ zF8Xv7AdzEwh0Bos1JCA@UG>FC^6`Xa)HcO&0G9eL4ZmU@$uD*mn*5otJe*u0O(R(&>5w_Yt+kAZ5`_NJlbI9M z^X~W@ual#L8S~;I4_y2JvU_#B6~om;UQd_S-x~KsBk$S3=y+4HbMHf*(^k z^F8&piG#AKtHmrB#oT?4V2bi@>nF~*D7v_m6Fmy~2DH0C^K0|gNK269_vlUs-xiKR zhPA$L;yhYQxVL4y7QlqQrPK%be(P@lO7>|kxpu+AZs>J%lFf3^>o#*XOt;*PMXGco z$2MD*@YFW!Zz>_3IUHjVV3G%)&HGrp=s7A~(P`5ey?NqPgeYNM3i%OlwDJTh8QDG% ziD9k2mtu`U4}Cqdiy|G#`_^>cK+e23e>W;Y8!eHdTC$dHr~~@L{)VNwWV9CZpRi`3TsO4Wv!$LIXuJa46zFR1rXQh)$CgZQ(2soYW`(DBr}f9g|2P0*al+$-Ui3kJ87ZW2-~-jSM9V+=b6^0njN-(a98tU zgPgWyN~+kDsvIyYyX{fmboYaCRm}By?-H!FLNTy$i9q$R9ids;RL-{|5A?Gi`Nn?t zya|r)KI>Xh9(OF63NPnElhL_C|b zKQ6A%^DAbln}kUkzWNOfvu~(Kwu%kuN$N7gDo4!HTwE=ab6%aw%2mY_+xXg#(4pk8 zjqjM{l17YZ5^U3AR^)q>rR5HeI~?M{ixly;0hgQ}!-P3N)8NvmF8y(i;sjmOPlo7u z_IYzAM=^1+FFPkbRoS^Hn`O=f(&w5NC$FSv{>EKI8ywp_Cf)BTC}T=t7mz?Y|J@*ezW>YJQ2odN<|y%hc@qx4Au}xNQv|)`nE2qiX&2Vf1Mns9>wQ2m|Q;YQ}a2-_glYXN1>S z^6)h39U#rUjlX!UpsLWwU*v&y;R~NqEyk_?n(|9mx4xdPrT;w-K^wLV7bJsA_^!g6 zbU>~2Bb!@IK|>M&s6OJaK>KdFVeHM2B8rfeP5HUHV?c$5oltr1!z#XA<-<@<+qhr5 ztf{dIo9%K=PXd1t1r0D*-=_+EI*6zPO9yVb7WQg#c${>_m<=7`A-CX4s$@xN{8~SL z4HRMLpLi1&R1w>x1Wju-l^vXg(JxuXx4Cs(n{Z|NC<5iVJh0b_H#bv2Ho{SMldq#? z?T%Q075*aSFa>^Ci;Xs;a#u~$vU_bHa$?kF&bPN?yDR@H9rHF`}vn=o3J+pRxK6+k1ky2oumcUTuHi>pTXpC1Lgv?- zE8u?B7lC1NK}24VXClLwrw)~*C9zTJwHk2N2zUjsh$g|y$kRQqFj^PVeQbr z6yW8WB8;QrUk+KOJ0CFT6+HacH6H)xi~F0uyhBvFymqY5j<*#Pb&Qmt@WW72=CX_No>5l+=oWByep#a;`ONAP^gcCh~ zrUCO)fz>V#zvAwACsWU`7urvMkgG2c6G<*@~1Q1LTS7l{Eh&+^ae@sUrzcHsq>~c*1$FD zR(cNWx8AC1zww6da0o+DwTqNALlX@|wt(yYJYX~)7tS1cnJY6}_k;KF{>g#u#re?2 z$#U59!|ri;e-wcT!5PdYSKH<22YI|avyz+*+ts4+C=q{|dK^xq#p5AKz6XT-?q+~t z%3dA zME9lOM0pTgG+3WGZ(E_*M7u6m!ddFagSCNxe&2e1-1P%o!V)1T70v)ZK_Sanp2$Jc zZ@_)LN2o^%eLSP2c=-Ys5rW=}e9vTjYbj^gwS$R2fsFt7tQFPxb1IS^vTW(n38(H3!!DZBcnUDN~*NDMSH&C^-jIh*IBiW?Pe=T{Y5{_=Ko)93Dk zwoZL|zkcjggtU-o$^VT7z!(yw0bs@zIdc6}LAlz*qstH#U%75Mggh_ljF^tmZ@y(l zxjIIW@@l&GcUF@?PH#`~JqgaCX50S86mqCrjIKUUFFP+SiPMmI&i)N5B+3L^nV0}kJ3WqlCLf#qhKLhDn6yWhXB4M|HcpA%B!iMQ7%e#Oi9OXeBX zF{$)j!L&avi9{ZB4fUGeeW22&oVP_x-VdW&VD2-JonKLXay9;k>!>08kXx1Q z^;t!O^C%P-e(>JPc6oUyKd0S!G`}5pQL*&0bF@+FA&VE~*E-uTp;v8ZUsZ72r29uO z3Jnbnd*K}y7_RH>dQ;g;ZEgMPT$4iUr5r$%Kd;3jS2g({hXSL z9O6-`FoqRN!6oCf;x5^R&I`o$Os`C_zOglNc$Qky77QN{^aw#f^Md3D~AuZylW_ zvi;5l1;>e>=@5lTnCqi;;YMaN ziTSGbUmUt8hWTOIUq5*e7hcP@Lgf$h2S zVf|u2K+0)Q-Xm3KOZGoU(G4!A>j3{M=_f8^I-Y|GCpqowdDH#A)Z3KJ+2?4snX{P3 z@5brwYm{!T+GHfXFB7>iV7WYbH{Dul9RIdMWazomYq~=rG6ORseqxhHd^O6Gc0WpY zHhZYSf}}SA3`VC9maA%2t)o|W2~3Pj%@I8V(o5yDEF>zG8 zDrq`>OT-WYY5m`V^E7P^x?x$I2rnGvE+a6nN_xV8z8}89Y_QV*WWRSNtWcwK6GNQS zXP?ZKeyBlGBuig+@a@|-fiGA*TWK?MSM%>h1bRv<)0dO9C&88Y6KbIQ}%D}*FqHHs!tf8A$S?jO_V!t-h1VsZpg&6CpK0) zZ|imQZfk&@F*Z~uAp>-SdX+5wKhyN14Mm2){ z80r6Ow3l2CPPGJB^nf`T+@{&$ckeJ?y@et5(;`zvLAt=9X5BKl zlti>6ZQMj5VCCuD1asWlt~cBWJU-^*-mDQ&;^M@<8Z+E0#QqNB2(tq*U-tpY#8bc6 z4nkmz0dt&a>$_)a)p@1QrJ_#?ny)qfl#iaDv?^OGgcsx%l6VqOrkF3`g1WRS?jX8^c<)3`+BN&Rydqja zb%4tSgo|4hwhC?>lVs~y-* z?!*I-$O|`Oe~33O6UC2gDQh`KnQLGQ1It3-sivxH?Zy@moD)<7$Ll2rnC3+rH!cEa ze47;X6G$v&igo)!U)fUWZ^xX;wJTLpdx58g&P@JVzLYJ;pIiLXwEBA79~eLgo-q-@ zjjj@=o04E5vKwy03?1#Cx3GRDvRAnTD>3YB+rM5l7_eiBgQb1TL5Q4$=^kdla#RY; z!IaujZiEO2FH!l5tWwG4u8lG)LKmiwiztH);77JzN7pW5}j9i-P3^f0@23C+4Il` zwgEz|#QDyIo*7oswdBiSYTOvfBIB;uE6HU>fQ%o5Sorax-Eudv@*@VbSG^Tv1YF5m z7}NHvbta&0Hago&j%- z!czA-U>dd0K+=#NAQ85_NnLeo-{vN!7;k9Xx4EC_3ihM|5(c2(1GVLYTW9JNVim3} zL<98$Z)&Qn?4MXX1z$L!Bbg?ZqW1WLdW(FMiXOyHcC@!@yGTV-L@DuS0BuG{X=BX*hz_Ehk*gPc&Tu?;f_ zZndj`@b$wCCIP4dYnSw#`bVB#r#5RejEJE*YE9}GSRHf|SleKfzPc!qKZgS3HL31Q zaoMC@w@`A<$lCoibIyyP8Wz``AdF*zo!qdAv+M@EhM9#SLXR9d;9_42r#R~b*Oj-=Ftl&C~&XxKcjR{%j6c>gj1Db zAo`%vjS~ONRGu_;!@0SJ2>S4iiDM+hVIK>jeyKD!^1!rm<^EcXME*o=>_Z=bV_pT? zB4fSMM_Vp~O*y_+e1ORI-# z#;AOmmWpO^mvT?YD6#A1*;A4t=qGc{W~_MWD`T65Ui=|a>PLqQ710JoxO?@59)>%_ z+HHBrUR7qsH|hEYm6Ac=FL*LdhB-@5ynm*lsQxPVO3(vOD(?`}!z9?LjbR?Rzg&__ z3zj;Ir2Lc~xBr@+zP;q)C;GzlIybL3i=DL@l7_gYh#oNM7(rEY;hZUmyzvWF>7No- zo9b8CdqBuAF-o~z6*H@a2#o}Ec{Pmd+u@v)GyL6%UFE0uJ%drg3Kcnt7K^yKe+>r1 z%BWG(SP)78WeU}1P{N{eXz~CsF9xh|f)$qo-g?CBXy#PKywiZnTxSWC$>l&Ptnt0@W~xT;ATmzo;UvbxQNS+5 z6Un%Fy|xiop-Ys9Hgv=E5l%kxEN za*5FfyTZ>?r`dzWOg_43msUaYE>E*6nxI;!o2j@36Rogpi{SyD$#)YpR@(}}TjvfAgX;*Do@Ph_3krL!od ztV@e?_ETeif3?VBE9fG+Kj)V?r)g2jTcCy+EEwH6@<(*c@zP?6q4uNc2hQ_fq-%eZ z(eVu8!j^_=+ro3d1}7*m=cpAX(Nifp6t0WOdSTOIxa02QGa<#bLyq|y>Um=AU3pXS zqPU+e#(hKcyuxh`pI-a*_P!HR>GiOf$wiE~ZTY^Vx$vCY6FuC_J+c-}177 z5&htQ&Ezljox3{0oHo0hlPp>tQ&21xKOg>dq}hNBf{GINLRb3B-e$-82UU5!q1v$h z16wNtGO07m^a(ExH+#@_(u;sJ$TXuZ8n_45G9AWPn;KZq%0^79zeQaTM!wOrPK6u9UXGz&l$;s=IiP1 z+y&suXA{T_DTqa|8BNk2fH+JX7(_f7j2!pu zGv*xQ!Eibd*Th)BLxAhjlmK)5n0TQWc2M?Lhou846O(|ulcCI|s5hi$zQ_CPnTqe< z`}prsJ2`RfWKLVrW_FYPP%=@#$gK~v>=9Ymn3uGQsIGi3lh`7SkVo_Wh&_1_l)A2A zA4=-?6XD#6GYfbQm`pF_#v@v@KyFBlDxiwxX@dZSUr}3%Z_<;~rJY4}De#S-Y~l8d z`)d@+OH~6{sLN+O+?SCO$bj#0O&m`zSxzvMfrO=7=jd~T+;8u{;WYK&OPRmaSsU7b z!Yg2T+$XIpVtsewAA3Fs-j0RJAjL9iK-rEw0U}d2Cax}6iEqsVkG(s{mN@q{AxNMJ zIrok$3Yky6#@0Tj?=_xt%yeaaHY(l-t(}f{AY%Swm zylBN`1$%mW-Ju09U80`YA}w$G1cv{heJCOF-eS3=tUyhGX~w3MoEU~CH){MnP>}b{ z-{R^|miQaXG;mavRVkG|;|y`LSry{Z&`D0ew?6WIzxnnbyxms=h!$TS3-*|TM-OYp)Ob{MQ*_aZeGEAtz5j^cnVx$!@q00Ub~gd%g$LVQjkf3 zFO|4UVsg!h`W>21*F)kndX1-q7AApl;a)1L9c10h90v-aUaR-!9VFdN61U|m+2c3B zP%508uU(IG&y6NEV~Xo!pmCZ9vg@^VXc2_1Of z#7T_*Ky4O^*ZpvA-{CJ7gB^zyif)9teRu@2v&AWo_O1DD{1b|Q{_@O-#g+i~g} zn1?6_FuPr7C+REkrq~th0tc9TbUv=jHW3pWlhJOoWZf#sUokJXsIVFejC9PK?se(3 z$h7WP;$zDeiu56#XwmvhccoU?ZET&NjVn!M&LGVgTn;749hn}B*GcAz0Fb9mO`_Em z1!&yK2Rg8nk`zswU#DIEi=(&1gikwzJyV-gQNzcQMcwhBne#67MiZR4soXf^;Cv@ zKuimB;g?QJn-h2pL*F(7XN&=k+>Lnv^oRO{x}|m>htlIaN8!bG8OHd-AkhxW{>G~w zNtN0iAcPsx1IRQ)BOZZVkHPBuvX8PB}yadmk_K?bNiLz#aN%dm)A#o zb!fx;fu|sZ*6s%*`k^mn}NS^zq0hFYMMZnYmBb%zfO*1X4kr ziT}6?HFy?ReIxDVaVNnORU+6YEA1Oq=WJ56D&-vgSimhtja@c$1->AYCU3c0K?u5r zmBX)rVt{;3jg9gxBCNaRs-L@;y7+e%(dHQ;-1NQXq}R|i6xWr#0790*p|+%%+t4g;lw%lDX0?TmOtfaN-5A8sz*9ISv ztd3HGwoSwp`Bb2SI>_nr=Ql1{#!iUUjgbLYQaX1d|N5YBwi@);Ai|=(OnaiU4{7M$ zBvxxy?0sM0B!uS)`(D3sYz#{xf3fK)nb3_8u%xtqaFr&^-NIZX;AY#7=yLtk*Jm2d zi;p;b&HHgOZZ^R-9UU(Y$@o;#IEr&()8ux0#2i|v%Vmw5u_)}EtQ8l2Z8j73ZV=kn zSUukLu`dEkv#}ev=IYty!HVqe+`8pQwb<-3rlOIK{Uz~#gj>b?gyaAG=>Kt<{T#5N z&@!JnA9{i6Jjn1TJp};6>;!Q9kaY$LjTssR^TCr@E&*UGX5P#KAg@|)PjbkT3iP(5b)5nzXa-j_g}ij?_gG>>k_KUdy5Ul=D9b zuB^b;p<*Gs6^^xXdu3wZd$Urr$v)=Dx+U~V%HE>1U>Y%<2Fu#S`Cbz;K93cab4cfD zB@1#T(7>;vN5D{hL!Qsr^zP&C)f-@TDS8P~ytcX{CygJg&rmKr@L2g~M2yulnRVWVDIZ(8kn^8FLp zwLA;@%TBZ6dPE27)1qE+G;`*NQR9$}XhbC<;6O;xq*+mm4>a^-Ai)+Kc%-Cs8hSKo zy$)+sggH|C8HkQE`x%fEwHjpKFUfyrb9(M&6h9@zyBHxpj~mukic~i>$L2Rf*?#A7@Yc7Gh3ffBJ@h=2qUgY@ z{^}jM$cn3SsIP_)okx`&f*v>n9zebLbhtUgg&VyYt}U?_#gsDR+}DHNd}iP-T1B$@ zw{ys|)P4qU+{!F@GMibC_D6f|CR>L+N|S@g5uUVOV%E_4>2uH{J?@ppUyxW>Wk{vg zKe9kYg~Fhw~33H!{D_;oHo*$E}438BxSMN}E-e z1zn#WK6i{jW>(nmN_I`sb}^|n-5(4N%cjq1b6@|A!8yR{o<-y@jcJ#OxU zd+APkHBFL`acRU{{aHHTSB>j8RUD#g7x&E4yIflAT2SV=<4NW>og2ECA|)NzsipR+ z8t_e86hy6$&TC|sDZ3L1KKRM@En5zEgd9I&bs({0maDcM+I>)we7CZeWD)bqONaEn z#RqCOF8GX)yopNids=UaY0?W@Rem{45ZX?13DnpQrw%?JB2m+~+F!5{JkuA`OSuSddk%RinEvZ$1krXDO-9>srct*phYa+7`ON{Wp~EQd{4)9rF=u>AO+j{IvTTA zQNy4%NhIf2Yca@WMrg@^Ux3CW^%85M2U*ib)-#D|_Au>e)Dj<3AwT)rGbZ>4ZsU{OHG3!buk8Z5sn$SO_x6$!Epx@t;oBaiyK z5&=0ZMrD{Jt+$p_-xiFd4gSB_$X~3p8>^tenmRDc?6e^emz!PLpKTf%Z`GE!5B`wd5fMLw|3?VVi z!tL~CWbITOu1IFqiY0zYSL^%7@CAvYUpA&d!YGs0Lm0GIz*KIed9O~Mu~J8qm|Koq zO=6lO%=n3i;=2%>oK-s;Jfdb{m>O}Pv%yXGONeMWmSTv`N%)R1Xaa>g2M z1)?=OmbC+7EpKyWhcMmS%yv76>fjgdwG|9h;ud@IUM8trcd<&DC=X8eW=*eQl>(BJ)$Uck2U}|=~XA3 zv9vgCHnA>6fUs8xB^aY`^0Uxmq-9e>|JqONx7QKl&DO%q-+ZYgr>K`Lg_@SNgWcqr z7=Q_B)XR)h%w5Z#J>061;3mB=gG7Z&&}j$d+EM90K)grz8Y18%kliYlSti-GI<}!d zk8&!9FxcAvy=Y~Cimn#B&F?9Adz@&A6$u-MdIf|{{XmVrSz@q8dqRHV9=gN(;#?Wj zT_yMOFS#ER@%{u3R9T~cq6$)_9eBxmDJ^Xz>?jh-1e+cf>__M9Upwr9*_0Q@;!U0bhV z+va#ggj}k8l)^)U<^&xNCD>C!N0gq48%-106Hb`?sZ-!Wg~c&yc!skdV=tL|y=ZqK z%O#G=EK+**gv5`z9v8aAgg*uNKsH>}WwhJvJUD>N@$XNNqCrPo5w>F6M6^G5PL0T_ zSuJynVLU^8{FAFaANN^F^>@r#)a480S45X~2x)>1@7F$G4rGL`jv#e;A)R&5OsLM` ze>V)$%E7;b*?&RRP*HcK~CV@N$c#_$#G4j8bK)SODN)Bwdy zo<$lSc)A##DyMnN%h+WOMNddFPt!2jVu7J&sC^jM5p$jmf0k}<4%ER)W4^RHq<5*c1gVe!vEujog7 zOWFd_J{a`7ZN(i#H&>a99t&1TQ(YHJ!Z-cC4DBoA%2m1bCROj$8iWIgt3Z?N;mqC9 z&RFl8%ZGE=As4kUrP7IUmINheOFAd@XXi?=X*$S#=9WQrJ<&@4^v4(%FsD$_e*HCI1I0WZ_I-G>y}~?JFp0gCRmx>^0WG1 zDnyoh+>^%EWDYWz+Pc`_>g^!FL_Fht35|UT-2qy z7;Nq)fPhwb0HY3oirl>^h0oJWSUwF#L`EB_aR4EFB0?6R1s?jS!*&WYs2{qf>k1ZubndS$l~OB$<6qlanE> zARejsF{N-=SH#XA9?G$^r%RkkPLN&;aTie%cg&IY#WO2ZLnAZ#quKU$u!u=L2)_8x zIG2oXy6skMS;;TYu9YEDwWo$_fl7u-S%395On+ohxuyZ4H7*wcR6F?)YkqK}VV3b& zbA37Ur3MSSDYBTuy@SvDrF0StqohBdwO<4zR@yJpf*oww{}W*D4@7=*JuGW`q52Y5ZT|;Q#*t>wno+4s_(#A0V;zMutf^f2bxxWSwpd=J;-y zg;5@zzgtVqMi?B4eqv~Ve`y6^j!?bMPM!;IidX@j#Fm zzzsvBeaPEka&S-Ws^9eqLZ!yf3A-i-(?W=)c$7sYVl|lIA004d74oC{e;&fn2{btH z6AV^^WmzdNz+VBBSteo8xW&TiD(jh9dN#8?8g{Fez>W$~Go#{xK($SHZDf!!>D=p! zsV)wYE{yL+X>V2r))pyF73p|!Oi0%lU4snU2tkTw3~|b#xHo78?&e?Cir&3@*BE6w z!b{LFU9(L-nxD%ogvo5BwNQG9%Ju;iqdljlqClSE zEzkW~W)?MofD|X4dvcX7UF}*;Sk^Vd;(}4BPQ;UF<$P(s03s)hj(aU?*;OtEQ1L2P zD5Tp2tFpaVM#;{xF2dk5o=6@dtsB!`b(zy4S1pj0Dv4HJ za7TX`TCe|pNhqepkJBHS1@Gh(zzeAMVTB=t(!+Y|wqytfKdOUg`Au^ju#S)AAX-ES zY!_;Gf-Ou2K|!B7h!cHhdnR-`U3Wtbj!6W~wa+mep;PG@$bZGr2B&H=R{Isu+&r4% z5IqM5kPib!yO*K=@Qmi*R=Qrjr28)8P2k3(7~8fTCF&{RfGnqez+Q;U-{SFqxONQ1 z>Q2%<5~b?Eyyma^{^ue-+s0d-(l(U!Wu|9b zClSbtflA`)$xG@C;WQfe*q*e!6i+)RKGCXfxZqhiZ;VHD*SdJg=z&-doM4q59`VyZ z@*mx%Uo7qO#hFex@t;Q2v4@XyEQ}V>$ndz@C9yxIvca zH&qhn)ekFb`=VE}Vp?7DYLrr50w)v%Pu2{6+m;ecMq)=iRQ{UBu1LpPUJ^q++N~~X z>pDS}`$*&2+a1qyT0aUo&yT&f0@e&z+O*bCw2^qxWYnHiLsw6SI9oG0pO@~p`o0E? zkwMF@`>j5%Wi1o279wBQuFg3UwKC4NPi*umfK&PwsuT>HUaFcVKlX$_wzr12F^lNy zhacOZNxt|;Lu<-miv%7xx~3M2w!n?nPJ4dWA!+9BHH6#(IIFTZ+IY0<`eO5@_pvuk z!*J2#N}024J*NwNZUX}y=Vz(1J?KN2!K&Wo&@GC2z+i)8Y3XAl)XS@WmBFT}WX_Cb zysE2*PV#|i{Po1qihrB6Gg^%SDVRrv7e`r1G~E& ze_TXc1vO_x2j2&}xQ?+phPDlub><)11!t7kd{x2CsbQzoLOoRc*+#NB^P)o&TrYe- zC^pxm!VXwHH;!u@>?F}>i;a!W#P7um8kWHjUGD3T6eb;!m#wIx8o}A_asa4b57$T% z84JfLBcH=3%K&Sisu&USR17Byu}WmAOYo5$;+ylVCdj)JPCcUlUiF!Z!$P%?{sY8? z_eiPuK?Se+<5jRxV>>gX8ZlA%x?H6FvBOZs@T+V#n?Pa&E=6wb8~S5&taT79JGt;| z(zrB2MJKy85+QlbAQPRZXnWY>(t8DA(yLKb!{y#iz+Cqnxx%O2 z0Oe&5diPGN>gAB5Eta-d)NvwxTf}C)TTp8EnAKr(_JP!c$CkP5O8BI?_afJCqlIL) zzME(d(&89P*=5DzTb2Xo+sh$hHjRE0)+$?f|3<4Gt$uS8^JN=fs#${tP2wtc&kA7& zTM-@yMWSH=AH@P;M($G8+S@zsOwlU|%~>s@pd4f&a|Nw_+yZ8(dAoj}Vi{msO@2_6 zH?ubU7j?{SS(-u0J)MQ-64SUu9s_^X2bg=sA6~>aL^ZF$%J@a9*niGlB>HlXw}eV5 zKk18QUg{ETSIKHO&mtAKNwQX}4g9Fp57l-H&nGo`lBTIX^Dv! z+t5rEpem^#$UzRz(molxIh!R>-((6YBn?1GgzGY+nxUFSgrz4~n<@|9*V+*fn4A#j z7+JPCpehrpV8fQ~%e5z|T}HQ0{0e9#G|{~=9{bFNgKfiyhZ|5K-e5~uhepVW0adMO zRv;C(Emf5%DY4u@tRk`1sN0rScr@kk^DfV4Iq|q3?9*q{;j{eg4>;d9N$^a3U)P!o z-OR=%fC=%V_yZx>m&9z@Os?9hKh0_+`U!NphP5{JlIW|O)8s)jZG>!Ohllq0MSSVX zFW|@j6)n#HA4))==`!tPI^>S$yp=A^i0IWdK`KR@H)~xHo_8B>803B&?$z^10r@N{lpXrl@N3)se;L6E{joJ!3-P&1eETYb~BPrKp&j$#d@cujruk^blA39 z)Jd>7u!9{=4PfwPlHq#$mM8-vhKo=$szD++V3-$!3PjjyIC)ayOPFWK9Hf>;>*F^Ceuz+ag8f!UP|Ld9jgZ??N{uTec zLc&Hy5mlgEW9`eJ?t-_}GMRP&44x3A_di9#H$CtaB2_mjJoYdA`LcQf9 zuG_{0l+%yBU)m9#GUpsEN}ML6b)edjyqAcFV``qCUf2#|2M1jC*xSKAw(4ma#oUQ5 zuE)%1GCeSiN@MF0e2nYGi7eL!dWh>vf!@YGUb8BGtNTr(=^TLge(3enfy`Nk zRvjiR{<*dzBREIu#w0W_li;CICE#s`^OBFmWz0$r8WnV%G3XeWjqqfsb`qG4_z>`d zi>#)d6+yi_yY2~|WDfkESx(B~bs5=4oupm+n>n*t@A?sxy;Rpf1>FbvYL6Af!W<({ zIB^5|&^mAapnUUPL;gy5T}I-mfCM@^G<0v&j(aADx3gXIFm{y@Q(t|7o1^xlc^I`O zc5mr~9It@A_vN#HFQ!}Gs5`(B1jizs;(f-#wAc967Hm#R?&G-

    hG;krhjEW^BUk3~K*JrzPD-efo^W&A4e-~UH%XO>UgYfZOnG<> zV!WB%ae6D2(d=scqP)E|A-`}CJ~*0e2C|1Ll^X?o;Yvc4{Tnvm&(_H!wfiO^$JGrX zCXiZs+&3giXxG~^9{P98;=mqUAW)08BV}PRL%yN5b`7PgqlY}zM$TIs#}E6DM7_%v zD44CSYBr7Wq(%+k%Q^KC=)OO-bh91)N`R^BN)umQ%uQr*oiB%WuP@oi-bf(z0fjMS% zB{FT&;T3GI>zE&)P<%2f&inbT)SHdSI6<=2YkuU8!Dhh>5dxwDZ#1?6j2G=fU7t_Y z^_&U8Aa-=q3+^mhv9vM3$IZXpJsmE@p29x%SK3-AukyWtC}wX=f0hRIHmuQkjTFYh zr}n$=bIE9ql_cQXhcSP8m?4?7j@adiHcXLMlvB`PtW&7@at;egl`nP*(rHEs*bN;p zBRqEz8`3b2QpEx6upB@ozrTyM?CZj?&iv_iKm3RpxsqXUUHfkvm?sf^GMRPB%+Uu*Y1yohN-?PJ|iAw}GJ$(6v{$ zf7d25e{r-!>1`p)^Vp(Jy=54PH_6h3O5T33V~xwRL1X0%mCY!Jyn(+MPqJ23^!`vd ztacqlWMz7f^p4C#eqx-|Fkwj6$u8qY0jov9Vy9Ix?C@?05PN09 zwVi{Rn!(CpEnc;%39hCkK@Irz@N|HNYA#)F6tG^crPM2kQkq8EDCq@lBX{My`JvTs5sU6oe~6b*TSiRZMxC z4L_5KRB}-nNvb4rO+%+ntK4e`(W$?t^fykC)s@*wp%qT$8J~{RD0u9+ zk8m>FD1sI@0ZptXU$?&5d=D{;vHV72z=dTHs#SX7qGm38c@|Oy9j1co zcm^7V=U%Dkk?R>+3pFVv6%rSJuYecw&_(hkVum7TyOYOGWKZ|3I-8xAf`FJl?wePH zuFO$H-&I*7en^Dasi+nT%60uacwAVu(&VtP8O(d*|F_)4lF~P zC`ij9tBZzkz7t(p?;3xz5aoVDoOhwt0$k&dig%{*aEaM=z50#b;@BV1OZM&`_&Q3V zcgfcP9@j+H+nblODy!WxM$fCz>}n)1_O{R63QZ;rHQkShCpPVK@Ml97aLS#K?{T#t zoRQy+E;&Wm$FQ>-P|SH%z;<<*>8b z`J4D|)96=x?gRUpuf}c6^}{7zcgqWd_>}bkIl-fSpvUNU>+TsJ4-Gs!$NqWJWDl!P z;q_vK%lDqspZDk4uN}V4o-{7sBD~F;$Z|Xpf-$9<>#|%fIt!w}8 zs<@=U3+!KykJBv2{-nlhuVT>G9Oy++JP|B)!h8EYZa(nxIynjTPF(57Dm-f4j#U7X z?&gpTTzMRZMMb8B96k9u1VUUp*4W_7w3&UT3HIgB)rh^&7n#mD{vDP_JMfoL%xOgE zrW1htVQb%6@jo&i;Ncyq-iXzGCOflLv>Bu1!a~%RkSQChw20q0J6pIIo4`uXLUy*a zfFxy0saxMjq_E*Au`GpwC`HPYGZKY`Th2p7Oy%YMG8=T@jcF$7fHbXJ76f^NLWJP! z+o9^#Qz)_>NPV0k>qNy?k3go<4rXy&#k42%k0wOOi=XXP7n4$qa1 z?zW}f9Z5XJI8+F^yht7`TImJfTBH5hcmWRMCO)8T26TU%MOy?~HGW6u;YXO7dwjj~ zXS+om!3a;ENfrT!xz%~ml`&8_E>>v_%c{jwVfwsX0$m|20VfSi@w(XdMi9U>Ms@r#341w6NGLQxyWvw3C$ zP}1gq9rUPr&Z5fG(b*C(^X+xzvG)ARp8lB2*4Fq&e;4I7SsI)8v!o23c2FvnsU7HE za&&l6aPZITJ>t5rHw^;$!0CU&6iVZ7Q{~}{t46Cyv z#i|HVC=w2dsOTtK8@)jgt@CflnzJ%roeV;kfr)4>uy_swfy86chr5zCORCI=-F@c0 zll{`#tbL%k3Rl2~Um1#}XE&TWWW0I>M?Kp5_3R(U8^B-K6%~ktuy|^Qb^c(=&NMJe z^NdVYee%{1eW)hspVPk~jTSmu)L+&gqNy39|D(Xd$3PeKj&Bw>_GIY3N<(t4<~JgP zm)wRbm7;d0rDVUIxaA({ZwB6e%_$c#Ma`GuxsHb{`d03x&iz^bShZabhzc%j!XYas z-4+~%h8?ROWuev3cM35oI@@ zkf$0V@?%-EMR~}}^wpWgx~y<%o`L86!lX-#H@#K^YygW3Vu%Lw4aNK{fVl1n0& zG%|kPE=f5+ccyEaqs@^*o+BF>9xmNKsoEBnC{3Y$I@05=3P8N^j8mF$2Z|@4fAm?p zWE{yw6pE`pzk!B{q0m*iWkSHY`wlS7V$?9OID!Ta`{49vkwJ};=!pyIDI}am-EJj3 z6FhTP7*0AHkv;oyI*Q) zFQ&N>N-&@H4=R=)ELooy-@T8htpgE8Nv`r~vpl`{gL`5x9pk|!-)kqBdA=aSC6br1 zd5qbU{eT9W>MfoI6W|6GHTS(^ZU;NLo;Fbb!PfQSa;keRT&%vsP9=9IDbCexW=b7l z?i$HwV^?)zHU{W==l=a#j%h_0b(&)R6I9z1$wwRBBGgvpDq2qFp#@A+@mJ+oE znEJP?q>2fRGyiWbfUEEJJTqtsx|SLBIN<7eW4{W2db;Ou(g9u6gN2Yd%$sVs zDkNTX9ceR7Dx23j;a-7M!`1b#Hey{q1F8uIWF@v&#V-qfNgVD-ToF`^inKw&l#+R6&3MP(kDFC~?~XIOMbuVegW8`Fa>HG4xpEuF zy{<~Ghx^FdIe~9))w=@GmI_W386HM+{NDzg|5&^$vAh_M-n8agJ2HA`{`4narRAu= z=ojOg+YGbux4yV;q7IS>**=)`E^>K_?;O4jc zo0qCGS?LyVg2yDm0M}nX?;7u{A0tvmPz}7$X&)zOGg^OSI!16%Z=!`iv!0Z@`kns7 z9z55&lufzz7Rfo;f!;udI#K+v;aKRoBlt}qKg=5_^y#>Wa(lI7WpPzc>fd0;Z+=V7 zg>Z_}!_e-oO;>2F8i!gCOr$9W-9F4Rh4kfA5w9oSo#ohR74fph*(8w}SCs5JAS{3r zzBs)AZ`EirD5ucBFbD;iBYPndxtz{-U{^04l~q5hBxz+;lcmr<9A0^C`5;VDdF##! z2w2aui8~NUFQP4q6X!-YrV0Z{7fiXXum}YPIv-cZjY%oEP+hfhLnhFi41LEGIWh6G zC*8BhKFZ1OyD8fUIZ0YV_exdNi&&;b+$SICVA_|PWkoS?6^^l_4!1^!Dkju-o3v*}n;8$`K z!%xr~VFISpZrH{$H>YX8v@g@AlcuTfD(ew&T(i28~suK<4W&x<1D^?$r5 zj+X*P6jdZFJcE!3U;mMeqW_}#v7H$h*ZVU2oMMUK--TX5@3S;1A|lg%?K?GW=~`NZLVR>E&@=_`;u^&>74I8xyP4^F ze7JIymOVdDbmdo8ShzFU=(y^8pSk*&wR(I`V4e%XA=dkDX8aAya0$;6vV^{)j@Ke= zp7sTsf|{n|v?*#rbZCtc!GHR7ulY;s;{a6$e{IC!#0lNl3!>|p8jvh z`C;i|4V$40Y8z~@q<>=FnK!yDFQpXLd&-Bg2UW@0L1$chS1!XjxGydNfvZ3k>m8~%J$Cu(jCpw3qNRYe#qys&cq9uDWkm{ZP}&Ssb> zvJxdGiBj#((2v;8b=H4sQiK`obnV@GSwNMj$xuW(e)AIlP@+$*lp3#MJ}j*@Tk@Mg zI`MwA-tDaE;6#z=h#a>J^D=AcDQ2)+je0r9Z>PRq+|5-_*VJB@B{f{pntp81tUm$! z%=OQ6@<0vYX*=iobCjIuyf+Gt`tJOP7<`vuVcSx(3HYi$hj1@C%F+FTjF?{z`o#4q zf+?|2odS%)x#kGto9O=Rd$SR)>NwQZMyn!20`ua-tmW74y+@JNhK-#O_=8u` zpYH#B?0+BpKT(-N`$vT3f5cv)Ep+axH208zda+FUI4a$qlrQEDiB4(+M00q$iM9oi zd!ibtTr!xolCZm{k>Ip17%idrJA?GQ-2C^lVJyO510dJ>lshIyFWZTRiUC33r#lFGS`I8H1A8E6tF zmLc&1veCC4@QF{Jwjlv)KS6k@tZZ7b?N23VqHlmmu=Qi#x@N6sNem6fec45Zv8e z3bc4}in~Lw2Ir>lJ2Q9gojD&!o`-MAKj-Yd)^F`&dKS!sqA8=mt4AMZ<~t21tNLW# zT@=*`jK`?*2op-t#8)aihCuX6qH5y!&ZS|MAZZpjxyEM`BRp*9>!-0`TDm|!Hnu~t zPimn3#V5Qr+lTIkroZN@7I5deP(`p-uo7u^9^v*=+e5dRgzZBO?&aBk#W}j!{X52AO)Lp8w*We*8vlB9X5C z9$(1M_m6yO{!FE<<|jHkGfLl4G|n*@bGOg1h46rGpVA0hKGIE^zaT6rcFG{=b1S#( z1e+ZFsxBgkz0hQV%2!x#N;>Gde^N>((uVdqGvXBqt(ptqK=3arGDrC9iGeMJ1Xo_- z?(R_o$6`w#r&!ly%D8eTOcBeK^Or)GjQrh87&Cq>uRXfuUXI5LYZp%(ct1kmeCIU| z8-!HjWi^aXyiSRWK2H)G6-Xo%PPJ15z;*BxxsGRZ%b;z3Tt`GM<;()v zxHV;Wo}b%#TE9!7GQ_hS0XUoipEyK4H}ZN$v^@t9f4my$9;Bq6BRkv{<|VG4B#Yri z!*VvBuam$*XMH<@&##lYX?)efF1v3cJN*0q9_T&pe(HN4b%C5v2K$tLQUCtA#P^zK z$>+jLB7ay){+8rd5;OLngu5RuclUH1SEaAEfAx1fjW$VE2Pk6(EEV|PYfvXjwa%Rc zfrg7LBwsubV%wd=g*cu^WHyVKzfYUfJqR}XVs6Obt=7P}8Fr@M2fX%wrnz@PJOI^? zfVI-$ek2@r@z4?Ot}<9&PxJv9H$`&o*5akUw|(jvQGdjb3z8X_ecp1RDTNC>(oydw z{|C%KV`p(VG}X-f;(FSA&u#3jh~-RBx8GY2ntHS(ccBT-dNgO=K@@hwj%VT9yTy95 zYX58U>iB?n%|(pw3ZMLl_jI1S&NOyfdW;A!fA-09fWnMId4mVcW>oRVP8)YG$CbCL zHk~t~TdR&9I&3()f1vF`MmEsO2hvdFiecX!3y-$+uYXxJ{;90d3ue+d{L*so+Sm|W zTcRr@;aL#GAF@KYa3%d$W!dk6385l8uw(uJ_Ab$3R!qTFx4-kcs@<_+YLZ5R7~pn& z(wrcrtMc{+#{st={5i9+D{gbjlSxTf=6dhLih?qXUpcVN)KsA0ws)Vow&J9YaAY)u z58YQ9UlX}M@Se~fhi|bC$Av+q--l7=kRNPf8A{yvgH4wTT#Fdp?b1(P&Juck?OSls zCFqpsfq?}l4LTHC!FJxIq$?_cZ`aW8_Am99vQ*!c&lJnP85Cgb)wN((!#^5qszb{J z&V)uBeN14o(*By;p!ufHy8}F;A3tZnO$pe2>hGN1Ab9*`&Fk zi_s!QZpnIcplX>Ivwt?TaC>$C(c{dhrB%%D9XqoS#SL2^nX>s0@*`7wV9d_NPYVDq zRbt_ybHs8e#dTm2o$knl!Rgs{fKH}FH=0qKwzPF1Yhei(OG(=t)LYPnM%O?pt*j;n zU^{g=f;VE-_q^wIt;j0^n5!3-GggrDa~Xgw+O%SX{=54-6kvlmA_j_>Ys6~Amj;mt zlI&jI9-W|YbZg5cc~zn!{%6S=)_r20fjIGLYnG+Bmjk_DR)C^}>deY3bd?!ndRe1N0}_1G>3Qa$x{cV1 z-Re#b_rCy*UL(hH$cK|cO%P;8#=PH6K!##l1BRWIvakFQt z=IjP5Y4;yNvv3Q~iZuDr&3t6jirI&%#1>WNbLwqsY$aVTa&zRXGHmJ%z|Nz~C5eLL zIOK4Q1`Vg9BpVdcGl7#at|}Ng#i86Ns-j#0Njo!|3qmNWUL^+;&l279fCR6FHVd)eouxuBsQqQLwEPhrso8KEfn#`U+IEC0w8YxzKU zbV>KgvV!K+2OtkNmw$%I zsZY3=WCyc^br}2%Lh9n?tN?LlNa2)kcIb|lhP55Sf)@=-T8@4`PtF4bJa`8omY24K z=9-xkpEmx0c*1UlwKSDZ8&8nizgu?4J6)9g@5?|I?}C!(|5(Yagj6V=wUlb?$%ee? z5d`hK;#*OZgk&slSd@sZ^#>r(!r+_mM^&0_bVo*Z5iVl9$~@jGU1kCGxWE(D7OEaY z-6k#7{FvEXoAjvME{JZRCZ`r=Y0Kb*JYk5boXiiwJ8fRlnh8OiU8k-P!e7_U3N4h+ zoe_?(8Hyqa>2!#kjuEYq&dNlHsysJOL!XFRn+9z%es&_CisF?y?NkK<9O7Jrau6Nr z$u&>)sHP-YvSc-+s5qlsie~W=_UVDw{*HBPC1E93)Vj_V{iZ$5I9W$uy6cH+89bqq zElX*_t7tQ;uj{K4xoOuQxM5Puui7_?Rjobs=498z(zIVKFk}RCp+U9cyy zI1Y*~UE8Z=W0Pfz%VHA|v00S|Fzx=FZ8` z&&Xh*(z(`L&5D?W;(7BGN>!?}v40_wR~M?BQniLaEjU$pPp#C*=mfMrtqiy~IG@*|0r@pt|umW4{D_L(6-+h_NX6yf)F2k1>a53V##zpfL@g?TZcJ#i{zQUOm z5cteWZc_pQC$b_ixxS*iK07=ms^xEJ0u}s9XbKygj%B#(V6DH9{M270>IQ4Clkx(2 z1`USs#MClOvf%Z<_8hhh%!$dj_$Mf1rlAF;6rg*c}Q3R{-EnDJHf z{np{+_rZSIcb?V%g=@tmYjCRsPgyEjXX&H?`}F<>OcidNRXgi+t3Yy!6Ziz!^TU&S> zlaDY}d|;5{!U1RrNe;)AlFlw)lIt^8h+I+?8S19wyj%^ktX5ebEvLzwcaVP0 zE6gi(C^Ms&#(q`f{)$atYyJ%4puM|GGbfH?rKtB7ELn>GGPD~oF}w8v-SAfzMecso zT@L8=Z!~-MhLa@s#YqSFzPu`YY*vXz3ryk1Tu;-->qJVyqqRZjnb4fM$Hm~}ymWEL z9q`&)r~4vyp5n)S(6NMAB)nO6?g|})W>wouFesXD<9$3`&fo25@5Cf{$) z;8|bLlw90KylNL+AA6ZEW20{&*TeZ(=wFGaJjtG<2vsV=4chgUmgODl5|~1*FK|Qn zyT4}DGR*J3Ly{ppNB)+*$F_&NK+AulMtWpu{7AoUWP<*|ZN1y)4$mJIZw3AZF`>ifK7eaf@piu1kYI?;M6{td#3Nsb1uR8Q}@cCN0=1VuO-uYKXyxNGi-M(6(P z^Kg_O+M6X&T_`;0Yn*YB%CG@eT`hEy{X7{JHB}3vu6eM<^It-%e)#svbBAT(&CF8< zZ!Qm2qP?gEM!cRg6?<^i`K7LnwbUiB)ro&~sbkz%TljU0FsE~TL6+u5Qr`*^{PqmK z*>!5^PH7X$UvdEP$Z4{r)O>}EpCrgW!w`SD>%yn8T-&zUZLHlwH*CRcsJ)YTH`J3X z-@1J2e5(k|*p=xlt#bpszTqPv(*@#7I<|S`_v{O6T;3)-b$|%HsJ}5$&+ z8GAPsK27Z0yk7V`RbT`O2ElI%adB|qD9x5a2+?yhscHcP9EEv3?=W38{zpnm*n(Ah zIGT4Ncl1Ud)7UXQ%Gn7okvirWIMa6bNLpjP(U#sihaN5teKIa^dKA?teDI1k-G)AG zvzTlvc>aZ4PaX#IzK@KB0;aSp+Wy=p@)mfSw2~EV_Ws!%Z`Yka;<-Beb@u@*7#`F| zM$89mWgJi)=%0l15e0U}qSQSvE|~zLm_VnU6XaMGiNbB#oWj&j_YE_FfWN%7fu!_E z3rjJGw+yf)9Jug+Jr_T7pyvdEn~$y9>gTSw&#TCIIo(;+#h9X_vMPlm<{#|cKdZWg zA@awV_^GpccMrRUm5hX!Szc?ieHkM!CDsrln9@%S%YTpaeap5$eF^57Z`H1sO3R+E z5}MYt%&YH_w)%bj!sT*i+3hg?y(IJP(e=B)%~uNl?^-#CN;v!9YlHv3H_)|`EGPe> zN{JCG&$1Y*ZLK(hZi(cyB-qT16pOMxRM%6~HrPN$ML~*Q%fP*^uLU$YjnpMlfgo~-$)7WVzxBX6#9BgFGc&5^u@6w1PBg*q z+{b!Fz$!qChFyv#Bzm&Hu9D~CUZS_x_m$#86A$6YLP)>*7Fp5s%p?ZNI%EIeG34vz zDD;6HbLiKU(xjwtbXyxeIBs7Zo_<$rU5cPOI_DaN-b57IN-LL-wQoxisK-@G#R+g= z-xwqQ!)r6h32IVPJ**ij)Q4=5+t(C?mm;a8ho#XN$x54%n4l^Yr2-8vPDoPM-`4m4>Hmkgs3+jL!?o(YLFBuVwND#41G-5MHVeX z=iTs<`*+yhhNxbe6ljg{;Llb(5?~*S+$)9s5^qQ|XvQPPBKJke44>}%1MJ}#Th&bD znCa-mn~~Dd!lVlta3;f4(k!zb41%IT-|?6ln^XB69AIRy{2#VF|3an(eri z5Ex>VS9b7yG4@QA@a0$LZ6+PWcEy9*kx^PMd*e%V`%JoQiDR&O$rp82ff34vUMT@s zG1W!F=AiJ=9uj*vl;szpJ7yBzp#N!u4eN^}o^b{w+H+oG6su8HEnPTPkl@!s6=~>~ zVNwA!kn^Rv!EBIU5EPBF{5brL0--r&T6>f#Z_QVI8&sRa-5X+AWkbwKv)inN*257& zn43Ih3Hf}>ES~Z!e6epy*tV|N7@!!j7Re{kl|Oi8MZ=0_pLCT6{_4j+q4pM}ec-K~{@=I%bzW z*~LQvDn~_cH853tv#y?tM_=2ZLTBfAnlW+{&4* z{PabmG{T*p>T?vxpd9qZ5eVmbDRrEOJs0bot6}~rV(6dZasIT1xV8I_1WXIpaR-R> za|zfW*C7Jr0+Q^~t|ob2KZVYZcfBuq)oPp{3WxN!b9M}|oN3>?Vc!x^pxs&| z>BPd6iidO@{_Y(f>j^q`q zUDTd$HqO?JcXEtIynHY8{2~M&qI!hOH@ZD{K^I36i{k_nM-$~2auecgXJW@)hK*x; zSNDP3rLbBns;|b9WhbZ-w-sIe=m7?y%z@Rp581_1EIFe4?&IIJF8{zULm=;>FYrt- zc9hL-3YEeF+;y$j-;0-fkZwc}Q4w$8t!Fxg^BSvrs)dqBT?75kN}yF%T@@CcKXMvj z`DpQZ52B$2){^1qF%=g>J!g@yh_a4`ronE%mmqvc<}pC;{fS?+gvF#fl#Bo5htg!*Y7stHTx)GhWfrDw9F^*8E1H6=C-ZW$OR>~_u**Ho&T7F zs_y+Se{6UPnjfBb;#7{TqeP)kd*!q5ww`^3j&8H+H(nJbyU4nY`8gYZ%DU6}Nui3m zjowB<0Rt(=$QtPB-lGXb4mRkpnt*3Yp6W67c5SAz+n&66{7(u@TrPm^>NxTwqvp{i zK<&@`HK0>PAcvnrc5_cgd_?-(CylHMNm>sLF9$qGav2p3*u*32HU#rlebmx@=$+sn z-HRj1J}M7Vy1nH}L#CK%xp+4x?uzl*S{*M<0B0?jBB=o_u>pzZ6CTAUEten#F%is9 z3b<3lxCKZF+_LTeJ?-N@#6M@um46xGRhcVUpo{cXVn3(3Al)~|qrr--`Eui#Z&I@P z^qOGo;+Ak`s4QBYOB|dUnq8|#4as3 znTrT>ZVpZ7Y@=!fJ6VrjY*O^MCU%s-|H?y~m$ygVvKqi5#-Ba1Pw2~_-G=@r}0 zcG#jaA^p=wS`1X{;r2#DtEfcyEQq!b@=N9hDzs9@&xFDgo;@RX7%P0J2KlsEjkQ1L zUK_%R`y+FQt2xo5R4iaVY^&AIo?7jjBb*J2?Yq=>0jcu$uUHbLz z3f_6hj*A`M9gJf9d8?RKJ2}brLgP@8rI0n#jKzw{c5pT-{9JBe2eB(^FXBRjRoSna z!$c9o!3BE-WOY|wbF-x7i1zb8FJ5;FFZoy6p~cM9Wyg+GHE|N9;^f@;r)6s{3Z?*G z5PX|@ll)2Hpm2DfV;kSlu^sD;}KZx^6uq;LT zX8`1AskhoiF+!nB8AAlI+vWbJ}VvHohA)-A;pRAR20<#RahswE^kM~U-WrP3S)>W9RbKmA)L0PI!-k_i++a1hi`tRJ0ebRKkmY#$)HU^>^(#{&-*uz z89}ZgU=JTv4=-6}B-6Ne(UMjJx{gx0KMgB{sp%`HM7->I{ecuNS}_6H(kjt3rUN2; zfqhX!EYXV>yn9@hP}}JEH+W>)f&0ibXQR$&yqOUO%TWn)CFI4AChi0G*C=qJAw8<% zGnA`#GBV?q)Ru1>k_emO?oMoojWN#P{IcM)Y}nS*!o+Cd=J-G@9 zw^kK{Ecs5(R6BTOU1L78v5mp00@+Q^V#PLHdcUBS~$(_#4pGr(k1LSj| zJ`j4b{7pQ1P8jd-JS_LZE7Ic`-MEuVx|pAP|50qmh_&NYs0Z*2xT>%!euuTbwvqem z`CV9mG2Vx#+gIC_`Kzh@|5|Q8`%#aQ3*5dC7O7xzmpi2H*b4=AU#R7+u&_^s3nN`u;XKcgxUA{$PCLnxEIx`wCDFWXM>O>Q zfA!(zCCuOF141vheua8ST$_JBU}>hj+Qzu!YJ8wf>MnvYf~2lXU+t_>SQ^A<&kOQz zas#P}Jdv$3F4>8n4j#J)p8Yt__Yn-JBhkiVPk+z76THhUc-4O7_KS=|%+p4K2nRtrFG%9Se|j_m9)N!e1zT=LQF!}1Zm^nDU@i~fgu#W= zVTy&ru3{+WCC4v*xmP<=N6)iXMH!@!j;rp<+K-Y8`@9n)WDxH@%jpgeCSKDRt8(V- zC}yMFB5&@ycB8-kz1OI%vM|HyhL9_UE)Q zj$|(Xu4SR5a#HRfn!o1sKIi4;-0VHEcfnPotOxo^BXQ@_?J{BYwSx44LThNN+w^8* zx6V6SmS+kM;A>-)u^i+27}&nt!Ih}WJG)7=Ruj_ch8INVMbTxN54z2#F8!PV0e!i8#v0}xldhfmK(=VZNbDL}8A|kTC;a znDllNfP_2v=L?u`4;m*CGUGXF4gW6FXz))tJMYR}CTZgLgfiRXx$~@`uU5{x!6I^o zSyLd~Uz;g-a|6VOu`2k_&l~js)j!Zwv`@&#|65+nex*Sy}hb=nRR^WveeM6nuZ@tKC zw)tyZ-+FtI;z=%nA8rqV9VeOV9+}h~2m$6hHJ5y&|~>eWQcxw zVFWaq-TE-k6=Vq5*9Q-rmKGYQdHeYJW22PnVzGReVcRv`cIoUn{yE1~ z>lACXVm=>~9kEM`wGMTKD%fWn(Cuy}Of_=LKCZ*d8U^YVX_YlFwPrDqj0XlN%Vke| zde92F!=d_$lBj=(oD+z!0^q1Jbgq3?Z~g~TRAFI)xpfgbUTE(wb-7hne^yTYmFiir zGLuh*R{$@g)Hb7n99qaFgpvCo#wFwcxE7_E`B1x!wx53`Pa(f1Y<@-b{L-po23~8i zHlzUJy<&vs#O%Lfc|&MOnNM=I7mvxL(_y>@s?rJFd*##-VruX3xgyKSa3jqPR%dP_ z>LA{+#K!zXD*X69PqA7EyC7}i>*#pq7pH-?tYM;1_M(AggWBJsHm$^g@@HB&CtQe^ zt-~y7a`1v3*s}!LTG;UQy4gQT*q>|l@V1WMc<$l~-Gg*zwVY;k804~kfj3M}*Fm;= z6dULXmUueyMjvTMS&*36{DlT5-uBIILo8$Xo zqT~Vx_*B@K0IP&ZfoLT2>IztW5*VW6vLWG)FZ~-&-y>Q?>!Zg_j3F-zl#jp zPaOTSy6$9nXke3KfNcuwbl+aZ4^vaQ`%oZ*{$bpWlK#UCI1N!octl_Hv-!5OU;DIDPYV|obDd_u76;X<5J83nZjRoc$Ehd z;?zCW(dc+44v0pU$Nxgos8L9Oy`&8HouoL`!aaJNA2b=bteVO+ zV@K6h4oeG6tbO5|L0_4|?mTA-No$tu*p;#x$vvkS74c2hPu_83(;;W&2pyUrf33)K z_9TX=z?ccx)S({&3k3(%n{M=pJRHb%hr5L6vbMyO7UMC1i49-)Us&IsHSSb@XYIl0 zzcZn3cAwL+@@y}sA~Z(+`E9=0F8??R`mN~rb=b-w*9m#2Kb~9TKYe5u-r~FXA4G~% zHo>xI3;3OMuJRmLMcCsbE>}>IRty@^4-ipucn~u5c>Z_K*n7rMd{584MxgLe%MrHW z$@{3AKMc*r_CI^0%HFDh+4;h&*qUmJvVp|>H$|p-zy<4lh(iCh9rMEVOz*dMbNe}d zId5@pss7uo=Q-3!-gV3gF=MYnHfaI>jBe3T@oSiMzUYlwZs@Pgv>$6BA>*2@#YbE&Gd+t8xkKAr)=l5Xuf03>!fEii2=Qb`uBIqMt* zM|?iLg%u2DmotA5D!Q6318EN@y|aia(mK{SO9iNOm$C&{?AeOa#(#^hIW!Bv{K$Lt zR)u*KsT3}-pN{gr`p--L>YZKj%j@q6pnM(P9lhR!J@*JHlC#ucMceuux$G&W&*nhB zedoV8*!~p$SJ!zPjuzQr-Qzt2{hdT2(;!Ff_3vUhd^wbInEE`jPS-I5`Wg9rVre?= z&pXMaq%D+CBhM_*IWWvV;F;L}x0c&38sAIBjd_gv4zs}7VDf0+cXW2bAzL8GNFc)+ zbLRFv;hjz21m3CdWg`bz%=mrxPs1}n=a+J_W0{{{xX6`BGLJb=wlb?z;~Q5U9f{1N z|8@4i46(UJ@`+@&UlVih)>_iy6o<9&{z%_kzjbp8XJWCyW3zeu%NWhBU1@Jzz~hgt zHi)KS_=wsf?wm2(W$U1-!PE5X$=Equgmy5Ex8cQkJ_1~DSVbFT;ze8m{J&P?|BdfE z3_qZsu*pZ#DphT!x3TEgXQNWuLpRh%v)x2TA|oziaRUhw%^_z%50s%yN&_VEDZ1EW z**Yx56uEEZ5t0GFNw)1VSs9;Dcvatwuy1Rg+L2)|))mLwfywlDq?v4T{~;MTZIHwf zKa@9%X(_tGtOhLPb2VJ7DtJP2E}0Ra>IhVw=X)$e=k4%kn;Ly*gQf0y%G?mp`AOvD zC7_Mcc?eqG7l+qWIfZBXsu6I`{u}4)6^i;zqtIE?M%))9olyDjaH6cH_ zy&}i7YJQ9a7B<3H?(z`bLPrw=1Vwmq8-6l5nk}+$BQ)8V0<>WI6*;BJk{qhfCJ;MW zhaI_ytE>UV3*7Ab)xj#7)!u7nLjL3_25FwUHdof63~fImSMoWOSuxu$m}HmpV7p>c z@{n4e{AWNPVjKLk$D3m6EKHTdQnmwwQ@}BfKu*gbX`&p%QAY z{zuz7HFPy@vYl93T~l+$=HF&Dog}Z^kch{~sfMHS5+TTExRVVgl!W|X*aS2Yh3U^F zY+zhJW+mnd;0?EUl`J%Ll(mIgdJiO$lp<`KmUB-svN$=Jf(WE|tpy>T;Z3&wcV)-p zBv|h~AhV$-GU?}yaiTdQ)tS?H*QHahbHBDh>OSS-<#wAsjQ2P9i$vBG#$i4IV2-Pj2N-qjQmtb zm`hDgnz#F(T1aZz1)gsdqheoV{y*12t`J0ol;dN-NZp~?+a3cG0SJRzQI zlBh7hN~W<~Nr!{7a$M~d+SPN7AvF|qz zcyzkH#;+m*A8B(zS|Bv5HlH+h`yO9Zue|HYp5ALvml}MTb^!o>l*BlHV!GH$km;zr zu)*6^`J!|7jP$$~3n@?O>F5sW(7R2{$lu?f~5$2&=~)AHQQlYxKFsh_Ct%Ds zj7=OhlWmxzQ=_cDcxXaYq0~y^?#d$16o7IBz#K7leER0pd_O4 zPnUH5Anf6Bdr9Xj+!vy|8sQ{s#I;=~Vl5pl-i;XN#2A!H^x@5V;k)?iWpucq+I$hN z4w)M&6%yP`)FPJuy5}=G33ErtqR%uhcE$?vXMP;ttX!wB|5aGVhC8z)%6A*7x4$#& zbP=8k_Pr!JRqz5QrYAp;qT4c{JHF`P>a#8D2#09}&1-pa2F=6yhSH=`e8?zU&Aq9k zgGTtB=RXW8CbgOna4p-wum6=!eSzBgMU1l3Vz_Q2d!JV%3IZyWlyg}(&g#u4I_?PP z{4^iU_pPy2&mhjWQiD_HqCM_*uO}M!{Xa{>o8MR2NP*6^MqOQ0o$-iId&!&eVNWcs zcUe`{)aLofD*UF?vYdhal_5ZTGy&(M3Gy;KR40-8!AZgAMxAlN3K@?eV4rkS(8LK& zAP}2lju=wH152o>LVrx;t6>d^nu@+n%h$MB=HzdaLKYYIC5BHuF~QllSN0?`omF-K z=qCNY$qe4IkZ;ATX_Z2tVTCbJ2at)PwRiu02J)ncU0Ei{yz1fMsCvi-%-?1!$ffsT zrl+aR&`$eR{y47N{!x{?7Aeh@!s5VW^Z(KlWJWPoyAU+uHv;n0Kj{#gCRv3d$cvh{ z7X7lbXnAwJ3A-_M%`_2gc?@J#3Q#WD7loTD+>^dtf22#tgNATyGANVehFk)7g-)s5 z*+hS`Nb|k2StJfo2T-%dXr)8G0by-6wZJlKh7cHmO?{M8o31V7KgZSe-|4p%4T=MI zX+>yI>~rxzHL}C4bR?4&G)8Xv#Xm-Yn&!DhgZA|N_PyktA|=k)_~W*;UnyMuI5VV) zpJP;U4#u`v(Hav^AKmeeG3BSWi?|5a`+=$_Ys#p!#BxJyWhrkGTjs|%%LzH(FS~14 zT+JZF!;ijl0w5}Q?g3rQDr%Z z2jeyuoO*Ngz<&hY#WitbtC|cR9Y#I;<9hGb;ZUrqLAI@X78?B1sbJmFZz+$#T#h62 zksO0jDNFO;ZmL6_;sA32aPWN>(e=x;pi3e`N1C1I6mq7~-jM-P#{%WPaURU`Xal83^T3prl+K^xdGYew69TZ8hCf!Ppjk-wEugQ5*p*qg3 z8$l=riZmdwg^VFS)mq!Yi9u9 z)%_B_^I0qfS_|5YNk6YPjuqN{Eb%%PPy}(aUXerh+O2`BS-qF$3~&cy*aM5PR8?4s z=%@#exC}~LsQZ>(WZj*Gm_y*CN%M{GvgY3+F!07F0jU>QRay`YQg?-ofl>C)RFiAB zvD)lIHFJv(GjM;jpc1HQ#;_kYePQoPVa*;U>?Fl%v6?9Jy7aM*n_Eb%1v_D=9MMpz z)C%AomSG2PVKI=kw6?y()(}+wU>2B}df%JY%SIX6C2X}1y^3}2CfPULFDCGQamA)| zrXM$gAc71uHn^0sYMcy{2((3MotnYn*|=a%$)J!|W>`lIZjTTy8G-Zk~sEdgQI&mv!Kg z$F5S{ZP)8lrie&_lR9)5!ESf02ib;x)T@I=-26`OuIJT}NF4WUcfL*7xan?47GW>P z?j*S-Oeo-<86{yTL<%3utXgo1U(!Du#CCY-B3(XRZjUvQpnUjye;3s^Vsjf}{E*?F`%&e;GX- zstMXlA^1cSbt-L7$c|d>=}->I0Iap44?}oUL=vIED5+Cv_RE>wI)t7L>;zUtlDjA# zo;t67A%8j469D*t^r0<#5L(iIFlu!jnj%`-$EtOzwnIgqrQTu?dSCHb-LOLplzp{+ z+)TL211pLb<;v^$vJtGmYG|+(8&UzLEUfeFfY1|;O6_j`$C9yRCXA6n<~lBT=q|5X z2?m|UH;FnB#6@p}z7dUcdb`nrK7!l1FdOz3L&~s z&Xgu156AM9CWwczZ7$~v%9qe=&3$>3vDtsr|ItuMYA&mJ1~FM-Xq*1wVNU}mYnmE< zOz*F^i6M9v_P>-_9E@_=WsNx{D5U$-aoYvutjJI$1YPZwsx|X6$-F&+O&93QdmrZp z_eRO0k2ZZOg?m06ZMleUgdJ^B;ra!nH#;zElo%Kx7>b?kBfGdTMRl_k*)cY(t(ZmI zLmP=XXVqH@suSBBWT6hxo3?67XF;|58JRCN`Bhb=Co)cQ&PQrS9bT>B6Am|v=}tI7 z_LzQJZ7(n*QZ{6E$4bf@*Yv-#`kvyLthS}5`%Qk8+s>yw$SxAe;fFB9eCH-yK9*z>@}gCOroLsK$EZ`ko^u z-nkw7dk_|VRQvC0jwc>a<-uSyCRFa7g}r8hv?hQU>i5QE82Yy)q!XR&dEP9r4vBh_!t=uaSXqY(7#`S0giIXb%$~GweDp zo%aoHfIZlP34<=lHzy|`F9PNw*g;_peUjv!2x!UqdloBJ5~YZ~ez;o^&^Sui+wJN8 zOe{(8)Tuj*xgIZUk9qW4VH7(m5S`o1+1Hbg>935(7n8@^G@peB*Si!Mjt|Imlk_ zt+YKxS~|RgxI1qdtj!z3)lebsDBi^3sEVsermvEWGAFSw-wTjNi?I=5*$>Lfl{4r~ z;PMYLkt5Bf>(UFSq47M8V)8&12vyhwo=1^gzHO%YEO_QyJ59YxCyudk|3QiokJ~iB z*TjRlD}Ypb_e5vDEHrcHPbc*u%E0HXg_2YyAJ&%nubM|3NrwD^cEbOqWw`CJ{-1b& z1OJ#X4RNM`w!OGMQrQwliS`Uf#VO6$t1#4o{806P2bZ=+1518hJDbByQz&a+5liM_ z6m>HpoPRvF>)_duVBWRyg+J7X*t<+B<`mlk z0*4bl?~=pWGB?St`x}kmDjPt;&I*VKp^K|?n2Vobt@Tid37D!t3Ktq%SREdudk48= zDm2Hxb01wVrT%uJ!0mLG#bj_~S7`CCh1~*pD~hlG3AvPCR4**-OWCdoB910!Xns6* zuK~_8Ed8d)n^!!5K(qD5zD$1q4@$%tYv3cpaW3780vrCu;qdSssKXT;Gaa;RhE=k!qJgHYwQtCxoUFMD-TR*pXMn~^9tY0WjBz-T4;>bsw*|TtWMEX`*vSyu$L1S$q zXloYExn1mer|p8+lVC&M;hl!joy5OU*FzIq4VUL4YwqpQRM#QxmQ+xW4xlj4rUC;sES?Tc!^Z=dF zfy+hHnqg5vsg*lKgActYGbW-SY#$A^a4Qc9n&`+K6WHNhcSK^w z^Vd@M|BDD9u8AGadp}&>C7|U1+rGe3bG+rdJ`*naZC>8J2+bkIV6J9H4BhxX??JX> zu^!-mr*?Z*J%2R%pSmGa+%mcQD6=)7XnyOAI&9ea|z`bK>$f z)%mu~k;Ra2n9(+?m#UAkyu%`CL})|Zet2i8@XIaPS!ulY*iqA1`3f3}+~}Kh;*>U~ z87)f4a%PfX$GNo}l$L9r%4A~<_A+HY6jOe`Y)Wq5?7(#2d)+A>iJ>FSN0^mTz3qh3 z+hh3FU_ikC>&6BxR%7a3l}@Reu1OiCTZ8v;N7I7knC2ovhBVjJ8ELBy(1it0w_y$m1&<5wrhsLpG0IPsn%__VlZt#A7*m>zBf4HV%0Z}2?X{PqS%vv3< zVSkeE>dUP9x3Ve5Hj(C?6GoEx2}0!ZC{3_ zEk+Cp;7(h7S4w_vtH)|#YdM%uR5IamllA6C4zTWRkNbHctQJQ)ROJU;Mil1S z=YY$q-OLuc&^GQmjM$gugx^B@nkTI%Yin#x44}mhK@HqIKWd_y*EA1#JkJULC;SSmn%r&?}z!RQTIOL%AVMout3$&0<5<*Gj!m=W^SRWf3{&07pZa zcQ^V)_F+LSdFj}bI*>>{Rl}`PHjozTAdjjtx#{83bko$l0dGY93UWnakmreygLkLtFag{tgFRxOATK5ET0<*vs zYdn$Pp?;dVq4DD7v1H51WO3kJqT$ z;om*c90Gb40VFsPwM5nB_64&<(-{(Nl)3BezpJS+jtYF=RkgT}e>>}JdCaDfXsVtR ztX5QM+D8(VB3@vko}36_Qe#3XnjP@|)`jazMzUr<=c+z5{1>}?-e z6Qlb7koDF?_Pj**db&3Y6j+ycOORWs+TCqnBzZwpr7mkdLK+KE)FvJ`+ zhLo(LEa6S+E3mxT62` zx$KAS9DsIQDTFHjPI90?HlFU%B}3!#bWD$=y9g|NqlOb~{v=VVzSZ}1Iw3F0^8G4s zW`dj<_Jv_fRqVU*#*-3Yw5B_ll|O^JaM_)}(+dkW09vx8U{m%bs2963N2f#}K(3*ky5;1r$(CwFjccDjG{&vip=doGWpMjD!7amMIl28r$=+T*D zS9n*+hwLDquIEEQfl$qh)K=)1%=72DioJD>UUQ>&Q%)h?8HGsCPDQ|h&_Mm9!`2hZ zleY(w=wguYhfjzhT0B8_If{FiKHZ8XqrD|JDp86ce?n9e&XRmZKf|s4b<*CZyxpPX zPJG@;tc>!aw)Lpx;HIa&Mm?Zdyq zfO4kIZU$!|V7uR&_O$E7)^ArKA{^Q{Z<4pHCN8HrLscAqf1sAE`8wj341!J2oax)B zUN3cP>kAgr$wad6K<`exJfzFl-<}!rFr%Ap>&%B%&2+mY9jjZ^o1IzzxjJZnu+{{V;%eG#Y(a;@Ix}G{jY3!cor| z-&>IVNM2kU<$SUfY8$Hs)(o*c(YeR^q?!o3l2;lV+r-du=m3!Ay$@^yOT~|8K zfZy+9ta!BDk?`H7gk33pWSp#-z?gL*?2*))whDK!g3I5of0!D2n&V@+ol?TcI1RT? z#gW>>jdZhW4HIt`+-OlYgvoo)k$x=oE^V&d+Ds8xmAJg~LSpA?AV`%M zUWd19qi6F?no&wL@j)~_*i#^0u0psM+wGdm5aVnkM2 zMhf)Q5#aHMZ`Ui$+Jq(u1i}ZnuUtF&sdN9e=%&c&`FtF|&6L}NS+hvZSF~DvG);Wc zns&F}7?R?&w&YYi8a!A%b=;oTJ%rM-{)dY1pYgP~y>AAo6Vr|Umpw)gC-EOZvMHfT zjRx^3lC478s(n|XzuGi$u|xZ$Y?Nz8p_Hx2e%OCv`)$Z&Mc&QL-+0hZg2#QQ?| zwFPGV##GAyWG=FVL;xeW08hnWgj>x>^#|H6x(*t$WC)SwWp%>c^Ec)DmU-i&Wp$6= zSnJt(h`F18i-4==yhn+~D#(NAnVAqHeZyEf*zKaWbFhv$@L6g{LOyM-7d&W>@#C_aTZFJD3i!Vd+A`t%U#YVMp2RXZHK1CRCO%~f z2fSvQR1CX(gmORRB9V^k zi6=+ABCX^)zcje&OjQifb7DRip_8IlPr@M+;T-FsD+FvE%N&3C=;Vv2|7>UXJ`t z3Psrtg=Vghl=l=+oxZtNn>!Ol#;J{bpuX#;zth&x^}{1vkPDWHz~b*9`iJ{Nv!yD` zN!tiv3SMUH5rLYe@H$I9svzej^VISOORP}Vzj7%c8-_vWF@h^7uaQI5x*;$_8J*8%;urG z6rhVPW8jM7IU2pqm(m(8Sc5p=c_^nfq7kgR!hISc8qa#XwsqGm`Ml!3I4Z|Z**we- z5OH&@)g&lR1$3;Qxj-P$RS>!LdEXRC`@caCSH3XJvpGu`}|3eztCUjrI9kJP-t~tS+nl*j4C#u@9uG4(wkq zLX{_v`1{#q*9AIwf7*zWu(ypuLda3xFBW*(-8l8sQyj^4OhGwCEcgd5d3k+aOCKY^JKpSGkogEJsk$NdKm zF>TzBqu*v31kevo8%7}<<7;&J?*_X?qa;@vG&{f*{6O_9X(Ea03$$_bK{6D6t!LbA zP^A7bzu7|u&BuN9=Z#Nuu~~m%`w!?Y9Ja(Rc%8R%3hwJZNtA*o@Lm)$2>N zevaNQo<6d@>#oHyoKVJl=9u2|*&N_pbb1{3Ilmg!aMESFG_4lp@c@?viWZX2-*c1kVgKac)buc?3vPxJwxbN1*8+HrhJ) zdAM+aGESl3_cd>KYL<qvYG7S5Nx6R@nsS1EIY#X9#mDSqLmBIgz#%&* zK+G;i>!$O1P{PZGUT0bk9!TS5{A-NF8>I-G{YBWrLCORnI{wkU;sa?LN`-R#@J*; zUV~$nHbYEHa7z98%Q&5Na0pT%D|eOA5p}wL0_t%&T=#MR4&B~DfK=qVx^vb_(;&+Xx?j z@eu#BqW&S+MXyVwvgMlyOZzQT%1p?#72($WAxA6X5;dXMHx3-+ht|V1n^r+TOMH1p5T<8qA-@HXDN{F3dbaLbXVoFWhU{(6UMkYGV z0{@QmQ@aIOP@YaXJRSaqA0-fKd*RTt0AZ35c_6SZ<%Frn*eoho%a2(dA?R3rzYR6O zz1g5&zoWybKUY}y$+ZIO#CeNHQY@~!rgE+=J4H)N4|?tRvnR+~HqsYXefWR z&_?20@#8~Vr}}9z=gM{@T%9~S62I@1m%Q|$;s&nhY{j7OiIrQ(l; z5X2$Aix_Z!c=@btu`5%FG;4@gY?;vsz`_JUa)DU*DPOg1ZeB;0obQmmp@08w=w$GU zBUl-7^?cPBQs%X=YSr;ctq?e`HFeAhJ6N}dbgpv!1#PiymVBtv*BDYTU!N!T*(mxm?y0tE{p1Jrc(?K19FP;2+%pQL+fpx*do@ z05_#=Z0}@dsJqMeUi*JNSstKBd5F9gah?0Jf}!r<2OmSyJnKJ)5=@B&_Y%_56h~G5 zQw{a0^O%gK36?oS+KqU^u`K_rsI&jko*n6a^wf%=RO#PA&vHAwpgha(S^V&wsot`o zwx`HAA`0jnp)yy=9FngXTwKbk5cdSzYFPG>ke9;VhkiB3#_?2a<2334S}k(-LBnSh z;E<)wjYjS+5*BB_{8-QMPOKU zRJ#oWNlMxD`3^3>CXdb42fqdRU$Um}aHAJs`-8t%SlxC5{9UE^O4}dW2L>qO4g>#m zg-b7kf*#LyNlW<_+Ly_S-?L-!H;;(&5gRSIEbnaTR4n9&X6L-mA}gJ&j6PPCB<8H@ z6-QbXAH0B8s6gcyJ9KATxS5WV%(->d)FQKiij^orTC>-`7P@UYT5_C?QJuJh?I&uz zho`=7qFEB#q3=<9F8_S{^5w&qh`e{{{TsxTjTG*l7$=9M0wrvwz!?b@VX2T-#nP~i zlSy_LxRtu+4m6IDsLNA}Y20SBS7>7!)q&)=60Tehi5gVbUHWbQMvVuHn_(hSE!NlN z+S8akL;`8&i7Lf00(GBcux^+WnrnTP^P|$F$2v}^I z&t+A+@=d(ZsSaWuck1h{U%b06$S29at)?d0U)H3SyKST(h|dE(bRV5fV_ z4H*rK0#-oG1J2Sek9~Ud>2SD1G52-Q3gK+Ers?yww$;9kyPgS{ym)e+=q_Du?DW0h zU_8>gXoMo)cJ|d&ciXN8%^&y`qTy80sNzu%?B9s?3F2)Mp1^H=yu2r&PK)olGlfwQ zNd-$L+%v^OI~q-t#6l%eq6r?+f~LX=h>kQ?&Sw5ZS&|O|uzr*e=vj#qb*6losx_t@ z2{hZ|8bhwHSCwnRls@6zW^{BN996n6{_Tw!pLhp$c$qW-C282#irl9_TOo&{YfqZP zojNY41nkkM?^6?4o&gyYHYl|+J_X6Iy1kFuZh5PW?V|kHa_@}FrW|_KMMyT@Dr?xq zc3RdR2pv1@&7zM}0FWSj{CoWQb6huka6$#-15f|E=I0cO(_6SEtV&imx5z!sh0VPd@Q|J za$$0T6@E})0Wy`lv&3tBtoHSIM6+dfXpScenAzz)o6xB|5{BvhRV}#pko;e##(&8s zzl0C1WH*|-R<6B$r>L8nLE0H)h&rz@{VBWfH_5zT*d~hW&w+DP7|R6pJ+Z&uygC!x zB($%dn~kZKnwR1gSZG!kr*Za;r^RJoR3-5L;BMma0t&o^oFFe;+E4 zc2P5>){r(=lo%c|P8Az)53AmN5OF4zF2^DA16o>0Q+0&X-xV~Gb*JNgA}oI0D!OJ& z81BVe?wdzArduF9_h3z@FOHm5As6h#t1}PK%@ysjpZqh_L29az~b%t@X^PgUSFUJ9@Sy z=j8t&mm8hA1VsNhSH}U(3uM5s*vmxhRu&XL(E;>S)XHAt>H_N;LDudTBBxz zwcA8d$c#6VsHsA}q017RqQl5p-xx4SGbn7Kl2#(+%a+W&s!3ZXQ192d?W!MuJTGIK z(JJ!&UmRy=&7I6IqXt~&5=X05(qmF1J%bF6j3(|?c(>lCPRP}=LKFo>(jW1aevX1J zAEVb~+3Cg**PfPLil*3a&g#2k@!9ulYjzKoiA;N#2XcGu*)yog1b;gfuimP?eM72n zs)*!PVP&t4*=B&pLP6JBs8ak#?vq6#-bchcwuh0$=jRlGw<=pCh2$`mWw74ztt8DF5~cF=+ys2996;j~757QY`w(@9=t|`@oo$5_izDlu}BF zb{yUtMG19SGK#lZNUpbop-$dH%ThXBK0-bnIRZJNri9JNh8t|~Ylv<0!JGJ90e)AF zIiLNzqoFIK?+KoE%mqm#jzHx2_?25xVRg{)+_2q8EXjye0(&?(Ny=tiew_xjz zFR9yWf}$^-c>$O51xMB$l8_=CI2I_z(*d70u50?0A6zHt^r6S&m|1?8GyK7Zw7(th zfoYwGOIv@ZXc=Fl{uW+D@;zlgW8^Zj8PRq|S4gzv$_%(Bnz0af+W~}4C+4~xdN&7? z!bP7plS4t0ar^pVopO(Lb`l)Wm5(>VHN809&%ePQ9?Z`#uavhW`$YsfwciW)CI-aT5(8> zlkZW@P}GzNzbK4p{BW5&!20pxk%T&<&1dJE;2bVEtT!tDBo`1Ga{(N1`ndffoLdYV zIVX{l(4qG_@)-B*=A}MCvCzEb;`Lq<+81LztW=Lq|nvrm2whKLlUQ|dI$un7&_g>w5ejTWi4cGzGEEt1FuZtB5TU|-34eJwyYuP0=f!db~%^3?5Ur+w`l1F3~IEG+V+OPCmm&Q=@ zU$XlRHi=WVhUlaBXDq^@%x*i@l*(a4r3t9o7uz|6UbnOq;e*SIY0jP4c|31_!H3`c zxewBu)c}wk!YlNT5X=e*72R^Jw3nNGg@3;e8G#T29C+tphIMR;n_|IvTW$rB>wkIO6BR#jx{@#p7aoxXDy*D)2@C2S8!7YPy z+~(qHG1Vd3Q{cljh&1{EsXg6Hj^H^huL4%Q@huHAh$!LOV*du9zyo*gRmjn(v}m0C z!vsFaKRFeQ6;_L+lyS3-j>j2^XvxWfYY*0)x-<)n`pdyh44J2-x3w5Z6HI3b?Q!%ta`j{9IHg-UwEUEO&OC9Z^lRE|SD zSEQSS^lDINZfWk(7fNqK;YX3hCzEAd!sdCE$ul^7IIgf(vSd0`jCXlXIYTjUN@{3u z-EYlMD8o$BS^&kLm+HFW+;_uQd$=P&Uv@mq$nbcM?*W+g`YdCKOyxL&49GhPCT{{!6rd*Ra^J#0xgWO|qRVT5o&updh*x`F_=2^|@9 zxyjfS!>Tlfs6)}MPSi$gtmqJ@`D2J(uPUCE)&ZW~z5bfL$R;uu-TQQo2h3Nd%1B+> zvP^ELz@LRF5QFU?qLQ0vYY6qqvmdlA^`0t0OjLkxZh2a*WN|l;y~t%MNzD7OEs}>f zuPz(7FZlACtbkhIRxOh(k;O0wu@lPiogD69%f=v0zTmkj<@dQwnH z8DTrXn((;jH*x$FZ??&w*&RyRI+l77h>kfrmKy8s5~Hgp{Rp|(jS+}V?AsRaRZH07 zEVVL_wKA=2e#o&^H+u2r4lVHw1!jl8P(@2qquktpUN*)ZW(R2#^4Umu7&m`nJb27* zE{&0RdDwi2#Uy03)sA#$EBl@>%5p8A`DP9gi-BJFTf&D#z1zj1c^%3CuyTB{J|i->eB6=|}JBqyVtw>@l*~iY;RiJHs6iy3ISc zI^58^`=6L^E0inZE2M)Vv||~qXo!<8q~3oi}>UWw4$J zXa1RHhS@!+A=_EWM8Bc&f>o04^kikdEfVFecsN{)x|Dc0ZMEDo@-enlO3~?TW}goA zua?L^zdHZzA4*IQTfhc3+&Afaam>4Gx^Po!?ib-<7gK6(!;QnQ`*XqjHo(u{+O{I+ z!_N^}zQ1apD_w2iZjZ}a z>LcI{Sv$_)H}sq0b&Pe^fnaI{1YATYN)PfQ^2H$X_NI$_?}o;3-=w;!N$~|1G9;3Xr+c&1M(33fJ@en|WVyZR&=)jKJ<14-)zY)*;s5FeDj#h9?aB zGfec;jEG)Hp0~QC4#hq$>8=|P zF6}Ok66D*ND!3O9cX`LiU2c#R)7eo?e%9xq8z~y`$r1{INSeZN6r12~r=mlNPZF$j z+bg5uuNgTu0hQ0NtY+8Qtq4BT-wx60L3Hh=!$$fvXNi-hKG1JJi;#&O=?|tzj3%BqN#$%meuC3&*z&Si&vMd1Jc@ zo{ZsfYR)pwUkpid&wO6}S9{yy8kOCBFC0wPt8mPz8gg2M$;R@{x%=}#DnHxP4%FgE zFNXalRbafA+hSFip+f9;wz8LcNBduqKJnhEGPqLG`nq~}%(~&@K@5S088VZJ{$;c4 zZ6tc9F9-|1=k}}*6I=ICT#H*ur^F*v??HZ3%Tw2z7BbzC*)R)&%15ER@Rg|LfO>Og zv#thA_)ihnqeVq0%YXc-3hjCDShaiya=zKaXksPGG!j_>l_F)_*gp;KDBK@X6vuX) zHc!Kx)+vMwCROno=l85u``l@Eh9_V^0d5w-1%*l z5B2MN19`@4^2qvIPyEcJskug~-*Ufcvx@cD|En0j_$>|8i)q+&gO%P_8Aek64y=RON2lIHnFq_CE02WS59bBb0 z{|EJ=)i>+fn5OBSK;VuUt3=e-SwdA&hzWUFd@(gEknCo)zENa@p)Iu-?70`!FFx<7 zuh1usdYtcybk?zi>9o@ALtl9qb9ZWxw_o_emyvRgjlL?5#k+-&VuPKH$-Bf=oGHvd zNxJNtkzK8^6;M@vA+ATKR+%!$v;DySrCsb;LDL<>z?}(M50>atH?*xXQ{woxqcj_U3 z|9{oo|BB`8pX&yWT4yJ{QntBFN!g~`QMfij90mLw&8{Y#Z7~V)V3P>q%K%Xh(4w5a z$%-S%PhxsjUQMdnvpW6kbRey21b%+qw1*zjHF4^WQMz5TUY)JDHNy&xs*XpzxSHKb z`>a$ct%wp4+S&)x4DHJ<48o@p@TD;cnOTH|JMK(e^oss)$Hy)xd3Ae9T{RG-1>7mB zC$g#r<6VDSxou{>PNZACDfdpQN$UY7gcG2M8URTh;;iYE zbvxlm%bE_1|2peq&?#Um6SAd?%hptVW4SIUOyrLISqEYMI8N;f4SCm0=OR&S7cd{g zN$Lr{v{eajuW4smE9bm0&@zXkJIk)a;H&*Yr%7OMWdL7Y{0sc@YwskNKYp^g4$+A; zNbNUdL&!}RVJ&+DfuRLL@s;&>r}c}}unNswUFH{3pjDNUTp5ARm<<5R0p6Uq^LkHo zc1(VTw@s~ernQZo-bI+?S2Sa}^oeytSnE!}O)J8+CVclBD|gl^_xUS}M=JRMKFJPQySM7V=X~kSEj_jgI>W!XK*@iR#9HDbQia$ zd!8_!Z6Yt6idsm(VaZ;}ljm$>I}B;LR;G;m?X;8I zbmf@X55xtO$z%bf3TNxE1;oZs8IIrod@)xaR%hjg15(=DNSr+RV(&5$y;(^Tpf7V5 zXMuE^n-jtt1xsn1$7;+IPmUeEsPZIdHwSz)eZyH>Bge>F2m}7=n*;-V$|cECVAX?JfwQhH6V$1%XeYdH`5wv=i~J0>Mt3U6Ilp~AHuD^ z?+eFE5Ht8Mv)P;uFu!)O{lWJ4L~`NcXjoRlMGmI~kn`-{15QS@SV(4X;sq4(ruxz* zZQuMi;je!%>%vmpEz*T>dM|QwSZKpV{EYax>u>AQo2GekBJ{^FG|33j>0VS+wR`7C zlDdl%7&Wu`v+4$_#yoTU(ZJsT3n!i;eknl~p<&O;Oc^m-W6J5^G&_*tK)OlHIx%^9Q4>17TlhUITHH^*)lSjW7j0UP z%zTu4IN-%Ine^&#`-b}^&F)(1eY-h3^zB6m&tVQ#XN*lAfmu`t*oi*2+aS=p`Tvui8J*48t}EQ6B*FQt-u}pIherE2JikCYga=%Kl-u74#O!7gHNouX^E0e1>fgWBn+eMa)C-}XP08~Pv_*n zBWSTT)2k|5U=DsBXa)*H9JH9&6Ud4`b1`x42a1en##Nbo*Q4E0PTsFRKdFRwb{B4e z3B>0OCdj!k&aCXz^ZnU_f^N%%BjFFO+2+RFQ_a|n#l}rCLN8CRSL21vB@>;igc29l-%;4{@A1Js#no4FeGg=wsNRSon>fh+P1~u;|D{7z}s`g5>1Z7|j zpcA*GaLZ7TDt@n)PY{wt^XAVO>vY?sQ2UHUKSFAC7Ko)X*^OIVmI(^&Dk%~#YIX;FMN%l{uanpgWu9dFupQhgNU<~2Zf1jH~V7jH?2kI~t{7jNasT!#GN z>6mS|E-NsLKmSW;iV>@Cb05SiUcdMr@>QOEIN>g^LspWE`1oZ#mi zCah>xLHTv;sVYI)Qn;JakaOK13kr#&T-6XqLd;o`H>X*)dug1%teHnm6td&lQRReb z2l98qJV)x`XUh6x2U|gjdn-y|)-peVM7zn6)?J3h`A6Dk==*`p0BG&Omscmrw1*TJ zJ8nO0fC>#YEF2A0^Q@15g-Xe^f@n8PT_1v+u8N=!GLSOFZI5uvh(V4h>!KsRQK8>x znitW^-bbUtQB~^Gee*a0f0#7KDWkj)&dh*y8$R2h1ZZPBf4r>t+`0y3wYSTVXsG6L zVJBE#Ny&CG+dv!0wLc|QdkGRXh&UeIwaF(4?9dMqaigYo`WkfWT@Am~8S0JrXTvgz z1ic~tbPl}6wRNtWH9V_}1B-fw;Pz3VFY7wP8An@_;O@;g3|mAb7x@t!gF}Q!Fgk9&P=ykCVZC zCFCqvEqw1YM^@1HX90e@0k5ct+;$N@KJa4auY5*ooM_Zh-mginZrV0@-JtaX%C@tf zWZvP?PkMkgj{VwVlX|T;OqkMZRWM1gchzcIVKR0*EcW55d_l~SI9pbD>yUI16Zx3I z!UbjnY76CzL-lq--zkduxoej7(bn>zam~g{8Xo3)K3>Il6{@{n>G*c>j_(zKOvG%6!7DHcb2&4PbjjIu)tjAuxXcpiUjMfMFhawa)+i$SNlTc{B+n3 z2{-u$I#d$d{&}2vihAwT1n649%tkS2IJ>lm#J2<>Ga^66W1g4DnePMY&y{QSum8;a zg>SJtAVBcK46UKWg8gbl;@;q_oFHkh3?F zgl?}mPd4znXR5s z0E6%p4?(eRXs|~sAAlNkwpY|U*|aIvj={FGY=&HK(C!E$uWO$F5#iN4MnxXuW3&aZ z<^FnA0J~hQTKGINQ2RHi!Cz9(q+CZ?H41;J8hgh6azTSP5$0bo9T`FgB?UXc?&q@~vuAIR3Uf^Rbxj}_=PwvEF;5FA7 z%;88wRk%DSM{x8X`ciA8QEemzuMC&vqoDNB;PgUHKAIY<+%d$?DjR7eKyyOkFWU)3 z6^{c&CHzNgHBuOH=|T!M8op~(q6|@g$pYvIoeysnNd5i|%x+_-x;B{CiRMjjP=szl zf79Ff%9T=oD(NX)3ivNy`{7@fMo&@NN3JC@W;;tD#1z3`Suu`bdBpSqW}G>F+PmAk z&i$Lk)R5H@>WfvKBGpcG3U6ObSJaA=URN1P{dlq$# zD{l|3VooukPv6b9Au=N1UevUsCTteHU!M@+FIMx-I6^DmwLTrn!BKk<%Q@l1i);5k z;p1Z8G3OOQg$^IC&IdDZx)s4@dL^S0wWJSg;;EJqXno`$0>^loHWx_q?H+WFt&`Ix zjm5upLee_<^lp*>E~r;c0qM_`Gky{GnFdUZjKdRrE_Qmmi%i+QzEx;P@peyYesKOR zBtn!vs{DmbT};lTF3@cKsl4}e8YkHEO+2so@XfW?!dxsJ4!?eNZa>qA`Gn4|EJ>ye zidzopw&JK9_i}Y(_39aZ=XH_h7w?nu{KgDwgJsFakqE}Weg9Q1H#+}+shMH{Fl!<5 zvlsro8*iTtjYzh}@eM>uStgXhdd1dobw;D;m1y_L%2CSs7(;gQHVLiFI&X(qcg~_c zQEJHh9&RVD8tOy+I~!#vC!5ExTCXa}uIiLAWuUI|HOjBsDx@2hP8#5t+#oA{?b)&y zxSM)%*ZrGi8E;*GYxLxLir!SyE<^9TMuZ1iWXIJ{eAr+e(iN8RmLyuIEL_%Z9*1Y0 zl&7Aq<6<759MA8|?<_wueB71I6=!d(d}aIQdh29_A>I^}LfiuBo;B$c6X`c91lQz# z-ZYQLxld{CE3$BIYhYa34(vXZ=N=lnw2_yBmtmkHbhdA2%-`twha8|8qJj z6VYW)m;-+H5dV(a-2?Kv6Z7H*w6^Fga&yo&7_pd9WiYvmJ%YI2q5J53c~M*E#YFo8 zAgni{2jFZrc%vTL*82Kn2zYG88su>$b7%T<} zO6Y*E|9H@j;r0LKgjofQa4Bz}6mcgQ0EK0LPHSzxYx19c)=HgMF6y8lS8Q*;*NDpd zPzQ-ljgB3>gc!ItgQETpt%ESCfgJ?JKBZ34$vfJwG z`^oY`HqOkTGS1W3*eakIW$b%b}X(&?nhYO?p-8Pqf@Cmcok}TE!RUZ@; zn^r9Oa(+gF$sBq*bNR}x0(-G*$#38F-ez}q%%9)geZ3bS>HpY!ZX0wc_pZAnx@AI8 z&hH>cai0cSJHxH=nm4|UOX}XTL=r(>EaxsUM5%T|o@+yr(L&#)(+ra-K9!@H*Du~K zZhS|D{nXvR!WNY#!-W!{KAX$jVu8$>!H*Al;u1m63DkUe(Bw<4^}|Q%_0<`gol$Pn zZNWmAi!k|~hPkI&QQlvP4W}%DMj~Qj0;Kh9u&s_aU3IB2dV%_OhPaueS)TOPv=&+7 z{Tq~!8COq-1@fO`%ltK2{>f7p@LPxoG|l7DLsWue_bP_l6bOe%n_mWm5nVSl+?R@A zR;F01Pr_qvv{ABFRA?sngM6n`Q#b%hT;D*q;65_$!4E1j2E=X%@w#%Yo6xvE`8KzNFU7iy7>zO>?d-ByBv&|^8D!w+S)iM@A~ExsDw-? zb(tp4`E97iuT>9VH%ElwBN>WHXORBb5wS=k~! z(TlwdTL@zSN@{q;l_`QS!;!&B z(WMl%?<9%ljmXPNqc=_wszeTC80TEiXFu!G21fyLv+cdwbc+-{NU%|xrt`V_7 zOwVzIKFfz=Rj@Ye|3gkq*LH^;+;Ni=~rVG6a+LwO0lf z+#kZrtwaAx?Q-amNAM)>P6y{fa!?jg`5BqWdm3aTY`DkN-~1mhKzx^iq1Ny|3l?km z7871(UFWFy)_XD=SZnX)pRDK{_VdH%C8Wil ziKPK$aLpyhXS;pM z>0&@0D7tUKNUSQ;o$cI*FD|yGk1OXl>|7#;nf3)gjW`u3=U&$0-=sZv!)M!lFGWIj z?oI7BU{)Oi&X17ktH*abMWoJT5JMcAm#Z>QBL60JFC&qd=E3^zj zCRH4IRlh&~IEy`O;UfO%kOby=!_YnDM|k&1TeTmZ3{$}h=gqr=o!Rh|Qqtbwu+4Q! zhy&&ixQHOi>|X^q>lg$&QJAHWlf0@o%|s$4uuUhr@OhI{L<=`@;d8oW>`@#l8=NRj zTIBDRK6u10h&vMH@oiv0gCht<*h0@elZ=43l*`GRy-4(~PT683*zFM0iK3cdQ3XO|(|riC1LN;KW)a+%F!z=HrP84Y4tiz3<#*aL}L;Qs6iz zGVm>d{lapH2JyCFD&1>UUqpl*Pai@+5Pc+ zl?8t=y19VLk;{>og5T~D{)OA1s7gZg5c~!&gHaY)TwOm~#yBfgbx)U(`5AsADnP&T zC&)-ghLx}qDUnNm1u!Byeqpt75_kTuWP89&4VXeN#P5e>Dkk>LpVJq7UMNsb_3L8O2(Ie*-p>vX4_fW=giL>e>-ysv z5E=hpsGG7&S+5RDgOO%m-z0?jDY`Xj?>>eIBn!j(5Zb_JAG1-lsQZSWao}i1r1L}o z=ap{L09Qb_Lxg7rIV{2-HveC}GNW!z`05a-wEq-(!z#Dgw~Qqxg(FyF=y@{l<7WuX zjd01~(B;=x>GB&{;o+aJ_riG3f}jvy>Rm-&4BS^kE{*)H=#0d;@A_|(KLng7%An`O z$n%Fe@a2Qx)z^f%SI~JoO7|EHB9^;7KO6tEu5sx2YL|7-eFvmOl}Ma$cs7pYJY~v% z8e$FT^}0*w!(n*@^%XsG3}E~pW6lZeiwGKiS)N|#6H?=CTdv;~*_jnxjO&ebycTG& zF*k<$(nB!d`pknJhcpeiPW!x|s*JAhU@SMgX6(sG zsz?fzKmTs+2X`9=q9(kh#eNQ6==}^ElqP6+2i|%in1Chqt8=sE%*js=3eLV?dzP#} zE3a*>cF1)2g&-CB{-KmDW8by}^z@+7dk*y8@3k4Aa4 zPVJCL(AO0_WlD#4LaxKLERIf$ZZJ;J1j|iPBbjL@@OqudH3=_&1)3i{F+*y~M-jv{ zz0-p2Gk^45U@fP?-r;%?jYNN|0atj_6*6-QqchnuC5=(YQkT(2Il#I_O9^o=(HKFn zoxfuKK~ag8U2p7rP_R)rRAhDB+)DWf9RWoAd};`I(T@6+`)r9e#l&ITux5yGa%57} zcD?VnC}HjfIAok(mR5Xu8N=Lt16fo4Ou_B;*{1w~nNDTZ&Hm?hZB_mcPwayNYq(XT zXu@M;MazT@WFrZOj}w3&323ZE8=2vyvR{&PCEDH28KKCP7YaKdt#7ksRoSUSQ9&(^ z!+$W#OKKNW7zHk&Ipgr11FY$aYj7>cD&G#^zqMY34A5&aAu(~QRq{mD5U5(Tm8MTd zQnXVB$_Be8Lo(F^0x8{EIb_sfGds&Q*%81+HD>SSMq{KeQ^s+$KZlW$)#b z!K3s_nED_9S=r~4M7;(q{IhH%B1jyn9;ZLcw(KwJzeGl;RN-<%W2afUyaiWs) zy&$+A^IN-MyCpJNG=?N$mxks|H6I00Z5bu>!!6~6!2$JDB4f{^la{(1~Pu)Ru@3P-u+8sETu$bY53 zfd7veINP(Nmz$8fGxj!7p|q&Ik$b^`ujq`}1t9d=2jMYk6Vb8a0f*zF(b@rIROWYY z^fAWKL4Nd!{DLZ^pL$v)^E1ZSFTu)pV@%V`tOTF902a1p`+T#vheuf}!|^vXH2=L? zvPCA(2<@?P0?1pRK0OGLxC%sA)0Y*ieugYM!5{c;6O+yxwQ+JcQsJlUg&_1wgy`8N zZd2E+*SXPTmeQ@qhNDpuZJ!Mtt=GVJW5Fi>e?WIdB%#|jjqs)4AK(-N>bs2ic2Id; zdQT~2eQ!wO1?%VVjPO@il|>ZOW_A-@BFrPmdrvv|L%Icpl(shfmk>r!7DtFM^l*>c z6!2&w4C+1zo$bSYPjCvQKe(F76cj<jen#X))33wUD0E> zD|VmK5qP&%t6biE^vu!!SA4f)X6oy?J@vE&==j_ znz1@9?I#8mv$A`tx?cG&w;KgqTur61u~T!S=?dM2B$WdB?%U(x*qLedyGYbBBXy4pPKToW$ z_TR~Lf6p4E44MFC-`Gp3x=G`Rrx5C@4<6Eyo(OhC(`4K4%VNK-NgJ8Ye6&T3y^jbU`yefZ-&p_`JY!Dt{+50PX`z36A^o z=SvBHI^OMdiMUG}tnjj{75h~N?ZsTDAE-6zfn3D>KXkoSRGV!RE{sc{KyYbG8zi_} zTM85pP~07Y6etp$;uM$S4#nMyyA#}swz#`H6xreZ*4}IV2meu4&Ys-&lbN|>X1bD# z2)!Muw>vRrvoP%lq2FaO{t4OPrQJ8jtfjIG(cXTzxI*!rAB;8Unb$Q60yLL4fkJMK zL$q02n#1y9g3%3$8+5B*DQ#9^(Et+VLZhul;^y;R6D1GGZYd-md9`K91KLtI&kLAGS$UZXAMU&DO(T}q0@uw#llg-=wbb6W znb@#129nG$&1BRA4QeKuB-YoD12AU8xaW3YT&cd@>{b~4aYH8AJbHw&$XozD{qcE3 z$y{kt8U-YqjP0~0(t_mZN`S%204zEn{j~BKydNA(j^!;UYnc>oI3YUFh3G}~c;x1) zHKP_^NqFa>JO7nAolAjUesWVnZ&9Bk8rb~jCs(l}#d0~plS5Vsn^18AMcPI_ZODxl zLpCvqOz)GNp5REX2n1JxNJZCY;({l3-eT0e8kQ=4&Z=uLsM6Z2$f~M1JC=mLC3<=$ z^2QGAW~TYUG4LXMBEd56U33yQPoE5xs5Z+h5!yhuTCA!Dj2YA@X;$ES32EfRY@X@< zp%hrfv_BCf|I5pLmyZZvD1|8o421#RYN3{#1c1a4Tdc|MUc9n4MmjaXuuTL>#xlj> zmMk(%s*(vHR-vpOuj;6&ss8m>!pT?U4FMJ!AL-@kb?w<7$u&)->ks@4I}o6dTpl_3*#7vhdF>-ki=@=+;!%%>V@Dvw>EVFywW;pa-OJ& ziZ_%B6y??u8NKSOE5DrQE#^{R9HwLw)o;!I$kW5s1Lzs=DzXEv_q`4Qhx(u;M$u-b zL!QxDh+-PIiFP`NM{l#3nGXe`+af(f21`XVKgKvcnu{^8C{)onq3G9Zax63y-!joC z4@{K*of6{1aIr9P8Ku>D2Z$If4Sh?~@K1kZ{k2BPA3m82WHKIskW_-7s!2S9xs*>W z3RuV)w8o4vW)n=YID;F`h4QT|oyC$djwM~C@r3)7bZP+`O|^(eulr+B)jLj=ckeRn zJxlEUm9>@W(R`Y=>2<;w6{Gx_hTe@DfSg_tP;Ar5uXP{6Ok8T3jSkR}NQ(W%P;fO6 zg7TsApo;g}icrd#&ov~KbR>F9#yxo`)impTT%(42y6cD>qo-;f@O>?2(M6M-_)i(f z8#bl-1jc}&H8hRH7vaUR1`&qjz|Bzca0U6O`EUrAR3NX@DP=RAaYol7z+K``P!)ay z&Y!-C!TxtERb3M78m-xb=%Dg10kWnI#3myp<~vDzmo*b=7I{NG7n*sp{&?($EBcYLq^rue3>GN(jLWETL8

    1mCzFF01~A>IW}*CkM`9esr7ovGm`c zNXcoVUAkWjCn~X@%Fo{a#kIo*A2<7R?e(1^tbIM4G^`0F-WL{(rI-KymcD#BLrPR_ zg&uO<%0g08%5eHK=-8&#?NN+y-i@W&i<`xbt zUDs;r3gYo8H$VB~7sY<7N74Z5e{xgv*ZAq4Wc!sLdtqC_@;rQ11Ko?L0e@2sx83E! zNWOI2{Pb_^oGq?5MvKAf%6a5qM#bin@J&n`ca;bADvcC%bi3BjQ!8OmTk$dB>U_4x zYNJAbyTS28BM`H_*oEqb3?xX`^{)0lH76sAy<+<5X~Dv?qboN1o?EvQo+$1Hv&HeQ zOu+6H>*Luw*!T|epuCalXof+P+LbrOnbw%8B&OVV=oaZXsm~^krC|Fc+$i3u#KO{- z=Po6?=G1qg&MBl`gG`8VfEj{KP89U9*WaslS8$?vM^BiD(KAzUlof zb+hWcKeWL3TDVAWm-xFyo^ahoNEZIkoAJo;pbwERkWfJvyaZADsP=#yP&kwVvsZ$= zlH&(Q`QR553afzAUq9E#-{&hyVYWh$wWFIrH8wU2Bb-gkkS*XmWs5Fy{fv-rR3BO9 z=dB?%gdkJF*~swOYbIvd652P?Yl*h{LcBa;4YooG{p%OEbrtDH3(w) z%Q@ZD4c6zMD%@6kmZf+Bo2;C;%~Efe<`}JI5~ncPMES#9mqVEa>2{ECNd7B)M+_f- znrpy)HJM+|_MS(ApX9yL`xlNzEge0VwI4{D6yL)`WMf<}+0v5A!tx%jwF$Kba7lpOY;ptC7Xgf;&27H{>my&A~3<7x^4o z%0m(l$~R(V+IHv{8pfry-h80VC=KJE3Ay#gQ&X(r5+bCrtR5@}K(I0fE`}PMl0XfF z>qjU0MHKQjx89_gk#}y+9v-CbTLh@Ul<$B<_Ar8%H06VN6-ajUZ3Q&?kO!; z*K^5LuW~ww}?rEaLVA*_7X>m;3*O`tL*pA3ZecI zJPCsa_!>LYO5#fFcI7L^QG>kD8+3M$AFy`~D|4?vaXy;y7IEm%q=?0rB3iogHZQ4U z=p`p{h>)M9C@%0`LaL!*bVNH?R@buL_~04gj6;NaJaU1^Udxd zd82OPrCCY{iZ_{;v}FU#e@d zR*$t)NsOwDxp#)B?U2NB#uzqRvqTEni;pM>iSWIOjtD62{l8T_=S2xyv?*Qv9nyf? z8}>DSEfIY~!DzE-Ks6KNS(&N*C;95Dsi8bu(LY-3y?#-{b>Ri_7Phpwnt9ZD21Y@Y zF4U%q{>W)^l^Ml8Z;X)ZH9!7{?cVqmP7_|t#T3}$>+yAAtOOAc6Y{xSG*(`ty66lEv7ff#7*QXc zLr_u&84?NDuyhq~IPH{PkcHd9syZUYI=b!m{!u~*JDFlcbTpYzN(#Q&TtJYR(GyuQ z9%g@nJu{!2_k+-mSP;=@(5!#7??R&Y@>ub13Y#`-LbvuNg7OfBfey>9-nD7h3tzh>3LRMv|t8iL&yF8CLnxMH=}P zJ@$JfvKm#i(7la33IA+uc15yK1{{WT@^6(F#aRZdA0!%rEEQ!bHe;~1%gA14r;&Bv z4nRf&tcK?7aNu#y6E}A?reR%ZeEgU}wRF6)8M!;>0iJi_yVar@t^?6zFX<+7B+v0x z3S%je-x3{$jcb#@>hBtg~S z)Mq;mTM&HurK=TrU6b7C+cWADx^g?!VsWaj)e z_cBVX;KBgseyq}dIZ^1Xus$L+Q9Rx&w5dO zUvz{*WApaQ+%;1;KHwu<<6_A~iUE8uiB?Q>5DXsIj_pCTnhFcBU0Cc*rP|f5Lo73> zsgp|Z;>4xQQ;2`0Gqw{GPC#b&I5u}fc_6k)itQ_C4iIL*PDqd}W==Sj?zcnvK{>-#cclsfhkt&qPkbkqK)r znXH|?UA<&tjjv6+H7!`Nm=jgv6oj+j=6Wi`VFU#f%V`ev9Iy}>;r+WhAO7Vmrx0sl znH7f41u~f$FH5lLp_bBUXw}iujV){CWm;%!U<*?w&MGXIc1PH})k3pv%GBes$wT9l zvU3^ow-^H(_eP|08n(pk?bH95foYw#Ly^@Ou_F$P9>c&r^}q-0s+Se@65h z?uJh|8l}Hnz*?M%`IJWca!1u^jM?#ac~@00F0euz8C;dD+)h#?1L+CtnpP%c2+1NB z3rQ-%l5zGOc!PtFhLReAxb=zmV*91zUsEh(;XGPj6lhJuP=??CZWzoq^eEC@c#42O zvDReq(1cZ0nYdTWt=psKE0J2}ny9R;amZp-iVSGiO9U&?153Mdfu+Yf#pI#tO6$GE zfBLOcw;6`(at!VYiEZ~WU;dZ&40WRV4TeNDXmh`cyR<3_0^7bRxyURE&JkucFzL17 zPZ#O49c@qA%G0wA7ZFnBl@g!^zg6cbCeI-cAQq*}qR{Jv(GQ1km2t4L6?BcP(yg1C z%J^qv(Xpt^L?%Wka&bx!aq`ZJ@5)lgH_l(Z#YE8w&VtU(&B@p{6)|Dd>th|k$69&a z_Cm-72NX)4mh`_%Jc-E1r-i!UGq_n<+E4kP{!O~i@KTmRTSA~xg$K_|$oMKA*| zjD0!0M}X2sJE~zfyf0OENk0+1pN=8a=+AC6lgm)gLnRa2w4Yd920*gHra51*1lxUP zJ;yq4xY7nDDZ`Chf^`{-$)dxk&JDWZW-P$y5|+Us=z94l9KMknMiqG-GyB;j94r6& z(P$b=N$($WT$ma1zeDmSMG_mg8fK zT858xk~PxM5TXXA%cFl2EC0ks+^o343$z)rN{Ku_(+ns*B>!oC``K8&!xa7bD6HX^ zT1;Q$OQrKz{Hpm5#4tzWMyUXISmZIhw%Vke7he~Rt?&fu8&<3<(kR`dP&a>jwM#Uo zLfRz#+ahyl&lofrV*;iYn4ybOO0-L5sdHZSJD^hPME^s4axy~?2njx3G1$W+I<;BR!#XD2Eb#G0TKKFc zz=_>LcOpjOh1FsT^&;=Y&-jOySU-7b%If-D(UXHY)z|O#voEyr#>iCm#CFAY)JWT# zFQMy=DWWn*?m8NBjD+;YvO-lG+o=QXH&Gk2kBb;}%mccLT=be;m`Wem8ob^XnWDU; z92Q1<`_Nn96}~gyEq{5KDJf7FwmI8Fx85Up_$C^pKtl0wCLHY=v8->1V;}3+;;9Pn zC)ikYNgKK(Gswc+26e{^#&T$;Vyaxj?As65&4J@IFn>^R54x$g{%9N4^E;`b3NxP+k^sBX6NsofOptC?Jl zGkU76{F9=NA1m*BG6;EoNUK0w(EZL1%~{dqQpWU2W9%J{<;^mzYKPnSW`tdcWm$X3 zQ{Wlck(@UGFnybSW+hymUq4OENjgR;$k7Ayw(oH9Q&N){!thQ$6XKY7^mF=5!TVm#) zzj6_P#mdMAejeN8T=z!`+nSL8>noAvzhH9h?9kXC_Q3(m+%?I2-gJpZSJ_rW-S`>0 zS+6{Fm^W(Jd@7;`4Ic4e4t&x~Hyl=%fI2{wfJ(FMiZE|*SE<^yVDHmUuKGXTCveG> zp<%?5LcEyb|5g9|*-B4EUS7Fv%O;-Dyg=>!Eg5ZsImK_jq;c|S4&U{Hfu&4LK0c=d zgv=3Wps@-{7S;*CBs_9*u&{PdS8I>MV$_ z$e-`Bev`L;H%hW7swNQ}ND>{Jahu%gM_s(^{indY}HI*XMEk$mms^czQ^z ztHs`75M$DKf4-=7z5PO12LT0(qet_a8XNu!&t^d>ot(J~2ldwpTd$4((skJwMs~^j zBKRFJGe;;0G$z`ZA= zfbyT$$WtXT#7@se3U{Sn#=x}||inCP)7;qgXNu$@q}>sar-A@fL< zZX{UV%00}qowo%X?Z&(iM3w3ztAG2WOG~MZrmN90fZy-N;@vZVP<18P6ayh#>j&xt`uiZ4PT6$##u%M!f%Un~9Zy@d!Mz zS#VmV9XzdC-H=St5kQDlvZhCUXGu+-Uet!Zwqf=t-KQVDhxl!!(mJvd9mx_N)^ZV3 zN=9$5S7$6qeW;NtP|bm(ke+4X>!|Ry#V0DPuk@sS^6{1#FaOY-$m3iCF8<~A%-!0l z)zkA^uC(xaD3nr5(N$ud>tY3%@?psK_D%CfNuvM#=JQFDzFU)JG%-AqYUG@i$Kf6A zph3oext3U~Sw!7`NxFY71*J`-LWGpg{d-rYX(1zk>8PzXoa*${AS#m8jVjuTH5Lcj z9WhYlG?>OsN*__JcXd!2wRztF*9lq#bO-D1HCoeOBsK=aOUXR<%A>*M4 zJ`GYE#~~NGL9$wE+!#2a-DgryTs=M__c za}v@e<;4n9hy@9f$>*NARv@{erk4V00L%Umx=174xagYAK|d}auM)24Scmi0`$qk+ z{WSjM?b?PJw;YuIw*_zQzykLv`8mM%JfE9h{x*s;W3dkNgXMkB)bhvkuMs7a@lW07 zFTMyiykGB^&7UlGL>ghR=3T$#Q)d&=QHV)>l@sUT8)gyUhB`~yca~rUI0wn0;yk`r zSK_a?npP(GuI*G|>Q9(}o@&;_HRRE3$LbQ%co@_D(NQj^oQ*3bTZh>Z$3(mZX*qlXCW1yADDN_tK2B_JMT-Kg86 zNAksP&*U@;@B(pu2kCkJ9vhB(sGZj|B&wPmL(g{J53 z$QI*-W#Q*hx15ZD_prlII_};jFusujeF;hvP;!@Nedl|sIZ%Mx7?5i4wMnIg3{26wlNjEq^@@`#y#;fwlNjX|b^Vb9 zCM@7RGn8e&X5S~@+r)kJ@^xotgSoRG-B&05S*MHB@Rcpr?X^Q6LJ-|7x+LBG&P7}q z!G*M2NP}L}lyB8gu}MNaWCU#E&vOOZk4d~*v`BjiA@%Azq;IQZa&>S&wxPiI$IHf9 z<@x5nC{_CD$g$943-UoWVAH_`Xfl@Rne$-U1W*=_h8dG7BRZ#uVGe8(@<)x)GADN- zaG;@sWW~}GR4%Ry@O5Wffp6?qj+c0qqF#g|UOnreBc3399;q2?zQWM%hLb2ut_;VQo&pVc6}A`go_J8ETN^(Wt0v>G1gwB9=~ zRREp#RtW>0p>W}@>XvnekRk7Z#8KzP>< z&hZCsFX#6oMzXlSRfM=n$7A|NuAn{5Dk4U80J=(|S8cm)zAjGDuh*N^Qo?Ty^v53D_G(@e-n4IJdDB4Rt=#tF+K>bZ`K!HE zLIu<|i&X9bUB^h*g=Z+hC(Dn$^Uus%0FPL)AnF2s3-*0q%}E!vFbHbZDvX`suC*Mo z$z6O8U3uuh?b1+sbXXW3h;UvIc31uvaUu)Ar|2$F{re)E=DxOr!dPDD8q(<4{J6Y2 z%TxBwizyHj?FupH>*if?05^aEG4uKT;J&25JmtA0`94P72Zi(reVY63&@&^TmwH@= z%gSL((HZPCejGAK`2*_q*@1VM(Pwsq*V zH#CI3YOvN>lpW3t2Zd*E5cHx;PLW_!Ycx=HYSM;3opy)Y=6Y>PZk-IJgh20n^+~FF z-@k1DXu*d%)5%*XBWv#esM^7#*si4eOPU&JO4#rqZ`c!BDD9PcT*+yyb=CEH8r}!Z zOss6$KuBM0{hkTDgQjD>v{feb`uO&qWuVdk4zsO@!hcvB8R71pwEqt= z!g>G{i~LquEt+_9!(Jql;clpOv=9tZEAkI}Qud|}4J8T)%le}Cfq9f&@vCo_dg#D{ z{M4YCM$>CL<-a7ON*{UJ*gjp}Z_rjUrxlQz{#w<2mPlN}oub0bHGh6^`l!xIc0C)d z76w-dv|7D;j$^(ZR~v|5s->A}AraCr&YBQTd8fL=C$pX1Gda#ClPZcSTFvlzW|qvv z^RqNr<;x}jv|=F6ulJ2~8|wef10pMU4mYMFzeJWr#SKgbif{a1^@m20m12q{6-t$ek069&yY-zV6|!CiQ2cO-W$ zJ#Lso-xr2d>AG`J)(89|@A^RDDsTChoqfA{wg}=hle| zYFi~-3nJXWCwTrYNXHlT;ui$#8^yvMCkaf#1UJ4Rx1V5v)V6U*NwmAi^0G}2Zq|eu zaRJITqDpa~qto0T;#6(M$5koQZ=Z$zMGWI#zRNb-_7U)c z+VpSqK50+oTf}FQ{fyy7bl_(!7fshb-up)~))>7`==s?$-aJrFR>-s~fhU#3gyny6 zXYQ4M=5+vGB5TtvAX-f6*xu<9>?Hxo{EHLPBKmo;p`SLY8gK3));}T9tq_$oRG zsZnz6NSdJsQQ)Gxpt$(GIbPD8l4*hb_&ovo;-b=ufj|+E(2QxBmWb7|Lyxj|7coa& zRR$|Q#q*)7<_~l7=m^*1HrgmtTG+~^amaCCS1~h!WXq8YM9hbH(-ovB6i8LAfaCFM zQ;oT0!sgbye%@ny@$g&lyH!?Z!v3dJ- z^z5vA2A-!{JBw%^0w@sex3V*zA}nNT;GD-Zgw+4ku=LNNI0)c3^tgq!eI)_eFjdOXjo+^euvqK>GJZV~@8Cx7;^%`w{o z!GF%Mo$w`QlGj8xHC;h4Z0Pp19m?iS`uiYZgpqBF1~2#osk}o{`D+fkhQJMGaB8Yb z_kQ%5HbV{BpQC5tg1hgZ_ze=v($cE8hm!xfmkqDvP9dY8w!wi{<;hq!(n92EjHvNH z5Zl))@!_(5#B2Vs>Y^a-6=fr>o0@YlN2VyX+B;X}xYoK8%kV^Ru*6@bUR4TUcamnW zT4NIdH{XY$8%ZtqWfm63lX}&rMga{?@caVYJ{q}Hac4>sFmNwhrs{z38~$a1kJi(a zBz)J9D81Z1^e36`lZn~!wCL@+^*H>Glq}e-BWbFom+WU)WO7`u&u6kPZ{^jNMF%S} z6te-+!Q&}6&}BRyY$6o`(`*p&k!2pikB6BR>oi##7AO5YS1*JVa{=UIe^&QMVv97J za7}*6`_PL@# zEa*SWRVrqa+tWX5z7Nk2=A@PVH#i&uB?MALRfckk)@%1%LnWLlm*-G}nHE7+9yv=p>vf9t`u`0&wJU*!o+ANb5!r zrAQ2#NCeYKC~bwL#!Wb;*azdhcrLRI-J^!94Zr*bEM^}ly`}n8L4pAPxEJ5L}MXw`8bTI%% zOwFElREWiN%?!C6Zg@Xy(C_ebda9F0(H{42n`PoEj|}bf!QajhqORX~IK$k&(*!g7 zebogXC}|m9{OzNy@3mzo(BuyMVKFr;nV1hrqI_s_ibaZiBf~s!xiMa)rJY9qAcGmXMp1>_3u*C4CkJq=pTSs>Rv+>=t)>K(Nac~S z5mX{9x40G&{rDF0vzxWG-WYyPqWOLMf2};ijPdUd|QH3k-AwkBbYZ%$8HBIL;7RtfzR?~&s^K&$UuyEL9ui`rnkYV z=yvZw&Rw8=&8^o&Z>Fw7s zzn$E;sr(BRzKn^cxR=?B7`AsID_zYF6e5aB;!!rBQoNf3D_QE2WX#kkiT>FZQLcv~ zOnUUiS9QdN#_i@QFv;KPPN~QD^J1Fetp0U#|bYY%5Czhk0PR@W`3f8YDJ ztsL) zQx(-wS2myl*4>pj2Lb)fI0u)~*7kQ74(Ge5#r&Wc$uMfrsy1pGBOKy!bwo-3W z0Dr17V7FujdOtl|d|R)}fEoXaAFr7N!Cl^A&_Mm0-0+HPp%(~D-$f%<$%B~+Xj!<*~=P|tPu>+udYm_~CqmVuX+N z?)&oV1Ww{CDb_$-v9t$a{??iaJVGo@*LKzeTknaeHAxYbSoLy{=D6f2RW zyx3k#H|Bya*4U)E!qe6i*cA!rY$KTCSfiwpe*xW!I9}%s6euIq&f4qCHH3qfTgv5qw$A!ywq4Bn(Y#+| z$>%wVrcT*}6PQeK8%I4ED(yCg$4j3saav-g&%|B#YcmM>r0%NrH`lWGK5I|=~ce5K)Bm7ej-o2b*Z+3>^!T8S5wBvlN| z#OU-7bV!3B>W(1Bf)<=wvzcZJH5T*YXWc>Ua zA~#0~enTW1M45tHQ!;^86E;yS8YYS%6GGo&Fu~-nLkZpTgRPVQl=?tN)kLRoiEsS>$ZFL~!7eLFGWv@kA z2;4wcug5iZw9Ruy3$in6nej%G3yz6=;g++J6MSlSgoC)KUbF$1{}E}3Bl|NWh^XV3 z7@eolUmmL(&Bho)!JL1)&oa{jKlQG}#!{k@1)(KQpY~W-+eZA&0)8jOQ2pzh2zLuP zM^byMY`&PGu=)coP#&|V<`0Wg0dtCoTMLz0aRA@o)J)FNIe^!uw4 z2*Ep|RjX0F&;R`K)L}~y&)|Uf6I=}mqq{~4S+;A1dpwR!*apxxHzDaVe4#z z2Rd(>^;iwA6{cG#>&0$SI_e53zq*^pD|UdLGbFaQ`~#zq0oky1Rfhr`hv88z+M7k~ zQ_Vah&A$$$-0HD}UmWz&AtB2#ddwoWNZK-aXy7he>8;#Tdnj+&&i^PJjC~4Nax}H5 zg4)Z*EPh?zrlMm~Gp(NvZIHDA5fjjd=M^Rl%U!~a{X}R5 z$wpA1;N(@DEoFDT;*zw6E0o!wIq_ohA&ElR%;wF>m#IL~e|r&g3S~Vs;mN4`BQaJ} zm-FACS`qE^ZqbLKvjtJEZHWgc&K&mm9FcE{i%X5W1f?% zm9I5IBd|W)HB96^5dE7I_)7EY&dHCgVXg*iff=X$6#I>uLoz z+^vbl7!=gkT0hgp%o0~K{jlF{PLd8$wHEn3f9!q(O;dX8W)nftomUInPd@2nWBLhzbn8Ef5_%3&io1*g5E z&u5w7hWG?^1z(o#=VGCsHv7b*-b%fyo3jB5ks1@+t@ilnihkV zZY*jHA%A8r4rIhAh}n)IgzcK2^3gi81MO4PN#xpFR|?{UV@ktH*V^=_X!?5*t^YMrwpz^z^dH?VDaUn=Lk`*Ua- z72LT)24tRP_c6plz~C#Z`eeD~#>?3-BVV1bI(#GI44KWmh1ME-W{CJC@EFY zoNgjfa-qqIeNGo*Hwbuq3%3I!bF@-EH5y^)!RK)+0V`j#AZe-A1lI|aWINl_%OrP3e z>=0*()pmOPGzKz>a7kI&oqI)uT4yPeGGxWs!I29T^9eZ{x^f#(bXCI6?1tjV5ra%+ zLK(S-rVzW8YCoLbqM_7xRiw}OYVOt#;`ydq?p(Xkeg~lT!Zokg1u<)vBic{(h;jb1Od8F7m^d13;lUB|{D|aLd=KVINA-ZNepV9l&T#P>y|c_vHaf zL(HMe%|SH69p5auE5DKX(M_^?g~1b{la(@QEg<~C9unwe$FZ39 zSUC(iOdCC1Yyt(5z+R~7!A=erta(`q5y`)b`)z#qPZ@d6fnO=`sAuc`j4SkHGI*-* zi0u*?A(4qJ6^w)B0q;AMjaVD@s^9s(oSrWf9c6e&Vh;+}F)ghUVIzvx8QWMJ8Gde$ z(=-%e{h-`c{)g*}zaA+Dx-&CwaID*L2Re9Kxr6S$3G&e?UI8|7q!dEIZ&6MR2)9*@ z?sPVeA8`M$|9GDtdo8Lg1^tQ0QJXx?@TxIDb3_$Y_iHuhm7dA(kLp7VHg8V}2eIr1 zz)O1St4wyL9{{^}858Lwn>N19Ei41p@y))?ML$bQu{6rgh}MOgWjoN7*Z{i3s}t3c z9E5ZG_CE!4{^lqBQ*(>NI#wEb5Xf@D^r^7-lwWCPur+q&4m@r<3D(s;eENn6MT4ey zP;w5L40R%WjX0NoIv;T^{cIdiVb`LeU18Mbpc>x}^)<dCkEfI=AsO+b+{3gc}zgOuw<&r&(aY_uS!{XAPR}^ z<%T45f{HlSkMa|wEK{g4gZ2P}@qEVcS&qM|s+LS^4(ko*+cQNOnuCBUJID0CUZIft zj&we&#?2Jr#?F1eR171@T#nVQ1sFHfKeR=_96lx5Szl#8w*-cp_E54(nM(fjl(XMI zNvNX>>6!0AwCC2d)4JfZjD9-IPa)=baZkP}g(6&c0!0=60k;+-IIw@V+=&hgg}n2r zqShGRMqbft@DibLwMt$%U%zJ<-YorL@SzM9=j5D$x+|nr7%3OA9ZP=4nr0LYwzu~m z1IKw^++mCSPe~ts;x0wK)gx(>qww?hSCxP#oz+hPPpb&^8-BS|ppBP4gBW_g{X>Y! zeb(K;Ch)t#bTiHB3!v9_qtwO|!bjXD7O*XT8{Ay`_0ku+aJoAqfaI>^a>v>MjH$)4M zXbjA-ne$l&#q+}GW=EmM@WQUggOO~~@wR*gjS3j)7nlf>W!m1zMGLv^>_1`mp~ zqhT7%$YhvFNN4tjCeu@#22+=yOMzR;u~w|_Us;h3zDz*(GsfV z7*q@tYb(Fh3YihqX#w}jy5ObN4gaI%P} zYa6qHfXX~_Z1mV{%|^-9+p+$sl$P87A{`|HS6UfRv7UdfDW@gT$O8jIQCYK(Tqq%M zPlEw$csyy(!;A6;1J8v8nNkK4jVwiWVlt zh?Ca!`O{u|)I`?NO16#k?`QQ`ef#mX5ktp_8ezlx-?bhtMXrW-_r@Pb>a*Q?oJ-xW zHX^UsUNE^Rna68eeGx4pNkc4XQ4gSZGN_NzN~{e&hvFKNi&7|?jyDJ%Aw$WNgB~l6 z62or)a!2-6(-)t?D^xhyiIYJx5M@$^fGotqyxDy~GsyR*{Dx95Q#Xqs3pbD0g;hW6 zmzXljsr}5CVqhhbu4po_TOuGVTUU`Rtc})A$%yp2RkqizlZo5c4wC-GLp=tudtKRg zbBzd}>s)?jje7rgdRSs%9r84`Mv!(MBcm&;jAzO+-vkFWr!Nt5H70$cZbWI?FMihX z6>{QCilNUs*Ibip4~{VM!>HvEN2k0LArgHhL&Wx0xcS2_x*-9%7=`Zc_;yd%x+OU; zL{i3Z0lZ?1qPl6we@UOY#PAvGQlz@+$%0!Ss!SxI35} zBfo&+Z#evss*}uMd~g$GZfYWMJYPoV!et>M_WnT5{f=imY&>j&S+qj!8!CB%>F5pm z_o2z9ya3bYhG~ZS61(QES19%C;?R{Jz>2JvKs(BAD$ONLS-I(@yiaZL)G2RAm|S>5HbareyYxwZl@y z+Vx_yqjqdryZk@1nl)oc4CX4)cl$u7xQr5#7LNMLM&)_8g@#!{9-6q`m_tFpqYiA* zeBw4t#C}ILUXQ1Ao|t~Jpr5l*m*b)$jjC(2`%4J}#I^H^b>5a^jJF z;^ebY*gE~1u#TieXZN##^+jz*&QDJA@5JYz3+ra~*y3!Hntm4ozw0SZ*An-?#|P3z z=ekF1L0Lt#<`9bw$R|Z*{zMRIG*;k{%czbYP#X0mi40ftRa4wo}Ia`1wnr$ zmU1poj&DQPs1(Wt;vn#xiKoaghVQTgNVcZx{nPo{?vTUD{#=x_cqMq#+3B>vvmwa| zt0ix6pWMs;jK<3Ka1FP$t$#ZmwnJwf7u7svSI^*rOpV5JlF!6W(~>PZrrtCu5~`+OHHj~CK~s~Q=N3i>10e5MXJNnTU}P8&WR zZ0&u?=>0XehPHx5-BH#~uXLv>U>z3=Czpp~!D&TbCuKV|{$3w@p2MYA%}nBj;k|!ChKOt1i!p2@_$={%MPa3}LFTgXvMeqg2AklY)!IyLGlE{M zYrQNKqA=i=HSG%nF(#o_5OJheU4rTYDaYpi>~mmT*Ah+)*(}>I-~Q68F6FEOG=;p_ zmPl4N9VJg77G)uQi>;|fh_H*Q`xiFb-7b9?h*(?WbLeo3IFd+G8LHtNUPCM7R!_n< zssXS2Mp3}7ONvB7t06RpS3vy%*{=)jc3$o)3 zXJLccc>M%Y6P>x1vrmjw{~xB_GODdUSmP~Pyv41B;=$eBo#O89T8dk-0>Rzgy+CmY z!8JIvc(76^?s~&}&b{}1A&a#jJ8S2^M}G6n%$aAq)Y2M5%7BB7TWEb-p^m;s{aCZZ zX-igNS#sxSL0o`sz9DC=8{O21 z<|)S(%jkk+J_?v3pQ;E*0UVb2qx-%lZDyM7SWwegSRl^6k|Zk`d@N?GCMij+TTfUh zpDK_u&o5Z$qZ!7og{&sSjuB-wfJOz7H&{mPtE@R_tx?q^ z9GQx%3O%WeaMTbUIe11+fYUs;*>3<~fz~fW?1#Ku_WB7Kf9)EtN*jJn~T= z{)f=RZ>y}X1X~}*_`{pvZInUn2X@F$Mf>*$w-IRuV_5F>J|8`nULpf7B`GHP!tO#q_>XSA!>$LAhgOY;|q0faARP$IGd%iy?}3Ylf-q7c1| z33Fsd8m;1eIGTz6rZ}HiKnu*mGOc`TUu=FwlA^zQrGl9`$p`w_NgIqBu7-(`ePb*~@NpD%XD*g!=4&;80^SpW;3#4lcaV!0>J# zzLI3}=lwe*J2e#SARj+hhwm<*SHpHhbCMTpKG}%T89Pnz@g*zxyg8j28up%XTbCLq zU3%Y}9DR&6{)R0$^+$^*Ki^3Z<(Y{wPTzu=NvI% z)JN5Doq=->Fz=H6>b@SiiMRX)c?7J64q==i-bGE`iT|mfw0RnHe~2O*tb-nQJ?U*I zxLl0iN4ZV;_*8x~p1<$sw>U1!SJ#`NX^aP0oVfY|+(P)gMkhM5^wWr0AnuTv;*lJX zKg4bIuo1V)x-oI{6;9}PZErz@B&Z&45CwuRwD8F5@6lu^`{B9c7`vZN>lT000t7G7 z$`I7U5{WIs0EQo9L}NvSGx0k&J{VuRZt=2H)gB~6&Al|h zd{A{pa2_0Fw066Q)u7DL-rf1J^^kpa^6$)08TP!{{RoanTMg|DPz^(>_Q&;}A~@55 z1R7e`Eu28wdcI<&8ae{fzI7fRYIC4Jb7onTD&~h!;9TA#yBMTjmJO+Ol^Tb40G`#~ za($nEzuSdh()~p*jJ*Ye3RvY3Apl5oV+3XZ-u^WoNr>+@B;{BfUc?D4L44u1e10*_ zJw#@_qr4fNmN_Zj|C>OOB>(Y(aqc2UTZ+TEyC6!_kR_Mf12}6neRkg$N1YsW8_eXq z)8o5Xwq23-JGiPuotU};v8w3BClx0OgGq})g$PSC5hpDBgUdnK#28mn61T&pZfz&; z%tcy~(iDXAYSqRv(BgWzDe=qKs)O$AF(?g#qgeO?zMBk^LO2ma6!jK#$N;H>W2j0u zcMj#i0;6npn3xSeo|}}Tb}Xeu3BUi++G%yy$E(XJH1y~~PXUVs0XXY;e68ko}gNaQL1Vt%Y-NUi(b{V z&=9mal?lgE{xe}UmfIa0N?o7`AdK3vqBIoK)6S4YS>RxX=2bUPtMCvg4zosEje-mT zVME;ea!H&1l%xI$mS#{Kj~=qoSL?fyI7Oz65vCcbsF@v1(l~EgAzRrf5nJK#9&J8K zwfOk($orVaaB_jK4(?Bm7RwvL!Q4(lwKVpEXnX+9a=2<)10!>s2HBcUf`LB?JSU(@ z?Z`T!VkVoR=^JiXu?hhT?S0^glIqAr^3B*$%e|m)U64BuC`~hv-?`i3U1sC3T>)Vs zVQD&F>*{ni(~ixOd+s{S9R$J-8og>3lNq7>7`&NmMM|`KR3Y9tRv3rd(oCr~J-#GO z141d@lA#6R@qI_iLTqPKdx5Kb3OeNkz)+$+%#2{S3ylzQPjxDW4PnBZ-(}77#;1kp ztpu2$feNKkTPNPAK20D*z|*1Us^%-Ho+$+}9{bYJSqP36p7=-}*LmRihHu_6AsCph~O*)9vAz zt%7ukI3%d?AI}judS)KJcF+B)wEja_@tGtG#SYJQsDV@wy%HQj%Mt1{4g!GRj1jR_ zfNfX*P3g)IBxB&8SWggkIFVsp+e-IQDii1zL2S@fme;6{gI0slZOaH*Ca{s%rPp4F z&BV-EkO*`m7nWFSJ-JNSJkjZfyO^M9F3>Nm8azwOT zeFH~$xFTmWO&`BoA^k$CmWpqR&UP40F_8EYD6TO$(H>S&3m34`E2TaQArNmvoyRE-#8c&dIRaJMjzZe4) z&JKZmJ*@i(7fUf;i=v5v3FyTBt4cy)AC|zsxV?vi3(5eafZKG3ikJH{V0|gXj11;G z8$pIFJ7zaRO9_$?hfMm?UlCkHrK26}^Es)&1-Y_QqHuO9pg!F{ve@i+dJIw`6%rZ$ zVt$BBGUv?iK_-&9sk>iiZR0~BFh{f>d$<4kc@kuj^kR1m9ZzUE;?;;pFDNhdOVbg% z_sjYAEr@i63e%gh$3;R`f(6~o5Ayr*FPRWTkyPNz->XE*_uL$XawPRK_lVe@%odmv zwpO^NGk78NhIL}~gq;V3rQ@sQU^R0{Kn~I z)^v&GnRPS2@?5hhjn!$9yI(f`fDZo|r(z9F{XWjc)`w%X7ko;i##C*kCLglldmsGh zCi3${-}Us+*Dqnyq@Wo+ry*j)XHUe3dt(LZw0*my_`OK%Ilz@yp&m^Z=X96u-H2;X zE9>3`U9&*qj(CBQspxx#oHuy}&5x~~ z#(SGiPaS!XUyVB{IM=)#cMD6MW6LZ&S%$yTbqu9EyQiNt+iXQR&p~>aw|POIOmkPq z^+Hzb5B9D@;qIOPP-ZBOlptyE?YS;lq7DkjpljN{zFc4$pR^|&;~J@n2& zmT4H6{b$fzX?AHtU47!n+BbowU&$miMmnQ}8zL;)UlG6WXhiluFhizd7O{o4L_gfV zKq1`TVr>a+0qUMnrMKotyeY(1$;QHl3foX`hnZY7vozzY?VgF+lq|pD>U?p=veWU) zEkHL?mse1hT5a&wIyT+A4ok-eC?02h(w>D=5|jPJ*BJ=QZSa{?u>q;}6>KvBLS;X8 zE>hd{6K+KWWeH7DDcv#!ttV@^I#jK>p8Upu_`Fj$4a37 zt&mSn9jAj|w-JR#H(Cq8F44$9Bi0C@VK{!6@vqfQ#gV-HP)Gz2rsF?uYr(Qa>32Ga7SMGl^L|Lv76zY`Nnfgela^sM&hBfTW$(BczC@-|55K?KmP{hF(X( z9~I#Qt)kpM6N!`pnRtVy^X*=OgZN%K&ow~$wWm79Eds; z2aQ~EZ5xyl1u&lL#vdCh%zm?K)yj&U{$7eL3ByY^F$`Ch1mwzF1eM4|($#_CX4uHJ z92FFj5D`#?3H5IwSQxCTE#A$*Oq=8tGaHtS$gkJg$*S!4i>82F$8hnpy_q{7mJISZ zhVWg3;qT40b{0O^Nr^(zUucj`(GJ&6(Z<(Dx`u}RJu^R}bT+H`TnGUKpzLcNpd;J^ z3N{FDOJILL*oVVgxho7(CdQ#z4o&v{hQ3%Ymn@YlHyU<1Ww=w5ZrtPdO4Dj`OmN1B z-@~l92zqQ03K%{O-M#@3K4U(j@GT7G!k$>$Op4N{wWADsTk8CHnyoTzX4agxt8Jz! zSGV}huTdoE@bL$eD8c-a;ak>he`*#A+Yz+>+6`;V&M`@{lf@#RiWXFo0rh%?TDRF> zzA5^tsY7%vGt9z$4)S4Ve=@kganMGvI}o$0%~8V35E2rzzRNiMm|HI#fAwc-Q2Lq0 zl~v`uiS>TQF2tpLoqmSy8QMHq7IAA8E89c;zA=uey$* zm8+?cY|S4r)jwSHEfm7CV+6(3!m%|JuR?$L3iv7XN9Hj`ZEv5*U4!S}H-FDw&zL@x zSM!c}lOV*U>h!Jb@pgD^GmF=4hBjOfvcFO)tB6OhQ1-rZ2UBF+!3&k^Ng{%~Y)|X% zKkv)7Kz-)VpHhBvjxNr~`YkCd5$cIka9g6U`#r(g% zGX&9qO~R#Nc}8tDnXf#lbUUsUc_l4P>n3!{qYas+JS4d)hlyqHZJ^PFhcM2rs!$2I zJQzVN3hbr&4Ay_Xuy&a6Xy;4A{#}$2#F;s}lHE$va!LQUOy zJ-Tb;;FoG#y;Cne6MJk#==XU8AwS>EwCFgYc*<0YS74XQ7&$xEN^SHHe)_Ao_J?17 zwPJluCgiM5uRGkW7+7gWsl?IPni4h1MSj`E$zcw5Kr#Mt&R-P*u4z4!xH}Ak1-&`h z?*{nT6HRwPbQd}QL4Eufh3%$N)$>s=+NSmO4uMn`D!KP2vqE{ zJ?7*<5x1wgvnqmR;wmM%Qi)X0Z+lf0XL4H9jaAVDlUfRw9)$gq&b05?VyfR|fMXl& zOciK4T4%aBtl(+2GJYT_IsJ5Sge*`Qx!+?^UwZBk)EPE*F(q35iHfxJrMg*rwN!br zo2K#F%L$+0cB2v`&;{|nR;b&Cp)ny5jcHp#8_)|u`eR7ZY$-)Yc!2MFzDNK;Yy~&W z>G9DuJX!?oJ+0hi!Y}`?7C;YFE6aq?gcgI$LT@Oht3A#I{sBTVtlcUCGmZTKeTYEP z+FKZ%OQY!n>X}!9+})r!gaL68ue6>A_kY7(_`h0qs-@b7PLjDYo>&78aL0#V2)^eK zxz%QX8+3=*fkO`b9v&EF`(YyMwbB>inj@6EJOvV%___?=&H2rXZk6$dLsAb98Pt{g z=kzG;*+>V0<GD0IHA3OIvP@jK&4U3bjI zO;y5U00h#SC`dpFQ*(Nsj`(3=uQyv5u2|#2XaV;8bm5l|0zC1<7hk#N_vI zkhq)%N@pyLBq3vG)u^*7gc5zNR+qJQJH@f%pw0Pir)#PdE*@&o0PCI`P-LtVj`wny z8I;JHmEv$BK~GHKQO9Y|pfQAc$rQeiDAeV1ADw+Ee>Y-i{B2s2VD|MxITwT0o_Z#J`s&k|K__`iFd<9z%4Qi?Hz##@IPDMlcDkqg@edRqY&2_F3tFDFaoMB!zlu?Yjr(2PrX|SCJCoyM*KpuHND@BDTDl6!M<>KL~jCR zs4s?QNlAQB51wGjNM5h-@^4G@i0yAy++6SvMbfJz?o3}QTxS4OAmZ3)wI=lR09iN4 z*B#giq)s}*O0Pr@lfnP%iqzMM|CidANx~`aTMvCvk*S;dfm)awsc3|o1rfU<(0PCF z1B~LO1h0{(x@agzYd=qwBsGxeGGldzJ&?kB@tTX#s8F^6upxfm&HUww9$>_&y-;vZ zPueD)7CHU4LF>3rzB>p`r{Gq=6^tUReRrLRz;Wdq^m&8BGpWQlY;7?>+ly+xcwQD9 z;q7k~U&$X{cv+@{JXB;Y01N4xzzqZ($LN&8+2M={Nj1)F*r*N`*irJyOI23C6&+gP zs@xm0@5Pp#;InE<tyqGz>kW=xxF(3=$$0{rebP;PWeRpELIP zNq?B)&Ak=9YfcbFLRW|Hl^Pr}$)va%_ob@}X_VeR_J=_&u6MOHO7~3?!*@eF9#g6) zSg1_oi;nIyr%1FR-1w-@~?NvJ?@v#jACT!y?}`t{-?Z{%+*J-(@BB z{7=liNO(O39?7mweuqg<`iYaTAlApZ6ST*Fi3sQ3F!%7IVyrOzHXU?Q^eG+k^ijlJ zjD**IjwefU_>wGS$*M;>iM+P7*gxy2 zCjR1#gt$UV3b!8%{NHZzJKRCC1G@iBqdFy1zbkI0^4EN&L31dw$@0(kO?CZsGZQ;c zZCAXm4o`GQD)c#6o0fB4-u?NZ!b|8do1(5g)QyslbBk|U4rbr{b>Z=0O##W3KP$M@ zy;WVg=sJNOWYAOyo7fgG2RV$?rKSKoV_X%M8XMN>Dcn3-J zvH38P%>)s&G1_KoZR770N3GHL4J3D1c`cqi^@>TGRw~ivq)ZIJ`x;?Sb^5t&$EOT9 z%3eQ6pU>D)hUg7-mswiFYw#pxFwgWt z8*~tHfli7seqhA3L&|z4zi+qB5G;8hfZ+t0?#kngz#x0DQU2 zs`if~gJFCDlo95w`{0^lbMSX0^VaExNt&o;SyQ5j#M6~g}$v)2()7OIHD zVJ^-h9%)CF2(WCmViSTOD&U+U)RBm7i3D3UvkBO0X$~9$j=$kwNo8Lnwe-2LS>TVi zl1*A!(sqMLquH*5pV-mGL}9rBc~scj_sCKQpNV9;@a#O!x#V=zO7#YR0!TAdsL^V99R0w(kdYwE((}9QUw^u*z|Hn z%m+)`ey<4+>Bl{{T7!s4L^AbV+%|}2FBmlhH)%8b^9EJ%p-(*{k%p(G0`KAn4XIJ@ z9@pPZzeb2o4!}`Y)VXyQT@Ny5E1`zN%Cq|-Dq$-U*6a`~+;sWr?23Yy(RZWnBG;o$ z0ebR75bmJQ+{zR9f{^zvQPb6pr@vxadAMJ#M>@K#fh06H@Yz6$7_X4m0GbQKeLZH- zg>9Ih$v_I6BD&UVQ)cp_?8?^^ve(@zQKP%y0o$=Qck#Sd`2f)USa)8PqbK$P6e1aK zz0EK{y--X3oNR{A%+)|CjK` zC^7n9XClm|p8V5$7vEFy?$e`=r?loTC>__^ll{c` z1Up#KTY)(ZkH(*{onB_dyq`y(&bR$twpXxuMZ|x-T}56+T?NKyu)w*%(M6HuSL{Y+ z8x0(vb$xub!KJ|u!H~j7G*|Idmd$F&Dl6;0&qW>D$9nsakHza~%tM3JS+M%VQjN;} zs>Gf^cT7F1Bmkj}&!AUVhUroRG#y8S91u8tCFz%*mXbdAe$dbX8%B3!CyTc|tC6uu zeq_n8#;{qZQn(=%Qx##D5w)a=7X!oLLJ6&j*NzXTNabzHvl8P~n~2mc;O#Xlxu=8G z9m2CJ*gZe8ywqS-O!>ypV8eQs=oTt`KM-jwmB41YWL^DkX@@y)5AkMf$XD{()6IIXw_cGfsZf`~oj|{b6X8`(F zYO7Jn&~2k%>W7<^nKZ3)28+IVPvF~q-j(~@|H9w5|BOgdv{cDW#?5uy6SCz79lW;P z6Xv$5lR+qTg@>@xsWwp`M?pj(eCf&P6R<1UVIJ~v=_5_VU)M}~)Cx7l7L*0F1qMyh z!(;ra!CG0(rj8zLQ!FcZGx!Xt3_L6F5T-3NE~pJNgY5!XBWrlv9>{l@#Dg(nS<*v{Zng+fu7|Tx&BWQBpS2s-`HvMLgO5+2JtX!t-m99e+^aX0?5RPKpaKj0_=!dE4D(6&nBiL zbayU7Ffj^#nlR##npHi>cy@Ox6SZCu^oi}0LOvP-=na@(0+|Wp7CbpA|9TpAek?IC zhcy$~s?o7J!(~a^PBL_nAR&L3`Un4X=HwRTad82>{T5vZJbRxQ$Qxyc$U;YG_o12nAzK9x|0$;D~vG;Pn}oU&$Q>`wVfTs$3=KO|CsP;EHL zSQIDFRR~9iBe4P=`}HLq(FGFa@uO-=iFmk7^-)~3su#K%IQfB;7rxYv)gbPr z2P8+W^?_Zji4s3TIVll`=te!X7D5p&WH@N#y`UpdB~zk zkgzi4cAQez-$cA7BOHbhnTyvP<1LrIVzOK81qr^srd@QFcQbSk{-E(f&v3$1b=A#P zEO+@U2<+N6Ahx0+6R@?oN2>_^7fl`ZQ|@;lI=%RBoG~$`GZoRVi3K;ApIwLYAL>|g zg|mnZcdVW|qa+!AYwzs!$OjUicjj^|OOLj|bPSTrBuDyI%KEo{7bNp!m;6-)q1sX~D_+Uu^ zn=8BhBjMzqpKQfg@$jt?{&OkAXBzvvS#9j|55DpzxZ`fzTu!Aju95Kv$^h0+t8!Q~ ztsUIKCL0XUb1zAlPdBCWkxJbdM1AuNV1nN8ta!rCG{G^$b~5D`fIobz%mqI7bN}4K zt`ZE9XU7%mlMtMvrhMJh34!X~evEirnxxf$>`hJ3eVXk!GT$x`mWir$}chg+ByvCJe*YXXW&ED-<%LpT%zfurs1rr1G z7&(y}?@?4-Trf%3ws;`$Px7TDXKvH!FG>Mm>YI*jLNZ2Kr8)@3Efk#W*Z=x`g2 zUYc%*H4F-Wo2z1kK5$;mfaBT%)ok%GQY%WIRP?deaf!&93K>1krL5L+v{D zz{RvPnc>JU{Px#G=gRf1WW>V+l2$B<&iZ*%yEGmALvlaGc=LjeqHld)wJ{$5U}rTcOFfzpoqjYeN|72vr;s`=Dn`8$+Cw-# zfX^@|1sxQV&r<3_Te|fZZu6<+h?g=y(4`tQ*oFLnKN^Tt{krXZzbv%W2#6$>|0_meTs4ToD82;n)mi-O@{$ zz3^vY#nr01IH+)9Zy9PSnO9)!MIh6AhEEFOSfs8vyt1ymO91}~04{^l!2X71lA8u- z=Z=`x|H3QY#$$_SL)+v>Ctz|b!_@m<2foacC;lxFoiw9Y@BdEjev?Si z@1DQaT@qbNFs;e{@mIJf`s09CLw5&^dp8sV38++dFjuLE)~X*m@WjG=Jkcd>-uuD? zS~fse?J!Oeikp82N1B|c*w+>AO$-mg+0t!DZTN(a$ZdervT$B${#x*7y!9mMz`w)K zE6F`=y??#839fGv^e@Aj&DR}$wBGcigMUfM*?n5I2=|M1&1X>NlRpd6*)_2DE-lD< z*@}4(T0%I)De92;Wz7+@V4k?Ez|LeREh#lPmCp3k!&tXHgRAe7{95o6(DUV#=tfc2 zt|YVtX=QwdRc3n2!hS{Ck zW2h)%s0RG^2>by2_VW|%q8$j(sx>ruZZp64P*{tpB zBV*>Fh;^V2?v0!%diE6a>30b-hS8S*6*|bf>bQ*^>?cw=OTuN4R5@Ro{&$o z80v9P`@?pxUQ2x%q-!dn zua><+$tO-7IIw1zpz!lUS*#Ji^KNFHF$>`i54Xe@6#wXncHt_fsM7%$&@j0B)e&0` z6LUl$31L0*IAcD)|mq#Q&Qik!6I6On*;U{Cgj&uxatyGITd=hM&eNBg~wgT1*n4*v_> zB{%29@UZGxUQggb|n|mZ=E#iS` z^1(N6QHT>HBG&(%^)>PPbQ#33&{h}^llY)#PM)!3XOq+m-g+xO>ni?Ly7ZPV$`X7F z?>^!?n)nu*r0l5!bTvxCVeI8EM|fuJj8Q7@y}d2jahloewu1zFr`Ni#dPN#Fw^%CL zf>>%4wWwICLvh}hVAnl&&zj$5JrcJYnyyi(7Gs%1i}P34m&}E$-~$> z8>M64-43xWh$1k6^cavSjvs4F-|FdLvY(s>6y=az8H^LHUF%KllV%$n72 zHLdxB3)-LGkAjef5QnrfREap#`bw-EPi}}V+TXw!(4b-uEO+?NFXTClz%-57a?_Tu zMZDHpI+_-#*4SB6wv+l@xk$*tf!N56EXyq5f{;K|qEqm%N8Gn6^8&T6YA#_yd`#%a`iUe)lOLz3?UgY_Lw%mQuzJQ|YDXgIngW zTj93n18*(#B+ljD=H8vyh~A+8A2e_c$d!(+`WI|&2ORE+7`rS;&DudX4KUJh3q!-F@gfVe+S#3 zH)AlwF9SEUJzMH&l zIwDJD_Hb%hx1;ib2uZ*{>7hL35i6^4`Vbk$N|vJp&qt+n#({0&_htRk_x^<5F{z`!wn0*;noF!yClC-mK~(A1y~n+2E>14gJ~m%S~({4BP$SaF*Z* zTR#~N(C*`Qxi4(fopUf7ISjvgTprG72uFFNYvd-9+#r+bfo$BpQqQA?ypoA6{`F=j!i@^O<^pU|*6-R=2l&>_#kDvJAwo?LM@EQ|fbjx+ z?q)Z|Dt*J}EuN5GNrrke-OUtymEs&OaAi^g`L4ds#9%S&-(WOll&WC09+y;BVUOO& zN$wST$j|a(0~ZX;7pbt&D#Q1;{okmAcJ^D+%exg7$EucY z!hha=uCKP7I(RwUr9=*h+qoKjedJ426~ARot5Ze5B)H-FYW9>f9+(Qu63l96J|q-u za7uF2Ytls0M1s@t?xav1=$=N4<(}g}jX+N&TkblwWSCux z(nEXde}={&-V zZA^xpy?L*f1C6#Q%TbNbkeDzG^Gr4NL``^Rb9*@E-yz!YRQ>FPeP>_OG^ixHQ7fAy zVo^MGNs#`|F9a^iw*IY2htOk0jpq|1%c#QUn_&XwLDT0PR1gsW6=@@Do04& zvFf;KjowPqrnhBn7)aCBwnhqqg*cjgr4dVc?Vlsge{Q{c6S&uA5u$!&&?J0o6s-LR zvgPg%$~`f8s}gnUi?gmkgxru)#vNp`_Gxvno-`!7#w0WGq7d9{%kV-KY(`#v?Y++b zf3$~P{|PNFQ1wF-w6XQot^r4}J4(!LDwzl9WpkiU669kr;xg@m8JcBTP!c9$GTp$h ztHF}A0LM(Z50-t?|6_u9Jo~h3U8$m|#hHmrlwJhVtH=c&A@4z;Ktg)1e~9;rw}Pk{HO zbU;4-^W7akma|Nuyb`Q<2%E-YqAHfmfC)dzz_lrrb_Gyw1J44X>aa>Uag=3+#b2p3 z3qH8bibmJ~B_Y3%M*owSLW_I1l%F=o=~Q>CaT%{w*@?MNaJ7rGB@)SiT9jD8WLpG6 zr`tF7H}jq+AEk&v)Ach~nA7?1BVam9-?JmZ;_Zq>t~^V7#%RbAJ*P8;6BAs4Ehc`rf^OU`oL*@Idqw<#?b*~-?TQR#KBaO27n~OG!T@+~8col|>d}Kckhra4q zLOiCC0aorbPuiW6#q9-56wZ6zEzAx>0d2)Vne9EH+A1zHTOO6wwXhiOvKTK3Y?&H& zl`!$BsX^Ehnm@eqG6Ni&+v<7#jkDB=^M;#Fqyr_~Q1JtrGzDVc`GT5>|5pp}+?!(79Lpv8Zfdq;B1yt(9-l=0G_2_g^NCCi++`Dug+O9Ud- zdZN#Zr_T?V^@Mg2f6Y-oPQj2$l)uYV=hi8^@S87Ni>}ba>4u8$(f@q0{_$0Do58){ z!M56cM|rXSnnnc)kO9Ly2n(5T9j~t9TQG%N?5Q!^SU%Si^Tu+G$L1@Sq4ib`hoB!3 zQrM-sM4zX&UkK%&@ICr|58qJpSQT`mtalFE-?QfL!M`>W_CG_aHN2XKDvb0_$DWLo2h;4n2>%?y;(Mwoi+r$f#_vS*+{eg(hIcFe61Z*KLSbVo@h ze8g8K_CGMjo^0rTn#z4~H1t-7ZErCt6nC;wqW==cFY3}W(*7qvZGi>k1!XBlX5XNe z-*A#rkQB@SDKVWwG+N*G*xA&N&t5V=Qb%j|+t%=*- zuMvdknHrnIs-&iB%;|`GY)qS3-o~oBQkmQlcdB}9<|}aOpS~6Ew^*J;;MF=dlRc z|7`1NHnPqqO1Kp<5;_wxJ{RZlo#jn8h8~=4>1m^!IX?_v)J0UZ%^4x#u?S-tjSHgjF zU5BI5j2m?8ZOcE>7kEA@8~n8s6p;J0c)hG5$eEi*yi#WKJI=#;>Wj565>E5iGU35W zjcRk%-YPKO$V5nN68iVI8>5ruyEclhvhPh%8Ze zD6xVd?Eilw5QzPDSpjnl7xyAbDJA1OyPEM=UTpS6rbZPe{8j2@^XG~fR=HMb)SuGK zj#%osJ%htKc9sm2c+yJjd^%s443+vm-;xf%OBOGFaOq%bM4{)27mabkKWWrt*^u45 zoiHhUgqqXJy4J<;@#1LgNU!fhMGt}BUmA#A6wYigvOhRRn`$&I<0Vb2h_=?w{<^a( z)Bje9vyaZg#(F+QaCk!K$hPenx|HKh#jy^gd~W#i^B=_Q_9^YhFxL!a*?1dD+lXn0 zzquF1X0SeIAZz0ka07jjY#9>K0N3UxKy4jIk35IZj>$dyOjJ_mlX>>~hnk zu3cM5#Jhd_X~^-@XJ~rjS;DN4zGt#i;ED^^bUnaNVhP&zHUmLdU#TZ3&*|?!J_ZK7 z1(QL5O^S8Q^G*<%Mc^Yha_=p!m9QskVE-Tww8VtdBr5m&J>rp2N?DI+PBmfuEVs%d zf~znzs>+9F|I5qdL_|7MW!~p8h@=0Rc{i#U$D!S@@-&3e)I-i!@M^V3zyEypk;c`F z(%jc8rlS25)%xchP8JFo^r2xVn;PIuqT1g9z{SRzBgq+Q$xjQ%;TbW+@8gqgB)#o7 zW;R08&GGqHT7Bx9wH_-Bxld30Uja*QIZPKi6&2n9i#VKY%X{TsdDjntxPB4Zk9SoT z$)-Ab0Sx)Pl5VN1KQ`Hoa)52JLy^I9u1n|b*K6yyE5kzM`MMbzel@Y><lwcp?6>w}=1Qux{I@Go^mModv44`7s*OOS`VY4+%_M8F3#k z(#m2wvx0SFohUsT?Ft!W9=62|KH`s&Yfdm*r=UL*> zoxCOM^LF(YiNA?FTndjr^as8p@qZ&qW-s-qi7l#tWpO2@_{8CK6))*kwkSvT!;5Pgt(=$zd%;i+98?ErN5;;7Pa zm^e?-|BBSF|i1l#02gXFl{MWzv2J9GZz*NK#v8{9u13Fa%<+%nYEk{YpOvWT+f zQDT?yIsFi1X86mUc#Z#L(`R%n>;$QhVjl4PB#1NH7ZYT?u^A(u(Q}fQp&hiP=_(*B z=6YV0-4fl$zU^K#3g3)8ed@;o8WCN6%T4@@u};>fqS#c-FD@Bm=z)>*fsP`bl}1Gy z0tK{p0cA8En+S{Up-`WrqjyVmAr^CX!lH`vN?m0e(pf87&j@QM9-M~{zmoQpvgNU? zbofqkGBxJ`?c9?MUr76l5c_wDtcTbJP>B06A}AsTTRA!I&DOf+#k;=Px0<&0kr8() zAF(e}H4amLg)aZYIl}t3$C(~YLPPqSC@Y$XmK~2>GtLa8${9h@(>>_q2I%R=EWNnW zjX<~!Q1W~4XX)lQ-Ync0`F+j$NFhr2?M;&)UhIF9SwBsu-Z5%&Ju;ygT+l1LS>?? zDfN}Ovbzjdf!1{T6VQ#Aw6K{Bm04hMX+iAX$?8B4n<#96=@gzyLoY9tGO}oW2haLS zr%FQ_b<4O*!*9c({7G=6mXb(mVtQ~quZ3eyx&Vdo@P|kfud$sH0aIBf%39vW@bA7+ zPB^4gjdrUS^E#Rt<7=I0mnr9T+b?);YQucVT+9+(|Kdh73x;3EfbZ{t(Aj@c@nF=Ta;uZhVRU2pBG)zSVX0j z+?Q?LML(P^zdc#%;p7(w7Ts=p!j7GU*pS4bBJlv2?n`^=9mCMW>3%zPL%V&QvTtX-Fbu%QL~_Jw zYD)y{EAt8yM9`XcwluL{K6NWbuEP5JUWAnehRN5wil2U@KVK6K@Lgd;DyAs>Kvh+9FhK z4&Wx>F=O_+fV^E(v~rtLQriob(w1$XSb1Pmbp{WL{Jltwwq4l(VMz9*+-M@5Z45A| zF2^D0=Br6>B>ai|mt)0Hkl>qJ%wcVi5oqI$XhoKT*FHy{GulU`1EQs2cshZ2%-?6w z+$vmOo#+bTxN0S2_v{w_D>Tj(^A>|B$0wpSSeD(C^U*Z*TX+ zo`cYK@?QTNd`rs)8E91x_jd;2X&ppb*5k{bb=ju3-*_B!y=&su*yQ)iB^vZV^_l1W zXXWunb_&CHIyNdP0c| zaj<}hW$L`HyA=DBK+0iZLy3k{IN$5k9KVj|=%mQ%&Sepv^IkvI|E7y;r&BJgnx<(e^;FW zUzU-9mgC|Yvgr@J;D>H3qjzD|yyY?NVi~^QL9u@@H|shlOkL`UoRKFw`CwrMwW0fgBSGZ_A7oD%Nu%x(EZqA~x;7@=ces3I+ zjoHs|PW@A$cL_G+Fb9GN4H)25?ot%d*-axL&LwQ*7^Up0y_65F0{|z7S>Q#k;KCTi( zQzmwRYrpzU9FTnWpG`}U=por-1NT11^|Ojk%MhPiCZ}}eBOxeK5`r|2jYdR5ats9#>F(e7zR&wUzdvBRx83)y z>s;rY&$+HQ&8)m&re|*&I4A6&ml%|M>_N3JW59Mw;(hqig-uJ$C zB^mSD@^rd+{tK74;4A~qQ&$LC3#n^dDH)d%3@|Rt;gLvXA5tjCTU&X>XOX*RrzfBI zwnAe>pg!~mEKit=zy#}lZk|&u>hmPR#Pz8mtOmCXdlHMy58Bv0-CnxaxAKTZzP%gc1grKQ=YoPUlpU}#~bVyw+uxNa_%mBjbEm%NBu+P z*HfR)ZuNX%X1S)a9H&8G$Bp{$&Xt?^8*@Z6LI49xv=}N$QT747L#c<# z0jcXSy>TT9TEkf7n82&^{4~*-%KJ^;>um>Pae0uBHD*!YEwgO?15~$qZ8qGNJ?Xaf zZNmKNJ0=IhP5`gt8VCLWc1@=KRymKSZ0dK&a6s1?`$|%PXbA7Pb9QBh+}|wK+MQ&( zqW+PYwh5jYeLLw6yO*MOa$>YRe~u`bb^%NjQBF7$R@W5-!T*S3c_-ad`2bUtGmvcW zU!e;*`nbejO7A~i*P#_K64XF{bCRPy(RLTKGnKDO(Qt_fSL~r^lH;Fnq074S#S7~8 z&1c!(*~2`qQrVK#*F};ITc7RzUW4NXX>A4F+_=a# zVFszAe)FJyzbeeTM*CWl2-Phb%YT5f#`E2UwS=|oGB1lK{>l9`>Bb1n0u}uV5*3k< zIyASTDZxXYJrR>o+#XtU94EJoTO%Vo;5uMD=$0IK2>@S&$INbu+$l{Z#^P^LfuE-y zOBr4Ii#(y#Xy4#=Ty@XESpNfnOzwqtRV(fh9GQ!amX#8O!lV9*2A`z$1yYI)?85n0mb#5}*lC)P^ zCh(`K#k=nb!9V>U0oN-f6KBt+!_nM}M^9$j=mn)PX00|yN8q;m(ouko>^I5I2Utdz z94S-?)|C0a1+uh}o)5n@vFTbm^L+A)a?`*CHzZY23L-wrSNB?t66{OrBZ?lbqXm@jSEKqV#g=PJ_R94qj)x{Hp z*--sc{rDV44=Wrtv&i0@ZQ_*=!M*?sKQ3`RyOsR8@5l5ES?@Dmkz6wWmFwH3`QHx8En@|* zxQcTpQX*GlV4LVkzQ^!XYzi*GNxmMkci(Z%IvDCw_O3{Lh!uydn^OdB%^#d`pKj=r zPpurXX2Lag5OciB-h)lPwE;;LKg}-sx#q3*ZMjV-TF?WL;LvIH=7^wjn$q1$X6fww z?3(z5N#^uvk=-G2bFuJF*;TZn=?_sx@5*v7S^U1yMKV$h(o zF1HJO+BYCc{-q*1`cjJG0iS63gmb*3^da!(wFBJIlZ&}+9)-R=tp$frcDeh#E%Xs-ZzWW{$U@1_MYc)NQONW9ru=tVrV`zW78&^)0d z$TG1^R0p#WqYhj;>9zHKzk7||kHG_7yNkpBt8*NFy30KI=y3BFX%|uIH%`A9mlha& zvK1@VN1Z;vF7WPmRO0*1y5D+Ps=W5a4aPfZVKrY_$R|6$8;9pbL@Y*}I8dXJ8=Y-4tQ8*C#wkunkB97q%&C^^%uIQ+CL z{q_Y$w*0$9jt;yIY;Q)@$A!vGQ?{CORw)=-?%fjMwsV3>~dIEl6!a{8N^Kx$E1!HIDEQ^MvnX5}`uC{tI?4l< znTncYiUG7q=#J~KxQ`gHxC%Nity$(PEKu^&&~8t$j{g%)rW0BvWEvcgz;ImOO4H|< zaNp9jS=K^Mw2Q0lm|81+I3<7IPW#VZ)tGmlyuqrt~%)luQxuN%m}U33T2+(Y|}4 zM)!w+h9>E6!zLG18RarYH^;^NFYj(>U%5nCmJ*1N?!reW_H#LoWJ?kX_|=wY{{Fvmbr#=6*hb8jAd_YAm7E13FM_Pi=o z4PDAsd_Ta8*yU0n)x|EAJWO%MQT)3TW~3flAz*swc^pfrfS=7;+MIw_k-&1A*CU@? zCoWI&nSMEGZL4VniKj2u6k6I-x^tn=dl%}R&VJqUg&j8`sDU%nDCYc!WZH83%li(! z#=WlJioGZCErs-|)8+jZzeP8avMAv@T^xUbDdz7`~9U*5@60oGq zHk99+`3X#lvHA$>01E3A-f_W;tWT&1o^nZyEj)%;sJIhUjEknBDb0?alI9G5YBix8 zy7SZt^E{>$1NsSXV4wah>w>Gbk{R9)3z)>>&(}!uCA{zAGfMV%gum%%z-%x2fqqaC z;P#D^f|0O@h&HDNa{hO`fAG~ywHPQM#!9IN%CzZB?w$sld=>4nRrM3}M$?J(bK_i7 zDA*{K0>DmDNzP6UW)pl0#*$h5kuGT9H8Ay4lDwG;(O|Z@Y-{Ia{)78ypEQyCsy;cWT@+kl8b=WCAI*WCo!Nd z`+xetB@2t6v&-WR-r+J|GybI_K&8VFDVI1|uv`-APK!7X%xDtdp7npd0ANO$tB>o9 z@_65p)}A#pEO0I)HuF(-aRyK}t4`iGuue>V^THK*n5zqq!^-j!fSb1Yj9>Zfr0m{+ zzE-973i`cT+=pniz&t}4mN^$nTp~yV9tEhu_l6hL8M^XT-Md2WOVG<8AK-s6J?#%? zO%c7Qm=-NV_ou8t>Vco6glrH^4USYW@X1@G`?%tqZ939D1}pK=3%0`nMl0_Rd>;Le zLaiP6!aZ-v72tYPD{Crad+(< z4=~R_be2+AU01z$ANszTojnWh+nc-yuLRqkWG0Xv-ogPgzFsDKgEx~p32wv< zS^2odWK|^A6gP{o#!L!>|5$PVj}NT4%==nHUpGEe*$vf%`Qc|Fk|R@ zu6Ltj-8EQF2r}8o1=bCcm_;beA~gk%v{^ilEv0|N(7GP%0v6EOlqbobq)ZCej} zogAc^O47fhr{_-0pm$C7P%j#7eMj?|)pfu6WI$c|V=wFh%$F+u=#RO?l2zAL>lVqiF zb19s67bWbF@56P-7!PETE(1h{(R6V6iJh?b(Hp4eU*L&-xSlxS+=nTHD&Z%)=L-W= z@}IlAEuX#9eL0-oAgvO0HwsT-_}LY>AJMk@cRA&d?ntB&Mo>l!l)@7N8r!<- zwN9t^yp?Y)D9yU$&lRwcxJQrHUa5WU326-FdsQh`6fQ9=d?>~7=FS)Hqk{IIf(}u5 z@uW;wZ%4AY%O*clNRj+o`kc17Xr3!*i_gx&M*9AtfmGn!M_-5{*WVmoR{Q;Hqmpmz?(VKAFGmv1)EFpE$4x7dI=i^M zT>0X!`NjF?CkHptbA;~*u5aip^pQ-Q=1-`})`b_;29C8)kdW9P)Xn(l*h+IFSD|O-SygkFh9tt;y6%Ah`+K`X)DVkA3ro*&$-dm|TRebp-|enf#;cuA4r3kgzTW29Qi?CB#Y6*9l4u>_Fz7WF^e6N1fzzI^sBKdhW~kF z%l?$%zRS=Kf>UJ4z>tTgoN7cT``<&>zdq(F(@E?g_9+-}xDd~lyV<&tMXRjV`d|5i zJ#Kn;f_NDQ;-gr6#sqqf0azv93|Q7>BhGDSy&7+oL|AComx|ClKI}og70Z{VWC3416MeJsh^<$0Px9uYQ2jhp+NYc^&;*O9G|Ua*(wqxx z&_nImNLj)wf9la6SDd|8aPEb6=*d7`vJc{m>*evmM=ZBFSZJ}|L&(;GeCdQtMCITnR6_@v+uaIMtjVH?PJ_|W0hfPoheR?_l4N+1 z$xbZ9Ev!T1(6qgDz-nOS?%&%$+F_akiJUy!DoUt^bpwMsG#A1_!A@R%5$?cIavt4= ziv6-gF3U+jPP7#$W9UT?z-1(s?s$E;nTUOx*Twu?YZR!Qx$c5EfHKkv<*{hM@Vog# z#jL+sF8t=C$CX8~;dTkrk2e!R@?zrf12o_btqUOdH0Hs)DYeM5w1yNABpoLW>9{-- zrxdybMuCg>h(N6rL<5G)XK1CltE3WhAtzyB#q(cMp$ooSew4e2-GP15%Us(a4Ps`{ z*Dut{!wK8*0l|sXy|@0ZF`qhku*7Wtu?_6KlI{AM&;Q@jmi_|tU^U7TPU}=d#N$bY zs|CjQq1AX>Ocz~b_=_=yeTScnj##A_0)Iidh1~i&IoQSWWirM8H+gTQH5ELZdTcNy zj1n*ED*%t;nuK&j3cApk5Ce!OCRKMiQzs}q`&Yw@?|UtX#<``Qj*a?75-Ed&4bP~e zqF{?{ZdPt?J8ME#Us_RSX$5^M>Z(bdJRZ%J{XV#>&(m@K{!SiHWJk2<>3sy@@1^6W zxwL||EPlyL_g@0(FtQH!m)4IltR;gc#>e`!THg9HF9|;r+)$kPk8MhN0hk9_a_`S- z;#-Seh#$CpzxnW&YpHn03_ZmnUm2nao?HpXq6&c=CZ(fEV;BpK2V?F_(nmglo?jk>i=&AbPpW;%Ly@$O6i2WZ-Hg=gNCv%UhXEy zh`N?E3r4r;|H!NgxMXPo>pndbdT4j`1VTXp!t#_eICLA5$C&@HS8?Vr-N19a1B<^U z%{(TfNxL~8EFZ;r?K;ifD?%Oi9Jfm(a{-}^OgqjSIZeEx=lr26)m)B+kawbvh55O& z+>&f_ymlmZdRTMNu-wyI&bMFso<3+J%z}w^J(JKhqQhf}C2*;VoIo?2=E%;5;`N#T z!zFb5>X86Z$Mt&yrh`w=nu$Yd_|%oF(cmCLoM^*~cvUC}4h^YWMO1Q&(moavnn%xg zoi|5g22Qn6*60Gxd2=>9AD$V0KW~HR&=OvGqt#mAueqWR^Fmi5@s(RPbQ5c_AEBJ< zwmz>dI?mCH_N_$R-!o4;Qrw$JBNXOW8tH_rZ;;~!qKdE3puIFR2)hT7EYv%UF6f#O zwj;vGmVPJUq^DE!5FFXOsWwCIaQoB@_w~n~q8EKiMWC{VV#xjMOif;1o+%UvMjhK+ zj+zqcL$aejYlel%+uR-H$yU{XIwev2xL>6VqX^c8*~)PZy)^2n+9=$)D-=ZMMIR01 zHmEF?Ha#??ii(OUn~2-fx3|SnjB-KgHD%$2ZIzy#Tej=93=^i1sjpLfT&VUy6>4yM z7aIf=yq3wSqwoJG3Uj<9aP{XSD*g~%Dw@MQ$K}Mn_I<4kvhko72Y}Rik#;q>$#-{u zt#;j@xVXXgC~`)QN2)=7OW~MtC3u{WS|eQ$4v%9@W`}$i4q4 zPQ@b*oN>6tDbMJ@e_SEqm&&QN`=(}rdUN-R1udg{KOP!#WIB!(jUqaTuDwk#ZP{`< zXF|4R3A|onP^iizS1<1|2<2;0V@&NgL4}z zIuqQz^=+@8@^_bishkqWVcwCGfSXVkDHG#BVJukUw&cfTV^CZBwDr{W4u~ilyLfgJ zw5N10%r}=TJkW2ZBF*kJlo!Ce$WMkL!(=I6KwsO*D@KfD%02l zFtx&!&kj|6GSEgxY|UcY-~CzSoKeaTJ%p$ase)Ah)&}Pr#en-eU**!Yv;Iw-mlin| zISN7jJzjjzgg?ZD#XV(}_Mu8XjW=n@aPIV$IvDfBOeWb=rj2tTAnTs4mRrli7vEn; z=<``|_uGCgzjJLGMr{#(N(fFhC8vhm7S(40C}pakFh+Q9U{}U0pc~jtQESj2pwr}! zreW8{y!g@~4@KcUNA-4x{Q4HTj^$>%qG^tAD|vTp$L%oPQbU?;7gPh)%k@%hlcq_U zql3&6JzN_el52lC(cy&cYQT0sTub2iti5p_FRo*I0+|n>zN%4@D7mWV@r0xr<@w7h zu;hO0ToAvo1B4s~6CpeTw-exdXTdmVxnt>01R}b&mGdpEZyv0XH|>1bnH^;5c-Q;d z$-OKcF)6(EKRdm=#R}Y}-&Cq;y!E4gp+=CZ0#c7-DH=hQsVA0mM5`pSK`GT9X;Adm zjvbz@IBqJ^M>(qLI5KiqPOG&Hojbt&G9xTEzf`!ebm2uCUl^mQS_Lw9Xx!nqkx4@* zjy0RB?|D1|0`htkfGe!?Wj}+R2CJ?;`O;rqvNFG?8RoUSmu|$(34_$(GYM#8;NQF8 z_U%`&Qld}i2~LcRhxA76UezSc;w{|EA|Wt#*P@wjiX@72g|gadX@Po68iz%`@j*J% zf8GlDhd(;j4vZGM(AqG7jfi>Xk39_GaAR;of1dQJFyhNS*L7F}WULA4qn8BTVc&S2 zxD)waN&6skz>lj`hcjsJ?))c1XR5fjW9GO&#((o4S~`zHfMJu*q7JKsQQ9#82F7lE zm;qHP$+q08^WxZMRt^=8@6>}HxNB*j3W^48)=}wu9TzEOEHHuGqD}#d17>A!O#5UJ z0h>}M{aT+6UeaVuRnwXp14-2y?7M37MROn324(rfIT{~QqW(jAj9|Lqk^Xj$dYs37Kxx0G`GM?rUY z=VrqDC+QFH#3GtOcolCP4yLG_4Lu!-Ck~$_oC=LdWg7MWh^YK%Zi;b_W0@9In4tJV z0l_@tZyD7aV@_6$uJKz@Q-S=nU-<{RCOXV3F#4LxONp+fO;w#}P8_0ig*)+&~y zmMLJS47{q1%8<)IwNhAc574vR6g+;B&iD*`#y+XST1mn_rO$uE{Ggm%AH5qufAG+!qs&CCWAB2EC6AvtiiN7l@xeKR`iz~|k-q`I zkor$4T(C_F;r`H%2F|>PE=cx%L8^PfjkUa~ouVN&197wsC&l-sM%g19c~srvq0<17 zVahLSaVfoEX#XvftHd&>`}{ytJ(jtyE0YY%26Ijz)bhOA=w=_!vt41u+KwV%h}-pK z%EKe{N8(ia=B)bcRVOr}@$ZJ4-eKV%O52eNZvRKAvK$IIaYEVk-wnnOcYCd0vFa~| zPzD`A_{3{jQ6@14SW{>dXz;-2$$*k*vdTY$>&$C)n{hoZn`7*BK!Ftiy?zd&bLw(4K>l^9hZp)R&bUTj)rutY69EilNcLKL!4mV(oNI0?+|G1@4(U zB=EL0H8Xk&w)HhdjRPmYyrIa?IXxQh|FA=h{sLF+mue}KJ|4xhxk$!pV05KaLAhC~ z9a|EocBCC>2(XoJ=x#@B=eikQzF>==l*RII*ng;88U357Dm@Ej#5nW6aTj}3c(Boh zO?e%4OL<)ai3nG?CTnZ)>Q4+DVjN(p4s5CWXuhUf^Wyb`S#PHa3p>V)vFwGxrDWt# znv1KUrG%oPIs~)h=G7l#`x^vz=Km@u>%WniU!LO zLWY)sG+kpKPO}G|>C4UkfE8X81JP?WZwrHn&3w+aZ@)h3BRld-#ObpzuAc>#H5Nm- zEhA)h!B-WmMUi+Iqjln3xbrV9lRJzwf(J8fOzP!wYXaW8g~RRMjXXc;|TWNz%xl^pln;NkiXKj7eO!azm5@a=xF^ zuX~Yr2e4dWuef76;IXSs!ZeXM0Z1mFcF{hnd>105@= zY-i_AwV6hmM*c?D)zt+0Qc#G31)o^b*l=@BXlmgPtLB5~ew~ou=(AV&rV8NZM)w7z zns>@kwlG=}Sf&_UnBsUuNB?tTSSVN4#kl)+-CUL*Yw#yb`!F(5RS>m!y}96rc4l}N zCS+DQgcKKwnp5&&ufr5~?rS zjqHlyVT;YjdeAT)T$?{Af+gYE7w7xVF$4I*M*V`Ke;s~ckvYCu<#=xu9>esEp9X#Q z?#=3E{x-A#us;ZXe0Lf!P^c+an;^bTE%e4dzrPtB2TfGW^>7lwYC=!yP6K5gvnIo% zL%J33qz z#4>-YRmqm?a{dD4A5%?3^I`cl=Y1J;iZ%R8t$CmSLECS?pxQ<{iuc7HJ5f^twbOK! zCJOG}dC)?%;7fQ@2J^nNvDq)%2%{Q{bSS{01mwiC-%V8@PFIW{-P7Ydi|XHg>zi7S z2Dt`=kLjN8WQ=y6?N}nH|MYb~r|397R;dQed{Rdy&aq-CKHGk2fgV2x4>X|}YccW~ zc1h)8qnfXWaFE3fcEO);krm8CyL@R^Xb(&H!Pnfq>d*92nDQ<}-c|DG^2UU6gh1^u zKQOtV6(VIvCBnZ(CAf#93EYsMf=|mLchN}kj$fVN6_<|tm$RTWKC}qd8L9z-`Uq1# zc|V}34wV1{HtYr%VLau+byl69Tz7E-?A&t}Fx}h6r&5`c7G8TR%3k?`ult*&LDG9S zG>;!Mt7z5S@#^pk@qqoQ`GKj!J8Ws5BsdY5)>eg!aYhXtNk} z5wzI0;!izFUj5FDP*6MS5$)Ku3>?`^Eq8shP(po!CWL-{B@Wd$AzXd`R7WlGCg>x? zoeTYTCt>X5BaqWDMCSMSLHhr}Y9)#DJ!Dw2YkO{C?$rR!@6>dgAzDF;K`1BlZk#)`uTc1+h)lGz>Va+syGCha9#@Y+;I0=`0SV7`-S z^*_oha7+muwYuk#5^CWu+N|-yQ)_)tbl5`{M!_+=7y(EtrV_KKl`3wI+9Ctg((mxO z3cz!hH*d)7pzsV`?0@i_=XIF1*a5cgl22l6xhYO5{^@c%Yf8*CojA%a*LnFylAq7^ zC6PV23%^eiQ_VkWpu1@URRTyV!d|vnr@~r9N}p#ssd_%xeWqZ?mt?GAeg6nn(`wU$ z-hMPEduePu(QN9+1c?js+E2PDN1N(A>WhUo%oEY6%agUNWPEid>~eU^%!q`{Bc>gf@ z%X8fdw6V-Z@>vU4zGFbBX&OGHcNbcdxhqFS`%+(s$kdIH*YQz*`WSE{7)h$^rf}a!Ia9fBQGS?!R@QXz#uRlu&6hYFk z(xMdu=fwTM6lh{=k#Qdmds2QeKul^%-tVWPylaybi=>EGf6~vL_9l>fMgs1n<9N;*Xr#H2^ zL4H7#Y}q!%mno2yJQDpm7YNPF@XC~-dCiphR^n*xTBd#V*MpnfpXMC62qL;Dzu>*~FN(c^Lpu>*4F0W(jP9m~Aj8EhJ z_eZ7M0UftzPfq$WgF^uuEojI7^LFhul~DPQ^Eg;FrK6nzHZR)l)DC)^Ne#<|LS1x1-8p*&MeR}AC z;a^)~jrY>;F!m*FoW-^={7T-`SYxcFIOqKzL*tHm0G2#^Z}=jR1yOyYMFIzNk+5$_ zh-*_+`eehm8UryaDZWnJyo*wfDgS8RbzoFjpTOjZPDE4vwctoWvYYyv(B+TL(TDz# zjOW=$Z*Hj=YtoXs%R4KbF|%!<5^L)IyEQV21){M;37%+~XTPG38nHwZI0BWL!ao=}VdpQQ>6)XFIO)-Egck9>`H&Rz zLUTH46B$!P3ZrP1A)AF9&p7JPyo154e_|q~L%W)#g8+1 zSKNo^ry~~^Mwjd|d^rg5jQm)idg!O&VWAMqw&+jK)*eXvi$-kUw9!TRD z#4CShSGT+2%q}#P>64|vk+e>~osOZIN&PKAh_%!NR*1}dz|54Q&j;8w({kkp1QG~g zd=9g(zfp#E{zsZ6SS4QnZ98nHMyBS_XJ|eMz)&5%Zn}#%F~7={83pU+_BpK+*{mgk zI9CSuRXtxJ>nZ>D+$!nAu{YN(HmW>LU2MUmx{HG$J*fNYjJfFY3pE`GP%(R|KuF7jA0h&>K;Zu3vy7aiIy%l$Q<@Uwd zplPoM7xlmpIu!Inoraaw%b_tgo@#-Qdw(GoeUE7iwJbi@VX<*qX3H9B&v5l9zpc*W z5ZyYx-YC|Z5zEsmv=yZ8c{{Vu_U`1xU&CCc8ZV8QfAbWeh|XggVLSYss-uX9&C)Pibp^S>*(d=#ucKXBxlA1qZCdtu z-$NirE`agTtZ_z!Kv2x*Er8niASMBe=#|9Jb#7BV)e#tFj9&5^PhWi>UzHf ztf_RngWH+3S_J6r_dwD7R&^DJoHvFhe>^Z-0wnyRY^#)sQ0lRLx4j&ObOy)yW#3ST z#0nK5{PURenBYVf%r&zXSm~6XGq%1+bxUF41+VZBRK1S&=lw6)cbF)TgpgyVH#Ncu zIEH*)%jNe{^c(kVy$e`5BiWu))W>Zqn$dytluLw`ZRlI$pBh1VQ{~ETP^V#I-ILEk zHyBjbMYja$zt>uAoO(RTtrsegg*<*P{-sBHz#}$Y?f13mq9AfVi#Kc*$xg|F>-kZ8 zd#*gu>vDvZ*|Ty)cwjsHO^X2jCe&vr8g;h;RYRv@=nD0A(`?1!>nf_6J-}0 z=z?@>ffM31Uh9OFVqGdDwVn9t=;~VR5mU{_`UC2G*Oxt6G`spKFxB+9@o>#|uOgq~ zgk#VV=r1Mclh9*T`b?C2^2kbhrU(Wy(-MI}nbC77SeGn(X6`Q<~Kr2`eM zeHI-Lr39iJydj0$se7x}Xn(R%kX}FbDO#bzt;$x#$w5flJH3T^nP@v+VW;5}@yo&F z;>{)hTw-Ox$1#|G!d&={tZ=wpx!8}X?T(bqXo=mn+7y#g+s3jot(%9 z*7R-SFve>fN@%K;|kXbV2KHZJ^&O?e&n5HAJ1G;Y(1!_P&P zv2~KQ_Que29Msf!2X!r0w(d3oG)2i(gMy4Ceobk5f68k5JFm|C2j^uV8cEY2e(Cnx zZ}EsfoZPp=@+K9Y9$YJ^_L^|P6>cKR zT#$=Idlfz9nWxBEv%~I*w^x5@tj1qdh{)yWZujv|)&RQV`F({PsFE<=?yoyT6={pP zrKUhzT9%wZuOXg-?>a_2w-P~I?4=>cdUr^w$k$)K{=c-dINtfS8Uj7AVd~dm|%6u!ZiJaj&V|w{jHU42kTC##I8L{0D@}@oNutJ%P{xU-5EKVJ9d5DM*Z?@)SjoTQv5iwB2v#^V>Z}2J=C|x!f#j*ty}f0w05n6UW0R@itKvQ3s__ zL&OvJze4z)-QaH+j7NHFN6bg>^H(^}Qg*dn)5yodll18G^pCkc_9`c^CP`Txz0)Jt z#tgZezk>|=4gr1V*r#%(1A5Qv9koJrQC^W@T)id32fO>dQ>4FS+e6cJUBCybwz42W zOaIuO%>8^o^k3J`*HSt!kHpisohlSoa&pf9J~4qIggukQ4bczAT2gXn5Bc8la#*K4 zwq@4GS%K&&$W7p<+_h(w5xmqt&;K?xTrC`tT+#V0C-^|vCiF(=S7tLe=QOM2YZEg+ zMsyxohm9p&zCm*FZB~wC-*E=e2L?@NA!Z~)@3oiES9sQc{z1ZJ_CxHMdoScD=nESi zrlW;)qv&IDhp0ist~!#vm@bOUsp9A)-g!HnChc)Xc*^&W!rrOC8Y_q=lh=y-RzTkE!5~1X zl#31d^Tmqda2;y(OzMY2THawrs2Sfc*eH@`gD$@H>qHtc@ZV=jB3*0CM z3*zT*+P<@u6JE7tWOD=}{>dFuQWlTRKek`a zL8pNVKmiQ?##v%I;U{o)+R3hKw?wdPk+gZi_YHuBgL_K#&)4(6yUp++o#-G(Vb1KZ z#>R%Z+f%nJt2r)PcFY)xD#YK(k#*IY+Q7@rI5O@zC z-A}*E)Mg>GX6wpmse9Iq89-kiWUp}S-*hPA_kYpFPR6r;d_jsTHwx<)WBUT1dLB?+ zMF z{?wh%LTaHEWj|tmhj~GGu+~i5z@$%5#;^%4A!a96@M)+qMQ1zTIsBvz5#JLL!iLIX-5A;&0$+-B)b>;hTYrGQE~pc=MTiZr6a>JV<|$EBmYp??eEqB z1y(QCjYBUwvPeJ2@>jQXLcfKBmsMha%lA!PD%sG%@wZw(Bv`PgB{Zt75-jn2hkg{Y4E)ie)A%ER@NW4CE;c zO<3s_3UE#z^Z)od8MU-(@9Sd%@XVIZXRFk;`w(+UI5yA0O8f0`oV2Et{!22rK2`wa zpPCqXWfW}yvz%@vi=<-fpSQrz&c8IZslZ&kaB8*pF-D2JO1w{9?Mk5|2}b2od=7%V z1dU$N@__5eFkqK}EepI?Nz4q|16nAeAW>K!`c_k8bnu(Om@xYbum*%a6idoj^GJIl z-~Oo}SjW3inRjq;xFE(}`#SQrzxNM)=RAKX@xK=0YYuucX2-@d3z61szeiGNYcIF^ zXc-5NWGeSuKexyK0bm;-YPB$i>xydA^MDsU3)VZk&4EKJ$sd_(@#ZieFvtbvYAHpFup@={+W~)ND8-05sbS^Xh+%wf zvhs>ma{bb;1oS^hG+pi7=N>Zjx_*qKV;U-yo9!L;Nu%sV4{YwYZ11!6QqFd!1^uGn z?_=%GZ`@GsR9@JVa4EbEqnI6XNJ;XQY04I7sd$hzDz;Lf1eX90&`kZrDe)Zz{*9|XC0F&z6Wjm_zwa3_J0HNna;x9m} zvH9`&Y56IJIQ3hH$&PZuw~}&u+?n3QL}{m zYx3aONnB8sL&->jSilvT3s1h;m}_Fd3xqGdY&)hQl0T&hh< zZ4kG6t*!3NFEuWeTCOdbwx$IN!+ub`J_@G8!uDa>bG8C@w0kTq_TPl|$o1hrN9cBsBg#yz(sM?bH z>Jtf(&Cl=$MI%2hR2{u4d||kDg&U1-69nWahXDxiJ{ApaHxEM^nykr;gzVjKf=*s< z?Op9zd-ZvS_=fGq+I2~$g<)or|a6*2HwmFU_n;$DB$nQgH@fE{hkP)>qJaW*-*3 z<5GD3ymBcm$%}e04EEm?i=KH`9lTo@$vB^xyTNNr1wQ2+Gua5Lu@!hV1{nw9G=5^d zsQ7;4AyT~r0pI!mRtaHW0|z`210S&D&Ht6v4;{jCtutEGg{C!_J5O!O_C^hURy0WM z;syu48kb+u@Y?>n{HsgA%F1J)t?kN^b`m)ZOkCI~H2?kDA|xclbz z?uW1Y zF`@xA>Z(}uWQ_LvU+Va0(&GPuFe<7-f5K2D-_6h8oQ@eQzaSs&tD$@v=R=xdS<2eo zMU_~1j*-Gf87WJTzpz~nW_oHv{jK9jdr6TTeT&U1cCj7@5>RGWJOwb1 z{MM=L6LrYO${LqS!LWOyBT~(tup$!h#OMG(6@nY$BPO-r20BZBJ3aLq#H=>**O&6( zx#`$$vBCRlX}t<#Vf9p_XB_zPywN|WPkjl6H3UPwjHi0Ecp$6E%~Q6YZH1bqpeqUT zlMC~fFwZjBYv&oNM;GWPB-czdE9!f`AuTY=D&H2O{i>uVQuq?C#y+0O+_rO$8Bzf= z>|%cuR9QZ)3|VaMs!g=&Z8-iPxN50(zOYuc;`NKB$hdUm7we^jIl0dpVP^4-ttdl= z2xKaAa@MtLx33fR=tWl4yL9;GNwzqVJ3|wt8T$Tdq%t8mfysLOm_ z7n=V1E)}dL#0wg-b$@+xOBptbCa;P~f&TmhKoC2sf+OoCbO`8x387AcJpn;8foYKJ z#Ekx+!8Z|=k(7zxXaYyws*-ro%-FuU015aDn&zb?nbq+NXf>9Di(+D%h1EM z9A3^6pRl)3^@;zFsJ9G=D&D@oX{0-b?yjMvyQEV(Waw^&?vf#-I|Wp_8$odZDe3NR zknU%^_xHcgYj`m;=bZ0Z`?J>GJ1T&y8PuCP;eqgfMX|_0J3djbYX2{ryia&sxw;v3 z<2QhH`+h-BC()dZUoxbg#|MD_4Wrd5`j6g?3u0WgcQa%9iOH8dzqdZr3nq21h+{To z9e)VBl8vv56bzLV0HU_N5#sZ|CyJ}KS!SJIB-Gps`9s8|GRG$9!olZ0lA5Igu6d2+ znb=le$Kwkw3azdeN+SLtH?yI-qmWL^^^Y+AQuZWHh7Wc+!j+2$Lw>(REohUvU zCYR>+nWwhl-NpU7AGA}prtb6fOb<#*;B?5n#O{V%NZMY_;;A7@{1@I7B`Z|3>S#BqbG$9F zh=p*BuzM-wb<17GwTSfXXOR^O*y~$9HObbRH!TMbZX7fX2pmPA@^z=W4LV|;%ucT5 z3$xH@{S+jzwkbLOrv$c6gJTqZU4({d>y&0a_m-pn#1EVEtZKf9FE{s|wFI*se2xDo z-vj!MiZT^;HBpMGgdY=jD0zbMHy>Q9dH;eCK=h@@rqLzdYK@xuL*VCRtF=m!CHmg7 zbXHEDyYl|a^yUW_&3+Pe`5S_S7^C}Qqi6k3ccSZsynt^htk1^fS+0ty>?i`h+ztNg zIlt3R1-F)dpIcd1_bjDtct&X^K7?;9zZ|oa7eE(Q+;Q|zjjV1Nbsm}l=15$_zOWL> zf`+WIA%^RrF=M5c^+IS0cM7p|x!)_ozE_l?h9@if6AeoCGm>7j17<%v3T%j+`f)E9 z8DvXw_`P-TArRratsCwTDp^UHEKJLj?eYjC@-dVPXN7@8iZx%vAj4tyV_I@#%F3F& zWh+uaO~?H|{>n$^OXpGU;M8|^EQZ4iD`^zs4sn_#W^ftyNSC<}e8yDuwnT?o#o3dl zhGmDVV3ng+e`>$9+N@&PfnRQv7>FnNJW<RD!y5cep7m8$@gLU+eV{nprQIAYV9l zIFbxm5{i(jP(%j1*rbY8b4l3oMSWYjQti8iLPVW-NnF9x7fm?p?U9CO2HHc^8D$~q z2f^0`ToRwyoo8Ko%w4<(qnrAVQ0CIKhS zd;xsWJKcd9%nbK|AnD=($@$oa&yFQKp!8h54PFjh4yi!Of&8Jg0$@G%z=K|V)laL6 zf^^dwlBb7(mNzf1OHA4EWcP>N-SN|kYeNRY$?sSehb z`_O2a3bp1PVHBAQk4FOG!IG%#plXB`XhJnRi7}{W>)LCy;ZcBbw+(54F;)c)O#X)h zEO%a-1?HI=k#&@?i1|x-+8{my2eX+Tzk0 zHe}QyQX{^vGIFZ?OPTWD8NNSCnNPmU*fT32hEvB8!@10t07upG3WvNTH)f_@|A!;$ z+-UfCgxO3J!bO-*lS{ELim3N@FEBa3IS8n1f&k$N ztyn|2Yfrm(6`;Cy>=sd8S8*R7~woYyum}~5Mg8&9R0|&gq~-e_QAwL zGa86oCx^iMNSi$gU-F>%hh;02HAP)PW(7t9p0ZYprKcqg6iMcq${Ynej^)ZH@zd$! zYn&C3EtxFC06S7*a0*sCBPU4fa+})H^k`(*-B9)(90xFNdLyEjj;l1Pj9Zq}d5|dcZ19yJ!$oN!CX4o2q?bpG2Iv%`wUi+Kq@EKge99%jYd*sIFD>0bg94 zUZi&6?`+vqO+<&wH;#_6kJ-Gt^uNP^2&$TrG38du%nXZeTE^8U*Ue(k#9}U_zyDQq zL#PM*TX~MptpJvfFE1jYk0y{sJ&couz+Zb8d2FA!Eg0)O7KjsK1uo3i5qWE517W|H zN^dvmEmdFyYS8!9bGi;{w>MzMx!ZrG^ZbP>%5T+;XS9f~Lgn=8nHN;j!tnAa435GI z%C&Igh~ogUOkjZ)-neh(Iyaeb3!@R7L5uvBDFKNHP?E<6zL3d6`yJYWl`=P+w~d&^ zW?v`q1?0Q!?gbbnML^{^j40{wX(U)8?#?4fh}iqr;jbH|+cPSos;i!qhMEnSYnkNsLtf9WH8>$>t-7#Bd~V@SAAs6{I*& zitm3B?NAGF<{Y$DdVi7X+uV3ELc#rleKwwfHoDOX!J77KZqCYlj2YiDDtCl1=DD_P zk*bUvvruCmMvD$PKc3lbUiMaCwHWmN(92vJ3miztpp2Vucx@dIUA=iViF7h`=6f`H zeC=G)SFGQmi#1<)ai_q*|1Es)atqi z;TyAfyg8{Jw|#Yett>ylYEOZmm{YYOh;f_U%_@R~#vSt=-(OcC|KU#RTMM*B&`P25tMVE<%CH zd#8yiCu-|+h%K@j>?dbs@MjI7@1zuNm9*c^~gQDGJlF5U0`DhU4#x3ztLk zz8O^~w^3ef8RS^;8-VXNv$%j3&)4^M`rdOmv#G(+J;$~C$)8v{{$Cd0T|jm6(oPiD zViRyh_WSwCc+G)JNV`jEX_h~ks|IM$ z*VzA>&Vk+0PyHNky`u|h;{sEnzfLX?0VFwI_6PaOjJ27HwSroK}3i z#U$_`3SVoJ{^bhILW0rK&!O+eSY*>Sv%-aBc|?_MG%cmza9b*|@n`h{fIh~(E`4Tv zKCq*3fD2>ZbDbuj`|iUXZgW{Y9Gl}h6If?!F_|62@2D>ni(gWF_W-@|q=m+Y^7=v=d; zfzDict=j2dDrs1sI_iT~I&X3hD|dXxb^?D`m7d84 zHhhkpOKEJQ?-&?&^7oWj%kZgfK>AET>3+|8S5kG;y~9!)?L-U#IS*)|dPDH834 z42BZ7&;Uuo1E4AD?fV)EnNOsFo=tF??S@1duwk0!R%wtm( zSvSkQ+#;?&8>O`L@srw68f=mhFZdl)g=@VG&g^4m!{}|_9?t(vmLYn|H{G@bJOC*L zdQIC+b?z&w2i?`mdP4UCz$MZp)(d}V97;?Wvz1dz=%GOlCwpzv^L^snRKWYHxi4OM z7$aFxKpb~8nCHUD6wJIOjnO8&akq0zys#QLaCA`cJ3t`AlB+>;zZ*`7n)b)pX#_D0 z{v+jf43``n1i(x+r(=U%5m21PyLfPgaN@fs{5unlBAcC^8||Jg3N~0lF0XEa9LN*u z0U^Pf%>k{LW-h$TMvh?{b`&UmA(iCa3XDjqHR`97)pA&!p$WT*VChIDwxMn{ZDqDx zt(hHV%rI$P3${?IIXgRTiy4-RU44_Wl;YTa=&btlz@+zUe$rSE#xtwLDa-7bRZ>2s ziY@-M$&Dz*Z$L>6l$ePxp8#Z z5tz{cODfMD_`kXQBcE3~-WS&sU(ZP6Z+`#UXX;x(sNeIg%9!-iWL{Fp=ZF&8<3 z!Oq~)%#7+I$V-fNVta}!YV04sAJ$aJK`$DSfp!iNoNs8@}3W&q^hP3-EDmdl0+u8M)^$JNG;#6 z8x(oH=F+#Sgx>SEt`3t47QQhS;BSBQSW*PP6dpQs|6|h~*$05E$gG+=CpEqSLgc(S z;F^U9&n#Tjcj{cU;pwq`kxmuMOpM`0^}YEZ!o%k~g#SA!V?#R(!l(4PnketF%jo?@ z&DtwKABwi_t0}9OGC{WiA}$>jz^m=hz1E3(tyVoy&1KI-9cTSSJum*kCqe}`qykg^+7rxYSjxQfMRpo* zFH8WVYB)G&|Ju11hnBGa)M3*JaLKTX7-9`S1E{k~Xh9PMiP-^y+aJ&a%0eWNVJ^>d z`w@Bo{K0q%xnbhn!#qCM_ZEe@<>vmDUD1|4Rets2DT#-pv#H1oBqFWwD|ERi0AFc8 zqpLvONbuwk*$IqN;4;aFD4g@Vx7=R{JSSxa2K>kPhY|7rx-ZCG81A$@@uAu@Zy+Rj zUtr0CBJ~0Avh5Z5;y+t~W;6f++zPl1YemEcPpreHjKcB?lp=#VKm9CMH7)K@(xDLF zVK9!R85CS0y$mr8k3lj|zsT)329MbGvSI!QX7mR}L`4q!!J%lpd6@&uDDplz)M<=R zefvkn8Mh3ILT|G#f`3R4ajQ7--pv)orG1CqP!2tMivVB9zQ}c9{XhBHPc`Tph^S_* zjG_8e0YOwB;Y1RaQoPcQTv`xp@XDC!?0oGE=y_Xv%k&fMv(j^C;@@#5Q_L-qYr-HP zE}Yrk4nS#p5Rq$mFoJov3H|0ZM!a{(YtN=*OQ*~# zHFJ%}9nOVkPWd_sUnOU$v8|%!onLQk$PLG0w-Rno|LTy;px;I-Rua)luUQl z9#xpEt(oRe7XgvB?)-ptN`0Id^SLsGYWf$BZ@q#4fC?SMFIypz*&fX0nGuL;$ z=UWB_(`{ATa2PfZ3hs!O_k~-aoG^`CJxV;bjf<<$sx=&`6+USe|FK^CFV=H(^fIfgg4(9Y=fvSLz+=pZynz zP1keoAbpw2(7%1(jDo;3bVs_H24C)OY}cSEN4E1zH*Nu6{astcHNV8Y7G;H~HJ$7C zQr;)RU_#_J9kx?`mJ-Xm^e=F14GpFcK1>RGrP)cj1RuOOA2epx7G>=u8?bv_>vypV zsCecg(1S(iK*%~J8?@s*b`g_~agq=wBBAk$&&a(0 z9tE2@gT6uLKGk}iFH{cB05>jg15OU%T+_ne1QQ!8Y@*GEHX&HXdm}|fJkn}dkY~X% zO&F9D=K*Q>vgRP-hR1^l)RwA3OJSu%Iz$%5^2z>^SwAHgK_U9lX#RTTb|EZGNMU@P zp3PUZq)a8FW@fM+mMB!Sv*1amQEdv>ve``HAdDzXyxi6{&vf#OoQ~Msuq8_0c7yz)AOGR?4|pvwj<`d%AH*>)eVeYB%@)qBbrR zA^5QvdG2BTCJ{$UIwpFRreSyKaj0%j4%gOVD|*yQ46#8XM(<_zyU~r>24%)4I>VGL z`%_tA!BMg;eU$G;&4XsA<6E#O5zI}fjusd`or^Yr=!IRtFs(7D;zD@sY*w`7F?>Oe zk=gAZ#S?}}IA@PMPWKi-W9WAQQi6n9zx*^a9xzwvUjBuQ$mk^~fuuyPsX(Xye;L4s zFxU%&O^F9X=4gjzHcP#CIzz39P{+E3D8MSKaF$ zr$Hi2^|DI0lzZkTUIG1UG#ZO+LP2phFQy3dB$x+kIoD@0vpR2--Wv{!jugntU(%bSn9_$8NPe&087U+U1vglfNv)3s&+U-D+_!+I`oYj5K7iFDs&^T&L_ zk11njlDo0Scp%XL@mV>Oi!pO%Svoh!!Lc>-N2F5GfR!TBfiLQ}l`7{H|Ig5^TY*Iw$Yr)v9k+-v(4L7`#f(ZI70^UZJy z(UUhb`G|Lbc(G*50f3avk$;VXdNlSse?8)zM|qa$S^G3f4A3L_Q`JlW!|aD+K~PJf zlRF*C6tZ7#);tm7OwHeu)~7#V$BzW`kR%432mh+5C6oZ;y&A?AqJz!fMj1JGMkC;k z28CC%yp0T*4vilFxMu|W_q@MQfi6S6GqCtIyRzq{g=C`A{Pq1ewTDlzVSPV-aN8E}2d1-`%rfRB4ZSD~taY%sG3H{YFB?wwJ zbyAxg7I~p~HG1}Se3 zXXjMq`6!*pv|KSXSauPVBw?ma*2+ zUb{#>78LwyQ6jVmOGqT^q7Cr?iyWpRP%Y-;*Xq+tkc)~0wCr|3;(?t?lIqKuVRP>d zTxF;p?3b|`5+bI_KzBhrRi54d0P#lKQhYHBt*DK~PbqM7y@Fz~NgRUpX;z)jT_Clz zP*{8@JuMh*x~WO?@|oRP-*+kL_w{&b)Ia^{$>&+>Y!10I?u)fj7FB!FPE^b0Z@xA8 z(D`_f3=2f_Y!s>u)%C8qa5;vFLErrQEAA8voqfmF?7tTL zQbRhux-RdL?RV*S4Ta_(OaS%~%+^i~q1+ZvKWw)+I3!Fe-*Li|U=SN{W+G1EJ-R!= zOQ=UL3h2+X-zPS{H3=zXY6>|$e`AuDiu^Mltt=vx?$}DpYlIXJ3F7qHWzpn$;<6si z4bf8!B7h2cHFzqNI3F{T?u-eEE9uzaS{$Pmq|P5ei2Hv?aa1`l8)cAc=zAOx+)had zB6j4g9PY0-I;nWRbuEv#x0J@*|9!N-KbceQayo?`DP-@{_+yl5ge6635ciLz8|j-j zS!7r_qX52~P%1Qx64{WS0CBP>7CZRW_;oebgDo2-uVkyLzpj^ke_p zul$GQ$H*~;(jZPraUxpZntJeu!(KPGLeHALNsK(t3QdWMp0vNVtvka*?l6eb(9et) z(r6R+EVg!WC4i`PhKbZ3>m?qfVat2e$8b58;;7o4(AmurSVtK`J6X84RbVFiNS85I zQ`^0A^R<8bXfSLbWVgU%Uus`GMpGs~<072I-*I*<`Kt95OQJ*%pxlBN7+EDshwLDdzJ({D zJw!_1`StW?cvht1+k18fSQI_ghW`FvSq{tlF#U^Gen^Rv7T&NbTGZ=#&MhydPKW|qJ*U+8a&mbPik9Y`hEElM|fns&s)?MK7Nvu%pbyz9CB?o zKV4zG0$xmYq-=4D zhYn1sGLCNd0!J-U`uTqZ=v((9_Yy|5!XY&=nfp=NrNO+FOaN@AtMyS+o1NG>6ISrp z%sJzsN)Qpayz&}$Nm|Bjw3mVJ6tXSwEgRy#qNF0Zre3)GxLE|lwZC`2q~g0#K9)J| zoA_h)hRU(H*y2G#T=$@zX8Skydrg5X%#)XcmlQX!& z?OvG16q8MW<@dWAv$uJf$C-oqphDz+e<_yaayDt6s@?EmwtyS+II9m79Bx-*WemZy zVTLVlB}C>CVQ+D{45R@5Fd+{UDAIH?{p{va-t4y;N*6)uV-ihyB3cZ`C+hCfB+Zc% zLoVxFeji;=`a?Zyu4>;;%IC*JmPi59^33wKpzFY54e7NFDoXz7Z}Ec&*UtK5n?-qs zDB~75q+Hd|I(`j{}muFwmop+FIHd%D%Y#?kgpC-N4tZEf`-U~Jg)IO`PPcDP)m9y zP)o|v$=`mtQ-Vm+tyA!=qUABu$K8cTZQ0$>6!e1;z>|HcQy=|S&2dBq{-kz@DFt9Zc zHATFR0MdrzqcovuD?%Ro@kX^P{0>VYAAoAKMqsODUHwsw*l2T75PQ61-gh1KXXN?D!lB^sn zhfyRaIT+J@ve%doyD~y^6b^)7$;-1S<9_MLbU30_tCZwS9L?!1Rws_Hj#;qqy)0AM^5iAK&~2&#Y6&)}x^B4_=Vl|yke-T@Y0uUH zYlZfhsQ;NowJeIGNz~ZQ$x;AACDljEBa{zO0&`;@v(sz8u}}2&Weu+XKgX zu*JRAo5g$?L#a9T6w6$hvwXLp-*9RI_25xQFLDsf1m;P4Pa{G4D!ny$rC{qds+&8B zm(wAw{bz2o{UEx3_u8l8WoscFc%oe)olVsuge++W2~8o4eNw18#FWWLNi3=!6+{h{ z$o$}o3knIOdwg$Z#~EH3`g-c@b-OYFxj-mtsQmryGVT-dXhH)tk; zuJMgqo#F-CZF=lBXCH(E>%J*a8#ea`XP(Wgr*F)@93O)(XKX0Hg}a8n#n#f%{_%n2 zoTL{v&3(SM}?N$|*etUO6e@ERwL#c{vdxy#j z!YQoRi>Lj%;6E3C-Ub64*%1dOU>!+7yC#^6FU+p$!79o=>!`~UK9yb$>)AxG$&yEt z-?03_tFu@>0&}|@;C#?uLT*;Y)N3lcrb1RdE8jNzPu0xY5T?LI*OA61{IX1TUPz2F ze>0jP1yP>0z?bDsmHNR@#IukE&mNJe4BD08wN1< zyWnRi$IUCg?3sWChuE8x*t&c|KI6v!!7Qa=ko=NIB;P0<)LzAnmo}k_s>cZ@kGapgU{;`+-lhXEfn|1tRZeqf? z9Vc0}11Y@?itcCNJBQEHmeCP;Z&eM|i(^pqQwJOs2w3^HWvD>e{eyl$+hdWDiEVK{ z2ga$@DT`>?>FlT$Mh~)ll4Yc}`b|6O?ggY2M=e)Db%T5i)0)9@coU{nC`Ggz8GA1F z2_us)f6dh*=ROFN5$rZFOLEA#WLD)$Dq0TB$SLI(K+(kNJot2Oo5p8+9L~wh9RyC;SvbNx{Q5 z{_%-+>)g+D{RK1mm-rg$a_d9<1Eu4-4TNjGR=B0vQzkhaqWKQ2#;*YCFF z_~xzYii3mw77>$6|D`|QOIve##b5D<6oNwI=|TMpwhxr_gs<^6E&|O>9?gBq{gq*o zr<`t1YDrZ1%NoDGuX?AR2sx6I$H{RS&BBnZ*<-9(3e|RZ@4#j56*`e2If%17=J@XQ z=kfastgapD(Him%zwkYgt@iMvu(eywIb#c#Rg6(XS>@U8CQYlJk zJde>wXHAPMI2S)kSs^HLnZJ-taCos>u7Q+zw!tFvR@6i=(pnm?i$zPawn!?;XagPk z+?!z8%{i=H+F&Nws0VH;k&)JNZTTy0n`@Gp$>hi*$tVR8xc9D;VtWna%~=~?k+Pby z-NG5i+G<*R^`zJ>-zL@~NXimonf;mkQTg5#-$tlmyjE=2DebAl$lq8XNiiftacG~t zaIL8$6r$DOM}A8aDDnCD@&h5O%1%Vpv)xVG_8U4UYD<}LA!EW}8L;P@nLr!I?Uz`1 z&-4O{ls5D>tc!^03lepTba#d!3G-FYv<_Ujjdg<+w>z<2iikaB^g5rDMV*Ym!dQ=W zxs%t_(OkQ19n(20=Q-X_{ny|i;nkKrr&p-Nt0lqbJZ#$sZ>lAAztwqbhrNN@lHYNw zNng8WQ%4K!vZwq`G`ui{(rLcd_nBvIzI-~HU|Zi}S`FF5^11c8-E(p)d496m(`Z@F zz8e$GKAVY~4PiYSwvBH<>biLy+Eug8{wnrr^~j&@r*kqjRCTMn1Zg;Ds|Yaj;yo$c zf4bKlJJOh*wc6X%5pT&KJM!cmPk`moe=e*RGH*h@`@X{-nR&xqVG?q?3FKw;W2V*#?5O5O50i9ZGh-xrL9x0p07peK_8 zst7ZR?y-H&^!faE(&Oa6wSO$WGUvXX;N>y00C(L$#|jU-2%3cr&FS_M1Ct84wr=5D~wq?L`FIJ|DRcPCkPc22ibj9nzRkP;7A2Yf@JI z8sl+!zs2FcE0_DZ7c{8h?Ao_`M>?n|IC9DQ$qYEq`QCLlTKm)M#n)Wt+kKrFEyrbInGJ`)xOUv|2w1p|uv9jjKPoT@HYz5J z5@z}p@PL2(BKzVqhJLNf`;d zoM;Wk>?8W1Ka9+u{BkKfZr@Y5`L!I2k)$eeMW0A-G4}Bd*G+*u7eywqb;@K}FMFuG z4aa$;&{JR%dhE(>_|sAm2`E##R!r3TxWh4B+}ovv$D=sel>M*_iYx?ZU8zmfP8{PW zG&|ro*srFuGAnj7F^*P3Vu+f+-~9+S+@P9Il`=O)6dkLO3H{`$(L!CIx!mOv?;)y~ zh3b`Kz)}yVSP^%R690xbl^pLf)E}N{zdL0kFzE*UMhH~c@6s>Pcr5W@eDF=cmha&& zS*9*ABr(ASUegt2qs43-uarsqI?~dqetc^5kng&6x*t@(aUe)43z?nD9Dk~x>UY_j z=Nwnpw;X@SJ?U+qhbl36>>eDxpUMMlMU6)J=eTWEFf-=xhpjIJGWprA~r}6Qp`x1|c#DEaV>yh0MJd5D1xpwrXD2qs#ltmV^CM0#neBS)-W=)NSv_%A5)YqPTLkQof8jYRKctCmk%tw&!$h zbLi`otV8e&XBDyvjAl^;+1?5xqnkkt)LxooBvBh*2!lqu`WwX5H6|E!p@~7Hxf+eu z=w%Gs3VUJ^J)|vDhomkP=u<%$vLeIRP~lZ~)}2?_gPCAB zq~_AN`RX@G)Uh~bdO?zTY;F=;DLlmPo~f|Ma;IalN;$)ED0hhVz_Ju zsOUr1%lFQ>FpLdfon75K)OG6F)e3;Uc&&^VnnVWSUFVGW1G<~5OJvAc&6GTyZJyJy zg^o{W(20#WeUy1BIRCA`KgRL+?S3IpqIH|Lr9d^Tq3Q&+af!M*SaaC)w=(j~0rUi>%{h*d$2r0Gg&ZT5wsqs3A+&c3&=iS1h9X^%WYp^-gm zSgp-l8bWbb*F8fsF_LjlV2xDQJ668Gxd*n5RJ<2;{jDkZIHuqBq_qB0#>vsal!*4v zL)2+|R{i1nA7c81=v{+FRHYhqqj93!^U-%Um?E8CFzrfaikoi+a>LsEg(Q6ug8O;Z zS7?je*UU9Z!&9HWBHXGqNLb0<6i?r2=U!rmD7+HW43dQ=W_@njXNoWBo;bj0m6-jP zf=QIR8I}-o1Js)Ibds!utZ> zJa}vB%300Z9u;!=?@ml~$aQsU zPR-aSZVUW50%s}t*;AK>?R=w$^cnAX$04b9H|-p!-?deL=5LQF`tqt zMPVyhzrnxV8H`o7_?Uo(|8<3>vfmyIK<<~0Kqwdn7ARa_dJjg?V9E($XUS>{NgxR6 zKbs5-Iqg^;2^3n#m8P?8yN%fPQNJ6t6;=Z@Jg8co0bE$3w-njXr`)Bv+2JlodPS`R zuLeK74F96bEmU&x=Y7@iUOlLBY#2zb_GOcPGmu)Gci8mx>P#jRz2Ixmt`&l#y7lV8 z)rrieNf&j+rJqQCPyQj$;@hwp`lBLeYoOscyaaRGZH?a30!&g^38k*-?ODEDWC#(^YMph&IrN}@G zgMAq%|86;K41nO!evvnlhaoRkHiL=VvG+Ms?W%b{95^{{ZyR>MV;{M| z?spt%MBMt$j8-^^ze&$*p_XLE)<&|g0jZobx0Nh_sR|62wJ*`(p!eu1svH?0_<|^* zUAo<@iLeS&h4`Wc>C__HYkrGlh9?>|IGmci*h)8o&xUkP698GHzRO@NoGXIQ3Oc(c zW|HFMbAT~j(Y?PNd6Z9pmg~~*#(_hkJ$g8l_CJ>U`OFjFWBmB#7wZE7#M;P_|6wVG zFC_x%(=LcH4<@k57*lBy+#Oeqh+%f9QgH?PnDHY(z`(2oUz}Xv{x4dL$0;B{qeC<6 zzRvIFcjJy9bYO9$0zYlk9r?b{c@rLoHt(VE7y zTH^|$Zv6|J{t%4~$yuk#nCSi($$(Ny33rUC@v^`dzi&aL><0ztIxC3;%|Yd3)fI7^ zD6m{{yvNkDs3`0>G_acMNMxTi4Jh3G686iCLz)9I18iXFChQi0{LVTN|0;uY=+^FS zb{hbMY8gWz>S<~FO6z0w?($Q7S`~{5_4&EnrGAJO=Q~6dag%6+=z79>)kJnYS6mJr zHti|+buI@}8#B=lg-EuhU&3%?F|sHwL}>fMy# z4;MF3bB^D9wFP=Yoas4G|I1Eju+%JLgtjJG!&BL3Dss< zO@4M^BbfnwX{Y1`t|!3vhYF*7<{70xlqg$KwXD=oKlX@cE&r zV#mSbKkuo!A8Yh(J{_FuTUj=g?5&NvNVOF-b@p-(w;5SRtz(g%X&kZa1YCuLq9Wr6 z2K2ap-OiE!S1tUL8Y&sEQsINp26|lO8|GO34Z~2NT1&_!qI⁢hEK7XOwzD9bhfNIGW_{O`p8O3buecG^scZSMs!z0CfUbZP4g zMxeDjX?dK{A}7_YQ7|_S>M`-|5gb&^2CwN>o7FlAHy(O2=1^oabdu3bN80r(3_Xfk zcxfi2E2vyKMpz@IZ$(92V}jB{lRsQ8fIy@`D;_7F$ljRkSK6qp-#nH|i64d$lrf{_ zn>j58F}oV9DSoD}69A7*z{kpjDrn>UTQ-+nC`#LH)OU|RW9CUC?xB~t#gSz0G!+&3T&^?NPy~{nSFMcxZ zp7d*<2GUZfH~x|bV~;3h)chFpsz)L5j)%zyD3NA6C!9>N>O~ewlE_`x`o#3*J`5VK z9vpiz@aB7YSN1eV>4To&&n?B)kXFHWZwiy<$|}ZkMvd4nT4M{s@2as#lEuDO8mn=h zcrg?tmKY>^a%9-TB4<3iw7ZrgbPTqwR&jG`;V2PSbz;GoER`lkH5P2iak>h4rFJDW zrRJNlQ4{O7WzcA(hx4oK`lWbgPtIer5P|MgQ}*`jS!45d&t`RZ8-jhEDG0C5*EY_$f#;`3)wfR7kE#tXMoVZ< zr;CqGT-Efh=VN#mHGxSToEx>LU9-XbD?xd&9H$#+ogFhPvrtjwGZ%iBao5RLGGgk4 zlx`)4b#Zgg#0*OL8n_`s) z_r2PeP32OK>{X`|slC_{`LX#1Oo$o_K<)9d%VJHF?c-1Ha;UBG+wJvR4~=c=!Bud7 z0GTSwm?pbX?7QDeO!-=1pE-WsCGli+f60wA2GMJVqw>8$`hO~WiQoiEabIIVd-CAtxK7ynAA&!fi9rSy2{MFo6v(nT@T_4n zM_j>eM}!IwX8gKgu}D;f>Vhy74Lb8+D)R|R&4xBf|996Yt!)ieQEP7`amf(Uw4vx$W}#bOob7aC zK5bVOn<`huCM#y8-#rk)C5G1N$N$IETZXmOc1^>$yHng{|gd;L#`gBqJMdI&mFRHbn#( z+|j3*f&uTep&C(63*OJs>ymF9nO`HvUkbEu9$a+VLvJi9nS6T{jO4U0DeGL8%ru-=CBPGKj zLm;CUYDc{%iX+cY7d@k7<;J8*lFS#EI8R&pUF!BO-31Cly_|oYjPn236?y32KC^%9 z!^{%xZD2WYDh3~5cME&OqefVS`tYZkx=q)4zH76^yAQqb)?)!bhBV=pe|ajj3+ioq zp4|8>jvvbT4*8vTqqv4jENgt%RPBd^f|uwv^k!(aQ%BX0$O_I@<#xGv%su`?Dv&?! z!Q|HsS?Z+W?*ZF>{`D1x{J(x(iG^eC``>I^Mi_G38vQ_xJbAJZ>@*kc&WHC-ntzli(#7QUB8b?7_Y`EbuITsO=!i_%qE!zb@Q|(Y%Ef@P4cFE=oF7UwrNy zqJ}5?k98YKd*V3ev3l(^E3oYdPTFNYAGguG17ZmAuRaE4#`fFau>0jGc6mVc-O-^zjbVh20dqoTKCme4 zUgF0Q7PuO{OkD*<9s&9aw16>CsKX#BNBWk&)8KXJ5>X#LIc|XNMV@p(m(k;rfBYxH zr%kyFmCxF_qJPJyvzpZ@1l=n;)VLKr+i6o|y0US`;1DMsvU`Mcn>kG2!~hUR4xkyDQW zh*Tke`P{b`@!4b;FP;G<4UE{}N$$>0>OP9|n#)KRNx3av5Krj5R!OJY&ZP1%g`g(o zkOJ|A%z7I;tEqUuPwLJ){DoY0v~hS7zkPH*^JK~Y+U7nBWF+9|5ho#K5FmrlL*hTIn=;2f#IiE= zZui$s`|q{6s8|q8n@<-}BAJ>Ea>WSE9uQH|SVqO^VMXL+`-m6>o^lYTWR?EEXLw8fqfugO`fuMiBzafW{zN_M`^ch8a#*73{zim|V^IbdP) zF@ic%jcy8j6C;3t z>XWLOgCm4`9(9W-ij>@u>3s!+L7Ay@h7gT^%|6d?ot9)B)LdW8i4dsR`a83sZh3I- zWKpPt51f>`-H5%=U0ep!%rsT$L?%U@xbuV%uC{59+QHLU&l?9d<5CbJj9A1|C6 z#m~x>;vNwb`^AauE6(pv>1&0{Rdol`;j10rx-&^<+HaJ_$9#Az1M2VR7+XNV=2|HLuRdC9~$bh(2Q{xKGwj~$L4 zSDi3UhgU0h1qL*_QQqT!#1s*rhK4uD-njLMy=(LdN-b|UGb?UwV(RNrV^*E|c2>7N z`tpeMW(S>KgT53_6xPtVK#@zZ7H0&J2BU;Qj38feoL#=1gaFM>W?a6qsDA!Y=HWyM zWg21 z4ZMr_l7lTnj|)-)jg0wAX-UE-K{)}DA?zzZ7Afh!XRr+2qbpi%`YDe7KM;LDz_co? zOv%pNGR8*C1)<;Q2$e6{SXU9~ifI9+Q-!@m+InI;cjy_YdpLXAGA0)Nq;g~29Spnz zM$d2A!0w6?OnoQw(~`e?D6q|Vb8(iwL&S&(#PRW=|LMt-Y`g#=2C{+%r#z$cv|lW8 zZAyoU5PnIRb4+sembLQACnjcp^k8_8KLa&9lafgbh5Z&*ZEk)1AVYxBwVN2RT_Dq) zlt@9)=N_Fj^F+vxK<)*5lg6I^n0WmffqOmT5~8C8Sr!=%+MF3!i3_JKu;XMgdso)W zg^C+Dsh+R+($(+)*)A{-p)vOSJraluM6^pkc} z=mnQcUP6S5&xvG8>upcaj=WRi-#r7k->qJQ2^)}}EcPZz90~Pja6=5qr#a}EYR0$m z-;yJ`ChiXq5$?e)&X?W~lLI{YICLBTlhfH1TU*n9HC=)5swIpZ2T?Y&^oy3&LL9Bz zXZ!ijoAZY(HV=Qu_`WB){x0Qs96qzjDxE z$V85Sg4x0=X^K$b+02A4X0c*{qfZUTGGL75mqn!Vkchrx21C_f^l51DW?M=a&xJZw zpqFrB!2Xo1zX`Frgi}wN$51>O%h#nP8Ri32y2;o8Ih7uy%NtKOU9w}ET|XA)py;#z za)kfm2anyv%bg6*l&3v^XKT)^<5Twsbc~fjjFx@L*1z$u(@O=2qOQjpg;cJ8H$`xA z8$@Sn|NAe9?BafXvH67R?N#!L%9KT}dnPm0HhJbiR7Fo9K656bR6{m}`vYBeh^(d_ zfy5G*^_K50I8nbjV(ZazsPro8TamJ*$N%#JkdCJc$-;9IYf*=fzAF_o4`YJ4 zH5vh_@KESE8i}?kfGJ5AbLvI=K^SCt^MEdM|AN*Ran9i_ zq7Z@Xf5ZN;PaNoXbOvr1zjz+eeP!2rJPG56P{Yp3eao5N z>kAf)>h|LgBm$S*^!pG@?m)D&L^IgHx&|Ifr23@-jSWP>W@zh@0@6mH8Hm`L%i%cy(QsjW!>V

    qHBIZdVuD;>n^sF@!sCOX^FLo4dso+UQ9JX#L~?pTYb@^Ao(aTCm`nOhqojT`<-{;? zL|(-M2^-X<>Wl%ydK(YDHocHIIzEJeW0AOt!)xWnO z+e(Z>8BAy(?$Ej+=m--S4O;ckQIjHm6&w~1InZDRSjZwXVhzTl?h&Of(g|$$PY`we zE|GgB+K>`q1$rO(G6N8d;=`FpS$49P)|5Dh zK_`t*kB2uk1SrvOOAo-ZZ0{veKKALEVDm3TYm5~&DuY_{l$VwDzaKB2MLi}kPIdSQ zCc(Yj#n}-NjHLpz2s5(kSYvBCS3x;=5y`U1S2==;3HeweTm4`+5eyObOP`+Whou)b ziWZk)l!!a`+`71b1LqHqdD1>1WH44AXyi z;2mf*!9ack=*6TpdMhqy?piEYQHa-V!-mPMLsw^NWK;&7^kyrpSuC{kqnh)JSX^qB z;>XM131ySwBLQZ0I0Q)PnRQro!;rm2>bKOO#%vf8nn&_eSigzISep!xF_)Kc-R%D2 znvtdVoxT7Su0q9_p!)CG(MNS)foTqfc1bRSws2K0H?Lhb^P^gE*+gl1;M*eKn4k`D z#RK=3ApLu}@^IgWxr2zn?2mCizV+V+>NN0y*G+a$q6)CUH#K^qws7-)^@;i@q@kbK z(hAg3GtmIeT8WR8#&Uc*iK1-0jH5&VqI5>0R1q{1QjK9hwi@$()N@v(ar{Aaw>_ey zQp-g5_@t{pI6A5co}8O;LLtgnr>rksh~2TdOt{4)xBB7@)@7xT3{0~*Uz_ABdszK9 zLpts?Ml84W(f6pwIg6n*5ka^#*T3aB0ebo6ddpTV9$F~vI_~}zXgL+C6+0VqzrHQM z+h1K4(lgZjk>KUW-0Y?tvY2%I52#bBxP%c1IuBQ)r(3Nu3_uKs>Mr9r<-6forsbf{$efit!xW=lhUOdqD}>xkoF6hxwyb#{Ebngz@>2F zWakH~aIIss^KTSa5#8Hn`hy=-b{vuet;ylYjUd_;+mA}Xu+q!ck;+p$sH@dKEf8YO znW|=6MOxQ*)SZH-JFD)>+(J{Y`51ox7l_}Zn}Zx>6=oo@)oV+4(2KSoSk`-5s2}fFk>r4C5RyxLd-V$! z2hY&z?_>7S0&m9L{&ov?Gk}by;kI~pX$a4Pe;%nx2)tg;rP`Vd^Cf@(gr_mSM&XseWdfk@g} zULi#@R4tdVdei+HfU!dMQq zxk1e^wwUY3OVGh#^&}vQ|U`f5G)2xPw0AU9i6)3M00@NCi<5-63 zy;0z=I2c=(7$|yWe&?SM6mQG;%xsuHPT5mvX5gUts;85m~SZ)vMdgq|3zYHya68HV*ZS>7|rh=>s00Op& zQDU+K$vd~qazKvh7kR?E%bnFu6LzO&SwA3*VFd7-8F_vSz4eGKf3Zvv>txbU!I9U7#eMdw<=MViH35pl<`S4|aiv6RY{qSbh6U0R4x zVbwjCnyEqr`;<<6@3WY#^l#nv9V^Z53o#Bt(xhSe^|4|)N^Msk506h5Azm>_ z+V_y^!D|i_uv8cP$v@rKj&AKgCJL_Z+^BE~BDnGiF01JIzKnp}K7OXMG^;;KOw|{t zv;nTjaVPzOazO$lcBiZ_nqS~@V9?73A03z)45jP?zafS%>7@pko|IJsvd+YE*&vz= zVkn~S{lSNDamfItt}MrBOnUdn3~plBI*9W596$4k#~_7NMZz$<9xKx-UdODuun%M% z<5f5pR%?myk#?QYR&E^8jU8z@`J{F>)Q9duF;xXFfXT?YvH}&nn+2sHfs%@*s9&iX z>JlWlV>aDa8&0zhY1D<7180~y`!3nwkRPOzJ(^4-P6 zF$~Vzd^q#F{=d*4JhHFU_E#Rf`AXhxjMttj(skC&E~3`2J0R8-STXoj*9B(bL+J(i z9m&D|d-yKFwby7!NzvSr-nJgLuszmepSr4-Ak@RCgbRW$HZC7_e-0I+k*8-%2}OM> z15SO>y%ey{b}&vt%{X~F4z_G^g&@4nmOQJ;hVe}<)>Wl;s7r&e%q&^NM{+W0k$A9c zKR9d%_fjB#2r>Rr8n0Jo^q+6sJq$<`0oG%Zvq6E(ucR}F_}@1PECz)E1d3*1>nu!r z;Sx4#`h|up@M?uM)uCh*U4!xY;S-=-c54HQ^)@lHUbr_;!_*bcq6RICpW$@m1j2gM z5RbN^8S=MHQ%3dq;^J-$*640XtjNs=k#DJaBLR2)tI5M!SzkjQAvjhUg_Te5AnpeN z+-59xEN4DjGjv^d;iTrHSm4)0_j%Nttb^N+o$ZG4d7nkwEYO~_igOqAAUi_iv(iBX zFctE^YTtyUv~XlNu7qE5p}Wj+d-Mfx6d3x>BRe;#|=s|j)}upoWY7Ys7g)LPh8Q`e?=I{ zv^qA98#gHGFdF0@`&qS9F_I}L8z5?vOPi~(PC=tFJmL5$okI6HUE4GW4kQpI=hI&p z9#$B^sBJQ&uHmr=q8iKR5MZrnKc{0Fb43Mb4I#;V8Dpu~X+TDqB&xjWiF#!)d1#{qoYTP zO6Py5k!i<%fc(RPP+p4r#UU>c#8s6iD)aw0Z1|BCK6{gq1{m-U92OM#d^v%p$Ce(Q zp8atj+Yu=df?X*vldcknt~|$>gMCF|MnypeOMXU0ZU+3y@3iqT{P8jEG5hk=sL`D{ zyPd60tgu~qIrPm0OsFyhNi->$ucDO~K6<0f`myF9Dyw^_{;145@>qjT?a=xuj5%pyQB*+EU_284)c8BPMDZa z2;`$M;WYb9_FYAd-$N?o8%3*dkn;(gcUaByf3(YQE0Rtn*{0WR^r!*Ej<=XZ(5;Oe zYq>Ux5yFX01RB)QLduQ&5vUfKhJW+hK$iKk%)uqMWE0gLL9;}^u?_#0(e6$VI05mb zkPw6vo1E}QsmB?SDAIp%0q!hY{p{LjM5ciZ#`yBb4Mi~56kF4eZ)=SZ{eIGPmrkHn z5z!}{_&Q`Lq)T~I^H_ID0o_YRHNM(uuBq|Dj(Z-(#A=W{rY#w=-ZPvniK*T%#R-yBKZ*rS>?D*d-&=dIU*$xJvDy%vZ1TE};s<%X~mxeBm z5GYUNxdakMBqj(y=qrdE9Y1vazB(J0=^t<51m5LfIYUEsYwYqLmXZ2jI(T2e3U=}) zU&J+ILhfp$1N`8Jrx)kS;Fx|VLYP2r!J&1k15x9w!=oy@I+{u@uux2erBV79Njvkk ztpxs|6q5iBY*R(j_mlVAQ|BfKDtZEO1oF6^SX8)^`0`=>I7SYcvwiyX~~vYSYj&=bFr(uUTM8^rokGpuLj;^-V& zLCWLr^M`ojW_!xj!PsEveo9W?k=9M@55$nCO!;IQYWgt%*XMPMCP0iJe>^_pKhajp z1BCC9F|?)P5&gBY4Hk&4e|dazaQ9>M!B5^!Efh!Aj*3bQ`h#p-7fEK=frQI2L?v45 z#$do0J|Miwnc+|i)?W<#6zMq?ygUZ>Op3*q>bmPX8{c@D5zn~H#9e_)5CYf9U|ttr z2ZB7y9rUaWL)a=Prco7qn}`b(FfYDA7S&(!SiM5n+qYR`Ij^%>wK!U^a_#>-AUfj! z!)hF?^=Ah@lKmIFKcyS3F&Tn#>!5pucJB%LKxpv#C)gaIgUZe) ziTHDx^=F8*|MZU~h$+DSSBnU;0vrszNaS>zvJI^35^=_i8K2sXrn5v%VqCLAi{Tz8 z@D{(X{jN9SZuGCqBVEa$KLIUFu&dTz4;5JduT5JK#IihVV2yAfnpoAYl917+xt|A_ z31>-ndQk{n;R$c^77y#ygZ0EYKVv^PInRt+#LzL%FafdQvZ{L^N2;K^tT`#OGNqoPTY{>neGM_*OQXr$y@%FO~Iw%;m=8d_b1~{xNiU4EEP7`bm_1VpVO}X z8ORjM1ceosCq=@~?50lfV{JQP-5Tji$BcK9F+*IgRsAuG_?Qze&C>D&>xFFTJu8506?>#MT3N}ip1?& z964+93#J%_L8#ccGh3FXFLy@F8WksUKYodIc|w*Y9G-jT;8uu)qg9r6u-}oZM1|hA zA$dq3n-r8`qkHwi{+V{PeAh0;Db-AfmA|@f^ob#x@B8JaBOD6|NbN}#IWwpvmUB?9 zq5V?p>PUY1f#Z9F!ZNGUkFgx)+0FX zhM{=7bs~Y~Kwkpt@9Euy=*0DY_|4f+y3MfHXP%c2v-YR3tGdzb!4aCl*jqh?Hm}FwT z9j@byI5B_Srg-^4H!F|iK@pc375+D4av0Z*2LUY)&A>EKMIw^7219?37U>L7Q|9G* zKmtU!c$=mY%fnA-ri@NL|8HQUCWNb?P%r&q#5RP2tD6u_Xy&uY5LVSa#Jc<5^*=jQ z9tvbWG_KFcqKW(KZ#(&8YrT*PpBwE1gFzF5cSDsOuKD-Q-OAL?-QVlD$DqR(N28GJ5=u{+6w z%Zy1Y|7T{09IW$%^S$=!2}hvleK<0%IQe;awjVjT2m{6ZCzF;ZEkQ-~FKYH~nfFI( zEr!g`vZ_V!Nk|5HsP{-V)9LWwh(a-|P+cA5ZaYL)6{?A#Z#uLq<}EIpiYx!56;fD}GSUcIMn>}s$rO7v{-(PF zH%#ZVNPZFz>Ng61XL4&f&-KUPbxrR>nYAMVgJ}$+_7JjmOg^8ULHUrFj5-$!Oh8Ez zmuis6_r6apf#;&0M_Oy;n)~hhf#T;tdNC^SbyL-^pLtr`d01;M zHSEzMf!%T4`rQjy=fqx-BXT9&D)wjds1`nigCwp- zaIAmAk4xJ0xfNR^1@7MA5#%E&^-OeWW!)akHm^1cU<@4ALYpVS*f{Fd$CwN;4F`Z$qg@qb(Glm#$XHle8 zQh(-Jpk=g;Q`aQDQ?o9iz!We2I<-$E@ip)6Apj&&~h*$i9a9fg7MGP>73O-C@1$!nF+U63Q}94vwp!IMXEpB?)l>uM)>%(T<2^NoIj%U{OvDYxdA39&Lh}K3`yyDP zQRWkzsG6^}2%h+_uT+89ZQ*Pzh59TJrbM2s*q&OTamTD)a9rXMS6q>$0$-n?FJSv= zCNINhGASl4n~%S+oKl%-Zx|b>_SeY2w7S2Tn0CEkJoG!VoC?pb4O-J3pE6aRa)frh z)a394!>rp6w!xpLG18o+JfL9TuX^QTRrz&A4bK_^tc5cvH%Q+1;WTNwx7f+ z$w6VDB9VsiBso^zB+WkzDO~+2p=FOBrhl;eKIDkDXJvLB9TTFMMp>ebRD4w6jMt#< z?jHgSUiM`4#8T}Gob(CY6%x}#zq+Aq5%W!%rS3~;Sv=q_aQYa51GxiHIxzwQCjwhr zaIRyC&SBpG%z!^l3a0R#My$1u&g@M|V8Qz=t_eJ15$f6^SL}Ai**i3yjo=;X4ATX*ePTvLBnV6OdK zcN3#+>#F$I^UpY+nX{9(Nu7}2#m{`p>ca&Qv~_mopEnbDvy z9PMgcfwE&l19fi1{1t;|3D_vdSZ9xm|ddauk11}Xy$J<$4lJvnV;>-Zv zJ^IhAi12lhZb@i;?w!Ph^v^?3HMQVR#!6RPxjf|Qb92UP1D15%hhMmGr2a-e(tePR z;f)t~?N(a`g*wU- zbBt_U1Kje4NDv<#e(#A*#4B#Kl237u6^mZ(JKlHC%O@ppE^#;@3-{8c_j6& z4}(e#g6+T0!t15&8bH{$cdwzXaTtQAwGNRF^*re}g}QytBAI8@muzLrQs}bDQ;8R4 z2+f0l>Q+B$0By!9MSlI%!jY?sfH?V`_D7&j;Ri=^WO$jA}a#;W~Lo*%z+7J6`D`@O4=(BupG=fjKA^(-F32eG&uo%BtJf)LrRJ z@&21-UBqW(bq{;L;getzb-992uy?8+o+!r?G z?R_o&%y*cOLGU1HZ9kF9q^WJ)iZ13gE9wUaK5uOkyqEGmT2uJ5sccgSahELrellI* z*kVJVNPajzb9&P??Q*&u+z7IZJk31wB3B{a5&plg=CS;FPF6;AtzB>M2TlgGbAJPA zvBfqvF=pmIm;q(m|CQczl39}|HuLmKfN=IW9ITYkut^JK@2(GosjRYoaDrJbiN`Fr z^23bBqMEiR=uxxQX%`P&(g`d0n5|gZgGmo1JQ|G+Le}zR769R7I>P+n15Q6DCK+-X z6j%vQw6af8QSu3#NCoyh(z=qn07f&2BeJ0DjoWmbAnv`$etZO7Bz7806}6936bUQM z=V+cmKI?}i69$D`&Ug?Lu(p;SGZDZ?{X#qy9FMNM=-MZxs>|EgsALB;WW{v@hlaTc0Pp5(cqSaP|s~H+mh7B5!6gb{5V4=*L zcn4)+wCzd?mSrrqT%nclTP+x;*q`IT@N=ZRa+r;4A0!=Q~e+uo7`b@FH5}(y;EcshK#-u&L+_ z3WR&e?3d%K{3V`qc4s+yW8~3C-?1p7D|=xODRKKlLd^)3=ps5iIx35()AB=(&^6D^ zO|4m5_?XoysSMusYwFX}Ee*`--HHeY3?=4EUxq;K$BBeI%&Pd0yD01hdVa*fAqxB*G8 zxwxOp`0lvP-TU>)gI{nKE!FWY{I;puvVbf;ExCT*DB)w8Rej%{!qN1UvO`kUt{o3P266hb_QSIh1P=PcJA z7!W3Y+$LwDt{65Uhcx1V$ceG(J7|{Bw7JSYC4n+cMs69L?!Y&Dt-`-rftvdeth@@B zDjFa=SWw^;pEA+CfcK{g>ctt#qx9HLCGpHxqMCR*Pozc(CG@R$k7=Zg$cK1R`T_;X zB?1Q;=1(PdIK(;KaG?m*s!F*I99&wzzGU2H!FMf$K}-oLP#$86aSC@h-BC^#IWm6x zfT~c0h@AlQ4g$)-I0$aUpjuU4Svci{cLtsE`TQkGplXz@^}N6m?|c=CO{j00m2ENx zszFoeyGOm*&`muX%Qs(~b_Tr;gQjq<9}R270#hF8Mz)-wogmNHdlFedS>GjX8lGKW zsF4d%v3B_IVf(E(t||F)mk65G%_!ue`11tWQS|jMCOI{&qLm^uo5W(Xe0b|$zB5u6 zY=%yQsHCjw7dBiVuA-B^>tf^SQ&4VLuzm!*UJ7r5{&C?plz=?$&wEFhr(JkA^~*16 zI3hZQ**7Idw=+nEMH>CKC&chyur>x=yL?TQ_0;@KKf`P+)KsYkOc1|cG_jl};rg<3 zTV<=VJrby$Hb>yZUk_7m{43c!3UcB6Qe=2@?&JjXdh$?{f1#Hv^&&&g`CyRdaEO}C z_=$F>f z-WJSB1!(>N(BBs5qds_i@cwg=RbEGHF04}Bg+DA5r}4RZY^La~#O=E)D>^=3BaH_B z;97ZubL68&EcO6xv?pr0=bG1NkaEYM#;gs&sD2=p8QJi1Z+-A-hbyB3=>il2eRsjir8h#Lr^}-&E-CfosroRqm8h=n=?Zy5IJwx2b0sYA7i@8CBBgg@526{_-m$)cD+mur+>%BiFYX#QITyBI584dzeDn0OaIr~8Fa-K(gCPy zp<*q)K}auM6?{ic*4}l!AWWp7b*{Jx_7+4QPge}I_@o@-;&W3(@V z&6u8q-jMz#DJtD^F>PyejVW$7clYE`g^z44?htop@1#*uN0W*9l=6`8Fi+sJOIjeR z&k(xzp;Zz@AGp6;EA}_;mzy{Jj9Jhf7+`;E?Ds99yVDe6*0k z0tkLMv_C!>r01fDes^Cu=)j4PePc3;;$D>^P4`z*Xm21cjEB!vX zK(r|z*RVS7HR8RcgAx@X-Fz0nI)agEv+A9hxr9l+nL7fHD7Oa$M-cSqgf`Iy6XL*Z zbj37J_3RC7SRen4NUK~fyQ?PmOMqLeK2K4;A?J1w7NBf|Ci{hPCZ1egd#X9Zze`#i z6An3-USr&j4$ebxW{|)k=WmwUp0p+3kgo?=3&q_idE2^*P5FmlLe)Td4L>l5G%+j* za_3pD`P2|(?Pr9}!9}eKt5h0ZIX>BZ7(V=!Y#EsI;JN3mS{XI{-aB|mn)Qa?qo zo^Nco@YsP!2xhEk5q~sJG!`zuVNdEa+-UJsXIu==J&c2ku+|ZI+n##obw%sll(^AP zPL_gVRA6XA3z7f@P!O`Ag0$DDRAOSt6rs4=3H085t)krw?EB5j*f-u{jfUS=`{&zW zg8P8W`rXS#|0(lEywGH?ff09d=dYmGCv7Nu@=xpMU^*^#1a=q`wDyS2mqeO}@pD;` z&^mOV-c5ym+$#~+15V-NZ-5Hjn$ETHb@y$I9iHhI!s2i>i?qu_d#P%qbf3b^kJV&Q zyDKT@sGG^>#V`c;l%vIESZ7^jL`N>z%>j%lV+ZzF8`^)BMsN~Asta%Z2K^n3% zBJdz2nuHo?!xCFpD{)C*N!@wL5nr$7MmzO7e zul*R2GzLj~$d8EnlJI%Sw+=NRK=SDrx7>(Cd0+I8WU@&s15TKB5;@K(sC==K{p@9bs*QLup>IZY+-mQWR#wMD6kH7S9E>a+5Wz+t*$m3|PlIwaaCg2lPXB zOSx{oD-$*4v-+sCsxF`%RGVffQLPoB9IHaFxo7&lvQ@q#QiMQD7CAcix@f`7kifbT z4Or%Hz>ljQP4LeVn!&|);5?(>(cFQ3Wb%RgLVrXxWU@$ul@k@ zmkz_)xtJ<95px$k3)fG3lABf$fCsn>ZkWwO4badw%Es#rZ=;O?#*sc`(yoE8MhwC} zka=k{Yj9s(AiwU8F}fE22S-oW*4mNvvR*on1X!Cl%us80r>PnzBLJ5w_lI=r?vXJp zA^f;|K58VZ=W);28+vz?;$^1$#_k2yLjVoZx@Liob-6Z4G4VV}afD>5<4MIKnc*6V zr6k3hFcR%~E}~7)g5hDk_Uv^t@Xx>E#nUCelyAEBzFR-gMv1Uj3+#i3X>$`?RjxZ% zrICvpzn^Xs5$d|QMvukf0bLjAO|zgVMoT;eO{sLNC+sJ5hX*_XfjE&d8b&8EqbVGo zDGa*o8l>W&ieevPYE!#kN_dLJ&CQao?YCH^oMMV~Jc`w;wlt#&3ENu2gGN>sqe6B= zTc0V&ge-_d;*)wLLdCMl{_AGC5qre7van!*X< zeFfw)bOOcPsJdJOwhsS# z`2_LbSv~JNTMWk2q?^La4m-z-`{l~86W0`IjGkJ`P{IjQ**e6+dn(@6Km5XLb3|k5 zU=S%r3Hm0$_|uC`H)LyPvEBW5YdaB-N;ONpfpJ)Jk-Dy`R?(+2`%2uvCpY`%g%ZuK zU-~xqqpW;G^?DFyOKXs;-_48|TCw163SW|X=#)M`8Q9i?5pznU7B}SZ-aF@ITOMd7 z6i&O8t&&UD_X$@CZ_s3{cDew13^|DEFtgC_)J){FMO(j@V56Lcf9J4fuzO3Ka$VE^ zSQMt&hUufZ3J$IYT%zfF5seiGq5@y*ai86x{F1=QX0wK#y|UhP&xPf;L#Ku7j})z% z9k|$Cj9`TD1t{^f=HHtS;|#is>%gkg)_6?}dwx%3<30n`%pA5amQE&`b7%T0zi=(A z3sh6uFer9@?iZi#J{IPj&C|KP5W6r9X5d|}kW|+);R=aX1Umd_S-)Pf4#0ZI>N#I+ z{nP12eV+uuT3J=RuLeZ1H5QOyp0gF5MgEdDl`Pdf9Y?KiZL!|K7mN!o?l*lvu*=Ha zUB{u5VFTB&_y3`*!{*z!wmIXFBK(6ZIw9kH>im2=SvR29Hi$0qV=8Zz@FAR??d!5uUJ z?Ile5QN}`Euw9#oRZBhn(EsVz9)_nD3YFPZKT2|lD5wTD2aJ-Vwht1@idW-zn)hYj zL*c0AZHBRxa!^8l0b6Ju1vEeufMU_{ukOFJ-F`jeDMPB zK^>$rYUOdtBuHEKK(h*X%x$g=frrzC?8s!5v7QPS&AO!=2EYB<_!-tH1$89-$8_Kd zEmP_zY9td?WgEZ)f*ohu6;D0tO0bg1=zgoIf zw=YgpjkqokrSKXa&QaNw>})kPs#%=Fcc_iih42z)*1f4&_pno1Q_oP^=E!Ya!N+`b zwx_ch7i6V4%x%f!s#X3hU<^5O{@a@4g9Vx{@|kRzgzC{vt>B6qO^FA$zKdv&Zy(i(}=XO1TDS!bN3eSV4Yt}!$ z%~D?)LLTpIO{;E_Fy@~gng|I$7|{+zb}M0X(29U9aACv3tLs@uwdFyZVgB_n{ii*c)y^twGMw z|0BjIz=!(lkg5WuBgj3iH}_6wL#3Hf*UQndsx#Ku@FV*M8V+2c#Xw``{Hr_ZZ%;n& zxH=XOB<<(T%reT1ii#C#=a$AnM>mz*=0>8iIp^@$@)e(GX&;XL<-}OHBz}9fCYy4b zQEbaH+7m3QW_K)s2%;XMK_XeSYyj(28KLps0m5FU9wj6?o)8PBmpP*Fo#Mj_(WO+^ z>xzF-lv7T|nGz~TerY73sab~-$Hi#}pGgzi|Jcx)cdzvBKybV4BMq(zbb1E zU-W@$cSnzR@6-H^*I2OVdaWf)An*BZqw zGvfPck@iO*gae%dq1GoL%oXq@aEF2Aw)UQH8o!B^3o_UFHWBYVP7r5(`+ z(fp(q|I&&BQt(eEClby3-Q3%|W8eYf{6qST5`@UdIAkRX5?^UpB=9h3zWjhf@{SKA z&-coQCWZ|Q#ls&93-si61_LX&ySrw&m)?+1`5Zb`&c|&K%1NV*K zrq_VT45G{SvU^bvjw zR_DpAWKWbx-st5I64Zi(^}WPj=E#?Ds&&NH)I9SjW7Fj6K1_YV%W0hl>U)VDm#vdxjJZ20z6cB8i@=j!9ejIr+R^K1e92eWVZnGi z`)fMc70-z43|rc%{t?Bq6bRDTPxuEa>@k#%HnAbl8cQUECVdvkmJF)V+(F8L23j@~ zxS}^6Y-!fDp8-i#=Ob(wwqTbu((CY|hutBm&Oz{bc@^<(og(9!V68G{X?nfQJ!OV$ z*Bn4lqGgW;4Ty!frjKSOBp-8wO7E%e%tU~-h(3ehJ6^_O2J1XNt%}&^&D*%X$`!6^#XB zE^m|zd{yh<$Xd5llPhK%er&i~VKB(=S6qEnJ>RVE{g~|2g<(c-iA0|cXzG^4ct0ch z2+3V|0rPsHQwfX|{v7c4{l^sf-|LS4t>-XQ%%jYA+-EBJu#3fJN-&|%w4`Pjl6aE z3Mu+9>(xebU0`@hBbP4S*TY)k*P;yIh%vv+lTAa;7Rjm%rf)c-F+C_8r#(fg;?iNo`~)6&;FykUPp z8|o2gnWp~2=5Nku(SOhLK{PgCVnu~54eEd&OFuQDqjYs{0PivHsKrnPJ)@#KS+}i& zMYT>fR-UcE$Rmg8XdB~F+XM>%C$rRkO5DKLf4w?;*eV`0C8QS%NQqChLw-101aAis zm1p{lZj>-OHLJZNFj*LVH?}V|1Um=SAOj{-jJ;g!lQRUWUZD-;a_l}X!I)0fuXE~_ zkjnq#U*~`oTEPv(j?7W|GM(W;%l!D~o3pX1Jp!wAtNMu3EfRnu3Mu^G;;SGY22p8b zNBIH=fo;69=v-t~z(-mOJ5mAjiFc9Z!Mtt#LL*AxQK6A5@T=%MRp}sy(m7R)kUa9Q zG#5vAZ~Dj$f&mNbk3Ve`bB9k}DXp7)GR}usgVLFTQadmdLIV0ELa9-gzEhqQAWMm6 z+4cXS28w&<3tDQCcflWh>mzs}K`N`&`$jk70xkqXaHa*&h+Qs*0s%sFt3GDabNm&3789%eVmm)oC#tq*2BJY8EA4AjM zjls5R>li4X-UMy(3%ZhHnU@wN4o(z+oEU2sIb|LZ$Aub)I-Sn&8qxdE9h2(kJew3d ze5$%n8AC?!PSUG2F-gyD$TA<2(vwboWl|r+T zgwjNv0Xxn(S!B0tpN+*(NK*LA6`_U9896P(2(4;66IS~6XE=o(X5usH6B$+8j-Za5V=|^?4KCm?u_C;D52mf^97&4>q{B0pBV@_c>akgkjBGF_urvJf(@& zm8|VMoW6nY2RTJ&Rha@?t zI|e*cpK=sklrZrI<%7KK26@q;1nGCIofA*|{Vg|ryYHT7$1v)8Ok-D9vFD8JinQ^Y zKH;7l-N{5xYRSZ-_jjJF%k8nuI*qV_{X49RXPmtl7ar)un|X!I5@pKPtt(%)UuBL` zHFv7-vk0P$m7A97d>HP5$dPq2ZJJpL_2oy!+kfq7MqeCHU+U8EA`KzmeK_v&V!1eY zp_0+hK?1OPvsa3qOY$vFZ;DFk<`y!{2EN6yX=Fky@xwzlx(y^4 zp@uDvXIdw4rL8l%_JQFBI?fBgaMmz?7nL?@(AAn2R{~O*m2lGHdZA^iXz$rJLpUP- z7On$7$mF~BSX(dZ?+rzrHIdlzbF2Qc0;GaYr^y;P2Tt?(PfW%UsH3`w;wqeV2>|l* z=DlwwV#%Zb5W)aSCx1~MdN+;(G4dWpF4oB&a(~_THp7;e#QKdh+JH}UCD=EeK=A%h zMXj-_!rMLU{+=%FWX~)$w!fG=QwUFoAwo{2o|<4W27#mh?*-^3*GIRcVE+U&`e`a8 zrDsA@<;`+m5ZU9+L=Vg<-sTrtoP8l@KTkRp$D_STN3wBhX{#c=w`KbTkhbE6215tm zt~`t*mHx!iaqvLd@nTWEVx7_Xv+I4vTAwzRjucPhk-QP$1l8dv60d`NE=Hfy53|T_ zq;1Y&d4MV|^+SXq<7~?+9jM#&ubBL=QIjwV$8m0Bu{>oeJ^LePtJ+m^zlSuv+b`vo zSOw`2CkgBB?q#6NdK<@kQb(dU_6|ezaR+W}CKBb-^1SaSj*oCH+Twz`r_bKp`56wE z?~y7=)5m_&N1*eR*6oludNVMR@wzpXPKWE(0dpFfBcNY$s+>!DQwRH`9cC~*Btpy%;=<3X9NMWemV*1fqERj%IDI;`YM z;NEiKsf|${49**QrwV$M5DJLo z%&||#i(OF`9!;G#KbOK8Wjo9nsFDb18pqpL$l9?XG%`v?V5g|>aqjSl4#1>R*hs8~o6_>RquN5z16+--IB(Fs;flTM2 zC$G6LVrAvE<@Y?zfA_t2%SzP)K7KxB%-XFiDF68568+=_fX*K+v^lo}#sasC(P`#d zd$tfpqrQ8!IFl6pG=v}0jVEF_p<0wde!4jo%(HJa<#BSys?S?#VCLh%*2rb7qrh!U z6_k@MzTl-vU4`T%aGerKK2^VA5*f+JH>E+kX*yW_m~yQ2-}Af78XWNG39?R%4EJ=8 zw48Tn!taCIK7JXJ2-!eZeRU1YG8Fm$>N3pQLp1BYrulF?+Fk#j*vP&eAB-7^bzR8= zvicXne&P!4ngzGw;I;H(Tt!`Gn#aC>e4%-?KK;n3DzH_(`{Vl7stUJj0bE8eraHms z)H#wTOz7Bl&3fWS&Q^$5u*FT3sq>v{#3<>F{l{8y*m8J1zImspNN&Bxh?n)*k1xxf z9WO?fX#exuth_ZuH}^#i!H!QuZQjwJyZh7TzR_R-xco6v%I7^a7@P3;-&B%W7KVNM zzHgFStjjcfgL}jA7cVB7`AH?xzrpQP8yl2yx70ds`R$vh@LVjv#g zue1cw`3{6#Ys&2Dw50123Y_x1c#_<7z3LzT9aNt^?17s&pwYrWR zri1fH+^bk8V#7Ud&N-p(ee~o~r2c0s9!Ne>vV_|+di1GjK?pKgiuA<{O%qS<3syY+ zpP9hWZnQr`HVZ&DSH#M9&apVl#@HK9Du|zROkgWa>pA5eI~2M2z)LRg&h1I7loZj0i(Hf#@qaT88_1|1PfPjWJxwc zFh+EQ)1(XMI=(NN{m}>G{2iC<6(F(|9Xs+91?F66*o~RUn0(;OO{~t6te)tDc z?Y^k=;{XIc_^!#$JneCNnnDbSAl2GOw<6h z#zU_wLO+oXEqV)|R6>%sw3IkB)PiDLMT(^0x{N@?8X4xT6&l4$%GH}q)SD+EefTbB z{gUlE10sEqVpP^Nk+cfGKGEgRp;X{~9$~_#TC+s2gO_ztkC(4WE%h2<*QXQ?Pm|a_ zU{V-Ga%V$ZJzqw6KJ}~!-Qu4L#$ioT$+ddbTY)$Fq!8Fjg8VCBp{4!YNAP~av z*e#oM_B53$jRbOloBzNXjzDtv9g%>zk2wzzPCm5EdJT^LgV^~yagFJQdt@?EL#b1O zy1db5z^7{{O7t(PR~%p#E1o32O_ z5Gcpxpmn}>D$!{EwCcwrQ`x7d#y?tcf)9$4aNiNW%3J=?@0vUmw{XgdyZ5`%+ zE~;(v!(CKVV3#IvW9>|*kan~LHd@yH>6&5u%qPU56mk=fa!Wz7Td(EPKq_!5%3=_4 z&2rm?2IWKCRv|n(h&$Q8Vx0c_wQA)_4gk@mj!O-8CqoVWC;ahaepI%HUU zg_R;3b)RC~45w!BCf*i5G%&h4cem4;`zYXCuie^+{GilQwu}?eMHB7)J1T}t!#V-M zLAt-<1Hd=nh=bx`?MyUDpLX)WNcF){wFA;3jl?JJRC`Omj2y%wWS-i9l;xRtZ%LJp zd%1ip=X>uKFqx70}~Q82J~V*Ar3)3(nl*_ME}v5FkM7Fys}*w;OeR{FW)^8ftg>JV)q*Gw4cd1WWL zg)k;MyB!$)&Y$$7MM??B=(JE9@ikiicyK!)%8?kGRFn;BijAEQ>ERS`T!d#apz;22 zCA>`-He}D-^=29!nG4+!JlL5N3aUZ-6~T(*jC25aMcm?V+X7Fv8jbZ%BYsRGyt=WjdYCmhXPNHrV;0XkMudDF*iz3=5}FHIxUq>c4za%Dm%V{;0=b zAr_)4p6J2OkrR3+no%lu;gF|GCcAsC!GJrCx7I*!zrYvQqF4Ue(Xmm2XmOR)(IJfv z(lU1C%-KcH?=Lz)j6X75R~&gCQDVM-pjzQmZIiDlV-0b z2A9J)h7ddUk3E@#H7Am0v?b7&#w3X6lWgO+g$ik57Hjfm#J5i|I8 zXQz#{S6o#qoGT@b5D$czO9Q*NBoRUwkkApcK$qLwGB>_bgB3o6^{tq zH&$_$49`*#hibPv6{g0p625!Ls@3(CFO;AYvlXs!uY zor+XkZ&~w9`BTC?9bSe+N0n7mB@P6#mJaU8({o!`<}jbxQcB%o|IW)$?K9}R!Vnux zn*M}jNPtH@@Q|+WaG&=t)`GoeKR-#|G{kXpxqHX)ED!Z|TS<1YxMy6)qK@l2)f<=h z4k7uamO#c=m=5$GAYqZ&JHdBs7rgFNIq*%4^5>>hOtSnW_H^r^qhqbIG$>4uX0?}; zp>Q>}KK)a1;Z_}cswO{_d}HhNXN9p;HGKnr1gd-12}y+{#)6Am&H^Y!SBm>A*dp6* zmCk)y=;5KmFj`J|v&8Lx$cOwH z!BuTl03>rZo_iRXPk5O9xA?^RF7t3`fH|-8aL(qCG-$@TWC=%M^U%k4P~V4!H1>Zc z2N;fNdEvJ$5^dRG(Z6>%Z9AqgWQWFv$OcS&`wKIY97?xbf3g1`*K^ANR56HfwIw_uhhL=Nf(B|Xdk7;E<+dc9Nqt3< zExHzMWTVNCwO3Iz;ya|SeEk^Cy;Nb#v{bYD^&X;xX}8~|YyaM-$P;I>`1>e|L(*u@ zEHn-Y`4;z<3j<^`!m}BPbgl)5Chx~+gGe`j*?Pdn{7apD{wL@N|A$e^IxWEamzc43 z&45WE-Y=Miunev128R6Y=}I#~SD2q*9N=I1?SH5ljY|au2`DCMNKgOHgmJzK9P?{o z{uU%U zon7kibm(9ac}w&cyluBFsa{vbxywpr2B>5&=TY_`4kRr2uhbVzEw0mB22QeJ{T5kb z8!quvW56Z!P3$hYD|2gqBSNunH2FI)??duS@!iVOo6n!dI^6@;Yl7g|Xe)i54CX|b zLqtYgqhcP_JLVihFoY@-?{BXk3v8?#8_hUtnmmF3K)7u(j#3N7d&l)as>Dxqj1tgA zj*IhQF1Vaqu!`A2WiHx5Her!jdP<_XHqU#fKLbBx_RMe0f1+y4*>ALdG6nNV2mg~&2zj6&UQxkiV z!7(k_iNHdDJ|RC2(tXZB~*n}Ah9lE;w3>hGXYl&E>0++ez>hqi{_ z=x$h6tjn|=bwm879+^jJph}Vg^$j}tO?oU-41E-D5ey9a-phocsAiNL=jB$=Nml4l z84GL8yMxT@^ig;J@~)5EOqUkrKo`G?y@D|Etq*D&i-Mex=dSJKsp}Q!3V$>8hwMLM zq=ciYcyuDOA(6zZfvEq6;R}k`p3X5@pVpOhio0P9)_1&CKtNwUtZG@7XEZr$QMB0K zGNFXX9d}o9o90JP3vS*w)y(=y(s&{7c|QtPksbl^{utW^*&x&+{ZBN%_6+fw$VVr* zWqZWrK+Omelbei1lXyR>`W~t&WnX4R6Q}?k6_)qS7=GBFe*&CEF(wB zxYzNy{0u{BsZkjKc_3^M8=}wx6lIeT@!oY4gULF(mgmgY6CVUV^-J=k(WYhBv!R}V zgLAD!FLtcG1I=bojL@SwSvTwC449zGQ3516;n$Q=lN`Io`#xPOn;9(Hrfd~Tfs2=v z`=7nyRke(JjTDatIftL{2m^0dRvGo+NaYafwuk3y{&1VglJKID@tRA{Fq;eI#bQj! z|3WSh2wDz>ZsB0dIgnFW*|YxeFO|8!KWz=d-fHV*5Zli9o0^g7i&Qr8AeRh4S0+2QSInkIeS(4TU9>>Mi0LOW4_& zKhLP;QI94NRL}9=i{bUj#SiIP5+~PFg2d&#Jca^(W>_kj=A#Q|P7i35C*aU6 zCs&}3AaXRD>!Q73&0PL?KG8^$1N+V;pvZ-dJ@BCf>>`>P+8XTCO6zoTWP#Tp0g19<&yYbPrvElL>{!))t>!D|~_ok_Y~rC1lCW0Obs+r-GZbh^*6mRNM*c z6+&=T?^V5?Tx%LQ1=xbM0*Bo@%ca&25zOXa@XC?-syLKV_Nr|F*TNX-&cB zoxrBck3&j|*QZ3jrVKD2BbI!@o816;jVH}u@~XHc_sARP?a8zzuhRw09cLd06U*bs z$YuKa83IZXr~z!+?7XGI$Ky;SVOu@IcOziz zhJpxPKKUCcv^_wmC=#Gly9GQHXG%UMkwybYKmVE)WM;Zm(ZOOE4Su= z&h=#HgH$vhhb5{_2`*_LB4{P@*K9$TjvV)IuK82Uec3qLcsI8S43^RfEzt;+#?w-< zla_ZzKY6xKFVOmb zpXj)k@@C)*AeRe_&6Q8OR)5C3tvR*ejq~K?HEy($x#oKo+)pRHq?`#Q8N#Zvo%;Im z-s&v2#EQZ3{=g{$Ur8U@e#{(u?F*D=hUE(XUJmkG_rt4{N5utaS6mF@OK?bHl9{%uW9Y&Jt9A`9U|Wmo^u}-vsEi@MKG!H#j47Q zK#73xC45xjo?Mw<4I95kBgZ+bDAzq?E_cT>#}P#)KKT;FxYv#QqpgOVD@*UzF~j^9 z`o5;vQt3=hMkDi%J490NS}YGz;qESZ60;wu>*2vrA^epw)%8591J%M~cYJ#CsQAE_ zZua;`#o*D%5n&VQ&Lhh#@K)?LWm=VH3V$K*AJOM#WW@VYq-F*rObpbMiFYLT?Iaq( z49M`Br?xg2pY0K608hs6o@xQl)-Ol*7@Q9QQ%Ok{YY(n@j|NQUaX|a-`o*DeWP1X) zcvfYsk)R@C*&s$b2+4oeU}o7RkLx`%qSjX4j}@8N#z;B&!4C9BrdpshkPKa(2VBJ) z*yPKuPbjKS-iXW8EQ2w!wKjNqP&CX`hs>O5s#jC0S;{FU)osE4R>KH9g6d<8G=4HD zS)Kf@lx=Ut&!9^z1{7^J$=7&8VuX4`nK(MG(EMc~q6Z>RIT_}r0cMa9UWn5}ZeuKS zd}PfR8)s3}Vb!r7(d#D}(hEuK*JC*$M*7I_N&sbYSsua_!pc1SnIhOVe{ioS96)e7 z%-Ix%PF|I)BYPCOvUSTsLoUwW^=wT(Vs9vD}O!e8gk_u=?p$ajX0k+S)VhDW6R;c(9-|*@gG*b<`q9r-bkZ) z%g@n|_fCFp^=nH?t!HYl(xjElLwfPP&|JN_QfltTI+D54G@s@2g-O3VB6t4@Nr%JU zILM9cts$c)RLt}6L$B>fE&RW%()G8o({tlPcT(8z`+ZzK>F1f;k2Pey=uy|q_vrax zcYC;CfBwdB#cCzG8#fut*Wy&~sb^PSlBOpNZE|g06;7Yc4*fec$EaFcAR_7JhdMLj z6b(ma$k4&{g8RYBW4Jge5I&(Z7RuPFfON(Lu+hibiM<+TGGDva9%=`4hTD{6k{gG^Huql;HFh0Iciu2j<#bY1RatY= z(55b2TRrkb@^#q@V9J=H_HEonkf6--Ka+I~aeBAm)`Z))>Qk`9BECjQ73^h$f%idT z0lrq2J1W15B!mI9TSakI_Bm~fH?u%();|}LomM_gI>AewqXt8GIZ^f~aw(#WzYiatC>Lk|2o%3j%{6S^~P9(C-6}*(7^i zKSg9!C}ic#6oZU_Lej01n181UV$Ko5MCf)ShE}K>pL#O}K-X9?>110T;69N3b4uG1IDp~dqHU_@Yr~qYEvkG&_17B);N`G4 zrwi^?SoF7>k;4(0=M(kbnr@cVCFoN^okqKMRsMGu2 z7>4g1N=HONjXsmt_6c`WApASNcK2~d%N{FLe`>AuX{b<;Dm!~dm-rM*4|lj(*=h*e z@TI|LaDdS1JGo+xz5;q}qjb^Xp^UqI&tiZILDxy_uL-pT>{^jZmQuEP$;^QRW;4%P zRbMr(1y0q0D*w=>!tE-GyegN?icn*3^TmD)X1W@K^#had#E-M2m6MH%SAx6gxvb6t zgbfBhU<0{hyGVVy7WjCY2Nbs{*I<*lAtc1ltNW42NU|4Y-Bi#ou&>z9IkMz;Y??TtEFCqPVT<5~d(r7%+ zx29X+*FOxGmq33&+AzjO~y{-yHA=efRe1n`DsRx$isGY0r=KmbDkj*KvlY=jrd= zjHkUEJB^?3h_|Gbz>w=S9!IjjW=)>?H3?7X+n(HF!pS%KW#$so2i+ZGK+5DcPUpAC z`07?lPOt2=hL%h13!7i7dQYvubj_itJbrH%=Dyza4%oeO7*li8ZC@>vJo(#MzRk&d z@M`~cy2H<)l82vVV~Hh$xmqd*p^D4AecPa4{3@}Zm7pj-3-lcT;51XxFt<`i?T&hM zAfKAWzl;;XaU`Zv2ZvyM5|pyr*Dr3LNKz?5#58Yd!rcKEBp6Ww@J8Jz!@`<=SQ`aM~BsPxg0y;#Xz&}53X;jY?uph*a&q_K>*+9JTLtOCM`#w}EXJwhr|d|_<9jvPI!oX{L~jgd z#MCWkv_rNUts@asbq_OWkjrqjYqh0$QFTm^gyc7P7jqSZnQBJ3u76vH#n)@7!qkX? z5gv{3VQ#jn@Zz}iAXBY?ZlZ}VnHfl-?8D0rcu<}55HIUu*SlHV`0_zmwdFV&ISs|5 zj7xi6wQh*olTFtFgk*w=*bft3MhPSP5C}HqjM(>HB%5xU=3Y2j^&F>YRu%l)-Tx1( z3(XZUN_o+hw$|vrQu^n_1u1P|n3ybdr!QAc{bYyTq-wuxv?RAl$ztH{>aYza5TW{+_@r7{fFIS+fYy3kV_pZ@4ixAY$- zY=49hH?!cH+NXfo2x z(%>u>H>z)UEZyW;>qPXnGKJYfcdMr-%=3lRdYX4mhOy@FeX$PakI8waB@CLn#iia& zj4Fylg_EVCk+o{1y|k7Ui;bH84qCF-*$)Bc;>~wf@`!OHSa)mH8(Lv$U|#n_LS+Pyml~By!QldTwf>H6ka*(ez(Oh0I>bi& zbT}%!ZKe(=g=Y2j+-ScoM|w(k7{qha7W3SM!^3)SAKs>uAL~wnb`VhV_+gtYH}#sP z{N*d|tt2aEaHSg@xghZQcVKXP3@zE=5}D#?-?jx^;|#W@qc9-l=GdyX2e z`a6(9D#{>-Q^9QWn;A_R4(nu(J#b<~3`AadnhbIhka5s>8$j=q29x5!T`l-f$n=wB z3w}BAzAjcMaLny;7Mn(Km)gKLSI2aF9Ec$$rG*u4?4wVfYO6$MRg_dkP?5RT^KfYW z#O+KtxxK=<5(EMmC7Ceu?Chb5B}7Gn$>!Y@o0WBEXDyg3IYhD6=T&>@1$vf-#@8^W} zzBjPkMSxYh_U6U&bI@Co;k`TE*NOL*@;}YCS`R*KA&Rv4+x+Zgs1%HC;?VNh83r}Q zTA+FtV&s>aVok;$G&HI_AboE$J8qxQ|e$5K_L)Jl3(v1xL)crd-hd75W9`){a zQ@oC=wO9g!vKWB~PugH*k)<_++wNS)R}WjYGhXixyI&VQuHIQ|Y`Xpja&`0{jyI6M zab6G4s{I|b-m+GXtJR04U>$RG50v;%fGctTIeLJ%J}%r&v;X}1f3R3lhV*M?$_4D$DoQ(y%mEP2HJ ztnsq36xG=}2KMl+ojJ8LTrJsJo?FF9cU}88h~HV989Sg1KK%LhA@6s7Xdoew>qwxe z7jc6qbcn`7x)zD)YkI*NI8d_Q_p3ifULS)sO89DF#u_mVfN->-$AT+{iAnOy1hJOf zTaHKJOh=S8MjzRr5tE|V-FG>TF72?yi(|kCA@(F9`ZeG8wNhOg{c6{kVMB9%To0w6 z9@xWZS26wO)88A`ySfL_-ApB%z}6JxiD{$c2ion4GwAMWafc8`=*%X-pvz1* zh^vpxWX26wVifLWhWbD;A&`RH(yqr@+POo2d=1S2-GI{^p)LpKY@M~fwJ4OcIY~tI z<3dQ4Mk0X-!qrNQVE-w`CPEjvpa6Vg51RjnaM|1h4L7h%tgT$2;|*qvbk$CK@4GAn4V7R9kU#zBRroIRmYcTBPe++@EQJe1 zBcfUeP8@g-wh49LAb?R|%qOIhX%TaNBKnkA3F#QA8$ubh2!ShZVZ(OAm|@WBCW zHh- z#a6&&yHX}5EdPzcJl?x z9?ity*J_vcH;Xz~Wf4w$UR1w9ihEDt2lSV@lu9vJCSqg4`AUbXw)ZqY&!#F@$Fm4N z<=V5#>w~1z*B%ep|MuxUp;jG>W}&I!Mgo43-A9E<<;+grQ;r$fEQk_vtTpcCuj<&xxdy2ENMoWS5|qdWT5h|SfPcg|#_&}{3$oSpLD zlYSnVJS}(^wP~~$$YP0JSE~8`mCBTtx9sd)|6O6OPY>wInf6Qc?`tX%8=@ac%6O zqSCPaA~BcMNSi2U28hP|OP+NO6e${3aBMnK6<@F84tEE)09rWf`gkIzDmz$;Kl|Tp z3>v(I@5Oq1zgAGZ{Z9H=-pLMD-fVUc-KhT$H%@3ETs^Ad*MxfFT-Jkn ze4Z8Fl6ef01_+VUQ8{XZ!lk(MMURFggs>QP|LO}Y&&4+RVG>SK8igM=_o?bewRa_P zTUZZlQrD;@9Qb zVFznP>ze^n*D+z`})dk%}ZNX|9XU5nRrQCQ{M!DvTpOzk1{u`>MBlS&mG;W~GH3v>XQ{El27{$1}npdF}z=fgau2sic9C-#pF z0fw7ZNuY)6ii%{nLYi!5>@6+5MyCy1WrlV}-PJ8wGu5-*vOl{`kJV-&7Kbrdr5puhAe4rGZ-mg-F%$2rn6bt=jJ$uQWQ0E;=^B!@JBpF+TS@3gdepgS|{;d{)GXdA<;V6Tq=M-0bb=F zc8BYu-|M3#7a(L`jnhNw2V&KD@FT8_XhRWf9DXL)LfVCG%w|4cuL$3UDJf%+nq0IC zAFNWi6AKMFF1C!49t=_S<9Gn`ZVd-~ZgQOK6kNoH>=k~V2TTnmhcHeKAP7n)jtaYx zDO*=AeRC2pFT?xM03)p%Yq6Kcb&FKb=`xS)O4{wJnC&aOdaRc`bbn~`4*F0oTFPMe z6BkaJu}g(tdn3=+FH$2;zD}ClQ#x-yKEqYGZZ&1Kn%Sw3& zFr(z6b~oi%?3V_aYB7gH;Gwn<2tfzZDa&^Adu?JrBk5;Re(A720mKy}d)4kR^BHwT zP6c|N(BvRa^gM=Xjn2)f!Z}=<#oxR3bAg_1wj4?(xn%Fr77MSI;1mA(|2mvf&rIDvV#Nc>KQPUd%ttG2~=z9V7R;emXC zOxTuPbzd(v9mhX_dGApADws2$31eS6HF#5*4I%AQh94#FBIcc+YOfIT^&RwxmO#Zi z-q*zbbC7E+wY!p>5($|3t`Z|j)PZXUq1cs-xc+mOC@Oe6<8DOBDMn40sfpp^>3{5O zYyaAwPrADSXT9E)d1ye?S`yh;%TdSI!2P`3g0G85jr<)~9zGyq^xaOBEzfv~_i$Eo zkw*iwmS$WGKfI`4EM0|8@UQK8<&WMK5t|chFpMBUksFOLtfP}d)ZXzBn?C^z1xD*6 zch|xm!G0OXNi()jky)$S9_9Y(Xi2xmd)yTSS zgISZqTICJMTOY~sTcK@^qrM_f-yvhR#g4{bzH#G2oY^PFexFEU*K)trVR`4$2jazo zSl|bAzuOF3y?#OU@Z$UYY1W=lz7TC}DK&q(Fv|?T5`iI?B*U{Ukd>i|lv<)gE{HK( zdbUA2fEM@X@X($&hNOh-6K1w%U%fxmU%9GMKpBw?eG$24kk==pLP1*kH!*|br+3~h zC=7u1HnC3(ch^%Q=q%_~xD~$g#W6GH+Q`bW34k+{Qf8lUnj+pFBg6)Iu>~Rku7a(? zAI>YypaW=YcxvIYYDKTEs^0T@pZ_xD@S%#y!IjpgYAoszP9P&X9%Hl&PB`8Wi4~1b z7rM>+Cp_?ooHAItK(U3hh(g`H80{#1f~wettEdS+Bh@^Mq)jXAo2D|I56FRUhEwhFIR&(8!ZoCW>DC(J^(Wi_zSEE)+e%FbHq-Pq8 zb3Km6^Q*l3AK~?bv;o+ePgSD%%Rb%YLYbc0cDEZH88q6|HM~%kZSDcj?M`m2jKfXI zJkDH>v4ORRBg=B=JG_s*r^2rWMV3yRMX6J+@xaDsc<1M%&MHul3q`YSFS1)>7xq)# zP-Sqa)%xnZdf+NJU&cWG>4NNvY1ba@ z^N-rvXJPE_jG@I0rWY}wz$dCTjgVgDp{;Lk!mo?5A|&j&Q6vm%11zDpqy)xO(o&5^ z{Tb08kiVAf>ZV)&*!JcqM>2RXC;$pn7_p~^Eo*41Gwrp^P~rzmP5gxI>vHYFsZ&tx zz;vQ3Wiwd1qTv|b)=+Ux)qzZrOszi@-o@JE#~6RL8b)1%vU_&+q6DnYQuO^9^)$`s z&nz2w8$`^U?~7gNeHqku)ip7)014|i^;DiEa0s=6RKCb zD*>yweaO9+4QOrQx2SxBV{0R<_0VS*978< z7LZH8F0LeXwpRH2`8U&-3@I#$XR^}|jmY>1zYd*&=JM;t^hz)AJv^AMH_zPZ%U;=9 z#XepL&Roy~^3!ul6|Y=&a$|vw>iuV$QJkf-uBpF1^=os#R|+S;+NPEmFpp{;w8KN2 z!|JWzyuZX)<+!-q2Z(n4X`O8mX>U97jsw;vddHzZa#uoG@{xN&ugOKXRPcLl$G%=I ztH%Zp6F-mdwYM?wyP)p8=t-0DL9f*(K8bEx`8)Tx&#HV`dt`kq(hXGD{hvNT3zize zypSTh8tFDKBJ-XVl8h~YosqmJ0Rslt)M$Zm@8oc(bDuf!BXtk;Xh6HA|5s3~ne%$t zMVD(ybUrm;X-k|~L=>JZp^fp{|NMWfYGoXIZsuy2>Qd%1kNus$Z?`hpKm7kmoVS(A zuM4w6YLNTV^E)DQ4htuuTY2Er`3FZGpQ#U_DOS^#7;PCm%<;qPGf8yFc5W=`8m7C< zNBr8R7ldw2YrFq4K{}Q-Chr!m!^o)9R{%LKle^2e3_FdY@+d;NAg#o1s&Hc25H2B$ z{hZk$NmADIGJY8jse@y|h17Ip+6H1pEO!c6Y45&ds`#>!hAUPH9bXJjEUqRQ>w7ng z(O8?{?KahNO@uh&mmLK;=0!~z74086o zGo#a)CnCEiLdLGbQ`}o+Q9q}S22*BTOKpP=y&V?d0-K1r@)f+@Xf4I}WiA&E=Cvyx zy0qvc8=Ic_>wSyDl|r26d0X4bvoZ(-K$c97zmLks_=BD7821c)MXQ$;=(SE z3ObmV>L2im4SV`z*S{>7nt_CN!1PnYLq=lX-C@>bh!iPZovIM$l!OZe0dc5tq2H!k zP3ZkX9I2l_IY8A|8oFCyjGIh%hpFZFr#s7Z__wA_FrRX(N5}s_9tRXYX5pEUFyKM* z*KLqzfEG2@D}fM&u^(sTv_*lDB6^wnN479AxwCJKtJpjU;lQUrRxi(o<4*^3%{ATs zdm-4Ho1#`5w2cvZdfY?*toqk{y%pOqF?%^sMu!|Z{GXEaa%ffCRG>Y;Kyt-7{>euc>FADlOeVPmT2mc1?*Y1LTWDk=tIUCRCg7O)?oz!4H z)IV>^z>uSd?=ga(XL}?kTA)RpDXi1cw0>>=_paTzSU1}BQrPqJKhHzt*NO6FC-j^D z3Hcsrb}(SRr~cv?5lHr@e0B@vN6sJ0jpJ9`(6GlBn>>OP`rSBqb3~j+*Zy^&pqAN? z8+fu9+{!?u8V8&3e{W6Ov!JEc(EI;WHD9-PX^lA(QEOXo;jGwt1)S9QOD{VDyfvFq4W*Lwh1r%9Jx*eLaBGfVFNdU<= z=Yaix-v9D$^w|u$=7tx)7Yen;2s|@g9q^$=z{1AE>pTpJ7Ju4o{C-9~lmOJAD8-B* zzz@&0maF&f{K8ZVIFjWrGGm zC9-l)LD3w*+-tHeN9wU=Z8Jbo{Aceiu33HtK?qF*3TpVyTPz^Um^niM0M4_>4;gQAz_FG z5!{qW2h3U}5EIa{wX@dn=znACxe6M@-@b7apK4H#(D=$Jq@gKC?H|S|VG~wfDh`n1 zbJ?q!++TRg3cIP>YL-86tYC6*O-NQzmh?c3QA*WA#tC{$ecjhYCKN)o<`@WQ2*k%L z{LoKO`2Hwnm>n7=56`F*u?o9`}T~r?ob3SV>zPZn@)=kq=|EQD69rAJ$ zKHOoytnl`l)ZBCcq-HhXysVs=9HlAxahTxrc{fPNbG%3e^4gAH?e~L0pHzc&nDw`= zAAS{GAM9MPwVabQ+rKyVzE3I6x#EOS6W&f;J*OmJuD6^?v^josoqG2qZq0c)aJmT$ z;PTHf%cKA9+mYQvX~c}>LP$>Va?1rPqsAp-IrG9Q38D|t0}Vrn6SAVX(cjllhMy=w z3g2F=biKZ39KlQ2(7&tDv2cjj@waS0UnHe-7r4TK2#l=GTz!rOD0ytuUh8{h(HNUX z*z{-X5?pt}+(9VWKeO&pljk}RdI#-K-_!2dtu5Ew`bS?v&(x7pQ=8$>AYs?;u0=FIwY9-K*N7^d=fno<%Q3)gvvmC2GF1Ir)AOqDf!j{Zjlz1s`nZ@$A68?e4& zNKjU3zGLGw<7~eg#+7-Bl>9|3Gj{PxglaSSu8nqe{dTwW0(O<@>|2CdN(O$)jMC@ z5$?W(GNKNTau9UKq+UldFOU8LV3Z33V^l+E(2IZ6!)n{XznhzOXg#X1g^BSOE1P^Q=B;9=NZ_) zv96Xy&=OU?(GlC#i>rG+Jgp)&Kpk{_^-b5Rp;YX!imz&2rNCII7LcnPy@{QseP2L* zAVUmZ954Gk4gR>>8w-YlnF@GWaqTq#-27x(8md@-+>}zTHGApRnEyh=Q=npT7%J0h z`eTmTBpH;@y8NMBnmMto{{YKF^~BnMcMi8a{vl=(l5L1GHByF0YX=*|IqefGZb5!c z2qoOkf&&q&|3L;}VSj%@Fd?3cy^|nL%-hi%q(+u$c|R|SkCT9jDR5F2u9OCv|)3zbfC`f^?R=SObt4o7q?nsNTs!yR?d3aAn5T%N{c zadx29T7d{p$sy7_{Npt`hFZ!hN zS%ip2nRG6hp9AiF^;bBgEI9BQ6e`|M9{DNjs`=G|D`$8=j|HnG9)s{$QzPGTYua0L z=ki-n2Jd0i10{>3p@?L`5Bnb(9&N!WWBPR}5cs!#tTd8iO=Ws4&O(#qPPry+&lH?E z*F$2PuK?_A^=u4T*OWtoF%QeXK(YutoP(zr9Ws~9hXuWD2@yp zWhus%59W)01PaHP`0oFiO_ZN^`KdjuF&1Bvueg*KA`(%epFc)LC2rOKEv=O-DrL-6 zp=S^+0Y}Ol2n`}42RCQmeW#el#J73UEuxng8;00GY#1473SZcCXKQ=7{p}6jAol)@ zprOOM_;QvR77l0&DS|%y%3DxWcrlbI4~_O}X58aoi3tor_A;6K9}6G@HQI=jDx+3S z0iy0;wy~rf5M0N-8UMp!awlo0AjZ;%;h;Ho>tGvrU6B{D1d1Xr0!$(@e`G9cMlsvS zC`btKRWWiYW7tegygsBGy_-7OSjEu-rBfGBYkUz;PHzeP_2!K@?|_-IQrLOjXh9$P zM+&b9nlrNV?G2ml2`gsB6`o1pt-;`k-}F%LciYh3h$~!n#?BgkMGh*(IYh=c3e4qz z2{9d1P#@iMkgt_zdo1Zy*8_a#O(w694Bg?@-1r;NRGUHlKM8(y%xok!%8!EFY+Q7X zt~Oy{LyXlIQw*6VTWpUezSpbsNbJ{Vm(zRYZ^_x(K6ZcRk#)~sB_?tI9qj~rux3m}Bt7!>j)sfVLOh+(jICVq*QdgSfjBxX9-)CmNlgtH7!0lK*qlv$ZV{ zoN);#4B=#}9)x_SU#lv<*`>$gD!fH(WOTU~Zd`V5{cp+NrUz&|)lnJ~gNZChuXHG$ zI|-U#Eqe6d8jIFV!{v9QAubUfI5K8@GCoEJ+8XWmNd+FB=@sUCw7h~>#8Ji+y~wY9 zau)5SIIh?jI*#>xr1Hq_2U#0C9LT(0WEUV@eCo&nbaY&qCWOit-rv!Tcu)Mb2-kpm zOjo z_)50d^Y03eg_izFE61g>FT!N33&i2xbK}pX4~Vpdozr{> z+o6E5`RfQaQOL=)HPi{3@2{_3feYTn>l!roJmPP9_eLs4v%R&_-o5kXNS(Jgs zCW`b)!q$57%X2b2J&|4f9;G)=Z;nLVH-}tjX5pE7w~o)8&7SzYdz6=0Mp&}^jyf&K z(I18ae3oI(hU8S4a_ba*KNt7sA@?HUx;~(@<4+3`-ZHW3LD-b!gtawmH;e5Uym;x0NeH`$#5VLj zd7_XNqN?pi$pxg4(#{FMI0TV_=FQ#;C%qhW(bl8a?3}E3Rb;@ET&-IiOBC@nF%M<2W&5Wg zLJA-4kUUwu>E4Xs8gWccNZJ_f1h!F%p*2NWy-Y=sz_p+DG+ zpE_`%j;Sn`rA&~ejLu@)(A$qIqh}^kF|Wr)E=ZGa`+(pqRMZC@T1DPl^sUU=!;B+w zP(vbQ#i?oBa`F(1nI7=0e2LQ|vUWb|uA{;Fa-#hV-dkoP%w9Wf@;0goE%25@aAk?Y z8wAk7#LxFyf?*|=6RGZt3CIlTCu8R$wwf1KPhE+Y>t2O_juS<^t}XhOVZ75OtXI!W zXn#Fr0LA~-yzNjMBst+0oQ~~|AtNm@R20iL+ijKl@Qv1^)w4K|6iST=kNJp{nTVo+ z714Rm^UkFxjIQBs1pP6`eoFapnO7s!!xa=z_~T^Z|Kl)E6d)V_T?jAA^Vlq&|5nl; zSLP*d(&&Xc$9drVNJ+p>LID{(8pD*^^KK}e z<*7&^_y19II`trL}B&OdWKlMJ0B%OjOCm~Iv>2NJpF z!LLv7r}hX>raMs=c;Mp1s+iaFer{!CML@irUTK>57A`UdII>`tXwci45YkJqI35n? zH1?qYN9Y7gtT1{keP7W|tQ2|C_#YaXS*!lcknV$sGxlg}!Vf{iAv>3Q+@{Qu0szKBa-@K z-wAHCL3fd=6Dnupx8ub>&qi9dC&*auf`YsfO+h=S1w^I0f)FrB9YfFpR}y^1w<86Q zqHN>;SV*1yrog6@1ZMy-LzvqCoy#pRq6BqjU;Jmeiw`qr!8|~##0^^I3GeHv8liVj z?Hfymj_~DKpIFf9TgtzMjMEtOsQ9nWjf{fMm6g&~9G*WrNbkc@^%l}g~O|1$ZB!;AqZkf;bh4{4V4WmOUzV@cUN{A7o2GD&3 zY6RX3HYh#eGFW;MUAb}5gp5RzRd-d8m)D2*wZUqgChzNCZDh})8bV`J$Y0bXqZvXY ze*o8nuZkzvblf(pULEK^)Fl=U^V5o5b>bH&xw1BhCS4ee`YSNj z>`IQYP`X8i=~x;ntiOKQjx9!wbd&Q3KMs>+-ophNptfw9>| zlGv@?Nx{hz1`a)3hSG557wl;KA$Vn=MW*mKyzat2Oys1>bbI>2Mw$M!uKM;ER)KWe z($Dv9vh+h`oV{k&gTl?9v5UTg$0D9(bh~@Q572}(7V(GBN%1WTO{po=TAP&p0vG}~ znRm!@N64{73SoU(SytY$A1S>jmsgn#C>>U6w+*&MowYOtg!3Mw`5a2oRmOz)UE-+9 zv10RZF=(-`1*Dq?0*nf3Te>Nf1wT?Md{;A?(SHdhAjkU6KcktAmq(X6YT!nzS$Qg| zU#}8J8Ug8{y5856p@>~7CNF1jI-6?1`c(jBnWrFW4nFE4|6-;Ha;5%VIc=KHQc%uQ zWE}8!j;!&s`b4YlY80Z+=A!rznRkVO$G1tlX_n@Mi3iz8UnV{oIX*%$LD8G$_3ksG zD@Nf!zSYyF<3K3u>`VKu<`x@4!yx33P%p4BNtt@!sUm5Z z6Zd{drs+s(!lj3`EQdUVIHhRzzVUw=<2*uROnv2l);k;io?+$vqMKRa)U|kY4#QRl z0>M9wU7LNg`tOCWcA;BR0B#a}2t_3ht}(XOtwBz=bp%KuXkF4pa#kC9~~+xs-n z*DHvbccbnbZx%2-R)Gw2qd%FWE2psT&1B`pjf7F22;hU0SAO_(Qg4&<{_&K8f=^gY zlyKe*({MiqYnFx6KZ}r7nhTfx#P+4H>xj-C=XZ#CQT&W!!rakm*#LxcVn3o9x$zNM zl-m|}0PWuWAM9y{`u&UQnT<8yDzqdBJ<`siVrV%$Q3mwa1Slb=)`7w0(y7|!~c&M24mmR@rj)Ll9vYLPl3LC;r zSu{;BKgi)LwLaO0u%5mvDp+z1a+^r>Mevv#QGofKU%y`^>5~X&V6|3L3=|DNYr-x0 z0~JR`WIl;NW=42zM%WbaJf|TS9D`-OLK4}J6!)$PaD1-tivTdk4y9l?cHRW8B$X)x zzfhtDc~h{caWio++kYZNEfn0b`zIX?sZGa^C{hODj7{%49HOOgr{PSyjrvdE(q}9h z1Sdqv%`#l1n`&AJ5-|=_pr}|NDaFM2r11`BDn-_uFOJW7<3pd#o98JYVW+t}F*VM- z)5fLVFa_}>A%Sqb{E0NC9ksw|vy#Xo{*8c#D*ff|#mk0xOq0~6(^Hcj!>H@W|+H-@05OR2+sVDfEUcJsFpGmv2d4j&J| zNDt3X0$qw(%o&=IP{ow;@iOzn(>S(N^NF-kj#79T0#+Qbz8p(yS zKS*B~evZ>W+d+O^1e~(??r}LxOMSXM*S5JL`8z|P-}dq>T`%0fIf5jah)y%q^-%I` zBWa;1b|qW#_ZWro`6kdqB5NZV_*-5O!AlmMT5QlnCv2U{P%ltho-i=!|01yVL5cBl z6}&EU4VAHmf)N7a7^q(~Rh%jrI3+lX<>O^CBRpBAoEJKAfH zGR3R%xo>oBgn77><<6y0*+I!W=#Aufe1YvwCt;3~&Zk{864TZU^g{e+ zeoZQ+M-K|HP-mR*sD)X*!JXG>w?}NMmK?rk2VrJ#81~2s7OYzoc?uJ)pO`;8vkh)4 z=uRFwBXw&zKd4x*P+n2{Z=KNSfUj;4hNi}K^K8ER;*WM3kB?U@FuWLtIpXe6@^m4}W6oR+FC zML!dzdJWA$SQ{dx^fvY#KfUNv|@;_&Mg9U|_+bpHLq| zd&31saejmdBYt&Z`{XbreSsK06)r--#Leus-MC3C_{4KbE%4XZHO6x098Can_YYnD zWq&ZcwHUWRo9xgdaHlgW@)C9S{{a)~qRCjqqf?LcI9 zcK1IUA?1o#7BlbDh6IDXos7lX1HQ(vH|>$CGnl zJs(J$IYAB4jZut=y=%Q8HVG&K=P3O$B9kZ@?C3%{90#!t336xeH30SGk@U8F*Q4jM z6(%1$zk+HbjESsoQf=K3B4fRYj)srZ30RAf-oIDKM^MZvTCh5Dum~0Nrebywv5&r)&&5ZQ zeo3n?IuXTjRlM`FvUMlP&(Ium9W_4zyfOrn#0yaD^nytn&yzI-3CQUuw` zqq&*V7+=7EX}g4>#OS4_3W{?!%j?^>V=`4I27YbO?C!S`+ik&qtG=_Jf9N}0{Gpby z?8F`u2x{Q7AuQq~!Nq5o&UoZ|;6A1mJR0WzVWT48cP-3+>Z&EWjOS-se-F%O*Vosl zo~a@61E@2rv*aN%1Ni@m6>@Bv2z9YBv%N>VsG?A4W$@2i}-p z3&qcVimOPcMALl7`pMZ=6DfIyy`))Qxkg2W)DwF=7-jK;uVnJg!g%kip44FCq=_)m z@EHR|9PsQCa!prKSII-0*6;A;@0J6zk?blIX{Ohhs(b+Vv4lPLyoK~%F##rbh0-Z9 z(K3m|6snOK6w!B=kF5t3e17jT#b-|+Fe@V~MER!2S2eER{swk+uibmsT(?`mn7;}u z;Csv}e;lCOamKdl_4A~K`X!tg(1t9Y1W}3sPL)rE1J{SAh(bOn-~77q_Uzx2^WLA# z;xul+DfQb};=CK330QaFS&~^fHSiIdMS;XeT7LJ<`Lj*#YwS*867`z4JVc*6Y>Y8(rn^J+#M{+4xQoWv9!}}9a1hEj8!%iA97~?<)GMOqcV~hO zG*(eWIq0zRVz>jA4uqJw#m2 zs<`uSvaD{hdAM~jM-iQ><2foB6JC)t_6%4$#=eWLWlyG3q9#Kq^aCm?>K}?QHYa;# zB%h?eBuli^C`Ki79KY~z=Zjetcs%MiD$&TA#dv%w1hd6Vc6PJ`+(kOc9B1S_T4o0M zFR?u}J=Z`sEGafL7%4$>{0=m%yMg8hcMcZ^cl&gK_jlyW#G(s&Jd5WvXV`d;@3Mym zLH>#7pZLmYaW451&rxR!qlUY+oAbSZ1pE;TFK`I~Q_&W`n1SbjWBd-)%%Pr9J}4#{ zI!-w*fYD*Gsokr5b8928h4=y`oF-7Z6nM!W&8r7I(d?!SNAwp9Yx48Vo3qbblNOlX zx%M700m@NmsIfbBPd@{rfKehiXc^4%`IIWyCIqxlCi8CT%`A4dHgz>m!XMbSbJ}!A zIaVxCtV=tMNCMFq61b36zjQ8jI086mm1cFOHi!210#u6^qgDj8e)-i|1mJ z46-~7*+dl!3a$fR#=!X?%uUJcC#8Gug(DplN&znB)xYWPlzYS_0@YOig5iop6~1h*52ot~*kQ%#Mu?r&Gz8gDT<~Jl5GltA`F> zX7(Po9@Fy?rTLrLYNE%vWpbO}{-6$yoB4RXAXq)G_CfriSNG<6Mxo_9DzP%X%pnfa zGg!-Qlda>Tz89~P7bzABk;SIl3e7nK?+^F5w*A%n(-g0hcSTsTJyK=&gy{D;-E*bi z*st;1_)Sk(EDX@sYebL+3gJu?+ww^6Cq73fn7FuAGWrY^n9@4ARgMj8k1*m1l)!~Ca zq<1WmybHkRftmcV@LezE+?l|Zy(e`O0Yx+5dl>Rv&YM_|=}-K}arNCY{+loA(8wrG zGp`==w}#1i4+8_<4X?gIp7&+OVvG8AaLhka+PXdk%0Z2fR3r&>x?~D**p+C#;pY}c zqbL-0Zw5G7;HC-H8CN4CrC5jJUD;Ml-{PRT58t5)qDMZjY|mA8`MMP}=urTNjtmwJ z*xaptz`4#Gk@~!V0$jqHoSj#l#W0(PV09gvP1HI@^(B#A)kt7bKuNM1?@7eN^bI(-^9))ESD?|f7 z;(pHH#niyaE5gW}-vN@xpf6w|_vnMI*i%bU%EHem-~ffP)RyW`vC zY9vYiKn2+1>koZ!y zVo4M%6hOM)hK+Z%Ey6+=2=n#Sy%p`iPq_dZ6-piE88oZF*ib_p70_i2jdJiiiS14E z8WPxUMmIJeA~;2Vx(1q`aTv$ODL(cCB=yKIrBblux+Jpjc3cCj`|5?vr1%bY&?xWJ`@GrzBdr5aCOPnOpnA|QU}pZHO*ThP9*Fy^qL?L`%p zemrsKv+kQ`J`e@Nl004>g%O2pFvI77OI(h!VlW}`Fvo)B2TH2A9iK$Ex{Vr9*xl;d zRn6ikfzN(kl3AZ}MFYZ0_QDt(KOn2&kCTahm%zHeMr$0%;-+GP`1V}e9Te^L23zSb zgF+wF0C*<_cwc4qh~{UKPR-}8>j>%@grUP!hI)yIq^#&Kks0u>Lx0{DIY#B!69N7v z7CIM$VIql=xLcJ#-DUNJt8;<7I8fDx%Nd=W;88K z9ID}L?<;! z@hrk!PJNbcuF%SeJ#A50Y2)SSZS(~u8bi4inEk8IS7>rpMQ`1v$-5DK>K{O-tftfvc!n^*W=NW&9n88d}Q|o*{r` z$PD9H?fF(ZXTs@Kmn;;KlIrD1)Ct$S6}aTpY34mfE)Mu#N< zyrwsJmHq(n?`ILkuwCQw+oi7yS~`2jiOQ*6^8`-wHrOzCV(HiJ4phvIWmkT_Al;W= zla8_$Tw=CoLz8E0x(U+wIiw`s*?NO^^1A3;o`d`@20 zb*M^bUs>V-REV5OPo(Zs6ecN=1kX&8zwYgqPYHmD)EP%*r5HEgmzi<|uM6@y1SWZC z)|AW&GKK`F*`|oj10q;Sn0HY>zH8N`A%404iZ&}Rg zA?%l%BF;h^hO()o*n^|&sxhuE897x(H8E>s8zH1iEvDkP$^_Jb=?3=_lL>6>Ke#za zT!jh$zCSB?>t*y!$$)#lZBJ%76smk^aw@%Q>R9$;^e$i|K#OJ)&^9)$fV7X#l!c(q0Z^mW=A0TpPb<}fqb(^aCY9I3@kh<`j8n5t+Kse3J!i zVTa0aT)&sPl#xWtCNXjNb!kiu-$mNig3(jUTQcZ@PuG=(H_eOEvPci71XA$)z-RML?Z)kfx4jOE*5CBf z?>LEzw|rB>T-sC5LfgXg{cS?;2MuqMTEe(m>V+kjHw82`HkDLI**d{=)*rSOit_GY zM-Y7`2^SHp8W{HQmEp z#xz>|fw@-zh%7%K*n6A%`0C**uw^=|%n~ispEjVhWpB3;V$tsE7nB|Wt|RC#7Yq)m2_3`s_1)YRiCfOqc{pU;4FMZ zLlEm)+i%;yjdawFhaZb@Q$FE64cVzkpu+Bi$knvwu#$*-=0*VLg^&%(ZdF7%~$EtxSTan zaX@7k9V0C2f*=oz8hTUld8UNYuLM2KRnjgrq_U)q95Dg3U*8F=Dfk|a$FKIz#~ww? z?FTBVC}k_Azm93GfHSE64IKGLWDAXhM2pjQZmEh?=fj7k-&BV8(oRB zkp9z5A(jB!iwqN6=msXiBs{_6<=zHrQpv2>Yw}ODRI9k<*4brynth*Va(2&C6DSG-F~r67xCh zx_H%y7~zx;w}xW=TJYBLIV`(m9pOP>OBIpm4t-$9@9iGL!a^A^?I$RPsSPl?(qs_x zrR2G0ieOpwkKX}A=l1jau|6qkPUY_p%+;Q6vty^0qb^S5y&TGgQYrOkT=3tH?-_G} z0p!FlH51eJJq-Dt+&*JOvpzRk#7bl$m286$8NGPudx4`stRh3m+i5YjtLhO^;+8cu zr$0D54_$KXFQuN`g|cr^`m!MqJZ-kvXbj+#dXC&s-vTGxRwHpsN{28LJo5)-aOnXB zaX9_n5~fN1rnaNH!Vak(?Wjxvql~nidt#t{*J=0&a`Y;+c;n;12G*e?wN*;i-|u(9 z7KV+KjIWayrBSeidUg0Zx8Q{HJ2OJ(Fag(0MkG3Xs(i@Hf59v{t>E8g8BPl!L+)>aTZ z8lBnnOhW#T2>+?iQI=H^klsM2%IUh5^ZC~tn~`2gi5rokOpiq|IvS__1YYSl7610a z^%?3JpISu2!r|73y`4V6`vl9_kX8rA@sxk_9GR5R67k~HWvR93;0KKCX6nEoQ5@{R>++xGZ*eMP7( z;n;uip~LsB7eiO!=jiBrw4eXUa|YCOdM@JDLAG4vT%zRR4iVMs4-LfVAqX~yH-C+D ztf+Hns=oeo!bUnL`=55_Rd5nEPFqznMvZG^ZLVrY?}7XBCU;Gh2nEq>jk04UftHS3 z-IMmqNXYc4$B}XGP6Dg>)_s;IUPPNOkuKdqN<8}mWmpt86eywEw4}xe7K7UV3SuA* ztI2bL&Qhq&2TF#`!=qvgpkI$N4osk*Zd|B^$C1<816tuC!)iAZZl6xPl(_`wF zFOXL+VytH~=@Mt8G3uCt`+A5z-*N|-;z5wKCnU^nxQm0-B^ZHmIT40-UB z2$G&RKAE!xu_opt_pcy4Z1icdG=QyP@hx8sdeiZ}&^?%cM{sT?uWo7BnzJ0#VTWtV zW7N2|U%d#X<|+@?1~KB>&&;Uf;nVP%k4vnYcfD~7R7x@cD!cwue_P6`l zwEjn^hTIuwv|a5!2KpHKPREv_m};5ZPcWo6^WhF-9ugW_!*5a($&@4YnVrQ-K0~-S zBfo&IQ)Zb&dg9O_r79YnGSV8%-$a2(r+y8JWh$zsOf%oIeLKE?UdUZ3eF8|2@SmNs@%Mk;SjTIkNVG7obH&GLl5v`OOggk~kzQc-n+!cPY8GBQFr@6Y=-a!Y}QtCKRUok^NU*NEcIL^5e0Yio|p(2-qtbLQl=%=G>Lq)5Bdl{XGAIkFR;cA=y#g^Yz+_U z#fi8V@|*w2*^_0`7pY zEn&YQId)Iy2e(b!yh3?l%q9Dcfag{xQrY}x9mJ?jZQ%`6W3lEDO5@WpefZutf9nW{acNL{h~l#^r4>;} zk1WG{CBcKlnCiFTy9ryR@16SlPiK9z*nRdbD$u6(@ZePZ38A?fT(xG?y7eomlXlaR ze7sX9E?WlqN2MEdQ1ZmC+wJ0HB!>#~B{)kl;6zq$jkTsNEjmRxqnN)(rYdNfx9ymR z<$cQCL4!5b9o*}#j=+HCxh!45kfuZIes+fs1yqqyh2zf<(m$7JQ|r^X*sGKH#E-nS>s^PjD8*b6U4ljg>56zL zs)U)+7r5RB%hl9I59TeLkM`i5e=OgKwQg?|zml%-YGGQDm|>yrpIh>^n*3vAlVEbo z;@E)>nPw6ZqHS#wbW&>A&~rO|UFx--F2o@i;Pb2~XBuZ3Xqk?zDO~pL7x$Z!ug>QF zN=TbhALYPf84fE7;R0_e*YgM-L%2Qh2IqgCKqekm!7lUWIqr=s)lK0JZFrvR@uAUi z;s8}sXWUE?(Lenh&xD2jA8tH4A(2iyn1fm+8q zG&2-oz-iNf^$Lx=etui+3DQeS4BA5{UtI^O`5X|Q9TCLbdox`rC@~Mc$Prl1wJGKwG4XzZuu_(vKUo1_9hpztn$8st!n@c>kg<4IdGI=sQYMdXI~uSIv1G zz|VR(9E#Y&Do|@KSzu&ncR%wnffNzssB_>ekkniz?e^;v+BuRZw<6Y8@I=AH;W@(! zfG3A=Q&kpf)A!o(JRLN_I`;W0>)f1K=JSploF644CxVy98xgTF%?~{SMM|ePyDl%j zyYbGg<@ZCrU3PYJkXj%R#NN0js4Umo8PR2c`A%-Gdz@GyLL6Aynm8#pBkrz%!~k;= zJ;3mM{?O}|TG!`Msdn?WN#rjro~~e1xpolQ^=5=u>WHGf(jnHkdsVa3Y!?SkLd}Y^ z8Lb!xF>5W7O|dvh&%*;3u4K^6o`?Y7DHVbL+7%P-;~gf-byvFBKQ)X;RJeegIKtJz zIfZy|ryt2;GFhLe?%%y_2fwL^)lSMV3)JbLVaCxtykVl-)S{ZggPf^H2SwjZZ&rr= zY)-3{)EB(3i7`Hkr%-?JjN_tcuJjscJ+x&@T)n~KAcIU2)5S63_)$6iQC_6zLrJ;2 zzBOS)^vVa-2nr8I3Kky@Q-XIA+>zJXQEVb(uX~dT0z3?n1&ohw!2}>`kj>qEmZJEC zlfwy$eehQCk0FY^&Try>KjV69chRY}hp@OHcZ&JFai~p}G+Z-2c+HxviGpOQ9nG(U zh(|9Kq7%Y@=DeVt_2c)Ya{S|G;Nr$p9l29c^5Dg07`BN;Md7Y1DN<2GUk>~sCLAvj@)r;R(bq0cNPyP~x!JEawS8iCrXqzjp7n>*y;cp{u^0nSc`$=2EMbO+#ao<=`kI7@- zvqo@M>K$u|R>}+4@YJ(zlgA?7*Uo}6j!@M|dbAWkaZ5tHcLVg^>AMIwUCNG*l0$>Y1ELT;@y@oT?jIj|9T`j3tmcLMLxhY7Vx5GUjE55$i?wIRpov5W z0KOw>kO^U0y)aY_hqQfyb! z!5(^@-`wX(mbbyE#43X2DNZ_Gkq*ULZEyZ`9E^*Y+iYI6MpJG91L^Tj1I>qW!7qm< z^u3UnJV`zAtkYk%dxlB9DxVu+D`P~;_q_-7pDTceLQ*he3-tk`RSOgm$gMayX|jx+ z85lHLcW&8o1Edk((2(ysbA9rAwA})oboW-8CMvvqG~f#DLZ;i*f!rBsvX&H2>yH1- z6pdbuB6?9cD<*JOnkY3No`mwpRd$2r9))gnFN6pY8uE9*?XZm1OG zAl6&MOWZs~86;^Xq@NeGxW=zozCKsA>B$s}4}gvea|FBXyri6PjlM0p!JU^x5eQ;SciBw3hINuv{JD=EnR zKq936@nb_v0$x-b>d`qqW&SrQOE9P0*C{=OAl$__sLC83c`3cIyAvQAlJn=pmHur* z$?uIegT(kgLsW*!P<(pY`dmjpdcSdo;=c+$RX^ z5K)Qs%d}v;U5;}zBN~p!m3bA&*!1FVYOVRW^mgr<+ zN;&ace*a~$5hC+=-&OBS<#n2V*D@2Z@m@S*wJyw{Be(fGh}NA!R(f^z`1gii(yc2W z+yN`Cen8;rSnGDJ!~St?*5KC7_^mpwI6SP_)XuU1K@(*9KKu90B(WA;5&K-VXvss? z?J>zQ9No#jxxAL^{ya#T1{Qi{Q;|roY90&k`5Bro)S$Z!Ndrq%h)TD0pt)7nSee+L z<^FJ8DG~e}4wM+*f9Z^yifC0;n%QJQLT~ge6~9FjtQ^5)T^$qTHk=u=H#?{vpPPKH zyb=2v2)(a4H+Op?0l8`l37Lp$wB{~o130o>o$EBwy}aE)#DBN#W^r4CWYYeMbC;9t z7B92{4^jQae?K~8x>3osl+e4}g*EUqRIe8ZqsvcG_*tD^Fzo>(W{%QKV4zthqgDdv z1{Xx=+XpX$`NI))W{946kq2saHa~@MaBPG6gUpH5*Q&@6Ji>_9LM+EV zTq)iwRA>g_Y5xOzIG;WNtZl=$YVa9llj&;xBYf3+{9yCV8@9H&knmaYS3~#S7)?>Y zpI06bcVNfJ`JjAJf5FP#wH`Iy!Yj)?V-oC6OR}eLU#jjl?g6*63f*uf6-$&O|6iI1 zq8}fL7W3&8Xor10vw9!r!1$(o(%Ke_?1Z^`5Eh?0HC&I|!1d3&i5Yt=p(P$81)J70U}93G2n9t=d49;v zO)C_K+emg#ynBNqWW&vuxnbPo5!EM zC{Z zh5F{ifMQ_FdK(5@v-dK}`}$ce9s?rtpu%UR(bo_K6@VoZ`hJ8ro`8>v|*@@Xiv>?rH=Iyn;KuXKA-fquB^M0h!H=v z#D;q^<)tIY;D?J3slUZzga?qTnh!zI+xCS@mvwh~fck@^h|)V`6=W0A8EHI zkwe|{yC|Kp2W3UDcOL)?mkgbq@Bb%L6#W0vN@;EZLjX4p;$B$R2!-%P=N3&6cGG^) z=s5}NmHA=7YQJHKdspI~pi_bhcTu0jEBU!^D0Ne;y07j;Ov6i9$UkL0Hj_Rbi>lj@ zmd;@_(l4sTA)?J`H2kL=b#zhZ*k&-3p9Sh*h8gEsDqz@7veu0X$CyysTNULFE1lGK z|6?POnK38jYTuaFvajTN*}8S{^k1FP!@i;-`Abrm+u40?=m6s zznIZxUFnT?sZl?k+F2IIg$BQdGsNWLT^b@YvcmLY@mKosPVAeKq$6VuP_-W~@HY%! zyOQNArTL6iAk}esN75hf@B`B6%>zM0lFerBaw@SDG=3ERA^$0;`nbPtG6grr)i=R) z^S1hSze-7|5D_gSkCLrEns=}JGhK)Cs8hYqT_Rn(ysM%SAep~hy*Q*b{^I*!Tgu2d zctoFr#*LLB=&K*8a=Hi`k&9l*@f?2a>}9vpt12(|BYPd@^#JX$F;ITcMAZJkOXPaP zi5YP!)O{bmV%Rt5JN?N3i(DIrr~C@kuYoU_n?J^4l_VD~JT1PIxHB&?G%k7*?ZRtq z{Uy9i(y*a536gYD%Xt}3{l46I4{kaPaoX3w7bgqMA++}q{7&*W9i;FdkaNy$zu4^3 zb{z4X+iSKzIkFnbFJgY+ZSDInM;R)3Etmggru;7!G{)|+k^08Gtv6pTxHLEO2%cSo zWJq+4u;e)5dc9JkH+k0&6QYO=iTll;d)-Ga+*CD;+fC!h^}?<=?^NelwSfxKSjeb} z=5$4Tdx@xPE_rlOAz#(CWser~0|8Bv^vQ>Hx*%`ZHR4}zsB85pzJtDVsaxuQNX|(l zHMOc1Y*72gw$rhD24lOu_HOsR#ewu22qoqD!@S0yMxVhFm!IAL%L4fQt3XBK&~$*$;g zS;lONHlG0_>LTIdVcySdYoxJqyyaoCkxE)Lrgvm&)FL?^NP{>y+;60nw3XCY6<~^0 zCU$r;YH@WK9a!@c%_RfZw^Gs1&NoOq1Jo|#D>0Qc#Y*DeQZaeFCAFdgXIsNjWU42c z@>IR#m$<5`h=CQ~XokV#t!GWH*O zV`?R1Yf}?{l4hl#%1NZeBU^n_3Dm?9xE-Z7SI&Hl-rh?_a;7YXN3?dEy@lngx0GiP`r(ECu4 zX#wKp4UTWc`5@5&s`<-arSs|9_8|(`qOMG`*5^+((6b5jo-K-WAmue-P`P`2(Zl^s z1%KndF08@FfymYmexl03REAbD*EhpXU9iuvZxYtd|Mu)H58o>SGNw0pSZd~2%a{)W zwZfdg#W@94Utf$}L}#LX`{=c+c0s)UH{|U__U`#mh|! zzr^wbw;!IYgBOt(nXTU8!o}pu)tMXp+MgfVhx+$7;s>KQ7#O5QJ;}6xLqvPq+Dhis z-aA>>{Y-Vx5Fbbx-?@b#5e+pD+bRFiqQSb!L=|$tijlDZ)HKRi*;u_4W_$@4mW2@G z5n!o3QzNj1i0{j&h1rgKLp8m8Wg#ehG5>1t1xUVar}kzwQmv8hv{&8td^5U5{mZ{e z2cf_t&hMOL)BI;z(jBA8DgruBFl8yyZXeK28sHRf*QWPYtM=XAcJ@aE%+gYNvW@By z+Dcp3_CZtgP5ONtmj=6!bss6fZ<4cHk2S2Ba5w^}Pj8wuA1=&urhhDyAOA%EuM23^ z0wntK>Y?A9Uqf>oa$?)*G0k=V5<_r; zy7_Kq`ei@tXFsne2mrjyaT6Ly&w8V|po3{VFaN2HQxj+Jimfn)fL?oan@VmlWyqiV zGy*c0h7z4Um7J^eV@LlL{;7j+cKkjS5f;8f6R}o-oo4Xy8FW}!RroVTm`#I1OGQbk z(MQqIIB&(|Zxek5z|T(gfKW>taw;=2Iw`A7Kr)&?vR7V*pkVxxfT~oymDsZ}yA|kP z3~>#&j}KW3gZK2rL3bRavR$>2u()OsCox`za7a!0)C zURqHW>asd(nZ!GC7JA!b%$h&32y37Si{Lyf?o}UQx*FT2+5Yz*7Yc19Zsd-?Bx3(~ z_MQr`wFm`Kv?EDCsSm%`TfzuQd(51-TlfZAH_a#ac@x^D0^Z@bSS^3fL|OSPZH^Ym zofg0}aXU_5wNSq81pZ44&%pM6TJypSIJJSeQ=_yu1oQ>^yV4eP#O@LBySO}OJEw63 zc)4d;31c-`h_4`X#_s^KtSEfWWlOEW1^z+lkT|QTW+HK$&A9dFMq6pEqYNs^ZJFfQ z+s)t3-|3PymezWcR?%hsYHLz1jeM~|^EQsJB4&a!b4TNg=-zLtMYc8($j5kVde|(< zsU))VDWG5g;|+jNrKpD~#va@Vy%;bOoH>=^SQwy#Cm5R(_ob0Q1n#_O#3r73{p!mE-EAo;)%s!UHe0DuQ#Gi3$;>1R^H8Mg$p)BtPzVDX zaT8uDz5fInUE|(@bTKren|d%}$^7^jdHfC*7EN>MP4hS|&NUHcwM-M@KP-+peOqC$ z>*`{&sbM4Vk52xM`+>C;4Q`ulxR9Sa`;M7SgRVt_kE+F{D&Hk=d;N0#n{?OePoHIU_Oqfhb5J1?u_})@ z8}&&P^APl>-U#MJn;`vtt)1yFBR8JUdwfRDWQN7)>MG-vHr8DaQaG3~ zttPY@z^dX}NH&$8gF@H)`A9ni-ZuqygYvVOk>jcF`%;{A)uGvAH^e@jx*I+{;*&rn9-aay3LdW;dqWh--oDw9GS-nK-eu1-v5Z}C^5Y=sQ z3beaUBv_tk>P(%q%SGk{nci1%WO+p=>5YQRF_pw&-H5kH@QQN9NyuveF199gYpKZ+tB=p*cY&>K zF4jx59D8!r7Tgrpi>6gRQ?&&-G@jrATQYoHT!&^&{Tgo}K{m>tY-8Wo~&HEg<5 z=iKpNC9hTwbUsrfhjy2;;iu+n!!%ZdVmM;v?B<4ks|LvCeQ0w~Efo|P{mrC__hapW z?`rGz$b6?rktjO`9W}{BJ{zRHHu)zW1 z$oM+l9tbzn-Uot@XKpKBe^g@{cW---PVImgeDIcXe^@mCCy&8wAp_ajv-wyj`c27E zj1KwyYxtS#pF%Q31&}r6M5nBz#keSp3nW^I+7oi5_mF=pF5LC+aQ$nz8g82e!9rnq zf3z0k%1soI9_3CmIIw7te(Tv~Vri6&PilarD@-$PE(`7uUzu7; zgVN25a0h#;2(ESC0WCAR=fDIhu3uAbv54lBHwWZ=T4X@e_czEM8IbNeUaza*Y7eqk zz`f-96S7dcEfh)FgAJY=K=QWP49C9v>sK#KxAX5wGCg7V2TpUz3Xlq((VXQXf3-oc zWQreUkr$=k=Jm75hsm>k z;+^2-zm5cBtFPzgjrh#uduHV7tZ*zt?=20i zqkq=17_4gBn6++LkvUN5Z`V$-%rn)3Iza2a7wpv6mXFSW(xG~vz+0m)y=9kG0oBt>Y&&x*~w6^^LL0o41dYje&_p=@`CZ+LK4j?OnUxKvFE=%J$xC4y~Hx=Nnne1WAm( z=<=#zQLz!{vZNuayFQaAD)~MaBh%R;o^e)IWSHBp3UA$99|?I4qeXf@F!jE8j~Cig z8`sl0LshWzpOna9U;qba;xl+G4JY(|<9Y$IAd5^=kcAO1ZSJ9fG1b7bXaq8-AHt?cmS$Kw`atTUkZKg17qbDa-+UOT?z~mU!|`8FYhO zTr@xHey2$E@U@^UY|Z+?)1mVKV$gga+}z^Pu^PK`El@3lkfK22%akWrb4Iy(L@D6# zUxxOfMFv|-euVZ40yj z&VB!!cYU3{bH6KF2YDk0ga_7ycp@Rrk}oK=PkcJ$4`Uk zJZ>%+krcd1$dVl)8A*+U=oiFWy6>h~W8akOMFtlGgqnUiu6|Ce&yVGoJzyO;uCutO zv{qQKRPXqjH*N)2{|~J8Duwg}-uz7$K~OZvq<=tyVrpt8+cYC&RyuQ%ty&Q1`QjG4 zdo99&=E|lfTDnixN)Bdue#i?u%vTSCH@(rpVzvB$TW}3vOwO;i-6pHO{a5P7Yoqii z3Mk#p2LEU~9sY?X=wT$l>Bija+QU5HA?+#5;nu$7k$nUod*@-=VsWDOpuPSI*fVXu z={Hd_?|w<%#N+Zkpi^0${Fh9>yfjMb@66knm?!S9vKhZ8b%JpVIeOsffc(^lV)JjRYg<%kGRF|?GCd>7qHl_n zqX{Vha~2wC&)LDHRjE4OQ_;4-P1T6KHE~#Ngtre?={PHvmA`;BPyw7dRXQmz#Ur>y z^XRWiRzMm;7lQy>LB1_1u_kb|Wu_+-Q)|aUNPz0R!P*%tUZ-@5D>~#J!nd@-;w<7k z#dBm&&8NB2TSiItSv3z@DX@E&Ac ztC{gn2AE)F!#*mz{X3D1{5hb5a0j<56|W50JylAJr#Z=v4N)LQ-o=<{UW zY8~!9C(*W&Hu>AGuFI*6WxOH7Jz6I%==vt_;ae|05e=#(%pd3vtTQ^T_d7f)tL4vL zLr#nDNvpl82K?26X^e<9xHccSPu~*t{^S2{q$>2S=T_OnK4tP5tv6Xde8kWRB)|Dg z1*8}BHZLUnJ|~q$6<$Aq@_A)!^zyac#{9;WGhjgksrBlBXm*b4^LwIHDD^2R0@B$5 zKNn_@&)&D#zwNhtX3|RopZ{wZS|mskSiO~)y_sUMdTo;r;qJAL46mn5z;Cc3oP+Z~ zqctxENg@YoWAZxbi`n<`oi=8+lTD&;(kOFtI-(_vJyACZ&v^!nN%RQUCDiwiBL(L; zYU%VVs3P?n~yEsC=&#|1e7CXFqvfH(b4=2e>#5!Vtz94&N-!N zb=x_P;FVch4c!xssCmdz7fD@f3 zUlCF#5+^5TA^2J70ntw{&}t{?7x|0nbxAJF1o%Z11X259ZGc!}v9v!37iSIxMmq^P zwFC{pHX86neRzqKQDwW-z{}#VlwbkpJ*7iR2b*UHzsc?VMaIOwNz(9I)=*^#tdWeX z<%rol(M*%6)(!zDXz?No^ouLs(nUW`e783kFBb^5ME+PMuq@v2a5sFdrgz1rETc-B z$L2GmKBJmi;@00x3QCBJI&F#C5Dp2Xm$0Ibt%8(0-6kCY0_5sl-@-cQ_7vPKa zF<|bvhFwUC8C2+($29sTg+7P#n`OD*g}(_Q8zR<%M@j z2MXQl-)T_k4xGFE4Vr>ySC~H3ZadJ@XLz$0$~qXpZq7T%7tcv$nn?}BYNkgkm?$>< zvAh^JnbxbKM0_&VV;zW}j&4F7rQ~wTs6NjhoNM<^pwN3bH^&YH(I*;~i{|gRI`CY; z_^UgI>3}C8-(ID;xHt__<+{Q?piYqEnt%99@H?ni?7QS~lU>rPEi4fDq3&(r;}o*( zBRaVBRT>wM{DFVsgpinem|sxlj+Lm5D2xUyLA)=My)hP!Q@aFSiL;2aAZF+oNEC~& z^^mx-gJ!#9tV-+R{nXQ>TWK?$4cVOemN0#qvya+)ua8l1y@wv>7m$32ZmHnbG^u}{ z5bF+vH$92GeH@%*cyDHh;lMQFG}cr65}$)*@s20-y+R9T@LJ@{=7ddcJpjjv z9>6pP56YxNp)m3?eHE%}Hajrk4-auL*YsiyrGZ1B2>v(S!5|2vG5fPysCHVy|QDOq)cfgu%o+J(I+_O17nm$Ot^z zhliE1tL0B_o>N?Z&H_Bpp3wc#5J9{~OOJ5SBHD3>=vwbPA&+ECMvVCT@R}c;i=s4% zf`{7Nzq#)h0Ti#y!@VUoAEVZ^OOY#iQvz(2a(AYt09Wc}m(J@Y-?Bi27&di33{IZ^ z5cI#5VseIRysj(Z+bZskwU! zwS4w4GVIV{TQmT&G;KD_coB@!Y7C>eCw*ez9h4K|H7N!CfXbnjzI>QVGg|tay(^eo zMuoQh_#XA)87v|og*hkWR@K0nXvg0>4|2QO3WWv;(s`iwRqxojy@h34&WLC7x8jQf zcU2j$Sd8aP*6ZTAERE|FJ(fCdK7!>$#no!5ZkC4~%=|R2dMp>*WpY>sIK{Qzc_plq z#bbz~BdWn6z9==QH7`&^6A-vCZp@`+4a@8w2lw?rJlJ>46LdaS;ZhrE64&W z!XHV6@_h5yNfBFJbMwdX5BRow+gR^ji;mD|)#;x$My|D&F3{!fdeaiMhji`V-?f&Z zqW`r-9ppm^RmAY;lgd6xOZm%M)xNM^z3<|nS#s%Cfp+ja_FeMCX-n^H#5=x?n$F@D z5_8;{%(4}tPTvm_U#3u2`og&)1*Tugx7662DEATQ(HdigS?i-(Ub(YTn2px`@%PxZ z=(H56&Zou?rSPwWwAejZj2KAkF9-+hxEN$ePpf7TFjIMH_~@`t+1XGfJFiYVsmh@6 z>C$V)loESrMqwsC{&`Z5GEIO4qD6{E-&@2LMGT3MkCs>F>cabl89bBOp!gVJj`piv zFO2mLG2f$hV0enp?^%n%j=^=)(jAMqo!;VY6Ls<2IF%et`C z9EUh=LId}~c|&$2ps$T?RjcfXDveJIeioiVY=P2PyhG{L1OsKH)1(7Dqz$#m;qOe# zq2w^02$Y|L!9OSt1?QDok6`mEqblMPbP#IHj*u9c+@r&n2luZPS}|8wC)#k#BM7Lj zJ5vSJd>QikQG1t!q`fE7n(=-%-MeP^RP!VFK%tB477=*Z=XW0KIO{m<-Hs-7a-XO) zJcC|LtD9`I3wW};z!FasSo<=|HotF`EzOU&Dy)`GQ`63~B+}~!ZXwoykEh;nM&4mp z%*P`V;*Th6{Od+yejB9KCP;FQ-V*L_Z9eet^Uf?63J|5QEro4{Fi%V_&tqemsJDD* zLi;J8O#cxyc&o!~Y+L9tF|sREtjCzLxM9tow*nYH#eK(4$>RM4Er^-|%IV?IA5*ie zQkttfL`cM@tiAN(>;r^RTlKPDn4~u(0{N6X-JzZ~nNz^cy2cW#x2`WMpJE}K=?+qk zMFXF?{+++CHCcH-=uF?al#eMEpOo^Y78-sOD_)gu5~q4bFy;H*4QfaYaZRFZ!h9F; z6>%aAZA5$5ii>G3(6xVQ-8JWt_g+Xal;lniH;xY!C@6{W4czV9{WA3xadF4h{uaj~ zL;^FpDc-vxq$#+#0`ux^7OA7e#6mqb3Q^1S3zYTplFTctN!Cn9?L__~H8*=3&U~c-?4WuOPp0X@p4&!ERKD2$XOICgdjuV}PnYs5|&*_JXNl%PmcE|WZ`&dBClhG3*o ziRTLgPZig0%NHq`bn; z^y=_O#sk1+)0qS>vt>rHCTxVIGXnnH9&6$Q0BX57%ssDKBS0_JS2PslU&Xu=a}|9( zlO26KgP+RP%=@;&-yQv{5rOP)ohKtkc3mSx>$tw|nswjXegkx$3q(5mc$4m9T;Z+Y zXv=qTd6R%{Lio`@j3sw86)6CZCU$s^5ZWHsYSJ!%dEows`!^OWjQ(jc0$5lAor3d@ zpWyUoF-2a+JBO$s?}udNk>C5*tmG}iOADkj>1K2LLi|s_`C=Y=nhDDq7kKX)ws(&kEeCXYgsWb5g z)v};yr&vo`!j%4cYO=^+SXlU!$bm-$eicN%XrX3He~XD6#?4g6anz!bwhx`H7ipJ= z^)TnXa=Ecu4Elm=wP3o!hQNRnrHx%psMS}Io#k@PdRM4a>MsdI29SOAOy0vhKOMb( ze$Acbu#@C}Z&myQLI}|Ux|evZDZ&p4JrB)w`l(ZC1HbG;r~mzZ(R%qjkiJ$YWvMC0 znPk$&Kro6w5RqUG2*}<^gZfJhoehT=EoQ?-sV zmP8)!l9}P`(^U;J3cIOd3&6q{1UXEcCVfzM7?_K31qpO%X}z*l7c9RAhS4cAvgrll zw|6=D6&e?2e_Y?ye*q)Ic+|2RWmFhq*EfsdVbzH-rTDBoy;bg$ynut$)lzEAMOqO1 zP^zNe$frcqPUlP!bCtoDpL$$b6>CmFUq8&lk2!(T9ofYoN%mP9E$(V}bP3p#5*m%! zRHRUdzr@ELXs#H<8C!AhbWo)n>DfOp zx(EX|%@@?ew*Bx$4XAU^$e3ojsMUgC)7-_S6))}~WH&#I8L#&{T1UYLVSiC`(A-ju zZIfe#K+d^81Pb)wrDxt@wx8ltP(jbuL~fOpv_pf zGw^>Ja1#E6b%q%bjqDQfOcGfB)5QY{{Em%7BycLKpoSjlN9y4&-=ff>oY4kQe4#96 zBH7SIwivi4yVzTg{J?I}zM2;gVv2g_dJfC8L~k_lz-*T4^uNo8&(>&{_f<+s-}suy zW|PxtdGMMQ_w?0`230T8|G2rjtT@>(s%uYR1H;g%a!ZG(lMF>!1hQ;wb-(K>+u=cF{Xky{ffa&qn4JQ<8nNTYk)PYCVXYT0>0pPva5u z#}JnVmt3BKSnO&z#YWZFjQ?c;aP#~&^MjvXYo^;It5kk*9zHh&W~iGhv|dR>dyU;a z3dys;Z>}upYm@&}W$h%5k@U>{a?6+c62fa%N%Z1DZasXI$0Li&^|0RL1rHnN%itAg zhG})(iT1^Odh%1Hr; zKoR@9w$*i0;E8aZywaE-HZEZ((@oy`OGjy=VZ^dB8Sj5@hFkkcZIm6d%vpie-x7x{(cke2G6#zv>Kw*;Ez>rg3HJ`s2> z$qw;bQjB#?#lsLnMz(1T=_J&dr9}1;8^(jGD#^9JH>B%OB72!0?>UiXG z2=y=YPp=gAz_38833AQU;~z~Ald6Srgd~i=nWqseWg+$j20qqmvan1O_7)w^F1dye zj1yOWs!n)$zLDgYd*cz>ZZcbo{R=-wsgBp@zshSMi)mBgK5_*)BZAq*dK{ZMq3}GRiRGbL}{}@3<&fZcfQ{l*tA@biC z`?OBXHzRLl*U26$IHuU=0fcqS8T=0RefD-4BT-Bt7I<`4$Y%Gg&7(O(@maQu5!5 zwK2eMV|%oboe`s80yesiAja(EtIju~g8&Z6{b0UcqG2!0XsSkOd@N=I#pn8%TyYiH z{K~4lvNJ-ITi$kCf)v|IHp|}`37Hc&A8W?~f#eGKSQQqMl((&2VWZ@an2$p3;e^s5 z@+rVB#QDW0wjjM6ayRmGD1nM@poCU2G`uhqhrEQS)X1H@QFH9T(C(nMI!k%AWXh!0>=*9ipxwmHjno^iVNt z)g5)@b+hnN2U{Rd`RngUk6?D{S8k=j3cO4&o$Zyd9k?A@))J*kL$F;=F=H)kBb-^5 zq3deXuBfe6rA!JF7B8dwQZH!Ej?%t@L5A%*?hzTGSQR2xq@-E{3hZ=BY3k_`U#ujl zNB}xGk~j={f4=7FRqP%IpL5wL+bX_IakT9vRry!;x%`X}v>Dj}>8r_R*09oHtu_qJ zox0(^)fQRs1hG-J2na6N%k#AI3nw^wHh=G$C~q#H1nhh3*91+6a-l zjHZXsotV`OyS@HtBbjG;OVdi%{;)zquP4d0LYlt$fjvx1t#h1mLW2>pii(+W&a|DE zkXyEK>VtU@y{j;-Suj2SkB5SHTI*^rL~!0=J6zaW`lP>g%Nw4fwjG-m2(FH)+i|6o zb?loze}CJQc0%j=M7Nwwa6n7vN*9ZkJx^c3wR3gqzx6-}mKYfLK%LVtkau9+cq`lO z*eKD{nZ!a(Pv74rhZN9QrL3-(643A5*+*ybba=gEMEl>|p8s|6V%v;KuRJm%l_@Fz zW<1i3-byPT@JyrYqi61mrb>AEbMCF?u2@$@FbVu^WT{NBhl0qPY&UN(sl_K-AJJrW z%}!EpPMC_k#pv2YFI3gj?TaJ4T>JDvw*!{pX2PBS8Ns!xp!WFLTdZ+!ta%rgfwfY-ML@;iyE&bpZC@`wX1DrkPb-o1gCZRw=TV8TtgNB zjL2_$F*q-k>BTw=&_^>T%C+GAVq0DkkuF_;Ss~FE5Bg(+h!6*nH|5|)5`M?9;yx8RtzWlKQkKHS$>X zwaK%3a?(6T&!{koyQTD@WPSO}dRax0S>q)GUV{%?dzK>*&BnBlPeB_f4&H_ALY&lm zZ7&KYYdMv)ZsrB{F&4l|@dMObIfFw23b_i!@g>kQKb!W5j=(B~E>v&_CZ5)j?JIvC z;VtaZpNnw$XUDQO;iW}El|T!&K>JRdirg(#8+ z>fT)J<5tfk-_mXdf=9yMgWr)5O-=M@egAeo$mRsjGRBv_3Hq!HGUhQ~z^6^_F-2u@ z{t@FviNQc@y%eH~t}1>v%zy(540%ya5c?8plW~aup1u;VzW=}geurEa8b~Sz@F6za z^2eTd%TqkkFOMznJPC&a?e&p|ju=lI^>DnTMmUv8xN+$6v2$zoggv{>lpX z8#P9C!;&@Q@S2;7=`NM5MP3JAerflzuU&FrhRz8N3_v;ewRM%6Xnn!LLpnk8GT^6V z5&k}%`=bt1X1njR(4`~vR3u?^^cGRG>$S0VZQ5xNbVa9Ko2qZ?dK;N#IDA$BJoyN( zNHbc1Ar%mBS-0=Uk!zKZ{_QHL1{b4|)dZ!vC7f2@``J`Z_-+jWc^*K0ZIY~n)y zIG8Jhv3?12w3Bwoo3=Msl`Ey+pNIeLSBkrwh8C4yELnD1YA&F70FFQUOHIkMWWZhj zo}T{}A+|NGH_Qild#g8e`7vF6=ybjno6Tf#6S+B*8M|U9mC0k)jk;WQIt4}mmrkn9 z2aSFmEEgBsyZRP``BAh-5ZrnglF}wkTf}1nSeYN80psFIUW|-lXvMvqAwL^Z`#*aA z)6_gCViWgvo%sO8eZW&6vG$H$DE#q(@JKWv7s%dya1X6A_BeO7fnKHZ@sWEty2j;md_y|BEP?6%bv#>BV{ zM~&p`$nEt$z)I07I3LZ0l@66obRhez(E!kXO{2XNuYW)HSxxv2>$oVK2U`q;tdfO? z*XfB40nJoymxZ_9m628c&3O;#Qol-$A&OIL=%LY8R5z?fn1uHiJxr!Ew%usB@ho_$Fn63 zw?2QB)0o)YZT}F3=bki&cOK4_4h&Dka7O}GXOq9&js5gEUVX1_dj(zS<|7kTm2X z$m16<&&jI4ZjJkrvLeM2@@QvH@02N3ze|eV&Aa@mOv1xt z96+|2PNSfEX4)1@YfH>$QObE2u?(gP^x3z`Zyv?@*si=u16q(Qu~=eQf_8g32wk7V zs7413Q5yv-zA2!6a_0Em6z!9j*aBmIXq8c37h$Y1u1-3L%WqkWo-5E%diER2IKbh9 zJw-S0M>jbCbUgZgHPu-Bgo&eH5lC!y|&@x4ta zqjnE)TEKzW(nxc#@&Vl+(_b~2UVH#_ZSLHWd@3bb!bN>zAm2QYY%7uX>XmdrBiwhy zOoU&MPh^6XST$6_+JguVq_Yj+s#3|MLCeT7~g+>i@i_@2?DgpCwfccWQ-v zAeau3dpE9|qU&hWZi4({8%@nXfgZ^Q>Ii>$bgQbIOk;Cx{RVEZXWXxs^W9^ zO8f!Gp(LoRLKyw9vS?Mvn&8i8r?U*5KNeuA1ZQ#^SM0O#Pl%rjI?HugPV4MtYSw1k zG5Bb_Sqv$F%xxT4O`6~+#GN*L`1T_St~bo7_jU3d1wILmHdq_=@r)7X45@9VJZVwK zw(b2XNm9U!Xl*sj^$_5%w$Oe($eZJV08!#YA0XSGYL`R(pSba=I>+?O312ZMkx1v9 zKm+b0CyY>geI!DKbT2Q<*=o`~^$nc)8*(%KKF;Oz?W>RMG?58>I5fcF!`iKh_u*ep zn1L6?*XR~I9cL2*-0GwA<0Lh-h=U2s)l^ITc--(`Cw_(vfQ^R;0#?41249GqH~F zNPf?6$0)W)x0cPqw=GASAktr(Qq6_=OGLh+{KxmIK>5k8`UP3ZDO*lgMBuF5T^rsF z_Nkm%*3tAo-BjXa^H=?BIo@01R0%xsT=J&J+2Ufub-~nv32_i*doHrB{!-+xRMNDT zC2hfpQ|$++GEMR3cT&FeO0@PSH?OwUWJM5s`mu8=-(n>qTZxmg+6<;hehQ` zr!lv`7X-eXdDZx>-KVJ{h<1(mBIit8E~s@t8TVEz&4tA2-$h|%vfIkyoYyI2{JF)K z;LC@eVn(9RN6(`iLg%9q?a0mH9pSkShvSqTJ-*L7rdix7IN68Nt2S8d#rvRNxhNQn zqXLLf^w8bJ5{E46`mKC6=M{gZqgkM@HX6QbO8!a$BAMWE9R1>05}Dd%ODI4sh$o2V z1RVqgzLky_Bi^3Fw+)MBC2=I{oN_2iDvTM7P}J!h0l$})!3{em^u#w-6g7)hClM0r z9I@$EzGT1$QVo6_03`y}GPRtBe2d{+A;b1;SpeTzmhON2koT6uz zTb(d)00W;L;bP>>GCHlX=n-CgRpiV_eBin*JQPotB?-PVvs*p-hurCt{2~i z^jd=Vhr-CF0U^rPEfkS2G`Cqa1ZTo5b+;5#>xx1Z3P|tiwiU(6OEprNZi){C0_e8N=bB@}!0&CGz$M7nZA_oP;|ICq;EVc1oJi`*<9YTacnbsqt z&^Opfui0&8k-g`eVencsi1v}U>?C0gN8s#M3AiKI16(vor>H4u^2{NS?TO znv4MJ=VF1KYEav=aix|3%+aaj(zs&K%iSiLkb%U)er4yEm3+cCyz9m2wwXPW5(C5K z;`th7EFDMIS)X}CzVkF8eQAXzzZqsK{ED$p*Gd@G(*zZ8c&9`KF#+OQj9@B^K$JGA zDYQ2Nq1grXh(sQQC3+C-QV{v~^g{Ndx4w1-#a|}#SbRCuf=tOi?^`uJC}^G=NHesO z8PET6(*}>ku$nCn^VCLRZ%v)|JBg{GZ(nb4vWyfSqri z8IGw#pT9M?-h8`G8+EYQMY7iGKT7h{@W(Xhk5zMvT~f6G+!{>qGMPwIuF0jtjTb9wP~Rcn)`7`b!d5qbO34 zd(l}l+emoqb4^q%gE45MOAt|0KAH6Enp9HxgB6dCHuWM;J{@e~?Pk zcmvZ@r_(``;1kA^_k;%F=nPm-`hi4!eNQ7106#v9N;!pP#ySryF}UW~FI zzELBBIB}xF+@*5}b7@Q))5dUjXe2;wFW%c5CaU$ZOM;9Y2scy=I%3CsAtFm$_FlVe zek==BC}&GbulhYi=~#}sW#P>&R)6{IH?oZ@o7jw|6YS_3B*tG#Kv?YBkK5*cvSCWv z!`4dT4+DST_|xji1!GArA%x8o1b6!~j^_+yhEKgvNwtq2zNAf~Vi0EV&4v>|2;+|& zI`^&BHDl;M zTGj|RL|Y%KR`hZucwL`M{t2)+`N{#TZd#({?+qUZ#z-dG)t6^jJ+*Qg3XgH zo-t}+QJh3SJLg3MswLfL{ak!6aK#ihM zQpY`^jhQ+k#a4JI*4X{9 zE&M2eIK6zp4@6{f#O=k2*!0 z761sPVonNI?7V3^>->t^tC#fs(?GhgG(D-N*N6x{4tvd7+bO5U z>w#^V$EjN>zGF20*YMLpn(jdiSUHYi{8W;lt4B!AO>{Ka?k3QxRq!P*)hH*ChggMM zXD|!bK+n&R{(D12XAA(|jVhYFt9N^uESq@EeGb#_T;=YD8FXr2NQhl@vry+>UlT_Yfn-D9bpr8 z3Cp?T@YovG17A#>9uFJNb^GP)cfs4$MDvwMz)2tLpJwJd-Z%onE#my}Ry75RNKa8W zy@4rGh}>i?Bxy~T%IbQ7=kUNhnf0~527FILGoJAVkUs1kvgrDiYc{^p*tT2s^cI<< zEg|b)ebO3awHppja(K9t!8=NfZAki0xTZUUOvyxq1xMlo>{^S`GsabEvA&-ElRFGG*wBv~Q(z@HvBVS5<{OebdFTrE0sH0N0 zZq-`zrXCC?-MR(~VqeWP#F+)P{9v3UKK7$^fUZ2oL8-C~0?bbXFPWoTc4vL)UU=)S#snP)lj>-c_e=+CZZ z>YSRsGLJ2BzkYI;bbR6`f#pL4L>QdJMwfE%)j2{kl17!ZD8UM>b5OuW4mDt;V&<@+vJMd- zXDED)hHj-OW&Sm#ERIfAud- z!IMJYK|^BEs}&T|?ZO&H}U@7!oShW7E;Q$n#aFZok41&(3C~DgE|Vx&`F}x^Ff@jh41i0~)Z`94p)kbT?Av>L%Dx>gi87W%GVvelOsh*fUV5oo?#;wh7)t zZF|;1sY~JU=B3Lpp%jk15| zbhvD&8H_#LJ#NjjZSgoC2|8(38P^mp&y*GU-k}hRV&jlH80mOH=%a z52{=nb&|>B!Rx6=JG~pR99l6{xJ38sq6lv8+4)?24(t=wFe)x38musg)6Ie)LD_!% z3{_A6(~oo%ljEuG^=FO_4CDlQ)w*spBYp6nEMRL*=KV^}V4sI~NGi%NVQ+zEI)rm3 zMckInhA{cIcZkF%{41uW&_1@{WgYdiB&H&);;>SJfrB_1lA6u=tpCH*S-3^jMr)sv z?(UFAq`SKtrMtVkJBRKr1wk6=kes1Y8mW;+U}yyOY~OR8@A~F17}&F)=U(^kUTY2B zK;9vc#51*-clS)tQrV|1qq*1%H;gNC50+A~k?f6J#X>zo#0@}3Rw5`5*NqOk4 z;~{(|2$|JB81rGi_JZ%ZklCi=T=)TE8uE#oOIaclpPR?_e3VwZJ&A7 zng8)82hCF|JF}tAte8OaffX|vNR#L?Dch=so!C;A0kb2QrocNziKIWvpV!utz_AL0d-@@@j+tD@bKB(!92;fpGu&L7hW zd{WKa**(zgE&J3x;K5G`g${?$3|BFU%($A_&bGPXx)_=Gc@r?|(O^stgu3Z9ju!Ye z+5n#+=*w|H->fA0Mw;?QEoseozBBz9ZY<=Ob~G>ybQFL1Sb7Pauy)l8W-#i|@K)-Q z@~9XxW}HRbp43t|DcXe~7h#q@fSFL{cD#u=X;SXi^F52<_=4oY)z^0cz(V3`CL-u( zz!4yVUK$Z^?5N!u{4X$TSp_aTmHYW}c6Fe{itn3BPrLIDj8;fw^4=4cd28Pld$uMf z+fQv>Ydr5-LELCc*SG>SuWJ@bcY-)D+NE7}x-Kg=$y~RW4&?l6a~lbT#KOo;aGsm7 zQ_uFEkZ-1inqFgXXmW*ZqGSh)6}&2QPytd&sro5?Zl8s~nzo-fJ=MIUXZ!njh@6jf zf10BR320a|{16Zq(4nf%mHgyLRwaU00C@Fq`X8tjiO}9l+_zyOj8~9D_&{ud8gxJE z4y~p$^WWyXRt~(@%){NEH^oQO8dbV_H};$o(Poh6nNL$yG#}5uW=@pyS{11ZsR+gF z|FQrBZg89%GZkK2V%wZeI6U8P0-!6cuXIsW|0xA&GJY?&13B?sJSbo#7 zJO3w*$|ohpVoC@fJ*j%IX1_e5GkrY`Do)`KS?ab*niWGnf!gEbF;H;`mvH0p4Dx+s z7ER;EzImEexNj`0uPsd{o0_6p#Ua5UnK*jfbU7W=>CHnFitjiSp77M>)A72jg5M~!abw3{@dax#^{JI(ax!ySG3WOo#|{N%WvD&24H};Noe{=p z+`s3ZB>uRuEvu>t{JW_5Q;j2bkPj_hisI)$_GNx`)>TETj&|=8{jK{bVAQ)cXg8iU zqgi$p9iJUS9y|^Krsoq&_Bk?~ld#KjOC5v3_#V|?HDt8>snjmm$E33ikmIZXBDk|m zY*G%fI#|B{3gi=OfjG&^G3RvGcd;WH?7#oT!hQ4q<$KuY8+^fe^u+$20u3-uK`X*Qj|RA#u&Dxp^B2xE`XxX7$6ki0?$WPt^u$TXGKL zR1Ij|n;^f~9jT)7e#~%^FT%%HT3ice$lfHXKKsY@>c{y2bN`}!G5;kXMPrJThObNG z%G-{x|1p=BdV2V)x}MUzI@szzJ&?7>w#zh%0^bBz($_RUfp{Vu;^efzW_z7tV!gkL zbSY?!QX1Tv8cy1@^Wci(*i-k3d|bjJ@6$O7SVuGB$oG;T5K0 zIW|H_F9o+ns#_vFZx61#{CqDVb)F?Kc_8o4M{#&HaS@IAo64K@t#!`d^qi;G`T$ zV9To-`{pK6*lwW~JA%^~{xk&+2#}>X{#S~J35a&p>^$DE&52HTZSAUnrmV%R@^+P@ zvFz$apL#>SUT@f)IQ1h!=m*o5=h}7qudDzUc3*tz?F&sV!+_hq>f6<|hqM)mypGf0 z1ouu8*D@iaXCdt`_3y)(9^c=2|9U4%tY4oVeD{3|AZ_I=kKc1Jo>b5qiiCjJ(gA)M z3UvdIL{Q}@9XKM;e0<(_R)Whtu(bPud{aCFDv_>NuYcbT&yn4=xT`W09C?Z=Wo+Nf zk=J~YylS`!FDQ^o{_|M?GUkcR0nce6W?!ldQE z4z-;xA~B{sA8o1HvdDL}+6*ucR#N~p7Sk$3v%s@^7d=`vvKv@)KgaJuO$IYANU~hMzd~Pte%sID{0tgNqwTstvzI!MXrzcm&clnXFio+O*FXF= zHH>+bZ;SSot_$rkV^kBK4R!Xzb}--uo2+F~p+5V0hTVIH0YxG8h%~~m=)Mqg zg!i;TgNOJ+wGcLmmr^h697cBU)6vE}vqUYc+;MK)Hx{g+oycn%;au|CI+9mI2afIC ziY4~=+E0t7QR?y$5H=9#YvSFwdN+aK(z``yg6x!Mxna2)E%kH5Ax7?%*0Ykghpor` z0GI1~sg|jT^JpZ;OPoq9i%QOk#pIf%AX>49F=xjzP)ip#W<1C1V$C=*Y$D!}qk%U+ zXAW?jj547*(NheKa2(8|m?B)%Bk|y75!eqK!K%{wf2yz7yI3yc=}?I5(eW}cK3W%G zVb|+9N1K_k;J)uXW_*v4yRR%D@8G4s-=|kU*bD6l&t?IDcp&ix6%LzznvT;_jKtcl zs2FCVh*EU%btnj@`AK$>W%qJ2V6J&5);8d^>!^g-7^xi1el?I6Ir~?S{{v&bS8UNy zN$>gg9ItF;S;vd$X=WP8)nwu?DcgNWO>Zj9hFvlAoIE+bc3N^=E{d(o|G9j*iC|dtK}9cUjv1kh43H zJ@nSH)cRzQfc(8`pz6-_hI+H32!#J6%)tFsy%)v!gVX0jgZDpzzCMCh_)N=tkh zNHZ^hIDw#zTDuYWovtE~#7Pn~(3}4+PQ8MBFlp%9+t>V^I8=KdZ-DWNMV|F zZJPMOL222@&mp$eCn8+sn5cV`E2p;Rop~!| zu`k6<-)XZS5!9#dOTP5^Qh@`~DE`G-AC!=?U#qlIuHn*FW&D~xXIW5BdhiW-aFYg6jkV$85DJ=M) z?x=^`^fO=Ku~*B6}--#U%ZT4OJgBmG76WHz%z( zg_}G}*%k?6)(t(+U_nR{jreR_*x(B^%;e_QFLc|9!F`*6nd_O^QZNUp=^A#{uecmN z`tD-OXil5kCcT7itcE=T=Sp`7B26|7E!zJzHKK(6@egyR;0EQog?4}mq+k_u2H;## zgWjO7!sJ0UxI2E}sxe9m?3H)k6ZAdb#M0o>n3rD`1Lhckhq^RBxH|I~5&!Ug(?v7w z=wA1u3coLKaDQcdbl&|6#Mkuy(>8klekz?%6yzcR&-KWLhX04i2><<4 zAGqeo>`@O9F-S`dfJQ@F86+f8^*zpJdPLD@P#$v++MD-vRka@*3indlcuU**JyR3g zBE4sXRApx?e-9R+&!6&G&?jfeeuH1y|6Ql;kH5Qy1~0UR;WNo1w7|615MxTZSpwxJ z-92&U2PkEy@4dcSFMxM8^?7NGxYgmXFw^n69=SW24kix+rrHYBG z;}G8FYN1*aT?=@>-b`9lPaG1zs@n{PeFoB)p>Hj#k%d%KopJSrp|1zg{AkUF))3#} zAoR-0Zuls;)3VFJ`N&3i12LPbw<3|9cqYS}{R?)betGky6N?x2i+-=++?k@?T$i7y zfmXaUPqO*c7LEOiLZ?3ma-2~@8DFeow?1F)^H3(Mg@EQG{+N1itrlI~HJMq*CQ@71 zjV!e;ix`rH5w&E)@dg-x^N2(8+98{L0{~omXFrbZ{f%Q`7vzGlj@mW|3JNjVBulXy zS=BR>#omlYmv^PdSXU!Q_DP;wv=A^D#1|yb+8z-QuJ>rn@Gup`I+k(~w1&`yy!>`D z;CZIC(YgvlHFK+g**D_`$=yic%O8;z^RiJq9U#O|z$x|;@X#xpc))SqEt->F1x4;9#0giF)slTuFI$ z9)qL3PJMw*UTA-r?7~05G%~{^fiPWM?_2X13F7hsRVkZG@ng4-Th-+VyDgdMm33j@U zoQ%0kH^mnSEB+csN;*4sXlmXDV9Ntt4ETwha3oWYR^h`mYSlNRiS>`+-jYLv$0JZz zJ?;#k=`0klPep=mAPy2hz?>3A?&(d`A*1uSNwe3MGWnCU`7 zb_e>hpZyUx(Qq$2ap3||fmObO0yfDZ%x`JMeZKc7T;76r;4a4iKa2T4(;aSf}u8G#4MmoE9FP8;#BnAEGBV zE{nfe$nGp+9~vHBANs-Cu+)}Dd3)}tD$OSFteEk{;j(`vXy?e-Qn2)REd;(6gn!98 zljlPtD_7|Jfl~ER__h;=H0DDkRTVTwXVIW8pCGG405<8t%4TNtxf5*wD;rIsrEWOP z;Fz1SSd6A&Y1}FwIwls~J$Mi$OpN}~`xzF@VCDfP#^EIIvj8XSh7YC6l;OnDcP^hg zp_C#2K^3ytH}72x`8^QpS3Ym8DkR~lyAmoDI~s1-zUGwb{}R9AF#PE?#|_YIiz(K| zU5!Wn6@quqs^D>s+*e;dk}$Rec1|ea>BzV5wQ#rLqrN{USMxrXnHtjn?hvejyUUH! z^&LbLm~p|IistdIL1#_~q=k|%iM+otxCcyLgN%@4q`$3ZxBl==UYSsv4R37ki;y)) zjEVGwQeHe0V=v(&sZ_Vzx20mXMdDQhu#C8nkq0~_Swe7<4P0_`N?JNLy~xZ0vJcC* z#V?k86F2Ddu?tSpF$*dC{hdN`$yN0udD*F-!rLQ~4CTan$FM9u0D>q_)Ckv;S9nr{|$Q>c5 zAlc(j3nLQB`Vg0t>JLkNy9Qd`RpN%nFb3dL%=u3IL+dwGuw5vw_YuSQL(ksPbOrd8@#(HrjKyTn7z`w^Z_9FiD2g zhSx3E$y2mM64tEH9@U1X4KhWuwpZk=`sJLOt|L)1*9=-dfG5l{jWZ{16z@W|lZ4 zrfrP*)JHncUf?1DE_xm4p^G~Vv>@5rYEO9-I}|rg7TcVCPxYRo9<^ND>WeDWM6k-^ zgZH8qa}pB$%pU3u?LIXd{cUf}HA96wDLtMx(DJYo&no+&xs-OvYIxvB?JgQ!4{lJS z7?^H2$e~v{US>|0Vpw(00OM@1bzZ+rSmu#cgbN!(1kZJLA!pNBo1}rUbo$T87tF){ zj;=ppeiwa8Yr(}BCJIfm6$QAY>%khgF4f69OckhT%=<_~vTYSLO+3+S>*jEfCnNKs zbPoxwZli@5yuF^Xoh8@x`Ldr_Bk?zKgsV#k)K8iv ziez*l<$|PRq_&otLSN0FeH`e%Df${WnvFOx)_=BTufMD`Y4Y6`k59g2B@C*O-Bk|R zfv2TGsqUhWS}7_{FW1#RZkm<48OMI9;4`g(A|yM*3#v>5FRPhYblI3;O^+TFGmO^2 zV*frT`Dbq|^^(?6YCM03=$QShG6d{`M?mFPhpXYOtwwtk1vv;WpPrEAea> zkM|HB!->u1OiCh5MrL@vqDSv9(v~Cm?HiJH>sV?{8B4<+jmvbHwf)PGc=Gw4?$d_c zb&1EecDIqdwIcV7;e3`w_2eFBap9xZ zQQ~w{{D4$7)5SuZPII;I&#^C=vj@qr_Fq{L5})}zu|N0(X|2h=2#STBB*4h#V#Z0+ ztfNQ>)YQ1F`z*x30iyxK&h202&qnOd^Mv4}7k|oU#l|f#x$_k`cqv$~pji6*lcca! zvZ7^>7PFgktX>f}W(9D9gCh#05U*$w{^siqYi4?bpT>T+7aon_gCvoeFv765F5AS? z2`{i+>u8pJ51+DkLkGh^IT_GWBEhv;nY6bRd8bC-LH|Zjg^vpl_{^o;t5ra9Jbt}f zJ$*BH#6`Tq-daW+B!+gxne+KQUl1RT(iTgX@B3I+A&NQOc8yi5m#QJ-h)emaCnBPb z2N$u`2_4`G9aI^{d_vmRMCCAY-yd*z{a4$eVj>fZEm0&8?a@*_HuRSPC}qN zD$b(t)zG}paJ!Gwi-hEsBWFdRQ{E7VutFdVg*Xbk?6x$o#IswtG4wJunJatWys6uY4ZFCNL$1a@oCBiO?Hu^K#*vBgj3hd7@)R zv)Aw~ag%@1wCDl3S5tnO<esEPwpO6 z`H~k1G;(p{aOZ6+EGDBp- zLQiuYXFk49Mm1BwC_%0bu}ky7tlwVc)V*HqDpO!?*3H>zmYI)(j0t2dq|Y*x1XtOX z5UiTZOa}pIIoUJPCf*%#FK&~KSnu?jV7_e1Yyl;uf>j7HggM(*cYsnXoKiy#Urpk* z5QDo~pmkS5)mbGu+WtoA5z0O8#aPgVxKf+_t@OPgs2nLM7Q6dUwe>^4bvCb>CjnC` zPc&gEKG{dR4}^l+_!wPOpzJDCZ5OU#4EsO?H@R$PUnOrB;cag2D$~m7d9iKs@J40n z4G+|Xx5uMGA#zzCs|<$`S#p-@FW&~aGM%=S{zC0&Fqw9n_NkLBifMzi z8mUi`yYtM2xK9gq<#I6}Bb#LgAV4Qj1vH)*=PtYB3f2=|A-g9Zt>h8dyaSHQg6J~a zwig?&GKzS%&Sl3!GX3-e72a(NFa_Z-hZh!bt(qE#0$vBI_d@T8T^-0V7<$c}9hKJHtsc zAQnZYM5)Vz+Y;4U^FBJ?5etV&=O#P5bx{2~eSsrcYd>I5g*hKmvQ@|-{bxmUS67s7 z@MzrkJK@g&k?Oz2p@~vF74x^uvSax!T(xPaJp?V!sB}dwhImEQisx#-Fye?4;lwP3 zyjP8gI*GW)S}k!-V=|ApaK2|}sSy*w_WyQoV^f{M2;w-pSHav2AH0uEAB2Au=JiS7 z&%!@7Ett4kZae!T_Xn#fnv}gNDruPz?!fLSEazo3$J{W)kJ-(@*=vZ(z?VlJOTa^B zrL?^!CBCo4oFoc!qi0Mij{RL%jQY-Uj-8p7TK&`0gtC;P*ZGr0I3Ix=R2>y>*xyzm zD+aOvVt(VmO>(I}7TFl3VNZEqIU?8V{l#8hk#I_i>Wl5`o}^aFR<|BbO64=Dt?(UK zGuTgI+MC0K^JX^jhV~rA3v^~%ouID#Q)+m^BML6nx^(jzQOF3V)tYPSmH;0=j%jMe zLC%KI|0CB&tA&6#o!Be?zWv~|HWnI4(1lf zeP9ceJUTYv73nJ6Nr2nHwnb?Cr!(UtY7}-crbl0AjLXog=oJZ|IV4EQR&O+odot45 zneBY{fA4Kv>DE(`0j$1F;q6jjt4i+5$qpk&qv7a_Zuguj!w%X=st}PaG9K^Mw1()p-^5*e0Hi#Hch95VwZVYh;GPeHM{0h-!tzB=_$ z?&VQAf`eB2(T9G6KKb0V@xq1Iz=%W(u$fr!bW1Y3@mniRK}zG=Z5T7)#+hi z4IuQbTlD+CjMY*6td&W7vo~!3XrnBcdsJFeU2`zHcxgK{X)pGqsA3yDyN>z=1h2LTQ5$bU#5{eHko5^qU z%IFViHP>%9Ya4H-)l3!ArL)nYS>+lD0d`@l>YrPO9dh|v2Q3ZP!@+2(I zDM6O@-l8{*jqr^bkK)75VzHiZEmRI|&6+$#^O(zT1CSqyu0Cf2?v&uQl~<$q^C-go zCc}Wt8p&gk<5)jXBL6yJ%yz=7K(81250{2>bI3;6^ZGxcw5=3QlqXG8P@4{_ z9)8O)E3}Y_GMb6TO&>T&`@i-g<8m|poH*-ABdzd~$DjQ8{Nsg3$e>l4v6ka7aPF+w zy3vAqA3ex+y9ChPM9Zj-2|1gz8DM_Cknb)S)F}n%qpM`4 ziPIBlp(As=XQQ#`_|cxo^jDx^QaTntE%XojaigfBDk@=hU+|(RdT?Dy5xl-O5l7d{ ziKb$opu+pp!|me|BW=wJor@br6T`{#L1Dr}(v1c4w%R?SVh|~1Z1f3J=l5H7Cg&C% zAVcJ~S8WmN#N@ldw$9S6&10aq_{Llv2BXQ!R};Gxr`qZr?5h(kgJL((@+186SFqj} zTy`Lvxac0;iDrf)#9MmPJd{XN!~1f3VO-x*zVnTX$^6fEZ%z#T@>1k8jok>jcwWpZ zRMNZ$f3%it89Ft~w7Vq#`%JsJTjn(h(!*#-Mt6AEl;!_r0e)aKil9cNsE59y_`E$f zRU?X$Jo4B$?ER6fiNHiTU~0mbJmP5jv4ms}tyGu0D1IYoL#p|U22J{-G+$(vhM}yY|V}M5gan9M=@cz zrI?*W6aupLXN|B z87)2!sYbcR?3Okp$}w0rdm%(#jNKANP}~7>cg-gC*F8HYqve;8JOU*p`^DaHPc^iY zg8B>w2FkR_Wi~bn$hQ#XehV{`Jb@BgP>gk-gl==KR&bnbiKg2;OMAvFv2HH6j_`yK z*9OMXzLv2!=qDZsg9Jm8Ub>r%6~q&j9r9sV%oj;3iiNQYS7m?hPB31a_-#z{yj{#C zT34(>Bv+x=UWc6x6v`{*%(1reOpWHif!Rraa6Fs9bM}3ye|q#|=xjXM=xm=<%uJN} zL^s#oI|D$S7cf;*(MLdaP&32JDOx^%g-iYMhnwL&`f2Gl1eq%3`|KpZ$}8FKtn^E zj9;zmTg#W*N+))IG@&Jt$PFT2WO+rh4Q&Yc!CstR4n)|d4yvj^eh3vs9C)3hQ3LesW zYBFj*TnmtJ`avWMu|0Qdgi*&7MXz)%K9bS9{Rq%+CTxp7CeJ~#=eANrZ9J4}1xkak ze%st-$5fJ>C>%I__$Ja9ROry5U07ycbsSF4XQC7isO$D)#L#nOGVuP6el;A8e&gPJ zgdq-&@m6JT53U)4pf;h!w;(@isPZ~zef?W8vv}8|MV1Tak3eGe5t7t}q%pR`^O78^{w*@Pk97{gmrr`IGHprbHTCx2h_pYBe59Jt!#*>(m8>v6O~ zX7{~`a`L=Ut{BT_K%D%7y1WJ#yl$VD_?Z8Y0t z2;ek8pWQEo6&tBvYtcO#4~y|2m~c>$LzSnlv-X;`+rDVr^xGEzleBs8aq=JSX4LO* zYbEr28wwdE+MHUJi(@NFN&c&?8MOu5kb~O}7e!|B9+5rTLA|1FA>6F@R3cj)dhY(I zmxv8aZ2BA>_Hzd}G^&TL;4QI&x#q0EBV9m5nB>Mr0hgz(;e`k=R;Eo}Odx%@WNV|A zAZx$6X99`Utg$(q#{;k5`Kct~`=A+RFz(%t4=Sm@d<5^9=|}1ST^qs|Zg*vym{;rx z0W6>+X3>jcmI=@kK46RPN#F^uK*?LqnFsdm)DtO=@RJ>S;RH9<9pAMJBXN-G%Vgfw?GuYRx!Tr08UOK7?8T&3*$3?I!8 zowY5TiZSK)%*O&%-{V6eRl@=LeG@&OS5H=>cIu5>XlT~TtcDZEdufh6_HnY>zYJ>w zZW(mM7du}QHKHqXK4#;U%g^rZAtrklH>bVWp;itLiMD#ZtiH!CkS1PX@P$9?AI5b~ zN~_yAy59|>lPh``{i(kQ zUem-{@*2F0Z!?LtBC#J41=fyU+ zKPT+g_4n6{l#(>dY}*U7@!FsswW^pL^nIo(?t|~!ERr$yFG;vNSf+AwW&611v1HL| zz}HwRKQDfG#Xc<}42yrGjM8#yvZx}UI9SWqfE6{mH8$hAwBZI=zi@FX0b5NZjEAk2 zb$8d9%^z*JG*i1_J@4EH%~9V5U;#tIDY)buLmK;NFZV*H-|+N-mKhh-RRjs(!} z*%!+L9jogWSr*<%6!Fh5l|dzc5THY=k;br!|utF zv1u%Z5|R6elHKw%8t{pZJv9=CBV2vA7Od%W-U{IpIUV&CRrvKf=|9+07@M8QW1kV;ynPvxT7B5=(DN>VD$BX5 zzX~s&ZotQ%)s*PdJ77#L!wm``W*F)_5?pToRY8`g@f#T0xPF%bxY}GSwLoo6c%_2)}mZhjK}e{$Ny@CM9zx?jD%4o&Q-e0n%44Z+^!m$_N_jQouE%zdwVE(n1SyzeDM(J4hlDHQf#16nW6_@{Wbl0J=g zVGF_4j|F%b;hp6IN+aNX_m>?j2soU3nB5I}`bCdjWHj`I3-#Av!3$HHUUcz}82ZG6ZFA&C zK?BamOMasJ&p=6SX<^WzK+x(~nz<&>A0t2U`~9$m^%L?(KR++vUZ95!6rz6?FPeL3 zxg#%|z1oS8MC=fTdOxtY#?Kvkm$G%PI+ez!A*e=Rpj{7L%6$)UA8Y9NYXYjM)1%@2 zL-Mh_II1BRY2Xe~k=?}&2fULxWL55KT&<=gQ;l)@K(&%W`1H09Y*7s4FTh$3q$D9HlYPBZnmB^WgNkQ-twMy9 z?@`%MQ+iVH(-7M=zBTkskZU}^f|IT-y(p1Il3&u&T#94*_Ctouba4YQ{?$NIgva`; zCn{nOR(;s89EaED#xSNci7ZHrSw>zOqx^QhyXALD63nfHs9TDb1+pTQHnE4hqWT-P zvgd#w$^}gX>|8)y{acH8O#%1X7k%>WxG@AS9`|dGbyZ-gl4w{ap&zzc9nAvf>p#dq z%enOtFbza-gV+97SNEz9@gaR9uQmLWm&hFNAuuJ}jI6`BP$#j4Lvy?&%O{!I&|hO- zJh$qB$eZ%*afeoU3Fiqh-#wAfGam{{-Jl4uYp9(OcUETL-|nh94gZ42vcbPI#JVM@ zSaVo_OBbUveFHvIH(`YO4xXWfe})sqowE{q6F>~xT+!>mwqM`YVsx8*)ZLXG3?ulv zk#l(V@b(L0EVc1)E#BPNC88VtR(IX-1?z1-a%NrpyF&#oqB({{R#IJS?xBwX)f4&S z8GFYvpEMh^b8&T+Ktc|ch6K6x;!py>WR8pezkq&9EHh#ujrTb|H zr0v`J(XL9_RgQ=%Oweed=#3A=d)FyxQfZa@hb3Bg1JG{^h$%?t#LP2;?^vl0Cq1*>;lI>J@S*T&Wm#H z$f17wrRm$2n84%Rm!+i|z`q-5pCBtC+WNwP#wX_gu2JuuKq{HGV4fXSUO^Y8CmHx- zOb{gs>YD2w7MrBSz|wUS8F6WF=v(UBrB zUe+2N%owQib!$^C6|*+r)mmhWtQ9jDJNoD0`kv0YkRjRz_ln~YVje-`oMIe?umGFY zl1B#NThp4$Nm5;1%TB@|cHm|?;#8dGP9+$1;8NZz6d+DTcc1j!aPD1N>MN`tVPe2^ z`!(s6MqhMJi?sFaVOrgq%=k>&kKt@mHrd2LQxaiI7|D}h6k*H6LG$&lDk(bUQSpj@ zLxcIyhq>!53-lmO(f|!wx{@4!hu4N0LPy0v?z-vC{M8!gj#!0j12}%t1B^rD-8;HJ zS_)TI=OGdD-rtyI+r1eSN_3xs<&55OztjS-siXxLYKk5jU<)gpe@CFH=4uPOh9?fy z7q6q3xk0@W1di^5$dL1xn3xLL<*GuL(lW$eBcm>u%Z@AqrkR!bWE(z>LHk;m50814 z(f|QE_}_`gGG*&!atcz#%bV!J{r$O>Q&LNGw4o7xA*0f zNyB2Rr&^_`TTg4(2^;e&s(ik#a4Q!L$SzTVpv23Eu1~tKnM_mw*DY9bQGHa6PiRt`=ThgNQS_Z;FmaJ$A`}VM&UB!Z+UYT(9JT{ zalzN*>?(cgB#UI<~2f(Y2mH&gpUk3&(zqHqot2 z`>VnJM|AI)Y23u}S{o}VNix;KePyBR6!{+8Cj$&nU}o)F+LSV!bCeZEtIIvb*Y_I7 zX|`#OUmjj6#ArqW-ZWD@Qa86&4|fm;1fba~9XJ8pwtHfJdam{dD8*R`^ubup8EyYHPM0kHPZUYtJ`$76`8w9bnHbgJ&Vf#;1Lc!!k>}C zV;+@etb(sxB#&A}W+sxF;KOM@@y?ll11N6U&m(c7|HQ;mP;?snC8ACgL~UzzaZ=Xa zTf+>%w1L8NaCgAty?_tsTfF88i-2kDBJvaIJuir)s0D93fPIlMxEqs;j_=V*c>;z( zcR)O8Nw$T>+Ogy?c#elxLIyP_cyLru^H$_@<9op?W!%s(Jg)NywVKD>GK~CH}CD zWcirT$LSbjutp{5hjEV(tfVa|Zgpg63dyeTN!5f8M-g+yTRyUS`}1Gkg4e2)?1l(q zko%CpEc*MPY7AVaI%(0{ef^r=hc2MNZ!eo7ynrXhT}f(!o3>~oF)m&>tr#787kkKo zdq=8?Z-%0Yxf~pOQ?hw_Yj^a-407fUBNdkD-ACSB-)Rx{#7NC#k#*DqwI>K)Py2(3 zuBUUkS+_T*;NnqvrZ5%otX?Z7zos(}3gj6cH?S)p=>7u4#w;>KMFZcf} zq$q5Wy{^%-9KoZXbYgEG^S&VslqGn_Gj&Q1K&Z5Jn^hYP-YJS9hE~mGm(HSotYL$5YKZG-G0^ zyPm6{FQ#c8I1#0gk1=YGZf*7HTK~-&yZBwPvz9u#*-Tk<|CQMJ6!b1j zeb0;?8_ifM-R28jX@+%G;!eRHl0JPS^NU39^kXbZnn)E#!B>*h-j%wp5l>}36FXq` zJ+Jum7uu0hX$P)2kL?h$HM+HW7f0!;e@1uz5( zss_3XW@JwaxxW=&0O%4~aH>?N=Zpwk#61i0oF&Bp>0b2P_r<0`5TWc3PiCy{65ZRN z=$P(r(w9MhLgxu3{PrUR$*bH7nbIm*Yu{@s34NXTnJ5C;lHlo3jaYzL0*f{hL9PKF zAg)%!m?vkB!Al4DvVX)F|0HGbu2Xn}#aT_(2+273JF7_E4e^x+M;M1sWL5Ru_ zNoZrRtSc71<*`TR>XF9iMc?Y7-B2|{HshYnM66(@B{7%?`3AEw+g=1rIEdDY{5%uz zzLK>`?>s$l!v-{@RK$(WJzQ>pUM8DeqF~|OXxG61r;EseE=I1Cu2B8Ul#q);mR#>{ zb0X95(MF^lit9S&Px(s5V7&Ou!sMY5Gz6jR2j)z;RN%(BiTh`+FDt(RGdmHlcVdVG zlkb4jS*_cS5WcG1m~TAjSmYhL|YSXnqw=U^`gX>Q?#+w6g*p^7997RWp2LWk>4e8FW!b< z%)!OuxyH!M_v2&X-)Se6)UtE>2$TQICCJtaGirS8dgb{B+%AK3C|o0=sdVkioXcy^0TW{$WWV~_$H8zL3E2ABXRz;HhCeWFdkSVg@69ui~@j0{;6 z>DS%&6ee!yS)dkQf+S;jUBFAQx40}@J?riKbwA#}!^hxil2 zZB08iCH5kv-edni)J0X+CnWL=5622$Za>ZR+ytEIes9T*3iW^Tz}6)Ly7xZ$Tod@h z1MCe;A&KsA`cqxKyi+77s%z%MgIcCF#&|o(esDREp3>sFY2)T~vLX|bxiZc@< z=}32G{?F)43Y0U6?V8+W8={CngVFUy)ToQ4z`i60^hg?dF9*%M9*GiDcGjTYejTtt z`@p{x@!9LI{neY%EH9Vy)W;_aOiv{t2}LFHF#~T<4k-qR7p4cIK)W6#Ve})*KA0ef zWOZt;;e1DqC%mTwMu*w(9TFiusPu@Z2unYVW1_?@iXTj9nSQRp3hQnizF@gEh~u4d z;%CK>WQd^+`CymP02F?47-d`K+NLFa+8+FLkCqZ1!WHnX3sK|2Rl9=Qu-h?7`%SHl zc*&iAhL4^a(Uqe`P-{Gw7{K!dCjc?_HYs37`ys+!v(Hq>W znUJ}FirY4Vx7su}#3m8rB&R;=id4aUMh7`SeLiAse^+=&0A=&-$ke}3an1F!D49fu zg6^Utxd;2F?uAmyV+f5>uK33IW0gvW-Bzb`pZ{+x|jpQ zqlwA<#Fq4V+DGy$QgGEertePA`aRJVFgnO^z@%}Hoav1fG1rn9FSi}KT>-bQ6;JJQEJ)x!h2|7EW+IZ}=OVp*bRp$L7b(N>_RdvS1gD-i_Z zCz-)#z~LKth{V&8d?FssIJ{*k6aMu^2s4P-PPFKpkXlDcgsV3Zc(95@ zlWVbR0Cj_TJIhwbU4rH!JwU6<=mHI&n)_qPLWe!7FYgMr$){ela;p$UfLV`j2EQ&eDUYZd+{dNoD1U_1 zF>5L*kxHuCQUroK8Xsy^ygkdTfcr5h!Op&3BB8wqKKlx~nNVPNPQ zT1qTRx*1}S7EnM*86>1Z0SUQ>_q*SH?)*6q@XTS(`R%pWT6^smoqpHyTfwvWkIMen z3xK)fs(7U3GQxO>AKdwEJg17(fqR@{yt)1;5bR@DPv6O9ow;D2ny1~hfuLn5e9J-# z>Wcd@ao1z?^gBqsmO^gYJx+bg?Zo=pR+~%IYhxSx>>deSD1`^5m6PPFg;z@hgJ$l~ z_!aC+QdD5UD6BUV<&^ah`A-^p~JPzUBk+N zw-^l4EtRuBB%`z*DAa*&Gm>#)VQmRL-SuyeB^xor9%rR_cuCq*D!NEY<{4@1^~tGy z0FicYS)^xQ_V&7FsHOYPyHfBjpo0cOMB@;mSAeMl6j2shpm;hb0B_GBN*~ApMfP9S zXN-orr1?9yKOt+8>R}N;(M$0A)Ah9Znah!0A2sDU<#AQCCJVERefuPSlssD^BoKQw z$lTp!_uNWgc&}?gV;b=pVX;c zjPh>+1P{lsp6Qb9gfq0ouMbd0&r2MSyNy)Wu|TUI+DA$znEQHL-s?D7-A?@A#VC%;`@#9v?<9jWTQzkq5 zIiovKDc1U$``brp!O?zEkddP{WNOG9^YIgSAo-CKLiNXrChJ(|ROYsC>U>x_eHYI4 z+@Kb7OCD8YO>ccWsKLKm(D-He%4uq-*T+)gwICUnPkFId;}j={KC-^vFl>8l;T6O& zC5C{+`EM|2VnuS}m6qM47u^tE6(x{?+*gRZIKGf8qzt$9G9vo3wb;>j4A4*I20tz7 zQMqxR=i|<;>iM9nqzSB64(R=kt(%^T} z{MU0*8#1?j(DnPc9zu3{SW~}Rw7UhA0m;^lxwv8^C$h+bh`Z>NC)sR+X%Yk4*`NMY zo#FlOz;v#dWn8^LmZNh)c1e-`&SuNQliu)CvHOQ)|I%FSp8BQBOH!Wno~b0VG4f0L zw9LbRexi6{I-n(G9?p=NVvF-vT9~gJUdVpXHzohhO-wh{Tz6cK{Q+Ci?d$2q)#V3Y z7~D_o1f1W;dYBKlgnCu7g%ooViw<|mC0sRV9NP^OZ>w*#5%4Je+x?(-Ck2dFe#@WhT~Y$=O0G{>C2j&? zXBFb?J2j2XZX*UhvJ&G1V<;1|zfx!zbsSu|%5wsrWtFUB{4)K>)nlsfI9$4?yG?_L z&I*ETvdf3HSq?kW%bb{qLBHJ18$R0ae0PI8>vu#_4NhLnw0~A$ssY}RIhdU$DNXsh zOl66Enl*TkJ^`rZQmXfcd~Oxf6B9xU>}{#a@XC5`-iP^~OV-5wNi%sxG96vF)$3<^5}+>m64-6P_qzhFXub7wDt8D9{=UQ0hN8wRlR z&Oo>MP8`Dwk!$kJxOoK}?7YNJn_sNFs(sxr7hVnnmUs6*@>zVQgFu9=ATf%W7-~Ax zL3XQgm%Lz#W9)hjG|g$3vE`^%^{i!9x_9lJ9%*5u9V9#pPsXLyDnpjC^7kaJyzKT= zEZY>crA0Hxa)*4MP#*znmcT=j$7gqng;_F0ch*=_)k_)(Q?QMQxhvA03f!D_WAlKt zLyq;Q2-!IM%Nn@>BGQQY8P$QmhP+Sz$LnIf^xT`nPU(goM20bIJW-9v0tjjP;cvVp z+UYrnPcmH@X2PIe^!fU~$g>rwT(_~S*n%`zoXnXA;b%b7DOBc2^i|%|ZVquY? zw1s>DG`LcdF!`c@$IWeGt0M(GoDh}yfGmenV3TO zg+IhFDyR)bYY_XxrI3JQ48xfP7Sc4 znNc=hOpl&~Suux$jDXv4`TBZ(v&@4K7fmh zyA~1O68Ri0UG10|V~~$Z^*@VoO*<-F??o-sy&peCFuKkBg@P?tPQC44RW35Z@In4C zDowV0d>FsNcVA%zA_t8QGVbT#T_Vq%YQUmd$s{o1v-b(dGgIKVT#|u~!LxcaOlezjz9gDG3|Gn!5_PpF z144{7QD6H)A4LD&$Lpnm3N)ahy>B~F)>A%yu+;lR1)>(~WYJUDGTQvv$IBg>i^aPw zB($3Xb8k+jsRDmO2-WP^hu%cvN?6YQu~4<+221!^1;v%#C-g?}sJD@+@vtehf*M$o z|Ix@gX`c$CP>t3f(9^E=y>MOgVBOw`sD-p`e?j*w-H$AK&I%G&hdt4AcHbhWD8%09 zZfSugsyXDnOC4#0XQ`VwcGAa(H}#<87!85VT#M(bmV^Q0uAEwaDU5#O5C)8F zT->O5?CQw2h$JMbY9--#b<_1E1j;yu|B|-5Av3N&EQ#>+&%YIUX1b4qb&@TkjRTZ> z$IQeh#Tn#?9NuKkkFyW9rirZ*CE)A)jav_J7eB#vM<{tBj_p!(xbm}8CvWhaf79^( z)@C2~D$%(;jdap=bTdW@k5?qt#0UZuI)tWT39camB-F5P)K^BW5?F(eKO#&83K(P| zr2@kh+w(Ep#rMN>(UCmpALSy55APv6)N^M~S zW@>(96f9;ChvSlARLXn2&Elv9r3(pEcgGLBCo}#c@<11E^=N@GYLf(Ok4wOcb%&+{SZU;Z(uvp24`9=C+d|OX*_c2Lv*Fz#w*vrTH4L!7t z#De3}rNw$?m{^yv5_rNWjaEr>%>4Q_Dr2H+XjJGiX0Jfi7%ypkNYyr$ zo`IU6?{xV1yL!ge5HS-e$M8gtoEOAQrd~d`bc%1_QJxI91TlX$8`2TQ2FdC9)AMf_ z*`P}>NBXr~UX7jXykv&=%;S1SOHxQc!o z^XpRcY9|BgwPMdTs%A8U;q}#D17(Ly@gfwRvwu7q1V7Wa*Jm~0k8xqFpaOq?^@Po& zES)^TTr)k1mTB`R8`ar?^4@^U@V01!8qmwVC717(NTP5NYhY2UrmacTMTAef_|&)J zpV6GvZz&HwGZFa8=p3fxEnv@;8u_6!H34(clra^<9j>!p=oIE@5P#zkrS!`Pr*xHD ziWz;XAI`;>_PY&vo2aYDX?FiZ?fW&@@i7(1@0a0nWuzDoz}6cyWf{snzYmxCYb^Fl zh@?mQJLIo-!&1YBjFY~nhoM0ak}Eh5L_5|-*M>}I#4VGyBM(W=n=q^96dEGR1uNxz zcj8*zc1lVcT&6VQcr+k2z3TkAb>TB!7vA;cnppgzIH;dj6v>OR91Mw5`95MkwVW3s zh~BLXA*vWw@?l5qX!_BhiC;k<{+9koV09s?T8$EfPms>N{y{Hg{l%oD^YE<9=I1YE z!^IC9o4U247}Yh7IL(GmFf+ugMDuv;%Cml7%5$@R{R~e>z0V&(zXAqw<&;P0jG`eU zxnBl$r}xDm*2AYA3G*AlvR=?dHAP`X)ja_WBrd90KqMltDfTzAOppI8Rf;a7>mZh9 zBeV1#C7o6j{`W-}x+D}nSZ#`yWp1GshiLrbzAfQ81^p^eJ{vA9qCdZE%8#W z;Mx-A(Te5gH)({-IJrD8F82Bh-B+g%Dqb5nR}L{sZ6e$7+NiuUKG{j3HMLGJ^m7LV zTxQ%4--0oxI8p;HD2ZLZeJ|hTmNHGwtl$U1ifF~sDLv3~7wvIdNbNKK?wZj629C1j zUTi>-@8p}9j|}c^-s-Rd52IN{4v8olADr3|yuxp>q$g4OoxV{J=56lW@|$t(+my z?t>PELL4ly#{20c)TbwD5*?uSZrstE4r3v@;?oZ?WYN3P@-^?94mUb<@GDx(MgpIMEYxk`Gf>4kJg^rlGLl(>)5gNresxN zh-4v|2MRbbY_I&iNvZrT(!HFtI&cN<<1XVa@AY1(x`iYh@)(%(x zI6uJ2DuGLDJu_U&AEx6W5FnU-v0eAj`s|S<8TBq8y+`4%(cYy|n#NX6;WNF7Qp;p#>o;CujyZl|>g!LV>DN zU^Y#jFRfKCp7VS$*TvUbF0Zi7QsFXON?#S(7(xoGS|iAF7%F$$uVIup&#rK4KDibY z%s}2B$J@NOb-lB z1g)&df3m}9MqCD3&_zNP98*oIw!sO+sv#Ah2kGFmU~al1RhtquuZF(8c2$(PEuV&X zagOcjh@`~a2NUZpaqdkXWDG_WF}snU2!24C!<~NLd&!HV z2_CIjRj33g00;A3_y*XuK?B!adPb}VS4Ucno#Xo<71XgTs{b$C_jSr(Pq_BDH>MVk zdQV5BCul{IiVFEf#-`|zC^;IL_28z={l!*-fV7?yHN!$~J}7n0aV2=$X;*H?ON5)7 z+X=^)s(*wvZt@d%iq1;oB<+d4rEtiFw`nZl*(M~PYL?hZBb@RR*2!>0Y0ztz>oUUA zp}~!Uy;F0O>o1~f(EcKBMzhbh#kK+(;wfJiN|FB+THW+FZh z3&F)m_D`vi*#_IP6?jy7f}-HZGI$?tz^C;SKM3>BljB8Uy=2EAfo~1zH-tIP>ueR+ zKbdN}#Fnmj08lr)So9NQAU^@N`X$f<~GW`$4f1QE0B6++}xMsoK!{1O}5!?B)|MKbU zy4VWg40~f~K2Lw!$pnNVeZ|o<=Khr|TZBJV!X(zn=lR<*A^gEtDh5T{sLLml4Xet| z-=__;?M+);{1hrycrI+7RG}LCBxs)=jY&E=JAkO|E@IYRUTRvDwD-1{9HhK&qngqY zkyGP!x|BY`G*uk*?7H9lIAdZmO3Oc<2aa9PXpVX>$93S}LkW*K(zTF&F=mYk{ zt?^*2<4npfQ8w-dSqdLq6rr}Um4iYhFPtj|JwR))b8o5 zJ>H<-Y|J8oQGh2T4{ni}79R(L2z+`TW8TL-{ua5of+{Z~$MNR9YtyW(!WfT35M&ga ze36eYQ0DK0uU)nbfEI8(;F$18KfG!=1iJVPP=QgWTBxxRX1R_d?!^%PtIjF~F5J}f zXKxtg@G-uM`di`%YP>O>4_(zU0ZJZA(!J)6Bc7hQ7t9Lw4QNC>(5BK6WnCJ5t+XH~ zLzbUJqUCJyKbx4k=52oT_?q&N2gAU9Ac`SC6$enC*$XaG`Tb^8+ziLEV|vp&E~EL8 zF=ulqdj4Gjw^cd~8CJE-@!!zRXGVf6v+!4@+PU@*g-6y9A1dQC`lv25&sjeeW#L)Z ze;aIE0p?xVHN?5b7JMI1ngixLjmbu3Vcg;2-P*>Sc26U5u@q?z;NWk2*hUBwx7&YX zWiM8bLU_g=#{^BE%Z4x=Q=uQ90xOY9CjLbLXM^&wDPH4(u|DJRpQ znkp7@^!u*C&$>QKgQH@^@inhWvx-FY-E)A$S&v&1!m-1gp3Uwu@(J3=wajC5VA`l% z^;R@b2F!DbsDrO8S`T{tG=r5;=MLB5f%X6lg3t92?(Kf_IrG|;e_clOtJWV=x}cU; zh?H)dlpKIPNn<;~|7yBZgobbD@4v0d3B?c!Vy_5c&ZBM>(r23qOr#n#(eJLQ^m=F6 zvA{}&?`+;I5Wd0g!Pce_y|+3-dNwHr+()@fQ*>TbQp0pY=mIbr3hM%+V_1ENOB5C0 zQmSJ{+X#{Po+;iKs+xPe*qU_L(#1NP1xV1))lq-%zCIV@)Y| zzD@~odcbX=p3V&Qt5ux|-*f>~Aw-wHq6&dm@96S}C0Vvz;NJWQ>6 z<2wHNHE{AZkL4r%wX?wl7}3FsIUluRLqSuqpL z=y4!AN9ih`Xg_F0Tb$jh`@@>@8;nX?g=0N6q7q-#*ipW2#ITl7fc+tyKg{x&ErF? zw9kKZN$B5`%Za5@q}yR%LM|CLDp!Py6xBJ5e@gV3Kw=eXtopR4d^pV;`{aYcW&$Ua zIl)I~af`g}EVe&#n){C?#De&l7_0a!y}(=1nvm4o z1MFu9S5W~a3%7j@5Hl>&SaZ6@Z9d9{*aZ=!9y;K32Iwkm1Xq=`wa1URC}moZ$HU2w z-R)`@{n(MMX7EhPf20?XH47t?<2-zZ)k!atAKq</LdenIGnqG<(2hSi>1qwZ(` z799gUX2%$IG8OKmir_hRs0xspRYjPVg5pIR5mMPvv1!(CA1bL2RA94)QtTT*6*}Xv zwpd?(3SMN?If3pg7bXPa@4HqkXEt%4&#rtdJu55mV)FBT?)J0Aa^!wr3TbUm^~@Y; z%QBNzKs#cJK<<9g%V5f2R{4o_rJwl55<7f}UQ(FzgSYiOdY}KR=IdbqH?yz%k#Krt z1$7I+wZ%xctRzC{EjNZ{?EoM`4Qm(a{nmljVBkr4?aU_g^G>sqa6+(G10`40cpSMh zGZ%}EHgXVDPY^sgNVF1+T5Eswet}Ae6HP4kJogPWX9L@>h-a$ZsYnZXA)nTRGUGdX z2meD?r~ctQb(OmB@MNYbK-$Scs7MvmN~`2m|D3j-0#*}49##iLJ0V$p1ckp2;>3>{ zgg;2jplSOMbrLuz?FFnpY85Fl#oAqmC&e0B@U{LWto25x#Oy`~fih{BAsC7oQT~pV zl}|p91jf6PIzNC*xy8r03K39OcT(>j{v{Xlh7%|K;s`>*px3;XVYV0ki@eyVHg#wP z918|+*%4hiK@8~{5HU)3UX^l%8Jy2h35XROI;LK01j3StjN-3*&%^tk`7O5~QSIFd zpdw6Kv^=)8QdoCw=51o#G)LAuRV%l8;yzZcV9+s;jWT+n86JPLYS{|r-VCmPr2uTV z7e0EfmkA{N&IK0li7Ri-*HI8!yXRdLZr~iSkZSB^AWs`7+f=;i0a|caBtqZDb&6>x z;$7iyd5S+PZI>&Ap_joeJ}8k1;{vsNrNW-jl6d7io}y&S5K;?nqrnuoboE-*f47aN zADa@M!$1CCFF;t5bHeCFPlrLB#x*vtDCYEu=K3&qk4;dwY~k)13GO?F=Ds!0KU`qS z5ot#B3uP<4OckEfFoU~)w5FWb(bSW)HKAX8!K?=fBpyHwP;gqgdL`mzmew!_-NkV$ zZm4Z8&PxNf1ywnv?CjZ>#Xrea!rLREzAG0iVcfHzjb*x7hv~yI^=<#lm<}vy3X6#a z&IKoQtvb|)-n&7W77goD@;`38OnauLyRtwILm67JV<=F}nM>)r%1Z@bM`uY_1lmR| z>K3ltSv}CwhkwP;7QuwVlVX_1wu)2>tq+4KVNa!p-rZ3mhm|DXe1*KmQz`SSRmjfa zy%mQTIR8>chCdJVj+h?f%?3Z_*bxVdYkih2(RXnWjwuR#^-6})_dLs=LEu}=K{-{Y zZs3nXj;jA@)NRUo#qg0Ncvhz>S)aKRk*x z|2wQ+v)dUPifq~Ai;=+u%wzoL%$5f zA_UC{>vl#!l5k+0qryoQ%JJYhx?DM_({Tz9_XkrEF~Uaywl#xwr$2go0W2(&v5$~SzvJQ`I#qJmrNW84 z#}PQv`3rr4wt4iSeaVRpCLuZN%F701Z z?o(&8Mqj8{XLk19vV}qtCQ?Sg00`Zh$lMY!$AsgB{&dAkj|YZ@m_39(muR8im{FgLKTu=KN1kr>;sN9N7w13mquYDpmtaEUz`m&ho)U9h=qDLGHn2CyphD5(L2xj|8HPw7ZRQO}Y21C9_1W(aNIOYm z&&F?J&UoctGgW+r)(9%N1trbdS8!PyjWgZpL@Of|eP5uMq(jq%Mf}B=4fXw%Ye7 zq8ZLgv3ytHpA3HyU=Z;}D$eXgRxuwyFCQrd)d$@9In!WWh58wU(|t-sJ= zqJ&?2!@msxNNA){8<3i&zNG%fziDKRB3A7MVF;9_0>2!mhKN&86xhMUjgId#R;&*s zT%f~^>~gp7Mx=;{f3b14@cVwjXauY;ltVdl$|*^*xKr?>k1?0K?g6!nw0>dcpDVvv zhs~|c_T@WutqrARm6Y;#t%z@SgoE3wUTe@+4u!oUq;vkv-{7suCNJ~#eRLYWx z1mI%YXfA5jZaK&P8t^+v{rw{P3lX2wvhTh4^hR;Wq%SY34$H&odLsYtm*Lfkj0r%6 z7)zFKlJl`F_}m&^)m^N$KH3WAfXh4-8yhfuHNcS5p6SN#@;P4)Rr-wF%tHcmm@xY{ z5GduGL)8`UUPBTI|4JVB*$1yUuiT_l$sg4+Q@tnr@SS! z!DR=VxAc^`PW{xWfFn|Z*>>+}>YRGkNKMUOr-oJ98 zCr_7!t8b(n-h@96XD<{SEbJ3!w4f-A@<^=NT-ZqQ_%r`)E+kp(T_uu%U_QUysggpg z>!M6(V>-CDL%vmFhma>1d+KNPg|c9#z@~ipEJ#BzZBDt)ApJ!eo;3N?7_isWs`8Qe zu%r2q$O-T+1seaJp|Xo(Af?CZW=?!??c*I_%`j8%<|q)fHbt1^zFg<~x_= z&hiKz_f0Vn;r1~#jdbvoj!)QxyCdZJ51p1%Gn+bK{;vA8jp#y4F=}hI=r6E7XY}?o znDP$~OI=-)3_$t)&<@D@hjZ)^+iPv?8kx0wwo!2BM6fds#=MB#eNf&;vqqrM7{Xk7 z;#QK}n^lcBO}9-p@|e6JZ&OC*eA?U+ZN?Z6r>YQ95jirjLws-(mg^8dw@M%)C`UEK z`CMXYWSGb8HY}t~f3pxBxU8L+77LMQ^RfNB`*8{uw4_D?&6ENQ0d z_5FMO!uI6ZIDzWNzbQq<_*;A5v|`x-&cu+ zn>raKN8k)3B!$H0?j2{sYYgn_BZd&ZOnG8n4JXOT`5x#iau$){D^67c>lXbk2lKp( z!{8pFprx5tnb^ajp!FA0wK;83>8vjm_|`SXFcDQ|G(0gwjH!2KkRYSiIF2XTT#Sy) zn#H`yILwY2MQxV$>}W}#D?})4SeT`;WN#z2K}l+XSXTn$pnb9FB$q#_%bVYlr#(~? zlr=wZ64!lB`17O?DhtO6y=VBS!%89jutRiow@mD`U}yH5AHN%`&4r$hcG_lUwvSyu z=+}qVtMk5q$FCCJOtK_9c|^JHc%usq*8;U0K*2HF}c7stNr!YZ`n| zvU|>ZMi-IJlHMg>)h*`yNMD}cw+^}|qT2p1W(U;@a%AM*`owC(ruOsm)kD_4mle6T zv=zM5((0{^@)gj_%2&gMa#q9b5EA= zb5hpR8) zUiyM7P14(77`_~(UuaVIAHCcl=}*V7>;jVQVKvyv_Rwkhx>n^f58t6l3e@8n|Ebhw;)x}$=`IRPqLK9B<=GGD zr;iRXmH;BFM70#r6tPx(ClR({BzKwAzPIamnr3+mP1yl+$7Q*hV7N*M)Q zkIxC5f`>zBIIFiF7QOclb4Ek2qW)0sPBg3xz7U$*lCe(l%g`fvF%_F26gC|n>}UIf z$oWH|Wgp+MB>QHtVdJxq<<9(HgTz}>rs#HZt7@f#7f#x}AlQBTZq$oGyjYSEQ3iVr zzj0LCdj;I$RQjGNkO)y*I{8&mJ_Dg|h#CHel&K(|k^-)W%LK5~6M8-|{R zM{j=*QUB)iX9cpRnkO6BQYipd{;lVXDS4!rBQ;1jo^DpAz`vPRUJRC?chrCw4+RAI zBrR7_pBhG;KlA2}wTsf0@Du%8P;gLoLI?l6$HNij_T@;@u*o$?vLFW0e1l&q@K{QU zjWtRxx+=UX!rjWMxb|Yoei)44oP|7%oLbj4zQ@8CT18C+rgdsMJ4;dQeJeJtv|9;o zLf@>yI4-SaN!%Is+t1W53-Y0g^sV&9*r5(frP`;0^kqY<1Pk`JeToS?ckd4YvUrM7 zM3inCNA@$pAwQbkQQGR_k@S$FEkpc6O3S!5-uDIey<0>rQffU?uP;Rp;W%qqbm?ZU z=!lSK4ZLd)HHEp=uH02V3asm91 zPVFMn?ao~TrBxl?+1n0`s^5SLiuz+t^zwNZ=b?Q25_hgPALWk~B%?*EANrMfB=QYF1f{L_$haxP zynZBjoWfmQ#*giRHW3B!o3?b5Txtmtdt+ONnWf?W=KK)Kjp+=aZrR`z6>}ng$MDB` za7H;(i|j0XjMDN(N&$Jae-_xoaPFo{^6ufE%=idTdCr+hv%?>dKRIWXg5POCe(ZN6 zqT`KJyb|D`Y0FSKQ;)aiuNw^?^*E_g14)OGE^ZZ`l20F40Vs>vQz?u)v;6}W^HB-@ zVfRWP@mbL#gMXRdHO;YFfZu-TaHr1QhwC-q!OS{^g&4#yhj-b)So8bS2n|Q2`mUlM z^~nu3cKd1$*Xf#g+XYmVD1UfY=w>s~6RD8p6sng(Uy5%?DKCC})3Lk%t>RmxM~&sa z#Ak2ag?G>1$q!vv>Rd089mt>8Ht*x-V8zT?Z%&fR_!cG+d3=n3K4 z;k^vb3i52qUbfA)g^v=u{xdq6^9AqQo<{#?#any6W1+e95YKHNIDptbDzpF6q^+9H-Gv)Pe@!0N@J=FA%nWoFIGyke@r%&RUjN52WC)@6fCDrD! zKiC`AIRdD|x||-(&ZL&!uP!{^0X8)|FT!+~?(>WMhPelq_ZE`0>MabC6!;kRQwzR-1HC{0?aKiXejOp-vCS``d8Z z;#jNVSbs%e1zV$uHbct7$=n);Rbo??i6{FYJ5l|bWp5Vp86~TO`XosjzM@*9M|L+F znqd-NMV}hJ-AT}bn{;6dYtK-f1iSTm8vMru5fQ5aE&r6eBgQj)7JaQU^ES^Z=7}a# zH}A&? zG5YwG@(}q9x_UWda#;xyNxZDexGC0 zu&mOHKJgVqt;=;hv6ph@sd`Mxk>RSdq<#$3NM`3%;5VM`v!32-%g^zDn3W`_m??j6 zPPK{FyuJRsQmM|>!A>An@5fTi@yNt=#r`L48b&(+!eytO0oFh}fSj?Nkv_SDuD|7L z0}C2->>+kFKXvH6?kyg<>qxe=HUV5w(j!UA|ErUXa@5J70K>@1yCM;aH zG8J4oufJwCJ>#j#S2P6!FOCdA=Fti~r;VEBxmT*#)bbo%*oO!I(}zc~@mUuAGFUh8 zA{|aWGC1x4_nNBE%UntchP}F&V=U}g`+0GiN}u!_tq}5>emoP?uTVKz9Jf&2tUTO8 zTbNlNXjkPiX0;2`<^DEIm=Pvga8;sWGyR@%z`lz{Ds1@JpWAWMpmEC2yy5Cw!>`zqE%lFY z|0!L2N^Ug+dJ!Z2*OW^#R&!HVmazZ}U79=nyo*yl?J`ngexi98C@oWcEZ77%c%_!2 z^Zy|89!#}&wu?-|U*xBpo^sjzBAXZK0#|s}lwq9}#VpLvZyKM!{r3fN9FTKHdvkCb zpY&8c-!PjCl>PVf;Uk91C!yxX4l;fWW2oe`L#$^LE*T5Bdw79%dpLm>{-v~?oPj(i z-+qoRFv)OTC7ukI;zR(tb1Tb)pO;1X$lnlSf`fb9M8K+sn=|oTsDERXm)GY*sbQEw z&tX64^v>h>QUvIrJ$KfR35$5tV%- zB0%@Uh`I)M-FlU_q6feb&%Kuv!fn*CR81GL)Ko`nW7R$E;ysShs?YV5o=KhMN8ulL z4I^BCSsYE)lQk?eF6O)@QOg+AZtUS?K^5$Y7ZdLcs8<1Ia`U7@Vo&3Aoho9J2h6#c zGJxxF18@h3vorh=1cV0sH?8rN?}F}Q2sChd2ZHC;r09E}#xy5T&LF7X9- zKY|+DjEr7{$({hp5KF;ycx6l{;`j7mO`i+GMw9=;ohR^uju|*v@s4mlTbrVA@voLV zy*}e?0V*|d_I-Juqcoq7Zl3@7xnGpfAgHh3^vuZR-2`*acUY}6#6{fP=BXdu4(3eg zG5y#06SVlIhdhqWenJ;1_w!K?Wag?5Tuln_x(OFtXl-~}PgcX!vBN(@oq(g>@i%zZ z6xSF4O`*ImCsj^gvk145T;QZr@!x0GJUe0`^75;XEjLEcje>`HwgMLQtnDf{YrUj%D@(vk2)M(NKPpW43Dc}Y^0)~tf+H!UKc<-$| zxmI20BJ%w}${5OZMqUfrUuonKN|S{PO6ywaEb4E^4ioDF4>g17N5VGa@R1zm<9lee zsQKA-%=tv~yzl%dGHW8QKgL{ zYd0sO=U`33b?Px!aF5J{mJin3tg&k~{}&=7Loq@5ZD!tJyVRyA?{G6MI@%9sXh_J< zE^kq=irAR(cL8p0BSb6CPiAx>?|IqU7iC*$xg{WQ?9OAPyk$Qy1v9{S>}l$n+sf17LrLiWqLxe>_*`_ZavD~oC`JsrwqkNT|h$XVX38!l6oadxY;r_>;W2AbN@}=h9bW2v4%m3BV#( zeZI$*#;i460Qgf#8?YlT7#!RB7(&>arO_VOu-(+KD}-PH$4G0`(4l(!Y?VD0I-VKkwkZh!e-IIr`@}6 zLEXHq!%2$dY3sG>XZwq`7GpfrWYP(uNh1o6{X;->%^RvddGTfS4d6-@dPp90l+M_kaGkP3A#ooLkrR%@5nOSYFgr z-kz53+jQxG1bK*UlMe3f>5o9}au*X4r-%3QU(DHlJOn6d!|es)Y{DKB8`sFluJ7b2 zr(@Z#wFT8t#VRr0bodA*galn3`L38;N8~GcGDXJko`bsP<>Hb^8>N-0R!+;W|)Aw_;&2rs0Cc6`78@t4aTLaz5eJg6s zjO6qSjpauAP@AWCvC(R>GY<2IL;f6XO8`$uxfgX ziAE#RG|6K9osN6k;=u+-7WBOVN1ucg|JMt!-g+fFH54sv$L8P_<3)enRNEgBAUahH zh(qi4wIUc*lp2X3t9GuC3crCwO7(jC?i@GuPas`~$dFPI+g6G#>V<4Qo>_8(;Pix% z8Xq(Lf%5(3XR*DRNOM34mRjBe&epts@fSr$%U2-&iz?R z8&=NKUU%=(^Dh8Xv@aP_lPYC$C(LaHTiQd}A6;zs5mt(k6qINlIf96ynCWjzer;Nu zuR3^bzWD~G$Oyifr^})Ui5hPUGl;JNHpQsQ#UBUt8N)-nw-^9J{G#9T0WwSLX@w`m zM<`IAfXo1Qpb4HPSl~v&(-;m0^JM;~TEyW;YeF`K-qn`^F8)@DZNK1WI(vXmMm2}Z4<@R*XL|hz;&i9@?m*}0q1|t0fU(ikk!=p|rS1Lc?aRuFQ47J}>=JVDioStPW zvuI?{L()3)!gNi9J}9W_?+YmHi}l3Hvsp5>(*taA(x>_7Yy>C=VEE7Rh%YltF6Y%m zRsI*fGs>8PfmPvH{S6)^9$=o~Rmdyj^4Z{hz^5A8Rlqo5v1+SIaw{L|%*HzGCypddXjvvdHP7QNZ0Rs*{+3W3CRm z@0y6pbdSxng)zG4at9LPfw~rhb0h>HTUS?@r3}@NUA9^eM>?jqAf*|iL7OGhOYP@H z=UrPN10fFh-lbYb;ZuLk>`nK#jGg`uPj49)Rr^H^(~YEbcf-&zbSe#kv@nB&bPv)c zHFWnaD2O01(p^JJgS2!?gEZ)Sc>d4xewZ(Oncr}(bM3X)T6^uWk`|$qHNUP+Lc-;F zBYYOS@z;=f;xTQqPb2y%aThqbZ9Y^#LVwzca*djJS#UIkGr6pAz@%AQ&l4Ud2_a00 z;VN-G@K5Ftn0>e_HYRD5Y3lK$ZT#Khw9XVi)K6{VD6on0P}~DYy#(A!)_+_Fz1{*h z6lpwshkQP-i;(zaBi;XJ&+PBcmxKV~ifxl9lZ;TKM}5*?L(4y8LP07~;p~|ZKFzML zD<%_-b;fgQQ4(WmO%khTM1GV@R~C)DbLn&Y5-S&Gms)wih~gji;opC$xPRmKXZs(tgY#66zaQ@r~_=XH>=JcE=XbxZdExr1D!Vzs-x!ZTtra5wj>(oseVcpEPb)Jo}C zHKP0WV^YE=DUfTdw(xYSw?h4J{enSSB9v;9{;ukJ0W-=aAzw*EFK5rm{q^@vjoprg ziwr6=WQOnxb{nN+FI?N|fyd_Iun-dPop;4+B-T*B!h`z;f2{<|tXOgm)V2}$Ij)HzH~nKY4&qQ1|s<9M;}iKl_>gJWN#dveCfIWZAZno5{$d-^q;@w z!|HI4o5XWuFh0td{!{N}`f*1mlIka7@d^XaIyp9QQYTlADkVB4ayE#3(n>8v)GYKd z(jTr&5vMGMPKf15-Aa-`g-sH`XHh`}0en4*>$?$S^9h^(()1HRR?m>Jnv{-h z-Q-|K9H%<5OtZ~9=Gdpv_i<`R{jZsJy#^dlxd;OVnDF zRBRljCwls2Ueg=8JI!^TnX(zc>nxd?G3(yQ-h^2{9xbe4 z6WIEF{&>*nLI?M|$|@G)S3U&L@_hQ+Gm0-ZD%CMaV!Qgb{!V?35$8;mdfCbp@-L&8 z1KqTldSLjc>yK&4gxmo&Qg>0dd;8e)QTiFSA|wy8#&|a z-1ubfX=&;+H!WB_ym7X<=0kd@F+K&ZN@uFhu zx9sj=-F`fphi*xi`Ei&u*<-sj{wps10b!sRA5U<&iI6`^=e}D+npDy|XO`|(j4Wyk zthN+)zAAOFW6d%rOxT}h+%NstwS-)Qo-!WUvLFaQdF{N0yzBfx zFVV8YsO-{RcHtJ84^6rt14b3=OPaY1AcB+r8pjvei=V>)~pzzvAm#buv2>mQP_QQ-kU8yn| zG}mnzE&&CnYg~NxuRYw(7nkI)2kx@qHMK;#L1z#^EJ^e$g=HJ2Jl&$gk=5va**Ckx zIpPv?F5zGB>d&4dqj92UJH&3egBK|`Q$ELwu7GPvYC!@L(6s32Q}7zyEvY6(ZH4CH z$K!X(rUffuH|#Zqq9-Rju~$Rqh$tH2t~2onCz99JZ5cI^!T9|K5$qh91z#|L{ULs+ zbFVVy`v&gwH6jC9PaR|N!;I`kevI$hFT`u}P&j!?kMf50I-vf|zZ%(dN^Lkd3o>`7 zjgBuh8@cIx2o#XXQ5FAOe`ik?vRak>ff+n1dA@ayd-ogyUoG(!w*C%aW~==A9d9BiVhAKot|?Fh*W%LsqYVJsR~=GCmgp6hm3@s;#Guj>8i6uWd9`D<$}iSa*& z9dPRmvWhl@=t56gyMFQvwLZyA67908?y}!5=wHg6o8HXo-)G+`I37Y)T)v3N&cmtdr~0#CbszF z!vu0Pa>Iz>M){{!fR|mKuNO`YYLkq7Ut5O>6VJ}xi2o~S8tyC)&if^1VzrVfi@*~; z^R)P@zOBr2ns)vEivsY>#6*|luVxcpop!v+SjQIwwC%g!zl;a_vdyELiTqMHOg3@p z7m+N?f(b~aiap9ke<>Rz&p&s8Ry3lyvEX=Kq5lZ`9L|}_U%5AQrrNqeJsDmx+h;;; z<7z$$$E_3mie(D5j;DaW#e4O3t9i1?4^D(AxF+6G5FEO36du*x^j}^EpiV8J9LtR) zGxn9Kl3W$*)=F{7mx-X4B33{I&L&$wo|+6a zkPTg4OBB-2Y@LPFv8Dv3HOi!X&HhL*{%U2D0r_fc)zo%w+xk5RilQDYw1;AVsYo}t zM?{5Xy?0}mt$5HHB{9s3pw68RQxP_3uc`8VD-47CXY$@zSfu2&o}_1Yz<;J69ePnk zrqJAa+_y}V{V3n^<7wp}2*>TD#BJKXQp|FYwoPonGQi@0cBvq*4ex5=u-G)jrBgE* zFINr8rC4)5eB!<{msCq#D1LuJ?W|Tv{X%t#J9RWK#hIQcrdw^WJdNr@6e5iJ_S|LT z!QpW>gS-wijG3;vMnM8tg7pWxXW4G=f|fhx z)25PL9YsE|sP(5aI&x7d{A-G>z0odIkzDpGRx_b1Tm#`NcBTwrntav*u!?ezMw02! zN{8?pIx?@XdI$sma#<~DW@c}b=$ipDZWXdL+MQY6X1UQV9k~+`T(83%Cue+!vdnFv ziG89^M+)Vp&pS|i?ARDoo!>S&quMUfrz%JOGQ%P+JI($oaGQu0N$r_`L~oxXi7#pH zp4m;l2;saB&0@C-cTag{P{QAFwF#oVfv@7XVbRS^je@)Df5^p)XW&s z_KS-rhJ^n0n8|cTR0z~_{0LucO(B(pe%B;6_?W4cPWfKaHS0Nh`y~mX+tB8S1H+aU zH(eeT<%D>301`B~(q0*hzX+T-hL=u%Ohu0KMMEbaJzT4bjW^rQ@+n#QDw^CV9J~Mg zCOzQO<=ug$RMus-j@~p$toXPgz76`M-H{axb)@n0{qb*`VwN`|ZG1Ie_mxiUGLk#U zM71Ls;SWhiauJni!&9K-kn||<2Yu7V!{Ag-a&aOFC|Th*Dq51f7d27^c7`eQ=S8)Z z`={-@AHJK7qRZv$c-;ogEivls)Vsd#57A(oP(qEwTOL6 zsq}adg{OE@CeaM!^v%HLZ}@)R$hX&?%49MGfB$Mk$wP+x1V2{lP%>31T10p}w=sa> z_d|i^HFqE&{syqL=Ee2p=D)nqiKxJBoF0{AJ7e3B2w!D01bclNS~+K@DWO;)dC{$j zgS&uDJZ{6+XOih)cY9-WXcj_EX`0*`jIv3`G`aJqw0rGsHwW3RuufyL^?E3MjJ>;} z&@tSeC;lj-@RsP(W%%768#s>=nj=F^^H(H?cf(QHZ_yUhbmFbnIg-?zLXk6^7r~RO zDvD3-%=}2+=`z#iuP#-L^~ZPv$%cY6l|a6RvPxrnR)#*wG%jYHnvX5n(<1nZz`a`h zB}Ow$H~Y-yJH^2+^}irLgvfr?QxHfn04`vnlTvwnxJ;*M59IQRs)RvV=Y7(; zj=}aql~7C(k&dlCLj85PQTU17>t6Vf>~mfqct$ZHq9V~C?D+MwoYIU> z_1;*Tm~@!zrfdk3$MxhBRw|0xh+8jzS$h}>aBid zxKZk~ww8((xfaVZhuSsNQKl+4OuI`B4(!n)T;Yb*cDL2-GPYhUzi(5yaQ8!DMD<0x zW(Qv*Q@_sX_Ms7K?VhnIuyh-#lh)a54%(8#bU#Xc2*}<5yLEdMBFV{0N=nL8m~=Hr z@FWS8ql-E*9Py(pXoa5DrFpBTeoqW{-IcU01|7|}yAdtvT;3@5K?pAk_fv!(T_#;f z*O&i=be&-Gj?_X7m_zoC**3XikMO$+6qK|HWKyEWKND5N1g_ZjZ-?_1M`oue;GcF1 zXEGbJTmLL4cDhk1z#=>iWEh~wQ@RiNBCx~ReoHfDxolkBt*z}0+DsgV+$&ZsO)qg* zPy3K2p~&yOEDv@oDc0F7T{9+=AOUQs=^%M-hWytMbI)HLE5lEn?=#_kxW@|Bkwtn8 zzZ#yJHCzF%0!LC|ej{CU_C=FXAs!i;w|Uxu(k(z~8PXobLOq74sK9R-DXe}SFS40cB4)RDYKEp@*c8NQnDr;oTRqCg2 zRk5n6H7;%cY2?QLEh318@~HXg-hAmU*WWh=!xplHkXnb=;r6;yaYxh(8?X6~1r!=G zj}Kh1%PRN1-2U9?6-MVKvFVA-=-Q724Zf^pdQ{`9;6YeQxw`T;{&aHxO$;^YcZkRH zUZX~b_Y|+j1`{e}jR_k}DKm+3tSY()+1=&nc zG{p|k3!zzS?^#1|4dJ{NaVU|8`{&Bu9zzfFpIY}ex*b_#O+g>A4t0fSsEQ)>9X)cX zS#fsP+!-O(IYsIUnGcN#?UA5G9sJD(%gO9-s18EVBrqY>Jps)KLh#6;hCG0jb%BzS zVjlpp6-)~wl5TC(9*Ndp$qaG41fYYY;=Gj~C9Tz1)$rDF{9j{6s&1;2GM-34tCf}m z1>@o@u=E2DMpdKg34EpI#l(v&+xJ`C@0AEO{ITrf>n)|X$oxSV8pK1hBIiE0e2%{6 z$CJddky2P_=*0dM{4JE{imtKbJbWiI(@!yM{&Eif~ z$le#id%lq*YsK(Mvl_#GMM{_5C@q&%N4f;kZ>dF*^StT@;EpNS_Vm7_$><^PDc#j= znd)@P?BAy|j7>|OBc%3&%0^#n$eQgV)iPI)6tCCHyT(&_GyA#(y?h&)8qe1pqjEGne&iRNY}Nm=cY(097CkBZ%jA~eMJI0onFc84jF zY?2OuwFwnS>I=$*6u~3>3(@793S}QXf|)sXY$fAR9<-D^Do1>p4fkzHjR!8C2gQ$V z1(+5+QrB5dC-Tu8ZA&SF9^-+g?2R`KnaD1PXjcaGEe-lUzWaBg($FipicKY@$LMCS zZSl5@7nxgpf@8wrDBy$4SXH`6@mq-+ApbKai^u*uw;XoAH~RoL$|`yr-J2|EqUu1n zAbnMQPTPqcQjOY)k2Ex3oF>;_PT-H{J1^k5N+yqEm{FZrr$&2>Wn;jzvO_^BLYyf@ zmv!x3SV&&aws2S{@C{>|Bq_yYkZYQxx53WF}1j7Vxi;^+5R6Y zQ4%8v<3h^oqs@$!@5g)`z>95F(Z^s_A%IBQY2lY01@4h1j!aZanu6Uuk{u~yqvu|Z z%S19yeF$Wbm;p^dS4N=K?ZdZGpS(L-3Begr`v>&?gf1QUI@gaZl1M*>v-PhzR|;b^ zi@!9k%2nYn)s@`4=Z&eGKs4hwU;YcQk216pfmT>YbW_A?$Basf2OwTJim&>$yBx(f zf&x0uqX}$qAxgoy@vXy(ugpq#N1F2VklVVX|0rbKAdoxM)C|E53Zhj+GUG(E?$Erk zScHd1=ibccN;RLZ%&$4(Wwis)A-}{yoR|DDZ&tDM(GNvTm`x!4sl(J@vJffgd)95A zT!9;=4fIH8BMIzfzZ=1C>{3&YPw%8_cX>f|Kzd%AuAZ~Izy#MBTR#*_lZM9RvMV7| z!1B{sW--QQiKm5~%X4A&`8dRi3K=ukdy0=Go!AJoM5Ax`xACTAAz4<8PZU}1?T6T< zAp(BZ{7wGrk(yl;*YcmY3@ZsusGGuT$!i|=d>Wr`d~^v*-{VWnIi_~s6TBpTO~O(A zMhKyyW?6fdS46%PX3<#NXkc7HYAvUyF)&uKixI56ZElypuL zWTEz)C9Gc4LgxpFdR#Oj59jfdB6UhYan$|pFKZdknZs;4J%pb9XL`+0TyKIqT5hly zRbQma$09tQO}wI@B6EuUQL7nsd`D?4(J88DXPU8YM&otc%?{8J{p8BZOvao|)~R(= zZgfF}zX7V@`)MUa_A>EM#B2Ji&`A~zshhlENM2S%DG&`4Ii;FwQ;5xGe1|4CpJ&T& z>N%5yCWv$V`yjmXTw43uJuNl~rG%gX|L}69Uh@a0ua7&yPiAXFj z4ojXB4q8|c7BBISHiUQbZtU1b*jusOgtLnm=v3})120X#RaNsK)NB74BNSK-U$_dF zph>FN^e9<)nnahCg;Bt1E8<+bW7`i3frD{P!nR}M?5t7Dz1}2B79m4Y>~xqG9w>8e zkxXepp7b$MN3Cs}ZrUuZr8j)kW0E6CZAaFxYWeO56)$KAsS*(zGd-HUW>YMplSQSu z#BxzbZT>tpLSiFg(7a~SS{Y4zgxBuC=0t?t^OoS0F!uAx1;U~)&aHgYPc#KGuI zNp$Pg(RP?*`R%-|X3I3BN$P_pfy51OH|^+66jBLTGRf39-#Y%~oFLyyRs!@JQ~iBAImZe6`s;Pmds@lA zqAuQju5VfFmhIaArrL$9HxfBQl*qaP?7|1a^<`15fo#_e&o%zY<}UtlBP>n!%v&_$ z!eM+(H?#k6huHo(s7cirY8WutQ-{ftE*phmIP~E>aQ>I){r>*$bH^A|n6(a!~r` z1B^hNun(U2;`y4fo%r@YJMkZ-li6NaPd(In@0(~jmS{ow7>Aem@N&b_E_x`%fWypo z3zf)!bLpC5DbAu!q;!|7dXkSiiNQ%GBK<$tDZ@6-xd9KYaYN&>PEq}D4kWP(V>cRa z5sxf$E?Fgh|*GpJI-JTk` zRJf2wuC7Q=r4fM~3(sPDN>~vVfg-soVu|&o9T4Z{nCA+JFHDDcc9YNEkycyys*0GqpH?r|0^;#J@2G5tnfXm|4eJf z)>M%{Jli0Ug6p>s|?DKx~dEMuytRdM1&1fIPfku zXou1@1O?Th+@q$XSeX;E<{=m-H$G0nm2m`B(Oe}%C+YZG#s{m3vM2fKA4k_hC2}nr zzASl6&}w&JzR7+TqAC5Xe{PCZFa*GH4<&_n-HXl8po9b(cW|k`K@D@Bo_kMq=dBE zo#!2Q^;-9fZ5K$AEyoDBpMr66l(v2`DR0}c%wG?O9Xapjd==+jqOR+6_eB%TfxYOD z=a{|2a7yc6Y@)JREjGHFYyKl^F1i>qpHIS5+NA&gya4cAgg~0Qs8sh|N4^ua*Si!c zfRVmc37@Wn2H-KT3PqW$E}XTwQC9bVFaE1Kpo9}?@Ktbd|01CaVthRqb@P{+X zcY>!!1TWH!$LsFj7h9GIKY@QQvd-shQ|L`>iKDw8Is;#wXmG&tb#@joJ(I8c1HQ(8 zz0@L9f#`B0V$*Nrabw%?#Wv7zgS#h*{%1eIz%GaE4Jkw!{)Q=HE)XFwZue>!^O z6{eUN8I9bx{Px)$%UE*9<;4xE@9v_3%T&Z2y|z5N1Dqr6SyQSsZiW6a2XDXB`aJw! zEeN1Qz2)E5x8QSC@gOApu3&t($BM3I#U%dRb~ekQTpU^!U?MQu!}}@2N_Yee)J{6| z(y19^GXjf|34{6{!GpnR3}e@M2_e=l0Q{?SoZ4aXrwrlCHe#n=s5P&S-|nMJEHa0F zH!I-Sgz7AFc(~4H9H7)h2<=hp^8Gm$clCeerWgK(H1Y-gXZYy(vTk?~h1~dy@FOfA zDk1`{+Ap2#U)ACd<+k8SFDzbY*oKV2Rk_ED@9h?gyq1x2il*QG(%dBN&0U4bmZ%ml z^lbgUuzLV+-}*mv9{peX=MDNX6QA0V28{z69*J)5+3JhUu-15&0NqAlOX#viS)+_T zenDIzD!66=UM=4J=)oLi7?J1XqmRZgKsA%Y)be~>)u{Gxfx+2q#KXY2#0{;eFHzcb zH%!+!!{jZI7;kBofmNB{%LfrtG=Wb+^qQ2)Jpm(fZ3_qh{F_KV59S15`u4DlS zTPig`8J5HZMABEq-oCot#^icJXfUof-WyJlkyd1USPU8sr)zDrht^rgLW6E6D1R|G z?Fj?Q2a)~nWvJIn!^yYs)(X1Vp44UdXR05hiL0ZnV^^8{Q`@l2hB~3M0g3riX#3wM zN=eoEIoQr|xT31@wT!EwRoVW^g%5sTu(Wb0ft(>A;`s=lG;(rP{2T|lj^KFO4#r-; z&YbV%yvu!FPm}e*9v3Z|^}3w-ZU68vwFSk%t0c{xc5GOV72k!NfiPTT>{U!fk>XO1 z63)~Ieylu^A)#>o|I0}C4zb;2&N;Rq1u;~|ZeVW_{Bq5Hu!nSkDFV)pNY8KsrVcnocnTMoO2<}=6UTrN!g`Qy?Pp6vx@Xa_mAd>-Gj=qHO56 z@*DX)CGx?u#{-6PmQPnPQaf{gW4T@5aAdn0@`g>i?61tJPB$yt?ZIy+7fS$H7y=9% zo=Bn4=Eg8Yrp?4eOYO9gZeDuA>!@7R-W=%09oCJh8&ROd_}e$#TiY`QzvtqN9aS{b zm!0#=wTit=^yWbe)ICkU5-Ogfd-m4&DefXRhjM$sfFYmL-mRa{h6?^$26pla$te?c ztk*`F^JKE~b=h?K2nF;YIl*C(V=6CF{z$4n#<4_5Oxt_L+T99w4U(lA<8o_h%dWwd zSGEX|myE_Kw7{MPN@@$XGhcXlXqv~MN^Y_ylAA{Z!tPM8K?5X1K5euZwx}WA>=JH!Iq{;Wi_TS90c3@b%t5G?dJPx~xy) zWLxmO=Lr=SzBUnZ#v}hh!m#d?;?j!;;UCWldi5i@gsH;y*+B3;dn9pqwm;6tn_~qf zg65c#amBa9HR=-(h`buBI~S`>req|m*NS5*rv*Bk0w2wuU<$8!0Y$i^o@lp^!H_GO z#i2*?w-}NxT8r)yyt}5rqgb2Et-;21c++%E&H?9U7~>e}%jX9?A)rWqJ5_^?gsxI8 z5~En{Aq+yt)sG6LpqcOeBIj)8_upLVUe=7d0|V?crZM-?oCdbZe|mE28G13f-Y-+J zXh>_QeP1I}3k@64$m5Jkp`Z&tZN`1Z9aBro_Ke9_x|f&r2Sos=tveV_AxOhdhtE%X zuRUmSlh1y|6FaV3yK3gJ;E~*4m}_2b@?RJ~F4m>m!oPBj(on_d4UtV-c%xpVxK|;A z?mYxR%RXw~cK53aFAi~ejCrbg7h&e@Sd7vtAGZzDPYGU>aU-d=;5JqSqWV-rz1Spd z>#9_$SP>&sJfQT`fAqsCyZCuHUb_LR#1YU#<`J^v(U|VAc9Xh-c_+uKPuSlZ8>l6K|jVCN`eHoks{Vs_`9MWE)l zu||r9QDEKs7UW-0PDu>&c=1uoPo=?H2hK{+K#Q{D>{X^z9>B#Y=B3aar%-@6(v~Q1(eB(*X6~WAXqUeF?!*M`7?DHh5ft&VFxsqX`e zpi!<{E%W=}3%| z!@2R!F1YLbF`2h;+tAt|`e)=tYyT|b#4>7~HxGXK-6~nK47i1beBnX3dH)QE>!=t< zCsOgJU?k;}7@#*2aW;K@#0dy0en6dDuv;!kUYeG(Hx6ukR~iJ&VaD%U4Zpk8Ut9Tr z6(>zQK9G9iS_(mYD3xVY3Cyq2la0FhM%`(gt1g|E4%llbcKD`dRC4jW0#zVrHO3pv zq~KSwy~Yd&x7+bPg;NjgdOA4LRiHDJ7s2}e1&`ddzg#Y9mIGsm2AeGVy`9oJ8i+|l z6OwJO32I(KGRS}>QuZ=Cd+D>kBe3Mr&ZW$(*<+k3G{6RyJ>UPbs15y}r>NaFx3<}( zB?5+oQC^=csUMwTO#JVhIDazeSC@L(iG(YUon86QEik^X@dsIIy*k}eL}tvdXZ&V* zRna@2?``1={^>4&a^X09HU+Q5o%>AQh((CpE!FS6`s|$|AU+PoLYLtdPt}f( z#pbnNR1c{101c>`Cb**iJ&-IWR5~;kv47P$cjXiE1M;31kPiwZs)XtVyj3;=?yt`L zJUXRI<-MlSv%x1Zm@S3H*uV z!#Bu8@2UndIL!a(snTK-{5Gvc2E-(#hZ2qPBKR#Y7iC{yg9e{RZat8nw!wF`(my9$ zFTZxiPrNkS7P||DV-rp>80ZArY~Xdwc}%LCetSnyC2Lls|KT*y?HuoKsf6b9VW)b9 zQ`Z=b)xys5e8*MU$+-&PCfNrUvIRaMMymZNb+|4Tya=VY9%h_%?1zex~ zJhn*px=_;g!tIF7jxzbMS@m^O^4}j0fRtMw3?moaHq7SVHzuZ{%#c9*Dji zO@VS#@9(;j$2PMnHeRe-)ySkeiVoMx*c|G}_;Qkwmzu+#-Gmsi`*NbB{xTR4jdikZ z!*9Z)qIiyN$ph=5*8K$k@TtknoqvO7P1HJX%`xJ$9bZmUzJ0*OZHxSAtTf?p^nTY8 zaTc-4;U?~d&p1ZmjSWLV(Lg=By=MHA@-fGH=~L#xN$a~Oy2MEkE~k(ter7C z=l}tEeKubs3$PWlYcgH0sQvB(JEj;TsZie5-$fwPeu^BWHM?rMK>@!3sW$i-d{jh0 z%7}s(Kt-_K+qVCdYF6Pq1`nsNhHC-mM_4(y6wO`+`t>QNnJO(bHWKYOHBDH8opUM> zem03L-E*tPZD_J3Fp(tVbc301}6)xF#z0IVin0M1v0T~ zWJ}s6zQNnk9WLXr`Z6EFUGdW|)ciRfrL4XYo-4`H=3=pr`egN7pZGU zmpq7lPM8a>6hO)E z4rgDIbsmb~-z>6<%aYqHzJfvRwMMp2fs#Zu#Hf`RiR+e1WQVN zxCWSYeoT4tL48nW^kFsOs(7_y7&V;W3n8NQSG8Jg)DcPy-g{<;?r;Kn4+Xqx=65cjNs-M=Nhs*pHKb);ruLi z_u4-HMR@aq(>G7xpGK%HAu>Xz4EiukWheIl$E0q$CJ-BNpW(qCr--8TKL5@_J~5Ab zNO~xWAOnp4t!?wTZ96@WRXgM|zpQ<)K0`#``n;z`=qFac9gq{#AR=r;L8XxSe zwJnk5))uIkb_-M6Z5E+W>G%FryScCy2*-D%tq@}tA2NZ~w3H#6Cv*GgyF6oMzS=KN z9nb5I9Bgt8j9}84qI3wP)h<|~oqjhv!q6e(^XRACgj_sEkAU|3Zq>N#h;h5dKl1-; zz=cV@MmwFNd7QBRKh&pc-oeN%$7}{}Z~w>3N`TrC=+2 z{{a53AR~6;$!QnxbMER%b=zg4Wj!MZplirJ#y;52?_T^{?zf4)CEfSIB9j6fSZuM*x$a?(fa!q7Kr)TedG?=J+h z{PBP6p~f-;=F;)KNB|62KbcwRd$a`QTq%a6kgQ{8_^TS0;BNZqij>OAMANQSv=cOO zl8U{t805IZCTC;oHLJ!6fHuNBZRAiKWy43IR4!Q z^rPg1t4pzA%6G+dNmThE1S!1wbCxQUeRP!D zK6m&;|6HX1nnb{xfA(GJ{#vNYUircKTht+Rp6n9SuuE>O1bCWxn}DeB2hX))Zf(ad zn9oCYLj)kTqk$Z0`*eZH9D&g+c2_hY{M-0@&esmE=Xr+JHnALq5>O*Ri(V_m%uOyD zh<+Xy*q%eod2cE``gm=*DyI6Sn8m*n4U0CgNdoWJ8^Nazp5pbOM^x+&-0#f92N;?{ znWnj`z8pKe)ju0C8%gjcqTcPC!bNtL4IvdD#R^Y(255LOrn*=O2?MvnXpi*f+Ip)# zx2Yu!!6?o#K~HK50M%B8&%> z@!%ba(ta<`chqIfKvEdZz^~O+Yrat6GrcIsHv>_im^qtOMc4c>QNq?h%n~SdI2f_@~sEIF#q3 zn_mO9VF~1bxL<&F1SV#_#t)Ts6yIT=_x?J#q#GG$mT=L(*=0IF9Ei@esW%031#Ete z*twKxtUKVZ_+*LpGUQofe4^>rpwkOme4?v9Nh7T}vc7d=sP)E02K&`Fi^lQ_u7Fo% zn@uzD#sFAe6l@tKJaUbRxinef!L(-3`bA4<-{WT!t*UIGW&1#}lE?*uRU@OiD9DK3 zXUqFz>R$PPluf^_aNO8OK#(k6fwwA@6~F#3Q)#d1op440;i3L`EUEOsmiLReZ}59$ zOS_cLELr-TLnb@~bu8^BiDFvJ~8T?P{SESYN*sB4g zH+!StOlU-+G8I#>{64q9!PkoukKry(R8>>mgDm0G!vFr*JSWtklcl`X3;!r^aw?^! zDWs>Zg)RVGO6~&v`xJM2+|~u~dMrVl*}e(y1;+$mO_e8 z5Y<2b%GoDZPN!c-=6!*fh zM6n|jadcWX@wd;H0)A45__EGRo86>Y;Gk<?i4=8=to8p=xUt|zdo5|H_gNzB<$ zbhm5oY~S7hZA!+PEHK%Dy>)B34cXVVgmaccfxM6mCVF5% z9IEUdB$|YB4ek#B%Ng3Psz@r2k2jPXXTHn>LB%H{7g58eSFijIIXQMzfT4}HKhGL8 zmW}>5BDIwZ7$s&q3w{twmNkkH?H@5+1`*BlcUFKr&*$-M8V8^>x`8~^L zpRc0hqw^l$Y_yrLVhvfdIwicONfR_gy~1i|Ss=S)cOp5>pIy2b!*)kaR+dN3op)`v zj01_Az^HEfUoR8>HxadprkaN3ezsh}Z)8@M!||6e8*7;s@ID;GJpz&Ie{`O#h9Vu+ zLY-+uOatZ>_VdGZ5dh7E1p*rF%a7+Fybav7@Sx3ot^k(@EJ1|K((D1O#c%m>8G&F)?J_ z*j{Q?3_r*kx>)rOgw=+MaWEvGO{Zm;so-v2qn>2mc>3V}3+CzTAAVOKUPF9^iF{7w z#;&E~(rxmt28sM05NB%G5wpv>piQfWmt^yBuQ2}l8TFggv$u(Yg(%5Au(7h7pR}Ca zKYrJNc`}<|Qz&+$?TZGScV?e`?(j}Cd{tk=DPnEe%w$o(2?&eAvI1C(XQm5yUn1q# z2buyy%bs{ye*!;_i>p&Ld;=65r7bZ$+)F2nidKlt#F=oJ6{Y~N32R8*PTxvxEr`M; z-e3&}?F7EuD`oY&!b|7Lq>0^0OzNWN$MUS@Nupnq`)>ki&#T$=PbI0_S+Nn0 zcEUZ9>77Tl68m2(3KyG3Y5#;jNjTFUMYIsj(u}&^ z?t$Gu2l@-o1}y4GVWhAdpLXI_<6<}M)Tz~45EdmF#i%ShzQM^0|4PXmFAJ@cr)toQ zCUEAS<1f(Lgh2(F_~afW?>i~ig}lsQpUHn2RA@o`y!@8sbgt_?vH-wZfC;6dHRf(K z53>kx3AF;$+KQ5YfosN1Az5w9@5NkApm3wot!7X;pZ=Ud`CB14^i*OIW5AG!1Rmgj z1k5P1>L$n<5)-Ey3fNG5y};0755?@`E}zrz+ob^BxAoFX@Kp`?&dorWMqrivw&)*; z9YB|Z;p%e#kwI+>vjKtq+$mX(hNN)4xOV@WBbktdz7B&wd zS7TtgxVyjq#;*@KP*V)aF%|KP8)h43-`6*E7Aug>EN;>Ua7X)hM^DBxHiviKG){9!{`$!1M{q^Y$c zJ{6Dm(#78*LUP#J&V{~n{+;J5T2C{Bc9#CNFXJm6AcCT9*r5~TjWwglhZh9JiovOC zLHKd74u06unv3AxChW&=SVb#E1P&*0KJEj!AY;~@O zg`q3OVMpBCO%a#M#n36}yG9@Y6 zT55>nGiLG-31X#?L?%v$GWIWLk$Ec61_c0w?w=fT&RGBeL3LKj$ASM zea{!G=3g!bl|w}K(`tQ|v+w(&tb&QFYw;@AO|W6^uhe28eR{HhD&HlXUD*@%tr=WD zPZuOIBk}A1c>zWPcO>4o=%~%Cp(0hQ=0BEzWOz|l89=UlAAb_wDFjmQbXS}=x5?~A z9pQ<3(a|fp)BPMTb1|8*ueE3vBfahU6wKuzcb8PgcSXF%>fQl+I z6zxXjAYhNu9UF0s$KWV0F%51j^#=ssYSoB0xD`#cR#b@otz3Vw^FD7ypU{l6fES*L za&AdMQsrjs=%lqS9VvzOEt)%qqP!A@iR(tEaH^@=cj>%E4MP0T?SnaymTzN*h?n%X z{THO2<>NMj0-2464mx5@sn*Bqg2U&B#|`s^z3Y4V`L{K9b85}cxPYA#%KjaIPoswJ zNQLjCy|UZvZ9#N+$StZ)OJ;1-HVntdRWmmG=O6DkeD3n^DsFW0_UTaPu{;=U{L2kW zIUQw9ND@@A#?mK{N9&aa(sUinA-DEVp!|r+r;+US-j6lESCbF{C|ww&eXdo3&O+gq9M*sDeeKJx_d-j3#8E! zVw0Uh<-I{vZX3}U!gEnwzxGA1kKE6pOy2U8H>@lv1v~bZ+Q}<)XOS;M$1}DU972bT z7Ta4AtMhI+Hq0?%qh)bEtp-T=oj9nyl;aihRVV0Tb{XJ{O9VM8A`KXMYFY$l&Q}O5zXV|4Aj74SOjhe*_9yq*`&PJ~)b8Sd`h& zhm&xQq8_EdN%Km&Zvwm5h+_pK)5JTpCawvz2iqP+1sm-RJRentzhSIgo*y%Xg$Q+j zO1&HZjCCgPF$Nuxt~X}Gpy`LntbWLR$r0U2^?=jl`UnJm1M2_Tr!jR4Z1C27{_PNF zpn>4NPW;~l%wNLq2lo~Mvhs53sJ0>OzX0vmd57kPp@+9l;ysKNXjaS_>&YQ(!fhXp=`bzhokdhZS;)-Vx>llwq zZZ=@SP1W&TcK^1*v7Lk}Hog-At?X~gtPDvI0_VCfV_nzXS}L?}BG|-p&b&F2`M zrKOWil-xmpImfWZ*Z>c|Hsu^hQ%3e zO`^C<&|r+i;unsR}fKqcX7EgA3YmpoXbTE<7WZ4<|c%mz*dU1 z*(!v63m;E|QnOWjmhpbr#O>a&f!*);7CSl~%;&6NprH7!KDufa)u89Bb%)^&ptp+Ww$N);y%jOw!Hr#KpFW7Mt=kn}4TH9LWAq}x! zSWMU2jv$h>ecG)SdZwl#W~a(Gy^LAKkTLtWT+|q5iNzsUEbu%-$GxrJMH|&ER}u;Q z;Q@iA_5$>^&Xqw+!gQaF(-MXY`wooUM93x+PBs19 z2^7Y)P-X+jfP#f-?s?3<8!O}ZnW4e>a_bKJhKO&FL0vNaG<)i|yYeI2+GdH>mlv;#4kDRYhR+!ibquK|coCkL~}f=IbEDGNLcAsdPw&p@c{= z^A`g6=ReWz_=EM3&q6(yDC`+p8=v@iL?$#Rm&v!Q6o2jHwQ&OKZ3eaPp!(8_z zR_71vF}#a<73sA12xEJ64J+8F@#IfjmGw7{-l-o(-zc4FQJ=$fx~kf~p?X=lf;Dq{38?h{xWrf23Z?s=2DSpRD$3&vt2xG zYK0qxFB53o)2ueAuQ5iLqOjm{U7@PrP|-<8&4TAQ%ts0kE??L?gk~j~~^{^K4plcpc3q0{r6bJ5HdNHV1IA=e-WQ`PL_I52NW#I&rN-p-lre zn9;T{wcr{aH}GlHv7!~xd%@b34K2rvRTP4lB>sk5aPk*~R;QeRqM}=Dd3r34TKcgT zI!-|B;2a*L0;Zb_AxTa>8rsydOu8$qo4TfY)>Tko=znIfxEG0aRy-!~qZuq{k$GQ8 z%U66Kbo%n@cS+jp>iGku#if<^dPc;?S3M z6F2txrD^%^6m|p)!R4$eKm#4CSW(hk-DgkC#~i!>YvvWV6-7$W6CBv@7}eWh`{{TU}sHvu(-{9(VGq=Vc(;pCOScg%wf- z^5?pAxJ4K;7^dv3=5ykz@zMJ6cnbI-Y$7M;NW$9yFx|eHg9Qlf&Yt;b1hZtL;QRW6 zxDM~1haLG4laM=n>K_kImTr2;ol`5nB|LhH*Kb4f^Re8eSHqO=YX5X7R?p@gxOBi5 z?igAMLHm>Qt?vAIUnMykf`okO4_La1 zLF6(N7mPD)1NT5TEh>BYEhv)M>xAZ+y0ZQC^-N$DOD4NsS{tfaH+tS0$2$4EQ5w3Ud2 znOV-2-o0-U>V1oOs7gvj+^A8S!R1q50qvKiZ3h!$z8WjPUcmUso9L{tbFA5Jb?t5a2 zPj+uYF=iX)#9R`cQP$1oo!oD|9315+Ko$$Wg{c4it#Qy$V948)Sy1%biY`nq3K-zO zHR3%Q=Y{m#^LOhEfhY<=IG<@vex;d7l}oDb4nNNjFql!B zQiJ${dVU9ng8m_`Mbq(gecFw@MgE7Vubbw?xgLZ`A}9w!vv|0eI=muqGz|kGft-!Q z;KeuccIB&rOQLwEycZ%#5v;hnOcMuSR@M{QtPy9CHlM15BFw)uRgzir^ELxM4C#o#L$pvF)eE7@LTUM-vtd4C6G2u-2t z)l0LAk|=h#Yaq>#3g(RhKzkzuB7`4dUjV8iAR;~f)cE%)O@=UvWnPJMZv zw>T`E5%(kG9=p&N3Iynk>)IiIkpGU3Xe9i?m(|e^N`D@FkdN3@8ckr6^=$R=@$k;E z2jUb8tT9&{pzz1U4e=!#`(wqai79uLV}DpwSb z%KNEgEM{T{@wAt6rOWFjwdc5u5Y|2S27Q$tUZ#mY_>r@f{jb>_P<(pT{gXJ&?=5kv z$Dv2sSDJ31YlbG&{4%1^)6O;VSK!*si(2;Qnm%0byoa@1uPq^+>UV-za?_S%hjna?TdWzo!G2@ekT-U~B zr<*vHCoz=AudmA@`Bcr9UM=P2oPZQXa?B(9pzk0wRmdGPMhY zsjw{NNF2YI*f<{c(c--$jtHbZTiN+679PhW*wrndSrIy^jr3ZO#~)J?)Hr0sPirQWR+}v@#$n$=2==+R#wbyA~trPMKDVZy_W6+)3UO6IlQCo z)Ptq8`PS-4tb>Mky@~3vCd?%ZOx)Wyna3LeWAuW4!JM2fZ1}$9;c=6MTTd+NWZU9eNdKfh(z2tPB4 ztMsH6ubVlzLy;*wWqIgZNqnRwnb3h!mw#o*GJQ_Ld1BA|tr03Me|x4t9ZQ#KGs0(- z;%6#n)7!H$-`RD-zt(`>=vQFqhwui|h5lI>@$JIdMJPtlmlVHT@7@?q?zX1~NKHsGWLdu3VLJ2rO!ZZ1=#Xd$bHa3F| z9kx5dAh{WBmTOki7UOWlOIRjVkxOOb(UWOa5;xNl);q`?Mb$V%xB$~%{Y@eNcCNh> znDe>=QUc~5doKLIR}TV@%lA{aMp$TR1cjgR`S@P*NEB|(w9qTy8{v?JSeeM|Q2XQK z`C7@@P@mB%704deiF=F({$70vFUe-k*n(@Z^bX9bkYuR6l;145yylDwl6>VQ@-;_k z;3f5=M96I5HO-LR)|_6ck?=lnsf!j(`MqkI9&};tbaH!o8lK$CF^~Ftd;5cb4_?(3 z7AYwzO`t}emB!A2k~>YQLZ)d0KhfD!+|@8r-0qi0HGh@aWc;bq1L`_ZCW$_ zYGs)-4sUu1)9du4b$V`x z4NwK?Sf-A@8Bc3&_YTqgwZ2Nx8Xa5b45~2rZofxz&+YQf%49d5MXC&g{DUowf1Ecg zA5xK*Ta_6xJfFVkzglU(X2 zP>e3R75s*U`G{4lx?a_ zkC=^2R9>R7@eyT@{r0hP$OP_J9JD4;H&edwRC`-1(1=^>&e6Z5_jfcMTvz5bxUqZ5 z>pLLm^%{*##2@itc209Ln>T^?qk6Zx@AER-q&qV}%A};1%_W<#k7cT*O7}KThC1mk zwa!0$5L2|fXYf>$S-<^zx}opbi(AHrxuy0Qi)C^lVB?yfU^1_2gUQTH zjKM^TQeYEi48C>TKWJX0zohafr*p#XKR74k2Mb*nVq@=?_oc64Ia#@`-GvH#XdRiS ziW-{~pqylUdVBDz7FR7(KGObC?~&=`FO6@sHO6PR6Hk5i;r2(QXQ!99aEziM#wbF_8;cO|2U-w^(qfNh zw#Z$ff51CK79vnSa`I4_wir3C6>W&m;B_K(>V2|onlM9-H#FI>6hRzkx6}T*^iw zI{X%~$X@P+AzqJhgzx=@^gEic;kxpsxW`U4Ui^il+=l+F#9}P+_>GXf{_8A@Sbde!YTmmfZ_AAUGvSRwVs5@_`1y0Ur!FSh=(G>qCW$L86QYu_K{eCBU2 zfvw2kw*rJ0$b5-CC_-2?1!wN7GH-DwQ|kTXv$;^|Z0rj@U1goxDMsBNlD_E4!F!~n z*WTh<7*o45EG<%9F!;Z1Uz_MFLd$-yRb>L{a3HKoc*ie_!$9ZCAY~C`!|_p@qyiik zr_8#B0D<(j!nAC7L}*@leZ8%5e+pj1Reoo1G_Y32FCnr0I?*7(A)aj`*N!;YXBV6f z&zZ8>hAEorlI9N_dGysp8OHI&GE0l*-};<)F&VI65dUtt^rsGMJP$S!^*T9c&Ufo; zSNKgG#w6jK-6@Q=3#aU_1u4s)Oswv)f;PNWr7Su;wMxOZ=)1zluUF8Yt5rucu8$gv z+ELp1%s}VVB~PA^HTCvQR5_!ltSr9e-}#w9S&q5gw`^LiisI4;t9=(`5E@{4^F>XN zvsUrs+Yc5SvcH$$q=tK;tJhY;|HxXH#$+cUF1Yr$-s8rhp%x@o?Ao)KYdF&>7K(=C7s9GuSl-`7c{% zSt%(g##Kf>Wz@^0j-5>MRPJE~34 z(Q?iGu&;7?C>=}dk7XAV0h=Me$%-uB>>OW^_Q6*4wY6HwlQHJHFYb*@fMpH7wZ|;s zwa*NEhG@~sVC1R2xoshy= zZ}EgjXRL>h9UVBiIT53uwdqZ1>NU2cnF~&X-KycQYsiT#{SSPB+ZtW_?K`MBPh$j@)Sz z+F3K-OdT0j&d_@ke}o#_lhsZ2qPa3h8#rX^d2tRjDGAica>CoW@fRe9KuJiTexTHGm&6iP8oc)9v2#%=1AEHmw}}gbA27= z7%kaex=X^eJkw`4i*-9C8p;PKKVuBJ^wrP);WnpvfqL74lVB8N>yP>PGA+I2<8qEY zIz5}^slKAw>E@bBT3xXl@1B);9X8E2(WK|;`Lh3X?=4htjIjK1YJM>OP$ulWZCg?9 zh)m>F(Nx8xWSV)Z&Ckno9Yeaz{A5u<`n$_o0QN-f&`@+H(AaKBE)M#g#2zrTR_s!y z_s_vJL@utoW0RUO0XJ!3_o%4pMrOM-IxH=8%_Xr0A9+Nw>(5LlH4ON6$PPZGSNu`W}~fZbrQ5cZvdBNT4tHPAuJr zJ}dPFzHPW9QwWIPoQtdj3#fXl`1$#d>jKX0YJ-O6EVMgZElMSv%`=>_|8z9SX%H$X z*6e0H+T*3<8ef_Vv^uEh+l#Q{Wawlp5M1{&TI591Q{3#2@vn|mfyzk3^@7#?y%r>uW^M$*ipo* zWI>25zesIjWDUomH54$k+0n|8HhY_wmG1v8@hR724hbdlB&hT8_g!l*Nn=NTQF~21 zGknJp>snD~)e_+MQAO>$JN)MuuVLkwlsj)Mjxl=Zjf>Wg z*5{lqub{xIS_B_lvzux{8kV`gezR{#m&A?`^^Nz+ZfDJcJBNdz!ibx$=9uy9g{vuz zY-&D*kC^Y>mvMS5QsqA}8c>0Og!1A)6+U z+Jpxm7G1|biFW|aOBNo>~!Ucwl+?HnO%qA zG7lx*(4jM)sjW~&==jJ@_O$k66U}>r?=3E6xuKz5@v-Zsxbp6_qg|QoZ~md%J8mp! ze!5tfUZuM(R^sq(b#e+s#cdn*1*|97B?}n8tR3qKQ|h0YiU#S*-t z_8Z6bpvU1BFMk$F38q@wgNJcmz~}IW(+oIi>K?wP9NR+%a+>)Q^&iS!ql@13^B9VRa1;6l{mZ+g=Zk0Lj>gCDVL-kMr;1lKT`mPEfKS zv%su>zIN%`OHPlw7aP0QA6rw6oc2Bw)^r%vQCWLQeXuc(vdSs>`*MB(=~5t!*=!dC zUGt$QRK>~|TScsfkP2^C!S_D4or6Q#uc4-)w~*SeY&EB7MTjzfw`rg6-^xza>fR`% z7YVSgcykzua?rmHD~E05`05MfoMys_=TZ>P&!e3)Ow4ZmFg z051j~dee`QNH(LDXrJzdwo-rmyFf!|tz_TD=F2KDyg=9cy>(3TcZc;Gu=a~fL$?>u z1j#1Ck39s=3bogC#Fg`JSYOAWXSh{&j5j~qrVdUl)tLud;~{8 zc_jXE$LH144}Kd%n)W>ak?%VRWf+HM?_pIxxa-VEf)V+j7l4va?;EFP1&!r~au|HL z>{~I!!y9wguc3&$O+Z#pyytX!-w!a5_ak zecz6lA7KpznSBDajMZki0jr8fAalq2fsono|lk6ZNzi!KXRhus1J>m>9 zHty3s!gEB7Zs}(XP3_e_0pVz0`N3)G0Gu2yA9!%MQryd=-YGqyu=yW*>f;M#@}n)- zpS2&|i)v^#Kg4tpBX=s=e}cccm`ZZYZ@CM(Fk}$vcF6hVzWDEl&`jw^k-{fAPAaC@ zLsX`_rg{G=>(@^0Byr>FCzAEm7zuX`i2YDtsUP2NZ<{Bq_Rk-LCS{&uymwOwKQ33d zOS)5H!mpnQat3U|b54bEfxvycU|uWg7A=-IXr<4uY2>mOc*bddvVl_5_LQ%~(x95CNw+kEC8ST0=y?A@x+2T_^Qi<2ef&FZZ26;S zYe3KuN`N6$Mga8ZCf#9ZwMd~0l!eKLC42)aaU5UHA_Q6@z6Si5D&5qSkr!pMz zMrinX>m9i1Ylwn6{Qi5H?Cewxf@>+E){4Y3LJZpU4YQY^5SyZEqMhod>1QPbQ%^n_ zVyf&9d!^KqaY%QgwbyYVHxZ%3!}{_9wnE6$m^lOkCeH=wrXz*<=dd^>N2;#drYWf+Ua6yOcQLH*q@JA`8rsJ%i<{Ql1i zKr^^FgMHOZ1Zy#Q4B}4cL>>Jgvctu`_Cc^g@uKp7Ub^I#GEwChVdFFd^2W- znAg@q1r2wHQPVN`rp01Kf{C=UCXzg4Ga_{v914geqW$=yD;F*To{FzrR)oxe8#Dvc z-cqyW{y6Hr5C~y6aZDWCU6CEXt!B*onhC=6H`C7-5mNaR)hlQb$Fe@>kp^u26)tN) z*KTgA>ZJ(ri4=QS&-8@Zc%+-A4r^u5V`*vb7LxS+TqC`HzE?iL7slbPM5JOWG>~j> zTYR#gU?&kIub}Zj;U{fUe#r?3c0TO zre@${)#Af9us=AX6ppBXx`TudzCrcMcU8OAaU#HzZ!K0?m=!uA@nE)=cEa`lueBJX zwbBq(gr`GJdU^3Hql%7p1=B-71XJfY)LV1Iz35IiXHsV+1})5?rG-nNP{GT*&0oHA zI6sC3jxC;P+ZfV0%y}F9XO&W@vWuh6aiw~%Z+5|UbTsZ!lF;m=32tCy77mVu8B^aU z>vdbx*F~3m=&M`^MMS@lsoPzb!h1eWak;ltTR)DI5po=vp;NCgQVTejYl>qAayNWR zovM6}76nd13_931`gD_=W5np*5v%0U?BeOez2m2Q)4{`c!}AjQOd@7COcgPD7aeX( z!mfbV9^YFFmPy#`*fO}SO=>4Mbx^P^p;39wx34YzKgzr1AA9=a`<|~$Z#rULm_Nvj z?~*P`;WqneZ(%9CARaVo$>x7O=z2Pzx+;Cl69#};9q#08V!*R=Ra~T*>?ZzZDC)_J zEvjXC83?bRr38F-j25}>5cQ>97;}Cs5I83kqLD2tGK40z)%08mV>CDcI+(>Q-~5T6T1N4a3xYOp`u@MbVFnbmFKUN zkz{rH37}>+En{1UyTNd65S=8DVDzqqa01f*S6!v;ChI0^7d0#xyy7E!M6O2zJ7MR6 zlqcKS^UO0fPAG&(H+ZxEb^46~=$PIAEEmFevh_raA@togMGs?l77L|!b;U4uF)v@l z(A@QcL{SevthQ-O8Pr^&7+Yg}WUkshO+;#=ia%le_irQx*q~*a+KB~zz+vJlV!4Dw zJA#Y};NIC%tVCdi+ZXTbrTlR!D-E~g%6D_`!P#)PUZk^Zgi}&a~1;Ll^ zy||N-JZaF%Ff-#;y5eyXoYSjNPUGe zQ%Sql&uIGXY>o?pCJ-kG#`&!{q;{iiJ>u4~_XL@q{4{y3)6IogB}P^e=QU+z;?3e8 z%xp+6nAg^M(w=7aLJzSYX{VN4Bz@FPrwL`_PbZi8Z~11MJB-jm1`s^zJ3jmp*x`@1 z`X<#oT4-bDUG&%c-L7K*!J$PKIs7L}WXp$Mv~m~CCxDYTO0s>ph9`Y3wKI&rz2nTM zD@8p3U%|BvIuwg@DqRpV&@Q;VoO~Tt=i!yKrT^m}h^er$WH&LomQxtkdot*5q(02( zVdF!(+{M!kSz_*v_xUp~6A7i${t;a7?kR=R#rcu_{|=E1SBu6?o{ErWx5InRdjATQrn z2#SOS?1>{47zWlin}cL>d?g3xZCG*j)k$UA{!1(0+2zrnu;ji#T;&sgP|HNZLH)HG z-l-f;@?cnl-Au*o6tQri_0_3N*hg@xFHC~n#K?^^?Mr%TT!Y1R812tTt!`E2wEgvS z!LI2fAw4u^R@NoF3ERsz4Rj_TSE? z26wnQ+=P;*?^=V`aFjo4kl>GMMN4rCW&m9Y`NK^8{Z|!h2+1pY)a&i6X|r;n0m!5; z&|M8uhs_w;j-(U*`6ZS@5!VW|I0-@tCT_-oC#26E*MqV$TJ+AgRtvzuH~(h^=#RYK&*C=1sBhc zD9Hj!rp=%>kz{|OUGJeAfdstOJy%XgbQ%zbbmRv)sH%ZcHZwQw4b>cT=fXHYUjjqO z2V*v=P}bqJhJ0@rA#s770*M_Z_F^et1raQl>;^%y`o%=GjH0VN<^sJ-u8=@xoYsjZ zCo3dyNbHr`4NMt*LYUyGKFm`XZ7hP649gilqDM5BkOQ&)SkF^LI+AZ-JizaTHxlgbMn;AJCFA+m`jX zxqDDjQi7F0YKB>5@=Eo~oPgvaKeIh(!kH|N?OSa=3xz`_;E^?;cgA!^X8ciEAlu3y z(N8-4^Cud5tZw=QDK$3-pHc}|ccFKAV+RXjmX5sU=pJml6xK|+>tjgUv4a8IWwS$W zry?c|Oah12K$);*+oC_)8m- ztr1AYHKd0$y9#pOlzFbV5RaD6evyL>MDI@eaire!VvlDkG9n%)m1e1O%%|5d^&kjI z=qqxAISN-j6eir6F{C9T%&%{5h*U#Dos*m*i>5L@jVwXX3>w^~Igy?+<#3ZhEPvFs z@5AFIy~OX3qVbW|BXMWTTf8lOf3;~nj$%d=?<14f)11EXh{iSC_GF;8sM}lf`#SJp zVC50bn~m&kTOF>?G%&o`{Cp9BB^JIbn6t4yx3nlPu7Jiqx9voa!g2q7#?bOCdn-21=)f*fuahE~GBeIXE9a8QDwNW0XqQaH}I6mHQ2O2(Vx$ z8BVeQ$~E3Cf75kiq0ZXW%pL`3_c6zs^Z}+s>2c?X@zI7AK~oCx=1^gD@Bj3&7^C;9 zX?DEBheta8f75ag!Xe(X?%J@qIm9g_G8UNM3`f4Qy=vYT?7v z#a>`a*fw-<6o1peQ^vAHjG{q?NXnK`VD#r=kUsRfKhFgO!f(b>T8wt6{(dFs*9i3bDUhrt{sxdjK4@Q$2Qyxn|xoS7|8l~V<)}M!m2iN(K z$X@j|G}_0(!GWGTG%U?mTHRZ4;a#>-J@zKu=iWtvy8q}^5eAA zE?hVBT8UKuZMotkOm|P6Dd&I`U=4Ocz7nowd`p462nh5PdpXr|fyF^wwtRKfsL_{z zcXarPtLA#HK`s)Q#yT;*2g6xQJ0%@u=le|309v6l&9Qf;barZ$8O6>*os3($PGF#0 zEhF3tXO%v-)PJuZfC(Z5fdt?qJ-@zWx|bTnrREdqjirNn)FWMws5v7HCr>3 zb8|2es!+w@#T71$?5d>Sz0hBWxP`Qk@j1692FqyySti$ur<3%ozLF1$gk}?KwwoA{ zMK7w&pLPC5Dx|cl8q+#%P&;;8<=PZkIyAmMnJ?+Wwu zRo8fe=Hltc+Ni%zx|0A6LL2o3c@{YM)_@RaLKyM`$+{xDr?*AvptE^e{pQ=I!sxE^ z8B$5dy-cZ@vpagHtx>JnGWjHYR?0CSi9vFsz8^c}uLQ{6cmJ+FKt2XVRS2tYw!J>X zt8Bm+63kFl!S}fLQ2`o6h7gXAJhm8DW)uI0AU&k03KifH4E`rDyIIctH;0AwD-X_6 z-QjPM0DA5Wfcz2NzE7)!TcNz$d9Sy4a&UHHZ}2Kl*-^ypR9&`u1><&x4)Okzw>Uft z^1%C7m8epAEukd_>!~x=25FXb3y-kw6r&9fnz9K4u8&!Y(to5|{kaYBd>H8Cc!usl z^QG{8nO*+z5nYO+pkB`&KivO>&@MOu4ib+aGb^B5GOot&X3OX9M-0T&y!_dq137|# z_e+7(EN5rv<`wYKAJ%)1dT4&$<=%bpP+7iGOLr2R1Sal=5^~$(8S(P@V9Hk^%@PLPSoL#NrqN9oA^;Qj#Ri~XkyqF`iU|5x?T z#&?f}sQtdO5B1DjY@`+yfagB`wUqZG3=k3eR~K6l`!y7~g^OD$_=NR8CqYbe*aGJl zT|=?@!L-xt85h`PfZXUtp%)~GQvxYvc>&L#h*Y5TGgF5hAQDbS#_?be#G%rS7(8#D zgan76m+_}mbr`d^vmV{HMRG{xk3w#Qs>a>@SvV}>YM2y`JPG@9^h?&)Dx+kqN_Ykc zKN}?2ms$#>0ZdF)C1@OB9UNk+@MFRX{~(w7;N<_V`?i93ptPVhLh0e^qApe(DGfj6tbA!o5tGrQ<{A-{6=f(7{fhOn*Uq;obGWM?_XDV_dbnHW~m z755!Qk)t#%DkC_!OSYWz{Q4g&O#B6=F26-PbT~o~?JYySV&e~yBlP`XyX-Ihg{(b2 zEHn1?3>c>Gpnq1ElY_tMCwc-ze{m)wvnPlBI3vFp=dbmK!pxE2D)xiHlB6pqQ0NpG zq%EXuL}3~C(w0On?=SAc!NHgP5dQu6g!)sI%2%vK*mh@a1@dpy)X4#~3wQoO?#cua zI=&SrCwV@Xr&&zLm0nL8ztk=bXSz_Wp*mT-3HG&W>(>CIC(qk-BH=%E@(iLt#_R-W z2%-P;MMK=QvKzZcD4`EW^G7UU< zns+etEz}nvM0we6GOb&$Su~XCa>cNVg@5rNbOPm7a*->1El)*wibrxH&_ z@}S2V>w%r>=Sva(a8G`i)5VY-uxS&`*cBvm@$dz!mBAjiwa^}>wWA(=Ut^+hBHSTh zTAbOWh{@jFZ?$~fPH|u)yHvid?t!6pY0VO!JcrWR^ppPI$Q4SGqN|C&qn2JLLtim% zcG$5*GSMb*T8p$`m_CMCICS_Bp`{vk4_o0@Z@FxcHsk-#k9fS`&HETegv^7BWjvwj zl)th@qHk8jAP-qrkD-|I#)^EYRdvS8KuKf2N@stNBK%7m#*s$ZBXeR-6+e< zqoczExh?VSxUwT29c?hl>$9KX;+)x65qjYbfI&%FY3X>Am|c~JZ%Q(p=hFG!U(hsD zH~KEL%GM=ggWM@60Sb+g5;JUC?s@^ZRfi;&9hOgRCq^W4Tbo%vY(D{dqDJoKeDrqh zldl_oE$)7BMp2deqwXhWWw;tAzD8DFZT!PKcQ*v*fLULEDL!;<_2lVEjp6ax+N+zi zDSeXWoWGM}M~OQ7jwz%m31y`dU@^N-?^~cCO;$14qhD)!^2p1J!RX_om>cIuX~3H% zQIe}Mh#O80FNqeW$S))#hq`e#G z$vL~xF8$+&=S5dpN%P?IBR{x6+=(O3=z5_K&84O?Uw*e}f5D+YY!HKIj)*&X%4`d~1ZYK}trnfit-)mN;~#_lB&}t`_B+JE zdOG*#eeyLSy5BX*C02n~-x)E>hb1C;u114z$K4L6@6L4ppUwTgy~=r1>BiFB1pkBq z@MG1T3kh4)OgKa|AUoOGPyMv%v;#>di{DYArEr$YY}Tn5^c8tSz%kvh*58C~l>EjR zyO&7*lr}8o{3uM7#G$Notf;l-q(i2`AZ=X+bs+WHB2U*cyKKybW7|7Ke%eij# z^M0>x^1alEG~yJv?0`5Hw6ixW;+K@B@pmbIi0$|}^72wEC$Wgx5l;<)ZF^kda5{-I zab0aZQ!P=mn%F@hmKs^X!r#7V(8jQn7I0jC>*5GuwVCsJqCmmR#Yrb2%HZxpD7SJ6-bR zl-kWU{H;Sz8FDgvzMMGyfXPb`It(E2G|mv8XH;L7K}!c}`NUbOXGUD@3@|iSBt7|B zw7m^Jl&Q`HG_Pi)??>lfT5#d9xUIqm7^+Npszi@CPEo&3Tg*ETZ(O++Kw%--^)mu ztJs(P6>HkaZ1HAJTjIoFakZN5l%u)q?iMCp9?B|u4AX8d*yw1@)-tup&DRKQHty^` zX#_@&0-|}#>>|Stt+LIcW#-C^bmXHpkdl`Cq(G+ z=S*EP@SvHB9DCEFYDKWXE+ zk`BdBMxLpxSUmf@Q8UGPG4Sw}G@+E+;+I>8QTBSu zM9A??W$qlYM#p0_My{wXua}cvMWlHX2?2Eo;eWFLtOHshOR6XhcsUj98atx5z^AGZ z2tqFr)5n8HT0X6IVrY@FENS|#{V`&Q>I}0T*DEE z_O-IxZqiFQX-+Gw8QUAQ&Kl(|2xZ6(k3j?|~+Yq8jo#mLpBmyf(?#b=EdB<)K# z*vY-wTKPP&Y<;d=<%v57<`|L{9gEyqHLpTF3SQ`s`~K1W@!jtFq)V#qa?ZMOSNEB< zed#QSYgLvkHRt1fjGQo{Sw2Wjaa$~1&oiVUUvAIJ$emA*h%t`vkSq^^+`N_fvHbeb z%&ma82lI^B(GwzFPEj6zAyJ36tgYCBBZC?H;LyhL7BRaD>XzA2h9%1vpdWvlHp_js z*VU$=X+MWJ%^KwXYBff~xVdak^`~M8e6l6Rr?jG%`A^z7f;bOz|Il@dZtlfni{Tv)sCSbeLN^ z#+BrcR4ot(ly-bnJZ+~L9xPEiv0BR;H42E2Q1+)ix+r*bh5sye*{?Uy3F1RwD0t%s zBW2p|D5F0zAO9RBJnspLabtTo3V#`qU{?pu?stLo1Ujl4wEiqdjE~kRpgQ5nHu8v5 z?~f7`xzC^*qBHFh#1=FfN|F+G(eKs5jqBnL^Ir)Jh0_bJPC7CU^)}V30O(rzKHL;) z=dn#ygly-f8428SfE=EgHfP3FP435pe1~?`d4|-)v$4y+iWIT6^2hmj3p}g`hS^?I zUt_6(>3yxNb4A(N9fsk8XU!239y#e=83xHi;JqZT4Qs(?r5$FxUQ^_c5Lzm~D?JwV zx}}UBTRI-m8W+e|C6rTRrE-cb{3`)-2yv<_|2CVSP$SPcq>b5SMB}@GsnXIDnSIni+{$P{VLQL>xuWr*!g~*!+LvbMzVzOUrj`)d6MwXB+m zH6_}R>Mo+Q&$#2;_hLJ2Ea;mz@SviKm;kQ!E`A>W_G1(y*5Zeu+9BST4>KKWYt-Sk z91hhdKlHO}T7ABlY5h(9mtn5ST*TYXx*RiMyFQm6uFqqi`J!l}dbhGyF z01SbGm}!PJeV5_>O(gE?cGaq=+wjYsZwa)v4uAWw?05d(+#h775;B&UU$X6-<;Y^fQx|%W9 zu+ixL&NIbUP)Z+lkOu6y#yH>f2nI@~jehbCW9%azx-7JLbFY*lW#s{c7T^<%BmZ#* zb|Drm0c0^f$znXd3oiy#-}$LIls8I*jRcQM*Cjh?Gyp`pTC*=vNJ__H#Qg=i6_?;y zYKUwM3el&gND8lbg4-BKU`VL1G z8_0>RR3;40Q8C$iQg`@uLXdoeS5XY;H7h zEw+E2YDrH$q`M_?-5F-V0z*n#Az~)h70OY5%lj+KP8& z11=#r3E;ZMDv-{odq74y;|r4|!<$0sf9pt~A&Dl|aniFa3j9|B!Hn}2pk5FvJ1K=X z<-^+i7_OJi&3d}af@1YIAem6;`?YEhT_yt;auTWE6kS)@_S^ILZRnb|oO}2g0EHR# zD0sd>=4(P(e;BX*w8_cZpq>7Q32lgzFP9C@PbfPAI1nt013MTZ3i96mzN>>Ho1_su zqk?osGht)#y^gy7ZG%VpGoz7T@cB`wUK;$;uIoKO*y@v0XJTF5T?kLr6Go{>&nKNH zbeQ%0;2sAFUH@0o2-WT>MP|l}8lGj{ZUHVs1eVLnKZw^@?OhuMej<>&;mD!4v)@j# zFu&Z=={m2-a>WnoY?W~^75#`yE33W^teh!YziX!--%L>Et`=2y5w%0I@0pLN9Taba zA#gQ(byXdi|HL)R>xq{YK#L|Z@-pIEv%P=l7&VG}yQ^wHC0WKHL{5Vdhg>Y&_x;`6 zYcxaT`Eo7DyU*i|Ct2`NrbiWH8eJzTH~+LCVMM0yv-+)_DeZ0X?eAg@I0|$jyt9`I zCnr1C9cvESUP2>o7~W`0Jk`ftv7vF$;70Kvbo^`xy^)`%Jyl4+mGID7|7J)$NT*q< zlB7XE=y}$!VrpZEYl4TxS7wo`TRgaA8o6{JhEws@TWa#&6?+6DX(o`bxp7bsCN=05 z;!!Ct{-W1#Kl##-l#W)x$K1Vl$fseM(HlxaXIo-Y-KhB`QdsczX3;)uQO>3^<_==g zyTz4a`|o6jb*hboKH7P(M7a(%ifv-V7BnaKrRDQ=tiz!tFv6DGdAtLu1ff8%ZIH>J zEE88aCJ4C$<`BLXd|LT0Q3?JQ&4Pmevl z?ncm)Rus=9bLPGgFfAm26uMlNx+sE{DJy5!RSw$$F?;>t z#M^AKYW@xz86e@pc7JAT58LX%VfxAk>_fzz2|BJ9FpNk^J7UZ(O%u%ALhZhB&kkKi ze(?-?jBo8e;UT_%{>dz}j)Kw7n*EzC$EuC6kpiF)BD|)$+!CC?`j$&@*>rkRTJbbB zyq%Y%tMwPs6dD|AZcXrj9Z32(6kt}E!QxIq^1Y_^4cmw3;I!NmJz+6Mv1%laj<|qq zFGVvU(AC}frvOv&sRhCOJM_miWD_v*X=* z;WTp%3Q5Bv2N8hMmVy$g3e+56gE?!ArGx_1MmD&Y#+1?0u(h*qMEYnEi5OYq|mcZw9j?OE)vDH{O2V?cWo7|42A8?(79FR_h>yhpb8Idrl)8v4)egQx)Fv; z61S0K$4NYOL;F!RU`rGZ#*q88(rjsJu#SDR!(8ig8_XDfAr}lxcItj}jdu_F)IjX} zZk;OI{`rH)h9=$%hzdCs|sGvL!V-@(jWP z@j~mAQeur%GHVm_V{L=z1C$IZ zG<6d9J-XL|Kzv!1#?CK+hHQ`co5~lf)aD9iS}hz;rJLL33jD(*!zfC^Hx5UJe{O&Y zeo+4MO9s07C-CAYrhGj$L}1*9ERSXCWPPI8mGHXd`KpG9+q+3 z&d?J@wqxvoK+fL=eFQ|GG}*%hqyS(_z5HcdguaEvlDr$p*J zs@1woJImA@6@hn&3;L)Feimlm6%vBg?rc886k}B!&X#-+wYl(`-=V{vj3LPQ*~?ZQ zX?C=wxOVb1O8kgu05k;zQu@fetBxO9u}R5{v2!tQq`FA_nm_7E6ynMXGca8mMU9Nu zb4hr%jM{N7-5214lTfz*HlH-errm~CKKbJw+Qeb)Zb6cbmT zJ;n|{sam>X%#o1Ww6Ey)nH`Ovzc|eYsBNDx%Hagz{xBqS2$3qlmz7KaLfh3byx>~% zV+-Pmm?ufsLw&aq%ojB;xC|u^oOSR?NtohZ zg+SCy8bI>3IE3!(o6|1%$4{TE0$PNiD52g?0{SR_3Hi=PVhnc&ezm*6#-bCM(%s;r za3yQ}bueKQQ;AtlSP;a& zd-@a=2>l1y^kYrfb{=YtJ14L?3H`zi@HaWgo||@3#Oda-eSYr*Z$W~de+l@`=#JrZ zaktGYBW80F=btiE!!5LcqRibC*k@hUGbN9hMq2nX2e_($Za;oiROz!=QY&ND`P~z# z5wFpsJU7#69iG1Z^Ptr$85z&qtY)7kEeRgmF>e~Lw$!u~8dIe22A_eZH1cNf zq4f{GMHb@U1s@}pR$pq%rrx({2~wP@XNedFap4o7WJw1jF2lw$*~aZ`rh6R% zNI@0^a+9<$CA1uxbq|f(>&^2kjE5PeAqwgpk^Vu8)6vh4jJjj7tY|4Tbg3jw#-Wx$ z(V-;`q&12rXdR1bYrJMJm;hQ5QN5M5dN!u1f1Bvu{Jk#?E!_gthz8YAk~*nyxwC%w z?n!CsD`PPjqbXUTd@G_8_FPH8?g={DU4iHbPWwo2eps6D_+wfyai6ZD&nwJJUB8yAHJOanu5>(j7Ao6x7V3r8 zS041`B*1Is5bC8t-BSmHoEzg8$U8F9FuE%2SMyT>l4Gg8nmcGaWUT%dnp&URfdfrE z8x(lrLSWnaD%tb9O;<=$qhA5rkIOdJik|j6S3t(A9Fv^o438;{ErN-}UDNYPqLU6vqkAD@o%u=k0s?zQ3_DgAA` zpnZzlZ*6yhPPOz2O5y4!S%9WW#HPdg{H!Cb4jnZ~R z^WOhf73U3}QL{_X=F%u8;bDGJwsmW~Ux~eG&|Zzyk0gATQFqNks1X~Y;ifd$vJO`# z$f%NeK|yW*m-~(pPUz5m?ZkO-&)TB2HrLH;9t#su#-+`%t~>hFNn*2#TaE|(J{uVxfTEhJs{*VPZ2J2*)j5~!oXaQ-CH4KX*|Ql6o@ zM;}a@j3c<^QZC4PSrrz5eHly_C;a+lR#S$!`Nv0NVdd(8miTC zOA~#eq_}fh4*eIQ4!lGC1ZM|HB#Xns$JWpXJz3tTgVMOcIOmEAqUGFi^DLhhd>VO* z1*&f7k<^@aXNfyy;SN_?zVpZ|tv>ine+IiZu?TwYJ7}kZW6MHCCKok;71P*3{5PwsKa&+y;0?k(REP3mpfg2(zAsBJd!G<8W zpR3K{gw+RHqV^^!_;p)reBsTN$^1k3ABn$a&vFqQlvrC{T#imwG!a#7W5^NGc@%e= zOXVatA)9D)R-L}{hBQn(Xel`A$sGrEBn)Pjk6(ZvTF<* z2h<1}9vGII4bz!*9jWz|NFEXgmRDrHVt2Q78F^Dz@APYlW!^i?V0kF8mt~Had+M$; zB=(LMg)c#3XR+bshhJb@f_Pop{p<7yqciMT%2NXe{ zPH3S%44C3~N|v{u`{VyLDqg9eZbtXUP~o_=&Q+R>!$VqFZ5ww~Mjlp#(&J)0dHlB# z@^*;_%p*PBa)(3P7`sCs7#s2AVEt3?%Xv?2P|D|SyPvLujO{w-EL=Z`rBZdq(Q*ZP~ei}r2*$Zk^5jOw??;#8S32btm3(bMicmEw*FYagb= zsF4rcO6xy-+?>-Y6D`Eip+DNFrJd9iTPSn<`%<%7A%yKUdO{ctoK z)0WIp^gf-WM0Mypxv8BQ4Ah>~VNgBrJrEkOD-zF4*nFDFL#yNpe`)jl9n{`Pt1+6Qw2mPAWZd^ zgIT7A-;D3xl)lV~=~&`RVehnXWcv6^vACbU;$h=Ih@;;Wboy(K#PhGHzjeU71ayN+eqhfysp!-! zKZE)t^tEW_fS7??;io?(87tE~X@58n3gCkYLoW4Mx114Y<7G;jF;OIrM<)f|7lGpx z1EZb3>sw;)s+|-QQF-Zg>MhnDTsu;lDIdXm>98H@lehJC3TAd=%0D`lH(+8%V=GC& z62B@QO~1VZH+#&iX-U&X_Rk`vr&0Z;#q#CpqNMBJh7OjbERg0$t36F^2ynPzqZHw2 z5if+rzR}2eRB&O7-R45U{{?tNsYo)s7>O#?T4?a)2fq0qEQV-TD_OA>~5{=K~@fbQnS%G0lKirD;k&Ss+Hzp_S2jd`; zJ*IRTEkh8k%H!8nMIP%i`x1_}+=%(~1-#*1evIR{i6@vb$wG3^SheM!5xtfbi}nBo z_-YfHQt5n-lww?~cHyeZ2TddvIbdzY=$J{kekxa!UDkM->Jnfuvt6E(aq@7gXw_fU zKoQ}$sj&SwXXS~tm_fUpnqiz#RdiwQg(7F|2 z^aU=ICyTa-GPBv)hs59DHisg)Ttrl3tk;nGlv=?gVT0R$VXaTir)wt{EE|25k6*PU zmU@4F_r}44H6_E>)u*glBC2N@$llu0W)S=3EcY6y!*$XbvXdX zi|MZGuVn}Kv*2Q^YHu?U_2xm00_sY_&{43m0Y{;?El0a2Irst%L{vmYICt%cJ6XCWd|q{769QjY)bziFnk70!06KuMR`%eHwb|P>MOUY6SNY*-=#}?W zx@(6#>&Q=(>44@(Y(%>nj}ymr`}ac~zl`!>aSI*Kkfq`P?0!=cHJGyXq8i#>@Fh|$ zAkWeEb=y{%m99R)2_1w6p2@Bju#$J3>#~wwU}D@A!o7sbz?h{VcGR;yx|H%h#wf(C zh-)tNM{lO*EKzr1FETvO%G=l|-jD(`MEsWL^hs$l#%UhcV_>xIjs8d1OW^*3;t%M` z?g01~U0#ACqUoCI`R++h&EUtjaj$GS4*TPIalhKxtwq1-ZZq>wSppUx@vwCvw24nz-AxkTC2_Qpv&>!_-sowZg!&m-Su=mrryrnTR-5;p^^x)xQJC)6t0%mmx{8gR3g4cuZX}S*}Tx3xh&##)H4|H}xZ?@@$ZG8G=Y2~8lhN^*$ zqU$?Gp$j%QDANVm`Bo?TMP{*Xl;hrl{ikYTUyCnJn@&zZw*aFI$zlK*syE4U;TFdD zZGfJ(`KV?<_y_ZaSma=7xQGQ zxo$Zv*D;U!K!WGXI4J;z&VK+Mplz%hOHDga0rnw_AMKw@C(k9uGgfRQVWq4XcnpYa zvBoS0z=|ALE3_~E7~m-R+R^o)_o$Pd$)vSGF59M;Yj8$dgtZx+cmwvxb>EoI**LFx z$pn%_2LqfZZg}l^?yw10=f)3ifnCEg_wL8+9cq#k3v6nixqd;~jq4u^{t59Vh=ox` z1t3yUMoq~RB}*DCt&jXZZ~H!2ri1*g;H9av3)Qt8Gr@TDsT*6H$ zoeXZ0CkQwsOTx`#a@Uv)&N}qDEs8i&#QW$G2U^pd^{KNpmgN3E0}r-b5zv~xhg!{sZB#D3mcLVJ?<62Bs% zG|0W|XoOVu5vgqGsnDX7BewmQz+;U{l_h3Uo30U4;CsZ6_kOwT5tTxNErD&SmM|&r zD08-^kQxIT$5asNa|Iyk337-!0Su5CpSHT9lLlHHhDgRN8E{$okUD++SK`##Fb185 zYS%s4A`XkBP|OGbw`gkfeGr6OQv8~B$8a7t$$Lq*NpJs_HwVA1$ewkTId!{TzAy}X z-peg?KN;;$C}O=TxJLhQo7+$gI)yD?WwMiZP4$Cjh)#_wAwGYv!&|I9{gM1b=E3gz zUDNaAhjwGW`&OhIAl(P3(6EWx7?_h#xV5NVq;w|6*_J_TAoPr^n+&+G*pnEEJ2^4> zRMI~3k|*UeO&y{bX06J6^6h{xE55g_s=?E-Bq+u+hc-)=2A{^hu-chD=wGoPC3?PZ zQh1*?cVGX~SXWfx>@l6cm-|!VUM%mRP7f7)^L5X=sI#`JwE%OpEA|m-V0I4tvenPn zAygoi{3^@2|Q_lqyb zhA11P+{yNeF7^%x%h*a8NN{6%%vJcHJS!bP`WIPgH2W&Xs27%Vz=6qAW^(r^;fUV& zY_3T)7A4K2=}&iy|myAlS#*-O>A$+ZX@(_Us5vIhMX zoD-1CwoiobPKJO;%rp)(CeGXH0d~<`jQGYFU`G(b_xrvT;@&>w@FgD+^7X9S#pW-8 z1=ohq7wUqgBN>gApT?U1lR3W~8K>gGTc1T&rxj12PtYb+bm1_#7oRrT_^9p!AN#dR zI+hKeUknv?u?2ms&>zxj>uYBLN-Sef&LM{d_5I81O*1*b4$n!bcBpjh&DWDA)(&4$ zW(UXXb9CUk@LoO{p9$!;$J@q@WL-^R>R&nyep{8Xw$jaajo|#8hP*T(DCV;W@vYqi z`+|8Bx2CyONb-rH=%hX{9+lzLoTml%^jxrP$b;P!5o0{=AV14z_B)mLtgAi4RD*pr zd>l*5!vdP$7XYhYa_dI_j~yQ2|0S03VkL6HX1^efrPX11>?LE=UHaui`Y@XxC<~cC zB}rB#hp@^Uq7Roz*tYr%$5-ghUput#5$_^;XI&g*6RF^Ckb5`QM)GJxt;BWV7Pkon zThTzZLtDz@Mi8LMtptVdsa9E}V)Yh>V*}lPILiS+uh>Mm>zbs4j<9`h7dtMtK;HnN zAC7HcGpql28=?C^l0ir@nUYcEu|EC?XXh=#kMnQhs+0G~80~<~gYashijdI=sc~Dx zgQ3DUo(zP&L z`cygf7f0XeWuWlyNZt4LFl^spW6sdEu(+{5o(1mw_~zf}K?c>b_alQU$@1n7n?o{h z{!Bfn?ziY#FO5I@&?!+S5Oz$t^=Z%#EsXs)=*^XI8(e+vPZy$g zz;d7dlqHkB7<824($g%X$4PpKIfrD6(5%F1RE3-bsE9G8)hdQ;j4ic+O;$F~{PKHb>*K)_OSx#gbt?k=@m(joX)IUOIXLt0GOF!%96V zYh8dt5jYKm_l`ihcg&1z0i$F-y(5+ClPNfn50Op*f*)o#bP~@Sh`V})m%3#L{?u!k3gEtFH^ws(B9DJ zubHy?Z*hA}_g30?@nrHra%=)MJf=Z%(36Cx|BEAJ1;RZvNVSA)EaGxOxL+E5*Fj9p zr#44jsRSn0Jgn8_EUr{C%H4`B8tVI5$zoIGq>IjX?VG^3X`3@xr5WnH_^K$r=AJ>~ z0}lG9(nul9TW6<$79_Jeql$oLU6Wk^kMZU{azYEt{^t$)gqu-uk|_~9aB~2!fppM zbpYzBZ)dXzwRwG5K~efq!q8?34I{CO*j6=z=Q3S=q)(z*ub_I zSS|)K?}a9soHJaqcLv85t=moPV*V&|9`yQrWoeGmQ)7Bn2muFfH=nYdq3g;mbd%tC z)-rn&=8cSnG`b_MW72XqiTb*%%&k#j>On5Po~nh@ljhTBPhe6Ch^ecjq&B@>zqZsy z|62F=CU~Zf5K2n_+^)y{F&VcuElzPRocW6-ab8Z>B3%7z68~{H-2Zdk0ZN=oqqxoB_IU2^va?|LVs)|2cEwjHNvsVKhHPTIZQHZOnE{T&H{@N8=I- z-K7zqbTpD(Z1kbkqQoWa__fKKFI$cRrssRC203rU)LRg!rk4Nw{y4Gi&fhT!;E(Qu z1BNRfnmaF}7eA{Kjv#9TT*CYbyCh}1qA70BoaYx;;VNG1`A|B&P*fC?d#^gss#!XT zU2fcpC)2$#SvnmjlSyWtQbhAy?7ib3{-FVzKef?MTZO88`kEY3zS1 z2hq22IhOo@>nJkt^gfFx^QlF3p0*1oi*Sy9&@Ch#LYXzBre9CrtZTNz_k7>-9^%xi zyDDrk*8BWvuMyYk!Kr-e08ic}JEjhKnooHFq%X#D(==0LO||M9`HaP=2<_yJoVgBv zWU$nOP5@31kfX%M9)XFGxZ^t&C^NCLE(Xj4K{3~lL%UkVKKRgAHK=E_^)+f2AfwvI z$fKwK=BtE9kDG@&Xfi+~-KRj?wC-qEC0iHvT*l9uT@`-b<-Ab~f7ykdM`w3*;`f9J zU$Z8d4H$mA$~7Z<|3A4p6!`Alf(17!4plT837@mayNgVE3VZ+l5>56{FZ|WjJ6ijd zby`^%0tpw`8~auJ6y{IsZ;%N%{9~4?zEMXb%9SfOc*p7?|H0iqaQW1&^+IW}!KdW* z`A~eGx(f~0?Z>6dO!48*r5E>~LOZm466f-|;PgZ=^5jnCH1|iQ*sbrLt*#NDIE-NI zs5Q)M((DVabW$6BYVxX7iyT~}_NaP-(l&p3R)OyYhn)!=Q{Yx>iGAfmT53*f;3jVc zNP}^DBEpvlWo*RPkMqs_rnh&$9btGD<=`rRex1V*X5ZiCS1OnAfVf@GQm@ABP=a5Q zU%Z#C@*GK}7Z>a~fn3XH`sF1F$`kH_&p07wWk z$XjXzB%*RrJToEZkL}?>N4uP$Iv6Ih*3YNEXqkST8podgI@|zBuD{r)FfK!PfxPWz zDkZCxV%Ykn3!eRv8=l|*=CwxB8Le!PZsVgkJL%f5RLA3@;5waca! zLx|Z`u*Ff7V2O02-S6YLRg@k>JgoW4M@o%b?8*kn3iSh0YwS`eYP{M!p>w3S zcy{2j*@=y>Kj{-uh|LI1BQ2q-ryO{;)Qhw6s#X2yg4-9ZW7Db4c{t8zDd;zCZ5$M7 zaa<_!bW%SllMzUL041DippxFkTb0-y)Q-7@VGI_q@>tABLwohD> zczD;UsB-Dp!p|>fEK+CL#(O2e8NQOcV_veiitV04jS*o1pil}Q2>vto<{{-*dS=X* zYZb`nweJC>>!wV_{S0ii2lmdn9s7RcKg}>ElMN=-XpKbhroeCKkt$aWmlcB^@n)LF zYXzygT&tpvlal*DV$q%&zkpryC2^djX^_Hh=(`_k)HhoRDI!z5T;T1HU-YAJ*Y@Y1&0chtsPGQ2Ic-v1a>pGY$&9KUYvduD+R#@-7FykI z&ni(yk+w>Tzc~Kz!QR$eRfs*u0T!cooKNC+beMemmxk?X*NBXXrGHGiNnkh00wAp# zlH`dOTF^lf`!n_7c-|GC2`B#E$3yei#dy_2i{-#mreDAN!^z)=hd0-v7cq_AE~`>E zp6kbSu75I5(3IS$53%N`x1O9KL$K}OPZJJOFAn)KcZp2z*#av(Tr^Na7jmtI-le6E z$F>ZL8j@hkD@a)1jxiA{&-1XaM4i)L+o`SWSS_OIV!w=6CODRQLNl&B2?M92LSW zQ|t5^w{>;An<+l$KXqSQ9}|46!AUO!t$Ay4vrP@-Z>4!e^NKq&UjH);_|J57_pXSV zd&9-OA7S4cRBuSX@e8p)UK`I=b+$JVAr7G6fFun7PxB{X*6MEN-&rBi6Bly9CGvN_ zTquvVWtF*3Y>5c4DIy(!+0fT!(qAK}+vKws%O+(R2{FKl(3Q(KQW#mPdLX zcpQ#)WPLV|-$(e#>$>w{jw(n;9T@cwQ~jv8VflK#DabW?JjExrtQ*2yQS`e)lI{LV zRdYh*pako#s%$7==$=To#jzL;cMgBXTGBtJ`tYX{KewZkLXN~I+k-K(8l0i(Q_Jt5 zjD!@*Sa=r-viKi=GXqbTqWt(vbm_Z_3v)ZL*Y`~|6FU#&=>k1ogH`7=3F>Pr+vfFB z#7FNECx%B=fFaVjbN*Wldu?y5%(^uyyP?a!1dcPToF41r8u1!wPDh3Xuaf80jFYes z0@*{!){E;MHxB|?SWXCHr`u}*cO~U7ImHC7@Oy8T-X$|tV?Si`=u&vL?dLk1n)U%# z#-EDj=^$S)Z2jrrj}cKQ*EUy!$Fh;f^O1x7r#_(6q0-+Ig?1Rh_ylyHitXRcTI#ZE zA^|`>>Btg^TWF=I0n6K9q5HgHKHaN!x|;)XRG-Tr(502@YBD4`KM5^A!kGuNpR=c7CgY7D0v;07gC;}AC38vC-O#(9YFGcr~ZXcEUBXc%z+dQmpY zr`-t)dBJtPGz#Q908zY7{(+~|Y0h0jk1UoeWW4tqKQx-#aaqh;J*iLZ+#Rb%^4nTm z;wWwRs_zv)N(yp>Q4^{r6V=9uzPjd3r=RL>jX&J=6A7q;bq1~sFhwl!P?LGgUK_G1 z*+3=#RK2WFLYW1|DdFPy&@ZEM2D4?m_9I`p1I#C2ytzR7nCv$gh@0WAKj`T#3CwUh z$^baj#LD;EI#m_Q!>6etH;$-pS^~NyS83of3&!d8428L%38LC4WhJNyV!K0E(P=Hj z|1MoYEsNIfhOMa~X5dTYfL4+(y-_t%ywVEHq1drb&;ZiI*XNf2P%4SbNM0@KTtMX~ zsG4Cg9Y4ij1>Ebfh=&^JYUU(f3Z?ULoYEdO39!_kLJTWQhI$4lz)R(kc<+H@6>uoeb$Ud@Y~#nm}M1 zK--Di=9uM`^eHncK;-En>#~+%Qea6E4IA24KGdQMJvxp-mD22Bn=}c9Q34;~Z^M#c zK<6abwtBNDu*D8AiC1g69%|@ro^ZO}UcQvmH7H$vIgY=1Ce}yOEbEk^lwCW3d}(8h z%c{GLDR!Kh7b&4ep4=|elRp?UPjC@$Y{y#l)b5}ClSH+w!GqlB^yhTrmwM#T4zHKT zbE@4a093qyu`G+4D|!uRk_+$mL0}#=A<1)!7uMI%^g_Ol;-uTS;RRX$WhS}x1sU`W zr{&2+cK^axWCY`eJm8b_GvhsxQ)K1hmj;OZbefADHYW^U&+tQi05J^V^v1lOAd|C^ z(Pow)6Fp}PP)hEPY(Lr97@&q)=kKTaG`!|xOLX^XlW0n-bp_+n7@6Lcl@J*dd;KKb z2(nFN3y_0|RxhRTi#+4ka*7>&c;&x|6x6?i{rc7Xc4iaDZ_L3>Fcv7^o#U`^KnXHb zvTGk9gPj{Bmwd-SeZc)iftI%4pdZ}vca<+=E1c;`X`NXK?K`L;iwLn*=F60jt($;2 z@ezhu$yOS5YsgTf^%)9~PkYR(O4=zNey{B+$hw0uvdTPHrGTqZ%oUInv zt-P49sG&2?9f)X!!7y!~_oJ|+q-wYRV5^!wvaFa(M#Q*Fz?ow$=6@b6l;~fdNfYJ> z|BM@nC`$7gZsFI;FG{%-_9T~?o16X>Dmj^n{Nc9c(H$2-tN8S`*#RDlvbtHX)g6YO za5FANUWtwDg&cwQ{#8HRu?4l=1sco~QrG33d}+<)?e!iVuDBU3H^gMFVt`bDmdBjN z2uEMtb?VqkLmIWdM~kvrsbfkQ#iD0c-}WKYomgRGbB+@;lFh9*>g1blTXr;EzzfgV zDtZaXKtsDI?4M>LSq6Q{6hhK)jm1Mp9a*r>wvLWgo*(^fPZ0LK*X`Y0u-V1o&Ok!D zU4}wvuK|MEFCr&Pr%GSP`VLnln4dLIw(4jZ41;5J{v64&A3lQa+I}!!enuFL;YpXk zy{~#f0j;9HMQ6~=w&{;rFN1*b3{E}>eO2Fga#^aP>t;GmbBOkBTX7^y6Y}vp3%)m^ z?ABoM)6y;~k$bf1_3`$~DlbtNbZF9*Oi9Jh_MU-vWo9K`UAd)N17}m))_UZ{3_~gc zA7Xr>UhobNNTkJWqA^~dZZJiX7Q;l|0IeXL57qCD#~JYbY3E30_rqc)jF6mQ)&<7w zwy>TNTge3ZZ`z)^#>ziK?{1X-tSzR57wEL0~XzJI=205`jS zzNx*Bn!{cRi{Zv8Rs0uK0|%=e{vHxF4Cx7M9}yl)t&3ocnCw+$`4a!xK4A2i4gMkA zyHw`$OrxVh!-2m2zrvHh(CCb7^=6at90{s13MF>ZoDLeDqKmD@x1+idt43+~I3GT# z;;7Rx&2*9TM*9TeVbL1(F4V&Me)}Mg=l;Z1B0cy@c_w2>fW;Y2eJ7QxO6IvZhM~T{@`)8 zT-DwMZIZs*mWXZG1;sIBlzEznBAiqtP{h8^(KM)4@Qnqe&?)D3_t{#$=Zm}*_Uc=~ z&yBUlc+j7^Ey_)DeF>UTR+RbFjy!U`$v=`QlZ_qUF{iN4TaO<>%sVB64FYru4v%eN5x`|q3BZ4~K!d^MO?bYpe+cH!vaurAwvw6iiS%g=pe84F*9??PDA zNI*??EMYRNdBB%4bDQHNBA#cS6`42AQp z`-{2#XwO3`g&RXn=ihY+D`hvDjB1R1ux4srI?3pQrCODuJeyKVW9!tXJX_Rq7?NE* z$(qR>ktQe^?X^>_+jvGG(Y3wEqk(%@be#{HDThhOV@r$ z`8R%;Jsm+zdMcGX7h>6KiNOw2HZn(3r7{M87!D_7bHTDd*aCroc1tvo97@;?Xz?w(C|rr<$}XRhB9(bz6W z1A+D~JrJV`fo7|{4yM-fmQ03rja=3~l*~18D)YB&s4+dsq)I_f2k%huWDJc$^GNh9`4A2~-FoiaNQe7%(Pm+x!LG~yU30Imu$|Th zeFg14iNhU6F8@^0FnYZaCA#08+mpM0#9(3jjLJ}MF+d#n-C=TNU<+T$*8p1l^bPmh zS^&1@{F=UYejmPxW=yH((iH2Za;du2TS2MnVq|%Np@*J-gF9lr}hLb z2h9qT%j0@_s9zHxb+`QOahEY@DH$WMz|Bz4H1wtxI*MCls!9r^lO`FX@Mu3FQb@|L z#p<6;GBEZ{gvPL69G@vti9^VNu`SuG|m9)mHJWTWQFSP945g(~@50 zCru&@RbE*kOdPH04;U&ho@hdA4{4;*>W!D)>)UI3beO$f&pfh{01bk0|dNI~*hiTrkD$A%Jf1v{VhMeYl!Xs#UaM7Tn zl1cRUj>>wj4zTG*U71HBXprvz7QK6GsWP1WrSXjuIkRNI`(J9cn13NQmBNVjNPkL& ze#^fO2w87IR{Bnc;$WTSMlC)%v^`gn zN3(2p3WB4%911R@Z}-V~+AgLobK9_B&G?#sdG`aOooXI;B16Z7MNlaJXDm#En|oAG z!N1$p98vps<-|)klH#pJ9Y;>O^Qkt+Do(s3Q*9@|y%K^Wi-eUd#z6uPqp-~mDH(<~ z3NCGxFJA9FOpWTwBkNpPDup*5JY!O2RJ=YkmUQ1dG!aloH zu;C^}QCVIUN0$rf|IbPk!(&r}$mP)p*!2DI=_ku8xon5x&NsKG)o);WV|mn;O80x* z;(lEHhhe}_Hle`W?%G)D&y;R*1J3_mgzs))eK#D0tv#kEQrX$V*KU$w_q)$As|=`>j?rq8ZDz=fk*;W; zj^yX;SU4G*=G;)GU1Gv_k@INuEKl(}`8!DhBa=pJ)Si6PN9tOc1NjIaK0JHhSX4(3 z^js@0G>}@OaNbpZE&Es^8s}H(pOBSr#YcFvvZz^WIgXvIx3D@&0i2!s|34c)J7uva z3Vxxl1@H~hPPYTS?4;cfn)0A}Xp)x9X^s@b$r20^VZ+Bmj(RIuC!E7J;no1r+5QU4 zfX9bo{bBI~p=l|b$8ba)&JIP{?Hm!?1BH(zB*U*KTSQCR0P9ic66)%ih&R-53W21^xRN_Jfh~v@q`&oZ0Q4$BoKVoK#F0%&MdazkH0(=XJ@b zfo7Z!Cd`DGb~)o?1%&`&0xr`Ak%~sf(_QaF}p5AA}-f|J%V%Y`H!>Zs6X{o}C+cv$b6o z#(PNWc$&RaDEZbhHt;ed)7Yow(%v_RN=v$zVo6WE*8#49sdVPIFGiO*ib0~TIRnH6 zC?{-O40+!XgSFN0oIcU@E0fdu=XXXz!%%{%o?*E{WLOgZjzyAfv+bgp)kBPMdF z{CrqJS>a-D7hk>rm@5pGR`5r4!V0BFyK%W4$^NzYW!xQ?AIBZK%(hONT6y%;uc1=6 z!c;5_maXKtg7iHSIOPcaNDAPit|n)bPs)G$r-Zo@8!Z;aWzw3}ll6`po}2ISgKQe&A6Yh&MR^g84+!SWGin0dQ(1_^y&=wGUrGwA6yJT)H;IMR@3G9FV@aj2!GWu@-Q;G={g;$B28Gll*H5jnSU&NJ&Mx)j$cFbF9*b*_;7W% zo~J&$RTtNuJJu%fBth-W{v|-rtMO|~v-3k zdT4>$8*F3Rc(LrF!?_i^f<7XsekimV2R#jT8sT&{vZKWZiX(U;}Pjj>F$;uO1euxB}ZCvU>HD3 zLKr%R5Xqt2Z~T4l`~C?RGZ*){&)IwJwbtH8iVE%%n@sQRD_k8ac#@oxA)TF^gv`jL z3L$2~!@G%|q;}fE)n=x$R{g$xV%Pg^xl=7)XS4g9ppi(x2->|k8h!@+je>txglIC^ z|2U7x=fWqi=9wDF_kbpYdpv@>R^!p-m3PdFZ_;*<9Se#B!|wVTE$#pT295CdNK_5k z8a?kaD(SIuB7;Z1nk+*C4lE?fAiBKj*?KzhPdWV+=}5}1ZJuyzEL=@N38x$9Z>PGi zxEm_m^=*(Ym{lG4F{pH6(X5n5uuJcH$6;h>`lSq8F16JUM%hPF64Irhi1UfTOsE}u0X0&udAemdsexZnJG8g~E2~V;vf-BQ z)x;>E?J@Bd%0+m&$cD@^@x|vpT?G3=Xt$xgj{`1l5kddXFA~DGSjYJUUHVEXuciIV zzOmIk=8ZLbcF2GE-;aG+qp8TD8mwxZDNOTzC&|#k#8MuCyt*&82GCm$uNa_JZnaZYe_y+OAYhxxeaC zqmOx=TfhAfqg&{G^{wmrqOZ8I#}rX0&KV>G9?5qreM3rCZ1)X-ESFHTCiA(4zR3DL z#64IM4A47MV{K%GOi(t@yV8*4|QD%fMi6&-=)6s^$VNU**_Bj1! z*F_DV?8nzuTlk}4HJLh3vc_yo6NHcD0$P9lOD9-UNRnjAeP z(S{lx*r3=@PC4xebh4i>bSjc+$8EpIZ|f3z&n2&R{G2=}VA<2DTQ-MWvkKX%o2Y=Y z@tb>}(ti+p{HtFJgo;xBbJMXv->A$>?bY^M#Z+0C@u&Kt@*(|A-%*xHY9~lE$g)$b z&=yP6A?%k^5Wu8bh8TnRb?4+Lm>UIGYv*-$^&0gZdTET%eM;@ut}rKpdUMmqD?xshR#I&9&r99_*c|j^kW5^{7_m6 z&N3TLAabj}wi)HvcxUv5nI#vukvPod9vv9Eq>zJ$3Ulvva`)8T8Ui@KAT zxUOgPg-F9Z0Cs;FUjVHO1+Cxff)cfOv3!0b`qPqF6sc{x8IqNvp`-Bef<6EbxL}1PuaLdwp<#7;@o1MrKZ;# zys3;0{LzVzP!;LJ>Ur5ogvjkgxVhvsn#hfu(0{#V#MazjDvOHb3s*3-h#wYioM!K2 zDVW6tr;hJ0i-i8wF>XC`8kj}`gvfBJeVGw}$R50le?iUnn?e83tvl^W$`FFIU!%qk zX#xoK`B`SKGVo{RZ@s2R=Nu&1v4?{DidfeOl$2eXaa$$A7{~zlRYKg^kMl6pxUE+nO~^^gHk~}b4=LzdaN%^-Jnl+vNib<(n zPYU*oTM;|jDKD?oJs;D9pTB+9sMg$vg+C!W=-vcPzbl4U70}BOhIMq?Z8Ml>ziFOQ z=J49yY!_s;J(Gl0;`M%vO+d~OAt!r1IKoD1A{A7h>Sk@m3zjwD_2Sw7p~cWJmR*_` z^k16146HOK#ex2c&AlFVK#Rg_F^1y14Bz_ME?^|b;qCo-8pD5=PTu9WL46rtc2S)k zr(-BW4qv~NTp@wqsd(x73lABeYoA$KNEizdn248-=MhuEJH3`v0~8J!ND`R(oI}zQ z_CIr!)X#^|xZ;;m)q6uP4(LnMlNZ(Lzap{yhxbzJDJGaLPf#v_&9>0^?j!8 zFAm6}LFWpp5}U*c9T$qWeu^X&EZy{#Vlf<-#J0syn*GMyMF-MuUP`JJdOr!{gzZ?@ zIlz?SwV&E;|@k(%c@F%_eMJ0X_6C-6@0~=xSzr=)9T#sIB zP2VKOn;u7?yjGu>=)u!u6c)}qQizZPcEF`b>`0;9e;etRKi?hbNeJ0y7>6~f-2rqs zh7gHa_F5y7tWO5soG5UP zWFfV2ksrWf0^<7Xz$8729;%^nXSUJfWu71!m@SkpX0d0Vg38I=qc|@zs3LVVW{iZb z2!ofLx84@#%m$qBau1f=o8A>r?NbELz9rPyP9ycqMj} zl*9k&2o+CyCE32Yl#HmiPDz@irkhKfoFs4q{G?wRuFEM;vzsf;Du$y&-r$}~>bNB+ zp|Q8)El9&L1Q^q31b%l}Sq&lP94`^mR6-Cw4VQMR4XQBrJM+5rMG!J04lMKh(AL{w zPz_4Pu3lSGM^cM~)J~NjHhbkLndhn_0~HBR0~AY0u)psHtpQe|++!LB+B>V-#h~ra zKHvE2jWQ3dYaH^wyxo2B{*jnyX=qd(s1f$x_LB|2Ul}ZCDdAZWT)^W8yOWALMK zMrgt0t^_v;WRAvzziz(n+vbDc*o+_gT@iJ#LWKCctopES&FCCA{{F#f|3yHgN;f@M z{w-0A(AQt(>%S+KJSpdS&Wu{6^#wx87B}V&U=x?jKFPnG=9oqmTA<1+=XfPBBMc}WR3r%A>EbcGo{BWmy6Z?04 z@zWP%=_gP(tC7Te@aCLg)w`fKvwpUgWW34rOQ=VYXaA|Y*+RogZ4-xWhO@J?Ld!;= z+c%#vUg~sI-8X<=^N_43SrB2I@8QtMk8p-=B*bmZsiL2_=0{4)-t16zGPpfCyuem1 zO~rgkg^-<}n)X3}<1b&S zbXQkW6rO+kOI;#A6uo-zt^9{og>`)rJUSTDY7`IIoc($87dL1a_>O(yCA2JzciPeC z^OBX4?WLSFItl4coWX3BeUF8gJ1YY&6iBFoSE+MW2sRZls+9@ibHZ&pYC=&|R#v|3 zqd{G0FiYsY#(i!js`pl7(PN*cwr&TzZI9Um387BW2W8q-8fov>z5L7_;|X)oUsd0)>=OlwkEPW7etY}osy z?&B}d5$>2VyLrY0dJzseeObisXw6;E^1i)%T2C=6r0weH_OJ3f-oM#`U;O`a9@zw1 zA34!|oSI6}W(D%kG&zSnksEp?WUkR!78Hrx%mZS5Gd-di(;GO7UinS%|B~>cS|)Bk zY_1fbAJ}UMyaB`@obgLdr4z)IIcT0{x?g3e3|+`FWDyLGC)?uJyq+M|@`vJsF%sFZ z7pMglza@(sEE7gQ(&^hlrNNx#oR~$X06M~9P;GzQ){-rm1xKd^s$p^{X?zxe0nUzW zG&xnoFB82%ET2^goS|;YOqdxpqegg-eiLCMm)h)*?AXh-0?)9M{+Pa#=FRrI_6ELc zGxle9o3>p4K&ze|VKb}3S#8c|D;JGLfihPK#!<0Kx%;0r6&2IoZfvE|8L?#Oak>~a ztd7zA2t?@d@I zo!C8i_;#$2T3d~6IZ^EV#{?sl7{*THieg~Jme_rYHJfTZe0cJOAduPZb>dd_%@#~%QC${ z;>%e)4XX7*BfdeFqls-Yf#)6TP&Jh%Ux*%3&?99qlbSMN78K1-%`f?~E6E(4N!e4m zI+Hr{Ji0YfA?Zn!B4VDSbs)eQp=bIft9BoeID2;KUR>O=uaM9?>b z^zB=tVfyY4`9=|X6S>7w9_<6x*p0o!9A%#SKKH(cH#L``<7aQ;4~mWToJ(seJVv6w zAsTw{y#HIhqDKpB_TxIjoWe*P=Fv5BSp{QvNAH)w$Z@(uIcYc8LWV}_#J)Ggkup_5 zh9xuceJ6uzZ?w@gR=u0MCnN0?;r`+Z0Sq zrp@L>>Wiw&7uv%j<1`|Gi2&PN2v95D4qF9}fs~GYfw~?w_jNsJBl6UE^ZK_h*$mn4 zu1`~cj*DZl&Gvu6I->a`&}JkH_akbY(9-5eNyaw82d}a>6TAH8#uo4Nmp6a9WjM9uR{!+e)&K41;P@as~V*hRvQ_Dsu&ukc!?l!{Woa za6p%_rJ`u0yeMoV40$Zh!|>+F(&hxGP<2oou{llk&iDeA>4eb2Bu_EF*_H9-u8{2F zsnO&29^3seaxqZH+UErNlC(HXpmV;kLzh~hlwPJU=|e{oaIUTjey6NF^!xWy@b8(G z8(raQ?>#A5v{SFNId&aEyKi7;Mf0QFCl*0AG*PzpJ1s{wQA$FAYq6S~^#&o3q~T8f zSB0Ol!}J_-d=QsPbZ!IY7yKya(dMWl`7f4SNPbGK;$*6|+8(LQ7gnvSG!XURA95^c z_Rvn-WX-N}c*!OB4u(IlaQt~-rED@9{H0&~#xOh0ke)0nnhw3i{&6svAE^OZDkfpX zxsIT5yb@dv%NU{M4^+r+c?olDCV+E5nDE;RKvJt%E0l-Un)yTXTyozuIHZp0YpJker8Qr+=FJaY!R_;SJgUf}E$Mdtm$2y#F}( zR$eGflKdr<8Vu2jHxqncTqRa8D=`$d%9_LqWGzo*UZ}**WG2xF3v~M4{=)x5Fbs2L z5{3;(0j;G-*RIK{yKR87zN6*LFkxG$t`BI5q><5MO|TRHj?F~gur7sJO&RJHZ*mZ2~v3ySeRVc*JBlyIFHPb@0EI94;JaCZ;{AM zytWf%ktQcMbs2I7>3u&gmtv^0I2PRvp0&8x9DjM0E`0J4jy1jydlh>gqoVS-C!xF+ zlbFZ?zK$FnK*pP!d<5BM4zTm_I{127udP}jJ8!%}KJRey7WWM3Yu?B#BxuYljV-}5Zqs5m&@sSBp`dG;yNd2GFMhm$o z8xuEcT*xz0NYo#wx#Ea+n~sG|Ee_LI+a$R7)-V|+KR1M_TfFQYhXhvsiV?_-83@n>nN5OmKV^Ci69RBrv|2ny<>H=2c5I0kNttLN}gIpaFE-Y z@}|gx>~oa2_ajf9U7G;7oeFe~Hjd{v)f;r!&{2wgc0lpNlV<3^1vu zje^?hcRI2dIqoX!%uudo0+=&&yr=UIgVD|QmxXT(%YjN}a|2-k@lw*)O3wA*_Fl;m;CWqATik|RoVJG<(bJnv%M^M{ zWL4fqBAoD!MKN-=+uIX>ky?a#_1!|g&P2|#VP>+SxX7z#B?V8LKD7$vN^gQMzx$Zf z&G$^g6X1lL1vh{0yV_2bm2l|f2NMcmEfl2-btqGfQwK1s&H?u7ww|bZ^2#rBZOrggsmp0X|5WC4I{H>P z9R7=TZGFn0bdd}_>Xq2^%}qyuU%4N}@b+j*_1JXcb}uiDlfyP=a_HM(NoRIHai8m`i3{tW3b51^eosSX-Iyh zaPWpkrS#lpgTrD_(q&5E*XxaWd3odRLA)(mJ<8h*)Tb=@buZk6Zh6m&siucFmsA)9 z{9ZxCe;+1+&}kz9?bYgemr>hJ{X`w!Vn@Fh(~Y=3Mzr}I%wjx9*B~>tm^bBi7zD#+ zP?@oLXj3;)eK+W3)(}&Ctiq+j0llG2j5oPmJl|u7(@XG8O^cJ_nvn{@R(`UvIyVND z8>`~vCH3Khrl`N9@7rp*BcP0++z!MF2@stgBFKhuk=IF;S)uM6!40t3@lW}PNpSr{ z((YFS0-k;w(8g;-Y#<#7b=(V3-htWVuIszfG|iezOu;W~L-jKJZFwQSC(hHgfuHR; zN9|TZ3144|2n-f>*c6o>+~t$)ZMFAeKS=792`bk{pwKQTukn@~diB!Cu-;EqW;<%~ zoq1K$h~QfyN)s%ABQMUhuK1780&hZ1Y?f8ld*u4M%U06qSIePvMYyx`1fN9RXP%_j zNA6zQMuT5MuEzJ4TAsX5>^0t@%9A|Kop-g{_V){Fy{>7+4eGUR#T*^p_dXcYgR)|!W<>X7g6CM`45NrI`JFDJ>(8xh+bImFZ>mM#K-hP?eEFdja z{kty-g+_bj&eHS!0cVT9*$M+V+0Q`|rSWM`3m;BC9Y)x`Lz=ywe=F(uC|3MjTDB0q zbdCwV5FPaEK{4v1%ij;Oe7@B~o@!FzrHV*SIVGmvq{;laSy%FKf!*i^|44U*>sL_i^54W9Ow1SBa z0S&{DelYH^l*gT__>u74M;`YaL>b$wJ06oSp@PZ0d&@{imU-adNh5NPFKXRT2AsYL zV5+7@oDb@zLGYC=eUTusmGX-=V-Bk zH#Cx9$V^a;4Uml+ySPQ&x`HLvCbitxpy`Xo|T;}meQ17Q53PBb7-aAdRjy8=~>~TUy35~r8A`Zq*z}DiM|KyP;J$gb^HJ# zNL4E)0?1jhRz$1>Ab7Kc%jhoABZ&pn+Cduv&Z3Bqz&v=JXQ<2}QIZ^!|qY6%(pt5*npLld96UBry^VcXeElf21GD#8f9GXQ9^2@TCnk zWTM=hbiOEMaO~Mi-PZ#Afsm>1fH>(!ZuVfD%67Hj4`k)lgmpA1?keD*$B95>I2>;8 z`}ucYeg`z=Pdv^*P^EEJrNP{fjhh~%%pqbmB&3gvD_W4LOe9s!%57Ax*X*Dev56_L zPzV?Bp2h=lKHm@Vx;c45d)CVzZK)&aUrJGSJSVM>1aq9v>=@2`TI#IzV49V(RS`(q zuPmMc%bopx^Shq6KYrgBXcsj`ZO5TzBG?`v!5BMg-TK2>5T+0>HieK(lh@WfGjA7I zfjp;(m64Si+=W%9qpw!4e4|lBB+Bz@T)iA7larKZ7M8k9+56(;+ zi{U}Po3?|!TL*j+3ea#90#PCoASFx{bkK=ZqA`*0O{2Y_ zH2(6=QrwLF&(|3;?^2xVz>dIFN;|aD#lWM@RJ2JmjrFFgM8rF?4KwlSA4KO(vrhN2 zj&)wR5$9iw)$y+XFogiLq%Z`Z07qByYH3N&?4@`~`rJae<2ZdEMPB|UBCFD4W#XI) zF^)5&E%)`5=9T7$J@{<_JY}Gcs7u}@H2z3+Z$)eVPS59Pdwy8f-(Ti4U1HesFwuKA zQ~G^jdM>ym*~qw3mv;soUUbv8Dv*j}K^hSQSvHQR$}@Ld!_sP z)?MShI;rr~JqC>8Q|Ks@IYrZ)RDXSr2ua|foR}uNGiGHPzKD^NE2RpPFHPUwsWRqg zKaV}tmGR9<0BsdcP{%Y?h4v^BukMOpV_%4upH_L9CL*l~;kjDt&0(sLtETgrTmsS=>TZYVa z8TbnzJ3o0)`lbaDH|HflG+^o)Nji;@q6on1lI%pMoK~d7i`cUT(~p^-(G12sGd34D zyXx*>;dZK6dYSXx$`1Ps47218*dmcG*2Z}01BzZV<4;0SR$)g`Yu#y zU_iOl1lKA@)v#g_L`MZnEel9`@d%-pxTTiAVYq$7msuA6l-Ivl_}x;*q`Hh1`fj2v z`00#lLtrdh4l8Ujblra??BU7UTx9!9#S24l^NxZo>6k2SC$&m;WZt61CrQ zZ~v@rHP{e@FXww-f0SwuXl^t!s!rHhLOM0&I{WRY>h*MNSi}Z8ka?`*#@~%Q;Wo?K z)sT%U4O?mkd-Kmr?IU8IO}|Y`sb}9ij`j_o_y2soAnHK05fm}%8`kG0Q0B(*X&cgP z460PpnHVrZM_s!ZIvk18j;SpU(nzcIkq-JK|8kmu0%^7abE7o|l&VP~RT6-fmo31y zSOO|d4Ig$!4c1}=E8Rt?TH`KY$lxzyyy7$!48Sdnj&BZ`CB!Hi6eBcc50G}gOtZk8 zB$bhthP}0J#gF6WM7A?TCx(6*zVq>9e-3RyicvJ3`_mc7G+dQM)f7>%$!m4tO69V5`R zJ*`v8jZM*{0!J;5jAyD#+pIbnY4ir_ZmoHi_9D=@vTOP_SCu6$y1vD*t_5#Jsy&i4 z%&}ho>ow8o$hqT0KmKR;k{hOwM96_OK#U5z|i7u4v zOnYRP4-eh_8g`0a;$Y67jw0e8x8Bmz?R*x~Rfg)9&8a=j&xit@5oTVeH+W!Fnhw$9 z&5PKzvfRd5{8{rT$qgVLHfgu;KniKPHQ+r>gq2X))mTnXs-&-wj+l2Vggj<4^Q3wv zgF?MSW4=f~ML!ny8?p>UggC{R6@KS9t?^*z3W!8TgO%lAV((-K7t+JElJH$y7IE_{ znQ3KWSK};VUutN`9_wydcZ2^oO5x;ZRX0}bA7)NS5fT(fZI)dVP|iEUIQ2ob_N9GT z@E!fbxn74;Id{Xng=4WUu^xtE)IiI?h2vum{`5Uz=|*T)O}{bH)ous%hA3|v&=1_YIA+8v-!@?!&JNS`8^#38?qwug7m_!Cr z1`Hhmw%aq+zQ!US_eU(c_T(sP;aZdEcA<-dv|wX8U{e-M4;(N4Pq>0v?FMTb8^6Uu9^V z*+-5&ADKX?gPH7(>lwe6{~SvF_OfJmi;YuGL2#k|#mT7s?Hk?U;u~Ja!{<^LVb9W* zlZyx(DxkN;L-VaQ55gj*5*X+x92O9%`ZZKpxSA;+WW0Tf40u`LvK!VJ zS_f*ImC0QJ%X%HvG9TaGb8jygV{ybH?yP!DleAt%qMXywNeP(N;mNPq-POlV2O~l( z`S<-^CHpb68-~!|`XYVsL4ooD|C(Ha_#BHx^Fe$TNP=8@Q+j~qt6)TC(YP$uLvbi; zcUo=^x8?-)sirOmY!1^I#S(1nR4Nv;|8UWFi8L~=lE9T{s7Q{gr_oK(BVPw*(Cfs( zki?pZr+IPSI0);)lrKVWPK3r1+F4_p_UhC%^yAy_6re{;)9)^k&zRC{;vx+p8|>0t!jN^~?6QSr>p zNCNF}&+GKK1JuDb5dS)6Qs8e?4DHBHssFUCf71vzhEhetqZz1)@;|dr{fJGPk(%d0 zHi=Dk7FkbvMGTv-$muO=G|tmNZc(>=L`pBVyR}nSrRGlyqBp;0Px+lOpQ+ffozf+@ zjsCCO10fAPPnNnK2KPPpb$-*pkg}~6;Wv{WIidS=eU$Fzt(>>VApA0lj)d-pLh5guEcJMv!$GR^Z%AAr-D823u<^8o0x~3+&nOH=9YLkl*N+m-~1i$sKFX@gS ze?voJco9bjoZAUuyQ&Z8y(q&s+&&D##Ok4NMD||!4=r`|cNyrmI zT0xm9A%%E+U+1OPLBt5f@}I!dS4DPZ48N~W(r2;!l7hbqcaf(VyJCFq~+Mle{s(&z)%PbdO75 z_1uXz?OykXZ7ebIlD!f~^NADxC`Vw~+X+zJ!({@E^+%qk;mrc%^HwRZ<%0MA>DE&= zrs9<2*6s9M%xNDbIr&c|8=$mKmCKHd0>LB%E6PT4`KC=)7+!>t73AG_7g^&jJ6S-mQVyXG&7kw*X ze&^5&^cNcW4n%Y`KB>QJtT#|Bb;=Daj>*?<=JXTpw!=G&?&kzz#6I0yA^WN(q4Zeq zMuUhHwYG*ByeTgi*X_P({7t^i1vb(D5UN6(WK=zpouh!O#KMKrz#=%*Ty}m$sHaEr zA{CeJWM>kwzwB^3FCIK)Zk5cC6|mEhF@J^=BQz{V^0{Q7>E+(?TddG^2^JHVWCM}D z6qv_0!}#6`^2+tep~J5yzJI3!ORB&Nzj1V7QDn?CLcLWvQjtpXV{jcr9;bn7c4^?PS1i9qHLuC=EJ9i?ZmhJApc3#&=tp5PMhkx z+ntIfu__D^+O%%EK%Bu_ld)I{cJwrkMRxBmC3whzI6jM;?7{xKIX&X_V%8Np+ZF>9 zl8qUi#n$G2C~z!)itD6kIfqH*`&Xx3zaZKlLZ)Q?P%cR%+|TPCIKNu?d~W}>3i`hC z-G4>Qjv1Ty5d1+|FWgFWbrmn^n&oImym)Q_8bH?A`9&zDS$|1pUZX)}YyL(qJP=<_ z;d6K~HofR=Ek(}taCHB6>Dv~g(|0j4#7wB|1)X-otPj%_AX;xa8^rfC38-isC-*Jmq9L|iwONz2&I7vNOunkIQu=5p zj*EZI7|Q0lDA*LqE)o(FekkC~cZX^z32d|DZJv-SDl*;JGo$Qzw}wvJ0MRg4*h{C! z;RTPj3lZ?A5z9qBi)xi%snc^4{^20`vj`=i61vERycuY8fpE`%16E#%I*sM9sz4o? zKy1}uW*;e%zb~^yvD>4W{Ryzeb5%*MAHyxA{sn?wu0r`_l}M(Ok&mCvq9FtoiIU<^ zc4Bxz`1*+4&HD^?ivxg_A<*>0|cv?io7?HaqDOxD?UmG*KIFH zgP^rQ11a2+D#@a1Nf+{aYg}V{J>p?1P5d7mIz!x0Zq;lOxqc-YI7yu2&P`S<$vE3A zdP~XBl=EAdrkI`R_ENeX6V%dSDeLt&5j!{SYS?w}@B)DTR1-OFbg>rQ%Eu();iT@k zIumfM_a&g}qi4Hs0a$FH?L+>NCE3Oip+HkZ&Po8zJB|O)`msJ~nRnY}KHVgi-BK@j zUj|+;q>!9jg7v;PG%@OO5srNp?W76fb6xe)jdN%CvdB1+?0ZP?fFU8?&JFf`g%t!h z7UL3g^_PY^tmivLe?jOB;8+UYc0t&75H0rcY&4xelH&A_xBf%z_$~kE4UC*VU&&%y1oB6N~DS@cI#GxG&1_ z9dJlLe^jtBv`JJB_;B(xi@5sP>$DvA?7W@Nu70DFH``64?fIUq-g8BI@A;&6p3>r- z`i&tI%l(tS>@Sqc$*wb)+efzC3fxY^(qUezm5jOBy2C5w*jb94fVWoZb*8m46So)N zHHy|3;qkYt5!TSh|6=gehIXE^bq*T7{s{?3>ul^Q=t#%l9N-~Hg`)4sEU&IRoT+0n znd!US0Cx}x1|9W=aT0xaM?#1MUdp8=wTEJzgB^YUSblW?{;KIa7hbhLof7UpKlR{u zqenJ>n~i{#^?&)Y*nyt6_;&ejB;@EEvzLvxG{gJ!2kyfTq71<^{PpW1YOKJEQxRCy z{>2)YQ1&1cSPIOcP@3W9Spf@D4;bPz=VACz@i6fHvZ{&%;Ep}1xi zZ_SlGPgs*l-CQpsSmeE6Y4(0vPRbFe0-$z8>9TcUr4SY26zvp65JR9^svf_>zSk~R zm@#FS2Ji(GyV_{=GT2etY7nBYs_#3|ukmGZn7bZR)1cs_&^BG@pEf4XT!FTAW;`zQ)M>&wJUR8RfAfytkZXb^oI_8L_9 z7l!MBftq~86B3=p#E&aUpfPJ@Xv_1u>h--IQ{W)Fqob^oY3_wXk0Dgbu{bIJWfe?% zpNVJS=%K2$d>CVM(URsN4Tmb#I+d4dIjtfrHTLb5^sC|90MS5xq-HX*cjrQg0z>SK^qXdbr1viGMZu0_H-OQyU_6D}r2I_Q``qfNxXj)42ZcK``eJD$K- zAB5C}KK(brLSC1>3jm-5*a?1tk#L!b-1YcW*2kq+MSbe9e=JAY;$r*hfADfQFZ&z| zv+PBLCK9Ah^YXe6IhU;%>+_q7zv85{@0y}pwCPy{;+JyLa8M@an3Aku$V`F^O-v{B zx$`#@Kki#Zx5Rx2u9hDFR*`KcD{OU*oi<{sS&(f=sj0C$`<7m?Qx!m(Nr z@MkFD*TsVtYAaMDj@idC;3R#}lfioKWic1r4I=eHX~*}#&1V9oiLOUS&?;DYrr#n) zf{@Yv!5VJZ*5>2cS9VHk&ZQ6X$#kckxS;P~uQQo`MQVj+8Cdz}MAfb-sP=uYV}5>7 z3uc)nb)Gin-`Jo_dqF%vu7_1!%mRCsZTWlrtusN{5obG2i&M}sdXxf6bP5Auz&31a zxDE&Ag43S53;n%iWY2$(|3c{wToHDH&3(bMnG%x_p6l@Bo_NsLI4TzZyJ1tni7jCQ4gdSX93{Su6_C7@41atC5|1 z?rvQGK414a=%}Alm4oaw5!WNqWWFmexzdU*hUOL_5)|a1>Cq2`MaDA!Nfj=qYIu0= zo6}sd#wNg4SFTB6nH7SYGS%yEyY`p4!nGoF=xx#4T?tqPZ0du!1oZLMQb9d7+0?dE3SICry`xAEJ)`gXpZ$u9!a znEgZQIjt~<;@fWU-pp5V=QM}gRQeoVnn%Lc|LX;yx;C$;Uu(L4QPxz~8Y$J7B~SRu zssXXY{%*W;%$j8rgD&b}4oZ};lJC*{Q|e>ScOS)5y=-UMfM^J6EJn-*3wh_?kKFJ6 z;K4)}wkP$?Z}@?Se_py>S(nwmFL|B>Chs{;(IgN4+I78Z2O?ZVJUCZfpLsI(PC%#v z6aNn5#)Pnp$2sa07QZ0eoJX`7$3Taj&CrnOh!g;aWX0?kgBOWl^WaT#d9KbyV4|?0C=xd&fVab>D zhX)sjQ=krm&XMYDgR3?AlKAWU*gfOI1i|H57fQmL5YMI9kaw)$GBhR(O9}Y62kA{Q zHWU?2zm@7K3H-grQBIonDpHK#{u|_~h0$rsxbW~R-K7qsg>YSJR;|`T!Q(0R1rbei zsNlZY+a@!DzW?62WTlQt-P>xe229e+Lld)TzkG^-`}aR8{<+v)F6 z9qz=QCR6-}?JvLr3Ix+OT=}PR0%OPUWwyh{zoowPJDwOZw%um?5H#s3Y{X`izIShP zXZT}WRJabyusV?B{gZXRb`EBx$KrTcIWgiZ@)F^AHx{C+|LF8BnvxvDRJM&al{Qt$ zvpy$XRi)G0^3In3%9YXv%0zwyFvJT* zt92ZfiiiQ@4KQA4ouA18Z%9vuWH5>d#NPn^;03?0kGx)^7*3Yomd#sjfwcqYy*-WV zW@ExQ&Em(<^AYU(1?+Yotv@Ec84#s6YWA>?=_I0(E;}-5~NgdO6dZEJS2vn00XIxk8*l3LHO`z z^m^JvZ$+zr_+o+lFR*hGVilNx^g#do_i|h~rG;d_?iRl&j?1^Jkaw3B)bB+>VS|-% z0fn+MV%1KAhOJuw=`tfN{KFT@6e7KCinY}$)ijIDl%xuAHfuY^B68#R6{}A3qQCi) zBGDSNjrEO3YoR{wp}){xg4oF{7|A}NNMdr*Y9-!hJE9mm6z`!ncjI$!!~Bnzf~G$1 zqd@t6-SS|&tQiKZimWR-(c^Z72^SWvgwtcL3g#UE>`|EB%d|LLN@h6)V|W`ifCXj^ zjbDvOf9C!{A|Q^ajp3byMLVe)JsuiQATJyKclzB0Sp?*1`)4GtXV&us17t?pg=mD{ z=q=;@Zr41Gk1Mt^Viq}<4)FsH1zC~-QV{h?c_pA~PyrRDh}^%Z)sr1KnopJ5#*3o| zhSR$Ce))%nu z5DCve|NUn8v=WxbF%W$7x@V7mdh`O%x95nypGM1Kk-+t>>1I$F*+s9=qEgS-;uAZ* zVY|Rrpm4PC=Vj9_34uL>!M;tRXapvm?5YIm6*XHm^4Dvp)%9Xe7wkR$Ca1W>;<5i!7PC&3MK*c_!Ft_E&f` zILB_bO!*an>6V%-Hm@uyiKkx)Rpp~>2wVuRgKvL_FxCEyG@JkpJiZu6Rg(WRlTKj* z1S&2M*%;b4qG=0X%S^wZd0@Ymgz-!Vmn@-c(7!81~<{d<;Q`E5Fw1+WtR+ z{a5C8Q2&AdAay?V2RxAmZI&VvzHGKqP?zKKb06@{ua|@0KGTCW6?b7Wz?t z{T3Z2(l87=S}2vHEL5IwgjUdzFaxLSRnmpeCe&$mg|WM3BS7H^{FY8M0sn&JVj^Ex zQ2+4rF9}%2{_Vjtr>TZU!6I4JFoc%AF5!KoNFi;D*GVyB3HTaIAo6ufiwPs~M27dV zEX6gXeB(3A&oSKdlSZ>Y{(TSwnng07$k6Bz;Dgg{iwF13QI{;_DcVgLefk8W)g2m4 zN=5w`$dqyXf@W0Z50gC|wV-o1oxO}BGXu}|=y2cpV|UvK{?pgpn;U34d}%EFvFo#;bals95BHxgE(qGQf|;Ws zsp^Ww&&qwCNZd1&cKRYE>hSR8F*sBDI^(5iP8cD)NwBXh#!NR?VTUJ`V69a#>%0X3 zmrZXlx7SoZhmmA&6}@-Th@=YZ5dCc+!04ZbcWUXZ%XEl%dw8iR65*^D&KmnX^7ZS2 zOCL=nK^O|+v(&SXs_I|*+C2GBOY4R-VzIB#NfSqeP9&y@u>ROGp@p&PtpUK*A0{_g zAR^u@byV_n?|=T$`}*CIESf92WOCA6%7BnN978UehdPUZGk7{1o7^&Ef*}q-k@3_a0xgw-`KWVTbQ& zyFKsU)A~_*z5S05l$gPM@Gfinyf(Wwyf`bai`use_0x^D7LalF1I#^b=v)$Lpp^ilXR_ygSD=9^B@mBcWapU@lTi9rb#dV$<<~f_YS1e|t)k-UvHnOXY`hh2j?}Tx^eZRZI-hT`A^%;k0nsTAbk* z3D_6PWL}W+$rLrLV@6XUQ*8e6R7@IR?rlgeoS3zQSliM*TQ^HH^T$PN08yptNvjyC z)r)IsL{cC9UV?$_0I_tTTQiE^)Zq860Nd0lyId+KX-P6~%!<)S!iv#=mlpf!_0jh1 z-=nHzQt^a8*tVnF@Sox=Q%_5!vQCI`(!%YjDrac0s-_>A(0c?+U|U?5 z*Kp7W+VElaNv~hTWxhv0()=GK=35ch_T#a*GS@MdizGe7&d@Vecx@jw7LQ|{Lvmc{ zjE>noBlq>@XuACL=K((c@5EaoM_)4Fg3a>#u1u7QpN9I0@?mBEFOW0HtT(*S{Htn; zAFyjsk#iYlOKGOy1hv~&N}S+_;(gns8{^l5*?Wd%ndYV_ft1 zV7@*7q->fNY>c7MNutAC7&s`9l07AzJzOAeRcV1lGu&@ZuHhs zc-U!#wVux?Zx4g@HjvxzNbvvT>8!%qYMXG4yF+m)?hxFa;@aZwUfkU^xVslA4yAaJ zKyWEq+@ZLX;IQ-k``Y^?r&(9t^=4+C=bjmKUd!}2dHJU|e!>OBaeOIMlr4|T*4E=y zw%KSnV!r4A&^NO1!u@7i{pqE2OtufK;Xl5D^h|WkS!13aU7Tl!)dJNuc0p56MQ62C z96BXd2bV_Z){CnDYVbI~>TKhQ4MMH%5T%k&eFzvsx~G zS^To3l!~tFQ}loZNrIw zZ{#%Vz5!aa#Hm0_W0D*O&T`xQ0n|eB4y_;Bp6deXl47uC*KE~EAlrtVnyvH7R z#Rb~^z`l#q#XEnPE19ot+2_V(iX+U!=m7Tk9XxZ^ph0RY*JiDlC2G#EzCXJ%+^+&Z}ts z&ib^zG@c^7XL3U^i=sffunh)=iE5tf0jO5rzis;3Pe1};tNY$|4_x3*&ru zhFm7xGmIel*97>^zmlSKy=_NquHCp8CHRIvYSS8cwfX)0PpWu~WsNeBHs1VS9y*rW zOYT3)EfhK1-u=)p3e=TcFLD(%t4qmCT7kwzziGD*t{+?x%@ZFbVyXPD`xW4HOIzE= z6K)fm)Z>>LkA4fq97toe$HEv=+E?2*lo|Y-C_6nMm0qvi^Vf`y-rW7JtjnzVc^r9C zFX=%{T6GRS{IafYo6(Z}{=@muCSZo1m2hp3Hs}Rf(qwRcQ&yqnFS+cQ{`UQL3%~mn zs)3TGBHrNA3uPLxbDIcUb6>d|HA<)H+A{jy>U9FwDN$S|6IFT-Wq)llubhEwg!maj zU*Hipy(4r?K2__kM_tDbAi31(cg}ia>oUe$U9!8mRzUrp*Ax^kKZ<@o~RQ=2XC(CH-QM+v*;Iw4nXy=34Iv zZ4hg-mwr8`1b&Sr3Kh__>MsN*y-gDJ)>J+HLTTqpLh+}uOc?M8XGdKT)sy_IQ4N1~ zuII3e9mX8F^4sUPeV@pJBWP4`=RMD@c>t5PlaT~HemSez?Nb9T@Kyz{AdU;aoZO3V z;T%?Oi!jI<<7NR>c?!n@|5p+?m#2sft4YmCFU&S>u@fie-Eveiz)`3wc8FBgsFJ%Ov$H%b*5ORr`neQ*ryg z_&$%63GS%&Glu3OVJojMt`COvX`kx+m&kdBx3n?wm8%rppm^$^l<3|$D)@1>B$;7lROBd8HV z{A^TCiK%9jRyOfPIV6gS}z z|F(HJE-Ij_+wi!Yf?Z|h4x3hiz2-Bkm}*7d)Alpzzg80E?`^*Iy??lV$xL);pzW{) zP$oQC#yK=5`(P#900iJdQ~-4A80*=#FU6(Yc9g&@i3)BP0)HkYU!}~_+3qAihk{QY zIt!;7G)&%drPAl0xOV*668)ReQ9V|;%wufGQ|)BP>5x81m&X8wxIO#ku||_a*Y~EF z5+)7Y_w?Z)#AmmqE`zjbc-Dj#cy9HQ_yaJt6TM9oCW0p4G^dbMweu#*b8P7WWOG<; zvdan3>rUjTqjPgCX_5OHrlX{CyxEwBZjtz`?S4|yeP2hOu!Cb&YD=`k{?Agz7WfgC z4);;sD;Vhqd<=bF;T!_5b)p-RD>l+5KX(o@C|+?eMn$_s|}X|Kfxy+s+2b14}3n87aJtjU|%B8oibInoIp4EI%?z3ia=H@;4* zS_qvb{Z+D8ruUI6h3%t5;>=;Q{FN;$>-k!*Sc601G~XT~w#Q{nn<>Wfqo?kAy8XyG zE6bT7t=Ibh$|#4EJNg0e=Mj>sj$y`ZxeqrKo%}DvzKluqUg+m@se%_8j{oWAS*}DQ zn6c_h>@6-y5TU}~V^z?2wPh9@9E~m~91E39k#Tf>jy6ziZ}p3*mm2o#6u9><=h5%$EJk zRog&4uK7qFIy*occq% zOleKL($PJ@0GC%6B0!gU7m$>V5&U&mljJ!tl&%WHp!W#JuOeOEPL24Fi?OQZqKry% zLZb(%iOgpn^3zYiWjgQ9l-Mz_n;e$HUlrkqkn?_6Gi2PlS(0b&BAW;uWmiDzPRgYU zOcI!hS}=u3i0LzvE7Ol{8>5O81&;QsqPx33>#)P)?;qS&fN}%W`1O$WFKHrTzKTSUr^&*F*+poB2R9*-s3BW7>-&=y z$(q5;wk!1fk-m+=TXQ{2z8N3UCS!O^!!{#;$u-ro4ZCFZGya~nW|$U%-aieSlo&WY zBMVV@k5fl#1ZQjuE7UO1-$?1<4X6RpETWXdk9U|zSXNR>Ai1kFyDy7mH*TfS31^T_ zl0?VdhRLhf@xL?)u*}wxipIgn>*qW5j$>g5ocKGN$)-F4>x1d&N_&CIkSi=?CPt z1&M<4t_?sBRbxC~)o?7X<16iX|SqI9L#0pvxTK+ zh!X*Ct{uoO@@k!d6jzl)(b6$*qgL?E;#Vg>wLpLX1o4bYx0lYFPeakDKv=k{Mo22 zv&|We(HC6;p^ne8&hzo zr`K-#IhUi&LK0KonvEWW(#HALOIqhdc}rp*hA@))bUovkB@vK_M0Rb$xm<|n5*$eX zS;wszWp(Ic5IgrA$8`YQa1Ud6?dhH3c5x`@y*96oA?wdO3vuA}2Wg`>(^b)swfW6p zzlhD$4-=s*W}nx4@^YYSV^3eFx%BeMK9GSiJ7aKvWmvZQ@h9qtURW)Eb>yYa+#j-e zNd;L)GF)k!1iF-{3ewhCo~7IPTb7diN)*OeL_^uD6#>Bu-zyBDl%KvaG4F+th!%b* zo{E6i2M=WGHhZx32`pmzPlD!ISkhv2Z8AQ#0YwlSh4$2SwN_+guGgW3n9kL_94x=i?#<(I(V{=>G#cI z-r4PAil~6Ok<#dU!$3!fj`*ouJ&f2mneR-eiP8SHJ4ociO&zuE$3QE|S5}@P$gZ`Y z$+$-kuZG!*0&{q?7-}0GgU26@I%a5qVISCq8dj7i#P?HM@&pNbvlQp9NtjP|?e}a66hPM_kVIKQHIrGaOGP^EmUmm8%T4oa6eI=mgeC7wp zSgLriYA^I!HGFS7Nfq~YfnpV=WG}%`z=Z65O98I?KuCd7!~m5EI6>ne(SS-`#5GjRgVyYbI7ZNW7Rv4SrM}pCtX5l-( zT`ILSiVgSeIFuwq#?eE+Pj)C-FqmKX5?^Zw59RGd{{+kNT7{3Lg8Zi8&O%ebp&H!~ zG(s3;8PqBgv<)cuBLgmD;j{GV1F%!pq+HLccsr3=d zcL`=EWFu^||Cwz)yOeBJ1iOe>g+lE=14gLmD8}X6~BlG zAa0~X>enZR z&Fb1S6Zg28<5=3)LT<<9OEVp0d+TS#I|+_fPUSim2F@&Lujo1ouynExgEFvR*~I5i zfAQs%5YK*9DZ^hC%Pl`WOck^!#p+7b=(fkD`>9bnEhcfaa~@mR4>5{3TNi$I5^=%O z{w2eqvW$=M2f$H+Pq~8oEagPWF?wT`few*-k>b7o%H{S8|9%5%nvx{#ahQJpX-)Ax zjGL!{;=C`JI@O9#Vu#l{H{7%#PXjIXu`iK7u8yYwTj*JksF=@A zC)Q0MZw_l;u>fh3ZXu!q1*V_FvCd6DSge2#vpGy-!NV8RTrEg-mpTFyF{+MiT5py8 zPI!xq6~`kig#7Yx(9Go0ZNXWsJSGoSYFtVw6eyehEXTH&LIA-sDNU^GY>hdu2l=9ZBUQl;}46RY$ zoJ&TKskW+jhhmtg1>yt4Z=A9$j+h7uI$^jua0zlX&%~^W>Azh)qs$sB>8%mUOWc3! zC~h2!_4iNAkZvp|5butRB3*l_j;YTn8n{$NKshNocB~qH)u6#H7YrX&|5T6)pAt*eY=Sq*wE`4l0{wSr?JtcK;ib@3-dR&-HDSkP{bRY_3`Te=GnL+p>!Oj%s#^ z21gzQ?;6s5ByVZHDQ<$<2&0Y>T!Oa9;7r3Ju3fXRYmln2TEe(9d{ zyW@rf#|lrCHy^V9N@Xx#`UqnhfzrMqH(azW^8nYJXjQId*Wl|J@8IT-=jMByU4;Nl z2nv=39R}JJ!99=70^|R7IyW-%;i)+1Syix;OQ;?sqAdaBjD$KTvM0~*NKY1217m3ybN^+@wS z!^R+z6*dc_N}Mon224Z*A`H!3%FGPuLolFUbe(pUJuYcsasDg30 zr(onb09}r!$VRF)>UsrOH7wH_VdKKPXQxtO-;Tg84?Jw<7e_A3`ysqR_HH#26BhE- z`EXuFY?&N>pCW%9f_5{#f4i=+NtJAk0f%#60wHSKz#jE}3Ho?~--5YK%YYTX{f7hQ zM*!kiD)<&mKuTU*Ec<;dIgdIo{LY-#qVR_Ki0;(GNqkhGO@~Jt-`x{7Cqtu=l`aI5 zQ~8~@p)F&Gcsc2xe{HQv$T?7g$89doSs_rViZ{z^$RLwYcoQek+Pd=f+^%?r8M9sv z^QQMqN>!Oo4_SpzQ|NQljZA$lvX%v+s3c6Xk*TizU3rjNmFEq!L#VIh$RaDN(}n_N z0JOfne>}S_TGNG!&0#NJr-T>BJG^vYtM03)x!vmnX16KgcrV2k+av;O4XPfAi@7>% z08K8(t_elS%^;9GN>pOwm|miuSa;|}5kY%c1%VzqicE2lb45a-5?*g}m%dXj9rd=Ak zhcfG2TEcx!y%YYu8TpvqoJi<8lSGAIlR=)Ebhhi8vg9y1^CcJ04gC!}g5x;KM51zFE^!5X! zn%!M4cO%Dc#+JQ%ma3FG_*l6RV~6MT1z?0qkqtQ!l*AQSE!2x@UP8X|HRL${`EfY4 z)EV@b=^`94HY#%FE91zw9TYjLpLE^!m^^8U(}OvCG(<83Bfx464~L($KTz5YZMh~X2PlEY#NAM}FRpN^{!FMy(#6PXF2B{C zTy%<}3RmGp6!Zb1`g$VPSkjzRYQC>ubHhtTevlHbk_1FB;KXA?Yhy_lx`C%|Df)MK zPZ504ye+2(#cTes@!+G{(5ivmgp2fvtAqrHhT5ugsPDxlaM0E$yk7a&s>r??ueg4=&&iC-lec`hp-cq2DNx|tbl(V#iwh$iS#RtOz z1dnN({P&4XN&sNhG9IBE>d?n_%QGond^DrAsnG{EePCn>uhM!JKHA;xvk!?FBmJN) zAmQr#kSL1oOS!}E3T2-ciHqfLOfoj3Jh*M=5P`j zdAy?XWlJ$;HP`6K#hht-XqFKhoBuh$Xo_S2CY}@_eUldL!6~?|j{%`I{_Q zP4IJ221A%*;Lml3=dLLBuflm(!EgQS%~=waJ(IBC1i8cngj6sX&sUvbHqgAsVACka zZf?djdW4A!F+#6Skb3d26?vRv54$o^uN#LJnY>$=oZEQ77IBD#ON=;6I-L1}G+ZQm zuaQA!G3KZi9&r3y#sgW+uD?v6{%I$jvMO{}fD&=cDOYfYTGKa1%gj6^;{!2Mfjx3^ z3BZgoaZCU!N|FVN7@@1@AAtmE@=uY^PQmwk5E@)G{ogii%5Au4?^uH9(JbP1HA(;U zh{=iU_6NU~i-FDJWwVzZ{R#Up*-|^Yn^M#htzooX{^N`w-qTZDTe-?GrCuP6J+FsJ zuwQT;uQQNu7zVLwwvI9)LR2Mro0JE|w9|2nptPBtS2%%!gL^l&zgmR*v4?w!boxJC z8rlLX8OOPuwj=!O#LFPwji`w||DgQd`So=5}`W@ ztMk#yW#sgEJD1;6HN_-;MU1Ah7SBS*kVwT$`453;!h5)=gLD4tsNNR%W5o8hgW`d0 zXY*a4742cU=#7E9y-#gK6)7RKxBnMBE7bcE7`k;3{tv_(1r%RIH)+;IaitLn|M8r6 zn3|l}qwPu|{VQB*S>qwd84pw9C_kcX)15ebR_3 z$_v86yNG&SC96bV5nsOtpCAR{y2%(Lx{#qeKI;9Cfw)ko%kf;+Ug9kPLp{?Fr5?uA z?eHD(B|UAeFE^NjVr}g|JA(lRkdnEGQx5}&|55;PnUL1}LG2yOifO#MOJ!}i|* z1TGWaYxm&jZ25VN8vnwJ;f^deq9x<6E*Qfea>Z*C|5GJH$l{OA8mcuQHrr|?vT}tJ zH<=$2zOI=SaV`sLrE1cSL}9>B29(5`f3cZ7-&t>o6|i#R@>Of1hs}@iXr$m{2-*ZX zfHK(1=V**o?z?R%L4Wygoe1bt9Y}5;G$;q&_=%l}S?|OC!)d=B zxrD02n>srmdcbqx7_@6faZG`v_7$t{uRLFoPLj1SN;nstwQi>PH(g*AnnQ66@vnHB zq?)LOa*MHIIzcxvT8CmTmst3`dp*_7q`RbuzSBTmuK#*JEKxy-#?%i;=rrXSf&U>( zQgskSCt;li4u|+(;@o+8$WDlTjdVWsMrMskqX{H%i@e9sd5v9Y&-a^@U;b|^5R!@_ zT@K0c;x~OjNg>TC^kaO^^@UJ6aSb*?2hml1utbvD$B;&FUKp$?ViBPJF|3ET5zB_E z$1@Y}pt5I3{<#b#%}ddN^q@xHcH{?Yxua(?`>4YKJ{`Y zJ7w&ttKIuHynS+Lvng(5!mMkb)JL2@iC-Z^9<>v3CAZREN%As~Nxbb~*f(q_|uw zgi{@?y0xg{Ucn9E7T*jt3A^VKp^q-9AkM&xA@0{h1!aX4*?kg%F{Wl1>FN5fUl~DX zKlfI`R$$Kn%|m2s#^J_~itSjsL9)(?MP7N|d$XrWXV;&%2;-(Id~Mhk%nobYbuOk7 zIti9Ft9TMo&I%Q;dM#mJl5`hO`LJg~VAp!x&T~$#kEJLMPgA83Q}v@}9&@j5*^-b} zDHwpaY*_GU*BNF)oo?ldyB`L{+>3b(L?JBVhq4M?T zE3v%$J>jRge_G!^8n}`()XBG$Ccxn!hL@q}9dx~+CL)P+T{7+#BU?^;JsW&z6WY8O z_A}mAzTyxLi1{4*)h$qfC{ko;sjO4OWg9*+05U7pOZzDxYb*PKu5`(%mBh#T=5g9? zkQ7QsTHN?5CDSoY@WgY=HOHmd8IA1K(w!``C6wAnUS7{!ubkKaJo#8^S}OG95Fctc zrFkh?E_zPvXVXzv#bgdlFP|(~u+4Q?GN(yF4~Imq9CAcKAqyKPWUNtuY}|l7F%L@9 z6WpG1-jI5ZxpaF-N;`?j%P~NHT9|-0Hl2IaO7~Uog5$idg)=~Q*GB{z^ zAY77Z4EUQ}VGfY5M@BBwy@f>^QvUcH;3|V8fF6SCo!h(&62}gpIODZ!oN-T~Q^*j` z$%I!ZfbWTz_VRCh?kx?a!;0B`wNev14U|?lLh_aSpX@!_)cmV15-J4>rGqWtR=R%! z+lVA!FRBXPN$D8sE5=zfGf2gW9(2rpiDfFqU)eerAK1~Sb?Wm$M4vdR=CrHMbxHpsRM%8^jHimXQx#j|JHvXmlX-7X6;OU!MO`j z)gnHg{{M`@K@aiWTDPVKXzQcDW2W*QDEb|oDXzLA6ep?SeqxqKo{>dhtuWSmd2 z*GP!sp&9A1+#Uo9Kt`ka*P0*6N3{fHi$(z46uUtM!{biJ?4u?`kE*t)qG4V+W%>G` zV}Y+jbGu?OX^Kg7tM+4Rdm1jMF$JW{f5S=Q6Oa7)OHZA5@xZ{n)xQyuUe9WuB=T*4 zkslzyT#Ugd|}{ z3XyYU&1rC#NTE9sx+1R$``0@i3tCL3=|3I4)^k0@zi%M$D)N4EEMOo(#xFxv|3ag< z_r^e~o|Ur}_wB_09HDRF%haQS!(Wy}R%UC;5jKZ^`J0SRPcrGmcu{^y~)uLBoO?r2Dw_$ z-*uG1trJ0Vmv?pMBsD&!5MP;NEhxPPx{-^L_p?#w=uT}sURW!Q2Ld>j>uKVa4c z#Iq#zuhYwZlag$fZT8AT$i#ur23<$&ih-#uf+Gd#_He=&7wqI(u_xoRE?h5od2Q3% z3PxQo_7=|_wOs`V&SN=Yx~Dq6eu@&~T{$9y84buEAai#*k8Kr!*y8s%{7o_dbK|RN z?2|ugPP+GeG&d&~x*X~i9mfx?n#3U5xWt#_8rZiN4Rhfo9`)ui-$Xx6v13OiZ=RJ{ zNOD^dWyY>Q9K``nh?Xf17Fd?WbRKr%ScVU%xrkydh^(BI@TGq|SQ8ReYr7OtSCN93z;@uO*Ri_hdE7-sV!c6f?4)KNpmOdEG zsz;M+DgCnd?|;2)N-bD9P>^+8-QJ0H74W*6aL3A8?@*C!+N-8(;Y17+QAY^y{S)`e zhqEObIy_zQMhvlMbzNmxfgrOdQ@hvXcE59en{;4i>fyO7s*c1?T9{*UpjCF{F4Af) z*o@u6YrGla3(u^5$~Ocuy2X7Ep_2f^vd5Z^HUAOKXG<==`{74|rM-OG7&?>p(EB05 z>0E*GSyn?mRETraaW{Dqx+F{h=@*2i5&6OMo=&eWSn9Cg%Do`rC>+It|5MY}w%azY zs3DtFzUYDEAbBMMgM$Gyl*mXuH56;^%E*c&YfyHu>RNK} zENZpLoT>6!<7^y5JAU+M*Ahf>Cn0`58N32ebQ?7TbzGrf(vj4yFT_9ie_iU23RzZ) zlve@9U33$_Hw}-@dLgTq{zcE%@K-K_V8s4M3^tSak2;%i*F7ZNJx8%5#)40Qlt<(| zh^+-~NusUL`De1|GEwvAW9?XU(L=pi!R(Nyj}C$>v=Fs@Y1usk?FWqFlxt)piQA;) zhQ7^q!skD0m-B5}MkOZWWlXVobS-0!ctYhmltWLSROVsua5$!`Rb{PyAZ4Lokej& zk8Lgcv51>|7<5cT$as|phbv9d1e0Ssun*8gNuT$oHSI{7-fs^lgP`Bfsagc3$|n0339<+WK&hS}*}N^oM!$ z(hTJ!GnCM=4m#+tG?kH&yPXKI9_E5zsc=CEB1v~aGue!@koN&kkKP|uc^~Ev<6p=~ zewe7ppc07sNff3vn&)AfJTz{vpe4LXiF#!W((N}LugU>hv6Q4o<_>9-Y`W~kRzID_ z#am`IF0WbD4eL=&Z6A&S%8KH&F<2~noL-K-%{}!FxPHF?1mn`-PBAaE76#US)*)Cx{a-=WKc^!E_MRX*gabMyo3Ec}#D;W0d&Jl{k`U~M+Ml$H&%WwaqzKGP zlhp*`%FzK=8ebfIXpTu?LRn!WhA6quMi*`dwWc@H_{QXM){e5>_N?MGvKy8kaRcdd z4POUp{h!yZ&W^OI56J#4<4u%{oA9T>GV7bJqMYUYipoy(QWN5pZE$twW-)t^)HC7= z)iD6W3_XMA20XHG!*(+Lu+;g0_2v=I+z(x#=#C6i5fiGtCDlC5w4=R9zeSH&_4?W) zvZ1M(tj2j!A!mlz!Wl-c&MuQaZtWe(sNO7ux*J02nZ~JYb5Ml4Q$p*@ab1eF#R;vd z0aLTAt1`{{hV!loxhZ)v^^Vn23xl!k)z5xb`ip5{@w=!`-e%As*O;7pEua=C9DSLu zY=&9nA?M34%+cmjaYUosA7n|Q>+JZu602Rv?a?^le6IN=F1^~qzq_xs8D?%4WF z3&VzkYcl!W_r{;kj2@;{7VL(N*_MIR+y2|ESv!09y*fob**~YZ1|Q2ii#fMSHcVb_ zPyC-JWhuc{i#M2ElDqKXm4v|kZmU4_nO<;2UhkN&TDzz`nanQ{MTh^%wBdBhv4+n1=L%5$aGI-89(s3wNIsy&GCw0Z& zw)dRkQXK#F;1c$iDu5x#W;0n|=#SW6t3-1THjWP4W-)=HuXJIATN%FhC&Q3JRB@1E zV=}LODfR#pvr$S75}@!*NjkL;*68aQ}5M)Gm8hwZz%5Bzxx zX4eqt$ZEaCKlOD@>s-JuX#;V+sdh7O>Goi`4`R?oV`Tz(o66~t`7-f&7du$Kem&)#7wW_6fqk$u zrIK(>`fIZj0kf9xJc0pNVe6loY(W~M11I?q8{Y7Uk`>7D0!WhGbv2#bxux8>s%evh zcJnyt96p+G@XRbCE$8mBk3EgfSUUmDEETgZ)%Oc{3h#yYq_NQppGuL5aQ-O-#d%x9 zFdYBcqWX*A&o&>_u2NK7U?&kc`sgJFMZ#C@vcZPR z0^j*hb`S@ube7k)k`H|TiwBTceUce+m&vpod%!YKKQ>qVRX7yMmP>DDRatP$1SAO4 zwjDQR?#n{Jo7~Dpm=cZ)zui4tG9hDS-k0rgYk+dKF4dcvMc7U>NKU$3OH;h_xz%dQ zz({7c+nXjh@5!j=;cY`;Wx%bsI$a}?OdJ3H^LHl6uf{pgNP0d}*yK6W{YJjR@Hqbl z@y32|3ZB44Ufv<#to2gf_)2Evl-E&V;kS##T$vDtZ~LQc&k~_h#%*xC1pE|$Jc@Qt ztq5p0+V1IO9^-H-!^1|ONTJ>)RwqOr&SwoCMq&{rdcu6CnvTf=LIe zU8>Y=Z++FthTj}0xa+OAboeqSwI(M=d4|Zmpxr5tl0UuIX9asRo^qlZXbx07qm zR(l$T`pY3`7*~QYTBY({r2I$1UGL!W^oh7+xQ4dC3=f;kH;5%=cCetYxt+6(U* z40zeB%L@8H;O}Xdyb~}Px$g~I|P zb{V8UYw5No18)>#lLpBHN7qG?SNKq(1LBeX5-b5UF0mr09N|hg?b)|VCVHyofY|VU zag9O`RrotFyv|yxJ_6dglQ1|_Ko%FRPS*`}+WxNZ2$@l?yd`*=>ArBa#3UAcC_sj} zU2^uDHqthh$5kPN9=jx2WsLgNITm$gqBcnTyg(VmQPM-~-{z)-&Yff5VCOISCV@Rc zt1@0rlPtKwG_O=;;+(a6ob5{We>10IYgII7Wv*gsuG(QsR=>72S>f(3Vz#n0GRM9& zU@W?+WO`)K*5a=i3!zr)X~>0cX^WtnGD|zh^HY%Cc|iC|Mp5r5SX;GXXdiH zg#eLl67VKBzQTFdsRL|57e8VpDue4i*Iq+GaeQNzFvEds&OD5iS;zk1{n`-YoR7>^%p$4k$zE)NVB9K=@fg}Z51tUxoN9$4P5FM zc$vsk6!iN51a^dK?|j+Kv~5BK>3>Yy^}fPxsGKMkwrwmUtjg$;_C70zag)edb(&hn zQ~B|T#v>L}(En@5wbQ*;edLA@vD-%NFr+s)y3$;5l?nXK_up%3&)` z?GZYZP&?t=ap=`ZCcS9r0j!;H=JM@i<>|gxs!{p{;UQ7`uHC)%KBRqmDc8iO?u&hu zCF9kB_8lYunsiPtftE95`tV^7ZA$2p{7$VzXH`D&HE0_f4a%AMpLIC5d>NZr;&kET z{j1#X^+yz4Jv!9o5$QD*BoBRp$GykbXa=#!>$BQV-V=5qN3{2+KQ?bmKu5Zq?GnT@ z!81!M4uAZ6QTMPhoe|#1u5(kjvA`Rf490eT&eCiHzUd@lCV?{~jyzZO&3VTO+R#w4 zpL|7n1|OQ%A~w z%mCVgJ5pSyy&fyIn7|L6tW*VC9KbTBAeJsA5UZnmQ#8&M4jx8Bhi7ys)U{RH@!k#?F#2NXUsccfVP+iiDFm#uC5x{$+%nmaeV|YfYipgvE2?rAc z7Kg~tl|6J1!r29fVc@H}Z3brRJJg@GeJKUztBBf>h$q|nu(3o(#I8wpUAf|1r!bI% z7KSl|hie7Ga)%}9$`=MtSwx|$$M?hn=!#lny}!_;q5i$8mt>oP&QK+*w}Blc2Yc#g zIp6)(IUG~JD>MJ~r%4dzf#w+5Xb4b7Jdlc~o zNkf-x9AFrJEyopPdu`xw!!-qT7>!8GPcf?d?*@KWUaA(=9q-I=qrYPC+q4*Ag+(pm zd!QnpdB`bDl^NR&$&GVId(n|1c&U9QBb= z(-JTw&2q)tIk1Zqrh*{r4_h$%@lxjY6$L@B2R9NDZcFd2Iat(Ad)839OF#WkCPb+8 zGWNnA=sk>fE716bBfe%jE45WryIIpx?n4<3?(||_b-(6L&`k*SVmAwk01L|Arzs|r z<&U8#hihtsE2)FkB6xz&n&CKQ^Cj9vOR~gs%;obWMARlj$wxvKahrUet z2dVgc3l#DMKH@c39IO$+*)PuulihNVBdlx7nY)13=$cAJFpoqmg+bB1>4h1^ z-cnEh!_(HuvHEQlXSPF=?@=^6$L$YSsC6pXcMjOQIUk|917ah&B_{Srh7-XkN?oBX z-;jz#c3BWY-?rQiMA{-tAcg;Y{l~RrSY)XN8Z7HC%a`Kp-FJf0=@oYX?6{?e8t(zw z%98?re<{Z}3)E05^l#gP*ZQ#AG>fHm2?w_G9mTh6aDZ z_djSqELyp{EeQ1{2dOol%m>)risaQ7i#C5xv3PJDVdN2EMyD2m`}r0nMm}`&Gbrcy zeOp2m?WPb|S1kJj{0#Jq{ewV#a0q(n`bqpTkmVgRUr8$9Aa&L`4Kn-yL?^;Qz%!h> zP5~wOj-z<2O%MZUAraL$Ycwm~EpRYdL57Q2l_nzr7|tI>c_dH+mqAZU{K1}=$aO#6 z>RAG_wr+Oc^>R$tDg55}KRBq$@;S{m(q3de^e!fxx0XK^j{K-SWD z5jX>MI==5wdpQGXwnM1h*o;^6RIsLc+AhCDaM##$Sov97yYtn@ALv{|$Xm~}3V8|@ z*q_^L>oclCU7#hrh}_ekXs;)H@?w6=^YKrR24-Q9B@~Cel5YKsYxbbPfIw^^OZ)-Q z18_124p?H6dGhUw^s9G?T~a3M3!@&tqHn{;#vo9c_O1kruFu>@*aPK2-C=5Rjrk9Q zwPa^iP5(RQBt=uirASs33J;=Rp23{#;$)PVB( z{g>CK0aM(kx_48f@uQL75_T&k5;8AgBmz(d%am&BvcfXy3jkcy?=ctadc~_DQ&c|v z5Fc}wD;#{Pg(~f6_d7^(qSn9LuLaV47F=jqR6O=@bMgtYmj0voOSAKzlJU*wsZHs8;{j z7k&K$8i6K#+w}kE)|XRU?Q0dvZ+3y7O)uec%F^g`t8a-)loe* zm>kl!)4X{tT0B31UOvGuLY0(FU&4ot8UV~@vs$Gw?k|pO)NRpi5y~aTlB9XUL$M`; z7P&vG)&8X zY+dCgCd2f-31WdUkNGhGKW13aCEp&Wy3dLa9u7prW?eAz>Yuf$KWMvoNhdg9Fl=M& zC7`3Es5E+U|M8iGT(=O*VDNyf?ep%4Q&B>dK~>>G95%iw=|^;B?2v>aeSc#(%q>J){5EbBQ}Rc|}bm`a~#>v)+7 z2iSveWDx;AKIpl-Y;?A$Zr85(yQlZx%5;?E*h< z_Ww5Z6-@`>0S@jE5>+MiT&vMdZZrLP=LtO((awJk`ol|75_eE6Pt|{b&bAhoN1~kQZwf(vnDw)0T7I9n?2f<3BYPz{uR==*t>2v6PSMpVdX<-FzDD=BUQN0+8y&{s@~_NQ*s z)HZA!GV5@8y5A-Hw|VBsJBlhsV|lmNvubJ9Ff5+kQKq<0Q9R=xc&g0$g6K8U`^Czn z*3_lT(MwZbVSkUkJXwXs$)QLF_}%zKO2X{LrDGaUy8KrIimp5CzDAxpcgF=3?m7B! zv@lkkNzxf^f~Y1QEJ=z@uPonY;`*W!9kr!Myn?vANVs^s7dm$aHh55$2Q*g9f0D$| zW8ofFQjD#n7EM?q7@q;H&R7=y^20-yDRO!5{b9Exx(fF>`xZ$wF2Zyfr*}+FbRY9A z^47_DfWN2`hPW}7QO9&*I=v=_43F?$XHf7}j|;Hs;-sVPL)8f!9j39BOBDSv)+%`= zkBBXuSZ6A4k{?)+cVn?A=c}Hl33tjrjo$;e7mAPVYbPTsn=$sq8Mdi_NAvsDnS|$> zAD)7Mc~L9Xj1=${?|Dk_7!=lHS=>TiV3&9^YZAQsu0PtJ13&cdCI(5Zpq3BexI4i(6_+ z+m;!_ot{t{yq$GDVvH2B5kU>qhXt)Cl@FIJ%EaKG{~w;dGAzori+1R4B!?~usi7OB zlvI%J?vA0mq@QvBn_iq4wUtL@tv%$RusqEm=U38nyW!xDE_mwd+gtM{3%F~q4c4kwTXH-Cc{ z9EmT<9=Q4+kym{;e3dEiiY((&n|erBiNr9#E*J5>#~GuZzwOgB*+G9JABvSIOK?Q? z_iPWMN-LkxTEa*-L5yF1#sKeD?%=LhDA~R!t}^9gg3#q2NmdHjEj3B?jvGrq&1U^k+w&#sE%N7uVE2DrIr~hW@SCSbF2thngNG=JHq2>G!y z=Ge7IyKOm8p)s1z^`IUZ2ot5geL6GyG=OotH>Y`4BkNulmj z!Y=rC*=wA8POU)2dw?gVe5%5?>Q$dK+}rL1z+r7#p*{vL+XA~C&IOPL{Cb53gBn=k z7{__E6r_dRj#JB=d$Rx zSzt*2~)6iOTT1a+^ZLvlZdAAyAc!No@8vVx7ejnoOiNqKL|xt^YiB9 zX5IJ^=FgOQ)T-Nqi;mjluQE2jiDy)MR=<6aUuW8m>aHig;g;=pIJ3&ZLrFbYUKpbS zryR;d#a>p5d?r)BI3Jt-RV!M>yq!g=&kD@LQ|(nDAmj{yXk%Zi1}(C9dI9dxRmi%% zM6K}+-bkB%J^)I65E|mB{tciApP9r%QI-@vdj7L@-iI5@pdb4x3L3dSNlZeqJA*2| zPwHd&gE=pPCAz!gb+nn1gnl&1Zer9!m>kW5;IjQ6osttImq|Ee%; z^wU;0je$?V0$zUF5DLYU#@^ndaaGD^w-4uw=!BH+`%rHs)`h!`Z&K- zkfse(3TS1;=}TBcB0qf_jn0{2FDr}~Sf%M@es*}a(=uo{I&@FR>d{m=yKAw+5t8DG zZy~*!74hlO8|f+>-gY==){1RO8dj11aoPV@#Yl=zO8+CalbPUOcP^*Wcnf!LZpq(D z^YRKMsAPW`U)$USzT_8M8(J?>9#(jX!*=ADKX&qu@}{_FBX0)nVe*>OE zSMfXme-`=4NU9RdO&;tJ{7PYdP7(wVrfO00yJt6v%>NX z0wQiJ58K&!$r7&)$+V`#Rp{;4Zmh0PrOf&oz^dKtG5_3=&FbOtjwEief<{FN)v;3e z9aAOwU;e6BNr_n)F!)kvoev zF%A;#&di>zfMKAit<6O)_&v&(MP*_+Uk6y{F(Z$H$k>eAX6WiBONzw)u(D6VxA2dM1%6oe zlXpf5i~`I&J7isP$2^fPJgTQ?CGQ#(zNV^Q^mV9MF4oBSt*(dVth>#i3-k)Bj==AJA0Y(J^HQkf|yfM z>}5P9^sO^?2e-Jy>)zsL*P{WM&>b?UQ<3QjAbq$|)FQE>CUr3#7ziFu8nU`MO*f-2 z8U-W|)^d$7Y;oE1WVb~y`Z?4Cp_AF@&)RUOMgajItyP3wpcv0aZF{;0KAZ-pz{cg zZME|^wdDIpyRsi~#1Ig#4cyzoiFYMq@?9JaRPAm_z-V9FYc13iJ~Mymx5)bN`O$Yp zqH|vS7rKotk8$Vlg4XVnrZRHMiwSxXP6=3(7G2(Ed35OubnR|ihZX59thj5=3ux+n zRhWeE>tl=jt;^>ClwW!6V zx~*RKA5a2q1@@D|LgZMN9JbVIU4!p^0Jdx2<+BVC`Q04IMe16$X8k!Tk_;{mzc*0* zbHUf611)afQ@kt1{mDJx?c}GM6v9cLa(^UJD^X;6Sd=oQkBK_8UI)AVh!C@`W0W() zG9kZ2EPo?Bmvm(N^POPT3ceV9KU~z(a+aFGmZz1ZB}iXN|($g39+(;duchLtO#7)c}emi)PlecFpXy!Di#%9J2 z4zRKapC(%2yupBHCR9uygao?8=y^PlOuUk`3re7oaln|(8VmAj-Lr+(H)rLjFNo_= z!A$|@nwB1p=68F7p&sl#&>^GNjS5F;5=u=V3CJEL0(CtZp^x75 zB&$dg7Vuvi$CcVy@!%X|*ymfKrW+rWz+~Nor-Np&TRK7$_8u>` z8w=x_V|PwD>ckToG#6 za{cx1ibciAEZ53vjYTTI_n%9E>eMYh>XYo2MajL7ksD~#mB{htm0K1fCiIc9bhQU8 zWXCSW(;;UV6~=A0zi9*Uwv3XTahxIahz20-#F9`~bllKy+Bb6Mr+yxZFeA{FYA}X@ z`1+?x!~$dYhBnNYW|*dK#9NHwOjz~YHz`FYcr?krqUS7IYHyGPk9g0rzXwN}W@$=DI5fUNxX7*@kJDnklXyj)mten3L+6kGvNpcRP}!X78w>gogwB&C2>YkCJ8({{Fe=Bx$euGXJw8;yI4YG%z)3SSpLk zn`#<>;ZfJf5(7%bOgCb+x#L2Ow$%o3QqvoR6dqHJ9fHp#cDU3kFK=Obo$>e5a& zPET8Hzp)%X=TS(7X(qg4g$-*?;Z=+VK74%P6~w!TdJ4|!eLVdT-MF0wPOpY>`!t%P9c2W~&IudBh|y5uwtiZ2x4Z|I=HOkLqJ38{5vF4yGu z?UoR%do)z#b~{0Am%N&0kuunnM=AQdh%%b8!D7uVAZV9>`lm#=X}4RC8;4&2m??5C z0HF{d{u4JSD#p8(Jn3+A9wTI_r-ZWtdt5R`+t!MAysx=?e&n$^wzzpcqLI=etCHpm zC2svQe(cPhAPwxZ!!=1KVQK&2HumW|;lZQG>tK4TP+Wc*H--V!pD)Azv91+)kJ!jORA&d*l&9=)s(N=Fwe^CE+Zv`}Lci z0K*mnI<*`(J;MO39cf$j#Iwwyl(Q0kH;hx|c8te>7uuG}S&EaWtj@}%@>K|!I&i8n zJ+N&#-P)xU;OZvqpar#Yji(S_HbvbLQE9sVA-NA{`;p`4Ed+Uek27`6YWyT^H#6j7 z0f{r5%q?2g-y^v@*kdok3n5u!otmM#S3g1w%7DxikA{|xt*hb1Dtdy%gsP$*xKKyen=@feX{aW+o=?_QiSDDT9|i+ znf=t7v!qo&;^hElL|dvc<~o+FJV#IdYylW&nIJIZR;x9k4&7qadHQ3;EY>S4H5;G1 zTwYs8&*_baHfqiwUV?=8Tl_8T@4W zH{vw~a_TgG`?$98DuR8wJWd3ue0abvA zGS!ho|DblS<|EMI@lvu(TU|Sjt;9l^YL;OmQl+}uUjcu4HF{sY_0%m6jX#k}kier^ zxq!(2c3><1lcbrTNqW=L8?X+6^a)B#IOvIWNs_gNR20ur*RIdX=ygAM2vft{q~d}V zu{>DO=)~Uce8wgOnuFks4{k9)&6 zylMmtC?$J3Fo9mw^F^r%W+^!hk7A2tyM$!Ag#aBoajB}^^em}K_z}&7Mdn1 zV3B$&i;&Q^x1X_t(D{I6@^qL|Cd+Dzh+dV+g+DakXci8es2CvTqYpUv{y=msb}RNR z4fZ;K8Nu93la(L=LNWzZ9S5&QIV2GF<9~}C0l*S~$RE9IDVG{<5>%SX?n35%tyHCO z-4t7`R}(|uzsbe&7Z9r~UP-E8gT%rOw?2~&@x{{C>$~XLg<;K`k_fXYf7KF4?Rhr& zyno?L;I&>U_)ZDi^qYoEMUVV}XOd6Yd31mhH&g#vxOfW98)EXmbmN%@;jjM@X8k`c z0K%)cpbG0IA&KGdeOp&my2=!5h*1e&8F3wf2Nd=qTp+r>yV1LM23_Vw^~?l81j!yt z3N&tP{9Lnm0Z41z*c0s?@j}Qrr9D0%GSLMVD*JMHFp195-IKY`M{DtIWYb344Si^g zhiS^&`=D|py-LWaS7YSz9Q-|XN4LgSqhlUsJ`VoTnv>toXcEE@J# zu&xt4q{2XWE%0PAQybUS$~>_tt0aH4%V@j#Db|yw_ z!5AozG!81AR+JUimgZ)}Z~{;0E5ougla%|2^RjsE)8M${yxgv>oH82GD)yqi>%#3; zHe`H5L03$@#=zFo$B9ws^jN+I4=E3Ge9d_`1x$r>g=Z^#U~U*wZWF`mj}h7I@A?vR z17m0-htaF<3f7m6)5JB{&q}Qck6u#T2;IK{z@aG{;N|ph+F3!02vy{0{0412g=JEB z$|dPfN<&++0IdKAN!a+NL60j|gBDWnUW`F@5`j+Ive<_Lvq)XKcNaA{^hlm7(ahc)M3``oKlo0#BU_vdI6sV|F zKm#_BBG@Xa21iRVAsVDLNXv#vLID_`to#7rUnG|M`@zoUMf8rLLX+^L)bc2rD-9s= zn&f@fJ&(}MJ+@Vo4BNB&=5v{%+^iis&W^lLJZ@{KwJ!0zVjZ7S zdQ{(!d;B3d%6Qqt*tQX~C+m5{Bji)~cFR3{Ma1D(g0ni5ZrdrcvMYyJ41q=_%fq?d zGixbedtf)8?Qh}8)p7aW`d#=#&}P9fXLpF#WXx22JUO_q;M@*HSyOCLjm-%g?`4)< zCTBeHcXZ^s8wzE>Cnmi2K&|lJfis`H7)C7W&Kr;8{4x#!zy8SAyCdAC;?_R`%5(w< zsr%O*FybRsXC?QCRW5da?tc@KFsAbie0mYt_kseC`?peOsE1er_6$g09xg&8Mkydo z0=yi6YrLW zu2k zBO`reT(XO@ky@)d{j+7 zdVVIOFSu9#SEdUPV=iv0w9PKd!G2B$lRZDnFl7s249(XN66=&1?P*Odf?@V zbE=16AN=s%^iY%p@un5<$yj1dnPrqr)J-n%)F`BLP4;ux*nc(#VHsy-7Wj_Y_7#Xz z-D&{0-BiB;W2Pmr(NuD4Dt7(wnbC}M%3g27B24JRP(an9L&RoZt`O#6AOAus9+f8X z5Az7?@^hDozC~s*ipq6EEWwDI@zng}j9j>kWPdAgb#`^IJcCnDOF_xJ)&m0(YG4hyt}y68|b030t)o^QbHD`1)2ys z=yoJgN<@@w|1Yb~Vx;yUQBCaSQ0Yj=9(QA?ZHFd2T83DmM?~pU$(GTY$Jy_#l zK5Y(Uc9!tp_Eyop5>iAtYVP7!bpHM@Z<-z`@;Dg2A)>qm2zO}XcBi3xWM1_KW?cUM zu?RJVqf`6+pxeC7qj~zU6=G*1k!E@Nn)^UYh8vN9JWr_{-)k)`*6S^c7uy$M33HYC zl(PQ(i~a6wof&b&Va*+o=8C%z4=(Qc14dr(L zWq=E3I-omA*0_E6$qJPak@-K5M4(b9^{FBcb4}36r)`=3I5o1lF09$6c1PZpF1#uk)O;+vAG1W4P6SYYR(SFN z(3Jsx932I+{fHp;U!w2+>%6~Tb}Ry4R8#y(*6BQL)Fs`&B!iV8f7=rhIgI69q++@w zMHuc<)c3N5Tm)91+IS;my0Scy(LdF+x%c!*3H@FTL5jC?azJb1<@qs0z1~|sAUooP zpmNI4T!Av|f)|k}kJuxDsK{NNEF;&LGD$3Uz!5MqnZ=8BKBi`=W*krYK^%?)tKW0q zB+@b_o-}(gMq_B5ohv{Q7)L(L{`q>o2(18I1yy z$AjZrN3TOh=i5H8-9|xYl3K}Nnfk;&xhopMMB728kO}K~nmPlf*282db=yEvK2As5 zDZm_3Wc#S-2*F)^8V4EUnzPttM5A)RT0cjx+cWVqV-m7=w}w#NBTx!>8aI-nypH?> zu9|;%Gj^&xA!UGiu|8Uj{9`|+Xu<% zwyJf#lwIMXxpWstvOT3i1&fj%g%~p>+{G7gDL6XQmm{2>DNWJZm1(44U9M+bz14>kj1W4=7FjTE#UkX$oEsN`Pr$chm;$I0)pX-0hV%VQ-IX7guwPOA>u8 znh@g=W1M301}Xyu9W;E_sTn|rR1-ao+j#h~bEh%IDC!HwS77VYe}}GGja}}!Pg~X0 z@Yg`45g_+Lg(f<7Lj#gi_A?T1{~xpcYJP#a3Par668}5k%_LJ*#_0~RaKba^kjJva zOyUeCQ29sROigj38{2-b@s6W!3I#)WsjJB6A`TEwWr)RNm4WINj6U4c z07Vf>3|@tuc7i2LTWL;0@{Wu;44Xfj@p3_nUVQeyW;DxeTU4cyJ zU&(L9YB;cKWOgJlcmr$db&g^VC}nGZeD8oO)$#M&!o>!&s$Me##66sm*e#IZ zWKo%Id)DKynK*DW?cF~mIyRHcIAlW8u-Ft#foyN=uIT#QZd2S0;)hz(qNZGdA*()^ zl!rQHjA1!(3qCbBnus*RE50C1SXazhK{l){KLNY0Z%XVby8AmR*7wA5ug~<+>Pa$5 zQLS2F2B%U)tIhGpI_-K*Hp$;-y~g*Gzl|xIq{k8Ew=LiYfPcfp08GlF0J25zl!j7Wc184iiVaUN1R}cWzQPttXb zZu})2q2b3NL#_f(#SF_XqeWx_WgByA4N$lBP>)0;Ud%WK z`u6X{#w_6-87(FG1<;OkaufKbUR#+r#^p7@HE6#PHg(Jz!HpI>!!ew<-&ZLIMy3l> zF%K<)MM4D6b`SXX)5?(V`b|p&F;)5`P#y(1Kh@qk{|@88hjjECQ+}nFRH+aR6b$Gn zm0B~+@=4zNZ1JC0#;Kj$Q+z8q`qx}QwD9i=btxX}M9P)#0e;HL!BTuzIDnSfL&lJ2 zFS$3RS@e=>FQc6<0U?+HNe1*NVsUR2si+k>ODOe^mJj+JSa5!;?tY$#4(%;@xm6tL z9}*V$oTzqC5Wm+{;w{o!AV?5I1N?M{^;& zh_AmUr{Xo`#700Vu)HJgM1fj{zMJ%i6c78?Y$En~0VT2V_)SF5bzB|df6b||`=IBm zEu-GRI1-;YS`69{P9k-^qBF1w6?VvtRrqm=3b|I_pfs?k`S6&|T@Suy4!W_S8~P(*Z2z7uwDKp* z6!!_V2O|Av$h(ETq8$HhZTid4i0jP&=RAo(3BA`DztEv$;_H5kmsd+8GLR3wU6}sK&g*Y)@rS6R2O?u}%*>^`ptVD3aSj${Is?x^li~1e3Lqf@iA&gY2L~ z9xa3VV~dCLf=|Q-rGWmYF^sRlzRc0XNEBC9x2s_XB?D7hGX3Qr412S>r*=DOP$FMe zs{p?yM%c>!wS;c1BN1wXb*L(_hPiZh|6$XMe=P)gr&3|Do_I_+H`g4r9iSgbiwEzd zM>0%eukGEI35;>@nm|On(NDRKV1{cZ)^k{~iSpR) zk$6?gvVDyGZb}wfUP-xW=F%mh)-h|#*zwPnt}MJsi7fEl|r3M zW|!Clelh^edyDe_$ESjxY$#{2h@tmw#Dmw9>!K;h3ZX0G%`Pn68BF8A8eY;>mFqYu zK$QDAH?)Eb_V58+&fG74UvUHr6U?6Q!M{e9j(e9ZKrb>wb{g!}C#RK(2{?z{&l+-Ur`r#?p@8Z4Bx82M0wg#|j4zMel2~aOFx?3WC^74KX&Ozx>W~sxEeEE(QyQ)Ck$x1R;kKsVUwvCV| zugnkokVvp=@-U;BQ$f?B%ZwgztnAayYRRG_mByrhP1TIJ5l+iHP^^Fj zU}*&{?IgAI&lZjF>-Ug1YHyK8Wl$NQO9P}bc&|plgHlr+JX5=PN1W8bT$V#g+E>P3TZoOVPh9Aa-GT5?u>hxfU$jNHSY<!1p@-M?f~QG6^KXlTY+p_N`stl{owHiq5; z;)&hft^`aqysbjJ$Ui&;epT%32Om)gUE@WlYwZxH{C>_LmHdEZ=!_FYWNbQ{d)iOP zY(w9DW}Id!2J`d`&I{sYHJJ@!J@N9OObJ>AhK`zPa!Rb@7ub8y!|i%60S!c8@@>y3 zmCl=XsZ`C~+pr0d2@ecj&n>}(F`WBMz%?GdZ_h*Mw>T(_BFf!v*Xv$&y4l%nmKH=E z8tx!|iy{-qgKMo9tWWSO8$(<`%gPMjsa<<8u9RsH!~VjlTh5TvNDUo}=Yok4fJJTz zGaxq1-wsbe!^FbF!E)O5w)h_5m*vf$rQn}nm{lssAm8y$eSxR3yFYS?!GZB2NIE5Y zCiQvDa*HkZq&Oh|B|10R$7a132?^^-Ge*3G+$etLJ0DOLvhqENL`#ZBVeQp=kxZ@B z+vxq6ktAIDXA^%CggPF-zd!Mq zdi-0PH=nb;C!qe%fALlGv$WFB+p2HQziMX%n}dgv$ll!i5cSJxjmSEm`4GN&{wn%4 zA*BmO99kb96$pPou@MG;@Ke+et@#k20lh-av_t`lp@8;Q;ybUe zjAWn_Gam*bhQ#ZugDPyqBfp2RyumM>!B^QH+cR}o37F|!DC;b3!iTqOX^QX0L|@J> z^|unM{cZDkd~pRMKR&5+-m!Zeh9xwQ9a*zTi^fC|HT!*FEB2A||-486VXX$ApxA6rVOkY9*eC#lOY#kF2H05^}U?aA@ zUiHd|2O-(5622GC#}V+fV^DBfaMa<}w9b3uOnsVi-baM3*?^suszr-0MM^Z0+oQ$K z!XKcN$O~#?$=IBu-!IBP)t_>bG@P&)dYHvG-Kd@!Eduyo;EDecbW^G2;`O zjJxDIE{vdv5ip1q0Q?*i*7~;oQZhe;Wdc;UT4Qe$?EU!ue)i4XK8xO5=gEuUP~^+s zKF33<&35_UCGY=mdA?`wTPep=?)a{x1=uiaoqO_-Sbuh?|6nX^j=|g0hTE3TFSA0h z>Nt4q`S1fZSJVXiBte&GfL;I~TBxEial(AdaatT#?&qYAeu_}ROcN5qRu_V3t9iz4Y|xY zTjjP~D?#lD#*kNQqTS|=s>N}6S|(i)fVi6fRN|0Cko5ms3Jbx$QDz$J3Vjrm zj9jil@tf_6;%zk=R+_)J{ov}B(m5~mv~$Q6W#NYA%vEn`L05w=aoK=9oO@&KEp?cj zlj>t;&+|bh+ZxFe_^mF=(`4dH2~l7_8F0BKatrO;3$#$Xd`NqBxbDuUJ{Xi*L70Ef zjiy?D9rw}OjXtiP0DncR8p@a1$EM%B&(x!XJgfC|muO2J95X?L(@NzUJ}0~~XQK0^v8$+DJ!O%5Qz7bnTujB$0=nOgQQ0Qn)%z?w z5ah%Xwa7G9oeUuOrybp;`a=@+p#}K6kmPuvl8Kt|w`nu0@#RKAadZGFUV#DQkW@m3 z6@Pa^^i=vC>F6P#M7EK3DQ1c6G9)Og0hD1~A7yHN%rMw~{S)8K;OAVZJ5POK{N4ZR z$EFF0f(XypPfBR{w#fS1`!I@>9rn-|_@le1rw+47@Nr1XqiPF-uUHcZVpxS8^Ugud zjtDWU+x`lJcr7#%;=l-0Mh>M@8>jkF#INl8QSSbP^<@DKLdifhcHYcNnicOkh?lcs zzASoFk{1}E{w;^QSy_O2r|`-?htUi?Y+3TV=j_-!^EFA&x3ta9=G=uk@Gq6h z))k{bd7TyOJP)cuIk%iNUx>K?Z2bN#ulp(kU!dYjFd+j5=`iVJ0N+UWKC^7&CwY@x zB7U|JIgBJ26Zw2+nb*!NLMwxI>E0z5^YnKHufAKaPpilR{9_=b|BGK!GbnASak{7PJx) z?Y3OSQry3)F`W$dlgRjY@23eTyayHdc8$fJDM{}PcNQH;khujLNuBY2^4!Wlqs)k~ z3OU}z5=Ob)Nt2w|8YURp*|1dd2HW>^eM$_;%%kE-&xpmC&(h~pHoxFtk1kG&LW`?#M_NuuDR$-T0{i8fgK>$OIwvIw5WpJ*B) zklM7|j75LID~3r|Lx+5R8e(B84Ng}6I}fMQJ(f$DZvJ5vkCvD_S@(c*xd?r#87jVi zT!5e0wz&8*`GYy#w-g=fv{|H1{%`Ab>%XQlNlK=qDZU2< zK4NML&mZ__#hre8gWSqdhMAodNAOy^lLER?lMKN$0>Dqh`~DEK80$Lh)`FfTE+znk z3EemWnVkK8Q%M<&kxClveZvFeK^_0Kl7vMzl?s$9jFmD7FSHA8qd%Vs69a{sBcpth zm@{9@Jm5OqV8N!P#>T@=etYX``Xxf9(@ix_DpvD zS7plxv4^(I>ln-pGR!;qoxG|_O4%JVKUqJ*+mH8~Z1~X%>+V~hl5V^Ch$knGyOnzu zbk2g^OHpxB7ZFCkWZ-YP+eFT?@4nyUbL=v;xW)8$C3Hh|Vc$ zzd+tA~c8TPBc2R(Jo04u!+O+!$EvHhQT+3tWbE8L}WP6fX zJ>Gr28de0>Z~KC?Qs13p{JT$D%=au0(7YOagUP`eT?mnjkrAF`qJOiJ`Tw*4FRZ%C zi0>o%4py;(0;=HpRe|6t4+A?2acx(grr;>SiDanRpb{x1+47za&h@U!dox9*p~5U@ zRmWoQEyHY_ynH;{zX|*vNpTd= zXk$@b7zh_*O8_e*bp+ZtOOVPZnC|?i?eF|WZN+m$qJcXBqd-}{)taf~Mu$sE< z3pK-OMwZGHynue#kaNzmyZZGLuzsYPGa|Ttsb)iT8&9y#sHu*cNcRiN{hFnBW zH`cwH0H)lMr%7Q7m4u~;%ruJAUcb`rutct;vFP-^^UJmEVRb02FZ3Zpj!5c%i=8ymhp9({`JDD_KKv$ew?F!gcQH4OMW z8LZ1}Z|a+KR<_A5&9bsI%h?*JxO=)N$=ItTh-EXjnV4^aSV`o_eKydJ#%&BlOfhq< zJ4eTz#z?L|Z8oWpig~d5nkG(Odf5K4GN1rcEpaX76^>nVSVwqXMvcC>I#*7@!>5q+ zOo{x=V#;&E-$+~b0qK!eiTx0-yvr{n<}W7yQB&BZXq}0C3ZUYrym$3nL-;$ z7y|A0=$L#)SNV-ZjVgm~WO3mj4EJ8J{1!tEsF6G!KtvVY*P*$W})c@lxm6Fw0#jY4#9eZ9tqAmEGRq#7Scb}PdR2jXNwBB3s zT6-7=9vU83w9Q4N{5#YnR$L#cvM2%~-kH=g1|~8kag$X&LJv&w55}uFML$=7h4h4< z9hw_nZa8_!4WjV*NzR;jN!6p93rQ5PAVPc=KmKxxESS+9x$zXcxW~beTUc;P6sy1L z@Jr)ooA938VYicygUr8&M}S-71>D8{~@qvu!z zl;3`{m3n7rf&WXy)Tbx&n`43QaXGX_c=Y6}q;IGuohtO>OpHRJrT=aP6@3{oqko}U zqHD7&AouH#L=yadRz(ADsU39pwy@eL8wVF7&47t!QVH$vgCPAuiVE2U*M9{e?Bai= zKwKE}-N7KcH}V&DrLiT+ijJ2!xOS}3+gsSKyGg%qIi-|222ld8@~u;)`0|h&fT!}s z0IcG}l*x8{yB&;rk|fra=<=_ab7MyDSqi%~EpmF)1kFAwEYQ)LY2N(_2$T*Q?6{%9 zNb?6g#-QeCy-;Pw=(?V;$VNtKdCysoCq>qMp3LQp-0ba9rv{aEcO(F=ir(Cu(BMSg zeD3QshpJpNE@R_uNRu$G6I>ucS())>qn`p;HB~+i7)RVWxetfD{=*~vSw@1xxl!`P zh+%Jgyf^mXn0L4+ar7ZZKOyx>Ay^fj3uU`%LgI^&|$pj<8tOL+W zCo`^V)nD_%0+<0NG7lo)_3u#r%$YqfGLzQ7awJG5(tr(I4co&MwG#|>E)AD8?YHVJGw_@i=o_&qicMLaVA+KUo6+CukP`9zE5U-io=8IWJAqxI>{&xGTchk8QgmuZC?5h)mqJrdA|x z9~xH|IqS3XFJHkPBs?cokF8u(!q_VZZu;-o{QAg`cdN@~nl&yvLsnfp(#RN|{t2!K zW-r!;}Kc?tpX(H_o@93#Up4dN?2(! zl+C=td11H{%)|h?VPwblX0qp$8%r1t8K?c9rM9`i@5 z!Us$>+uV;Rq*9oo&avg+5TR^*+AeRrqE4OvUw2Woy|#NR+LQWX@OICtU@ZJiJ*mqX z&z7ORi!A39+4kq0q>v+f^3orH?HE5Nc4_!kx00QSpHQ@~X{({T zR+6l6TRQRki}q3H1660;?vu2=wrVt0GS(rk{%xBZC>fsyvhzlM#2a|arP}dB!upj1 z_dl8we|YRjWU{7Wt-}muA%c_5M99=q!!~5nT#RPiTgUW2)ITP;vV*jVuV5`L7{v&>VBm1ClY1&Kv+qQ{sP|_&M{bViH6J! zi3N)s%g)ci`)#5t)a|n(AN!STr*|~*A_R>mmI7I?5y-z`WvM&MuBHz2z70v}N%K#A zAHRfPuis0A5z0ysjM_4Fg9g9gJq(3!|2A1|LMXiV$__(jGY?dCA*%pL< zKj{I`-g{ghpu-NR@iA+%E!-k=G>#OcoKx%zw-3%5$3Iep%)m^MjWWizbaq+oi&p0n zPKTRq=A?4bD2 zjw;ln$Li?&Nk1}C@u9AbhW=2q9buNZaJ@x|LWA~KgQebQ(0S@2veiXU2GQfnPs}?h zB$m@mQIZ)$?PpH91#7Yc4k=JL@)|2^G*HCQj~M5RdkLd*I+r$qeBzCVv1~{5W5IX) zMnh-XkIK9+RNQyyb2?^pEFV&+ z0^P?35NMg%ptUbfqzX-?Vrn|?xTLH(F6AweW){4q)#~Ci*Z@w|@OpYv@toKjWe0Hi z1GDz>3r(Vv_E1T$s&dtThl9*K`-Tx-AH&lnYWVc=?aMFZcPj!l9`F#S;zH`#;A<7p zZ=SI%)jSiLe-U#5GY+3rgcKPx>C411)@XzRhK<9;7uEi5-)2R2hd2W zsjEr46sPIebK}Eg(uEJSTy;7-hHq(hDM)ua@GIW%Xovew^%%rgidxg7K#TrCN4e!M ztS+p`*+|JsY>5fqc04I7@71eD)P=;mdH3Wn&bal|rvU`{hO{nk*Bl=7?2?GQoc<^=U9$prf$EUsk`WY8>&|% zwMJEFcQGUr6h8g>=kK!M(Txn9+ZMM~JnypBf5 zqb8fs12IQ0i+7&1!jbWJLqMqtR1TC0ity9pmw<+C=Tz*f%Hn6Cgwh1mo)vboSWEDC zF)z$p?7MoAxUhJ!lr+!ogeY8j?x4(u#qZE)&*^~W(VmYx-A`{d>;?kFz=XXH8B2~S zl!&90yLz-;hjU2I_$KqPls(0yxjYN=>$cYUfn%XDYql;|@$q1o$rwLCUaPt7^~Bc{ zgPEpTJnXCo^UlZuyhT-+6k+cfz7>?CGb=4jNLu3tPc-ZBzTfm-h*%c^sXNK)v4gjQ z-WSk_&N#)v2>F3@W?9&F$tj zMTlex3GGcDa6!3VoR4YR;EHmSyK9-IGg%x01NOJnwrJ~XVwxZ6 z)>C2{o;+0eQ));mW(fc58>gj^;dqd+A8jAr@o(!%*vDH=oF4)dk$}iMD3|6go z>;0RMa8#cbd>1;r1D0n_uEb-}>#3BoWVWeHt}Iv!HA_l5CHkIXor&OkK%hA8ich4-w3?0htEn)an~Aht2=NMa&*+W(AgMtEGvx_gKu zvLUEeSd1Psn86aUk;g-NPqNpGwQdG9KB}ZbjUv=pSANbprB)!VA*M+@SUUpfpR1AG zF6B$st~axNaZ3E?u7em5g7N=~blI1-Cyk!~``5WJHlAxoyHB!zkuLVjjl2GH`N{OV z*?WKv>U)y4M#1jVt7lQ$ap;pULm3X_2~UOkyDd$UZ{ZYV1f2JG1~DNr+XmiBqmO zdz0{w);~bg^;_3vHVck%E9CRxE=j@XTQK)&_0f7Ug1mIp>O+Nckuoqw3=v=t93-dA zE(k5ax+dR^ojU9ejiJFyh)Hr8xW(C=oM0E*N`Hi@@`Q8+a*Q=p@SC#OG83|Su?qBT zE_h;N-(X^S827oc$8$;To(Ggzlx|6`lWKP=h}liQQ7%kii}bQH%teAB*jABLeJ5)p z3`_bCHcmn{DECj6k;VtQ`~3MJ{B z*zR?T6O1kh$Fy>NxGJaYZ*;-vF?1Y4|17@Ow0t3yMB2%nkw8YCqB!({FkF-`9x>sa zxn3k&B*N3)VqQW;GCq$JlJ|S+8^o8qt5=|$+Jx$v<>QY{8lydgp+x2;m(XC68foB-+ys0~JU zV#!imN=>jK(dU*~sisiPDl0}*uI6E^6XTQbI=tQ3L~gR9Q%Z{A;*LMjf5%Q}`^>1} z);Z6A)PkpCW#2HAu%E*}$NYZYRHC9c!UFB{g#!Ef7ccE96%n&H=pOH}yqyKqG+(`> zuF0AbHC`zTn(@!OD^SJ~CY@O?5p`r^7>Z0di{OW(MH1kGTe3e{#8Y?!WU!iyk=s+C z;~UtveNzZFwNfq6JgvqwG%oM{q1r$2SpWMkNteASEZg)dws>V%*1Q>AwO5yF&9?5R zb1{Rps76z@@)E^T*sJ4AC?x}NjN6{kk9#Pv0;nEIs2+4lPN2J)jSkL zyq=^$(Ot)X1zVzcwHJ?qd0PRAq(G@F)k=Po9g2L=J@`Z^-682)594SjESj z_M6?ocxV_E)MHeJgwQ|W-v|qFW91oYD%BnaNs{7(%aF|;^V`YMjIWrnzZgqyom~V% zI(^*CFm`yO5<0WwcO3+_U7%}6Zb{jmI+}K*zf}v;4se#|wU{D7dbcVrir5E-oOoiv zm&^gW1W0L6xm{WV1o0GgukfY5r|{(UGXbDPx-YGi%d8I z6OHW3@M^r>bhh;E0~>m4{&fY#X_~hNF(A?%W9$kkOB7KEj!Va0czJ7>h3}cFYMH`w~sp(FTzvc8u|SUPj3abzpsFOdKwp-{g!Qbt7{dPcHlwkB zuER*ylfzm(O34I_eoFtYQkbME*dS?}buH1j)g$+5Oqni&Y5Rl%z4K2pY2_5CvqdF5 z!Fa$Uw?9B?J6we9!Bre}u-T(J)NcLSE=iUXzUp5jIc_^BQ|~toeYH=j*1atp=TcHu zQW#l+EXiRPH>4+Yt$kH+Yrllh9`M2mL3D46()!=~x3eO(H?N_*Ip+QPAr1d;R+m%7 zt?phogHp;|dYZs_Q&yN%)XtZvZ;{@-XPJEgA&Ak%7aY7Rapr?kP%9nj){)nI^`>NM z)${!T_f!FoxxU72j;}eNZWJQM7`PfaToH!Rd3>A5m4tr4lJVU+^WocKGB?pRDO2ZZolFdFyXh>uRN?(9ycKsaEn#cQrx%t- zi(lF&PDm~OC8syfRWzIDkO-1%=`|ysrjLED8&l#{72k5ZGuN|Pe9!&yR+!sW@jZxd zKS`4CyJ(2m6mWPa;%`3SIG$b&T$-#4rw+UZ9c!qDX8K3|!fR}lcC+|J)h`=?dBCg{ ze-e>{S*91-64@=rFd_eY+%HofqLUE0`og|GrJAT!6_{xP7iN1@! zNk#4f=Q&jm4@B!<#7V#cIu6g{4tKxoW07d_{h!$Of|CgYpI(+{oz#3m{ApcZ_^x*IB?e*GX6tTH^PBk@QJfn3P?#hzh*iL6l z{75FnW}N=l@!c6rpO77~MJcU$nguUS&Ni@jk~^h!&o{3gd^5^3C78{egw`kuZI9Rc zL^_>Q3z3r_8kxs^B`8GVZ}_xUF8a59(g*bGGl-=2$S*>ewtycPdU<63NpZ>C$SjKL zXRDH1aD@vV$@yIE>jA7&L8$mDU$Zp3?Z$`SlS#h#vqKUVMZyK%9iQl=^e{0V@=K2vFwD$a0p#Yv# zIBgnO#l692WRJiWzdi&Q78?@lc3jpJmdB%(0bpRPlPhM1*G<7f1H$T;hs^O?gI zdn0z1Z9nuT>?OXwzBI<~7sZaNli%S!uXMlD{6p>7%7IVEVP?fSNO+ArN2F9V4O|KC zaB6)#btYu0N4X++Iv1)E_ZnYky+*jN-pK9;*`@U0d)AhGFx z_=FmrUj9@;6rvP?@fY*@F8WDn$hC3nd*Ey{$}O+8EcheOjwgab`&%3j{ep6k0Z2;R z73JIEp=A%AJDQcy_4<-b`o1wHnV!_0T>fW2rG@3|*+U~(toyM@v*euyDzX4kSECsDLu--XHMA6k0Q^a znjXh|$E5(>4e=Dd&0t>$kmXFnE7T$6tz+S5g}xz0L03}wgGN|-9;$D;oTiUy!J=rkRL_h__~HY9}qD!~LdBBIEd) z{9Y*u5sxa70W-OeaMA$O;mK)^j%Xn}d#Fa1ZP0{{(ce2#Z_%axab7YT%yapVj@^(5 ze1)tY6*A}uaNXrBc1XQ2{{~_{&b}4LeCZ0vee%1PU2Znv_FSyCzh$(QMC8_jUZg+e z-vfS2hSlR)AlB#zs^3<4$&`K@-@VCJY^5p0#Z3YT)^1|~CnzWs%m<`#~& z3!$RjqSfi=&Q*bw@Te>GyG%Q>;fn-bsc($*3L&0bLJwC*+r`kU$p&Yk+th@c1`EgE z`Lm%W3#I%t1)Uz%{U>ia+kKLrsl4HcH;je%J+Es@A*NsCjykj9Muyt6AKc}#%_{7# zWQxDQgXISk!g*#P>KRO3Rs#yTu^8Jn;7pJK8gyGB`6a7s`QWaxn&dv*CI2`$IIxu} z>D#5Svke~^+3KsVUUnrt@ES%Nd5ih;)zm3S|MY;n-LUOYC~6RSHtW`O#n@MbvQ$07 zsSB_9tMxh`Zx*ZQrr@^9dh-$j3>Eb3<0Nazb842{rlwer`XS1r2#9U&r!ENVqW+*; z6|&QX!j{QLPl$dJnK){QTXCQgc`p(8(xyCwM}bau$6@I_>a56w-&zOIZL_@YeQljB z0U3QB^#%!@mL-LfVmsGLuy51IJupIFK2yF+&HRu2^F7J=96656wRooI9UqmuEipFw z)~A4DF2q*^@&PQ^sqqF%EJKbahaQ#hI8(aVX8! znr}bGl$2{sqrfGV5=`DHW;G3MBh=0hy+=7*WuO|(o_Xm3N1Nso!WGLQqsp2z;QvU4 z9i0HJUyyG%cEE?k$rRP`G|f{gsH)vqJ?RJK3zxp{_CcSlzs$=K&)IG&MeAxRZ}`rL ziLM6NppR=*6feGpp0R0(LrW+yc`%5q zm#FO>>=(M;Cr+tHq^-K89~l5tBR&QW+t&2Kkl=UUQ9@NX?m2$9lg6pFnXZNPmdusZ zo=Tm5IqW3*`q^963B}~#Q1Q>}Aaqf3jXp_VdsvRpQjqrcFp58U8S(;84po{BDmle& zEoA`@Rx&BxILPTlu$cksFr>#8<^moWWA1eoIG+RVse#7S0EjNCH*Vce>XYLttpfJc9}hGI&lLcd9J-xalmaSxz*xxVYNr}0-Jk}2N-tUz z`WlqBE2hZ!0|H2e+oybXsV+CJn!ZLEf;YDljC($I^Ul_j4oqxO`&yBZOBpmlZ(@X@ zF@if4g6Xinz92R8Qyi379sNb=$r$nSo5+fAJ{8_I3Ke6F3~%Yrs8q$JqpLCWTsR?} z>vibc7~P}v<-Mk}-N=|Y{2?_PUfwRbTrE@xta77mg&6NYT$5a#c)gko2tyHHcb{ab_4 z5Z}kUQd+B=$)=tkRR;O(s^D`cNZrEpYQttJS$sRwQ(U-lIQn34$c$5@dP}C+tvZD8 zwQO%#?$Z@e?Bah&d*~vFVGO=v_0bQO*-RNM+w(Rha2%7)oVRN!*@EOHPhus7ecHDQ zKCQDK!?a)HL^Lg@^np1Dy0%60I+9vhCN_x;yoE6bY~FGJ{tT9?&4sB&Zub8?`H!S_ z>OyIzy>(C=bg4~fblQg(mYuDIAZp-4@Lh8990|BETxSsusBS)C1o(?xV= zC$a+uzCzeelm*BIJAlTFm_bAg6cN~;ANc_QfcYsTiMXh>pOjb=)X@>zAW|pP#m%^<-v# z{R#YUAAjCETw9U$KmB|_h!nC8kanRbS-%FgS03<;5WQN&>jKdM;}+r1EX)4+R{@@z z3Ggd__0z@0ZhmgFHta*I&Lvri!UtrvSF=+4g7L{7=%GJ;VH_ai?m|COZx(^}6R>*a z^0-pVUyzN_Lw5c=+?5$kQtz{SF4qlEZ+jHsBDx{>EQ<`*W}LUx`#;bB;PR4P`ZzWc zWTE*ewsFa4Lh1G$NO-2bw8KL$mnSPHVAwHkWB0$ri>3cGo?be=kfPQwpbsq_p^^th595uyAu4b zN`I%Pyu%C7Xw|CuEBju8`_q_lM36Aiygpjd>%%;TFTg4Y5ZHF&r)IjkS%FS9-Yd|6 zvW+=Sd@2fkz%Yw*Ng|Z)jP12j=4DbEsg8@OHnhkumM=L*42t>o62E9G8MUs!oaD2e z8Q7qWpE9#0+Dsh1nMjwU2n+H;Wja-vQtWqL=2Wks=R6~*G4Jl-3O6%d1QI0r69*DN zXmI_3Y7MZY2#*Q|N!19P*HH$Cx zZacpP8j$!XwI|>R@p-}7LAzx^Qghckoe&xr9`f;JI;5Eg5Fm2<25eS)uA}!;yH!YJ zYO%muWXf4}rxRCd-ti}c;6^e!$;?{1RKHTR-7-cS_Iff`$zLxSy06~z(gcXJ0)kYh z5KHRD;e=U<(D^&L`DcSvUChD<bufI3kfY z&XSs`5qb!Ea_An?-naFVA4n*v$Ci34**4DecGeE)yq5~XMHjFtQhvjRq-4WJSp)wW z_aHmA5u;C?yLasD&p(n!ot)X24(P5}-PI%F9k5q*2+Ax~>jU%bdE$Gn0?~?%l$JWb zH#Ils9O6cw)S=b0I%k`aS;Gohtzs8Gd}~~Efj5)PFMDI@f)@5k?n6_R5Nl&!nP<(= zbn$w{{kANhA2AQr0nCL1m6v^Yh)ShM-9K@;PhRO0Pz|XBvvA>-@$kbHsfa0dEKf*z zDujDd5a}PE0h)iOo!{i5BN#a<%JNin+%iFi%Fc<+=3_YiS+&~!e@m&*z7R|JPC?tb zl^7o&<&zz}Wyr3)WXVq8Pqkaf4Ske4z}$ML_m>^mm!y|$CDI4vCV~X-XmZrARybja z-OBL>1z+bjYY&M7<%uEgVA+E;HU5Y3GE%K8|0mIcs4fC{Et;`^5};FJ{M(L5fKuU$ zZpLq{>Exnjfa-v)hLm4I7}XZ}dRdJP(*6;}t1|8BU|o>JA0&lh>`KTH3@uH2P$6Zw zStY$4$qoUNEYzBBn1KwGKn?rrp!0+KtK}RN9xIQ;PEIxdszP2RqT@1$InN@Z zSA48&Rn^!mWINfZenNQiCkw~!$jQvYehiVt>;nIxUaW@|XqBxE74IOaw?XCL9nTH8 zk-D#FKJ^ilG(!a^WtiOxOhndlM3~o|+7t;pno;QscjTj5xntoSit94A8KEl(Za0Mh zDyX8zC%|^n84Gt3H3kZ*3$OaWsK&wyE6&n*fK0(qxF2*Ti*<9uvUhFOP(ayBl9 z2Qt4-6~celi>lKuE4wY^cgu8@OljSYEJ(_nZM|de=L+l#{%a(6-6M%p4K{?sb? zY`;bJIOF^68A#fST?WgKzH|sI|B-1G7`6rdIa}a98X1H!Rv! zl4L?QN7b*}m9axK!!;sv-psW_Z2yk~KH~ZvIfSLXvic5M-aD%2{+S zH5C61%{?}4RrMH`?xKbVT9bocq`G7I>FT%pGkNc65PUv=`vo^c5_Ka3N+Zo2^``Rb ziyV_C2E3Lhi|B0&MQsl17=qiq(3w$4@5ygT${)!qmZ@q)5qD7b?%TLMhb-n%3T*hl9n! z5QjUVE!(}O|6Od1F?;ev8TBVMb!8!GBgtWI^GX~72Ai%!I}j13=b45G;on(TgcbM} zMZx)MPa}3v!u0)qe&kRjM394I)z*95?&# zLjsCpwk2kgS1AkFBs6zLq84kgAP>_(N;oOH&Flptvee^xY2TRv-;Xv{^Shje7djET zqQ5Z_FHtmaJ2{E-1u@3gG4N{uPbL*QAvQ|1uo@p`oafmT(2Gzf! zWGXGl%mgAT%oI1tQ4+*F+?w_GpTz-kzw1rpT)UmQP@Nf&`J>+QhMxnJAGv^|elTJP(J(X(mwQ9wc< z8vGuB?z@HpK^vAiLsMiZ73zWzHK{d?TQf8nHPP4=2O?P7EW7ac_Aej&PpvL2xxwg1 z7gNfe=dZE;Na54VZ?cRly~Y1X$6I=8kblKQWyKn@Vr4bBM9&!>f;bW>mKlB2z)up| z>EeBtoFTNUKZ+gg6@Q0EE)9#htgm!gPP6(%DsnCdv- z9R}&ybYf0Ve1ltTpuq;kcglL-V(iD5IP)hj3=t>T_FG1#_hmC${zdJ9_BUh7myQo# zS&n+qdliM4J9}bKQ_9+xpf=Ok5jGLpiQ6Kyc?wmlZ?kBN%wK6{RlX`7lK&*Me% zx0~O|rdTq7oHju{$01!?nQlH>aAf$Zg($~KK--pJ=XqO0V%1gByefU$N$tX-ytG+A z`M1KMo!{34B&jmz=KfO&hGCA0MN^m7Qlur;HZq~hISwz5lSBGR=b*a(CB(iPn&k0* zn`JzYk`UC^2>zIw$01dN`tKdX$0g#?kihqA!9+ab!i=(X9n910y0`Q}r9i*NQ6^!j z$-k`iIKLezO7)O8S9fS-5)Q`}_Hi$}0Tzo61(fcg{|sli{zyCtU;(iPfttCnkH%QQ z0|iTotmqUqQ--bYVAFAaTv;5%bMopP8x3DcdAN5q*P)$HFD1 zO`LOUhv+P|j-Pi+E!O={1R3!VavxL8*h`M8cOFg^g zmMoWfT7SPzPf)?@{;g8R>P{-sf#YjO&Jh}WM**dIm69R}Ce|7@Q^4-%#rMF?;QpIC zXlQm@JMWJcUK1afuSJiDdwqY~jp;e?_h9g{-DGds^x@64mu;*zhT=y@Q|#9TSm^vw z(S)mWmrAdO)!uXkn*MP{T_>t{Yztb*i|;5c6J-e7HiS(JjEg1{f$YGBq=aDsg3=X2 z6E1x<=IK)Apb4+iC7%pEjAMtYq4Uw*r6Fo+F(GHSV}VmG<~a(}t11vlXU7y9jf zWRoZ=roFbvyqYi;5(9V|uv9?2&+~wH9f$yfB;rbke$hOvZcjW{2hEH&Loz^}dDQM> z#?Oupteg;Uk(16(gP-9aDFCDA1;_W$nyb9R{W}>*=OvjJWHk1$uEFuJaIqIcK1KS&x=G4S}U8UqAy1+{l%i_~($_rZ`ydU~Dr zB(_BO#!<)^BS<6CrjkBFURTwI&Fw1+nu}0DD%Z4MrJF*rX?T3* z@Nze8MQoiy>skV8(0nGx*zAW`K*80tc7d(*f`}Ai3^f8H^;OR5#si!Lno`Msn$iAs zM1Sz|gU2cs(GPexN^8Cs(_n+ntq|^NGRg4FMbTBQ7}I85b-|Tf;P0d1FT&|DLwoVu zf(?w*FRe0L%r?)(^=3&()Nf~mX~rx61WpcVd7iqtwAoeq%0hJ+)=MV&#v3Ug1z{vZ zvC5A>^iLkZWri{peR7k9Bn<3mfiM1Mn8g6S2mh&#s-dfYH9QCu9n@e?M9IL&0VcS( zw0kU~%1*WiNpDSpcm9hj8 zPp>c!?+NPq4CeTX`8JK1)(!dAyIJw@jD_-~H8dgt1CavG`@1S!47w_?E%6y6hHNH? z64+P0@VBVyfU=tT^hH;=Avdup#(>7}!!eM^Zle@uTQc`V(0jT&%^R(Se^9Nx`)Hb@ z!ls@w=Lq|TR?wIvr`q~WG4k|i&fA=WY@eVHQHY&k;V0^t^$fQ< zxY(2F)DsVsXf?h6m#}X2?ha=lvCDjSRog#RknA{Bvt~B9p$+NohpeRnQ0@j7apar{ zY%&D|m5?sa+J7rIPeqyDfcRiAji(>6p>+94+hz*~v~^r8B?S`J^ci~UdT7fv@^)*Z zSPSG=QvKFN-}n;d!yXwR93q#e01?Xhhn#RExc1D7bK?J7=+=l8AW_7)=U}G4_kMPY z5&74E0`};GB1XFc>dv?F2lNcGfBm)@VRUdp&6EJeEmiVKJ)BFiaRc369i%W-?D^iZ zD0ip#P;oqoXP0D4QaKom1=p*}PD>=&sY{8oD-f`fu3EcXyGLND6lzKpVLC9ujM#~N z6HwA^3BYcot=Jdk?}^NblVDx2mpzGQ#~E%U+a3Xg(1;{3sxfd4N;^(O7ca)z*3Epj zf7leA`aLam@oK-`WhJr{CYd#o^Cz0s=%KMdsqnG|}6>H9WKGE^oKA``Sgba3wUQ>5j;d$zf zEYxf0U)hlY2eu16**$IBRMIQ(WJ`1K=7TQYH>@Wk4B3>QZauHp1yUs>7`?G@gB+av z9*}TcB?&Ic{F#Y3AtubY-L?BB z>u@s~Otulb_cd3dUFNA%r4`Sa(bt6UE-&|$BFZHLy2FY9WD-}oRZx*CRwyf#FFL=d zH*#t>T2pySNuz`Z&kP({-2&L-eaRdYnmSuRIRAmuTpXjj%0RoXQubcJ5s92BkD!eH zGv$)aA6A#?s`Scr+Dwu~ci1zPYddZq?(-`fzZ@dfPY@Pi>mXWoZ6_iZ1}>nMGkv_>14J%YJU~rk!9CK)dXtr}`xLt@h$bcud zmQqK_S&5r!XfCKUF;uq(qIN8}Q>Il#Q)XS7NmREKyTG4$d(r}lhYX%fZ$}+Yos2Bv zGbYIb;@;$P3jQWJW}Qvj&c6^OS0T(tjc?rXjXWUkErbRFdSw6yqrSKdHoudWPl6sW zmJO&Iy;D2i^u;uR#r4vAn!uf_w849l`^v{rY1N;IxZZ1bVbG{L^DASqc?gyn%x4{? zXtt63%@9jAylVm%j9%@%n`>SG(|+`rcSwL+QgxE{nMiAdsBl`OHaP8$>89ve7&(=-n$r)-q(D^TdyqJW9)R$|DJ0rpZV zD-Hf#{+i_Ey2u<%5%|jh%Y?4wB_0uYh{8Q05x=r|K<15(m0SBG{jyNX`gi#hpQRwd zD69^4H1uVXh*Qzj+fd3*F>6$$M^n|})d1rAp8?9jE3zDlJ!P1DA!i6D{UXI++ct`n z>%Ov3E=yd*H!v%JrhTIMnz(mR(wq!X72yUL{6Q!Dap=!4gX3 z_vPL9{U(Sk+mM$~K>{tBYy?#xV0n!)bfTP0(Hc4WX<4nFV_KIIr`j_0m*TJ~tYRibN5_bwd0 zik6R2i55I31vw^T5)-C=moaO%TuchwHf~wBjq;U)Cr?kLBKTLIdbWg;zAy{`xp4Krz%7UKeh^!; zfQ`PGhzuIHzall^7IPs5Um%*us(tZPZr$EY&k&?BVin2i9fYtV$oX_q)07oHm`AQ> z^_Rwcp)M2jyQ5Q2+~AtRNaSQNVzxrnOz78vPs8l8iP4w(wb3#R=~a>SMvd#E0t8!u z9TlSHyJeMopy}$-5vP3v%rKbB_s<@Zg8*F@HLoG|#dF<3-bNyKkLBW)0YcS2q(E6Y z;oIRn)rUoIsqFxWbfsO9@vk~*bXRl+^9|=05&8rF2Cc!;>JO4I;u1quz2;)=&>gW2 z>Cba!E-1p#LJ(k-uRDEMl-TxrvwqgPYf){#cl(e(C>g6Lm>L+Z@cAE$lW>kri_3D5 zruIchyw^-Q$f`W^@l4+gW*$(y-y5Aj-IbYBhl{XOj~Lo-OT=VDZIBv$E#oW}D5)^N zf(+0kn(!cXqVQ-cbGipGVOTH06|6;v`ktJQ?c5y{Jv5qNJ73;u_Z=0W6fp{X z2HE_X_qO{ZTf*X@=mcw2a-;>dVoK1ekc_vaRgAUqypU65yUh+nF-`!Ofos;aRQao$ zqfkAvO%XC~Gy5A(PZ6m2r|jHjtI}ddo>}F0dMG}Dhyt)2_=V3-YrA=ZRv0a*v@2Lv zfE(wBqbidLszRM99~PJDw>0d3x)Y{oK|B@5Bn=153V3Jg$~LK+w%FtUrv>;{vL%?E zOpn`GjW@7{pGHzpP~9B`oz!?~VMFY56lSA2kz#zkSp>C-It_^M%oZh8 z3g&(|qT*iq_>0`28%3COE?I=SCr zgls(yr!4V@gepU0ObN3bey1ow{km_2hy!zTs1?^hM1sNZQd+(EIY8DGKTtGsy<6fz=jF98t6Ar#UBwTubK9kn}f zT|g?rgQ}2xy@?+64kj0X`S5w{PDya~=@-tm^%SVIEB4F*P=m}!N_t@3f z7C7hb+^Hx*p>OG6#lFSCuSF(bQp1RqA;bb*M}0GODgwB)c7qQ0L@S~?;es&aiuV) zP(24ZwK<=+Ny6H`Z40~^DBIgGvzAGvpbZRF@9-flrs(62G1K7DfIMw?Vc4ajLle?s z8|&l!p8^MjO)d@+>d5l_Xm-ydOoe4z_Ss|~Y;#-rEGiT4bEmyHg%gXYQiojEC?h`2 zCC8@S-!AC<6Wm;@wwiaDCx1X=F@Ly1`xL-Otr;E*R0Nk{q*d(Bw|(vKwP|HHVoCTg zrJ3w)DLM+GMDGxdKcSn3?Yrs;5pzFi)IS9ePafm^7<%^ui50bOv&t$1-nifG!SgWu-+osMrH4of*Yw?L z@$DE@lwv)(HSXp6^(M4ao_sOkk)!(rt-?j~UdE}lAH4b1W>q+QKF&_t8SV3~FZkA&mdYBLj5s2UteBz$AS z5Pr8_*qschlp~;&od+woE*VGcWVkD)5uM#2e?;M@0PKxs7vAnVd2|$J_*?Gzuc}&{ zqzqy-jNiH(-@y*D*L=&RXm==h2e!&u!%VIOAN0p5ro@l=r-2{!%KAh4=FatNrUAKU8}y^M4MUFa z#Wd`#Z+`mc85+&uqd{(Zv0M`g?Lx+apWV4IxKa#>iF!0)jjl9j;^X%p8TyQb?@9RP ztf%+8siC5H!2@Y8U_~Gn_NU!8l*fybmqT1hPX&`ohXb0Y0cZoGkVy`v`nLBGl%?! zu>HBg8B@77g-i=cM|^P)$Wp`>>O&7J^d8Szn5#(|!}Ez878iYTKSyrx??zAb4R8QrG8;IDfGC=i+K7OZ68;&>E-}XT;TdQ4kNm|@F)z?j>&Bzem@q^yC zVXdlHP}acY$Ky|5$rPFR&u!K$kw$8?Wtcj*aEW-hMM5xl zQr%0SF|MWeV8h6TLCF?L*oQVyMYW;&YISMHr&S5>dWuykD0RXVmaBN2Aid~Z**-8i zx-#>9zJfZo!eRD*NYQ4aP=LhR-?0W-x8md2p9xj}t)3QBo6oeXsGk3Jsh!NJ+J)WY z%k~eyR8pS9|6TcD-CWy5BFquI(7Z&XwhE05J_WwdKO6ue0+q4xNpr52R9<1qeMZOnsBfvs&9pvc91VViX zPR&J&e<;T|xPyhMy@kRag7HXE@MyWuxUrBn>>O#Q0#j!jA#0pz{jVP&p(5Wimx8LU zOR2R{OIK7lG&alX+JBx$h1HWMJ+UlJR4JCB97Mmt?#T+n?a}f?Uc!%xus{_kt3vuL z#=%)u#343$`t);Gjn$=0o zdxr%7ctSDW=J46DFvK{asSZ365IC=sabu5oi5u>l)1d*5vl(cU`m5+VsrHxfrShLd z1Y!E)z~+Jyq$nVv`0%i4+1MzjYm|B%q+`QZvKSFzs&)J>H ziE|R7NnOKx$gT$xg~F(ZGA)ST|4OYiQx&J`T0R6X5;Hkk2=(x))kZZWMmM+(q+6Id zlx+SKG(v_)CevYTpi37t_Ztsg!(mjJn8`sc0fEdr=<89^V?i2vAE3=WyoSu z3WmiWPMzS-z3hm`Fyu zv#yaaXD=Xf`;Vm4&u;WBL8+7ixSA*Iz@Gi(k|0nac|0)y56H_NTR*(}&sr*D3!+R93BqlG#`gl^Tk> zmSIGO`aA-Klx*UFMyjT9KNK^EDTCRNJ7nAVUyVtCMUvk|cC-+x)eZ@cDln`+hF!dx zvB6>7n`CNwfo>G+gy^#v!P2itEziS}OG}(>cs9vI|5(~sMo^)179^nxv%LK_6iBWt z5!P93C%Gs)(bKJ5P>ZJAzmSdWB~~S28%WE9#YK zPLn>wi&Vkcqf1|Xb2pA%ubbPm)Ql)AiAWr}MY9c$B+m>$@CA0hsm(9Lz ztd7KtMQ7&%smNt&M>~ z7=)Z?R351VWu3v^`RD>Z^tZ@OCcE41DFBJg70gPX6xIk=JgoB$j$?>N>-F|L{El`@!q@bnD6Ief0Ti%>oHLe=&b)&*-1q<9NA%oNK z*Yqq%znqYkffZ92eYFPhT#<5J!^t5X9n_)SWhrOMu(`=keNB{nzFg2D*qUqaPxN+J2mai)P`00``;W+bXV0<=77qbb+J7l=xUDpt8?>nWRhMSeRZ-Hbs z4Zf_qrWmM?0qOu3a9O0<17KsoueH5+*j3oWfMh$k5E2w6P7E$Q!$@PKzXY$i%!Q{c zt>Tlue_$*5!tw@bKu%d;TP6lg*UANaP#Ax_rB&XyYFL~7t6m|LSeMu>esLV zc3`dI7QMwae<9a6R)OPkkOSf(1}2&ierH}LBfI^wo7CQtjv?&9di&NAewAvQG{5y!4XMHTU{zyaAaFRb+yZ7an%IALorZXGSkIlYiHBDEq# zxf?i&J#^K8_5WjJvbh-_~@ytX~i&y^zw7b zIb7h^0cumJNhoL%PO@I_wsMXmyY5-=GB&p2Uo&p9T_-1a8&BF98j#>lo#rcT1l9ZK z_TE3n_yhP{eHwY704N*Arg8WGnF&BAr^cT~ws<#j8aK9`qPL_nZ#sO0J>i^I9Zk7| zQ&f$~G`|X?@pIIO(<-nxWW!nJ3O1st%<7$2G$136k6EKO!m^cAn&dyWg{DwA^Iuv_cyYi;L#*S5*e|P zr~Meuy$}=9mkWI)q4G@D(|zSaKzp_Bxezj7$%LqRIfx;gK)65Wh}K^gE4UWhHq&N& zmPHa7i{=mFUIZxRaG5{Co)XqVb>@ zg^;2$@rghc5v&*K_9ZI+n^Q5Uq;)4mGB7|IzFB&7S~!iq)7x29u{HuA^yRVX7^NMe z9Wp;KVH_U=DI(xtq?y=Sa>bxM;vrp9HSDGZ!x)iUK4DY%_jk_fiI?T600O5EM4Aqz zdVxOCuU%ffkB#c$Ol-vC@>W8(z_DHA2?XkdIG{%U2G~W^ry47SWD`M_-O+Bln0bEM zydvgQ0BoG6jH1BW<%tTgKNFRBuuYfG~ zwEFKl_YUFoTB`M6WkLpY&JU5%v)0v=b*ci?^rI`O;-s<+inOE6{84Yj?}~X3-4QJo zzJJ_v>sGZMTM|jugQpgL;L8|9;ntcTc3Dj*$6(lA!MaQ- zyd1NvCc}M zzK=N{egy{?xoaPlZYn&;)4gVNEt*Lhi!=5k8F@>nBy1x61%EYDzDAT$=#&*xcokKN z!U~3#G(%kKk>hiN04NJN_i@_pDo8nSID^dIc3g$?33ZuWaswMbdr`@+8@)Yb@kf#+ zcf|;gw$1VB-7YoxqtAx*v$wjH@mqEBg%+Fgo5G(4B(WJ}GmeAbp-?-UMiYhNr9o}M ztE8{VmrtDzf1-ay>XfmC@E6X%I@F6DmQpDwA^LC^&X0c9v673m3P z?6q-GK6rsdzz+F$oi}#3@S%A5!}1x8zF|>S=|FMtLA4ew9@j!al||`Rb&eya=-+o! z!Zes-ROG+EGScEkNe{XH_*kw{HeF&+HZ8IG+euKx1^X39u!?M_|;QYgHV!ix{L%i@kt zA%yfMMA^=G8SM%njW(%(S>7mo1@=|p{57Aio3@|wYwZf=WjxxuuU_JQ=omsqxWK%z zf7#6+yF0A`k91S_zjyz!#@3GnTs;Z8Kk6Xjd3|J%s0A3n3|*#*c=$DT*QY13^c6$j zQaz|DMhf);aEEM(yd)yJDqQ6QcK9aLq>)7VA~{T1N&;sA)l(8M)6>3c;}$N?q`pwW z?&fu~jYo>lX>`b39;eYRdlVL~d;~%@9X2F~=`H}-L{n>Pk^Jmv{UQb>oL=>h5d~i0 z(W(&X2#a8XdW%<`2e&VMRuv#S7mBqU_Ullj^YxO+LKu|z!lY-kKd7=;_O4c%J-fl! z#*(2C#c5nN=9zU;FP04Y^?bAt?mxhY68cf1PyU z333XVn1T%k?-ECQiLVt?W1{hiRo)KiRh2tXBix>wlg0)a03Kw(V~`dinKQYj+CyAt zqy4SN&2Gk^AEl+iu*%Y=RS)}fucrQ_*pW4dzgpS&)EvxEbo#X2 z^2%BDDbQ^9R|>wnB+V8~*r0aF#XleBhKhM!AKQOroP>e<+VFj|7qk3mxxDN5$cj^$aSnv@he1{>gxJ*VgGXqL{mC=)N#5 zbUsaUJ^SHOZXy1RJharQ`Okb_@MiPERfzrx_oJ44-(HtHvtK5nCg%wzQ~k-ZF632- zArbCH-*3P}MOdqNeo2(Zjq@WgbQ_hZ8>a0LrJ zTfbShe%;qAldtUoXb>u=fNy_DmF1{Kys+F!|13Qt_;&v2No@1SKr1~(A&dLntF(qn z$sQQHSj6FkejnV(8TA`|A#C&(w${lMEzPmbJUGN$7>vD?Co%WV%JaDylJGMZbl{Xh>>nj8@H;rtHoYpw4~G|6%Z%sJ)+i@FdWbe70~ zA~oHdgMds?rUY|q0Y3_-OVFFzuw(mLOO~%`-*wxegbc3#*Wzu0)J`UXBFP8KM_{rhmtlgSc5kv6>3f7(s|zGTAWSk)8(Fs#<4WRJ5C4c@Z*7bQS zvCB5v*`1&v+WKgRw>6)wH5agm5zBr0nE*$gq_AqmWFOY%Ka_x3$nvTn=IYGg+D~z$ z_3+#Y-=4li`myCS!j5@^tKj>0H;NZ>9(MugMU-ejy6Cc)y9HH}dG>?=uKF=-{akPFt+rgSv_d*AEMe>dkfM6AXZ#!VkOFm!&%n2)LsK2q8XS_o_y5LC+?joh*> z^Z@zb3vXG85tx!S1js?HE65X!Le1;=<7BG(4or;`9POk?FeIRrL9I#-0#KU=c!pA; zq5ZLsSco7edqLa88pm`I9rATRZY?>}WG$5N-hWG4aw7riRjeq&Jq>ZRbF+N-CKAY4 zsM1JPqi{K;B4~oZbfbPLP|taNDW;>f%lSw{=!7`7FoU=^yImKL!K*c>8TUyre`%Usz)j7mEyMP6N$+qHh;p?+?Gn!U45-(Wj`di zF{Dn?ismzou$(LaD1*n~%i3a|nN8?kb7<2qu2lSJ_IX~amvq}FeOxp%vFxqtTg6d5 ztuk;nTG_@mrNY^~vYD;sTBD&EuD%1>H;uu>$3EHzrF=AN1?7Ax)5k&)jV10@g<81B zSdC+z;rXP8uXQpJItb1OES$s<%2_p_)1^4m_pfC0``&H-WR7&_Vf`VWoS*c*O6&Jz zQcb+bf~kFWLV$~?19m7wA-c)c$*@nZh2Uu&<(_*<++g5*4pn5EQc_=HaXt*1h_58x zsU#qlf*&L~K5wmLlJUzIq%;!5on>BS7nP7h2%-N88$oZF{o(fmYa_Kd)}-6`T7P@m z>&1`7vzbcz3YgMt&?I5F9Wq91m~~2Lra?*I?ga_4BpF_j}#J;wc02_dR@8Z(;gFa307&@1b=?!HSl7_jH$jkQ+s`O)A;-Nwu{ zWf|7308vU@*p3_qS~W%=NDK)UHH8~nTjPm(C}*K1hoUJnr?v|4;qnYrz2{=uEOMMfA2c%K{b0RifOP>7|_Kwh`a2G z=#5)STIHava0{o3aXEsXRP2UUz$kmv4z3VYyrXejl%5ZI&5hHWK1sD;(Z~2e1hJjD zcI2in!ak{)JpcK^3T;n3AzX$&+M`+H1@i353wMAWXZ;`T&3AR(3D+aLk_65XVGfH{ z!dx^<>#iX)3;%AfEfC_liHbt8X!fQBl(mEvsddqC$-m3hBm?+?oeBc5xIv#p56u4X zq5H?pPea0i?9NA$Z0+s6NKjoI`5YX=p5I**vxYNqMIaBv5FG*NM$G+t<1#r(by+kw z!4iKlJaH~DAr}bD;X?B+s7U?QfaO7+L*r<{5?^zD#enI29Rtd}nCR+-=8q#f!&<}1 zzRO^LBug+iXv)X0VJ6#TvrYxq!qK_yUj44SuvS`V z@l?v1LnDJ5*axy3^pxD_2AnT-hMC7AR6}hL+Q%aVm6BE9E9hy9>bs%1@<1KQ)oARx zHnY(Efh^hS9|kOI2JQ}2d8dIyxlH()T#8UD^CK9_E&d!-pGDI)N5dd$i*`x63)5Sy z%U&#^5rGoB3pM9@CeNVYQ?9254pMDBsh6J>|Ne=KgS_iJY8Q+4pc@sAaVe5FWZ+u+ zbvJ>;xvAHZUt^SmZ~zy03fht~h@1*s+%VPuX1@3y!I{_bV{Q9IEZB2Mu0MA}VbgcYzhLtXTB_UX|cLa~nhi zfE)St9|O5ss~ntt5dCg^KoVv*tqqPH^KV>xDO#gg;Pcn#Us4tYD^#j@CA5|3EFXVa z;H}412S9>{U@%^Lnhi6bU2erv_jE?j4o(|&L0z=DE@2inRSJ^f7p^Vd}`8h!=(5JO<%1bJxo6oDYu+E1HDgrFCRksrL8+QM#+m2 zj(T~)$k?^q%{aq@Heqm=P>jG#ms-5bH$TEG*pIjaVcahc zNFy|G` zwoCR}E)MN7>`|J!fz@__G^IHc`8NZO%EI8z@KPxeYUG>ZHO^fws~vjJIX0CZG*ACe z_q0g(G;M06-{+aMdMeruX!|xD8M+K3Ps86H{4`!yGq6)=NUM@(7Ayy6_6F$0(nWfR zQa(=IFwGO<0o(avv=rKtuxt}ZP@!x{!Eyc7l>*LRGoGd(;6VS za9}?@1HlU3gEBpfQKQtBEX2R{%^TXF9!VPOZU69l=j`B(5RzI5b@YMK=q=wm<`m~N zk686sB?xz<=IjLj$D)8Hz_G!^R}wlL2!4iW~Y;N#vS?RC{u{a31 z2yi^6Bh$S=h~rhaOs3K%~;F7n8oV`jz$2KmmM_ zsqFr9&{i+hak8Nn^X`dnc>GY*=urCNaeex(2p*msvFY+FEZFb!9PVi+Z6^q0>SRVE zxG3oFI;fMzmHY*+dg5U#xruI`&B~h*C@Zi9x(J>}S zw#f#mToVVG6uPvE*T07barLtuo~iJN_wj zu8th|Z+m>W*F1$GmBUEHIUSt!@Uva*v{5;D{XaN-+@}VZL;WANPnCno*DlXlj&TR* znOfnR)ufUlf!C1*`S&Vt?yf%(L?YDmVlNSYAP1EbGBC&XE2KVMa4JhSwQKglh=$l2 z0Rj|&=py=q;QXqw(H2p))2)P;bEL(PS+(9STG+95!ydq1(4Vm*+3xJ2A^F=9jcL>X zLSvt*u|05CR)eY9k38#!t$eR5ci#8qrFcG?1%i4i(;rbZyAruEGa3@<0DMUv!XZIB zl_~o6AGUw+AUw*i=9&(FE_P{yay<7=oHRW9#ofD#Hv3N#Ki9)$!cQ$taX0%a=g+Aw zV5#~%`F=P}GJd@;*J8hBXBMu()i#l^zCoT$*th0*ArRM`{pqC?XP%UaQARKJLpJEF z9Bu8ly?5Z(V4?}!&16)=Od`al{hf*)ZvuuzupSYFdM)9YLGIiK3X z9m_Buk!BX()oH6t051OCOyV^f8Hvb&lpl z@n=8bzZ(J&ip1!~qQ?HaK#o5bOsS@;tKP11c$SVR{0r^kbLM0!*vfKTBOnd**JQ&> zBDgH#rS${-Q9}Pl-;fehiQluibEuPkUF4Na>!Dx<@TCdW613W}lGU22`LY9&>sB%4 zNPgzlYzt!103Fp-tx_2znpjm1zu3y`_}l@*24zO)t0zz1dRFh2UDGHFI!)J)CUs1JMcUg5_?VCfs9W&3`&ZgtbKc`wy=YY7l~&?gjNx8IFs~ zp6A#%?J2BB6pz3o?_rP&-11sAx>t1dw7>(X_#=0bFpZf##4cJHL1${&Mh6jy_0zf! z*pMbJJML6MJ851AGSG`{^2P)dP35+RUf6Yc9*Psx3klYT5m?i7a%~WlrZSQ{T|H+U@1{uCT z+@KM_r8uZjvQesifm1yMD-x^iS>}eCyxN$@lKlk4!bM*FR`Rq^T#OhVL@3f5<wW`mYh`A^3{PnTKvDDo z9ylAWkE-jRTh6KVsU&ee-HETSDg%hd^W&=wHmrTig#I(WHgzWWh-PBs2Ugf3?r12L z4=n!_E&5l*atm6boh%Y^;n6-_jO0#6O(|d%SEg2e`xFq0(Ermn#$cLY#TBP2;Y75Q zTjl2$=`2P-ox ze7Hj_{4JM0xo|LgG(z95OkUVBs02p{n853c;D||*5 z8peI|vtpB(2Dh0LBcUCM->TONO!48=dv1RREornwHw7DG(L#LEVxR=YU#?v-PQIc9 zp>W@?$w;@FQuxg)=SqUixkS1em0>uTAec$IN};tPl_5v&cgy}ec{FyLRaE&+?I!^~ zRiZQaqZF1ku@Vj#nUv{{Scx=@T{%HM{gNo0d`(;gQ)3kQ!2+!CIkuSWe{ujEv1!$i zDjfq-r32N;H4e%fI*IB#2tUAMERae8oenz+r~QNN)%Nv~VEJUox2bstu+7cg2Zo>M zy#z6vUKVIWml^|k7=$hSdw9?u=IO@0f>;GGjA(OD+ z2t>I=A6{?8_Ckfi2K|$YVmm5UmGQU5i(CA;mYSaTE5!{tO#^zjLugm7(HlS^#1|Z~ zEYcjX0urQL({Gw&?RZoEHbapSUWe49O1QzVv12b=!}Q$nn6D9Yh51*^-S@afUMO1_ zxqgoKElov|t$-8zuI&bGuDKM)q2W+%riHH?!^?;a`w4=Vx?J|cgHff;>vyh%@UA|aBD^B$1 zwV`TyUEf^Y*w-i=(fmJqDO!cZ!AJ9OSLy4sJ(k!=yTiqkJ4WAwFkbCRl^>}yHmMaJ z&?N@s!rv?Wi=cey*fy1z?UeOtJuAG7I6P?k?_S*&?eQ5eRvt-htWbjs2Y{I9O>VmoM z`a%GnrC;~FKHXv4G7BFwL69(?0*?!_SNJvWy44lyyDXQ-uZdzzqZpX~_SU2~f|G-j z5z>p0(o`AYaJy-nXXm?XyL+eb&rP$V^$3k){5TMLWzzqaK^R`}QyOPB4pxZZ>^r`> zWVqkj^wBOi^o`RO{72h6R6^*k`a;XI^X6H-{vhlT=Z?VJ9~M6*2V+3?;i$C5h|6^U zM~K*RTqf06J;ec3-x~?gFKb%cwf6IRh5sb(`RkiPf+lB)oGtD(;*hga4)gtZ;7t3! zJ}mXp1w8__SHDUAvRT-T9`UR3y2Ht#c+1Ms)h|>eG<~+VDm4Ejz&4BX-1+GL@Ek?F z9BRBg5iQ&aCO;2KM8dQ)B0|S;@P)g>&-e2CC%X~r-meSV)EeOo5F#sw+j@BpOE92cT(jEp0n$?mlnp^52S*u>82VExUMIkR?DK2t2{ZMbF zTV!8s>23*=GJUk1BVrx;(E<$SWt=~LHF0)y(2jl7y3FLx8i~J#M=uXNOs?<$TyLJx zteXq>iascngK=S?CwTHNF2V)3?;|m$e3k<_VE7n}39z^cfe$00`K`pcfg;NvtU7i8 zzkk`Pf!>rOeODm?7B=xFvf*HtT$G^+R$2dMy&{$n7HW3*$OIfF+@VI4=|T9BK7(~w z8FD$E7l<*Ox|Oq8F%5H1;pCx9Fbb;0%q2x4L!oPbFj}}ExE5qTo@>Ay3ATl}CK<bre=p+=! z%QXZ|UPK!eOfO(5-eEk2>vt;dfxcKTU7_xIr)+S4oR1`3=auhRS8 zX^>K^jDYO#i=EuY56}b1!pJ!3&0k#OdK71Q9 zUPA*=@o0|JqTNKyGK6=e((EI|slwH~)Y+7ex(^>}jFUcl#(nmGC2VUz)R4Xd5@A`a zRtAye39w?%I1)}NPmLG>c!_xvZR?mX3%6^;`@?`yXRiyYs+hI65!8tq_xFPmnH=4n z@7TpXH1^a$6(0Lu0d8F~d{MS(p2V*Jaz$+YN@E zQ)mc&4fn-@nezhuiI?OmWHoAmw*D&6r!7CdGR41w^eeV+W!Z&rr}2GYe>UL~$!7~{ zL3eWAl;JJuL1mI@X`Aa=y|kJCW2>Ed?FaSw8hD6O&!8(G0|grLTxs0v4-~bDCH7e? zv?9gnKB4Cwf$TpMaap@BqSKO{`s_%0$nlCaYY)|N4I?FcCVNnX62O|`5Qo>##R2g(}_Z`_xbFdq8f9+oMMY z191ISPYYl5Kf{+z{~ez>f93v>7EJy74IqyI;Vu}BuGmL3MM8`R@28j|&BP^P$zyNv zO!OaKX~QWeVVEWvqTSdNW{Insq$%P6ksG ziZ`*MD9RA?2bNEVD=!B%)ai~#tdmrL++j#Ob}oJcU6xCpf1>23BFH=sX&`jkSxDXP zzupugFY#BgML0E(RTO=yKA==F0ry_{`C2C$&d11*HYn2o?IUAnk)w z)3Es0Sw-Sx8LlSFT_`KiIUE;edWyl`k}bUH?DW%Y`#x%m9O$(BXRnm-mD|&+?Ff|O zxBET^>N8Xqjz2%qo)XusuDDv}&m36z6kE80FSwz08OikWN${)_06NY26_#wVDj_Q8ut9RKw*5l%xq;E_^Hd3q0t z`lXbj;Y&AAp|K`_-`3E!#&Hz^tHDL(X&$zU+a{9}wbLGBg@zS(jZ3mWcUOH~+Nd{n zB5PEtV~(X?V5A@I;?a2ARj0NVo+}XEWPi|zNs#7kk{7?r9O+f56*axF7GC;Vtfu9_ zf4)&*u%S2h~*<#*XJmLU=+g2VZLuyFE|l-co5 z>5&7=ai7Gfn?la)%{ickY=50#(|22y=ZnQb8_fpGl5oMYO2~E?&HL31;f;nXlb@BA zq7TRrx_X{7;fy~Ih`$W$a_lJfw6pC<&34$~1`K*Kq!YhCEmj(3ggHCeuwJ2FC>B358Xo+1R<|NU(~s@UKNk^ zJ6x@Pup4VWpTxD`Lu}mUkd)YbcNA+*1ssLcP_311etoeJT$S8Glr3q**PQ7&la*i{h+dl8 zM;UfSI{h8X*&HCnXU*x@FTzho8#&a7cP9l!WX_QPK)BT>!ZF?s$Nloj@wI#-TK&n6 z*UKhqbPpR^O+>SL!5ImXiW)%=A@lQ?Avo3+-Z;`f*$SUOK3fyvFZLz_AAI+!z*$~3 zz#hUk!W7?fut~?IeJL0fRE&yMMsDg)X}VvRn|r?uon?{#6HSE3N>OFz5a{Ile%QrhtuCIsx`X>TOt#e=>3H zM~Q99pG#PPHquZQSJvlv7IoO(U~5VqCN2lOf`kqUfx6j&p1}T&a8NLV)w~atB>BY~ zB(q|36sqdaEsv*=a37^W`iP@Qx!^G42_~$|_-blGq=;+}uQ$4Z3OFu)-`Fb2@`~9OP|9;V z{wsV5Q9-=J)*T@lgBqw23jCJ<$R8Oy7xZ2UlJ9qp!ME0;MQ{9$Nf!NVv~PB#1@-SN zFg@ZaezSg?3S@S+!6$++IY@s9`Q~!#zt|;X;hI^pxlGc>80{gkaweVH1$>+bXk+l-1Kj7Lpib#y~R?UEVTdc^? zA`vYql$Zn$`?|~oqm^{#wuyo8g_yH&Bn8WP08MBIZQl$NbCBfshK_2(Jjw@%9+!3+ z0w~ww+9VFH5a{yAp$a;;y2V)Wr8Mt{>H0222^7PK3!Nn`?#&jC937doRDJ^ zixk_e7%^z~YKG7`#AiA0A#E~d)NEld$jEFzt~+rk>^Xe2f1=wQYdG(6LBCF3oi#Aw z-QjKEGIERHLQT_cX>f5@e4*I4kMsv5U(KTEbF>T4#RK~$t%j9JQY85HbO|QCc!z`; zaPC_VGq~dURpL$@7bn(X3 zFJJn>IY^xa@Yl$>_wqiWcONDwDp$*!+;gtR{Im5yL*%;?E!Vfi!*E{4yX>>n9Atuo zm@%+R`;&!vnz#iM6py`uBUUMR`&r08-$A8#CHOJmF#O4`SK9_{_dO_wq!(EVb&a*Z z7j7ToE4d0Rgzy)zs1yATe>e%Rz6)6O3$N14@~L+PqiIVlM-#dm6FG}~RS_@nk-s4$ zkiCdb!cf7>){*;yu0&OXOlS%Z_-MI@HDoZOP%Hx$tRY=`>cP4{bl?60T8O>~ptpJJ zdQX(ZkPm+~^hS`;QNZ=p%m!qaMDY*IZEy|KMNcYf_9p0cQ7wH#fScil979fU7jJx| z8GF~lF!hiUE|>xu$$@!!#u3TE3a<8k@fCmYU-)3j3-cy1v@)~a#U9#=?IT7BCQAMO zP#Tla2TK@CwfF9;X^FRH?adcRIaLZJz|p?=iY)c_FS(T9s;$A`kRfr3N9s@~DT-oF z*r$u4ll$(YI^wEwUeBCEvd*RpJ(_=QBAN{g`x>|OXGNy%o^m1tSVxHh&a?r=7$Ke@ZP1#$Q+!r;7|B(cWUNYE+dXBv7 ziHI-ogCIVXfGe}I>KdVU*D8hg*L%>&xAJ;+yrI3IT|K3kDg3OL?=G~c5pJMX(2qw8 zqyXw1xV-%5bH4VvwsaNVMPj+`+1lqIL@iE2rV+ixWJcIIR7ar`eoP)&FH zsuj&YJ%53ih6K4w#W(V&F*j8(hY`7fWU8eJNt~7u*rJ-iPZJx5pL_V(F+jPKpnxjDj`mf8 zK$arqUV(QCiOeiKNsgD@>~sCbg!7OJCi>&n#)G7ctZ~7>MX!p_M~Un&Z^pz}VjPp0 z3mrSYzoxAGY1QnU@wpNmTo3rvgM?TLdD8#@W@6z9^slbELZR@$kvt(~loCf!U*bs9r;4s6>)*%9la`^dJR@E%{*m0D2wNM+|F{kb-DRSdB=HYXN15s2Z^}P&{Xc2Wu>`$mcLw`Q~0gl>qthJXzd@3ZeNRob!i!>X{?QmpF&5VnAAI zG3aWSl>UPq7npF686inZOt0F1!l& z9iM+Sf5w~J_A~QbL}l3*Qx9?AN+u1EtuHRVo%D_NM-=(BXT+w+Zp`4lF4RN);M;!M zV_0MaL3|M&^3Wtxg1~}N_}r)qkXCgR+FQOMp_yORcQ~F?fW|#Fs%F=wTIi|VGrYR1 zml%fX<6n^$)~np-o%?{rjkjWFAMMRDuL_IujzZ)F@#U)4Z&WIAd-FF3*cjy*!B{77WtoX@) zUPor%B&?WEYqXeU6FF4lax;1Q4ka@CwJ1sfZvPqarceg^I_FFud)};16^VF%r3Me~ zImUjngIiGDN6&@#7_+i^VMFRmbf)d=NwOR%MSX$yRURG18q3!Nf+z9qU2IwG=5|&p z&{iy$G%S`FU6oj0A|&CrMh6d#`(5R?e!O6iObB8UKGuDY`JT}NXUYJe2DEB=7555; zb`L%?u=Wik5x{}J0wL65E??F4vj*un8g4xO3S&NKe|!@iF^k(Pv!^1A#h8Fu%6-Lp z`5!otJ|24dxjV=c6j~#~S|}te{zi$?(_Z}Dwp<8Dh;qJZU5{n5(}c5dxRwplr4lH$ zqoIvKW8X!hDEL4+UpNgGX5Xu_n@APWe`@L)$WHysWc4O|J7vkf=eIh&!yo@W@Vo9g z-3FmqQE#)Pu8-+$L=f!JWP7uK*S%H3I*8dDLY6CKc1aKK{{jcZj{#Dmy8MAW`5A}+ zR-;Sv(Nwkj62ZugD$`e{x5}df`46r0Hx>?R?XHXUi37-dnQ(&skFpX4ceExQhqja# zH(&(K+A{uCoZdZ`5AOldN;EOvVQ&f=e~YcQ^UzIU&k<4qvr}m#R#N^JQ<)=etdKzH zCt5BNqUse{!d`1hGCA@y%m$T9|Fjc_DGF9dI}{#ji3=K^coP90L?BN~S$7faFhK;? z(U>ziNJ}1VXYtmE;+bA&B&T2&#lcqKQhj0db)Q1h+c~iC=1o%8UB*%9U%#HrWt|4f z_bxoTRM4qI_R~Cmxr#qfrqW%?RL-59Ry^H|>61buUL)_1uWLgsC?NG}RN)&R6w>OF z#k{P(Jepy7qwq|1MG+?IqK3=$Du;?nRlcLht#>e;SVZ?w?tO3VI`2|u`5HA|moXCc z-T~$(^apI4Du!RE(ex3%;8w7xoi&$Bf=8Kb!L+?drGXu}iaz`|GzNJp%&E{rgmCFs z!m=tVqgGGJ28e!Cl-N=j3PZhg?=g(@c#2&BauA{UbXD(o?}Y$H&``3G6emmNZR>Bd zYK<`niv|U$WQE1ex;Gv6qDsLed)B2@<%X}~-X!-&czZp1C2Kd0=xFH*B;-_4SBp`c zAK7W?h``d2js60_RbHn#D-Je|L3f?^O#zj|ObMW)$)#-6Nx@A!8`)jP9dX_ReSkhv zc@7}3h)z^(1L3`XEns8F+z;ND0GbT=^h0#Kw#4cyEx2x#%4Zb&k|fBZMNi10*Z9(H zCBRCQK5WMmq6Cow`WLR<5kk|8>KP65rcu zG-_#m)5zwfpz7C-Q`<(dUY>ryh>4-K*4^2I(P9GymxNkAWZp{QVYX-6=V!rSmfwvG zXlcdB4;|8L{Fz?Ev>Z5Go3xMIj-0{ABr1KQXsBT~#8ylYp`dL2;c7Nb>eDfCN6)mT zO@AZLL0Uu;#ChjaVlS9b61FzH;?Gq~`^B9xfs5h^{#j;C?;^P{ z<`=QSFRyEDH=Fmg2}^l9p}9TN8D8B(h<$sn$V0Zma`{@?nG=)Y7x%Wyk2~Byf0L>E zW*|9X+=3o3%U{X6#Q6Kjk>AghZpHoWVVrkM3oh4F*05Qa^eG+g4lfPj1G!XCRks6P zaA97+)O?uN^{Eb~!e2V8#?f!WQ8nPn+XjA@pa?vky`XLh3q?wo11xGdjM7|?_6xqz zM2!oe;t%boodA~eJrGKY6#3;GjbFEbN{wbR`$6uWv?%J_gAXD9V6|bF7|_i#y2KW2 zr))9Ie)z|CM*}@HZ2SiQ?nTy z4y&R$G{9|Q1booSEjOGy2c<0hOg+Gq2-YAanK!>#_(GpE3F99642MI}a;E-vAPY#C z3arJ!&Hanx2vvuu?qGTD9HB+>5FQ0mD__c>Q1dsw{X6E&>E%exm{7B%M|N^!%v@u2 z|8q*Z!Oe&KY!Y9UEwUFkcbR|Q;cgDUsTX<350t&?y5*YWlrszhN!0`6p6}$7ij@a; z62o-uthV#sORTI#&)8yF6CAiFg+N01sYj%`VoRT?N6;~F@Y5XrL6)z62kuM5mX<-U zFX$I`W~ugS;+K(d%j=PXKm0DNen%VTg!v~5`O(`bFsOhMn-E{yG``L4H}*-e(|$yf z#ggWB<0PXJYNZXO#HO3>@>lk`G5A5B} zAgU7vUot1!=C%ZJ;iiOW(p2N^4KewF@P!!apyXLzJ-j%X>j0Hz$?QqvAH3NF&O+cqLz9?H9|^|0CUs?s z&=#Sd(K(VZ@}ZL`3PMQdz4f{a*1fxtb%N$~V2gbLUpw+Z3jAcy2NQ5Ii&E_3*1@59 z?=@R#64uD4dS%8wYo}?3z}ATodNN1}!+ZPFoQIn2s+orxpsc|#$s)>&FKawxb=qW~ zE=LOH&EL?p-TH@Zn;887q(YcF9ympniWUC(%ZulDK;V_@DoG4L`r_n3GDp5ICbjZC zQ|_@8x)iH_N<#g0N{F9Q{v|hu1shCxc%>erSr3AONC>Gg2t6>v4lX+9CLo~VcPQ7j zR7sJB(Q#-gBe3KzrAa4K*H0@|(#3N*?qV-9m)DGtG=D`elD$j?v-oa{WHtIEG|~cvNjzvU~Dv&4n6kY zqz_!4oOPMD5Oterv}mxEeWXrIZ}CUvT9lS`?>5Dvkyn3ZF#-zy2b= zDZ{|u_V8Ln(>{OW>DD`>anDQQ{8!hH@Dp{0i~l%+lLsNsmTCF}m(OY~+0R{Q zaFszdA}O!XFMbsp(s~--d}_(bfsM?rW$Ow?jKR9Q;W2JuHYfUQk{zy#7mR<2A6#{} z#h^Hk4EQg}aD`}2IO%0)qxCZX4`q`eC7+FiNC&F6U?@g$5{_Je>k_g{GOgT6`P^b0=+ksr`~OhT zpLz6@t5((9_GMl*XPzXyrHIhSKKM+rmCJkiJ#flF`GJlE5L1jyiWLpBRPG(Js@e;@ z;4oCDA3Ub$V|G0m(_AMU%ID|6ya^%P%0ZZui%IyqnpuY|Z8So@FjN5_qgV$apOp5c zX3JQu8xrhLbGOY%u7L}-Q+_-B&H8D%Y20IF!v*D*Ws#JLHa8;qP~zyMIilFM8pT(9 zU@asgAND3&B1S!OrcEVeLh1H2Z+G&+O{_?&&m0c%y{fL4?I3r3npz@x*QhwNTcpI# z|Fn_5lc*zC<#w}uND=wlj#Ze&kZ~!g`8m%AR8Gu640H0Jm1{Gd*ldeuS(+U>&Kv>2 zL}fl~Qwldk{ZL`2JYkkIQIlsfH$SC6llk`_r|1Km{KS)h)L>>3yurkZ2$UU(Rw;yg zc4MA(OgmRkx9Tfpe>ZZrsTs1Nog|gtCjLaZDptf8`SYHLF(E{QHnVwFiA7Td1A_w_ zrLlO@=9;%7Q;G5u5sm;k*G&eFx>=+bQq^WgDoVnXIPWZy1ilo)39wuRyNpFp^SAT{ zN|0Fv=fuRQ=BA^%f}ASKP@*o(s)M$5FOMvW+92A5!?{<-HikLPS&>YcOc`HidbCkW zFi>;N=_TSprF=VPhXiN&ou!Cv(J1ufmtf@Z1?IB8j`nD}2pPGB%HMDO7l_+!tx731iE%E`$UaD8UgCOEem)dEOcO_^ z9XfnPAp<@S5!xFPKhVxX(>B*4^hHd?Zy+34r+e6JLBy;S0*r=sDwh`X=U{8{ph zqA#aP!0}N7*POJ8w%Iz%Bl4x~B)n3Xh^|<3quJO{5+=Og^=?-S!Qeq>*x|0-PDuc7 zBiaj?8ZT&%Kd1C#cx~H0lQ>|9zH!JeO#(e2ubB=`HB^OJDqR~-;y~cQ{7OtHtALhL zdCo)G?f=pA6@F2*(bhu@jg)kQG}0}d(jbj=OCumdw={?#%}~-U-90n|(j9|<^w1@I z^WOX2zu?U8JaeAC_gZVO6}eonCasGi2jD51FSl;Icm|2XLiiZvMICY8Aj1daH>x$A~Jj9&lndgNTE+xs&P{7DRl}*blcI~D`2uwBz zIiR>{dBdQ6-vD3~6**#rIp-HEx+HtB>cPHnK_B+#Yi6xU#{T)UYu0ZnVTi=bj3 zvv4=?iT}?Oqe`Lj=7MBmgfUz#K4faMzqL|p%UsI8@+AAf`W5;miFlICfMHwAZSrdx z^>{o6$M49Ci3Y1Yxrj0)g>tGZg;>btd}pMG+=c7*!H>i;m#vaOU4`^?%O1~Mxu!d` zh5Sjtm+=l1>P{`4zMhf6kmm$HPwujruDc+AC)t^q1F8h<^ z7{4NYu@}SSb`>;~AsYv>qC0ogWz}l_K=M@2-mpAR>TO@JTje2!@@6(62#aSj9}v9H z0psOh`LjeV0yEx_>`t6XeGU3+V}^&Q#vRd{2+$mx`G{93u>0);WBjHv7AJQwHDVNx zk<7ZlR9E@*y+|3%9M4=T;~=bz z7khiL?gtxOKJTtwFT5SObJt6@Evkl2>e~AK7D1at%sD*W^d3ol5>T6@L0vr@jVDSA z)x7!6gikbxn&5;z}-&Wj;Ko=&FbQKp>(q8>T z@J+<0r)|=KJ|o3BHKWcX{i%j2FVjM=K%DjL_iW*QKHk4P`Mk0bXI>G+HU2f?#PG@Q zuD%%qe>u<3I^A}Qb4fE%!gTol-m7{vUhimeoZ62!Vc9I!0LLT}?NT7Ci2kdPz(bib zUFX6Dlrglev;Th6emi3q(`nro`CDB$04@?C5)X^+Q}&HWHkj7avz#NMYxnNOwL3=n zmNB$Mp92OwpM(;YHO2v~as9KaMv zet*g9`{=Gxy-`Dv{>vuy(uK9^Z3y){b+4@h`JW`-Mtpk&HOtBUA8vKfGNAxBQf6_% zTtKp3w(iHpktb9VKSKvANl1VNk`;j!5?2tlnI@BAGo=Ws$e;q5dG8XVW@%(#k1rpW zl8M~(zaRZ^qUhmop^d*J7LbbiC>wIIAIqj3F2G_`*L&p%TDE_Kz0k}ODtJVCnD4co zsLR$*HpfANS$7Qsy|O-*6OZ)3M7?%dO&Jbpv8d|3G>B&5%_`J)7Ei7ikx3_NY2!0@Q0*FyZR6AoZ_D9?&1Kt~3M+%S43-#kh*Ln@+oW|72sS zj+Ny2EopI;L~O#3Jl!p@Sv@Ua@Kwk5cJB-FbPz$orfd3=Eu@*M(c2$fMHRf(Y=nyo z{>iPG%e4D8VR*VMxl|~|uUkd^wG6h7dW4G7TXW*VDZ1Lee^XzVO3?ZZ78hIWUt)?4BWaks%^oHIpKrXNE5sy!*$K0Sz%L8?BmI!iCKSZz8@$ygBr} zw0pyli1~I(%4?-}z$0DWQIVjxf312eL3VE2uP+39aR8v0Cm$<9j`HaP(`)KCKY4K& zPzSl_;w>wXY;qcTd=8@@5^6xlYTsC>^2G8N;>CbG!PH+WUPi;fpx*pVxxW4!2Wk2@ z^C|Zj@>yi%cp>t&)3l37OBS16%=7AG)-uy-zEuJwQPU6_K%^(Li5q ztXs|;k)3T!mY_Gony68e{DAz3SK=E#B$Vn$LMjuXywU~Xo_JL8m_OBn4cnst1M=>6|8Ecf}@f7obn;K1n zviy#iU@(d#YVdI?sLo0B-C4V%W8;B!=f;0ru0q{yEg{4;DWjExIQuIMKc^6hMvS{N zhv#&vqH&)^1V23KCc|3OJGrP!G+?K!fx)|c=0H9i4@umc>>A6d{~G=%7I%ak5yU{b znk4kXMYy+eBAwoESV>8Wf+{Xyh@nhhoP7P*t;|#0ML-Y?Yt^$P$vo(p!h~2Zmg8}Z-hVzbs-hxR>E%@M zNOD$4oT&2WEF)?l;gel4z8rhNvQzWl54h*%gu~p{CM?PC#ZTj3UO)9xqUSnf0Rn=n zyqo(3Eyldc2Bhzl!q@i2RSL`#v-p9Iav4rP{5^m5P!8v?XAgiiaw({+Y^5kib%0w3 zp7cCp{sY!;F5aLi;H8lg|qX2zL=xfeX@{NC)TRufs6+z71#aHW@kbz zyjHm)csNTz3*-$b*94pGADkCL`&T}ZCQ6E%{&Auf@q=Ie!EU5IDL(UBge`8=?vKpI zw-SSZmNhRSeFi4|>j+&LIE)M@ua0n-5`VHcU`x4gPkzmmu{(&_v%_bjNc5kmtG9c{ zR#U{~qj@OQ#o2D3zZy!5;uQc4cd}+oG*>!IUvx7#{fm_5?@>>lj{l^R&JnLuV^P`EOQ{nk1 z<|4#Agxyst>e!->T;BJpPa+M5J$uq8W-eD*tp4Ko&DEi~Wy#B_bqJ=;ST3B&D0xY=9H|W5lV?GM4IcM9q`VQ#twgs|<+U7Yl zqwueTFTJ~`R=!u+a^N8=8E2m$ru(V;tc@&zk=xa?h2H_-VV>tQ@8W-XqmEl%i~mv2 z6rk6j{HA5&|EBe$wc0eHf55u-h7{GQl2Nm9k}h1BXEjH8*6~m+LagU+_vDdhzibm- zwD_OQ5B%27WRJ*9l$?@c-|5f^p^XfIOJZA`oMAq)o^tC4d&k zW?xiJ-VtFV@Ai-*qKoYfmg*62zn1Ke0rhahcuw!dFCe*ZYfI=(&)|Uf)@A z4Pc_YW|CGvEB+44w_9j=vG+aNPc^EK%(5n|ytKTFCITF>kZn}=`VaXINMjt)$d`1i zRN4Y$L!PGc1JU`5KpvNL@p-n2*G492QZhgI?d!kg>}|5mw&G@X{+S*kYj~Z9ebl!umj`RibYU z!p+t9Vgh9^OF=|pqR9d)lS4(ysVsn%A1h*T1I8G52iOyTMV0Q+i7`A(c$ZhJGyG;| z?iRTp&6I7akMiATV7F*8Zrl8-9t`a+I>ra(#SSyrhRqcj5UQdB)XkvrI3}gyjSN9L zJKzP*$nP8wQEBM>Rzbqfal` z%$>x)*LcND(?F-?0l%M|!U;1oD-X+GCVFU)q>_lHk)@@TZr#R1CuG#dR~636NV2A3 zNIJKpx`xmbA+iN^V)B%!XhsJC7KKp%iU~t!NOqTDLOnFB^}(v&*BC%E02&MkSrUN} zWJ9e7`eqTN%W5!nTxY#}!I>GeN2o;`un5Z6-zMC%WBv~K_!hZ^_Z7jzVtBONr?GAm z!6@O*v;m^Oi%J+;WTOtcnDb=FbJE8??)iizGe^tsj6ClL%OpSPb~xH;)16Uy6Dq$h zw~B@67R}&9l_l+57)d9{$VJ>hk?pWQlgQW7Q4oh*dq;S7>nrZ$8&i;0)$7j4(;@e+ za+q+0fx03HR9s&-{5G6d;$Z=JVRKS&V-dEpieJ{CGHW6bUsYl4yB|cmHY5EW?$TUY z?nE*)+DzDrxDfOzPPfg*z9F3%^Qu2#&dw3`F;PRd{YlOn0Aeehowj%6{Yewj1|ze( zA96Gu*mLs~H^jZs=0)s=x`Q!yM9C0vnxQ~Pa8GC{Tcxb^tAn)sg%((BxE;~vwt zKp;5V&&=xl!xmGoUc^!1c?Qq_X#uua&rQjtKJN&{Fe)dfYeqVhy>XxrTY#ea(*qpp zVm+p;>+ue`GY{pcWuB;pLznD*$gf7rxX~B&<0HRfPljGN1*D$m=;Zsu+t)!v=sdFs zoocC)FX=hbp!OD?v0F33dP@XcyM6Q@zVfAWF0yU)I*bzI-#?i?u5fC?cOC6_Q@TJA zwJ(UCIjh3;Ft$lx36QW?cBz=_dpN;6?0?9~UneIgP`9YiU`j3X#+-B*nK3d&hMY48 zkaobs5ts)MMiP~;6b(Z5BD?xoI82_a|Fd#)7It`$>AZdPa58psvftHVWjf)2obJZ4vY>&YWGd+r&Ilt_rdSvWJc;D3ACe8G-# zd`r}>sqrtu&kvK$z!}sfAwhnUJ>|Gu@sZ#q9iZ|sZVcaUSSKUgKKEB!Yu&bceE2J_ zc<;T7vUF&+H6CqR+S|v-8Z}*;V7Gh37>{>@5p*y(liVNA^~8)0EpbmBtwCH(DLC## zNO%9nBkJcEnNPpNHGgcg5=HuA(@gaZ{0KWrd;7o<@11u39anfcsr1i~24errK<76! zB`nFsxfyTL%l{Vz3dT7V+CIm>=s;WlkVJg&KZf`yTuHO4odzB1il+a>@J_z`5G9QL z(czQ`Jk5Qw0CsjqSxveiH?aZkd@t(meyY5_*|(rEQ8TiAe1$uk{2H;X) zNt0uW;}K;m4NRY?N0!HdX5el`7s(e<$x0EW1a$e;?s3dU@Lk^zoV^rk1&GS1n$C;FIN8_>kI!cE7l|6Y8Tn6?=!- z9=|xi)rNI|tS`azgo@fJ@NBBuSOkCSUom0rGN?hque~<-7e@`Fl@S5{k=HDCX zQT&$x@s_dHNE~C68uEWYj5N`8V+6udlh?x!>WGnAou0_kxT$Zqu1wqCx;I1AiKb{$ z43cafd2LIm(7{wZ!tgv|D=Lb>KLU;Gb03gU`m0~d~(d}!v{}>%uh7yuw zWN;hitAzMu>`(6Nf*g9tm6#GSUS)cqLJ2&n6t^E4s7Bwt$`R>H?g*OKs97xz@Qcr5 zpg|7OE$1aZp1NTT#O;`B`gSn0@SVeZmN5dFNP4Ijl>0@+3)yt{U$sz9zb<)EQZyTXNf(@gI3Gec${LO^G-4(pu=ON-#a=#J(RjFhXI~cv?b^k2HA{AJ4UET5Va$J^^KVKK2 zOBGP)BPOce-m=D`7cDk_|B^V!+qaav_MQ#rY}G$oG~VTtIPR*+0ip z)JgtnE~Yd>w04+PQT-O6NdH`8p~$WEtyC%h?w>N9V9~1o1CJQb2m9Bozqw&QW#%SYxj9qy$nQ+gmFu_v1mdimO&ZXjg`)>VKtkj<0F z6PFqgsUZ?Ch`vu|9oe2!NJ*m+PO?~``Mnxlw?7;m5Z}hwzCDo>fBdiB3)OzV9B0-pY&$om!TP z7gpAv(WSAS^bm}E3w#Ko04f_92nfu@N4*KnkiOOH_S3;U->*Z8pf=u+%n8GFZ{nMuG9Ydc=MIrf%ex=!jOp8_rhpdPS3GQH6bYe_BD3%`E3c)f-l>RAZ^W)Sy2owlMfi{1s;`B^ zPWjh`KQ<{h;U-i8T$MU!`qy@8wme70SEjzg1dVOQ0jh0S9=1bw*Rp7fdWuv%uPD{n zmsig$mAQtQ>`biO>sbQOxadK;4a29vn+$mCAdE0669#V_vCaz$r_KR0de{jfV>1G2 zCLt(%%}G(|e1vnWTiMaM8%rKEhZ0|Ypm*bCvC-WmjMTiGSGhLzg zV&?Wv)h@HO7|)Y2PEx)Nfj%Xxp4}xa%(xd_&FaD24&Xn&H~hX8J2p7l-Da-1yse|}WE)#YhIVBp&F+IK5g4Cp<$Yl?Q7qdS_Y(=x~?{Bh-M-OVP$iMagzZGcH)0|h;wXacj*>&jjmg#D~Z|1 zfJ~Y6FWOTOHk}3umY@h^7HKCk`)2WEVZ>akV`Z1Cqt3|O8EfylGRA7gW`>Aj;p>Ev zO`@8i|6fy|NcsaQ(v_~0G#71iRHy?X$(s_AQ?x4^@h5q`-D6#)cnmz%!xzJ~*D@bD z??0Cu3}U$ZBCfdVNzKlu|D&(0rmvL-j)fe;0i*$b$*vz5oPtN!Ev%I;X710TYQtAQ z8mtIIR@45&xrV4z*`=vB{kn z$`lev3Ii8vu}dECsxaUFwTBl|^qPFN=x4Jzlm=~lG|2FKo88=z$8Uzgb~_Gos0YG0 zH>-Txfgp((V1E6mdkU)qH!Hw5FkqsSv-1VZI$6@*OSv%{R+dlgQT5@QL=M?UaE{OJ zL<;{fC-s(OB3WEL8atMMyQxJR;#|1a*e0)s5T3V;+9J1=znmcX zE9ecsdE^&{cn;qSz+7pOo4i%RP}nUEPlPU{T|=Hkw~J zhpDFop6);*=kof+@MQTUBaC+ZWAB|!TXC~bciiE>sj^0=dpw&EgOqwrUi$krI@llm zR}qnJ*-P|yNl3%t`xkx|`v0FKV*5X+4@ zjTT?YCjqlX_~2<5#f~u1(qTSWOX*_N*=mtYtAPyu23OIdjOO9NMDEYaL1n+w2fcS~ zU*c-g;G$br{6TI5DvyJWRIU7F^S6g#Z?=aCU+Um?j{`H$&8SP!%w^_r=inKL^N_a1UEHF-WcFkLubwN zjQ=eweXLZgTM^Xdz-1?^#`*wEZ zZN`t2`M9kCd;zF6`AC&0ZFZ@`-}S1RDamj``KzFlV6{ zVp@n~zwj5O-MG=|Ij&`u-3Pvi_B1~0A=7c?9Vx|MGI@4#@Ev%Xyn!o4w4G!}Yo?*R zN0_ZGjJR}siwkv{1kq~Q*9{E_V?l)R7I|yJTK{o=^_=u?5F0m0zgXHfAvLepXiC8C zG=+Ghjbp$L{rVOcx&CzU-!B_f>2%j8;{gzvC->P8xAl@zNx@z_gxt?k7MF&-?utUd z44f_7R{b9mwcGoP6l+e9_L;-^HsEnq1uwtQ)3eqQ-@AK@#LLiC!C;uKT8n$aXyiasJr{#^l%WuaR=)5n9#*Z5WX&wM56gX>q^Wf z0p~9*sWm$W;vAK-qrUeTNv0kkkUP6| zox1a|a{PE^StRPV<*&E0!_TMtq4@y6k7F@upA&tj(qYbnq7f8@j2WfD%F|ckvG663 zV8zU#q!78qEt!8oDpJS3l}qV_R{;68XcpfrFW`IintWxSTju^-Ve?P7nxmso>8h3d zp^ZBoe&dkpjk}SzswYtmz8bTRXEu1iHHX1UE#%Rp_Yf*)m zb-PZ7^Y|_D7#FgRQe?>b?~+3D#kJ14XP3_4cQdS%QRzsy#jtbv(*{c6vUUTiqt7|t zVqrNV^g`qk8*xK+IRH*e8^$FwiV*(OJuYv=XGa55g9$A@S+Rf>F#%5BBMIhG;=G;DAY3cC6qM;{07bo%I!*ED%)i_Gsi=`dk(S2 z7k2%Ize9==&u=Rfb#<_yKu!Ub-Y}YJOY75r`mq{75jUi=p)!RxXkC0}JWE_4OzmiO z$`8o-rglgHiqo_zU@p2J*mQ?)Pzn`r6Rx+uQ+x&*e)AN#OD#f#Pvfr#h~u^bNSWhN zj68?L*pC`N^!t+Xd=OWV=F35_e==Ls<>}G>@q3X``|keG`ozK z@hkyVJKTNB9jh&!pKkRK(*Gc}N>N+*-7mq1n&lb}?<0e-;#@nDE<4DN)RP3mK8%koN%v zC!w+{f+|RoUP^$>F;-9D90BaeTP_v+O)R3^rheTuv)?bmiJ~eKqdgcNb(pcb&nX}_ zqB_C2>(T_zfrNXY*SX$_2ZouEUd&joTLQq>$X#}gu)o*zd52!$K(emx*g%DYs=q~U z%oN(T+I_1*^nFE5c`aRLPX}6ivo;>c~Wa2?Y@$ zZLQfr#Bqh~DtXJ`g}e(Jka45f2#IB+ux_hqS!>QH7FtgzMWlVBbQwo68j9rHwIk>5 z<24bewtk9!HEx9B^^fPO)%*;Z5+wXwEbHkI&ajq*SD3a(%(UHjN6^+O)DNVTB)(9| z3f5hDUUG~xZ#9W^>&YL>OWA)vs#1d0WjBpaT{2lC-pvjt7}_UJk0mVp%&*$eUMaI+ z?&N47AZJuSIt*lU|8gZP8R4P%m!b(L>``OuN2}-NeZ}@)ZtkXZyB#q#z4)@X=)w1YB33@*?F<`My?u8I9uX^6lgpJkN|Nqk z!H2D_vhe3*CvMoVS+1IVG`H2RP-^O3Z%gG_6nC|1h?>Ot^(UIdVkg;j*6=cby8wb% zK92TqG99B<0ynjhzsQd$KX|@G8x?=m~+Bt7LS%lD&?~T*)pj>aQ zar&~q-J@6H;KXpMba#>VP`apf*>!0xmMuuUmqmeoS(|JhjPd3F}RXk-V_k!=UdwVQ7 zv5?Z{d)A0op+Yf`jYEcyc+KaMiws<+QaAx&b(lBHjal3if^;V~*4KXX#FeeBgAQ=9 z{>>W#J0mKQ78=ZuOlyWmxYZvQM=jh*_TM?G4nhb4pB?#R zw4JAbpJobw7IDN{!k$B_19NZAFk$bl)zvmRDw-{h7~>CQFCi>+PgEI)SB#oV5jE84 z734xo3jW8ZYfjT|4;nFmDDAK5RwS^(240EYh-%U%x^n!^o#Qn;unu}%O3R;k?t%|D zDZjT_d(~Ss80)Q)MJcKSVVY@$A4N>oA)lvAtVP1t7i^n-7>0Ao4V$!U2^zCtR597@ z?RU<_Pzh!JCx-lr{#BYfcULa*`x3EV0jM6BJ0Cndx%yQ)2&6`Z>;lLBwU~VB7z>ud z!ZqftL6uycA1W=ecKz6(c)BcHSI2H?>By-&CTow-B5Hvn?Kt_Y3kGG$;OsrOqL z>GFOZQKqy1dGV7BD67E|ro~Qg@}kz8Wz3^qjMa$n=OcRUk^q|Jt+0)42xXyq_mSug z!NhR}nO5!R2Y6y81dH(w?sd!d-zS z_mg{jzOfA8jsYSx_^J;ZjoS!cg;)_qe4q}g2>E~@UabGjF07S;851cftdBv4HA|5; zmPH_y9Na@y&L-VsyX$Oto{SHcv(!zpf@BzCaLbX%|BjvZXgHUqsl!y_anKqh6VRNY z3}=4ejU^a~jnW`pFqR+;CtD}ks+AxNr18rs;wMsu^b9cYPs!#)!l-1qvJmzbN$=ow zR8k`g0x8`zMA5`Ysph&$fmuZ*8AS`fEy7fE_A-mcViaYxv;gH`DMSWr1+RE9`_0w19$gKyLdmkor)NNc%mzo1*o;9o5gEF@p!pdcw?BT+|C z$WYU7uEf<7LpKchF}zWVgk!I7$*({M%JQW?S8N47B?)2(BPpJ9-@cwLqioGshCrQweGo<^xda^Cvlg~SAi{TyH?{EWWcMpnaIfp5M zXZ(gLhLr1HJ&wM!ggZ$5pB6xza=#)U#9laO6XStdU}m6dNczl5RPE#AakkC=c|z?o z+9KO=oHNQZu+^8j;LD=RLchsasagO&h!D!+Zi4(&KWOk-3BEnL%Vqt?@&`q8szhz6 zB~|zV^Mq(obut9)E8Zes6s{I=$oAen1`;#qbhpMTIxXRW3KD#D+qt7vo^0Bod_51A z`VPn3+9#wn>sUL@Jh>G67R~VMVWIfTye_q;Ubf_$yEq#H?4Aohj?~c34Yjh;)BZbf zpB?eC7hUggJzvDb6;e5S?=q`w18;1 zFCISllD$v$Rd<}n_@wH|)M)2s1+FpYa1!vP?Mr5LP6d?LlpwT5lTmW9eNB>ob>FkD z-YWM37u!%RS!Ys&6#9;rOM2Jl$_U6~#pF2;dJGnJo&#>&scwA^pBze+x?9n^nf>$< z!cT@cYu59>Ot%dVLYFUTLZ;YH;ae?;gZKXP5{$Uz-34=!V=oCs7UK*u;f}K13GtFd z)b-C&td{l3-b7Jsb&nRX74-_}K=vQs4o?#%k1*NlKq9Na@36$tLm|faFI|yOmpg4} zIyBt+8wHE7`>?)9G;?p@^A(4|>glprUdBsxa|E_)P^E;~!^#x6f)wLns!r1(g*sbRt%ilu?S}LwzrSp4f1UlJz zv{&5h$h`T8_(`>dqzV%2ZupKb5@@%Wu9`zG4L~L_-6Go*F1accGu=d=>aKpU*tbpd zE`_*Qluq*2ku7gRdl3<1#sZb{J{s~K9;n;~Xqr5!U52Js7iNO!bvx~mj$ba2p4)oA z1`GAP8&(#QeELyB6|hw&vz4kT)V zxg~TjLV@5wJ1>Q4C)&b~)3)@bXGmgQrFcc8q_=!SqgacVdc97VS<5Ekdvak>I5aBp zQHecCET#OzE}v$*4PkdHHc4>*Y%j0A%Oe6-PbMUlE_7HAju5GYj}7cR>+P6CQ<8N> zg^0|KVfYYVB9MfV$_Zi>V~y$bxQ)@<5J+&5f;=UQ+aW_QJi;Id1NMCx)EKhcX8tl( zk6YhR8Aq*Sszg0=?j?Y0Rb{PZ6fEK>*YM$FQg?x)<|Q#v{j-S$_>z~4E!5Hr84r0M zSxN<~)4$>dj5z0CWr>hy_Psx`bL>heV6?L`L8!QlwR57W)QV(|OqYB^ysyW)i4^2x z3EzYI6-s0o8>PVeuI;z1{b7>h+g}ANWLQjy3#^D->LhX+9Q{_gp6D9CvsdHYq zr$+iS;?XTxpL4{RXTXUN5vAhpbqVcb*}svsw)E_t7LWl@%(Fb|+UB3cmNmkZVM;dRveYfM%=#8V|mkIA-c?y>&CBwKOl+^1ge#wI6z7rxQ#h zF$sZ_#9Y2z!|wS8>yv*HkOf86D2Ue|`%UOLaL!t6KUaSUF|u8$?v&r4Y6C&l(L{0x z1x&&tJe7GLnEWs&m2Z_tsOG~IvGX4x7?@BbjCOT#x5WLBTtevBqqO%t4i2?go&qJSU+a!hvSA#IeW@l~!O1ETRH;zc; z=qL)_X2QO-Hv^;gFWF&P$VJwQVsA#RvG$%&f0L8D^_O%E=P6o|<5Sjpy0c^r!!0iR zIG8-fh?BWZELkT!q84N~b4H&`wCnt`#-%rnN%9(U5QLpTCBxk8DPzToo&S4g(Q|SsM3c}0a3U@*tE|f zID?+27vMQ6D>76gx>E3z9LZcA~*!p`TXwJn15i*t*&?_QCWSj&{*l3QJ}CTqwe(jo44W;M&_s2n=|#I!)K#+_|wrI*~I~_ z%vt<2S|^`H_G#6v`Ry9O()bJ^Ha6O z-G-{x;`Ag)acPA?FFA(b7a9a&0Iv>d;Zahpht1fgC~4MYX_l!`uJQXFWIJ)0@!@%wchL?@W} zVYXku;8qSS1@|33jo!eRuIz(r8%(p`Q-%CMcvi{7W)GKR@liTVy1^A0@Fett1cNB~Qg z$L?-XqQ1vEqoYkh!4LBJ2oqM8vYKz{2^i$D{DXaW>aw_qts8%9+;XYCz@}*58QS^x zhMFfr^^?`d?hX?W`QD&}hMluitOiBY`i1XF{w}_dno65wnUUL}vv*%FG>bl3X%+I%hC@~k zEUtV}O^szsRmlfu5{ecnQS^TnwP*FUp#_6e=$8-Qfr?2<6;2KmB19#K#VsJgnfo10 zJKYlvEshO|aD}ui_)WpJGnv~0wosnoY@M!^Gg+$*u{+ z1kF$0eT$C&j$N>jZL^kQc&H3WvK zfQReW?zBqz8;m;;T!h7}XFu!h4F~y6HBLSAO-BoLPma@5L%r2JbMDR%v0Z1Ae9}W$ z%$eWP@!(!|ZR5V(qc~nMnIpnTVtZ?ykOcr8xzikcD9>U{9K2FQh`N!3ez#A!=A3wv zbLhMM&Ma@GX$`FlzQ`jqH|j_|(;!Yd*ZQyD;fNnc%)gO{`I>2P-Wxo-|FE|3OPPZp z_@n7$A*1gjVo-h@u26q?8xt(#u`xM*!qN~ZsbsZhtwOhnXe6Are11D>h^7jUxGt3y zZ!Be$bl$l0S5U>Ykyb8Na#in;$M?9IItGia?(5K0u3Yi|j+ym%qFnJxjLOTZ z_xfemuR@UhY7IC->DFai?vhtwO&gOLlXiCS=Fc4pQDq1XQSiqf7m;mfSzJdJ_mrqQ z)BJ=!WX|9!OlRBd4X1OxEz!%yiHHoq4SFz&TOFV)lJA=y{Wf|O%5iD2I(A4>Hk<$f z{|4B3fSaN|%9J0QnW`M@W@e@e(Q@VoHCtVWSNwLJI>$Oc!>E$VvkZU#ZiiR2nRzO3!jWmqBeTMQL?ic7gAM;xRXQ1;y)FAeU^d}GoS5cH*=}Lzu^oKCJ2UwXSBUW z)3z>b4wDgxo*G6Im%~5tB0x4l6DiX8mQ)ydZ%ri?muy5#=o)b1^fAB3dGcBk2X1o5&o8n*T zI&hypO}H_U_16qdlmiB&425E#2IAt`HAVe!X`kA1119+n3!3|9|FaU3QX)Z=4QrQv z*_fgbARmbs?bg=uix0P8(kTmB=>)3^zC+?&=4B(}P1ceVxNF$W_G}wa-Vqd+b)=I> zL$xcwloP)%FPfMl0*O}$0}A1&RM~lb`{FQ$KfzrBz&wLnwZ!b>ntg+P7UyP4Ji=mI zS0;?eAU_tODIJaAk4mvG5KW|6Ik@3W+?!_)+pgqC=39Xob`HnS`DdAg1n(0^I3o&` zX}_}2AbiEy%BpOJG2~KrhLr%Pe0vjPVyA~7_PPj<+^a1muu^f-JOA0)ruPAId2Y#R%EjX@_L4HTj`)JYF;2=3Z z;fFr~QbQBz?)h|PF~JTD+y3QH=%A?0z_hk%#29iez`7C6;HIcCPzOg%PL)7eK2uBD zcF55J1qHlLA+f<3!HZEv=XrpUr4UL6(<;`+$oTr1_DhEGbgd4AAmlRSuW_~zexrem zy&2jfD+ZdIUJLgem_e#CML$lP;PC}SJdtPwhoK5RJJ$)q(p)r*9h&GNUD2j|VBz5} z;{Gaw9mKc=y;_Ws7f!(w;a)TcR6+kp1X=#&xIxU0vna&mRw#Rsz%4yWixgAG2q`o zX6Z`KC#wk<(=oS!7Vs&ldD}n&`d8kD`-rGyg&_HCbk2dn>-@Rz>MPXG@Yj&VQ96Ct zw@r(!t#1NsV3usX#2{RV8~Yq~(1C(aq7iX8esa6-O|5 zp(=Sbh~SnXwpz9ASo%oitxG%Boe#n|dku;UHR+vE?l<15W`4G}7Y;V#vM{UHxc_QL zA{xmofHu4>x`9420iWUYp@`=Rv{lbU#xObdn$aSYA%7R=8zeXjfMzD@WnbCFxFIL8 z0E4W5S+rdE`}W*Z9|F^}@6`JPAFRV4yOPtwVpR98?`=K(h=`CVqmklMx4#Aek#z$) zwu-e+FD>0Y{;rvRsWrg+ExefEh4^f5*XU~Bme)T~xbx8`1$?fV|63wvEOa35X;M0E zc;~S7NcJ+FcX7tA$N#ZSyH;R0k5S*yq1TV)oNcQ>;7=F-G7oduRWrqLyKiP!6V;u0 zR*E`+%qwS2v)yJbNraE)m`Mg-RjEg!m*yYM5pEKy{}&uKuLT79K`j$64})OF9qF zSKi8yB{RnfLh&RPZ_Kka5DNq^RLa%V(FeLN9*u(IV=G&A_BoUH{n*O8vd55l#~iCA`dFnh*HI-lRjjR_Ob9Gox!t zoHaZ)izBezZxFLrCCNJc@ofkYJmA1n{!0&<(|@%b~tp;BKpfB-%zGh9&*E>9DB`wg}TH?cyBy~pw;F=E4? zXC1jDJbwdW#;Jd~9kYv&@_(0=lT;DYp$f@D}~8QO_kEfSUkaZLC7h z3)mY=a6FTU#^*YDFjFs~XAaf&*m8Rr;26+sEzSYjKsai5;M|C4=K1X2R*I6vaY}nq zFzh-bP1|UlD0GqI#;<=}w|>nDXtTAT`CjHvMoLI|M1Zol9EU5@+K%y9yI#!W%HIwH zA4=W>_NFMDt*%N$A1WR{+P@BQ-Qc2K8 znzCZ`j)}WD1UhoY{P2!r;lK5JRcA7~7cu147yD=gDV_;bpRAXg6#s|M^DM7I=^29* zzRuT<;V#60Ujab|osbFW^1pg)sY_`+<^3UmlpFHw!SEl3=TpL2QM1STAyJt+PK~qQ z@C|gvjtUo%1n~>NXm0oggL}!PE_-`1u9u6vBiFt~);h~n((+bKKmu`%D0?#6r+vDe zVs=;r1Ddlul4AUO+Ea%&HX(vs0=R*dsvsmyYWkK+g}G6OFP3gSBpKXA3$l|vqK^7U znEry76J^(heUTFNym^)}GXIaLuZ(J=i`ItVZY>bpp-|i@?!_rmN^y6W;8r|9X>oVg zB1M7+_u^6rPVp2k_T|0n-u3;(Q8TTeuFHk~ z8y3{fy5@W>`}3M+dJ9D6cBMdljX`;!Cu6y-7)W%=hWw1y%W6nf<56X(34JZd&Z09y zptqRA{>}C|bwyqg4GS*E=1YgQ;oiw=B)oYHV-hD+$8PcKfKH@#gtpww#KIftk|kqUoE>25!16KKA+Ea>s;V@ z6{PjM0&l@X_>kFS_c&PK^$#PEROu@RY~)^vSt_qdQiQdkeHE}|g;ijDt_G>r`CF1{ zg3YCXd85lfOnvdOCSp45^ZtaqYL1+G|Ic4V3&mPLiamo+5q-BJyaUCEUhYYd?DqRu zQ$lf8O)3w;R$wCi^c2thgH!+AGiC#DX9J25OvwPBbK1>S}H2?r!f9 z-O@{8KMI+1UbM)DybI}e9Z+5UG*r_HF!%SOA-Uqr{w{EFLngmMxu7rMjj$ zqSp1ZbJJq1cs)NPsM-?iAX-JJM{iA8DVQ&R_pM%m-O??=wvhduAqV%QbSq69)@Eoj&~lMA0c(GhkH)4 zl#D-CzHIG@pif1%`FuaBmLLP|Sjh4(#D_-OT)h{^eC&n(zNa{wGK=R}d}HshZ6yA2 z9Q3ZxW{vFn^Uv&qY#p>d`&TD*R76RD$RCDy)u%oErP zdfzWc-m}&*zc_W{mq6C@^Su%oR0Dk5%+=yLeREG0%gCF~@UJa6uCc|t()b+$F=w)2 z#i#fiG>I;_DB`0W=+CZh(nN&lVhQ;7HzD&I0&52zO!zN$D;1l9!v}LI-}kqNF2{s| ze!-q<$4{>Q_$Q?aIm>uywuCt>*iaWUWQX2!?bVugjpgNx?floX-n!0c$HM7>w8$QO zE`4|7|8c~cf?W3gKZ7l%nwJakh)J@H{3_hS{LeV~M}#ui?XgccE1rd759S)NM1tF^ z)w*(|bCw@(xgx*aaVOu&Q zA|^|mL{d75Y@&Smr#`-tw9HW=j0GWVm;UbiQQdvxKg+_~88AvDMw)mXuF5IhlO4tt zfq|M$P$G9!NXkr?hz=_oMJyhhl`N(O^pQiT6hVoKs`d z%TdQ>yWvBjS&ms-#eBfqKrNY^bc+l$5-M~*?g^@W32!b;mTD#nU{r{;>~*X>h0Ob| z7!6M^D+XPt2FdRg#ctVyGfTp9)tm&l3QqqjnRVbMRKjMx=}wX+ulAs!RK1>O$0jyD z48a4Gl=!?IzTjIm8bEr78Q$8Ai!R}$ku%+3=Oa0=o%c&QR#8DF8g1r+kZPT;A?EO_ zf&oZ2z+37x#P>C|r#Z?o0!FIwf%L_yT5|nW4Cie^dXyjPim9Ew@+Ofvyc%7!zKQ%K z0gs4LG0Rk$QDsCrCP)ABF+5F!oQqNOo!-e6);of|eP^VlAXS|2{w7;-If{uoXsnEh z-WG*sl3Vu)Y=)FF7y~1E<^Pn?ySH4EqRwk#^1N}-_UyB6J22{ z6>bRiBd=#B7e&fLqv3@&fNA}vQAkD$KT1_p?M7bYqyyaF{DQs3)Gj{UKx90KM3d|8 zRG?__5K=i?TaR+BeC zznKjFAJL8hoiy{vxz*OD%hzFo*GM|{6YOr{X_|a2;aQBzrjLv3~qu3{Nr56{MB?XT+dWw1cAi7OM zz-=#lJ1nr9SisQa?5<9t?~pro=ub4LTwOe`wWlzThjYO{_K<%yR7cD6py)DB#KRB1P^=jwOK4KVIrygfFLgY{Weg&2 zK2_Ly;VuXQw8~A3rqPOZL$ZpeOCcKDlrgT{m0N~q{jQx~H-&dX*vU&@9;{F||ErJ9 zk%zToE(qfTaXXwt^JPmZceV#xOG6=MW$lC+iLoLb48W~ z>`BK*ss*0WtT@$wyXT%-D3#t>;pqhv&SH$5p}{>RxtAT>rnmHOjS=;-9Ai4A5e9_P zjr=&w_3dbrJBu1IC*?IMfCsKeyg3B-$IvT**p^W|0csrP>aos5e%X3RjlisrK(g2qXzBtLiqP-@a_gG6*w&~dlbcw~_1?uiBlg6epzCmt-ejGyMs z2LCKo55WqQzZhy6KS@UE{Ln-;i*zAy@$!?aNhno2l6P3V+qo#f@g zERkQ)*h1j&5Ds?YdnJ2kKoX)nq`D`FxoudCD)i4Hl11tL06>Gi8knyc>MP2?gt4sR zg#I-KgY}zdkCDZ-Kc|YPkz{`_fu`!ZeM5UkR6^z-zlojZKW(qhP)yXYje^-0cR$vD z%$5@f^O^yQ4Tl2i{d)Ey(YQ*DF_0djY6P zZ<^m(a{i@`LGY;uqJui{J-sr@2lfs{zD6x+qjXkzXXg6PklCjo$XKKWGaVBfLdNI3 zCJ31cfpQ=+e0o%So#!{<%qSEB1F-xb7a-2N%Gqfb3w&LxdMY;ur#as&D9(Yi^u3;P zPlaM(Cv>0jAwcnejFzyz!Rybu->)vM!7u2K?~gw``|5L;AYjwmZ9LJo<$-&aDQT+6 zR6C%o&LIsY*5SE=0FRF)HCyGRdPVTLom697IzFp(zZK#i`X4e?$yo@nk!E+01nWdu z!UjtTWms&-%HANtO0ix(DHa)x+^5RPnXxLTSWK3+8cXnS_U5g^^3E4?%=2aQ66}Iy z$p{S@f+D4%yvEQ@c4yef!hIoVn{QUo+4;_JTIP$R;aqpJ;2`Ze^qb5sOF!}KkK;;RT}5Dh!wT<@`+|P( z6t@#f5PFW!TVi|~E0~JkFBv4fBH2++sni#b?}z=qUy`b8gM8$ARsk>a!{Odcw;{d` zSKU?-m!qAo}9&2;ZCK-MtsgGx7@~{#5nI zA3;*&l?iWuzl>iQrxrwM$#A2K^6w*G|J_AAJr2Ia1l~kW8G@)4--=iLs;o2Ul9J;? zEkTYPCAei*Dds?Rja+h$R(3kkE4V5K`83Oc1KKL_y2;cHN=bu$T+V|bI z!|>l*IX0T{!#^Dbl&a?q&$%TomLRK$e=6i1D*ck>NCZOEP5bSvZ+=++NNC|0l)v6% zZW;Zh2p`r0K8rwJ^gE`FO{#G{Pl;oNv)d-90w8yaQpGDB$cA1kZ@LECKI{KF$rFuZG$PyUr51Dg zZxa&*O1a-3REmC@-+S-|dSL zb`*!})+aCK`dP-^4`{LB1xr*B#3)mT+85O~6jzpB$PW|C2XdC-!SX*fm#wh_gay$$ z$OJDQv+RS16febbOaL@IZNuQnVn5xcp#ox8&mn8Rn2yB&$N>@9R`umZ`)6Z5H}jli z!mJv{<&g%{P?Rfe$#aAM*Y5UhA_-y)A_R>sY%Zw(SRJB`eDY-2FY-4Bt>Tm*^x>O= zxRK$@ROk)%r1^%-2u6SK-7DnNCIiGeEj*14#RjWREN^XP@7RCG7vfuPBs(C_G5$7? zH`JhCjDUi9qp7XZtL&6j1$TD@%fKyW5xFMfseXD1@y zy~HL%TIcSIwzj+{2jtQx6<)3n!Ffgx_{VvJNxatX1HN8Snr*l{OGK^!((Ks-iQ7zf zvZ31!vG$iej}SF$qyJuWg*v{S(-;mc(a9k4W8<+9D)ScV)!AQVtc06(#xD7pr=DTU zZf#*45cgc*`8OWuPwPNyM4ZvB$MmOI#Ne&JsXE(9H|BbnLH=%=B|}kU zT7qF1+!}CawXka4YQ3r%oKu1HESZ0CUx52)j3yQ) z9sXZxZ{MLO+O|hONZcX<`q6WGivbjy3w}`^VhtU34{W=3_BmI}AHM!PpTqqt;~x_G z@Eojgmg*8MAqG7{5zPREg2>*u#N8*7znn~olVw*DZs6|rCzK$6(q5M`OGL(DiFb%K zWS$r0)yzYGi)5}oKN^MSGYe9UUG}Nbx_b@j7xhBw#2nhHV{14P`p+$)2-Z6Hz$WYC zRiS*|hh1+mkf=u-f+vpB+|1R4fqx~^1pH2Tu7T<$VlM4v^DSo)|KwZk>O^MuNaR$T z7V^I*cDiUdAWuVdipQPc&5{Ny*r{$%=J9Dbe4J`#^BGEe(O>w(T#Evsj*8e5AsA*R zPd9@M%1fT1x3g7H@@4CZDN+q!Yd5c&H>eKLh;ze08&K8CWK}2@ak+WU`$Ktx3*4ck zP>jH_BnQV8F(Nal*ARxw(xXM<&KxGo=tP{{&>)+Uc}Rq}&-uwK$Zmn^1)$+$BF!bl zYDPhpHSf$LgG*Ov6UnN-?ap<-6N$5)zIPxCQ?cJ)o->g>)&a-zb17UMF1SG@n0!Ix zm6xd%_{veX&9rP=0{hDYM@+FCF1wK{CX0Xqidkxb7`F29w)jc$pL=F7nfl3vMLP6` zsgNTu23wJo9Plm4#_D~N^`;T30^+^uQJ8FzFzC}hzuc|O7fW~ZKQaIxyzYfhH5%mY zG_ZvdB(n>w910Zc&>v7pdu0#2f~sDVLXY+2Z2S}$?M9mZqFOqY+R#`=h4*%0g2K1D z>DV&LF`_dMDfwU+VXlbO#yr%4PlTJS(!_X6dc+%|Rj+~vuslc=N2#!1rf|zI0;ay` zfP~g%R)6!|h1eLWGTyyq-mS5JMJmU0Ns4vrb~iC(2I`yLFB)Sf4`)9Od*hoN`u`6>$1nD{>sZh)Y)h7mwb^OGNBQZeAL;3q!3?QfpJT6 zb(^+~OICT$9N9e6y#kZON5Y0YdL4c5z?(}{ok`?PDfkBb%W-^|4*79YPf-&0vMH*G zyq7tGNapK9k1!svaDc$TWVz)-l(aHAv2e{%x_lMzStgZc(N}(?*biA8GO<JNe z5fMAopeew!j!@Bx;+u7E2Cco68LOJjf~EK!yei&2o*iv89`iTzr9mSjTKEA8EKz6p zK1tp$_!tW3n2HuOV>(g|aE$Q;|dqQ99Ti}9+sTnysz5;3%v z>k;m*2*Su-0xJHX!T$)H&fVN+!cvh3b~>b8zGnZ&UY6fRw2r6UqsA@mM2L$eF?p17O!qhm ziz^+^!sTWZSfN~X6#%7!cMw0YH|O=wQ&RFVU(C88YNeh$`O&CWq%76<5xRXVwq}uH-{-XfL6QJay-em5m z>hGGkQmG3>re+Lin77gJ^cRTqzY@~esYl3T{}Z0VRc(#_E|lIxoE+$&pU|L)WeH-k z2eEX%1G$@%;NWb_KzEFP8;PbKM}} z5G{YR6j(k(7Mi52`kB~NPcB%xDgQXtC-gCXwKL?;QIU(-(Z_0`!vv4@0}0oT|D-Tg zNm3^NP1r0+LLv62QQMDpn1Q{WZ5g%T|qj1nAkW>G&7Hb(zaDC;Y zgJk7bY&^8Va1zu$t-S|F=%jm;=0%6Y1N)0C#sGWvhy+#?lRsOjF@qwc1{K!U4^leV z6#{JkX0F=IkZ%@}%DKZ^{Bs+XiaulIa&bCNG5<5_mp0th1&`y^X=QkxwWfSdn{PbR z!e};al1W$?a#Te2j}CM~SOJeS3fY5j+eqA5neq5}H5h8B6AND*R%4QpA{;b0PB>mq zm^Z$${2q;tlYpdX?3)sMqWI?p`L`qL;@s?p; zHYvPKNs4b3i(*J3=J)cPrEnOi8oiR!rF`V`Q*TH$5_+( zX48%6x0+9hJJ3XaR$MGRCgdz+6&(6j6#Jg^ZBiAKKB4DOAus>WhGMXvB&SPTr?_~H zTb75a)P^eGMOt?dhJo)xQ2~8#zQQJawzYqttBTpyKRoSx`YiU1`O`P+6^%!ubguDl zQ=-QwO}DF#64OC1G{x;%{7YaP;3@GXUoo)wQ!+l7#cyEI2P_t=co}Gr%*e6R@F(j1 zp>R1d0AD2o=xHUcSuzJkjxdo)lF0{aD4@$0aQxBgL`CVN#JGY@Lf^&esysKaFz zh}YuWlLuIf*0?1ugf>|>V+>f7tbqB@yo{_=L`nHqe?7RUP&5<;)3_~DhBW_EMU~Na57dEBSKptcpBh z{E&i{?>Qb`L;6-RValOD>UO|Ct#Ru9O(gCoCKi|lno)XTuXOmgYZWS<#{6FCtcM4O zV=^qUDNMQ*^D7nRk3UjU=lBw$U^~LZaL3?Yc~J^#^aT62Nty7k5St&iUQ^Dk6iR_G zA8%YMBPsxyLYqiTd{nO_4N5NoZ|kS4r|vQFIiB7fVwA3;MuFk!ORd68n5R#8m?6s# z10yLd%?nR`d{0;KcDWj42ypv(cZ13hFC3U4t>abTQ!L8V1vYhM28Y_Q5M!pG;-TBr zea~vs?lte1e?>&5;)=na{Tk1@zfjg^TfziG+7BxX&0JZ*XdbJ|DWBuy=28 zn&YdbV#=iKPG^s{h_^ErK*C0o%)8oe+>d5Xm0!^kyi@6?>0lBR`(cL) zntc(4fshsO<5I5qA5Sm$%_bpK1f}H|c6zZslqHkkR^`7@cM{dPCEERV!!3<i4n_M3i^e~hI*Mk25N$2Lob1ZfQEge!4`ozt!l-z*9R0~&Gf zLfk@ngUElfyB)7OIuE~+`u3eSl1;osPWt@tWjo(mc>5jWU!bbfXZZ4-slIBEVr8q} z2f}N4Q`3FXNm4e9fmctr*z=L|@&z{e7=zskql^Hv<_tg2Z-o*?FH=kUDuR&Yhx`Fk z;hkZm84NQ;g=8DF{Sw7DdV$VlaV@pDXuRZ49Ti#ieSf!Ai~7J5Mg%4T(_-r#ZE>@f z$tI6t$Nk>MPpBPg1FItzr}}nAyO!tuK}A6+hl_N-7r@;+yqktOQmK5Wdd0fLwKf9d zw^ARoK&k7|dP4{K<%H93EV)H<`|Q%|CqE13aM<P4B; zOQQR6ruVuiNkDt{Vs-b=ME;?0>ZH~02+TjD(fA_8%$Mf|AW_-AR@n>ewYPcuEh?*E zehBmFCvbWcd2E{A2TD9Gg!lJE`%;6p+`Z&syK#FE|GL{fogfz9`ES5rfh$ZuPJm z@q>I@m1%dr#Gsn>3frQ)%NEs>`oujEedqaci(P8I4U`-dam+xW>WlkKr*EL5;kb9# zGGHl`AB1h&-2^#hnXWdyI zRFm$eML+x81l6CsShf+=cbPfIc5wjb+*_>a=7U#~_I!`LZPrPkj#BOO-R?ER{Q7Tu zbZGf4;aSW+E3^Iy3)Qdly2GQx9+uuVzUF^=9L>35h6(n8RBN@5t#Ux_bN&mr=)sFH zU$=qde`Yn3tD&)s38;8o&FDpsJ8c(^BJ`4BnM}xnlK78ILu8eIkB2E6JnmUIC!p4% zMlRcY5VHohr+@EZ^dtmtE(rCyy&(x9UJze|;|;Ky$dzopd_*ZRlIYj~it)3;&n#59 z#PgbhDo4z2C@9W}^l|tTUf_N+3Ra9?j)Kd z(9g)a6c^1jQa?!Ipa)y)wE@@qQQuNk`fV8uCuDn>lioW*dhgoB4}>-5cfD$7YW11) zaTv3h==R)ZYU8M6>4~p2xiTsR|Kgfqak*TP>lUM6txd#h;m^mfx*+?BfjhC*md!{9((Uh(su{anIvTZw07P*Yoln zP!vpMOeZaC^CI|+LdeF7nh)D7G5xD)$laj{}GCf z!y4M0lROlRT|Di~%T~N*6!_yK{=}K^EF(GYjA{YSNO26Y1aN*ydh~#;T$DT$h)0z5 zmXL`eJmWj8{aR&T<c1cGUig=tKjY!k2Os-?bxOO&9(kD2>J&Gf>RYX5i2Z zMs6>>HRJQyM@I=aVeq4OfQ~qVgTCS_L`Nh?WXBHyzD=hQ^7Tbb>v(M~vysSiB6$Up zKt=X<5yC;C2VJo!4%URQWgZocu|O~o`~G0gbwKMx#*M%G3o3mZ zu&M9yzR79|C2FE>E|vzUN5Usu$&gRbb=#UR$82=xgax8@mow8#o&dkiyi#c+sbh*x z`A(BPI-Fg4FgZgAUUhiRt#mtV`TWRGl!Z%}3a~SeVs0`qP6(?tEuyr{@8gP<*dHz@ zJH%5Y*ta;R>)_;LvkXz&K8c;Wmk7FAj9bxn)&6sDV(5{qcQE6i7Y=luO>znFKamB* z(oA`%e~L z@0GlIuQHE8-+m>gfaaBQK}8ZuF0pW(vBT}u4Y|vD(ap?seimFZR#Qme!g096e&W#J z*}CNm`t!Ru^=QYy&nKFg0#q2H*X^ezv>0Jfwt`V(Pytxp|4fs=RZGq22Cz!Q3AGLu;#naN{3K)@Sm*l3#( z5)z(|yyZb7Us-9;tQc%K9GG*aK8p5RAKEB}Z-!*(Y>aerBy8sBN(brg_rJaOj- z*=-l2DzE&)_15n^Zrn`*qN=EB;(D)wExlgS0hMc$l7*e znxo8-kk&be%OkHiY^%lW*?xb3*|c18z$$bLt)`5HTVHCVFR3STY6p3@#UtX3_{6XY zy5Zf{W85Nx;{g}*n>+rwecSPy`~@-1q*%H7Q+gv0zvU1*M2DrxSf0V{$a6>A+~ZeO zBXVd52lacs2NeX}zHq^K1J72X;4yry2>ohOk|aS{N++#}=Y+M>&Qr{~v!Sn9vI04G z-}J3SZ^)YqJ(3>vDPzaFCSR&tMsKejS~6$*{zpjG>7n!2P_XW->7pr z*#6&num>*%c3LlPeNiYQs5le@uN8}C6xKI|5_leIK$)us2`Szuh-0>ayly0S9reeZ zq#sQ9JTHw1?hq4u`-@0W+!b}UF4$v<|b5=l8Us?BNU!T6q>zjBTuoIReDKD&urP|3v0bfF>m zVy)nc;g*z4FkdCsEm3gE2Gv>*yGMlyGc3}HBq7`;f=^M;A_+K6?5BItW#&Z$q+?7% z{*=gsDtBRo6E!NxSDI4&tlrm0=Tf^c1V$&(0EkGeJYFA?FGi7i=W1W9>TUuBDn=@h z+7+s>?gR-F?4C=>`-~`c=WmahWO)F|YV;CZVvkz*A})hVtJHUrYuO&(6}Qw!;-ik| z7CwRl^LcQOsImTB-?Em-`tDN1qEm%_Oq2UUN$Bj6af0cb0xbYy;CAfJ6wQTta{fhw zAp@sL4eP`kLgb=>7XQZu=$Pzg8S~agX%{E%+K&0RA)htKj!_$?s%vhq9(?Hz{7KY) zT~iNVfd8EwAzW;S|JE&7= zykeyAZ*XqsOQ8vV33~JjbtRXg$l>b6!zbjvyt8{FC|#($OIp@+d|ZLSPhEzLSgNJ) zi~JLA>$Hew$3VV%!p75tPsmhf;*&t2T7^#EWZbUK^v!wp#s5auxAM zS+w{`eK1NJB{Gj=+`4C5&bs+kwJmR;CJ;cEXp&9Pduvma=8O8A!YlLpZ-87w3{Ret zczB~_Rl%9{amu7)NlRPO8l5xxHSY{n!TX{q05#E(x&VOFW`0n4O)DZ*`SV{akQ|wI z{?NJB3YIK`CdE;3;FILnGv+!8ybJ~v3U$;zdE-^#l)20FJ)X1C^>mC2zk4kSU3JN} z);bB<`do)K=3+H76D|sMFFI0oH+&B}aYjc)9T%#Hx@(7AONheI+N1%ywrzvLcKlv% zx@6xx`gKX?37k#t6($sjW5ZUhLbd+vLP4y;+H(6 z^izOvD1OAb`8xNVMmQ*`(*519^@C9npiaVGcJs`x`s*S@VE1cKViWcwQnZ;Q8{7<` zRZc9OHvO+4Hf*QZ@h5pfF;zVqy3>qZQw5slz1Q4UKi1n!cjw&ry5kIb+U9~Seu(7W z2<*C6zZNBEN|Z>q(6sQP&l|X%m5^qpc+Gz_8r@7s4K~V_PQbTPF3*L;_a@@{OnnJ~ zM-rbK*XuO(>Jis}cTerBh6il(hX>$xv$vH$AZ_M4nQRZDUz@aQc-PkEFpCU79vk(E z_O{>kv>Y5t!rT!-dLkDhLpNWWx|-5iP1uI5AO;9T#unYr8aX)~6mj3}2EFIalz@+t zOU0oR#vJq30sf(W4*iV5@Z#g~9AG{ahj%1&H^ZrVqSN%Wdj7kDALX$o)_3gQQqw$; zMOgCkkK^g=3e9vZA)=Jf3?-m^+(vx&Jn0%#Mm#S3$1vV$!feaQE>d%7RD{T4PccY( zyM6++!Wn-Gx0J~H?tZczL$}Ex^v8kWHVb~VL;b_Q&7e_c&B`ecZvcw82Z*CyqH}jz z#~KIM4D*>xpzl(e4JvXf1u~4c!S;pMbP&y_aP7w+Q&@iJAU4GLw58R)%yh?U!llNf z_TnlPG6;3(D-D0gw`0kQ4Sni5_O7xvqGV9rGh5dQD-Xkq>EwB~oFrZo{^yRU7;KrJ znVz0r()I2x|1fpfa_GA(+VdXpK}&5Q*zRw*Mue&2{&Mou0BFWMX~fEtUnDnrXE~OR z+b#~#9G;+ijy zmrSd5%OcMe#gr_N(JIh#R=-=y7~u{i#uRWH!XqrdpOxXrBa9`q#(8&;kCgu0zD8)( zdgohn*x&d35T?N|oIr8%b32eQm+uC{GDNVviE6p$1u2&wFIlbO=X55HQE=VjD^pB6 zLb5H#FNU5rtQOe-f-HE9hmStPJ3dPpQjw%0Lf0I6-f60wIW=_}uFQ8sW8(@&S3hy! zDL~CPKggDC!@9Ij@P_i(ZpM~B(pa6tn@thTv$yjkq6I|`n`4+@?fCR+N1zYTE^1F7 zS>YwpL44?z-sd?B;_9s<_Y>-^vlFNE%#%8xJQ4eK?6)Fjt*)Mvm6}23snOUAF`M|f z`wHwwUQV~a)!(Dz4xhIpQRG^7#8+5#9LhsI|IPUl>`EB$x7TERS)IF+HGrTE(cx6j zMmG4xMmdZs{A>XjGbf9N0wF`5b06Z^iQQHB@XFnA)|77wgeTil3dC5*zvsAK^Rz=@oCkn5p_mD>QciZa0#fE2H z++)UOfZwA=W1NSfLZf~^@9svSeA%nt%C~pJJ5Xg!Uk=ynH&xP_6#eZ`v7rEsa zMGA@uD>57=D7OT4AWoLR<}EmxA25+L^oC`BRAdnL3i?KFlOTlJVx~Xx7ls?k`+77} zviDSK47(9AacEUBdCGjdXjN$>R#Z?-{lL6r4=*zZx!MBZAQQ%ko?u!$&J z5sfJh{`4Cc(oJSl;ahslF!a92m`HnYaE)SO7ul?1cQ+UGJk{%IFY29ur58-We|=Uk zI!Qo{Alvv?M~~tcDO5?c3c+q&4(NwW51W)r<%ohX>FUA4GFp~m^SA_`I9}RSH*2OG zkeb|_7anqPR%jQ{^jtU0b$r<&Ibe9)w_EE!^+OrEFv`;S-C9}BrU)sZAC>9_qkvV> zMSLTRv<&{#1XFiRUrw`^7*>2D-}Zq9Jz0FBXEAD&Awv>IsZWO!yuKU394NG+ZHu@; zP#wR{67sJSCGheLd#qyOuPd{xDe~__m9x<(-b-mZ7NEu@4ySOe#VA8`JaUjPa9?f_5TE?w@)2Xk2lC#cyt^V?Wc|YHckCTZbC(CET;gh-rj6WE7j>wo9Y+)ex2R;^^Dn`Q5);glcyG8M%(f zl{gU3&Cd|W^|h0b;s-6E*IEATt1;cg~fTChi@bI#FS;&8_Mj9azgl3pyVVDaW9 zp8Z1JTaDC|V}GH&L;SUQ_l|<{%*0g6>owvY{G40ajql*s|NVD)o{SgOd{Y9mwpz4< zs~x@PQ>eJ+D`E>R6V^npNwXquSO8JD40-fG7E!gi&e+i3JE2ljW+&HvQZ5rt0u{q; zPj<+i<&=LmAozEs2uS(d=CUPvh{xymPAMp_3?LrYILVO2c2R&p47!F|Y2zDds+Av# zIf(C0DIO8Qo~@`mt$i|QcN5n)Z*fmUdg$QCzkdfJbQrCC&BS)&la$a>3EOH>+%itt zY?;qhl`W;~hVOz+lF$Szc#J+C^Fhi;!9!v#246rzr3?|m90o+LGUyWarNl2riC>%A?YdK>{3l)8GiyRT+fOG0C6Z3WZ zDN1ZgXEUx^NaZDcwXDE37A+DpU>!D5tAH)(LoT%eUj#r=u7 z9Nnd(C~+)^^FyU%oS)|!v7k481Y5Lu7TQ>)M~mr21l?H~^k3c6x~I6{5dy!V_z_$u zY^gWabDDl!uD6w`FDl~p#|^AyW~4ArR!rIsuYIV#`-EU zD!$L=T*XiF9idFb=3UmSHZ*;hyw2IW{#|r`rR&haAQ+ogfj*tDkD7{v;9@FtkxYNb zAE7LxW%@cWrCE=3Gn~ca3|*-H-$`xh$S@*iokin@`Unq4J%7AqOkyYz zqqRw4GDITumJ=&SP2*px$hF>1DLFqBJWLazEAG1}+b4G3_cV=Vj3D(Fu}g$a0|nO$ zHUx4NX-Jgvx{)jjYYBJXvoaWMre(n7QJ4*c$dR>$dN97$?Ziw|T81r_Qw*3rH`3kk zpq@nYdI6=il>im9w!H=v30JprN!R(lTH6bx?QbdS1$k*P{9IGrHTBk?GfQuBMM2U;$Ow2_30=e<>=9LkdyBPnPiVgbzy^VefeOERS!)6^$*@qA2IO#))Kemg|>GI{9FDXf=Y2n zk`wOEzU>8jE3QNj`vgAE0I^Nqb*Kc^68V=^F^Zwq*jL`{94xB-YUHqx!hhUMT*g0< zKgp;Fn*-I08tk*iJ_?*Q;)mCh2l7^5xDHnl86avcHnWRp$3s4C{&aZr?BHhN8Wonq z^=yJ#ji89p)lS0Zk7k6|^ ze{`5a#nP8pryCDE95EUWm|;l5Y5hV>@a@vzE&L?;Fr|!A*hyE%GqMAcmsX|yLuOT% zf$^6ls*mv4sMPj>v6%1f!`%;{vwhMUk%ZC=dJ55`py!_M&0^%w0;E2&tOk<^nb!$! z@~pvU-uMzj(EYn}3EMdA81Wl`g+HvBfi z{Bj{=U+74brm<~jc@PZI#%2`$SIeKC8l@<4@q$YGnE$SOV04>?$a@t0RG>LL+FB#= zV@8mg+k3N%+awoeDBOa6ITQcXoQF7N?MxefzHFe16RG5m4=?cVpj{Y|DMj1tq9?kIc__-~bS`L$U&u(P`1-MC+C zb+j?J4Qa2H#eJ^7Jx?7mM8hprRFe^qM7|!sTs0!$xM88Gv45XdtFyR1#(@H%0d>Ky z700^BZ`uCl+dM91UI$*v*Yfw9Z(Z5)2TmofS=o2c^pS{4x^;@7s~SbR3vPScKnyoT zywm$W;+;(<1WecM^pV^@iYzwzxAgOW^mvneyytnV3K#W68Tx-TeRW)u?;9@NjPCA^ zF}jgbBt%lWLAtw9sZpYIqhCrGNcRvJAT8aK(cK+q{?0l7Zl8C1_j&g`&wa&x-PPD_ z^MT&(q1FRP{F#-xi@Dn75WfPXgWUdu!W6?8$0#+hPW@-Rhbd%5GoH?$a*Fte$1%gL zCVo1^kE$>@82(?yV4mw{0m+bCCSM}G5<`-+X$_E+oSQ$$VGc-z`=5RdOH=BS*kOvS zLT-*mj34VpO@0_dUgL&Nu^O#<=dVQk81NCXm_J>;lorD%$OwF1{C>5Iq#I6c`qdtR zHoHg>dv`K4-wrE?;8e&ZV-dobH1{&TSB&~t^mNQbacM|03h6P(4dh#Ij^raT#eLY# zacO;2AxZilr$EtR0((oA7&Z5wrCeOyP~U&TDfjr1-XccNKOf|nP~^S09z&m07Dfb- z+S&_rq4;&15t&32_)q-~e_JapqsdQLjMB88pDSQzgl(|C0b#*`8yokBtHeebW4AI* z&?@)wG&1z;*^c00z=s{>`8ex_`GkAD6nUT3{l`W~ov7S#N!$x7B6_V{oe zA1IqFYUnl*&D+6Ro%SpOJ|uv7qiC=sXsyl$D_ zf&&=`qm#->o}3gF$z!Z?dlj=1W!JqDcG_wprP)OJzVlxJ3`5RU*r}QVa~7vcn$t@% z_@rb775{=)B$ati8JfZ3)waVr;W1G)7{&f+FKyCX1nUeMh0-|#jzTm}NSL@5U@n$^ z`Y?5f#o&EvUuH27R${GCzCO}7{`*&sP%fQ zdA_&apV;D?7lv94Zqgtavr#thZ_!9i9bVV)ERT!ZCIadm{~U1m))cgQA2b)-I7^rL z0jf$OSYVakPKZbo39XJS=Qk~L9i!KV3`>G&@zL^l5CmYK_`F1~Pdyd10=)jpel^z0 z+6=K<=Xay?d{PAT^N9gfYjk1+I0N&U@tt4ukkeTYWM&=Kkh=)WK0*{ksbU+BlPBoa zW))6KP-tkYSS_Y&5M|!-*SD<42MPccC?7DNg%+H;>QIf3+mYPC1e~eeRJ69w(P;3? zQ1TX1@blI4y0?gP@?)W&YZ@6qmy8L}Hc#XTA zd9yqhJ1I2jre>5wcemk^;G~A^_Mj_>Qt|1CGK!@ecFF*I8m>wcMha z4}(q_PEB$Bifn1KDE2g3SfjXVdWs24Ssgqj#J7~fo9;!V&Z(#_B??u-lEzo(+*Kl6Sc~yLP;ml5d-6><6w%y(V+rASaBUvtzS-7m+yY#`RnkRfG%2t8qU0ODcTATPLC*5a9D)W^9Ea&wUq~+5YVg*G=xbjRsZqI`9ARA%&%33q1bvlbDb*<% zKzmyxc+<-N+QA@kM5&Luoas0(YvWdUwpBR$5xPT-OM892ScrmR0K%fEuu%a~qYd6~ zub_MZ{#J=4G4|ApDVl*97|D-rWqj@JH0$EKgGlG5&FZCrbM6AXX85E0OqmL{Z`ku zPcwAK6Df8y`%z;~X4e({SEB4J>lC4iCqQ@*4Uipv89j zEwY7U5+h-eZQJ96fy=t8;XG&)1z2{SXD?k)F}LOiPpEwBcU|7Um>?#RAP2w|ljLd4 ze>b$RIygnAmH=$Z>W_eZvWBew`-Qi1O290voYxipdbWtQYHpnr?2yuvo5) zOKyQ5eeyV4iwgW~3j0V3!3<}wE;}ZS62d=9tAm86#@y~+jOZh#u50F0-@zm>;YS$$6Bxm17L`ozJM-V74{O~?U^amp=Zl@yi>2W3^HG&KGO1tq(JDVr2GeXlO6wI{GWa~Q-6LHW}Sw| zM*tB9A{GvS@4*RBpE!4w*Q2+Aytd=xwp(qm;TgldApiedXet)Y{lO7t_4DBYoQ3x) zaY#FtMvTI1mz+*X&3#jc(2}ae@iCaiU-agx((aLAP~b;aA+o%bI;fSr4XQXAuaTA| zjjeJwOs))u=3jVeP{4Oofn?%Mp+>X(b(S)V$3fC{p)v9{C&=tI+fkeLL*o?e&qFO= z@k^0u(d$lT^3F%+|CQBN3)3?R(H3SW(1}-8xHf!Malu>^aWeR3t|kKu;ta{ileHp7RBe#Z>LA2 z(%-+Fhj4~Zfw^V^6$P0{P`Oku%2Yp^l~{b|9AJOe)y&n zvR%q(KoQno8o5gK-7*Cw*c3MB(F!Y2FhP`O7-!wL{;V}jv;tI_56(+}cx>_iH8(7F zhi;{gC4+z1(=M_9g?}534Cx1DgK=Ovg8x*iz-i$3&~&VJ409GXL$+2W(>Pxhgm37o z%#7Ld6eIemc%`7wfV$yGIeUw%HkuJ4N2vFF!vWAiB<3?S{VP>PH1@T6$Env0y{K5E zga{+M@JsgfqJ?Gp9ivx^^s)Zxl_F?r9C6IpZyb5Lvw_RY?Q)&5XyxYP7m7Wrsl`ne zJ3fEtL3>k=rQkUOBJQ7aVDz{$Al9ZyA|-$# zQ%!7d&@PE;Oy6W=ensEBR;D%137t!k7kDj@=FeIZ?qxOVaP|(wjsCsbqg6a8p@Rr8 z)RATFb|aiM7sw86;%? z#e+#aTydW~s8Y+(;iW~d>nBl_|L+A5=o<#EehM6cZ#8szp~w@XVV_@w>Dpqv4Bk{iA^fvK+{yCj zOQ$zx_s?Hr#Ogt8W((VoOdOFcACv$d$t}wxkOfas3cfNN4UPs9#1Irk{Msl(Rd_CZ zA*%rg#;eEND2X8^+gfFHe}w(>$PLB#eo;|xR8fDEWGFsCl4ufj+kwi~WdftN81qD* z^y+Cvy;8T0pq%%Bb-j%bn;Jr}6YW6IkV+c6#{pQp&K&8xLeQJ&f9HteS|S#Rqg1NG zG{F~WRjCTzfp$0H4$ECKfs{iox6HpSsa;^Y663JxnvTdh;CvZV4%)nrsxS(Mt+ z#T!t3n}KKd%F4Je7DnFf>;eh{%_suD%Hl z`VoY5qng%xofs(&a7&a5LQJhrzQCW2Vb2jQSm}*P7%p^);8~52zS<%bozsKozPu(Eb=Qlf z*9*4q%hU>eO0Q-(?-H>tJ~nxNwnek*$1+b1-GvMkM+o(AFCC*@GdJ-fj(TtH43~@R ztNZ*C`1=FdChTCnr2DoTWA)p$mw|ui^TAY>|63@3zny-G~_E8*c?6jkZ3vp5xoTxEQ zaHbJI_t#}iA`88R4;od0V5+JbS=X=km@s+rC9ntdZ zmJpD!6Refi{Qwjf=pfo>TAMB+qpd>tS5vL>(NZfq7;$b*96FAi{_NcpekO1gV=FgH zCiibiSA^Fv*N*gwbWonQfS2NyrKbp)wPB|WNIl*x{!ppoD*g2#o%+6?q3eWMOyTE1 zY*_9|=U}&O=wEitaPPW3aj`89@u8N9BBYKl^ZB60$c6kN(xDD?8w}w6eI$$!a)0L<;oX2GNmpkR^F)4=EtV*C+}|N3O;b;X zEO{g%iI^mzB?#OaVQHjGo(XpqNmX?2Id#vT$y`=BJcJwm%`2U;4!CswSO(c(BIaXX z4Uk2j)qzdhB1strSS;Zxnk@fKV*TE285z$cw!6q76CCdxJ5&k=cs^g{H| zo=*!g7xdla!UnniGa;8@EJ1m(;dz_NLmN&mf!^zc8XXAV;%M@j#g-=c`m8J)bo0^d zVYMuCk*r=m1Ht{NXiZQwm~0g{yczC-b)8dpo8fZ172nVmyv7jxivKh=uGuz}@a80^ z-~T!=0x53e`Bb4%aYO~MlOZ`|#6aG<1b(Cr<7DS}`CA1_PSr2zd3UmYrwrv$M$4iNOo(@?CtSRr*fu$o?_mw4#N#H)3?ki%%>qhi^^-C+axvF`V#!^4L@s*xMn z9>PhIHY}eu7})~l{xS&)L7-S~?M6PY`Iof%gmMvF?5M-U(cK}>wnW?A*d6+Jf#n+~r-;VC7Bo)H4Dcw3Si@&fQ#QLbs-9O# z#LI95rId6LBk_46f?6D z=?uD~14TYy^bqHhw&Tb$`COs2D>QzQ1BpSZky_t@)bqo6ut}v_Jl-bpgQJQ`iS93M zQ?CN*^B6DjG#|D+drw*ztJ#ix)+|@ZNu#-rXQ@9~ZLVQsY?s?+!Wyu$8hXiV0fL1S3SF6x-+S30v zNAL8;i69wTGHNTK$fCJWqPJOA_*1SNEtAcFo%)@^kfZ%0WXTpKGHH#8@#dQa34T=M zBs(w_oQG`8(xnyoMr|MO(3{Kpt(%8{6xk!r4)RpB+DfHrwr<4@I>5qZ&73S$X`p+ zzKJ!=5@q}~G7@b1DE|-$rrnT#BkYly%#aO9Tzms}hVaAY3?D0X0*?hMBPnocY1>bak@n^rt#ZZM?B6 z!)4VcKTIZ`lBb2G10S8J>1FJ0DpnK*MD792TmM{X0@WS8@PJ64NTCmT3VDRU5!g~J$z4viaFhF-E&Tx|@ek53{_mrBJ1I$0IR0?(T;Sq(^plL_Moxib2;ru7AnuNrn_$#Q(xy)9^~&l z{an|6q=c#4Y;^pSBT~lFWV&oN&4XK6pYiKPtb71WPt&CLTfdXq%+@m_1K_v4I!3$? zhx!k30QfmtB^3WvpoM$_VQ{ec_=hu7-U^3io}+G7EZAs(_7 zwCm-x2jx=EC5!tfW}7ZhrRZ&&k?~u~BC1ks;5b~Tw57hh?90~AdzHwXWD4Z*e#ZR- zgX6)^foCr2A@1f~x=doHxu_P8LmW+R(&PWmWBmE1f6jXttWin9&9jOIl3lIlQRS{@ z+c>gDvyAhwkbU`Zby^_vTI(wlhJW=to4MrcfGYQ?j*dPZcKE6vl+{WC7D4MOPiqxD z)c1FGsozXw%%lu8)+XueIb+=xOd~Jpdizd#r zQug~3H}`&zd9&s(ZlWwZVySU|$soYnV&vv?A6lQxEPvxOck-*Ws!BP*(qb{TD>gNd zT1aGT91KSQODhgb>Y|xt1~M$NmqH!7>lw!jc#w@lhhasblF7C1h#{;_V5gm=VU&T| zU2{@aQrH^y1r@ZNDtBBt&9ThyD6s9U^N@CXBJ>WI{nJv^)umHTP8t3O%d1t{k(xc} z^QY=CcS7EoZ&9z9i9uMdwLk|EMj)y9{2}}A2>>AD1MSNLp+~#q^oC`xfC1&t$%la` zxcBwvn=bg{XcZXqXDH(SP^%aW>KKeT8vXQ7m8RDR&Cka7)13yDZ@+4A7~nP(lrfqc ztb~k*j;*>>UtgaYixyPa8JlP0Qv{aACq~YFx4o|IW58-YCN#F@wHd0;aZKxX;QtyZ zCLep}oqyWD>#F%?qlMpFd+%5>mNzo&C6iBe-Mvcb4ytuzkTPs0T<|t%V|(JHRnLpa z%Q#?flNo{O-NaMNH#@mNy-PpXnW1M^mhGkT0b#o#8FQQMWq0A@3uuoip`YG|n?P`B z7KtKFNT&tXFIy9&0;LC(W?TQ(c4b+-)=#)AdGNs6NWj3y=upcUDjz7L?gYD zb}D>e{Nq7PzN1b6Pdy2z2y@W5$A{u1=#TtecX-3{hN=_-xouNbVe5KS0+1)}GQQvK zn*Y!%nBx}Bd^lY=pV?Ffs1-p`0by)!tMfm4I`h2`I$#IedLYFjDV z$V7ry33$KaZBD?U)>RV*mP+joKV2d&|AHw>vsMe0E~SsL85vfuNq@`Ex8f6m4rN%O zp*?9LTUc2PY;IWfI1R5FvMr5zZBgdm*XphI)|$fv6ZJR3D8sh4`%z%piCOd|61`Uc zDZMI@l5+vQbzfTcEnfwHc0Hk;pWD~R&3Sd=myo99>6dKjp#dKgZs}0`WSK`6dxp*( zRUfsp1^?zj;U3I*TIrXX8vjRLz+>m$5sy@wSdPsjI z^qGF16S2Ttkd7WvzO{T3>`y) zDSPu5ewuzvrCG*;7S%K$NAEwvsn@S|x2Y@D$W1vIQN?X#^HnVdK}{bAYn((=Y-@x~ z*3MddN_$7<3uWF6ynh!fNEym#Y_(3d()lp1^fJ+IZuLdTg41`EL{tJF@b--uQ zK3nPlwCgOd0ieR))tHLoklU5YDqmn>0&;y8y0!PdmNPO!r@@DD(pmXfteZRVQ*|&% zh?t8ZoprtiF7*6$fsH?##K#1Sg7h2xJFyh{Z^Fq_RCai11^{UDVT?hv1Y7;X>{A8Y z7PX3HtV_VV=xZDCnd#@8&AT|MoB03$+nNg&aoBs=d5>S@gL>G(+873f6-m3WIXktm zz4r_tcK_^gj%7{kGrJ~)ZJ-j$>tUdZT$I%Wv0SEbftMz*;IL=F7;t|{uP9{0+(u(U zGq-s}{AKk1Z`gqewE;$39KoBCW_@cT!{TGbT^l@*!F56d1Q3GN!9XcL#cs~ z?N7AUJUz~TG%D@XnG7!xv6I2}KayK%;TULTSdy>S1J7?YaF2VBdfs}xM%@UA0h>f# z1a6P8T@7h|WUQvN@bFXvcX0X?9iV}4`=x{+s`4%{!$etzq#Bf!)>>l8^uYz{bFcJL zftJ6zI$q&S$O^*xLK(pBn zc|82uG2K@!;UmvKwW&5dzrrPiw{nn0jirjMPh^G@y)EqsUo-r=zj&O4is;Me{#MOQ zR2fEYRJBqEHM)>}8kOzFt#>>XQN!dVA4f*0seq`b1@{(LxMcxLAmhzD;%gN|a&{V1 z(zVpv;Y8t^`(HFAS|<-lJR*}3@|jYJM8r|fLhf8VUv*&bUB`>u|m z(}-=WS?8I`KJ!6^61F4A*CM`OoE{zM$X|QXdFt7suVuxxZt#gwLJY%P_}0*n9qTC{p#z2j zKf{I!HQ(_cPB;QB+MSEdg=hA?xdHw9YJ2Y@roloGGp7jonSCGb|KvFdZY>sz15jPO zy?*uZCu12e7RM617@9joi2u9B;;GKHGn~h3z%BvnN*(!u>QTc)7#sI(gw99Dj`%0H z28jnAS4+|CrcDJYcuyMZwgXRJh?q38Iy!7##g2*Gkiiww;d4RgmRXgbCc=`eQ8tln z`!$ZhaCWbH)gvRA0cQqcXgcCIR*NlBh7}`U}26d{*@xwr`Dqe62}#vrR&Zcdyz2&Cc(Sh zhQqL=UVZuCRkrzH)rQspv49Mh-mC@IAF780-)t+pN9$3&cAx1;J$HZ~MxP6KR;s)b z{BS^pL5BxA__lZ<`Jc>@*uGz&YN*M{5>^$(Z7eZ2l~pwwvnYL@2te}M8oV+O63<%N zX?RJ)ro)$?D`A0!mcaUH8i%JeEsldlwNxd{Iip4*iwCLHb*i*u(z54JN1%W1rKabV zotMqdVGYq-H6xFfc)Pw{z~JzOVpp`3-da7*bsXKEZ_;2v^;y$)y9?#X(DlvkkjOLP zsZq4wCG5|*P{Xzn@}=FwhV)5fBnwA!!{7qY^Aim+-Mdtn(M$0R5aYc#5aR4WSJV_w zFWt|q(m+>=zmu`kq?oDFT(qR&D|Rs{MFG7q(%`qKcAX_~*z{|_2EN86W&~eh4Ckpv ze|+6AoMk^zkZ=i7zctbQ_5jb_g1I>=p^R#|ZEj5T7 z3`c-*#89Pc|F77Pq8bXU@5!BN=_OTM=P>gW)q}}aN_BU!Q?9ZG<_zNRcD=A+ z#8Mx^{8sO|bMewj2fH3j2Ax{!PsH9^xb10lp4YX}PW6aQaO3T(1ETgM+0q1epFe(q z0-;my=?Vo4XgZey9~8~%hduO6-_cuC3J-{Esb$&PxRWEL&RPtN!k9!lza5 z8-i%4K&K%g{W6*m&$eoxxWT+XBIHLv1M(nFCnpmwk`9oeP$=Vz;~EL%r_Duk1*d6! zx$Spa3*zRa9G=^mr& z?`f#{fJIG;*h?`)N#Fk(EPp{(&koPBX2sdF7tKnP*(V#E$M7@k^bi$JzUxIzT1g^J z@H}mkXw2mJy;U^D!0FF%qg+Nq0sg7#&;3UC8|cPfXCqGw!mBEbys!9C-7U#BD>4?Kg^0bsK3)|7^3`AO;j2x zQaM@ce_2oChbz3Y?oo;~MSeyhqL(x;EA~7UKZil@Fivo`nD4_#Rw!*EUR~t2D&laz z1`GpO)A93^BUAexKdnJtd60d=dY;V4)niiwQh|_x zI$J1LPHJ2vCHTKWQ25`DsYaZ*w94YpdG;v2JTHGDF4tqnu@T-A#$u;3%oe`Ao%pgv zg0!Of66B6VVO+LkwW5|I=Qs~sU#lFU_5&%xyRNyiZUj~RF`0T*;>{^{*k{dbmH$@8 z{KAf$>?3;PBL`@w959*0Kz~f_QID$Tta%rd9TtJM)S*+?p{%}nB88kWC?P6-#x+&^ z&iPer4e*A*^KYf0CTZ^pS{j83i>T3U(`?QLvKqjs&3 z*9?}}CsYS)uP>}zRxxUl=gzR3^NP{zxSz}AR=G6e>UALe3pMOnbJw)(QZGImD}5_( z3Wu2yr~gotZTpth1vc<@QasHfeg2poQemwn*!T$W2em}L|GC9r6tF`O-!HNnn|LdM zUIjwDo)c<_y}G=&)CPWgwWK=i(Z8K0LvqdQnWB0$$m=?9xix-It6XFct1_^z17D-n z1H;|YjyF%v?M^`4?gC&87tCs9jEET*Tb;=0#d-4`Bm79@Ad>Lvmm<{LeA_OZtKDZJ z_sv7g5wGWVWvI=oC>QP%*UUre9X1L3(4cKUlr57ydz0{Q-P2;t+bjyz&1R>1ho)HO z!Y`%s>5|4#AYV^gpYpmHMh_0HlB(P%)84_?G4vkLi&$2Cj(b{+U=VU1qVbTqg6$Ag z5sX-pY4mYaA;PUx7%BloF5;RZIT&Y4&YQp8T)q4kvNSVk9SnE;c5Q~dfv+IJS7^Vk zk$ujERzGm1)|O4ll3AcTd(`&)IAblE_}D(_Htld_PWQwU9U){eyHlNOb#gpxEvJq= zP?$QxulGfJ(9L~Ko2q&S+MEg^WyDGBw9_fHx5Hgrq;|=tOdTY05jfo;+;d*u2rupg zYII&Xj8=Zh%Iwwck+jY#a+ehK>04x?sgDm`Wj#0QnrhOvTVsqf4sYH&qk4zk@tbv9 zYuk^3#~Ey?J)jg+hVHn&4c@K>CsB6JIqF=`bVltZpUKklNLci(M)|pnCZOdH%$`0N zU;gH3-p8o YS%t@7fK=Ayk)4B$~vC@p`%)uBkJ?M7R&J85sFOtkT*A-Oy+E5 zl*wEJZ9y5oUvXS_Ky%?#zL5JYrFz);&7V=?SC;Ma_2;y`5;j`6<}d1vN)(ZnIxlkZ34~Kb)v1b zH`V!wjK;=JXUajuDWUD)IrBmX486}zvYbwq<7uP6w#Q~VDte0pqI5y{wZ7tf4HIqlbSDH=1r3 z;YQR>u@L~M=u-+ox-gImBL*XYh6py;Ydh1J+>(1VL|-OwI3ZmWG{f2+__OOA`H%|h zdXK-O`!x)VSjKiZYfu@4xivy!x-(2En(=?4#3H9kI7!$FuH&3{e?`HtKSxY3h1INY znn7;G*J1rE=8g*(0Q2%ya?J&T4wKi7bb*_G?T%8?UrQW$RNSN=$%+_pfY zbHSp&x!-+DJ5|mZz(fN~2m!GXm(*Nz9mM@^ct3#05lpxk9k!LoMnYu3XoMUH=P9^F zN{XG>{|DO7blo5s*elLtowU2;9umBv zLK}_QjvhbWi=JdG?)fY}48Eg&kI$pPGwCcZ;r1Ob-Mu$r?&ko-OBQ8LtP|T=o>GYx z`EQxDos>^z%gMUprLW~@7vd*#pH|K3Q~n4B``djPSmOGJ<6E^Fwpgo1ip2KIzL5&3 zD*S9^(S1Fc_#-Pg=`qwDYmYtWbai8E+A)-Rf_0J-nSyw%#Xtu9_4yhpYj#P~wBEMf z$gaObdxQcKYh37-E#*@dcy@?BDk<7IPNt-PU+W+A-=i*9ydIHX@9})ncHp-x{ST?K z&Vc&`fBDe5d$SyYVGO;a{%VOXv->AMjqPBYG2^qeEna$K)l<06;Yd^kd@HvMo=Q(H zMSG}hVl0SnhahK#9*l|@{&*9(Cp#7ovxl~ybX=mWW8*EG{eBnnD04V@8fsKrsBhH- zUYIW$a~(|ib4-}5LSNv`+pEkIn{N=IBz2i3=Lj?Gq3nZP;33#G2dJmB3`gxO6I~n` zdt0W!GMdXly)VR*0vH2FgBj#ewpj!h*kdM*gJVlN`~HeH3&9LR zI(wamFx4jO%DL?~9UZm{(w%BBA)F4cneYDF`jGJgR^&Ct$Sb53hwt&>9_M-KT^E8O z{@sEu`QcQEMCvs?rtT0N{>!ufos_(%+oVQ0r_u0;>rJx=VSI>7zW`Py&MKIz^+@a{ z8_o@)RGUm}nFJdkOD0HJa3>ci12Va+!QjYd;R0KLF6if`2YX3O-A7t-ds=!>(Q)au z=+ZHnRej2ja>0mj6EuESzdRq0J>r@vmvhv!zS2U%BT$ya>&jnuyLg_0NQ5m2yumo3 z1w;4{Lf4r3;mF5o5e16Rqxnm4j@GoRyFLuMJWfqv7B8vZ9>H!`T2K7-O{`)$Szm@UD4iFY@;!xCJt8;yRITg;xCimPf1 zrN7JO616HVik@^@wOWkqP2V5Qt#RP=n&vM;o%}M}%;*uy#K#JFBS?!Ka`InfLCGXt ztWzdQCsdoBbM-6jk7UvZk_o$$>$oKwh9z4C8OOM%H25NuaaFGfVwqZU4o(>7bE;N{ zSBvWf!DK`e9~dN46sL8viW6>GobM`gc;{`l{TL=jy`{pFB8>@%Qq&FXtRpJgd$BVOlU-9fNvW50s;1?Omn# zcIjx&ivUt#Dz=i6p9VX2i0P=@js@ohuQFqx{ZldHNf=)%rq6fuaUcWHRDC%JL!Ugg zn3ijn*t`_Kygl%$279U(fpW1R8(>CLb1hViWB|ak57m}TY~IeA1TkwiYh1a^u5@=v85hY zCUwQuc<=i5Gj}%n?|qDHC0w>d)+`cg8no~twt)fWZxPskH2S|mcwX6Uz1h?(vbwScmK#f51Gi7xVgia*PT7n2Pv<^UQRiCvgm>vRf1`76A;I0%v{1Q9>5X= zG^)t06(0EbPWM+dBqonAZI*@Er?wfH8ABaobrc`VP4+1vas=n2rwlDfd5i$l!AkV| zel<$ab#9yk_isXs6Q521U6^H7FTi_47#q!4#hdt}<&-$@H^(14Jt_7IHjbYk15mSa ze-I2}?zaX#ol(aR{Divc`erNp1^>AZiR_3>%FPw^L;W!5FM`EO@w+&R0mZPmsw-L} zDjz|?&2L`TPhE%}Ol*W)pItINhXr}5uJ5rKM3R#TJNzwk0{$_8ruY)SjS2Ya09z&< zCYROK55SXVs1Ip`Kf?ZMG;BFK(;ms&&abWx@?MI#fMrJhOVjbRR-0`ivkEv2wt7 z1Dl)VF;HGaUfKtAsN9smwT$e)E&k7MQ^HlE2To$)Srp4`%kj4O5#2;7x+s_p0l&ol zEfsuTboDl;Pp)TlkoGIAuk^)Ll~maRnCWbq$d!)sr#m(yXRYmk^mj0N_u-lt$5qkbCGJ=yp3A9XRAT}##E5U%hf9C z@nC=}>dgIM>f&0e*FpG5#Gw|F$aRHtVIen04=L($aQn8YA~S}{-?`P;tP+RVmV9t14JYPRtG4_i#8vTj#36s$H@JwxvclM!TA}9A$Fk;u#Zor3e5jfy?q;6~*Dc;PW)3mRd3kh-pA@5@4xr|+5Oq8kZc2-wB@C)?G z+-BGOa2*&G29fINl4aXS)4{R5w%Rv@zfi3W65-ApH17j5DsrjU_(Ng#jWQb@AHaCyCmTMzf98l76cYEGhw zy7dp9Nk%l}Nv;YYijvYD!JXg)`WS21qXZ{0d?JtUA;lT#F^Am{mjAw?A1@X!nd|ev zl|5CZ?^x2?FdDI5F~{|+C))wk#z4n@6s}f?%UdFu{%IfA4?(*0==A6#ATNILo9A9< z`9CRvc(!~nvIJK#1W!DdovWL0Q?gN3DE|;OAp+2I*eSQ%+I?ri zB~x=WK|@l5k+II4daQb*;Xx#!H6uQq(@f&@?U$EBo?F^fi5I758^s$r3HJ!J*m{N7 zKma67|6C~iu`xSE&jjcI|Igjs6E7RB=c*}VM|jUU2?p6d4O73|V|os=8ehxgdn1m0 za+N(Pq^pL}VFA)nbB9qXWq^~#F8BsxVjA!VtsDU85U$kkVFr#bMD|`an$fMiv6cl+ zGZU2$xh3H%N|5pgsvx$2R*Phvkj{vtNw%fuEMrUoEeye8lM2_UkK2){NFD_5J$o<6)O3s8OK^&2d3QdGgL1bdcd$TT~ zFf_9GUsgkK?;g`X!B6Cf|C~Z?S((%Os|?mwe-BL(qUu;}gqLY=Jc>4kiQSh7WbGMy zS6O(ZLC}F1t0BGL{nzv%Q^s{0OU^@kt#4?KnYXn>#oH=>TnsW!2^73QMmyPIK~ZY^J^=rF z{-Ocq%za|sxK$B>7bsr|BmIZgkhX6zj#dolhy6a~4_ zl*BWkSz1N5+mIRZ+5%snH|4cacdX`74E(-+1?pl-oof=f3=39p-IGDBRV1t6WSumz zebU>ge9ay8rRtW0y1VYN+@Z_{&Sm2OC!9)1#$yeyivxl0 zoh^hBJT&7bV{DUzy}>c%#5)`!#QXC#c~Nga(g05c@jKMlZ9+rO1;Eds?x>|Q)0Jzh zgnuwz8BWNOZH6NVJ8mTVgGy!M%W5>(lIN^2oFBa;fRN!^vnD#aCX^wE9HhDq1xT%W zj|oc{$)QUu1W|;qrNjw9k=h#?5i{e?;oqM4F{uoHCvkv(2mdctAN23lQ0YE5>T4_~ z>i*RCcB7RkUTPqlJ#>pA;UEg6k>am(yb_-z2#Y*u3_J=vOT}dTE=-R1aA#HR)xB(k zr0EW;^EeSD`T=d!#!z9<0(aMQf50L>;&GK^YYEa@xJ2}NIm*kC2XU__SM~rkVQ}C` zX7e_S#Ee5=;3KiG4XQys`QOLGT*4;q+IMLJEVWV&t~`zB8!UuZ^ZyQC13|BX_;dR_ z?7Y}Dk2?$n2??_fKCB~YjO>C3WJ5WG#Z#617$^}n{~lHy?ZGxXO*_Ywpp07EpgbHI zVbM4Uv!@qZ5BM>cO?r&=q$hnGthr1O%BH`Qbt;dh%gKHD?`NSyNm{Tvqp;WP@8N??y-xYq^*5TT-xyCU@#TGxJZ^i1MWHfK&c-Iy zV<=a-BPx;Pp#|DqMxbU3!6`W^G$o!}04n(fKYfMFywY&WO0|>*o z8AS@ZBj|M<|Eo&AT4vvDA-_lYJ|xHpGWW6d=D(i$cQ6XQd=+W(d#;S?86e(+5!@N+ zV7?`IviDdKDzi0fR6@GSnsZM9ecz#{6^i%dFp@a&ctR`*(Rhz8GxPVE5Zx(7IS3%F z9=Ah03Vp1P4(JUxLJn_lNf{IxrU*aXs$<11P_T4-7$5T0G6_yhu7}ci zvkYZd-~>urJdgnvLUB$b;VhVp+}pB&!nssnihtVI#Ne%ppho}G`6*|GHhdtio&N-J z7aT4=LwvE>ygQ$Dj@#pb&X9d-39)n{(%O_}NLaDe&wAs`th*ryuKtQAG;Ke^(Ss80 z6>U{OGf)+&*mCa+rAs_QVdO4Cp^>#kcP#)6?QXhEf1x3KOd7!}iF&C=UcD80n4!e{ zpA`F`nd}TD19$<9?5KU2WUQ*3gWgt^)EkmuVRkUDCmKWRi+2a~&q zeGH3P=f#*hF#KbnaBOVMyanHb8+ZMFT>Gv?-LLhtc7p*>L)t%OxHOAGr3y_TdKRUc zw3_q~s~W>ZmlSZPLl@!>I1npUFTwtk62#WYDu*RE`LRhZ&fVTO7EeyC_LdaL3vWOxyN!9`ukXt$tfP+ClPDORc@%SC(P@_{3gP#5@3${?d0NFCU+) zY3TU%O0+wuZ9{8D?xr!c1#TR#H^MR_RSS$e-hwT@g+=Itr7(%VN1DzlMp3m%9J>q zBWBE4F{b!c$qKmFYcP~75-doTf|gs3>bi2{FRpWKw%9}a@eOyY+*|_r04B=u3JfvT z>e*qJuPufUj5+>cW*1Q_v}ORVJ|j)4`}L~wd|y5WQm1UvbaNy3uUu6J0#i$X(5jpFA&;glUHUyS5W0vQj z_vDRX-OhRhi1+`{bk%=Nzi$@?4C#iA?(Q1h5>gV<(hbtml1dJcPN^ZGgh)$`8Ym?t zos$${bmOzn_w{=IfcopY{pw1SI}y0=dL4#lEgJJT5a@ACxErq>VqO=2px z>Xc$JB5Z%#OuzyXr0?jNX0o?+t6pOk0Mk+uM2jH~e5m$8>R2u|PoBO80f#?~#cpCd zl2c}aB3!@xo3ryhytw__&1sp`okt7ZTr5jDQa0lfA_#f$e7+LwWf~BtD*!sw1XZbx zV6`LFF+I3LtTA9v-f=A6KsynyD6d;>x)D{%_Vvy7QlK54QZc47@z}()UV}q9npZ?mp3jqBxK7pr?vuL&599mx=k@l)S`AP9D6p`B^dw5egcTt= zsRm>t@ZYx4`3W~lq+O1JF`tL$&96hO<0oILQ~W&QNxDhyt^Y7^opUWsg|=~Gi`Kvn z+E^B*w>NlaO-Y(ehJDY5$**uF_ziJaYmF`}Y{-aM{RS&Xree6Hsp{8{e{O8xC0LP) z{{$68tth|#$1_H!(cKH8V9bx_aifQdmu?*mKikp#A?=8iHtJm#S2xe<@UZA$2x4QO zMcsYq80vBfeE(uFi3(re8s16zk0|)V;4A8DE7COfruUMGp;oq*7)?tmrPk#`?#jsL z-t0f6W|8*sGNp?dw%$S}0=TVJRwHLhLm6eX2)#k#L_a{nuG^XVuK&>S2E|%U^T)zw0t@1m95Vv!T?r0 z!Lq1YXd(Zu_UARXD?Nm0&PurlKeFURWGxoEzBnNRN(H^37U(fNqiKH7?UR42xNn|Q`=K2KKk|E}LL z7Y9eR(;7|wOWhSvlmm078G+emch=sn?=l)~I1d&qz!}UH8!#i>!BxlJ2EV6?SKs-r ze|i@<9=z7e)$YL3o+C94Ac(r*+^L{9q9ZI&b0b_>@`9t3l`ozzI9wFbV=~G%^=spL z=teBc)V)8+B@?{gV!gXri-;1#ng-*3Belsb_?f$%HGT%XgO<)@$ z)Qt#B*_`jVYaE`c(!kJyb6O=jg?)hWd;6riu-V|*rz&n?mn{D-3YwY}JmECN_oOZ% z%;ge{9*h;AF9cEl4dbZ&~A0{d$Oy|Na z2;NeH4&>C$pO7o&EX*#CI^ljTd0pY}P0zZyWU=C^VprYm)#XJMOIE(ywKR4%)&g(V zAYx1fUs*UhNWw{~RR6waJ$YP~sH*S(pj6^y1uKG7?Vegj0aV%$(B-Qt<^IQ{&)##3 z2I0gfq2Q8NwYvj%uwRXy9~9V;OajO)ko5fEzZh&&2|=5d5wGaJjxFcGMu#_5gF_H& z=b*!Vd2QKq;nT*?&{QdS{8yQtAm&i3^){0_F+d5mmD`pWTGqMW_Y>I@+~Pdu{;`|& zSK*Ww${}&yp(r7?yac1wVk6|~ZB5M1l1Ic6NLoK9b0c(t8RPq(@^bBHFExl)`8)$) zwPWuq`Ad^BkH?n*-RHmq-t#!J(dtdsiD4uZKr z5e}c&5{&iXN@TI=$5=ymGY5+sw;#KbO3Az8Sm>us;|sr2Gj}Aab9qghHI9h6<$rMd z=Sfr`a-m~(Iiy4CVOy4hS zFkT%3Q(c5~KS!hGiQ>InA3z&YH*adF6rDdL(BK7N3Tge0K5$7suBs*jNZd%5;tQ~DP$L}zqRu?(uP&1}-(JL%JYc)H;<2di>j_15|TMC?Ge>oQagigvQbgBm9FYvowv66heE@trA!en`$+G~(|i4gf(9`p zJv5oryDzK_H_GM*I=C)v`@R&EsaLh28o9<}T;}iqhk@vD!~BLEM0TSS$F%Cr8wPL( zaijhL=+oLMu5%BCdn7(=IL)usn#bc6Hy;ngSy10IcXs$?0bL;YXXR# zf!$ZJC3Fg@5(mE@Hg&0I68zTfuZnr93;w}3x;TEFtBJ&5K40oN$;bG3%+0*Sn^}{J z1FQlU36}7c6kHB8QC~}c!I=U-E$O>2Si5(q+3EX{P*>4YuoQ;L!6++u3qnn+ zW4dLdErq=f_MIP4;XCb0cM`8{U-+7aUJkb!C?n^)t(BR6Dw zbcV8e-Gm<#4gw9==5z*Jm$fTI`VaYi?4d=JP~>mv+779%9_T{cl#_ZIYvcWdO;gYee~_mK!t&ALyU^*}(1V|j+l*pDFtb4NxWsBJWu>xZs@bLHzjTt*5x zcT_c0Lsu>boE8{(wy^dak*R!21-FlV=WP5x=F=^zfuZ)IvLadE=rZ6K)x_O)=tAJ91B+ZVt_zko@@kPxSGCt?%U!^bL^m;9ASJh>A zF`@|P43kKo6%itxX_BF%^xG0^59^>%m~<74K`}DIV)nx&LMLzt|DC|DpL)$8U7{5` zQuo@d0(wo-mj<}!&T2nX@_^#*P6wxj(kjv*%(z61huaG$TK0^N!=vrX*fMXoZyGTekre3WYz@s40HZkm zoLh_aq>q1$klFSgrb82EJuTS`&i9W$-d)c9H)i{CSF)l>=S*PaPa5fy?XehH$}k#= zm~fjnpC?k&!^VRj`WDQr>9l2<5v5)3=?^=`4Wnhj`SGzpMzQOwH*wVTQD)!tB4d5G zKRpdRh_=|tAb#n9s^LHV^k>~I?dWPdgv^&nm@naqK1QZ1{6FdP66iV#9LebmLd}70 z;)Qx6)PDc&!9&ku}UNBJcaZShQnh`RkZH(=!8C)_4@V9BuB!iRdJ=R6v!{ zYi$Xu!zP31u%yb-HS43rT;~OJElig1VL+J%!xp&E3g_8q*DvyB4mY$CL!p8hXzjG~ z22n6Y9}G?sb?gFG%+uo}bzYT{Its5az*6oWcJ8 zIQtNQW}0U!y{F`1UXgV(#zR|kKME|RN1@65es=B{GSoCDt7+2LvdQDa+wDuqr z3&pcRpGc=or4ar=b-86+J6Z;kH6%X=K+ni%Fm|^lCmEbq1blP*^m(Nf1qvKI3O${= z#_12&I8SP&-!`^5lf}MM?h~t=b-fbxtBqKt&F!24!}DrCTxg0{6L1c*0{~uX!-8A8Vo_Q^9Moa-{}+^)A|AU z@GMe0YDd(K4%7PW-j~X$_Q2fmk|IURqHjp`U`#f`TVpKuSYCRjjALUk_6@9ka@8Qj@6Nl<( z%c{K?<%L6|z6D++UM!cx@0vC1;=BoeD9bQU-+P2FG)|Q{8rvVoUCo?qZzy<;Ri8kT z;yOD~*PzRozKTw$rHW+svWMKB1OQu#t9B#6(7!1yu{{^x?%GzuB>#^ETtRegz^gM! ztMYu425aDn?9nY7A+af(j0uPb7QaY(Tcjg|-3G1w#3U5=sTh2!rYDJX>@!b5`jTC0 zb26qOkZP>}OW{`g=C|04kSThxNP#KW^k3(TGEXh=1UDqTl?3Wne>uL7QOl&~i~?U6 zmuP$}n2(m1t0E3=M?F*0@o|f{PL2RmjSZJMt4SN!g|UR=2L334FbA63#(!)yfksWa z5}S-ffnzG!Tk{gp0f--$xUFjS+4Ifv8dFBjKtdzIi6c!SKVSSB#-)|8xBhd>Ze2|5!?#__ZBXa|$*K1VjYld5>pa95#9VR4KKuk^7?YW2lP$)v1GM>=%l;#V)JiQky?z)Q;a#v1 zLC1T0@`{P_kupZQFFi&qrcqG6HI=o1?xnCPTaMUN?m$@7KW9{|-0lNgqE+t7r+LfY zOwq|AJFA^P`qD~u{X(1(Vo*cXN}QjmPntJ|>bP~aA1EVj@J%N2(EY&~W<#9D z^7FI1(e?hd+?8FTtnks;Mll`rBI2Q2A&g?wd!{jD;&?M|fNLx6sZA@n&C%ocgl1nb=>(~l$K#|nW?X#em;9O0Z3LoZAbT`83?VG&N^2zWt z8|KAnVo9X`YWhG4Us}NlULrWbNVuMEf7z#0Pw3|dH8nAxz1_70ACHD)QTt)d{+Xq4 zYHN?{SFvnPwPM%eU+OLkq|7iTw7ur>Savh8-*-~>Hps>L#`pc5Y7e>nvOxi>%;5*e-ce4BBS}v>0(i#$sZU|8WKNW_G@E za1?92fd{X2-f;C=!&R2XJG+o7U(5jy%uBQ<%y26fN5l=>qFWlf#{=~b4LSY$*0A1Y z|E~WRL9jqNpX0rtpl}H09=x5WP<7Z?yj19AgW}WLYB9Y9ITT5rNne?8yg^Np(F1W+}kYZ;I61hTDe7=ofC?q&HV2mSpmxifA$`daF;oih)B7s9X!A{kKWA!HmDsz|W&lyOHqth~Rqcq~yk=|w_m9c&Fev1|iF!%?Me(q*Q1AjBa z030V5d6lN@)2GZalIi(9v|jw0>r7;U3B5OEvpl1b(=hKgZ}VdSsSvRic1HnjXw<}- zD{@$b>epI0MjCa!){1{z*vLHWBSo84Ow%u2p6h%=<30xs$d3gplNfP4z2y84dy!Hic-_n$r0P!5XcuH+l1s+P~M=@zT zM<&omI(LesCn-9Rzjnq3UpVCbi1Loq!=%1gi?x60SiC&Cy&I@nK)0>dYA1(@w$FEs z!u<-p<3*%?FR1#jy=ad@X`-j6ZI!#Vp78ZY=zj#^v&4`P(NB!_7V>@*H6$nE5d zH52wWN2$D$=r(XF?-g$)$46(f1=!id0vmk&R8 zqlK~Tqsg4lt?q;SN98577at1ovA!nQR838%F>e9gGRVfqLv+0k&Ex0eFXs|wiPYY7 z^6lS=t=vQ4%wv(c%BJGq1g5d%1Ymq{;zV=jBGMr|?45ihPD$48r=y%;;n*YBtXLv| z63Z7c+6NYm*H{6Vgb-S*rLqRhY&1y{bY({u?Vd_yYg4uer4TpkiWDkaY`T1HY4p2B zhtha9aRthsYxp5q*=TWdVZ=6~Seo7P?Rh;QkLZPuafq zFA+=n^a*C>Jd?)fb-X0`?MO(%X+%qpqkZEH^kutrz=y>Rif^EjW>J~*a7a^|?-iWN zzi711-zIQ1Ao0I7IH|OT0^gd%WK(PB-lBuow2Y?p^JAgGg{--SCyX0U+zAP_{crk; zi))7D#6VnXQfvt`6ol0yTshG;nNiv#%S4t$nC;u%{rJwjxFkvgK%?!j3 zTUu6+D^s?7oeI5)n;W_;l05^BDUXcT77{wM>|k)*ylIIkbf-zXVmxEawP9sszHpnL zKSTA5eU6{U(HL!;Rnfp{ip#4s*<}p__@}w4NZUU;ndyamJqSh59%0;PWE7E4{^fQ< z(i;BMPCWGfS=Bgmbt%>mRZ-!rREpM4*d}Z~x4vrahD)^ix-B&~znk{+UJj`E*!>D@ zVUeJMPtWuy`O5PB?9zpduyav@FRM>^ z7v#@tU;`VNh=X|@28WTSS!@_kq#16dFHZlfU99l8cYO6E{JFi^)<0*&?xpzfH@~JO zy4yxSqQ4>oo_Ug^PYjy39#jQ@95KBJ&8CnBtxV-Qj?7mC3Y8#miI}LQx7zIY3v7w^ zJwY;dzjqLl(lt&RUg9bTFGcgn%)<0VMBjq0yqe({h*6PK{;fp}A^R*N`B>X5U#vpA zkXI}O>NcP5b`$&v-;#6LJn*E5 zph)Gn)97{apa8j0S~Q@lmuZGXJeuW)%8rA_u}Mm+|Fouetgql24J}Ig=x=+^0P67p z29l?aeX6Ka3m^eZ3Q+3!56L*;N=|>Gb&nG(h^=Ou=7w3P$IU95xS)L#bfL}pQUK&i zK(8!z3GB@pG&fq12YekO-`I{TF80v#^FzByW!pi~pSB8^T@eD<`xrO2msoCJo~+bi zSZT$Z&POW1m21Z_GQ-SCVEyOf&i_*ydz}&djzv4T;pMCB$C`;!gW^%~7q50*Np=W_ zGhh5oSYvW094&jqf)hj=D_;CPQq77LVFuCeV?DEASAM72@CotouJ8HC{-;@1^aj7B z^2~?Md_AiO*ukxbbPWEmDdr&o+lNfh2g`M$9&@q?;@IX2*qy0ZGV9X3j5aKQUAvQIpK6H!SpWJw9vkf zJwy$-TsuaQ%*hzWWa??Mzt5rv+2!lPi+m$rJkU+Jg115i?G$bI@6iF+BsT_j)1FzZ z!A3YhiVi*~O?f%Lzf+1Et){UGks>=>=s4_oq5>J&!>X#=l^^5oB&t@f^}`maX>LsK z&6oyXYpi|$ki5HkIP|ITwH%e#6ZK?pZupJLo!!Yl6Yrn+(AOVEpES(gdtRu^^CSP5 z3N$HN?Y%aK4&@!2`NLA#k?BuLy4>^MM3l|Dh+LK|@Qqv@q};Nj8Yi6SAD_M9j-tV8 z>v@+OrMP$aMTr0WmLKt1*2H^SpQVRxzI1fE3VOs$6Y_YUhcgv95-v! zGq1gXF{6EY8LlRxm0iDk z_IaYvE4EW}qUob(+xYxR#}@v(s`Y+cLWNie%Y%VFiH(_N`=-5)qM`5kU(jxz6q8gk z&k7n^tSbnY?ZvxiL6s)1iz7d(JeQhaX!q$7L@di{dBLA%T9e~@!s2%8LrL_zGKQC% zsE~bpbLCOx<`Ho!YX-K_Q&A8yy{eiZPnbKEoCmAs`=_^5uA;t#2p0He!ax))>lE}A zz8sr3VxhP%6{IxPx4C2c-jLjodOSryi_*Nku}$Y&s{@RQrXnD7a3-c~W8-@S)b97c zNn37Q0@ecIY~fKn{8?5}H3oI(pX@N;6tAoJlw@A@iZ#iM?xU9mn}C*7!4}|2aiX(BK1>-C2BW?V06n!p z^lR4mN{87oV^Uym8#*}V6x)6b&ra+NZ!)xHP;ETg&FVCi6E{jR^`umkG0y`d_|pR# zHS4t6>AI10%HubwHTv~6%b~Vk3;vzF%6tPlJGK^+{I(eTNUUA4KaJb>%9wfhO=7u; zJu#a=gr1#ofL|}blGIXkVR~*r^-R8%=WV84p777Xf5IodV`WpO!*GfGWHnBzdkvU? zc1nAUi4%XLrbhxjdCJEGG}N=4@mAu(II+kvAt7U<2d)L(NrPqFsqk{{JX2F_eCv4| zDZm=732-b_{KL1yn(Ifbx^w6MWJ*ZdEDj!(Xh%U+S^|I0LW@TnR|g{8MLZ{6ZQq=D zyY<`QlG|k||>(LWmCjzN!Vq!9FH=y+2+!y+--zn`Vk)aAIeMU5K*woVtch8*o z@#s@TiJw8jBL#F>ds+OiH3o-rKQ`B=+%*@go8tvDsTEJ;zPHs8VMs1gG2R18xSgqw zVYp|IiaFSiY%&IAm(Jhc(!+<(N`J2S?z9&)f+t*mdA}xmh6&3z% z;UC2R5K`7T5ov7WOB!O-&^TddysT9hSjZM$XS`!`|(qVBjiE`1|L`$>6RNxs}1We2?*$GPmB z$15}6DmB)iPc|r!LjWMoKJriEeT@rEj0=DNC3@>HJ}#r?6!FX_8a(PN{HmmnA*Qg3 zEyk)z>z|msiTAK%in4x`M|L->>e?)v9S6!%u15rd~A?4 zQDM>a`!x42Ua#dt<9u?z+u|~Y2OS#MlU5Z`$>broV&}j@2H>x=2PFr*I!AuX++Ib<&(m0y7oS`gv`%_2kYc<96?+?^+;noYQL=t29i7 z?dc_%b(`X>&hTU;w~xgq*oP!U*E0_Fc2ir84@Mv^%z-IqT*k$wM9QyhG`b)CMEq#J7cez*p`k&>E6lxeA$@|4m z-(h4Q;}W5|%Q>RODIp>Pk)zL=e+=DLkAH9`ukOxw< zWJa|yaLaXbk5=b()hCu<4xNcZ6qTP<6d1;MyXe3!U4)~&J!tU6iP5~;CTSUC$Z9hL z(;wXj^ZGT253eGsZ-zJ9$!6Us&vxxGAeIxp38#k8LD5}G0REMO7 zd6P2D_jbgF@Amzn%Blyt2EWpl#RaD1X){&Mx`>^2sy2S|-%T$r1SGtGHxd>nBU(Eo zajnDJ+_y%HSV9_Lefpcv({iz|@_iv_#R_9eG%#_gwq1_`EuXR1qAYWy2eIYjSioF` zVZTbLa6Q}dC)LGAqo*(4+n!8$bUKH<*rkq=hKI6iHNL5J(5F?HFL$g5`+jNsx$sY@ z!Go(o8-TMB%=BxN{tKiQP%9KS_8f35ov`SEB|+KZrnpP5=T0&4fZlWM)5X6X^UsWc zdJPhg1!6C-G|GdPVZn`+z#mkpqP{WUs*$p^Dlz=(b>3s;&W62*F;PZF8(fRmO{pa5 z+euwC*FwQWexEl?HtL^mF|u|yVUD%JaokcjC$`SSu$?D?wqF+3ss4qsKAVifb{Q^# z7`WBzp&e%EMBY(7S~2%kiAg_a5EG>s@la)X6LDCyVfAiueH-Icx|qIK{m1D#1NITd zwNI=b?dzg9{X(|gC)KdXz1gP zPY9jQzD&DPQ+ps+vE{+DpSZ)IBBWeATV&eucSjWUcp$H>Jn-#v+{fX(W zG_Hxp!3yK%w=VkC!|A8#0r{mb$Ow8KHJhvM%sptEQlmQZLxgNeBGUGs8uLTX^^U$e zY9@$8b(xOwN1H#;{sn3l0HVB}+S7iX{oG&XSmat$RqdB-Hd z(ONEJ-5gyD*Pj|Sc*-LwRW7S9*bXPwp8p$4Tx(4 zL5bPGafA^#vd1><5{((1@9ON#sp~M__^LVA1#11>(!=5V@Pc7Q zW^ut5|LpC_22#}i52#KrJuKlD^BT{wgB%!5tvf|##dfrN`W@PTxhQm_^#57_JN$$oQ<5~H=A7#n6d840i4;vE zA;4X&qG4{2DyDYa_ED&;1LCFsM+Zyj)b$=GgB-t%PgB9wmQJ*+@Glp{Yl1pU8>p#Q z?OMe$*?&WE+KXPBS6vPh0ij&hVpej;J5m`FNE>YZ!J?}am;AcLQk(ZDEfd6rI%$pT z!|2hP#MVc0Y=Fi=#M-Sf6xM^^)h*(8@L29`34LI@BtGrdf-r~L>_cWH=mO%POz+_4 za}(6)gY_q?!8_rG*pU(p(rgCJ@!+4ol?X`s&T}L`1_3c{=!Szg|yOjEl@BR#nWZ}_n)}>V;~Ez70$gZ zXjnr^K4AviWh+JwMDULh^RU|j|L=?4@nv7BRoN&9E#`kWo~Jq~$lh4U#|LcWyln2` z)sA0&vdCTIf1tu>eolcg;aZF;MajE-3`5v>eb&)qb#v2=bw_IhtS&&3xF zRAFG!4@k8g+N+4NN4=QZ5TCaln>VaoLI**G>!IvPdsR1hl#SdYyu{+Y+SIGH#~;QM zXrY(qONKb^Zd&D)fl%7;uOXcMzgetw76i_A9s%U+AUKHDE$S^JI0wDk>^`=aEQp{J zr+KX&BIfvAEo;hE+Mrw+9IeT4bZP!f<%qV!wTzKwlj_gv*lcP3$sffiQ2*v;EU5qK zL>#w9Iu2W|f#{dLpOpp8LLMmf8DOa|{-*1u**ej=-Fbd8N8qz_DjyU(?LN<-CGs8l z#l`vGSE>sKDHixvxJ8^NGo}J3!!Sqr4cijl(RXzs`O}A1G>XbBNoD z&WyxX-(8;tVE76l1f0V=Tl?P(aL|^!K5fRPxooy5eL;-pojpZf`qHO5F%}26;)-@! zLh?l9(m&9Y^rfgZTBopWU&5%CYxQK7ZBHxamXRPpE5I^w?Mw37o9ODgmko%##^$a5 zj~`j+Fwgm^@XE=}c^wi%*i0`b)#k%FUTM$}GyP54&&CF71Po#0bN!@ZeW~j7jW)U~ z?y_Iae(Y?3jv>vCzt-OH{aAgGMnlI)=w)E{KO8641 z?#Q!P01|yqEnn$`LxE8YTIc2%&4J|xrJdv$T(L*b^m4QJc!{PYO5zk7-sS-?B4l9w zQLBacE@T)z&Y22qz9Hgk7uimiv2WHtNfUoJc~gi~c?YrWV)Tte3ppGj@fM=nm!X}o zcFX9_-mhb=6GNY@TFu8}W4nBdw3eiUk?u?=VH_zfPaZ;_9s8G@NhDr|Ms?RO!ui)6 z5KKWqGtz|}z7p_c0IMNUu|%p8y{<&~xH4kESq*A|P)UrB+KqD2?V?Pf5p{4mcYz18 zc1xe*`eV*L>3T5>bme%?HJM%@@LWSLrQ^DGqLdOVMQg=SMLb{no=x845BtIRB#ajP zabv3^gZW8+QJ>7Ef*+L+V|pPKw+}Bni=|2gVWENYtVXp2j0{GGD|%kIz!SU%t&0B2 zip2uMcyj3=m^1p+hG!Z}{0I8#=6PU0A5_8fb_{&}?5S;Eb=$}nFbB>v@sC0An+3EujH8Y;3UnJi3%zym{tFD)J|D|SOJ~)nxFG(Xo*ueWlWh)0$B0z(xbvZ;D*kbomm#UPH&kjqO|Z91l_Ofgoxgk9#Ze?kM0eWByVF!`!-gp3aP*S zU=lvjfD<`6thx>QuJQP5SjCB%1Qs*?_zdxdD1H9N`m%!3zZON8fv|249`f+(=Qg4l3y(YQ7qqSd+q3F4(GYc-gf>vtm~Mt>N24iAh3B(*`_HA6(7+Vh z464`fRHURS5+?QVm76}&s*;OV$!Hm!yR7yl49tA{4Q~>Cv>{bY-FhSqmchqysPZd! z-xr+tcY|@vg{W@Pw1RzPd7yAZOi&EyharlfE8h7$>jMt3Nrs# zM8qYAHf);*qjx?%>8r!ET;kDb*`21Zru|s|WTJX*&0a*Mq0v{Dt1sPu7fC0@UOe#m z1@1l#6oMb5d;_&dd^*l5!ze*NBM&#mC561dJb%tRhGPV4sTMtdvoiDejqsYnO75<4 zg1EDccEt)#af+=(@2$kjp}7@+aR*cRvj1zbQk4Esi!>UGG~SjzZv(JQ$S8{JkwXr% ze0>A?5&=+13ju1jx>HQzUXNunTt;37M(RWUo4-8xWQ8N@M0N}M;EB>j4i0u}!&_G= zIPoEq8agx}1tO_kN8379bUt^9V==CcgZ(bZHW;&_0r05j_(M3;EDWYs4N~+#+(ko> zyEp265IzpC>jRw2)3xy90Eao?LnS!Ukwb59O?i?qYBk=D{`=8gP=X_HL@M}eO2K<* zG^ajxaD8f`?Ih1XY11z&8=8ZGwtVUg5r-tsL0?9Wwx+e9sHFSqn*LGbZikWg_#J64 zaTh^}!(*q^h+;4K+Y=ATJuFd~Gnpl4S^bxddW+F1%{d;fBEZ@(U>w1$`v34|~ zzt$>RLDC{gGa?iDr9$?FeOOb$!f-5+Q}iB#CAGzMM<{F!JDd)wC?oV+HFK2&pR5F& z%bc_MK4X|_g}tmT{&*Y_>{Y)t06F-;g1Uk?az1|T%vJnsz5ask+#EVe@%%F8vyA7N z<9bUd3@!0ynlghgw}a$9rRE$I*OJ+84o)JH64Bj7#~ZItf6clLB3Vuv@ya^XaUksv zpAjQWI&J!{7wQih+kZGHP6vad-RTX!Q@RX1o^0$-O*Aw%lL#pebQ*YFs+ZX z)-Z3rF%V4nooMWBY$>ak84Y?J2*Dljxi7?ot#ol;oj7Y-U4J~m%D(ev1)5KH1TIEq zPk%iyBJ%upwkIF_P+^Jq(lOEw5<0?;qXY}@u?Q#ZiQ#6DuzXXsH5CNn1>}Q_5lU_} z^4TLlb&B1F?ltT*GfVNSkSgcst=(5Y8Q$1PZccizZMTt=SZuJw-tkc}9v<&*hV)i) zSav6_10M<7E34vd3OJhKT*H<1dDY&9v;P^|m1D>~YbvH10%L@zL)Kx!s+u3>S)zFd4!e`K>_lM= zq}-+bEz_C}cZN)t{^8u)(yBE!>|4UM5o(M8>2gVYZB&;D+RB8`YVvyORUU|^x`#+PGeq2d9-Tj5ZOpv9^##u@>0_sG5Z1!nV0}lPW%s@MT(;QKDgNJVa_!n5*NkSLR#T3< zbDo2q{AC<~mnK>v$UBrbNb$0)QtLN|h92)0Q_ztEOVKZY0_pLElrF#C3FYq^l$_=LXDa2}>H z5m558p@ILOhH2rHY4fy-kMT~ITPj{i&p|Zn)@Elh;>H3SQcF(cz_uV2P(nw1(hsi3 zT^*(LK+M-D}L>kgk)~L7&7fGy`&>j6VYO=O8Wr(Ox-z>{Q1LN$Fx= zp%kn|2~u6(Y*@yL&NaK(Pr|8#IcYklrC=hjR0)2%tHZD60y^SIbc=38h@) z1H>E1y$i)5gTkDjIoV1nFOnU@P)D^~jmi9fu>X-Yl zDm!=%?*g=v*#06~zyNCb@g&`#&Co5pIUvE-1bmSum;BtwQ#V#-E;T{8X**A&F^ZH zQ_XVDve9$FupePHL_Lxw=7lOIF_LRv;BJNtDnvJJcN{X4Ce(z?mW|B$`%&34gGL$nV+3@04))S$!!Sz(g!2*;0-_=hwha08L#74h^!QR*tBEGB$7U(-- zRuCeXC!y-Z3dwQyn56)g#ezBXcZ<6VG0)8;YVBr<{O}XdkPg;2SX4m=Y^fX!Jt6N@ z`Lw_z^F@xpIBO>A>X;$g7kjO6HAYd)Mo(sO%j>=Xy4F&W zdQk()wN-ZB|D~T#%yJ^c2J!BUWW!gIvYN*FRzga-epgo>uD1xC6(b$y+5+1DQylAM z+wHsUM|x9u;@Kwy{$nyz;zI-iYR#&aDg#sTe2TW|U7{)2_26m$PM`p%_-HO+MpZe% z;4$d1{e*-2#!1H!hc%jIUlcypePeb!+yIjmt{?wlb@oyF)t!~#zd3RWB}e_C;bRgk z%dz&M!8#jjL~NLU3Z?pn2@%m-rh@ij_${B%@8bE4&1rib(u{{wqUPM#Lg5-UZOS@e zN`g88f1(1=Q#{_OtwLl|IcC7H`}2@mW~tYwaFa*=eLaaa#tfimO2-ddc%3kd%WSJUKb{HO5F#KdGRiqrLbrv5A~ z+RglhEgjp>0pBb^lhN$`7^y<)yEVNxX^d@ z&G!4R@Z@m=amF{e-ue2zI|oF!9ME2zqmd1o-dVfl9goH2MxRFa*tOIXt=Qz~;V7Zs zukVqc!GYa@-New>0o-2!Cz4Ps%=iNA;&fjPPDviWtMm)GYYTp8L_j7n+BRO~RGpy6 z&ZlyaCpdGGdF}p2l~r+KDD8kvvAEi&aYvm2ET&+$mFq)xT;)P1cVUs}zSl0#4HZGSi>12^e5kL=7 zm%Ie1Bpw2Lg=H-&B~2@|>-6h!h9hu5rzfl;zuRKPOlP|D=b>4~0s&3^E8Jo_MT3$) zNxri|R-b^|##figkl=9TgPSKcTW+xT98p?2im1ufhXxu33+|hBRSE31%y} zBE~#YEfUn#P*`5mrGse}?tvJ{JR&z|-h9Ik>`j`0oonA31{ zj7;Fs@k-(>6&%Dm4Zl)O6!?gL^;?2o@I;TGYZPtStby?mV+mM!+rIyU_^8lr?aQUt zT$au6*N$B*u|`zVCWt8@*AL8yr)Q7v?`8Iel&?3Q2jh-(n7MpqJ5(wxPwa?VT6i+% zitXvJvm3@jTN`JaopU-J@Kh$VFFy-Ai=scqQ%$WS>wBLo#Xtx^R<(lvOTYx=yQ_q+ zun+gvb5Fwen;eGzgs7~OT|rOkjD3bv^G1I~ST}#HEm$-uU?hw*s*zX+_#K8%VQ6L;&Q+vy&*$Al{TV)wyxb z+VynuFZGjW)!s-6)qcLq?s&T6v2ODYqoEZ8m`6aIeBU^DuKcx$i8!vhVqF7c8yLc_ zoF!Mnm}3;N1)V^P^OOeH!j^_OyOj1h){l_pd;hJC0R9K5&9= zR_y_?3kpg~W7TTug_+L0eUk&U${#wIJ(cX4+pqa}S=NXgiC4*RpeqT#vxMEpCjZiQ zgc$JT)AHo={mo>iA`_6hwkAs-YL*5;Ik`-453pf1ivQVM#mlECW^ecwzkx*W-Os^bba zp*w)D+2{!QQqJoKVXUPLt*1sTp+l|)^f-xyu|ot4!G&sceY)hH&hwTm_zWt9&;)CS z7)Z5aYusM04NbS!mvsk0*T2N-(DKi>RC|JhWgG^HKP!r~qf2ln0L6euj^ywgZJI@g z8S^O;@9DzWYvfDa`>WdsK_V37^kEJ|F8W#?puzem`d5Qyn2uEx1UPQ@%YT)>*JDk3^r_8VE8e5p!^7p}-jUKLAxhs=kBKW)@CH6Ni@--675-}wJ@nC3dK1kUO^6o!-riXC9XlxuYD8Nw z&WYlS82_Q$tG@u=4G(j}S1+|^=X$+o8dat$e+oQf#${J7v+pF(`R#Z<nKwiy68WdB-OI~%ITC9$%f%gIbyR*ao zVsF2z+AvdaY$lFW-~>6m`%p6uhSZx14#@YqQ7@v$%*P}|a*T4C%O#5XEKrXdtk>ga zWOb-mXK4H{R{Uo!*Tw7375QA+aHu_-6(guTi`PgN*d!u>%y)32q zhy;7~#rdcR@m374g{L_U;bsuv=S%_2j_KIt>1P zkll}I^+0o;I^B=_N3l}e%wI4A2-M7MRa2f2nI}aDbS~!fh?m> zqC10rG6og`5dBJuwd>UwOZ>Ks-!-^DH!l0iGW)@7E+ZL#zEQ@TL*&hZw_+TR=NS)5 z+-8B>6uIN7<@WFde?Os-&v+A`YJ*lLf$LHY+J+X1_F%N8+_GM7JU(&H#1vs}HdDc< z1RvYv(eoundJKT-Iei<=7c&au6v#}e_hROuqLV?z&}7tPW#3}752kETPDUz2^6`EJ z2U+hjqa3}Dpn&drJ`WW2fV5s?#v+sU6!@|SOGZr$91(L4wv0oRb969{kT}YWBdcmA zgT$1&HTg}}xyz1Ne~ zFdqiKIBZ-wTRnuAZC11TsTr)H*)nS45KW~LwMqu%X->6{;I9d!-9qFr0tYE_fEh~> ztyrq_8?_^2_%s+wze|SA;1Vhf%m>q4>!7?Aw+lBMEI{$Q6fhG*W`rop!LRv2xgnnr zL2jlLaDyH1ixU+=orw}q&%}^$nEpI*b&LYTeNQwQG^Oin5O_(j)r@B+y0)vX>pk`f zP1GYao1pFaij^C5YzfYmaW-(a+|>GDeE&UWaF6_Fi@`me9kyeER~blJI5>{T@xXDw zab_GRaU5_YqxJM|gU4h%rpRL$j|by1Re0>EyVyG4bNH9vsJelS3sb+<&j3wDzg3O# z|GgSaedaPgxJgYlk+aM=U#`i18{QAlkN6=8B8#|nZ_m{aZc&u>#*a|!wj7MZV2<)i1Aysc}q-QR*wX1H{ z@ge7eC@wVzX4U}r0yiu2-OSh?;aIB8PsQ<7^Vh|;JUdYy8wYu0Dx=zQ#%UkGjTxSl z@y$iB_x=}!;T3z}9Fz{?2h;7rsp4+D9S4QK3)ckQ z9MIXpn-=e_i!nZC4EbKQQD++bQ1Hg9I_yVty@GQYYc}ei1c&jz_&@*vAOJ~3K~!~i z*o6zdE{pN%jD zE9Z0B$@OX-UcmZLXNPT^&*d-1!o|vO>2*Q;s)@C@fao7;az6W7aGYAXLC2N?D{}Z* zi=3Gnn7qZuC?g&P?!$Q0A`i=WBu1Y2%0>3lLa+OLMgg=M=U8|iqv9QJNDgcX@IZ__ z*xSpNYk$smt-VP{S1SB3GgbkQ3jVyehieuGrh6YN)~U9og*O?z%Zzu*Czu;?D9d+) z@qNMfJ1^vc`5FX$c$1E@$p22q`4PkwogMt^{yYdPM6N-cmYm{G!y$-;z-j<^81b+I z4+VJ0jEB3rc=+0%vt5&a^Zpwj+@z*b&bh(eE#I07lLrDrawy&H!MG!bAADt*ZJn*< zCb8~kQv=NB>gxEDzkj#&&DQrX#=^yAo7Fr#$hoQU_$~PT=s*C$%Ld;7zLyzyed$6T z-j{pAign7`nmH^Q#}YUOaf}&9Cqct8W*l2J$sf(wrpS{ro+iOugLvAEr)uhWYVjN# z7m}^s#IFH=fpKqcd}t;hk=crsn^j-h#Tykk7dXd^bL5cP5)Os9x0q0s*mCp_cyxTD z+{(?WZ|J9?Uo@5)s0(G93DiW<3S_}(k0KNhEjh%Z25+9Ji=we;YR3gxwMjgZ;mw~R zy%uos=|(Ru=Ih2qWL>zxuO~IL_E}^&x-g@RH-VS%rj=mEaExRGhRrBRRLq-oa*0|p zqC~wx9WenRM;r4S1kJc`q!5SJ3+l{hoHe1X8|Rd9(Wrxx#9$Jh_8ANi7)ZZ&s}M26 zj!bj`-IY3aMA%+8%#NKsyf_~@5vMjOzaU<=JS+^E_7dmE=%t-h+CZd?G>mjwL1W^@_!Md&r? zLv#n|i5Y#0^iiVMDs=Vq&^MJpYVCS8R_bV1h4xZLdlE*qBY!mq*|l3>38G!lZhlP` zKNCS0hGq1c3!y7XZEohUh9)`Oy0{L8aU+SX5>Eur2Y(WcXQ|=2SE}f8B=^}0ObkBQ6tFA^Xi)P z6RP!M3m6XJaG;dTP!ur%YGM+#IsYjV%#!d_n7}Md3Dn7fA@dr{E_t3jY{n6Y3~>*Z zj9GjvFeDfzFi0dbqoN8GGV0}dOp)IsXfhX)2YEhM3$&R7>T`3UcP69O9569$IMyUl zz)hSNo^q?SZ}#ahCP+`NWN0L?VB|7}aRZ|~!8l|_Iht4VO_a@nFTw#TC7DBxEP-N7 z)GAWKkc=90As{m9W&s8hDb8b2DFlz>05mg=3Z9$7D7a_{A8W}R1hfk`Xd1#nIRh~= zM4;c~aC}6)xk=j_1zi$96g(QB4x>eIkck5@mKYqYvFFDSVjJFk{)}+b1(bl`H9S{p zXX{MCmMhk&p{<4GGJX!Y1iyED&*0x;;2T$6XwU8CK6_2as_WE39d9;xm*89zZ^dZE z=tulN6Zb3dkVPI7RAwyr*GR3TfZ!It*H5)x)nR_0EyVf`yMq@H{UZRp!j!6j;6>hn zaTfku{GyB(O#A{~k9+}faGKTIP4u6@O1*jDP1SX-1YQ1egb%QXYc$U}>!j+Z*BQS9RF`EZ$qSNtc`WD<%dBpLXN7u>0eyunxsGZ#bq?6WI5XT!V!}y3IkIg5rdnWOrn{_}70`>u%zlaekqY%7&{p~7x!!!nYLpL zoOZNEH^vNfWSbI{VsGnozkI!xR7xD4!(k!S#V8DH9Jbju!Tx@ZWK>h+s1|rU8rv50 z$~9<+=*t82ou9jiC$7lE%~e6n+y{nbqVcAQxJ0{pyw z5Lhp``RF?SbEenUT*j)Kb-Y#h0?=XN>oVSKaO}vq%gx|^+z>f`BGFR=#@omLorzs!{0qq>%_6M?>Y`{chwC*+)Ta8@zDFeD=3Qf+S84pb z9j`yt;UMf6F&{`P5>h=Wquu20X-w;9J`G@{C@3u7F0suFvKy4Q!$P+ zH>|tQ0=Ea_`xUsgZkSz%G|^j}Z>u-xmoUB;dp#b z!t)oSkI2h7Ot2B-5Jq#Gv4F`0FFpDeo}7<4o3%HoEgK>X)zVNBt+7l~DAB5%Ce_dq zbL!HZXg!`oEeXaFiJwUTs2>;!GG(+$gf#bFFA?PDW+{PVYw%nwGZExS;yEj277)DP zMu#4w{j4frb@I;^HK^Hv*!gn&x6u`fX@0dL7z_@yD`O0$UWFlvA%n64Ll)ftk3cVO zXwYL0+}#A%;VVuKHaJ#uj!R{9Rt$ z(>-hTCVdUj+Sy@0JUj4i;`VPj_TqYUQtX;3hSjz__{!yaS0(BB6o5LrH@ku|POFtrb#NeSI z9vu)5Pc?_P7z-C`Ht1b4HVVFQRfm0iK9~KGjXFIS7lpvZQM^4px1R!v9)hD7?F(^J zKzIn_Vc_8i52==i=K~Bkk&#|eH!0>6s%s}yy;oHet7qaGN)eNr=uJ_BsIHHemh#e< z&b9K2b;=HGq;;@{=2C?Qm1rT-5(5nuX|@svlCwteM&P^nJXuqbD;hLKpI2>2Iq(0^ z-kXQXb(MGipZDCV>V1*qRo-NSvB6+t3&$m0}Tc(7r;rFw`TN{aY#fJ z*dB+uyAFHXi~}!*xvgW#)^5>Nh)?5t`ue^;{<^VGwdg_4MOJU|9$~A}Wf?&Us2h~v zx`w4*Wbl6WGi97_z2C;7&achsd?mww1s_gjsuLHc zDQc0^tx1xeKTncMg{Tsc;!Mxe$qJCRTb0rKRxjR{m%>R(f)KpVt1i)G-iOnKi%0p) zf?F|XF%v6tcmB0TdZrG|;Q?cM2qvhj0!$>RHwLZ^6gh_z+vtCI59;XPVgjp8yc-vY z-C^Qp0=FDXeV7Yjh3He`EHUtU^Yb0X^~h#bzH!4w{0g48`Ub|$dCnI;`wn|%q1Sk<+Pd5I zl6uA)OuWJ1je_&>eRLOaH}DN2+xrH1=xFAYQvK(u)PwV;^fw%CEN(shTYUY6Fx&8a zu@7uh`#?@p3A$9JIm>9lXO1ekxOH0yRMLI9324P@VimkTQ1r%i<6^F@kn&d(&n6X? z1ARch3Xvx0K^(w1AQzt+NHvxL`3%;9AZoeM7R2!ioCGW*eS6#(xB`0-3< zvsQ0X*51ygA@DBX-{7$2?+d;d#20V8!XBE%m%M04VQaSPEb3f}xWv3>{c=41dsIsB z?Gks-F1BNA&&2jqnz{dQJp$!TN+v-iKba!%g4i{lulxi6l;rYlSuX-g?HKSX_6TP6`=sH{+cqt`M{v z?22Nu!PczAor|KF^JnYVD?I))ybt3~fJZ~ldp`3H`@vMdvv#wt2mWHiD(jl+amTW) zxkDG5@%1d@j734kMSHPWs=seTT)yE7`+p0)o<%$M>_{NrzhUqfr+t&|=X-K(?Pfg) z+_7PmePp56vS=@CTXTng*Nl(!^>M=U1?akVi+bSK3$R@^8+zHNy4A4YIwG(I%v)Edlk+*dciMND7O` zg8jyAdRZ)SF>o>BV*EPJfTzs(mc%z>cy;*oP>Wqhc~i)bi+zMwb0jTAvQ8e@pS<4;5ea?Z%+jfo{RNm&(MC*XbMfV7K5Zk zGe4rkpoDoNt{e=KB@jzla=18w)&_`B0S;lja$INjkQq{aUzeZ$GsUbgu;X3RK(TDN~9LOWPEpm_&dx*qL z^ePZTPEWmptWHm*jtYN$^(JLYx;VQo&NpxFdnMvki~^Ad1v`TAki=fZGBaK#csWn_(2Qw1Q;Z6ARDHC?*aN6U)MET)Miz>o62;@KsN~z9z=J9u3&Vh2E1+)OC-91 zB{(#^gQ*+wz=b4+B?d8iB%U*eygvo}#9&YKX1(5E?5`Vrr9fXjqxV>B3|V)Vx?<#| z1y~wCmkRNlBBmS*Y7jf8drpnFYqqGZY;;WoaR<6c@6R}hdzVIG?i0Z~>iAyQ1N0i~ zkD|wn9yId3J_ULe=`-lFKu^f&sX<>m^d0M}@7HeCvPzY+6*wC>N8%jw82lVYW0dFc zYjUrQPa(da8;`6g^VqQjwwVii?-rdF#ASjv8eEFUZW-`ngY8jlE0y@ld=$vn+^OXz z_g515`yxj7=P^SK%6NFT1_IuDyWSiEe*(N71D0bP&seY*xL*(jB^&Ew)C7Yjb}R5Skv#z(lksHA-944T(|KV3 ze8Rt0Z&GDRC(8s&qm977mnyO>!IO&5{(Z3w-~T46RTRQ8JqbS2lfZpFIFzl&0zHcC z$LI+;rI_&&;39*!%44Lx7~2fC0(afG(jJ?S<1pS*QU8;`>k(fd=Z`85az7;RIT5%e zuhUe{=rm|jpc0La;J$PviuU0C^jJW-52Ljr%7_*VoC6$Z4&~c}4>^Y9iVi2HDOcpbn*6$eGT-|esIRKzLf;FFyR zFfiEg*M*^RhZ8FXm6Ss$e6c2G zJ^*;gv1tru?Pv#)MOA<~@V%CXoFi$7-ylXI%a7BIe`)pBov@5huf4e zvV@UuNsl!g!Y%xG9nMER?CRxHn07P=!9(Y z;NNasW!sMA`RB^sw?!w^B5xL4ZpJEnP-ej3n}V%oY@MqC>a|<+w}|sLtg_3d`#Z&; zNOTa~1#;oIb8*;0z(u5=!gvC)$Bf;;z7&r(DR2(rS21n@h8h4ko)2{3U?Wg`I_6NE z$%fxapzyIn@1szw;{0v|;6n!AiSW4zfo4YlpPntd zW{cV?;zPji0fT0I{L~5?kEOgu@xGR7EUO!DwTySkhr|aF-<9zL^Y~$jc|Kq{lMCO~ zL=tQfb&RTvszroRPX2Ohig!DvSk@tMZn;3rO2O73zBwt#E{O)rC%9(DCfW6Ou|eY3 zO#BX_S8y7EQzcFh#u*Z)G8P_I3|a1yc--J|8M}hm6~yCB@Wip651ebe`gV1;WSkwv zc^DU^I>W0N9ai0s*wI*jE7iI0hO6wrZ2bK-oAvJu{;R~AjaS%bkK{R4Z&FJ~Czqr_ z@?QYX0G>q0c=*_FtW?GXQCo*#d4juJ6U*Oif!d+9nU9QKmnu(*`Uh zQWkVZXfkLg(i*~u2w)q*^K^o?6q~e}3$&G#`Wur#MM!xh7t%8-l7rn+o^Dn_b1J~u zp4WlHK(Y(k-5grPA$NHa2NE8a))c))Zh@*fRJ$r;$h=PO*GHfl#la96B%_u`2F(G< zgJ$%_NVSyFR~1894wi8;;{0g5(%^zrt2+Svun-E%;d>e6(*$OZJf?WOjf$&N#QGz@ zYa{WF$3Z}fg^KS_B~CJJGp`>+IS@Ui$kO>VMNUA)dBG^XGrgw9Z_H0VSP5|K=R}d) zjdJmL%t4N|1WOb!EEh|RGKK=w5m9hZP&XG@J&?|ydJGJPoSKX(fkFK1c6pD$Nx}Wv z(^U9dfxQwx%!~(B<9nry@024C&eXrUeydJYjW?xyz&ml@c@M@{4Yr2B=3`;__4>{F zy9i4+uCl8ZdM&eU1+XpU58rI?TEWY3_~x?`yMqf)9TbG%(4$sT-Yyue(Shvab5YZ= z2H2c zW3TW|=2_Tc(Pqa|PvqSOcb@u9er>MbyI=n&y(F~qOPRP_E?&MA7pXNy0lUwb@urzaSBHKR(Pxqz-ku_Q~igai_ANr3Hc6Rk3u z@t&gA^s}z?T3YbFwdsfe6*11Uf@kqu%%Gsp#K8!IAWU(S)R(J3B|w`ZhK-!N9e6ISOQOXfQ(!3uL^=?i1kOZsnxE5y(W8P60CQjT zNNUvM!-b-TU*vU*xWiQ3U;H-?5xF>O8@G~_1Bj$JBN#(+|L_1F*VhO{!^Ow(pBJwo zrkp`VqK5ZMl<+?25>T-)(%amG_st#-!qSJw9fLrR83XdQ3@EbSi~$q<3JhdMe=XD)))OA>$67J20Pkl$N(kIL-k^m<4jZ{tiFVBR(g$_029<1vZH0z4*o%#5AD zW2aVle6oAP`?lzW8vG2t_Z$NCHrSfg*|w12-PyMH->M}5Rijf)WO10bQi%$pHKx9M zgQoGK*D@ErHfW0JF$7u>6@xa>(5o-nv5}tr0=7L9^FAA6$h`Z0I7SFYHTCRQQ@*c8 zAf#L!#)!CmAu?4)G+~5PUpBmlkYv#CX&M}Wcd5Y>S))uWk7n+^N$?P?kfT!wKK;#bpkxWmNF zA@GmSr=H8%v~_o>E00`Ykyp#Oz~I&LKHLgEL;XE79+3Q_xtRz4$6IV*KG(QB*ZoaJbo^#<{PC`PTFB`Hv#*@R}?734N+xu_TlHm%M z1@R8SWr&xhbyxA;y}}Wyj6$wu6)XjpXhGLcABuuD)HJO~(1=bL7QGv4{2{ zzN^5!hs8h753;tuW`|i4NLd-|77qH zi=1^NEVJvjsXGkuCNq8xKi^)C=VHE!`+D!(u#%3&{d@jx&7FF!<@^nvTlllyK0ZF3 zd7rg+=r=Jwv0;@hosV_Sg{`|wr{_68m3ZUEE9@H!y`Du|v^h7))^6cD!0rvJ?8=2+ z&Y~TgHe<;5+RgeOi1RmGVVBPJ;^xv;Z&JZs9;E;PAOJ~3K~$x)lYSG|-FSul!$PlT z(O%eg{T6*yV%LUMcI`s1Wx96#9r`sHpWCp?W;S>*OLq0`>TC{tAGm$PD*KIvSi_pl zy4K)tfO~2+-gC4?j758XS%STr$XMxxLg0TtU9X|`4#<-$L7Wmp+sm@(@n_iWb_}dmG-kIMBPPP3fzNJDQ1=V82xQE2`lP)!T$oQ;CyeAzWy)K-pM*iiVm3|K(} z{DlO7IrSUdKhtLSYqx4yDd!JNd=R)d8vpjDmG-S!ei@5)4A^zs)E%mP+{A}4?pEZ> zz&S~M`CPnFc?{^VQseHq1cqFStV-90MDJ^Uvb|5>n=z?x&NDQqI}w*_94e6<>`SpR}mT`s`lLxGZ2=qQF6ED~~~ zi$JiPE*Tcm0E09FxbV+Lw<2anS8BTN4Bi~vi5I&&@Zsuq^9G#h48=5B4KIk*5&al- ze8?v^=#vjE4VV#PWGJ}LSjA{f4a&{tjlOLbA&!Fon$6c&0V*a+f{c*9HnKGQeY7@= zuVWA&`W-YMnC&+o5)sjX>}D(>fj8ygq+a~K*^D3Wi1?|&*9m-GIS*OJPytLTAa!{Y z@o0Rrq6sC6^9%=nr{O~%(k~Rr&4-KRkn)G;(oboGSY(kUd4g7@fvhD4OH3?LYQQsx z;4euqw-)@^79WQLTa5);O$;&`0a*$E{~-{o!2USMfzU?l$eJ^bH}R4H%Oy@iEGKXR zuuRZ7GI;LhgE^Cf0LDOfWbAK*ZH4IH6YMX5JB@4W@8Q|`YC1VA_`v~=kIUF$sj)Cd zc9cqdcdp`$b+@Rs-bA`x0p)Z5JSfh92FIfLvyymHF{d$EbF6NBf-=DukoPhCwxo>kydRR>k zyM6@t0mh>N9*N?S={Ctd-|Xt!)!9_y4Hmfsk7q8%_mCgrke{z8vTeTd5Nqz#a*JGu zxDew)e3()xcE^i!BavSf&bDu{1?E>C2k_)QsL(21< zu2PAA1N^$+PYj;UjrPnqo=As82S&RY6(VgwD=sS3n*8GukeMhGC?{WdN?{$1!fa^x zJU>91u?vX=@{z9{+zUn>9})(K&iIg{`{PxLuf;Gvm|a5*TY~+kxIzFDH47tuZ{(ac z14WM;1i?azAskX(76elonshLBiwdArpal_Rn7JP~_Snso_++S{kR`FVmtHTp1V#DQ>iMQSpJZFG3OCa9VNacda;=JD$gX^1r!`%967Igt4^nge-o z5iJU!96%u;bu0|0PGr~JrjxP~uR~md4^AMum&-myEj~6Hy_b!!E^h6f4Mz(q`zO-x?9v* zFY`uo(7@$5>?8*s#Nn1(OULmq^C3jO_6~gqWBZ0x_V333tP$pIqk^#KF`C;R$+OHv zWNrO=g~#8(vw}a`xXS+WaBG|hqTiTbDFFJGawi2`ugJ5I-~|o2mO@;x$h8!?z{8ot z!`*)z$-Rt##3#!>5 z!$+ac6Zzm1=7ezJxTh!byYq~eQjK>Syi;E9txJ5}jDHdQYj9X&OJi(6IuD9<73V+^ zBM45#=t$!WlkIP#?|0*R8{X$4hczA?-T2;?ma=C$*K!*8TO+X^2W9+s4f96}k!vYz zqP(UBmNZ^-4e$RccntGWbLhtao*!>z>YU~%3o=73waJMloi9~W?ZCn4@~*2R@{f)C1Xbr_ZIiQQ@+Xfk0h71 zc8mTC;`dBkGaEh3Yqshvt8-P_Gv9_33Qa8sh-mr0u_l)K^u`)LK;qorRFt~E_~n1 zz;gtMJh%{8Nbt51xLgu|i|PL+8?AF4BKCCzRzTux-1khWqLz{mvydB6BInKgdHnn? zawt`dVHv~b(D@;Ma)xm~sh(m98)y_3S^3Y|4;Y* z+>DZx;DTO59{~(l7!|XyRQFH$vTpF>CMB?;jeZ}-e0{VwoIqq4)C__O=(P767$OfL zeeHWw7Qkd9f;B}tGMMkRl8YYR zAUb1ly&4@DT^4DNUMFnF@Ad6wv@6nsX-Y7z;K8h zhzWEZGV1jjF=W(b#1un~fKrS66EWo}$L65M=O8;c{A|tGd=w4&#z}g=#^j|M_nHz1 zt#M3i}D99(nOn;H5_TY@7|ew4u)?0*~YQ-yZ=#GVw!$A2mmQ^yw>Y z_`2J4QWm&OflFT~Q13}{(Vd8H%V@$y>AEdX$#crb-??86^QM?UuDPh&+}0`nyDQEkJA|VY~x(Q z5D6GJA|8^!aR+mLI9<`Q5wV;@_n${4?l#z3EAy4vsOe2+lLVU53k6m_ie z0#Oa(P_1}BLkr%k(QKlLV!xTlCXemv=_8l-ujlE}QSRRc3*=FRk!#*4nUDgNl(i^N zl-ru7?N6`qfFi>bz4R^|F>L1hqZt)>PkIUOck5_)MRlN0usaw%h`orXav014r5HI5 z<1}-@@1+1Tb`!Zj^Pa?S%lPUGwO4dHcHK5LXI0*YgF$~D-$QqpxVfJ3`Om)Hez?F( zoL4J)!wt@36qZ=jz5Sl=h zm*e-S9l$Mut*1Bf)niGldM5Va+tpN$v=;aBLNFt`z)lv7?kGa=nX}^FR1vfl_wWF1 z>0a4k-apuFo+s|cMg%gZJA>AT`^*Jodl=}!`|$=-{946(sfJ`6G^0;2oCKy02!?~P zzh0*rniy1-{&Jb>T+Or;HVMf4EF3~x)TVoYACvZ~VvcK}=TfiTs%4d&6;Z4Rup+u> z{n-RwZeCyaJ=guL0gRtW+=KWo@EFF<;mBh%72lnXt-DKIvCfqkzbKMGFMP+0e~OWR zS_H)|tX+M(I-3Ho4+YfQITkI9>p^W3-&B z<0|{m9ItIoZOvv~VDLbUocCe_wl3QI+6T6&eR!CCCVu_-1e9O1S-))X#lAjD3#Ha| z{TBU-#6Os^^2U{R*Fvlz?G;}DmSU{ku+nZ>h;=O5!rAIgs&sVns|Ftd&K2BdflqFD zyKP_SwJn4-s7YRKaJk@8pc%0fbJfQX*nGp=Y}cAEtE1G)l9&c*@|<=Hlx-BQIBG_h z+2}C;M3xFp2S$D+DV&e|JW|UtMiR+U)G0ACa2RXEmYk7-)WJ41zG-mXEo#l|@Xc`t zGrB^VK%I_Ylmu;(7vxgGt}}hzh0&b`+?E-fV#W#b=JAOdHS2gI>yu{e0PZV^uk7pN z`_ob9TC}Nc%~qX7ol6myB*5+~@CK!kX40(Awi~Xpy@z?K8QI!9bqSF_2Hs?_74h$n zbkOctw($ko2B_u=yogXo>@s6#GTXTmlHRA?css0c9`uOvX zCR(X*ftjCEh|BPXq%kmgiF^C|`SyI?2Nso@NA3FC^#%q09yngchc>RX&oA_vrn2?h zRC;olbH)uHz8Y@~It2XP-_O0z7XgN2$*$R=w)Ps8LD5=jp{Z!jj*%7_Z_MChh#yDs z>5yS^FkV~H)CH6!+ReP#3y~Rg${T<>ak!*kXGRx(A3fYa(nMCp2Y+N@P!I?l!~qRC zJ{T=C0tKwk6{1UKWNAGmpln7aO)=c)gCY^30OVlijonlF_=mAxyz#ytQ7@X+1j7Li z$cLr-O(@F2b0N?xha>v%M;ev@vM81WZ?rmI#_1M0O~%Ri@vh5w%)}#UK=(n*_<8kHw_*RVl{+|^ ztPdl0P6u{2A2tyrcM?F;WYGEJn0!wf1$H$K98LgRI%J^9A?|yRiu z!%F)e_%$;Wcxm*wiZS^L#bawDYGkz|?BVUW( zUmgPfAMll`@zwck>`y-Dg@V^0E(BhUzc(2$i1A&MgTGBYIGpj_>8@}6dWFY-hF`|` zW8id&&&J5dUTE*@v`n)1-obIe@gd_liQ`S2h;gDKr3Fw~TIcpwMK# zQa}Fw4`K`_fAye=Y7+AqN(0Jevjn~I;mn8}iqMhAYZcH{YuVD8h`B?3mx+;0!A5|ai?MP`Az z`SGgY{$C#bb!Upi1lKO(0Iq-!v`SFMhi5SNSIR1ePA%o+H3z`CBQZaQ{?%CX_$tAi z379-?G#rFHtjGa_8i61DCRHHd3~GZ6R4 zXbtc(jjJiikRlsG;8i9r8vpZ2tS-2#zmKa%ViL*LY~dP%|CVwThx++WVY#xjjIG%- zwAY%cL}*i$<}9P77*r?FVUf>L2!i_WJsHH`2{J37k;dCG&L|KO36xkfcsk`5x;PRD zn}Z+2WE-LYGlm5JOibs9pHEfufw)=-3<&B(`VI2vAp1O&D5=Kp6L`|#qve|CA*Oq8 zP9VltH`G@z1Dev{+E#`#Tml9r?R!1^+iF` z##MIJY`&(WvBF<$gfSHG=*M!|IHB=9PXcNq@9AW~a7IBeMILt|I~*{)J%~%>VtU`g_(y}E zOdxzWt(?hZaPG-o( z0Zt=uY65tj4xExc8n5@gz>{(zu*c1KGK$B8@kER~+27Bu7ek$C{Wg_$<(zIg=UL>U zNrf-G2KO+=j)?%EMNd*uUy8%Dg}`r{ajhbsw2bc%DVx!rz&Rbs&vO`@(Vp7vimB zUZ;!XJ&AEuk%K;*t=+5*z^^k&enBoS)gL1-osJ;my4&@VJn+AP*8?Bfu*&{qI_pSc znHM(rqi+U+#6u>&M#fjOHtwqrQOas8Gow8krRe)@6MkQ4me)GlGxv3xqi8m`5(iFw zN5b&lz*fBft|`Ty6@#)ouC1i{VTt12>E|2FXN-E}mXDlG8WE9`fkhxBEO;#9_?ejJ zm~x@B9&C*Y5beHBE!KU+ZFTt%yWq07#I%nJWfn- zZ9F#&3FZ%Afs%?CFA}iy_0gKgZ}rijkerkOORzCZ;&RbkaE_Eu$VQ&Qg|7=66<(Wf zNVbTUMEq3b%KT;J<^W*i@8wYOcp25SZ)f=aYKTe%3t&XgfkhWmXq}+1Hp<_(+~P=f zDadnShg?TAorPbMZ`8(#QPMrSyBWiPrLQ8Iyofvy<&#PhR24zxC$3bR4^BE+A;U z55nate;h5sx^20m{1=J(m5ZC3qdtWDve{_iSjE5E-Di9@xa##zUB)juefg^AJ6h60 zlHKoXK`0Fe?CF^F8=4xYT%R@8fRiqgbqtZ5N7gxxGzPvz6 zNs~fir;-f$GKMk6IYK6|?dEO>L$KPsdF_AbHLyvZfy??=%_wYjWYJLP_N>Ol7{`Of zs{0*JIZ;@#5MfZB4J{Ytde_@KFomkNRWuC;C^z*=Bm|wjZ;zIa-Ig18Ut89$$N_lu zW|Lx74Cdhqhq0hGxUIy}T;f3deA3m3o7`OeyN>?}`L7E&p1q^m8}%>}o)6uHg`}c6 ziPTMFa51N1a%K4(X$gw`LX_DhJ$n)QQgit$8v&Vg z@Kj#(avLz&EuW+GgXu@X>fdYGR(TUwbF&upAeu9NaK zk^0HYzFl>NLkYzs8mCYy6<#VkHGp#I%9fp0YZIOd4>82YsB(0FJ@qJs!Y{6aiCN(f zjr1vlhJqQH2pwmM&-XXS{pc$Jdr}mgGt9p1Z>Doxku}Q=2y~cUM+B1U>>;&A&Fvko zqa=0a&{=$LGs%0ZzKp49;kY__>NtV%tTf>!DzIw&4^{MhE#2+%PcB=v;vd}HMJ6bp zmiPr!>@$h_>EbUw`lHiN6n|a*k~%IZI0#?vj=Hs4>1k=z+lUPcN_pBk>5%QfXX6kf z1I4iEB9an$Y6XB9Pxr{zCo*_QKZ=p|)6tO%fzzhwmstGl*D6yS4zjh@%38neH}4kW z&SvK2aV6PzQC+X(`9$8E7tDU(pG!B+o}ho=H^uylDIZUNkqPgt-{Sk{*jc1&j)g4i zuRXmC3w46G6dP?dwa&}_S}JnCAUMSNR5Gbtxy9H{`66^RG%o|C2IKxpMM~B4_%hDi zrYZYXXi(IPF70_x7kM@B84(Kt<}_K}h|Jq=Uh0Z)Q%f93PGDX3tLNHeb#O5k>3c=g z!$Q!)NF%V|q7Q%mWkVgjUrWQS z(#HMV$Lm{A*hvGtS)_~j;EC!eo2_NG3O%w?UpP|;$aXiyee^0i=l=F;@7Y9+z`RtF z;}SzQrHSi>KiuI&>T>!#YB1zB_*VF+=56coz-qg^8UNU|akjF3AfD9AZwu!5h_SEI zAI4LMwhKGIIWC#}shGVM0?1J$|KZW5^tWM+*g@%(d%LTwAi<2PaWD<_`$LAdte!BG zjES?e(bze6h(d7Q3!emr#jOXhcKdDc%E|v+>_s`=0;}@Q2G-wqY>Lky4wCycG(in+ z#R0zmi1k>BwA7o{56nl)uHh!lllz7ZkXak->r}@>D&MiI92CP%c=oMJx*qkuWn3-! znQ7-<*R)M^-$7$Go@JLIl=3^;@sQyL2PQf5JR1e+ z&g=e0_3mt9$l24vshvveK!<`~b$0mw0r`O<$MIKD(y+g#@Y0*xtGig~R-cwlG{gnT z^@t^MRr}qUwO2pYtC3Xzt32`D6QZEMHZm^4^nZu@nGrv+ok#aHTc-JYO<<$z$!=N_z=lOo!NgY;r^}jO)7Xb54#5Oq&^JiVi zXQjJU0|v{d!zR`L&jQe3{$LRJLaEfDg@4rerG+l5)%JDJb5wchLygE=8^g$R{B*Zv zN%k0Ss}XS093l^3{Oo%Fvhtt{F(}r%sf+o$7z!F@UJpT7w6r=iW{vzirqi1I6Kk6Z zHcQwuJHt-~REnH+#7g?de}cRj_C>D$c}q1Xc;rloE7tV@I=$ar;ij{mPN?#XvBtf+ z-+{n1jF<=2uvb*0uYfk>RF23O&G5kub926)C@?`Luji0#V#eNBIxGC#a#hEAWCnKe znlkpcdXa}d1q%g+*mf|B3XXib#g8F~EV)z-<>gA&D9a?49sLtGM$Hr49}ruc1i+bQ z*pZ^#qFg}PM@%#})v+HvqRZUWc*@as%gIDU`%Qp)5UaH!4`E5O@YCJj24@jBnQ-)L z?O$keU%*xfcvO%Ly*VCzluj@^5xPKeM5o9%4tYy*436y)L|7kNL&k2pk}H&uiL(NS ziJ6xfhDFALgFQM&J-`Ti%6VaN5S?HPIufGE}_YVo+vwUttO*S;9rBQ}*D0Vz! ztQ68DreUbSU95yfmeQjA12mA*%X~-?@bb-mN3<5BW^grRsv4zbj!6&BvJD!pN|{Tq z6TshdzG~`0YV=eCdvbk)$Bs9YYzWlPhvu04yTvCzj{_y*3WuGWi%m3G6L;Z+b&i0ibp^ZpKL{ERFh7 zRDuQyOk8!*Yf*S&bGV0KKwXl8RcTO;E$1oCAn_pi-G0@pSXKrWR5q^|d7@U@)QeBs zta8G3iBqf=HgBRlGl`S+`6na#nn$KsHVuOlVVp_C6OiPsu(PjwZDk{o#bK0a7Mgu$ zcvYgreP?W`mQO|pZ9SN>xHN0{;(Ih>2#V2fxpC|%wMfX73xl<0$kKU+?w1I-={8Sy z1UE2m4KR`h)z$OeK|@wn%JS7f#pm%M*D~C?h8QlCW~FlkA4khdEpD>alMBo@WAG5x zn|Rr)`IQP(zz`Yg!A0aI+^qQ%hA+uSVPD4`vI{Em;!C z^~Yn`D@Tl$;S*(wl&O!2VnE z3vSx57#)McWEt)JrRbJsW6`19Z1en+DHnq*{q;S9Fs8yy^zhUp;l+6YTWQ8Vzwd@=|3B&tThsQ&ilgwW#y|><}tEafiCV2vi2EcX0oP# zObv4Y^)sNhu-Ad9#1*@Ly@EK7d-WRSlO-3M zt_==a3fk~KTHbXT8~4$-Nj9^-Vs~XtuvVZZ>hY4dq_C_6(57E7GMG!GOtnBI3_7x@Mm zN14YJn?qzPXm7y997~WD_SJrht*;0=Z?t;Y+y0c39h@_DWLjZSD-^!yO|*(}%{s!RBLRukTv7gVp~Cd~Z@-nDL2 z!4!Hcs`A;!V4K7#mVhssjl@oJVl4INZLOB+J191?$ozaHO4OHMH2dMg<4L*RJKMYz z`i~Migw&{&Gyjnz|85jbglH^1^(X6|*EHWlSIARUHEr|#cYLk@7OB;pmG@!?Y}RgA87y0fjL6cPZ{9w~ z5}2==|6ib0pjbvgq$n#}5F?1i4Ld~s74t%29Kz2jhLIUUld!QR?=s*3{z;xmDUCow zctqU;l{m3CS89f_s3MDol7i@Tt@9H)rhpkYP~p;_CzrDF_IPaLpshl7 z<#>K)`Q2GQ9Gc4I81+fS95hdWhv5AkUy`J!-WMj3_!Tk9o`e1)XZE=9hY$N6LEc9K z_FxY3#3Och)6fJb4FoerlZZJD`8OcJDf7Z9_Y8Q^Z{p!ElSAG+{bJto=e*_Yy8CD4 zanGA8j+S<^11=054ja3=J4GWX_S7BJDiv)*xtdsIbWOi}DoOXf(N#&t@f_O2dFrla?&eQ|M9E#tq@@=gdWg>iY9+$3$Z8 zG>7jeI`Ai4uG*6NdtCmn0AbVaOdovtypk;YLN|%zyL=Z*>Zh2Bp~0iH;neYeYI7NH3!@ z?(Jt?W>m;3v5p6BH9uswNCO@oTt7OQ*)?sy%F)c>6Bc}l_FI3oYwy7C4RK%fQenMj zNabt6@8L}Yf>_RD4vRYDtwK!+4E91!ZM2c)p?f&fdoO&(wk25@_=_yU-aG_zdHYkA*L;_8-d^neP9(2Xf z4~JXt4Mar#{Y}uu3b4cEgbHM@<1Yft(mZKZ3GAZn(z$EdZqZsx>rF0;8Sah!?f3~0crz`v%y9MlrY(Xdf95Wu(`;1ZDSI~6V z6-&= zYrMkU#sC@n7NMeXh+FIGONDSl?oa_*|r)y{DZHB{~VN#MVV=^2*>Y<8KT)P^4b2pkN}B)?cm@8)wV5=Vz45>d5G& zwfK>&X>QG@_0O5qPKi%AGBY11EFUqB?qk5gPoua5zU@Qp@45qH^;98jrpz}FsP8k4 z%J+qu#0&S%{_;YT2`-2%1?Qyd2XXU(mAwc1sYe)PR^_YbM1{ud2!OA zQdwApT~;%h$jSPrr*+YWJ9VbBVwuqiO2v*gfg5BSEcbjuzaoP*k};A`5COww>3!4f z>3$wPZ`9`k!=tWxi1lDn0hm23F=T@>K-ooLGYvf>*X}p6!=E92LXz1U3;DqvC83QpQPzV8bvMEU9 zOONpL8XBc-mHzLAQicfBX1vm&Yn%6-VYVbI16PbEhcCdB@+c1D0gFy{q;$V*zOi{P z`89%^ub`h8y_wI|Pc0|Na0skazf#x}UT$|)dh)jbJqh>39Cnax)ZgV?KMx5v zOT6OlT7C?ixr!xkgdaoey|QK)L8*wIx>eye5W8Nw)DlLi@&>#Ar(=zmIZk3BN~I!e zB-0|~eeUq^04s3K;@YYWm~^$)C`YXx#`PHsc-OYzr7BiU;93l;3{DDO>d}i9c+={^ zSx|>@Q7Y3}3|rn+=w4>_P3e-v3Hh6^Ap)q6P)8-;P(Iw9*<35q6Uf;m#h;*qZYb{` zNwF~rwh{R$yET0Z4nkolRN-B>N%0c7KkgOq1QL5UNLSP37q|L`ak_e;&@2(DM&^P# zfnDAWa<*d(Z6mCCh&<4vlX-l1=2-p3{DS9m+`Bp&rXI+dmfD6E(OZ7~(GdQ+&G>JF z8k6Q8pzogF;Jp`NL`OKh=})eC?s_n&80RFXCp^?ZgH7JC%Q48fp34!0Eb)xzBmsBi zd*&@w2O@#gpOB1O?Q)%#1$QH|{;Hq(SVjEQ6>cYCI-Eaf8 z_&RLks}oE>|01ld!#rDIq?I7$I&ydgAx!dvj@Vv2{=Av!7qYLHg= zghe(wUgD0Pestx$nh(G{KhO4II{@eA^?uWzY2yRVkf~BkbkvpN7d*SM69kTu9HkPK z$oaZdvch?qHOiQ2IL1oN`26GF`NKbi8+Wxdv+Ev(c6ULx6cbub1_Z8&{ok#O?Of%$ z0%yt8o#Wsh0M!yF<3%RnKyGAJxwpcyg0M5un9%TSpLf0{-jBqi$4+;H<=Eiv#vV42 z(o3iH`n}AwwO}25a0NktH||42Lw2`pX8dF0yGHU250p;s zGQM?e6Toytj3Xb8nfDm^F^nyj;(%w|`aRFY_;&W9E6PdG^vByB7G16*!CJ3J3(13j zNoO2of8q#!7jw?H6WtN+3$x;wVhHFipk@v+N|>UfSAHi3x!t#nriqxUjKV6CjEQ%T zLZ3?VPgPgbMOOLyXPx2^Z;N^r1$x~={8RUncOVs2@88L`!olRbMpJs6yiQ(=y%Mq^}spe z7ed-6_u$einkFWxrA&nPmu7sF#QIBr zodG0+MiT_dfE7pS2J2d9)5Eqxtz-B_iuktLO2-4b2W_wsTT+{DXpkD1t2jf<*Lx^PzzS9;|L%rir?zwpC9^m(gZ5Tt&{asy8VtGDCz9xc)$|r%wY3gz?4R?MtXnFWc*~a2*U9Y5Duo0!mGjplK%X5@Y z5B#)l2+D2lIV02J-q@=eH)ot{E*u5z2hIP%xlJ!oz2plv~mX-Q$#4-D=LJw zD?q6;H1gMS*q`5&t>t611y=JYc%!K}1M^8Dd6)TAeV?`Iv+>s|#IhE%e|eW+2e;GM zcaGSZpC410Dp=S9J;{^p3nzPihE|f(UK|jQ+d5TN8+%HaDw8Cq{i4f_kh>;7QGDe)12!?{u8fzVRonJ`Qm)_gUaWoRp{quP+Er-4=LJy9)~kO=*wJeJbFnI1 z;H?-*^Oci#J}3`ur&%2^>&BU~^K#3`kpwuWq%CXT@`e)Ts!RWM-+#l~9*23lNRw zcu!oUwmkd8dXhCx^A%`iLKbgV-RH`U@+nxNw6lT5f9z;5Z{Z$#Ae^pDs}|E1yxO{r zr}-CJo+~doMH?G!DPwLW(7HT0FHe@hx`%UpirFGkEQ z{uoKsx@#b0ign}9T)=6r^zhHtPY3B#3q#p*Z5^W2R5z;UdQBq#)V}LBT|>^gW@5PX zLdn-tq(B8_ZbR=Y@L%jdK(O13VtJlE-<%?$-(F(;-8u9`+RZT{x74!RiR5@wIw`zjIO#?jT#yi>y0t@ue#>nhztGzQgZs_-@Wyn z(=>KRhe^pX4aq^XKs-|_HiN1_)4pFdty0q69xR->(Z@D*e>JN)ncKhmuvivP|t*n1<)c!Ik%mCGHFL(WWjJgR`nH`2kN?!cV3}^gq zT-CBtPs=4B#_u|&XY$@P5_XA-aeH)N8BCo15x4@|$7&|Mic|YzCo~`J;L!YMKvd4r zl0n#fy=Fw3Nj?$#BXwryzx%+pgNND$@8sv{OH}k$<`p%D8OuhcP)leCTLTJfQ^CCp zB6E>w0Y$E~lusN*PJc7pw(Q>rxQMk3t%@C*F=t_F(fQ+Se4l{@-5jJ`^o2`jlFyPg zJTwAbo~%E)j_~1Hrg#t!^NU(!_~Q?$4u7_Pq$@2qam(=_+qHJKv`RSDX)j}Ak zTKVGq|AJ=cbTth2AU%GBN26@r{y%4$JVJ;eQ`-yd?MFn_X;+x5hHxB-i{Cl**FP_v zb=9y0#gX)d-|FWQu7SBw`j9Dn5FcQNgz2JLr z#73jv$7p7Mc213ovAXgsAFt_%k5M5;3yQ_ptp`##RM*zqErZF{V)Fo+10R~vsGr|u z;Y`Opsu!33_(07^PXi=rm>ZG zVvi@q@bm8Tp6+6722mMy-_a1V!}6&wZwvdF`|K1OSVjQPrOsPFCWymn?VeQ|{67n@ z{hgkl$cGmOD9SYt#X86aR9CXO`+%?jbzhkOHN3DTG#_cZ*&e;&f$V+3hJeHHqrr7gNS1Ve}s|&aTC_sfOrD1 z23Y-ZndBuy!Pk}QA4L#jMvThQ7Ncc=2!{U@Y+3Jh46X*~W(N|U+!i3ry5jFz$p=s!MN?Iz_1~U4-<%}OY$wDM zdJJz-*F+eH;<>t~@b4ZlF2D4?)jX7a|uJVoiAQNvSfSZpw zluV!2m5r>HQ1GPDVXR`Iz z`SA;hr@?~a;$(1Gim0H%V#pOB(0KP39$%ZaZvc(R38dJpcY=OPy!Yue$!{4>Z z97*h~ztazJ2roxEcEUxPhz1K6LumHu|B4p(ne{=-H?uX^xP)dmB3JnxkLv;kI9cYr{tQ~RA@U{qd$Jt3GdCa9pPmGNgkrLT_2MiH39TWF)37G0leLFr=PmovdfKe~0X8>N@#rqfBT@SF5mFOrPY4s9k1W@&@CHH_O$sC=^Ovlu5G0?$Qh9WG}xPx!i z?aznN7M!aUltM=bV)*g*U4tn0!@PO97@kD@5TRTHDtEJvM9w)B+WCVx0Vh}%>jR@R z=A2)1c~QNpwQ@t+ydBT4PZ+F8#m86-EUr!c8QYfjr5Ie_Sw>S&@F8SMHlG?9L7WtO z5fQudBsiDkCG|S=Xi^bC7mTy%u{AL37C<}n3s8w?Lg(&KP2>n$PR&aFWjqDOz2eXx zf-QmRSj5K z5@9{yiZ~{a!Qn5IgNW$f6i%sp!O_fj7FQl5!rrPu?`vV6AR%g~e7E|dU%JN>CdA`j zLlYK-ZcPvmN~Q@*6?r2dBE{r4s9W=vMdl{~p=^}UZvuiW=g+S?scva!3((pmual#G z3JX#h)58>_W!-Db9q*Wl4;;!xC7Aw7I5_L1HBJg4k0q+>g5-W&W_?1ziA~kT+0Q@y zEIIpG8WNT_a_(>pb9L3!b_HGVl;&bR2tWIvw=Iz8yAL1WvjII==8En7&N|+Y_%m@M!Xw^9s}!eLk{_OGIoxP*B8iW_!N);syK3EAglb`i8flvaB*bDOY~ZH!dSf zDq;LLrV4mC5pP{v{gQWWk5RvuMj55CJ8Q!X1Y`P7`~Ov)a`644mU&oZNZJOn|5C(MTFIXz zgh{1#8D?t{)MFy%E4rIJ5%&tV6=O`Y`U0klY(*QT4^oF^>?~+vQ<->je-RH54CNl| zS0;PJ8_Gt1nilY7QTZu0XDIEhVtCIBL)8WFp#~nG>%1~6Jd7)*Qdp=~ZN4Tt>2YA< z1yZ9oX3kMg?wH%~)9_qFNrRTH;F~ufTBMeVsxVtp)VB8G6L%K#Dm?q+TRHNcZ_+L9 z!XDo|f+%h=!0*?2qAjo@Jb*kZ_J9?>EOGvYfbKYqZZ@}#NfIWx+)Fka2NVL;I^Bxl z)=Hzl%9>Al71D14{9yZS<7dFd>YLi9{f1Oh#BOyMLeHP^X}Shg>k6tbij0{^c+5FY z1K2nt*e4Vtd+L=hgt6w94l0@WgS=ZVy2fNWjkg~$sxeJreduy@Y;-Pd^SL=Uw*$)~ z6!{-mDr9)DiHWfxJEgY=@N4>Ge*>~D-`~lQ7U6rSyyC49;%Q#zkKDY83A0WOLoMPO zyLl!k=)v)Ziic^E^!m>WpMJ~FRC4;ccSq%JZ~Ed!-`6WNFEY7kU3Z%%nuYK75oaN+Vzy(&rC$YNG#%Ez@1LiLN{Kp6yyZ6x_x-9Wr*G~} z>WA@yI;f=kkR9D+t7l$>66&fv9K08=36nJ#-!X6M z#^q2*nlr;Jc^B-JrTmyUMDP-AIb*Fo67Be5OZ;4@A-~V@SM2tVe*#~QBGk>kx*<(z z;;WlE{}!Xn7}iiO3D^oAfDI=Dy@KyESK1tmTcp9mPHUKwEnFavl6Wqty-3g1glw^- z2HnTuYhAXOJ6~#&G7(5IL?0P34%Fb}8%_J41QRx;1G!v_5|mZyvVfbKX7@FXKAVx# zfQ+E>HqcSW&xbcRuWZO5@q$Y>bm}vA@omN1t_!+J!Ihl>W&Mi3y9f^}AF?!$$*kkG zw%zlo=BV3f=_3zi7^x3qB_m7+k8G&(bDYN{y}dXmurHlk;n)VnOlgT1LI%2Wv2KdA z(GNZXxQUIQZT>(@!`Dj}DH*y4ekgw0)UK6$pHDtU8^4};>AEVn%NIOro-O`zxe0xg z;y?t+ZkdMVjl!rizdm-Nii5WHRv_{@yz=!C($YUCOTk~wRUXl7Ec1TD0U z8JP-sh!b6yM(=z*0yqm=FS>VJkc`ccd7fE@r9q5Cq0)$f7A*mD>XTsDF#xGx;(rUO zJV@xf?W^`(rbTa2bNJpVI`;fb(KAEcovVJ25iq)h<4@(~R-s<@xrDtU$3nRgqO3bVitIGYEH6=NyMkb&5$jr$@WjLb43yCyNNuy2*q7S+3>3F3rP+}&G?Ce7Ie~!+vX$=Nc^&ZEjgGH#(y==*$W7Yx zj5_!!@B_<{#76br4H~T%%ge6N)sD@)?1-I>%#GGIa9S5#E%^rACdgvI1Y9?l=C}Ua zGvEcVrpF^$dR>P`_Hw~R7JWcH=*PkQp*l$Ai`!H}fkAkiD|7^>rU&iO~UEzd1 zeo)H0x072A8q>Qkf#0H(?CUdRAilLj({7SYHmdooHr}m8O;R%mv^!VIab7XIqAcNs z_Q?&yhK+^oC)cK2$Vj>yN5LolgT*MtzlNo&t6<{c>_3aP1(g=dyR>uwy3#^*pD*#B z=C;nE%DY}z4X^7B60O#>{cRA2F`c{V*`5OxdM3;Jwm^Oj7!x2JuA(04I@Pdu^xbk<4F&vaWJy*t75CeQGbycqyC z<~XqZb<0>8BZ#S?6&`Et{eS+O{c|seTibOT$DQ z5+~q{)^T!hzu;LCtpzlOAXKB{7+I@WLq5y5&ep-`lMNfOZ3 z^p$r?GpBwOij{zGoo#zUMpK$8tSGJ!WN)(@XUPgoB<26XVwa$USE#G1p&A?gq~2kA zD8sSg8{jj^cns)leY`K6eVWXF%yorV(m^bFQ|cQldkZ5_N95CQ3%ZA;O-@fN99KXV zjiAqv$Xd8peEvpxbXSB@TD%>xYOFF{$OY%g0Kjza68vqU|7;4%`yDD4V?UIkoo^}q zT9pTVt&(g>lpn~V+V(T6@wq3qLyx#GlJHU@f3}0AGUvCrflo-aWG`&ZLzXOEeJmqg zCqdHlEo(z&7$e_6?J!G7q&-Cy23u4B-n3k1z5^yUn|m;-p;FR;t(u1hVnw8YGOYuL{H_^@5cc zj>UiC=cFtQ%+G^$l1ytHH-Kn%=D;@M1DY5EOPunfCuru;+sKE>A43Z0#M0dnr*OFTrWEgZ1 zIeIgxgU$>_W2~3|_>D%vjSPfIe1S=pDMDqjXiNa1uN~>H173N=`qu|PrN}S(EHg2I zRT#j3fU6N=9RiA2zadr9G9+crdcwf9H<4tM=5 ze9xb$`)vG;&v&y&ll@2}YbtZIJ(#E&&%95{GP=fr*J~O){LU@Ce&r{243OxP{iS}o zHim3wcPF|{YVcvN6-A3{R!wX$Ymv^N_t;MqlB(M@+7-oT@nK$52 z)=0%zSo}Y0SEo^(62fiu0?@6Gy-%|tp(vibTa!FjO3L}FD=uX36gbfJY;A|vm1Uik z)5BA|-#0GR z@<|XDL)3H3IyPSSD=6nBldw;i{YS>L>#69lms;>MEOK^|3Hqw2a?XK%*h4ZkjhKrS z6MS((Gk=no(PfM0qPL@fQpH8@tvOJqo;`QQ?hQi${XCw6*65xUt$8!N{50ZghWU^O zhIiT@u(Z&(4S}1tpoh|atvox{kGchY6+h`g9 z`JgB&#c-wIV;eEjt=6o}>%~g+4R?84l1LuHEZ`gS$$k&fo3WiG13)M=7M7O;#C3%X zUEQ`pACw(}a|MJuXm;how0!z|PVSZMG8HT{YK0=xXzw6mdi0fu#lBjbl@8ulJbkgJ z3N9pE!{}eW6QmB&U1^EdX2<`UEa!Bm*?{NiV8u5@#6I`!nuEJ?Bq`aA)xaG?Zo(-& zR#@V5kH3zT@xCTj6_D92{Tzl%8>rngthkNa#vkoK^{wI=tkzOh_IBDchwEX^~}76RYb8NjRUG*nQsyz5$pNnITiQD z#2;q)W&!09(GgCJkWqSJ#dC4dFvuUZ2}D18x|pTrp*hQB3|aOpXliL z4j7oZ;E^FV2L3Uat`cIeRf=*$jJ0$PdAi4L!N3`(+4B=y>p9p0L0DV{*Fj{1R5}aGR(ln!ttx=1d2%(NTD&V+Syq8w_GM==a z!xp|@w~+${V~XXFo+z5Im~$?(jaKH|anMD4{Vc{k)m}5~!RV-V0U1x;=G|^o@3zdc z5rAD8tQehT?SEP#*WSH%SyK5|ie#5zE@AfC#$$OGT5G5@j44~kYnG*@Q*^Je=&BPu z`yDEtpl{i*fp(zw^3DJO(lGx*Xkg!Ux$=IJ?x~(LXo8KtA!LDhWawuFR=POt%tMowkx?Ow1!`K4i4qDx*REp#v|hj448A+bpwXIchL-`Q|eI)OfRaV?k^m znOEdf39sH0KLoC>5e8hi#Let5M*oL3u^nz$%Y2tkNuQ!)qcpZFQ!2C!;lMNhg@@vf zso0*P%e>}a5GW#_ihg|cVZ^JEVSQu&l>ScYheEQP>~>z{Z*YtPl%WOygROyzi45Sap0I zsL8lMXntPm6>+}&b+6UIy`?KIudV&YWxSlF zo9&;y_<3^Qu13iCdc=oSmA!(hEX(YSdf4DIYW<9lf-Is%1r=c;-rHP+%t-{gM2$tE zr$mLXfPaN-DysX;1)j-$4{i9N0fHh~kH;@vH^D}f}#~H+1{%Yt^ z^}HnW>$;(tg?G;Yea&~;w^qHdK$^E67CjbyYeQIf#t-dp!xUMILhg}Hgsh$O{H7NYd=PoF#JMK^e>Ga zSk&=61 z&wZxBr1&=}LsDJiaTy}CDq=*FSs99_?-KU};%yT#4Eu|Pwb@`v1??@^F9ak1={n@nPy zzN%-254ikU)%;}<--~C>ekbCd7n6qwPJoW!FOVJM!qX7oOS$`xtVMcJD^NloN)f9N zUyvu=P?(4mW!qAR*4wCQQlCgzGiHrw%~Jb2S6iFK)AE#ydmp*|SZ~+?N!P9Pi<@RY zemsQu?V(!HpgU(4)p}>Q*$?n?K>X?;&o(y#{O;j5(`YHpb2glB>_^Y|+GF z3{n3>)L90#)qh$ukY6E#1;M*e&F&fC8w-Q5c!=~r< z-y~*wV0~{v@|`h%z2S&g9kOKnQqQZb-SbrNu+Ea}!W+H+H0;572r~?5Y=zO%tFeXa zGxnM6*9OF{vq{mgu&r{#of!PS7SHc5{U4I;XOqHm-|sx#;koxTPIF2SM~UUY;N=3G zZEIKtf|Tih{Wa#&qRZ^@WIOXalk@EAlOJEHrcGe1Zx70SAm@|_l{5!zQ;DM_A`CvT z3AjY{?(3ib$=8=bvE<>d85h+;y_3CdGtmF~Wr4PeaU%n3up)!{?{-GHSIAuTNiL>D zD|A7!-83Ic(9IbOr#W)y-RHDQ*(m$M(*nO-0J0>OzY1_f*3?n&uzI8!Wn?LIjpCS{cp#>*=NHNr#gthjOKyT%M&Q! zkGCriAla4|f=s$?BK9WSn-Sj^>;}7Uawk)qDvZEBqxa39We8zmaAbpDBUR3Sva!VP z0rO)iNl&s?iUI~|jXpV-;s2nYKVZ;Ivihh5syQSB$~n>S2I6tV;&`2Vv;M{h63eel z99R&mxmW%uO%jURMgQ_$Wf18-Nop2|#HZ*R$Om3akY2&P8}A?UbX~`*boI|@1ePK! zoY)F7B!mw-b3Eu=-`IxWVt)l_tB{s_i85o(C1d`9ulUDBI7zm1I2WuB=kA2E;4mK< zJ3Fn$k1Ds@FLZ)vF^l#S+`(pPGh!JHn@PKD0Ot!pj;AqX22OG{s1@>BLe>*X;rS_9 z)UPVL^Qs2QDVeeYH8}7kv0F$wfZr5)wIjX77g%8^$+Lf(Nb3O8y< zcjM>CD$hoC4m@mIBpb8`ZGm`CQi>*Kkwr6E*JW;pe?b>ntFi-=9Hl0=%|EQroj-lG zKkG1EKiysn1jD8b^m6Ka!i;3h@G73O(VX2KeY!Z+?1wbdsJUNWbT9TnELO`19Yu*F zpMi|R($B`U=g7Jb;c1wk({D29a?^C;jOnCQ!7a#v8r~BP&}G zMOf0w5(n36+X!cns!wNb{RKP1=#6y{H3DPQCK+I7t|{q)q3ac=F0NoTs2cJF8g>S6 zTGerW`#%<-8~3ValKTT`Ezci4(C=Dw|9H&r&8$6k5oJ7|TPZ1kJcs&f5k=~l-Y$_p z_87sj!20%>^1ZGK-&0pn6~@qoK_d$UD1q&LQ=gIJ^u+%DMEUBc8s6h4Gt z?jvfm1*x_Acr>IpyBWryc3PdQ6raDih>zs~;gUQ8^Uq zBx>_>#u6h=PT~4vEta-S(n&v6!B^letMu zxVjwxJsj0id#@w_2`e!c5WjL5geEczbjEI#yU!ri-NlLl#sMlbcu|hIWo$<1Uf>Lc zrtM#F{Ib!NBuR{$)XsPs8_T}h$|G)h-#O{|h5G}W8M73P;R!kA*g!H0pJTa|`>glE z<{W-=K&FR69GjW@1qRNb9cEHItg(79xF!jfu2W&b07?P!45r}6wjT!Usda)4bmB|2 z*CxEV#|Z25*ZOB33tJ!iQBXWyhGHWFqu>cWpb@*;%KSS@Gc|;fn=SbUTursk7?PQCcc??ryI=Fqe!8Df;DL3)- z47JSKkyt(34(Bx2@sNhdG*eb$LHUYAxvELJC6o#GbP!^565RldZfV3h-pa*rf&0!V|Z`PKT6 zVAA1Vn*icfdQM7etYe|2o}DHi55;;1uNT0N$x@G^sSuS9E#AQ6ZIlpQ7>x zQemsUWBjPMvM&V(0mKw`Cf7*eFHE`BZW#I8HS&=N6(@-}+(l*`fq+4&6}VLyej=*+ z1>}L4f{m@zD*oE_aXTC9RZ>Xr%SghmM@5rISl7=HI0jnc13Y%ul_q`yQP6f>7wl=~d=&whiabB7y+1w1lwdmF4++Yi`ygijbtIcum`GSRm1K*i zlM$d2PL-BGKmECn^V9vNl^i!A`)M*#fxv|ePEfHwFCVO9%YM(X`xm;ELz!gSrk1JT zUl?}>u>!6#N(u-Ma+vn87ur$p{Jt)K>TlqHlK+)t%iABH}CHu&TT`~ zxs61*EA2dX2Pymeeo;h+?$6JTKuBkTz+)nXrq1jUDiqF3Fx^votDpoE*=H#Wzv`x~v3rBmC4FRQi$W%w#-e)p$dB;OF?i3?+;Um@QT@ z`9WNl0?wC|6W{VRE-0z&J!&)=Xk5c;GVDL-?C)67)~@FAJx`V)FEY zC113*$$|zgLpEeJQiikyo~igih@_tqCv{6)vjzWU=qAW5y}v}O{C>mr2u;^azwTU= zpt_{J{jeZ}3iZb;jRF&SOm6;F2?$9du&q zxy}@oblEgbcc?pM66ub`6Z_D^&{C>VBXU`~eY^s~ZBP>XcD*hSp*8(0W5k?uq`^*Z z4Q|MlXlE6j045fl)juECjV7`KW?nM+b-6HBZYm3gnAGTSow=SB_Jj7&p5NB>Q2Pmk zn0pZulh>x%`-H^|5-b#_#vy$Z|QFDT~9b*!(@Hhp0kw-s4YOn%H?@n>mM+51Qj(Upx#L z)?;YpvNoE)+xZ@tTA)^{KVAntY|t^d-nQNf=F5Y{@Tz$>!p~$w(c3#(zJ`gKS;ciM z&r7E3n7?6Aq$9JUT6|m!Y`xm+6!ZBE%yZnvN~nniV?^;G*`q*fniUOBH0HyZ!`A`H zY?tk2XNcmT+_q*3F4m}=yKV(dDR}h|tFg^;j-Fq&wyEEt#3heM=! zTreMZD~pfuO&?$qx(7Yf*n%8 zz_>?0p-2Dzx?m#QGzd;CdFZC#Xn@$~>sw5Z(7UE%w&~!o&6WMUoN9)@zcX9|1OdtZ z7Tk7daSb*gqz?%@(b6s-St15MioW1J`fjSHSB@ebt}#$@XB4IFF>!prZ{SdA#b<=T zi$e`A*;l`b(~edJ2=AZVY)JLCR40v*RWay(w^@1;|CBH46YX>RHwb(4v3GM7j#4V0 zr+v42k5N8I7E&p@1+MA-SPN^A;8kqc`<+Lg!o!GNVy#}hc|U^}x_d}A%V1_ELQTN1 z?yZ+r*Upv8zy;>T%BIReG4{`l9*pO{;`Sl$w#^`{m@dNy+BUR@-9uNF8ull_wRFA~ zC!~pK{o+wyS>K9L+uLGImw5j@9?Q1|p-5iVB&CogdXWR;|4j9)6?%%|DL5LJ(n3B_SIkATXFG2eQDVUKT1a8D@d{rW;ewqFg$j6UoS;@{b(Ho4!2OGwO}!f)EJ zd~es--V6$Qn9)J(V5%ZIzHt*tzd#@jThOsyn9Y$Btv;N+IiBawx3m%?MVD$>WRpG5PUXRpcDl5=u;o^zQ?oe zmBs9W1TCru=j>q0ncl9r1eS)z;KhTIBbPK^_W;lj3Q^A{!Fzpg9ljT2#$~a!^hq1(xtjwe|+g!KY|Osnndv8Z?g$@El==MIF)E%H>kN4;k& z#y)|>?K2R%L3un*<*O%lqEr{KKfqsDfvW0vl(qmWYkb)y{^Sil$Nb@l9HUU@FC;#E z?`UcHV(q;KvLbD|CXh)tq+T1R%&jCGKzfSa@MmaHs0{TJf=(DhD;Av%j@HE7rb01^ zBX%}7`d1|2C@o)%Au1^&h4&&>cuLU%IG%MMzj8zYQ!YxxyVSb~MO_JJSu1cer>~2I z{AXW`juPok_!dQs6FnCV$G4GpCKkdd(?LE22(t0Q+iRHGeBgLq_~Ma-7K;jqs0EBuT8UT+*{6Dp!lc;!a)Do#qtp!hj6cI2? zXUY{R8q+`k=adXfWPLznz!eOcg=_2#&CfwmF-dAi@MQErb_4MO+cy#XhDInSC!fb7 z;t};WN*9e3a&-?H*i3m>cpVZ#DSc5K=x5k?n2CU`md%W~83VuN#c)WSw`jgj+hH*Z z8wlZ)k@J=qb7xK6v?9rfV4{A1iye6(zSk#xqoR{VdbBF-)3IV9|KVQD-C4P4FI3rM zw5z6-mt4PD|C2k;gJsGqa#Eho%xr&SX?4w3ukOE_r#GQv*OJ%(TsbRD>iG#R510N5 zaUzXp>6y$yz#*adZ+FE_5#$#VM*TMOHvOSJb#V;nJxb5cb?U{h3CoTknJ0uGg`;aB zWJ#-Ya?nGp82agk&AuhVst) zu?B>_B{J@%ow-iyaws`Cw|5|)pl!Nc(PD$n-~6uG(2pVyU&te;rH2C zA!}w{_*7q&El@Y_GX=Vs9kVSeFui8vZI-K6(|PT9MAW5#1u(tAO8VSyxkYoqp@!1X zuG=eOJdNTraKhIhWQjdZK%cAk`=6VL5b%Tzj+ln> z47C8lngbgpKJO&Yr_PP#&gbag$6Y8;g4FPZ>J5MA$MBhV`ljW`PJNvJ1mBn#*(ZSm zrD@l;B+SBQC6=X!GkGQOr;Q>pcmA68e(A7A{9HYl)1R?dZxYuSeeEkEi)0?0K+rfm zf7IAtX;9ioqMdvnj&e(CYf|sJy=62_GmiI}_-Wh|6_Y~MX+8)2_r*OUZI!En4(2@J zHBrCbU!OX3$dAY!o$^a+bR5q@A4F<&K4sX#-PGvB8CGJ^G~qUV>M*MEHW-QAy{Y0h zr~jfEPg{C1h1H~*HOlVwxs?=!SL_pROq4SgP$HV+uGPV%5~XCndw^-;XLSg{_xj2P z9^4Lc*M30!9JNrOz5`rz705Ry?2j-q&1GbQW8yhAMR7rqI1jw^XM_MF`h9c-Nrw&a zRRl+5zTG?z3IV8`3K5aE90kY%+fibhAy~7(kiV5fg=;~rFfNrK8)oKqWOfT*T$y<{ zIRxE;);Bf=L@Er&g#u0EadZa&=@qCvSs*4v;-?_J+T>h2a4lx8$W!;J00y0(0r-&`R3)W7I)Q2)xTWwk%Squd>KZCT(V!c3^wPP;hW?w+Pwh zgvFJd^qX`{KgA#g>6r>oD~JC{F-Kw(kqBB9x)95R94}H{@FvR|Kb?@*2z|sFoj@=p zH-2|}iF#>L{ZlbTx(@kinnV(7Lh~4HYVF?D-$lZ|&O=KXld6kYgW$*YdFm&fe(RLz zVXa9z!$|f_CQ&L3wAX;o;yA{LRm7DF0NRuLqsMNt8*U@Bg{->wY@!>2x(%< zgZ*gMh;Prr{JA7!cC0w2cwdmlIm=%8OQD2Gzj#a;tZ^~j(!c#=#uL)SlQgrUYPw;5 z@O1jEMyt5f=*h=yh|C%i%KczXwh!l6HPB2}L!ox*taRv)Iq+Fk#DKdpI-TaaDz|u3 zuLiklH(Aww-5CysB7Q?ar-gU9|1u?~A?o*M? z()}f?ue^IE{`I=~_7r?B)vH^Iq>#j6N907HB6=<%)lkZ_1>44|T)cdS*MN3Ny`%Y8 zza!2~@NfdX`!QFb$ERSdDe8`}kGT=+8HkIy8@({Jp~H3A1LaSywD8`#`f(f8(+B)P zb9rz)7bv2+Kn2zN~^w*l3rexCs^vx02A1)^q@y`Nl zC-rrY>_u@PboYnT-`dBY$o##K6U}C)G-a_W6ZQ*EB@1_I=g%;dIF#=nx97e-Nz<-_ zs9oWD>1`_QRKKt>SOoOSwoNRxb?k8Upf{fr^^;!RJYHXpkyzgB%OraNorzf#z=?|({oCPKn(&n5l@#=8)EHC6>|CKO49Ftcn!bN73$pC*wuu2B7qrDJn; z!iL3Pzvdd=A{gZNcE<%)eBw|HD}1^6`}DQu6tnleP_yHgj3LVcgR8VfKfth)4y-(j z0+}Onp&E#O+AjM%C3f+8vkuz54?ZCs^g|C866(FXsXiHv>bV_TT@Y|dSDw*@drWA@ zDjq0euvX_*{tVq`Dq4_pzV-<%FCqkr0BqxYi%66Gh%RPCR9#-o2F0r#-82C^H`&AH zx45IoJ@O}WU^rmOxhwJ`$EOx)KX@%J>{+oCt$bAa8(|a#YDX%*>Q*+>jE5Vi2AZUZ z1`;Kk_$*{~r6r~4DB#DXFT;`RCe7Tz6|f8lX`s%;k|q=Ccl~qWPz7%&Jf=bC#>BS6 zvvn22Czs#AHGU^F?!|Y%W1mB_$?+EFLO~whAX@>-t14s^#?J&V!Uuhv)>V7T1&kM{tlZRHyV5NBEkqPEAokvc;l*(E|Lv~njKzI`3HGMfx zhBa@_oFrAaKR@XgQ2Rr^C!-Y}Rog#-c14_&Ua!^-TPw14zxp%Ns~L}iys>37Y3ya> zZfV4GQ)F?kwRY|BxDSxD%ZrOMUg%rCYR_1;lNQ)YamHZ^DL1NdS83^Yw^_4Q)Ktnn zx3$HY8^jLi-nzHu%f4{WpCy_E8!yp7dWKp=kfp?+Z@um|hFFWtl__^6U$u8{zMDqimj zAJX?{+9Lnsk4mQ< z?5h=gvQxz@bvy=N>V?|aJovVMwvOEWbgp5qljV~{3I?1J_*y?F3{I8--KjCUgY^iO zeyw_c+ck;12!+(5kc@a?J|cH%=T#z4le`Ds(4FI-Q-E;>eJzZ?Y^3nSjC{o3UjdL8 zqlmLZ)xUX8&JuSOEDY)bd=)%<%L3;-kI9mck^jAG5K(BozVUo(1Qcd{KTac`*NdRm z-;uR5iQ2~(fA5)#>^Aj&O)@ngH@MGNuW6;+%*fyE*!+1CxUH! z#{@&o;H&j^%c9co)|BO^{NLIrXC0n#A!iDd$!wnjh#=a&w8LK8N`e)^btICd-q?bOi7+Y zxDzyl@=|Sabu@IVGB?{^`NxO6nL8HdkbYU6a9Wq`HeF-ZWz=gX1h-#fW_6Z(*s7{G zzIbdE6~i!P>eV74Id{t1e4=M+31;f2t~Ipk6M_9AonkR;3i9rPp-k%JbXUWk0N1YN zM6U-EdbNkMuK^$ScXb@QslPkUks4joy#>UDP|dXA+~7^mJ(dan?G4a-+ab#RdpC-b7B z1VAqSzPfE1wJ2K-uXcokzDN3PbGPxG+YBor!P;s{NF6!JD&NpmopJdC?RnwEJyBdf zDAS1ETr%UEXA&bN!$l{L<>z+|Ej;LMgmA&A)9PgsPE$k_%tpKOM*#khwuB zyz6ZvH!didI4#3a&1`(>5Ff!Dg){X+U*MiAtZ5nL=guTU*RAgq=dKCoJ3(_ClX&KK zY(y!ff8X1sK#1l1uoDT6mx?u!DHlleTp+^v_l*A*#r)p_Y6?auM?(u)<@dz52oj~> z#D$VvW=Yv17g$$J*> zA7bJpG(j@~GULlbK7K-I8hp`%M$qeC3vhfp;cMfz7uNiRK`FzJ=g3IpCqNv&C7)y( z%c~HCI8s4bqFVZ%NOB5ZITi<#|6}v^P%#0*dg=DLx~XYLoK-@u9DmaP=AyXCZddQ_$7h_2RLHI;|!pru+Qh}zm> zG4XNVJz=;D#$nL={;&Ts(JHHg+UVI~)Y7Zq26bu<(gCUz2)aQzOK zuj0K$5`qIXi-zDSuoe4NB>ou4Rx}ApP@mupMZFIgL<4)>?~Bn(*m(c@#Ng+LM7rCxA#ObdD$!yUDsq7F}&|M# z_dg1|`+eyPc)vqc&!2ptcx`zN2{DjTkSZnzq$3hI12VHnZoL7|G-Pk-@~;9h8^50+ z9@4SHzcO5B7MNaf{M%iEPsS5Y6=N<%RhFvCtZ}@WM%EBs9U?l=38j_>*8o|oXu}j= z2l*b)q%{{5&Z}h=6KNCXOFWB3OdJbdv-%K#CIy zD#QrWqxZhyxj}*VZI$tkz~4(`m|^TgwpIv@r9N6-hrUnQ;x^ZQlyAym`xh@Llb4aR1IGH4mWjW+X=ghf zpNTvU@B};6$xQ(Q;vPmt1tm0EF+@atEF1y?oqNsK9z+vbDFey_2j*~U@WAH?&w6#OBv|HlF}^lN_UjFX9~Lhzy3(+iJz{NsH6 z{ttO#)$VmhaE}PfY+>ekUc`up_IFyooGPF6%s9OtB|1Y^f+#4-bcCLS2(>6`csZ)g zKU-EWq@4+e;obS5!jM!#bB7Nl;ZR<5s`oGwo(QTf=Mw!XAcY|DzOOP@hap*3K zhc3ActNg>U%mBRjVZtH00{dc!oen+L7Zm@1^#kk(@g(kLI)$3Vl~koX^Io&};ct%T z)X46rb^VsJ#>nIx9#?Wd(8m{@Q~RmmNvwktL<@7(n=-B3bixOR2O1go1S1>On)#=` ze+sTz@78QYMr9XbjMXL)G`jY;5Sa)=qVA#_5?F$BBFGA$U{h%*W@5tgQieb+N$H6z z@nJ;v02)d;Vm+Lg2e*xCxT4m{9?Drvq&X_Q(CGUurtsZ)aseo0B_83sO}Kxlh4Swo zsczf2o{rgXVs?eZM#60?*hJm3!Z}ImyP%2V(%DGMYEdsHHOZLof$eem^CbK{9m$oZcV_<`1=U@#k7exe-uqMn4P zQw12#9=J^iEn-`C!Z{D6Q=r;M`=H8c~CKhg6prf1#OLqEgwj{U$&b*Wx^&H}6p zV#cHHuW#ds#q$~gedIr(HAV=G!GEWIE!>OoPYj(PM}ZHF0{bZowgW_2Qz&lHCO?WmsR2zUBUYo7cRXU+Sb z>fRoAe={sL@ZAT8Y0ob_$+tfuXnYipyYOe-kCS*2@2VHJ^_+w!Tr$0AvpPk=rRP8r zomf&VD8zNtRjBSKS4}U;vMx~3>aU;H3)ZN>4{@(VH-~0kh-2}Y?<0AoxMW2bo-MDf z6D2HUBYz&^=euiBxoD?w@A^Y1RqAg5QggQ=E9ZR>Es7g3t&cOqLN-^tVS@OWa@){l z)r%e5eX&VGrm7|drXaf;t7-Cz5wVC-yL;uH?3Nu?}tjlUb zwGNvJ@N|)7Mmd{i#r1;cv}gTD6OprvrGOv2p7L<%qW`95ok#y6UM-F# zIUoJ(*lEy)!eahIr`g0-JkUUE_Y9G*u8Iq9ZRg=PXo z0LBhmhenCd4t>PQ^0muF4(_4|e+%i>tURKF;pBJ#cfm&`_v zSXW-(W`$O2*8tJs&iE@nGO7H%0x=sG>E|MwlZlruQ9MuOcxXZ1t3ar`k3}Y_7^5$` z8HQCR&@|Q*ur8e}myFy=f4$7T&Zo=O_@CGlEy5LOI<`9DFV-u_0?$SN5B{GPSfX)4 zV$K#2ur50J4xGFdKK5?w>d~ITO=!7-?KruTEN$r*!_)j^o(`KQ3OHLPkJa3|0KNno z`Xe8tH^^7gG6vQo)d)Fd^Htpq1^-t^_%(SH`g~90F3uhkIr(o`$6g0&2M=m&TMxJa z!+4gJraHkC{|!0Z7T27>#om-jyBQ24_myhT$Ig|vw+=Ht$NYUd+cxs*h@5Gjq^VwW zSyxAE=CjTb`^ElK7GhRiWgW7nF7*@p0pW3ELd|hO_WQ)c1(J>G`5Ybv2qciFO%jN8 z!0g*CEK*UCyA>e*0X(2>C$@2{Vje$t8X`;Sqn9{)lOw! z|3Ni=+HWBE_HF3|?r}i=3Yop`NSr+!#^9A(=2=;V#=9o7p4Tnt|ILrN+87r+2qfrR zS{;8j>>b+iUPtL!A7sXsj2MRY*`DtnektSX(lzI{zBpp^J@oF`*Kv3Vd|^ND)8lF! z;6W=`s7aFi*cyzuDZhNg*!|R!5+n>8qn6Ta!bBvVDEGDY!B9U@G9lf^>)JqP{(o9= zO^fWmYXASlmInIdOuSk@=9fJcSy(LcMFlZSEQmU1yFkZ?*4yI3LQbJR)> zU18cq07QhKFBH1a>h^P0pgMag-q=U$i#ab;J92~OwaRF3`YkZ^wBWFnQpKp{W7&R8 zha5PFVI$#!GnnredAqhpCaK@`t;d-&WofU|_useg?`gLE!V`p5m;HYHH+L-)rRImi z-rNYiepwVLX_sLKKB%}z(Uoej*UAq_gW)z0Un|SGgID(O&y~~@gL#;x{b0?YF*yba z=P&;;#d$ydx4Y2%6eyf||>Gkz#$xsCx}*Q`*;e-F4MoGBWQpK(oCQ{M`o?90N2 z6d>H^{JkGvnjww^#`NOrOa&6($OGOl9#W3oYY(pCwy}7Kd9=!NItv#D;=OI46^cDP ziHqj42e>#auzjV}Z}_mCto{2BSFM@VaXGXHcKiyKr+Jllifn%dj!zQs8J}N0Z>2*X zXgtDHrs(T;6OTrj=5h{_xtD-caqbptsNLMNHY-aBk}X=p-<`YVJsKax_vnI4x+6*O zU1=FT$(|dKq{MX~tFslm$2WoyF}r6LBuVdqC)ZWgw!@av@5e1Pzcnn`)zF1t%sh1* zIqX{zbo-E(o@XbrPmf9p$V>L*!3p?+aDtILxg7tWmXp8$t-NPna-I3D$$%9%j+B`# z>)qq9+MYSGj^cNH-5AiC?8))eDw@Nq+`{X{z{}S;!a6J+lmSwRY{jiW6D0uIbK(#l z@s~u-3f6J2W3D{=#uPD1&&fbgpaNJ}Tj)u$29FX%DoMo3N$JpY|zMtrJZTe3xgk}ZC zY|6y*9-4UrqjWd809+tp$^$Nd;SV+9`q=2CFsbk)1fg5g)0ltJJ~fPGcMZ{_o#yy( zCf+Adk-v@)YAp;np`{br1;10Cp+Mw-UnwR@5#_IeXGqG5VwP`)G{j<(En+oZSD#bSb(R=;hpQT6^{3f#Uvkr5iny=#OJlpq}dP<8RE zbB#?7!#&#efN*oSh83bm!XSqt!jzz4V)8Jq2rE-XE@K6G(69|nb`#||O`GlUf^`t$ z(Je;Z;0+*FiJNlD z61viM($Bnih&yz16nhKK>M{E8#Dm)gUrUn=JYYid=tgYaz>d z3tyau8t!s*D=WN(V#Lm#=K7aG%C2`bf>stcPOXo4dd+g())TSg4fCzDia7_d@HlSj<$uu zg+K8Llasi!s!n0hSTM(+Y)V<2Ad^Y!Vqav!(aY(L_~YNBQhaNoiN8|q7J<)Kz^~X2 zLdnHly~LMA##CO2aVKX{|E$U zoHaS%*Sv^$@cKBeHkg<+njQJKFV4cq;|?b#sm0LNR9^`U>>V!6EJ`GY`F~vsG1;3df?wdYYcJX zt$$clj-vrK+~*+>4%B;~NUDTgH*l6f{+-*-j6JwO+q~mAo$pBFE#|I!Un1>P+f4uH z>}-EZ>}+S0AhTv|&ilwc%k%Tm_}!|%8A77$4ThR zcZUhbg9P)z{!Uk>SA=$EfU&yU_J!=I>HqkG!~hv~CCFe%f0u^UnSnA9Dmf+YM#zzA z_qEY@Tn9`raw0VyP{@pX(Ay^*HwYKTHi&NoLE;V?i*bsuRqVJ^;}f~CLRv7=GVtO7 zG}rP%n`==6@}Ug=JY>_k%L+D6y;jKbbszsd<>=?^`-tN9|6uU@W_9qNEbI`YJ^3YL z{pYysRQ>2Znu2pYYHMlZHBrAdQ^9~gJXD0@vmtnGM6>uC5c@rfE1PtF&{FgnYc_-TrYRyz-Y5Yc&>Vw zeJ$mIXSHBubII5cwne(%7NnTMpQ3#eD5kphurTD3t(xZ+mU5yXEeK<~1!`oWS@3=U zM8~#VPlVnWk$0%c`EV1dcWpxegA>MES|{QWWRc!bhi@b7xT^f)SNT|LG_)`eU_}pC zK1U)@9Npdz!rVriq$sfJ%7j{5j&=){wU)%0oex=`vD#uuHaP2ofb>RN?*c{qH`@k8OiTy|fSVNTyVlQaqiuFZsKs12Vi2p)qZ?b{q zh;?h6hdxt;kwUvr$V)u0a;i_h4&3L}qjPkrG2@BU!yD=CMD@lsiZ|j7USXgA;+XXp z-4Rdrmshj-p&%B)o0{a19(hJ;Yk=Swv=Nm$!DVF=O3VUpioPulbNksc`YYE(;lIwN zAhSrIo211@-RDJK^HD%2;5YB4|I8LPw(_;x3y`^~Wg*iZ8aUtI5%u$HXPjRGGzovH}; zLEWz>(&bAxoe=*Cm$n41c$?O^;L(J^?(i?*9n0rRQuje@a_g1%#KkR^YFW@dmw~;9 zQNP4UI29KO0qa$l{L%TtM;|A$3J+c%RBD9_JHCzDk$|UmySs2ivX8ifvuB4m1rmCT z_5aPLx9~Rby8j(2_jg?gUnT(j050O`59`iaFhTSWPqH>xmY4jtoqU+oL0A!qE5|>A z9%-x_2JfcHXCM}Wt&ulV+bt*YSA}02``TsPD+Y#mE;Har#;<-(4-J2j>9>oD!F~4? zBs*|E5O?d@B-(I`u1S)iY2GQF^ zG&OR_dn01@q}SDY(h_i-BgzB2O0cPBos{<}|3paI^03=4MZ z`&n(?wZG~(H|QGCJh8!I7vlS3NaT~t{!pu~Fwqs>YJKPDwR5=R@fWi0FCcAg*Km=I zi6c##jk)zVCh%ko7BTup)SbvX1af3@mEkM*xsKtKOOtw(Ixq2%3NUNaa@ES!m`7%7LB|rPj0wA^ubL^axGw4AT} z`O`8cD%$>gjsK9Wd*c`e=m{<>f!p4ZKsa&DpU8r*OB72dn*u2h_rs`qUrzgk3`7G9 zZI*ZJ1# z3@5wwT;|c|?}0#bu#n@T5tzg+xKBcK&Q*-K1=fEhwRy>4buWGLR8q#Ouv|-S$Akvi zwjZ}3MZ3)F^!N4)?TK|6l#awq7Y`sOmR zM5KS~rZ~#QyRd(G57{B6(Bq{NOC;++z(Q(sm@P8HzB4( z3M36R&G5KiL>$@j3IM;Dhe>JlY!I*|+tr%XBa1xKo`3A0(lTe`B+#|; z{!%2)H2^F)<|4Hck*{5;o2#>u;Z?Pp=bk!FCb%%I`py&dnU@Oh-iV zP2PL`w9TuAaXwQ?9vS_P{=7|FalKsVzI47;*GRJ*B{}i`C`;36)>5?qe(#IX$&oqK zFxqXvnh478wmjToO#4#;WS-H$MRJq@{YD5vG^i>$MU!;Htlavk9VqTJ9vD^yedq#% zDu7koWHJ|G@k;#UB-AbQu8&?uC=E{N+M~3TJm0>jgC~(}?lNzn@FicDq`1tV-YVr% zgO|`k+&F1i7Bz9R3#7_fZsnUtf9T6-qANHf5Zc=D5A$T{SYK?LssVB)ct8yr$;kSTdbtf=Tf&FZBgWoI{bC*T>BhK4P}Fb z4i>Vz?42=dYqni7wd~n)f()20=9om$*XRx0w@1BC#PGcvDb2N8Et(nq+jHq=EWV@^ z!J%pnK5f81iya7*nB(-E$X<``BfZ#N4~=M|!DdgnMWTq=2XPU!wpfcl$|bCKl*mYf zol26bcY;;6KLIr;5`#hs7Jl7y8l;+|lS(Dzw$vmv%vwk*B=nmQcv+tpmU=R;7bJug zUM;_wxMP_dIqyjD-ku-^H!C&_v#)bS^I2<9EqgUM+dpuKPAan}ZIeaG-vb_s;&Rc~ zyrH_{9?gUJ%xKZZv3Is#pO?!bXNnCvS$HQPL&0BM`5H4|h_3piS3&N4+H-C@S2Fw4 z3MvOL=0iaiXNS$s;T}QX^H;9*n-IPv0t#kmJKXTlh`e3ixJ&Cx84kI?_acSJG2i!X_i$fwSZ%!rMe_r)!wLBgj<_Sgg(&WWzI1KJ!%blQU3ONR06BHOB$RNb^(=qd)NjiyMOT{2kle7#lI?>3d z;2ld5ev93iXGA0c!76fT7D6}pe>A=IL(|{;K2G21tW+4JKV91SG$EzCPdgAF#&{=bW8$U-xz0*YynO>6A(mkqn-*r8DCZ zaz!zajrBNC#LYL7ZHOz!dr5oehk*%CiT47K$bt#hOy$lo!kLnyhCQlEmm# zf<6CS+LNJgrZTZV<&5P1V|QWGcSzas)VR-_$|!Z_ngD%|Rs5M|;2e=c z*U2KR9b0U$Y1jW0kJ#=x4t1u-uQrJp=6Z&LKnT8tz$sRJ9~S?tbzmqd|A}*VH~NJo z4eCXBiSsq^GmcxUe1G>i3Mv}^NKTXOQG|Gj$n^$S(f)YCb@a$FL?Hn+2s;?07Yp9v zv3xT-J$+W-z_N~Sg!xabk=Ur#ydBg@(C*CWWt$*LEy-NmgbtV$Or8#ckHi73e>C=DPq_Fw7aSPVV<# zUrs*AP5eg~=x(+#TP7_&0CK3~1NRyAk4K>xnwW{Z2ise=g7TFZ-t$W3ptnAP>sBx9 zbDsCH#rpTVXy;3#jgZ&ye$g@mDJf$GnQ1=JE;sN#r(;|WK(v8pj*4-11q;jvMObuxPNg~3n3(G=| zzm%QTl3iCQ>+L4LbocpE)R1M5h8IvNMFla;eiURX!A<~)GZ?}N(^acr&S<%IzV@7zN*by&fZwn=wX6FCnWZE zy@AVa3HkM4`fAa9b@@*s;qCb@)`J&|Z(wJWR8UbMGwb(;!gs)f8SqCVZ2f0uZ*rk9 z3`FZNwDXdSNZr$`BhOxL9m`ie4GVy$Yt>eCnr+fRku4J$-DY%XbJ~oh) zNi-uIn#6YYi_?iH9-$FkDamZ+iSm+_Ez4GD9jZ7MO?pDTs)-jA+DXku98Mt^lBv)} z#cbRk!7*8#Gu%8>gkWA8HQu6D{;}vdG1Hr(huKW23<;|%?T8B;vz8l5g81DW#_pZ= zMzbDS|CrJy4MErt*tW*q(qH|IlQkb9Xm`}l`*G&aE-P#WwLzHFc&+$2-lqHkq`B1qmH;^4|I%p+>DLI&}Q4Q z3}8#9LRm3uqmnoU{9-oRvY}jpn%>)T&i!wWkDg<^wRu9nIv@O-^^qI7Zn&K_4Q^qoIv>@kHgGUNxZ=gR*IzB8 zXm5<-rN`Q^+wT85CL4sgU19lC2hP-evP;ZXraVo=%FODGGeTyu0ovc7EA3_JYY&7m zK+X|PtOOYyunalEZt>bPeaCPv;aco}16o;M9kCs>(cE@4!n{mBZG>w2=ER4xo{brx zO}^2VYVM1!Qp5f4;%DP5;3m}#crv#2S~fJ{j4=TMQu?xgUP+`i)xrM7Ol_~uVvDAlDZXDL(G7uoT3RcF+WG;O9M zMSSl%AS;RP&Jq?FzRLN)XMgusQ!y~3Zk{Hb$C$stZ`4j2XgngmD;pg;;zd0wG+_VN z6urDodxw9f>{?oE%9e$zY&9r81(j?4B8yL|wQzY9c?-xTLXSV{V2PvEmZ=`11+&$h zrFv?#1BY`==?x>w6n{8xHAYceDro zS${D$?pczu7RMp|=W{QvleB9AxX$J^MOv`;;DN?39`!p5?GD%kP&RgFxUTxxt4I+I4CrFY%=-X%;#e-zX<|4^#UGh^y_*= zQLDBClDCb$gNrne7iU|GKUI&<3|1I+xJj#2rcw?KQ)My2c=7JhqB^3 z<#E$@wif|J&*>9urAue36SC^UaBy5%u63qQwqX@wG3wYCZ8nqC$^!HZIon@KmO9ECA1)R;rs%Q!!@|!5X3gWl z-)u6`Ff+j4>Um7Pk-he45EDn@q|r0IR|Vdb`amnX$hz#Qd$8ne&%F{JpPveUT1QR7Xw>dU5yTAzb>LAqpFU5YCc8To z$^sE+NpCC1@$UY%<=}U?Nt4Rf;k%`qoUB&~zQj#rUG5fe5)c=TgptjsUP4a3c=*%p zK@S>TG5m0`20w09vZMt+mX6um_~YM}7wU&f7kDLR^$ekpjO{GymYDV0A2)yeQD~J@ z_cr$Q_1U=yJ~BO^JK}W9L z#YrTEOLFpk=^JdZ36fSxZx!*HfMTtae%T+Go25*8A3xTQlSywni36Jm|EW4AXyE@r)%Y$w1|_;th1Q}2fK`pa-RU;@1AT8 zex$tTZorGKgJGFqQfdgii=v=^unb2^s&l}Ca1WS%Yy_NUvfcF&7mRFgyL)1$BR0bf zY81JzwVAB}_gZR$N@}Y8Pz(f7Gz0FZ7I&`%lLjH%IT%xcb$@Y1=ihvHNay4Rb^y;HM)=&ad z0BWs=cOcK29j0XWwg(#Y)nw@I-LEC->&o6b0tgBGW&=g@>E{m}J4Z9skA6&*KC{rO zOlk28-tuRj-$9K}X2y1tCFWMVzhh59APY+o1@nQTq)xhtSF^!q!D(;t@`w(Zr(aod zZBilL^@FI}v^G72<-FSv*l|pT@4e*R(mb;IwZ&X>E(EgkVFPMQLR%5(}k(u>T&^>56hyvVzh{5P_X)is4FnRPu=&R6&>8u{tF%PJQDVv5OOQq-}5f~B*A!X z|G}~MSsuu<)6i7 zhn}-H+A7f5teA)kx4?Jksh)S055==g6r?1Qg?3M82Xljeyu?;JD%=u8-y5kky@iJ2 z>u0xKjdoICgA4V{(m^Hb3W(`c+rv|l>u)xFe-%0K^=WucWokAA)+5JfWJQUG6$mSZ zob>(>f>#|_e^q?ul5j6ny676SO2ZwvtB=|2$kE+;5PaXnV$#^L_fBiZ*pz(d-m9JhyYU>r*-_mcZdcWS_> zynW<+&JA9j&hKuRs`37Z5VVopICJ$92l&hb%G}FPhU32?2yuU zU(ZoV@&EK8H>NjFL>uqR)2-{mTd}JXRUXmmCINyo{)gJ6jDdB!L*rOk4-PMRkgJk7 zu5gK6x8D>eX|RZLMP^PFZu}EAs>s-CNSnnc7R2G_s9`)Ld({4IRg`>CT~C`w=WQO{ z(^kxq%H1;ez3yiaU#|1uaSP%P+}VJ#tjt=Nx00Ie)r3K#&R~N716SmeJGsVQ^QZ=e zMr%8FF@+G;ABl$Cr%KMWh9`D1@Q{2-$9<*C++_f*OVZkj90U~{14vsG>P+9ByY)62 zy(ST$xsHb3e*O03B-?0v6D#t^{ht2yc>_6V$43k{Gc>8q;7)hh$5)a}s`ICW@ zfi;1l5zfz>(Jq{2QgvF;pIA^@@W4#8Ep)A!X-)ONZ&@+Q8>Yb!A0#?s@c^1MhotQ zC+q_9uu#p(X_|K{ihqtv&!LXR2bfXwPFA^Y?kvCOoAaVwDcf^Zh#`hkZO4bUv>4ge zDj^zmHU~G1{AB%pp!tnb9+u;0n)O^sh?qX|(~b?Rnfgtbm)|=j{jR@e}?_ z)*F;4{AQCi>8hHa{(zL7|F7=1(>8PrggY)H1$4B(3+GsJrR-gw&4}^F`aubM-_W8~ zke|@Wdj?1XCPKDfB0_eD$ZTwPKtg+yB=VfY9(jMRV<+>$#O&AgF@y2qr>P}Dtf&qB zphSJ#{4bwbjts}{$VwtU3Sf=?m~yeNPnYQJEGLN#5j5(w{uHR>A5 zNoNC{iOyt8v1hF#g80pg)^WPczX=|w)%HnJc6fYA}1-qb@U{O5Li zOG*yMf~?bTPbLuME{f81+#m{mi5k?{S*#A04^TId65uue_84|OU#-3jmF8gr@^^=?*Lz?flicV?84>Sy=sFUikC%8 zV~jEF#ZE(sYDKO+K1_^4Hkrz?9*`wTvK1}ea(p7Bla>$^pGNn>@VLwvWFXS|q-{3l0jw5M6+(benop2C&JofN)W{<kVNA+oXw9pAqFEpmq4Pp139+tV?P-=Bfeo*KA=H9SGkHuY~dd|(iYJ?G}z+7rxPI}5! zYU%IP7pWr75HplVuE#m(=3nR_vAZez^qXU5hZtdlVtr(;A4bC~xRgejxL)TI^*e7% ztDOeNDWW{egpuO5p9oo4`&Y@5-bnKGEKVbxF%Xwg0?JKz{8h{;%~$pi)SqTFcZrUF z zZj9c*(-k!_jPZnGD3;YSikgHHh1FSy8$HcjxPpbvDJ0oc5>Iok!{#wf;yVofP(8#a z+#z`LoSZ;=<5_Ip7zyJeTzk=WIN(vp`VN?{b^^K!@ z=y1oK0hE`G5zlI>N21sp?{oFH9Kv#;0`6%8aa3Ymk?7c2>=Rsc#9pmF zk_VYL+Kj;Lnq@7(=lgtmbuSru*X&&5{2=t&G_j})XQojtiuGv9QLzc%_ERBSuip~c z;4g_egh^!UaMILUg`5}4w^(}8R)W-TW5~ZkNbX6rp?3dl!6tMDy^T>qQkT6>*@5HGLWs~%l@8` zVx9f|RF5B9^l#^$ow|&$fR-am3)!)R}WU+TasNyMRj<2rHpvMsNUYAk=frA z*M+?&n+M^|X#W=TTlpwV>O{~icfi;S+qy&?VkWGYnzk=76`wQoRi$zWdN%z`ZFqT5 z3}s>GZi`*MEYba&e*3po2*Px#tr%U912us+!c<}aoaq0Y_k8nZU4yddiu187E<3W`Itl%5|FN3|5)8euY!cyeDc3d~?JOF^}nDC={C%uMkYWY$hU zeB`+}flYLDTpw-RQv=GVwhM|Dl{BXOrX~wSgU0Q_VJ)reUMMf|Y{U4;sM(!Xe1d#g zT0m5~8R}o~uwyM~hN?5EWyo82skjZq-~C7q!N8ehBsb^7GmV^$)77&xRn*%T5iZNZ z1}K^yh;uyg85p(Jh{f?z%PXBHpcD}6i&lK%ioWVom__>;hzvykJi@V-_$ok3UKWA8 z=#<4tj>yVF9Tk#dq6;Om$kGGIw4UHpjwGx(P4(uvu43Aj3Wg+b3L>aTWEV{Yxtnte zCocx=dwk@Ku@_FX=09(?UTS?cF)8Q%$0x+r(xf;;uEMTAT&PHZfzEYp(NV(ii@{eetYi zyeG%=mL!n}?nRFu=835V0?2jqqoHKM;Ppa?%)my!jfbCj!4J1p9;%u@hg6DtKEp{c;pc@=I!V!zKHeqsbZ|&@qY*?h#v{ zE)u4d_QI!jVc(g>OAT}Nd+Y$jZ=BmPFx*L^0?GZ-5_c$~JY|Dt?z0Vu%vn!;`#Avr zl%&I$FywU+_#DWTl(6Br?$W(C@ z)I?c$GW{~i9$~98h`M4_#+INhw@e<{xl)i#EI`_ZeoA@-g{8r5qbQB_WxnSw{h09j zT__K_vs2)VikWjSi4TJUkc5cA^mwAUQ|euI{REYaQV-)|;St)Qo4sS#(ku7vjx}hK z_R}xm{k*eW9SjSq>X$*w@h9lwaRLx(fy~CU`WmdfAPsFHlUgRo#Z>^~clO55yz6Ad zAH8I0`2gb~U-l^3NLT1{UU=ddsFCdez<%>-+{svk%rAZ!qAc9}$` znfsp;vyLpyGM_gJq_KsB)yahD?=&UPx}>}a{9w^a9{_ZcNvU+5lMTggnqeX!RFD z(4o1X{nvG!qSwJh|2ib{wE9XGJ*^&TEn~0~@v}}E27lu#De)eiXW=@Xg}@@{aqOIO z>p;zE*xy%!jyHOx~kDTk}>IIu=p=ITcr;>0B>)bH3pLHEVMw-M?cDM1x$u;&4 zBI_XIe*3xVs7UeOnscSzaUE78h-mn8=`hJ#Ik{hJN90PM&+hPWu7L4xEO}J!l>z-{PqK3 z!7^SFXMoF6GoyW*n01vPf)XaAV5BkoT67KxP7vhWz(4;?DyDgLwL0&xY(TXGUF6TL zjhEtV=VT@gF3(|Jsjd9Dpfi&tJL<4*mqG{KzQP8{jbH2|F1{sJz}Neq2Z5baC{Km%i~w_r0O7+qW){GI;o z=*Aiq?L7AU#;p$jFRdlx_hD42*42`9O^yk_n)7m1T!-2$e;?-)Dw6zDsaa)!z=a`4 zKU8NbL0-?1-u-*_7RJ#Mt5{y_+N@hU<+95eVHu-fv`{jD;=tMF-cJ1RdRIM9H=$FS z;i@N|UZ^eu3Ik3So?12SGHO+Q@#lj7?it|#gZPibb-3$>fkqpLD-!q~i694LbCScRb0g-RU+_;v z48g(o+=6_e1RBl&rU3OQoxYoWOI&TLPMdmikBN<3VJ$S19z`rT8M2KhQ+xO_oGu+BGK*OI2{5^xd+U_%n&&DjvTvYHKM%pwt zJrNlwKxRi@xw4V!>FST#W@E0FX8hWXdbi%Q=cvKkh!BS8>C98-w!p=AFlx}_cln&# z*6Qi!p5q38Tp}Kw;q4?5PXfcr1@hCN&-TUVd(t_8u(|V;vnZSc$T*>F`=Ocu_AMxDJ3KSxsuu1_)1z3`{q{ z64KLTtJm=>Uh~Z@kX*U#G@!n?Yz3$&>HKObgNo1*rBu^jqUuXnTk?Ne08>4!l7BPx zc8lk<&(p8GFz49#FqPm@c>T7PdCs!`>*9%+dZo;of;S84goW^9n^j8;F)*G#Q7c5! zz85aZWq#ti*CoX+6v^4SK%L5UBu06I|EDemqx9XKekc6FN!$WVN0y&#N*O}`I+Z4l zr~~!#FhtoGJ99Qp72pAcFMB|5W}@BjPfw=6Tw(wDm8nQBt+=Np|r0|ov&4Y)xv^B9f!cumb z%BB=bB_O@ejzUqiXHznK@Q_pg^;aH+0^AN<{|^O7jMMR5*JZ-OO&P*Nl9wzF4mA-@ zlZ#8LV4el5@4GF5qK&3D;RrDqf1gss48HTPPWMu@K-*V1WF}rSo;&gT`%G8zgN@PlTLm@^c zII<5MKncY>6;|>i@K#r{QpIGBPQi@Kf3iEKY#DvXT4Jgon|-q|MK#1_yMnmfa;j7= z+tO+xjV}AV8=XQO>1TaMW@C`6Z{;dz*YRLp{jSXkP8QouIKR~cWL^n@nDY1oPhxm z1hBZfzM3WXV@gO>@c(&&hKWmUYMDYDq!!<;EGIw>2UT0ucBs|CCjRZ&gTL`jknCPJqg7OI?e6_)Ew}HdA-;EqLc33m7bQVj_MgH!DNwajN^v++ zOu#lCgl`!RTzHMoLpjWi=6nOoZoa<7wKu$X=J{kULXQEzKEHAUhRiNBQmsv~atUD| z&is&)$}y_Ntgr80!W~BlfrhCk_iwJc4wX9=is`&3AKpJ0-E@nJ;!w*DlC8Y4z0V$< z-%#XkECy!MfUV3GE|6tr0xPIrCrnO6#tQY}WSVtWBFL%>Q$^T)@_8nHO1Me!-Ko8)I}&gsIE$@qMc*N=_u0DxELMwxX4gVLE* zzs!?JMN2&uujp_5;hgcH5{$mM=3Y&N#3h7WqGK_#p`^%_jehR;EN$ ze|zn}%`?AjPfK)CW>UAnti%{KR4}ef*AQ5Umy+P87zgjFUn%T(p>D-7Ek{@_JCLSHJ=ZSKpe& z3wg1AtM>$Gk8^g*gOnx9W;HFN^^)_rB&+-Fb1893AmPy=v&ja`;rSTLRx5r?a@kk= zNH2Wh=?4R$1iQzZFT>2k@|hFgWYe|kZ?ebOS$livl_^KBYEWHO@NZYpZvsBge<$p3 zx6d{)Eq!nls`p-@PPQZMq3;r$ejifnn?(Md&OwoUU5>&C zitAzzTbMYePV$&8FvvNys`)pP#vtxmar#1Zl8z@*@J$uj=%oODNLRl+fgJvdDzk~) zgU5Q363=ux6N%XeY4GLNyuG^fWI{NXQGxw%#*1mRO?rkC&l@ z>T)pCHuN3kdA?0c?)+8Y*wyP9Jh%FrL73W(p48P(7KwsOPSHa{<$r4iBrl1SBEx?V zJp+nVlm=JQ{hlAh_DsFZe!=_FO+dcLhaxhMS2$H&)evbC74eycc3v;5bzj zHsV1&>5^Glm|y99=|;E-Ar=|FM%dNvNq_c1ldpdbB|bWt@&g#7KJLxY({}7MVlO~c z+#;r1iL`~Lvd2ry0dq>WfE3ZyRhgFce<7cF&3o&t@2K)qFTU0C$@#HwiG!UIa84oD zV|2HPnEhpXUf+xxLz-k(({@l6!qgj2z7=3wCct-+nmTfEtGqcy`BcsA;j=KX{t>vI z2wBwm^D610W8lVPsx3-dqKrg*a@jdQ_{zCc1T@i3pI%kM;f@)e!?BjMuh7T3-S)a( zZ0KA)vf)_6>y6*np8-iC0PMifClfp74x145yYv5=_EBf|G^-`ZGa{}}Lr?t?-iQe1 zaeXWW`X=XzYj429(*`Q26plsO!gFzrMg6LVjZv`>xy4JPB(d2YHnyxM&_^FBz$uG9 z#K-pGm7w@q4%vMTk9U555QqtDe3Jk_aQ(Y^`70E>j78eD zEjk4!3bh$~;gyW)(VdT6iiYOJo1(ky^f%Bb&^)HGQ1z$xtckbi)w3UJ7m7Uq)c&+h zg7jln*^8g9miVvy_z%=R8x;9nPW`tc!E1Mhwqv3@>YrN)rncL7Bik0&{Mbi4=LNo> z$O$t+BQ{1M+rQsP&v(@Z|0Z1Rrm1JO{(|ys*1(o&aRTbF=Q11Mtj@l^=cx^}``Yhq zyhomm#fpyOuF>|lduCoOw!I;|mOCZv+$M*D~0S{5Nv z}E>apZ z9YJ-YN|B*SvGY*;{iw{_9ZfR@Zg{>`LJayNs`)KlCm3t-7>Rh>EJMlSt4?wqXmq^I z%DgX}Hi+&4a1M>_rBXDO!=B=;644N~NKD~5?wIQqpE_F1K_h&PK>QJsS^=c-Nv`vH z_O95GM(au)kKG+1T8r!uF(EE~N}3w1Cs5i~f^Hj-#5`hOb3d_Lc};XT`yU$@16iJ` zL_c61rikxpZQdZDCLSq?e8hElZ(rW3j36l0=knPwwH(X`jJF^T)4FojwhwxO?!=n- z6JB@pzx|JuySn-d`C%;V{BAsEbHz~8n~@P#kl?oeM}qkhgm~32jHffts-xw5wQ-7O z+YZKv?#S}pPpd)l91hgLKpt#qz#KE9zLhJ8@!wDLz<0&VvZawT|Iyu*5bC!4vIzo1=MXK@JBwGO4)o~ni8UrjHpipAJ;XeWC>^pqsDaVgIw}EVPhZ(;juZ$Z)|0IQ1qALQXaB1v$%X?G$|nEVLWUS9Ey9H8;)=%{ z`?z`Ze}X%$fNDb|**1FBU_5IiW_HOZN=qF@xt$D;cu+5F+V3^ znoOe=UP`84rk+h%hjZSwzBjTmeMapj#GhEfzU$`o%=`T(7L1sNmx`a%2#tINlvnN1 z9&pN-Ei_-Q*pkV{D##jeIMA`vAG(E0EG^dZHX5i9$@hUKND0hMgWKLIAU-I+73Oap zG>i3`S)I_^@q(HEj^+XnU;EEqw_Ln2uPV`R%C5;(u)ub5Y;L|js>eC}7=dx#O>lo^ zH(;h^9sw1Bts4cjbBQz_D5T<22N@g{Ws$xLqSW~sLVnEz%YZvubh>{`OgSy*l!L&X zdb!d^n+uNo%#8PiIpu8N%6{X`G=n9sfiuyC=$w|AscJPI_Y{y@D$UE;Fy82lhTq25 z$ns_8L;FJo4SBzFL$C#g)=MD@S_&(8ylDjBGK)z=mM~zNO6fJIE;&#h0yNxHpICk> z&(p!H%LDVZCsEoZ6eDm**)@zY8D4z%x^mff#*f+d{O1=brqiCzjm}4fL@IY%w2v6w zkYn6^Q@Xk#Ik*}~Jjksvs$h3bYnJXvY=qC;oL!-m$;h0VnR3(Sdr4~koAgi{BZ0Fs zOeiyls#DD>Rryhy_XUvbhkLyjS8~q6Q~Ynf_)*+Pz)6D zvPBn!F5&)Y)x}*iOM%iHmM+;kvE;DhodvL?;$k_*z0PO%Dos zG~Wc`TZ&#&_4?e}3WzUdlOq2-$s$YGi$=Z!I|GZdA(PJ?#T>s3+T|?DV<(&2F#nDD zA=nXfp|n61e?-0vut+JjHFHTy8IK*zl|E_vC3W=|4_R}6q_L&&ot|RByWO*6w3C!! zZ1Urag-es$*M*S6&q$A&hu?!n9@sQVF?8)Y<&0n5fm{j8)qdn_%+hw`R)L*pE-?i}|r_(iOg<`AuLmK zUrn60%MTNX9bx_+^HCZ=;NWT-{P~ST;ZlY{OTX+cT>QDW;jFv$I_T}w?n5EdeGEv{ zY|;p$P9$2CY+3?z$7SOJjtkaA$4TFHxP%0WZrHxif}m!SuorO+r{z9O1k%lY+V*J0 z7CT$4`b7VHsgO)Fz%3K;9-`<49B?Mh9K`u@c@%)DsRW4FKd1b0gj-P{9m%f`JCL>; zC0XMyNZTgBAyYF2?$9NpsTF@?M@Jn=EC&=FzY-!=WMXqH z-4J}Q;|G22HgxczekU+xb1b1wvClT>Ala9GiRt%MD!qtn=jF$%r{WeBqD`c1e|d*F zP0}xai%8%%D15cnCTGh6ylu1xS3VR&qc$FIUO55ohkLt2frc}*Qeg#=2!%sdn$|%j zK3W*&MYG9adE6T10aNnes&=0QVL=^n0|;uqsj8Gu0vD^A%)1h@qIyUl`iHsw#WO!= z6mRf0tR}D5YW|J<<12y2hA=2s&L@Rxne~n#WSwF)`<$=edEeBf7j^YyLhp4%Kj~TS z`kiuR6s^uGTHx6Q;u;)!YCj6Uve#D3O;jAw?wh~+=!<=TOAipsUWm`>68ShJD2UYT z=OB4GkZ+xPzC*(|uS{Do&_;P}8ha)zXv&13NW*xjQl)}b4kHyJxYfI%6r%oFFU^J8~HWIydVRmW;oKb!?t zyD{;LzZVJ3dUiDEzHbqB=l0>n4D01*Hp|+xpBn;)Qnb7wx}_Nbk~||&ip?={Hz6b| zReL{{umxGrdc4~Rw6hMb!&UO{cB(dq(a=i__B#3>?AC)V$%pf}Wk^0`FXJdHGC1i! z5qSs+mnitrhnCCz8GKJ)R!q=baA3p&*W!D8dGSuRtZ&n7oThz(RP7NqstPaJiIU&0 zezvl+P5v*3D(-^W_m4dO44cKDmKx*qA3DQ!{`~!pc2H6YmXUfB-|-(^5b1#n{|ocE z&Yy@QUl%ed#Wd1PZ_)Oh-N9m`R}!T=HzcE1jex4!9!yucjzC*o7qVL=>f&0u@{3g7 zmyGKuMJg<2>q71Vu!*#CUh6MwsQzCy zSrXYuKgV){wVgcr(N4xLWp)d8rE=3vgXSK!EYQ{+aR5H}j&$<=R}v!)8Nhz4IYi_p?Tkd6q{`0I-jc#Q^4`jbzCmUiNXgtRL^{#$?gYbRdSyBv zp@8djt9I5aoln=9XgRxqlr96_&=oI_4?W7bnTU%C;PtCvzmI3uH2kWJF8u%cpV#7>TpTxWO{-zjIXC^dJo4eZrj;F4fd?o3U0-c|BcKQ1sJ7s`A8Euvs*{4t7 zb$nUQ>zTWkntMaPGg;Qf`R9KqB7PWc_Dk0_6)^n|MVS;$fI8o!$*ZgXBd;dKpLC&- z9H|x>ohgaePB(1Pp{*a+(OP(Eiq-t!_YXqv7#LPC@6r){Xp!Id7|4uClY2W_O{6Cr zLR|4G=fJLj2i_f-{&sQ)PTIa4+Lg>2{QDVuM2D5k6sZnF&67>D^aBP#R21HP zsS-k-RHY8fP4rYu(&RG!0!0G|VMnS8?x-4V4H^t%s%Ah;Y7@&~p<>tUDv-@vG&L*1 z#vw9lUq9)jR(yc63y0f%`Zr?u{s0j~L6had;?9DyzgrmzclhJJJva&#necZJaw!HU zbo|FK@i#8?bFp_52OTPqP;tin_i0Y#7>hgP!})X12HdsJL|pVmXF68Zagy>9(}^`r zkbe`faskFM#J2SIl0g)*YcQEvBC2<@G^BrfgD^r}```3bTEZ9fhREeE{IyPEfuYN92xqh^>~twocp($6#;88CI{`Q1E0{FoqEJlY!mycRCw! zdOn@<$xxsEwW|Jge$i$POIFb(o^(+eRtk(4NflI_VnJ?)k*0cpi?OGGnyFKEdp}ZH z;-H`|U>j|hl{FYW>1-cBO zrVzM^Bp@;*hvJ2^KkI!#$?<|J%E!nv7`IfFif3m7K? zPQ4RfZmyE1Y<~l=qHPo=zi@;_#AkzC$>%vUclu!Bf0Ccb&wJj~^oJ?qMNH8%ICjz( z8rc>a7E!Z35*ccs4sd*F@Gw4hVEt2~=Kr70C!-Byi|LMM1AzBb^sgq^o)){k4-m;_ zYqC!Pdj4t`T)mTU%ed+r{4m7vpL9ve3$gBnH$m*1qsJ=5fFCn~^D7#N&X1kFT#qk| zO=b7GYa1VXL9YjFp%ziNAFRNsS#VWR@SnQ2)1-&^6c(-PQ{o1sR=LbNd)tkXr6?SB8m!#-3FjEK=I|oQ<=?K zoPIjOfQ4Uc8xeh?&+aDg?w(=1DG6t}_W(wnaC{vE;J@T_oIuw?d=@Sq=)sBiqP5~} z+7|UwIMvw4{~uFt85Pz0h6@kfokMp^r?d!23(^gPbT`rsGK5GsBHi6EG)PN#4Ba6e zzT@xzo^{UGS@UT>dp-NA`@Zlh*eHkYu#tcI)6`rbD%d|u;IMM|d8X^!Y8^-hrq|s9 z$9}o0j%+cwI@aMoeSa}ZR)4ojLKpa2Xjhr}Z@|TUTK1*memhV|7qhg6w*~e zRvo}e@*LY!3$q{csfMRb3Sf>s8H?cC^Q z%7W*u8zQ7K>G)8U>3`b>V@sn*q&lfw{}D9JkT&3DNQ<~5r#$gpUqd)ieQ{zo7n+jE zBbavhAumC74*0_DNpPqwS1gSq;9368sx-BVvh&Z$=%yJ?jhQ4R+vPca;G0_WpRlql zIA4zzD(p?A%|*e`d6tZEYn7Iwy+7jo`G^VpY_9j4{I_n{shFM?p@BkO?_M$@c#@0V zQTacVYCjr~_U@AnbgDbLCuL54Ms^;~=lHE;3P91G|4q8&B&Vs0vz>}+pX!|j86Xxx zg4&oOQE|y%==)={zg6l&mJR-3vEtmaCN)vZf9cslIug?oV?Gb*oN=WR{y39!`O(FA zk1>NCf&Z>?s)B8tH=`b(velYR`qP_YdPFv!VufJE3%9bwi6tQNu5|-aq)6&TZ8MrA z&gi{i5kNWxR@YpluGf|ZPLOi3j9{IA+A${*Y$1#3)3$`>%P3fiy;r<&AxvP+rVFhZ zMR?+uAiFITfCfFR(l>wL!iGPUo<&5U9ne7(NBYAPiq9qjZWoc z!;eEY9Q|2J&h65vQci9J$`*Sq@w){Vfe#}=7|ZRQT*Uf>seSj=rr$EG5hAs@k@$st zId*s)l?7NVJq};Qf4f`qsgXhUE*!|N+62JAt$`Gcv$x0VU6}O+uW$Zgd ztqQZ#-bDII_CJEwAE-?nB>&p?IBi|Nyu5W9_cp%Z{+9aLUhuLGn2BW2-nQ6L-MR!5 z7aVA&)XTW}K`^Djff!%GwJE?3#1lio6PLO7BNiDMjMXAO-&Oqj zf@&crGEmt3ou-`1nqHshT^ZFR7QUV{sKqtJsTonod3EEumbzf_J<&9mP}WJ`$Dp+< z5ltcyYf5^x@x$+Uh>aHDX{DbWxy`$z!5^67SyRSXGRd<_@3CpeUn*&fJ}b-IydeKo z6_1!3gG<{#QQ31FGYcw66PU)4&{VbiJR^O2O*aDJI#>{MpQ`$-IT`V&0beWxvf1`od9p z&sP^y@!A!ZmEEZL=CW>O3q6~!nwH7(eacOEp);FYV1iW`} zSu3*VTjtd7X7M)2`oc{F^VsKFcY$57rKmSin#UQ#5&IFBz9U|m!10HHf?JOEb;|(Q z!a@UOnOW=demSUBPv&E-1i2d0cgdpctmx?ZLy~^>ZyOUXo7HF!0wQsU9 zZP_kLm)eD427b!?nJi^r`4I?Hw{$k3$T!mi-B z!)F3>$FRFqfyn?rZU-O^Y=gr*su87>JsDop{1BhK`Rn5k0k)yj4!vzx3X2;@w?$J* z^Ke}|kqv{Z(c9l$#^?XAPj#*+W&pyyyADaW(zQ4gE?+woJn(Phtq%H%`dPM5@>h<3RUAsx00l&UdXjCL$H%S z6Ou!s3?-I7LB+WLy7(%ePipR)Yf?zYr)-0&Ts;X!>Bm z{Les>c#%MtpL1#yDlm`g4dqNLK8o*OlvUgVGq7*naQCW9rMTq$0uXE6q2(LD znsnXwrQH~MPouir*YfM>a0Uq0iM5t;tpt!d~`>C`+^%^Z&gK_nO z=?YzfrZm4TGkgZ3G`Gy7|EsZC}?Z<&L&`70CixQ}G%R|+WXyr%<%^~UVcrY~h zba(}}e($f%o#Tru++ttV+4y?^IDMfNPrHG2XVc`9@tceZ(`z9PDOTUy`SEwFr$gZ= z?+>UB2H6dJwASeUQZc(xO4mV=09kIsRUL&}%4E|Mn^6uGs~E*!;5~gmHD{*PU*ki% z8%?~juAt3Z39Ob$ph>QV3e?%zmwFmv`--l$5Wh=F8i?INT#J3LcpcCsnMF(xQC}y! zO=xL8#_z&tb_tp8L7QEu3-}=VMGJ5%9vGhZSZf#yE1_G1u<)JXtx7azXuYgWe8&C6 z#mOx!iTq+Dg-SdTB5+4)|24Qb6Df1JcGp{vMb|mEs{dLDVt}dbJ5-!H*>r;oc=sSy z%>%N;-1DVRCofwJsf~j}e@ChQxgk%T8ITK*Kz`O9%;m}jm2Z~BZGA`cpeLtp%A-3- z#g_gi!SK-8wwY1k{TC_RcVZE|m;i}j#ksoQ9@qm;^Vpdcth3xlgadB6s|idh7%+cG zHhRapw(E;D%jC`P5=xIPxp{v#b%Q5&%TW8XM4}G%kVJ3h$I?E zPfGJ%6!9S$`D>RlrtlRb+y{uGt39xad(IKQNGTNS*HIRq;9Q~DeD0lLpKZ2uj&C;4 zJowlt)1mvQ+CTo_K!55dIj#xGtgvo_d)1oOA+JX<_T(ksTSPv~$xYAxxT?gRt2z54 zVNX5hYE}BJY`kGFfrR*;!n>cW8=X*x+mpQ9gQzcsAvVZ{Y*5~wUE*bDloR9tn?bJe z`gQVdL%{{(GUspYvyo@>No8zQc+buchIYcgo6=oE#jG-21h)-=RtQ!EG;z3zE`b<9OO%$+YhC^v3$fcK0tMf8kAXWee`#0jDGz{7rr7KZc=-qlNLYQ2n5m1?s* zz2bx~id#DfK0zSMq!A}Ct(F+zLNMlHuH0}(%2fbJV32aj8JMxp7caRA!kCO!XJ{y9 z6|rJK)b&+O7~+|rxy(62b+4`ke9%PX7d|iHRWDDlkVNLj*ge94bP{eS2$}JA05yW# zd@&Xnq7%sd5Rr5NBDbUG1o=&;#G9CJ?g3@$fW&6pJZSg^9XtZUdtr#QJ}z1uKfFU3 z7KL04Jj928P})kfkkx~9kC#*>=zF+Z2wAw@IfE;DLfBhO*&yB6cXU&vd4piWZ>b+X z@9@&(+?+NaC;~C%a^Q6fPJZ9axFBoyLKPwV((CVi(Gn2e8QHTxSps|sL*y`Ua})1S ziwG*O8bHe2Abe+hxU1_rQxtP%IQ#|2sjme@kWdbYnSM4q{0t*DhV6x+#RW2Wh5=T& zz`WkF(qEOR(IhOtXI=jMetfL2DWSzgH=wYC#cIE>52gMHAEm>47Xm(9coP&t38%#SCwk09d6q+Bp#iYd*OACDZ=|b_9aTp zSt>tn7BBJ47VU1%(KHgi;q?J^VtkYBY5dz{Rbet@m7rD)J06-Kq@VoTc!f%eqf^DR z!=>=(I4_57uqfvd@n{#wRl)_w5-(6PM9QV^B&&P1c<;nKtPy>S2T>h|wde55n_d~4 zc7rWLE#dnesky0-WdTkt@`m=QRBiY9)B(rylieT%Cz=hx0I}s2|AWbC39hxOQM%jB zc7JuX(YZ=G*yOG6O|C+3Eai2*pP=Tb=Ke&84JscAbnKIr9OpT3A0G_(qd4{{mR=eu&*@wXaf(v1 zY)ZsK*dCd!?;SOBT2ENB-}4HAX?aPA9E8G6j-cp*CCNn|K8(yiBq3bk<^Azv_ZERnhFr!4t9+5I zzeTDLst`CCAP742WS^|b#@;VL6|l)iVUk`ZERex zpQf1fE#Z-mjhXb%)nFVFw$db6J|N>OL-IhLh*@5o{AC6=Z$n42wG%CZ`2p2ZgE*IG zYYj759z_N){kP@{G&kiKICIaTO%aMA?`xlVh5Y6!YD&kc@8YV*Vi*?XecJs7L?M(4 zl=F7f_M!KXYk$8@dtT=g2l!dp6D%fRsfjiytbUBJ+7jU!np5%D-y*!rklm$&V4q4K zt;RrhvF!VY?ZtI-_;sgAp$OI1<0cS~$Yedxh%3El%&k(cW%A!zEkyQV7* zse!K>#f_3LIXxkMYPk~G4l7L_U&L{r&d06fXMzz>?$1#IdJ4X8JiRno%!(e;zt@>M z08f75>FJMVP}cMoU+<4z7oH9&U9>(2I&h=QQ|9C7%bt$|G`3fZ-j^elTuU(Dei>47 z0oQN9()Cns9lDm_r2QHtk+gDI2Q-kYLz>#V?iqHlG=^I@96-FN!O0d+*v>o&=h|$J zv;buEJ9Ak{EmeqrAl#!X-+s2gUBv@hYrhEUq=|FsYeD3` zXIwBDhAHi%S;nX)$jxMB@!H!h%4>}rGZ?qOrhfZHuaosxNt6S#5O}a`zQP{K&NFs# z33ryP7i*D=7Rmn5?kyp6XYa>W|Od=5L}A<9rJ2^(RL8}Q|!&6ja)s(waQN4vrVH%TI3%_ z2kCUMi#xZ17B>e=CWiBpq4h%qQs_$JIhmPp$#VejQNgA4VeK!|xiB2NNB+oV6ZC|D zjjc|x?1Fp0ib+rux5#J9(#v(hNY>SMZS8%mt#4mJ<3F1nHhEYp8XFbDyJ;buNW&Ug zhCRbla$8*veC%nNOts>oxOaGC(eNkjT3a4XIiL7V0EDKmtU;k!LS-CjCVPx!9Hd@! z8)g&z=z||>g=hN(jgUQ#ay@Eluz`ENQYS2}mf;U4pmb&w7J+#1!s+`SQWRzdWgbwX z>DNsQjE_6Y+1t}mJe*pm_J=qJMvO_)D2Vl_38j}1H&RJH-BXHKrK-kL`BjDCm<}DQ1!W{K5RpQ(-jJ)QpE&>G=u%f;0B>oA8%6`qgZm z5Rvc>nn`6hL$U?=m7om`_&-#`t9b)4yGhl6MR#2-Sf(1E;YI*7k8_!n4~a4=w(w6ZiffM1WOqZf9F zmV**tRx=NtE0%!t$&`+t{-I#)E^dc!_d3F0=|zn^zP5lN)A;KB6GBU}EUp#^yt}K$ zDnrl(1-bHxMiA15={8{~_2~Uk-O?)G>PqBRnXH$crvA79V$EGUYHc`<`6}yB_Ndj0 zBWf!t3cjkUMv*tvBJ|TvnuR&t)`JHxEi(u|DJ?Tx;;}wtjR~7&tXdOF8j}{4rpVoe zHb?;6Ar%w>U89cqn$9`rGBKNfK`$0f8a^j}i~{Zbog=d&YqRaYQe~zK_=W zyT+{{H16ra-v&t1I(``r?QB2#?t=I|*)S(o=JLT0HZipWF6VKi;rkL%iGN34p-mp! zH$7F-O@x)GdLxVa>K=L+_GJAwKXz;|c^uMozoBhf-XqvQf27~^hneN+AHugY%MdA2 z$YM%kOS3d58$1lVeM_1JjAU$j2e@HJxb@9(F<+hBj(Jb zp2qstxy*e`{(|;ERdu-(nqM_x!;(A6GgN`Y4T~zW88JZdz(P2CZPTVU)3BXMpQ_{x z=|O_QBsaW2(4dZaE+w}&U&@hU+bGju1j;!Tcu8r0@gb% z=Z*F6bNZC@7I)ZkjfUU5|3A&b&^deyyqllp_G}Ry5a73M?fJR&`jLEkYCc4+ljHu+ zRqL%&GN+P>`zTqgjl<{e=;k-sR_yFXIqR?`LH@+hYOF3-TdY8yESjZj9TuR@!FJe; z^&I*$IaARF6#*}g^NpK{tJNLl*{M-p(HB`jQfdn0h?@mkVAF2GJvSHQWS4mQxH;^TAMuH%GAib=-LKWG$t? zxTWFny@Ydm^c{Ay%Y(BHzr+*Ug*0D^mdoXh(*b>G3#Fuo-Y zH|UOLaIF;jz6^bI*Dm>DW}k}y1e`Ihk%WwcNYwWB)k z2{4_h1Jsh>b&l#^e!+ii-uZa*6_Sj)$Z2m7bZWT~yGe#{{n5@jq!bWcl8@@cIRyMu zjg7ab#rxS`oPLa}0r38#VtKeogP~uwKnhEAUOh1@fOG6)m;=EUQYq?3L}0W!{QC=U zq)i(vM4A|!O;5fL+_rQUbkd(kH2hQGFK9nW{1(TguMVnpMx+T#|6p;CdNTsSp#!u% zBDx-Z10($UMJy$O!UE5Z2{lE0VW?G(RN)clc$VASV!-G*pUBg@z~2%Q%3I@jHa6Z- zWYb~gXKlaz7IL8YTv4E4!=|zws9o&T#6Jl@ZT%?z4I`0u#kcTlccnJZ3v~7 zKf=!-|4!=DR!VN%^m~`BBys|ex>AVE91jPj>$lGWPCQ*y_j_Ylk6vD-F)H)$jQAF% zU$XVy*y8aU;1TLjZ&1r_n98F>P0{w#!ne4XbWlAR2Dwo7TFW*J*@1yvLw4?f0;8!T zunc|xJu8j~V3p{VDK9i$irv?6&W{P)Z-2*XuhwLH96FjENVDE`)a)|2>s3=Oovoz=7 zLh|imrP7%q*dz2kw0!!g8{$#>2|^lt*oxtTZA;)z)dpW-7N`euGo8eqMu0xjBwL!U zCSsiU>P>#T0AnhY>kX-8A%rVsyio}2j|<6a`Aib`WWNWg6KzGiIBUU(Pli6FBxT(3 zZ1PlyRvQB7s;*VAy?l~H;3!FK)!v!Utn5Ae=k28heZYlsGyn_4X4Aj5nEu@19=r!gRW%y- z7D9D}V+F*uBD9!7Qv9Q%L;CQf3R7Y?FzO9DlN29)UWA>rTmc#boo#?Ft*!4D-E0^$ z-afq#qTxOXH0%g!cV51k!P$Krc4;7X8Mx73@ytZA>|+VPxv9`(vAF-#ZHI4EY^$N- zv7EdZyHbJ;R(w7+E+V}2Y(Y&5ah^q=PE&rBU+ ziPRe92G;dPRbC)j9bFhNc6~BPj-7kDL42gaIDN?X-e9ki-Wj`4R2VB6IWrCwq#oPH z)=%TIixstL=B7?z?IZGa9 z?or<5?!jzCmdd#mHpw)SCs9GI-^iQq^}xPUa8co4oIUT&hzqyUo}bVh;mOzzc$}$e zcJ_(7j!}ECc*Gz7S0cf~PXP*cqDo3POh@BVA<-c<-1?O9dg`0QvZRu}jAskFq|~#XYy%d! zOMIv%cCpya>2XEtXecJ%ntSeqs+bc~nrdeS|Ds@h5KXY+H_7-t2En=B z+sUqt++CvvW37iy(2I?CFDa^V8#;aw=;`j6HaqVe$n(ZuDKXx1>#BRm30 z6sm;%{n2&HNs7^0vJCfv=s*IovjN{YtLtWXi0B6E8NbxnTZB9Vw83CsXC6-RCi1V4 zjTf#aahAX0YQ>8)XH9F>ReK|f{TA!1B}yvK!9XGWM<%cB zhyCD*f}Qn?pk3;OC8!WkB|j#Bc4J01;4$U-F2|m> zYPGHnuH7G_8+b-D3&SC^3vO+j=3tCBfE_Nn{!G!$Jk$CfdI-q!x$Vu?Hz(shB`g&~ z&>&rZJLQXkBTz^vin8 z8gbCGuV3$ViX4F#h;HyO3Io+{0j+kD5met(#8F+#xmz39IiU|!?>=IIrn|B3jW!Y} zC*E#uUsr?_3HG6#WDnGc4n0tDM&&Jxaqk1Rzx`gV4(8Vr(H@7n9jn5e-_pWc;GkGi zA&S`*NQ1qEJHC_3_M6ftV~6$kao3!w08%hNmYe{ z2%^D8QEQ~4ShwD_p?4OB6D=oFTyWRu*L=~(k_4*O#vUQ;kVhE%c@_##Oj?!5bdi(Y2!t+;?m3@* zBtyB?YOc~8H-p}|8p?3Hv|>6VcjH&w<|G%-)jA3{Qj5=p$oYTbHhVB^&;R{dg!mt@ z*OsXVAE!*#YWOgbQgj= zdYMyLf6}U$TH4&!s_-crHtlgvV2IU>0BczDFX{U$$A9r}6Xj_?waC3QA}&WNv|MJb z@T?`p0xLF4=0i~zytlYBt=VsvW+09atmfRiW^Pf~0^eoSY=aLGmftxcH{DXqW*dry zP~&E$3Z>QdH(zA;U{8ES>)cNlMiC}~!eWDjW`$JV5eXk($O+U$E|a1+RI8xr`4V`u zQzd##T~R!roVhNRcHK_DId;=5Me4XVskMx4x<-$(zWqUsNG12I5r?JdmS*c*2K;oPtc}{6hN&Ek@2ww%)=4uR@?nP*w9WAD zhq>_uVvR8^?(2d=j(o%y^OujmdzrF1@5#)mE&@CDq18#Ii4pDm^G7XFNijT}c!t|x z3?ixMQwX#_Pj^%OT1+r4m|@LE`a5U8Te}En!hLxu&J|7{T*p!}aixydE2FCGcG5d% z?baB-AqFsU{~3o=`K)vfg+URcJ@v22McHGmLK5L2cEElo&rJUVV-Myyt>ud&K?n6EGwiVcQeAu}Q%{FUHAa@tq8D{;9d}Jjx8<;tl>9U8 z%TJr@oU+LQu1B;2WyK1|nErv!U-Of@Xy_s4^Bmzbj>EVxw2>1x7mqt>4#=YyNPWup~D;})tG|1Hn&0j?mtJ~qVqpqlXWB9KjpI!t&34Si%IC z3!m&BBJ)=z4@&;=|Dy-)?RYf*ALnRYZGJi8+-bWlHnD^4#GEGyEZ<_UuOZkyPM86^ z{RE|#%K8Jh4DbkvVjf>jEze8)6iw0PD7)^P!EaNgvt&#^=hoWq<*;e-=$%}6Aq zzVfoD2llnH(LpNoswRtc)6+JxUom8s`JD{zSbXSzp%r4$m;Osi{RN)$I1jL?5k$K+ zLf$~KsU`Pyc(f$$PTMG~r5PRt&3StkUTk=v{^APBIpAH`FV#7r%@XFi)3?-V%dG%gX2A3c_cG%$!xf^G zCpltJ3M-__qJd!$qgKV5F%2zj5??=gKgf+jThVS}I&pG3amPm0tp^cKO-aSTJ6m-d zVj344UxXuc1dr1Vx&Kusa+|K0Y9)M}B0vT!y3K{&hxKDvK35h}{E7Sf0gQn%<7|6L zw(HsC!jnU8VW?(ZtkEw+>XljBmIz77uR@Cbf@lr%PbGXB97qIhitadgq5cr-Pyu|U zj61i5OGocc=fbK4CUywfO4N}Ai%_p#+T5l!+3~ulelw5TJ;O?Lv7=ub&mO7x|-*8wD5rV;TzJesE>ccQv;A-Prvk7k2T@&ARQhVs^SvmEh1EvQsqoL1>i6o-Qbd`gCn_ zuxn6Hi2qQVz@$gF#Xj!M`KUx3yy2+%Zhp)Lcg(IRzOs+7-KBY}mGP*LWyd_Q`qMB% zYl5lkbw_lhg&50Zn_utaYuV60snI|y3YzPc8$1eKChbBDN z$4U(O{3)2#GONsW=GyXIRw{?I`^79kBoGv)gH5PD=j22+FA;9n^dif72X3 z3Ukv7IUZFoqn5|Xz5}WsU=S@BpkAOl5;I`Qff#VKIlr>ET-3uk^i31}wb;)3+WqUx z@6-{%xD4rQ;IZNy1@F4!AYBi~royJ@X4Cp?eXw?)5t$NJbv>Y_6&>pO?ym#RAZ*no z(>#`CHmjKAFX=PjvnOxQFx~M!6%W(1w{ILjOeem_m8>F_k8?rG-@vMoub~ayVyrQ9 z;!{g94uyRdvhF%`w$*~JgRw%Y_f&U8Wo%TAyl0<@%E(1?&{VTDG`c7MaQF3uhbRnO zWYyIgvR~j|)Zt;W1g$}+2wzpfsW?8Kv%ZP9Y!esT@S)exPCoc+Dhn76f`0FVH5(mL z6=k}#nYM+C%^wn;FNxJ)ETY?guf?jJ>zSWj^jt7yHx@g@Rx~j#86kcT>iekJezYr zro(QTO1u5A->(QcBNC+VE$(E7BzWCPg<3V}*%z~`_YOtZ&539;EkU@T63%<^p-T1EIV`-{+XR&U#@DvvGl9K`T4S5$Ndcv zZm=;g;67j+%b7pzq#@`cf9pf4FmN8pcZw63kce zo5(|(Ueq4&-^lvRrQMe0pDahS@$zE}X8pl*3Fk&8wn<`wTw@r4T;6!1=Jx-jUe{#-$+HJC^j(&~5%Rz+`US7Ahz}^j-*iq#kCq7$XY#aC0IV<8KkMIOh6nX)ys@4|)0=9d z*cWx_dUtWN(=r0rPXJ*8k54RSG1=!dr8s1teHtO=zeL-N;eGX3M({gH_U6*jptkuv za+>30)&acVsT1+@D4A=0omH{pUvG3vDa?`$3d%)8`tX-FFhu0x26r6##p_7`nN zG%s*aL`1ctNs$h$=({1cNJn?$$3Tc>E0Hh2UC;*LKrjnzSfP}2(G~%~twU{{_*48?gEr((bkeW!`A zCCQ3c^WU6+?myRYEABdH^bQNz?uTRZ2CokbU7bZ$X9os4Qj|xka3My|npc~=d~txz zJLBPZqC_-HbT`B_Cd6a%8t?7+k-RIxkwKKmu>DIILFN7-+M$F6Yke{4tf5NQH#r+{ zKXU}FC_M2raDs~0bkx(TC#j1(+|i~^FRZaQE{W|9&l>(`Elra7*&G@^4S_nrL+$@W zs<~|v$m`Dgbz%4~2buqjz806&oq-MA1EIhE`h7ZQ-Z70Fuv_N(=2>xjVRUafHkl2S z!q1uZ8SYVB@1g@JDWH4WzXn^}lB1aH#Bw;FTqZ&YNTAjioP0G=>-L%4r%gWqR17c9A4k?7jV&iK{9wxRi5hNv4*3Qdjf$Bad`xL-si}|_jwh=D7#@`9HU8Thn7wK+eD~*Y2BTUje~og3-9K=p$-(Gdmy)F9GEdyCo*K=@8s+(ix6YdY zyM;>7iw(vds@JdSZk``_oply+5}DnHag9_%izo-L*NEz}-2Nr>QmLUnAGwD`qiQEB z_(+!t2Mu_!>6tQkw6@>#EsLE9E?U+Y?aFz=nN$AirY;!u@JEU4uofzqX_<`?+_xU^ z%FvOci=Y15c0YFEt^dZXLkzb1gp*sv41C|vV+ppZwCHO3W9YyCaG1w0mfQ9?oTpE@ z-}&`(rBIs1_InEEevwPUMfv-2>~}y!u}?189oKMuhTaQgLz@UwIMZ-c*eCKysV1da48HGuXvP~v6z#NP-ga>#oOj?rs30e}$O?1$K|+A3 zDy59bWETE5iCIeR?jDe|gnq(5#2HHIGZ`>in<^F$y~m9EtD)%Y;Op}2RA56Ly+Lkl zYd!0W*#+IYnz8kE_sSW05Sww%+A}RPE$ipUxHv0C^wuk~G)2kBS`DuKWG*_$x8q}Z z#Nvs?T)ziW@AJ>FXVn?Je6)w>xTp~$=b1;>j=z2O3hak++Ru)Md=8N`kXU#vY(M>H z<@)|=;DzYn^?qR@oL9MyIyC}j>)^8qr0KhN5AJ^AfKY7m0)pk}-#{W-XVGd76-pAmq0a!}%IM&J6^h9I1+JEdV+O4-&GU1XAwD~X9 z42{RjMKDghuiw2s>1NZ)F%J4Wnm688Ij%cZQXdo!fzP9Yaz-3*v_Xm6S)r@buu%|^@m+srde zF9pv}^u@cIen1ksiJ_JR*R(@Eh$SD@bqPR3avmIjkkFwA(<=mc{@t3y zk3HB4Q{dpQ^9)KRe;eoLM0_U2tS}yR^TbUHE9G1BAJGb=-&tb!(Ibo;LTs(P&zC|k zQ3v&5l)y?yW8nIM!uM^XZ*3gIpbu$v%Dx!i1pVx{@7vlaLCicDy`KFXA$z&qlo;X-4$zFeHpV}U9Z8x4IGVUP17w;85WepV_ciDHS zKh;TQTT!vo%(R2T_sfRFFdBn;4mQJDMm+oJNpV18S;B&xt@BMfWgVT<&qRuYvCu^9 zqOnRj(&O~nM{h%!lPO8eJJm~Lwo`%zdQV*10e9}mBVOjR)PH&=XvpmcK{4TDx!zxf zq^Fj2$b7{0>9M?uT0XXY)AIxSo-)TCD=U42Cmm4!5i^QX}(}9uAlo zd{ie<*K^d6^7Q1!fiHqvoB^WS*5r7$Gyef*oqh(PCk-SPL)>^aeB!sox3=v<*I=L{ zkZTgF@KGmi#?|n%8HEOEsA&a)U|Q{b=U4e_-}H=KQg2XEc$agEd_766LLAl-#jhk3 zA3uhTT3$AR<6l>L1qx6k!l!o*QQ7G|V4y*Vm0P*DJIkJUto1?pY*-Jlo=EvlgD>E0 zz<@*|Q7~n?bwW(@RIF%I^SXq z+3|3GZ{dK44B;WjU!Pz>yP$`OE0yI*z)~(4%P zl8=%|EaQp(f+vq1S6tLAMcRgC&OE!~?ta~iITr!{!ugpUQmiZ=`&X(v>agz@aT9=w zd@S)pc;yHZr2=Ho#sYMEAjY(9u;8#ASS|CiIBch0O^eOidwPvbR$xX<`F2}#Q#14s zQjS+_*6|hFnICC!I6!PNy>_nu6DbaT&Zw{Fj;(jVA%|}j{yra}J5+IQ0T{>*CEnb( z`9+N_M7k~YU;0Sg%Etw6a17O~E6tpHmnu|c9X5Ed308T!t@X)!TBhz&OZA=%1X%sL z|I>hS|H#e*$-e-<5keA1FhM0|4=*Q9M6Hvm_#HG_MwSC)LklmwsY)=#4>2qvz*mI@ z?#%6ZCoOxJtnAlU#t3e1I;eHoF8d5~HmFr&9EZZc*4%Ibybv&u**`e2l$J|b1FbT= zRWP^5@T-tI!fF+Am=(YK`eAhIy<)Ef{)B?9txI8&0nMZqeON<@-g1Ax$}A( zsFRECr+p}JGUpNCL|HZo`A11j1wOq+>hVx@Kjx(kqA*~~mRf}A_Q)p46R9no%a^Tz znV?CXI%VWQDhg2 zZ_b|cI&pWe1B9V}Viam?yLs``MBN+zQ`VFqwbN}ORZ(oo%poa$?;E3qGF^z|M7L@C znZm=`*oX*%A`J5QPb7tn~i=oOn-1uhaJX%{K&FUa2}gKyfl*X$JPb z=_Z3RwhsDD6Ml<(m=rU`5Pm{Wt;$D;wiP-IOupUxu8FAhsmUgY-m1D5_2BF%ZD5>( zH#z2cC2k}7Vkd5h|F~xSo0|LLkR13xSSP3tq%pd%!Bf=qXeCL7JM5(f-_X7isMdu; z;SpH4aXNmR%@2}0j*0vo_z>eH;g(1sG);n3Wo4@md z@;0f48W{|xhR@*wNu;s=X3SrBQGS==yU@#U9r>td5PfOAKt6`w5j~~jPpbPyx3fDv z7i-AHHIRjDs4`X9=|Rl5j_c`uYAr)UYXAkc7TtJ9*O{PxXX6Ediq12)EhS#cW@p$M~>h?#45{kNtAJaO^c%JqV zioxT^K4|IF>)|dbhS3k1M6o-59M)Y*+>JzA-NfLYBSt1YfJ_5913EX76Wnj#58DZ$ zGQ7XciIRHC;^{&=BzryFxaG7tp74JDzVh-F+px)e#IBd~zA&0kbv}c(d3R@qek(vM zqy2#Ciq~ZH*%Y10msL)Js@5*;=CXiWhxo{We9Ab@>XTKPNWxl-5q1UAIuf^+PVR0k zpuDLj^>RJU+PSWO1i)n6zsS1yxkf(Uu^Db{0H^7H-))vm}-Y>30Ya8{Y0 zFYt-r*Kvu`Qf4)0>z#o@xh!ysj;Im=Sb#^%%V*AUsk|8*mexw>ortQl>(VG>577le#H=#7ofwk7>v zQ;zyn+SX$N`9W+s-5brhTv+ZLSL!tDg{QLY<~lmK=UdCS|EV|V>*&wXJu9d;*9LnJ z`X+k{kDtQ#74S;DSk1&9e)huzQH2}Ry00Czi>&Hsu<+$cf0wy{V)L6wh zG#5=a`_glf?R~$+shv|t`ufy%=dtr(Z5Qr4YC0CQI#VwOcxGM}qBla^~&C#Iz+{$ut{id zWW@}n{{opJDio^HxS94)uv&&0els-2TSZF)mN+dibCoTeas~E#^+bq zcXm31NVos`94#<1b0=EmvLEZ&wZ1c;=m|mhmKr>e(Enk#gm%N19RtNCFXjEMJ7TrZ zH`E_f_S6rPiwp44U$91qA1X!MYB7)XeE$q-UYX+WP&)Bbes{r+WB2j&W__cH>{iR< zp*rMK%xrknQv%R@ED#t%^qu)cS#$o|n2cc5J3DsNEyo67EG-dPW|jh87zo7PF+D6% zHUGy>B^-Ew2RI?b#~~)8$=8lylOPoTo9pp+=D`d5=NAS*NyVTq)W|{--ZsNbEvwMM zIU*=4Du7T}coe7f4?-Waqn{$^2cNDUA_a7;c4K`)gKm4p%zkX9f$mtSaS}3GmK8%y zJhI+I1SV^W?y=)(RRFkRd!W1I(*X4B6ln;_V)ACciEM~0*RCtN{>--x8?sLrSRe_N zSJ-S?X{9^*;S@$RA&B$NM)4^D52+4_<=qB4pkT6^b|sdNzf{{amo$z_S5Z4PtM*>O zstgs$&iY7F$%o~yn|iNXE-Q6mfgSLH5gl)f+oLc4bvej84=AbM>fpt68`m(eL*9U# z{LmP5A7ishnrk#IS4jX|@Nll~_wiN}Iim#{KX<2H$N4#Ns({94NKLzRR5aV`W?rcaP9O; z22F^a?}~Wad@NAGZ;2*lTLVG{+$q;R*QRZH-R!8rdyjl>QU~Qet%b__T?d{2XlP4q z`d(@u=7RS5{S}I*qTJAF+wS9iCR1YqOFd$3!zqq!!vO2o9Z<4a7Z?!1o9y)%%R#}b zNtY?J{AcK1Q3hoZG%p%bFEypkFpSC@P?r+dD4KimPTfXvskr*^tgoDUnkPU5kZ&dO z(y)ZV6bHaFp2@=z9&{-Uo+t07e|MN1m+yz}*BMB`k--PC_-QShsPPXZ_8pJ)*c98G z5WPXbXQxnb`B63Je$RT3{WiD!U8PV_%kO^X%>mp{;;YBut2X)pdKg7AdoPrJ$`SvP zH|z}k6wW=FH#0t8AL-fziuoPS=-~GjNm_oTqL=l!&_ixD_^I0l->n|)dXc5ds=k$n zRg+d^6e_)3wvou~Dp#A=Gv?mE}ZxpyF3N0xNotB#ZbJeG?rL_g)bKE1g%qu-0oj&+u;uS5Q&g)MZkw(AT)0C}$}pBs^spl2fs%02$&k^KIJZ!=;C z(3WSuSGSFVzGHTOE*mLLdpl{l+J7XQ909lJt88PKpLRY|B4T;hKMWWKY@U*B@&K>N z6DJ_cQfU^xF36iU@SF1QzkzG66;XVY^*A6p2GWh$DkB_WYLRgaE&$D!NL&8sL+TT{ z%^;~Zt8c$r88bYXUU&mzqxZ>vChEWVYEjhn~i+Vz>R3Vi^M&wwq@Uq}gP3p^5WIM=4H#nyfbea_LVkOg6XH zvrfiqKjFxMD~WlVzj4-UM^#kKrtw*q$p;z09o8hap*ocLF!O;$7>FA@AwjUFI9nj1 zd}0ouXE;zkU>i(x3a#oYATZ-;c?`cMYQSAfWDYO`PJfZLuhE0{f4*Rtza1H`ra=aR>iW%{^n#0Z?|?Kh_#Ek`ek3<9N>lIoq3iqn`A>MG@b$K7Qg{lNS>yv9Pl zMI5^S{beuvH7L0i7ys^y1mArrS1nBb%a)W^HZiQw&)kc_ z0hILd&%0enuaRS(gy$P%c1!)su5NQ9!9lyiG0gA65kjbwK~H{AWV6Hko6Y0*vn8+j^8k}r~vaDCLFD$VY}T*`KYT41G3Q&kf9++|a31t{fu z*qrHjVLQh||8oLiA?l1fhVp{e(^p*$Kwq>-r)sf~xt}3zIhjE51eREZ2-o%XXLPxh z>?ptHWBgd8_WJC2+5~GWuY=ew#1bfwVcz9iQhxvqe$-%Eu;ye))Uv;u^IQR5IvJW~Cim8h{uzp)ilp8h5JKwx$s;`~r2T`i@y@E!P2~Q@ zT5s}nGOQ&=ForU^W0tl>M`t82iaC^7-BTY{01%hd7?~-r`~B-pO%~n$S_PdorE?iH zIq3@*mjl}PpCMBWRBc*<>Pm_O3!OaWEx+u{US}JI?lp)OmzsXP9y<9d5T?5#61$6~ z?YNmt9Uda5<4Sn->_&?A?%)SwZH0L0QL`8-s`TjP^w!_c3mzVa5w8DU6_|`F_4Q-i zq}I@`S19{%bXR44eAYvQlt%PkiX4dyi;3R707llyP7vCJNA$PMWkRau;?45EcUJXm z7kH!@(n<(Ud~*Kct*0fY!aEkC#Tyj$NBb}9u+O#RtDxP@p^|yGal1--0R;CSwaXA1 zXDiK5%d;hX0yATIdinjdK3oh~4Agb1H@sw#Bnizs8~k+^Mi4DIy{nM|UZj!B3TO2b z$SlLUop0vhv*2Yz=~jPgUeOl-BL`u^Qx`SD4q0n`sRRh8w;>c(pz*2tSCjDy&f^B{FH&+gW2>fXCpI{`DJQphM#TwTMn z`+Q<;fJRME@*e6W!K8(s*9;{Jb^{F|rv}hQ44UUR($&aPrp_ht_FcaMVB~Ze>vjkE zr3{;C$nLwWqq?5$u0e)%K!Zg8)B7bO!Pg<2+j8&kl!UmXM2Jz|gdGA;&|?FIN&BVw zs>RsfI08)jn`jr@X!e)cgXDSN3N&WP5Z@6d;WL@%jUbCNYSvawIxOA5xOo)B9m4~G zQ0<9CaVV+8$47Mc@A?sdAI6~X8j|BMDP^@Y>Zr5k^>5ct@zp8?C`tPVV%qP}lXLQ0*lbFknE8l(gI zwu9Ek@cF>e{loCo=}_g{SfV>1GQj_!B`VTdI9JW4x76Icj?gBKEqUp(@B7V>yH=51 z!>=Pg@1PSmu?Ae*q08q2#TwnOHZ;rq@?$j;{crh=a~ESdo_Vp$*4YQPv-#?GIzuMfOmMkN z`M+9F>;+tMJ@O{D9Y|MqJ>wSjequ(HUaPyK3I#p; z?=9Is5egyv%&_J@cGh*>Im_69faO5Wv5+$Vui&v^npkQ1bQ$bRy^gY%!LNQr(ilf1 zGXahS$JNx{tityX5*Wxdc5r7p03}{ z-D6FrC2a8u4wd(LSXTz}Y#m|;Aq-&TLNh2mJ+wsOA`9gek$i;31T1Mt_22CzireSy zYP7zs@i0%i#5>t86X=`ydDVAAG3WO>ihbZNa8&nxS@~pbNwIGL^ApltaJKvR@hbTr zFPGd$)YRSpJB~soWVz&>5)f&Hc_ThLO|#+@Qgj}*CUim-8;Q{;b1rq)P-Q*TRj`xG z-&Ixc#c$nC()E=T)3^n$Cr%q{16(o7{)#ciPGdEy*_E!;MuOzm>)4kzRE0l6XSz*2fqf?Ep@Ri=3-cyHe0cm3);7VP-nwI`oSS$TzQE+BmHpX`Z5Go<J>iX+?x$FNn1$YbPXe%{h|b_s4HSrlld za5PC=u>7pN(X%ELO-L4L^JF^0uX5U;Lp9vN4f^)NI+b8JiEKq~e8BeWAxqF)PTMpX z|7v|D3zokeAdDok|K8Ie=k{ak^{#;7KSTsHh#W4Z;X;-eLZ6@Hr~9rQ412sOFXPx9 zdq}=WE!HN~lM!ySdjG?8Tkr>%`XpcYW~T!>nsibeAK>Xx)y_%s?9l=OD4q|)AJ)!G zOlUigcxzX7isdLs^yke5aXN8n0K;7gd1*iD+j5jm5+g}4=)f2@RlWG~7oJR4ZPi{K zr$vNFz7i}e&rf92A=b@Y#S7mTVD7{E&8mr&9iDKG$3HG;*7%gFJ9Q3iG zntSR8`tgtNVnGa~d2bR!LiHt}6s!}=k=}_a2 zMficIB^0^=C%|FB_ZmBb?-mgYN`i%Z-}9sLJmHUqx4u;=2&~*}>G@Sw(wMEGIR!a<48t2w${6=^qAz zk|M)}sJN(cf&CE4uj0X5D8koZxLU`PsIOZcM2^x-Omtu*qm;Ngj9(JH#s6^V`Mx@| zvKe3nY6ma_aJVtjOjI;;W02q(vz=5azYaN z8)&O9QZM)KfKY{z-Sc#YjqSd0S~_CT4u(2CkqT58M4lF_fxISnd~qXHOI+$9u?c`P zQC>SAC^3*71dEW|Tyl||WraSqPK}uglN-@tQS{_QV4v=;;p4^*v3$%K81t!tmneF_snidD5-=+gt^8=$Q>z4M93Qls>waUivo)jph7>-h5%0;Y?cqR z1`ogXyMkIGZ?XwuDHakG4Rm|QJYowZ6sX;&Og}gC<~TELK|L~9dwSsvRXM%--O+Uq zs4$1pyP%uey7#MbY{$Lq0guYoO9TGgel#Smr79#_=PPiv^J?6cvjXQ+_A;&8$#|a# zIAn{No(J7XflK|}|8g+7>mf}l1HFGeY)N5!aaw*G0kGMi|NafTr_61zdUjt#M|X3_RRF5OR>D#u-GA|u_8drkJ# zHF>nmAYzVIbAYivG}qnNi;iY2p78Kau0+cb07?0B+VFbP)r040RQNr;FgbF;|K@b? zW!uMa+tn`*btt)C=dcbmpCT7Y109IXUKr73oiY#k{MIaVGrXIhPj>yDFpm#a9dM%^ zVsrBq{ST6r1q!7u8`B@%6oqb-?;-|{0Bdh0T@nJwh*RTSKVSN!-BLeqlpOAojy^tBjRE>5kW z6sHfTry=SlKENwTqo*W5S1KiI?Oqm+6$Dj>W{UhAe(~}$WW`Bb_Ia+Q>}6!Gy%~bo zrJM2KHOyNqSfOa-Zc6wztj2iAogrnA?Hk4Eh@cS)+s;4{A~xkhNsmn*t;;1|ff4yr z^X+!-A6f)G1%I;dF1pEHVrg=(X58Y#8YYe?ZU$x;=vOL)#L-UxE)*F?iA#_pBE6$D zN{L~Y^+YK(1%$-r9i3R@8V$x~0z4iKrd)RHU7DYJ-m&`{t;4^!3mLJKuL=59(3))$ z{`r1#F-jwBD-0RH?$I|(t*Agx4^%T~Tg_dW=ho95jWuLvKZnr0wt6ONC)1qGVDF@>8fAR`^}1wlx-v&8)K_jVAJF2=JjRnik!YWc>Q|LtmB8;`)zBql-h z8c3Ui$u@7qXccZPV6kST(**jVYrQ9%bSWx3D-TF}j+V!n&5xsqm54n;9muWB=87x! z3Xd*{;Jd(yOBZn1F-kyYjePWLq#+XTk^?@9dJn$F?iY8QS#-5nD%dx@^Phwd^)(J& zwzA!*ls9J|mkQ!E7{Io7t=Dxv4LVzsr3lXrbI?*6^lpUe4CY)Tk+j?-^h7xwi%?CF z21ialDl%Jx=kRfW?}I+vy%Z!9K@Jgq^3+8aK1&aZVJaj5?CVPATcs*^5{GDxUoy=( zI1ftLn|v>fn~{pEbTDM@rtjilVn!<36WYl{#9-(4+Ybl|#VUREF(zKqJ`$Z{)8?ogP@XOW@+8RE``mb1C4_4^iYhVzek3> zGAH^*MSfPUIQ><#N`DrbgaG$xD0-8ObvgyjJJC6N{Alh3GOPVH)_rc~wgtWR`z7T* z$~jBGMZV`UBg=a7xJ@O>Elp1nsg1=QpSz$9w6m35xVtqT{ZIMTUg7)JLi?@qoYy@} z*o~zBGiK^vYcpCu?qEP;Ak&JC!i&LzCuIoEfr8Jhbt%1H4qa}ZZj$~ETA5khkYs$n z;!phA_>_tA*bg46Y`?3B=%B5|p2j+XQcgc|US4($fW{b3`upZ4>tXED${r$6<=Fy9 zS|{EAUY15NP%@8(f@DuLW$#XOtNI_8*85X`47mqRh?9OOjKz(^gP<=&q-Pvt?zZx^ z*Wh!_V2i~O=EP|sYY{|P4m;ia93vktB#?||U&T;=|8GB3(7}wM1M5K7`rZnHx%{?O zJjU*2%#hLsz-bN1`Tl zl_Xfww3E2unm48BBpll0=ppISstI8Y3@} zD-2Z**uRT=6D(FKPH^u{f?%#FO+m@Uu0zAqR*Z|&&1A!v;)5P-YRTe>BwWCI?VBu5 zl$|++LMl32n)*&~lTyk3LVsL`cz5C~$v|JLf}$NC!F`iwKtq$DLu1mDXACrw2;!dH zm+8Ym`}Qx_?52Rm6`A7V>X+cmKW(vp-40X|yi)P$R>U9=^ucSa;DdJF5x# ztbBidNO6IbbMu&hT#k`59oOB3^&E2_Ba34@m`ELETuxR#0>m$9_>nKNCaOXFpcD}9 zo$D#fv7h34oXr|eFl(^GLDD?~)&Z1uS*-N=ednwGF^dmpN|<>(NC*2*!^W|^F<+kC zkdh)W%WT2s%qa%s+OFXmSd7%@lS*d`;{tFiT=FZpPv{2Hw62(tCnB39GC`|?0is(g zPuM&jP&pY8Q*pEQ!1TphBxS%_dt=wF0OGi_{yJdJc>R;UI#e&YQgdspgSZ2P6y7u; zT;$H+5}83@+!WwHr?<;qd;z4#)KC-j{O2bw)Ab`X$MeBa)1U14XHRf^&ougl%qQv= zwCv|Oy2!f7M853K?s@q8xw!7l8S^mid7qO5dOmLHEu_KA?bvY*?RV9(>kwj8O6Se% zO#YCMC7!BQ{6Fgq|2F0F6>plAQy74G*xc(9K`b`j^>$joc6}Cav-q3YaH8r6t-@b< z{{eX;&?Qw9Sgu%Cp<^wr_&2JMm_Zvfy?NW8yz5WpAcP<7cxj2~rEUV(=hT1fJf1QU zV~W1mP!KDYE-kcbuvMZm!vZcmwRSu~Uy3`-YM+S_oG%&kbO@Bdd`v>vPZ6tFb8?#; zeu+AMe7YVkCv?D-ipj_rv1IZnO+tupBfsSZ9#suhPg?Ubf-yNFT13+!uw!2-)~ty1 zla)tWQ1q8@1$xpjbBwBdcoSKNp*ER|BwWQ1L*e7=DK)Z$*p26q_0jkv;V$ zj@Vkdh)hv`#HxKf<=1k9k|X?^oVJ>B)^*11Y5C0HwjFTMZ^wGMwWT`+>9SidDVLT# zz*q>nTE^aSa`Htjo!u^%x$LN}r;{?(lj7!@2c7XuSN)@Rtt=TagQ}}4?%zMukL{>-X|BZK>Jig zcRo5u2G1> z$Ao4J7xxC^8QDC&h!H#_*Ey(0oJ?uV^Wy3oiem1L6)0`eZ^-GGaZhs1JTz5ue%u_l z$I$9)*Qj^1T=7g>fG#==@!8acteb)D_Q$`R)tf-{dO%2uShs4X8#$m4v;kY((KxT1 z4W|*?t>+_Ojo=_zo&5G1y^CyE;GY&!ek zv=!3rU|m0T^y#KDd1|UZ*gtkjL%TkSj*<><0U2FGP`NLF%@ojPc)WX0w5!Tu!)w^0 zJ~4fFK(x*$WBnQnihEol(Tr~U5-RR)T^k!+qH$)7e{3Zq<_ytlq^`?-mDgzN+j8|e zTpXO*roU($Pxrcn64NgxYQgZLYwM$L>-RIR%)OMKsUA_hmmV)#RVNTKShD*LvI_;u zTLGGr1?@;j6}zlip_R`g`qlGv?Z=PjXITcrRMV6!Y@q$usL8el6+3(S?1xyPEQ}^2 zwpr3}D14O>6t2;X;KmMysaf|snF|GS-C{jUT#i@Vb zRdNtkU2e0urLJ1d`m!GZP!BD6{N__$&kfGZhe?Yr(=X-NkMaL<$L>bAm#aYR^op2e=~pdk`g)>x<~aJ;>p)1`nLp#=BI*ctG8>5maBGkP)fAE?N}SWK4EFH zg#`~YwcWlDaOD>a|8%v94EL_X^_dw#i;B zeZKze&bcLHaK$M-ojk39Aup7HV@&P544Y^EywB69sy!iTo#hE&*jXGD;D>Q_xc2n)Zv1Gf#n=l5&g47bbi%`muTcJ%9Fn^!&5s8eE z89F&4piJ3EjIJ&r7)xZ*F(okWjkCP$^nwcw-Mb02{zfF*0TO*zBBXi3Ba+t!V>u#w^?Lja= ztQ}s@+p^nhqIruyT#wH+RwjHwk@*Hp5bS!3MU^MD5|~rMaCWPI@!LKv62iyq>n8{! zzl1ODUXFT)9(%cNXaC07>%ei$NnV2F1uB9N@#dV(mG$xO9=0Nm!O>`I`viMOmIzu^ zi_4SLww7>P-DNO3Lt{MN{K+!tMZqiva$%yr|C(n$n-QMs5 zR1NwrHc$b|1qbVdJZMI=uOj38uYy&FBplf zCwIjVUE2pIjjUFx)WAx)1WEAx(8K9wZcyObg5J)h-H09Utq8pc?)ti%`$?{ml6j%g z6x-jUNG5hG^X^itRNx&4VEP#ig7KAfsd#yqj&yr*?O(=t{wGZhY1)%{*njPeh7vFE z=dm18G3GxkeEL)ygG5{C-;;gDFF(A)GH_wC&-o?8gh}+`(>|*#!p%qaCYmgVre9nY zx4D+TJ|4c2;W9x0?EWEu_(MiuoVdta&PL{eMUPRwnIXXUib56~neW{c<)f{W0f{4G zs!Vt<2%sDNfspc=-=~gj%%nY^p~`NzHp@fWB7$MhZ*(>ji$#1wU!#XU44nE!=?3yd zCLdJUp)2uf)b-li;|`qWLTW%h?{vA@1_5zkTFRDkWFTzzWGxgw!kPsC-A|UdtxnLs z%um;#$Y#-Jp!Na-o(>@TYeg^+cE85`gEl7^l0`V!W8Y83+j~1EF$@VO6oQmt`Zvcz zFHYFtCTe&GIBUX^JP@NlEIwi+d5(uvV>`M zusl!IpuNgX!7^=WdP&)jvuI?iiC-%obFhi$5&qv7u4VsK0e0s{Dm*!SXN&iY}K6tM0Y-!J^g3fdw;&XX_2N0I@ z^VSAuaqNrbfzBx6ZZUA#tpI)V>G%b&2G*0Cw{@0C>x&wn%BIs#nmsuzm2|WV4G%VQ zFD#hYUBe^Nx|ygN<=IaiE8UJTO8XTI-Ouw1YX;_~w^jH5N&pfvdwCx*a+_KqH+e znJ3;bze}C&7su?EuIgaZ(n|S3v$rt)fBbYrMuaVY&l46k(!sQ=#u8@bMh5yGCf&G$2%6TGz^a# zzQN3)42Wk4%O1a9G%m7h*%YlZhPpKWrg1LkX9a#R9LQjh$`?7)%Uu5*q3ITYKM9!d z@2mE3S0=c6zD2__S^dV`i2lTo!1Sm5e+lH1qfwRqv_e$2$ZvszWNa*yM>V1D&Ll{2 ze{yG|EJV%TGfAj=&8#89!~{wLeNLi|;}Az@IFh)TDl~-py_w7v&v(=6K`PH0Dzpgz z;*y0HLxvba9m6HRHQWk+`J>fId0F`~Y5|k51#)98t`zuTGoDBZW{mp-L!|ZY)uBo9 zai|YiL#-$8`B^}ZbYx#A*^7|$VF}dEVyL0o;+F-BD40i7`wMO|$be|LGF%y2RqGH| z#yPass}1fDPbDnMa}fp~aO(_RP;ORc44+*P4B(V`>QcQfvV5sm9rdAvd0TZu9(gD>Mn$Tv z2wld~(qJG56YVhP^H85+&4g_=X=AKRZ={*mQVL>DkVq~`Y{hqOz|w$sx@X2fZY!gi|X6p zy2kRL7`5+ptkdJt@2L9do18FQCTkBY&4K)Y-dAhy&ZODm@}N)1Vx%}_`v&1@$k)qM zhnt;65!1F=?#I^kPcFFPVIfONe54JNEI{IwOf7E6tFA+n&$F?{hN%M@zg_mDY4Oe5B5DuOB{6 z`E*$Nb~R_`(NvI}>9(W-Slvfo>7)E(R3rtnjpTGh;lX*JGuYxs4R)Wjcx>X&&z0y9 z1b^D`fM>idz17Sr^Wz}ZcwH@0Jyr@N0Z`dq_*g<q?~wpcmpaDS)6eL(lz z+LcL$WCN<&VYFEe$y@#rQ))Qr)6H2osPdy9FO1lnBKb`r27XXvynV{3$Qq%ne%45c zjJvh3_#2;-sDqAzm=>#lRzD7{{$2l0^Xo#E68qi+x`Vf5l;Uf%sY6pd9k$4Q`4yQ* zKOC<*HA=LHM|^C^H1}*0;*y^&R>70DdRUeTBE9(LqJ0gou$paw9%LSDO_dS4{n*=r z3p@cg1Rbir7lWSHLAyO~8>$|}EU1Od3=2*b6S6UoGdgK52vJYl{f=28W2NU<_F$Jr z0u~Alk}k=Z0#Ts@jy7&-9IhF!E|_7SP%E7N;pWAGd%+^tLg~#8Y-hR#%Ld8` zd<^d#5OGhkfwz98v{tvJzNKqz1ThI0o%P{x9e`^LH;+rX$0G_87R*4850UF5SuIvs zAk6vAMXNUty6xKccp>x2Bx|Bl@ zv)_K_C+Y%pG@d!-tozS~2Dwm12kd1B%Pv!4=pNhD3E4dT{#fxwu2o zCn0V~O0NLKXk;ScjBims-X8$nvskJH^ETbH+JMRLJs5Fydj@|cITzh*MC zezp2wjHO(!yOVVn&iiwePlr!u7HqL?k^k$&`Wkf{IB(u^7r}vJ1w&khk6{yuU#$;K zZ`ms^x@1;K#@$;py*UMRAJPNN@~8AtL=1(+d(P8GM8=^rE=~!j;kzU4q`UmV(WT{Yt~yhan!DT5 z7&GufyK0$tto3DAWQsKUuod+DRuD^)_RWHS&nBTExS5jY@dh!hI||dfavxf85}gj- zIywRx!HlOal_+(+It_2qks*CSgqA~(9eiZxesnZix`&h%c5UBg@A$*IntAF4acs%lh2Az#ePdo-5f_xR3zf^cgjl6TRvt<& z-#c2Bw$v*21)xbKdq6Gmn)MqmiMGF21x8{@i4qvG%09nOtE?Qge;@ouQx!jmBO}}7 z9FR2`?I5&7zqZ(L!I0ojv7r{@yBNb&ew2^ek~qhbms`qI_A{f1kKQ7e?^TUYM&g&w z%|9(?3B<>C;lrGgzfcQnrX{=R3<^!bg8+-EiQWgWW|^qf*G*#8+xA|}Ym&K9zgI1u zH#@TG<9*P)vEGzPUvr}R;%%jMSlhEr=j>ogsp!wZ_Y*JYQ8YN+$zbLu{?a$|o0o`8 znEHT(sMzI8QR)?f*I;#E2;e1*1C6$GlWC*>Jk;5R2cbhOL+DgU>4ED}UKE+p*HK@- z#Dz@k^8jqUCnlz>=MrM%@bF>bF@vi;Zwhfi!3mh4~KzrJGo3*2zgh|jOQFU{1SZVs?3V9c5vHOJoy9=s+iy4ID;{ zT7c07+<3WS_DO3!*xYe`wY2du^ij7kM_9}}4tpT?$nGagP%PNPP(JgjF6)`;nt$pb zDt(8LEIkjUpadh8!Q2T(o6u4n#FspGxAHHTp583Wr+wN{#9@V@m=Me-z!1`k1=Qby zC*EqZ?r<-{PX}gYnV6JK??Aux6e6eoh`XwQQ4h30~I z@K-v>Nxe%|LCNlP_k`u>Zm2?gQ8bYMxV3{SsmB01?J z^t4<~v)M7k)5NxeYVf8?z{+(R)5jKJw3Ug;BFw$=2{G<2^m z0IWpcqyfN1f?Lqa+a@Qa(ELD(D}grYf`24710iB4-D#P&e|^;?B-g!8szKN>2SIT9 zZHiTqXz@i~>2(joH1u$?>zpAp{xmg&;7A-41DVHQs!b>j$`18MuN;D5+@cOnVedC% zfIA2HG3KR>2IQ0=w_4AJ&WwIyAkro+Qo&ZFIV*~D*HFnDgU6e}fdPn|Pzf7-Zk?3K zqDFVNkh-eW|m)-o>7ad)&aWN2%8hY)y^h zi)$uuW*f~1(F9?k8SXKA`I^B<7!AoUZuV`rlQ%l_yl(!&K=n8^^-BWy0icSy3llzC z6?JSJ)+af|1I#Beb?+l4Skx79p#LesP ztT*r3hIllup6Z#R%cl_%VJ)B|CTQQD2}#l1 zZ}yNbkvOTxOdm?$$e}pj>FA@;It9VLNq5Vi{XTZC(?~;2jI&!{%MO$-@%F-Sa4|9sXqL-vi z5RR1|@E-U#{PXhBM7Lw$e@x2mprZ9JI=~uDzTf*{9=e9(>!^jO1@cDBMhjRD3!>H7 z_m!57T0DQ&@4b#^@KEw&QVUUTGJcT~Q<#wk>8atKrN4``(F55%SIfw{e#QCE3JsI| zSmx)D{ZD|RZ+yIt+Q%|OdW4;`-ti#Q{cm_jnD-%Q>S(WXuvX`zYqfp8JR8z1hMwBR z>gA{9OtjkhUv<-Cxaza{6|HXA{!=#<&we}@4P4_ACnv8dlBZi2-c?rpdLWe}5|gRl z&=%y6N?xhiKy`YO!39m)f+v-#UpSbE0~EIf@$M4;)zQ- z7MmFO)ukSuco%8IsC%*2AA$LO4RLhM!gVh~6 zn}+t%4zC>edhL6!RR5VddnVD*GxyB|b9Me+Rqy-?7Gdj4xCEUr0PT1RJZj&rHaPL1 zU;OpCv;ULvS;=>__d(?H@lrURYMxl)Uls*Mcb-bq(@ZpD)=R-35IgGU<{a=Bu0(`{ zcjKfCKXN3S6Z&` zA4HVw_?0Umh6V$eUE3il;HJF7XvI`4)Cds%Lb)gbH)@p7B3u#A7(l)WFB{!`I&MR_R1XNkO4@5Q$YqV;jY3>xOf94EZDwk_!*Qjdhxe?=#%j&1B3H(j!P>I zcl68eUK?VLy35Y)>E;aJ{R}!1qx7Mx#uQ(mpTnFtkK46cUXWgR2oQQ(XpwueCu;*( zv8W_M0sAmYqfI}S*BK<9DmRaX$H|xLa=dJaDU8f(ctucNEX(hRP#1E%V_b1tyZIUP zeR`4NNLPyfJ>K}1$&YR*E#)^hw|UHVO?JSw*&^?{+jW6Z_K(EJE(E(o3WO{4cfSn~ z*TvYGLJtP06}c414D%ST1c%y8CSu|9;>p9O(6AW+?H|1`>K6n#`X8{99~{px z|7m@&g4wGkC^26-{0rRLeN4XVn5z7v;0L)_nkEBg8ZE=yL<)wH$VOELU>b-)lvE;Y znKm)1J>`?+?CQK8L5`a=e3e9=mik>|)}`i?@y4k+sdq+7{X@R9*%Y;di1*ajbze*g z{;aia#c5MlwMLZ)cHW7H z>)_yHh6`Rnn-{$pX@Jw$pXxc54&5}bIA39-jAvx8yPeuOm%7jmSlk#TYQz7MJl?kM z{G7`+E0c;wty36rFcE);G_mhs|Is?@87L|9+@G0~e#i;xH{6pi2pc3IG<~HutVrJ2 zKWCPAi`nz6=(Ni@Ii}3B(Dz@xj0RdU=$#l0AG-9=NJf)#->W%u@^|_7vl)a4&iwlP zB!Z-e9^!itaARh6g7slmd^`KstJqQuFhxk4#DNI*m3Q$^f-7(I(@K-_V0bIt1Q>|l zFRj8G7%NVgBqpU?uzYEOKR6!`#mdGnx&RwlY(Cp$si*hL!DaV`vDhM-Soa2FFodK-i%+fSi)s79V{L8>AT%$Ii7S!EHX(6h-fg+Il zAHPCW2R7-4di6RA0TbBfxvkYhC(BW7UcT_LpJ2pVJyV!5r&c!yqMi{=SEDHmWRft+ zsO0I%kzX~_FPXPE$1318G5+Lemopp(kc?klmH~A%c-M0A1%&Y$ZPkP0@q!7d9vd)Y zLk(a&_E6}Is5&;&8}N7gx*lAi=DQ6Rruk2Vi~NqHX{*44+JJ-Cs*68t<~PwcSU3zY z&uWV<`%0e%hyGMS+i{h#6J*w$9eh1&=_A)T^ZDj(Ck_IGwx|2JsFMpxNIh@U>UD{- zWbGG~Wf{sTD|Cy8BQO#p*vUz_z3Q_5zep?}Ya%NzIgb{@88-C8ZqQtClu*@tmHe*e zA#1F8JrgaW;}D0T4niZq6ihBTfa7P{i>>oeiLFI$QuT05$3{dd*;3`w;GLi0yn=MQHJN15f;gW=Ro03l?j%HTq@E1+@J6NK^RHIPY&9t&ve^Of0 z(Qif6o<$=6QitIk)KTdP0{3v^`o*II@{`BA9dvn4+>OMnN!TYj_GUM?Rc_T9jeaVf$C1!~Ih0^ZEDsEKl zOq7J9VcuXZ7nEH6ly;%2=Xy-DIr{CJQytkmp?0b+gvraVW z2Yo#HXTNaM%l#lGEr<;W;C!ZiDI?~#)fO!_Xj4!d-;lxCv~$m7u>~p%*4tcU{T?i% z038D;uM%u44iSrgdC@=zp+ZwhG@ePXiB~%nf-4_B_fgD-kp!4YH(+LUnFePEpu5$Y~i6-0HKs~fdsD1NXv9f`TgNjQP>w2B)R&fLg z-3TAN@QV8iUln)}=YJp5_^Pm9Ne#iDBq}J1dgz6}Dlo;j>_}gq7-1Z`XO{n~?z0}C z-%iazmVj9oYo9`HnaMAI$Rfx7e&r`Kv8^G8-c) zQp!ocmHy1scqq7a9vR#(8jrbD1Q?Q;35>52T-a~LJ@?t`<98G0hj>@rj%^MygNoT|Qd(JAZcEoCQy#%zb{>(7+ zG!AP_;%B0wRGr(L+17(b`^?i8&E%3GaTw zdUt+YhRq;!6EQniIM0F`6G!}-z-w4xFu^_}L7foT=PS+; zgGc*CdjU?dQM>DtcSY-bpdPgY%H*z*oqU}qDleP1AmpD|gx_XuvzQVo#%9G6Qt-^r z6H)`wy!ftf7Vlx^6KFeE411};`Bjv7k<91_O^Jmw^N8Lw@>j&-?i#f|F=czwP%K6y z%Z$Bc1f^6KTPQ2Lg6^Z_EyJG}hy9lP#qY2Cn^(iw9(#spwbK=xKxhk)vjs(fZt?bO{WPzZGtbF3P{7~B zM3a3H(c5|C94od+rqKfv!%3Y!dkW#SoFi-6{lDhx#)t(xW>(kQ=<%NvE85bMtasB; zaxYXI>WskDhV13p??$%2RUyZjHS-#I=;N(u!!WvlkP>mSo1evBp5X@u(qUa>VW<O%ZeQ%|R)~ag2cqBRBK^T=B!ou#zQr zv*TDhoT4|KZGa7~F~7?@eDLpXI}xb@#om^1jUD!RLN%9KJ{-#1gpA%uQ z*XDBRT~ZJN4}n^>n8H=?RZcneV!vT zVTU}=4e-N>u5nMEQF-f^^DUqHd1R~Sz+(Dv5FV^@TAGe$RN?^hXlVMVJ88sE@`RRy z6nzAI`|Jt$N_L)(zlDz>$boK*pUpEWfy07ooT;YvDGttVp(~XIm@`8h@%+aId;(et{S^44j*IvSJCjQaJIsw= zq3-AVvh6=gQA$7|PXh}1$8@r_;_WpBC1N{?SSfjl;YS^KWA`JvFtYw-hU3Q}O?FMU zNJQP>z~fZG`uwWZ!jwwjm2gM+q@P}tEQ~I={Ke(d1)`Ujj|nNMXisj-I!iO1ru+2> z-j_v(bL>Sc;IfRnZ)NzB%)U(hPV_e``i@1Vx}Fl>RlZQx^otVXD>66CRq9^zPF?WT z<=|@*r7)&I`14|ieH9A6Zv6;M3cF2saBz{ffP}^-UsUHK!62tdW8dEa2PEl651Iug z)RM%RkMpz0b*+6OWs1#FywS-~x)X~(_5vF#&Su%~8%_+nqNW$UtzP3DX~pu)bNcgH zQx-RU@wavLAeXgjH)qel==ToL2-qfH+dHmm{I(YgRJmgCraTFRF8{@OH(6ZX6Dp9( zuDH%+-CePwbme%j@EQ`GFZLq6A?0<;(x1PMv&|VMFC~)4hz7{S%h7cM;>C3d-={dQ zT{juFc6kKtTta&@jI5K^^b-nXPxz>f&fh2S;Z54uWrLVxV+(L~Xmf(&bsy=1-m9uhcM{7K1`sHlIBn+JCF1>*uw@GdKGyM`fR-dh?t7x7EOR zQbm{JRL7(ztM6Y;?8Qw??0me)wQ%anXLvyy{?Un5(KxQhq&e%#IZ9-3k&RhJ_xlB{ z_+EYDh@>FhX+BJma{*?_;Uu~UyA297pGw{Fd_8~D(jRq0KnM)2*Dt87zVV`JU>^+g z=`{3Ux!jNsmd2=Rv(0d1jUl#jUXm~n7K`r{RngMAh0jE771iTYdOBlDeNZcE4%$G+=Qnl$d` zSgIxy;bQBKFzWv4Pj41}g)_IkJa*~s(Zj8XFpQreK4}Boq?YCqdNkA()U*qpDsncC zk;HQ5qL7sHoJ-u>3jEHQB1=hpT!6Cl{Oi)UY5W~$4*Fo#M!4SFEdpBC9Jh7VjFq3DE za4ApDab7vf_tD7?z%WK>L~_0}$esLybN;eBkV>o_VdHiUCpAlcyq5OFU0*D_wl%p6 z%%!nVU1=GBbBDe4>ckW3nwFL0tCy>Dx^6qFhWT+h@`~vs7J7qozj(%(((^y7Ux?M_k-e;>G-U!{xh~&en*k1o;2Ga-9m1yl=M$Co% z8i;DQZ|u*;^}kxc+}K8ZU(}1)lX@z?;RR=p6#8dvY*_){VpOVyJWm-_afu4Ej*{NCN9$J1sck3{06V82%=hLh z_?bzi0~Nr6yF1>i18L*fNi|2H-Z|N@W*Z?30ezc$-T#)REvGGngwi{Y;96dy`{pDh zxTv~0n}j~&gY_!M(c6Y0Xg4@H%D6W*2v4Gh^c~sho8tBiFZ?jiQ$&yn7IO*<%*Ww< zRoT7wry65$tV_{)=1c68Cjk_bLLX*N%y3D^FYkLYcT1n}tAkPK!Ib)=X?^qSTYf;3 zE*V0I4A(_d4zji=dUtevwfg&g;dALT!;f!b2m*%LxsnN7@Tvv39IK*g7&G|gL{g8Z zH6MNK7=4#%PezJ-im`}*?)`1-^@P5s)=A*O?9i?9;C>`W_^ogySMSrr;iq2$i5tgF{x23fX4cjYLV8Axql9A zC|ugbe>7BDdVu7cYkF@#bu@o7c#PGurWvKgf-{1rl-HVKUFKs|U#Y^#6^5rHiB1C0 zS#;HE1!BTld!%V-J=o!ZV@sTs*v|DM+1B6X*{ava4xqc1NNWp3Frct3Wb;=&a}8i+ zj5Ro{6RIrjLrpEdTAX4%>v=37DJ+m%c+Wxm`Zf{&{IvGFiK&ZoHYyG~GpiMeEPE4Y z$J@R86^e35Sm1f#l|nwzP}I?BJwTrWjt$X5b-|ya2*laOCU$x{I`kK9drW}76x9?J zNN_4zi}wmsj7*C(yLyVfFE^txbMM`N(oU8aNrTB#XZ7t*OMz8;M%a~@Nor~>S5 zqTD|X#Nq6DWrX`U6cULL<)O#Z4>x5)td6-i=^sjQNXekT*`K;;d8O zxJ7Y(ft*yT^jI`O{C?J$=NS1g!irnieeOv+AoZau$pQ=1taT?chq>ksbCdiWVofnXHuKE*RjcOaK>ZZc|-;gRW|dvr|Pb1oMvt zd!@%B^~4QQG^2*&HRFM7`ms9Fv|X9h^-1cEtwrT0O+E*oUhnl9gx0>e2o{j&OQ^#w zgut~>j9(uNnQ!$7q1$x?qkOltI_yMBVr*^ zE5VvoX~ILyN0q$>=r6`Uz|4Q#{4nG>rbM-7?cACw6iaRNX`aWFS;RZfNNSKt4o*46 z7GJeA~1`@)nzuL0c^G(U-}~6#^vHz9<{{`_C;{CNvkV%6SmX>uCoBEy7zp?7q6jettvm z{Ry(1)wpA>WBiw7FGXM419xqq)b;%QF_mw?gJ1G%F=p{z3f(QIGN_WllxJ^RGvuF^ z=gp*$((G#IL>mhiKXfV{f8Nl&&Kj-+RJ^tK^0ldZ7NnTtCC%tv{Ayqw@OFUt+21Y{ zVGaG;joPV+N0n-eQ($F`aJ#8&ZE63W~l(Z?x ztV*oSm}r(@PsYm?{pw5^J5bA0xZ2F}Xe zE1fKZC9Sa{0mRNWOCuE{)bf@5m<0!JzY~WYMLy7ITUd ziY;FU>)OC)f&hFrv6!?kYMox^T_*?;ItQVcq8-T#8a6t!CYnxsO)+UqH9_jMFg2on zT?7?^1|b2#fgzQ`y^;C2ciZehqlEZgrxy{zX#7KirUl(-45GZW~V_Svo7Y;byHh~qm0MknXCBl_$8 zUpRj`UVEBX*NNo(>y&HJqrL3db0BL=#Wj=ipdPV3R{j@Nw~><4)_RVRsVIk24XU?% zl97tUT)lzNtys<*yWc+QwITNcrMibf;vm5x6zCNQhfD(Y9{EV#%$dVYbqak+aLS43 zPdLVp6D(at{ET9zQni<7MP8y*PisDruI3&#pi9tOy-Q}<{>;!W>K(A%B5tAqu@ji=EkfL($SfEZ?PqTrjI^q5I;N@tCyR( zZs|#{n_H`5^5TpvzBIPHrI!E@H3EePWdHhuuj4W2o1e^X;`0c%xLk6%yRQ69eY}{5 zhNqW<_U__`*KLtVHzTVtCdgir&E^XjY8mdXOZFa!GxvkMIR3!7QY>Z_i8;QsJLj{z z22HQ^fsjuS)4vMQZ{R*5r1x9F72M~r1639*3g`hXi>D_Co1^uZm#FCKRq9e8-wfT4 z*2Kcub(DIyJt{P6keT`NfRgdM`-zMGwkQ{ySU-}Cg;C4WX|*Op)T~f+@m~007%5yk zMaVDNRnza0hWerD^vlo@76I-83LM3Bd7Ya_+1`2%;wiC1P$!-A$7?O2q3$@50%G*M zl&atZ=P`#RLgk8o{2~aAvyKCv=?iC9KxyccMlyx;qLz4jGTt=^RXPUigL$>)9R(yl zaBfXP6bV`Ix|t_8`X*lap4kh9SpsH+xbfBpuPAe^t0nKffWQ@fJ0JC)Rr@*Y{GEj*uoKW%?0OZ-{v7tj2~hI6y8v{Pe+vvW*2(UIyhDMIX${$wrr z;kA5ae~c*LI0GAU^X5Wgez?4S^9g$q|3Cs(ffVl3i!mCloM0P1nh?!Te>XJuV$>sU zQ=7n)bKdsaQ9e$igH~~#Rf|lC2it-YeY_C1t9sd8>^7 zR8cW*x1(de{j{Nytu)R(OYexvhzuhK1m_AyLBU0%ZNvLKwhl=>`HqRI*u`gt0p&h_2SkkyNV>0xy z@*b!eo1vM#K~gKfHCFr%7U_o8ihS{-U`uhjla46;4I6yP_(GbKM&e0Kh%7~hx^l@{ z?@|hL?*JwYb>9;ly4W0)@wqNFyt}300Xk(QZE<>B?M+Cfd3Pr&7!Uw=|F2&{p zso+MrmNf%_V-J49HiH%&gl0gS`-~-UX%s?+8v6QBqINSFwCfLd{iply#l+8_T!YN! z^KD)YxA$n_>MuYR5&+(eahYgKt*cxsdgMSRJ^yE#prElRTr^Xgja&GV>UHv>@E|{O z z?cxec@2=$8{v#c&pGT4XM!36fzA!j2e2|{kVco?JS2M?+ZZ`Msz~jv#btG9exqo}a zUVq%T6~pM@B-58_@=5$0d=a@{sVxJ6YU&NMEPky`WeT;Vj;Yzj@#|&o)pqFA$;-6L zTX-946;n2Hw2=Dd+cyNKoi9LSnt=Fqp{6y~ll{zpZiLeB$9O{qP*iO}>n1Z`B z4#&mtZjzJ2#arG;&wwR@DY{Wo{X4Wxr^w~Vhs}Wsl6i+&O4I>34w3a-E#~@ zEVw3onYvsV%Dts{Dm!?~fZQdKM8$JnlJlWs=NRvAbA4TqnLd7fK0%#3) z6C8QQ#F%MI58--Zvj>&(VF<^!F4B&8WS=ehUOZ`J@5EMWY^ac2mW=4qNNG?oSm^A~ z3B36PV)TH%!$(MicpwvqX_8^-@HH`paB|Igx!$locf!A_Jq#U8zMqX$4?hQa3Er`3#rIxQ;n~mn(3v{R_ne$7C8II{_g5)bvmCg zD?iq8MV!IH9pSi{K;5JDp<3W_7adH0<9H{t*`#)2gT>6oUw=wkd}yy#Am@derE-vi z2z;>7!ybEY@H%UE7*_{K+pg)W8#fcb4SbOA#S9h_gy0QB<8h-yJQ zz1e_HisODI_mij)r*GdEpS&1))U{*+oFsBvg@Y;3Hq_1uAqv5vJY;i25hYMx zx&*kKe+0`*GSr7k$n;av^dO+WBb6TF4p-klsCFBb6mV?{yw(G=j4%CaJ*v z5jI605)>|&dWJhUyWdYth&q#irLb!uwBF%3iaQ9VfSkPoqRr7C*PmOp+DrxocZ+Bk zVU{d?Z}_m8y$lWh&kHd0IspiGf$P+Bdb&2qHkbZ^Kj2@$cUb225>TA>mgwGS){%4KWn^0ZA{iuECCXEiK3Tt9}uE=dWin~X&q?V^$T zsk7y7)#~Hcj_+45X?msjd8Hup1s)yk=F+I(2#;K)i5@8%)-{DC7b$YP2Vy)-SG=*! z*fn6y#-Fl9yp6?(eqyI&M1LYw3j5$tfcINUWu*$ciu@~f#8snx%jwkLF8u_wz&|d` zo@OjKH6z2hmPLt>A_wyZ=xztwZe4Av{*W^v)pkLQiI|BYK5lE2%(WvNCoKQnGE$LX zc9ZZy!04jTqV^M^`pE<)>BJkiY$B5X338J}vQBZt71aw^yVbx0Au`AqQ5GSNsR!R> zLk9e6|2>ZlAn6#-{Dih%`bQb-5q+{qS)ZEJ!NBbexr2P8V-FR|cMo>qhy>+j%Enlf z8Z9j~8lp6&cPhz#ozrS^sm!C6tel*82T-gBdJ9Fri@k5iPaJ#gt8j!RG(Qb&>yUJ| z-KzBY(#~L%@o1g9DXRvUk6Lo-A`e6d{S#P6Ne`ZmoGXnRb-sAMAt#8$fD`Z|vJD8X zdr+?Y-D*+~Y z4jDda);H8G@3)lwPfyIc{ESG&!i|vZE%9pDdxPKHD0fjYH#K>9>2oQ-YqGKbWDQuF zQ0M`yO!fd!rG9&~dr>O|Q{OQ}1>H01xWpq_leZie8n|c}%SJ)a4<6x2n+j|WcVA9)jx980S#wit}O1a zF5f0aA#_K435DXE1QOxBzfRRaqPK6W6gx+ zT9;Oe)V4qy(n%V1M4F)J}UO+Xgik^z;K3wM%j9C2SCI+G!TD`J z)ou($DIt`{7b~e4gtEO;jaJM1k>F8@uYGVZt*4H+s4^#Q1hGMvi{N-yD*;qmkt&2w zUGf)}hfAsKLZv%t;=71BZYUwVHGsB;AnB#pnf%?lirk`APq4?=uOvdG1DEvpCMRK& z9W6RsJSZd!t*E+2?>Xc%nJkO0_WMoF&f^eiwl6P855y}InE#GdKFoaDh?toD%IEiH zvojI%ZTr;iae$k2Te)8><6=KYTJXs|NQ+Y*)vWoD#g3T^c27#&fnLk0xnmWe7N$r) zOMoQGu$zZf7*}|QlW5bEF(L5@GB;c4dXC!Z!j(MWN{iKEFL>>^QgY0OFzO%&R3*^| zX|X>CseKpX>NB1G+CLQ5vAW%}u{IC;;e&mvqIT9)-W=6R!R=xPp8;MWrq*jSJR%Eu z{Lu{R(rznP_;ISTU4{`Kn^7I>IEjjpH*g=_OR-Kq*58>AGgM{Bo%u*F76>ea9b7yBOf^KV@$GwwS(~0dQu1QP%Y z4%B_@SJBiC2;u=JTG$xG#FkE|>vu)u&E@I=c4y{o#HqqkSNsjbr`;dK6n65#Kg$3$ z;JZs()aw|rFv={7gUp8Mm;-XoLHT7#Fz?|mlYCYX%sPklApWRoDnigp2&F>H-f!Kr zHgK7)T$a!z<~`Y}7Z{GT%L)BW9?x{|QJ94|&tHA9$}=72;ak$X9CSqANB>6MNqp*v zLcwzuB{jF5)1}6tvxLjdJzdb2sIeh*PiILTbmH3((v>joyHN4&jYRNtz9e~f= z?K#%K_Otl>fDZ>Lf`0g0TNni9-YM6qjjLl6?-27#;N;ncWxx`K&rJyNLZ&uJFGY@72XL(dq^4r3fJh zSNv6q0TaegO^tCK&pra=#&p)Wb#5#BV$}WT-MwtOXJKbjK!XjEeLb9vEiNcV|3s%h zE0+Ds7``a_9a0J^XPXON!dtS;JJitobZSYio>VP?oI9nbEoAJZi=Qk!e((7o$U>Ph z4S9?rmOk`Jir3SFqYdk9;7c;gZ{$$;e0l)MF6@K<64emC}@``_-8fip2w!pl5B_t5u8`>aP*LaS)D;-rl=lv&OPW7@3v=LB>=O(d} z;40yrlbn2_ty_n;DTrPlnaoHwe)MDs|L7Vj5(X+3W$6)KUA2=*X}G!M{LsYz4 zt3sPph$4U3vuI}KtJb~>hsduvI@3pW2DB8`7M*O{JEZ*>O!_WJ-C!%0wP`P2c@v2^m+B zX8?vG0@?;9@%*?j>sMZHkgY!+9D`jm!d-oB8+}}DWtM{e_FAhXRlj4NHRQl(Mt4Lg z_wuS`KQv)i7|A*66ltwc!Tq$s5VO3^5}<`hlW|ZlNO%^xfqge9%BE8DB=AIy-9P{| z9l{|(a$GG@X{4}i6?ohYkW=>dn4VspgkTfFdTal=W?74Wyg+RhqK7hv+uEm->dsGW z+$D`E;iGU=IPD3+3F_*%4IAKR3C3>WBEc-A-oj5WOO$c%(y_VotNtmoF4^{*{C&o~ zbC>(>44!!K>Gj885vkeJO@P%sI$d%22j|YPhA!InYMSQ6`xz`2jF-sFb!Lrdq0vTB zpEGJr5)i?FWL0Y9s+4ZtZhps)UhQq=Ur~9`ZUIyS`tH%LqRX7C-YJg(pUX_6H5bP8 zYAiEy%f`;$u(XlTpTzva3yZC-%Az8BE!M9HpGuN?;P?n>0(K1|bqA9z{C3b?f$EoVcQ&>Mi(81~+5%~IOQ+-fH4(qt|M}Jm zV@rKr5eDe@{{2j|L79NAU}HZqNHX~N+B}+xMUtk22{!A$kW<%mWbv_D1#KPS5^*;o zcKcZ*zv6o}B@x`oC7D@hm?RYUhA#M5}LbTC#=m? z;$auQQ~yaA4=tCK%DHdkq=R1K7OU6KJoLYBSJ9`3f8bOJ+r2vf1RRAQBtMDb1Y5@) zXV$6I)C9cqi!=QQ+!tv(@#O($JH*5=L zmR!T87e6(DF&i@XGz_O&#Nva>KA8;;Q(G;%KQu{UH4iK~47B5M`Y2E=8k^)qgCH)F z(1>djPAXa%+U_;qwXfgVi(dCrcXlj=o`LgwGUUsZg)^yXxa`SNCl33^3m4)@)w3a% zws?w0PBI@OR;G29l|%H;S^JdvC}L9rbUTyo!jFe!78iT_`mhO?$hZ-mZ;H&EL@9?3 zbv*0ZKEGP)e@hDbAj_wyC!M8xXnU| z^sQOI5hIZGG1+DP1z+_3Z^@&!OUaqAz9c5-5s}Vs$uBJD>vc7Zm1)nyZYi6rek{je*o&~S05EQ>q8(ylipyF9u;@(a`T&8~^)LhHPznf^!;l7yS@ zB|Q8;TNu&R3-h9fG{yu<)>4H7+6A^Ff5$hrwm!A<;Z-{L`v22OV*wYK?EaD1_O`4P z^FPamV&>k>aOH&n?$yNo65*-;np`^3>kx9eDkF#K+2+K8sk2uh z+q)ULUt;7mOgj?bm1r*?;bE6)8?wJ>(A9l`(_&y;E>J*ib9pb5V4H83S$)}r4wN3U_d_shxuoUROWQy&V z9~oKpQZlz`=1KWnVXllc?%Badi8vNqkP?1Rh?3YkhPx9*^lehAiIS>j|{B? z^p#CnR;%14EWIXzrZ3MU3;~@uc-S^oZdlVB9FA%rx}qkMho~+7=`JC@{XXyc#1tq2 zwdYKVbWBNPirBx?;3&ZRi286IbtNtvz!S@mM$o&vj-7x_3|0I3a1@;T&jO|2D(yxa zzwE6mpWuLHha2|e{eY(*>HS}B2ZuF&PJlmAIZ)n%icJo6rm%4%p9>VLY77zW_nN@V zi-*`8ktS17uORXb^M#=LYU!GXtNH*2X^35(z3jBXWsrEg2O>0-Jh${+D7=+f8&7b^1N<8UO#Ai4vOoq&ma zp2%bXechvR^f|O@b8*obl14kyfE z)+Wq@Bk7M=FgU1@S{(X+tWjFZF|(i)X3iczq^x3og$5XdIA1T)F&v695FI81aw8p{ z{rJkcF4?C}TPHWTzq7cwiteg6y7@&QF7n~*hJuQy0FP~ad?Q?ZXR5Ip-u21%HP|aF zjgDWIw#Vd~z~VZR;Gq=Wnf%%d8MFT|(LDeY@f+keysm>Tb7KOiUsYA<(ast1t@q2m z^-~v#aXK-sZ>h#%$jsPR?-TF+-A#w`vW__-84%GGG;i(=%iFur%>Exou!hGwbeSre z+oM|%oRc z+kcnXD-%2rWf2J&BGll9G+P#DT1$%GgnIX0yn*4`s$ww*eL3r@Hu|qYlc%s`i4AEL;4BWvd{7t8uz*5a99LMpd()J&+Pm|z-EEOsSA_g85jjve{fXX!t zIu#$hF?aigN4(yxG|1Asm>B_y-4dAt_*{!tNh4(Ok#k~twk2X;L+7bz$Z@XqHQqelU7g)A$p2_3u`88N(^_@Nth% z=gPuMZSWa6ecfz4N>Dh!^Eus+C;0aItv#yhX(#qIYCWbEW~HCaF7)6{b@nLL0BCcQ z44;5jOf7|z1RMoHCUAnHw}Z7+BW*NOn`^&mLpQMb%us2^zdOcdIgc@>(+q9CVWX^?#aKoIptn_VJOoo+z)#brxVf%4kBHm z_JFz41KZ*x;~UQU0%z@*xVlvTA&7T_6=b(el+%9_kPD`Q^(_p*D_s)_p2z|xf+v7@ zjF?LpuZ`d;DKM|*7Uc(C`oy$&d(&~?nR(P{caaWJU_E={?=vs?B5i4SO?3&&% zN6kZ%#5!WDp&yB({(i#)cL8>7gdJW0kt;J9(0}Qvy3F@B7nXxG8m@SYRw7Ms_@fNX zg?97_M>C0k*jMo%z^Uch64)vH+XT!Lxyyn%X2{3wq`sl@98y`8^r{q&3kZh`#C`R0dj`m2nCNTb6JuyJK3$U| zRgdb@!4Ss&fV-5brZUm3CzE+(!|(ZaLN{Z&@jh$C9Myg8 zjSUheR~3E(ghwZx@aAB!9P-{SBH*NhOT5jaiw<7RA{M z$AaeJ&53K%?ag(h38Jhdcp16UD=hA>eULKvjee(oH!o6q`wz{DF`*Bjy!#Mj{8khC zH<@Yk0ZfaZri)Vqc*+4QwduFW zZEBJ7w9?rS)8ayKhbo55w(H^izJy2s0e3xcM8;A$yj9^HhG^b;h!R7<*5N}HfmYAr ztdC9No}$(6!^lK&vtp+s%y8wS&2rO5NxQa>addHq*|8O4*|jFbV9Cfms)D@FDW+eY zKNd~^&twnKeE>ES#5Z`vzF>%u0BLv~K;F691`|mVNaD?!am{Jy*GsPun|)lo+-b& zP5QOV6fKGj$T_7StBR0f21fuh1-A*fW^W9-T}%>+jS)f=?n^w*C$G?D{8zC=bG3=v z%uoZMOf^*{;&>0qlUU?FL7go6%;r{OuB7C%}0!Xee_JeM8&!}rqcD!RHS zApzrJf0K*YCZAS)QrBj=Zd-Riglh(dh0FY@lw|COchB5`+c1mw*I`70f)m*-;=*2UrKxf`&uy9|({E8lV_$YV%!TOq< zf}|?(gG#e%GXw0xH<-ukS>j>47TRt%Pm}qoBd32=_`=2-2+#z5j7uuw8?{L{E3i}r z6V{}GTc=HA!jWxiSI*qZimsvI43BEJseIXUBw&wF?34cGeHFdIP*`JDo%iJ)1IUtZ z(oc-RJU+=v{{+s1?~&DDRga4?7aTaxm^olgz|>bl#?zv9S}_fSncpV~|48!pR79C6 z`ta;%j`3Uq>YCz=Z$TsNVoU?+Vhnr*VdcSCBmeK$Bz0AcAoQ__`*>;Bgh$b91hN&Z z^z&;!zO)5K$K{f_)nCV@=SmKincXvsYGuB!GD|GQ?25YV zdxYxexYTfR_#iLd>DZ1#W`cKerSLLRev98*qIdiEZ6c zT#bbH;|?q|EEzI*@_Q^zUhv29AgWn8{fJqxPz?Xr_6X_51c+pE(mX88C&Mi*PjO<`c4 z%PWPQ?6KliIHYx^U!&lD%Uy^-cu%KEAg1vh4NR8ITAIG<@j)aB6(IW`rqpXkG46MWA9>H++hV`Q6e+ z)^76EuRc;XNyl-^9zU!OGXKEEZRGv~nCaI=KOS#^|1QR)nvafuu~Fi6Bg&4p4179Z z7gZ-^s6l+y5gpHkCyF-cQx;G04e)WAkV&DCw%&{}YSM!}BWArHs8gQd>94(jio7YL*06GC44%9QG&UWT z6n6N3JbeX2l;PGb-Q7bFEj@sAw*u0LNXHN}bVzp$B_J)W-tm0r z+&}Qf6Fb&gd+!kbDKv|20G#~bivA)y0oyJUhb>>5OM9%q(u59e>kONzu_u8I!2Uf# zFBv8uOvcu*Ui#HOFV znT$Go6{@;q8YGjk`TM<5#c#XQoaICCZ#NW7%%_&dhV0tDqB{lk&G0;;uIil2^LSs7 zci?Mpw|_TVS(4SX19|UQhUd!=Evp%^z$W^O!XdOHZ`GUN2Om&58z`S8pG89${+?3( zz`<)K^GaY?T-_ebY`A@Xr0rY3i*KK+QD{igLN_sxyDzbn3ryv!iV<#g$gWtE1MY~| zfUKi+#G4=KgKe?4pz$+fllf{~Lm3_uDo^FaEkKHQxv~S2azqcVn#k(H8l%?Q(Pf_R zJL;;pR6ibORZuCa7hZU*gPHq1uW9dqh%QBX1Tf4_WOIGgs>If@JS{m-F6HJ_^b7W4 zD|<54OeL~{3N&pOKIxqh4ngYy5sR~p_t#9J$(pDe1uXf6!aH>8!07}xVaes~>3@4z zwEhF!MZVi1ByYWL1qE?lP8k0(GLWor44|+wac{z!#-|b@?hfU&5ZcuPyY|<9CR=NG zzvS0`gt+Jqo_0HVF}dWX;dZi`y)1-5PN4&x!ga}aqRS`AJ&>Rs|UCN z;RKK(jC01iR~pRUEXCuR(VJ~c;aAM+dM5(0w04gkMI}4Qc@)RVc3cAEdCKScb*RfZ z4a4ImaVn=>t5V~23T^ssi+gV=m-4KUJ?bGcAh+~fdWpUGZM|q$HZ%1EgSE94K{DVq z;-^|#$XH5eU>vvQGt!LZZ?xjI-;9jMJQXv6tq|SKiIG=L1B$EMQH>@X(u6-9^#eUIx{ED7L&haX6JqS(b^#sdpH~GJh+&0qvFJn4?p>pUv6a&r{QH4p}s$CS^#lGjm&0uP!0C5ViK|9c327_G$1yK%lYdNBG7fk zC{P!Fthc@Wu9f;ySMTKQFig||s9)t_9!u@2njzO{i2RH@F4BcFO9La7@e49tIu@h> zl;^c(UJCI2Q|#I=k70$4xO*->-Q9E6UcS}or?hIsMc||#KYd%+!FKR{4H9DKb0YCK z*)OJi_L3k)^*Jfw5J8l~Eg$Vi%u@&kOw3WrD0nXM-7 z@7ORbtdz$n2x~qW{3EHlvZk&^;lWGvWaB@XZazSLnsvO8*48Yk-b|V2$VK$2#uYR~ zNDUoKl|c%xLf)QQKDX=>73R}POpnXZ7q2%5!Kf4Lt$~t~I%P40OHS)~Zk14rbR9LX zGDnykAcGsp5F{3wDiyawxJ@<#7RLA4xrh>GBD5|?fT_;YoWg{W1YR5$RY=;N z_PteF7=CM7dmq`dz5`CR>Mqfu%6maYW}dm6aw(cp6o?%rxsF6op&3Gn7SJU{*OBq8)I-5em`pg4%xdea9CK${Cr z6=CO>uVmcDCy8Ss3XlL&!;58=wU1~Uk<5)+=X(X@++CNe5%yOeo?9c_!ab};h%l3K zph!-;i4VDQTTz*F?|uJj^Cz-+(h54nLz-J=_`X}@lRIbWYW2HLT_PulMfejZ%Jo>Z z0eDqie65TPqJE+xCyu;b7+3M3v+qnWJjk`}IZ5Lm=#WgB7?7VOx1ILFLf27@pfl@M z0#B-3>^gAJ2ej+MMaAC5!YPRmPxIGAlKQYrmfFIJI~#CP6J&_JH6dPNRR(Gp^zH#0 z&dddzs$YZyeoYAL~A-qb3rjD0;G0d%UG5WZ}ahDf6H%{*k6&P z;)9Kyf9~IJmS^&PJsNjy-AxL2i)Q6_gGPf9amd64i4;G4E7R)taq!RnH>vEk-nED| zfhPv!kg8&xBU`^-O&EL`j+f63ZN&4Ft+Qkv)t4M}f#72# zb+?ahE69K)q~oto<(?AI}=oHa8oA>vb zxmjB4U$-ogF=zy+>TLiOHSPyW8wXzZoxQ_D4VcfzkmFr`1 zLEII}2m_K2zLo?@BCRWrw8F4s5Y^P*axYC*G?xucUBl#)Z<*7izP_ZjryJ_tr9D zdu0o%KVg)Q1u**Hx&fD)=`B=N&{Gj6L&(MU!=FB@`YT-A2kr}z?b3v;cdZk}JyxjV zar8!w>29#r#AYJTSGz&r6YQAZK$HM0hFxE95&t(Bm@ZJ+?C+|?qDZDS0|#QGxe)cA zn*ITjz9MEjn6DkIxCQbH59z$|4;T+{4iqHOu`Z7=5_%4nQBO&p3#q#7Bw>HjGUHTE z{`lq>D_xxQtH?wT74^6E*iXJ0lFC`C5nh~R($Riq-g|T#xmVLf5##%&>N0qlsClt! z0llwX{479zD65^(_31sWTo(j4YSPZdtabid@5W&`;*xZxXL61T0OpFc4~FNfXU~0( zB41ZJN1`kn(hfKX#IRLIZ)AQ!{CHAQJ1hC_U|U|h#1$B++j4ioOOG<)?PtX6NGuy9|#Fjhgt_bv=JugWBxtq&>@kt*pNH8XvmOmpPIp15{fbug6m6o zjn%Q`GguMbPY>R(5wOm?BqhMx19otHT|?Kbi|G#M4BeR|LX6==Q=Ak|5vGvtPPL-V zJgg?gcOy|$oa?3)jQ_(@)=)-u|D9@j3-3uH$wu!a?*kabc#yko86{3?f_BE%pUW=y zVMvX`O{35Ln62Uf0%qf-HjU-w{NXr~5KyPW<7ljo4SUd!m%sC_}nov(b zx8vrs?j1rw84<(pIcGa%@JEcXvZ@XI<1KJ_kh8?aTa~nOHF3p9L)rgz5!bCa|MEf? z&Ep!GtUH1KcK5Thv$gpTDyW})lbfNrR@=2ipJwppoRsPmu#RB+57>o<4{kF;IHWV+11p)r@rmI5q*C3%0`;Szpv*j7KD}r3518E2JiQ zt8l7BkR*__ct~~rihGiIwJjw7W>EnxUIb;q=w7lvK3`~IYy(^!?SGi&7@X_^~k z$7DBqay@ag?n{!NNr!Y>AiO6Z>231z{)Hv}O=7|?{y&bs9X+1=TeBDQgPM*i?A#vE zR{nzk>+EO%&h;-eP~ykpX}}A|h=I;KlSxU5n>Td9z0>a^e8+{4w{roou4MQbx8j$r z{hbQM*Bp0m3E;b0dpemTy4)4Hc*1R^%b)M=07Nq+o84OxL={fb0tK_X2x@*7ITETIGt zf@lNQZ^NB|uEKT37^({kUcO0r`6IS|Y(q3a(p>Tdt*R5>D0}nMLE#8(_GvTw(_bk) zhfY*x58%qYci?tZPj+bi`_NfS@F5Yxn0{-$oGW{$il6npm6X74J9ocyA_<^PI>SF; zB+%ma2hURKdxSRcvOQWv+udnbe(ANLX_1jxZFc}BZv2}~ZS|ej_sa^8)SGTi#uwh( zdLrLMV70Z`%d_L5ziWJ{;n$o>K{)Vot>RsQ%rzz@A&Q7~M~gNP4iP$zw+}Jnw{8o@U#J29KlH9XcIt?|YeLs_@)bEBJPq+x zFtimc9h2#88FM1K8Nt{u_AC^ZzJkMQnKoStP(VP z3bT-Y89P=vfl$A?x>&P&?v#rI)JF6fx6a?1PF+j>JJ{FxQl*qW)$g^J)T1h>X zpc>J1cJqPSiiMp57cXjeY8||N8WWr#ucE5(dfPkK!-6=&8OR5wy{sBcgbgNu237=o zahum4X@p-aJEI}B2OfLS9wj!1m+n~3teLJ@qz%c~Ph5KFDj;j)BB%6aXeoWw1^R*K zqw2g>zF?N@Y-ZkD<07@;lb9Q|OoZ{z%Lc!!X~-7ypdp>0DsfClhu#T|p~%OVt188R z#8Uo1QK~*e@HKBXap0VrMRgTPe9ww(sC4LM?vt%ro5fp|J_SrIOl=b5`GRT#@Z*`r zZHdHq+RGxj&j^6390j5DPsNHYmU4I9cV1yiP5aNu_aT^5=8wbLL|Mn-Moz>_FHcRV z%{vl(DeO{CtZknn>P~CsO&OdOHJfV2vpH2A2P9#i6J3n-PHb$`t^rkW%hT< z}*?a zakbION>oDhhmH0rldVy*k^iJ5Qr4M!qV`x^V81c@dzgOY^&x!+O(a{AAtq-wMcA=y z#<5Ri^TLY3^VY|&8UAw!BO75vXNSck)>95&gJaNSl{#npks;GX%RiGvLAM1}XLZXZ z$?|yr5J&-?9co+TUOvoe!S^yrpKmB8{fLp9un#VSw&RD&a^VhbRcYcWU=}`)>DEp$ zBTOpqpf_%oTY||JXMRMYiv?+!%LD?IjT;htZNk2nR@4f*!0k6jWxu$Tp?QA97G{9Z zB?>wYl)Vn55zw!wYb%d-u^id(zl_d+#5*5Ol>(>9mSvixS9PGd;n2zWBAn*pA`;^t zy9*G3dxJW?Fi1eIH54WFApZbK7voI70;r5+=W)sM-njVi9YItgNVVz;FPGBuz0 zSUhGu=OJ085XH5~m0dEODaX^IK0%a;J*GCn&vDJi%v?DYAL!b2Ys8k z$NtMo=iL?F!p5T0P3aj2(TQpPh$YYFNg9XNdT>vu1s5JrS25X*KQcj@?bio%K#d z+aciL8Sk#_CJaY;muVA*2XQlco~I;o!AG9*;9vYt_vC>+_CA=q+C%&nguAu%t|4MH z!2}5FBIN-+)7!tD$qLyh7W6%*=RdW#$d9+Gc8{HmRI;MljrsFL(}IM}FnYPKRv%zw zK3x5Us?AJLot;U~_4|ZPx|9H-@a0RwG`?W_jSjh>(5B7BAH?$*WF?AcYcyTwm){>! zfX;~49X&8Dc{ee-@j{5;sm7X@1_md;dhL5$)-j(^kUxAOeaGG$rY>UKaO3MGpX`R( zi?W_@xsiEzhgp%Pt8bw3Qph2eHXQXC2bzI>Kba)m`=v8PPqIEW@6rIR9ZqR%{7~=` zn>xUuM@7_{+bbo8o-^=Mf4XMYa)IP}Ex5rNqx`FfOqpO}%})edE_ z^>!f8vi+aphyMqn=0pu+;G!p$2Piy>yQ1IDOeeJ+FrU(#J~VggUp^9Sx znxU@!c94SrPN~k!+(i*@g`FqiSJs+Y*r=yWNHjE{9#Pq}g4*>u5ta^8+ztk?Ke5+F z6;b0qG-|jiz>-C%Jw&VqVez7@RCvoG_5X%gbVlkgGh_B?mtYvNIMBvhcb6;JN7gLt z-=^kViyNB0JDkMDWLSM0bAB%nRL1BiNSYE1^3Z9T2T0vsq`I^ErKjLmS$IPIe^H?1 z))sisZQ!_MEwBCzuoak4MXmpuGs8*Sg5~ylu#_Y>;hs~0e&?OW$HqRAayX~wDlI3r z`%aJuJrEyPk`V&Ll)8pa`P51Brn+w3e`qxyy$cp}7zTC97B3Lk;W`0ViIT7cU;cnE z!IK3U0s*wXz0n))ORyOPV-ReLRXoqp>r~Ei^-*JgvVT+3Y~II3@Tc^o%eP!F0rTX* z0t6cq&EG3Cf+>}za;Yeb%ohA_r>{96pv?plh6WmmKl0Jo9P=zxp%ELuox7$##QF|m zqrdRhr3RmvM!@qO_~G{}Wa>F5FY6FsYq$^tM%dc68AKVA_hkr!O2xT~XbyVlZ%K*Z zA{zp+SXB+@(zng}BIxkEwA(lEyaP+8Scah2J#Xd-2B>?Gg}H@yO67M2A^@J>!}K5T zP3G>NqV?u3ZZl@XTQXy=4WybUcZ3yZ)ZZJsOvh@C4bzA zZY6yF(FqIN9P79-UHWx7&^2H385B*0d9_c{ULLNFb7QEer*W-&MfcWWzw z3dB7Y2htCRS7%)^635B6@gwqb#*{LA&N;(@F}>4Y8orr zfLoR_b&tLfg8x8%3f3k!|BS5)9~}@Eh)Vh9dldf=HyCiUDCJK|ZA-^jJslCq;K4~C z&^G5$_WTa<#5mCoeJCA?KS{ogx$MQwd3HI~*ZWI{DMN(c`Lk?gH#GDX5uo!efPeJk zfqxLc3B~F0b{6^}$_|eZN2Grq0v{!gYsY`?Y4w!Ued$aen@GBw=kF8w=DBR4s7Zf^ z@|@~DIr&2(yM^!X?R-f|xEZ~s`_H3}n}d!OVO0V4yU&W0_MSdAQ`3@=(OHU&QLfsZ z1_Y23Vd5qfv{)eV2N`sWd^f6_F$Q1yvNc_+S%DC4AR6ol(zbq4C?S4MP8hDuUYU*! zLR@f({|g>Jd@WaCCoVDXnV_dRZtga!1gpU>rhaI9|9YRG*_ZO&>c?_uCm^zJ7~qFKWm zjP)%vf=O;4fYOEEJ}BRgvjNs#j8xyJ(Zqqe?L)on+N8MiZ7tBxf4|9|&tlI&mD z#OA$h^c_lTJa4_3ofOrvrz!R?q3su2+UX|Jp%IEcf7n1B0pv(oYC6zAqF`#scm8!N)3duPqzhc?L4B4Bq+_sTYzT-j@wR_W3TFsX-(Ge8enTQrW z8kS#G3cWm3cJ5wD3gB~~NVRnLmlP&@+OUvW*vcI6jv|Fec08+)oe>!5A()MW z2Of{;?MT7>TV6y!xKphf`5*=~v@8LQMx~W29SUj3BPE{7ecf?Tpw02b)2sm91_}of zSi=+4bd83MhM^Q7_A^6{b^^~H@B;iU8#=bYjcx@>EuX~^@0Sv$h1TVhuAV*^_f9MC4>mYu6BJ7@Dh zEkIIk{Ek|Hd#>%l2AE>VOui{bXqX10S@^_@T-xPK;GLC+0h;t}JmvoKN3v-)oo)dm z9Hh96phZX?KEhYEpi0`1uCX){Ma)6y`EW#(oW zpsNRgkg2dOhko|_k|h{aVgcF>N1WTf;0D;+1qUZCsz2wi;W=bDuhXM)k?l@@H9^Fs z5{3i+gbdRdBHC6;ec}Ydp3qb$+6$0krK~TyEn0@M@8!(8=c#n(iB2>lradWCkpq;Oj%`nUtZHeELDGf@dWtP;P?3ndpO^UH%s{P96M8?jwdEQd zdo!7A@eh6SWW1h6-Bd>D!rm^TqY~?~7MCLHcuy`Egkt^u_>fK}3~)&KhNG5clDCM644mI`v)vYczOs2h6MT{P!RpAG3YM z!a+Xy41EzhyOFcao$yycL*~CoHG!oBJ*+_M<3r5Ceu)3aVP^xk`4$pWgxx$VqaR-= zPi##jr}Q#?Tlxen6@P4Gxu^lZim&H)`VT}ZJkO|2&6Zd(FvLr0pFr-gq|8qL*V;rkeq7b)R_ zxi4X`rFGZokAHc8i}Zd@^F<;xRa_>N9U-P48!3#rFVCQ2j}24Xr4#UO^z~YJu(d(o{U6HRUsG1dKULCROW?lyXO(r-uy<2Dw01J zLHljh7cct#A-0qxSE+Co`Tp;ZKd@=1ly z5W07CubG(g_v6u%M2z<-jQ=n>OYqSivip`t z$b_TH4Dq-RgJO@v!E+bC{VXUgr?y1bsd3C4P5B)})~C^QKV|({C(&k}5G~Km8sa=0 zAqHn5SY0+m8@nJGFr|gmMJJ#!aC(aBRB7+>(PQFg@>|4-tgDXCGn?>*h9m?=p<`SF z56baA_+Pv@&0e-nk>G5GiLQ8ah9z=;4Zc5uRDJD-J?P5CK@gV05xK}BqcX`RBUS7+B`3Rhm5Fo^+4^UoF;>xCe4^4BZn*}HF(z^AtXeA!>@zINV`bm&!;rzAYaHd z!Kq08d>n^&%RWq#K$Se@`8^m)`dp?;)EM)vj;wt*(dMyfNbYncHEa_9)nXgGAv@Hhy~rohQ| zGo`!0esW!aNs^x=KdD@&9DV`wUn#4u;C=-!n)DC0QZLPpc7fg`B{9D_rhwRiUQgd+ zH`?_6y)o)flE=WE>p%igsO%{cj=Ok~?k;$KYc#S_jN3~lXhLX`P*^#VXlyxicS^Zy zXo`xpK^YxWuB-vSPa>o3Xc2n4!7vemuO;P|^>vJr9nvu!DQku888h7CJyMQ>_ncNq zLdDL`w&Mww(knwOYEz>S7COUOU=x4Lf6)8|%4+3(vzxkB@aIu8Q>Z zqd$@hu5!XlmbhD`0RIgfa~hw7oMpu2MRv`iKfOQu0h_o_i{a^)>RnBw`_dVtXZmXC zg8oeK(iq3oIxL%Js= zZ6Rv0-4rrCw|Rcj63k7^=b`Os`|keE$lfr?FVY>Zo_3DUiH>#3&XIEhjHWFTb*G3%uPsXtDoD z#e@hWi>OLK_Z$~EyW`BwAHq3qJnEsopQuhO>wL9YmKcu47}s<0yZThQ7)gcJ%ATFiW?zT%|YeYNlb6yAEQ zikludK;~Y>V@tY08?9-*q2{e$FMicQ-1m-kX#`&{T^j;QPziGHH}u9`WDl(Q)u(K7 zO)5Gb%Hmb$(DCJi93 zgA^-E$gy5@_+zf=;&rL1hbYSXHan{JRidgr2miE$aoSg#b7vAiFNJ?5xEbl_Ixyfk zXdqBTGO#^VWV&8R=;laQ?q~V+cv9!AnG$~J8^1onXZaOe@%)Vf0&vZuBRCak225nF zL_#zd9?p%)mF9CHvm`^d*3!IAzBb~XbhyKTCXdLiL?K}Cv{{$gP;vYCH2V!Qqr!AD zHGZHv-!-k)J`1E>&mGE08pqUru6<3LBfMU;`)>1X3ce!NqLRVC&q=l>;TxpMD8!Ah zlaW4uOR8I5UZQ*>XjQ^U7Df+2B-Ji}Hy)rAF_@>QFmV3E#y^^r335WI5?0i5^vNAr zEj(Z?5Q6ULvF3rnLYP%kyHC9}xtD35m;~HN;>6HpCi=Bk9UsC}_Cb7ZI{{$Nnt~cf zUb+pdrz8q9@esytN6@8Xk zam$Caz8##m_>~>5f%R7;bn6_jS5f{5uiw$OWl+Ig$XjoWIE4 zYf`GU63ykS+!xz72&WXFGYjovLEePRd1z7G8V`QLI{&9u+~ww*M&YH%1#W@SwKHHo zJ3Go2sSq9}q=1R$HE`%}TxJ7=l4J0m;Ns}m>*+eFCyaUqHS;AIZ!&r(x+f|r;$%`l zuCKah7NLu?IxqOv^*Ri_mAu$@2@czZxGWrm0vJtQT8`cRTw8h1CsK!^1keVsV)Q)* zbkOxOxm%#s`~$JbK(B_GuDPd>oJ}>`p@lNti@Mb;-`GgIiba4e-&NqzF3|1lAUNn04zZP4|6<$U*Rt~98Awb?> z?BpP~7pKksxc{hryyEa@H$PLo2m4Vjq2}cwUZykDO=*W`6VwofYJf{40op~q`z~^V z6f12GZ}$FG-mFg^j(5M+5(V8;}C_gq2G1M8_ zNde*y8&*Fuo#(MLyx5$TbR#HhHWF>{LI4YFh=!D6U!JVrHEW;e94gbYt3T%f9!R{& z@^yH?{c=4-BX~`wqLiVnf@KXgv-4!nTw2Nwdv~H2gcOJ8ylDIh)aqu=2x$Nf6W>_! zdpj6VCZl92vgpUMtjTHat?n(p{KPXt#`SsaII+EQaOP&ZUr96dJE+w($}klo+F>f z*L&~5@chkil3jtxk9Xxo^Mpde`e-U^FJbl0XWw$-g2V@`3f;Wp+MdpdV*Qj%;Bt9G%T3AI2QM{`*&eI%e{+NYwj5bZxeU!YRaoR!R zSt*@iLntBdX;04z)HM7KlCql^)@9300ghTk4Tv^kCUSoO+}ulnY<*s6kQ}Td+A+wt z1m^e5TBRN8?)bmjbVz|YNN%W)FKoy3nf%KhEs^^;;9=3WXbfvoL*iRO&-80gekJ~a z^@*fKYB{;A9ICQhlewIlhJC)p>?Y$U*u@1%4FUvI0z~lbnA^U*2sc3BW=2V@&t0AN zCf?B$>J|1<$shIT@1jxyQx3gUd~SA8){2_CGk`;cuqLq`b0i7TOLk>r(!cQ*I%Wt# zs8L;tKgR<&fy_>Jf}pGF$rq=|prtuew32gaz%Pz@b5ZRQlBWzHL3ftmbhMxmi#8*? z;(e$FX%ljD!+5i0>7wR8f}|5*T@17%`=kR-0$8J4+mco7tYgGbp~nNMtScm-RJejD zJAb35>;87~>6WD^7QU{~-2t62nK;ub(5B(;2$F4Y_gtsWrc}*>6;N1uq&;Rz8MDeI z&1s*zQjM-3%)0-vh&Ub0q&|3szyPzR6|0c&1=HI{+wf{;rE%x1obdeTDRC7m%W!uM!>vmgr zlIpTlj^~n?!tG~-{siV@ZN3sdlIw}X01=2dP{p^~r%KJgbJ-=>rs%hYmQ4nn>4=vP zDkI3NS7L+*vW%OmsU z3*DttrSg@r>Pp^5h^=70-ow|1;mf836{Li}KPAi=YRVfCA%Htn@CwqNhYaY6MPgTB z*IbK7+9rA8&YimzTP_*d?^ilpd!H(^t`sEd3el?f5lU7R z^aPMynok5wCN+L-y(-#4O7C1nEWf(=31ZlEi1?DlM0)NSc$A*a2TCjey1fJ-$M{!k&-;z{MJQCxs< z3w3}5B1^HSwY8hLDb5?p+fSdkOL114=+8|Ix@BgXNVdllwf(pUv>#%<+M{yrIdreo zd2jWV0>T*$;@6o%jV0YfID07q4gtl;c^Dc-S^FtMuG8Z%Bz(4=yWJFRJ*verTTPo{ zpFxY-sQNyqsMeypYJ_aIu$TsfD>xF7i!U(bE1%qp+g;I`Rj|pk_qEfg;ZKhma2hXx zbBZGah^`6PY01^#?S57N5uljW8;d!2WEqv$tX&M1i;^8gkK$YZ$7vyI64ZurKT_%9 zv5kU8xg+|~Gs?@s3A3-fUuC1DAj60iJ!l6piP}X{@(u&Wgh{Sx#TGQ?EFkW+uRkj( zQv_H`dc3lV1b0wS_o&CyvuzU*-_s;f_dxyx6b7jXi&F*1_yBvnxo?_A5@K*Z)F;eV zck-nmvrilmvFwckIpP<4f9%%r$atz)Q&S)YrU@w)2@#lc@>y2?(R#?kuU0(Iip zNT$n>3}_q`j%PpCuFmyM;iVD- z*Lh#g%f>gK0e#<`KL5TL!w=g#`A0%|tlI$Hz94M}VIorrWnUC6CtcQvi+MF74 z&6B?)9EQ4X`|gM52wmN@FGv#K{W#LyHlkhFyijBn^wP+_3u`@d#fHmFZE$Tv=ZXc#i$Q_@{81y( zIf8R?n|%KLA6y19N%3sxZ{)yYCdW~;mU2l8&8~F~?cL>^{35K{(>}fJCIfkVO?u*4 zM|0ZqD0`y!o&3-ntq&G9#DGA}H3=3^Y!NtD-K-eiAA)v0sL;_iE;G3i-+a&o=c@~# zBw+~7vgPje?*a$&nn#!t|BLx0A}7>NrrarnxGAb=YIzo0s&Cc%$b()p7amHoBu}Wk zq;-QFSS1CsAqbA6o)F3mLioDrp>~>kvR!MmiwUD`h9&NnLw<%}`ip0#ZKDC&EV=nR zDT8a>?$?bl{ipccymrO_pppNa~|)?^S57N<7^1` zV{Xr*nHb+Z9Dw&vNxD2L$IHgGr^H6BmUwmk`?@^i2zURS?VcqCMUe4>9)?w$B7;+v;OT z2Rq7k0#7VtQY3oZPZb1mwGrI-BxWU+SyED?P}}9toyF5f9m`PysH&Pgnf#kYs{~Ks zt7+_Gg8MU;a^_Ap0mb6tLA!ZXT9Ku|ZPLPtAP!7Lgv7uIME^n{GvDGuHUVZ$`f!)@ zvuesPhiK}z<7~b=edzBT3Hpqi%~ze_6X;SQEq8lF75zG7mJoMd4mq+HI1}1Y1LuX> zFSLnz6o7{o!bFR?RprJ>(kZ_=kHYfDZNG@lLc3N)B+1iMML_6N);-Mt(-{114(187}^tMDSGeY zKaxzM)M@FPulmSFWIcLj<4L;bbLQ(Zp8iS; z4}%XwIpRYU@nQVlXnLoPlD@#kH4GWFq_r;KLD!PEH^jRmbBco6@lNb z?Uj*#yku>F1u*Q&zHh#Nu?rBn%{y%77~kx2Yo1zpK3(}p*o~uIIMFv%{n2BrNm@#QaJO2n0I(+ZC1-Y`IS+GXh}eI zpqZ^1u5y9j5B=z1JjsANjHf>#ZS0M>nt>z!W`UDwug|}4AsRe<+jJ{F|5o_?Rxi%4#E4E zs1qN;DM|P)$tGR+NIC2%BBlb>mkvyWY7xD^U64D~pX(jWmlET~%jHEX4`Y0D6e4D{AQ38D2rxR+n ziQx?f|l+3Sa6;vF`6bC9;(8qzf zdzC>n?@2z00O=pP?HyCQQMg4X;5ATyfFjNk6x%(pJ}6&-w~#g4 z_MySsyME38MlRPoFU->zJlT}aHjQETiukbg(=o{s#&I-{+)6)$=0@f5qgVp zgG@h8{)9t@gFc_B5Y1QN*)QGkDY#BzKfgbrZ@qX^{HLxgzE6DNyw9_-CREBc4{v`; z`%FF=uph;LooS8eE4jV@#;~)=4f#qhs#-Z^O{Wsosmdu63HcluBa$(?0gXa(PreO= zL3$KU_*wdU9J>EGAd%^@MZukITr1Mv!in`X?=eh-?Q9(Dr-mRqy2R8sx2^hGvNwJe zR190+Hj7KnU+)W+z3TevGVzXFI=U1x#Ko(hZ_R2&UKXB59VCI=yWzG&y(Y`?0l3Qq z-P1vC#$((Q;KXu-ei+h*XtRr= zO$r;~5d?dp2_Fn;4>fnZe>RI>_37iPix<6~H-n$MiP5NDiXPIUwG+(Z0ZBeYW~kChPI#jvS^gSo(XCFqtV(S_@u*!tN8hRDcBfz zh=PI`$wiWZLfJESaU@z4BfNZDfeH^vimzj{0&5WO&kDgn=5eIh3bZ zr9RyEl1hzaU%*59JuN?b#;I_H`3ZQy5K^o^d$NHScJW1mhQk^(#F7l@{85^tQEn3q9$V9+Cz}YtUYK z^e3Q7{QgRR9m;g(>EZNTUInBQLe1;r`d_VB*SIE9eY!Nq_YmnTy zx=GAC#fUI-`Svr>0pUJ$D&2^qw=coAe})qnPIj#&^#+7mWiv_2gPW~7$sS|dm<#W#kO_oT=3N?i!JnC)ilXZfXP_@IXA|eyU^|Dk7dOQ6 zN&R-nBt+lLyYb_j-|kA!=rhdsJwItq!zcZ_rpR3pW>5LqK3bFLMYOreFSNfNU#_*_ z1X*wOJeq}gUVCCg_i=_@c&x1&4ybln!8v?p!0Dvkh@9!H*71(-|1s@0F(N$a*7dAN zN)ThLHlHFFFcJcT}o(tDDmmj0YI9SE72#}td~S|=bid1MLwHm2hk=s_!O3Oxrr<} zyTIn4JzP^@ub8{;4R9NC7!U?KLzhBF^!|>%1Vj2taEFt3xpnT0h@j z(Czh~ds%jOtns2>m)^?^qbehblGf)0~9zE8U%`&+Z2fJj;Oe(3hA8!O$li zv$>m<9xevDawFn}tG9|g>+JpOH=eC>t)Lq6DO66Dw)`JN;dozg(Cv$)3x-suj&91u zkVSk8Drhv@G|yOrxMls#g-j3YO4Prs(OcT?1tx*pRJw<0-KD#;_zpg+6^k$hFvo0W zM4YR48zChr4BLUi@JCdhE28^)pV)%^c=DeS?>|4U;!3RMFK9>B!`a;BQtD2YMCJtj z@DsdxKOwZ2saA={ATOqGm4OnVv9y4?&dQZ0#SMqSH*lx4%VZ^_f7&B zqcN~W5cbJWEVXU8V79qsiTTj|BEdf}JS#+Q);E`j-EXsITCP>hZd!yL+UhyBmfs=@yV~q=%61kQhRchM}YcC8eYph6WJ? zk!FAakw!Y+@wfiZdcOd%?!D*iv-dvxZ2qjZ?NVnqT~)9N5!uuF%+ix6$0*k_BNei} zZ>W;4qNj-V#~BQ1Sv_7mt9dyr#3*r{w-M_M4nC#d=+%ZkoEOhbxL>w{8j>p%e{Y)| zfh%byPUpuAN)*&h$zU3t!6SJYol@FnPe5=5+t{k86ZoZ?lt1^~Vbz_id1rXaho8jAZ%KLP?C8_i>DG+}AoU)b@7 zezTR_rzNl>U=AS(AA2IqtB{Eg7)i5E{ccJkk`aO6)2n+P3T6w+`G8r@nj@($Tdqs) zFcYHG>uD*qvEuyCiLvJD2XXdmO$~m-8?U}^`Je)m9Kv|F*?Lg2bPJ;X!?z|e(& zVKX5zKpsZ+C3<25Sx1UaX3a4}(xkzkHOZMVbTOI;&i6H<2Fw+b`{$Ge@hk6=loV3| z@n`SZNG_FhJ(p8_yciS->@RTD=r68W(et9(-$tP-dY`qUmX6#x_WAg$L&_wF^k)UF ziem{%TEd6%RcILv!?%O_Hn2n@AU*__4sKBKmgzc_MEjdFJ=>)@&J zKuAfgBsyeAuGlnRlK6*Er|l07e4L_B1j9L2uc&B`)w)MSVb*}T1p0y9*V3BIyKt`N-9`>{?1^&42!af#x$%Kjl`>9b%&{~ReU4+7N zd^bPD6bXpa+JL2oP94nRYp;FSPKY+F;{MnPoKOseURR)9&q^#Tzsu^ab!;1~K}_=(m1c9WjcKV*n4=5B5dT4KqyIr|uk}iKs<4n{tgnv9 z-c&UnSTNnoZjwiUdQ}%Sfs5EdNykTR36G%`J{h#4tw)A87nxeOu#Slz?hZM7Fd5Iw z*>8O|yZ)$W`{=IRK$*zfyr2h{;iS@8qW+f-EXB?*jwWg(0vtn z9aS6F130yzKI;U*ttr)6>P4Hr)7BLs0<8j5Y4yv zob8Ed&Bl@}aOEFsI5onXI9Ni}`U8tNBc&R~h4D}7Dp=Wg&L?=KQTn(Y8G?Y4wUSIS zl;4ej*fVgR!*kT?OBNUzx`B9f$;k99%jVQxP6ogV<;*`{8TaQ;bXjL;Q-uUe^DIvI zOW4n_p^Ua8ld9M6b;xYcnw>qYZZHB%KE;2Z6a2g#vu~$)jXk^N%YgrirGkfH^V_9O zV{gl;)vlohsgkyW&fquwj;?WtdQz-# z(r?EBc^Xu*7afY(>>HceN$(oo@3ZIEY7RVFVJKW@09IoZ!K5k@Ff;oTu)ZLny)kDI zIh7r+5-)omVGP&~%CsR^jtehED{A2)drS4b*Kb*u50vJOZdwRhUOhN0+5M^$T-*g4 z^5|UrIkvcLqD>@9&uD4!Lfrs0ydw5}m3{=Z5}rxYY1Q|)D4}fRiuuo=%wSCwF7Yvp zAmQN{yI4h)5O z?^v#k-BVk<6>Y(*^KN{hd&l1x`wpG)BYP1XC3O3fVnR$lbaTlI<}Za_%k^*AkWZs;^amQVk5l41%h(_MZm81oHkQ*s>Z*r4a~Fx^7eP=xTJN;eY! zRFiB&BF2_96 zK53WH-_J2)4o00CyY~{=y!JK}TxX*2l8Vx4XygS0T$1%O#yRq&?|*0vvr$UWlcTEA_*-Ee}$` z#q_Ja>H&^7$!ObGHahpymIHm$*x|c&R(vConb(*bs?ZXN`$YOqhvHTr^98>o5&j%d z6Og(PB!ntwhmkkMG{D1dEjls*n&jzE!C&>3$d%?tA>Z&fJ=AB*4u7> zao9~^;Olp>PMv;v{mn%;6ColmxBoCc2bNufFu-(Eec5@zj($LPkM_W{te#c1QVnBJWUuCx{yj=UZEL7Ki(`eO*4d*=*~_o zhM*O#-DK?A^&y=hLW z*HVA9<@}H|&QVs-xyh;aFU&reio?BM%XcBx9oIchD|4jMXw5nAgFT7#Gn!OiM zLB%TmFbDrNKl0)hlX^cln;88LU-~TBg}DZIh^fO!Nx`Y&dHqbfx2|5`k@2ho6A$~% z@}~U&+t_W;?eYkFh%7+?DN7tFDV`a>a|pv5wd=3v8Uu1e6X#OYat8u!pAacGgALWy zmM{9qY%8SPd^dG#v2iQR@G`0~B3>&0^okz|zRL${z?TKvgYG*xaQT(*)kW6gPy0sC zu$R5sVqFfdBx!$jndU1C)#)-33kOV|mv3MScdrG4V>{Qr>Ri+-sEzx;OcuVa?l}(Jp%)anP0*)kjjuQMYK?v4rHCfw=daj1?*Li^ zRJb|MKUQCxv?wgZIp!&EE*R zQVzkwy02jVjLuQ1&*&4yH}WLX%(UgpW!_x4D6Q4%4+Q27)TmL|zAxnbtM90vWRS5f zffp?-1Zk>a?x)pr(q7U*JIQ&DiWI#iRj5y}wu0&S5*aX`Uo|Fq(G8I)OLplH@YoCD z%kGe}xHQX0zG)a&SE~txefPgls$mKDnAhNC0=u|XcZbC}u4vH2w&538T?dlOtz2FB zZF@{Ld>9EsJCBrS!oC8gaggY#!~7hChIcuik1gg`U?sA0&v_D+F(OK}k*4c-MfRx` zuA-DVZ7Zp{o?VgJk_?+e7!4D6{SJf0`J#a4%wBTrdn#En2Z1z=#>SrtvWG-e1kGPk zE3fynXfq0ydXW)nh(Uc}hEBAZRCc*2IDMit{)2|-<`n}wMaNS5Pj6Vnz~j%RJ|9wS zs$Y-32wh6T0Wxn#36^UcGDe`H=p)FJtlG>=jJ`?qsorEnDCbRtd^i7c9S-_iPhCpme&U z2qHZ$sHCI4nH|`Ph?^4ct4To<&4}T-=xB|LJ*1RTGAc+pO@e?3#T#mVNgZ-o;y$c# zKF-q+-@updmJKw8ZE0d3zqlvzW-H3QjYbGUFd_b1>MmOWKapR_(9lZi=@@jTc;*Cw zS!4s82Q~;d#FsAz?k~q&xy7~fQRHY@Q$x-&j*%QUi)VycU-Idd0beD)r|*?<_OU1* z0kY$$#smT^%UJi)K$v4&A2)EeZsvX98<+$5%i=$qg1thlgNxr~4#WBS4;3(B4>UH* zZz^Qv);(p&|8++vwz^5Pcr-e-#)OM?m?k?o$-ESRET$P?XMhfp8%uMRSDWjRuvoqi zFO09#J2ZA`f{SkuqacbHbdPmxmm57BL|X_sr2>D^tv3;@ZD7NAjv`oLzC{Q|PmJwH6(M?+ z6FUqWSV~y-3^uN7hOGOY00eG}uDg(Ax!)K;?&4{7%td(~Wm0E76RKVPiG3x&TeW^t z%!WPc&zqQ~HuQ=gKu;Qa;Q}G)a$Zkp>-31d)zKD5+7_plhMTos9eFi=8Nbk{tY@iN zn#23$dlW{YW;B$;7^NT~rVZcn@nIuM1=v70FfKJV_3aeRSzM^7*Be>}8DgVi*EV}8qsXTI3Co5W$vLiq&+ZUI+dI{7 zJ~n^IAR~4X*Q5k!?qrQ`;0n@JNDJlW;BZfI=5qRP9(Tfqlm_$a6ZaKc@+t7Q91Z!D z`GMjXX$h<$g144YDeYr(hhQpiI#Ipc*tMTD0czfKB98F{E@d1d{d*psC7(jGrGSIE zQ8VZ^`-eN}XNn2u>MeL^@*3~T$!Vgg*cw*~aNN3^piq0_A5<~2PGe&HL#MHnC^(L4 z3(xC(tdNSZBf;oiJ4&Z)%q&%CS2@Xwmv9A3&&%)!=dSb3?zuUnEF>wS_DOY~+ZklP zYmLF131jSAw9SUviE!sLd`Li%kj;tPORtnz+K!abqu$C(a@dtx5K~#SEXhRT`ldm$4ouGo?!PRF-9)B}Dg_3AEdHstdV!*rG5xySpm zg%RE~<{Xki^Dk>P0g&Of8XfKNFV6G2Xg(OJXvNNSCOF}Yr2f*g`}FD>mtu2JIC*OE zKfK&gyyGisCh463`r7mh2eZ2>uSy-K|Bij55#VXvN<()F*{z9UA$m3KA11@*$e=JT z@>XI5=gt)$hKj#g!~jsHikUFc#ww_H_Kge#-WSC=S-arfZ)u}v&@#>rzeBh|zY47p z-fMq9vfJQ@sm@XuGg|HGE;=qO`dWYoHO512$CY#@+qN3>SH5pWk;9E+BlMze4XXIk zP*3%blARU@7uwRj)DRwI)j$qQG-cb6BChR1s_32ZZ6w^RUP zSQwvE6w|5zV?p0G*a5}5VfP+!>iqtzokprdY3(6R{GI$^G##Q`ZP<4F-C8Hzv5{Fp zM;=N8{3?|Smo%S+%{V#+H{9442)alF#+zma@Yl}mZ5Z#4?&1iMwJVk8>F2W6rczIW zcbJ(wGh8Bi9Yt8U%_8S1qE}Hq^Y1t*INck`Q?DbrWdGJ1yTg&wCl3qnNZ`7slvOJA z!Z_+T4NH5Nvy#~ZXW5giU!xrAH#WQK9Di%}n1v?hg5!sbfRa^jf45&3jr?LG)TDjP zL4$N9HZKlP{K}@%_ril1EM6$wo?DFtdwv7k6sI<7{Sp9gazpPXI~Y3X1fd5s>F9Tp zK^{BgKtH)FnFzo3oU~*@A}^|y7n15dcz;CUWtn-$Q&o(%|8d{)=yGvED=G3_h>A<^ zmcNg|#a2j?{}^^IhTIii=N623qCGeq4QqF2ay@w2sl0fC?|jdXTGgz#HPaFg%m={F zxNO^aqO|hzym3f0-~s0YEN*Fw>Ki+KHs0vxe~Wju=AN(ZuNdZ$_kfdvrwmk#j&5J# z1+oks)G@&OwGrpbj0@O3r=IvTPnBO6muX$j@Aw>%H9c6Btu{u?!Nw^N-2nTM5qN)_Yn zg)sxCNiS$Z9MRrfo!jYv4y>ID)I0n&OE`*CJShM8*_Y7W;f(}&e8#uiiD?1yX4kai z?i~x;*4k>Ic@#-|J;O-L2pP!?up1!7R^O6DDK4(yJFb=&S?$$|%}UBwH?sbSFyWW#i-k8Q@D?=auwefye3l_C2QSCg~|mAKk7)@;(oB0(DJ%S6S-k z@w8VTe-WOGBg_!EnAd`915jz3I$N6~X+@36^H?N9aG)vcT~Ze_kHiRkpY2ayXnSs( z@j3{Vi=(dmC_j!D?iph<8xe=YAlib*+yz zw0`wQlRI*|_97MiA#DpUNs{Yy zj3klWzs%hOsd1r55dB*gpv$paTRK z(e1D^vs0@{zPrU;8}d>*`XVvKfO{(h+uj#er<&!!&u4z$Ur@Gai!vhkEz9|Na>D*^ zI>(OgmXIoUUf8zr38SPd$M#7i9TXUAKbw&{BmWHg8Eh`A1F3?@%)ABBrFT_|< zdkl{A%0YecBjdL>T?gv_UUp>iX^lM?4Z$hFnXJlHK3_Tt_64II*ZQWtD1S!EW}d4A zZl>dO3GuR0iu&w=(G2Ji;?O51;Rx@{^WkIsvf-(9?u<@WF(xH0UO_9AL!m-L0YxudjHmnnp}O<#G7mg+vD{7#U|-1a<8R5(*+a3W z0`6~60`5lCmYxFJ&Ca{SlTTn8J=(JPmsC*fLs$4r|7|LKxP838BX*)llf+^8?i(Vq{xF5Pgh z{*Nh}%@Zbe;;+Io;O0~|W`&>X8?#xS^F;fKjFVF0-30_^#(%QyqK>rGkn5AD|5`XJ zFiU)qP7O3Xlc<MIp^kO18BY6W@=Jaod7MBN=o>oD927J@oBxwhJ|T%Vg8Y5yXT zr1VjMpiiGBNDw)yNeTuK{d1L!ySKIeQ!%r&e8W%sLw%d0vKDrje@f6w#q$x@i1Kfg zM3rR2bKBNk)4TTtvKE6Y&XJ)Q2$S6}Bp3Osw|UgWw)gjKe=qz0BfU-kkMv%y43zr$ z1{y>Ee_jA;8Gb2K)QTJ3xxoc`;*ZX(Tgmg^_Mu%L$mTP*xvD)E#*pL02bsW+uKlNd zfP3u0-kuro*N~9wyYsOZEdg~a2c}K+rHNueFAJMAQK{xKQ2I@UL6*um`J(7LMv5CW zI!nA$)WSGGm%bac6RH7Sy2!2vwa}2>W%1>I-+jTe-#g~{ynj9mI;axax&rK;0NCm5 zDGXB|d|)Wg+)T_iJVj;=QPiFB%p?9yoNvu}sAGJI7J_JPEX}8&?Y*b8pqMg?rBGio0@+KNg8F%<24$hJM zn!Ot&7%~tw7$6`Pld5qs0b3`hTh$$Hz8F?@q$i*t5cwrFdSZD+jr0~9&1|p#c|R4g zEU$FXeX+{6+*+tdd(S5521A^g*y+{#m*nAHmAu+4B5ADYuQ7=l6EH!!H>n)q-n^BS zt@rnh4|m6d+6?#z;cgrQt>!i!kWsW5=l8s6Gx(6^L_SQG)&QdKU-hFc|4A%Ju)D!I zQPeaJ)jT$Thvt!Gfxa1*b5z&_@FaW7T2MU83eQkXxe}F8_iM{oknjuFN#_avy{b|g z+F8orkfc}{%-v()sfJljz-bWWN>ysqVU0@+wj;n-(+1mK*!!c8OwPG~gQva$vzM~) z`H%vvnkwpeCuTeGrXcROll)ejn}FE$p3v9_F%+b1D~pPbO~r<(4SOm^$FX^zw=?&| zQ?%(2@}g{m>EZ|9o(9-qRe@NoJ;_TYUDZE**gqF~G06@tMY=6`KGy2op@}?uLf5w! zGa@YI5cM2Ri_$u#7SMHR>+kMETH zlx!s0OJs1tF|MGoh@;^H(pDG?owPY9lcIh%HBiga^Tca##a4((^nzgPHMrVpa*hYG z_2nG!`AwPIM8(I!7G4P68{CY<5T%k*afF5-> z^@x|@#p`x}d-hIvHD2Iqm&xayo_QyFo>c#~;PNKxR8~5S4-x-ej;*O(T$xbn-fTH!_QpF0h&6 zyh-H_;LTKEsIGb;!@_#O=_L}{b=`PP6q>+^R4FNe_G+R_5Lg$ zSmt`pf2c^|{dMef$#I({4w97hRt8d!SOy5hEQ~9Sc&Qvx6j1>6YD3 zSjVPhAO(b@P$gsJFE=siCZFNMMcK8Yg7Kx}Urw@Lh*DpAHgbsf`pksf%@#gU1s4Zs zv;|Z5#hm712=3&DhTi;+$HUh|Y3pNy>&EURJ_r}+yf19xuXf#JZE(Rmp-T?_Yr*(s z?dG1y#iBFb&^cGe7PLn`3l$l99`n2jj$SuW{H|H#w6k$vvJlLlg`I51u)p!#U& z8by6T@c9I0LbdxOz^K zT6(@g#WllTSQS_oeevtPjp+<7in9I`u(tMQKem~%VCc%3W7BDvxiKxw}Q_3 z`OxHu@6$F2$)6CN!W^AWxjADUoCzsKW`zn3{Ag=RC%-Ef#}^#C{a$=aMkE4?9rp}# z68-O#+0^2%jM?;e@MzwKn2_9B*Aj;nka4;be^bwU`aQU(_54%M7@T5l?d>eWAp~?` zo^Zr_K|o*O{p*x<306GciS|-@2CpQDT&F&x39pIS+(=+N*o31@|B{IudxsrmO@$6f zp6F&hm%U58#ms&3-Z|Ab48^Cg+EPEkfY8_sWh~plSi|^L9tWSgu{|p9$i*OU=QDCB zmi6G|sNhn=4qLM`1xc6%(x3M=kt0cJZ@4a>;4KzxulL)o#Z~IPfU?Oe&!)S0Vu+o`=mLi06(B}Ja8SINF|H}_H$wYS73 z!0p9f$xZ5b`kZbyb85Z(&zPLe%aB?dU~rNqg*>O@QNF;TT7i^s5L$U*hZC6;_~fl@ z3{yl&;(l~Odg_1nrV}AA2%u_9^PWY!N>yGi=9$#Ek9+n>Wa?){8N^(Q6b_qWMb`X0 z+e(HRp=Nda%oH-5?+p%BKB*MbIhV`kr$kH-@W@?Ta(H?p2IYia7s~7CJw7X3TtZe4 z%7yoHB(&}r?vref&NHfGVPnFXa25MeIu_UNy=|nWQ|C`oYGlEuo2j|ip&GbaxU;y!7!>_V9c=6_9y~>X||VQ+VfjoB7^;HceQ+0S)VQVNFs~4 z7(_2&HG+TMP?tA4T4bQOi$ujd4gVRwB}HI6&Xx%s#xN%;JX;$Tvv!*PAYF(HVFYu~ z8x^1ob$ASNwx>@$L21<8azLa=$Tlp^-9VM6&biMEypim#325>h>p#qK`yW8I_#Z&d zBykluX+rjpvKz0Ne9raP(h^^G3_cm=OgN0Nv9F1r65D4u(A7kXg0=GLNCQaGt{kMty?PvSTEG{ z%prhC(j&mPwe&es!4~ zorv8F!*X%&4xczD&vt6>CJF5Np83W`R^wRfqDKmMeNSG-C8^lA6#hGteH5fGhQcyD z@2DokXyC~}O>6QlG0ZGznicB|O|eta&XBKbG{uk_58E=u04(X6hJI#jPop0_YWtpS za#?kof?rZKl~f@LVk^gi8l9|vBU^`JLJN4yi1e{N{DivW*kNq$lRFAwVX_dZ31an( zW|qwi*Vux+q8iq<1M$T2j0qzW9t>HTYRO|?b?M_M?;I5x#Tw+R`cJ+r#T>k`+Um+XC$4uLu)J|?Ta#~qyJNwJxS^UN3wR69a~#O;l9dc%(=amRH%d+I71D&T-w`)H zAdkYkPEl02PJw7e%sH@=ECe4RZ2(Dc0;`i>XRUa9_U63L5{EieP#=raw4UKC?ya1g zRmVSW+r_?2a#l(46TQpZHEUhFGx&u-yU0nvpE5w$=e#S^6`Bxqqvs_vw!ndW*!*IM zpK-!mr5vfp%aTH)N1O=BtiX$duv6V*)R!X}x`zSnUDh9bH1}YQwA2jv@Mz)VnK2opH?1Uv04B1Sbw&=*FL05- zKdoAW$@ts$V0fL#FAwnLKgMb9wH~q=V0km^>F~Nu8u;NwUk*e+61$lBCCP zsDrDCwE9n~g}tPRIOW=Hg1*}eWv<>npAZ4?`!=e<@BkB5WZk-Wi9dt@Y7y^kn}J0u z?PR+J>ZF*Gcx>Ex9t$3}XHo$)m|4zlKUo2h`S1YmR$W3zuhly3bDUh54<*cGcSyF3 zSVS}LU=8~Zd3Oc?K62v#ADsQ?r==k%`!w1_Q8BIZiB4<9%WEj-svN5$a^TX zWTg*ZFt+d1Ztde7ptuR)YCJj%aqx$XiG4;oyvIM912BEmVln#%G{HM@_TjG;v&*>z zrkJ}3U-dMt+v;a%D7B1 z1UlM|hmdu!}KGyJ?PV&Xrh=Nk3!hFN&us&uDGLR@>AW<^i z7906Y`T&o61hnk_+VAoUQcHYm|I&Pta<@~HDdUb*iK)N!#egWyT`ij5bi#k6{8mMx zJlbbPAW_(-_Vh?=PER2DYL|KnezQNb*UvXu;V!+)e$txvZtKa+Zh91Za@4KCxxEfZD6!qa(j6uiQ-^CSsUAfn ziwoom$|QxznGVEqe9uw;!cE)40IC2;kibl_qt!9KhLf%bx5OWuH6A1R7Nm~HJi|D8 zt-MhRUSI89V}Kw%DF0O$2h93xmrnzfzLv2;)uq$yyO(NF4>SVXXtm*!=T~bUp65%C zEw#v!|HnQj%juASJvB6wLO;%|97U^+ z1(nMDL;&&GX;@n!ISu7-zptk{6~q2Lsk$&*>(kWR`X`UbzRs7g1P7E1y6bR;S=ZGh zN77Im(q`UCU2<*3|1;|wo$9P06_nUCmuPAhxco43AyZ@10kiQPFUpZ4Z(Gvfh*3(F zQl7ld;)^u2Vyfrn>Q1;QV{`k=Y187a!EK_-@*Y;-8#=&^IcOtXHHK!RJl@Vv6R2U4 z-+;8!V*OXfl25H-z6K)0i$UFDzTRj{lE7Jqi%lsvm;teR5gcU;^Y{i-cYXC1fvey4 zI#?1%<6t( z5*M)~>Kalmq{NhtVoNjce9Q}>Y}VZ}#E%*@!Qye!FmO-33YHx}09jd5M$q#}$2h;>CT^b2 z=LXH*@?J}Xgf}yqp&@drC4`H>fh=;FDE%daAPGq1(P5=a8;Z?qR4wYT&l9-jnaxGH z;2D$9)7$y2(^$w*aL3wY0UnjEtS*;__~|@lA*aR+oXb%>T${63f2elAi36ygq(|fM z%~l1h+{L0;hI#D7wrMFw$zBqYS`Z};W+(Sd-fvFi5tQQxNu4ln(mhNefyhtZM}O+L zOr@5^Em!}O2{N82bm2$Lneb(alWQeD7|=qR{Q6R(bkZpNlCtPJ49K*Z#hbhn@_;HB zN5d5K8~a-jD4r;(BBp}q*XXyS5!WG_qTlV2BDSy_L!zKZ^8TGTzad?hKhr@F+SHmC zBVt%uJ!qqp6)ziEgS+EuQ5H`^FWDjv6^{XfG|ebdj3y^msdhLD8|=m89Nuv9zhA1{ zr2Rvyw1+{@51a{tIe~~O)l8789GKk#*=i%?04N@q2yilla&cq~7 zLrbMm)WB!wt&YMID(sWqn~hJs!ubeb@~Ksp{R59xWpV5gve;MkK{cl;WxJkM?N=!j!t5J$bi!M_s znxFh_F?_@7;I+*9$n)Tx?8W;!(A)9?-vwyegdjgh5CgxK*M66o{0Sa1g^kUxyGSge zc^CVSJZ*Sbb!|-tpyj zfE^F<%`{Jg)cmfM+wk=`lIQ(_XnHyZZLM@Ax5(J3B-KfESk>}Zd{i(# ziNk0ESM6iZulUZoGP1R8@1;*7Nuu&(q8mJIW&-&ylGZ2~enW+W7t&(O$SN$)f(Wyy ziChT$^iY==fQw*8qc8h*R_Uj2u^2_J1Bq=84t6XMw^s$8|JH^Q=qJh(Z!s)iax@Lv z)_Txk^cIcTNn@xN%^oR7eYC>smlBcQcD-_FMWc_0ta;%6ol^=SzeA{MgO%A)C%(HI zJe%}QTRgf={LA_+Y6|1$m3`6^*GTS>x%b|);*c+qBdy+pJWp0Dk~4uVNi!g+FTS%=jKMNbO3p_^kEZ|@=a6>tC!3Qi zC_6u1T<)(AJ3Tj+a=sHlTa6JwYTA*3nTzk|a}0roFL3!Oxbnup`TUKDXTqqyI{DYz zopY)APx7JO3~Y@~_N^~;6Zcr#HrXOrla-!N-oq2iQn zD=&+{`N;LaO%BCD_QN2@5n+`Kx@of<#StP^GJITI>lb6fxEk*#tuUGb(0j_RzWk1u zxj$W9wzBH6Ws3TZbs$x(YZ@3}y52Pr*tZiLar_=c%qe(GS(rYf?pJWl%ZoG*v{>7- zzgKZoV@Lg9ijqC{#giH zo$CxV8&~63-@m&}SgZc{QC~CJY&`&MVi(inr1)#59EDN!3|luJq`8IhjlY6$hKoaY zguL~K6M#0*@eJ^hMNhfNC0{DS^hB3D5-II67ZydL_IrymaSQ$?6~oHL^^r)a8LDB! z=$@u#UgO9U6mm?nOTvw{CT;?tCl*2V-GVUHqE0cUOVDq3PK86Fe*(~he0yWc=1&Sh z;IJ|kyQcP(UA*IrgbU@qW|~*a__!wlIX)4pX%(iw{DC~z)GuG{35ZG>9Mfx^@@m*_ z5>D4-8N}Au9o@yF(fY1sXj|`h(jPG?W5qIr5QI=_KPWq2++dKTx#*KVU=5uSyt5M| ze&Dyi){HxOL-(yGMj$xoNxAUPa_-$zv6jUpw}q*Cg|MgzRCHL)!M?*?xPo-n7$wBJ zIR>E}&*Cyi!o>-U+hQ-<(AX$n1f!Ne%w z>d)*kjTSYf*)4Pg`>C*8=9qO36N$hgaR)W%>R)50i>kweGSbxLy()5@k8?1M;xUBN zsJvUviuw_$RAeMQC1~IE9>Mv})7>#mcf39eU^y*59%YZyRx<@wN;-m+Xf3{&-6CJ^4uNc_z5k?p#!)Tg1(@YoC2YpK-4~Anw$b`M!JAYiCO%KvI3D-h3Ppha9YRDb>j#y}my^Tv+B^xO^ZD)uWMJuf&+f%xi zJ<*BvPLqM~%-~u9JmpK-gvARH4m5#eM_&)IX2w97z$UuIf{spGh7dH6CQJ)Upa7ZX zZT<1%)>l&&;~Hbl=QkWv9TTAmlO32H8a^rU8%NSntQ}{@=1Js8_Wgi8DykKc z=Xyh|@Nb3{$M)P1i_dQkC2JxDX4+&64}TeYjkJvz>*WMmaH<6GY`p;!q9j((%%G{W zrd@MG`U*a$^Mz81iJvhf$q*co+~e5EU3~3l8Yt7|iS%ni{flw=u-u=XW4E4Su}r)t z4W40Y!-0$jMZCURy;Q4hKd?8($zVP0p;?JJ)q8;$0n;(FN5zDI!lr0#U_IfxRY&X9 z*VNb{ezPH zoeOcDmq*bu!4b+4Q-6RuK`)b}BdiSjXlps;Z^6nPS*V$$7eFXqYMA}Tte zAhoTf0mU?m24YXydhT3@F;%LMC6q5kEQG!XQ2O&zd~-JU8w}%MQq|mGnz)u4I=Gv~^mS;5sIe+a4Mr2cV z5jL_+8I>81_T-!PikOEl3j2V-t;gU%rE>R_#^NMVo3meiM$=!~0s8iM=D33+qhXS) zYqv0T>5JA8)bl zx9sXM6+%)msyWUYv6_LJcEMbIxN53Y0ePPt;U?lQ#`8dW#O0@Sbe2SGFzMh=m*-p^ zf?IY!!E)pk!fJ+nOptdJSS1qnF7xJ)XClw=&&cCRrt>lLlVSe*9Z~b?#{QEWGaA?L z0rHg_*pJD6e6t$Ti>MN zV~fmSJ29ZxlV@&b%4LX*22~7}>gs!bvsFtGMZc8QJ$Vn&9MLjeHVa0~xq)FIabmo+07z$+b5xH&VtxSudFo5mdNT8uu{5y!f4t1LAWyC~9GJ??># z1A_?4xQs`PkWbPim|MpldiyY6iwc|J(`oN^^& z60wGQZ=^)pNgbt3rdNMQwcbI314nj=k##*SReGU^xc~D4sA#Rt{pJO~BmETPlw{-2 z)i?-tBGby3Vq75fFPM$rdl7b9R#S{W|KTks+TSF)N+@Ile zkGh&t?D7*B>5zP^XrIAcK8NjNA8%hMz4FP^ksUEYz)zKRi(GB& z`RL{07!Nj~YFYV;fdN4oAe|te`(s$eu8Io$=A>2)1%QddqL>~0H}*vIzy{IP$@)J6 zlm|M4>F0EIjDB>Mi3p|l+32VL)Js@j@v9C;j34GVYnEYLJf8RWv9y|&G@RZqPJpZ; z&r01|?Ag+GlF4x-aWO3GS&Po=a88C_C)_(4v@DlueM_44ET^roC?6`-O7j{X05`g1 z75B_9_tCT-a(!anm6-a8iagU|6JpyE-Y~x`mOJevhna^jDwm5(xd8;%a0%YrvjG#Z zwKtpey&Uvi=nI3gDgvT6;$9&YOook|R2mXZ--hLQL{iTrd&TvwyW867=3C z_?n~s*uKpL`8+J#Yv}7rr+DTF>FN8h2rKTOA;8-R{$%5Bg z+e%C88sBO)gmiqfQ1-E~kvrLm?0&o^QIFy@qTIOqH1q6NF-t?(ua~`WqT^aRBP2%A zhvLp7XlUN=1*Ap9AHO9HPh=8N6T;d72s+FU38wXqzAe>LP3yHcdz`NRk(VAkl_Vc& z+ww5Tww%N^{|_;GS7-nV-dA%87j#$80(686Cg*DO_eyaq-cb-R5JVHkIY=$ahVr6* zAx3$KiyE-~{z#x5Ar^8_vf7kcc^a7E8Yteps3;St z){dE>&SE)nsHrbS;SatTuAp|s>QW=McJfsX#RlC{9{3(Z${sg?Y)Okw3C|x>lvp3Z znr~D(qwj=9SsykQSXqk)kMNhf6cr2c{RpZZ{aK@jU#V0KxB(VfJ~LV3qbDB2g9bL@ zX{;NCthr}ga!u+FvHj^!zynuz*w>sSQ)u$9Aq$tf17ZdFOOJ!RC=`I6+Rad`pgzv| z+!gnA1oUk;sBQooH$0JaBLGZ3cJC>m_Lo(G%VX|UGQJ9~fbz>Aog`9l3)K-JM~~zt zm~rD8a@KwQrnrG~p$$ExeZU6iS@$i|kgh!Y)%ZqlXp3Y-;EWZ};K)=!EWv;5GF=D^dI!sId}gaKFCj8e6v0<=84@g zFwmFNl#OC7We+?0!+FQyR-59-n*ugzMoR}b5$H@W@w;?km!)IeN!i`c?NOX1ajZDxsW7V7^MrhJ1} ze9AmR6AtQiNiV@KgLBL!7e2+jEc|~wU1e08(Y6fkZb6C__uvl2T}q+2ySqbi4OWUn zfTE?iv^WF_ZUu@v1zKE+%S-QD_x{StuY4=#eCN!bJu^GvfLH|?KC%D-GMjX8HvLP^ z4{_!W39Pt#`)E$HmJ+(kRC~2=taLw4Jsl7K)Xy+Xbwlm#Kr*2FMG;C#IP`i) z&Gbr4QJ`K9Lds`2YYELoO>%OEy?OZ5+&w|(;@l|1s)Yy=iY!5u+FkG^QJR&;=8a%8SH%))|mv& znM5>+0pa4<`qe7;YVhb-fcgq=%L#Ua1UULcXD#UsuzIMYzSMR-VdQ-TEitDEu4rp2#XraH|E1=6B_D|zl$ zZQVY!gFTJfoFklE@@k4zL_-eblHu;Cy_U%EFrLnjlbBl-$3`==D=|N*&8evqe%cZ6 zzd$Oj(3WgKrFrG>b30= zb*z-h@Xe>_%7T=yOp_M`1EiZn7?8m%HSs@GW=mZ&rmT-oQ`C9|F<;`?zf4i)4A0UM zAS9Uz+wqTB?b&Azp@%BP&Qxx$RdJuW+2J^n+*1oklWaZb*it!WcbV~K-D5m;NJgQD zD&)*CZ+Tp)7KaQD8?=TpVaK5COajj>#|J8*^+HVaGpGH_y2P^T3Um6I6x-9xL-vdS z)7j@+%s&4w<@PHv1h0fe&%G_Y33|&+_I~poBqZ?(x7Y6aJFHk$)q#ggC4;3jT$p4@ zwRehnCu&P?2If-SQgw%m-YL!Hq(Lj;0SGvfw<(l3YEV2UWU~?jeVR`DS|#3?coI)G z*@B&1M zBZxplXM8AyPsP6|W%20K_QY}M`6nGs*XXx?h4@$ZYSt5WrlqS9s<$9)y=`QeM?4WK zvy(V;A|`}nYX6x#3K2^YB^DdkAp+^kg1Mx*A1~Un<@Cq#XcE#kHrJjQrQS8<9&fVg z@EHpT7tPFX%Squ9CtXGpH#F`iX1uCz%QN&1149-)qWTFQkpno$FE=WLJ#pj#G$%BJ z4}#pnPScUXiRvf&8U&pOs3vmWESi4ZxhHSy2r_&e{>FzmR^kiPe#~WH*DoLyQ@Mzk zCnkY^L<+F53KIY1a{O4QKE8qWn|b0*wAy5t`J%c0=R&P%`|Q$#w1HG;eXNDul_+o$ z>aLqy9F4l$t+nQ-HMU)vbPbu0T758-G3ts*h1#>-rhD{Jtg{Y$alm);;7t%|d!Rn# z8nk2mTHUz5p35N&+^ZKH*FF=76?TAWyLIkv%AW=}7zfu8%jfLPc0G7|5uX!(er@Ia zysdD^@mDaT#ob5XTx+azv{9w(-*&BqdllL7TpNQ_x+H8eP;7>8KKFddXsK`62@6#` zBMK5+n)r9)X}8V3(<^2|8<>T1P~uZ&W1v7t+A}!n^UEWyqmkFxoIIQ!B)i_jLTn#7 zQnPLo257{+zjwX+<6=||r^)8ir*qpZf(GB5klUL7sMo+;GooDx#kAr%cf)`!NqLZm z_E1T;UH#|i)NPc3l%cXqa5SCivraWeY)&+CI>yn!xE*vmFs<*Q82q{m(J<{$i-uE70LMn6>t=t1|+K5u&ty%xXs zNK|c*;Oire-jvS@mO_DLV?EESBJQh9yf7SB6)k|*iTi~8Gj-nUq&lwX+*^o$Fn6as zt60D6k@EiTlM&cK`tjS5?wlbJ_WX`6o!ZA-SCXRoCFS1M*M||Td>{KZgd2<%e6Yvz zD+%~5=V;+rn&2H1?QjAz#5g$AG#k<00}&JfR1Mp9u*j4|!iWJeY4KPhX3r?1lO_Xp z2u1e$oJ_9_c&?IJq_e%WiA}vgA$J@q2xEGxwZ`bSt}aVookNIfqNB|}fiL%t9^yS@ z%&jItW?v8*_7Ts?WNtYz>?Tk)3rV`ANDkVybndTG$-wk5!qkgwgIh_Q;2cD0Gle?x zk}q_xvK}=+)=~&Z+`j4B#lBQOJPYljp%hRyWS-@%aVNnCJ>K|LL_|sC0-*r zZ4^U+jDGG{&B1d>6;(tGrag;fC@KyiPL#V`NfF(XNU^`R6=I;PdF_snjS7_VO z!FyrUNNx1M0CEDzut-&BrB|}yslj%UHo~yBIMWyr%-W9lzOcZy8AEi!3&sJ=E}?q$ zeg$MSybLGLjPWKsAmza^w#>QdmIxE3>2Kzk2(?=IatC&^OB}x4d;<1@4hFKxc1Z6X z=)sz7VH^qq#WV)kPs4mDVFxna4CO~$k<{_j^7$DRD}z@9L{}Y#j`{km4KkQsD8R8C zw%lfpfbQlq8b*XLT$!NtSSBQ?KAz|Y|5wEl#)4>C!91W-75YO&<1W!hBvb~|!Q13` zc+Oor_Qr=z+{4z^65XHkMVhAz51r>en6$zg{uFqPjdo60ghM-<69w`6{7w{qL;v6qiGvc!ojL zuREgaD$ErJj^pr1!m{phAhP0zNp`#<-5#vrdNvbt|LDr#2)waN5T76cEu#d`Oh}lx z|2bB0dBh|(Lxi9yS)3BvH4PpmfZCJj9wLKz!H%fWfnmx;Gt}1d6c)o6`V5`8KD&FK z$m|*w6mWmyI6I}pIM%`Sc>9mBE+6{bQTL3>hUgcD5sJ6AI;G}?a5R9A@qOou77 zpK>AZJc8&0QLISQC7W=@B%`RNn}_yqpN-A&dHlYOQ0a$om_*)DB>W`&YOsQPK%*w! zWY_fM2LJBGic!!rE8mIdF9o@=>dfPDJtldKB%eZ1qrR#yG6PPXN>O--gF8FqjGr9kNO{KIvr+kOU(x zVs@hWo1D3$QZILnXqbJO@)CJRoR1A@@Vb@z7j5~0Dk&fYdL05MKvT_7LWc(48$$}P z0*t?32I%fS=&MR%G?4oHO|*)z3gTK&|7L+{Us^zBsT8q>YF4OqBn(t`` zK?1>;sO4h)ZBPTZ!oQ-?J#)Tkb=H-xw{zC#+~Cv!3xO*{qu1}iuJr5}D}=ai!XMH4 zFGpr@bd%+ufUPNBOBOPKa*}N|-;^j+Afm;#nt43seedr5VIDs9?@N|#b-wk^k2f)# zLAoYgQMuUsA1kP}W#zgCp^D+!r$we(%qUV|uqavYr@t6+jgU>3uepaWEX2mAX#et4 z5xDPpP))*)aoGUH_aM}BY$nse(D-LzTb4;4{Xbsr4OP=)LX@96rhBpw7jqDO>UvwL z?LTGnxG&~QQeQ?Y9MVb+YIUp)yR#LV(wT)aAh$(Ef9R=3mg&T#o_?qW6ruEpu zZvMUa-k%)D-ky5SjZ_lCBe-KLMyYV(-P%RZjpq?{k)@4mBJi5i>QPN`(x>+S1~VP+ zvJ@8p<-ttmtuq5dOIgnv+dh!1K@p%9z%S)C&QxkrNpS3-%-P6KvQ|&GUOXlveLZj5 z%-9v?h{C<-Sl-`pY3p4&l$%=dyVv7Kz@)#T5!d$BYd`&|vPBrY|1&RiX2Iu6ABqV4 zvYfl~&%;V2!C!`vQhirijna?Z!fv-#n){v( z8Dm2BzDOS3-RCJPoA%66??2pp@f4O#Omz6GkQlFL{)L<~B9nNrK-wgWaQXZ8=N5d- z18=NAwJY;0+V+fbAAJ`8c@p{j-^XQ##$J?U+uGcsnV0u-a2Mo!1Cb04cgy(GGr^%R>{*akTRI%j_1u1OnkX(u79mV2~%p8dy5(te{B6nLQ4{;0? ze)wH-y^P{~xuOT}yQxc#rDQL%EZP_I-1D3*pgy3W!OuOKPk~}%?V`<3VVUODyi=lX z)f$cDPC27EHFV7)UtnQ6(qb?SnKwg%ctc#ss7Att>{AMS6k)F5_Y?l=5G$rtDlZGw zoZn@I8%747x;ShKuT@w$Pdsb;EYiE@r(-!LEz#n6E`hx0NT>yIH0a%Su$;b-AjwMu z8%~bnU{jJA@;?f%Dfq~%&gX7Zl`EAoNd*Hn3*O)qw|XFbMpaCTx5X16y=P5o+`X~2 z#ZC}l0djKqTEi;AronG-S%?K*^)VK?YSuyBIburU=*VV;=weJDTg`yp`PzRAAy-`# zAuv$=v0+&z#I@D~CdF?6r8P1BcWqhO7(`A|x z8~3UqgEv9-pkF`KL`PgW1PNkyB2bZZZh?iyz2+$0s%v%^Em;N{pTgGhj*v{j^r4-d z)Mh{1y#I%rUC^$AP{qbCYrhW0n*7{;Pkv#dXON{Wc74cfBVOf^OS)tI4=?|Wwucv1 z-`Re4m?IlUfPAI_Vllr{{UHAM$4oD%*YJSYIn=%^4^KBIc?Ij777*O73uO_e9B=R zvq8(BF-2cBo1KhQ)o41(!#oPXW{7IAe)97|(x64xhCf6Pb6Vt8qTGY}kT5`|N_9P; zz-cgoF45eU`x6FbsM z=lGYJ2vw)B_vxD&fho7_1{{B!2B#^eXG@T@M&g#)7do5VcuUMwP@#xTK6o#7b^j7uobtVR}0l(uH#ij4_4r5uHV-6ZsO~hg7F7fSEeyYT9 z6A-Js5T8>7%q9)}a0rlT0#S1;Oo4dMS1pu^AZIZX_1YZ|#K(Xn{9DoNXT(rLjm% zFw5#4;0L5-ZWkiM>Kmlw`%-*4zAdV+{gnbU93{9j=34u**)*|4V{xqd-0! z1S4}=F{&hwwq9iz7QqqF;M>%2QtWGRv3L%VVzTO$qmIL2Vz4B))nct|G#{JrxoG0CIclPqs& zzy-3@o7HmPi6LT&AF$={=^U;33HBg*w3&hW4lqyXkIyoA_$MC<;xx=zF!nT9oK?%z z-;8CMS93VdcJ^|txq=Y$p~A`MjRSr=92>VEB*#?~E%FV18ZCT#x=$s40A1HjT)1&n z(7D4I-8(u%UXo_flISlY^^6zIT7Up8|B(3T(~1c^mgcPz!bbf2uS$?Y0b#ZsMxu== z%8f+Jb^<$grvp|l@TYI&OX6c*$$khz^l+=LLa|v3a;5wnkC8V17RF5`9Tr_KwVn5- z2ueODSEA;L!xzr-yX>lVsdqA*^jDZOA!;gm<^HXjZMc$FDnB-HXvRzP}X|u#-gx z*IL}`@8o+4q|F#nI(POKI$)mDzRbc!rz3y_o7A0HY;lDU5Rbi-M?wM8Ia&N+8Znfv=M z|Ni7;#m?6;hZvz1hi4-TzlX}OZr^Ol5-WYkJj(2jZa=H@ZO1AY6Z_mPe@ zVv{CuoK6a^M4}7T{fD>#c_?_e@WCb-Y;ui@EjD$HH3D-QKpgEDN19-{B>yVp7GM%@ z6=yYpU~c6#0@ntEHfN=J*eI*B$m7%M1#$0w%EIJ-wEzn!{ah$Dlp^8_LAS-Ffb(=- zNDK0$D-TtFz0JWG4Eqiv1~c)-dFg9qTh6?sZPzBnz`eDa{;kqfkN7kym5}gWKkz^u z&22m2GJK*rBXB%R<{@9-;N2&OE@%ebCQI9{hd=3421>THDzvj9YNMbMZx_ckYIQ40{(Cp{-4|o^&z=9+o zGib;$nC02RvJG)Opp5(wGeJSdo=5}W66Z_K9Cke{Op=&>(fp75oA@g=+eU_`dLemB zjkSF7Hwux2a$LU{P9skAf#|_#fy8@N9qE?X5~vcuwF?W}xgqZk%s|J>E908p6L`6| zwkoYNIqOXN_&L7NdsK`f!L&5=$5l(N!Fp|>R%&tHmv3E)F=32*1_=!ai_-cPC%v~u z15LK#O?!F4cG`C$buuJm$gnq8}Pzg`pfr<>c+PjbQ?AqKIAR%B}lYNR(-rg6I$UbTZdrj{=>s%KLcdG|K#a< z`v|730GrOftK<`4mGWn?`+D`S&kGk(0nZXqY2-WO8^p4IA#dF_RCu52q= z*@xFf{Y569T|BqOyigT8F7wH!W=&f@PF_Up^i5Aj2HIiwMBlQ4-IO0`utXL;p&yUd zpPCg&nh9s&s5Qw3emj=T^J5H{*(!YPyBUNXTM(wlpu8Uc1ez*`h#fSX{dLxql6c?l z4*S=H_;Jb38;T>$weumwz2vy(7xLTEO^p3JHN&;DeALWyT+hSWBJ4CQPn92E+yZP*LHotkoL5%xewGGWPPvuwWIyCd$^ikD3sU z*)#2kZaKWp;ywMM9ErlE_$nEbCaf$CtLO>c{u6V0lqp+y?iH1v)>rc@S9g46ehWEd ztq-W>&wJuR>^S4Q1d+fUWR~a3XhaTKphzUbX}pemH+cvl;guNHDP4*m4?blBG>qJ1 z9q68{PlT-(a53gY-kI%Xd1xV^3vODDZBRz z=5(#0Nn7^O#-=eN|LK&*%}3S`yB>{mCM`PS5aph=ctaVav19QIxde;RI+!cuy8e%X zLS-WTpK<#E9k*oB(=U9AkvIHILvXKAY~%V z4J7s7Q_ilvkH}l=#k+yNylgeMofy)^P==zP>@zz>V`72EYCTl4w&1~3AFVA30gXAL z8B4mO)`;mTXB*qfP?mrVXz5D^nKfs#i4W$2v;Yc|0eN3KUkS}Ys<7)>u865}QscUC z*Fo5z%|z8Jw5utU2ONm8&ImK9VUIUl#&-o_+>>>eMKJG?)7eV;+bhtUuuD-eR#aF5 zP?JITi)sr;X0w<+d=v3fSjUTXG#Te4MN`n8`yWg} z=fTge59x+(T!5Y~k347)I{c#B6p7pq`*4=LPu)4T%)PiAc9&fi|(+Ago|cE7^V0g>*Q z+i18_xd$!};Zi^u)cuatjq|u%X6%-OoU}*yqJ&uQXMbi8GlR6yEzhw=d>>dIeSzMfJ^!Z;kZ^jWR z?g|s`2e^XJa^V7wK(;%(=%;$?SGxvKx_G+<-SeBvq@I5r9?xI}*psy0_E_5frP+OD zm+zpYl7X8+VW9C>KJw>C@)ZKOq$LAQaK)_f@YMH}-k#ieJMp`M-Y-H7@(y)2Rr>DK z9`wR%m_Ut z-wh7K&1~NjpMkX%?)07I!ZlJm?k&4{8@ZHM8P+BoLODMX{v?KUL>Q^98emS4^bmogomF8kM05P)`^ufE=~ zQX`4K<#JbYw|5Wg;goN<^^(b--4@i5jI+c?LhcO|-m|1C!SbLQQUwJIMWj3Qe8Yya z6u>n)XDwqvqOUdI ze>vq=KL5OLHH3o&Rebo@9l>1x%t*>ubmD$o##3Tz9?y>)d z-#f>H5FQzq0A<&>+AU&do_zkjCg@%!dFrgPr(lZw?D|ht$@(3ooJ<$=Po$Lo4D(Tg z27AS&H~k%KG%)RYi_-bSXEIo=2`jY4mK|`Sqh;N403uT15J!!(0#<~XPN2#XOT;zB zHH~^*2Pb^gyfh{u{>ln?Sna*?YA5^nZ1kf-^`=fp0nip`9&_JHAa+8+@* zfS+s;xkX%0nP_2$tq*~EOu6fl$dVbgdaNLXEN&9?wV!pt8_3~_0fo`En$+)H{vyxc zIZ_xWi<0YNyla~jpBMhqRWT`2l_8TJx!*vo?WW+2lURLv}_8{JlrArR!RyJ-6U?n#g{Lv&w~0>7Srg0{sCap!E|$8vbNIpAf{Tf=F9|WjnE#fL2bcdjVk==U990m{v|=w^4Y( zC}R28N-jo{@K}IAtsS#=Ng}T?H6<*oD=F*4#B^AknT>f`nJBm0A8?>_GC?>ovcQC8 zT7nvnUa}r>)ACc!mvqVxM`!=USh9R+4$ohX8zF9q`3(17V!#$#DZP6sKRN=1Xe7jK z)!^*gYZ#9L@=lz^e)buJj%~QCdodoHGm2`L6pV*h5>bbgk{tAG_vNAV3%sm0vEp+o z5myh;FM&(9n#N)ggyzy%6gA<`rl{?meU{N2Zbk$|?D zvMbN9jX2wu?%VfAb%`TH1e#LS&PBR4D9(!Y_pp(J!1rwZyrf=KW0+ER7j z^}6!aX9D;no!#TILmY77P!-b$-a4clYZ6b;Piml=ViVEZG_ZkTB6bGp5_F2$DO8Xh zm#2P^Z>G$@N*4SjB7jiw!|5h}scs2tVM6rOA@#le6gy$vW*9V&aDyzEtVE2{Qy%5G zg{axY#q|7pz0^J;PhrzUMUi{pTjA=5nUs}*e_*fg(v;7YEO>ZRFd{1u`TUhga`rws z_j90RQINr<6P)4F#nX{6m2YCIOrWp&<=~n8N0=4-tN&3o>5VL}U>&q_a5hfcN-O>L z#L1j@L$WXiW5|PN#1>rY#c2z+1k>JgRC6a$U~j@V+&K@pg!=+K3j8uW^F14;kEJ{E z_Zy6AY@%tIIY5Aloqyi8&hq}&R2mJTaicu-tB6f;>MU!3Xufb;c`hH;M31SSflb#_ z^QD7;hFX0seSaV$3JK#+f{X1#3@>BU^!y^L2qN6|PvZst@qRl7;-EehUcEiOHw zePAiRb23-fo6LpVF;O!Ub@4ggy2fhuntx}t$fOkDDM;|b%4Q?f0880s*w4Vm#1_sa zX+ZbkMxPhBWyrIb%`f*KVGlo<(b%nq94|S9^vg^C1Y_DL_Zq3@gicY=y*m)=?Lo>#g zY_m=R=pDoy@bs$wq>q`NB9lZ^`+y6^6*mFC0@{tw{(3EHGEQ#i{TFvy#0dTPpAf5F35i1u-0_7^O00T?*KMVsqnlrPXtE7Vxa+m=|t zrSGa;CS}ubu;`Y-A*A_Lz8MD5^HTnG{RQ(RJ!5Uco|X5u^pD~d3qrUN9hEpvB|akC z9k#@}$8}nY`*n>*4E(P=Rg<@ z5sxWfN)RbkC@&jF7VJX->i_z!j-yWI6sU=_&l*flJBk+9dIRMN6#xuzW{+<$`loEt z6fEL_jREe#7?41D4yb0#P9}2-z6OTN+bVJB)rXIOBX|bOmV^rz0@uDo0p5nXV!*}I z4|a(Tm6SZH&f7)o9rM7HV4ZHDv9z~YfMWc(BR#%$Pbumi9C z)%1Z}I+zKpCqp^CTcqJdT%aTkRd)43)uP5aevX3{;n8hNl84x02LgqL$I^vj>DbWs zEr~w=72jkR$$sqEUYJ#n<3x5!Afh`$ezQIsFyZB$DGDDT^0@3P4ObO^B{X{l z+$2gQcW;3|0UOh8MFgH|Fu-33<`_kXivDyWiDej1ED2cKdvZiWEj!O_n)9*cTWZSf2^5QbzM`epWbB3sB?FHJDv6EH6rjsUzcIA|1+?dvabp>TW%W(<xw=4Xa z+d2bHqIUIkFF}m5;T!-0{k6A6yu{HShX=e$Z!K&x``^DkU;gQP3@Y*4R|qd>t?-Q20|2|WPU2%$yAiUHtY}#JwUGQ~n^y9udAJ<)3o<|NwzxCM! zZr}L2Zl97m9v?r$hxVy8afBDC8FFg?5-fVSX;zUelGkx|rqik87F<6H~KlxFU_`HpnHxTXU!&yZ7g+_$K+;aJ01r@EAg5Ar5i?XNS8z z&MSyD6`=)(FJEWZrtN5e#W=wInMfvt51{VdS7y1mTzBD5RphU1D9`eG4WXt3ioR<$ zW_eQ!T0aJVL%Q0RsA$x$|9TP7lqT#O4^$z?81rNr4GmCvVpdY@q`nmoDo*{z2_JYz zu~QQ_(W^=Hv#2NeJV5nQ2y6ZZ9BZ}PKXEDR$1MAK2>o(5eV|v75Ky{P@AY^fQyj0V zyF#xJtwfNUnMBFYn4cHM~dwvKzcOi;Jo+{s38l>_~ zt#diPr|Ip=+=JZ#6N$0Phv95oe0*1j_CS1R!y+BDDT^Xo>~-Y|levM~6U(GW2EVOq|aT4?{sg3_Dy}rn-z6Ou&Hn=EudMZDoWFz1n z-C}Q@QXsxgZTi5H)@{8-2RcsOco|zdG`+__YZ7(p0VY1_H^b(+cyU34I$#Pu%F;26#qh{qM&G?q5^kOn((I&_%-i zx!=WUKetFdQ_>`i%qfF#~@f$mqyvP%Q_3WDn^AvTXaA()5Xnbqfr&p&DS(QwY~ zUdx>Qn3%I=y7RhtEWTWGC6y8L9ex#nQ^Pgr$*dP-Kd7G(CS>Jrgy=qY(4;4JQ%B5B3}N9H`BLn)D@Cpr8TNjj}d%BQ(Z&f;+i zt}$ZbR*sy*S1#v$H#TaG7zBs5^eEAHQikw@U{pabfh9P5FHb=?U)q^em+G}oM!#G@ z-iZQQ(kkA>7yy~AVN*HGuX=7$$L*2~1FFIT!G=T`dzF_EUMc~mA5r*m#0Wof;TeOW zDI4AtX#{i%mM?eiM}J?n@MsLhrs6Aa1siTZ;q1Hew@EQ}dqY`ZsRn?mosoO&{U7vM z6gEX01SYr#-h|S-y!;9f1v%O0)^||KS1>EVlSEaRoz8ObDpTYJlUuR_bVm^3H*VO4 zYob)({qOcw{K;2hyBeL41&mO`Z98-)qgTL}UGbM`vEFAw^s7gB3h9^oKvOyo=51H- zLOP8(GquSLPPgF&j%io!FMSW3^oJDXhmAWrT2t>F0+FG58Y_LSEA0WOy>z;IlnG;q z&V^4yeIbt-u4FIuMQ}jlB4u{TJeU%ldVq%ccD36HmcH)qS(H^bzL355*74F+SMcXd z>Rcl1X4%FjoJvDEP z_g0Jwr`Zx))st5ynhC9gziQ6RXppgtmcuHpb4_v@(<6GsamqFxA|}{e+j(XntL?|7g4;gl z?32?EorFyy{IcG?RZe{KZ-WLQu^T7*tT*6#BpKXN)%Bb9@4C-vL|R2y^=d;2n3L~_ zhd%8b%mb+#LkdsQZ@nU=g6v<@7&|`nGjdkfGEh6lzc=_1>~tvkR2+|o@O|>z`q$Er zd#a4Xe#(q+r0%p}Dz`D&ag;@RufJFIqv%U%SsSs-1Ufhx*uuI z5&LA4EL?F)0Ar-C{BFV|`S*$c?vM9SZsk?HN1(gbncZ(&$@j~{`nk&uX1~)*n*C=i z>wi$z5OQ)c2Q?sC1z@8VB3qK?C-nm+*|OCp4FQpbD&z%e=WoSNkzC)1C+(Do z2`xjS16mkOR9u2&zK>j5MEU`y(4Vb~3a3b~&rjDX{(Pz!q#82`3lhk)*INvBYPhwF z)8os;a=dskld%O`pr`bgJI~=-cq`|_J(dHBz*vbbQ|oQ-Nv}Oe5XS>1_euz!`sA{v~sxcJCLvbobuFm#kn_Ivwu(&E3_{+|a;KI6p_^ zN=)oPN3F`G$IG$$ocdLW%Ul_=;-layJ3R3zg+7qJBo;G}TT%Pm_%Hl!ouSQfMzN6; zjBjNDHkHItcvwA5c>?OKS%Ew4gVs(;RIjx~o*j`WITT1_E-R4sG||QiaX)>aRtkMJh*LG|5C!NN7fs99!q{`- z>t`hv`K0^~_=yZ)-XzUUO35eBoZKWye3-9M7NAY=Y6+WJhoJwL6*k^`zRtx6OTkk; z1Cv)9vhc;K3F)@0`@=R?d8JiDg)^z`@L2_dY7B@}owJxzdPnbw^QRstPH{q+!GkMU z^Z6ENXY2u$Cmn{R-l4-*qR}6?SbKBQ`qDq9eFN}t>FFC+UXm@s_9h?cS1bp;?@*@( zkvrG#;~d9E^+`qaavDVQb|}261xrA))=Ny=sPDqa!2jnm=g`~{z7``b< z8ccOBp{`6pV)&DT9_=J(e^ne;MWG$74IQt4j@Y-x1`dK4Ku3K7k}9p;UdiX~fLLv- z>CNKxqRj1^^l1fIf)e$+JT31qHvo;v{kQ2rlP5eSp7^mtL}MbbhSrT5CdZ>){81nhK}IUyhc2vN z&6*hIECBSeS0PX&qT+C;Ua&3By%KLe(T+lU&v50JWPSt<4^@ zuJ*kDC7Yar03VI@r4qc+x_G|AuQimnW9DZr9_??qz1a&u%d*s-v(!V-KXQqBP)CF5 zplT8}+!TLbN%RUB4;D^_a>Ba@Lp%viIg4XQbTK#v*t>i~TiueloGq7~H70m~LqFF> zF|vF8ix!(6iXT?S+%$z)Llbd-ZCCTjLWS?d8R~~Cgn8FOifT;QyKZgBdvHr_jvA>x zc(wr|nsiqXY(8tictUOW6&{A7#WS(y;RrgM+y&32SpX}9gU?|Iw{1rXx&!1!GHvrp z_u;+*P3XAk|BQva_OfW)Si=9b4I>B>qMB4wg7Sg-?_b2bJP?9;IVuGLZOG>F!H z>8vhXQVt7w^p01Dom8xDRll~e(n7Ha${zA1%eiV}=+KJtvvt%aDx zp#h(`{?0_e>62v_^e^!6S3o4nqBPy(A9-|uTL468$l{WUdcyto?VE>$u&%EJX8pIp z#OL1&Lt_itiKqAq{=HW&ND~^>pYZS}JhBx5(%n%bDCrVWfW&l+Rb!9M0~y34(lUmX zZz*^PGzgL_8&lk75>~phNaUA4 z4qo}^+odSIE3Bs?zXr(TlPeQun@p@0yEQ30D<|3>}=nuwV$q_g>5jYGe z+0@`Wp^vgEAPQb04+`TpMF#}^$evb5?9uQ~WDe$vE}|N~Y}LmeAHgHk48xA^Va)2| z6*0Ae;H)pgy*XQVjlEuknik>(5s_beCgFo9oD#9heovm?QrIBMihgi^%@}hhqZ6+PHi9P+4ZXsZ49Ik!{o(3=7j`PkIO^f3bcvp z%6<)eu{f*Ve4vI*2zU2(+FWC8r6W^S7TuwyC$pq8v^opkvk@f}*T|6ziQ8BDre3oA; zjq71La(jYJs$WkV)0F5B2T)J@iXW^ZPIHF!Z1*UKN}ed@E|PuSf7~ar{f&}?1rBPs zm7c6XrjQ*FKy|Y2oY~yx$$b4Wz|?EK=L(=0Uc#G9K?R!9rczu3D$=yBh;lD9kjiY* zYcn^9W^9WF7=kjbI9_8A;X$|OrFEYRruqV%c4ci48n_#SGkaIH!5q+=y)$^5W4vFv zX%mg@0ImF627NbOVR2By-3+PWpd)cb)C+NV6W^G5`EMDX@=Fy&V}%}u@wI)i2oNH0 zYhCvZI)xY#6$p3^QllI^c5N(l;ic^^3Q4}P3t0a)xR;k-Q%6#C&_t&Y15Sfn$X&>m%=I!rPGC1c+B|wz+1%j-34w4WeLn9>z zH?^53@AyspCv!c1n!7g?ilJL|c*}K7p`PZD|GhwnU?0>v`CYWORkHX{h&+4+lbm3n zVhol7=^gqgq)7r4wm$t{jpAR{1G_sZ58idXQ3^n3bB5S|}Q5Nplm?UP`EaS55bojRo97jp)2q7M# zd!?L?`crsJCw_RkGV$GgEA{g0M@UK)NJS@2RVQaId|2l<7*(7^xT>>aotz}XF*5KC zib9K=iTHCB-EAAY#p7Yl9|2ShtD;aZY#0<2f@#%a5ievu|MnnbQrJ6G&g zWuVU7Nugf1A0oS-uH_Fg?{V}L$t^wGlINS=g=gBROA}d=Pe;u#=-W;YylawUIG{&$ zGT=G!qr4jNK-x}<07bsY50EL%7Q8A^w7JTJSzvuVPC5ML8I0NRW_!nAh=y~|>xZv2 z`GWjTcEwD*f(Qj{!Z2AuO8ac3*Sf^@b+HupC%CA~;tD@6cVb&+bFrDR1WnORR1uFL ziR0cv(DGk4G&4YFtRGp#+D3=wynw-I0>Ti9bi2)9*be4dRHJ3D2im;nCxWmK zK6@;R{Db%xY(yE7fFX9Pv+_I`SdtQlFae)l4xNN&62Smm9q)C1er+YUM}E2Wfv1E_ z%M>0yLrKf35(k~O&@sXm9m*!x-tF^p0Ec60PF9VCUQGC&AezZ4drjL!Cd$^x)ffOK zM_GhQu(e@SSlnUxVC_q=0eTAg6@s+5xaol(29}Lz>;X3_($de`4c;BRjGgjm)SnYs z3B)HRO4@c-rqH=k%k@hZb}MWG5nx&z0J{_1ORfhPA4*>&*0M;2Ra);w^p2oFcS!)G z&1G%G$qMYkej>$me8fL%z5#+vS*>gcdc8;wn6H)$5Sd8AND^ zhlN3J*QJoL$*F)4hqWRXz&&>oZacH_fu;{NVGpUR=I${Vfy zw{sYO^7ZKy*&%uZynGbIy)P|MAmuW-XcYUiaVyNNiQ&;JukgRwn!?s<|zJH*f%g1PSTek3%`AYCooc?yTy{_p= zMbKOmDT@p9Spy116Y{hdboxxDEv~~cOd>-g>6n^?MDvz+)ERL)&mJ43#FB6&g}O$5^qIc^7|(FjWH);0G(7|Mh4Ns%3R{TKIsl-sP3P);Rrt zJbh(A(*gH24bt7Mba!_tol18|2?K%Aqd^8JlF}d{jYxNmW;95S(bCfWpU?9?@27p* zKJ2&Md+xdCo--&&gV3j3#4*jQC8i^bNe(9bZRd^_;fsHE!@5B}Rq7$Y%N2rp^TO4J zB_HS23|+U~&}FeIi4IkQ>=!Jq8qoc1x*L7B$AC~Jnj;U2Ka{+xC+nqRz_VZR&49WX z;D`0n_0$`sI5FNWiM)7Q{#&TcgB%*PKQ9R=>%|h|#;Qk4#7D9|-`hYG}n%R5B~0$7e)5&_N|?V7r&QpM=zp=vI#uhcttw8xxOQTyHom+ zENL`QS$%P8a=5wIKp$R5;39{<%Bw`9HDf2+2JjsIym}?8e8PE8>C0{ajM8(ZUr!>D ziq_Awy)>yvgXh7ifHY}T4zC^OrXwfou&DmFtI@Y=EXx17%F+BpW}z7=`~wle&17mc3zg;ZpM}%Iu-SBjvO6Ps5{~C@P>IWoz4M6Av$;yXQ>fR+I z-;Ygj>yyRV9L%I_R)Ueg3lUO%HYy!+^Z{3qnAz4w({> z1&UwNa)coP%?h?Di`|+v(nQm*wG(~t~UW> zL1u-SGGx1`RTN=dR=h*YwtCC-A{E&pmX#{zsEF_fRVHO?o&p_$>y)_1zp`;2l+q;7 zuta5vMEiuInJNSFbN}r?f8wNfD|}kc6ki{tb;<5q%N-0e^|;2d!f>!do@pVmv5&?O z2{5v>6S{@?os-MU+fEuW&F_M1ZV=HPy6zVwQZLUa2)b4$EHB=)s;A5XzYB8f#F5dP z=GdXzN)!(CsSBkIUPe~kKD+Xl*NUy7UznBc?y(&T5o9@`*=bIC^ja{!Z~F$fA>W-* z&Pzc<>wlc)?ug)5d$wK@5YE_105(!S;KIVXD5Tq6Us~lRH9&d~=&T#pv_Y8-QrxEdd^6U|Pafc~#y22P(zRY#PI^T)t~VK0G6S2u&rHyhwwq-}9#(@+zRV64lC9u4)o6;PbqjicK zLW+i^t1`~?4LpBW3k1=8UxS@1yg7_G>+V699ZTlb&+@DIS@$Ka(y5qaoS29F&*yX! z2q704V;t9u$G?%_wPuXs_5RuzJ*O?^ZuBlwszODkA*LTDoQBHA>xVsisuvl1Z_70H zweQ&S&2s7Ej=@ExD>K1$2UhO)7e9y2$-zxX9?X?2*&>T4HeG%}`!gQ(ySzIRpY}V| z=ESoLW$A+2FCAwC^_^?||c-xu<$+K!W&=B*H(w0daj)ptT2U42Fl*4g{8! z?%*hL64vlQzu=B;@i%LGs|u+gYGV4p29)9g8HA&1(_TOfP#>jb817$daB#bpNCdRT z)wAUNGtEQ9P2lo;DVkFR8ONjhB5v~DMtxo*Q`rr%aSQoYTk40gnc}Z)lYI&QUMwE5 zdyz3!mvLaH!TIBRg#ltc7g?uXOAh6vbwyawAowP2Tb8e=I6otU|JucVbU69I^46&VcPXc)XBCTQrd;CAjLz3$OLo=03d?ZAuK ze|*2yfAQBs|4q8d_2G<;_}OI&UXeMyt+a~xH2}A88;+4W;VrHAUm744lLi1IAHJHC6+z{Gca zLE?>QJqZY;TqNx}1K}(-X42uBWS_ED718C;v;6qhaY*?)(lU)8Wv%u6o}f5M9LWz- zwxE7M9$aq7^T7ozr#+(=f*#x&D%=LR z$ZRX6sHD%oMJ$((;Z?OyzfN1DfiWZgK)io#ww(t2DNe_KNgKfFdvM|0Jb z*xq~)1`_PAA;JG4mSn3(3*teu4Z7_hcQ3t3O~;L(2t9t>yxfzhy+#?AD=JyGW{XqT zHqqY^=eG~_dLi&%6bleoB;p1~sfzqA?JX5orgYONb3j-KEh?I^tDG%qEdNh=ZGQW2 zQTq%-LQhaMuuL8+g-hgMj$tJ-f3Y=chQSmDf3fFFX-||;dhoSMuBC_?wE@+*oMy^N0!|)8;l~YDe~gk^9Km(~Hj5x6ro9^Xuo%BK<@$hJx@= z>>P22g)BPS7{OVNOAEuCq*S|Dj-E-BLNRXuM1tSBe`N|6oTv+U7jR)j zUNA1#y#NW zZ;D9S4sXe|hL4H4RWq7f-Abx~ntV+4Z_pkwB8b3}lq@RbL{#6;3}Iz|a|65$hYdEs z(Px3Z_6C35CZI?gGPJP~tg4Qvgx7@>0^tHF#K9)eST3hpG{P?6cG9z#ZGv~@Rjv_7 z5fk=;ozUca)d-3Paz<*6Ml>|<`{N^gVoADbb?<$b2g zcRq}k7oNnMwGk)jser~=R>xBJqb0Nl)YIpxN6C{e(_s>Qn>jzz~wyZH%(^#pvE#|D9i)4+y%;ZNS`a7r2_jQ9cm|Lkj5!bgonzuw6{q03rm-O)1fNl=1o5xc{g?wF+^`2 z?ddl-lq#ymvb-=6xO#{YCG#oWx}6kZQjMp1s0T*oV+@Hs%Z5piKsRoumOQ+I3hpY7 z?my=BGn}m0YY9DH!sqXEXMcis9XvM?O`Z9$C?pj<8N6F^y|LU-iy zvUQV#LNxB~3pp4Jm>-gXi-AwIznlb31{6!MTtzG3g-1q_BI~KQ&uogP1aNDV$yzit zdQ{m`)a6v+j>d)qK!gy1`_E@@gnUAPi$MNcI_LWI1esWZpCvO2 z{|j{Q_yiC1lj!-3<9#<1PD07|`eBlr^tO%L31N)W7BYgdvw8Wio-0Ax?AxK%B>aqL z{<}cyy08d@o#18K=7$Ksk!CtQ8-xYK$%|aEO|-%#>&)I;>;p+A=@2Rd1s9WilD(fu z8Zs{dju|!$C*h zi3y`zVgBDn0BstTmNk+>I$qo@u`f87w$&7cud(q!3|ICK%m`t0<#ZmpfFLd=YI%Pm zor+Q<4WJC&OZK*CSJ%kGViiBXj)@SGz4;ykk9&Sv|Nv~(TXwD|MwPl6K#viCsex_R(f8Akicv(zx|RBan6dO(RXe0?D=p(K?&`79Vr^^3wn~#2rfy=U~W05 z8_KUr*zifhH_~rmd1jSkVdpL0E%zOcfjqg(Y6<`1EyB7yZ?*;-Oh)LHhmpSKx zVLw)oU~UJXhh@`Eh4(k3Ui>|Cq=qobmFvNH+4&?4>=kF4Ph6DUKIs#t3B=`ZS6*@? zxsqif+KKLeV&cEUnmh=Jc&~u6Z<~Xt_G*4JwSUt1`p-{rM2JxqSJ8Vavm@9#sbxuz=iLd;@swSyf~41-S0@K=suqESA-vGWN4 zl2?-sSl7)Cq?jE#bavaTqZ3l9&zz;?73mI*-WlNnJ(`_?8AlnyC%IiIu$^?%uk$V_ zzr>tQQ(#kWX1cNdSR^$D`JPJ}DkKM%gj5YpmSLtDtQcd~!4F5hqNT@o@p! z6g*$WHWf}tNWvqSCg8J@S&u|M5m3+!5n|DE6m@5xWfZWMtoAvGm%CQKFgg9<(}p%r zHx;o*FA%UJl+lJ*ioFE1A(kwnM2b4+xJpNa*KS!HvkSLYi^}Zo9IG(n2)_#{it@+{{>xXD zB|Ws;e+}(s1qI~f@{$G4Js+lUaA|C4zs`!9WaPzsW1XU@QNz#5I_=W9aHz+9N2B!4 z!2Qh|g?|G^V_d4ei39J|0q`x09R#r>+OX_n2gob_gvx)>{nz#msy?PPGyjKVo@w+I zkucs@GX9rkhBz2B1yp`9c7RZ8;j_@8CBFG6zNrG&^@_9mE}nUnZG7pYoqk-JuF9}j z^KDAc7xnqYO%#HNsEd*GYeRL+&R_qOd3xUnzAb8l zK0ZZ(<(6B9TPf}qvF8wlaGeIGpqG}Kwh_Qw%|aSit-Q(F7?3|5t|wwK7DD}pXoyoD z9u4xw&PsRk%w~cADi%k1zyg@6`URw{aUpB2|NDpmnQjJl5HW)nhwR_U9N&O~q^j>N z&Ig;VQ{W^dIU1UnC*mT%w9ngbKSgx%mfZ|F?eQiIv$`Un-K(cIsuMO+nuietqmPLb zY#y%yn6g#EjrpM_jC2`i!}EkChl9}w3D2Y8%GJQt>*!aN&xeK=ROuwj;=t}tJEp!8 z2Ltc)odbl3f+_5|Q{9$jWzmArZrnIWJ2Wms1n`fBF)v@Kyq3kdp>)lBcw&20<$sR- ziZ2P-kRd^b7%(2jh2b-H4QUk^ zVzuL33H<6~F{!IICQ+U{lRL6{|#K+J`iay5q3K9=Nrwx zk@u_Yw(QZ?PA{&zxC_{&x_3zso=RDyV=U-C>Qgan2jCD7<5%S)%;jX*s1>+xM-Wk& zal6-5k-Y_uCC5La3O`K6O*tcTdPx%SPR9X6-Lq{XClK~!1>ZqGj0?QI9tQ})nG-s) zTODyfPQTi!hpY596zh`ikT3=Yb@Xq-Y!qt^e@xyo|69?Ic+DmRn2uN%i@hDHpQhqj zo3VvpD^9&u!X>Jfw?`6N{;O|-i?$$6ncb}GwWLNkq$se-Z!53b6eSugX_+Odjn$Yf zOi?~D>t(h2a!TzRSVfp=ei-<^9YuX1^%L$EFlN7v$$OcY!GXJ zix7!?a9sRwz(xq4P51jo>@Kg90<1Ck&beRi;@ZH6r7!)TzOsnp10XTWE@L>LKLF){ z=Qja8k{2Z&;L8R{I8>Pka~E~1xyr)A@!<+VE{Bainx|`+EjJ8WyX~^xw;%{%TSVDm zRm^)Ht4?Tlt)l>~*6YZ92~SdQ*E=oq3p)MBn~>i%r~Pa^d>1u3of3J^Y{|2EeI_0D zW!$X7WN@qDOQCE0ZD7B>cnj}9-LyFl0yM{9gg#EP-g_Vv6B=6Xm??T}dAcR0Gl?R7K(;PE8m0COu-Ml}B0l`DJEyIs;$8*byVu7CKAAU0u)av& zySlP$oiSgXM)#z0FRC>VpeZg7d7e1P|DJ`O2U_RUO1O6>azlIY<|>{w;vji4M)^(M z%^Psvn`TsOtFIed@?vT=_Uy|+<;GZp&0B#?PxJAoVQ^}$JDj_>2e&K=p-?z z@XTLlbkzICn)lkv*Uk|!2qQi@tRBbb!;KouyW58#XbWpt3+t5;4Uwz;itQ^XfR&Cd4 z{#sMN%VPVB;8KM|H6!$ehcKJJfH5d~(P*|dp@mG**`mZ(p~?9@2;6ewEG9rY5`-J0 z&Zy^4|52#b+wKAve>#VNeRaP2#QJcxWh!LX)^dGkm9xU#HbG@2y!YFi_79hvk)K_$ z0)yD>X@3$bdM^gz7taKpgf*G24@f`jzgwng;2i;AZFQ+1H{)wMe{GY?qLQ);PX2tgpq zCLzE}^h0OX`-$Bd!>(@4z;BR@Ueh2v4i{3rZCWj2t;p8I)JWe9g1JNHNdN3)V3a~C z1w#Yra|tbcWf|6)-GyV^}rM`!srLH8`Y*lG&j+b6M)VzL}D?R!7 zGX4Ix>F}M>HX}J=x)7S)TpMT(-crgI_%rUgW?-kPN`4nK0CL2^&&NQDlf>lE`jzFS zn3rsevS!R3WMBO^GPs4i=Yapylm|atg{?=(m-R~iqv_(NOw5-{{`a{8yOfFju@QRU z0`o+HcN5m8Tlz(~7gB|{Xl~>U0gdysO&o@2B%RDV`Y+gU0c$e$LFXe zz(>aorX2WXd~nF{`cB{@@2nK!Y=la(EJ@Ht^O!8K;aqxEkb2A@DdE0}=3F+9&)9x8 ze>rBd?Q7(%M-7pcbu(N-unlw7Oyr2cOZL4Vr*1I&(u`rz-HaM7>9RN*YP=r(c zfrFwY<641kQ-l!~2X?@NkFt&Q#5HYGrL{>*S-`ayA=hg`&_GcYkEp#iYv{dE$#`38 zdDZr%V>=0gswQZ|S&UyS5?I>hYW~3S2T_dykSsJm$w8@CZ&4AB`EIA*#prp^?|9q) z%3M;8I#l}F9JkLW1KdxwSkBXX1I_L8oe%g1GN^*j9?lQH-|pf1IL7}rlUVDdYszX) zs1=nA-<89~A3l3zhucf4NWQRQZxt067_^$06@e-5n&ITq_8XqkrzHtIq@U#b)dlkJ z6e7koJ&D&2C>z?v#v20_gf+rv*aTvxSj^N4*+|+%4<|YDMuMH^8?t7JWpPT-5hnV! zJS&@toUxg{-B*Ogn3Snb?78tt#L_wuXJ;2wxNybs7m0{xxG@sj`OEHoUE_5!x#fRl z2!FFnsonz;$%uL6;}u+SYu$;2%`#?ouZM^{=M`6Hs9?e*m(-=)PZsmy2hkEn)XORV zq{4cLDo(YZ-yl8C$#B;V0EyY;PN`!hTTN_9Tu^#qh$CkwE>LKXh_erZ z|ARXRig}WpRh9rXU@KHXLEmCJhEQ0QuNx#Zt@21OZ5w_dyKTI)DUTHHY@Hb%)}HCP z%7=(g{6vu*#g9~k6IFxPni6!hms~niyf+e8Jw|Dv@!MLK!DYF~F>mLc!wNyl@FL62 zVjs=XjUvPHz|YS_JF(Za;Ie?#{Slk_-lcl68}=#I1)b!5fN^31o0yp ziAt$(r-G+1M~1;a5niy2*(+Z{+_X^3w9TR!vcGA+fDK20)vz-F%rP#8CFEqIY5Dj0 zBQ%lDYtTwfX=G;4Ko~giX01TJjtRq36pI=iPxSZa<=1DurA*;dzcBao*sl)j7C&>L z*Z)uml{J^Zd5nm-u=r71baZt0rU#MhMh|_?sepy1fc7YA8fD6vNi;W2%5(y$nTuov z)M#b{%lry^mYd%M(9%v^>{MAdjzmNX=?yKU2h}voPv)=Fb`S?Ex04U%+0ml@Ta!P& zr(gSot|tIQy0tz<@-yx;M14jxmk0yxlKsddz>;N9|8$3>%B4u8rT+?!*B8S~i#bQ^ zAU|RbOn7saNaY;2bi;J;O5ZWX#t;>zRF^~pjvJ1C$H& zS9jSPWE9)|&~+{*4W!1614|?-C4AKmwx8D4%8A~wl_V18K;9DxwdhJHoa^NsQgj8C zCGO*D$NemI968l!Fjlm)fN_{{*whHxujbU@>n1nzt&gS!Wk;Ikx-F~y+C9fZ-WcLi z;zPfGH~#)k$njs@R3iI%fmSi8m5}HZD=S$Hi^}Ua0zasn!KVIWTBLCz{gZp9;Tx^g z?DcWBB`xd%bvy9FJv2_d4Ou=ga@0D3I+!I&4N$Pbn6}{CyM!xXxFiLY(6=v&wc)aR zB{ufHK|q-Liy7xmuWgjW?dLz4jPN(eCT>@}k+D#6>^w5utRWj^l;6q%9E22KO>xNx zR3e?hDRG>R-=5LPc<3p>a3mW?n92mYvA=$;Wnvk>8hX#7CFPx1x$gJbs8XpGF-^?o zjDyFGAfz)1lr;^cGnIS<={T=D-XJ>=5OL7aJWMM#NH~@H3Vlu$UqE^9t772UcmC?5)BbEldGv>Y?d12wBjP zU?)-#LSGwltIo;TV(cEQ-0*gIRIAOl1`b3%YteFZbFkKn2wW{S&FPyrJNddzu?x(`Lnx>O6hNQ-&76K>b~G6F2uyz zuopFB1C*ki8S!_hx5HcAite~zhD=in?Am)~Bs7(mhnk22-M9%;d1#AynNE}MQ|yB9 z6shKZ=BU9sHj2D@MvW`Q&F#OL-j1$VuYbqm*xuiBsh&Rrxg=za@(&H57I%Z!f_D)P zJ;rH$c`eJ@=CcC--K4!XZ_22-9Q}b17?9;=or5y?(iaJpREaN<<(QFctuXQts$#mH zn{&jj)Gi%GwEl z9nD3|^{x5{NmwT%;AkSjZHPgL`~|gUe(bGld__j9?7R{!XBj10ZY2*fl&*d|`{p96 z%CFOMGYD~>QvBx+WpbU*g6jRDA_FuP@rYB)-Qm>n%>&Xj?R7mc5lwjtDKyL+arQxl zVxaFrjxUfY={5*a&dS-x5vjpopaFgMWo%E^4h)l{nf%5ipL~-j4%63t3z6{FUj0w? z`@uBZSOO>ZnjPN14FW>n0x}>mV>cpk+Coq7wW!)YRgt&{>mOM3=UA?|pT6yF-zBV7 zgHIv6vnxuiw1TGzr0jx;^Qj`#;*Uxf;X1T;SUr6a8%lt}}y2&PC=EI3FT{KcFKrvL?l%+S~U z;2sv=Eb9N3k1Iy?{4@YfyrKNtzodkN?s|&%47MX)7uuBSd<}$EH%-^+ zKAz08{Tk`V=y#7@9zQDwRz1+d+y05;HUFz!`mxI9d-(2dk3Ydt7+K3vcp%V2OWq*J zGAsFH_@2(7hEHHa<5*kP@HBX2FHzcpLnmEl%3maMq{A<-Tu8OUOZdB;Zj)m3y9jO! z@4@a52B*velcQTji}Z`eha%V;$6swm<0yVCvrHbx(koxbPI>?6{)$)&N8Fquu4)YG zZ|{2>2zq!}KR}w(;(SK%Bb)|N_rOZ(XNN)Hm*iQjVHYw7+ykSps>Kj#YpMBj;qR(g ze|LT2g*)DUco43M!R!OV|j&su<{k5|}1I9d-#HDcVZ>PGlP#2TDPC$w2;`O|cp@ zs|U^8_^p+;cJJ)$dt2BV^ZmW|nWZNC;mch@J4&T+8yx;COE+od!etebg$q(fk01-w z*ALQgOInkNBqP-aXpo%04QTDVM9|QW6A6Q46p7^ADMKZ68ibE%Sy0 zLw-zPnqwK$44ps$!v1F@7){^4B;WY;hX_7Ycx7wQyS9fyBV19r<>c2DEv!y{SG4{_ z8p0*~kcYW@CGg%<*c3@yEJH7e)&B=hhk4u`$A$jj)Bbl}5UojZ%bIjePhA*{N(w26 z7rl*P(Vi~-nJ&W;agiXhQ#LAZky60x??KqG>G?q|=eq7%nqYCffABV_T_*CN!D`au zOpTcQ<(~KCZo(QVGAv=wd;c_qH_9ioxE#^)KaDgi<@$X?$WFcbZ6xSb4o%)oq}MnS ztlc6kLZ|r>0bIFlWZio;%pjF6SGXQ+AbkMMx~Yq+iiW~%7>b0Bkn>xUes%B4IONy_ zj8Qn@FPGkqU&*kD>|taH)n+k#tclD$uf%%GkCM>gA%t-iG^XxDO+Iw`A}wjMesN>^ zA6_lXUUEyL)}Q@W=3^6FJ|81FWr`CVC^NZ-dJ`lv86FjwFTeZar3^(3|ApPf#{S?G zn~u(50>LF%ZX&OjmwD-$ar+}I2JJ6zDyJEx9C&AufJRR|4#ETv;qm%QFP-!S41KXlwIJuQ&;W}Hky!x$Q z*JCyG{GoFlnnZ%(ga(xoKN@%;^e>>=bGkI!^3&JJ*?~C=f>i24^^-=?Dx9 z2pZdO>GS;L`M!ExKHBhCh?oJz5=Yt*vO06h7W%6X@-FcHo2k@Na7}Av)GC6tUPgp5o1)%7byv6bDm_V{sHgF{`8>!knT=l3OxqZr-|0xSJ%$b=v zM1JC_rMh82*wW_(l*-hNWcf~|4 zbSn(JzoHl1OzHQ$!W{t%u&TBT1Qm=6G%@I@DXg&E7~!z~Ue_Xi(wGqkIyNlhJC+`Q{a`PzeUDT`i+f{i#h zYW2Jv`xfp5?j`@^r=l#dHmE_Ya>7yVpnKCfhV97n5JPLF$bX@nXkgwKTd@DnTgo*~Y!+2g5s9vR9vd zC(PAdwRa28slJC10!>wGUrcypVEjQ9=`Jkzc4O)OnwSxTrT+eL&RHIS3-szo4UdorfDIK+|u-M(#lFyid8n+)8xs0NRQs zcD0(3U#u_OEkBxpocuQ4i@lHY-U`o0EyB@@WvV*NxUeN9%n_92sr|e2H%rBVy^LtHSYVEr6zV;vTps zeo}j}`A_r&MXM87rP$09;{qB2s_D*P_<8>f`YrI&9 zf-S+M-6>rUQUNP~3_x2}%X?}OfpFk=hI2ScoBa4YTk6qZF!~rAh<{Mgy-vI6{QQLS zAVHxLn7B6=TQhnF3H;Eg_AW5crD3-=gz5%5anmEWXk%r1bmaV9ioiL7`u9DWgr@Y*45H^lAaZGR!2v&46U<_Yol|4Co^O%C=3E; z_1ywJgV-dr)xM{1dzJ~sP}h~-FWx}A{l+O14yeuG>zz3*PthETJO@82ofWT^V9K4n z1{EE-!5n|CUjBJ4O*2-iC=_PN_2b;q-rjXe{?Pz9N7k$+^=|q0NV^;b2 zdWj2RxIcI^(x=uvTnFh+_F?x>Fuzl#i_xApsU3D2uCD?-$Vd})YoDb@YUC%7L1DQZOa>a7jHpg zPOY0|rWPY_IRW@?<}#S4G;3|2S`PO62nW4r_!K$XqX*Lk&?V|OqIpZH)0)06hP)(ZPSJ&V%8k*B%w%PrYcBfLhj?Y~+M8Gzp zNp}f6D22o^9XIA7`D`tRe}a`V7TZv!9{>9RP*)NL0 zZE+h&{qANaska0}@=cTDM-;2iy9{^%TZ`aDP0A)W79f$U$m`S0Tv0$cOhuAI+`$vl zA6LFRX7t>h=}p(gGnmv!T;}}<$h+7UP5ftp^4aTJn}rAL2v5h$Z_`zDq}K!92k{t{g?XF3Pa_E${S@+$ zk@c##bX=$qWgv|snj#`?(B}_>(qS*Ko@&POfe+^05*Y|pd)i7Ya%p(eS}C7ie!*I} zjJZCCn_<>7v+Dls+|qAFtRwPlKoO4~@*a1G*JS*jULA3gqx;cFog;;qT}yF4NQBDe z&%^$s+OIlpUz9d(VYxBnXM1>v*Te58zeTZk{v->PKOtYjvk0X?$4d>>9Dwis6MU7| zwEBL@(?;)$r7l0RP4X~MV`daB$A^$0e5XBByLvl1NAs0zf>wHoH{nnz;K~7W*r)E5LJieY<#$26z9bNSi?M(}YG+Mb+}C)t zsv1GLj+PyzuR7z-GDu3d+3!;HdDR4bQqltGt4n<841ad!9A^r&mu95|xm>*ZZ7d7S zI6uo=MENxs?Glxd;8J&LDVE8w>bUcM)WnK|q#4()Ti9krAk#mCPBV~laAy8f7WBwq4vMbG2hX;ofB z0x)SvT>>7*pu}%M$U+#eFzP;YDdHM8>kwoB$f3@8{HM0|oK4gd^(vVR^DZD@Yi|-Syp{5;fohPA-XofC@ zv{|{UH(GmWtml{kOe`7u`RI7r4c>lKS;E`=L9Q^79Ll$G6Wi|{Yh@N+o1BW#$I@VO2CPYXaE!phB}!=I*zOFeKz zsfR?6#*?9o>_sdWd8QKQp}s{NL-Yih7f(B2j-0}_-+|ZWoTG>c;Ce+P?aDYq&SQxp z42Yo%q71FOj#7Zc(DiR~wgr94W?g*#tG0d}o(y?OG2hhGEGR;A4brZF2rcHG) z%r52bqe&sF_Dk|a`}Q-wOD^e)wRl{AuYiU2DGd_(W(c|+wO(=tKMMa!jP9}whN0Sw4nRYE$E8{&E@7c8QRu;2Kv!;ef#GNedK*~)W1Tz%>#AU=!;^z<%>Ta z)O(D`y9?eS^Htpj;naJd62UU4bVj|$U>USJ8q#*BhhaIQhS&AWq8|C7 z_%o5XP<3$4EvHqNVOZe5zZM;=s9Oyrr_I^k71Hs89-di6Kv)eu3Qu6Y6A)G5AEPy> zMTu>5D^x#}WBL-m@jWV+$UBVDWHZg=IBe~FC@gs68zFHfB6Zf zDs(-k3M$eF`p}eeEd3oX?hJM9EP^!z3+VGOz2NXr6~QNYHnb{rwB_QyiFy3aiUm4{ zgT!Ptau^&$3H*fnMA!3~O4DOucgW9A$QjbL*46hE)bNzsP)Wd`Kia&BKsfzecu(nG zK|fJ+NI8R&z$Yw7zbsX;?kolleMD^_U#G{OLZ@kTHvC;arj)v7SszMN7E$WZF4{1( zE{1OUf3*)xJZ-1y>IjW_ymRr;E|H134DO~72s!G;zaK}`ynwk`nUDnj`RDg_Lt*FW z>n<+NM&jva0K zE+qsIVduZOI1nz{p}Xq;n#R1BRl-ss%53~h+nR)sIyS0BH}Q8}Ii@x;6q(Il+79kd z!nOs(05H36v@`@|FC_nQHTLnI|IO%H_U!Hu5;5>w!UpLw0pbHqAq+S|xkIPnk$?Ir zawq_6hB?2iG_aw)h6or*JpJ%n`n^i9N9OpTlRqeZ(wah}(0)=|eOZtgQrZ*HF9#Pt z+&CfL8vf0IF(VF7J3>vr&nZF(c&ZTfIUc1Z%il7t$=aN*D~Nd0rvD|yy-9gF{lko&OW z&AcL1J^@N>s$4oT-9qqcj#t3r zASey^-dtEHx6DiAce_ZX7)Gqv6p2uUbFcRynh6OxfVuZdJ9)Q%k8tq58p2Y#m+gFN zQH-NTufwOhCY>W>ZM>JpPWjQP!Pf~{7V`mwqWLKG_hUwp3i3p!Ins4(zMCzs9T>@t zfk@L%lQQMih&`c?fC|VtjRmqrDWvn;{Dz)IbBmQDfi1;qOuolh;|@>gih8BO`6);8 zv_<&N$JTuvz1!I~QP$s!(&DGC25W#HGa;YTB#G;D&RBT5(7G1iXoa1lWtLauj+0iI z8eTc}C7jcCw&z!`1V1l(mfqh&7bXt_z4u#^+q7TTgj91s8Bx6T?!OmOX5H68GfpYj_ui# zo{kl;43a#|PIfhbK=+kB=GR@<<8S_{C4WD*(wde1oWnX5)d6{+9Bl6o?uisF_jc5; zT_@WL$<_-N=&88a#5b=n^<7WVOH6$Bg0RtgpYqM2ur2gThP>1{P`t00 zAC){m%%V%;oy{h28I+1&-`(A2&9R%77;zpU3tx}|X2DeR8^}$qhR>s*EA|l-E^>1L zKi>>xP1#K*yUfSXE!ZmJGs};kW8ZTyWTE6y)}v@b71*R6FbCzHEzlE&Xo+8%vL%kY0%=W%%nK{m*st(f}=srPgd4Gk#XAZQn7lF;U7^5v$b<)7vvm|9vQbA~T@ z>|?EJJ*5^v^^~tm0mxoVln$ufN*bBNIOw>c&qVH(u~K1q=$4;=XgANvcn?PPpXUv$ zeC6_K1VVnp-oo0t*=EQ?LU}S?q*X{Imd_a(H@!b)iO`&|Tt9Gj^OY&p{Q?#Gm3H;J zGuR8-nQ0bgrPA)q6Sl%TRk+sLpfi%oFQ^qP{ecP8*XGN`vPbh2$o?xEX=f=}uYa zIT{9+r|&@lAYpm(XjEfuM*JJ1-JusxqBsLR(pdh%{P<}M0Tzf@kRli6R6TOdtPIh? z3}qAk4~aw?R993PE9231e{5!u;*m@1Pk!J{AXlP2wZ8SaC-V9Dmfe2$H908tHQMR~ z|E;(-mK`p_C)#oAMRYNF1UcW5ljfXv&qW6%#z&IwJUV%ssO|$zgUHi2EEt8ZJr^%A zh{1L#Vb1=n*&C^k40`>if~>TffehW3JD&;0_iM#5UmLJib*JcaR*^xFCU#8?g4t~a z$^siF8o|0QR;waSL3^Pfh5-wHwetH@fk2`}m(Bm9>aD|?{KNNex;r;OQc`MkgGi`= zfS`1a?sjySj8M7;h)9=o_ds9_q`QQnND0d5-#*{p^L>uz`FlHd?B4G8eO%{xy{_}> zSh!^q;n~YkrHd2*{csb7)n0PI>2YAC1oM#Y*Ww!8ypnwO0}hP1r_0^~pP?qP<1Zud zOd_nsO5$TeUimqW_9uF<1P-D*MpT{plBN?%7NM#N*{-;F_-ZIwJR%+<>nQ5MrC_?8 zW~y#JYMh3V+=fb!fPUf)cfk<0r9}W-6!sn|zF(f}L_3S}DO&N@i>>o_D`jG@gR}-M zy~g$HsoM90VFd~0@E#_AtOV}0Go-~v z3*m^r#p||G6MIh2&h%!m2|PX&6Zk%gLp+XHB`$#F#AoM)?0xC?rO%v7%6Zt|GF>lG zE%U?V39b>Y#8?AHG*bgKr;l(HPQ9VL8K-DPPt;E>o5JI|p=;1Uc|gfJYQ=IFq>!(m zfh}@5knI5J$mDbWY5Y?4B_4^B5l&$vftcbQc~32B0i*+(yqp4~+$?!tQm4I!BET<6 zkQb*b;=hYCRQW+K-;`#&%UHlEZng}ja4j65#8SrVesd}}*z^0v@DPB~Y>?~5bH{37 zFz|l+nF~`u64s1rxF5FOy)XQiGQYu)aM&b! zPmSJ>e6-e?HTAP6Rp5lM!(d05dSOz@Qs8VA;WaQ~geMrHb9x*cuwsRAeg)g>a^`yLgearKcm3d1) zx*$jQ&_h|-S2n&s=N+3UL}Mh=Xac8?LO8gkFWH`>9@8g&0>&LMDx7RJy=-5sV%c1P zSGK&KHF5pVzjn6oxpYfgvbOD!UeL6HYv70mDNe@REQ*Jddjn*+0L@gt+0tZohgI_Q zz6JXDG;^%jUwk4ep=3LB4V&V_-U*%Lk2p|d8S++;Ml_Zk12I;;)G!-I?*~BF+a{Cm zs-`3=f};-6($Bkb4h(aiJ=>M6n~cv?3`YevBIjLOt4=o)`@ePtRoIGjqOpYHinK=3bQuFb&>>Rs3_npGw-K*r# zCe)AW>e_Y7Dbdz9@qUZgCzeDPezpJo6-Js%y->+V5uUaorM;D_nUub6E&q@OzGdSY z*$pNsh<>?f)}rq(RO@5CpJvB)>hgZFnD!u@qaf=h?9lU7!`A5hzE(iwU-W`BS@3fFfGLiVi%T2OzojISp_0zJe)HQ@asP5#`G!#&ZqkXePGz>NGCj3F<-xb8}%SEKm zr9-=rJvzp2MNL#K`mRG?4}-~<5J>DO+B0?&fgLh>0N;LPV$PN!AEO#SDyQ9?$*|7w zNo{!3_qhFSv zdQ9u^teK>xfG%$XLJ$i^oD8|v_QSTADK!dL)}b~4(5ul8jW7jat4F|Q-f!#pHTbj# z#CjcFA1Ja%u`8B%SWfj%0gcyLIIo}DlJg@JxT2gDXbCE%Ut$T*g*FP5I+Ma1FI-F2J0^w zIk{kvGFITrm@n%FH0gD4+>E1#Uyo-W!H4Y#uP;{Jez3IlRLa@wltrw^T-|5mQOY2V ze(h4z#=ua{~QgPUAY`4IC zJDWy?zWRw+3g;&$(fw!X2_SKePvL=vFc3?rl8v#whJ49|?IT|a$!ZJ2Oh5lK2k|gG z^oy-vV!e(bK#{BNRmizQZawA?gawN)YOUFMrEk^7Tn!sV#^X^YXQ4NtCmCrI4G8C__Zyfkda~!~DOHW%~4c=A7kL0Z;h^2^eCWA4s3;FJa z#$_i+d}>@g3Z#}pS~Rs_oq&jST(JC8&@t_Li79z%-5(vv9(dEsg+{!1H_W5^h~Vfo z1de@#2}k6XqKV4A33fz`sxon{p++mdRa!&y00v|B^i9zBzR*C>r<}fV6j196P?53z z&wrI+U!oD_A)p!!&)*Fw8ip)walDcB*?KE)+2!eCv$w1;#aR%-Pw8tB{eGpx?1>Fo zCzW#X+jEqA3j!fl5g1M2m^8J_3Er}G2>Z|D>_!ENd$3CY?m1MG%WyE;c)9iiWlqqm zT4g^y3|yaeQ3(7zDcKzAoI5aLx-FTq#WmIqcl+KfeEkf!JNQ1YgI6m04c0qKdxSLt z@X=Al3(gX)WY5koYRqD5Ey;{8^b)+i8HJoXO!}{^{7kmLY|9@?Eiy* zIA7Y_r3_rMEjia)9l4v-{SW@(@=Mj}vgemiV9?lXSw`I?QOw}s(wnv?IQ-%{R%j~4 zM&p%{L5(IcQKm>0b@7*$Q23>Wke@K?2q9G&W$dgiC&t|_6cEqjfeO=2P2l`<_^p16 zH$Zfj`*{1^Nm#t1@BO8*L3Y(~kV^gEQx5SBQaYVm7<3Z@N5s7iUKP&Z94od;vE;q} z@e`pc{Th;dz#ZcrL`=H7+?R}HM~ep@5*_Fkb;JIn%n8oH%6cR*AcUQM#9A? zW^G33^U%4~R_C_egz!3uov(`)@ca99qpSq|TPPsyEt&=VsD!GJ{&Umf-+e0TsQ7de zo7`Vy3&MbH-?Lyb-xpl=aXZuwHjUy`9K%E$+UDa}&y>VVc*syZ{N%c?JL$-*vy%eC zEj>k%yb;Wx`vQSJL)X_qjfW|vzjSyGK$@xL1XQfhWktN{uv7=~&|F{#Lw`#eD3A#- z0e29U7d8-ePt9#-9ZgP{1@w8IzWY2->_%LQaxr#wIXVa}TJ+yIM@0!c-cH^>`WH+3 zx9eD@YGFZaogSf>?Wmpe-iE7mQK9fFaMoT5Ii_@C`D0O=dg}1|WZG=t8q5{O)s2r*FfS_9l z4@4Ll1LOx)X z!XRqvp&x?+Y=;isuT8GqTuW@5172g{=&DbL2xtxrh6zzko&N?jQ)3MYc`FxXU$^61 zhmAn_PbxL0LuXiqlh}zq9Ib;L-}ib?%XlKHS)h_Mp2J(U+{mWrQi3H z_1`ObvI`TV$mFo6%G7jIznRQ>zU*`w$y#y*sy*3;Wv+KUi3xUogWc~b)rUP(Q1pVp ziljgJEA(th!geKwqq`W2%Ui%0=-WIoyG@4TXk3;=#bTKzhbWgFTNxcTZ-cpPSy}wM*>^^Jo+}>`Hx?gS6Jsvh&daDzd3lzz0AK$u*Ip^SBt8a2# zlJO#w;gNBGgA_(Z=mC4NbFgQfte9=l%D7}X=)1jzoPSCcu;#(}tkbV#3-&wqG!FtP ziA^ZenXMOW))u-8I9&@qv-OIa&CF-tUMKojQ&eZUA*t_aAkSWJUrXZFX1XD5!bo<( z{h2gHS?EiVeODKu1B_x4A85fC=B^@T-fRE){F0*!5>b7OfOwH5yJ^k{I!=~u0tLD4 zz<@Hzb&QkTm*YJVSs1W>g}%w_6vZgP7rJaBM&o}S%;VcFy%cTC`EiCX4`Ui{7R?72 z+xE~?c@=G10Vv$=aaoTcG=KEsb8&K~SGYyl-owGHR~JG7zs=fJ|h%(#|oq`hYN=rk~szIXvj?(45 zaSwkO^OCaCpB#V}ioQ;{SeE83p6BCy!7Co5(+I}PCfVi3u{#18UtoQJEUCGu?YZ+2-A$KrhHF{( z!vlArSu?~;e7W?XOAxVS{0g{jDvFI?ej#~5@=K25tD*k19TYW#EFRevdL?lH(>9$b ztLwZ}YDq6I&yy^8hpDstH9Yr$(E8v~E79oZe@!8M`aN*ktu8KV5*bw|LFt{5ghXoD z_YA#Cwzi-1#B60X+}?j^xi;@MuJSxE!Tr;l)sRwjCE>~(jfm(b_jr1Xjx_sikFqgS zt;M?@JEOr7Y$RNId66kMW48OqGr72S%9z%f1C6H1THR{ZXmnOppOnZi92OTUb+WOj zs=?xR_fIpb81SQ-T2FRpLOGg~DuTUU?_d@bFDxi%#LI*!;oNm8*XJXAmxgtZ`bO^m z#NKz0G}oBgM%b8hAH0K+zwfn*<*6-2_L$zoQv6WPHwg<5Edtj7IHr`)lp)%n5%QMnE8JW|^)Z6I6O=MUbkb?Bbos@^ycc7XDgIPq7? zYIIk81WTN2ea;7(J#o$Zn+&Bg%3l&34M@}>$OlP@wsrh#j=i>~2Keh`fSh48#P)$- zCNXCiiYd;pj-N&U@^X_CJlBtrHDuIFC_aeIs}`=&8?863Kxo^3=7INs+-=va4PpEr zm&`35lN@3h(JtKgsW{!o79Wrm%^xE8ZoEWZSrDwe0#-8UE&LAVX3e2weNztqrYr07 zHUZo!U@VoN?udgvF+oc9DVHOLL^ZQq7*}%dmkAa}* zZ1z@~DO%)U@?leOzz0D#n~YO&VB)qQBQ>)hlqq8p#Hl~YTvmxwMrzU3jbV~PUuseW zRea9`Jc^=FA9KgseMhzL{YZsZL$l!0{}V9PYd;FJta05jS_B+QL z=k1%|X*|&s0Jk01D2PW?!*=!~aT2hC6no#}^M4plHCH)HkKvfSrXzx-hgR28qn=dh zXY~}zTIK(;095s2yTSAeyJp1T-`Ih0;`1tj?OT2-G24m1I*z`rFI1bdIQ0@c#`wi~ zgrK+rB;dGdJuT>XMGoK_{CY}ULv@6g%+c~-WFM9N9#dbM>8wRSNOv@#(lr0hUkrc= zD76&6bKI9K`<3t$X(yY@ht6jxG5!h&eLK5ElkXn%0zJlb`cDe&y{l#|z1*`hs3<2j zOM2;ww3Zw#en(cAx?ldE{f;s0{{xy6`4@QM8o)cA1#pe#g_fIF3VGv)f$R3E8RTu= zFu;Z-I1Umn0T>2gO$8xMe97{5-Iir$F`d8`w-*76Hur46hk@bnmGGn^vm+gsUw`KQ zm!Hw=JjA|hg|7CTtzZamM+{y0|4|!1Ln)o&r76mH%0wP-d4uLzB>wwGt|k~_t6Jx~ zJ$|QH^v8G)7K=u`)n{)flefG`dCHV3u;WEG)McaFQf#p`5 z$n=FN5Imtfr#pAkgq(yq(4b=WSn%`(``7G#_gGmaB zRke3NXkhRwLtE;g8(23ooEhd`)2h})Hj_!?G(%HF8(4<=3*-L=Io^`&SoF^(Y(6); z8fqbU6WHil={qs{3G#@lhMI*XDpC$q`X1HH!W&7aOV2g({4q(wTgT>LOz;)WFZ=EO zm%HbF9&K04zAY5LGtEYqTWGY6&p*0dQU?HU$%X~0im&+t-6M)D8{d~6M`j52;OoN=uwAz^~!_)6D_Z!v! z%QJh+ar!FSYPm03x5oe3*#_afxTLzHYh;~^sOCQhY$9};D#fW1MV4iAjC|lDM`gGt3Vd);G+wjY#?>zZ_D{+)qQNKo-9ta7>DT=m2CPhTq>jmoa}9%g#7{>9H;w zcF1?qi}vYh&oCACoa=IK0kJ9uSW?^v2P~mz2I$(Pi$IfDS%>(Ie0BJQ7w#ToC0i~bg{JARsFsU<;he@#8-PW>=$APE+eYRiElYrR#` z4}r8p=TlwRl5s2NM>MWq|GN?Q$Gaz!T*>RG&0Tkxpw+wK{5YH3cr0wA5LM#T&GP`5 zB|`SwhGwQNA({^Z2BoHxoLE&yUSaH{lyJ5?hZ-%GJJ##HpYIxpi&Ayaf|Dn>d(8r=<2D9Kf` zWesG6$!^SgXb@^-<2zYk@)nw=3q0;uETjG3$1eQK>S8F2oV4p!-_gKvJ9;^Ie&i~~ z3PKKH&~)RZ{c{Ws!<$ft+qRT?9BO#=i;B5miKZmW2#JM_>-X!W!%60B0?Luyz@MD! z?TuV7U?tettQ&0tRHpo4w+4Qr|CNxsYIRBG-c5!-OIwucT0qmNryKHTBp#3S%kN(A)>}LRD<`BvKVG6mZItx!@H3 z&CMblN&QIev8#V*Rpp33irW31*CQBadkYg~y(F4-uqk|H%X^DitXFu~RTjA@LSPN% zU%x62XwRU`N8141`6dGqm`Nk$x%j`X+vurwCgfW-D`~(<|7)xt@4S3!lLNDePd4Cd zaaH!JIe*j^s3sAXH?uK3Y9i_F9t11QSb3>AXI>VKi5 z`YoL#hc1c~1ZJmhe|^uvxRTE`mK2Rk|~ zu!rwyNPW|u{(w@&sCFMpv2~XGGW4|^f~Jc$H;iRCBgOA!rMCAfJw!0kCVW`wm-@Lv71cufX7M# z;Pk*SMS2U_Q3u%|!NGQV1=^m3e?*XDsAK^S!(xB3f+^Fn;4>b(lBW*KgV)yhqpW8K6f33t`jlbjSOy3+@P)e4@p)`qeP-o1-s;9=ALOANY zaSCLnkSuLM!rq=0z5Vt0zjD!B{RYmYCkjR6047O1%NqW3)s}AjR8)r~;gnz9UqtNT z1i4Fr5^}l&U3tl}aEV=nEtP-v;ZFYdappZ#`|l|BzI2IIBAW_-;S1Fw#vZBF;$mxT zsU?@`PhO!y1a#(g`$0G?vk4?6xr)P$l}|ZKBgRJZ-sMNV>$oqdpi+q)BEf3-L|fkD zJq~?3>?^ztjTf&iRcIZU#=#4he*MegT$zb#!c zlQ!{^p7}?j_^-c<$189zU3u827)~S#4 z=GB`5Csi$@v3BW(K$lWqygXN&;PhBgo-ac5PjhHTWRyg>H7Z>)OwThgl*&c4=Df+P zpQqE?udmf2eDcf1rKo;-X~f%7h(`M{`vvd#(yR}~niIJ#jfg;~#HM*&?& zm{)jqIisdLjKX(&nc)O=L=#GZapguYyArLq6n3-nN*$i2fuLW3 zTpRHkS{NpkPaX`=9YF!lXSJIXf5s|Qi8vg|SFQQlTQc^TN@FQwnX3cBL(O(yVV`FIu^#ErxkL%6HS3HvWHPB7H@NjjvQLE+EU=VX#KCj7d7=>GIizTd0;9e zmZ;%hvQC9)ROi%pjQcO?--v;>S5{VxjmGdjWrz2dr#+=^HYOLNkljUB;F9TXH8Lt@ zq&1lxxg*g@Q6@;QR&+}a=(fR@-$`|S%FzOqSF%49-kQRdKWeJ((b2K!{eKZ2)&Gza zEd{5Y&EFVv0P=q+o@$;ST^O|eBL@C2>B?^+=<5tG5A|tjbCh+V$jfu7s$@*cB6&ik z6Vt*0V;Zt98kS?kvQ5G^-Dk3;e?}sj3H;5Z8pfo;hM{y}A`w;wjJjPXZ?an&n9=Ii z`CDn{w|zI8&Q>Nz?p<>&m->6_?4iz?8!jom1?7v+il7@#X~a)!(H%sw-*YdShq5(^ zw`;d^!=Fi?*?2-_*zQ}V8+%C6-ovR_+yf^$XPXqin@f^fDD&hVf{+~ksAPXx%|7XC zq2vh8_7&^+cvnF@LS1%+NxIx$I`j0g!C?*sh3t6dU$_PKE5^APwWR_n@fpdK+$RTZ zf=yVc%pL=Dv|@Z4>@;2|0lW}{!LLO>3zXy}fCAwmFi^GFYXMLzjnhim{{Xo$yQoMj ze4fdrw%UG0#1|IVXThw~!qA78qBVCZKDXp=3GaXbS07i9K`Hi}E-l6sE0A!4@ImVPTACetS>!PvaT4|zxLD=}7KC->5+6%r_n5s%Y%lCG|76=`DlBGb~OC&{zy2RIu1Y zXh9+lBd=c{X9fC;CjarOsAjAmwc(yFDt!TiT+<<{fKUaTgihj<%dr_}m}RlfwC$&PRbyp+V_jn7CLnJRoNdbAI2PM8iS6eQ0;ocDJ=g(x7;`SrXxi zCW7yUjXTo1x%G?|e(>MaeEc{6LR4Yj$y(K~&>__*_NT9#AG>A?eOrLbfb%(3^xy9; zr3pRxgNse4@W=QJy4#r1_=qd9l=r&~Q2v!ICI0k#?o`{CmMVN|! zAALp=$hAxw=>+GZp~Njh;1=DC9sR47WNA(M6sq|bd$=$@VEKvB_4=KaVTaOSN}6xe zmcy`4|M@9TNB-GWp!Z1*9xEX$qk;!~R}DsV3Sofkw7pwtV%)=ZkI380p<-)CQQZ8l zvf9PIGbg%T8z>AIdfnIbpydATQG|aJ;^aI(G9S_2G0+~qdvT@h9`?kYHt>eb>P0;o7SE8z*LJ}%;h~Sw9Lmh%d<`nCc z>@+)VYbzNvYy#`1JMGC5F8CL&Z%_Vbkk8Wg^t)4c&HzrTuy8?AIu%oyHU%(+iW0vsk=TcHyMhYDAM}NUuGOm+#V>qJYJkzj$s$>jp0{q2$9~lL71J zXN`2c!94q9Z^a1WM*%KbHzM#Yf}uhjpA{m7p2XP3JZ_GQJ*HH5HJImveouw)Js&_( z5}hcx`&hD71fRzP=g^WOtL-rq0=jSz0zKSOR@KAKpJ8wC6Ot9;g^47EppT_jH?0mr zn=``xaJUOEqOk|u9oABie|gE34?FkjDQyDc8Vn9w^vSq$>`LR1h z!r&1=%io7f;MWI*08pOGo`!*&7a1T~l)+m2!%WTK*t+M}8LdXPI)}SkeSdOPcN+BM z@t5cWW}2poIQLaLPR`{>B>P}eY^$gL znbt|VR5R>eP=@e__cuo&;BR6W)+@$Cq45G%oLsSYbnh$M2haQY@Za4;y1q9SkgcLWUcPM<*#b5ZIow+m1}-WXJjCklluk1!A0h#|$AQ(|kn{>wZs0(PQk z5HRp<7nS7vc+^*f`1`T`%!_?y!Ms}vpqu~+yEb>EG63{QNIT@=#Ze(`3kCpUpoG9F zS&b%R%$*^^w`T$>?3rTc6V7RUVj>$u->oy zYW2pR_EHm#R>TakzP&LOYVqUvd(0J7IqU)S9B{?r!5@v#9hSPkP|f>pF0^u!=0WU# zoX|kJd!ysG?V8soc~*gA)yBQxq@~hfRK*dg-Z%`ux5g>uDbh6k%&PU{hoPWe zZ@-II)yna&%R1WajnXgkgf_H14rHJpH*#;`5LOw+Lope71vpijP=&7R*EsjzR!*(| zOl%)&>QZeo73W+e65f+Z=RFg`Z|-^SdT|aK%d=XP9OlV3U6lOiUC{L9Jan3xON6kO z7f?^rJq>kM?~Rdd?ro0kTRP}ORqF>UmARWFo-~eCgEsiu>6O_u$nOcxa-9^+tIigU zzFzJ6zCm52)F{9U{cp7LK zwbk*kx+EDbe~jFgP;+9+dd%Q8aN+A>Yd zTI0cI(K)I|0hcV7aZV;eR#Ki`)I>cF7rIAb!-}wWV}ggBAfy7m1*mGdF2D%=d?Uhb z;FiPb4Ct)`zW9i78scz5Itkr>o@KH>9G`w=D;4l$%^6HOt5!*&#-?ke8jBFq00z<) z<+v^!I{f5OJSF%|Jp3Hzqb^pu`ar|&gF44q!hjt%Jqg?ksy%n8-P|Vb%`Nf!NdA*f zzX;Yt*VZb}{a%UuZ(8Oa3!%U>KfyCnu?@-)iyg<~jv-dd^TQDRy^u84%mXB6&wC0S z-f7&6k>{H%GHV9|2U>_)OE=+bJ3nc!oII$u5+nSfE9HRAI>ekp_2#SvtJ2hmeONsGVs88*{{U+FdzD#DWST!j z=Y#bZ3!3$TgVgEVDU@Z%-3&KE@~vPwCT+Z++h^#-uA^;0-`zEUBG$)hcEs#az|hK{9TRHm z8{JFzco|r9St_d(v`%mFdOo_~X!EUua1h8y^G{4r;MJLsty8qv7w))c*5)6mzYWZ^ z6qHYJza%EJAfZmeeqo3+CnRU5p;q6oTH@Ai=q(uA1owcBdG!Vlv)(l`5ikhSIjVjHpumnER{zB`35LBkxh6s>E6i$Zv$wALMfvrm`xe9#%_9Snh)M+sJ>QjiSCV?`$UQJiKJi2Y z;E^%B*<$fI?+c6%SFBHpDtP^Tp256zq$V5&q)5$6pVy0Be_Mvm0E@-P!P98;a*ERs zA9gPL(k~Uxk$c`ktC~M2E&zic+UcNJfK<*$!01UjN44+=$dR2zkep zgMc^_bw3`|iiRYz-1i9GjSHS$0#YAOPm~ToKEK{(W~}ytJVbYbQg4-Z?E7^et=Kf!a_-{p3Rp|gN!wYb;XRj!FLX5xA{63(1%ZZ#lj ztS4KK#MK;xhI~3?V}W~ba>VG9!?c`vo@T?nMPFd%`y}uBL?hEWsMQ!A9c+4hDiy6V z{-=0*&%iAP4Zx)}q;{N?i9O3v@1@3l_LOx|Yj-+EjHg1}k{TSlJhYPP}Kcp9Z`&T zv9O9sc<&>^%o78*q~Y+Zq0IecOud~74)Jq?{`)%xGT6QrLaA_!2=%`cqnxhVCIFPb z*b)?HP1*syR0!zRtH2!YHoSVd<_XKLjYS!@BiS$aZdoEPLT=#5^DoJhCq0K10meVF zCzp89G^f460n3faE3mAr#V+MCMmSUx0U5;zfE(r>#q6%U!MG7Z`w)CWUaNTATZSQ1 zM?IVf>0!!j91722M^|V2|2|xFXyScfu*;Wl?(@sMa=cLlc`z$t3q1y~QZBlgC@8V# znp;6Jt};)x9Wvd2PO0Fbii;UVi>^>f@1CWOiYkHOLp)07+l309)M-C?UCm3!TGJ-W zL|Zkbb2}*-$@^039Jg0G2o$2dY0k*JaL%Axk0Tvz3)7FdVJ6>#{{2JHYv zBp@JU;3uS!2eEK!N71Q%me0YWk&?(U0GX&-;eaVGvW{Tmd}GKZKbH9q^iasB6ndy* zE)pMLRm8gb-}OYlD$*WBH$!=&7uyP}76bphetK}pVh~>WE3h=pMetMi+xQX0z`5`J zbKl+e7fg9kN%74MCdPj>p#_DoeK(uQ01p4Hh{5#wJ@S6cMnpmn2!!o)rcs~5>V0VN zR?bV_>h9M&Qqik;52UPJS0pp-e_Q{T1vpLHDmeq)`}Bw=`s0E~D%@#_?O5}HAFOzJ z4anY^@M#zomOL3L=vwl`kEmGgb&U~_Obiud3^yjClas!0q$-|kXEO-f2@p)@5)d zBy{#q?%OuSp}<-1=NC?|>xn_xT}&y8^XIz5nSIe{b)HL8V6ND+GX;H+w!i!_qwcOfx~5po%IRj_5}HT&5%?A=E(Buh5}W^!_7n*KN# zS>CNwHl|+nD%>H5^X`vtJ5r76B2Fdl;DZ&dqKfnJ(o>O0viducKLwg;2f7`(O8col ztL$JR1p_6Y-jEoW5Y{a0on9vZKBNJMem;1}9d?w-eK;HRlbS@$I{cxT_0FoK0LjaY z{D_T_rB_*SAvXAS>0L3SQ*54d`Nir;s~DAH-KRv+gk`i*CMuH$iw;P@ryY*}=GI>%+LHsH(4PcVcSMMKu@x(0^$t|GhmDl08DT7bw! z)c^gi7$ok~!~^yyY|B-@T#|^F9B#*F)eO<`_%2}w(a~c7LU)#PKub;(>))>qd*bJ% z=nq~e-s_bz&j6oQWz!W7xIPY^m065Mc3o4iJNUiyWp{a49=}Yn>CUpn>C=RcemdR& zP+IDO;sE;AQ8_RXZQqyBcxSi>9-R*cKX*FZhQEZHss7N!s~2ahzgOKkcTSnnuR$`E zv})y~2;z&l8J-uoVv7`7bsuV4ukijJXYL&LtcpjhEZuRRz`N(ww&%qPNq9L?e zEu2@R1qjg+ibU=X3bxsHOZKNeH>Xq(K655rQ~0 z_N^2~EJ|GE9Q7>@bVr&f_i7kBPYUd-aP?-l`%6`cdqo8iY&j3VcM3pewB zRh|qWGH$yozO3}hZCsipi{_U3V+O{Ms}*esQH6YiK0Wx5a;WyYcvJV(8v7rqtv5f# zCr7-&%#_l&u(swf%mk82xQNI{RISIz;k;$kVrm$!wDxktt)&*izayfv{&RtvmQc&Z z+8hk*Qa>rCmqeB!c3sMll8$Ea5x#WFg3s=UdTn*2G_^YyqBe#G%|je~w~m{zrzn!e z{K}Z(TQAlYbT`TmC+wB*-N+;5l|#Bh?MvG#%c`x6Fj1Bx)owpkT{m&BW#E_dFS~c% zc{Y{&|J6_DVMUns4*2a(oYq^icdRZtd8QZ@mbFl?I64PIoW2$RH<4bwiFf?Xg{AYR zR;s;<@dZ9YGX9NUm6|SH&r`p#^z}Q9C^cD51(Uot`SQbS(+qVq4`3f1;#`sD*32zMy9 z!a2iwn9%jv^24=dv2wh!1>TQjJ+sciLH^PiGQ@Vw6z2{SJcg!y`S zazjNrj^(OQBV#v+B~r}7#uNA`x~GMw=&hNZUc~lPIh8gXg2Sj|GxzxAzFr-ZhDye> z$4QZ`@Gk>AC=Yo{_BO+Ut%Cih;$OHX1?A$61b^Js$^$!$@j*9AW%*-h>3(H=B}Qn` z!|AJ=!=y7yp<10_rCLV251Uv4HX+}A!jAv*Z>6q_Ks=?*wBu3Vqp}@HR%o97RT>dhafswJi5b(dJj#6h}Xv)eg2L|Bvt_?W_W> zzb(_%U<4Ls&1x2FQaBzBBhNoAmz6syy&@kC1t_9B!LkVsDU9!+n2E2zrb9mgBGwm( zJp*C}ST3$Z6Z?wq%m?5j>LBVKh6C=e^zjOQB0=@QEiwv&u<bacjC~PZjc$O42|X zi5#t>kW1H^0FKL}c?_}clnNv~?@vjxv#{c^?55;ona=UJoKaXWW( zPndYC+QER6*1oVs!YkmT0cMRA@)gdE$wfm{K5pR%xn;4;t7=(|q}0@BSw2wn$O0Db zG&yRz{kA3qlmZy}Jn{J#75+&6EW#w_!pf5Fq%trK%E_dm9dYOC1MukQE1564Bxn+I zcQ za~cOM4(0Z``Q-m+t=GN%*l5)d?;LU6da#^;8&5iv`E$-r>f;u5>3itMv(G-S2&H%O z#Hox!j_Ul~dmf(top)R|my((nZ^Z)#vv%+R6!EVAjAcz8yze~;Chz2I=1qWf0qI#9 zU_u1+HSN+YG^rt}PMKS0OqD-{3dIfn{GE%r?KbJoG9{uyIvEw-Q|%Y?$v=h>t|g>y zQbS&!l0!Z5&~m5AE}5R@32~ctHGisQ#`eG_$q#>3CEi(8b{=wAFdufaKynAPB8|3^ z4cE~of7-XGqcuf)88}n3R9Q|3epgaJJS+-z0 z4mJ2WmigZUmF?h1gzr|ON6t?aYg)h2b&U`}l*7>l}t_Cfzmj}%N=VAynjNBcE*xd^1`uR1~ zer&{*u56F&Cs%8ouo+nOX1C=M^{12Jmmw~YlCgpFN6)@j0RAcvb_xIYXohFN%u8ij zSlmVb7XMV5XA-&yqHJXqN8{{>&p;p{P-G3`@0ODUsgbeP$#x!sy0$>4%NFW7a(F#2<0ZjcL!GO`G+Goj0@@MJeb9k#DvoqEG&Xr+jHniH+uJIzM4CX7|kJm|7z!02qpma3>D$te1M1V0*N0Th|2*2~br+{qZ#}7{e`}l=0?Brl4TagZzF= zuu^@os73KhI4@>4?8xZ4cd1@*tsWuq{$y6R_){Vy)+Tw#tH@}zsV&6d5P{<=r=v*x zb zAi`Ohlc%PVwxliXb)_bjB{G(R@9(4*AcEM6ZjOIDV5UJoq7?Sn#aPfqFEW^R3w^z& z%j~qrOAKjw;C2O)pg3mV)Lr&(GdPcdIJ7f5GNXdvZn+_2ez8`X|HIQ+hDFs!?Vb*4 z5ExoOI)`phaZu^*9J*5)8IT?XRJuVL3F#hW7`g;Sx*0-Z=;q9G-uIkO^KD;y_O-A7 zUia_5*IFUYkCA&LJ|MNlz++O`&iD!GGW1xaA0=OE*lMX9c6n3Fl_jOdBBneb5J1}$ zeB05r&xH>yXSbLG7hMnOfk{JuHc_zHqXF1n!9rbQ1roid-NB4-F)HN?R8_aj_xIwR z554pzv33KDAjO1VRJ&3%_jjhTP=WUZuqlQbHplL|HsI}$P)xw`U_M z${f4XoSc7LOb^U_e>*H{*Dg?O#>ls5+x;D7LI?^*$)85|PzUC|k=|Mv##7^?TSMJfAv?6_XTcSjolCB9C1n@OcrM zB#9#3f20Gwy8Gnn7Ef@hU4)fMy*-;>FpyrWybJf)5h*Xn%viz@5<2XOUQvAOCrj<> zuGly4t(}+^qr}&ni~WUCpHj>;@0{W7f*hnAcVa_b8#Z=-G$5cQbTalsI)fP`@;H{+ z{6sVgQy2y}u3XA4*HZ-?i$+)yAN!#f+XZ;Hr8DJwOY1*Y$Nuv!QL5*LsofH_OC_ zLp;Exi1=WY$Z~f^(;cmLI^JJh>vKeT@V)WblIsT2CI`E;nL zheW_a@jZ~L458ou<0(2CrXOqgf0@#{aiUpy^BWZ`?@NqaC%4I@ov%9tX{$@m11|UW zhI{vi%gA-@q2F%Gd2kWG9dE$*iFdtB{<8~Qr@kYLGEh)7Yk@iS^ww8cLht*ZI{yU0p@m! zgIEi?B?%U=(c8Y!Sys}C-;;3^r>G#_%!W}6T^c&kzM_mcI_VU-k!PSvO5?O5dg zDolc|*(7ph=p*#PhfaupCm7EL6*fL9`288_WQ{dNdm>jcR}XjX@IE{;I}U|VAXGbl zBxu0;ycxG!GS;*h@(E-_=|f|H3c3}jW6(^Y9IY=Jt%#!2j|La0R*Nzr+q3b+ zA!f}z)#N#a#qzR=ZR7*C7`~sTh+>k^_QUI(P$LrH1wmg4%ySgLEI;B|MOsjT_B(RU z$BXxzN9f8EAl2~jBBU`59sZ@zr@)f-9s7bqV=E(ftp9wXlr_f+p~7A<*?^V#IShvu zeW_q+hU=!8Ur{sN#X)rIm{wx+{&(XVvh`C7GrxRZ{eQLLd_-~otyjf%F>pd7*s8dt z3@s)qX*N4b(gX|t<5m(Q(=eg`aHkU*oOAp?w}lpTBvYOK5vGZCi&~#jOl`f*GryPw zxlZUL5|3qRWQhyssCeZ>@@7-V8^7vZlzVD(ZBwt85hN~F{!g|DITBDC*KuqUnM4rw zo%*Wd$A1(mZq}y^F2oQ*wl0dJ5U}(9(9+DeNe{JMWIM8W{`cEtYpxwkh#xoD0w+#> zz*xrIVS`=Hr!7KFkX9VleTlh39^xrqcXYldmou2o&}Zn&o5qi1b&$3j}R;EI#zb7Gdab$Dt(>gAv=Je8rOP`>V z;g(j2mOLrOQcNBvg*w9&8hP}1JaffyU_Zu$#v~vui(}b7=JO*5}^JgROK3Xbp`9vaIdpUpWOd^ zNB+{qO2@Yuw_UFYU#MqEqqgHF|h)Lxh8XFisAuNIA@k{8dvol%^mSvq&)E&O_rJe&;3YfE% zz=s_4X9v?%ab}Q8RnwObzZmn2G>+tcMQOimlvh%UqDMv)$vRnl?WWIVNHX;`qyH2q znSn3ztYxPF<*0lbL%v0T!?4LvRF?GttaXw9uA$gyeEqDq%>Gn2@C&I5;pjRv%)&kAx=$PVnIm3@|2!e|H?4F zGahQmcCtm;4a5D>Kidjdid`%i#e_##hz8-B(=cfz<&#k}rq$=|zo*IH*W^mR!6FY8 zB?#T1FPuY~d8&^~N@)sOwETBm{t{a{r$pOE3B7*kw!NF;9U_E5oV#*Mr*Sn`qVa(e z1BfBTyWQfCZ^%}72w`J*20K3ll=kQ&**1#(hHbb|?BLzlG+~&c%`p^C7s&<8!|7(l zhpP<%$fWi40Ro6>`?@GJQjfvu!Iq<5bz@n!ORC;#u=xGi^(Y@D=S=#LhMvnsi!EgH zkazKs5%%D}J?4=Ff8X6qQ+M`Sa>Eoc>eVYF=a8l(@UqKBZ~tB550K`YaL;R_DYx#L zy>~wSf(1lVi7O55M!Oa^1eUMVlcAPl+e$LeuzFQ2>Fg(?vq83;yia_y`+lY4KZ$(- zb(omLA6uVEfY{Lr8+6@T_?@|~%j_*uLQP{`lRV9Z-BVhld|2!HU|>KJVV;N=Jt_m2 zIRT-2*%?<3o=y%PRFKR~MW7;Gb z$AK8P>SAL4M0x5;`Y|6EGyyq-YsxeL-SHLcyTQWTi-GhL@IU#=%d9Iu_(9BJonpt= zBa-Fg?DRmPfH-WVfD?Of7la)3B*7`yLs(Y=dX{!va+e7R{^od$0E5}%Nu?SG zW9^_be8h%988gp>zA`W@#xnpr2`sr3Ii#53Ubvsq*G|(ZOD{h4?TvW{&GVgYlA0Z; zBfavKJ>DQ75f*XFR%a>`ZZux27FkH@Ua%W@TWK12x_t$_17`jC3&sP-6Z3(^X6Qz& z`6uYiNdm5&r`B&;?ft3}#%LK_II{lKjt@*5>h_s9g51AJCG;6qd2fu-iQ1AE4-|>Y zk(vr(m`9MFUJCGNXX#c-Xl3kHx(Ee%h$HLR<1C?(OSY4|Sp| zNj!&;*oy2M?pF4wZpDEs@30>K`k>?YtZV!8KRdlXKTXi|jHB2>-&T-1aPR4>c)Rhi z&09Bn`P+k#v;W?z!B)J#%&YWqZkWwON9nU`s6LnJOCq&V4g|k&EFg9EOf3VD1gZGy zll8OQ__-yIVgQ8roppuTw1{+6$w^q1w7Z*rX*$*q0S8Lr$$y;+Ts^$qv{wW6A>#2p zMd4Ys0xk2ANhB`6E4?dS#>xcKRmb+fMre~zzY9$K9G5AgH9V5onqZfsn^NM zB_L@i5!uY$!!nLJM76oJ^4@(#YG>&~J%D99d~09NOM_qPgYIxy^ic!vkd&b?6_j;I zoiZZwW(3Q)fIU7B1G88+rTOawV{+urVChT1#ITEQ=%?p+5M9>qOf<8WW`5DupATez zCfS5wv}&)jr^19Rq1TJcirPu3f1eH$zd<+8@yLua{ry-!6r#{k5in?dlz_x+V+4sQ z_w_*w0n%UyE7dF59GY3_1KL@^jurHEX!>bcc_I;)->>eJlv<6Rro||?h3!4K6ElO75nG{`|HGM?@rNegzzQiL2FNKM8PQ?w z@2kxq=$7FE!?5%0>?!!%*|}-<*B4WAr zbSl`)z$GCAMF6xCDkiIcJ?SC*Ofq@Te)oJAx;RtHt343Az3(S#eR9((LDzdHE@QN` z_yH?_qk}H}Crd$en>?8`>oDc<(K#)cLCsEtp^C zno@X(Z5VVSM#+<`L-6va6+`+Qu1~f|qk9;?2EDt{D_W^U2fs5p&LSQyiwui;Si8Gd z9mFKHF(iE%nx5)v0xz_CjgD)Hyj6Pv23D;WcC7;d_unIp=(tXL)v`|yUa9C!L`l7{ zM8^2H+99 z95g#-Nxpius%nfNYf*p$ocU zCHyYiv;I*knb)UuAj>x^Wf8X^$^9a_@98B8JM7C)2`nfpXZYI)u1RG0h(#=VFIzeX zCjs;;TzNFJ++VnUIeLfhwZD8hEg#YnLlHB?{J4-oabQ3Y8Igp>4&Z|Hhm0wf{WJW< zUfLMXOML&s15Mnydz+fIhJYMhxC7$MtcV;$v4I0ZJzq28HOY3dh1xu)Dy~;H7lr@T z;D61leU>$){%r)S3wYCoyOXxl48tHav3)R81d%PvHS0y%6{2v&vta-#HQbDMQJ%GL zNH{HVKiLq|Alo~`-4;97yk#1J#xYa74Ql2G{WlC1=-Vo;jkz2`Th$-29{=Sn989Cr zOX*+GPs3G}t4qIFlHQ!7nD27^H#1f)X8SMk83@C~8JBRmq(Lm{X`t~3XW<>It?f!I znBpheAet3Tu-dnMdwLH9V=9md%3~!4Dg~AjK#j&#?Lr2vB!p0(k{0bh_@OTJR1Mp+ zGK=}A!aFOYvv3%eehx?deV1gP2x?On$8;(S2SQ&^fu{;TIgA2yHhG`}X(+Cz^Ke}xcI_vE(YRoF zxH3K^rax6roO*HT0BMM55E(bHr&|uoX-GdcYbj}RY8pe;$%S`@Ct>Gsg@=4k?u#0!c=)nP~9vY1ah*tCIY7tHZq86gXK~tG^j_ASPsx-(TBcy~^KR zDwCbnKk-ft2VBIQkp@g16H!H|af_zSc3v;iU-*kY8(!b|Q3?J*PS9g;)wd3=KbDF$ z9?dQ*8B=Zle_4Q{a@?3ghbe~gJ$q#~idRyL9mG~Yy;oN3K~Y#Yj6Bw)bOZSwuNuqn zs^6Pp+rpKh(Uh@W;q!unUq-aZKT~adeYR0GQIb#zrK411^f<}-nqi^e@RcAR>_`|?omNDOr z;{<@eXsy5WDiQcn?WXR~_!@g@++HtnYCi!<%Tx!LH<4FNCEvK2aHQ);Qu_9h6a5w#oEx|S7Va{Pbl?{ z55bo?AwtJDT`yZUxQ9HKwJ~T!JnpVGX-V>fROZO7W`MF zkzvkW8<^`{M6R zp13qxhaAeVX1pOWFODS)l(WI|Fv$?fcrLI@R{ZZVoE`?cAMis`1)vN0aYHI25*9E7z$xeMAqLElx zmnwC~30Gu+vORux&SU0@w|t@+>0~kixnBAB|Zk4@0c@71l!Uq2l7RRSy!*1@5moF z`~3f|-%lp{)4|+D68mJzGe9+l9Y^yuXsJ z*SRMhoh=>XoIJ(RQdLT)N8qFwV-b|bCR>?hVsV^Gf$d3G4(r}$UX-1xmvbPaY!=1Sij3=57F>&;kgWJL2h(0qQO>-$bwVHAR4U-H z5qa78fZolF7#M(g}4b69ALqkXQYX$BAshxC2?u7DwkT1?0zRnZh_=-hUDas_5!~y+5zsIKLiun7)6$l=oJVqMFw-W#zkE@}D z&+x!j+{$=_#93Y-KRgvKK#<^U)S-OQ0#=CDu{q#F0raxAH0(d{^^DB*GY7dpmaiz; zb{@W;q@3ny;DWI5H@2ki9qpOsO-SLh=o1M%p_$N9>+wfTNIU!k(Q&>|R^~)trLp;v zcin7hY4ho6+!%kpWj+gER_3B0et@~H^DhItpeE_DQ^>ppFTh{-*r{Qn^9kTGn5@ce z_)0}2?AI!3C+8&zG{64<0-TaV6s0F-OrUszR5cc|m;3k;Tmt?wxU(S#NFZ zzbnQDwd$=Bl#b8Ml4q%Lm5nXv^hg78`zV{P0VnMxEaCKx0UlpFr6Cdxr8Bcig&6&d|1vyl9_)=FzDsiABcFCzQg1(K9m{4Hx1H_+_*)ZV?Dk*$v+ zS{1V9oSTwX{{mfs%c0Zf{#f`N4`R)y<9uCs1tol%|DQ&4_ZvQTz|%StXB!b)X*GIH z&sNZuMcnxzexoS8$_b3M7Qe2 z{)!90Jhs73SSBX_!rK3?|Gf*3S&voJ;so`9V)fA=b`RzvPixOtR8Ldzc+|ol2bsCHZAQX-VvTZo6GhTW3+uWci@FrRaf-k#r7Y9uljK|FXJ4MVefdsJV55~lim1qD6#T55DSYmOUteZVo912oty&K$t4Vo zJ$T{2C5aEY-?yZa%G?aZ+^(DwDRCsxE|}k6Cmm9!as|`!zQ6Bl}i#dfa-ZR=NO%$y9GvOO6v<=tKp=@cSqs?tB7X9pZdi8UszZ<2;^dRMS0Wtpqek z{R?{nbOGfdewv(tmiZF}UTBHzyn$7)(KhDD9j?|L0vVOXan*Q57#Y7Q5<;_qH2t>r zn^Q<;`I8J}sg-MLy}&^S6F<6(f-p}xhZOOaaWOz9p2{{y@U_NL7kZ>CJn-^Ah)8^w z(R+J*wVgk7l@#NSd z$Q)1)KY|a|R^wc`?wcHFtK8$>Eu%JqmSB_G%VMXe5abw?yJEzBydmdq7ZhNCsztBf#usW>m4-D^nX=6Q;uiZIZ-IP4 zxCXOkfVF6L($#!*n*m+Z^+P?-XAwxT&OGHvI3TLiS^=LKvl}C18BPlt2;8(;N?1mh z_&)|m>^d2*+!=T7nF1`3JiVxApZGjG4YpK!ZVhCA|MMG%;C|Z&<4&F#jN?j4;9@6Z z+>C`|{O5=m$kxuEhPw;W9Z_`>Nnzia7;Noasyd`FDx`*idw`OB8QA4loko4?w^DU=1D0F<;q zud#Q-W2GdMcUYlQ8#%=ar{xYJqT^n^dD1E@^6P}V;oML>mEMmUlAC{vy{QOE z->}hceRko>Jv7(9HAz3e%~M=nneTY-cVKGyL-uWGzJsE4K z8|-I=&5q`Kb54QzjDO3U{XciG1OYZS)5_!VlZpaLdFn z+{$#Q>->AvF200Ws%eCVyX^~QqBqiPTDZ}p!mrV z3HXZCz~0cYfh#Q|?JusG^Sa3OqFYv~S5p-5%Sk-Zkn4B$3^FSK1#r2kSr`h~8}`wt zZn*C0_&tiW&e#LEWErUBxR{~<*y84PF9F&3#L2ONPn6_xg;RJM zu#nf-Q5005R-eXhNo5kvR(6{2+euQX4b8~@@ag?lu4*!|a90gbb>+2{8w_FpTotqm zP{mX4l~Xtr+Z+g$0B~)#mEtZQ`*!blxDaL01kytABT>_V1r)Ru(75fN0BW{_^MZM& zR}yYlPmqE4{l8h%@UyXA)e`-_2#vSj9Ck8MVts|tR&MgGB(^_X1plO#u^7hieEH3$ zkg&pgyaB?S?2Wv!dYSux-W&UVQ(;~UB2YJP&yh#Bo?CtETvlZmur6-*?|H^UsnP0X z5*4gQET&5{Mbm0Di=oRt_F1uQ-qA9o^Ao1z`=y~>uoLD#1v|vsxG$fv+kqNv%$j&w zXj6bq5Ow9|Q8zah_CnL);IZ6-5?-r%SJ2Ca+Y>Vz`VR)#8%cKm9_>r3c>f1*`?5WO zg?f8-C_n*Eqw6R}>Rh>Y_TOV2qT+-m(jP-e?8@xpiVFja6s`FFkz8s0IOD5aYfhUl zQ{GnGmwwX}&_cc16%zb&>D-Cz7-A5c8Xovfind(3@bHc2BWHKF2pAIBc73wweQ#&N z0<7iA7_h9R8%5eEjARf=i(?U;rd*$oa$SBf+9*+K5*<~Z4IL#hgiEn5&4w~o49*rH zhytBwioN#_APzosOaK$nV$=4owykyQk-6@&DmrmquBBqOe{$B!aw2T3Do)Mtz8I# z*FdWN!vM_6r{LW8xPjMUfX)RU1dfWAQL{^VM-27rXVKk0m)hvRo3f%T&IzIo9nU~i z=~0P(XOoyS^0|_$gVZN)e`vA^gO-=HEn}T1^pj_>i!d-5$S3Hidqo9l-!^3~YE2cl zWdJkjI7B(Y*@Vy~1N*GOr#6NJP-RI;`nPpIDMUeP#43u+uUb)t95?j$Y5OIkYfI4s zf7;-bVVadC*GHdm=auJiLrmFt$z#c}UKHVE1cvHJ|JK%@?&+8J6YV038fWqh&Na#Y zKH7)he%$ovZcgo8^H%GKG?kH`XS-r+Kj%f9^YNt&g<&$qS9i+2uw)|0bS8 zNTl{HXo67n9}d)uUH)i4o9b-h_Q_Fh)>{|J{wrgZnc_gQf_Rx=FejBC+j+I}_Z(f8 z(R)1l9jq_5l8jsFxR1VPeM225Mn2SVzwe#pae}PR?P{Io=;lvCvqpv9OURuf!@W#tz1z3-BLjN7* zHXd%+LfQV&FVR=4NHs>-n)Xru)p?o8mx~~h@+Hr$Ll>t+yaA?a%Mdd$r$Ef#oY_qV z<}8p*qwSft_g=xb6!MBPYFh&Ki&cXkLMnfDPk@%xm%E-F77;cx{9G!t4lMrJG0l*! zsiQdmstPgy4WSO>g`Q((nNoSl;RaCEPliqu%C)Z|LH)1torHspc;%ijw*~(7% zvn{MiYjsuXFYz!WB1Bzj#4t$N^Sk4d znJz)g?=vehtZ^|E{4xBkdBvSbak)SFrxmoWo(}2I;=py-#Rf6?i-^cgl{ON!@2*Ah zx)Y}HKyQ^rW$YU%+MtY6?}SZ12u>0fVcSyRCua|CCZm45cuV?Gh;TTTb>Sv384Sn4 z>{6yuMa1A_uupUL|#ATPb7 z##+=+`W;09QgC5t=!`K$||i>j1p0C?&@M+JTwLti=ImImI%653hoCU ztdd+(LbGCd!iFGfpt+DmDOz%`l8F@QF;!8jt-2`@C0`jCcJENO8q#vG+WBD?qEftkY^xL=2 z6qj4>BM#PO^hYP?Th&Cf5v`BZT2}$Wh%KPM^-PO4mAf+kaJgv&kE)#Qq?WTVB18RI zESl@&^Pe0MjHWHjwD%Ht$X8Bj1KjMO6@7Ym#Zx2*#8(XJUVwhY&!K^>sTqFx7dMK` z;6xu8MsH(In*Nif_Hau>_b~Ffsliceb!~UHY*s9YHJlqHy~X*b<00+2^R{p|w_~Ox zr))Wbb(4Mf=3-xUvo&Q63$5Nt!c`_FH<|F-mrzRe#;w-YhNvj})hevK4FNot%X6 zI13@OXaIq2FgD4!t>xIj zKG?g0mrglH^$M%F9|!-kzVcSVU{jM3Ly(#D_>FVj1#(y}#13)45Gr`kVcxeP+xqoF zuIO`2nkZJ)DMhtH#U=zr z_>2YMndGr-U(vt(#68r0xK<-US`|!;UUrL~fz8gGh(KW^DWd=a%!0Tloj=J~FEAB9 ze?sqaXQK39Zcf*H>N0ezSSinmzX#fIjx=2NX$pit@)xwzEjH*&!A(hBY@To60#BH5 zx~Y0cygc9l0RBOYBN#fY}+zS%l0M`1d9;ttD6_1={xw|s+ zxL##`DQ418pxFO#>ux9^J$`C;$9OCRoL5#*U3J-IY$b^Cw}kH*)yG9@u)LI0TV2CQ z+De&gJe(Q5^RJxB;D`R^D4muI9kzN$YRL@^zR9c*LTclRN76y*_J<4EoO|yc17k8j z1E)tb0!83LUGK#IJQ7~Ljx&ANalPw9M|LsdMO*h*{B%(`qMo6iVL|!eU4D+g`YG>9pVv2a+CGenONYgOKugAu98X)^PDU~nI$ z@hX2$661^nq@-rWB<^h(eA28nzA+itAuQjYs|<1}yrE;EK~kAtFI&W(JI=^}H zJ@bo+K5YXXSh60#SQ&-;av7vVqiU2U>g--1%?2nA*ZS!gBxg^0N8fjZSzL{=F#C(q z0$((y54^1-pf||(_``K@BXKD5+JFXf&U^ArzNU*<4WsH}lx(kz6 zMO1I`Zwb$k@hIo;M2DvZ#_Dr=G%mP8#fU zK4%O_;m!z%Bzc)l_GWykcLa{j-rte+-@Kf^d+S$jP$M*rC@>2r^Ioup_w61piF98sELhAhE}KK=s6le!;A2jq0a zuVry~0e1a0=c$6C<{Y9+dFSctGOwFmoA-s^e|Th5@u(ivoKPmJXto)IZ=5VHJPBAt z8hjRbWes$Mzj23VC<$<4V*e5>*P%ZQvm;jjCUp8bo0bf5S!iR?#}Gcv6iCRs>bKrqZxgUYETK1(oN>DF2Dzx{`@Y7+ECv3x1s+p3*eqD=~dwK ztq8BmPHoeUmjlQuDFHZSu42<0L(Xm}8J_?XVQ)-EzAMo;EIutPKb>7Bu`E^oG-CjZ0e$nx!-fFyNS zEnb=nMpgieQdR5_wwO2jgt9rrXmqYhb#zmIU7)u4h9+rDNfT`Ts4Xw690ps(4`+dc z%jl2OIUim^dZf6^Pidu&tiT~ut^?yZdYFev4LNfy;+G62yG=Jzuzq4CaMoH!et76=7_3P6% z7eMi>BFPS#R^|^6=o||grZ7(ACzTcouvN~oVSX_+TMI&)IQLe+#L$-{IfL*0Co(~# zS*R}os6Bl4yX}I%I~9dkwsRt!dK^U3)0D>E*Zk;#cWtX6Qg$}#S_ZXuY80*XUi!|Z zXke$oF*y9jQ2W+?EiIYGrz8Fj8GccT_w`NQlLg78@S>dZC+9_&9JFKql>$iQphBD9 zF*s|~rv^U^Q%LL%JaW}!YU%b^*Jb*CZFiN4o{$>xWKfkGLrB;eva44vVUI9^s@XuZ zX+cSAQNO6FF|20!KD%T2R1mn*2t8zp7F$myr>!ZA(-CcxMEONtJM!ZdQ?UEc7+1!E zFrUqTP!Yb?U)B_jcd|4uDV}*p>wDFfAImy3N#5qPZ zVJa~dJO@v$GH^1#!`&i@1bs9v;YPF>itAtiU>A#lq$HFlYxNIyzW>oIe+7)f|I7QUD%vT@ zgor?CqZ+&s@}Blz`>Y~dj+HOFW~_nxb!RoR+Oqk;qwWQ9IfWr19FOCN=v4>z1sDJP z+6ji8ICNcfzQ_GASzvFoVqh*2oUk6mP!&AJDdAX|cjzRtH0tLUq+6j=>`V5y#)JJ_ z#;OC;?0UC2GG9M)U@nzG7Cf#&^iQNdfm$p6k?;LT8YZvqAN)Kk8z3IdOWU^=o6Cqo zG4wbKT=W>LL4gethio8^$)nkk$jpv77v+Ol3vkK_8Ep7vPDwLt$=B$&y;Y2rN{t;m zOAH2`tZ-?ZeE2iPiCb~EmfZ*p0c^b0ukG<)1hf(mYX5}69L^2m_T$uy)&-C}=)8Xi zg0s>LJ;e5Rg{RlYgqP!o7_z#Ns84M6@1kmOg`0%9^_M+6Y)Q}E)=!xEo87mi3B%R4#fEmBv*3u)ZN@tow`+Vu{xEaA@^rJ;QDtyUIDwq$m+cFs0>;;AHA9tj z#?Y^0<$$lsS+wr=Qu%_X(VC1noP?Q@zVu-awsnht+fveS1Vs0gO@_WY{VCwVUu;6R z1<!_x zt(u;-be4Usnsk>I*IwNyJ?L!E8VleR4uV36I0ZSf=8-<~H$^F36>z$pyiXdo_`dGJ zsOQPY7Tz$6GE}u}H21-(vgFlKXc@ z@1l^SJQEl*(2;?yJK$CB=V9gvLWCkuEZU5}2Ohc;&mLi5LKv&>G+&HbH4<(TB$!B8 zWT{D?WBpq4SYGIzHFtUbriF3dAfbq+fH^UXL(8AJ!Vhws=Pf;Uui~f6wSj%qfzY_< zzG&`fYWTI5gi{L-7$|f(xa_c0WLLV}YwAugmOVUlU}SzSC>lVTmwjEi3O3kwZwkCK zgOrgi7p7=r9syhN9YF@G5nx(NO8j;=Ig?GU^so}CHo>No9AI-tk5!- z;Ny-hnHlXzuzmH8n%8fFX+3(8`!S=>AIp3re#^&Yu7aA#6OUs}|_$wUd z*mW09jSFTZ8qaZI(Oi#%>8Itk*6#$i^w^*@ptN2Rk}?cp!T#9=!MC$F8c!M|B)b^J zCjxz0CSsF#D0)iA78fT@DNVo3ep*)&XFRi1nq*A-*Hjvq;y^;D&6G72%UYc4-N;16 zn#exogCw)&(9biGZ()>ABS}T}l zV(7LTTMFZwF2;5|5{F6I)O^C&I;>(#?v?|G^j*j#v`0Pg*EIn<>!jGqo;N)Mh(t!4 z06Zfn^aD#r96`;K$zXLfqmGy!CRR`Rl{DTDVb11ixLB$g-Xtx3 zHSWtL!eo?rNl*Gu@R{fK_RA%u*054EEgvoq(Fvlh$zSBGcK@S zvO>#sAT20?U|%a^KCR#JA`Eoe{adLk48$jYx;3q45cEg7Qh;XVT*moUVQ|vqwlS|z z4LB=w(K2DO859nCK#xOhO1i%g8mq;dz1c;7Jfpcd1BzGOcsN}FclE3CXinnL9DLhs zinfz>?K5Yy0@&+l^H)Oft{Re09gf0sL+yfFj(1Be2*jBXk=i=8yh=PlW2zjjQ@z|p zMS|dPy9Nx)r0=VzlQub7@Ka~1?8Tf+8+Z3!Fqz!tpPw0~61J#oJBADa1XqE^H>Sks z60b_I*bj;CXqm$x+_hE5$;oEiF{(FOS3Ne)-Tew7j<=HNMXeyQTm}o>LpN;`00le+%As#wOQYkm>3flAIcWl!4|$BK^qI`K>^h(0hsp#+!g1^Pe{13|(=i2*F_kqE{iLiNrEY#S~a=e&zZyJ0T1o zNW~`663N}%PFfM8b9hzX8;l6-9U%FHi=u5ZR=Bj4WNIV#y;nK^$IqG3a>cxgi=K}W z^ISmyHN=0sTbL6(PWR2^2ZQ2IJqx?eC3}7x1P)bi#@?Y}Y6jbRRVmP&EwjV#vZ}_= za?|g%!l#-&<9-(aa&zC$XFGJM;mN46t%M}KL6JR^v!R|7aS;E1THxT1Nmq7Mo0-1` zXQ}uS8_RTuMciz<`jjW+{pGoiaLK4JQvK`V2n@iC`zx?js9Wq?K8j8pv#xsh;i@w^I+4_ z;vhi6sg6y8zUD$P!_kay1N_m(lRThi)q}*n!r;1iB{X%+?ec=8u?rmvc)w*wn&I^Y z{u;m%e{8wp^ZkCTa^*IIvw^cv8s6wfV6XOB_Y(woifEvS=z~w&_{=eW%;xZPeUm8v z8mK+>6z!OP2HNwz*2{LY;*GyXk{{sY59-!CJl7J+Vu*+|rV*YGs1L})7@-IR#}W(8 z6V60vY0v0B-B;{}-F+z`KSS3ExU-8whhzWNQ0E1AT?@~fYL49IT+n7 z4br2eLqL#}lQO94-IQ3{OqA83u zYW7FQjg@Cl1>0%Z2{?&h9u0TGp@lUIc#_$n+bSBT*tAk1hvW76+U$a+vei6qn@E}_ zM((D`yxY2$fA0sAG(41CzniG}sqpA5{MD^F+`?faCZ;(&l)l;VW8~uu$@8$=micZJ zRW?LEVj;NO(bk;2 z#MCl{1;26IcVom0aN3kvp5BOf;y)3ilh+V<-WU!bZJr38v`KyW9l)MQ76oKB{BaLr z6WQ1LV3S%WX7et+OPF+=nASB|y2T;1$l-0y6RP8=VG>>;CxFEC%qpZzp;+;=M*PyZ z)b)4=IP>m-&*=mKspUknL8c?6WDQ!>W%#!UCROavZP1?Z{SMbq@Mlg&d7Bc0C+BIh z68KL{Py;>}sJsaZ{}>=q!ilslY)ejPjtmJ^SXC# z#ruby`2`Vm*K{ttk8@ftp`Kx@pTdXfEQgZr7!4Xp;-t2IjKw7c!bOQ7@}NO09+5Z6 zNWfn5Ut+vz$S86Y=_#Z+c9>m(m4qzb6&C_~%}g@Rhb$kP9UA#DDeXoWR&0MeZW2o# zT5UcwGmeR*APYWscf}^zyb~>@L}Sy&!N+w4YlBX1DSYTjDGgsttxL4b{Mqu&r@z-)>x*11x2Cx8+r9hUY5? z8BFd^h>k`^Mbl7xu8809S-G-T!lcA{t$g%}g5;3zSHmNV8rj)I0UxTsA+U&b!z%ptRN07dWTE0ysifau+&rFU z3EUP4&waSVd^> zf-MQ-j232J&tHBz*Z86i*ZO-zZZHgWNH36?RQaIoKrdH%y?DVzX-Q)igK1QRj+&QG zq4zkXDpK!{Sv(jwUMoB$UXSn~Pw^Yr)w;ctZ2qGA%TT?W@``(Xjj3}|I)L+5a5`NM z6-1C7-5cs%U%aOL3zP7Ww-nmQGOcfU?Ebmp^{KL*zZQSZV)XGG1Cs55H^wg3++sbg ze%j5GpdB3I!;Rh@^r@ZUTbG)yR0AT%znr^xV*GllF62+snxTh;MvHRw>|G_~%WlUyjKH-lVEdVFvO&g)__B)HdZ5eVr;E;9=%Ue>*5l+c6H=&} zny6RvV%Soxzm9*SGg@A&B+F0{qcGKfXJJBnF! z1j|xAOgcF%1v~CaxGXP0f`qaf7kHkh(xO1jD5?i!{J>giTFj}Pl6JGoc>Xug#iVo< z_W-w-vYj-bC^O)&c44v9{vD&6bouwvQwTp;-GFTaurU-F785{sBn6?6=6{TdR}#>) zLYaIy3#^bP3_N2}*za>LlGy?|IG@}btJi7PQ6Ie;zT4GoVn4-s&^!{4>KmoG9t>J* zzYuFrLk(vx3wV^=x^8w5Y;6v~NZNR}WFUExj&kwK{zWfo{(h$@07vY1%_qLjk=m4* zSdZL|fSk^^g!O$!sl&HTVjlkG;cuxr+V$#ZG@Ug9@n#cIyd!RY6|Wb?E&jvwP3x2G zUlvDM2n2bsTsmL`P+zw>&f}i=VKI4A!l>Eu7FsuD`K-aCaOlMC*E4tgbL@z^vLEQF z&gc_bmR%OaB8LE6(MlW;_odVsA4XTi&p3ND!}T3^Pa+d2CiET()Cd;(27H5jNIjj% z6@R+;!r~8Z!eK4uZf(7F)aqVdOxX0tFa$TU+f)_c%z*ohKd*j`?-_0Cz#l2Y97;!3 zdBRQFuW@Y606g>(h7Ui(uN=tMumrKE_Q^+iQ}L@!M`|UZhj6`Bpq8X4MF-tP2EU^X zyuuqSogfjBr?9P~zQ!`G{h1Du1IsTr5@nNjLoAAZ_qA@evBmq|@@wO5#Z@T!yS|M= z5PC(v8@6&(wkN_Fyw3P2e8!DkI?mK^X9jyHxv*4 zNc)Ik_?1?+Vf!Dm?do|}P zGJmd;6O7s+K=n?sTLS~Qg-SP9V}aOjVdFw5eb0h{Zk9;8vGZ4DUGkAAr8{~#QL@5S zluo|Po@j88#P13c=Qiv*%nQ1193at+FbsFa^+_8{St1+A9lqUR?6VsWp{A+TA} zaSz3sy9LcGdN13tCq&EEW2)pr+M` zk(QR|-{f0WQq)UNt3SG6gLJgQw zuRZJG4GA1{!JEwvD*NIs2yFPHzRH)i`N!vxI}mre2b=CXVK z?+OaTI~4yvh4(?mAu#V6F!)#hO3X#zNYMOuK+kV}jFTou_M2WVYoXXsP1*mNJPxsOrHc{`&=d>w*aaiU~$oa3(IMY6dw`s2v z{BIt->?;7$-?^id-6_0>eV3?5>2OkuE0cP%o;F$eh#j&(Y?#my#*q877h4ACV+;f7 zw^WcC?Qjd%MzL^nw;D{PW}2%hC}H?o+ely6dCP^>;bEW?t~~)n0$D(DuhsxxH>_dYC#sFo+oEHe01EM0MI}1f7ZhXqd;pN+ot#GX{Vv* zRE3fRHvWmiv4lp{`<`;nzl;1hF>ZwS(00D7ap(K;FKI-ygRoknFl|W>UFwbOj?#Z) z^ZJo1J0uAb`l-jysjF?jTlK$3KATEi8?i)nANje#fN<@2Rj0q)Ac#M(Yhy}-m3#Da zi2!5Hv)rad)q!KMFuOzkT2TU^Ji>vpyWPT*4sBl5V^S1$;PtBwIM~Mf_T{!((UCc=P5UCnggoU$(XP^R){!Fjt-MUSHlfKXyA!aJD0^^+WN!cQBoV zr*D2oBQ7T=ZX*v3>A?%!i+tNZUrvu`KvPsD#Q&3)RVq0PAP_WuQ&5W z5|?U9#IHUjMTJpMfa*zLHO1rl6~<3G`_rTO)Mx(XLvlb2Zi>0yiR^uw0U#@Gw*pI@j{|2--N^Ub7@@oOQm!jw zK~WU8^J0X%-A(yAKPoKMyrE`3NaK%qtRR&%l89Bd4i<_yd0V=K@GY?uP70z(47xNp z1_zzK0(bu>@iP75qRdl2wWGTy3p;{diB{<8Q9mbKI>_gbIF~-SZnv9a3 zRs3n)5>p^eK@Dwtf-9S0k%uks{Sz5FA;-`qmLYT2tRty zsfb@N@{Jj9HOePb;_{A+GKb}z4{M|loyr(X<|b&(YxV>abYD#R?Tue=B9-R^9}B6& z-$CG94Fa=Zx6&(rA)Jt*yB15S*-SOYfsHon?p*NcPD_g8AFMA^nb2!7ZmEF?cMjdK z2AgcQ!o$L0P>rIXnAu=XCWC6gX)l0*J&{$QLYaNY@)RdY${wJXdng;?kT&!$om2K3 zApe_nJY__fuobnMvevrra9e)aqjsCJOCOa|dwhcXRn+}3#@Q@PU3ZH!dkdB+e?itR z1*M`0g14KkQ&?U8=H1jriXD+1#l^>ZiBVy!MPGRqr^ScK2#wc9N!{yO;!2m;ryf(q zhxxAfULgJ;3JHyYYc)sEabv8|-_sViP(Syn=sFasIMYFXhqu4L;gdTcf$1kmQ7%S# z0$yGY+Ld+K9NvS_#T?h$A-DKaZ#Mfe{(kId&pJlt)|IUWH+?%cZ1|Gf^wRd=!=mfD z4YnV<-}8|xw|+P8rqB8lB~{c&Ea^5e^a8wxD*zH}T^l3C1eHL@OvaynOh;hdbw#yX z9;Kl7zD8O@hC#7QsQ~(|%V0v1z4U+>@pkuDXb$LK_*fYY9pM`++2s%&GRe);qjE?e z@Ys>Eh-h7?t$Y4qFZgNtgu`R3NMUBXFsa!yPh){P0*}C_?X!1c2Uz9m>gCI6RPl^O zeO4x-^uP5R3)`28z@^<5@k7%kRBFN53ZeJ`bnBE@q4(3y?Wm=1O{m%Y#@0nz`U;={ z6Wz$5Gn{ODxcH(;!mZ`hW90}Ye(Ub z*wj6b^Z!|F9bqz3m8M%{{F!|rX5{}|08c&$m;&!i1d8er8BEfWc>*Dg9-#rj^a_Qt za_jp>H8zx@fL~KK%8{j9`~WU@FJ^7qjEUU$ZO7#ox<-P8G)?dA#I9Y=+HEJLXnx>D zbZAbxWC3V|z_T`fZpj`09GL$4m)zX~Lm<>DNYCO~5UnMg%`zb(49;#z(mUTqpsGC8 z2`@(uwK^q%g_db4er8_oo0l5v-!|YtoW3ZUIuALZ*NtH6<}#=evGR#legM>syrcq+z|=>yJ2ZIfDW+Ou*8kbG6zy!lI(ah^DWN#`G*4_d&2D>f zT!InMNIFy{{vF;dC7N5|2wO=h2SHeUUGl!(N zpnQxdzi>;En2|Tj<}(vSJtCP-wWH;$)ti!p9a|-07}6p2=Vsj%CsuW zy@3P}FeM^f`XQ}&%J1fN^Ma7<;+W^r@J|p$!+fJrjI}$fk{j$b9Y4p3UqAc)n`Ydj z3f}#X!@~0}ClydN;?T|co{NQ*9*yXK-opg8Ukp?s(8@6G00QF^@>};tB*GWVM%)Mw z64E}-d&>wkzA*YKYnqnB*3M(@zi~E&PrdJiLQDCgW^0AD$5%`6CWNORP0P?Bh79NN z-}0;L=aSRMH=sP5_$n`0hF7_AxZ7Yx@Ke-9LX;a%p^KAFq3bB!J}-fw`03%6(@#8V zZwp6y_t_cwBdp79;le`T2c${9O#c1Sqji#LraxQgD5MHV|a>n+@Vl65d%k=P<0`_TH*kPJl097 zXp?fePT(Y};MUhKIH=7n=s#qd$s%Pj_Lx8@Px~$miVMn=v7CY&zCm4!byPpi$R2|j zD=wL+SIfsN%wH7NZzC`oKX_7dX#S>p`Kr?%F!d30nZj4d zOXpAh;HuZbAGBVK!H>_cF21T{*;O(+`U_&DwW`|Avt|Q6j|kwu;G-q(AJ(g-4YZ@x zO~}D6CuiMaAB$9>qe_H~o`w&A^`^6k-Y<(ebb-=X;I$*qB2OeJ_$+5pa~^o*LyB{c+UQB50-lw*pxRHW=X#fE}AX+XK{oH@ZV)pAM#!4XdNqovx zAsaG+0UNbJe+E{1USSgZ@Ck){&9zq0=CfHX)_W2|MeHEx{zlFs&g=;b`&T_-@RNyt8+sNIW}H?8kw_O$%AOX?s)CjJ6T<>;4*U><6#aSU6P88Tk5?ytZeheBb8_p&cZg;klT zn@H5OxQf5n;wB$$(DubdnIc{uj~@oseiUP7ZaehT=j5c-jjx&p!y|#3F9hviM#89> zKR{Ige6oNdIgby9;`U7sM)OufTwUnGSf`xZI@Y@E5npM#Xg2NOMpght>RS2QS?fl9 zyJMGxFNrwID7PJLZkOcO#&*i{PFZ(daK`a=&S6$SV7OUCA8=+`6>v(1h(k%En0biJ z^5*bBA?hcNHo{~~LQaBVu7Qk~8*?fPnv(Ca1W#}>6yGOfJIOCM!dFku0b>USXs8y- zpB~wv;ZSDPO)Nz4uE<3^igY~hO5lv#Ci~IM6$>>&|4d{PiCoY?+rGExa|F0uNa zUt+ylTtNSW0F+hI@5sJ&C8jG3ocNVADx@G6u3$1#FN4cnu^myeB$Z$yVDqGfMFI;< zSR9~@e7M3m-N86H@|hv_-)j++W($~c4f=DsfA0olEWmmofoWRBvPtemM&*moW=f-d z`b<(4NX}38Wd_?sMZ;C7|5I#>6?_nq`Qc~SlRUH?Ql=Btpb5>qbcXB;ky51r%k4=3}=$Q=I*67Q2V8oh#HlXq1`O*>HCPnIuk+)1nGQVwZKySu$mDw zxB;;Er2_5xKe7eAvpWhBV)BL(dX~mNdhGl9oi6p-lgpu>VW!b|ODi`p^pWOqc*u`& z9AxEi3dH9O?nIW7D@H{%2W^ZNU||mLvdCH~^0CX=UadCBr23wk5Qkuh5*nwyKmmRG zXE6eAd|2QOR6z{bo#ZD`V8|fW7q@kdR^C;3rAo2tXWpVj-%ZqgF$_6vBZ=gGHg?%~ zXbziQy4P$&8rX&mog;m^+{-f&5aAiq8V+!e0hs? zO3&@gH=}Px1a5vEZ|@3lI86ZRMy@VR{lPvxI7#>Zd*a|=e9t5dszkF10++uDXU?d# zBjl^;@j+jqYagdDexqcN6_Ic9sNl9@z^G$TEbVwV{Ae@-!~_KKb zyJejB=OaOj7}8Vu*+v5H9&X6%^5_hAbEuJk16l5nQJkBqp>8ZT9pQlZc@pIP|AO8f zeV8N@YV{paj=YrNkt9wZZaB)+>43JOu{+kj0cUhh)jr5+rbxMOctX}_B=(*U*L%nQ zR(caDW}uN#qAe&B!|?NYmdE0~JTsbWo3s@P*f_rI-QnI|_aBjsr7-zE(E6XVZ*t~L z$bDKFzg?5tb;VdrWDNVeD5Ms#<`#?r<3PAQW26u-JI|Bu2xE{c1hz-V*m>4Kp}YX8 z=OFtrfO34sw7l-P(%r-8_o3uH4DIDJNb#t^fT|R@l&^sM$9A4w^x2j z*2!pM_%SdlNhNr`SqBIuqwYo~3|H$XySIH(soH9EI+B_}sd7W0?@Sawz~d?WU$Jm3 zHh8^1ER{osc~9DlW74p5;z(qBn{N*(H}CeL75Kr5;+NmoPuqI>!9i=mk3TyTNa_dM zB_@U}BBxRq;`$7cPX}Mot$Ht2T*uZTKne88ez{yioGUi|WK&pmc%hRPH6sd+g(7Lc z#j6FYx!laOT&bKF3Y8?WQFqg&;*_?)y&?)=p10|hu>~duB?gmKMK7Tj4_#-f5KG|z zrX%eBM_;>4(wgkHu4`~KZf|}c`Q57P!qV{6ke|!vi5%t&(V$DfC&a|^{%8f=+xnT! zp5@@>*Y9LjM6%P_+*_djXnij{$1~;b_Ju~H5W(tY?tCX92J333jy}M4<#l6PLkv60 zL;_*mP}`pKvxyuJf3hx5?`V7UDd<95uT_MWbucGsaNTOjQdKdJAZr?zpj|}q$dlCE z{QS(VVQV#Q)3s`e(L zB;8ma(c_1Ua`c`!Zz$Xaly6u51D1`VnSlTuJ|RX(;z@xD%JyB%O&${KMTpZ`4|c<> z;1F{0CxM?|D!t9p=J>!7_j{?o$IO+Esn{`1bT2e+!KzunNj{G{CqAu=tWs@I&$8I| zq0BbVG#EEffL`0@1;CWzW6kKnQeM#cILE~{c_JfQO%7chb_A{f2!aJ9Ch^QyUa+Fm z3Ed_-(KC1AgvyW0t3{OGiQz^i$0wuoAvdy8W>c>3_|Mu}r!yA-7;Jc|=z<;i2F4{W zPZ_e%Rfvo|A6(p+?tJj^Hm@#MU=E{~cIcMuMd=Iq@Lah8A&4KuhiAH3S?TRpS)o6M z!g8A#pvXn+wb53_Ui!$WeL-xAD@FkO2T;b3P?A_-|BMvfHG;cW+t;L0YZjT-+i!b> z9{&<}10LzKbV6j)iX?R7F2>e;UN;BzKMt*(y=iVMg`J@2>eJ&L@IlwP$!+@clcpk) z&R=fk>ahcnuUI{Pc3FZRPlH3||0%Mfqjet|g<=zVzN*0{?L6Ar@rrN{G-W@kXijM; z-96RLQ3db$Yj(}UiGwsh)#hruE7dPYbTyN1_#fXCGW^qOWoA~UwHRu}>i|l8>s_b~ za`!v1{3|z`TwR8w*S9h?$CEEIDb#ULnbI5E0$JlUE^o@{G}`OOrJ&0f<8@!UFM$h) zoq~6U=cXSxj9;{Zj<8+c$G_hGWo1gbLK~c>#FwnnW$M<@|LhqJ-UgTq+Xg2EtHC>P z^aD{08u=<2d&k_@zlU_FV{jm1gL-V)9q9uh_J;&P(lHE#SS)Mmaax?$0!NoV%z!D*Y&n zD)K@$&h_Z?cgE>$Ab~G;xu+FSMeF75!h}8qAQnm{DR*-=-V!g)Et3TlxF0v&v zlWa^KxrguS-9Oh5s_fXtLBrYl?|em%%q(8Dr%k~YaJ;;~SiNw~&(F?a5p|wrw=pry zWx-jC627K1dDq)C;chM-*F|Z?_bx<9ErO1XoE8Y8u{d4szbfc2B787fS1~{%s;@-k z5bq}6iik2 z=!{2br@V_upXB02^nd*;J-0}#+Pjna`w(U{GvHuhFXrZ!8fZW%ZvafcL{I>J;_eh` zoHI93G_i^mbU6#}r!95&!wvp28C2`-byR#GEOv!pJG`(LK3@}gl4~@7nWyeC7TP^1 zoTD5j17VPYzxDmm-oIGT&p6r*4VL;i;5@Yr-v@$qwdT#jJB&c{o$AC2 z+k8q*zg082^(AP2UN?{^-+f)xb6fM~ov-(C+*e)yWY9gPx>Ir=dxnAZ9PGJ7fFHfS zq*UmX5tb30m{)zL-ZRIY%ORDrg9ZKV7((>S4L9Xg7gy<&sb=zNpdRR!kcJ5kCQSuN zv3OpFv>l}pY@e?hn6xACgP9RNCta*N*?$9*?kA|3m#M0}d9N@R)n|(O;~;c4`IgK>b&`H6@f>GT~Kv=H9po+e3neRx>F}1-7hn}w<4k;fXO8ji6fP{buI+war%|`)e<=U^5G%h)w*ZctqkG&Hfc|S zT^#bmPFN_05HzTRS)&m9K3lewg5HfJi+LcQBSwJpyRTsTWM9GXa4}c+s5L9J`EG~s zuc@&Noih4Ma|LylYRQtY_NS}N*tz0d{ZYON|jAy8}v7 zIBCNC7RjHr%T#F_#ao2wpVq|dFi}j`pYo@hu<+WDr1SxE&5wsUM&HnboTEl)v0J{; z0v(>=A(fr7)?x-ul+=k796q;KXVFutrH;Lj_E&G1t!Xcm@2n%&fRMN?&xpFK9tVVu zS~*bTZVFE@3vtBqo!5CQNEpKo#yUPH98cBxOI5noqPIpzy5f(0<-LgbcC0uTkFf8< zxw~xv{Wcbg4JRyzgQ}{~erT)b0;03Re^LBkwdYRQ>mHi@>E3W{zqe&r?K4`*yvQuX z`6P!$P&@Lb?5ri~<~jUu;2~wsikB%%ovU2=(z28E`FMR4fbLUnzwn9T2fzL^r}E(2 zr{7ah7j-BuH@mL-z0nz8<)hwT;$-3`$!)VtNwQ!XSm6u5JVu+e@L!TgfwzzV4Om9J zE^;FiJ5Q_|ET{+!K;`j*CV=lSjYFLIvBt6;vn+c|Bb+MZv9|u)q}B#Rr)!gPP1!J& zqvqdrmI{R-ETG4WVICVCU{apu{x%6m#z+KuG`5#xl{gIxJwM@kSNH~Js9}VP5RZf& z7a<9UkzeSu6P^HXKARDYB(kdUUqkGBtHR$qMP;;hDZ(>kH}=jx{xH@fMc;uSy#tal zWU^HSw&IMQy_KIqDN)5y4hpee{A2*aW{(k7be4fgR;o=gq~kOru1NTBrEiqUlcd=L zGr3v(Suzo+I@3PwYqL5at^${@g8S7>3{bxb>qANuSgj8M{su^#8JBrFHn@-1o9>r`s{-KBisQ-6@XICX3f6;2=1FRl5=SW~5uL?C)H#uVDH$}|E^ z$!4<>V>sMiks#U9tpmFAfkdigKQXc|J76cIZK=mJL@K-bg84fTtw>-47Ub5*?{a=@ zrpz1VRB@bz^_|+0=;GRwbesW6Lq3J3^c~SJgq}>c%2+Inm6N-^czpou-7lv17MHy7 z4&b;ljrbC027;Y>grCyF@b;AiU8Bke9WkDhDPdb?9Dg2Mn?qJzkLXUtR9y#dzVQEg zb7So-u9`LkHOvnHzzoORU)!{u524`zwxSA2U~3~+mOn=-ycRhEGU?VLrYN5aJPaZm z;)fCbU+&MBEN&4>B4pHoxpctXW3LYM>%@tjE#r88BP3V+1}7))w7zW{T~G-_mKM_c zL;xn6;6KHQOKUO(Z;Ho+Y1uI9_T!HSd?nM`gvF~Z-MOu?hSc`=VLb379g*3~uvdM) zi4z}>+er5$;a4mqD4d7d|I$BK=v^zO<0iJ4NV5>fdJ7tELjRjpr*)%VU>MJETmR!B z$FodjOwkvaic&WGP2A9a?~~0Wtyl0K9f#72f1&lNLw~jwuzJAR#6-zXD|sAz@C3G& zcg1{Sra+GAovY1K!WM%WCCO@oor;$5@{^GqXQ91E)ZqEHuQYnfg#A`WfY21M)_$z# zWbrn_k{924_PdcbeF*OL&Bc==qIG;B=_pT^+MB}6mRI@cx~|n=0!3^|JR;q2ditf;JNpmgiHJr8Odj5_Xd^aN#UM-okY_PUBie;{ z3cYzEw_Wb(D=zhXa5oGjpvc00ud$p$55WDX@p*@U(32h-ixd82blxZdOzlCm>m+fMDH-F2!V0Xy#7J zg-ZTb$DlgsnrQu3kbBd=uZ&^dh4g0z!42y>i_kwkZOc2NH;ew#)oE_oe-vVw2oCUI z$uInHJZmuw+5HIp@*3rARSaK0&VAWnuxZ4yz=2z)Xejwz|GUdsL<^_Yi3KI zIn}J#7f+w^d$rl|dvaj8l&=pXID7Ec;WVrsEbGI!9G5mB0fX)@5X{>YxP}{u4x0ez05?#UT!XK1L-+^$c#qOm z^h8^Ewg{Jj;oe}k6|&%bp^cx2;1HOzQE7Qd*$fDe=RMyawvDn#Aa1+92f-DwQ0Tqt zIIn)^na_ebfmUy1n9ETQH2=tCLrFcDWo0O=Yjz)ZbtkCG5mV1S8cwm?1jW$zZYOG)?OErRI#{Q8rU7f?ha<#a zB;z`4&4iw_gG-n&quHXdJ2`n0l2OOB(O}nk{bz*YEHz}toNw~j6?K!Y$>;{SEAs(h zS@rs#QrQ&WO~iq~vn57a$)Ohpc_*D3BKAKiO%+B3tY5pSzA7rL;sBDlRUCHVLc$#ZBf)4ymQh8;SDj!YkC=ZLZ$4@!IuekYeqh`&R&g4-hwcXg~*U)PjTX z_e&791B>F8>|Y$4ZvM;0znufC%|YbA1=n98%^FtZmhS3h=R-UuH_|8+qRv^~Wy2TO z(dpo3%Uu0${^sUgFi+tQs~+OVkg-~Se%LYbclkG{TFjqnG`aAN!HX;B*H5AzM`{Vf|{os_$jBZH%*vRxp{@!9~HK zYxjuD;gOKTzMql8H?K${>dKiF z`IT(XfF%sh@byDiJvMDtWjZuBHG!6?5a5EadYcZEBZo7`Mh))UH5uM4*v)|O=W80f zkG)E{KhE{%`zC&+H6@d~`B)qeRO3_S!D6pI^sgef0l0c7W)%J~kL|LHXeB85z31r) z#$o%Je#&F<8yn~@Sy@jI5k`#KOr}PCwdB0N>R%%!SU-2jk({8ozSoR!z~jJL&%P0fr4w$(GNM&_KYNw! zNu9dLoyQrG&UMII=7at4e=dM`+@tEE;I_ac1$S~zqilALO~I4>k(|+DXLE1@&QHR3 zDKk;&!Kz2gw{9&1JGa3!3ewarx|8xR7z+y4 zz;t&rnZrpD1u%x4cI<+A!C>cR!>CQO_|AR4=n9Me_g>#r|A6U$f!o;!}F^c>~ zm1_~c-GtuRHEn{!XNEta#xg)<^)(Ys&d7;``&0Bd8sSKo#W$)+TyQ&u9`@U9Alle9 zO)>LqDjoZb#@ANNl_*-(1vst13*a@aCW{0Mex;>7Zlf(RGn!!fA+7HcM>p0|P$4@8m@Wl!$P=mLBZ`;3^Z>iNhS z8Hwk~-Lp*!V!9;cv6=>=`yjPm`Qs^Ws=E=s&6d03+0@sG{${n@s3D02pKuby(dz3F zNS%~BJyxK{t`1WyXtuF;e`r_P2fo1g(dUy7`{wp$yUCM&MhKOF;N*n7*LBCywyO;8 z8RBk2s-B|z3)b+^SwNV?lrH}i_Q!}ci*mkcwgy>SbljGS+?{Cfq(Iv$7S^T?pvkNr z;GK>(m;}`~iL4V>mskh=rLjq1G@3*RNUUUB_*X z^(RQV&ke>q!O348PX1+oGWLvlnE%%+p z&k3&)BSNv5kAX!vViZHiQaj^+3O05K)TA(-e$u22ONaYgx`a~MCj$(x@f#$quT zCM*ew>0oiz*L&X8YrQqa7qo1p7Sl?-_Q+nsrrl3)H7=Z|3kkPnRQ^*xd|BN33verH z5Zf(c9NC@8T%lH+4;f8G2F>KayLxdtE~z;UzYH&iDX&D(pz)_3eai?{x>L(U28Ae!hOQ)qsIer~SJ77AN3~Ui^XDC7r9Cet zH^3O*+5wYI;kt1fWN7E)4E$2krLEYsDrW~vX&?z-2a88d-7h^4?p-AF@=rMPpX#qEDU^QaA+h*n4S=R^u86kTdh7PQ@pB<@(*dt4nogAqM_ zDe`0Chu20Q9h(rXP`^V=WK}A_+bJ*CyEgsBYqO8g1`Nz?9PI&CL0YDHfJ<*71IPX3 z>Wg=bxZcDYo?D5Yai{ON_f^5zr#OUMb?&({iahkqB{QrPl(fJ7tgzTet_D~N;{|Nl zQpw3M6Ns=kochn9$yhCU*#m{VJ-7_!pbI&?F7PJ)gX!OwE#Z`4DW+fb8U<#)_l+bz zlJjD({39m^Y5Dn(oREB;8~eM*2^Q&Es3pO}*r0tPz1F-WQ4RjeUm-119H%Fx=rL5Z zX|$poyRA`#I7cB(IEuWrOH;USx^=MC_Lnu6n=E9TDG#iufr|MlHaH;Z_ISM?1luEG zuG0syLh`s}el%j&5x}LYmWN;O!o7?N4~_qH_vglVmo2SID0*)_eFV>uzgi47w0l6q zbp$atXhG}x4v+di+uimD_Z2Gek%J?g0`O5 z0ec4h>uyI1AF7Jw;wA2~pdKRbBv=oaRD{0vyq0nlzRTu>C8&TC*%$L7YfBU7ll`+- zR&F+;gRsN%x!KGa)p}p@sh|n%?G=Nm+UpRK3~~JM%#Ak^X+3N8jLc)hKI}H(=AQ;c z6NzBZ)WD>*4=Qk-!gG29Al!m_+&E#42=T%*0XmgMW;!0w8QFr`@)>4y$q=ktJ78#8 zjpK*fVil^)AMb&e!%cuN8Q*>4;p@TP;!NPFFK|J70R8@uyweqX{OWuH?#gtH@E3Zg z(XVn^Fy8p|bN*A>8y|$-S7-IfNv|871G=ua%a5slp;!7+iXEqjl>>Iri$2q1bZ^J(KYPr9El5M+vPS-*_`;%mB z5!_qRlpE+Vce8Se?p_b?uq4W{jGQ>c?j^kXS45$d#;~*45kZ; z*uhM}?3)|C{zKaR?vKb=QDYh}aj594e1twUSr}J0!o$u^Xz^B3sxU=J$pSLq1aP|0p z+k2_$+%s&ZC?W9rT_>*$^G{o7qLkK)M4!gyM~?RlJiffs0zm3|1t3X%Sdg zP@;OHyoUi`nK!&v&o$P8#(9hQQYEYfXD_$o!2(&Nm0LXpNz z%XF7IXqB6NxH3g&eQ$;kmJXY&SiZuB1VXq<>NCH;bJB!GzD^&3U=UI?;Y^fRu?pwx ze>?l;h&qwbA+9SGsc8bM=z!L%kSozuvntGB6BsCNIO@0}b5s*Gx{H=H%?-PLeeP@b zaaGYv%$c6HpcXf90x_F$i()jk`j~qE2)pT*5a!uR;-jEA_soEO6#8LyI|t}jH|PET zeE%oN=n&ATwZ4DYHSys0Uv6LZUvBSo7<>MW=fpVvu=fcKhW_+_o|v7Y6LDf1(YBGK z#+=c9+iQ9?k~#mv&~f8Gvr=!`Lhco7e;Z~P>7DBQuMpJV*LK^@75B&dzwMUijoOG8 z8%jhL$pJ(GTHY~_H!eW*1JukL<-J%yJBI5x{fYWbWWsY~0REUQ6;kZk2+|39+&f&0 z!N|{?-Q;hh7P1D9om>yR*s%=ooqIg5MoTA&OO;ri*dA&T+*vC=-w# z?09e`wUj+U{lk*E@aS8TeMO189J<@^3iws-4!yvQ%e(Q{NyId>T~Uzp*R3#)-*MV+ zFq$P+o02Vq1}M(;4)lPunjW>CjMMX}z_ZMWwtYt&{$Nx!wG2YwgUSIQz&g?-W9mmgLyI8$bdwX&~zs=!|zD%xl%lnGue) z00t#-P4htf1o%CgBofVY_?CV6L^BSPZ}r#22R-(LEfLST4>3XSm6MRj4O%*&J4W8_ zBLv`<%C0zmyoh=|2kw((UFz_{=y3xyY%;4j0HHxVwV}3gt8sGJ z#Bdn}w*_^&D-I9(nbmz+mFi(o6x(Z=1PhlY+Xlg;{4aM!_&&$%@(EsrV~o=Dxs%}d3$Ksr&aA2~A`F;e>ZA+-of+D@@LS*H$A1P7-VdCKf z2D&m0U)BQb==6Y}okPTrtl3!xzlQsMWkzc(3Gme+nJhAMtn`we{)q~tfVBoby~{m| z4E(<&kPJr!!@`KvCh9Z$rJi<|yM0Vc%eu?;E|O|Mb`!hbBDtU+Mwj}*;35}DDefQ+ zHi_1?x&2o1SW35#0QrnWFS-abJQ zd`}D0X8asv2FnI$z9)H}z^C*#sC1$r&?j?J0r%<5xkCRMKEijc_M*2|x=>B~mUOQO z^YI21S^ch+h{=SBa1aGi30$0tQ7*1T>0hGFjedp&o8PMoC!0NbCcAMi%rgUbBABpJ zK2j}3G*W_aZE$U9U~UHS`RR=(Dt8DOl7hiLnb*i1w&zVymCk}@iD5qK&EtOwb8FPk z-yWs?EwocKX7(N;Hf@kUuOZ_b)2s&v8}%L6qruBm>aecVb*$RcC8%Bs?@ipsbQH|fNxS>X44B1v)C#QUO zJ&Z$ZQ!SIx!_tNBF}BGi%EN+eX`gzpq+dn0V(7-P<7jPooR-Rx-}@eX9U&I9u<5nn zWgSRie>#Oc-npj>^XA%yjCY5k$Z^}avK!Gbsw2>y7#C#JOR^R-b#uTXL_yHUy2j(G70<|HWN6t>ghx;&z$IhBuBjLwR%87|Mb)U_18qojn z^wvRbchUAY?hXZldvSM%0;Ncc756}JhvLPG2Wyew#arCnf&_}YOK>Y*tWbFK+~2+L z@LxzKlbLhQcb&CAYi~sLz5HtdTkUfQYutcyd0{Sz5~A>hW=9!ZK2{un+_7;xPFaypC#UKlV5@R>-)$Fi?M^t zhEAL^D`;#{WoV@71Gbo!N<43_bS?XEyN~1o+b%37 zBdgokQA5%LUG}<;4}!i47NyCrm_2o4h#f0FcV$M@)0UlDeDR*$7mS1Ns{&kA za@3R0TD;7d`L>-V(^KHCDpHcQ-L~E4<9c)rFQze!hzwK|`mul@ zMwx8rogc_E8Yj5+v&Dn->fj&2u0AST$l8(%*zyAs*i>c*w4d@MfnEG-dvkm3A)Q9+ zh^t}5Dq!4dZ3S#%$ue)7s2J`Y*tPKy)Jfiod@1ZMJPu|35m+VB8VOSzEOnJIaJ0ha-`!@~^x>|fvHe#{IB~rEB2y;A z2a#0_OO^F6yVnEq7yj-8D4CrLjg=NOeFw`|U1q*K3)zpIpE`m<%0iV%5bbw14|H;$ ztS|fn*#2&geHlh{woTt}R6rQDrSiTq?>{Fj5^BP|&W5R? zSNLkELnWjs#NNeS7D3d2cj1|+wz{%`oPDM-+)70NrUrpp`3dmKn77cr!R>2vtW&8< z>Z2<)a5jnXKU=@V>lnC4MAAEHa?JbPHmX+!2xMnw4gpe_li7@94jb=|07UG`tbep% zrU#Jf@>y$I>+yfR9fCbBaBcLQ1Xct6-rF#DAqMpFI%L`KJG$O3^mVc^v}<2*TkB8Z zgdKTKesE=(?|1fi)sV($_@CQv)+Xt$_3|A{8VSsG0edue%3u2*x1Y!C zo%CFsfsuny`!(Y_?~VfLX5ggD?J8osAwFdPF&Uu)n+*|9wus)3h@JUjUy)>6@_z`A z9Ky9mU1oCQ-w6$R^OpneTZlmMdj|7Xj&~{=eF7e%Z)OVNv|ZaDcf_uHLpuN8y~?D- zYq2{TL3h#%A?Qwj_)BoL;+g@<(5NO*oK)O3xeOE`6t-i|Er~G|;Z{GV@ndg1q$o!E zRc!kB-|WcsYCWSEdg58oZn(AtyfflbDU=U)g|gvDWQ<92|I|zO$WJ|nG5iQVHNiWL zyocdsTlWJ!1pK{Z3|HeCJu6dN7UgyB^WA@h&u3g zw9w%iBOMR(%X=gX=DOD+IC=6)nf<2Ard~TV8ybQUVpbZ;>?j%;S~i^=A>CizGlK*q z)8W-|8dPM{_M9`n1VQTdTFwG;?8X$RRNfp%y{J@i5^|h7L!pSd0gVfLMcFQ&2w`8o zyYd&7^xZvMcaDqVYVM#1Xj(EV1e6lzeopqIB1N=0+KFTX%ocptv@E4($(x+sz!{!U zp(12yHv3*0F&>^Iw&Gn&6V+6f?9+*`XxETmb)Ldt8x!UgOUsMLz?q!W*bzh?On z29C8f1nd+mN^lim21jv{V%r~n$8!r9LtosvUI1BP>WbS~bBf%3;0Sj6&R#lVsH|Sf zsS}=r>IG^{!_)n{FQzD{dqg!(#6IF*K~z;06F3>_o`=5Bjsy03%^gv8jL;G4}p2{SWjZfsnp9!(nir~y?j9WR0k`&n;- zG20=P$DKJY(LZRO37KX#M<#=+6~xm1lRV#4;Zjng{yHUVkf_iU_*0Q=;^-(7x zuI5wK-J5lTaJ$F-({ZzN?pIUQUq1ZVUq5h14K6vzyG0nHb8U!J6x#FnCBch>LH{B* zHF9K);N5Sy1PadP;|~nQ=+la^X#+0g27{dZd3b#7M2@K~i$snAmrDMJ}IAIadHK4@E6>SqvvlqBuUK_ToX#N)4XLiK;= z(7qNcxgd>miNx6f!-9H}eM&GtX_a%WvIg@SWn@V- z&T=8}gHzXm89_Fc)#-yn5$CmU^0tNZFTE*ga!AGj-l`u#H5+E7NqE5|st@h}CC3=l z2ANq5i?|-XxwtEkfR5=&tW2)MO&ZK&hSEeGY9#|~0DCEf=0{8Eo-V-55Hy#`XMU&|HLe2gDMju>IMMlg$IjQH<9)cO1k%|{zYzSU` z;FtN^yN%H>E$23Tr~*6fr6$^J<1`G4%$%jYb8`0vhk!2ndvS?fI&H|LoxHWhmrX$US;4ZAQ$aC zzE!}Gjrjxc;|mb?X(c-Y!sM=4=m7H=n58Te+&OZE&iYSeEW=XDC0t$B{Z)H7Tf3Hb zBMthfUKE{P-u(3kYz80%KR(5=#3n+BqA$Jjs;(cVi!}rNh9;Q$0)IoF4#f4^LOztm zXA{s2ZN0cETGFJ5CwlbZByt`YcIT2(x7`|0twWX^!g6DB!)aM8TP({SE`M9zcwCXW z>$r~$aDa7VzM&;<1%7;8DpuwtD5@N>hBvHtq`#tZL%rU%<{Sz9H&>i0{YbOWU z^gQX>1t0!bif*pibwUK)lom`~VjNsSRhR#%=g~@M`MXnL2a>DL= zu){UmZuM@I2<09XHw#1?l~Mrs8+?6ut(5|A-J7(ID;~4dzmNcb7{0IZk56(D-V8wS ztw$_;od0WA2N85w!q1z=8ua&nj0Bf9?EYMcP~kgetg2Hv6LaB!4x*6!A{l-w$qvTrL} znhP+;d>ZKbU+i27R#(O(%Y9|X?;2j9jt7>JOc&blp4>W$#rz~yj|$}t8yFuOmcCn% zsJ%~u*zWdfp$ zeh>C`*V>ov-mm`?!V||GV<<1?Wq1P!Y^yEjFjQHY)x?m+SG(V5vz>b7s=`|2B%40e z_{?kJ#l9HFop5vGP2S-3(DQEHTqbeRlI+ObNaH1NT7J4F;(fp-dDt3?GT56~#7o}6 z)irCL9Pgd?g-n8RKtcp^^m>`J%7DT}!k=ewZDV)7_|Rg5PT!q0&cm}G*Qr1 z-3-}$`O}43>$@$W_43FG#rBHmAtiasGiXhmnB^hNMp~2-zC+<;vBmBG%Qlb$!(eph zThmqZ=+)PMb!s7b&0qsjDmz!DN4esIZq?@Dh<(+4HMIl*T8ZO1NGL0XwTw8HlG!S-c3w6?f0f-ntXR#_nI z9hj7Z?~)bj!6X#i_N4A;v7>mB_?UJ|V_hlS{BsXX0!Zlgl}!|gqZ9$MsK9jb*P8YC zq#UjBfOBi?j25RM!}xEEIjXVuud~POM}WP8uD|vq%GU;ZjVD{;M*Kh+4>`bR*-2!9 zOt3dzp^_A3K@2w<<_NEfw%B3T5PzR0XAv}6;!pcnTY}CR^S${Sht7^n<4nObGgXPz ztEB^78vf{M-jl#LmXfEK8ozq-PxlagQSie!PIP`uc-zlbEANv>87*GQ{v6AHH;pw`P#wIp(00@GW3ynsofrNc|Gl4#B6~I&m_Scx@5c<=bx^h zijLtA+4Z2G@em;~qTDoM4kwdf8cyz+L?Ui2$mCC@A11}NQ(71QP?$0SnM$rquamQ< zlXYI+b^RX;P*Y3Q%Hc^%-*dttM>KO6R`MJhU%<4t#6mwSCI7b2MP)T;on-H!p+3rY z1B|HrFnLW6!Hq~8pwJ&4RqYm`_7ESAN)=|O*^e-L?^a(_N-^z*snH(%R38Ti*&C6D znYC?+NraslEQ3ldB9x6R8S}GVMbmmEXkElE_(IX^x>Y%S%z~n5T4^lPP%rmr$vTgb zJl~1vq>Fy$qtV1^%p!8l;K9QOV32AGX7vkNz8^1Y#W~_udE~ZhOHw21*96bL^f<+a zT1E6bdi@Z5tZJM$uHq}X$l{yKc>9U;-k6kc(2v+!45`~7m}I9hNP}i?%ska|(^4jP zIb^0M#4@<4hRab{|BShE%)??tr1m^Wk2yZRa}J!1UL)*>o|k=sl%IY{xqWH*bR^TV zMA3Zj&h;^1;^%LFo<$McP4mg11t;r{F>EaLdR|8R?}EnG zaz;$MbDRRt_ddy=e{V=t?A$Y)Bbq>tNnfH zX2fu1sleHrzVX39h$?}_|CIw;2&5}1D6IKv>D>+k^tR7VFz)-g0C1zD-+!N@n>v^` zFrFC9g+qw^CWBj6ws>S4)eZ`}=ofG!?x9F-84&a{U3k}B*FxU%F))y~0xgM;3*(Gm z@jEC*i{(&@&=AWKob9jsX<3VblAu-{Hp*)5XwLGdMxcNav+V73BSip`QX=ednX_O2Xa!jbdf`eFB_Yr)sp`Ju1&vFil zHCgiCDM?J{sN%xSL3gS`yIY7VUlME*rAAO3d~bj_d-8chUJ@~zs)&qylLaK_6fKot zp-d5#?!rkamqf!XY-s+D?LUEdcU1NnaqKW1)LT(QjKa;B(u@7+pL3OxsL$pZ-x&sS zlvclIhN8$MvlbTZ1|zI?wMD0oSa7E;su!3O;;4p5r1 z^iY#r=J0YRSm0|``@f)!@xwwZ{s9s)(IH%^$Mb>&^3@E^^8!d*(w9wOGJHtwPJ6Pk z!1=0P@AuK5+I8@qJ_V5NkHW5XI>Ru(Os8t+Ou@f2-o#tEVvE||?6R`9x*UT|#BBh% z5#wovk2;&=$B@1vOdvWg|CL}jjS_#@n=_S5!+ldc-2nbDK^4YK)7m-d_{ijR&%VQ0a%)P9ObVW&Z4CEEor2vIwj7lO^(GNHkAwRio(X%c{7 zb!Q=<>Bb+S#F@=|e-o}eFQU?Z{xbKaK5s$vOjsC_ki%JC>=d4g5SfP0_n!(N(N)R- z)*n5@4DkeL$6{sdP)TZ$AFA-B`7sVrT(b2X3G`aJF%PaWjs+Bfn|>aBMTmZHtQd-= zF)4XB@jXe(AXisG&x|emuUok>!maT;!dLju%MZe4-PhU)V-tdTwqQF~bCEpj{a9hU zBn7u>zd%{S)L>8X|duvvL zNduBhkmXNgCIS{`MwXC87ug%qrK9-4s+jEjp6Lu8B1#FhXlH5c?#X|d3KRN2Q;ZR% zyvNfDp8?PHo`>F0F%1Lr@G#5w_LI->FuPNU&g=|Mh}zKwnMoM;+VCufz99*I<-ZmQ zCW>X^#j`?t;l^Z&())PxdqE$dhWYvhrC>vyFUeLH0KiI=BGTvI zLS?eMFd_wBV=Cn+j@@lfbVJrq%m#e7`IkR3g0Z*n7|}P{h$CVURaJXBdv8oYJWrHU zSXkd;jH^A>5_y4@HI^8w%MamlVT>5C$#+Ko#Obw0Piks(a)eLOTTnm!SP~i2;t-Z#H9phOS5PLTB1b7r53Iq0U& zO-8pv1ixEfv3c?%tF%l^MUh7^nSmYb`c)e*@|!!zo4FSC;309PaByMwby(<1Uzorxp_vk7KVI=K_;|3}bQNV6;Zb49f{Qn5^)#8` z2bEBYR1Wu5782_TBXh$TTRQ~x3nav*(}?<2v$c*|u{iBgT*n+v9f|(n6G9=EbG^u| zBpl$y_n<>gOn+Dq!3*JIz=0;h+3I$hOWwT>1k>8sFMf&h!06A z^C)t4UF#-xw+*Wisc%g01M3Tmy;m6f1;L)uXUULg)uHoxg&jl{rV!-JX*IeVU%u4#G|BR?(qKEKwpfWw`_MWkve}RA z$D@WxyiPqLlR1{mgpN%1)5`mC!UR;v8x2SJvos#|X0*v;TR!^|p$Sx9s!If0&ModX zedYbnk#l$^`G8YQZ7BFmsEqtyvL})tLBGG4I};YKgbot}hQd9_{EW9pr|+dN^rrWZ zBGD6NsoO53&KBW^pQ=myMaZQwm_5g-{L9h=rrHHEnZC{WvE{>m;ySQ+5B(eY1a4sN zyY0i*Z{`Y^;4faYB9n6ANHY9v?sD#mBmPcsLC8ZALu{H$^M*`36N*R*NXU%-too79 z(R9ujoB;^=PEPu2__Xi1x`Qk)0G%HB)`qtGGnYoCSVdQoV=p;n71Z#H*<5SsVeRYQ zk2b$iK9MXFAlR8GN*E=HFy8UBCTJlsd`+t|evzAJ1R?|(grr08+>PCJwtwseNyPDq z;dFaDM%n${X$~fI=mGR#boMOo(q>$nZ;q@Pn3#TySXZ_**auExrJUMmK+aE6>!#UZ z{MLs1Z1SZdlfeT!$usiPOAI+8^QPQtjd=UIXCAN3D+2H?(Ivc_RDB!;?rBc0eMWLi z+axS)Ffx^D<*QZKrQH@)B{~H^$WE|%WjUkuwjdV`+}tkk&9_$~cCRFS6WPM<;t_h^ z;=5^`zka;aKJ~xG{+J&wUG%eTibdz$r^h*cdXtimEXz`|yFS*+5!2Nv731>h0_-Wj zt{LDAd-AG2v%x-pxaSj6Z}QB=Xfx#33Jn59Lu;6Y{^n(St>$N?GhSbQ=c4bCrayOT z2SkvP=#rQT(qAL7&c+e&69w@=Mr#ZJcq%c?jb%~NJxD6F#E7e1pv~NbV0V6t&S}U% z($CzlzvK7!aa>}Xzhm*gwg?$V$%O}kRzsaU8u}D3{K1o27j~H*HSDGBt|Cb{`^urXUtYhnmy!Y+z2E;r(SWbgdE zbgfk~-5*P=_u`6UlWp9SXzJH!)uss9(vIqP#8^OME?$qIi-P1*-rMfk<%n1^AcdIh&5T_nJqPLO@uhgNnt#qM6OUqno9TleWm<*RFPK8<5XihSGDIL;JD$lfd_8>-4GCjsI-B1S z)D>=k8I5F2fX)?`_b++!IsEuq8#@OXqITN*Piwu8WKDPKU1YNsxyOUk4HHI)nO7m^ zYre1oB>`JSa;>=;uV^$>)|pt5kh3$CDit_L@Y&@HMdoET`cp?0B-((B$_Tq5HNs?) z!p4Yv%uO#F)u>d3I@HUh+2P=c8BP&elYGy*^7Lmf9c{y&SWC{vG8g5$3)jZb4H8a? z=)Y&y+P>0_7Q>xCjyvnCgh#Bz&$#Xh08B)J`5E4qyEpFxCr+^AQC#-Z$r5LXViHzE z#Y8`b#_KtGGRT8u7t)Aq!XF^3b}RgGVm_%CC0GB%DH@`TI<3At^B#sl!%8K%tz{L` zB!6)iW6G(FS$nHZwWeC`$%lfh$ZS2F$jm%3c}y~X22hxdu;HbppY$?Q@!{lsz5n^> z+K`XP#D@tDiHnmqx9UTgbFdA6=lAH7$@V>IQi}nlVQ3_G9wB7(5euB5zHhL^f+2;3!&%>*W{-Twv4lXvv4{>xYSt^B zpwbVsm05}Ui-^P>zxWXRWpX3??YmETws}2w9d*0idTHg2M$NXARBsv@3!p$Kl)(g% zYxu(-E^%7-mN&Lf(9beTc3hrM4|N^CEK_JnSfhpK*KsL@@mQF)x*=!B_gd=gag-Kn zK1=Re*7>}&M-t+@&y!D=pT)L8`iQ@UuT2A9@AXtbgI9wIfjxWwHtz1Y;|f+7#?O|B z0SPMOU}C15ddoWLd|TNl-HGwppbl>D7=o`fEh9^clZSR4k#V#^zlTY`j11uy=zWO_ z01i|tY4C3rTJJX4t8@tCVTbK0R(?TSo%C8M_*IA_iAqbpk22U3@@?E@?)zPk>Nq-O zMZe+L)7pC&Z4n5p3bq29*sxGBgTO5JOIWTe0*Zvjo&O=-d}C#kJz5e66gJ$Dm*AC) z%~^ZjOK9n=6emGzfF61G>aDzJM=lO;1&L{bCq>HTt{sEEwbb zNjM?;tW!aBb~tO`_j^QsXtoj_(q`yY(Gsi*^Z|YtUc&s1{fel4fUa%Y9$TSCaas($ za8%QH!pO25tstXC{;ydM*Y~vf<+r=Hlx^c+snAsc*EdI>`Cxik=3SOBY$iT7hB@_K zkAX`fKMptdZR6NT3uH=v5KL3N*Ix-Ho}vwgqA9XZnlMVXa^%>cdHq=bbTCno%HYa{ z%{wdV&;6btbMzIz7m_9;1En@ok?-IlmYJbOFR}onf3+U1umWg_eq*R;!;O4gEu8$Q zNHTo61!-rXA)9%97Dl6iL9Uy6!}*m4Jdz$dS&^rzPGD>ynzYW#XdE61XNZ-!_8E01 z1>q9i-%h=z_Kfr=RKH?+h+CD8PHtwa{ zHQaa;N{uTX>ZtPT0#}UF0UcN^EInq`jHqF$4I~oER)jcQ$l)n>U#W1?Y-+g46>hQp zPD**rbFmor6eY2C6AG0DJjVPU5)XZovN$0#fm{|Ugz=iVjDNy1M=?im2mC6>ctX4_ zC1n-*TEtQ0*7A3qFoljy4Ir?nj!)@!gfaQ?;?kS%Ai@ew16enwfl}9VX-Cg-(uhugvmzFJxd&pKT%R9>C{6mrD{_G(?MFYm|07ZHK$< za~?u%SMR%lsoFwGjEH$R-@u8#9#0Qd+9KQD4S$dIP+atDEWbuNjM-rf)2MJlI;P2& z8;Z{mTrj7beV;4EalcBr$#x$AxBc0*ckpe%6H8-gm>b4KF#OYGveCmy%T;?g=E#5F zOy>G1OB_81>mu?n5MBX4U;kGa=b^PHq%ok%jHVJ7PFyjKhyGY3@D=K3rC|ugg4zE) z!@vTU`Cl*)&^lygUl5f3%fUVMz{%%e$WL+(5!E-Rg=z3VOJ{cS!fR9fW2IYDfW_9$ z+{3X1tg*6rRbP7RahT*$xIjj^(kfI=z@sUX*Uq+ler7SDErDh5!E3@u)LC-0gK!Tv z6-kFYWk~||LLw~fCrv;gACef?u1926ETc z;(Xg597LUJ4PGqK`p9y@$dWjxhYX4g( zx|2?|CHOw4k}94rR0x!lBCaVRCNzQd9?7l}jt3|+b`R*-Z>M(nc5k+b1j=1n4}h^! z2=g!^50AF44^r0rPN$PD%ul(`r|Vek4rp2R>^g$l{UN24Q{HXLpqA~(d~kJt6W66c z!*1Dwe#^w>u~Vxsrr=EO;OfztLgTzFXh_bzts*8AemQvLVBSu~ ze}l2@D?3~uX1FJ608Pf5$*6>0hEk_CJu=WxoRrz2?q6rK}v)rpl_?w_DGiHkzST4#HXdl~Ip&JNG*0G@4k?nq^A? zs#8ym#1!;n?>W$ChOhZ%)@Q~Tofe$5PqiEN+xZL#0mq4GfsE?b_~G{xpI5Sz`4)s8=nRt&77YJpa_D?;`rEFA_52`o0$4B?oi)Dh;@eVD z_y0@N#vnHA@hu#yviNgQNoX28D(CvBPW_(Bj^my#aMf}G+#H)pfEa5fF&cELQ*CD* zU!pMGu2nq|AQ@!1HMn?{KoauyA{fIWcJf2&6R~&~a>xUXU`BpaHhX5f!7v0S*GnH$vFXt6VXah|BE*C`>?B}RV(`I_I>!k4C zVcPCj1zo>C73uv7eU0{ZT>S4a^~1Mk|KQUK)0)&9yakY{h#(Vb<}ef3#|bc#7q_-l z8zxY$%0o%2{lz9m3sq&@o?X!ND7$6$b<2gv$d2DamF-14dQyo}>~d(fUX}no^C^)u zA;Ubj?MUk^&a)KQtArbEX2ylMuUm#`sR%w;qm_b&27$lCBxo< z?|9^hM1{{?(9osd1lrHdHR}_cksOAaQ_h1w*BJg}LJs+EqNm?@^p4fZ$Gyz=*&k>0 z`i=K-=RMOKa?)hIJ8HWB9#_;*>wlH`!!5_UQ)bh7p164svgvqchWPU4>eqCR`3B32 z`hVaJe~sWn8bPDXcgtnI9Wuc;K5cW+L3i_uAHPRT9tYy*)q-ofvXH?4-sxHd-^?%G zlwrzN){HR`;%qq7PQrbeo{pbrdN!in*INTF`U7aU-x7sjio3vS$k5MU;Mu>&TwAJY za*q&ujMGs%^pe>RWiN%{^Cjxt)z)XGg`0vm^wYHd&`mKvq7TylBHzO;EXu80))xvs zl;`FCQJl0b0%Q@ORD=)5hZEzP6VVSqbfEDF!UaNuCy1;Sb{ziNCJE__pw$w+unk9M z=T|>u0-`_GR43$R23xxnMFg#2>BVD&n-c&`Y5)$H;;2Y9mP$h1?il zHNieASJ>9!DeR&}Uy&>7pP-EXvijsVh}##RZM5V{Y;D9)t7A7Hc+5Ji!@*c8z3)T{ zWLJPuhjP!O_F)c)S6E$sqi(X3VNFiF*ybP>j}&LLM>o_Vyq`%itc9biVs8i;kk7qk zoTa+3wPeG3H&(7v$s?2j7;H-CzrL8w`i(ag!*5Dnt}MYKbT5*Eyc0L)?&nNOS(~Oqyc!Qv`UBlUtnfx7+S!|kRr>T1fAmr8H+i~c;(B567Kh!Yu$%s7s z7i5xw5M4-sc|mHd5$CGn)!)xAq>jI-t^HWF8Ze5|rPf|CNZLi1`nrvhU~K zso<$4@$@h&&07BWGFaMjEn92g*O1H7SpH;u)jj?QI3d4D8zh_m?5fZ73HOYay%tBF zw=R@|wV6L%5#2J6+KW*uRhdInsJykhp95yY{=ulPwL6~M`i$Iu@XQ^J^j!e|j}Q8swl+2q2`JX42H z&E5r=6>+7U@Q9|~Jjawd+I+Z;T*3Z~0~d(zMB!RYG6_1l>7yXmb?qlqdmCWvLWAP$ zNl;U%8|tfon$maRq6rS8N`8yMU8LXVKRVe7pafSTgGIYA%9SI`+zpxx`T5uR$bRF( z&E7Wl&^{zFUKkG$%6QfUySJ=*3zYZyjL6#aFm&J$R)u~lNAG%E@&lWibyjTny=mXq z4{I3xT!=F1+HBNq${*T4q$jlu`tU_YjsLe{m@R7HjKGh+dUea&71^@hg0xw~@X}TQ zR0HMb7({^O63P7=bQ1d+xL~!vKn$v$YyYE$G7UuJ_$wBGHViC4tcZ6|9zUz|l|`BO z2#|R)qToyU+Ip8&FcEb~48434>+A0VyH-trZkuz>b{QW;7h!?&F|50 zQq~|1m=WAmct8B!o=lDcC8Y5qrT+sYVV`OJpej;T{*`R2P_mNp{`Z_j3Fm^y2nt1% z)ra6-uxWSt?MoP55s~ni1-ti70)Z62!~|clct(CvU#c?+ACkaYI}LH`zacj?>+UhP zo_?`p)gk8tw{%op3|vpR6{dEvj~;-2;^N#}o*>+0atFk-37UVg`GV3fo%xPK?8bpA|`|2#%6R zrOcpg?4?XGnLQ801~W&EQ@+7d$}bZWaOBW$8tm89lkA4pth2vh6FAkOWsfgqIqa#S z*p0LC?{nAMPo)dEOovr~xZ!obmahysC5vULyhtD=D&%3FiUKXDD9VjdCg3}_MgvAPB>sYZ0GgHH zdR_Mb|4gBehx-L(!em0xK5v11wXZ1yU;XO_cP(UxoR;{8@H8^?ajM>>T5?j_0e3Y7 z`6QeGx~#R25qBP+8k*KSk{pV=#=aofF0S@pAH8*JJS<6o;gDx~7(Uw=;8pij1~%!2eUy;9rO%Peu)`}@NHd)CozvQR)TEAL#>H`-kNw^VmrbFs=?C( z?*>vWCs5+G8zbJ_>rZ|Ry#7^BZ(f2{Y*LEZ=>oq_a$O}w^MIl2vQqvZ3ji;{;>((J zN!qzy-3ce1lQ7SQM_w(-xoe;r#WT)BYQq_645dNc84@-G_%!`n;5SF&1n=U^1H7+r@{hugwO`r*?*~xhN&hzfwDA-dx-8L|aupW{i7>b?s`^v>%D-x*66Nsn% zkJw-g<`@Hs8;Ot;IMOCcv^M~mS?9x}TG%N7-;G@&x$6zK*C(%p=DPA9 z-S`?DQ)~w`09^6PDaJ@9j1-En#8}Iey~Be)fi7Gai%eOU1~@by!+Z`p3iGyW=Yywa zR6BAooiQtQ%7vTERlTTRDmiZT&l1#j1-vnoV5v&}93WVBsR- z<8YGggTD|1MEl!J+xa3$rfU*Tu=V|;OJ@t*ZTni~yHvDB$mYNl8D~;eufHL61G?BP zujA1RsS-Zi7};0$sgdoPs)Za8C<`y%N*A8&Lf^5iOms*Su%So&x{L}95fi6NAk7G< z*?oR3EG{_FtyP=Ui%j}x^LucqZ1|a|^&P=k^~QoZ#X+c0t9HLpTgnIrScrVxbPz0* z>9KFol_DgS;6X22x{{HeDeTqX2JxpE54e1iIUf90?$z3rBd71J(@{2(AMUk((%>aH z5#=qHq%k<$#@{#BWKHB-7jO~t8CT%?uSz?*)iaixlvPg9vyiap)pwG~g$t4^QR1lQlox0(pV# znZ8O9OoM@I{7Q%vvkEd9C2b+9Q<}y#3Ik?nwgN5v3u{sAG`|I^YnkT3P}HZ|yDaO| z^O)`Vm`${e4)RcAT<#mq(dtS9*`kiIdk6Rp##_y&UCgrvxsB6LW@@xSDi*ddsWAFp zuXisE1CR6_(VN{Xx6_35`rQ^BLEd$vX>VFbepr3U^U=${%g;VPFbVEaZ1{(_TK|NLaseU<21m(CT zx30p^yn`Hj^HJWSzl~;oDUmbic#^y?R>=l5HQfmH`jJ7U-?9r?e4E>2`;EFE*!PAw z%fX^3{q~DmjB^yFx&V~;q{_Fsa3-d#vWxw?JSb`Q@eoDKFTvquIDa-i;*pAJ-W)=$ zPF7%9>OvNQ-augzcsZp_s}=2L0OuvGL479getpLQpl=yI7r{xq#W!y*i+JnvTEf?= zlZ|%KZQvm8HQFTLDQ{pXdXWC^F{Yb0Z6xT%RmMI#01Hf}B_yE6V7TS<8rR|94rm^7$D6F-04 zrA?^CQ?JZz?7FLoh1Bd;KaRz-emChoal|>sGs*p4Wk2S|3%SY4-u{gb_Md9zmHf9G zJUeg0)&_biDLPwv9zyoKUr0x8@%=qJkLOm6!Vj7O!}WCX(rhuw5~jYrOf^ZcJ50Wr zXEW&Q3mZc9UmSV6c_ioRn0}$WQ&_zLQ=V$>o*X7=l|7_dhbqV9e{epuzdv6@|IIcI zp%9D^;G4iq#I)x?9y($rLXqk9pQ$YDHz3oQmeA_cLQ=c)4`q*fn{H%p3m*D%T?f`; zt7cXik0+pUb^aZXNSy5OMmRu+Sl|07Tws6Z{-8q-i~pg*iLEft6kFwp%*SG;)JRGL z`l*4XHsniCbja3VLg9{YP0l=Gh=Xme-M6Ve+=*fN%@1kk$L z*}`HTd7A7WGfDt8-xwrw!vRbII zzsU#UXeK^nbzw|QCwcd~HIIrl?>A4Ly+4L&Rgo^SnuY3!@ zX0@k|lso?LC*Cgt{AR2DnNGHe(~FL@h=&+1&u8-cM-qBS{(($J`~98q?5b>WU8SY> zcjynMqDTR{axM92j6^o95lRB=KiSj-31ypN?YAqvLB_u0+k@0zM{d{qi>uNp{+;$f z1(>ikVvvNR2>CHBh<9)8ISiO(&)r}E%VPr0#NnW=DX1WD?b7asfYo63us(@0n;QQABZj0& zx|Q#%pu6Kl8|0I962Vi!8AN4FIkmmNq>gjCR~D8H6cGm~?2yj2>>J#c0J%q~IG@sY zD*L=ixA;&vZ1b(O8|+$J`a{CO`SAT!nt0TnF}Z$(=t8x_t5%-gMXFAnZCg;M+BSI* ztuZ75YK}I64bsd3hix-i?Mh`1Rer=g99|oH{f`c>aJB|}|KyZPWl~rWS@_j2#ZWYI z?yvnh#uf7l`Or((gf7GY99T7*gd>`Yc!N9y{RrHO40lt z0+n7Ak=QVzIz>E8W@dgpMJX0GchXkvX1A4D7<55Bu5o5*SpYMqlBH-6U1gr;Hi z1L89F>tL}V9cOSf{OxF_QS9!^v!9c;VYaNhCyyDg1I$H;(Aa#KWqWSIat8ZH|-)>x_G-|#g`Us)UOOe|%MDB7?sq`(;PXe&VOz}3#DGXz79 z4OgL3Y3B3SJ3G{$`K$eZ58m*KXH0~7`EkGGz)fS0KL0flo>;)0;O)z-Pb!Cvavk)^ z3c2d;l9P%li@}%kw|#+rPt^_wNiVG6eZ`_Ne}RaPD!{Z>1xE6Ed2`BXl+l7WJc^o8 znc9R?;O=wrRP?Bi{M^7{HF*0{cH%mgtC|%H(H8k?03&v^TpItSyh9Tp1CJ;fM?g?dogFWe+SXkkidRO2z%mb zlM0XT*hQTOg7z(svar9MhlHQnZ`z(*UGHCw&phRTvDsQ4-UOSP;iy!rMonfOC*L0U zOh29+^fy>t%W%Bl9h|C%oeO=m%6?W@T+UXjsat-YYigu#GYPnN(EOCOX6n6^4?vV9 z`8*n+JZP?pWi=(OmZtE}^up$ii5(+Ts2C?J+`{S*5C67!2(Qx+(Qi{_cHwaqZmfDDqIH$%3S zL=TiOc35&7@_zBO$jP#Er8boaVhkZCVE4)&UKsS;lCuz5!nn%;Rj0IDtfrs~M19SR z5qjTD=-|x#wJAYB};^m!-$aUM!r-RUIKLYJcdj0+K9J~5(2%(A| z--|1iJU{hXZ=iW{Mw^!rc80Og0v};R&`%AV8M=8wWJKt{5QR|oR^@TG#P78GQ+34T zVH2gC!v$zy2>*EtVPu}4A>8q_vk=7uL>m%E7$ejd*#eC&Hf2cmo=wWDfHEYr0mEVP zbHdgksLg5pz&WP}W@&Tpsm;*ueZ7Qv-X`L>4)L-4O#_hom+<{{lTYgu8#QNn2KTH z20KCX1$2^cM*sc~ZTA@P(!ZE~+q2r;I68iMf^(>I7g<|Em7n`N-;5+e@W<~==NU24 zRc?!f8*hYxjF6cK7kR?_qQ8Bf=>_1Y3=TTS+_a%zKNUs1{>ew?QtPpEq+4`WD(TQx z;VBl*oV4x~;@h%1YhaOK5OAbGiA(ZNYSfjao6x-#{Dl7*=~CUx>#0XfQvT3*0a0A~ zh_*os$7ER%d`^H<$oeI9)vmgnoNV7D7OkuvUeEzvsLjFuppffH`WIKJHpKs&fV2T> zZ^zCODYcQ*YB=B`k|Y32#;^IMS=QOAEUO>cOp9FWp`)^R zyVWG@-GGtMGfH$Uul12fiXyB1s+<${iAo9+P}_$PKPSXdJ)f`}6M51xlt-hEo<>ewtT0bEv=Eg-vwzlhk7fJgeP z*=Rx&)5liC(rC=oHkqJwi{S=outRCo;P#oFY?La(s_*R7__c8fNKe@+ZbAt^%ToV; zG@VsIlnu1C>7l#3TVUu0=}sjD28KpjxH7?5sIYG^5GY53awS2l_D*|=g-zJE&I!Q$28=aMm8=YM?Mm6Y>-)9ouqOs;8*Q1dp+rU1e zjFatwVsS4hO^bCZ9%cFLK5t|iV8zr?zxw#&p{@iph;mK*%^BaG8W4N&T!Ee1Vmqow zo{o}2--;0}{n4@9rt-p_0@cRl_0k!LoXBp?1?MM@=t9&;6f`sT`<^>x>Y;b(O@Mtf z_&%>cpGw&&i4eQTbZcq+wl*+E?u6p^)!T(l@V5f9tLG{a_>vJhRr&~LUCssd(d*n! zJ$v5%Y~#G_wx7{abFlnR<4}+ueg>5$dR){kB}JS6v^7?8oH(3Kw{Ku|)sZFJ~VDM;Uvb!Kw#jj4D|;jcJ~H>#4RdtpuacO~kUBms+FEa|f1yQ7B@U~0;D zw)Il`Cwc@CsVL5Sgm4i0wqOjP@0+)ubmrfOJ2yz~lzt4!yUP5aYlv?kyVMGhw9*-0 zac_?aJ*zk$ks%3ed^1lIYa0nt!HW?WiIAj-CU|Adn`e?XMU#cfI|}WG>Xx$!-O_qu z0a?Nx8`14;Y$edL6#KO-!R=PX0d|@Hju?h+h3vXc8ahwz*4*Y=Y5_@3eOXj37^R;< zX(L}zO1&-<^jVPmHT~Owxv*;WKam5f%fYo9KbWGMC@;kcgZm-v#5S?0t^4RruX#DY zL|*r4Y4Z+7ehReptSEOwRIL4}SUns{>j_hM8#F`bEsW!h0-kuc2S`UWNAEH7c@qI0 z^*`ST%%OurBh!y+X81DkLzK3GMvMq`sN_3`l8-8tk84XW3saqiS>ahqZV|B~XA+}? zZ$VK^%yU?|mnF>nSeAm@tXrfJ+f@0J#{LHlt-l{JPJJv6H!DPbReD!2`;FcLFw!G+ z^P(hru{$t);rk1hlvC-9@JJGjVH&*WM}uL)?^OuU1iuxpQwc7hMSAv$?2WVH!PKD% z#<=b3cVLw*qAFTbN4_?)-dXq|^(R837!VsyU(MQbNu$-(50~Te&;N@eaG?)bX>UGD z?)u0c&_qHh(Jxc>(KspGTE*;>RCpR3NhjSZBzk}|lbvnxY2OQBuHRjU78cCoZcA7? zVC?le3DqPXE!H`&fi_V`t)Y_H0HI7MyC#TW?r*aZ+)0gN$DgQWaqb_n#nnLbjw&L~ zmHZf$*lKoW2?Oq*x2)je_nM|md7H_n()bS2gq!bs_7nYx*a5t9#)6 z!pP*dN`M;X+=t2RzQP*$K^&B^k=HhRMP+sZ{9^oZl_sKab}f5>V)+SX#S5@FGo|Kb zNz1Skk$4o1Z9e)W)Dy!~17@0#4-^NB=+ulinb3T8@|p(!PG3en25QP#yMOSwwV?a%siuX;PBkpHApPFbif9e*Ob-x^_ZX+)&lcb11uH< z9YKQmxBANns5@aE6<^NkHA@5dNC8ltVGjh5H79Sz;x&EEgHeK|I6p#JKZ0q)h!H(L z{9rv;yb3K}ambBoW?n!2$_h?EdoZBL=uWq;_^7dW0NrPo1P;yZ)R_yNj*W$+diB

    N21=NO5|;L$t8J^8F%ZLxe3fN= zKSZ|on?rW`hlld}mf*m_shm`ErB5`K&;`fANR{x{QG`Q&CclL;0dgTpX?ub+qU%ef z8p$}u_Ko%WhOu6H9cMC19^jRCZb&5BJ5KE6akk?5YfD-%%fNjL>%vk4B&Nh0uW<6B=bs2oU(Uy~p@qy4Fe|-uxi!LF;MefwG+umu}x>i(X;m+||4Q z43?4c&>}HSKuA^cl>dz`^DMi-EC(&4x-Y(;RIM(e814}{VCJi6F-?w&yYyJfuxwW| zJAh%obS5ine$?^XI(rdCzo$rg^%l>V&->kh%DhzJtn0NTKX%V00>dr4weB}^QvLpb zGQb}F223jUjVi5f7zVZ-1YvFr=gZ@&BeJ(lX|wa}AzR+Pc*DSU;5%WlsH;37t_HOR>pnYYX|g@ABGQ6>7x5+jpP!;x`GgP&AKp$48iLDS%5W zS_PzHj&rCb{9E4r=%}t_ls>ObNIkmcbr=FwtT;BZ@6AZ$0oAGcNiHf*%dpBhpJ7~>s8ITFiY5X%e;k13IlwFLdyjVPDq6*73Ho1SP9Quu9L zfs=rm7O`C1AKJg(Ofd)3CX{;b#`(Q+=X_tZEiR*2?Rwzisz^_=n>TK1Cbi1Z zY}6L@?~nH`#m?@O>5>^7ZiBz%G4$YNo^O)dRHn5S(2T22)#V6%{<;uw#|7Xt`;}br z8!Kwau~}2Gu+hpW?=C_u6rMi5{?#*4aq2KjVU?|I1=1OAynWg5f=xSg>rZ~W{ICIP z%Ih_-D*F%M@2q}0&qdRCQF$~IXY!wf->}Nc@;!n%{Dt(RAIrM!oUA*1Q6Xo=6!_2)x?ZH@rH2_LWQzyb@D$fo8$jjHqF5_ z$J?o?i%tx%>$W*Rd+)cpo?5d1W!aesmOW2Nvpp5zK;ONz-o0`X@%*Loe-OFKyrSw= zE~SJmY$Y6bn=9@{&X=G!UQ=6=#Pu>sbt9$-MNm? zI!gn?_KV@pOX#ue!_$9wo1zW@mei_-qQr#*wP2;6;a2ZnsVIch)WsAn+H!2G+CDP$ zRa41%2Sp9v*Pb06xiZWyn|v@)=MbQ!!KdZNSwKRJdQ#*Wu+~jvd$p!-tPB*sR^eC+ zY`-Pmh=Zn_o05dRR{KO$Vx1Y;{RU(}?sO%;i?oP3Z^D0fXz&fdaQ0oh;s);mtt!cs z;zKhuUat|2i*tpN&{ZjgV(Ggg!QVH!=&?Bv6^}CmQ;1Ls95G%U2Y-n~i0!jij7|IM zV<{ej8sDRvt!d+5PD!PQFItQ=NW`)ab7}<(!Coj?!mQ6^sT@4NVrLN#Au050t;^pD z)@;5xZd}-kJ~>2a{0uh+Z@)2rEy+_7qgVc;a2KVfS}0;?P;UsOKWtmFxu)et(PfJwbDR6?eLctVU-QZSjY0haN)}lK$v$Ijc^1 zOI$wEn(gG(va^E2U4F|@y+=qsN63lRQ9pj?QnvNZs%?Zi1SAOannH)djkZz3O%(RavT#~~YA0<7OUyRa9BYcRzSi7cu2waU`db^w3 zk&2_nS0O56)tb`WD{76ns54P$Zo>GuU|iPN#Vl(avN%3|!fg}*fw&*E_boQlseeGc zTgnwY%C_qeJ8#TcVW&b4pk2f#TMf^0c6;xJ+1SVH7DrhxwySB?s|D^`5qKu$X}}fz zgIMQUdC$9rJ1a8ZHRPPDJ7`A(_y`-bRwv?RVjvGxL~Jov zdwS-V<2ZVZ(&S=ddtm?ZF1PFoU;QYgo9JI|*y3gQTMT`jBy*{X5u!^c3lSD5Hp0>} zfC;CI5Y>wL%)#3*zh~9n!`SRUZ4V&y&rHw>J`$_chmU#Q=h#u%;I22DZ3q9S1<1ds z@RzX6e+RQhL!=B-pR+;uS$arOtc-TXP9*uCRytjsDP+n2d*octeZ+4c7W$00PU4I;bJm@buyg``*gturKXAIHU)WvVnh;*p5_Ah zNMc-PjcC?6YVaySjGL8D=Q#bJi)m`3tnnbh=@NQ30o?)9p%5nKCJNIo{~p?AB6TFM zac%rEQbkk`ld>0Xy?|Y*<)+{Q7uo&4X=B@oKR#CqCch^0f9+R@DeWqRo!KA__&B6M z+AsgSmLasP67RPta7ZbVAY6)S&p{0J<}pJ|W*q@VE96+uEX*UAMm+=;VA$+e=LL?8 z0aN=332&B4r@O+VHv&n+BRL@1=vMEnToI)mRl8M^#M1^f&LupjRSUmvy$G>nG+;*f zdlt$8EG-K$F~ILo$Vf`YVz0SG!qYjOPzkL#so{IG$Z??p1UWg z#+892#9wJ%;GyNDlwA#l%|6G0@AJQn($QIQy1q0 zqt+`S1u#xg(9y-ecr~r10#gEBqxC?+3(A9!vpbU=NAYAzD=1?#{S(0J3Yww(R&?Lv z@86G)P}_HcbZ`CA%Kj%$Qx^lds?-W^4XFnyyC2qyxW*e!8cgwr)0yeKOIyi% zo~_j3Yh-txW@#pZy>eixG35yK?I1&%4VSG;Bt+7#LYCHK9U%RoN*Mv<n{Y7j94ham6dxNC;(-Ihxw)PaE0(L=i%GPv+oedCmM}u1H`H zI3@((Otp5BKh&M{;fjr=uGm;A-K=&)O+E$WGk;MFH5UMHvHH6WBq9NW;Z)tsLhH_F z_Wgcv?@y)u{_zkFhV~Vm6JMH#j%Odlq#ibWhr#TgdTtMQM;^l{B9x{}+-TExS;A*9 zJQ)(T;`eOrUptT#fgASe_s`r($Qp@QOCX4=U}-z?SJQ!s!wYeWKVG4{q z4-RjD+X5ymY}v zrvkT2eW$fbJul889LH64HGcxPKK~2I3~~K}7~t?D6PUm@{+`O*_>_JnxcggGSEWWE zTgota%O=!w=A!y8Bodc;|sE0027*=ZD@Be1?Hf!=ge0T342qGM7F( z_-G=Zs)7FGp-&;5h8$Z;b^OP$9sbjMz*GWwV9CfEDAFAM8+6*wiVVELCr2_22Hq0e zVVSq8eW7qUvWTL9$Haf1{ws%RjtUrNwVBSqeaR>swhgfv>TsBO0Ep4+&Wm%Z$%CCt9g^-%iFB0fYm z9z+O6P2i*OAIe263gOJ7;%W+Gas@Q_$%=UPX(-7`Xg;;`WFgOv}uS%|Cd&wOts5q5c^Wu+d^PAn__gv8Ur5I3{Cuk$0qH_7#( zLs~LetHm$@;(Mrt8C?Tn#ZV!B7q|=|dc4mgg+M8Z5V1%KGSE!{e4(!CTvu|j3)6bE zX%b%0bLT4Ly=?pth?h$+v4PbDdk;wsJqtsUw;IsY^@4?`lLSOq_VEfKLRDlqIXHeJ9Vhlm|0rmM9}XeZ-jM_IU>(X2CdNjKVxc5O?ezTCvwn9mpo_% zBRsM$L>q;%R7g5}>U^5DccV{jL-6;4Y;@8B&&S(fJ(f?mkLd)qW7gCTQU{fsMq zfe>+mv+rBv&LRj_>Fs*k((uHjet9$*GC1Kkmy^d_9*jv=m`|zz010=O@q|+If}a90 z^lT^0nn6ebu5CSOiFgEi-kJr|S5RW6LA^R;Qll|jQ;ZbzZk0ew4qRdLmWGC6ofXnj zE|r{5jv_Ik=C2Y=jOL?tTAT+Gu51jquZo$$ONsmPizRmNKV$#!QNX3=@w^R}kY1vdYU*{7#Hvo|}Od2{4Oo~REySz-Z=u#$(6)6q;NF(E-c z@DlRQMtNE=*|3=eUYz1c!YH2_eo0jl2TWn~+dk^rp~e3soo$oZL~f$MJ2-;PgnY~* zf+NgH$p)Th1`8IsLs2g=G8U1KdH0OplG)&V8JWDppjrtSicQ@9b8Jr(6i;?Jt(#2h;FZ;ts z3ZMikA#xH}=7vp)p@RZC z$)3RAIU+{>7%$bFtWDX2q@JUnM3qFkAr5tAsk>x1JP}1KhFkkHGaG1H+d{E#!rYZ- zDXDi-LoK@Kq6LHoAaxd@<<&eBh;ft34>GTJy)L#g4@xSE`a~;l`Q^E^?;#yuC4z{I z2pOG;D&R0V#ac-aBH8oL4arBSxxXdk^S|afNy+kOzH}nq^6jltaOSWo3f*JwfxKUL zfnliox@zDHSa_U3Pkx^5kbERf{k0G^Ucx*Or3`qoz=VY<6P4ukAtUp}>1W%(spX@k ziN4YZjsVf6+68&(d(O(uIa-!$z zRAJJHG_l&nmWAuu|K>vo@zv*n8gi&`+ozG51}_G&leSNni6KUW!x1EcAyWo%AK=Ep+_z))K&ItsOPH4!cZwq2Lq7j%vH5AVe8U>9GzQKK- z8+%0JcerdYdJI}JPE4aBaeZcjj|HjQkLWIH@^&Pusbbi)RjT_Bu zRT}uIN_cB*_q6$l$I|JiZ9H(UYBPOvU*g*Z8 zfgk;3{nF{vw&_EDh})XEPt~E38{R{IPeA6zVtMV0e?o@i4}hdMF<+aM0_k!G1SN6HLQl)EhcG(qpaX+bDHYDzo(gnLV zkPSLtb!8ZtMY(M6G0-KeOT^7=(Y{@C+8{>-NGAjnS z#N+bxit0~KL-$xH-^CEqK+9Jbyhd|Vwf(_Yr@_EjJE{aFBRg7Au!=+iB@Vei_hL?^ zGNNRAp+l`n|I~8QZna^P+8MziNoV=czqC@y;oYS%yqI@$u&cj{5{!42F!iYUe3WDB z(O8HqR824$-A~(98WEE)yfoG+#k`NNGV7eb|1ORZ;f1onCjilTFDJ)UBHYwytFdfl z&IOa*EJu$<{io=}Xo9o6?o8$yr^3I%WNdBEDoH*%t3(uuW0D57HzwhrK`Dxoh z5~BO96p_l175l+!3Sg!cKz71O9;ql#At+|m2luFeDNr>Av!gUG8G6=cdm~{?dIvz> z0alAs=-Y!@eT=&W(^Hq+UIrJ;*@E%E zGNKw;#m=0!1FTZFPLJ-80{98orc+IL_pM;OyHtUHci*hTMFJ*UDC-2aXD}HW@>kqL zYC`^@$qrLhifvR-sJ}}Gjq>+v|Gv>&)lNt*eAS+ospD?ZY9)0<*Mqu!-FFo3G&m6X zMBWy}y8k=}GfDB*D}07>DRO zqcc#vzjl8YsKHWmMDG1WGBF^7B9L$mJ7BxKZp2@V`Z=k==|8EKkWrc#Q0QiMX(cdH z3Jl8tn#N@1)Ge+}^3_BH_G0*px)iThNfcH01?9~ZK6OC&>IVJe;*60tAj1y;foIZl z2jU_svM}#&un?ZzYX^IB0OF?ngSXHGfPFGk2&MT!3` z6=b*=#6Kc7nxu&W@Z$E#UJ04F>p=o6#xFG{5>qeXElOht0YcMtLa_}D12()P+8={j zaF`svugELAYOJ#wfgb*|Zb5{s8kD8atpnZ!eHrQuFUn}Un`K(J^wj4rIFQWq|4LTZ zI2*`)JH%ewz03X3ed4BDrlFh7J>plUQIYC)-+XxYnx6Q$_k=rW%(t}yJNJM7k+?7K z?+lJ2ToR4}is>&>Tg@*RelaF<&JQ|__`Dh8iS+0&;UDIB86?)bo|SxkuTfF)Z?($U z3@*pi1Mo-l4=Wv;AWJzLUlQ^A3Y6^+6TYQ_OHeX2^i3K6^{r@iyKmz=@x5~razmn5 zc>Gag{HtJPt=9YPl3a0RHDVb?j`>!DP%d!nt?!g?>(K|p)GxU8Ho}TcMbg>v5S-ZQ z6r0}Z20$iXp}EE(PpHGhwkT#2m48UM{wI-S)o6i2hchiW7kmayLnJO0{xcMR@(g7* z5ZM(|#gN0;#AnoYI?>XR`kd7y9ABd~G07l;)AE>@tt8&oMKAK!hvbc|h)M^$5wS2P zde)cqOXE1+7znvdoIEdMPC&E`U;z~nWArHgt-;?hXF&?#@Y!aBOoi@<7ZB<2M?j^R zo&^swBWRo3*Y^5VV8ro=d}PJIhbGI-{1M)WVHT}ij>aU`5iLA}wEZ}arl~DuM@_8q z`3OW(oV)UCGmYb8GOEntR(7Mz;RlP`6(D3)6KmC3qc&z>`Q9jlJL=Vh^?_K(L89n9?Y?uGyw8z_1jQq$W z*oty#ZW?SN|0AkRAjSdUpEWoXi-TLp1XjK0-QM$*PcMCaG*9E6wZqsTK@wByiFw{e zm5fa<23ASU8An)H3AG^RHkm<`?Ee88)uJ!2wmJ+ZkQ=ero@YyC`pqw;BhIhy~W640^(5V*L zGF&Qm(OLyl`25oA4=b{g>NhQFDZ1i~6`pIZB^k<2w&_))Fd<+LH96t!^`>8mG6>y@ z|6RNdI#|LV(#bfJWuo5K$(K5g@`|=zIzOSHpHd8(aUh5a zkQ$`KG(={OX-U3g{{bB+Pmi-LNTdbjrJ}!uHXhuF5P?1aDx7EY4*X2=M3VG+G)*F^ zAvgnA846Hg_axEJp60yPE^+czNO7=AAUa|EJwyD*`~#Nw9*x@BN!OJhCKg(Dp8miM zzcZx>Ep}nf*RqC=ESO%58GEcBlFlsJ^>|9yKd8Kwt6H%RFyS<8B%?M}CF=P%b=uSh zuuxt)>HH(J)%QN)vX)_Xt$ZSKfngwN@0KZu3^u> z>Bwi!g4$_GyqBF%4;IiDfI*=VYQBXcG&zjNHW?Lh`vr#<4WF5wk^E6u~DH9W`J#eg#?%eJawojh0MK{2p+1 zuG~RFqV)}y(UKz!Zp8hAe@Ihmtz~KrS&aGM-rUoG-0|8vv}Y3!`J=gT$yj` z_ZY>hB8L){Fm3YO`nz|Y@hG9TXPA61JNH$BSEl4{6h0{2WNvb zOe;K-);AETrHkC^F?f zA}>O8Hg`nnHvo4JqXYvD1w1)4j2*kG?^7+p5hk6D+!IQEkhk}FYhv~f3r`Mm!SVeM z_KfnrfbiORq4F_w=sw$SWkD4w`&MeE4FN4!ea72R;p{s9!;1pH7@J`B1*U*M_el^p zfi&_?i&~*7J!-vV)irtYzkKH=zx(i%|jt0{eN1WS9&wG zZs$s6Bqm=9dVjsSL7GCPPi6_WcF&<1F$gpnFVn=F{K4b& zJ@*hmna@dr&ew)^`cQjWO4~R@@%ozO9I&xMup-pkj@GX67Py z4O0m9Exe}lB<6dkOeVKX!8gW@Ozr~v-`;g@0^1?q&L2;73@ZQE3-Q~VMa0v&*Ld!3 zhse+)^U#CQHH^J#wQ_x_UpuL~x;lb|1gb+;Nl}(Gn(ZFlAdh<|#=nePJ6$t%w1WN} z2_AWooRN2#+zqt!xvvM8$uzIIR(b|`JendI*i44Mg{NZZ6T=CygqKk

    Jiw<|waOB61z`~z>ho17sraG6Rv?WNM06h74tpud$ip?ZE zP>Cu3;Kk_A<+%nDQHi#jA16_c!o{(n1yqO$G-6Kh8W?`j1Q7!ku!)q3{!a@qUpgZ| z=q2B-@$>PJ6t%Dm-NslbiP z>H^{1hyM|Te^+~MB@bZfzA-`>(RCmj3KGC%l)Sq8t-+}7=zuzq+3yrU8H6&+N;d_&lLfkD5Wg!ZLOdy2zb4G)qMAiI#vh7JCxV&PF^w6{Mvc zBLZP$C*BE-4c(lL=4RWTGLW~Bx$F7V5N`6rag%WSEfo)<$}cWMsH=n+`-06!a$`kt za<1!?m92iqhkihL+P94dm+`uvNK*wdsH5P&8!FD-x{-wPEocPt z6K#&6F<-s^g8+2Ty1bobQM6<8fK)a;0n;f*hlUS1KU6g5El&edkjY&32!Rx-{>J1+nCA=7)(=IZS zq2H;ndxU`GB4k=Etdm{$TF@yI`t%m<+QPwPaFi$~;`-unTQabxCk^1O?)LWIE8zO< zrYX9I{P@+RJ8kh>6x{JEm?~K1LZOzItYaZunxkSdDvF>FkpSl{+2YC(6>X^Mng^j8 z*vRWUMB1tPW6oCZ+cYs62l*Mqpm);1M^QP@6tTZUl^s3uDG~=OU)45-%CJ(+J$7RF zlN)xLymf4atuz%p4ikVnt_&89YL^zIVewAH@YbZW7eifX-;|Yc+OlYUXV>c^U36pH ztWJ1~esx*)9UU$7L^e@$^G?aK7!h2=k7SAYPDL^#A|?XB)`Rp2CM0N~2|kF*UNIcL zv~=$=Hdfh|O_09KTKe5v9TGeh64=x~A)+db4$U46hQixeG6OfM9M4TD?V-Pw>35)I5 z`)Ey4N;9ZNbc#c?&%293#Y~u@EJ)@Zk9Ht)2&jZ_4bNwVC^K_RtLv>9-M3?Zm@tXQ z7s`4K!JnC&HQQ(N2i_S^V9qRw$3*DAmLV%+c%^a*pWe{h5RX(RJb+sewJD`pEsC;>CmSf#c+?-?U%o_6|MxOOLqpBJXY|cctkq|fTAy<0Nm}V&Dm0!;FeYJ?C5X29(zgnpw8M#f zS5mm=hHhdW*&)%#hT4cC?5k%CwnQgz8!Sw(6wDs=!tz5(^!A%%tQM>WxWDh#`(}`8j#V8Md z(9@Asm|$3%hRcT~3%>^Ujh>i|hxHrT{qjy>VwcB{D5qKu`#|KIJr~h1Fl@!WeOA_c zlqOhIy)o~vJqMnz4@+lcgHXH$#ysO4`D@FSpJDUv{>Kt>GT_ z&qD4^wuxvn5Um;uz%L|HOUoC3jH6+68IZV>c3o?2J+gS0iLMEBR}XzhD(J)9um~0N zgfEQJ0ycr?#!kpWsn`$Yo|J&7Gb`$AnSlh`i1xlnBXWeG5SSjy-z2Z&Ka5)s7i;u` zMkA5luBCOaDL$*Jd909d^BNLq2A=69A@WO-uJP$Bi$L$^4xTRGMJ6e^as3q)qshJt zGKHjEppPqQM+D|3l~V(RSiz*l_fGeRM9 zH}?SHw=S0$aSX7fPB}1aB4AQAhB&;-RqN})ez0{QCLxa6XY2Ux=QLBbJ#Dvf0en!X zY;yU^ge|QM)Q<&*d&r#w&Aw<4ya8g$Nn2)mJJRkrqXwWhVVE_=Nb!7zV^ED%t~Fiw z#IfLh850=P8s};|uM+I7!|^Vy8hqFMeN_BPOCPxfqgG`5;Vc*mU=IEY4&He;;?nty zjQ5Eg!8p6)#E>W$>5brS%zo?N^W>!FhBGxPR1gh12}vq1g{j~2@IXYcT8ynj&WH^# zI?JmqUVI3WJBSZ=IqS%D$Q%Cos(+hU7Xys-2fxpL4w}5LLUDu%es5E-&uLatlrEkA zdvz*8gq(=(j`|O8cxARr%3RF!WJMcDWOwYkuZa@p;<1<<=0zpAGGf|{U%*`V{ZA1_ z_V!E9FM_EJTi>o^eiqq;^NPr)hMz@lfcXbk zzp8BSH%UBWK6HZ78MsKCRLYIACBrzXYH(IXN* zN~kE;uf`epz(VwKdqwNtxjVXZb~qqH6ZcsO=Drq)?q`e@?of_^uI!g1c|@m3g;&6a9ZtdU;eZ#Sj$8mje zJg$jus})N~y?p1vQ8(D32a9XI{+%mtoxD2^wmXEU?g-CZDPQgud2Zd`c6q%gn=bEy z>6K1Q9||ZojAi5&-sZOCF#Gqv8FylakvXE3rWWsQGm+{1{Jg`$q{lLgbVw|MqL{|f zkV~mS=)D6<#yE^Hbf)w%nB~Rio{AiJA2@w6r;o9QxrV0DpApWfp-0M+JChkT%3@he zPFTPU{GP%%{0E9Ui=$^nZ+PCsR^J)W;I;M`^o>QUKOqZ`os}=ke-)DTI_gR+HiEju z%?4A7Oa23niMITl5eh>*itHhSy*Y9#0{!=1;$;;LI!HgU{aTS-9UD$@6>ko(`K|!Onb!zXOnif)c<_7ePh69 z#t~?3D;Rxl^K-VPhm(<;CZ!tE*hn`7cF09cD6(_TUxN&`UbR}-F@$uic+6G2ouYTB zcGWV8O8qdA1AEQFLJn06v0=3cD?gJ!lwh`kTGai>4e8?YMtDMirO0P z#{9{lw;`w;IG)REJ$z?^!+$uH{<`k|IUkZMYtZPfhAGf zWgiva0{gu!F~YlGu#5JMC#Ecd<0g9b5#E~nWY+cG)2Aa^7DXES5yu0`UkeLEr(oCy1~v!cBVIk!rKQ0ZBmT%R z9OBrEyS^p;!9zqqv~s^9dk^b&0&qV8a#nWzJ0*>sfaVeYs`CWZg`xLc_R04njbXo2 zQUhqq!u#^^Ux9mlX3G?RRb+4xP0FcZjmuv>uoqyC$)STLM-*VDy|q+zAiSDz zOOO?)A*banw8kZ>G>4fq>^Z3@;_JUJK?B^lR0Nq}NsWqJHfMUk5$g-GqDsH}T2!#7xt{<%ibI?mY~!$7q0%;|NY8)uA;WzS+Lis3TZqJIuOjM^$Q}pMJUf#=uFA; ztwAk&x5cI0TqHSgWi9vbVjE`+PXEMP+jq8Z&EB6^ZFh;2gmd%yw<}T6$Rk?=mTCJ! zn6@J4Ri*kUfb`8HQ8WGmd%>TH?!5ePbWJy?Wx@ z34>A3r0*YyXn3ZX(oj#GL<5WiPD&6LiJC0sbYbb~rbuvGY-fMYQ~m7Lwe#eM;Y^Q^ z`qJMy$I>yr1qlLA%h+QGdbN2z1YKDX)emP6%bVvyJCHD#fQdUT(5IF0%Govc{d;EEXcxLPX}5EN9H*k!y#%K{Sehzks^ z?^eU}rXQfBBfCL{Gmv+wZU;T0ZuVrm-dTJ-MvWPLzd^ia$fZJAHOtAQJQ_hdOtZ|T z*?A5T6&EOtbU8muPNiTFMMb*a5Xs{fhGe(j75n>J4iTs5&odCKt{wh1?^DZ!;XqeY z#60%%Cfn5hvZK2cf>BRPsSek)Vff64r}u7-wa5(Az+Hovbg7vJ#I&{JrJq5YKDy+`2yr#&-6#P4q$PxeN%q9UlS~~hIx=Ga!H#Cc=Z3glriA$y=nF@6^a7B0Oe1CAlo+D2AUTsY2Ib`dbujk zmx;QD_7gXUGH-J`aEVdWCT1zJC1|TGHrqOwgr0&AN7fxChh!C($`2@7(*2n6z)7k7 z@NI;$@tJaN3@ExGb9A~JU-`pBjjdi(d6EkhQ9hp_;*zp8Q=>1DWG>%*r@>HYG3rAR zVMMCr|&mCT=)hChrF;5@5Ct zsMW{r{6X4;dzpoico*qDzxj_P&{$rFjtC4BfbTa|7x2Az-Ru8?m1+}J*D3vb@1q3W z)eX3!^y)jdp8Q7xnJ_1BKX<}O^xW2{YNSnrm z^_w2I^^6$^y8cn%{BjB(Q>f~dv1*mvA>P6kTBP-ifefQpUyQ>_U{!4Z?~}wFCq^FA zl^eG$f>^B6fVbe20W)L-90k!;-HXlUeU)4**X~(OX~e1Z$!9mhLZsD~6q?$X#EIu7 zYSNz4kCIrH5pbAikrc~9gP$Bx-KSZE6U3BM6^lxLxfuDm!64mFg(?~Nz>TN1#Nk!Q zD5+r$qGN;s+tzPl5s5-60o1L}NITAS-+F3;2105u*e-yc@rU}yov1n|4!m?=Zb?oK zbG9HT90d>4IWBq8iJQrKr-B@3t^*@0tfwQ)&g#|t=8;$PddR+H7ku=|;OnkfuC3%x zQqU+-S&3@en6`#z5oC}4?KP1$Hw+aWw1v}ptXXo2@Ybs~h#Q<%W`}xl=pjgM-v^^V zX@>7KY#63IMTkhkoeAGUkkc+H5U1Cyou7g>X3sL!K6)f>yFu%v_os~`Zm;A#RT7u{as*#G8Ka56KCndULEI%{te(NsWK&J8xI4z{4g5>l1x)p1$K?GFtLa`y{2(?Y&M0M{|oDX)Q-rvz_JJ7 zN>Rz10$Q`vwgY>p%QB~6ASf6bl0&bX|KuqprnKo@NhSM=TLP88M#4v;r z4Ih~GB0>Hvjz&%;h$1RO(F)!rddSKFP(X{jCF2XRq;j$QQyLl$R;tV};v8RU$nsp# z?lcvJGGaS6Ed>@NT;qip^cR{LbuUreM?L>*2Mc6fG+(JvKrj_Y6ZG1+AQWI1{<(x$IACBfn)MBqomI zJG%324OX}FKLG(RC&y8LXsr}!j6E)mz`sunDLUT>a9_m zWO#G&_`-AH5_p$?z+?K=9vpnd(rdCM40uUD(hej3A#ms;k_h+Dy0^V;!Km#IRK=)b zeVfwC*94R5>?L>cms&UvuHbnR=<&W29UhyIbswlJP+MEo4uc(W;;EZbhXSmp4*7KA zga(e0@_w`b=SqzFxKe*$Z`y)!r6HE>;2hB<-r0(8<`en=gV zMhfQGjTZ_yX2HY~ZJ*`|J%pRh@MXUwC*KPM1ZuS+ZWVF9pyecPZVaJxj0txr^RbE(HF!%m9Tw7dQlDyW<3L>O_ygDbLZCxN{ z&J57s@0Yg~Oyd_r*-igMPG@T(>(8gNxmbex5yJ@|4ZW&DqPn8dK2T-Z;*c;Y-y(_U zk^RQny;(}Q>(}{dQ=lhu&l(zpd{C6bm4<9>UNDr=x&E`_lyYwI5-)R^N4Ujj2;0WPg6^u6WWR* zSs)1weeJQ%@NYOoOQ{1YrxHs%^YInPw3H5>r+q9hM{KE6&?a-rA&zg!z{R9WX*c6J zwKRQM%1$0vz^2DKOn9TM<$;5>SAffz@A8`sBe?c8u&!-DbM~wirjZCKB@(rM)L?$t zv9Yk*JL!ApgmNRL*TUvKm*-I6Dr|txW#?Mm-ew_|-%qF$Bznd68o1Ci?kkWZM(mFX zqdDFKKrxs4cm3hXbbJN*Y2q-cn{g`tPkKoYGB4n1H2b>*5;irm#bg2``e;@;3c)(? zXm6>SlS}jB{yh2Xj|R`R!%ME)`azlY$a+e7zu?wAa~ZxLE#}gpomjWru?@y}+#nsy<^^@f{e5 z3Ci1ysrb3czuC<>0h0>LzYgYJKbQ#fjr|=m+Dw)=Yiz6__i+9p^@x3FFF=Zp+dGys zrM141%O&4-|8Ph1&+XuV%iFsn?{>Eu&z6<%j+Rs;Do6AX&*|K_;)>qk!d~=%y@0mWwcsyT+b2G%u;rA_hs#@^_h1y!_+8ZFkqk6LSl z^upjI`=VQ!U-2c8R^*rq+IoEbvb5K7cl~c^ulWwr(*!F?&}6v+7l;pYbZ9?dO5qLN zR4-3CdjS7<(ZBRnDA=GJY6kH04cvJ6qV5n{_uvUo@@>IDifG=HcX-gzUv6U$V*bA- zt@f-tg3=Kx%9qYt40O(Q1*0O&_~)N&%4X;(>_=*9wU3}@G1itCy>amW3vq#iPKv)cxEw&s_5Eu% z8~7v_?gO)l?Wr7)OnTA1&vzGj?rczw|1xgFYqBkznfhe_Ltbpiu$|tib?pF>a9FZ@zSx`4eyNCT`0V2xcJ|H26_<; zElL*r_>cpA+@vd{2aL-tP9grc^(fHM(B;-I!)#wxr`P^KcQHR8(P$^8{k3=h9I%zy)rys^cEDtnl^5U8#; z!X!&3w;XQa7^*X!yvP#hQqhLU)AetAbuh*{8;^jT{DIXam{gK`wLT0ZLzt@ zu%fXS{3&dTVFlc3z_ljxI`UNf?+<^SQ8m%N&2BV_Uoy#i?u`uig$1WLXAMaGAn9F^ z#~Ndks80x2DPLi^{wPPp>PyojQvp*10ns_|xbVHNG2%@FkL1Bgh-_Bmu;9;mktJi2 zps&@b=k1y<-3GnltAJ8mrAU&JA(DaFAGRcoCOj)`L;uSHY?;l;ln3d+C9{~X!1!9> zI0K`aMX`G`PDCBjrW3?r(h;zDT?t#dqTJgRNMva7+Q^1 zz(R|fXGJ2^4b|j1#3ukbd8|1H9I!i0XbD_(g#ws_MqRD=1~(kT;$s3SEuIR`Nf<7V zy`ZE&kAH>iz$e&k1MqXYbR<3sYus;BnSuPyfq{T}NjkzMLYVDjw107Mhx%C=wUhR2 z4FTV?XV0LO3q$5h?oypu_3i8_>mBUNzSIk80E=X5RKYp3k5=*k zhS^2jV<2^236>gLd?}`icssN&t7f}~uESnIp?{9n+Lg~#}U8j75aG_mS+lYUZ1l8Sexf~kOiyhG2X;Tvc z)^Z=XXriq!Q>H`^IQXyJ(M1XVZ0!at4fcIN>9cXRo{oHtd@2e|iP+LxL@A=99mK9&ZCX^E9ZFbFj&0kFgT}|zO#8^f449(BZY<6iT z73I+_iRBQc3Mec5)yAJMXMNrreCZj=w^7!f- z_F-KhR=_?XL=p&A9KvUD>RcS%GQ*Xaoc`nXmGj}}X+2SBUBKHMpFp+CB=z$R9t%?Z z!Oe{jA`z|xHP@a*W^Y7lGA|^Jl!+Hh@Xz_(6T+@ipkq5 zqo0zD&;t}?*g`Sal}#y@S)9Uyhi+X6WAQ4qS8dAwKsr(y zP`A=#jy;rAR3S#8^${J*%3;exR>1$C*SE6J+pMEJhiS#BoLf*G6x2<)AwdVS%DK!M za$0{pIDrI++5A=3lMd|q9Chdg<+*@EU9YW;=0EuH^^}7v%-^L_a-kIaBAZ18O&Nk* z8OeWBl$Ufy@2SWR>H&lE%U&K@q(g^K*3LLRw+)-SS!hY=Er-@^u`3eOogNBNE~VuJ zd0YNSPM}N~3R9s-{Yj>$6XrR70p?^`VfrwP@q3w3oB>nrAIG4)c?CJIk&T%vFrr65 z;+$e&m2S8`zksmb@KO2_txXzm!f{m~pJS;8y`#9Cq?$95?e4Mg%I-jwLAr*!gSZ%) zWamtUc85PBx$}U7^0!Zez3?U2cYj;=kj*RJP!zc!k@^M$P)AntD-AApA^Fy0w%>dG zKpVpPZ0DbsX)(&N%&vtp>z92$8gqaWeilwF-RG3TiyAS*tOV|7-YJ#lxqBVmPx5c{ z_qYhYs95jCwPawJzBWt|J?~$8-EH)B3@bMh*Ga~&Y}R}{WNMn)>z=j@D~e&HcwXrrcZ*c4F=BgJA*h;bR5u=LfShck6$|p1pFs{KR%h zL0Nf?q$8B@J`nogmO|9m)y79%Ys8Toer~o9%mj4xW4>OC^eHSjheS6=cz8iSp3A1T z!6}$e)@0-4)jm@j4r+sQ|G9+zU4@e)LbjK}1MR!Z*ZuH!O6!5gCRc|QT0QTcM^L(D z;m3`8_~cbE2joyU*k#8V&d2DQIN;9k+4%0I1d^v0{Ax>Q!M)haF{+@W6?|@U{-DKA z3CE3I?o~RLTr0uB^EAsxJG_!a7LF<2J_Z}+bu*0Q&bPc5=kz(CqcE7zqJI(z z!paD$zw}L>L$<~SX^01#D7XJHta%qjc0lHK|ITI12u-4i$EMM(Ed!`YiUuAWydHZ< z-=31ozE%{id3Q};v`hcz5KV*Ik)SI^dWNB^ubz(ab}k5@9m{XLacTiut=_KPYX(qU z^#3(eE#!PVy>qZBn|x>SrGpr_^ezPXbgyYwEmZxlF$%NMqsEc613S#|=W9lR^idfh4pF=6Ks*b4gKNP^R%?d8_o^C%NvpH_zTQ1WNjRy5CYEDq^^Mk>EHh=Ai@zyAp_`NKG?d)6&c>{(FUh@LOW%4bKuE; z)DJBYAPgSF!^JNXy}nikeptG@{}CbJ@~y5X8RD<;aRkz5`emstd|52od7r%l4y&( zx?g$;=5>t1te#y`7;REeBN|eN8_j$`bBc8zKOwb&jD`b9%0%lQj-k5*lg>%fV}j$q zE4BNBZ(z#MP~i;2?oJg#?s!6MvWFNBmsnTQ(dXMfiH-4w04C!ClLd9c?&G~f_y^XU zQe;6G;YSUxgy|sFo{GINdc*))Jl47Nn1KX&ICB)-GOl!S5BUBdOuCyyq|qpbtj{nj zy&-iWW(*-xzb%WAXH}CUO<9>WeRC>Zj>EFj}rABqCjh#qw_U6?t!<1VWf#=7$IQX4u!8cvujfoSRW zpEtyf6fNchQgBtnLDXg32MfNap}&)1IJj;u`V191xZ{>sj3u@|f!qP=ii)V~ZFtO{-x<#z~ZLR*o%t0!!$M!*wB=jwkAdW>9Mo6$Kgn z7mZ~VP8+>#E=ilD^ePEW#?CjSoe)GU)XXWMI!lwWC?Wn)>vu`En6CswsF~t$(82vq z1$|C)sY!HfGSQOlRIc003sFF6`Dml*-K`>_SfK$&9FO^IOe|0ykA+SO!0IiZm2=bB zs*fmV6NCKyKWUe@2O#Q1=m-JR0S&3#8bRn7>=5c8kx3KEON2m_2VnRpjv9`ylq*#@ z11fpPBcHcS?U$pj*VW&)H=+Oz$OGFJk1zSZR!44%Psv;Wa;nRC50CY)hh(hLXxEsd z$d4QUvEo^7tu*f=phMz&vX@C{?4DE6Qc@u~ig|){mb_vYR7Z(>LF!4{B9$vq@#$)C zxF&So@WKlQPY4Tgy7M|Jv{33S+tbjv8WxFwar)h@k#jZX+Luh0mE=3Zqw3s5E|4~r zD$4jFcrjloyzXW7%alz9Xle@10_o4u&3)M@uQ>8pXr14>$y6xa(A2cs6kfjQh^BMM z!71!E0EwJ{m86xJM{nBUNQYf$g(*s!&5@J35vMl!x>HCx_ue>0~qa zl8>$M)no-=MaX5cz;G$5wap}}EvG5vyG9jNdtKY&=P@bhP0(IYLzyjy5Ml*GG(&{5 z!9(?M4-0`veMLD=XtNqHV1BFM_(~DW8ebw&$GqF`fEY`R~^L14gC-3*G5PG zvHS!Vl7@LONxl8%`bFQ!)=;`R zoKIfrD)oJ5D( z=_4hDw=xZj8kIq3W{Uc<_vhoV94P>i&U7?+WseHh-Ayp!r>UJ>nNZj1;~C|w)}LR? zwsNE@vkJ3$SyP@L)WnR8ZWlckZ{Dn}r{7$G<)Y3X%T7M^_fMQxauR)Ihg+=^Zk*!q zdG}vrtUyd?a;k>jP$opR5 zt2STXwc)!@jakV3mIm-A`1U;*xu;CW%;f7kdt>U^V=?4Zhy%u(#E}+c^-2x-qXyWz z9KO|&P{9*pLZ*+N=~9&s3G>EvVlwqJRA(=f_S3KSPlp7DS_@&C%0;?=kO$>dW^;Y# zH1Oip_5s2244ywbPith%NkTl~Ax+dto4=cxZi8(+V5 z)Gy{be~Aqq8#a6_=#p3CYR&ZmLocX>x$u10i)0zCj`qddWUzzsDg3SQsKVcy_wnp4a8{@-uqvx#6auL(kKtGUkk0Ypnok@y{cJUEHdj*m=7CK&m4&J^H7aMYs@cB&fiau< zvti$Ea$-?CgZtv3nsgE@0DHl++kdfUUv%!X!7gJgTy=2?fsW%u{mbX8f>&RU?M*q4 z2^RUtjo*Fe)GqxxqebJ!{+q8#0te&6iuKx4LDuc?kI@!8UwTl{Vid_`xnf;L&#lL( zj6s=wA8+hLWiFq@WV`BOTv+6Rj9yA?s_0T{kesE?(^+_NjcCqN$-*J0nWL6n;Pat} zv=$PYsoV9V<5Uqa*;y+_$`%D+IjwkPw)P#Si3t-mt<&%&$U2!&$_3RUF^&PH9OWAK z%WC^XXE9SgW1pHuSD-Wm%NSUBK)OcooL>{bR+Ph-Ka}e?iOW;I35Rm6GtYh8wdH&4 z15#{JIdiDXP7y{tM$$STji2<$Kp0{>ok;zysyZf6->wi<@hQ?SWSu8n@5ZMAgl2Ws zMMACWe!m@{tun3nFu{2UDCfofGmJ#ITvtYfIFk@t(xP&Jz-a+5D?WHPghXc9!8kCs z2N-oFihM@^IP$5^2@G-}+a@BCP2y7)VHyLIS$V!uxue6y;();dGbyB#*3*@WzUXj= z=2AL;!z?#F1rHv?FVs+x!!Vn`=jDf!Kph>K_%WeSqb9E|9KT!_;uE0*6?- z19>v_Uxs-o)uBLy9^+cvvm$joCQ!G;e=^SI%T(4b#znL5>++6=E39qi$(B6~I> zAUK_r!*@1+AWY~0)jh+HSavV$k#X(`sZf-sI_z;>Rx!n5#&4=yPUzhbnIq$Y`7$qt zL&~GcwtkCcf4rnOtgb}`>73BfsyyP~{&?YZY@ryvUz_qJE4@!9y?2|+$(eXbvuIB9 zvdqlF$C+QO3~`FXH}DuXh11+o6N8+w)BBst!wo);&g(^P1+>lKx3>=s?LdS?Vu@Tp?`iq-lsb-(wN6Z#2Y-|IVr}S3}%s6(qWiOw1`pnFg59 z2hi*fbT6sZqi#yg?G+;BQLNPJPg|H8!u1AQZ*=p(>@nwqd=J^8NmdYx&Rs5(eKH>- z7ms#|pXyej3=&Uub(NGq8(NIx#vDTzCFpLOlWI>a#55U{L_~A8pn6L9%|# ztcB*huAN0fkHq&E*210Yo?-u>D^CfU?RMsq_VJ~G zZ%DBv^n%{_IPIU?SM7iO3K6{HfpjoC#sQTey*BHBJW*&zd^Gtzr*mR_hDS;y7(Nft zqVdD}x$zGsl))ZYG@4_yZHfz4otosSbub(dL)1ntfvR(6mn*l){EE1NgoNhUNJi<& zji5K*$ndvk;*@-Fh=UuGq5!N?xhd|RpkOC9JH$^)Zg7h9a`q-S&1#|C=B751^1>xg z=V{!R1PNYX_^COUV1J}lXhcSs@sBb@fzjmRVkJq}7~wezOKvKqx~#=PygC4^@0)A}F1~*S=*I6SnzHx0 zlQDN55QqDXSPS;2;#Z*0WfZ2NB}5i1TgSBH{K#;s+m>@DoT?!(+XAxVQKeQL&*rO~ zr0taJEv|II#^0Nc{MP-&wUE?x!qnKDdP3hL)LcUK`z443gtwO+-Gy$#Dp-+?^KIO zNLQdI99IXJN|MHUT7{OHYs_sAKJkhggaP}J!ECi(OAGi*ahXDXXGaqj!OqSl96F6b zg`<7dqK*tnK6a)QXetQH$j&_W@(p{~%`>T(@f_6V`PNnTl{!F8lJ zqU6s9ax+`xvpB0nCD=^lH{ZbBjNYF+Mk55PE?+%Bxx{>jg5~*f=&!0M-x1*HPc|y8 z?G>iLpv;XkW_fTmOMLfLHQ?74GRy58vREG1-|A@_n{HD=a1C2!iGCy$ zfbfbBSoP=EwVUGDKxQlWqJ#Hqbap@Fhne2v$`Zx`;P>2-MMGj^{74v9A=7!-FYn*m zvA*jScu%qt@B!k9@&coy0jIh(8DU4Z z$2Q3$RZwGbv!;NO1QYVE?a0v&pn7pV8kCNT1Je|ujn zUXF(&S{K_VLqlPRn6sIkF2sI`Y}gEovbz{85wS8lA`==KP|6wTX|g)hZ_ew{d!f}0 z3A*0|rnmVpA%?TBXO%^W=hWJM!TH-rx-HsDen_rCbYTHuderRv3BaLiZ}U0n5p*8$ zr*1)#gB2cLCIFV_wk%^Cz;%uW@LImW$Zl21QGBve$Nksz@N&dtJ=0F*QZqes??4-F zXw?u&br(d$8S;QZ6tN+`dlbrcmlJg8^`q%Ix$x}67ro@KCWwZLwgxJImmF-Vi=iY z0}hHrFIL_~p9A`DvUJ6~H!3ElJkT%Ewz$Kw$9*T?$T|gj*Sp0#oix8>KWH3w$O2t2 zRcmg@jyH@q&%~=owRXJ$^+@@kZswikJLhJOTM?I7Rr

    O%mtdERP!%kp@#=oVKBVb9P3^J;;m2+%XY|>&f(oHxnbX@`mDLlwJ6O8IQhAq=L z^Dr2d-5Yb>qXbaAWTAZW?(Xbv#Z{|(*smp^dIM_*?O^-5RMFo^zkJxY1>4|LxF7jO zhG!8p9r!Q&QnHxd27ABW*ylk{__Be#PLR~mr#7>tz`#4wQy$B>z@8?{7U`mWPfWS# z_HpByRRz`!g%I>gk*%JT^|~K3wxi-ds1G3ZWLp9-W*F)M%2EWj1qcijp`68B50@Ir zel9A(1wEirVcqGktR@vNVPpOf5%mHV22Creu$OoW!Wr;oysXl?=hnAeb>B^x4jC0~ zvfHmdY0IfxG9nX;sK=_GhX@ZeESdS`l?h618VK(?5_+lBzL*(;2SK>vFN?Z3EBh-2 zbuw&S?sU?+3-$%Dku6Tyt3w2Y*F#GQIK_ zSL|)Zz;P{g%SMiLo$B94DR72ewKpUU&{;5*$h+Ms>hi?)=IJEAIr^aqTTN-MaGIB( z?sJ#Zt}+$4!GXg;Qb?z@bK+m3WG0} z^7@z~df@W7bBoC%p_Ad3A&nxU{v#}rwL4CBccZ9JFS_4{R@Fp%tZcUMW&BBoX)?Ug zJt7mIwrX-Dag*!@=FJ}Wxyv9hy*8v_JX{aWHQ{EbR+DGVAAAz9J~muqM~mBq1j?oT zt!s{ZWmc;YCc{SdfFtF9{Tp*@&H`1;)?K29Lrd%AQq(! z>4%tNwvzm;I83WVc}6?Px56b^CJm?=D7M~>ae3;i+-+%37tb;3CL#9SyG!8VYYo%C zVUkhr@Gf-c;2w$4i>QN0u7vquB9sIEd6V3WW5Lh6TFvF-DQy=N05Yv29!O6ChW=wf zO2cQ~r3pK3Sc7qi4o3&VNoa2VkGqbO7sxfb3Y`y$ntz+CdA0|g@5#yT?q$7H`q5Sn zifnfx8vh;~<$H@7I_2q2IQXNj31^B8Z(90qJyje=92=2n!hreyP0Ne4>ZW&c77(a_ zCO>oS>zwCJ97=sv@lJH#sSi@;8|%4xiI6%e7BfyOJ+k&SHe5?9aKaoEYUtDu+zj=R zzOG9*Z1KQ1?$lzKB}|Nv1b9Ea=WEP)u#3Q=dK3@7-LfeSz033u-nuj({P0>bPvax9L6kBg zW9x=*!US6F>zFd^X2|`Q=I3eM|5ZBk7swm1uO`>8J6-bfRz0BhsrH>XKQ$O<_xSAs zU2*4Yk7C<^T8M;Pf#Qdb+iuTd!^9U>(5L_DJ9kKJKL92PZi+?sx)w!V=>Bq-KocN@X_Db(BBM&;i$JXm3GW zrN4DitXKKF67%WHy@-+rl|Ky&u{2ZG!^o3AOw-v?XtvA)ImOCMUDjbOiwpP08Z`-2 zwy)e6l@uQa4T^|=CjE|ENz{ALBJ3X%Ym~e1h1{d2jmYD~w6yEZ#Rn$5(6xoHHd0q# z+w%4vmeBJwxQFU(p!8kS<_k8A=H>b6xW~^a(2KBwSb;OcHJ{(y8T&EKg1bmks|`+K zu~Z{uv0`yEe_R_V6Xb^0$uCG=+goD6ba96l0N{Dj^)r`e>jAw%U8(`Dd23ugOkty` zQZ`DO9=pr`p(+L%nvLWq?swCc7^e#Z-q)J`9S?FOO)1z}`v%^3l{f9%dph@8%1)~1 zdxAgnz059{y_G9=aR^#+bPlA2+uL36tjr6hR`qE$5^3W1?I=)LBh%xl1m;k}vP@!VkX@xmzC)cx(m!=DNt*w9uC~=B-_M`|)v_tQ4Y4y7LDNSH3S*xNr;~<(=p82o+5*ZlX!9sdBYI86#^llK z2@=Dp4k9?HCL3hOf&IWzDMhb4SKwiA&62CL4Rf)vd#QmJ_%efC8MM2z@2T%(JXRG( zq9k37o$n#yRo_KD6Q{r-gl+Ph50I}v`AmY3!Y7?BG=w~eH?R2Ju$>4PEcnL?ook9_ z%!oMzbomG1TMEo|?$%QFb)Tghbe7eSz}Uf3owj_?*%aj9>9)AKs{Kz~&zNsD$!#!u`Zy;zY6sTj2-qCVHF1{`_oloS|lB~J8R6n z+iuo-x6sd!3lDjpF>+KSFDw3ML^E!y=cL5@;dY58oU<8c0+Xn7XWFcEU7>rB6dvzQ zr;-$;_R5{}S1QBLm;TaUxN2Ty$`0~Nv33ifZQ+r##^0|i4`$_Gp9Xo_osidw=fGob zT36E4lVyQbD%J`JK`EmE<6j&1f!dQ4L8*BHRtCS=+$BEgH4~b30!dFE!+UH;4;d^#h9Oobd$f;Xr%QEk3PAHz|!dnI1z9<^OH|EpjclPgG4uN5%A=@Z{S*6z(H@ls)&( zg9g(S5>0nEz#IUfhDRfPJ!0bQYnExo`gJ-jJNvT}s}18}p>=&+?#oT1tD*B9!INMIw)F1ogk3*~De8bx%r&&1 zCDZ(u^KW!DAtA}6Pf?E}_WLFjd}D$m>;(!{J_fdYKi0*{sMYJy0;yP+ST=~W)2OFR ztsP)K&JS3Z6vpNq@;PuA!bQ1l7PqoA)8;#!x zUJ$4a@M8~n5}X0?I1fweleO>=Iv@cSS3dBbfX4n|_E>J}S=_;{PP?QNZ19VOx>3u3t(m_wC%B~m@9clic_cywWfZPzuVN`C# zP(M62dXAM+21}sG9(kfkW+=L=y|qo=E&}N-?%7lREfRYD1dDtE6D=RjkGy;SNMw-} zpqBo+teu5j!|M(Qw`2fZYDyt_lP7nU>HIE^1)^orBv(UKw=zfzx!5r>eLXdQoZG*# zZsI5ExZdZOa8-J;?r^-1V$O)US9qVR!=Yu~UkMUh z&3<8SxHL_PgQp$}ruhD(!s0+VA*CZPStj16&nf!k~+ zpO~R)8rH!^vwI=`nd|AXoYcDGpcsb%M?NM+iZ^B&bZ_!ie{ZIPjqg#(Pn};deIE+0l#gLJ7Rlzkrq;pnA*@rV`?aVOwnqQ>fHJE} zIgIi6y(gcC=vyuXH_WFjD+RBoy)vHBzv*g|?NKh~IMue;))+t|J^>z^gY4O}rdMxU>*Dhym%)wSRYY3f z-4foQIoLHI~A=qw)9#`O>oMyc_89)&<4S$_2zYfiF>7 ze*aWb-rRdv)W02O8M2ySYP+hW=N^DX)5B?bPww5Y#>P|ey`bzhD5EG>aA93)I0 z{bE|iA-pRWNFp@1y)Oa8)jyY3QFIH;wdBAtpLduHHlQ2cl*Og<6umN()ZKqo7% zdiF_M_JrpBOMaXw65=dza9c^=$_IsDHY{?WtNKv@+u}qnrh@qj(Zw!l5B;ql?pW3j ze|s~TtN&9VX{Q|QAqEs4A;LPYgFg{ggngQjfL9Uxa5bDife}Ur$~zr|gr>Mx>&%V!A)(7T)3*m_HjY6JgE)gbDFsp=eW&@#m{3 z9|^;Fwq!NS0)M@Fyewt(>BmlvQ_5o!-N;W0!3@M`y@N)DYlGnrr*2i9l`F5yBXPH| zXmm++x8A~`5fNF0A_4Ww;)UkgHebv~Lq|RW3JTuub_q71ILZTOkl;WPi9dnB_=P+S z79J`h+}R^3ydXo?rF=Xkc1S%|OyYX)BeDrAApq^8wW!Tmx?o%U`r6!qOy0~6+G-Mr zQ0HHo9YdI-#>T0C4gJK5o}iv9;UraX&JK1ctV-(Vy|Ow~iYCciXTiM7uo1#%CpGZZg zQ_OFa8KmQQB2($tAlVZ>V-v=XtAHZ;DH?*!j-F0Xn=H#f!r1V5u^KqWuL?TJ zV7)tpku(WNFN2)NX^03p(wR3aw9r@Llzbfnm#xe6_!2TBJ2mj2z~i@`YInJUeGq@P z&k+}7&gm*56TQHRu2UMB+_S!db|!N--n28`mguKwbryBJ`%6OGqFs~{#{blkw~qf~ z4dQCanNVbxJ}>Dj?o){LpK0Els-Ly$hz7WKMLhe&fi^|Hv%*5H;#;>dlC`GNV=2@4UnvYfS+FlEN~-(*L24$ZKLJI zVXSzO0?(r|C$N)g0gte9LZs!5+kyE)bOvqVsrq{XQgBoPA`z|C8Le38AL zXD#~ZgSg5rQsgKKgER@n?Br}FbM_@;WevsAk?2Y4@F@FA48gSD%>UV`{pOHmS3XEk z65C}+5<~8uSwAo3+!e5clo$c?SsW==w$X*DX}@`z_@X}rtrsoK5jU(I?zd9-!>Xlo z)9Yd{eb@#2>Y3B>61oxBbxzsMml*%0WA#)-2(Vo8@~_F^puRBp?Gh(L=VCI4tJN_c zA@juR90B6Wch>`o{>y*VQ>)4V4_mA38XLsWA23>R;}tNu|7VA1fy1Vn@@~GwxJ6=i z%TdjnOK1tg$Xq^pE$1e(aR+tvllo^6oW&pDsS(_h?eT0$wl9TL)D)^A-JlRDEmkDW zFOh&nBA9)j^XN3jxlRz)DOLZt(8it@{{JP4;oZbmG}eg!Lr(n#E~@A!Rv*z?C+1!P zk%?lvm$s9qBgi9RiHg zI5>YSU7SEOUe1C5E!NUZlOi*aMrZNir^12G1Z`w%f;@;Qdoc;zJNP&%RAsBLvrZIa z&|eei#j1=p+v5Fhd3-mB4~~{!6l%mRn2Ead-(?N7Yu|SCzUuap-s%=G_NY{h<79^AJRDdgECAY!Zcq_Kc-x3zco}?ngK+H{L$0tR;@Sf6lrh`QPv@@QNCnc zj+R41LNc5H3tZpCE3)ab6tw;fB~aLwvoY&g|0qeejbG4lIGzs4 zXHNrZJKZQ>dSR4{0VMg%g8}|!x(G}h93_=Lp+g<_LFqu!I!Rna&E*1?Ih^F;UOv1| zi+udM?PP7L9&DSckg9|z_u!#8dK4!N$^80>B>E*-ONzGtYru<_38jg!x0EL!BRGel zY-*cA#wMtrdD6^;n2+T*ZYg;CxTD|NcG(t+dLE{}sJkj}T)G-`H7H8BrNl7T08}W7 z^J2r#*nyhc@cn(l0p;L<@x5dYeAY3@I?A_pbRXO8tYAdc{&sy5;SSrh-(PI=XpOFiDZfmR|zh zAikJ^YW3ky0M7vRF6;92)uWH^2-^El*1{Ba59~WDN!Cb>yUYQddigBuUs)wFt3`Q~P*cAt)!ertmI3n)ehNODrfY|o2Np^6|8!=EHZcLo6Aj?+b*z2clZ?n^%#qO0+kI*3XVogf0U!a#;{seFTsSvXn1H z?&NcqzX4q$a7#cgCE*Kq*DR%dkh(MP9yJ?GJFBfjrl`W05>_xIqFg~m61uh00Qs+tB=D%8{Xq%Q=7|q_ZY#4k}(t#PV5XnPrN+41JnJAsF z=fY@5#&8QpkSP$2b8qW9%Xp}z)Qb>`e1Sm<(JoOXvLmSDyjfN2YY&wA4QQm87_ies zm^+=A!IY^LZQ11s10za!V-R>i*5NZc|K80&jcJ5?j12;gmxDYATsu1 z!fOYqiMulxR#+uM1LQs=AgB#V;@YjN<*G9(HHmBnhN{i;*Qf<8I68^;aOsp?U`EmP zl=YYL4S~pXS0OCBNnjFEA1|O_)ntfjtRQ^W9G`5bS0=4LKZs97R%?o^Re_MCVOar& z2MkLJOV0vZz-*q-{r*-_-yXla08sYG3C++U0@MdX!jwnSZLw`BQbe+AiHj_YEMPVF zsg}w7kMH#a`|0Hj5y-;H{X)I&! zds1Y=6LbRJ0dH~7wi=o&W?p52LF(t{>-8tbqBA&j80)ab)RI^|!F4Z>zTow9+;!EY zzdxka{^1-s6afC|a+=m`uPedu*oR}BCs1<%{BbDfA_A_8E0{cMpyP{+SiQVLs>ePA zhE0*)ZP95HjN~yWkZpBO0fnKmV9Z;Bb&ShA1iQ6tVQWOFa?07|W^hgY+KKu!FVbKB zY=13|H^YGzh_JfoIM4--7Asj-(U=Ofe0=5Nn(R@@w9K@gy-jJEJ1CTtOMi)~nXSWy zkb<4z)-$^}b@Bsh*!He>&7gX8P9j=`*VaObnNaL@Z~*WI@FYBOeyQFULlMmrOPv28u@c14%b+pe-@bYLUQOO`*JRCr%s zlD8U%mJfeF1a#Xml~Ymn9u_0^t+fAI_M@iS_D3BHaM@FJbFmc*KsjHQziYh=Em;_M zCk!tb^JU&u zcNkT~di(`-61m2m4KQcIKMN+1F5KvX%}$)?0Wc$nlocx6ZQj4gRj=R%!V>3+xjIQVo^caa99IhHvIG}+tx zAzTDXfh7PoNu#D^T(*RbCDKlx2x)07FXjmP6}lJOBNIl!p0*M*EQbc_OrHzX(KHm2 z?^}S=D(cvnKTD|5zXqN%Eives8U(?gDRyXJ&8_3`>^b@=ULEus@xNnouTtij{j3fJ7umpBT8&%EA8 z$dr2TSlX*KD{FOrr4(*iteC^{m*lVQd8+J*R?|Xrnb0YbhxVo`q?Lc&Gf~!mW>?jF zdiS?McIm&6Ign!1!|6XlL&o+A(<4XXohNjjdJ5Yonh+=MVNBETkz;RPs-LMY66A^l zp*s$0Hy92%>t^vPGs2c%C%~pRbAudPw}&TSU@%YYGB33@PqL`ZKMvTx3X*>CF4bOoBdlg|El0XS-l)Cs%KMebq$tbK308$Z_5Of$?X*?R^x4wfuB4Bo`0826*Hp%#CX(i`z z;4~#rd_=juneGXdUXKMwJX6SkB+JBoo;0%$K&IM)U=>zmDJtyjq(}HqI3nvb(?hw!w+lkoN)e+cnXt-{rw9n!Uwt8BPA!cJ*a; z(R*}xx`6<~t>QonOd=wpvp?jo>k&~zGGqw~Ebe111{vkB8s+H3_6vTw`NnN=49>VO)YO9up=H0V8dLv>w z!TQI;;X$GrIIJg-oi)`A!|C@?KuWF(&hS-M|A`?zN3~UVYyi*5MR4=J;_`-y+3g4E zXYJbKUV_!0Fk0fg{3tLw7?atMB1*f-RWR$6hZZJ$V(_^dV!JQI#a-Q8Ls>0olo20f zNJ2}n0}DsK>Vlc1&fRaM z{&v}5+{-^2qu!NIiLYd#*sz3Z52V~$yh69zKz=^R4oQ3Y1bN@nuJWGtcPlwMrb*rl z7_?CwOf)hqMi`~m7xL$Ly%|B^LPnBs#yV|Jr)3F|!aM3V=GGihS^=H*hV3dB| z39ppvgw9k~NMkDhd^*%dh|r2y!9jhEE*4h}eIQ4baa`#GKIL)?3 z7e|}irllS3!>ZfMImx1Fm5%}Z@{6%~3Sw3;tjkl`Ijz@hCYsQCNA8Vmv(+bf(CtL! zm&T`z@UBfKlnx~MeQO%tZu#$`7eG8UszuZv*m;};9i0fAcqqu#aeZ7n6c!+~3D3$U z)+TLmsI#RKc?M$=2O1)!({3hdlxfIbnMUCV7OE>@Xd2}m16}EOR z9x1*myH~z_Sn_wAS#%;x*HeR!1yjTjFgU;aAX@7|Qo*hMdz#{r1{W3;4~>tbqM(c> zQPro3QrTRI=Y=gkxrU7QC4`h7*J)STIm76632(Xcxfh z`RrF3(kCtwv}jW}LCt96DI?rR=#;llPBPoehq<=$(LM` zChQ7Wyo5%&yMN#jnGdvoLZ~g9guslRLKh{SzYKqK9SO(gQVrbii2w5Pvd_Y8q8~UC zH|fnrXef2?>0Ph4F-gdVMd%{*3wke_4dFcQ=P})Jf&8|KoZ9@W z8R{K&qbp;vf7)%@(!vwz4ztC(dwybxI_Uba5`g|B8)fdJ)i$*tZq$;~Ew24~lgz=* zpX0mk9^v!OFU7`KMM=%nXLTGqkR&Xh-EI09aTm}eb$}3|Pd(X>&y{B^GyK`P#eaf< zf;oFXp)7Y-jbCcpW>Jw6p3x>GyB#=wL`eR)UA~(1=wOyB$e~1|!qKvVZN&wc9)lad zPJ+V048HoCffNI8{hh1Ae=kY;eIdy<#9Qc~))LO5<4ZO3MjEKdJtgB~-6{V%PZapT z8c;~-G9}5n|EvgHE|sq_5A?{Xv;Lq^{o06tw+Tszhu&hAidU5VrJJLszz)I41VOAJ zqpp;n0X*HNz=+`J)Qnr!cCBpOU?d43F%|$}@m(1;YBoqlZ`>3l>lL$Pc%rG#{i>8r z7=1x?B+uk4a6XILruo$m(11m3Zu=1sg@#v? za{K`F_>lf4SE)4(Bd6iy+-ihhUNU=vd2F;(*m-7z6z}B6K=wU;zz-BcCMsI%!?{#m z6Yx_mq(}C^7rKOJ@>OovO@;pCHPCDQ)IALL;nnen#N&OxI*~6H#(C2XdBinN@0q)= zJksXf-=4LA6Vd@AOtQ)S!ag9UxS_6I&!PCwvBA1pH6M@m%q# zXxcv*s8}2yvbr+{vpJS>f!k2^*j#8{RJ{J?r9CHOdN#`Pzd{Pqj|*pLLO=Odj)hu{ z>u-13>7NJnZ+F)eDHo7~^i*Ds6#A_Wou)a!M}|i`l)YmLc^ur*%nV+cc_Iyz8Y%^( z_*uJ=M9!(gKlew#T8< zIb{pp+M zFymIual;vdKA%F#%(Tn(L>WP}9@4vdPPQ~8y>zwLf)rWx^3C1^KUeNfIL(+ili0XR zW8l63xSTD@z2nn5<)tKh@Cbu6=k#QgDVerYV<{6wJw|A)A)JNO5XIbEWesDH|g{e zhiWr|&wsCiEq+U6r6A_y6VR)%TJIiEtn1yECX`!N`LIZZQlvgh?ARjRB9<2Qoz2Ka z*bo7@vu9suE`IJw%3`q?3P!v3P1Hq`Ly~@PW=Wn*zBUia@<}_LNT+sW*HKwYm4d;! zg-Dv&GkmTnMmK-c%qqW-{vP*~W@T0rd~#wq(9h}1^D9G~?YKkw4{%>myz&K!piWdM z>SsneH2z%=!}YOo?Pi@U#aE0IQ6!bluq@TV^d9c@@nST_UA%<+??V176nZHwnA}KD zFolG@BYvIoKYKF^>11?WuQhtYUJP!hyJO6H1e0`KvhlnixQ~`F7V?gG)*$G5%jGAe`*%)Cn(_0nNZH1H{082a$cw;%w1 zCqL+%lUSD!z8BX<9Uv|@eN(0XwS-Ww75uKJlCVmIXs^TTnDehmVS#(@+UX+M1@o`Q zhQgYm467Hqk$vU`V#Bb``I4N50}FXf|;!abIjdb06oICsr%7T3j`{t%WpaVwef+VfUaKNf8PVj;Pl;%(+G=A+yM)O1?-{rpY?ql zIFBfH_&lua40Kr}(f6DEfM=OhrHe5PSF=I1O-6(Wi?wSg}AV2Na9hN?BIQ z61G=ZZF3Io)91@2L&fY#B0+u@s` R(SnT-|f;ho+`Y0z~;F;)LQ;Dc>(xS9T;f zH%qQtbR=!yI6S84Ph=XKoZCD7%#o6Z-$*iZ%X_HiBea|kC1&nk*x!X)#fFA6-V}Xu zF^oWNHpdxa`98RL1B~WG{iUbdtnm2L(H&jyPGQ^MPJe@=^x`r7Nd{t`H)@h>FOS&! zzMe@%QJw0&AQE9@9ggN}X*sw%cB=qw2%(||^d@iqsI@H{#)AyuSu`EH9Y{WZMr&Wvur7p0K2LOkHsr z+YjIJAeWw#F~jM)xkgH$m*Cwzssuyl7WA+i`zc=b?xM$50J^W-vzRAEmXpgc^!XYt ze4=bq7;0=qBO%NjOrb=kQ;euQif<)ccQ9l43;s$`eWd?T(YWN}gn+JGtEBO+W zuIEKV+#}2r{#AcvM^G+`_m_0`xlt|2|5l_Fh!O`+hunC`>K(3(6U_-em81;aj|MM$ z7A4F3R~8Cf3U3`7lIs^&s=axzc?uPczFI!|WH~!9 zrN|gzA(ksj@>%HGN2sd!{nm9liS}8*J7&ZKrTMh-7X+FDv~$AE`Y7daBY);87S8X( z3z5HlH@5so1IDvo!ztWvWc&h|R-6h3gugSf0$7z>2Pk0`nt2!GyJcGJ<7Y_Tk}oiC zr~uJvqG1B*fZLvA`k3$T+AlBk0=IYPWs;g$W-S70NKC@b3MaE^bbe5EKL9;g??(^l zr#g(JDy%uInf_`&#zV^&CWgc4;6Z&7G};~qdiV)u3@-W-fLn=O=>!@H7z7&ZG3vr84voBX_VbjA4wmq1x*a_7vg~wukc#<~GiT zzbnw^*H6-CuWCx^GZ8s>ZkMpR4pbrD24nyNg}4Bskp9F6B{SyaD{sLUm9mkIq$21W z@*mJ-Ssi_NHp`f4#pN6tl`7QneDosD8b5JGZinq9xU>CjNpn>kRrHyZjBV8)Xmb!!%r(GxgQWB#2yZmOs)$n!fP-H8^m(&qiSWIYRW2gZmn@dP9H+ zkDjF)w?dM~XH(>r%i?BJ1ZZT0T^=(6P{lS{VJi&j+k75yXlsM;Kr0B^FJ8%3e!eUC zl(J=*@MZEQ)b61##i@mGdgjElWeuY(uc%c6FLTQLfhU zyw}Ej6FM(WDvK`)ysbqH=~Ue6FehK*UAd=AMA6Q{LKIKF{Nr_EMG-$DH762Z-#|7e z`imd@J)5ijWV&hpWc|TC;yM-e$-CKQ4K~wyGja}Q{(Kd=3OP}Wi|N`}Z(U^My=Y)b z9bI*75>DSEh1sHG7b=>Yx#QV~cq;@Ve`6cRbg`9ecA?4sWm=~cn`H@ln2(r15|zSH z*thCMv=hU6yN1(;)5kUAE*-#j^Akk`Kj0CD<_mp}KnL;>zw~lA_{G>kxSt+35qMr`Q#E#qK>oCr&3D@UL?P6s` zPb>9PgPRFT5}7)WGW=Gc>GJ9?byK%hCY$rS4nuUc_$Mr87Jdac{pf*L2Q}KqO0dC4 zLx!NN<|FjF-4v+i`=>Qj;_#-|n`P)P6Ur37Bb4)bUkml$Z>fSSZ!pP@I~{+gziXh3 z!qgOX&It%Nf<{C_=_buo$yZJGl*OsjL zUlu@jQwARdM&%%cW1k&|47o@(eIF^{+p!9XMr5M{rTrah;#3wG?LF?&nlo27o5dPC-${*Y!5B{-f|(a8FOEhEXSRzrpAAn z++89ROK`x3T<{-|597ny&B}dk0lJVgP;yS~i_E2-2G)l`f3!cApGooDo97!ZH^*Mc)6Y)_ zC@zb~?BG{Tr2`kq(`;S*U#J*iUubCbGqEL+VaDPrCn)+5OO+`=h%;Xg%sITQ`?}qy z)bK~cxLnhWx$z@Cuhl+bs{xz@mzRx3_)laJgm}&c>9z?_&6ltlgZbGx#({G+8`ZPod!Hu{@XeAGC?{#sw zf8Zi;mA0mnwAmNom})|#tni$WwatbKDN3U8Jr1bdIqu$#6i(=r>L$nFfrYmEih?fr z=N4vC0#bLF@;|AE{^zX&ny?Ese*Q;MH^m3@POwjKeK92Mkms?nx1x2lHbqA>?*^Jy zIojnokzx>)qGBsSht>Nc`KpUN7=oT+ZB#k@b%DT+zFb~=_I4H$SN`*GKSybP*C-`(pM65B zZPA>58&xhx#T#zQ@r*NFPG6cWvafETo9C3tFle+~@iiwUv^)4-ga{GerQ;(I&%KcX z@y}Bngw{T2BR-25|((~Jf zls=03I5ZGO6+3!aLLACx7yk_qC8ZP@ zp{DD75K~+M_7PYzH+=ciAuG+P+F)U<86lOWk$!Did<_WFPF8l*z6dQ7tj_FIPtb9E zK&(mq{gC&?6YMSbJ4xo%AAGa1`>At~Sufw|At}x<;%SXQ(xS@W(E8<@@YCBLtM#Ra z=5#x*gN+|m$_9AIYWO2)Yq2%cYLW@zmM2yqEV%h7g)E2Pd-5s8f656vpI&$tL7q_7 zwp&``q|$j_7&uESo)TA+T&XuQX{^njKkcY3W$vx(PCXrvjYsklJ2pWv zfY{N#3Lh7YoQ(s(3}Sg9BLNofMPY(@+P4LEhAjA1*^T)6?%=*xF#SP~Ietm_o(`yf zO!A0xUpssD&nWGFZ&u7w>UHwH6joJHL_jwguc9bRBJU%U>N|6&iWdrv4PEPcN&HLr zW%D4AnzbO-Uy4REgR^j+uH6VBb0mMBPI2D#;sFEq{-pFTh?2v97;^OYgxqfD=_NT1c?TO&AD0v5Mq!|fB&;mg0DKX<5kG;_fk-mawEgGhmE z;f8U!va4x3nArPagdlsAj{v^kBQ))UaNkLQ8ObANLKzDL4cgJcM091A^}*OcORIlI z&=TC*Ec!h*et4S&+rT9aMR{y|c2E$wXh#=@#jj|K78ta;IgA7*rHQBPFpmR-=EyQA z5RSAYMdxmJAxpG`*O835mJvb8=$K6Y6q>BlZ_oFODEZykr{OYD;ze-(-cvq*UH?Ph z$^3PYjpulNS7b^xXiazE0VgRwsdU-V7faWCvSaA~_vl2CV?EdB5UIkfgu(6Ze@@U( z&uD{(-&nFjs+y@2<@iJz0YsGaC8Uj_dNzh4D1k8b9Wh+%gl52=&@{_*p5Juhk2K28 zyPbe%ckaiwXzI+?LAkMJ2;TFnMJatjA!3KrgZm<6mkO;k z3yy^-ozy?`YW@2Z?HKXy&=JwE65X;qWxMHxj=X#s>MuWO{_Kb8+>JTS!wR#EQ$Af_ zB6iTO8Q%;GY#2LPNtdPzyDG;|g7$?sOh6X>&r|IBGCSJ^=FUk7D}Dgv2)P>~SwM*| zq(f=ULsp-RLHKnTD`o#GI>O9S;^3nIaH_B}C3lHgDRJ50TRQh0FyY06NN2RqLVimo zC*WCpj+El;jC@_R^&o7$e#z&{b<6wFxr}&KqJYwexJiWPsLVLA+=7K*Oi3&dEhwM^ zbWA;hJ@PCvb-JcCEA{=OMf5(s|J2omd^1u}Hk-m+cq|O)!mf)BdC$MyS=}F$luIo= z@5x&I&@x)slljiC>?8fx>Bgs9?NylLI(*vjOs52CMG`nqtVJl#4i{M8K^4kWxMX%= z5GMgqdUN-Kh54{MRXB{7+=)nl*eU%_vINZC5_G0MpDl|$2MuP;8GBRf>{Iwz2!qSGW zZmNBc#%B268>3+8>x?9~nJ)Hd1+z(r|;na~%FYR4~g*)%=+dH)qhHvh}^w4apz(kN#Oi%fYjBoEcW3wp=*RPVv+X6JDhhv z{z;5f5N;jIi%C%EjI^dvfbd;X&PY{y@+wc=fAG z5pdU7yX3v24nlmJ-PNLrv?SX`fd3@ZCwORG_1#h)TcWCwj>o-H6AbI_7 z14Ew2qPeLmq2ysO;@^$iReh94v!)VKC{A(3kK_3K8JLvNMnaDsuG|=EjPAr%3ilOK zdV*!5K@w$NpsCL}LkSz^pb3XG#-jHw0VcB31XM3yu}F2)`q4a!6N}MpuJ!`$eQYfV zN7L5!mES;aS#;$aQ5d8wsT-Z!Ok)3e>Bo^pfc{}?#YulC>I@s5htAp0J_sB|TlGfb z>b@U=x^fY1)_lvPs&zSd#U?r&I?6QPE5$5Gro`#-DJ#DnjQu2$cp~Gr61?Vpg!2W8 zF0W_@{y91jU~F{Op%U>^?*&c*?bPYAdRAYzNq*P#!)J$!kuhp7Y{Sug?a7-F@T28M zy?pjN(wmuN?^e8f>i^;&0SSK|t$WiGju9d&Hc+e((RNAgZgo%KDyoB?ET}I~mKP;D zzB!#L_k8y5LpPiWw@^cYS$>vvUu^E)@6ab-C+*^cPy#hOiohk7$KkGko=xYWHy z3P;0IfYVI;WoD&=0=1ENfG2?%h0P1>m$nA!fe#r-(3Tj#DwYF#DMi^>iAF;VQ>T|> znCx3B$tSM30fZ>*qInM8pQ4=?Iu6C#`6?YbL2I5mz6dBfXh?y8p~mQ-o{a- z9?STi%;@o1?T*^V3Hkw6Dg_e4Y-$RnczX3x(;5XDHf5w0QuNmU+Sosm@5q71q8%J) zyRGT9#rItG&Q&@R4)+Le`tJlp16u8(ApshjxM>p_v&fPm`a9$UEV8_%FsaWsP^MGOCn}IF!oJIUlvD^5WTCSE1vGr`r+!-PR}DF#!eF z4*i=kP$J2f?6`)$TQPfst-bBdwZ@Cz{6390Bkj^(B~8b0nf@G;L&nJh!38BD7AaGJ z;d$mV-cRsVf{X7hHXE``d5_I zwGfgsOHpsTExTPRg=A~uDEIZOoa9o?0A@^7JvQRJmN^gSpKvPg0PDs|;ug3(E*jVt z!Tkp&dZOR{ub=n~dqVMct3qqaV>NQ?xQ4kPS0QR}Hxlbfz^Rb5$M$Q$fN)-Mw?WaH zVEJ*rf8XM!_F+}99$N^0rtk)8`%3TiqCe&Wmqq(ksB5yO0CjVLc0#lk^Ic>v%JEYv za!X!U#eC`3>D~^*b!7n`fmuvfJE2T}<37V5=vhin)##_mwB>M*1|jJN@CZCCgbc&H zTDXS?tZg^Vs5_^p@9ByAD&I&gWgBK2COrY=H=EdO90lQ1!@ZD>=oE?Vz3sqfvXvF% zXZi@Q1U>tRIHsdxM9BK46qTTrhr`xCqi2&wHh7|)=tfA$;Y4{LfEzXTs%`lo9)!Ab z391SGfc2NPf&3J{S?+ZlKL;IV0>aJ()-|c z+2Al@C-GTT3gk8R2Zb^c=Wblj=)f8|8#MkQkhy**PxM#DH+j3Bm6!OKFg!!oyDSwk*(dzW0WoRRc`n);um>-$Q zaW|=RVoPWq$G{Cj3(%Mk&zS|~`EDBGH?s2a&(jz;D|RlDpCGlOJBK@oq}JO|B2(7# zh=p)R%^f1V!a4CryF?v-#)r+EQ?2!wbjMu5l3cC?EKzhmNBqywgZtW;E7R@8pI^o7S#S4Fk)9VI3u+TBt zqvsatC#-O_-TIJy^FrH$L-KK7~xwD zB~vJ_P?Mp!QJQL z9bOl-S8tv5@>U8AJ!cn`M<0N-b<9;d1iMYJ#bIq=0|-}NGB^5n6eok1=p!B_0P>6uD%@;G*g3AdINiK(XRN| zVqq$6Gk|f^b8;yWz3BgX5Q_ruePyh3bu;dSz&cO)60Khkb7YO{yEq6V9YV8m8nMmz z%siPfgbbZmcqLsr>at)vGr~4TR+c@9%dVi zVH?Xc#C7ggjcEkoWM(A|9sjr&AZl0~%6BQ6h8iH9Q~%d`6oRB7L9Hx{ZY5k!MWvE!%{fe=~Wv&G=z4PFX(& zQfRw0X4cbca8jL_c!(nAa|I>Qq?!7Sr^bwbG;q*m3}cKX!EP4z0IC@Kz=xO#mjY`y zta$}+anw7p5$_bI(fjtA#e;!tNpY{?Tqyu{kL0Z!w2)ovJ6vvXM z2S`#t(s`_r#cvY5Eh5@)XA8QcWbas_xjr&X2THJ)zDdHSm{A=B5toqpje_d6Kx4Fi z!??BCY3WbL0%~BE&&ep(X`jShel&evOlX5VZ4%sWJ&u}IC6e0hK%iv`o1Knf*cW1N z+K9BL1%4(cX#?k!g2ZI!$?++Ty|$j=sx=?sGHf3(i#hReN$F)F4#z6o(WX_Xo%@`# z>un4yoa6)M5T#zu&Ai%iOLqNL2qp86;|Imc-FEPeP{+hSM~jRjEy72OcrSb`L;C*S z2auAsUkx@vitl)Rl~Ktzvk_y$8rYv@*zU+wl0kiq9*J^>|4Jn9y}X-lZnCqh#V9V- zD4Z)%%d+#yk(@K2ks7>$jrU)Ub*8TmI2dosv@_q58!{*xeR?GLIkl!QJ5{L>t*5tB z%J0|*uyp?s@?}+oFOl6MV8s}C5wEkI8TA67^+)q*=wuSmGwt-jCRQAh#dyqEmvzOl z`}<}|aJRH<{{UyN18Y3}rR9Co7N5qYq6c}BdkR5%5Md>39V=3sL7NTe4Y?YCUdqa# z#M1@z&CM;=PKW9G@K}?HPL4*pF)iTjfNMirU{NZsw7z5eO9|jItnX_t`3oSO>V591 zLsaT;wP+&y_X0Bx2*G_26iKNf$K2Kj|2CM5jySP*GL3qJ0$HXBJN*K4P*xl|E|VR_ zel`>rrW0)3=)3x>nx)kKIJv1D7>GABHIBK?Mr1fyJoD@8EMA zdAC0IktO&HCF|Dknf_7Y6pM??KXd8s0oQnzujTDg)K|32W$uI%{PnA10bUWM><6?C zlT$l)Z;Y0v^B5TYq+UETny3;lBSd2#s_iev&PEzW^jos^jLsZXk8N3g9Af4DtdxvP1|)<)E*gKI8<~Q#}8}aXk+*#=r56T8$Ut_`${&qk`U(0*% zEr#zZ185zh8(ua61B*x-7J+HyD(`M}>B9t(IW_hEgoA4n$c&hhwp3uLL#(h$vfbl1 zS?;4iS{!pkf}#nxN)|EPf6&h`?=ax*N@?A~glJ1nBnE(#B!fA?wsZTpC^{~asG)qH zRdSW4moQ=R96VyJCTS4N{i(vqed84A>(O}#+y<}5T+e5G{=o1;wsY~<`Wl$=AL_gZ z`7FmpT!Tp}>x5&ySA0PbDZe@wVR(f>%3c^m*r7ULL4yyM#?MWSLl2+)f?H|^>OU19 zAQ+}|(MjFoe329q23hJ?? z2;SuhZx2_QpD76E5xviXfzN6Mg`Xz;nEyu!hj^UQ>&D=jyXMShPH zfx%WHz?{k;C2ltk(P~A90mAGg-@~UoL<)25VN8vsc9L% zb4V70I>XT?qiiOVtjKRP|UU?OUxSO$W|#T zXv15~aBqTuzM{}p{wit2GE5&q6tg!O@*|c1SqV9$>zbQikY{`8IYU1QIuK>%9;5cC z_e)sauGv2Upbsm8?&bmVSgv#U?#>;~T%2W6p_g=e(EkWyWa_-1HFza4o^IxH5^H9k zb^S)z_qxpTC>-rQ$!xuFxnw^68U5VSF~S40mm;8vB~=RUcrB+@cK$vaohJ)}UB+!p z)a2$}2eS8NZlp*$z$GUALK=$8d|KfR=iK~PZXX=b8_cIaW&4GBvb6j2K#8P1`)AmcP-tgrilJmeh|Yhi^2rf@%R?5jv!msok;b7jBsQKR%UsKj_O|{c zZNKzW6!*$!hmpMh0p1@Ir{YZqi*emc1PE^MO3&QxW(n<){DjBGpR}NdVUO+~F#k}r z7`~wMH2*$ioFwH=jP{#CXm?muQ_{)5Gk(wcb(GDTU3Tw+{&u>M(Nhq(PYDG<}((GFE*VVT`|=& zm3|1f5~}R?BfDZ9)~VZ$R$a;Wh-;_N?>NB1sNie%*A5But{-^4*Cyyq|1(q7ZKD4( z`8}NH-Ozf76HavODKujbMYiFlMkM$4=iv0(yK$qF&`r}RzsgWerxtsV5UNV{D`4@b zl4Z^Z>nOCZz_Cz_#ws{_QvhMW=^N6p!O*5GrCj1C+-kWhQgDN`5$*5R;{*qa70q%9 z#O%dF*#Ux%_@P~p{uBhptOwj%u?DP0C(Q!W4@|3qthcif|UYCW-Mij z4cLtfCF^$3S7<+pl5U7^x~m#*nl3PG|8d~vzK|d8ejpr7MHLu%tvlWOW#$y^uLuZM ze&8BrF%bRbmzCmNp;%}KmDQRwb5u=Id00B`!Ak$XEC8k!h|&_(9QA>%?6Bf^NV#J?MhQ>D!xxA`kW@-v1d>P^;f66y9uSjLm4EV3uc5?4Unx z#x}#Ev{(7$ajnvp89$Omg}-AWyZ6z^C^Ued;u{C1bqSd;6Onac_gwLGoMYizT42t^ ziw5??r0 zC!+SEOmyjW5Ry1JL`wF}{Ia=S|7JIgA{5CW2_(WE=HMZK3g}p^yg6V9%E-P?VT_MR zolnVl9lCs;QD;*-_pTUsuhv!0oG@T54wMZX3oQX`1Frd0t1eyfG4CUes#?wN&uj;t zV;`trm$&<8WDKxbJ+(hdNpp$~OT~D^^a`;_f;lgDT=b)NuPeIX3pitL> z!n^p$D%lF>Hv%*&T{FTMcwue>lOR2 zLKOc`CWEYy322+?-9t5$#eC+-ho12RY>837bl7FTPRu2Z<7=$q=lN zA$p%r3_g(_Wra4QkqL28R(`8Hv24MG2rB(_+Z$2K z;zfU|w%k2&pH=4*g11Y5;RH5;+fN4MT@L>uIli=|9QE*}9BR$@dJy(Gp12J@W3{gh z>_d=Eo?@Bqz1nCWv9Vo7+JG2WYY!p{yC!eM5H2rRN^Kjy*abh4JwKZHeA3-^09@OZ zL&wkfnFP@x_coK()54z_9G-uQyn~Sn6rQ3tjj#TOJLdQZX3Rpq=&tQE*wWte1EbaB z|6VrQwx!0qPPC3=b+zD)%5{!KxxM+~FaIN4m4Sad8tYE}1PhOB`1qIl&Y6Sr8(KRo zUtV9L`BPWretK|Xg!b#=zWj}SyuQk0eDp459=OGr2C;o9H@XfHds{ls4oi>icAD%D znl0crRk6v0Q4dau;yNg?bnUwFZ_SDx?fG}#oVa+|*;_`4lN}lqH#zWd$aA4gi2hXQ zYdZnZTk;VfDtCK^+C({)6`D1u&OG7h(zWY}$mwI6ghV{|wK~Ia2Aviy6`XdyS|YYF zhA*k%N&#>J(0!!o#B=?Pl4H?9Pd znmK(ktRJErQ-&IS{jmjJFMo(>I`@R1*D<$Q7w$P`$Pl*u7rGJk4A-rh&)9hEiM%29HA6-Zo+BW^ zU(SivdUgS|H>#@&Nc*XaAPsTrg z2lXREIl~BF>SW+U`V12cC3Qmp;(#mep$?F8HKe^&>Dz+jkm*^$1#Pgq#&qLC;=$MU zb-U^T5kycCQztvDFnbVqwoK?tiQ?KWNBDu^^aa?YmB`bU@vWf30#{hR#PL&mKN+ud zern$q_8>wxNz;`{u1&Xd)#TW(38gA?pf$$M^b~~!_I;HW`xXrTxSWyP__S%YBscq` z_RaEGKeC6hX$Wli>+_5ZDFJNu3C8To9jg@jO8$j4w%TY5fa(n^H2I z)LM}@weeBHmR%EE0mA@xJE8n+05)!>+^(S}Wvo=$jsY%2+wLFaN8fwO4)hets``$| z*4>)Lj%;LybfVBNQRM=UJj&gdUeZji;x9)za4X0Y6m!@L()Pv;{js5STHH%XAM-FP z0Ob^+f}WqtN*`5}EzZ3GSwBuL!O~Mx_GR1mo!yd?BbAnIkuKxX?{~#|?cAc#g0(g& zce+-hloQ8C#KE8N>=gmaGzB6jer$x-?pfOugDwf8X;AIht2%XTg^D{ z&++Q7g!vt$==IUdW@N8TkxnQAUx*t@9ZJt(-IL=79MQZJoW7Jx72#iCNCn`i3Xjw9 z2*8~;sLGr(N{uA`>)ShL+JqzY{Nc+|Fo?$c41!YU7y=V4I71vud^E z)he|Oo>LOVLoI5wBaRryg#kkMUnd&Nc+9~@FPJWp3NuqnS$>#bWP|zZVOnCcg)$dv z{~Fmi@}s4UsF^lZYwS-~YgH?V`pB-PF1oA9lCx(&xitDAjf zV2&AXGd8fc#Pa2e$5ycUwe*1%hv`)BBXJA~FhiiVTLkBgw#ed*x2xM$t3vOPDy^?X zT_|IiW=}c+eF4e@8Wcl9qoVGStE(dE+#o0u^&98+=-l7s`ZE(yeg7Xl_a`1ikFJZ7 z?IS=pl8V&mGo-dT0Sdw>PSPk7y6yhfyU6QJZ|lkoy}Uhf*o<8Shn6^<_zmy<7@52& z3eWUc-uNzqW?0xw4nh^t11QEdKqLzli9)Vf(IUXlL#_Pas@b*S`rJmHlbU|vO+AB= zvg8dnyxkfG%f8Al!gp^5V6vs}p^qu`d{}$Q8tH8bN}e-re3$P{ZNQrrmtO#p!``X|9MvSur@MX=MnZlkVS<%3rB*?!-tCMxfGgPn3g1#@GrU#z^oPF2a)1eWh^_)H7;Q4UO z@Mkgo4On&+R%O!>!+;;B?wF(#QYHl5my`#qTaeX0QPb4Y1~r7M3RX`CBfoG|u|*2*?Ml#PvyzXC_CA zhmt!5JmP@3#Lj-aIN&xQ^fJ5hp{tl{=A8R%%qYY~-DF0ML?4`UA>@q~h`fcipNz%d z{+aKWIV%taOrI&dq=Ep1MeT`glYU-Z%ay?q%?QxaS38aG=EQsh?b8F4z(gIZWWPd$ zLDO~sMuN1!4L-3ZqbfP;G$2)9LiirYXcLX-p38CCh)Syi7i4>SNdr@(BI+#_R%078Iv5|5Osg@J0#Lk?$4)8(u3m4jMp z&bt@uzb3`=>JRMT&nv>gdenmP?yMzbd(y zx+PO811`z=I30D=D(YZtb+2xjIdA0zQGVs7!`_?*Y&Ff-Wl2ws>u~l}1MLGJL{dgR zbFS#n*iMJ1!je_AGBV3F3)4QV;n{O%? zEPd>C@|so#EPx)*#Rx@m#B`KM@F`zEaAGk+DDDB6zLo@lB5nlWBOC8(lDTu6$kL3= zQ+QlNzFOiB9Ak(nDV^%ml`d!(Xu|In39uSZwljy&pgJIJQQn@xS6MlQ&&)-Ue8pH}a^un~l|F!Ker6sEFAk6*Z4Fe4N&qNpUjwl~^A(GBD*1Fwn?reaA#Ac4hwvA*{7jCl$4vs>%N{P zYO$&=aU=31MwCQHzOJ-PLU0r#!0FZPc(G+MkiA6ZWE>h+-)9Bw10t}m$6Fv-R$5HI z1*biGjx?#f{>B_EzoQ1P`m;;LEYaSLx334qf9NH8cjet#;`mWZzC>}A7Qa`2zX=G1 z!-@TciWKgl8`R1?!Yx}oq@Aq2_^GE?ACxnq$VcwO+%MYpP*ZBMA0KIPk}?0TmE|99 z@CSy|q~SetqdH;RexwlA_UEo5tk`R&y3*hcIJ<0KO1fuXtZZJkaDBgp32=0ki=ZhZ z(n}uf3!-E^U`L#M-3xmJbh4Y2eFzFVU-(+Z>WCgp0ptw+(y4)ULkpN*x%#D0u>qvo zg+gmzTt8JScV58n_=)PrMz*VbhAIMwVwk~jl;rn=0&##A%pebfspk|_l)j{SxRoWx zv&*rs9k9A@kd@b{CaX5qpu1+db*q%}gjiu%)?_9$Uc-&@M-jE9As|6%7X)TjsKOtph6@okya z*ErYY6Pc9kM+ugxM*0~RG{i;vG*kHPIGqbBKL@BzEzLen{UtPF3!H|VtVi-JY!^QZ zmsI8>UM)Od423L%Fq7rE*g}$ccm^Z$Eb~{#GzMYjc3UiQ1!~3MbJaxD0*#UcR;VN+ z!*jW&8A%cO`OSb7N@>kbNFEFk0B~u z?*6{1Y+NYDCWt(m>P3GEqold)usMjacQ~t9VZFW3G2*%nthv|!EG$q86>fveY#D~$ zWj;`1wggq&28&qs_3JZ6@FTy{kXDkbkkYEjqXhhWZo_x=hsuq&sK!+)#hUEC(^4K% zR8#6TD!3+ZmXppi0{_?h?S zn3hmW2L>yl|459$&8S9WTw_g$ug;ebAp@+*vlTYJ_jNegtfcukaT#)``Ox2;t_QVK zFzy)cDn{nT-!x++wcleKLmH!mG3>Fmw;R#kFw5Y(Vr_m{a|~@3EIrH5w*5d(@E`ej z(N5yy1@IgZL|q3%<7gM*ck7TXn_6{z*Aj+?+Jkl!F`$G41cqPoBE^@DR76aah4FRd zoJ_)N(VaTgs6V4&^6!sfdfTb?9{6@+bdB3(4kx*U)cyl-LR@JTc5Q41gL@XYJGBj# zUGGvOo4=%a%|GRu{PMlm-c&+{ii5j3Hot~VaoQq@qk&t{RY{-1giSiMr%ERzQrtaG zl?6qxk3?GD*L3|xtr>&n-XLvn=KYOs0aE|5JW>L`E2>4*@A^%&vsYBk`6=~n&sW1j znr_<-ln}e4{YIL<8?UJkFFpkxX8_1FuO_A1-2WwV_U%cx(SFFWYVY^sH?iP&?GTp(+t|pYJVS{t0)|V}>HLc|5eSjS?L<{NdV>)bne#)tArQVQ04r#C)#JXp?y z?5bY1W}~cF7i{^fTxmB_KN(9s;mTyu+3VY@ZZ)Vko}M7~2v~ki5Tieh*cKxii~?Sp zvm>Y~>(4#M=Z@F~#oK~b1)XRazsKjk{gCU*c+sFWFzcgIKcZB{GOxC^WK^RMm0-(| zh}^&{J-nIhWpC=d1P)Jlm2{fc7>>IL<^BaXn`BdjVE3j%i^kA{8gUIPBYAn&y0dGdxryj+m!E)CEG^2=I)$zpnHxNZB#isdus1BRDX=XUP;t11@poSe8jEYNnq$PYP;C?xzThXKAZ%c0@>iPPJO~H+Jod;+|9q_9oy%4Ch9kpgi@bYYDJ6)e3O)6qtn{} z7pAo#J88fc&n{#cGoCcRpf}oK9`@4@vGY=l?=zH%1UsHJSTvBt>BiyyxnVDPvgJ!FsS zs(#Th^~(Sn;H_L?rN79@m2T559)r{Q#7vwSVlI;`lPH8b(JZ4qk+a-qxX5pnE?h62 z03ik8xF)2)s)3f&CbYrY-_=W-LOGjt<;)@m`R?Sh#}Yp5g;wd7insBbTu)E@B$lJss9gcWHoQ;Y>G$xOGq^2n$5j}d19wspXFAIW;t-t#w3%=#o%>8L5^ zd_JN)gU4?sP3?>dc}3Sb7U-A1D42}t^#g%sDriZY``67bEXb4RUQvOOGB#uO3T@=D zGTQ*HP%dHlh^f8lD)&z-4WIF7pTmQu+{=f3^hm_Uu^c4H=S?u>7QZr~Sv_DM`+N-$ z2UE(=iQ$9>2`hnOTwBu$QRP0ko5g6Shf_Z{Y|mXMJfyp>;jf@iteRm<7P*9GOL!Hm z1Ay%)6jaS{iEV;@c`IVlO0#7I=sBO}dKZL--m^L}!*`v-N-H6GIw&h>1oSKXLnwR% z!`_=&UNEuCP5@^?lYxTy+qrnw=QoLFHLm@i01Fj|MTD~aEtWl3EY_86a&%G1SBzrf zP*5>>3^_rj7|&*k&UO0{^zbaZYe8Np@oKVZcSfi3tG%MBXP3Gog_U`%6?dJ>k+8EM zm_>q6s>9M{Vc^YiUuE=H>GcN5;xp`GR>@+^+5&q7&|NP)>tDw0r_?R=Ys0revryO0 z5E&ninh>JU)eopNtYqf2L^S<S?HJ8In>wo^%}nPBNSL&gUUf ze52kQFmE^=xb`}2^Ynob;W}I?Xbek4KPRa!;xE-NO`)OP{t3yG( z9*}^JMX_dYVH)hLwk*S8LZ|Uq396x62Ud0X7)TJLo6wwwJ+#{ZHz%~zfQv&?Sl8;Mo*3hAm;y9$c{ELewdb$81Rc6zxcAO9uFha z&CB%ONAayw(O7L3X17V}0kis;V2sT$ehL?~P~7am9z!r;x{K<_P< zfg{`MJ6EUV$ZHK1PNU|wG>ib>M`U3QhEb_SL(qrJ43jc?YTc89)8Q_^PCo1WtlZVl z?W<$e`YA3shP^vxSQIMFm4aKyiJ^n^-mVM_O8|IB9ygwb zFGb#1{Sy*ik7ArJu?|&cRP2X_O})iBtuxC5-?ErE*l!lkX5RS#pw($Z8OBoctNo`o*FL@z4C(9heX|9fZI0l{YLcE;(&hx8|-whNzW%|!zPa$ae{PYb($dgi87kO zFJknpzsol+&;MbzTOtx^Z9RafW2fDUNxaezJ3kUa zz9HLcA}OA5U5Et)@9^E1&njp(gP8D}4zwV8wg!flrEV2O+`{@cfYeY5=3-7GVs4)B zVcP7047j>wr--3;Fu4x&*0${?IB)OCnVkQFL9OBsc>jn_1oes`Fejn8joO=0Z}Tbl zh2-+~@b}}gF~b{_7v)sl?xh>GO~+bC10ds6$(&Yk^zFUAuPlZ5)8U0<^0Kl&=h4ZS z#RZ3CvSf>a^qvq&+6>bVQj0c9W^rxuDku2QQ3WL#c3b;{8Cc0-1)&3%Y8i*&q#s*2 zUW|Qg{Km~z&!`0%N{`lxc6Eb4?{zhcWB3Nm1zFP+mvOKyNQD+7!MWAmrI?U z&H?$zuR=AzhiJ|Ul(u6=QehkNMf^n+*&>B-&`=3zhK0EwrdXM_LAv)Q%5pG8rU??{ zUe&RluqdGevS$dImH)&5XBk+31+0ll@A=rn8d_@jq~=feM5Zf07q{WH)%#R9$*umJ zv@o_Q#KB{V!0uaGM;4u2KTlH?u;M=mS@N0#_y3#Mwh<`udO&vnk4yuUJfn>NIzua` z-E+(-J@YcH&VBeu-<#<*50}Z2AN67H>gds#v-q>2K4J(wmyhG6Y|_r(Zf@Ke6MJ@O zIWI2j{jT2W0hJ zk6WbJUr5+CsJatz+IzCUoZvEZM`^vP^+Wv`rcl6Xkwm|p&0k`swgDal_)wDVFjVDD ziN2S>Vl}q>VC(02>OYN*qXYiDR0@pswbt$ zD6*NOl)ak{E@r#Uv1hy3_x#Xv5YPeEygn=+DPhtM^P->#fN;OQn;@kCk;)I_RP&>ygJB-YJKsEB@xiZLeuX(*ahn&;9%r^`dxD{1r1lz3VWL zU5p7KP{I3%{n*$8!-C}gj)r2PEGpR~-_+N}UoF#7WZ_!UH+5B%$B@TN&`K|)=M^p3s zb<|(t>k@Df@AYhX;BekVv5@0F@3Q%cQV$jBUyBEb&XV&CLHa(%|D!eQ3o$3ePYo&O{I%gjDdd9@D_kf@YSo5$qS;70kS$N+`oA&F9KZUtoqOh4D zPTOdzC0xz6387-EePcYD`@V>iu^v9^I~*6T^|l|yQQbs$L6sbTZ?wm@nJD8A{Zb?h zw~N~5-kmZ?KB=RR>m+^-$R%@x9ablGUL7gt9T$LF(?oQ*+@yE&liuEqW8WGeQ1b&5 zA+NE{Nr*PSuE=%Zbg*uE2%3!bm*X0IHV2yQN>$Alu&9`RIlo5xbf0Y}fqu4>FggJT z{M!oJiqPi7%Zpvo6?nlQ;CB>uQ>>C@Uuy1v4w(^vM;Jd?ry;U*y5iq1*w{?QLVay_+Q(gaCsTK|8HW}4t|g5C>j~MEeCB@=;I_Wd=B;Z6Rk()K zSiPGo3xjlL28p@UT8W%_RT9S%W*n;vw?_)yE%(qyrtv>Cbo1Zqo3UwPR^Q8NhIcIp zXG>Bzh`F)-DtQfedZAzV7p3MKoUS}sFOK(^!>pl|{<8xFNEd&sNv%luIdL$~3s_(d zk)M|9a>@FzDBC`Xkf0f;r6U%~MPbOMu`#=*FTwu-wqqQ5&4rj7MwuHF zr@=c?QZ_AW-kE0ZBgt7w(=ohe8GVg`c_5;s;Nw3G8h+$KX4AE zhsIPViz=0e^fVm-apLiC5pcMoNraF`_x$@>&~V;ndNw59Ly^GwD@`A`wO#!j3s4F+ z7L5LX1TW9a0xbCe(-iPx^H|O`nv`zgqM_YY!DG#7bOYN+aLx+m5BfOICj%kI6r6D$ zR;krgEa@YkMF2YYU!ly|b> zI4+?W{VEwRM@vZF-k=@l_xl<0i{lw8|ELW!p$RZ}!oA?m(ncV+-R()^NaAQ9+#{Kw z#C%*zV)%_Oy#A9L~C*GJXCcmvFW8eBPr1>S0dA_fHPoU5&O;;74Tvq}u2ZINoH09yp zd%U3?fQ_h9`sLQa7V6gbkTUc)BUUc^8~7hjqzVp%@tD{&R}MlbN{1k2VG1qEp%6hu z^0Jb&U}Ya9M3FnHK9WAl8<6Zvd@bh$Mydv0B)w2)1&=_H)#TX!r6c|~?*z<&hF1-m zP1E~qKZe1yE7RBvL|?$P+9d_K6OHa>WWfZu3iRR`yhopV=dncuIf#)?n>|qj3B)@_ zWIL}Fxo^D$Riv|=6G7?&FO1=&%->_ z5?Hi)H}DQOWUDzj4CNT??VgO!J0NYODm3<;9%~lQiE;RQ)l_a8Di9(fw(@8tVOQPl zf=%~#wWspY5jdw#zH-h{QByCV$)0iM!VBi z5WvTIxf@sS4tr#K5l|V zI1sws@sm!F@Xft)9s@m$UcSd0TIl;2h$T$2gw79*H_c?>FI*FHu+ z234a}n|JU|aka8s@Xa*dq!oK~+LI**H-2YlW^x+d8KZKu-VB>+e}X<;Df&BE+&OK? zTY>@$2u#uwIDW?HD`h(*(yff*?}ALo+#)eQGyY1Qv)o=0cH=|0(!{GFJ0vGZf z|BWqW!Gvs{R|A7Mp1Ar}=d`1F#TU;m5v!Srgg!P_ykr*)qJcWfuf|D?tgbUex@1T+j**Ygdy#8i&lQT4Uh+d z^*wCK3KyNmab{RTX*Yb>E|{0TIN@)$*JlPL+=Ar~!V(&eGSmeL%36y)&H@XHbmv$M zQ$A!R5S~KEUVR&jM#Ac#xwT!;Qzbm*nQY6KFNOpy5`a1ZrUR*jb1Q*AG|FMG*CyikDDI zB^sl=h(iK0`#x;G^$S3xWoZ@t~?)9Xs6_|BT(m@P*u$lJ(r7mYsc zw{_wfmxZ+t>&93u=2~b;QEs*7(ocC%ShYs6sPV}N>CNtEZ-3(q>**|g)P)QX#Mtf+ znDth}D~kKlN@CV@sGDnf@zEy+Ms`X@x(P(WjMT~(%*y7$=|b$99|OtY!4%xwdyV6* ze--iLhe~YYKZXp14JA$;3LZZZ$96 z&>M#w68UIc>rzfYk)&i3bcM7E2pJ);^cVPa|DZLtJJx{YrS}1S`u()*o|3UkU~41#NEK0I1>r~-qMw*< z%DQ^9<>Vd;FF`Hb0VS5$$e!p5xEiv~^E^%_+Pd5+xjoT;7GtbRqNx7z3k@j&@{GLf zfruVkRsWAnaHRqxJpCn&MJwEJ#Xcs*EHHYs$*j=OM*R&)5J!C^-ZAV$lS$t%vqZP4 ztnRE<1oj6;c7w|nNfrdTanw2A!?f<+8#qb_Ena~8S}>zdshW{G=IuTF`8D*e?eEd&$`4S znXgzU@2aGE_e8zF%6Cu6J2GE9^(>|}PXBJ|3($TidTWno7MKq7QT@{L&)Z5#!&Yv2 zuwYjbmZl8b+gu75x48)p`@Bw`C!+jLr2eQtqO@!Y>YZ8*W$i4DUu2~Bwo3Zz)h5+3 zZP#|QLboNRT2!&{+95O1lO-mv`PY=U0f3)a`@o_QzDfez7Q)>@eeI>(mnU^+K;1TX zj9uec>{P*aR~3!^b)$U*43pxpJjumIt*IxEHpZv*PMNgd1k*j}y8+*c}S8i2y zdvgqx`}XPX*Dbx~^(gCj9{iSH2cM>#KBew(*l6x{ZT|C1u8D&rgKv_l-FWQcmlJla zY0WV#X<6htN9t#G#R&&|>QNBswGab=*}$4o6s3P3VftDm#AN%-x@!NGpp$OY)w>Aq z`MG1WysLw1XrRFA$oB`LGZKbB86Fr~OHdm}Z{$R#%YpJo=r?@&SnAddYSQ*{R&mz? zn3cDtY|l*X?Y{S1Rf|eSDPbT$8FDcv*o2=tW)A^v0RaIVcm(Cz4ih>T26)v1BiM=% z(rdDB2{Cef=IYJy^$PEaHcqG@$WO=s^&u)mk;VId-y<{DdLF4$pRDv|+IXW^542L^ zj4U9>g435&l&8iqJ055E^)!4%&2DkdcgK6)yod#A{lQ_~^QS*^@&e})L6e%c;XPyM zsh0#SU#&9Q>gGAd*a^4u^B%$VLzvv%m`66)Qc78jFy2N%fm%T^KL14DBIS!R#zs2# zeUlCot!CTvkM6tHbn494Uc6Ff4LuOF&jd~T9!p~WmSsJKYKQnSE= zmJAEZ_m%iWY;z>yCK>LgKUWwu18J)B;N2(#A*$)=j)6@#g2?c@?vEPgJGRTii(U-U z*`-rP>#YJ#f>Vk#d_+~z8Kb7zY10&$u;0|J5xcQ`dGCLuyFr4jgCeuOu&2q zIAH!}k^4)I&wY&I=MU^zT4`Eum#zvN3b=<7q6OmW&QsXzQ@+XF$dT~vkQhy|8f5A^ z;djoXS`oUL#)osp7Q_{@YU(1x!d22r@oZo8^M81o8zQGWNP({9gquHVj?0iJJay2w z?lxUwg2f+pqE1fFhR2D2%9i_*A%V31#fTQa1H)(UaroP>UUKRd4O-|VJ)ctcd7kSk zE=c~$wv^;ulIIQcqUEN?nLup-|Eb3>q}6)y+@Euyb!&DaEHDF=j=?R1VzDR8hY8#M z&o0@*l(({?5f%XmofThE3N8WCd*-{GU=}I!N2uJ&u#tWXzk51POP+`LnFmuN&31MP zTQdBk#To3m|HA+nXaKE7b6rZUq?YdL%opi)%`}JJF;Sko?2n{O8eXTH{s<=W=LB4z zBuG=^`B(Jt{z*zSOmmvWbU*A6^!mqZqUkwA6W$PM&c4PDkdNNiAery_%&6hYPbnz5opm7LW|SKG|t>%SU(KSeu_=- z`n84sXnfDP;qvTchTGd7FxZ!${`LY;^uF~gga3^nqVU6}SQsj1X?o^trK66sYr7@K z%k@HtE<0;{B9kmcpFCd|kqcRH1U+H9*rqyh1M|_FsI3i>2aRwc+SRP~ohscpsL`p3 zy@-*BKOxH)?U1gZD!C8G;r~1{CZT+fvam)HrYs~~OFy)}def_2BesxZOQ@ zaKsxOTxGt;%$@FxswN2&UW|;q=`U~0GvWru4bCXd&3@7?3HwdJ+Kp7t6OxU`_sWu< ziRFnq`wXG@B+Vw#b&D8TUhF@P)J`vpH0AD$>*d{>=32{&KILx< zS_JgBy;05>ew9mN!7r>L47q+-7xO;~+B#bUyzz;mzBVdeHl&=dqvm;S!b@aWJ`lIWi+ew1H`V}46p&BK=Ti(Vl^>)S$2bAf*F za}2I8T+T^lV%vXkQ%9?G+8gIRI;bUtl({@)4}am|VC=(yX=5o^513%JU8t zl#;3rTsmKVI@u~E6?$d%X#Cx-pzycq#pNr{Jipsqx4`Zxz9w1X1$qk={x|&LJdRnD z>F!V+T=F8Pd)8$8fIE)b%j*Ma-7IKUnXX83y#kP|kVWHwoMWsts2MR6H0Q0aJzxIMPw57N;xog!8|$>D^vy-;Jyn(O^M#vT;RYK&_8K!X=Cm zh1|bvz{g4*n6? zSMqzUxbpMuWv2J)_oOpzoN_M0QZOp;AP~Sh+?-AJ=2q z>Cd!$Rlrmt-eT-RwAt<|l}WN_gC z`cPF57OGumt>^lmD+`^>SOaPoI({gpVorjLerh^@p`3n^21v-MM*oLXHh-y`^p^>P z59;as*vV-8JbUSo_qH0JMJ!chQN`@}3s16bv~KuF)nykE8Ls?`V|GDDp&}k}R~km> z2lr)2aVggEIkT~WRxZ45_=_ zq9n_bOp{g%0f{TwEXlHc`Pl{80-tVK{ic=u5+~W$Hpzn`*-Je{tv=i?YdWRY%z~g$ zHNEEzX&I|03Yy~>JJ>x%C-!!uL=N^PN`6pbU8KN)|7Uo8jRsMO5)a)|l>y7)n?UKr zjh4^P8fp}v)$(7#Cj6n(!oS!M;$fD9r7)8zp#;7>@A2>oGLzX}2cKXKiDE?A0-NX4 zPcYB0=_<wjgt1h>s1{4!2Ig~ynB8eHuDF1d$6L8~aVzr|&7EkTr^ zxkxN?fO$U|NOqupvW}73vJ$(m?jX7;PB^P%aMTz!uqg`!j=vLq*U!2_Mgv^?;J5Jt zOyGPgqBN^g_YC#&Akpt|s8xhiqQh1K>DlYKrf9pwUQ7FXbD8M!cJ|$@RY%OOZs=_1 zW@DZAA+S4rLO!2Ro}HfVR__l`KWn5co)>AXE1#-7GMpblg4q<5tXEYO;0y$7DN=Wg z_0smxhDdN5t)l2l&IWz&KWEK_47su9=49>+mTN6^+IFirH?=xu&|GQA<-Nf;MZhFG zfmwgva`DfK%^_MXIIb5eR+oK^De?)v?ltmlOrF=_Y>WN5S8xu-69#5bAob??%K4MP zTR`J8JVw_#@lVPVJdMX*yef_gl3Ly%2I`2SX3HuINLQTab!fDNUb)8=d2$p2Vj|)_A4@4Xgxi@-sdsC%qegbyBEDo6M@_rL-XdGGZ1FVt zQ@DQIBS2w`5wk;bg&%mzcO=C`0`)^x8Dg8^!wLg#WxK%)Y0qs$3)1r=F1y_>|8cF1{IL{P1x zAt75Z`4_?b z8DQhyiUB+VqhU-Qjx9GI@QxY56j2;H-)IKI?vL#_;&<#252DR@{8;EJeFV=|2la+M3R87b;Ufgs75a$>8$T!5 z(IZ`rLg(z_Xib*P6vmSiaRnrv1?HpQR5Y`j#5wMcL*x3C-keAlL{6ukK&C`RhtXKq zv$ZHv_&G_0CA`{k4p9ulIyTDYP~$R=#iT@ z6MBWDWx?{b2Qh^tg%9*^%Qn~+a1kjUNdhqi40iq0Hu*_qo08=RoCE&j;(LrcWFbN} zH10$^(1n4r_Q!quHe`P^WdD-fu(!t5+0*D~3~#Ib;l12VEu_v38aIqji}X}bL(sT!v;yls71o|Xx|Yklvl;tiuFY~S zymJ^1!j`XT`Z@QAwo05Y_y)ClsR`nKNme7uX#BSNJul9jwKgo~TlG?Zi)CfYQL`td zBa~B`i9fc6ZYCy^^;x;Dxsz&=j+a(59iq-2CjmoN6(-^qTnVig-$4& z+}usg-;pmy>2Br!p*rL};RQbpJLTnDu|DDLvrQycu<5DqaRW^;<{F_EnN}+7Uvl-#UFJI+ULzRh>dn4l&*?)LSk-T6Ky>1Ig}yX zB>E=B&Y$0ZDRwb6&+F*Y<7GvGR$ zO;{TMybwhM#I(R1YPpksk_*8-pT>tn(C0P!&D1O;aS%wc`V*TZ7mY7yMd<2mnJ}U4 z43SvJ6qh{k*Ga)t3076dBD${G9p0(p1aFBNx9Yc+g$@^S?CtrPULZ{96JAO=3@#^cV1d`QoYy4 zJU1Zv=-F=cno~!l1u0QBS+8X=3^zXp){4k1^%;(x=g`52{4e5K1Hp>wecab|<&fO=bPYXi##FUhBITdN=xU~c}c}SgoPs^a<7*b$XhI1^X zX#OXr3honHX9WlJR|Q9S$JnTb^v|?ps8@f7&hBEMzR){u_)U%o(-36$ebfGD4nLb+rO&(4b~;=}S7Uv} zT}AJ==~gM!(%SsjV3!Pt-CM)S61XGGh^uxaT3tYdc%vhdc(bPjT!_;=md#VNxY6Z; zF>=@glk$;_TMFqAVUrx9Uds2X?Vf$tVVjA>uXoO5D_kU9R z!^gm4JagYeX&PuND#2Uj5j>J2-vv#$DOSpVgCTJ;imu>LC4~Y4_#<7oD_NNg=Sz+X z#-IA8*8;9|`Hq0VCSZ{;;EY#*VqZ%$bPL6E^+(|37 zrme@yWU%;AapTalTj7Na+a(%HX$-Q*mQ+|P+^7-?SVw47VKP(LaxZo>SR;zCNW;{9 ziXcVA>fyJn=wIW!C0_P9piJaK4$YdDEp0w2kF{Ug5AVWL%*H*y6STsl9&A)AT5kLs zQkG&7>N5rY^@`~Uv^sM`5u5if*`B8;PM$WYvZx@lqrtrm(LPU-W{TCu$I?YDNv5(1 zNzEr({!VBWd?Khce1B7qu1{Gv?HNuL$8bENGRRz4eDq$Mffk*gG7d9@Sbh+$EtxA* zlAQs?{bJ%XKFC=rptu=k2_D3Lvmfh?x!pk-f_3=V3}bq5kA$-WRSjH{&OZ=oso{T| z79M>dVqQSag;r3jQYMG$!NpC-T8hh2J*L%4y&}<_mJzvXyG&jYWKl^!A8Kmh->X%J z^GlnqjEhp>EhZBQxh&Hw9XcheQ~g(Iph5Q6CD*UzX2=If@a3|c2VzDGYc2L$;~tOw zFvkj4_V^Xc8Vc5sS?Zn)O75>kN?0o5+(rn(!pnL)z5Ndv3`wMLwVQb@SdVP$6?g=LjI7fSiox*ng z;Llpf;G>a*la_|-VVuXzIz=Wq; zsy$EJfUU&?;2GTvaC=eWRa3^H&c#5NPqRMIJRj{@_jPB6K-6pg6O)jdJ-&Cq4jh-; z-RawLE>jJTqX$}msDF)o)`QWD0FurRc)J2e7V>~#x!$MzfU$IZ^>6*q(S}!b+GQZb z-#70*&h3tPqdz`yyerUP^%lExc1;w21^=$RV>EXLp;;m98Kl)uJH#`2DoTHsbsFdW z$G7h${M{^z395;}P;8H?M#o&`*_rQ~S;B*_zr>DSCaiSLhFp7cJ=%B_SG;}W7JWSP zR|~-#(_xI3fDo#VPNj%uw!(5jx1FmZ0#>kXfkland=w7 zII+zz@X!xe#%M><|5TD}!qC$Uv54#zAV0!U=h+I3ZaGOAo(mt{W(U z3l!|Y>j=+%tZh@sVZJIDEQA^1OLVs7>#6+A!Pw?ut-`;aJT?a*(K`^)xnAz47vpN9Wd9TeqS`ijsxymeQQH7@D`v72|uTs_TfQ5=!1c)Ngd^)$IVjnKA1 z&+nT-8Q>BO_uBMbwoDxRCNm2YIU6k*`*En9pQh8})*zf4^;nX{bX&M>{(|{EY}odR zx3;MA9r)zE((#7v?7rmB$<8t%DoN~v8j`1;(&+nMN4fwXQ6rkW)O27S3bH*3sG!^1VzNkmV#qpJz8#m$`Ik+SN`l)2*&}M z*g6DQUQaekoPEiWB&qCmNR!|W4jA5BK}c%x)n<#=cGUJ7hA8#aIIh*yxBvBYdH|Ld z8=i(K%14Ql!_d-7RGu662{nKF8#(3UoZVpb-Yt$VAH=kNQ9rT$X~D|l1pwq60%1Mt zxotIX%?aq+GdQkdc3}}e*c9_ENg)MVUq41a*2zv=6V?@ z%)TBHCW^smTStUOm@c=iNdq6&l1<@x75>ZI;v0(az>A8{Pzt?IC5(Rgcq-mmSWoHE zl?r~~Jr#@Q3%7jL(Tz=yOIqmqx_F%7n3C=A*1~l-XK>^XJ1u$%FIv7c?*gJ;zA&F$9J zT|Xd`P4|dyRZ|yV$w08*9}BB3;oe7hP5f$^F@Nz2$4#G|Yk_rdtB7G|<#a zioViG!TeYD2V=D6^u%3W-bKr@FV9{p+8y3}_{D1`_3wZ&^Fkj$dB?zuYWWFqIQV6! zr4WUF2?+_OJrK~?A{gPnM<_fV&Zrnd9QyWvjiPS(Jn?|y4}!mmI`Be zqd|UJnZ}fPgSRjuJ6yeQ^IVvf^}bW?I*`gzxIb1Ub)_JR1f^^tFCWp2uDP_1mMcH^ zu>Kzdnq+@QuzKj37B|I9%tg*<#Ygb**u&#`OIr9Xl7JAn?`gy=(hM{9Z)ibze@G}s zHK=1_o!qwLi=avAmG|N7aqT7fTv)8lu8B2i;lVKNaZ1ZF)G7IQ$kN7@EzTx%K#=I; zn<(4jVyL$;v*@3`WGW87mC#dZ!J`!Kyxz*Nu0gFejf6X{k(|r7%?nj=FR}(i8bhjl^9vmz7m9DFZUx9*wWtMkO{!HoB-R7-HfQFuQ zE*`ZS?bqFwQ|xj&J+^1yq>bgdfLdu6Ufo7wh0P%zfRD-T#!i ziP$H|Q>LgZ`O`z;u#7JVB2C;b`;%q=sA3(hIIjK&V4F&Cd=mE>-)XRg{1oWGP3$iG z_#IK+(`!DxZc)4S*}HrS+=I4PrQ-Id+2UkbEhD%0zi4}q!GnYh1RG-PuAh5l2YQ!I z&)x@(W+C3vShm6`r$h)}V_xp}-s@9}q0lgndPk$b9d|X8-W_D#S7lzwJ-9E3;1K*y ziZ6&ndk-3d+Jr5JwU$9Bs^bZlL>1WwVB$raK{~Q8NUCCOxPM9=_E~<_?pTFbLv;+o zONEp?ew~d3ytRV<8YRNtmNnW3?lPd&8qz}8J%5+k?#Z7F2%%@Hp&`3B}>K2ofo_gu+;tFn?;>bqET1 zuqczDR?NOA^M0&X*6%4!GFz*$ZC#yhcsfbKOJ>?w;7+N*n~aj`IDxvN(!lf!?z z#eV~>e+|wPmPC*L1STUk=|;=a+|NtEr(e_C^6^evr3ZaRwo6G7z$NM)%o7c)cdEAI zG}N}h+Gfn@F%&gIffSRNjGSqlQl~wiSYDwm0xC98Nr}z`@*TFXOp~xvJ|7lz6jvlY z8>gm-_L2|Di3O+~33G;0TaNU`fO2h(CF+E>D%8PKrEU;ic)}KNZ6QiWwZsjzIhe_u z!;nQ|m`0RBzJTzmLoh4H{^XQ@`oj4~(&{6)=YY27(;^s58*MC5X4|N4Q}*26Sz_#0 zdgqxzMC($m>ej>%r^XMYeNx(FNQ znCG0uk*H3MK2Ytf-Y?*Y!h6&rC6Z`AaZA6Ufl-83F?MqWY{JswpM2mxNcll8WQmto zK-Yi04$N%%&6Ns zxARgOQ4su5Nf{MEX#e4D9%n+8%xG?TG{FGMaZ=o*EiJ33{&QfNFx%?`+5f%*TlRrW zb>geS14<~-^19m5wZIj}n?(8A_Bq3)!RwUr{Pvo6nz;&cwXLhkSjnNPft<5%#SfffVu5^ry5c z-k!hTByN#s1BUz#KpOTgzO=Jj_&sJ6vv|!<%~VJ$-K=*5{>eb%TBx9`))QJ*Yx9wT zh`g^Jciv2mvCr$x@vL69igFLiwBxo3jPPv^*wZK6-mvTh@FeOOXj^J8o3eJb=Nxw~ z^}Nw_OIuUcok>U0%^UXX0!$|vJ6n6#{NN0nZd|xyguhuW#E=nUg`US40>nBSFc4ES zhGEdXKwSKVvyXM8f1W4T+2g93s%C+bG~2*bLb-52kW=o?OcG_Q03wzo?<8!^Pl0vM z65Wy_q)KG0MfTBKwEO2}D{7$HjxWcDbQrsWD$&jfTw&0Mx0=+i;S^36tTZfwyGhR2 zA4>ab%%4f@$=xNb9LRKI-?1MbRrSf4^TCfywjQ|7zb=LhqzGSMZzt}O66ng?w9n3deW(Y*b$gFw7!SbNFyO;?C-~w* z7cc~-X1Bn!=nG&uI_cSwbyG3$4)r^jO*374wKI1pv&g3ka*twe*Qd$mzA17?!-+H` z#fgmeqUVLfwPOwWm5aPl_|;RQYT>!PlmpJ{fjR!VWm++H7l*o+K6Q{9HVfeZWe7?| z^|EkwFhJx9l{$O1wl=k8t68zQxaFsS)dHo zU^6M7a2e*5ZvK=I6w*>&8&FgpTe>C8sd1`lC~UId)T(C_+VC&CpFs!vV(c^nfRQv} z)Tsl>1It=5r>h%}K7SiqA~I;WB3nqgh_uz$nhmy68ym z!@t8N)C=$_mhpY}b$wa3vCdm(r1A-NhI+-nViQSof-ta^@T#bvM4NbY$K?|}VKo^f zwezMap=9zF`hy;uHS(S?KPte0c)e7#p<8J*iTp5Xm1olqcaTp-w%3$&Z2RO~+B&!Z z$Ngi?vmVi+F93uD5M)t8)1IfG`f9*N`-w8+m*dtn94CBW>dCcUMBj!tZ;~U2H2#Dq zU5*jkgipORnMJL@G~fW; zhBO?RPqj7Kfn>TJeqwB5Ta+YEQt%ql#9K0lw45fi*pTJ4bf7BeGMat(6#1D= znDrspQQnl+yKBr$t5JY6+YePPo?|n;xS~83#P4B9WJgJ2?2wNT<41Sw3`)ZqbC8#jzvw)|x@gZQG^ zmI1_H`wrgVCczKVO}jvc5|CSv=4s7F_bYW}0(js0r4Uf*CwAH#t7KkKp|Q#Tq@yYnitn(byvUtAQD#22JC2H~A{i)u7oC9GrzQLoqAc=mmvLpLfdvKk&pOE(N@O*wxcL~1Y z6evVld;vQnNm+uIz0vQsgak5JZnYRpict4Vb*g!0Bw&J!3!+9}ShzJ8M5h-d z)nN8D$svy`$vc|YpU#6%1B8ugq#}BSILYFdV7_qcVS1;|e!4HmV_OarjBSc?h!6B` zusQp}1EFeR&w?nh6P<^QMnA7RTD+izBE8T_*_t3kv7ULtRm;<-N>zH6;@=Hr^s}{z zk7pqE3qW#4GsHaF@Jiqiqt(#Rzikb{LjEc|3F;hh-rtq}lW{vuBkD%6#EC4xu1S1JjL;4Ck z=UlJOWL?LF4zp1@)ELK4z~RA)u>%6i=#H8750chlx0c$kPs1&$x&u+4Cmtx9!c9h= zZ3*dr+kG>*?5<_s_rJIR7bN`Ww?`}Gra_R$fwfXt_r&+R43q=`MfOc7g}cCq}AnB=?072mnf`VXl0E-Vrf2mq4yRy6hM>KE_D@oDLv(Mau&3_ za*mKt8dY9L6HiH)r=6%QOL!E1y_XBATi$ZX_Kb!T!~Oa$jKH7~*oH97ISK>2hI`np z0UT{lZ*~w6Jt6(YS<=SYeu;T5&LOWy(lz#B3lUj<79oamDz^ZhYnzdzVHRHK>ixAZg=qb0VQY0QY2#n$UGQ6!$97hb|@A zR7{Jk%_Y~unfm+U)H>JMd^kfq{6lgezVTnH_hSvX8Oh?k-f9`^^c$OSh1@7LVa{yo zA1+#+8%_u1oHHcM6(r~J!`rj!?`p7vM7W_enHMtnTB z;OLAah#UVBA84oB*_ig`6`Cb5(d;ds$ZxW~%=@Izb-AE!lP~A*w)BID?MDcFwpE~( zj#0ZoR-fg2Fub-{uRNoeaU?0q@iY5vEek`wn)x#t8S&4V%YHFN)lKx@1S7XTQs1pL>I^I_ z`Q8A;puFwP#FB98{wiGZjr)Xw@}eZ*58?i*PaKo9_6AjvA?5!jFq>e$ug?Ui*D><7;w*8y@eY6#;JzJV5TW&3-3l03_q`y2S4$RHF+d^KgZC}J z7*o`c!Q1|Ma5ahA7)nV`^oId1y(u$h-=-`kWUP&O+dPfnNkKMNYL&Q$%Ls1Ow=X~a z|Jz6>@1Wvt#misMrbF|{49k)nq)nwQ>4YorUjbhcef7NiMDv`M>kMa)H_1;i@`G~Q zNZUK|@hlVG!l~D6-&=KDls`@^EBK5-$r}rRT)^nx&)B#88o;zT4V_@fIrL4Q8-AA- z`wa2FTW*o)8c11!*f8urufkUt!_($cPf;6uMOuo$yjP6srAogb2}B+{QP-$f%Az8o z=o^P*g4KI_f|4b^DChh-twLwPW>Q8bXWvEZ;;ai0fDe{OLI#6*ObS%@~8+L&M^^{;1$(Fj&rXONujV;f!6X2&T%f>-D@8c()vJM%gDlk$6um9Y`7{h1taZm*OXT?yGH?$oKJbHZ@gezOM%k1)S!xuk2_a2?L&>lmb>*reCVFGdGs6 zP>TI9WhLVab6*|WkZ_?pDWk>dH~}YjD`$%T2ue1b4c3jg?J9BQJXBgDUXq_{ac8@G z@QcWfD34^alFqoiI-Lkzf|#|5bluE1St@>J6wBG63Us@Gm})MeFA**&fkP9!dvPMN z`SMA+Ts9)&vrYMkEh;zNP{_g_(#6YWzu3pW_~md_OkH2pRAF{5s>>yoyC5U3K?Lrm zpFfqhw21I1fQx(-n zMfJ@DqX-Yx9=!OEEZA;Q{jHNzbuYQOS6Tb)n{7_E9NW0-pJ??_{>Ut)1+C{Y=GqOM zEwWS}IBjCJc@ZQK!DC zR|J-O%oS6ejto=bqi2EW9kEct<$S8&gz>mcKZAOAcX|3Un(a2P(z22C4N-vdONB@vmCf$Dsc%m*eK^y4CsPfovX;%Kc11h zo^q^Dz23v-dSLWmvL<{qrU>@DYe!K)qYVSj|4;J!7ZnW({>!33!Qa31R0F7o!6vWf z|1uY50@+`WB_>&6meNOC3dh2XGD_ag(qs?d^Vkt4@CDzHkFZ2FHYq@rc$OTLhIrJYn! zJMR7m_yd3KYuy)ef=n*aG)ZIg<5+_f1vjF&-;L7u{w3@$zGhMQweCqULhK#(bIw@d zjTQxn-(bGrX+^Enlg|m>37inDXk%$U5&{~&ot!#yf;P}XOAZJctHF2r$M9X1&PYfa z5y>z=2j>S3{?JTHYE}-O!Nj_&d93$uh~{7=uyeEgXFL$EUtJXewQo*@j6GeZG_W#8 zw$khP%ANW&c+gn^Ng(D3Uz!HO9iraLRByXe;QP^=^eN^Qeaa&f%A@*#kQb#f{m25# ziw3m^o%p@@8G4q#r=HGkHejt-|+f^JSQaVko;?E;BP!VY6rVAtgJn8k; zOj8GPFlM`M)NeyKny*Vui1(E$-9SCY&lI7{$$J!G9s9BnAOE%oi%pv9QwM)SaluRb z(Dwsa)~{ZdP#_=e`7p7^DHi-@6>i59Ssysi{2^+1ma2gq9m#L@6cog`a}Eivk)Gbh zrk!6u-~9)2W~XZFyYFMMiA+6ZW>+Zuk}9qLMQKgrzjgw>{irwL=*e=P}>u6 z^%Bj{I(^!_$T9L+$vN;GxDE@HOvxC{abKFxtRlnjNhpp_Pfah3#PwK0t+IjHvKR;c z!?Sv%;vCOLg|^M_F5F7WK$fs?U{?b(lKK)?UdSWmS*-GZy0wT7)k3vl`e!MpLFwBT zj32^_uuV@~PUYjwRO^~OzY+$gGYb**n3W`aCH>8LJsl{_&3=@8`$65?zgFCTGW+sL zQ9CNui>JY@_q{y$m=sazNXIeK)N^UCzlzvRPxYofr61YPdyIY@wT2ZwdHe82lYI}K zz%{%kpPQZ}8Rp(A47cAqOO zm9(#gEv6@303)0OSyQl6V|Vw9XmuMFlrdIAeG^N9joE;qunkuLIJo3dn-W@~MvQxO zbKjM)JJ0gHJY*yj#Ef`DJgtuNz2E_MBAB7k`_q=xrhmLiZ|J3ro|aD?IRtoG)po!0 zs4!edd7u`mnlXORAj8=q9)J6%OF+de|G9VuGuej;BElr{Yy?<~U%<^0mtu+@c2oM! zP#J!>W5{xv(pK^1fYNIaJGKEuKw!8`wi|pJ~L{#3&G?|=ZIAA*6bgo zRz1ONVrgLd$rSf_Hn2!yTJWT(3jbuv&Kd!bu`3?hB1n=DZCnIodp)5L5efIdgQm>k>HkPQ%M03Tb8JsaGfD z4scCi9ZDm1ns{Yf61#nG`R(&P8@bVuiedZibS{b4HvBI5GVm^yqvqFUznjf?QKMjP zXKyg87~ke?06ZTqR#tx97sMUc`fsGW719G2z?D^^>AiXlJCeNs-fm}EbpH?j^*>)U z)X3L4|C_wb6tKAz7Zv5P^>DdQraN`L1X*?8>v|*7;=d+ZE9EesjVO_x+5lOMzym#P zL<+}!@65uW%v@u*sZ}ww#f#K`(d{++uMz{JvG68@<}E6{q!uk@2ibN!c>`X%2@*xb zK5Mo2xj`e6(Cfti>$>e!B6Bbpe#Dq(v3^sNu!S}oOE_rb(FD$o1^m!cdg*}oy^uK} zV!WRRKD)#BSa;QGGzcDIZ3Uq?iy92mb+qrVPn!IF%+88lG zsz9gj(tzQ$>)FG8C7#Cel*Ud09c5{86q3V=iK}@Y`;%&+;U9S*sfcOR#%J`M+L=;j zS)3Kh*tp>L`n&TWAG54^)&Ned@k;*KG=gFQHLRq2vSLynG$UL>+GmggKx`!etno^^ z-|lvT&M3@kmG9yg^IvpqTMLh{pMOq2k}AgUD;IwtT4KVo0)*=NbXa1@TZBfsQ+}kX znGZjV#f*&=+sBFfw=TBG!gB#15J3}s9;YGlb*8u97JwS*duQTsOh(0d+upD4!7zCp z9kQU}5wS=s{Suq?fNf3iu*XYd9k#n-l7=W??$zR-n|C3I|h;vp`*W_VLtbZ z5H0)>*K@EG71GTILV&RXI|zO?Pz#z+?qHNV=9Rl<@8G^2t+C@wO#3enorx03eERB_ zK5dx_g9`0LfNlaeRXvY}CMAf8Gfw7h0T815Y8q#JiZ13;dK{m6(1da-%_l8!l^kqI z>?w?XBNG~Pg}P)>ma9PQ(&rPl-4!pT4NnSbhkb&7_|OKXqc#D{^BViJ?X`!GL&i=BuZO7T%q1*&EN`a|Mgbu9{u@eNO=!E<`HE zY1AWn$co{0Z&sn{f7>(}&M+QMOh)Xm?EKZ%AHJ9hPcI!m@m+=+Gxc1F5ZtbJR~uYY zKW;~h3b&3H-aqSHS*Pu5S~&%Eho;Ijq`Q7MQ_4Bs-!bCl8r@yF9W=lA)xg*4kh-)l zhhRcy!g;U>%Dp6FL>`4J(6NX80*7;7rElG(KEHvG8}j`FmX@}um^Pb7VoRiq@=K-k zx%UDQBq#UZJ{SF4F!GaJDr5fMX}%%4)2g*$Kow563MjP_n{Q=cZRCzT9Z^jVS{-l7B=lh?_ z%dfvI1t*V{@6(ARw~c7*0-267AIv=qbMYP7$-gO*wf{mv4=uEwhmQ_N%h3nl4{y6B z+z(D$k8n;{0qE@V^G(Vl@7da#S?9mFsD%vIXTY>vGd{n}70D7jc%faMxXgo?;&c@n zV)7jL%0vEB^+FRvOIla$eMALi%GcQ!B~=To_oQg=11M^|S5v(&ELI=tW@H^!larGP zj?ppU=LKz-hrx`&N8T3;``7oOVT2L`Y0@Bj!a&fVv?8X!Y=r{r{yOwH2nt{)TFky^ zjlK4pObUx|1oQMY_I>i!WGxE~7;A)QN^s&sORRFijv~-579191mj5uKo1Zec4jc)azK*{{4)qQ-9c(MX#c(9)BU1; zsy#yESIdcHyToi{i8y6~eY7qyZ03`3OEMjRUg2UbZ4t!I;FnAr%43#-2D9 z#deE;d3zjJL%?Y-<21Sdep6h2qu}PMH86<(VP_q`AE z@f*YHHk0{jYlTK7&{Dho@;M#jdM`E!MtCy7C491Pr$Otk{Vg>Y$NzOY^)g?!s{PM7 z0%S!DWv!)i82x-!JV?&lM*g-Q^S+9fa~?y@ATr(XD>-Q(@P!aMn_-M{HDOZ6Gt$*N z=2JsZCO-yo5@)aLWMv|me!Vu51~wHBoVkbex9*3|mYzs4u=8$Ql0_}XC+2)IoMeTw z%O<}AX+DEma$+%nbI5V&gd4YCCZ{z8s-uO8I|%Mq5fBbnA!6_)LmBL=FM`{iW^J`% z9;FNai5ha8CUCG>q9>-wDvtxYVE!Pl3o#fzD8|CoyOx2lnqhi~f4~NtYYV@`fhtgv zVIGV@k9CZ2AAYNjwgMpe$(;9CRx@Bf;|Fyecf3{oNJF-l<#_~fpEGT=%$0v4SL)`Gzj#)!v`$1`%GhV&l)6#1V7&N#8*nM2 zQ~o!oLOKkn`P=DjPj652Ml)aN(nfPsottE#cSKz5tUq`~^u#j};(c3DA9+OgQ88;;S72&_!pz2Z2(36Y168lff*d zTCk6=W9jk-&O~adTw58h3B02PKETC z9)9(!?uQ|_pgmb~lHHurB3OcH&F^CsL3!hEumm8mEW*ZEqRXBoCDCGS6LOu8sQ)Bty;35US{F%L+(5-w&`>dIn3?GEVM6ci4!2G5?%m(E z#J!G~8gCXXcdlhH>Pg-skuG}y%`>>iW?;SqJ|WRp0f$sp6t(XK{k}M1ixcFdjc38k zqJ^;??D8{q@+ZV+hXRp7Tr27(d12>)DTMYer#5;q-`s$xMwD}o9zL{)yH#u)=q%rQ z;SfoI?SQp|JNu{^ct0loO?hSR5-+do>bKhd=XheL+QYUndQ;Mt{@`m-g3D7#0H1#? z<&PggB)HEL<+F(gr#;Pw94|F&OBfR#zjDGcOtVd8+MI#ZO$GYp)=kk#X)VcLRr@RC zli=r~L(pqL^kSY02wmv`;Q_n_`c4#i@LR-ASmsK{FHDaBJW^fykBIl7Om%GT%k!2N zso^TV1;}`U04Bt3en87w4Mqz9Yr~heM*Jk5Uf_wus zbk!8(t|<|-L|slBbVY6PhBHr>E{CEQ-X~fD!gP?Z5&x7t}CzhNa z>Cz7*1{JX%(@9%zSEap+LOmJe)PF82r_0>YFFy743-rvEIQ$wReN-}Qzm-r5`$iMb zVd0Cgrj1X=u36CxjoLcMUvnd1UX#Mz|HXh(a6qwF%@o3^`-{rz#%|snS+uboft)*s z7y{hHKwKLab4RVoKZ>3We9XX(XS2FM*)wiRxIoxiM8y3*GtVyH{*n{w@dLX?F_5_h z=TR~?c>Jk~VV@)2`+?jRj|*7t-N#nh5;vhxG0o_B=(lXX)+cV;Ya?9knW1pVX z^~OgE*7buA$h_KP3wO+5j%(~2>=00Z_PV&eM?JT=ZjJZGm(+#LU-^1(evVah6;53# z6nvB<+(wWV0{d#C<=qL50nCuh#4Sv=D_ofuajb)WU_pdiwO55u;=v1RO>wf8a$wn3 zju5B^%o7s8Tb+gDVUw~uM4)NzdY|rd@b)~)UbZqkbDzz8b-licjNk|I5V`F8KJBhe z;K5w0vng$@tu=t5@14H2w8o5_bk*TPeCaP2;m2JZXzNoQ%{M}@4Y#d-X}Pb4~X>1$c`m})xE3eICoP2Hpt#$X8i)sCRFmT`h7DIx0(p(ccd zI;5LO8Uw$^)#?SAJxULp$eK)WAJabDEw#E+U1_~(-g|!F4A&i^z?wSY$9pv$stJoo zG=nFb0bCQCg(VrO7)Hr$WW3-mXKWLclhp25dew|JN=Z=!U21O0jm{gIRYk^Q^{p0w z;ZL8OKW^2<{kqvLF;X0eNIaQqVZcZjdU`{-VR6G-xqhK`CZWRA!+wJ$;_yO$M*ri( zm%4}ZG}f>g5H8amCan-gpe>s5Gul_sWPdYRQ4;Fn>13D^7?iK8s!*2zOo8?rDQWt2 zM%pOUzWd0ZL&a+^VxJVngg7mZ#<3-2?TS6=uk2-#J@=GqnIWN@6?+_laCV1QWu(a5 zJPA#Uasbg!E3X>H1U>eaA2o!B@=YL1P9=*UnXlH8TumzWAD5>oyZx%RTQ2CQLpcw_ zw=IIbs*bMDF}^SMD#F-e0xz>81bm$C;ENn&9;nLa|9^f4J&W}CZvaNc;OcLT;ku>s ztko5h*|Wb}=p820^e72)N+G&ptFcm$-1YA|D}d*GMAC{t3?GbSv@@Gg+~lpv+JcXO zZH8!cLLH9!W&eu{5P|Pw-4FqPi#bO1Oqkb@rK`|U zp1*ehw9ZQZ1m;zi%-Qx_Cmas;ilY+VlkLqz8J;oIlpxf9lh}wq#YQ}V=VNQpV<<6K zlE_nv^u5EX2;?~4Ajg)Hk08|Mfrf8mdebD6Rp+sBJ`)_p5=Lzjm(;!MNnWDW3)Ef| z$>Fok-r0tlXw;&XiH=x)tw8NsM_sB#Lycd_*}xR16a>}H1vlt(`iywLfimagHK1SK zJtfTCdUFz7lQ|?mLu~v^MC+~MkaY@W$i4nl=mhu{uwU&1dxs#7A3;loc%}lEy3^l% z!>OxHyhoSc$>Y72t+7AEF#GgQD4(v$>DHW23iGP^TTg!Jdb4$$8vM%s2d^~S_@E$y zbyLEdrC7k!z#60OE5o~*MWDMhgaiN;U><592?8pB4-e$Tx=7qrD>=SmPRqg zhmR8iQ9M=R(c5D)91tW5i$0li`}x+N4I#h8zrJ7Uo9xndon5^&{@rx-@AHl6^W6z( z8+Jv3fkG@4_p&_!BV8x>crjn$TZTf6nm?95`8T4zR|cTF?qg@+MC>)=dU8h(xo>UA zh7pMCW2docONw)p>SLp zFrJ;(M`5Ohqw2Ho10?U9`7d%$XpWmo)|dogb(Lcz3Eo972l^~u++5L#Iia`62>kBu zzjA2)X~Yh|wLMNP?3#Vp+PXOZEq~9tk!rMXluHrPgD!r>Wp~F&aOa0UwYn7aH&BFH z`0%XIe8n@HqMiLP>E)#P*+M?nn&1ZR@mE@u)m5ZnLrO=OaMKp5hB*(3V%Yp6)M~o1 zjO`EVz$uCUi0&&k@jNPf%#+>y*z0Lgw}gzBYUsIy-&e$eEGMyGD+cmnPT+eA}NgXaTaFLBSPNQExF2A6}OIPLX=ht_kM{X#_#^au&E@B4h4IE0#gJ) z=;*y6rLiXqgmFVD>W`5F=MFQZ?!xY(A*z(Sp}P!yIdh&{#5mOy#G`p#dCNq zvkwn`GAf?cTX%!4y{dWX^ycSQBfX?a0UQ6v__y0}h5!h}Fuk@4TQ24qpic6Vpvr4S zEQ-{0S?O4x)FyvN>(oRn&H!WP!#;sCx7^4q= z#dQ_YzBmrt?Z<@Rkz|D0)LRG!mR|S&r@B@$Z=znP2nM~N&;oxK0Pz&t+o)Q%^MGh{ zahxU}O~gvKmAi$7c=|qacTB7gl8R7lv-B!ht}28dlqD^GV9^7pn;gS}uyWl7qQ%m% zUfM<;M=5(ZlC_aoEG#KV50xmiOW^omCi4eaQn7DixpHmWjzV?UaxQ4~KCoqbu27Fs z`~F3smkX8F%1esvNr$}o>BV>XQNHHE2WbW%c#Q z#1iPJjcTVhol&YnN`~H|iq|yZ=n5pjXf}Jq#g1`5K=YW9*l(Yq_07B{zUbFQP(in1 z#A+8c%Chn?p29LHqtOKA(d&(-1cfbwVS}m$psh`TMjN zulV@yNB~fRv{zryr-+KDf8#mac1wml6SXEwf(!+G z?G*}e$BfRd@kSVp{vrAm)Q5+w*fWCYe)?UvP{JV}{MB6*Y&!#O| zZz>0jO}djU+FuHO*7jMYi2MU1PpkO`SU~dv4YygTe%ln2KqP;H{jwV3BAEQx17 z#r(mrEhI~<#EnCG6!gD*A;1P2#S%RFc_E!!hZ7kobKjjpd=9sm}Q%+EeGR^2)L_mXmBdTdoIqZ+2kbvw8t!v3nY!n0i-5{}aXl2MVlPLfhjRyPE< zr=aVsn?&dJ6(-An_C3|r%vx+G;xy`%a~#xpKwjbmIn~ZTqRe-9Sr3TH z{?Ic?ManfM&MJ=8=^CAJinaRKd+X}7Rcg+3aGlh=9@rx6r}n33E_M#E8u46WM#Tl*e3IuD%^EPioSN%Jod6z@IDvX@)3&~?ML?3N` zdazQ17^IPN+;Cu*#SBRR*g4^KMP8X~U%j$~Yh*{a{Xu1r04NFcg!z~tX5SYLxvC*O zI~sVQK8wwGofKAKaQsb3RxRRXw=F_1`8eLPb-?~xP3WKEF8&iVyqrn0yM?acgH;Qs z)!?p@%e*V|zFUrmB`}lSu9+2%=Q|Z9lBIWBcx#gwL5Q{Wuc+YYRe#{Obr%`pCU!hYfnz0t0?KPv9fd;`K*6 z*YfHLLB9V6F1;RL+^&V(<8iu2+7obh;zQpP3&*@Ar;b*nQBi+!8q&)%M}alhKDJa!ryfq2Bk5^fl8{xvN{QoxKi}sp~`roS5LN0;tAu} z5w_NOwU7=Iq1C8bPDwSR@FF1e0#I#XA-ADBnzF|7I1|+OaNPoa;EevN9_i$WEBKV|t4G%BL=K~`(2UuHb6vz@v-GL8>RfL0A~BXPu^+32UsIIQ z{z;q0A|j}x5K$V#)iD;%hmCqTW3hA{aCFdGz=h2KNe?5eH!_RklOM`K5M_l?)%Igv zqhk_(-af6(gl4d@)l3#6a_t)TVdckcKBnLVCS)_UkBu~qz3LiS*&5aa`bF+&F=s7}_vY`aCJXJ6 zP6xZCA5Q`&A{1VIJ1fMa$^sf9LYFm9c~ZM8COg(BU~bXDqk~uzXqM32%{BGYX4F_o znJY~D6zh`PTI@2xMa@5~c>T+X4w6yXO!RRo6;#jC)pBjbD7ktZ|N zVZp1N7q4fLt?ifJ!hN6sUHGAyi2aGD;cQh4Ot)X=i*N zCBYlz@f%$aZ8BC;lCn@tMQ`sZ)%PC*-`>-nl5<%3;pmbx%k2J=uQjtGyGbExqVYR zn&3NQBHLFDF={hO02aQHJc8Mh7w4D>>|o}4{unjFfOk({coM#SsfosEjFo6YeHS9K z^%XM`yA>rpGYU}El*cD+GDPQT=5m>7Tzc5RUn^Z;=dW2}Ey; z=SVe&4Bx!A(AKYTzv_+wnQlqw?~SN08_TxPR}krZac;lusu)i>+U=4%oM>B-H4r+g z7NfjZA4C4CueFiD)wy9Qo+#!7sTP*S-uV3h$Hhk;o|DW_C7_!SeDid_|G7)X*irO{T}t>DLVAD{w@_DYc;Vx!vQ2imHcSG_;~ z*1s|Sl9`bUI`m@B{`8+ir}d4)3OI1JMP6fsOK-umt1hxWES^pL%t9@jDOl0D$@9`= zV9B(rcXJHWT-`(t_4>J-QHh$2BbFL~BXgK8=?>AfbeMF4qRgTII$Y-E$tQjyvEuPq z3H*q_zQE{H@|`hHM)Cdrz#R!WiQa3>*e>8SR#cLwH(BBSyg`(=atJS=TGaC-WJcM8 zhn6qd>I->(9&MGxL>(rVF%w^W6B5EWAn_7*=cbx2ANt)leXNYE*^#wRV%i6H zoaL)St^**;UmsW<+7lN?=XmOt>04O*SlxQ(v<2pwV8&~h8#E9QIadUdQ`;ydBjxEp z*io;jcc#lT1aPnN_<9NAJsp-y z{biby3W1*qd^y1%!yn@aBP@nAVFB9$3nlTwFW-GDYok*AOXA<-aRFaetU1WsfobIw z0VybP=bo#$J~8&L^ZDC@KTfv`r}_u=`Kff$+*igu`Lq67((%ao=Xe`SsNC@T^{KbL zG~`OzN_%4!U^(Ys6nZ}?u6r-6;yMDl+@~ko{+}=9q-+af3XbUo+%z z_x4X+Q{n#k&r*Tkslc$38)z)1BY_ZOz&7LUg59O(%N9VmOYQv|Jb3=e399IysG2b5 zG8d@AY!_*zLoV~iq8Y%e(E|3xH|T3*&vo-UrXN-z|MIPXXzNH~dxSq~U`^JH7pe#t z6=(6J3DEbLqm9=;HZ+D?q9%TM!QaLo55C&j0omn$qa7aEIQA4#k&RmNWpJ#Wd%@P9 zz0GzakE@rXg@od0WH|6jlzr=QTen?VJKm9Xp?J>V{&~WLlWXm#8gsMv3C&shz44kY zb~$PYyQ(6Q6}6Y)rj)f((G1*3k^csaa2SO%+W-bU&OQ;6!kUm&A>0_)Y*E(2*qgNA zhYU1>q72@Q?s3vJ9bwF?bwa`CK+r1!V07{$4)aJOyi!`&NzgdY;j74mOYTHlbI|W% z?0Cr+RJSxoH`(}c_24*Z&=bp_wLy66H|#e=uLPe`g?Me@}gl&w!O&gs>|l zaS2+|dj5aArXYu4zsc9l zu;$D)f9xoQkfce{iku_r-DK`U+$o-5r?Uil2}{Gh=Q!CLkEw0~W0}Q3@MH+V1YZD9 z1)wsXmule+g8aC!qV=YPXY;@2AE2dp19%-bYt&zU2tB2;YHSKD6DsA-y~=YX=G!g! z_?qEonmvY(mn>-dm*)p0FM>1hH3oslAMr2}kibA~e-mb`tu|CwkCp;UiwX3Bo^W_F zt$cfp3Z15%en5hvR0wQgmPQu2WLOGan)vRk4CrP}6;{L){PQIGUFRfx;G9~8Zji_; z(5qNbWs%@02&m6Jtw{TkQ5cJ+wSkn$fbFHK2F#7Erw_;4SKLuK`^;hJojE_h`j7AV zVk5I{wS^D2{v{~5*A$aPGC=kCG$t@{N3cs=Wa!lL&hEMFb%&_L0MD>9)7@W-LavKt zhl$EdiO|1+_gW5jvIr7S&-7j9Qnr(t%Vp>8wv_?P>dxRT$o-1}JnubfwYZJZ5&yB% zFXcxq?ll9ROkoC#`@V%(D~j%+jexF;(asC+Wnaetnkx?Uvqxo$qN3bw4W0+y|0l`r z+H~qs)%=@n{Lh)uOP4v>A~h0qe_<}1t1U^m9#z+`5}iarl$En${i6+F$VA6@vC>kYXpjOe?hZG7?{~g?&UyZr%$k*~ zm8{G>d;etb{c>=kR82Ktm%epDfC?wubzML~TlC|1;x|deI4F+CrYO4F-GTapO~BWc zYtuo#pE-h{M@rE2k?!>pFcJY@$MzG5&kRJ6ExV*tff)}=p5;z%bBYrD`|?wmArpKp zdmxyi2SZ^C(}WSZQ*JC^U4RDdhZprsCFU6yC#Y@9I|FmTpa5mhFC;w9hz5`w69kq` zEO9Tv+(Y$fBv1LdQ7$PkH{|>g?En=)`4|#)wz$F9q6h?HZ7=9zJ#A%+C8J5PKZJT= zf8b4yO^95)5@x@5%Y<7b2f17)K-NV>`m05H<6gST%K+r>&D>@{MS!!yHr-t^@)p7v zITh>q=S-zjtkg%qkUmgZPV@s!EC!6G8sDZ+wWPomdVRB&6@+z*(M6~=)#Q8vAv^U|dhgrlYnX^_# zZdJ3~!r$_k=>b?wzgR3G42|P9dQAi0;nj5=QP}m zq|^+^Vwvt~#k(7#K76_}hf?6X=tpo6z_#szMm9rafeiMR9!O1SY?^c=NuBRY`!&A* z{AbNX>dbD{j17M;MH5G{^1@JZHTc-`PHYu2;UL@k?)S<2E z2fTi=MZ<%PAl(^ePPoj$Bb5STT%b@X*liR`C5AbR47RQJTBbA+gjGdcgL_OpI#6WY zz{rd8J@f&;k_{Ox{_bymS-^Z~-sM=bN1@5wQec)we?b07B^h(-J1jDJbLYCgsl)Bt zOCw$dMSUoc#QSiHHBdKz$7mrq>WzeAY3%%XGnV7)oPEmMh<2kBA(Nn^A59YdmMo-t zD`4*>U|S09q85BzqEXLKJHd+9>wJ^`}DYrYyI6W_3_cxys2v0OAp)5-x#ty_bA=+D$EWzsDzQxe@*r|n+Z`!`4 zC?4?q4$qByrIf#QeqLbVYJT-k#h7Vf5)sbF+Cr5yjnEPmHa@=jo%^xo4HP39LFj|s zb9Ync9`b(HS(65r+MoSDkZ#_3-kZGteEC%!>IFotd^;)ic+Cex(4Wk$ zXf@w*&$fNNs8FC%ThfNnuj_4{`zZdPv8e~s$}5c-8g_Y=CsBe%27PNmzKT)tmj1i zL^~G)&7giSkd4vC%t`4?I7Fcti0HR`vCRrAdt1)w8gjxZHX1@l%9-k_ar_cDgS*Vg zd9c2mLZ?`=ic0%|YuGIr?}O*yP=A{)_Y+X#7)+-LbEv4ix!*rzTMAZfvq^f8f)^_{ ztdIP*Xl>SV>6$-0EsE}*89wKb2Ghgl%w&0Jy*kB&CY%?1YEy? zZw-(Ri$wAWVqR79x%_uU`rlUlSDkj{|AMUl9PKqh#ks z@%}Xc1u2;m)FaAx`(D%bPbACP+5d(l*Y+q&%ZCO>((Hg%nx3b^*3b`6SCfAz|FQ3R z`NJ+BBJJ`e{V+^!FyCetGMm&64t!GpWwoBaO9cxMzMu6fWl%}o1pzljxn`{GHEkPn z9ejATLEF4yoe{+}woi4_0CO&pLU9}EA@!58ngQ*Y$!#w|v%ub9$aK1Ij}vt?0VTNf z4R47@3~aETTySbtx!f#T2Rde&lX>P`>?z~W8P>_M@3lGcsG=+O&`MQoI{7gQB*ftUN2XV?v;(N?DmadOwJT| zL{T5Uas?ddL5C-seO$@xno`64FE7C3TVwgI!32zvcIZ&%J}|67(unSW5rvcSpI@*} zEsgS}jM0Ws%EYHw9 z-A@M%=5H+Pl+ZHHnCl?#y`UhbRi!|G{Qh@Fy>S<;u3F!TpW$ql4w7uUGb4o* zl9@qcDy7}LISx4fyx2b_6RHt5t!ipIaS=2rSql$6&_HM) z=b+b?ZwFwuH$8AVe|PW|o>y2eD0ofnE+u+t1yTRhA@2E^GCx8qo{JSQd4h-wgUxRx z?I$$~P_&U8B3tYWlzKKcIAO+U4y*wT$Ga=0QZzxmb0`G62cUMaOIA!jL0>1%;^23& zSyB&0pnS-8Xf>gtiwD2E$4wBj8$#QJop7!AVK{E5ed9oK9X=&|VO-Qerc&i;ySos0 zSO;>KIxT=9^jg1E|KQGL$>X6L=LR(e>o=k6^ke!>{yZUYz4+|$lcm5%zZ-k*5;w@#6-!he!zbmE3_)k# z2ZnhFT+;pHU0p}1Y*)BFvu~FP$W^rO<;$+o;-7#} z7fwt!6k)X{cSje`Ml~3$+1(KaBbk44z<2N{fO?Z|;mFHJ2v`(MQo0j^D=T?C*i&{h z)@r4FRTa+9FHEDY7BI%yl~m0VDtY8_(3tMHk|od>GJW0xWDf*vTHn$VK43A_t{tJJ zMLCYx7I~w-BCr80JW7)fPpti)aLxxxdOsV9YR`f=e#Q1mk@XPZu=)h6jz8`zL+!J9|ERbc-^K zEH%rK))=AjaWAc3$!s(`GL`D_I?T*iWm+k3`p3-rjUFzLG*>hqGt0}{{vw_kb*L=C z-=o=52&(`p3B1)tk=3kovPy%ixQo! zM>JQ!M-C0W(G?NoyZ|~Us;T1eCjhORz2!mYoI&O02Q0auhX&MKMN(+X$7fbbTox+= zdef&BBlcj@1rQ^}RTk12baxe)h%W9zRNMkz*axUi!b{x^HOt@_!Zt4n7(b&wrJ=E^ z57ZJv6C=d7f5vcZ)?yWnkZ5kFoQ!MWi41g!RlMBHD$keuy@+0dZ@fk`Z;=z-9y)WM zmV}WHRJX)X)UCDdwa3m1(~Z{SDFAa{HD$xzab9Ak0l|YF8#hfwT)RvS21W3DK?ma5 z-D7okRwzS;N?I}&O(oXE)MP!b!%zR zP(PWvOl{KEnq=kShsm0f9}8CYO|wZw=+SWy=<5<;+xl4qXNbExuM~`sfGWKQUA}GPs={cR8;dnzN7zp z2tsrIk2s2a{z`-u#iLa1?LJr#>$1Jt?Te#kOhq-8>YESb?;SOOTCgu2tzWizXxn+<473R|`O0aBcA5Y{ za0DMwWhgiO>9!uUKUvPrYnKbKK7i(%3m#WMzJSSQ@f0EP>?1Xge=d*v1f_M~F!>^96-ghh+j3F$;AmirM9ID1FC3 zQGOmw)6QMO$M#3rKqwuUEg$+>*3t;`GNvs$)XKNh-QSV}5ccKXgkqZvWCWi=vNkjz z*;$T$h&}IQ-1EoS7LoQxDOvwC04I^{kEtA^#3A9+{YZ*4JIDq&_24x^KZeX=Do=VS zp}(N^C0#Nn+OnhV6^Ug(d1Ahx?X{n6bR{pMi++JiT(8D(^qHBSm0a_q%*N)E(_7gr z3O(1TgjWP`ilrP#kejLFvK?LgQvM154vrVi9f2!k7Ig552>9G3<`vDx(~|_3i*6@6 zkFkkdWUfZzMW!Xn@M=2V%su}YS|-ScG>KQb4|M#`Ki}PVH%Eu_COc@>R#e1k-hPh1 zK+=YPa=0_5-8WNITcC`Y&n$Jed+QeP;?K3u=o`E5nYV-1BTCCJ5x`?^SA4~KlN1XY zFd^5a5jMAMfl<*di;{_Dri-503o!Fg)+ox3HaN83H-?73;o>>@=7g2i$rV>ff7dm4c*&^QQ{ByuDIU4sI<;}8F))lUA`$WB} z)%yLI7YIx8NNKlr5#T%GSU!E>$})YbKi4a*9MSXDF^~R4$b#Z;K|$ZZX+9YJa*Xa$ zXy?}v)iQoZ;No9S*>lErn-yiiAAKZa7Q`@bjA1p(QBK*T)L_pFgDu6DA&Pw*AFek4 zhLwF9NHFu!i3ba;u!6~BWO=V`-Fv`!01vrA>?Sg9q2Sa+VykT?e0bV2$=mF3Mdzt< zC67YpD48bXlse&>yoaOcoc;v!L<%0v+!wbsQ~X5UP)Fv2a1+?sFg(O3xh$dgbCKJfm3ZT;EcZxfkMe=^T#xOeigz3Wl%-z`74pCZaq zL9%#s(*5&4>7omgX~OTyu67Lrzp8QUA%t$T$xeYdiNeL-8`Io-er$7XT2=nISgDFt z`vl;)N@lST0iX!YQ;o2#Sck(Vu9zFyidB&WpBu{@$Iq}+HnRxYP99#Q8l#N$SPy2s}i4+`;t97#n8Ckzk zjQujx94haTr~LC?Z`S+yY|jUTg`81MjU=lt{Wf_vwrpmogp5J^0t*#|fg9iwhpmhp zis{j875$Xk^CmaF^Nr{<)#a>4cQ9L)?hsgBtcc$R7T4CymH_nli;yJ`KOZ09ciJFYp2(BB_iy9`Y0XS4TPvV4DqZ3cHXZ<~MQ zCOTie{Lv^p&!4nxO+6ZQ-n#i=FRH}u^px-_16)@M3(2eE0PfL7vjS;|$gpsqOBt1w zL{dYYX@QI&Lk8k52M!p?lWU|Oq%>f@*NWBL4_Pa1Odp_-r~j-iSu0Y;H47cXpk8kW zcS&N2?rb{mZs(D38uUVP&LYh{zaOg)9wW3slPN70CUYKhOjc*HY5IqsXyMlWDc{*W zjKMaajy*AS+c(4Ur8;Y)<+?g?iKUKCh3uZu*-wecaV{S+d`+_l&YYMWO%uk2y@D7h z)3~4xNdS<)y*ZELpZ?lcZk92n3!dEa*3o#vb4{-ltAu$e(tg2a=^{cTWRH|qQJ!r{ zH`0^x%JBFaio)kO2Byh2B^7Z6`S>ve%4qcP@5%@-RA@8`*Ca1~!pJf`QLsE+OfGG+ zd6(FdL3~{Aa+;7)TcWPA1|2IYN7NG<-@jkezT1{N^e8IJ`D5i9fsvqd@MWgYmuq?p z;e|6M>gPEfvNLy3=005!xL)EhPqL9W!mA-GU|+_OmwJzZtGji4cppz?++Z^zwDAnS zIab%b{=|6mgz&V)E$lD;SIyUdy&e<4 ze=dbtZ=TB(;o*0<{Wnr#=JM}G6ayjX6@~c98%O{;|BcHo;sHf~eZkP^wQZ{==j&7< zD{e}S^sPUjz(Sk8s-AYtJ%KV-N+}}4kpL`@E=U`DW7j`c2NLV8B-pGE=+)4SpPgjY z;X>V#W5S<+%%L$ru5a0GU-g!xCKH}HYb2-SVBK{V>_mL`ku(PKio>_p( z0Hvp0Az@#ms_n;p&#VWnnS(F+N4MCQrT1M$$OiqQSeSc>S}jV}*|*8+u`f(x9N z3}1Z5VOh^lx{956J5BP$(G~jj9~Gmt^lmcD*{_s4D6} zu!F~}QV59RN$Z^-Sl?$Jfft-TqhC&GjZsi3j$*riV@BQ&kOw=CirfU?kP*a)?VNDF z*k0pvCS7LIakGXc2lA7KLJxjN`M|$NijUMyGNN1jV{=SDb3{61%3YeV$ub~IWQ7*| z4lQh}A`9rpuA0ReutfdI8w0r~tewSyS)wlNq5d`mP@G3kHlTI~S2`h#`q~{`BZlzK zr!(4BK14S%^~Yae^%8c?Z_zSZ@#uQ^MAMFeWxu^m3~a1}qUNWNO}@O-AN2mB%QJeT z1XxXiT2L5^>5YRn8JTj0EVc-9^-%U+?ruZ!iP%c+&z8=aa7;6}2=i$lL`Ulg^EF*E zo4|{N#ioCj3ectjyOW|U2%f!m@G6jHnk4l++cVpE+G2vy!aa-nzNS6bfn!tn_!qTY z2os~f%EK3{U(3@-l{nf;yld6yUnN{&7(CNHl%xF~X;byrx6%lNE#d1o-jak~a{%JV z0U?q7bFFQT5D28wrsi&`Vqlsbdz-5L+w3WOOjEB#w?=zzJfpv0tn(qW9#{eza!(Vl zH;(6sWsLC9ml$~VaCdKLH<3_jKw-(eEFs9FBBvn}b|K!ug~$592Lzn+^NB1L-jahe z3|NZT08eqChEq3xe_StW{Io%Y#Y&9p<-df~Ds(ej_eU)={{khjIBll=&y=a<*AzoQ zOWx@#omHD~&k@V7;(rl)fEK)%L2~o9`pwgMTl?&POlrINX5wA?fsX8fGlc0@OW@{vDvHHb+KYv?3}6%^ zP&&fXrxa11{j45l6U>FX{1gJ^9No7bu4bLNFw5a`it%30oXWcVmjZm&b zstv<+AJH0iVxwhFlwW+H+8{{}k}ioDD#Jkc_h%yshIa$V7sZMPe^c3u}6 zD}g8EXV{W&>kLO8Yp)f}WJ71>jKOA-Lyuy{$5%Hge@zJHjS!$!jQ|u5%Ya0~L1GoN z^i1+{h{==4_=;_+8FEa`%%-mkpyh1pobRPx`x@#m6vhc0T<(l^%>TMC2zEZGIjT9j z1ae0y30ZW!A?=Ab(}6ZQIS9uCWLC~C@uwkv8A zi6)7rh`M@wom@7KdIc*l6vD!iLaqm!5%gf1A=QHrDoPz_0p_9q&TxO==l!e&YtYF> z9+t@q?7iwC6JhRp=j@uqB6{b*2PNwiY+9lD_(`UrvY&$W&4AhpU$T?4zXqOI5>ZG* zU&tjyhdt12SP~Vs8-A=@;##ALoGFd=cKzs#rn0Fi0$4yF1b-S5aH*kIxbuayIWcNBdLHWz)5}&gDe`PV{}8%Yh#_o4AMMhcsL< zIXaN>>q}Z8ny}r0fW4(uyP&OuS(9bhg3|S?SDqh3v-jV1tV+PlsEiV`H?QcufuyJF zQAk$fvYg%g z&N{N_`v>}^VFjR=&x zuO7y!lv|gM>6*KIe1lU*I90E}cCn*BG?3pCR7Iw~&5P#`>Vk~gphHKu-31Loodd-> zxzd$Hh6NPJzq}vaQFB3IP_BB_k43cgAV$KVm@?Y8YZRkR9F4#Cl8C8Pe{w=JJy(ZT z$+-MD?! zrx38)ED`EMc54?Mm|P^*<4!Q!mJWJWTp*0cnVZDr-|YRaIJ0eUqxK_K97BjC%>=DSRIKb54GgFamFlgW3fNT`S)4fv{(k?9cCJ41+D9L>|mEBD}rnN2deBa(!`Zd=3Rf zsHM?CDu5l@Ri(hFrlCxvUiOz9-+*^|lPKiMItPDEK#vvevUcB?z6}*S@HWww*`Vr8 z=CcImfvJcPQwz~|NR0<6`iZ( zH-RED{#eOni%q<0oT9voLRv-V25+T^KDbiQUdcPQF_@&^^4cz@XyunNYLXzUAJ5XD&dphKBgu+>sML* zM}zZ=i_{5qAfL|uZVcILJ@Bq(EeF)c6tF5lsdXd9IP^XXJ_Zg7MT&Q`bD4`wVR_0m zEDD5e9(47tULJ>QvFti&t9XhhzCum2E&ypWXj|b<3TnB_?&u zFg^0%6R0_*p0^gEmNVhztEbFq0_wZI#F_WpAEfVb`Y9lk!iOd4z-BBlJq zNFJ^pC-eBA^Xqfq7t6a3(@w)W)(?~?EdgDZ<_QfiLZ-SOB9(i*(4<^9Y`FW|TZYz6 zEw*Zv!jNyA2hzwNs)q5bUf+{xNZ5yo+&>mF(WUpFSK{)7(3=PDYQ@qME{$zyp?3tYXrHC0_@s8d z1Ok`&C;;R4GPBS&3NU5HogCW0#~z*o*}O5>@BvHXERC0k-@C#NXR4qwhaiq0mAOT? zROHgD7zI~Vv#;*O*6YVJJ{=F?U>CXB8JNAk@SAlgHVmgU7CmUTC0W&Nk>=Z)_Fh5E zG#@v4H|jlQ!^whvX@dHC;$?DL2e>=n{?2cwJ1*eiyRZeSAl$@8#aiTs{FKzKGt?1g z|CCbM4zoh1eEVT)=);hbP5;C6x=GLuIL0u%HUao5=cr`owc{lG9<$c&rX(STHJe>y zy?^ZGg?J4XJ|s^TF%C%Kc&BW%+&3as&hneW1-g%itV_qGA&?3TT~S?(pk>gsCio!Q z&R$r?HbNn621R3~-VpY+(J5W16HocQ9X3eLCmhcvZKaAtN&!TQ{+LWhy{wB=etCu5 zhJwoMXWGQo6%q-y*-ubo)Xb;2SJJ^wt(;7;`U>wPTI6}$DvdMNk*Zv)j$y9np3y-v zS{?5D`HfE~Rz$9rHBDu^5BXavmUgk$W@Kdj-0(a~{$yyzJsIFlzm}PKY=##yJ(mCc zaVHgy9UJM=RvSfG26Hwhm~W9$d4jW-8Oh#UzlHpNIG<<`!%?BYY)a5JP`39nbMhxVtj`o<(r}RC2L(8h(XE(-s~elX_Xr zv(FPjqiv7I!Wi{q9`i-XZOA%i1ACv! zQ}qGfqVBj$1w%;kI8AS@>|e8a9w4%-sBH#yXin^0#F3Mn9qxHb)YrFcXy!qH(zd9d zmO3Z!sX0`Rc~&Uok@5qr!b0jN*$cK#PEDXakh2xgmcoqR=i`bbz}UZgKD#(ej>UE| zKP*=m#m+%cN-#OYm)n&2o*^akfht+NLe?Z96sEno&*~jJK4ielsmLt-skkV1g$O`p=|u?|$u zFPHEwBU&sSJ`eaOCc4$>gsWwgg#Jr1nb}GTeE|4Wjr$3xh&(fce7=4euKI}jV;uOS z#Ik}2AHZlJkJViAXB#B~WiG0P3gv0-^VzZe3t24kb#9u+0w>3x8cro40_VK>rrB8DgvTAb+m7x6!$tFTA16o<+42nfm<33UR_g(v9fO>!Bb zINRe)1ZY%qvnfE^qB%VVWpV`pT)x<-4`W3rFhaC!+KaY@4K$Txl;lG84i%@;pt>tn zj%u6|#yL_%+L@IJL@(>IW#lcT0BMLd&8~RZ=h;%@EAbi$IWOU;ql%z%AhQp@4}58Z zT5~~cta;K+V(HsG<(a=UOjO)K&=!Ndr!(%Hq1d-b{@%8X9NHdO*qr}&FS^zIi0mhH zu|B4D>oAJXg^QYSUuCg(A%UtvrA7BAJ7YxsP~1Frobji(Kd@)bwZcWZk8L1WO<90Z z(}C>U-nEyG*(ATlcvsmQsYVPU|EvW|dCL{%IBC;s5A*%w?GxB^o12)8I*`?cZMYt( z)1uAN-ay9lcRW67F+u9V`QRew$SFq`BU|q|t1Y;A{-?t&aa<=!tZI#!Z9U4@{_o%1 zP*EZYx(#hD(b{yInNXgc4PoowT;#M$A9>VkUzg)7IRhW55wk$z9zgC{26!@8A^x;_@MQpeR7*fE}6{P3a3c2WoOphZLjdO}@W=;6Ha zj+V*1DN{Oi=)dBlko@=4Q6EH4^q?vcG$Z#RExgCZzb)FPdTz7iwzrxCmS3xzN-9L zIbXlTz8URAH4}-u>qj*^Trj&`nOQ4n#JZ1OQ3xF zIbVnb1-1F|?n#)OTw)@%ec^MBfmpdjk%N-LPEBGU{X|o#gV5)|z7C<8FWOOG^Jb8) z6KX4NK9PJlgMfJ!-2FNI(2gD4+96KCs6(v68CIj(V--u*Ndse${4wcB#3in*!zOE+ zkO9c-B9ABiwX%-ox0OL@=Z{yn*K%nn`kV_{Gc*3mocVk--kgy}2DaQUR*7la@P`X} zEdIQerLpXw2Y=tv-KO2kAC;d{%axOXKHQ1I+Z-U|=I5f(xYP^_c>~r|gygE;i(q_b z2;cQD7weLH*xur7JlZS!VJ{7hC0rr>>%OHJ0D@dT}7 zastQAXI9+@NI}@bYG5-Ooz+1i=KHL@G!Z5ie!rcmn96V>7Woy3){e)0M;{JBnC>5? zUK%^W`btN?R2Y?-`5l_3=4gc)pO9}?CA? zMBp;2>RKl%mDfS^XrMLeH#$sg>7o_lm8z0ztvM=l{PSQbUXKga9c61A5y83T1RS19@2=G=JNz$VK*_%>4r0<%^*`3$ z)NAe6$mAEfER3T2xwi$axzVJ{kxhrl%7kOWa#zg7yS6ZcZ(AWHfl_KNE>YCGkz(L% zke53OduNvNA3W$HrG<*Pffi9Y|1<^;zmuFGUQg{OVr=Kv^O#P0MB5bSZ7RA^e^5Z@ zVC`H~N9L2U`*J@xN4f3H_;>6ZLtb<)S(~?>W6);hbbM=>0Bbe0d;s9FTM818Ie(0( zLcqm0|GoXXjJcv@UsePKo2Z0kFCT4j=Pl{UZXuCXP=Iw3AfriKExU6RIBQQ?)n#Zi z2k_==SB-Fh59A^bXafTXOvO&is9qP8d|RG!!uckm&~O&ilvOf|dN(hGHm|XdQx(ir z;vGp#O0sI&wy&65PuAk~n47bF$w--@`2O$2xYy^kw|}|?8rIkP%+uPh337k!UWjY0 zVrJa6UEUr>AzP#|Uuvr}Qhu9Lh+UYms1P6aSF9iHp{A--yk=*zj#!v5LNZHb+h|h9 z5TY|AzVTujib6k|i3)7i7?6YxC6}nG0&XEiu{Nk#^dz|S!hxH1S${7Q7uJ=#ES);s zGv9~7?9u6>n|kVrcqif8$noNWHjHR@)aq<(uqwVQF0OoXqD3Us#ALgJSYEZ)l%}>U zKVwuWtE?@>fJ&6H-&$3eJrZh353V8aqItp=KeTJ=>FLde&fPXRwY|W{{laOiB!cve zbJu1xMr#2kbpfrJ5AChQBCSgda&&$ML*_v2jN?*SQmW62jepEVM2kAdM*{)uuv#%fLMP;55a#fN{x6ngwfDFNs>PwoYOQNKm9fIv8TLc;eVRe@;?au7=QW< zAOptNzCcXOp^!N4zYFd+|B2RtOm%!gW4vw=uuJr1mFSq#K;yV}b0h28;`Y0@T+q-& zVG>K&rn^kwBi{3kcKhvBUfRQ?Rolbx;NG2OJ!Q|sVMcKH?MtPe{Nu0lx97Y4US!Ls zbKW)7!=BTKBznJ$TZjE@o3CV<#SvDGCr~2J{LK|r|2pVlMCPvXaP2@8uSWW`$6)7+ zWChk=MYXM1(&mZI-`N-R6)-y@z;`u7i-r5T=pXL%a2fCuFX^{|(s%vr|p# z8-;^cp&0`iY11JMC2yY15;uRcH|p4Gz#^fdo2Yrn-SI?%zQM7}?fd8P(Jl=@L!5f_ z`ms)X>sL27I&Zr{e`QH}*3Vfzj&g;U!Ktb5sFp1lpxbG!P$Y^^kDse?j}qsXdd(t5}Rf zdSxPp5@d)|WDG(RaNu;fLr=Io7Y{RY6!fz%~xZcc+w*JNS zE*lH-@YpZ7yKor>DR&?}qCb-7;VHAsUy$tOrEwUN?&+~Cb`n@CiHvEjb3ziO{kU=& zz6+J*e{7P?f;0m6w5`Kb&x`TDKikufP3=T6IdTG|pVhIex$-uv)xDN*GB+p3`1Gs` zb|5k7AccgFLQN_PAw3p=jCJiYstJ1lE0kBKe~~88jvAd{t~J5h(2>t?hD(M zee$)QIHQeI3$hl8o-&Vl@kuZr37RinW{ReRRkL*3lB2{ZKqsr;jeU(=pF$#Avvz8+ zn!x~3R+S^$D9fUJ^`p(-?%>rcwr?$Ck@`OPQc2j>aqO~|)~e;s-_l^b@oO%%zT#_j zn{^wxx%(GStCLbQPTexcqmI^T4$EPGdezLnwSu*t!nEcK`76Yjv#VTRW^Bb#3l1&* zL+1C@I$_2%A~*WZ*7ojfW%b=#tGKc(xFX^3zY9+bx1GW3nkA*aHT{ye8)=f=&voHV z&Ci={!ClA41rI0d#?t{Hwo{Ez4Te@m(rLAqUPb9FACu{M$iQw-%)oL@LS*0_D~foq$B}hV|3oinHIeG&W+b$po}V|l zm-sDZgdA>b3h&o(LPCYeD80NPq)|dDa5JipLpCgVo3|$&przNREfWyog^GUdiC<5{ z@EvcS(Q4vYjc6d0xLuSA9!g_tU4mMZgXn?yZe!a->WxF@dmgzA#(Dzf!uLVxNJs*W zImlOaQyqsp9fimT%fs<`EP10B#yao5Cg%c@GWHE2(pw=@L=#6~RZrAC(;uK6>kQkU zYP@IL1&}XUf&x@?g`f=6(M3I^%%X^PKjz$*&+fmK_j8 z883gX!S)2={5;C^Q2QHsvUS#_`G^AevXdI{%Iy!%tN|H4YOw3_t&E8c%5=%{N!=?z{g8Db-3mCFjHThn&pQZYRN}9FpNr5 z=qe}uudUATMF;K=6-e?o#*b?8p&HA|1aE$N+G9tk5mrK_=Q%YfjU4CGgyNt?9Rg#2 z8%Y_D<=O z_z!G`NH4Fbx@4x6Ia}athpgpV2hKOf>$Q(wGz(2pFYa$Vq@$lu_wqXNw7o{fSF21h@ILp3M1}x2w6f*7-B8&dBu7Cevne1a58%}-D zuO%{0YNSpUf_6iuAXGLu&xN(n?dL7RDzqprjhXKdg~r0QW#&ho@GDc&#agQ`Sf(~M z!Hn%|+P>EUGpr%c?w-wmz1UO5z{weU1^io?;QyEes{;$4QomeN@FGqByzs*AVeaJK z3c@yft}AX{Sc~89F)e&H=fb|1Bz2m$#(2*`jREUIcbI~vJ9y$-nNkecB^YvgB#dz& zbJJO*yvvFFy!wG-=BZ%SZxGHBt}^j)w`2uyOel%lgA}j=I({F3Y_bJ8;Xk2=U6TZk z!$6TO1&%YdsAKS}m zy3Zv}uCnqTeE9lemH{N`)O!o{pL%^wH2sdCREPbYB+&5E~L`yK&=A0zMD%O4Tk@|VoFYm znyB#M0g;t?-X0IlIQH_4+#(%j2H$O8D`e8P!2Ecx;$4&$C(gxhDC0J~Z9b0zTy;DiB&U%F zInerO+-329l}vmZq2qa88g=oQ3`=}JjnHELl4M^E%R3bH!D{v2SzvQ+Fmr~2oyT>( z*k<0S*LJ|P$h0or_E(OTPSRDabfyV>)`ET;c8krgxH?6*A^UXwASN+K?8m2^=we%C z5`Qos`O$ZA(#8^xs9@(3#Jo|(ciIrwlOQ$A{ON7p&-u>6oZp@x=IdsL ztV1rq8oSE=1H~VF(Okg#_eBbfX~GeEUh5}IY3@x~(R2Q=m(t`C7$LoRba}w5?l|n@ z)`lBI${KE)z?2e-=r>a&mXe#~Exq%rI`6ZRrBIT-5{dI2-M3e^+!cW%kc*SRNy;xj zT4ZOu9#ZpxKHK=BXl;qyuqZ{A$Uov<5SP&v(UxZ0i)1a@29j@Od^5Q7+@CYL?Dx;2 zOpHzDi^@2~*}ajx7^e1>Nv-3d2-N$pcg8_;EWAHHuQL)BUH!*il6 zl_FO|OAWER5tE~s{V*}hj}+>BvQug68OqnoEem+!h5AThy#x<)GyRcy)ABuOz>iTm zpSZ}KXn4-?Y}qQ>fb)JoI?>xYQeaSWeB(sje3_(Ax&*{v(-Ix6tgm-WLN;&?wrtdB zl9vzfht*a09hU$QJ3fx!vP4YmV`vgC+O;zgADB- z%idqRr}+E*Pg$0?Sq^Il8La;^uCpToJF@=&3hX4k7*1$e9Y|l7q1%VDXMTV{iGUs| z(J(XX-?qzJw0%FI8(NSXAKjZrbo64}C^td@Bx*=-M4D;Js{uh~PN0K#`jIYCf!eu#tK3~*71i4ss$e$dOqblT*Ffe-t zTKRQr-chLu_W74=FJ~r1lUHOb;pSewmC&3MecOa1ML9%F%ST?f`z?Zzp(tc`0$2B7 zZw)zOhTZAKYf;eExiMQ~PLZo?5oa4phC}#b>+U!l;+y{qXPNK0+1Z0^d=b>8t})VemBeI<1Wt1KD~Y!rXI(6# z+K?XPsGmQ+$zuJm3)h50=S^GG_>0I3JBror)YI>(yA@Qf`A{%W9p!kM*&QJ;_lPUU zl2%nk=YduruQz((i7mH4ynPWdGkSJAQ7)L7*PFNTyU+_=EkgU#!-xnvZ&eTPV=1d& zbFv9Yc=j)wO}<&YpOwpy+`rUE$~aZ*_TzV>Qg}s{*Ad6;3nBJ({Ao^ZgW#|a@|RR` z_7=#0dPoUgGV%*AeY+PwQD+gpT&?@tuMO!3cp^wdmnr#(l0QS!QHbN0HC$};4^Mvy zXz^R`tNrthf&|t4QE`#$hF4JW1##v1#TA{v(8)-0y$jCo8BMlfg(Pce=7L6vu;v6J z5wUet17wQ$6pV6KxnUCzdb9*PRz2G?eqsK2M~4ieo9k zPbTA%FS2-TD!&_Uh*d_-^22=#*<*0H`oRRImXEq?pMK=B**8{V=3LU{BuTEgTKey3qV<1cDBRAxJ18?{R)h9;SKDylLiAsjIgj}wK2uHa(fum_*^ zwdnpS^q)8T2EKg9(lpK|uy;=Rf9U$kpf>-lTOhauC=S62#f!UJaVu`cg1fsrEm|n9 z#ai6mp~2l9in|k>%m1A7&O7(qxqBwblgXDS`H=P7YpuQZIkIB(BIV!j9|k^fR$?&! zk?8PitU9|g)Y6*2+oW5o?0Ou9Z9Ze$68b2*&9$M|)yVqtzN_))-Q1R6hX-TRhy}Cd z!FhbAJ!C!U4h8M0)nn$?11I*VYufPc*YjHC>qBM0-XLv`?FP6JJ=LMVy?S2FprnZ2lNGB(J*GI`e zXqbSF{R6agG_E~DC+3irQBQ?)y1#5s&=+7Tu`*%CMM>Xq7b77{nkT{=op8u|`ID&f zX}ACQFvCgFA<2J}QTMo)$a+lo&u@O3_;M%iE-Rv9YNd=`OJyh5iVZBVya|#M){18p zVkA)CB|ZaiI>)yZ4uY*Twxw_nY@cxlX`9-H|3s!#`6I(Z=)#VVeH83=5x1fSAfz21ABi9e}c1K;d?uUtY@te1E``mGOPFu7 z3of|i6UZRU=12E*8bX&6=3Yu4N280`;&vQd_54h;%)_T7F=1Lw_wBqw zabch4s(&|s|FmQtY45&bF8~jMENgn~w)C<=H)C=fCNrF8=2>!jOFqPB@C_N6%1NaL z(XnyHfunY>MBjXeAFQMOIN82|q^p(F_2eFxa1wWd;Cwh~762iu=u6)mQW?%R3;11!satta_u7Q35kD)NLM@Oe!ujA+T^ zUX`i$Z-2UPySes#icWJ3{1m21GBc`7<2SUwajG-jgE)5Zn8^k52b)axsX)4%2am2E z9u)w~&<{Dw%EJ;lm*ZsDGu`P6wS;W7bD+BM);>@UjXZSdNC7vE2g}~ouzvTKHOPJK zMol6Tp=j%EhD)k$cTLtsIk7NVtev7^Z)fKu5MrvV1~c<}fh$Cp69NquJFn?Pa~%~c zp+fMUgl+Q?U5~Da`htLK^O~K?med&30(;vZbU!r8j``tljEU+r-#R-p7YjK_#v#FU ztZaMA?rdZD?Hclek5AQ_`7*a?JBG5zn0g;3_gh-$LgYVf^-msEqR_`YOuxv&LLSa9 zn|br(Pu=9`Kp^m?6|U#Mo8XoJZ$b&dum4?ZM)lq8^}irjit+x0)sp8%+d70sSd4Ng zYN*%ZXdqqyY-adCL-0$8A}vZ?BI*+CG>S>%+>*4wfJj$DLEt(%lIXWvQX=lb;zdbs-?uk6;5}g|CC7UcSuzOVl4r%?_e53 z#J#07UFehxG61_jk(~CngLS%QuAgtNP6`W}8t@gTWqbY--c{0|5QO)l6KqEfpJ1eH zc2HBS$Z%zI8c}9N2u4+XwCN4_f%70pRQ~rR`waQ@MFuDa`kvE?1<8H(%MFs=>++I4 z)RA;w|Ld=G{6oc8Q$1yxYc93wnY1$D%pWCHd)- zgLM7TOPTv6uL9tyc8MY&HT>S9KJSGU<2J|EBhj?vx8L|N?Z~kOO*5)FPMHz+AcIZA zX^R6pXdyf0gGrU_`%KEpx4)75qYZLwKbMGmsd!j9N5d(g>X?TKK-rorAgkLj@8$tE zF-j&^31-80l`ETq2;(qw;UiVi!(`%bzvXV~>SapU2syik{b8i!M3fk|Y{JuBw2oB+ zBRE^KPvCx&651Hb1k(D$W_YgV{Fbw~2pU{Gp=kawee*Z+T2Y7-jVGw6f{)o4N;rVB z&0p}F#~f$)Op?lonlR(_kGkpJOXwi-?)fe1KC(ANarn?r)ko;7-_^?@nLTbzewUP7 z#hUo>EM$kFM(taBi3yLUE&Rff#_@AL=JKgxtQx$apO{TM8>3rhpo01S~arm8#whG zvDY>^D@UApexvtd`ZIq?XZC?oNk%A}hg80Nu&huFay>)7i>OY6eGAtKuFmU%cn&~n zsxOK@6v^MpzY17D0AuPw9H@f9ymk)kpJ0AE-V*MYUv(Z|CrNNBm zZNW}l(M`H>&Ay<%+uHHc&iO4iDU^w27;!%$|5Pi>T|}bj45K`vbf3nq3FQ~HEUL>F zbXq*$uD(aMwV0F`s=jY;{56CJ;7j%OTVC%g^ggFX%K{4hW;hpzcy}eh7eVBA>d=1u zC+=mVHOJEfc5^M;o*?w`Uk2_w%%InIl{U0yW~&y@_Ct**Pi}$;O`}zN(5Yx0Ol%gj zu5z;tyA2cMr`cK&J3Su0k&L1@;D(;FTa++cFkZ-navU^zYdX>p?olgkb9aVwwMY+4>UA=urPM^v1jMHxCUW)56of|3?NeNX};C{lFUoa|fz(9HJ>Ky;Mbx zYcOqX6wJ~EBg{EbOjxs@>2c@3^_&Qudn;+OrigiSk#->GHbz2tB;n@Y2H`|$;{@~) zs(*^2Els9#VnMgarB z3_7C7ORD{2mv4lS_!yh$4|6LiTLt3rjNji7T^3xtcA_D~kcgnz8&w@P^YTlgnK0z% zq2YLqK+7_dP-NQRlv&c~PoEwr9p8y2AaHoYC*vLzIwicV!;I=6(s0$bsS*Ha7ptX4 z|Do%?yEJNvOG3kT=8ZHefS8p<%3LyzWyJ5ej@ZX*~PA~DJm zy38$!`1`F@$0rce0U)NIjZ1fmlOd%R%)hP<*Xn|-?X?=$zX9+CvXXTeuWjldIQt2E zP&LIZ1Is>hu_g$)u9n@_*x|Ah~_r;_==X=kJ_*HMKd_NS$-W0DSaSA>&r zM2}Mb;{J`W&Bj;Gw-Q8D{~k}OYf3-p*9h_;q42nd`v`_ezNX9-y z9Y1(q*40Q=>h}D^ggN&eXS+P&gf(KMKlvGfLO;c1EK3V)8LoL?;lb5bZlPm{Hf;{{ zq$mr+L==%!1HEilrHT;!TS6XDuWifcZwUwxe80u$JkXp#j#14P)w&PQ!thC`AkUwq z&k=?aU{hPy!r$w1wQ)sf+gd(nU<#MW+tM(vO?#e3~ z#B*@I))u$0)X(YK4xBp%zZusz)(;vs?W5Qj|J8T4)T1IpPc=lF{#!|g8h)rN`oDDK zw>SHC#fEoZ@l&L-VVr1<4Et(!Bwg}t%1tr4<>2zBlpYj^OW6>L*O?c1tY8%phQ?{^ zM|!N!>bZ3*!_xbh1cS=5w)ONFBcGAadDx@NjqYFo^>E7;iC9du5wxEcY8ONe^4ZW& zX1cp%tiQ8Uy9)%_XPp|-diPxMvRmN!4UV6K0#;UGZUD;STga!G>TNhLigCFe&Df(_RfspTSw`9`z^FABk%3#1( zx65xUx;l-kp7Dsn_13z#aQN*8C)drx%$P4@I4Y=GQqOQF`f?{e(ewr@0(Rp{ZFo_) zv#5v65WwXaJ>!81zg=9h)(e=20#kkqkuW-Mh^{Hm^TM@t<_v|y-QNM*@ywOpvyR|! za(Ifqr0MD@KCd5tH8M?yHEK)9eHQqfSa9|leJKyJ6yemBy_pOCyXU5R!UBWy$Z<3i zX{GXw7Q5kSAwjVb5cRj-bZG+>glaHMgG!@LqE$NQZ(^Eaua;t=t>Dx7b{u#)iPLLk zW?}GdqFyWx7$3g+$Fi}{_LC$Siif90lywLj0_=WFT?Cm=Rbu^+nV{FERM`oAr3>Ea zvjQVb%EwpSU#|(VRC4?h`f!RVt3szHw~cvRXnK(aj~g%=-Am_=-hj8Lj5WE6ZjC@u zMXu(v0I|J=ST+uy2RuZctRDNWeI4qm7K^)Qs4@8FhE_%!f6C8lVIqt;r&xyeN)FDt z<^$riem+(XM+8j;o&$fuG48cDHu&6%z`PSr}kB2LGHPzDSZ>N`UY{2<~ zq2CKjw(sR2EgCZP)|CQie#G5x`-h6{UbKqR#kc8lhwE#xEZ zxmnb0Az3pcRQDaWsOfb*tKAh17Z>gkkOm6rcY59Z4!3NG@4(w&SaaLIU4ue}!cyUM zW_Jm}8A^yqbEos-a~I9@7>jA&qAO2a?v}|LL$;L4e(j4*mu;@(_6u?i&jq8pNAtPy zve}Qiq{mTlx(u*NkJbdwQ_(0?sS+_dcNxhXl^Zd|j|z~=v@;PlcUnT_6+ng%cYp{v-x*>{f?+PobRsy#JBmtDKnG|%x0Xf(b<=}+_TiHR1`^4c0H z_8VguJy@)(cIm>Xkse&(8yKaB;PBRCM-BwDpp~e{nt7Tdea8MJ!98%DN+f?FPt-yp z<6?!_PRH+c`tf&4VE#eX$OYuj>WVNt_mL*+LS3x+NT~yCSlHt8jJg-!S5YHMfXV1y z+@6UkAp>G{5jk8tfBo`kjFI<7{KB=@j|wXaE|;UOR}< z@-3x3c%qWofZY!}Uc-ChjT_C9UaDg63H~jdt~USw5%BK60q_k1KNf)#8T6urPpESi zx3d=uvKK?M7frKCx{Zo&d20Oxy!KN2vJMKe@(1~OLY`L8NEMm9LcS|+EWjsGJ*H7_ zG~VV%)*H9h)8;CCcVhsn_`H+6vVGsHJ&i(YSc(58?Zvd<^SwKv(?;K>-2FyR7fVO+P^LS zyZ#n6k>bf&(Gw4Ll-kBRe=k+iyBUh0Dr1q*v~?L%+MWjQ(dJM#Fh|8WDJw$K!co;@ z26=5MPdoVS_yE=a$MOQzyBRjl1-JhW?V(qLJ+IMK=nVld?S{$(sz)exhist>@*eQw z1mcY*-AHeADP&;63@qdD@v(0Ve*Zx(bILlb_8MZj3m#{H)^OP%e*Pv%wQA4YB9xf1xT7$QgphGDb@+BF_uRCSSzNLL9+ zvcY~WJ6nz2jP0xwp43C+LB0Vw~fS%^`YXF8y&NidbCxUSK-DIDX zb({%G6Qgd_rb#~>I4ae6<7E3>&Xyi)xpN-IXH~)hGvFV|a6m_xg8$XctyD{!*iDBd zP6xI76<3F_oD*t&JIK52xvxdm01#he*{o6C{@j(^7+I?a7qH zTaysfCy=4vN)A1Fa~x;n?724njbcC;F2XJzfdtJ)p3PN>42!UippioUN}1TFgh zRNc!^)i)0=aYR{~(@%CK2IqIYu$in|1yPCEW9d$EFE9KCjfy;Cl674wKa*R3ZnOQ_ zg4r8rd-}8d1n$Mqp7OtPcL_!i@YmPn?Q>65*FtRwX=G`@UE~JiR9oF&eJ%IybFb{5 ztLnY|hgI)ChBo|oJoGWi<4_g>XnGuo+T!=tgM```YQ9FH!957R|aku6KZ zrk-;Q{41v$a34N$y_WbO(P7y;Ch3U3s=C+$R7ePC0+VaoJ)%1Br$HRFwRKy`&F|J=)sZ)*L<`HW) zCKk~Zh{;*CId6}IFQjhlCzth_m8bmAs)oO7tl1yWTocxaHr~IKnzOlQ-1k|AqT)v~ z(TDU?`Jr8dhtC-!5qA7PzRgJnG28XBu+i>=2erS${|N8cxe%ZHu|JUR9>E7{s6q6# z-;M7;MS|{lF{mv&jzBH?=dc{O>Q4qvr#rTHRD=$2CEu4fvjlE{{d>^^sMx==u}TaT zr9+qso>Zz4;L$;K#%?qaPoWuZwB?MX-~P;7mdCDB{y*9J7Shrm6(_E5gJ@xH$_9)B zc-xg=C-LfIGHYW)nh_^yl}IR6r(=v;Kw~GJw?6$uoIUETj_*V8M!POKJOixTyWncC zco+ALyqC9(l12&5TsBtLGWoLd_nr~y*}>i!u9roVM?yTvwe*R5Y-SFEGjJ3=^#lB z*J(@kM0e*e$U;XwHl<=~$IYx2v>^VLX?&;utB|8Y;eP0 zB@sjdW|a`W1EW!s9#m2fx~+He*krVRP~KMYDYzG{4a#ve>pnAa@SD*f9e{4`d@Zd z&O!2gW}9kjh=9Z@b&@vq%p7$vDC5oz_fl6@dcK;Qb(65l5D}qnzB*slyjIo(ueRU% z`&NcqEREl)@@Q~2a6)0~7wMPcta$j`G&cphuT+DS^h9P1-D*`?MinPK9!#7liZIx> zOzaqJZ;HnBGMTI}X&g~_2W?BAj7E&kPZLfN%kPH3y)+WyRp2y=4!7xSi6)%tC!-PT zI+{sVagoUEXfK<2P%nrpO!S8}4 zS15i4I)UVA!VF5FOi0JRxSidJ2e#H$7B1P29q|=Nirbd)8{Thk2>S{96u(j-W zCIro%Uu&Jq>DJX~&3?>uA@^%}d=Wlew#Zq!S*kD9EHB|dYHTBz!gVGzZ3ptrz?L}5 zluA&S;=7-H+r!9`@)KP;s~YQoPp!UOAX|^#pTPLzG*xvfnCy1G0wJoPPL0lgNqA;wXAcpG~N1jOS z0Ffx`ND3hX#-(lMq!ZJbU+hQLG6Vh@RaaO+A?$vS1aHZinZ0q`f>Yv^&UQ1ve6pi- z5b-j)fMt5yM`%#kGanLeLQTevd*>AHZ)>0g@7NnM8`Oz?c=e+e_~4egAN1j%Euwph zqGcZAXc$E3Z9vQ@pVzCgFdxi$^@ER*34uZk^=4o%=jMKrmxI?nyK;mt20Bq?dSBdc`MoKQiI?#EAdJpOmj1M{?*#vGF6V^Ez;sX^zsc(SeL_mfbN9v{ zkhM=DZtn678XUw+pdfHr0O%21TabJ1Dqyubh z$}~n#yBv&t|GPZ_^ERR^o>5PnJw>!OqL?%P6NjZ`&x}Z{i%arPpoGS2`UzC z%?`v}IKa0rhJfiZlVqHD<=VB=CT_rg@8Re7!{+2lW605&*;_osVBUl1W^(W&5hh(k zUi{^Y*DpNPHNn@F&S9v9&oP`;lHHn6YHRz|kCCXX9g-2dSG|*m)KVE@%u#*8&K@YZ+RkFCoXp@>7^Txs2 zR5d~oLS~W_Q8A(Xn0dlR5TUU~^6_FzZ>EI&e2&^M^fTCWoC!&#V)%|BwXwt9&b?;u z28vpn- z5q_3lw>LDvzHjVCmi0D+^ewu2O!hV-ELT8}P#{ZXj{f;XbV75u> zl!&nGFXp;`p=wZJyHVd8dp z{Zg6@C==<&pT7|NSw5eZOhij25YTAk7NPb9DzFScesci{)Z81!cWem=*c8lN)Uju{ ziW^1lr~t2U^n+2u)`v(#nWpv?1X*j%tIF6uQn7LJAN)bdb9(w=)ketQKPA(j@{F~U zXJM8%?=)Y*)vsg7!bLi@meZQ$(3uk8qvnRHs$&QiEwP(?c^R3i*S={jcJX^`OA~1S z<&W{)8K<*j#o{{-cmQl7U{OcX#sA6vX=!!5h#t^XZ;x=~$H@h+XdGHDRl%1@F|n9KIwHI=Zht8}kI|qs z$>n-`hHJism;gFIlB&DCP~}>4;CdRF&e0}JwIGHTEW%8{p($_1+h^ZuU2&d4co{F9 z)O)wgo<8Q0YGdY71b^9X;R;X@c14f+C0A|QoS$K(?TkdM27biHeofjo; zA(@}nw1gi8I@GjVom}wnXNjHu`0pn@Pa;VGR3lX-8jb6uqwQ6KD|?gXLY8iDJ!n34 zw^>V`6vW?wAaz-^>Ds#EY0|r*U8=mI$O=wHe4-TPV7Z*t(+Z9QeRkZD^XwATQRqn& zT?C0X)!mwE6&l|PE)q{Zb!>}Y8U0>e5b-kWSnBI03x`&AjY-xGm+M#zI zk@rj+jdqrEhfO9E&4TZkZM{i@evJi=d*n*jB1(|m6tp&@vr$4da1_ zj^SDNMsw~F8NE6bek;4zDljos+(dbmk84W_PcjqmtQzUG!JP0R=+SKO_b6{hrgI`l9miFvc>5QfXOiWV*uww_b^?_+ z>f|Wt6v*o^bE~5}fy4tn7In+g3}mOs*J5iqYZ1`zfsd12+jZ659Og8fsh15WrpEj0 zib*pfRG5P`!y|B+x3T(~Kcb6C*4Pe#p3V$&E4&*G$U-DIpDK;wOMVwn5V&#{FYf(% zY9=flcO``OR2ug(s3r2cXLvtJu7P#Bqb}C;x)ULMHQx|z_~%Yg3#|)bBjQ!yk4>e{ z8S&9)bc81Eo=!t}1Lwo@Glug=D!`EeLP?Q|x$`e;phbnadfKHsPwst--{q0;vVZt9 z3h3c0iR7(B_vnUi-)7kU3hGh=je(&VWwe<5kT&0dESlu~kNWzG~E?7>JBgvD&L!;K?qj^!lFeYk$F zv1tF}1%OcodSe#k+^l+3%S;^R{)KDRBgcq zWC}DD8&x3$3M2!tLWp(~WUn6b4^s;t$|ivRBzGe-IRbXCyB6!~cVC1?8f1nE&x~@3 zo_+`rTDmgBNRXm)idzhlqNBSpv!Z1BZsN?fLhp?)njO4&B%`N;ds$EPb2R6-#*_xu z9n#)HuS{E8G@-#C8PjkU-+L^94>}Gt6>d)9RQnyWZ!^5=S)`~^Yqubp_0gcF7DZHu z-kBCeuxlpkeFPd}?TW0vTL71$UVKlInr11OPlj)1vwUXLYd2Zn|i++{x7X8d8fDzC`s8bg_}}o=_gD$6-_D@n}f(QYS&CO-pNgx#A=#O zy464yJ7>QfW>vEhUq%lIiyQXLPo!n^L_#tCP-VDD6tx1fF{iD7G68B*ZtbH@W=; z@GHcHt(fk&oq1Ir9;f%F&m$f+f9tf%q0RZC_hS2fQj%|#EsWaZ=ZV^bhyCyJy1b6? z`CmA_%)2~rcz9{Ew2tDe4ly z@r)-PgT8KYtHl5v%ce=%RR2Z z;Qach=?supvYRP&hJYSYUFRPn$6VcglMzwiMXH_)()%z{oPE34 z^mjnQ-j>IhcGr(VQYoaCJ+-xZ2ZzR>1}`RzFRyuAI+Xx2WBl#(1q@1ul5DlG)hdDI z;zne|2+a95*ooC_PK%WsQxU=M1Y*QL`W3yrWDtKHv*J|e&Obj)9f*-~nfO#&{cEQx z3}sbnOt};ncSeLv6}+D3H{~SP(w{#ME5P`6Ums^4pG)}4CDQh^FzDJ*ua)|pj#BGz zrMx&@%jR-u&rc`x$aD}a4jji@@U3 zptH>)iynhDE2Co0Q;Wm;(m~F6gt*XG4b+RnSQ0Sf0O~-H)@t~3fl8UtkqT2>YO%_s z*NwkWMXecS82JvXGH4gbAup2QR?|!*uvWIrs}^!%4hT@rlXN*kLc}%4?Yp_o?uh`* zAq!YXuRq%=!;ZsVi=tw<_e#_%new4GVdG}@2AeRKmSVMhk4y{+9*rU_ET-7}Ar_4_ zs$(Kq+Ji84zX2=Cq@xQYblOUdAN!c9B50+$aPW7lK8u9e6mOZ#JEyLhbxLnk6rcEz=U?MuH4X%M4Ex%D z*=;#|*YDhAhaDZ(OC2GpVLXW-MWO1+|ElP$B7IQ68Yd6GcEYZ2(fXC)n7REFajj5! z9kYG7m*jDfp}>126c>?@2_dhkaHGKrzP2Qr7}@KQpxKtME6rqNg?Hd)62J`gP(SMG zz;&GkGE*ZR-S*y(fllk-?lWt9n$(nd%f;`qUnNe3V&lh^1E!%`K_QFyNCq`$jz(jO z5dbvM_Bv)DAX*}mgz!H=#eoD4pMTRf?f(mAR$^1GP>ZODj?hL z@eDEdfXYp`VRwMZ}J14NILHc4DM@Dd)f z-0L^|IMPSZD(5K|pp)tR(iKyy;zpJ@W=JckSyuURHR}hF=B!2_z0x8t51xvLy7~|0 z5Lnj?O@u82;DBIHkUDe9ZsxA&S|Q0dUyOG2gLJn8DPzcQX`0g{bFVC8C8JGjfcd?* zmpDH;-@(g3^!5FGp7w0Jm<@vZC?Rq~>rZp-g$I9KREpAy*E20r;HN!%VBFW!douMc z18rK<+a}pRjfiTMjl#U>#7$A0E7~v`X@I`1lQ*r}RvfUqjed zuIARLuLOrQB+@uLn~`@0D!!^3VHdZ>Kfmg!vMSK%TmAz86GxnLXgGo?}0^zhijtvJcNgI!ZN z$Wtm=%eCxkxF5UY#goW_x7>z@XGAs7`O%+8yQ6{p@H{TaXznm|B+;YTXa_J3|IzJS zePU5FTOej=+~M%VCg#S&=0tC8e>}G&q&-I{_p$9K@oCm3H{n#205m;|N_;O{lB;>E znxy4Tlg={JF~T#R6^IjnTEX`fi)AMAyDY@c5x>CXI=Yu^QaYbDCo;nc;HSZSFn(_9 z$r8%!0T)mAciDFYEG-daz0_Jzxcyqj^bSkdn*#Sghwm*2pu>yx?w=pA-wHk?ox1#V zZ*O(B&DygQo)N2XS%2J-7C`2X@rWCHk<+Mjh#dQJBuHXAvpW5R#D9AIeV;>@RD6+d zXJmPKqs{cDKBs;&R_N0|Si0>e@n6kp_RGNMe?Iw7z4LfnIRoBguG57aG@i=&4Bp6`x6Ar$DQX{Ia@@TntVQ4VH{8T-Bf zWU0cf`_jZwJ1|pTT|Vuk5)b!n>Cpx#+i>cXayv**pITYZvKJo%mp>2$i5WaJ8YEhM z<_>e}(v~o#Lgz|P?x!pKo@t=+Gc%MID^P#5hu6)5@1ct~>>YDNFySRbrVnbkF8aq0 z5z<*Z8(S}eaA>9Cn8Pm@Ah<#w<{Y?Tdw?S$CUqq`*R_2mob*n3O}JG2G|gyyaSX9B zbHhwy1E`5;$o*cASP$O4x224!ZM!Sl&Jal)7k?o(;eCP1m{mo; zEng}E4cW98Y^ryx($J=^OQx)bi}REqVz3>}s7pAX6vc!P5`XgWvnJhz8Q@enz647| zkG5@rzprEoMnmO?)|n6L(bb_~+$LERU*J#Fyz}^>4*qi?B)K02Dw}w*UNXzPDgBdx zAQ@IVtg=Z`$A_+P#V;1gza+zGlgdD%RC^6(KTf(=) zNfx6+(n!$alJI$<14BmN4F!IqzwJ1=`?~G87Jo=8?_pkWzEeoFeCn2EMM8l@S;Swj zrVT_M$*~cMv)17Kt_D?CPp3J?@ql zj2p_?kL*8)MGygwHj4!Lpyms|uNpB9r`^r$>*D+1QQEay;(rX04ZJGBiDg(3kt9>8 zs>6d0^OX+LONV_nz-@bMcDNr6b5iLMW83M<0%SfLt-Oh1NcT%NJV=M9iNV|+PCysS zIc9VuceA~Mz@I(^vGS_%6;1?u9en+4VZT?oocEbQ(t8!s$+);`;2Pb}+TE06SGz0G zlwrI4D|Mg(G~ZBZ%n5!#$L0L`OPt76ivM;Pxz_^4N{XR>TH~7cQIsOI>MB6>%6BV< z$Mb5GXZ@+r@S#uy=^Qg){`IfzP^Hw~nI39!J8ndP9i&z=n-XDd&4koiV8$DY>`AcK zKys!{yTToQd$yDL7V*WltljUco#Vag5DLytoOY8 z`l3n;=i;)9SZj&P7d_&+0wqw5Iw`1vq>lR^pcAngMzjbkwC7&q;@cAz<6oqX17PsA zw<8A_6eeY0zv2w+t;}>Q-K1sV${Fq|z1!tuof1sp@%qpY*Irpdl-lsKMajz5XdA2d z;pRbDhH5}4#qOKn*k`wLyl5PcuY~kydPu6?OYf$Q`clQI(Y~cB>v)+~((x9B{-`E+ zPkU+`q2fVYr`*TH9z~fGklB0qq8oUUdicIo%I{g2C)KMZg0;48RE-ud2t{f0Ak%^u z$AiXP0i7uVO;5pXvE>C@9C&Rz|GAXk!V*Z4V{>(DMXcPFY|LjqOG3iz;lIg;JV}zz zeN<(oU2()+x#M!@5><_Al^K5|hvw{QlbyU0B~^FhE8)6Q0wj&5x5|k+ElY>>X%-fC z8P0Ml@IIe$(b<3$0H-+KCzOL8wEc=mvsH@el27wF&kXAT_%ZqV_yvB;^RUirtA}_yGNHgH zp~R4MALv90#gZ?^T;+1HPxDFa&=QBX;X3dmPuK$H`jH!m{6)zn;sf~R$8WvYb}TEm zu501hje55lS6iLILir{L|I^dkWJs>@YhZ;Pu9T-+_3< z3+R5r4_zQ9+gL$@K&ziu!Xx^5+5NqhCNSA!nZErL5#(p2dA7*KvCznbMlddD{0o%Q`&L=BKp1OV^uQc6jV^*6k&(blLc# z!~x0~5{lUG}xzO_x!@T511mc^Z1 zAT`Q?2#0lfj3^-nMtw@naFOGg;AAZacx4s(fXV1(TGtGPHcm6W`^1eJmjd|ZhP#RQ z`f6U1%tuU65g4u>l(Yl>2&|6pu%akgQ5ll}U7%8tIXl`>HayUJ z5xzJl-ax8x3uCJ@5#s{TFX@lkl6$Axo-Q9~ znnFC3t4?@=-@`wg_&J9zPUX*?oVip6e+ixfJ{y6?0E;;2L@#@MQ-f&t_i2^1!d_|# zv*~Z9@*bmUd?mBj==k6jRk3g#JcbPU0>O}YK+2&i1F<=Mw4EQPG?R8aSxonhcilH) zy;sgN^siZy&VB`-3+AS0N}wzZ9xUB4_Zxf@#I=n#mm|a?gJ$MjWjA7n-7%z1Y>GZ> z*@@`wKqozNIkp^}3s-|!>=nTjt>3l+HLfQ$B}2r@d0~?=KlnZ*#P{L$RsFegBPw=kR29fhV)AlJl@M`OwGw22uZvS*k*d-xIbW*g5@c``MEx|6Wt= z!19qG%Lxn7hI};xeI6_u}xIX)2IlbzyXQ+nn=uWbp>KCh71r`|xSj#%L2#{pmDb z!Uf~B>4IjgTEGkldTw6p@JBgSkmz>lUM}t^{YCsmcu=a~Y##DE=N|AnT)mxw@xpd- z7_{1bC(zYu-v)SMgOE?5H@K}i?X8+X1U3=R{15tVo4sPs-`F1i)bqFD(>@&Ghi|Wo z0Sof>_>R+5iW_dIM&vc);{bK%#lc_Jgz^*<0Yx z*rNuYZ`h>}zvr)D#>AYJ(e`q|2#5^$5e4i8Wnc-w5Su5LUAC~d5A zO2^m?kXpkJukqkKmxNR2#lE&``wg|~OqgPOTik+5kc4DhMkzr zf-F~;&L3ITr}ehlmYOOjglKyoyi4^eEmt9yry;`UOT^Qh&`F3h_ZQ{aGaX?!q6J3_ z=7Xmk8Y=^W{-*@6hR~pKDcjjmAy?60zqr-Gni%+kiHVdv0e1v7T<`P=LHSXvT?cMB z_3-?r#j{VS1~u#5XiQr1#{7-9&*8@Vg@*@-sx+Zq!5Cu6!|;geD(`o3TZzz*!%)5w z8!>q(ZApvs0J-%ptBtP%hiaEosR5696%V>$!0Tv>)!wtKLgi6-_2~vZ2IG;p9x<-o z2YLR6;Wot~LB-jFkUeitS=48F*p49Zw-K=JnG7Ch+ECrD^eSphT(*c*{iCjbwO+fd z&&oB`mtxMdZ)?Z+BQb|MHUO>&Owz z)X^|DFPT4|cke^kO1^XNlRdQN?9W|1@Jl*uoW+j;3 zXU;Oj4rUGB2ut$^q!IPAt}Xs3K08XnfTDo6#Rz|==;&5nRgYQ*A&KTLPwKWnz0xh- zA;+9CxfQ9Vgs`cmvO!&A1&due8P@@8=G1*$DTyIaK2pv572#_^qcr&tqnIi)Wius? zKCXpu3w#Iy<-|eiz7U#K8CA59$HiRSTCfibi_0l#`fNC50o@I1-2hL)J=5jKUS$uy=a{%f%f0yjz-HXESq_JLj+?(Woa?{Z!Z(oJ zZqKLC|6d@*PO!Po5V7i?0FoyiLEnzk+8Zn|7HYR;gvbPAG#_et-#Mewa|Sn6I|=eW zHXL}Z$;3NJY>st9>Zn^;)jgNNRPpr!&1}`I#OeAUw+bg5);kQOmXvA_Q-aJ!1c462 zpc=3}V7Z2Lr#h~_v5;q;j%TSdIKF?*ory8m`nvN#f?ETYj>Ltxg~KKs#ZFsVb$?vQ z$SEo}PW|Q1vdeNGo*`)sD8)^P$#R7&*yv>Ef~cMlf`&+PmBHq8HoDa}k4@KI<|5c2 z^7z#)P$QipUc7Vu=(FcQr&f2F)VXOC8kvCxe#2_+dxaMS#eThvUW`5hz- zJ&wQ+>&PrACdQrK;MJiPtI4&h20_~vS@Em{j)i5Eub;To{!ZJvy4-Q8-w`DDr35eq zH|e77%xEe6kwu*9+75xR(2JI}5NBYQK6J(fYjtRoaI5Jis$A&f3@lGSuLZ#={*hVs z-o`{>L}sf9R`9I$teOq{Pft@-boi>I`!=$T0-&p`vBk7t+d1xG{rfPOLfZ!1B76`{ z_aW9D{mjl>X32n*qYyp)d<-#>fzNqH(C#oRt>tmdJ9;5dp~ zUtRYO5(C`C$y*@?a3#+o59*$+S`BM#CYL8f_zy2vQDk|!UkS`MZ#6^q39Snj2}@0tVzQiOOKcpC%vWV>f^ zz9}#n8O(M^s}SxombGEzyfkQS+L@oc&9`CeV=^9w{9-n3F;m!rcJs^Jy!4)0Vw9hl z-a))7=4Wlc94nS=mdgt4OitYVpW?1Gs;O%WgH*5#0Uj!mDfY2iKq&K^kgAL-q7MpK zg#c1OnFEF}&(l*9N)f{tM0_YjnPm{dC_z)@<)7JA7Si5n%yt$_T1Qm}gsXE+CjMCuvBLW|0JUcL9h^cux_R*6D_iBG9s;b1s+J>4JUXX|5=?h}P9QfV1xr&ah$nY01$E ztpG--MQ)+}deU}Gm=UU?Om8*rgbO2-PG_#)qBi1@3SLqD^({^UvTxh&fm^9`WBH~> zE;sIwadV<$VadLst>Y?Zk7yHf47DZBk{}*Z%1wyJ&&%?_=7-FRgPX5-?W{QirW|{8 z9?@J;Ze&(U@AOh-l^xnevqMT%JP+qu0PxC(?Sw)x1%&Aia*z_LMw_Ar(us?^dxb_y z3F$Om=O(p#FZ;VaMJq?DrQN`%-B{E=YAvIJhtK*XcRe@3M4~2I9LFcyA&BO>4uhXL zC2!V7fJ>s^4^>C3<1N{$0fbWG#%g0ou$NA$J1WXzNg4rm@1qe-{ISOhVvtI}V@ef$ zo64B%p|@4T-zN&aK5#s!Uhm;n<7h2wIa1a2F6miA_vD7nDCp(MIV%g3aY-_ItW0ub zEk*{%ca0Gsu5_>(@cnCk5fVt))lbb+^U@P+$|@fyX38SoK~@zm*RjdwM>}?HvfcR~ zWu195BT`t&JE|x3FISJf@*&5)HrgNbKIPUAen@rT>^;`3z>H(`&>XI3aFWe~4t*`> zpKB>;6bKSe@(XhBqdb?O91YeN)In15^1hJf1{LG>H_O$f>XIR-X^G6&;rH7fb8em1 zm1(zSdny(kpXX3xbK3nCdz7ocN&L2>=qIqxDEQPh)GsKbnOI3LUC}yE(xXm{Iv|Kh z{dMX*mbJNjtEC2)+#A(!8~Tqjr>a}Q^ZD7QFS|k1nsc2CRNNQgVuO@z1TrIGHfc1k zJII$*)U1>e?;ltz8GP|4WGL@6dG-Lk;;QnY61}>);h;{dqDRFLZQ$2_D#sC_x#w=% z%QBJb*tcbwmvHpShqAE_ykARo<2srxsCFsZAyntZMEu3NZw3ONWZdm+Z)@|;tzyjm z*Bl^-5krG()0B?&hT1!%)as|8lJvxwMfLjf=>iOAZ6QWSRep%X%y2D+OaNtihDJS1 zuV3Pa%Gr!_J+6@~$(S^06XvVmerAv@a|W_MbY5`WpTqVI}NEBy8jaC-46MxySA|AptCnN|#U3{F?U$}K9 zvBye$?wt!<)|9wusP7-uV3=K%Dj+YkegF;DsfzA#L#{cb=oqTnjxne@e!?ZrCH6oL zF<@w&+n{w^SM!?^A5nvQ2waI`Qk?0H?%-~1S;lps+0Q)COASS)_JR+2qxl0Y=P90KA^yk-4`6BHuVsjojBGSe&Z4EKET_FsT<|LOlGT zn#fSv2ZnlAfiQn$cPP>G#ZHyI1T(sxrt&rOkc*7nN$T=!$sf2ub!l5tVfOVybd#~# z9B@)+dvU)&`O$3%R0@#b41_i1)G!p=`#X!pU%|6o^s-8IxOdp0ZDSrI9{t&Fh?9#+ zB63bP&*I^fju#cnZkCy;gj12hKyhWp*&KIq7QV^uk}!k(Eo_=`P1N_e+@futby3(s z(XU|6x{Hd5Q8`+jc5kvF2SAfa-GH8qX;AXBx(AnCTSQaD*OABpK`gnASOiZ#00$u& zF@CY(SzAsPmA`a+TT! zy#!TzzDD?<$LW&>feq5O5{x4bcl8p^2_^eyPep-*z46T=o#qBM^oH{d5ieIXg#YPh zt6aLbJgE?X>5x#AV#&7d(K`Z|LRW z*qDitOINsW<6bkdm#jlsWusGj^-B<;Q6mHe+CR%a}gt#}i#G9;`rd;;Gi=N=I73Li?-cO-qZ z6AJQ8rT~(Lq3Ah`^nhu5{oXhu;3E>?W4Rh;=CX6$PIF7>nFhDT#T$~qxYEwEOo{%3 z$$~acg6N;Uc(HRxyryF3K8JtVksrDm!3}O}U2jtjgexz#?h-d*3YQoDy*~;)dNMS* zS|a@I=vvzQE)=gw?zH-d>)W%4NBIW9hOHap7bXb`tVby_?r6Q4NSVl4sSRRVKr1h| zf7pUUMRv|5%#}yr_rD^{X2N}i8~j>WwFtu#AD+i_lPZrm_{psILOF`ppDv79r+B(> zRGQWsOal${IwEP0>#+-(PO$`7&E}JIV$9~N?!~QQ#SqQtf*uYHrtvXGJTA;|Jb2i0 zUai*X^(fc+qgS3mWYu@r#eF{USSCzsZcO0CG>*ks8ERQ6%Oc=yO!bpyplCkw5+oOO z(IANhJu?+LZWA{oP`FE{MXO?0XbPJVf?RAx+WugsiY`DeH21D{QGfR!7*nEzCF@S*IzE( zx$sG}uy^~QUXgM`01b9N)2*Zt?UlFZR*>HGQ^%8^%>G*eO8Sm~Kd^WA7b&xSgW0Dc zusm@kz?l}l=SdG66Cb$udG$p#Ga0_ZZT5zL`p=h0gYkc|Xn!kg1%5Vmdp7))LjLu+ z-SZ_48A@kAo9#N=Q9^-)xyFvR^GHH&|oO>ul$tuE6kv+SjMbbT0a>5WAJv@ z)grO)J}6)&s(e~fy^rF|uUFHiAW$fGnnIz_U|Hg#$lXCiMZ$h(dqz9@m-t&bOHB+I qt1R*&XXt+l>wW|OzkEjb{I0-|3Ci|oTLmXR-gU;@#;p9bYy9tPL$|~L literal 0 HcmV?d00001 diff --git a/doc/html/_me_m_core_8h_source.html b/doc/html/_me_m_core_8h_source.html new file mode 100644 index 00000000..427e90ff --- /dev/null +++ b/doc/html/_me_m_core_8h_source.html @@ -0,0 +1,196 @@ + + + + + + + +MakeBlock Drive Updated: src/MeMCore.h Source File + + + + + + + + + + + + + +

    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeLineFollower.h
    +
    +
    +Go to the documentation of this file.
    1
    +
    42#ifndef MeLineFollower_H
    +
    43#define MeLineFollower_H
    +
    44
    +
    45#include <stdint.h>
    +
    46#include <stdbool.h>
    +
    47#include <Arduino.h>
    +
    48#include "MeConfig.h"
    +
    49
    +
    50#ifdef ME_PORT_DEFINED
    +
    51#include "MePort.h"
    +
    52#endif // ME_PORT_DEFINED
    +
    53
    +
    54#define S1_IN_S2_IN (0x00) // sensor1 and sensor2 are both inside of black line
    +
    55#define S1_IN_S2_OUT (0x01) // sensor1 is inside of black line and sensor2 is outside of black line
    +
    56#define S1_OUT_S2_IN (0x02) // sensor1 is outside of black line and sensor2 is inside of black line
    +
    57#define S1_OUT_S2_OUT (0x03) // sensor1 and sensor2 are both outside of black line
    +
    58
    +
    64#ifndef ME_PORT_DEFINED
    + +
    66#else // !ME_PORT_DEFINED
    +
    +
    67class MeLineFollower : public MePort
    +
    68#endif // ME_PORT_DEFINED
    +
    69{
    +
    70public:
    +
    71#ifdef ME_PORT_DEFINED
    +
    78 MeLineFollower(void);
    +
    79
    +
    85 MeLineFollower(uint8_t port);
    +
    86#else // ME_PORT_DEFINED
    +
    95 MeLineFollower(uint8_t Sensor1,uint8_t Sensor2);
    +
    96#endif // ME_PORT_DEFINED
    +
    113 void setpin(uint8_t Sensor1,uint8_t Sensor2);
    +
    114
    +
    130 uint8_t readSensors(void);
    +
    131
    +
    145 bool readSensor1(void);
    +
    146
    +
    160 bool readSensor2(void);
    +
    161private:
    +
    162 volatile uint8_t _Sensor1;
    +
    163 volatile uint8_t _Sensor2;
    +
    164};
    +
    +
    165#endif
    +
    Configuration file of library.
    +
    Header for MePort.cpp module.
    +
    Driver for Me line follwer device.
    Definition MeLineFollower.h:69
    +
    MeLineFollower(void)
    Definition MeLineFollower.cpp:53
    +
    bool readSensor2(void)
    Definition MeLineFollower.cpp:177
    +
    uint8_t readSensors(void)
    Definition MeLineFollower.cpp:128
    +
    bool readSensor1(void)
    Definition MeLineFollower.cpp:155
    +
    Port Mapping for RJ25.
    Definition MePort.h:128
    +
    +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeLimitSwitch.h
    +
    +
    +Go to the documentation of this file.
    1
    +
    39/* Define to prevent recursive inclusion -------------------------------------*/
    +
    40#ifndef MeLimitSwitch_H
    +
    41#define MeLimitSwitch_H
    +
    42
    +
    43/* Includes ------------------------------------------------------------------*/
    +
    44#include <stdint.h>
    +
    45#include <stdbool.h>
    +
    46#include <Arduino.h>
    +
    47#include "MeConfig.h"
    +
    48
    +
    49#ifdef ME_PORT_DEFINED
    +
    50#include "MePort.h"
    +
    51#endif // ME_PORT_DEFINED
    +
    52
    +
    53/* Exported classes ----------------------------------------------------------*/
    +
    59#ifndef ME_PORT_DEFINED
    +
    60class MeLimitSwitch
    +
    61#else // !ME_PORT_DEFINED
    +
    +
    62class MeLimitSwitch : public MePort
    +
    63#endif // !ME_PORT_DEFINED
    +
    64{
    +
    65public:
    +
    66#ifdef ME_PORT_DEFINED
    +
    73 MeLimitSwitch(void);
    +
    74
    +
    81 MeLimitSwitch(uint8_t port);
    +
    82
    +
    91 MeLimitSwitch(uint8_t port, uint8_t slot);
    +
    92#else // ME_PORT_DEFINED
    +
    98 MeLimitSwitch(uint8_t switchPin);
    +
    99#endif // ME_PORT_DEFINED
    +
    114 void setpin(uint8_t switchPin);
    +
    115
    +
    130 bool touched(void);
    +
    131
    +
    132private:
    +
    133 uint8_t _switchPin;
    +
    134};
    +
    +
    135#endif
    +
    Configuration file of library.
    +
    Header for MePort.cpp module.
    +
    Driver for Me_LimitSwitch module.
    Definition MeLimitSwitch.h:64
    +
    MeLimitSwitch(void)
    Definition MeLimitSwitch.cpp:53
    +
    bool touched(void)
    Definition MeLimitSwitch.cpp:146
    +
    Port Mapping for RJ25.
    Definition MePort.h:128
    +
    +
  • + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    + +
    MeGyro.h File Reference
    +
    +
    + +

    Header for MeGyro.cpp module. +More...

    +
    #include <stdint.h>
    +#include <stdbool.h>
    +#include <Arduino.h>
    +#include "MeConfig.h"
    +#include "MePort.h"
    +
    +Include dependency graph for MeGyro.h:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +
    +This graph shows which files directly or indirectly include this file:
    +
    +
    + + + + + + + + + + + + + + + + + + + +
    +
    +

    Go to the source code of this file.

    + + + + + +

    +Classes

    class  MeGyro
     Driver for MeGyro module. More...
     
    + + + + + +

    +Macros

    +#define I2C_ERROR   (-1)
     
    +#define GYRO_DEFAULT_ADDRESS   (0x68)
     
    +

    Detailed Description

    +

    Header for MeGyro.cpp module.

    +
    Author
    MakeBlock
    +
    Version
    V1.0.3
    +
    Date
    2016/03/09
    +
    Copyright
    This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    This file is a drive for MeGyro module, It supports MeGyro V1.0 device provided by MakeBlock.
    +
    Method List:
    +
      +
    1. void MeGyro::setpin(uint8_t AD0, uint8_t INT)
    2. +
    3. void MeGyro::begin(void)
    4. +
    5. void MeGyro::update(void)
    6. +
    7. void MeGyro::fast_update(void)
    8. +
    9. uint8_t MeGyro::getDevAddr(void)
    10. +
    11. double MeGyro::getAngleX(void)
    12. +
    13. double MeGyro::getAngleY(void)
    14. +
    15. double MeGyro::getAngleZ(void)
    16. +
    17. double MeGyro::getGyroX(void)
    18. +
    19. double MeGyro::getGyroY(void)
    20. +
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    + Lawrence         2015/09/02          1.0.0         rebuild the old lib.
    + Lawrence         2015/09/10          1.0.1         Added some comments and macros.
    + Mark Yan         2016/03/09          1.0.2         Add function fast_update.
    + Mark Yan         2016/03/09          1.0.3         Add function getGyroX and getGyroY.
    +
    +
    +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    + +
    MeDCMotor.h File Reference
    +
    +
    + +

    Header for MeDCMotor.cpp module. +More...

    +
    #include <stdint.h>
    +#include <stdbool.h>
    +#include <Arduino.h>
    +#include "MeConfig.h"
    +#include "MePort.h"
    +
    +Include dependency graph for MeDCMotor.h:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +
    +This graph shows which files directly or indirectly include this file:
    +
    +
    + + + + + + + + + + + + + + + + + + + + + + + +
    +
    +

    Go to the source code of this file.

    + + + + + +

    +Classes

    class  MeDCMotor
     Driver for Me DC motor device. More...
     
    +

    Detailed Description

    +

    Header for MeDCMotor.cpp module.

    +
    Author
    MakeBlock
    +
    Version
    V1.0.1
    +
    Date
    2016/04/07
    +
    Copyright
    This software is Copyright (C), 2012-2016, MakeBlock. Use is subject to license
    +conditions. The main licensing options available are GPL V2 or Commercial:
    +
    +
    Open Source Licensing GPL V2
    This is the appropriate option if you want to share the source code of your
    +application with everyone you distribute it to, and you also want to give them
    +the right to share who uses it. If you wish to use this software under Open
    +Source Licensing, you must contribute all your source code to the open source
    +community in accordance with the GPL Version 2 when your application is
    +distributed. See http://www.gnu.org/copyleft/gpl.html
    +
    Description
    This file is a drive for Me DC motor device.
    +
    Method List:
    +
      +
    1. void MeDCMotor::setpin(uint8_t dir_pin,uint8_t pwm_pin)
    2. +
    3. void MeDCMotor::run(int16_t speed)
    4. +
    5. void MeDCMotor::stop(void)
    6. +
    7. void MeDCMotor::reset(uint8_t port)
    8. +
    9. void MeDCMotor::reset(uint8_t port, uint8_t slot)
    10. +
    +
    History:
    +`<Author>`         `<Time>`        `<Version>`        `<Descr>`
    +Mark Yan         2015/09/09     1.0.0            Rebuild the old lib.
    +Mark Yan         2016/04/07     1.0.1            fix motor reset issue.
    +
    +
    +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    MeBluetooth.h
    +
    +
    +Go to the documentation of this file.
    1
    +
    37#ifndef MeBluetooth_H
    +
    38#define MeBluetooth_H
    +
    39
    +
    40#include <stdint.h>
    +
    41#include <stdbool.h>
    +
    42#include <Arduino.h>
    +
    43#include "MeConfig.h"
    +
    44#include "MeSerial.h"
    +
    45
    +
    46#ifdef ME_PORT_DEFINED
    +
    47#include "MePort.h"
    +
    48#endif
    +
    49
    +
    55#ifndef ME_PORT_DEFINED
    +
    56class MeBluetooth
    +
    57#else // !ME_PORT_DEFINED
    +
    +
    58class MeBluetooth : public MeSerial
    +
    59#endif // !ME_PORT_DEFINED
    +
    60{
    +
    61public:
    +
    62#ifdef ME_PORT_DEFINED
    + +
    70
    +
    77 MeBluetooth(uint8_t port);
    +
    78#else // ME_PORT_DEFINED
    +
    89 MeBluetooth(uint8_t receivePin, uint8_t transmitPin, bool inverse_logic = false);
    +
    90#endif // ME_PORT_DEFINED
    +
    91};
    +
    +
    92#endif
    +
    93
    +
    Configuration file of library.
    +
    Header for MePort.cpp module.
    +
    Header for for MeSerial.cpp module.
    +
    Driver for Me Bluetooth device.
    Definition MeBluetooth.h:60
    +
    MeBluetooth()
    Definition MeBluetooth.cpp:47
    +
    Driver for serial.
    Definition MeSerial.h:67
    +
    +

    O3`T{nF(vqz;TYB~_W{T51 zn8&o}x`deh!Iw+5T(j`$sBk>`dW0$Z_!8OcW;V)P?Dk*-3~8`m#K-}`vULQTG);ch zaFr%M8|e8Q;V*%E1>4*q6}fvNF9ei5QI(0L(>gcQWXjQNkuITne?({O8y)pYDZPa3 zSENIzKd;XM1q;eWY@Sb!xfD&pAyt;^t`MyKgo?rYi5H!X;NQ4d@iaMGp|oN0bZ#Ux zp`=_)P~ts*bXUn!4X_VXq&o9bh*2>L;U2>ZUPhSL4SqQIoWCP*Vex`Wuq%HnXdfoi_x@g3R< z^H>Po;Htk0SEW{(h8v4m=uaZ@y=HOy9}1bbONMdwf}I-!;8}0ARyG-diZzA{#(Np0 zSYm|wv4m#AHTW8~E!DwiE0cct!(U>86IfIX(OkGlTiL;Cg{_{qMaU5Mq(hX_EN>G% z^XLt9Z#usoNsiz6)&DAq)gYKQ@-qVYHvXt1_#t ze}AA|z@;7#%5fVsqE-ZDcLZO-oU#^3NfTpAJJ&mqE}Bnv0-sX;vK6D&b5vmz85X(^Mh^NWuhoCGEEI*Bt&4ByWAZ3|Mm!^;A}4)zJVtfX z@2o+nyV8QQeSyPVP(Ag|e*IJ(oh+mAc8Tge357QFET#=`4ZjB9q zeDFK&JH(ldm8o1Jd5nC`t84)SN!PqA;y791N7{p_u>WUdjq4| zu{JRWzj%(8t5Z`qI-0SjsrTz@CE$0?tN!TR&-&ljp&_(Z zOLc#uR7^S)S)G(H0MAdD&Y8VTVCi>*Pp$zp@Kc=$_E*GF1KD>(leVO^GKAhdUgU4T zt4<{bHD88Pf;qlL?OtEZs?8fc-&Tm6wp9#;czzB|z3e9UeqZI)PsCrFq5pE!>rqXw zY@A4SyFN%-S?hT(_s($$6hq6+`H7O^PULm|^r5;eYXfKL&OB1f?I?RW^K;xieN#rS z6_>s}IW>gM*S@PNfUW2_Fn&ue+DETM)uLEzS})62EGMOiK0j_lEV0;)$GB(teZ2K6 z6a6-YTVv?RK`W7ZT>)YpI?>|e3^}Lj6 zkgGM-by^Ef7tGvd6kXR%ybUbyE;`-+emK5svQV}`9SXj2_AP(79$kO@Z-Ym-sonQ& z)XN{9d1ucv`Z5><`Pe?a{5?ItM3uL#i`PNnZ?x5U`n;`Cjbfh!tRaCsL z(+E}f8q)c8Dz(w#(YemQT^|bD6%#=!md-U>2HFt;Y8dnX)eFxAJTOC#0DkuzK%1Yr z>Vd`1-0YMmveWTP(#&VaR4&J^|Ne*@0PiC)VzMze^yRSQCWMz$T|Ytiv7^2J(Yt0v ztk!hm*AB4T8rBJ|4|?}7XYbKktzL>NDi+pPK#%^c>+KA0XGqP8FBc$JmW`AxWZ)?s z&5lIVty?CVTDA5p0dQ}oit@$#r2q1iWGg$QoyzP>YYg~xGdM}+sp#j zE%ARGZAFVf2XeDXiOFLjTJ!&E0fuFZjF&MD)+$U(Wb1&k!-{CDwl&L8->#&f|Mb3X$w5BjeD?XS)#P#cDNg8VLyi_KCM+V87--%k8fhYtK{Nye z7X+g}fU3JlJFQo9OhF`tgl8^bM)*M^z_f%fml9+9sV9wkVq2jdXQR{+xx3OQ3_=ha z-sXVLML}-%mlCw{_zg0NgS!ElICq9e`|0S68MVDVM-9k?~ z$?lH*ur=O+rQyx8vHFJki$&SKnLfse)GMcLw^KSm6HrV1Xiz5p9d-5U1|i#8T~P)l zAT{EBu@9y`S6z4$EI&`TLzN7z&E9Z*fzeE|@J29d(3q0ohyK%eo|m=(Q~EqCOwW>2 zI~2%1>K)gLS&BduVFsi(<7g&cq2tsKKxi1cTQzH>HaOVBGw-!Q~lpe7b5P- z0h+TUyvMjvE8bRg6n%gGu#&?E;k{#X5u@WhGsI|tj8QB76{mr*8%6WRh(bF)xV}`K zdX&L<+R<^)Ztx9a!yd0gM8UF}X3dtZ2|hJXZ_7^v&JGOb%eAiI%)a1Kopz;IxaVg5;DP08+HeQkV`fVPbjq2xp7)<#-j>cHt zkL~F10w_SPXTO;ou+d1v5rZoGCeixiWKcr97crdBkObd-BP#k3!){uwtGwW-uHJXU|kcO@Nh&Cp>E?c7M>@_cANruwW}p zw5H`nWC34CFOo2cd5%aMeO=CsXay#h{Ux#Z+l#G>9e&k!L3?a9*uL4`YjLq6Z)(s7 zil@RqO*t;QBEw@alb4#Bqn#=)K)X6QD$j~hW^@beRywxA@2zRheS^&Se=;cS^~=_` z4puJj{l`0rTG>k2zw)NGS#?TW1Ce4VrhwC*>{Ww&hR&RmC+1Y-geipmT?UzWy5nCt zn@s=7MsvKw3-d$Mp-m3~{|5L|8h`}76*a#2?p{-!2!YY&*;u?&subjgiW4Tvi!%A! z=7Bq@P|wWdM6EVkpY`<)PMuEw6emaGPO^}cj2S+WXI^6jcO2Ex{3oZA4jKzqbEt?e z#(9!nCd`yL*v9D!lg6O~&-IKT*xpj+=3iPH7G=;TnRYR`zg$VDqn2MtRd#CC(_ zAJYX8Hy_ZL$Dz+)V2P*o2ds$QHLkSL5pAmCmxq`cACg~mDc}yWyXZosU9j`xZ4Xdi zn=#4y-30F6j6g}yOoe}CkSb2ZhX*{{@)azz5H8J6ap1=lWCe+_+9{slot2MVIMdyK z)}L)pOyPKq2eb3C!6^AWoE2^cfo|i-D}YQ$Hoe;r&Qs|S>ULkIC@Dj%u~e1@ekdpydkrnEqSRvD+Xoeo+!yxv-%y54g9PM@Emjk)LN9 zk^l&_D65DkaHvWlFhryg$oVHe->*V*!8RheKo^geMrH)L`TOwik$tyelsIwa0Ldon zy)Q*0J1}Zv+P3FE&hqAug+mIib4*+?<6JC+Z0ciBN7Z@%KIsfezfxNu2Y z$VU+jv;>~IE@1Z9LIvb#5taz8?&^HfM=QrjVP714@~tGzul^Vai=Mi=@`BZ77U zqVHSIC>x_HT=QsNOG6`fnvDv7uY;_BZZmU*kofTbk8F;dkK8qKgYEM_Ip;Ke+2M%w zfD(Ti%${d9Uk-i0lcJ{?3!h6XVC6E3e&7jOZ^zI>&f(wx6p!_;#trB4?(I*j>ih2G z>Ye4;Bf{hW15Q4e7VZW%o2UD)r{(`iKWe~A1> zwtpA&k9z1H<-V|z4cL!RJm@(8s8CVBM*ejBc3hy&Y!AT%ZYUTJo&4{NlK3V>7BSm3 z_UJ#rkl|)Y7$LYFL7)(S^M$%VKGo)4LS|Nxu9OP%0b4p|0X+{>@zwYnM;h;I9nmzY zcRz|N0FL*?s@C||)P$pZPrcunX;#-oiDuzX@t~myv%eucuwq0{` z)fosG05*|=-U7DbNI(FKWM)`(N@GTfa2GxJcP<-z$Fy&qs0zU!iu@N zd%7tX1;~~j7md>E%R<(qXlbZ58dy|_g`J#SCz4$`cFS$&@2p7{9ro#ye7i{N$n_X+ zaJhNews|h5Zr6e?PL0!hfzvAk%DpZ8U+Kfk`TN zyo&Nl^rm(1JCKD?PuAn|Q9(<9If!k@J0@lk$@} z0!GJOIp$o{26it3byxIyxx4bO#dPtAqS#4q}zML@q17W4Vt%|_pQx__>Rfs2ru$McdELxX~?pNkh3 zh@m}5ebPSf=L>$jn;;1PXf5OiM&v)Oi{ms#{dIU&7-d)w_mMj@+9Ooh>8u~1&71~s z4@^H|J-_F|Hb`^Dw*x#z|MC)qO24%?0f1rG1)`_-xept!^V;G7iY>bLttqlGTne{J zxLk*A@U3tj|BmP$zUxcO=;)Y5Sve*riDoWEA6i0n8k$q*;9@SMqDhT^QTh7 zNAiH9L(%5`&i;D>ARJHb;LRN(*N${ZIz)*g0L!Wc^3_0xcZ~fh$=4 zGXEes+QzEVK}toZGpU^GFF_g;Ez*9MLOd2EG0Vs?%sNUr#(6p?YH=zGYq_-=SbaJC zBHVh!@^E+{KZmUH8m}X3HF}$3SR|M;jlpk7Bur2VhY?9i@+99nMzi)>iK=>8A{(OuyEd19onO1b+wm>F7PVD#5X zG{)Ovn`}PPR)y(>!YFQ59DTYdv(IxPJ2W^hWL$3Jg080lL($@;^4)DAyO}M&4<~DD zXaZs$eKJqqF+-}P`H|JZKUO=`mTN1umLHlfi1lJ5@UC4N24L|r;}42;f~Iz+-$z!f z$XyXRApgpX6u=Ae*TNf_m4CrGDj$MrbIiVJW1V0^5h!b;9>I^5}Q}=wot=z_Ptp zj00pE>H2%h-Xp}ac3%6w$-zWqX+3#zKsNih{YJerIC z2MW&vv3s@ETkjG76!^kMKkJ$6*8OGqIhiXz5`FPW?|0}6jMjep3YHwRp_51LxzPY&&{A*<;)8y?^O`YP1T64=EEFo**f~Z-;Z${COZ5QGUB?=WT z-wBJW^~t~Yk0wV2O9kT`z7w#%P^*S6N71JJC0E7C;Q6K=*RbAGeQ7{AqPLk|$l$Kp zz9LFj_jZ~ZClH;mqTKlsQd4d8Mx*Oo{YUQ=o|!>TSr_+Wgkv7qv9haty-t7z(APBiwIv)LVyD7b4!I zh^0wVj1$yzMFOqeH`9jb4#={$_6K#SJ2iIr^(X76!tczwwF;Ka)~#8CP6$-WHd*@v zoZMh1M{U8`HNW<~J2)*)Qx%`uwO-#-m^jHGoc{Runy6;RiDt}O;|3{1jc+6K#iLb&KZHFBA<0xp7X7{34bo=1TR7S8pVVQLqg+A+cBi0wt z+-nRp@p4CwM4lJifD#3VUD9M+)^If=HN$&&Y9p<;jh*U^AzlDGg)ca31TzfhLG-+j zHHi)AAj1ms0ljZp0jrZHjA!dls>fzCi?VBhEd`a^F&H0^p9BXbIRY~Fmr)ouTs8hh z;*xfTB;z(P!UczVT7OjVtVUx9Xa7?c@#w1S7jHF)U!+!X6z@yNhJ#q&49!dkl30!~0b>VdzSu9LpEZV!_WkE)enYh1#yYVUbgs#nXN=nv^bNaKpPAP=763 zzLgZ6I`)*x=C}AeWzjD*3g^pPwZY6$tVcwkrCk>qPd9~Lcc!X+2KoBUKem)_`mKu(;MlmH7 zRzk6J_B5As;D@T(jeg}N>s}!cl}HCZ?vXN8&Le-H@y6y*2$3Ex6NZNtMUN3D&ga4b z{!kykx}_RlqIKJ}ZyZ*n#ncfk+GlP34P>(2+wTb@i_Sj#^J{bsY`T%A=q92$pFHJx zX3u?A%ovP}SII@wBHb@v92N6Ku;IUP&!$z zV#IEEt5%f4Dgnuo%W^J@o?*Z+DMCh- zWjr$~qwq$rV1K3Zs**Mjo=3AHpE;WN$39xg#;30ejF`t7nS#^ty{-x3LhSTH6^Pc$ zqnX66iWa%yGwoiMuc|y7oUV0*+ROvulgPKeF@UP%ld$pblvv(N=(&w6~@0{EKkor~ee{ zxgiO#E9oT4<`#I1+Ts&bG>LrGo{X@v?Spnjf^d!O?9)Wk>9u|;1HfxJo{aBHxpdm{+LtddQfpcL<9xhSl?UFe|^m+`Em(+x>@kS8=r=Ar1bmSs2 ze(#*~r#Xnz_3f~zGQoRlO&HlEccdoOgc7=kb#yV5fYKL4+(RBIP@<8a$M<2);qXG~ zDPkO=Ul-@!)Uo(A`+1tMlCTT|KU5OifS}*X=h!q{QeWT2N@%H&M$jMGiG7NZ%N|g; zy}}XdG|0>J?C$uN?%2~=l#i(}3~gNpO{!n`g_(L(XQkc09UdHNo1UV=CyXT3ibci}~5e%W+FD~&(aMVDO_ zLKF6=oA?<$bW{o0sGSPD;dFOYurDdnK9iexkpaPzc>|iyug_qe`NohN9Itq~e_?~q zJKypu%EtES4lqmIyjM$4ipW4+53>t-|98(d>{Ebib-U8hs5(fuUw=EFNTLdESpS&3 zj6+i~wdluaJEg{9(bPmY3Km5C3!z4Hy0$yUy0W+S6z!|uZmATdyo3wX9DnmlMf_1J z2ignXT)_5HYmbwBT2F`Sk6K;R_=Nv~teXs^L&J`QDdB$W70z6lQQb=}S39Jr_nVpw z4DJ);o?w_(D~9JNC~vL#2a_TRbD&Sw=jyl(eiNXhr}v4LmKk+GV(qCTw(5azFUHUjN^>%;4gST#(2u1!a=dhI~n5f`UcD zgulV&>qEH(>vYL0!AW=oq<(n0F1Q6;s`Qy=^$4o(Ve(cnzh=@>uWqCMxISD^aMZjb zvN89M7-it*V(3_yoW=KtY-g1_CdBEJ=2QI5+5(ITN)fB)cR5M7VKU*tAjq2 zgkrW)q{#CW-C4WY0uvrtw+QN(GD#d;#a{_+G_-$<*mj<#jPQU)<5xeyj}qlWle)x` z6?RY%u`?!Lnp0fO*IWO%Muz07+hfCOgBgN~!P6#dbS3@B!r)DNy2_Cz!~m}B!4@|T zsm6It74YC=oaOFmgy>4IMZy>~e-V=RNQ9c?!q^y0A}daU8!09BTuxf(yzmF2nKp-Wr)*lOP5< zY6F2Wi68n;;_wLZv=7c7?SH@v1ihw42-+`dE2IcMJQ*AV4y9IeO*hO+@hgl6e6Z#@QefV_U z$9U-$vwLF`7r(Z7OfWH`hzAIZ4;FLq&%W4fv33&B-0wLH;vBa=&7mjQ zGDR;vwS7mb-G$G=ObNOs#`6^>#{Y3de8WvoCIkchta63Fsf^+@pZFJ_X;O&vVU5!d zM8irWE+DxwTE`aQ!y;JI>@bs0^eg=-wPGgN9kvQ<>5=@mv6V=t1~ate(?(3(&u_b!|^#?wMj{JGBGy=+IN)I0t`L> zlKS1pw#SOGfkKJGfAKHB0zH?4(dDuBgr$0Xda;Fc1d`lhUB0I8tIZ}JbfaW$dAh#I zGej_VHBisRCdbNF(WXK25=h*;B@RVc1ugfY`UVJ2P#JlIkLC1Fze zwKBc|y_s~IuNT*w{OMN?u$wmD=FGIC`=;FTj+k;oM9wKnaoSy)K zaCEM}4S?iisU*MOsl`>oZJR4U)A;w-4a4xq1&NYxE6B+h?VsjNwOHgMta^-};{Jwn z9{zcQne9pa%((;k%>&{8xm5!#AlvSwwRA!_@?2JuRO=hV=OKlu^P@JZuylWO2b$Z{ z$kf)`R*mX0`rv@TFXD?w=`Sl~8-ebJz)}Ic-#-qa4&g7QnO6^Ynx*G%ippyw%gjG%apd?g>`~x8?NJQz;P_i% zi`8bB3+6yI5v-&cWyh9zCribi=DVcL5MG9q->8`DxpfD%9R<=2WEQ~XRzSbwN&Qo$ z56>s&=U$J~eg7*7z49mER>Qwgqj}xxTN~k9yoG#?#+c{(1CiGi_&#H>OX(;1M#81V z49}0QchY}9&J>sILkW>B0C#&-_vdchK#OmUFaY4EI}g039G8~f|BLAn%h_!-8#yVe zeM`Cd$_JjH{Hb-rv*>H)a>sFaY{g!0hewTn+D(ETX0UQ*DopKapPy0ISEnAwxGkKw`H{_c)EHKb-k>JH1e^0O#*+5O{Zw zf8H#gJXTsBWXN~@*7I4~`ahK1Cir&+=%59r$F{xeU>d+(&4}~Y1JH$=pLb20s&#e6 zXH4GF+17BFh#)XG*p z^jT3%0l!tsZtBk=Qh#KG*A&HV_uspReb|^0ClQG`nJB@I_llJ*I_HlRwwes^IA2ma zynl&ub#qS8@cn4MLK=lRP5)O%7?&L`qbj;Qfcu@9t1F^y^HnmDvH#Np(X zUu}0iY0|W%SF5ij`_Oy|5Vg~~i^(G04a?lU+m(ausZ;4DZC+x({_?$VxOT)m6r2lt zVWxK^MM3?Qt49js=L7arJoY!8svq-A<3&jYD4n=USOT`>(^x(dc70ld=|)y@@;m&B zq6S)R}dn@~k?YmzEaiRR|3bfV_5`s3(TQGALhQwu|;vHWrIB)@TOu0KOZE7UWL3OXb~8;XKS;|b3E z#l{mb7xX?+lehaS=kg1+YzwHb(b4Xps9gL2P`EAAiD3?qH}?NM>1D`wbkO`!$;FWG zQV)4j`&Fq$}|jv(%x0us-1;>qzr5Bu45r&w6jEa-xy;5 zy|tgUa z9mWY1n8NCGK4l!GcX9Lqb0t8SJ`dAypnp`Z{9^mMw4D##eFmysZ8UFgw%=SchTkB{ zWneV6XUSG)F?>b+j~7eZAK^wiB_?_9mil9x4M`(8NB#XK-HJ?TF{$#4x|5r3xmXdt z(Hm!za$2x^_#N!`Xh;L9VE})%arN?Wcq58lMh!cqFQWxzYG9fdnWr;-=4#?9E7FbZ z;aR}$F+ceUV!>Kgrx!tbq?-ZZZN&zm^ypnaoineMM)@76&{; z-Jy3Y$;}dPquyk<-KL>OS&=~X_q=is-~loxY1t^nPI3?mgg+{I(>HUhj``A;qW?D@j0tz5ys?Xb5mu z>Y}S!SZ8Vpm0|~jiLWbYjZEcL-o~U)QubyToptj(1PI`P%_!AN9qoH* zTC#lk?J?}R5SI8ws^Oq9f(n!%(!B!)n00Kq>u4rNA?KzxqMU4LgMjnOAB6x^gg7lpQhM z>odgJEkD!#sf58PZ+>0g>9fJDD3XpzerWXKPw7!5egCDTvAwXV;F@6NGly=Bo(Bf9 zIW~y?%f=rv-Y+5Y_7oDi_bS z9sVY*sJjN^bh@jj!s!;~(5x*^wKI|jW)pX&W z=%n=Ou+kP(6dthmYR8Ohd(79ug(H|~JJ>9^Ape1d%FdEAz9r71gn0TN1L-6BB~VaF zRWsxC*5GVq>PK(p{r{q1(lJJl@~Qu9kq?SeA}Z24-frV5R5G9{f)h|82#yW5GS1tVYVR`*;S3+2z;-Jo1vcs;n zA5R$+z__04%rzSLk5p-1TVPL*=HbiJC-PS>!hd=p*S|?D--j(yK4GTIpl_)pb^hZw z*f~5IXu+CcgWVF_zDgwrX>JGDFB;Mn(sz|p4N(=4?X@ZlA=w#jfqLJ7UDKqtJg%TE3!h3U)ZFJs`R$C(n_BDVJSCSH*jv+Fl%# z^u#~>2TM+cWJ$)jXQ9}*e|vO=zVx+!jns?B+Xm5h@0-&lq8IypCzDaXnsqCPZ6gS9 zb*DpjG}PGs`6Ko{(kkyB?{we=fCH}%aU}}u2#es)=xBckAg-O`oloBNbrXI~_6)DY{I~j!LDDv6Bt4w5 zgu}0~=#3rm+dNq-w@5qosj_hotrJ)C_4j!FE@d=7SsT$j^Lx1BUoehAy|*e!CMOQV zG?byAs2%cJi5oqL5 zyXM{vx+)JUT31u4Yz=RP2p!Hk?u8o9#s_Ap0~uT|uJ#c<+ojDj zZ_v;O$Bwaq4rq~Kcrmw`k5nNO@}_Ip8dM5263gE;V`;-TrA3xG#jrW|=~s7kY%9g? zP?6un5`6}2)9W;e#Ql_4G^L4{*9-J4)PgI-yS12k&W22Wz>riR40zgTLlo_ME_PPhY4gO|CgJwhF45! zufIf8uBzzYc~V^zj?!QfB2N#MA1)ztn;n3wQO7>KA*A*xq<3APe+=^U6X*7qs2_r{ z&Z7v}aejgI45i{>v+EARGf{qeRof+r265Vr8%CvhuU6-jBCX}Z;635&N6w8~Z!|rh z70`u8wKkVhYyid8R+}4t_0wHyvi1wumO&LB)|2B?QWfHQ9icfdeg|6aDV&ddrDR$v zqYnPuUOU|8^yVo+gzw|VjzCm5iR}G0=6j)8*+!5t@%eUuKquB}(O>XtGW4@pkTJVt z9xbZ&qDy0a0}?GM!=V)SF^9gQ6bE!r^fs`hv$YV(Jsf(dKD@R1at9zrJzY!|K7~bz zJGrU)%SGSkw~o?rlpvp9^Jb3~PA=HORV!0k{}p|0^Osf0jmrpo7Xrp~+@}~25NBpQ zygXruoVgh6&aC;yb*%Uco3NL-;x~dm8U+t@TTP`T=||I-s2;ACesv)kql?x$M4yV? zHUeTEe=&8Z`AJ=bcs-Yx={lwNx0pP>g&FF*Th8J|u{Es#v(=K&fw?S@rlt`&a;L`q9C{Fobg|#-Z?cIi_L3<2O5|kWp=AGo(P;r#{~* zcx~MMqiwU`0&E9*V4UV;W%q_Y7TzZ^XBnI06U!d-^~6+oOze+}$%Mn_@xBu4c%ip= z3wAH5c?P1OTd;_j{^Yimlz>uWr3cfq(e$2#J<9~xH)qH6jmt0pAxFcDuEL`b0y`Pk zd07wfGfs~8MB7y%N=V^~T^5>_G5_@Vh`!p<@D~I{N~rJ-vJwVjRHDl+O~<3XhA zwM@)q{R_ztm!6U$i+}Dk7qPnBVC;Vu0P1uP2bRk1{JTLbE5rWWTOu3$ zVv%A9T*O0IsDVt+!{Rp;DWj+LdZ?;z*hZN;i4T#@LKo}7ypmL9mc$0f7#f7|g>%KOt&Xsl3Sk3UM4?s=W! zHHyvT<_I%<+~Umqx1Yd3^d)X`1|TBe&TE$vz$Ex|vjRFoO~gMZdj)n_PsqEOHym)` z-Mcs0(T}AQ6<#x`ySfuls-4Wf>KhRQlAA&|yysI^Hw4V<#Bn~pGip)nV7Y<%eud)p z8GGv+1)|kCj*?#U-nOETbFt?$Q#$anJ|8DwL#CpDturC2pdXAWf;u$D)5SvjIlwheO?xFT9g7U6 z^_8Ma{g+f7$=4ZDF|;wIopf`LcpzWwJ3=la^nI%ANW5z0ax#BC664`>vp5P#iRPfB z+z{gm4vV3+f;x{N#Wq7(pod*$N)?{j9ZqM;njyx+p-Q)jHsO~FsUSLu>ebD}y}O$) zG4)^U>pSkkC8?U0AXNei{ZqSN{0-M`OY2jWtZ4k(21os=_yh0yX=Weh$1w>^hT~gA zCfHd@aH4EEYCeba`UoBV(d9kVOr*fnQY3|M##C9APoDE>#IXomlcSI$;)i!+gk+)o zM-e?(r1brS;s+;}^FQdzNVXJkc{}m*wys}{VjT7qg5CmgBqIrqM{f2I_~FU*z+f|I0X>?mcZqa{$nJBlO-yJN)h@G7>1BB4MdRYutc7x z+0aTJ!hLPqwkDO5K)#YFRkS7w_!Ua?!9X)Bui!WzyT7On$WO7gS_Ob z#Y0@wb!p3@sWH}6>?Y&P0mM0bFjup?@q+DQnF&?@9gKTT`~atvEE@QBah|>R$xktYZk@ zp8lwlbDwr*&VuuvTJn(({iuPUX;fPwXwym+R6)d8fEo1?y!L!8>SZhyc?$OW^R-f! zA=rDCrJ}YCxLFL?v9xG*kx%l>MsW3L7lSOUzfA^tY$(sDJeKqps!O-tgRS#SPykW0 zH5vtr6HKfaxg)sL=TvfkZzRi9?|1Sz&PmA%<4EpNx4 z_q&+**Q+Q{o(xdLgMUGz+p$DGjUmVcuSbEEl21QQ`&dJma+nL_L#Qg59AHl45{Zl{ zZX;5Dqb@?b{q-MO8T1k{ADq)cbFQgxH8arWKH_5;?nlX&ifzL!8Ka~)kY=BcFV5#N zYepm=oH{0tedkYj5h z&?X7&rxvW^&Upa|5)2Hq_dXFyM9OejkfPk~zy6qL*s)>0W_G5iUXgF1oIbvPmXAzc zqZ4t3kgxWju5N6dv2s6+KQFb}tP$iN*~?56rotxjnfNopUvDl{!R2Gn&j59ag*kdn zA-1*w3dBJAk(rDIZd=EOVXX6x+`jDFWS~1~YTkao*q)x+cO>s(`5a1M_lmXo{vYa{ z)8p;+XLW`$b=N0DH(;W6dr)K(z?)f^Q7FJT%{g7@z3@g}!I|RZ+U?Ei6q%-8C<}yq zSX`FxeG6nz+0m5TC1-{F~w>AK>2_N<20@RZ{tpHCId zcFtXVjNVt`4l&u20uneE8?7&cdfeMlsXn%tZQ&lpJu2!78|%qI&F<(2EQ^5hQFnMC z$^LbHvc=4`fT)e9j`r7wM&R$Yhs+iL`Y$t_$9GdZ<3PjGZ9wofvTdV)aX{fZ#Vnt_ zbySHg#i0qg+rBfpR>JB0eMhaWz>QQNN ze~IYDL2*~ni*7X*s%-W0pNKJYqheM;Rw{mq|6PoxzG{)>V8gQJhavv=(p{Y0-&1Dk zy^_);0o-Y*V&<3RitE~646rmOGIg`;@pkgi-sZmz*^#LFO`tyb936@Z#fDD6KI!yk zBxZCTiJ6~keB_9B(cV}wuebfvH$NJ4SNaa@s%uKtSRK$bkttsuMP*CdPNHTC#;sfs z48{Ls!n<$u>j5U}`=J_!_U*n;Fzc!Da>zTP(51_s_XU#Az%%Lv&Dh4A4PD;}l-7Kf9N3Nyz;sIP zl6E-qcfnB0$-w?h=Eb)oH~xGh8FeGN&cO8N>(^^E$yC2|(cF=~VBVB_oE4N6vYYP= zsDHT(cIZT{9I!sG_0Uv8l*3DG?; zd?zQ)^q?de+1_pGHYi^HqY%fuTcP(a;pqom?~qfeB`5IGA7UPX0w~#qI-HCDdwalG zsWU7yvmfUDyyjsYUP4Dn#9tZBkYeq z6xX4SvsbO*({^FYznx1{eKE^Xc9?1Y*|l!Nq~Y(j{ENW+C@C+@G5%$fd2Y4gSGy^g z>R2Q})O`M6pSdT}w43)0rgy&W`k(01zy)pT0iVEm=^;+((6rtb))p71M1AeRr`1%6 zkZ*PzgZO=7uMVF!I~H}ltsbxZDTwxgb!L7I%YQ^;nnk&oNav-rL^-!rfy`D2-@FydniP8KKuH7DY zt$sM)!ZF$=7%!H^@xcoibW8)lu=rOHQ)&;RL%YV^x#9WOG^5zC8r(y{pdPVXT(EWl z!Nw;+X*HiqHWwx&+moMAP38fw)Uk*eWz-p!!s8^JH zO;z}hi?EoY^J!G><4C8;DDLSj+@<5N$EUw#8t_7h#M}arR^B?}4~jvDE(FDIV=YKl zY|beifuxw;6WX(~(_7WAOYcRQBVG3%|HmZ$mR@Xf&A-C;@%OKZ_z1ADFkr>x+Cfaq zYfF)whFf!|M104Pw>~TY$Wb!_w|q27aHn&_-x-(<0K`55IMEonSWNk35-S6QCDj6? zZzFr%|3}gSdWWzXXuycN1%O;Nl>v5`Ap8VM5e)O4;qWjJE)NU93MRn*Z4k~raw%Z3gwXQx_l_^au-3!fI?sy!Yv)^p8=ck zGa03*VU?)CmkxEek6Q?%Ae-Lx!0NLEKJiH!ZxTy8A0!sQVh(|6@l?Ot8=_NTe1PUt2~TZF=+qX(Xt>)fPWT1rBZeZl{5?+lVlK7P7i zZPc4y;);L6(hP^9F`NBEfz7DInx>g}SOg}Fmf=obnWSSd2{I7K^Wh3zeqotl(fUZ3 zyj(|`on=5kY?~8HOb)gNeVq24;P^GQ;GoP{o*+bS#y}7dVw!beH+jJZLX3b;RH6kD z*Y_ppi^&>$ZG$>RS{(M_PZ2vA&Y`>4nv2B}ol9(uIlinYrCk(vpVD~lyZy)|-(2iO zsw{KY&){bo<(rfGZRy2kff)yBMMx=RJ28431BE>bJ#@K{mRMA{=j_jaVu7maQ{qwm zag~{^z0ReqKw^SSqIy+tZTu-ng}i}GlV6>H4wQhVjFNyR;1Kqn`kAc^4H`Z*4$!|Q z6S`pd_{}FO;!!g;ff~O^_EBK8%=wWxYa}`jJb}y2OP=FIHqk@gS8Pk&iJtV2UNKEh z+wS`ev%C7N+%pFr*C{g4aw2x-4WZmZrN#m=+mj`K4DZZwJ}0ht+3taxsA}H=n+|hM zm5N{`J|KYJ;uaEQxcCdD$SLun>YEMO%DR@!GSs&a{_sum5R4+|u3HrMfDd-R*mr~n zU^4Z;#t~?i+b4X5q0BC-1b2QbjNX=4GS!q7Tn@8<(tlv~N_QcFaTF%{NbvhjGo3KZX(Y zxSKy*0@_qI8V+{XGMp4j1nvH&b;$ZEl#2l2RP%K4#bYVNO(H6S!*upy+CEFdizq=k z5tJ$E6}fj@Cud5Dy{69(PmDQfSuti&A=E>|VIg|Y=`+(#6uP3`Mgs@jM*{=g>mN+N`SQVAk#PHW7l+ zr>Hlq;(awEigc`ncZP>2CFlO)c4}RR{P~WfCtLn6(?yy1Wrgql{XZ?h3sdGA=HcvE z7{h1_NyaV|w{0;j(#b5c^HO~s{5ZeT`Tis7mN@>Kum2m}J%9DhCr?V^TZUkD5n?yK z*2TZa%v54e56H_uNI(?q#ez(y zmw9S7lf7u3NCC15!c+gkHR-LpQB7YN)h{#ZRGXnywmEAJ0(7)rZxv_=#TSf!bx@4L z0a<19dR3`6k}oEhH8O`d<1fd>v*h)+!?H(+AMa0o9*HkY*ODElJ`6) z#;~R^h_S1A*wPMCLIhi6EvM8pVb@V)@$S_S_?om~(SSd#A3<4pre4kf-eQlDkrD(t}7+z4G zufHliI^>-V9A7BUie|2%vn1CdC&p1;z-QFL&>xXXRkqjOeH0gaq3!7Ci1E$UQEX$? zo^ZF<_#n+453`y~r0ZCe6RIantQ;-tGCfu(kvdUSpPvRLxRxy$McJtoTVqA{Zo@EW zrX`aZ>(N4cwR$&Ob-(a?{i`5{j*_%O8e^q+N$qfIh_-JNr9vOjH0i=dm%~f!m1@HPPWJofWJO0L)HfrFx~~*ss8Dd*SAMdE;H};XRB-M?;eBGS>;n$e=?s z6q~FGs64C_b-FL8&KCjBFO-WAdT+OZFXu(yk1YJ_nuX_9q9R@T{+aHav!4H60@>Y3 z3Xj_Huuyy4NkyXLi^K~OR0L-`=meG@Awrup4$lVhO4Z(}Z2&nWsCCEKd9%KJ)Hc@2 zg*iV)?uf{zU(}Ix`8@^A_~K|}0HQludgsiIjOur?xSvSF)W;_dXo9o~P$mHR-_o*g zFU=Y83Tb)WHd%PT<%2iaXvKSl-o!R?a&6J{W=*AUAjO%KX0@bYzsQdUh!CwOSxrHH zSU@y)S_Guf-xjyEbK4zUQX}j1|GRgM{8%rjWb0@uq-tZ*7CqmCt@~f6o^n5v3Etyi z_^U%3j5MQ-cD3G7*Gx!Ippe@a3XO`WNk_svZc)4?zih&zEnbgbiFTYCazr{IetMg_ ziKcbVoSAn#kEXP>%btgrDSQLQ=ObZ%r-3je-%%HB#n@zEWcIG*NJM{vguJgvkb^N6Cch0)&cioSEcEv{)=A>e9^2oRc9G}x8qr6xy;zv~9Y@!2}I_H1)< ztD)2?Q{adk)+>@o)2x};Auaw{6zI%R=)_1x4+T1Pi^Jeod&@@sIw)(uyaz21}Xz^6*y(y&N^!Ze& zeg6Aw%i?xY-)MLU`|OMHB2qKC0-8AzP3Bu3>UR`Er;8Ckv!#A61w7vrXmNre`cMfn zXwZ}6rDce3@vyMP*w9Fy4lkg6^k!Hhxa?qmg7+dZT(R+`(Nd&g2}MHRlOL#K9kl+_ z{*TxuX1vA+pGzaCAr%X^*%@w3Qs#g6E_-a2J6)4ucn7_z2&JJj>@bMZ4#|!jJR_P> zpk+Vn%T4$l;mnjvPY#Xi3zS&d44pFb$?77(b9#X$8-d$ty1RM|*AmvKEUJR27er_P z@39dqdG)yBZ4$Hs+D`M?(f|^BWa=KI#%mxM5sW@)aN<9{9DiHL{sk-=-2kdY@3*cq z##YV<_R94amJ&wy=K{(AzLnndq+S65*KRFQNe|kBe8R9Te~LYSqG@zn>0LPAB#%T? z4;FF&Zka2Yp~WHSD+%yKV01>s4cQ5$^~{-z-nK@QImKsz+B;^7f`o+`u7WC3_HvH{ z%c-Y5qL3{5_8K)eL65`;nsFdxdzx&39al(IPSDnlVVUaRHr_8&LF%8d%hv+*`4t=9 zwe091{_~%NbG~Tm_#e|JFl37NA`xLTci0znNzWhy!lJt+HhrHlrLUgx9k(2!CH+G! z)e(d|cFJqdxz*kp7`jupZjVON%-v_2mOLuNvRr|3a+-*bFH zmy*ib<*%lZO)y_=KIZfHWA*H#)C3L?jHft}9BEi}+;o=dghh}uM8J>okGnCT*?)N$ z1*`oTYHvd^5gk6E;7d)TeEJV)B`Aw~_%H)|8j_1Q&x*a;ZNR%dfR8R%$Hg9`Os)LT z)y9IFp;Fny1Bj3!aYw-<&}`QU&dd2yvBwU}vkS1CNB8MhNb}`h8737;`7^#4z-TOF zwNWV7UYOmlk-lL9z~|c;kX@6*#Hvbw!y_#e73h_^gMWE|`Y0bd=*a)4rg~L=ozXS$ zou~IxN6^(+y-2V-SGhmIY|gL=%tR;`&ARyCQ~gdBucV(r%@018PdbJK4X+1D>+9b9 zl`0ysswol%;2GFRK-oXpka6`bMlVY@$qnIFC%|<+1oX`n8%L~-)?tWxz3OPu91j!r z{K`kY!a3zpw@I%0;jM9ydbmH5`{Ax*U`5zND^=Rt$Maf!R(j#)i^kVq5oO8=Wu$|h zKtpy505$;;@T;#)&P%{V^ZkEVQo($&T1M1#Wy7_u;1ke?tG}-~@E+hQ4gW`brpzsh z0@C8MDIm>ROB+xDbM*WdZWUPVw&~2L>GvIcDM4raEf_$m$*2FpII)`&--Cp_Ad~+{ z*8h>8>(v?9(u*6eco|QpZ65!#@C;&FZ*REDlz(<$^aj+u92hG=6!jEff}I4adS!(E zM=WyuCuSz60#yVdYR9=@WhW_($_XBu`AYeK^~@9RcSYl(*V|>Ox{>wUCl?z;kEr- z3bK~X_qU&WXrMj1J5n6ncdqOn|NU1!STf+LH8YD4`EEq7ZfuTau;=VN+kM$2TXx&{ z=hW!tI9DVRX5MXvmxD_wG56x9DR0|!^4N>~G1M-Ds2nb?F4+8LW)Hy}%ER+=utNpS z-0o@#o$a>Fz{nafa!$|`_>HsVOG4J#Za{@OBR%9n*-*fH9*0p2Nj70xE zj=Dx}xoL;u#Se>5qJZR+q&#Op?P{19{DkkRbo^fZ_;I}9r11Pw)ay7B0c&tx*+8@a zDn~t&DTx`=I>B;juZz6CHam98tPG|9_WLZ{`1F?@Y@JOo=;eSjBfBSFMcUU*%4*-fV_rWhJ{k*%{DV+jN7!# zIZ@{;Y7j5>G1KJl0Ppwp9i-*z{2{C?OgWp)<1%~9tTgZW^GxDlQdQ13IBlgEPz%k^ z`QrJ$8tQ+#YHJTd*6jZT)$(~;m>=huYU9S|qjP4C=99)oJEM{2VJY!}b^KHM$xV2j^67T!sDTio(Qh#a4Qoe-eFo!rp;VhP)~~iQ*_gDd(e2 z9My6W)Sotr`k~|y7q+KxnVmY9C?CpNRr)KOGlAvnk`gB=Nya#z5KitOwLbdtw~4iL*_%&GYE{LN|Jt9zd3RyOV zqdh$i1LajJXr`*(BZaMV!p398LwFVAPW6I-!?nGVQq>xFV9jzwx}f-F01uAIAo}S;Kwb z)6|6w|BEr;qt+`eFH#?^z9x0bX^M!M!OSSR?2)u^GDSb@;3WTowWBTQMm{pvS27>##nd6ssDKZ_ECawc?seDcsKV*9+F9|T{vi`c4 zim52PtcPdxA1zp>tJDq4I(_YTXP~zAYO0YFqdjmV5r()9EpWQBP)muZc8ngK={;H$ z>If6hzQaT$ym9hR^s<$)e~li0O9FcrT2@0h7m0yZ$6YUWfJ%g3lI-q| zu?RfJ37c-yk^Ut>a?z<>U6^{{oUXy6wDlUpCR5}6^)y4@sAf*hO7-Eg1EXFpc^akx^@j?yx~A-6A10wA z`z0x1r2P{`StAoSxT1Ja#HLbt5%%FadgOqcfvsetH%CIJWag#4JSR ze0WhnVHU#yM*wI}f97V*RkMYf`R20n)@8MB^r;ZV<_`|C=P8MSMxwONVt1goAgi)K z2oY98bL}WwmUU#o=Gb0bWr4Zo*mI)$ZK9o?RUCv5IrnXh@*)JYq--xpVz}%Z)CbyE zC9>1c@c*LFN@5o~#GfG;p|9s;6|o~p%A)@wB)*dr?_VZJGzAm;oLs-asHCtpd`HqF)lJOxJ}3k72z}?$;deQfvOyC=freH%9QD`9#}NWX*v@qwL8QM{!{*v@ z6_})Av}YMcx5C>t2fNw&N|zVrm1)hSa;)$@Io_xku-^+#!+1lwnO z-m0sm(8F4%`YAzb4~%^$Veq{jXc_-}Uos4beeH-Ck)MkFHrR%P+*4=Gl12WTjmvKF zM{;CmoESn^a%A+WyJPL`WaP4;2X>sabcGwEB3@nMhc z&&$cpzLAv*MpFG>I3aGSE5s|?A4@E5U=+t}dF;>253(vKO+K6?8hDlK} z@4l?ncD?EdYC6_Ugx69xgnhiPlh|^K@6vwav3JuU5}>2ZFo4k;FMJOB?N=KB>fdth z4@{N{R+UHrVQcR=;AT$NP2b(A5&4a4iq9DboeJ+X`IZJ_>=t^Vohxma<$SPXdHWvA zlUgsK-Ds+UhAjL18QLslDvZCK*dlUmgi1q9TFe~(5m<1yY==XfEe%m_KZ7EPnO8AO z&@;pw4BjPZeG?y>=si^hH8vEcI=`(jg87cni_oeF3gyhT;roRVD~YKe(&X+=Uyx!b zZn5nc=pWUOEN0UBle$vi7v8G1s1-jFZ-@b$pXNj!-1_;-S3fKFa9%O1 z&wu)NIV}tm?`_dsr7o60>$MU(@ z_b=Wlc7wx(sr}+0re!D$ho;ldK3teF%lwo@_V%MQ-4G6kbcse9!{yIa`)}bJl3Sm& zpEp~WxM~6oD(tX2{J*Po7F0*y+T1wq7yd|b+Z)%6W>e`~|D%29o5u2?=Sr3J`xsH{ z57&>*UZ!;pyt^VK#eZnQ)~voP%n84RQMMkXLIx^$E@Rt3hm3t1*SKQm80liPTI{y< zktb9?nu4AJx(|HZzWq?AJ@QYfEp;hR?L#)PTN6FU6>8_u3}=jy%YhRSQvC|lRO`B8 z@XCUAhw$6@=Sc;OuInmIiM}5rxOz!-*j_+pKW&35Eo!8kFTmdPeTh3+hgp14yt$$Y zLtJ-i z@;Ri36#FcN3XR9~2EIK1OtZw2(dF-}|#Yo^TceX{Z|KJ+6@rz2SbDxF3bN#{te z`g9aaD>Gva#fa2vTN$)yQoMHrDg zK!C}KOW21rn~g_00~gwRz@Ti|2;`RwX+K&h7vMRwNF01SjRAIjVjuUpOieX(K7?Y+ z#m4`RVo!cv+;wOlsc-yKH=}+m!5)ju3Yi~c=b1v3z%Lt}IhS5ZyrSsv5$ue4wXiSH zC~#!w>e=7doLzQ+47&-?y!IaCU^M-^H~ccc~=e zUQ0HGn%)O+3_c%U*X&EnMC+pHnWC`~SZ>|byr)KUn;iixrdqaVsrXCfO;ySQ5{cVfJtMPzt7h^e|m9uWA zN8hl9XA*xKTmpsPH5qiXT81_B`+o$)%#&`*uJ#EYz>6_hi%0xd1E!6phZ!V?Owj&v z<>Q+PA(}@AfMfo;(DePImPe6j-qYNN^*mvbHXB4rr^fedgU-zp-SyBXTEtOy{E`ml zUYKxwlfplorOxg(iMOBla`ez~e}~Scc@(U9E&|42*Mm?iHsty9Dkttrsl|7BW#&k! zx+W|40-azB_J%IPAK90e!0#F?0`XaIyR@xR?}X=JcZ&LZISv%e)2Cx~d1t?+y&wCd zH6Q;L8%xXNY|dmDr>SCp#?|h22p_jqnDn2^G99%Z(Btbx`D=yuWvZWb$30oo| z9EF+Ikn^#eI&4v{-0C4{9ZI4!ub z9e01Y5Ei;|uI!GmdNqi&$~WHp=*S~+R|@lZ)_3U|w=qo)EO1I&?Vn+{B(hHbxGpmm z?Y_J)Yx+L#f?m)muzRp5v=#cgj@Dh$1`aJ7?R229Nsn`sr)iWX%{3#iE{ta8Mo9pX z`dd0L>ppXY6fEG4sTg32;Aga-g+AYy-}4|xNgt`&dNS;D7G7l?Qr&R~mF&l&d+mO< z^yA7j7HTtz#p!%75TtatHynAvJpz6&|6N6BOc!HfNiNnhZr)I6tQFMg#{6oONt)2z z(LD_h(|%X@tu8$oLrna5^Iov#KJv_;1SGb5Jpzl2R{5S$ITA_pj;!AgUtQt<5cQT( zZ9U)jFz&7i?oyoK1lQtLym*1)QmnXJfFdpKZUsuQ;sp|1KDbM;77gA4?UR1j@4ucm zd6AX7?w!ocJ!hZ2XP?WbFwk!yJdIWDDDmUFqUXfpj7wQtPP+l1jAKP@ISlKitFmqy zYoSig{b~xWfJL*%y2)Lo8M9#0%iI<4?7} zT-aqXT2qTo_WCSp#)X#4s&B9Qn)k9GA>>KFCM5|oNA?pb77i2MA-=L;<%q9Hvt?`d z(*p;kA+zV)hC*qt3J9!-6>UXDIiW?PtfANugmn-t8BHg> z=l3DBiQjh=>^mQ0l5<1{vZ73zxgL1F0`HTHN$UHk>f*Hp>7SIc={7;677a3a4Bj!k zQKhaVd+Gni1f5aoxV1Kdnh-Qz6R6u37IyqBMi55vJEWv+J3dh%ipUsyi#D!LePr9n zI~;|m(;D!6SUaLe!ps;}(_@@q*QQ8;g6HmU$C#fB4> zUvMO+P?0dABA&D7q05(71mQUDTlb7bj3Z|HeVIpLGu}|V(a^ovyDl2k11I1_3V6`r z1W}|acQXF=;MgNvpl)8E1~jvaMVJ0Z=Z~utmodt~wtLHc$THVyKL`awdNObc{MuBo zMxg+UH^Gw;r6?=#KTAOj?>)raq=@lmy<-w@me4jWKF)p0ucS1>!}6W;8AM>MxbLzJzWtYV-sSs4cA@i%EqM5fTR;y&pNymNaef1o!WZ+Tq4H>Q|80;aWLTO_dI(5xGwv7I zbdHTg3dOLXCK+T^$FPd(zPOYCuR39sY$uW>lU!3e@}MUeU=S>=Mqd9QFlHV3^+3@k z39+w-fjQh9j4ew3cERk&FMgKT18?sOLg^a>{HJj0k;p5{qf*|q5N7d0d^8LEA zj)!~HD1>nbzW0;S2MIw;P&$}-S`a4uFzRf7?n3e*F-jpyXwoYB84^?A2z&eWQQsd@ zw~^_8R_(M9cw;;JGi6*R|BFQQ-k3N49(d;<#cO3H50p5_=W2cyZQt9`Xh=*dpITmvv#%WzGG$;v*lgFkWdlXW@r0(S2X2=ft@Z@2 z0N1;_yF!GQZDahyQ6)BqJsZtj{)W}8kAMBC!*?So%LZ49dH8+Ce=tMr7m|^(tu|mE zx3pg%VX8}h4uFAnl ztxhjth*p{7ZS|qQV;kpKB7vgWZi<4ydOLlet3hv&)+tRHXyqQGw+Oc_S zc*^zDnkVC!m`>%|`4YF!lK^NfqL}4RLul=$&{A;K`y%tk3ne#XBNN<^yiTeYa9;d- zx+aqCLQTPsQ~IF=dE*b8Ej|wGQeV*}IM9TPGar0GvV0G-YsTH|!JAjzx8uk*Rl2|V zm(w7i5#K`(8()L{Jf%jVZ(-3?`x+q&I~_O?^J!-%yVs!IHFLk}pPE5i&bD+Wz~!*n zA#{l_=OXGCa1kLQIRTm%UvUmqW`q5=FmRr|Dr2r4iJ=U`R`VZzT@>MX%xHz*)0}!Y zA3f0ALBy~a(yh}qp0HU5CMU#yK2!{hI2N23PK!!dKy!_)Shvzv67BO9kiOAU_UIEys-8h zA!-~M*}^(nt}I6`l`r5z=vh*t%*Vo}w;#U{1tEWWIZaxIog+KgCHQS{Nx+HJQ}8}F^?f%s4Ms@Vy5Jkuo{NvF7>rXZlrCbIWC86;OCbQ{nT14 z-+OGn0vvIVRo{^xTFJ<#jU4r0+M|)b7QV}?o*?@clHU80@b&yF!=8}xpNBU>oYL4& zOoUx@qJcEM>Aqzz2RCX)Vpu12$)h<`)cbu!)J4b+wR}l^_j69Z!_9$y92qYn9+mVz zG1ldXc-ntXPa;dT8kV&YfO=fJU8fd$7pxEy7}4^apV%!6Mo*d1mmo`P>sxB}*7W?? zQ(b6>nS!tn)$F2IFB4u0H0z0rSlgu!_5|vPau3(@G}SLCE7+c9j)YJwFQg>qUj&s{ z=!wipe`W9>FzuXv#QBx=+;TCBsx5p7GaUdc67^25q^;=Y3}p*~^#pQGAYC-lu&$f~ z5W0=T+lAY=X@D#t^-;qYWLNP@MJ?)fR(`!D-uq%m#Ro&;W=zP)Ywxgj>EJD!jv)VR zpHm%hH;5#3(z*-Fn-5AG$qykU3lJI&*M7sWWyCY_kyc1RD&8ynhw77Zsv1ce+oie* zaoS8w;9mOdqx7O4dOsa(YMIPVFaMwue}+D}e*)b;1-E_?n$pB{C&SzGeXq%xvhCYzAao(bq5!9J!VI=m^dUBJGJ>*Y2 z@`U|ckG-tgGlthuNA&=?iJ^63O-61r3(j!tr_{l5(MJE1tZ*!39O4&+=MOM;bgXd_ z!JLfd$8X;!LsIw;PHU%6WdCzHnI#{1eb#uliv*qy3rnT<=x3trsrh3k(gI>g+=<-( zn4r&=t;6Sq=XaAYkSOpv^0n}1tM1_?-GE?6%A3er^SzW*yVO_#$LL||a%2Bv(!sbp zgum67OC|aNRc2TM@ zT`CN#r>}RhPyFM$$H{EkWTz7{^o|;N+^h5OXZ*#Osb6pU!l)B~)F^%|{Jl-a=N$yc93oea1nc{Vb}Zs+|2*gR5xnTcr~0=9!%@#9UVO`bMS zcJB3!IY{@x{JT}Qg6z~!o<_+$m)_+4m>U;6&~ntTcXo^a zV6yo2i$orR&jX#xb~@}#rAGU-#l1^b5|-`>hlzjjZr;yaSu}m|Wc)mn_sWcwKt&X;%TA261VwdxqE|jx80(KhyUd( zTGwAu`(Fx5bioqCJ1aj1JC27q9=tCUfWs1a*0R^ctI7!{JWR9=L4Q*N^M|{uyY;^2 zd6-wPWmH=QUB$+9ZDsC%7fm#YF;#7iVJ@+aU5!#sj@`?`N~DQ4r@O^44Hb0aQkpu^ zM@cZ`ca${MZY2}%O9Nwy%2rF6pS+Licu{U zs3piG#K~|k8H1+ADzEMu(L>OR(kZub0tF^0lV<$1*DuG`NXY2Y+u`D}BQTHX35<@! zk=N-}pE?#_(G?_ExgdK_*{;tvxtaFwdu`^@# zPeWoR?}ybn3^t^^?~ZfwXPdXbV^x>wb<`1H$skAY!=~A~R6-qr*^7ZPh77P*#~~J9-d)b{hM_`{>Id!%CYK?1TM3gga9n)ji8&Y zGow6ktw3W`F`VmyiHbrxBtlHLLWs&{7PCZN!U>CA4@H=Lj?R%twGr~3oC?1y7$+|O zb&LCyFqOq|f5+%`LVQYPR%%!Cnfms+anq;Z!&_c|Tqnty2@A5H!#= zu$l#v4rWFp58+x9h8-#dK9$^cJJg@sMbcfrnar*itck$H!pDt`$A`~EJ^b}*{vhAH zO}EYqDE-HX4H7|KU!7{ub#t}2_P3nbAT5G6Yk%8)cjepVPHZ^did^Gmdwrqy6rMSW z$fgYh&IHW}6tuja^-4IT#Exj8=?#468(?BVKI?wq7b(+muxSz#S#f(^GULu9(>f>mi;8m##4 zPfvnaQ{QlGVIs}YEPeNU<1qzUR|!vof-<~ngZMRf`5ftVBj`@A;sVN44)!+C24n1e z-$e3DiZK$|c!(-RB?4Z3&ymkZK=|XP*on;tH_Bql0Wh)X7;n1+(~U1(s4VH}ra2w^ z7+n%DFktAbV!>ahs$iT+WquD(IEp127G-#W{$-KE1cZEq30I{u3r7h3LS>7t3qbrf z2_?G#NOssH@ojz=KpB;)6YL895)Vrn;RPnLL51j0 zSF&2YtkOEB(6!Z&mNQUc+FA*Qk5%K?zTxJ6O?jH^R+4rb@5OfCA1i?K2IUG`YP<8* z)Trv6?yo||x!K`b5W`7{*WAfMREaD7*-b(t4;o?tP3_ik+i5SfWT4*|MYC39awSHU z+nzk=FUUSanpZk9BIWjIO7Y%7V*36~!v<}q`Cb~q77m!@q521w$o5yAwou$+LBu+l zxOl=ggF9opUyUgDRiTp5nMJSpd2aGAbnI~V-8JA(Uv>to?gcC9rAL!@#}_2xtH+Kw zIKN#q3kn+NheLkKVP3V&KzH;9?IigD6Cr(#O5rZhP}ff@;%aYaZn26{!!iQ5K&wJS zSGQ7&l3~lk8j1uhGLhj0Nxy!mZ_bvQNC#5y9(@fw-{Oa-T3DQ64-JTrqkm1qSdf=Q z<0w(HeZD-xN<*`#5osl!ZJwLjv38(YR%b@(M?zCsdNve`uqskjyu+2#l*VL6oAtQ@ z>tBLVKf1$zL%5?CV}f0>7Q*Hi_8%-rdJlX>~;5;xJDteLIW z253BSLao~bTI3|7v)m^vJOu#W-bQ4Zr zA&<{y>Bi9Zc5NIDf;sA~G44b6*H7UE>I6IL$Iz6#b!(d!D1Ru9aEP5g?FUTmEM@! z;;@pL616gGJ)fdyjXks}}VIQ`Yiw@nq?~LBx8vv-&4MkNVn9E)jA1Zh9~ctMMU^ zrgk?fF-K#6w>vX3PUUh^Jd(qJU)p@?*P2ut8bW|(f2AB4BAtiKI5j;YOoHIAi1;ab zlDxF8F@{$EqJ}X&v;#`^rn-nfBRU(F>qb+E?)|-s=a6IyujQv|kV{$DatuXUxMTB?-TvZRH24Le=2b`<=~bUWtUbk&X1!~F z?6)M3Sjj7o@%{h{kqf}@&3Tm~4}ovK(eLOr2<$jqeyO%i{uuhtoJLcXAA}G5X=s8po)Op|fIW>Q`Bn=ZsyLnunt6nX_09Nr5o@4zb#DDgQ6PVIB;c}ieZ=h6 zzJYEFl}99BQ|rI`pst=;V9=vkGx6D5aoQ#YDC(WkF$Z}cM6-8apd^?_*OB5)DAw>R zzQ=InT10>~tvU>{F{&^UhJoao`$0+L!h?iIDS2!QY?G8CU0&{~r^WAapvv92ab>UI zN&L0}FHfhbS3(7kp8iid#w!1`8M88|Q-TgpE%J~`Qw@Ab3Vs)rm^|s5PIpvR3RX?H zW{K90f{_L8e_{uV8UBn)&H7i{`(&R;y=qbMtDT4fgFOOumI`w_AvAR}XK$7hXeufQVfy4@KnB>5D%Lg1~(WNnnoM`Q>YXD{#SQ?i9KEC9Wt7mm@UG|K33I_<0064bx4*?EATm~FNBfkp9NAjSH;mz`?Q#6{P@Uv+ZC_GBYi_16@UcOKj8hpj~D-`HmgoQwAh`IJwE*- zX5X|mF3$u0Zf&_R<|C11T|+yOyI7~6cKvfWlKeEoY};%!R1bs#vp2pBGvpv4waXq7 zf?EwUwh6TTMefhs#eET^SJlw}46Be_DbX_yV(PB)E*N?B7!rM3V<7>rb>TnBH=goIWUn?Z>jATb6hkXxiBa7%1kUV!&Wc|9u*~fp( zZNrJUvjYEtuJ#5F_yCfI9Km_sx&PG9QEoIeS#(P-ILJ@*=_1=M@-}_xU%}pbCu%ZK z@lsQMYFFpSIfl)Q!v`(%5R~!_8MGb=l8ZjaX;!7vt@?1DZ6pr}qstIsGLG{nWpIWqNJ&qT~ zbe{0+fXHf4SS-tgbP_ZhreQZVVDhoKHNCl@fy7xE^;~fn*l z#a@Aj6VIif_MfWqkmEDy28JcklhLJa7fW#=t_p|yi60}h{mwY}=v^B#hju7d=b#O8 z0d@O*Tk{d&i9V>7{HY;%XhdU$GG!$}J;l3U<2}oiMrs2v#W*sdz#+=DWtzs;8G2B_ zpmdB?z|E42j*kE6ge5_eWc44;9{@=p_1`MJ9dN>BQgeXQsfl1O0BvAm<-%qbKNl(f z?wgL8j6M1HSI@glo)ocJ%wAHlm#yUe$9C38hZN%hx<)C&fXhDGk}A93)o>iBu6aMNz1chJ1>J6#9@vQwB4K_C**0tX}UIk_KR57 z(rLwX$3kjJrv)9-(~21V@9;d#^2rI{lIVF9E7jOIn8 zGTV&vY@F(qqRc^(s>J11Q1NYSM_GZ}PGWQ`F5>gYpNWr{IF9(awI9BRvS1UuK=HgX zz=#Jv>SHpI`>fuw3>8%Cq-F$R^`-}iVPpf11Y@1Q%o5XU0@C;)Bgrb?{iFem)xti9 zwaf*KxGdCG4+`lIPaWlUJu|8&<8!ALD;G2{5Xg?F0H z0Jah?ngkb5T|H|-tFEn^@Ql3=xGYB7wW)b3{>rSC=Jm4YY?NhUedHTfJogLroxAZ9 zms{0?_WLqah5YiDrHnP4DAPw~g01yw@Bt3R(y&m7s{_=uoEubk zLV81cqtdJxv5ASE5QY!64c5L1E|Vx{1LK z^Jt1BasvO>#eck)?o`Lk*09`-vc0lYZ26t$1uo5Un&QgIF~Mc8M=5g<+_eXW@)~S5 zl%WyG3KL~Sj`>`#n&F1h8i;)7K8TWxjYooLALuXHn|>!!J44*vZ@k07uSN9~(g`rQ z@3;U7=cspqbM(yE0v$GX^8`=ImyFZbtD+{W*W{bq*!9d2^p>_zvK%j!8|bs`D{VsL{+R9p=4gjn*wUbR2w%^Xu$OMPCgKpFDaFem*kwPzMh~i zDqvtv;25OeyuzXQ_#Z&?k_w9X5{q8AS>!8hGJRMmeEK_BOn~*GM70b{jgLn7I=6;M zM6U*tu0uiv?7#SND5>O?ifLH=3-QZJnbB6uO!K(-1?=l1F3E?jhfei`(k!itB9xf% z!(=J~mP4}7O^JoXZ+ztvOJQPFZ&e~TsfF;aC<^Uolgaen=_OpZWqd@H<4E7Bfn{dv zN9)^{~I-KY(tU%FH;%@@z+6`uQX-G@OH}P9+2<(_;Ic~T$mf@c>8|{@U z1NW0#SAaNc(Li88aQ$<`)dj-pwsUZKiMQ>ZaUU6(5ZquVljO{?W9ug-UzoYt>($y5 zwm;ExGmjaG{idx8#>BnVO52Io(diez%BMP`DM*$HvBy{;DA3vRGYK+SJ z-WY0v*l210_()ty5`yE;%#XRHXiCg$3uZ;c04=m`aH)(MTHnCOR9=ZmI=m3{A;`@o zFiNFQ^S6(Up8N0%*s~3>X3hDz$qCPw2y?MxC?b!8$bSDL9gR{uku}vg^uB(@02iub za}qY=8(&@w{JG7I^e1pW!KDM>ui&?Y+9lVEWJd69tw?<)(eEwlo`X-c9>0iv|swWdjeQ_fhw!9;u zhAiMHRF;^LKWO@63u)XyF{8U@Tff;{?R{P+<-?2vv-|4vi_d)hNL8M!_)@@YBytWD z7gulK*bjc1h&U1;R+BS0djdGV6ZtLqCE}<3Js^t6)gDW__o2(I69#d#tisSu5ABPi z`RMGODtR^Ot%_eHMR&V3PiI?lOG;)QKNnFgIn76d17DD&OoLg>{2*0w^!JlbMicX| z9_;J1TH?)N9Q@4PGNa~}-9l@hjUR_EN_180mCyx9nXXY1c|ix0T)l>PwCi_q8h-z6 zgi323Fm~5OdYCTyDgvS;3@{R0q#am^cA9CH9K)G68F>JvMwSMLix8R?IKf6AF0n8E z>oG_rH!#ftw$bz$devc$+ERg{P-;UW1Gh`RtADpiX51N5imV9zCp_=ufL3oS=SaJM zg7Xg-5*Gdav+znRu;#Fc<1i4`6D<+3ZTor7RQS*m7n5L zt+FkS>v}5ymA#%j9cc-7-sESG*N4-!SuLa-U;NzryC~uUzKd{mEkl^Hlt|Ao0Nn*d zP5-fVAMP!k7pL~`X~0pP;b71&rMaZ0+BuglYE$KL0s2M`aunna^&>!rwRL0;46hwG zw>}UeL|JtHnm54uS_T{j>*jquSIQHi3*;3;bW}?H`RzObhai_4NE`nA@#I}bfTic< z$$*(7_@_)U&&P-FPEBppsqcav^NioQ)F#fL_Y1;Ji2P(8ofofC>U_C5E6{tu#qc)+ zxjqFPGj`F2wRFjGf#Jk)W32-an&{prPWCVt+;!Z+>pE3aZ=NYUl0!@~!k9<@mu1eX zeDR;i4JB1+m~y1ED3(}~v1*B31#2<6zz$+A%+;`$rUgndx21xP6HCP~x+ZSOP_nUD zU!25JbMs+l0<+TXPw#m_-K=r@2bULwq13yiTXctT8q6|($bD)Nk6h&KZaVbUT*FPa z<+!NORv3+4HIR1yp*^ZAlPJ@B?GmvC_(FosS7x(9;#;6R2}_cUO?>)*cwRZt`92|( zQ0*{uWHmOMHj0~pKBxI=jT1}gj%R;LjP&Yvktl){D971QN~P697Fcid&s(p2)1WWp zO6eVaO3QM(?+b}pUM!pa4ZJ8)f^q0lo z5n&gs-hb-_^^P%p*LLR=`id%g`cMmdzv^s#=sJFAf49o7?##C*QLm|;z*K}nI%n8? zYS*B$Hip=@eA#T2GK$nO_|s+Y>KbhBHj=22bH>l7hdz*<8T%JEsEF!auBp7GA@eDG z{JMiU5OswCZiyu9sFsb}tGNaCT~=ETef%N*e|W8%49VeO#mVxkzcf(_BXF`bw7=+2 zou>P9*=weK8h?J|ex5MTH+X&pdgVG&Vo zMm4xQ|F8H6+9LDC%qCk}3&z~`ffj1990eiqqsRY=;@xa@?umBXY^b5CiQPW9*0fVS zp;fMng>|~VAvEyksD9J#m^AuSp{*2J(EzUx(m0a(6KfWY_H}aTHorEdWM6g?AJ-w9 zN6mX%J6kmU{UGG&Uf;&>W2Q)>(X>f(>cKPH=Z?>0J@bEB;WzQ;n0F0t+fI-|;?@`S zjY=J8)$JW?Z~o!qk8O6n=U%A}NY3};KU%m9?WApaN2!%JHMjg9`s^F#|Nq%&7aydz zbI$I+k3}s5t?xgDTim7$9>g< zSmjgyskbg=FvxwQnVogP|7d0DTb;zeynrdg*WhP^g*u(W%%pzQEskT1KVI(j&w=08 zMeAA17wZp-!qIuyWl>MbpQhK0AFtkZoK#lae>OCH{XL&FJ0CGY*2FXr+Q)Y<@B z;CIcl8FLHmRuh7Mh?#>*bO5OCP3} z-vTaAeY4e#X6r7^#3#3}r8WWfFnj>sYc}W_E^Yd^$w;lOuS?zhMJvui%p^1J2c$uj zA6Xm!@n7hvDv90=0R_%p4TCI+a8j6ULCNJt3+vXJntH;f?cjqwt(|l;c?&(v-}jUk z)A>Pw){?c80AM6iSW|z%W0*VaGbB}bLif)JJS2S^*kE78Si$Th5(u+&`ietyDPkjH zCxTByCxVm5mdA^NNkcN#644*|^KwWFvxK;1nJ$!+Zuvw>U%nXG$HWTsEd+)AW_PtZ z#v@u5JG8c(b6Iz0E9`gG&mz#`?}1Gzo+*R{hcOyEu){1-mtjh!m2}qIqGhypK2MLH zssm{*mN0zL^xCDkpuN2ZV{xfAfT{1ld8MJi<>fl*SH*y~@k{}>$tg;~Vr4*9^&D*% z8)zVsjz7mtIid)chL`Q`h?Rm0qT0#~a0mjy=eT}In@JNvkpjHokbll9P1}|H zIE7<`D6rGdiY;R#RN#bMvv0XWvm?3@r`UpO+0;IRy!LVtnm=AFmKexI6C%3c3{}A# zn@+8Y9g3-#fC=po`BHgT^wcJ%_OyujuQ@dxUOEe7b1^w^OTppGB30_7MHlUb7ZgE@ z%HSOG~W0ZOSO$oV@NSl$20_yL=RC-yWohD>$xJ2NN*UN@qoQDhM!>Z(F=5 z@ofgpMKCtyHfY!eR3`9L##unPUKErlUlSwExSr^lD9$AnTO4tt5Gbldws?oc9I>Gu z$VRK#HKOPWg|YVw43nh#K=Zs_%~iQ_%8gh0b$YXwiWL$DA`X^2iA;`+$$zv0qcZ~b z`63?4ah>As%lH}oN-49%o1u_#QyDT41o~I}W@#8Lw}~p#8>UD~ObHFN1QTQLZ9n2- zuEy=P_)&1t+TWmOc#%HD5_6!}CQ6bH&`t-dy+p-$CCEHd_VyGd6B74#VkIq2ij zR=-nku;wQR!lFG1knIcH7Q z4ZUrquWDbQ;PPue7`AbKi7SGxWOq2(dS)6edj9Ta#w?o42n0 zuKh#iGv+5jVI6PX5KYS1Vu$Y`cfI9bT1G0bSoW5<@q5#vF<1vjD~-TKcsujGw1U`# z)lToEE?*%ggTqNxBgaP-#$wGha?MM_P>Yg;gfDBN*$H8cZ6( z=O%Yq0Z9dPNemq1RU(FepSc`6!&fCOqr6{|P%C%V^r^RVRVi&SK)UmN&dmki%OJkJ zZ<6}LY?X%K*g5htOlX2*`WMSE*nGKN|H$WA#phWe`nw=JDhRVolyXM^tN4)zlDGPm z*<6Tf!N$G2#uBkYJGl;@z2gIII< z#nZd*n;n9ssWp4Z;KCc=4tivt6FGvrVTep7O|`oJ8TF5vtRI5qz2@|1zH2X^(^%*M zX8`(zh@H0WWxQ9gdTMO!8>aU-H|jSS$LW8cNctH5<0)S*5m)pq2hSBZBuq=^=ge-t)=ddo%+>cr@wLHo*KjsRRuUb`mtv++skqVmUM00ur)g z_5C^c59c}i&kM4}