From 8c9b2fe12843d9916405da804e0d17a1bd60423e Mon Sep 17 00:00:00 2001 From: madgrizzle Date: Tue, 20 Aug 2019 10:48:58 -0400 Subject: [PATCH 01/21] Add Missing Kinematics.Init() Any changes to values that are used during the kinematics::forward calculations should call kinematics.init() so sled position can be recalculated. If its not, this can cause a "sled not keeping up" error, particularly after calibration. If the sled is at an unadjusted position and a move is made, the move will be made with the adjusted parameters and that can exceed the positionErrorLimit. --- cnc_ctrl_v1/Settings.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/cnc_ctrl_v1/Settings.cpp b/cnc_ctrl_v1/Settings.cpp index b86af643..065a016a 100644 --- a/cnc_ctrl_v1/Settings.cpp +++ b/cnc_ctrl_v1/Settings.cpp @@ -382,6 +382,7 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ break; case 37: sysSettings.chainSagCorrection = value; + kinematics.init(); break; case 38: settingsSaveStepstoEEprom(); @@ -400,9 +401,11 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ break; case 40: sysSettings.leftChainTolerance = value; + kinematics.init(); break; case 41: sysSettings.rightChainTolerance = value; + kinematics.init(); break; case 42: sysSettings.positionErrorLimit = value; From 7748db8e3de18e3a3a0daaf4cbbe9226703aeae9 Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Wed, 21 Aug 2019 19:05:01 -0700 Subject: [PATCH 02/21] add B99 command to control FAKE_SERVO mode cnc_ctrl_v1.ino: - add global flag to signal Axis::computePID() and Motor::write() - check for saved state at startup and report it Gcode.cpp: - add 'B99 ' command - - if the line contains 'ON' set FAKE_SERVO_STATE otherwise clear it - - report the state - - save the value of FAKE_SERVO_STATE in the high byte of EEPROM to persiste over restarts - - note that Setings::settingsWipe(SETTINGS_RESTORE_ALL) writes '0' to that location, which turns FAKE_SERVO off Axis.cpp: - at start of Axis::computePID(), check 'if (FAKE_SERVO_STATE != 0)' to determine whether to fake the encoder change. The check adds very few microseconds to this importrant function. Motor.cpp: - at the start of Motor::write() add a check for (FAKE_SERVO_STATE == 0) to determine whether to set the speed of the motor. This check adds only a few microseconds. Adding this check keeps the motors inoperative dureing FAKE_SERVO mode. --- cnc_ctrl_v1/Axis.cpp | 15 ++++++++------- cnc_ctrl_v1/Config.h | 9 ++++++--- cnc_ctrl_v1/GCode.cpp | 31 ++++++++++++++++++++++++++++++- cnc_ctrl_v1/GCode.h | 1 + cnc_ctrl_v1/Motor.cpp | 2 +- cnc_ctrl_v1/cnc_ctrl_v1.ino | 10 ++++++++++ 6 files changed, 56 insertions(+), 12 deletions(-) diff --git a/cnc_ctrl_v1/Axis.cpp b/cnc_ctrl_v1/Axis.cpp index 5bbe8063..dac438df 100644 --- a/cnc_ctrl_v1/Axis.cpp +++ b/cnc_ctrl_v1/Axis.cpp @@ -17,6 +17,7 @@ #include "Maslow.h" +// #include void Axis::setup(const int& pwmPin, const int& directionPin1, const int& directionPin2, const int& encoderPin1, const int& encoderPin2, const char& axisName, const unsigned long& loopInterval) { @@ -84,14 +85,14 @@ void Axis::setSteps(const long& steps){ void Axis::computePID(){ - #ifdef FAKE_SERVO - if (motorGearboxEncoder.motor.attached()){ - // Adds up to 10% error just to simulate servo noise - double rpm = (-1 * _pidOutput) * random(90, 110) / 100; - unsigned long steps = motorGearboxEncoder.encoder.read() + round( rpm * *_encoderSteps * LOOPINTERVAL)/(60 * 1000000); - motorGearboxEncoder.encoder.write(steps); + if (FAKE_SERVO_STATE != 0) { + if (motorGearboxEncoder.motor.attached()){ + // Adds up to 10% error just to simulate servo noise + double rpm = (-1 * _pidOutput) * random(90, 110) / 100; + unsigned long steps = motorGearboxEncoder.encoder.read() + round( rpm * *_encoderSteps * LOOPINTERVAL)/(60 * 1000000); + motorGearboxEncoder.encoder.write(steps); + } } - #endif if (_disableAxisForTesting || !motorGearboxEncoder.motor.attached()){ return; diff --git a/cnc_ctrl_v1/Config.h b/cnc_ctrl_v1/Config.h index 64f4fe10..b7084d91 100644 --- a/cnc_ctrl_v1/Config.h +++ b/cnc_ctrl_v1/Config.h @@ -25,9 +25,12 @@ // LOOPINTERVAL tuning #define KINEMATICSDBG 0 // set to 1 for additional kinematics debug messaging -// #define FAKE_SERVO // Uncomment this line to cause the Firmware to mimic - // a servo updating the encoder steps even if no servo - // is connected. Useful for testing on an arduino only +#define FAKE_SERVO 4095 // store the state of FAKE_SERVO in EEPROM[ 4095 ] to preserve + // the state of FAKE_SERVO mode over resets. + // Use 'B99 ON' to turn FAKE_SERVO mode on and set EEPROM[ 4095 ] to '1', + // 'B99' with no parameter, or any parameter other than 'ON' + // puts a '0' in that location and turns FAKE_SERVO mode off. + // Useful for testing on an arduino only (e.g. without motors). // #define SIMAVR // Uncomment this if you plan to run the Firmware in the simavr // simulator. Normally, you would not define this directly, but diff --git a/cnc_ctrl_v1/GCode.cpp b/cnc_ctrl_v1/GCode.cpp index fb1d908b..7a5b50cf 100644 --- a/cnc_ctrl_v1/GCode.cpp +++ b/cnc_ctrl_v1/GCode.cpp @@ -19,6 +19,7 @@ Copyright 2014-2017 Bar Smith*/ // commands #include "Maslow.h" +#include maslowRingBuffer incSerialBuffer; String readyCommandString = ""; //KRK why is this a global? @@ -367,7 +368,35 @@ byte executeBcodeLine(const String& gcodeLine){ return STATUS_OK; } - return STATUS_INVALID_STATEMENT; + + // Use 'B99 ON' to set FAKE_SERVO mode on, + // 'B99' with no parameter, or any parameter other than 'ON' + // turns FAKE_SERVO mode off. + // FAKE_SERVO mode causes the Firmware to mimic a servo, + // updating the encoder steps even if no servo is connected. + // Useful for testing on an arduino only (e.g. without motors). + // The status of FAKE_SERVO mode is stored in EEPROM[ 4095 ] + // to persist between resets. Tthat byte is set to '1' when FAKE_SERVO + // is on, '0' when off. settingsWipe(SETTINGS_RESTORE_ALL) clears the + // EEPROM to '0', sothat stores '0' at EEPROM[ 4095 ] as well. + if(gcodeLine.substring(0, 3) == "B99") { + int letterO = gcodeLine.indexOf('O'); + int letterN = gcodeLine.indexOf('N'); + if ((letterO != -1) && (letterN != -1)) { + EEPROM[ FAKE_SERVO ] = 1; + FAKE_SERVO_STATE = 1; + } else { + EEPROM[ FAKE_SERVO ] = 0; + FAKE_SERVO_STATE = 0; + } + if (FAKE_SERVO_STATE == 0) { + Serial.println(F("FAKE_SERVO off")); + } else { + Serial.println(F("FAKE_SERVO on")); + } + return(STATUS_OK); + } + return STATUS_INVALID_STATEMENT; } void executeGcodeLine(const String& gcodeLine){ diff --git a/cnc_ctrl_v1/GCode.h b/cnc_ctrl_v1/GCode.h index d2cf12f4..880a601d 100644 --- a/cnc_ctrl_v1/GCode.h +++ b/cnc_ctrl_v1/GCode.h @@ -46,5 +46,6 @@ void G38(const String&); void setInchesToMillimetersConversion(float); extern int SpindlePowerControlPin; extern int ProbePin; +extern int FAKE_SERVO_STATE; #endif diff --git a/cnc_ctrl_v1/Motor.cpp b/cnc_ctrl_v1/Motor.cpp index b2e40d34..a06b322a 100644 --- a/cnc_ctrl_v1/Motor.cpp +++ b/cnc_ctrl_v1/Motor.cpp @@ -113,7 +113,7 @@ void Motor::write(int speed, bool force){ /* Sets motor speed from input. Speed = 0 is stopped, -255 is full reverse, 255 is full ahead. If force is true the motor attached state will be ignored */ - if (_attachedState == 1 or force){ + if ((_attachedState == 1 or force) and (FAKE_SERVO_STATE == 0)){ speed = constrain(speed, -255, 255); _lastSpeed = speed; //saves speed for use in additive write bool forward = (speed > 0); diff --git a/cnc_ctrl_v1/cnc_ctrl_v1.ino b/cnc_ctrl_v1/cnc_ctrl_v1.ino index e844c51c..b4a1f1b2 100644 --- a/cnc_ctrl_v1/cnc_ctrl_v1.ino +++ b/cnc_ctrl_v1/cnc_ctrl_v1.ino @@ -35,6 +35,7 @@ // TLE5206 version #include "Maslow.h" +#include // Define system global state structure system_t sys; @@ -45,6 +46,9 @@ settings_t sysSettings; // Global realtime executor bitflag variable for setting various alarms. byte systemRtExecAlarm; +// Define global flag for FAKE_SERVO state +int FAKE_SERVO_STATE = 0; + // Define axes, it might be tighter to define these within the sys struct Axis leftAxis; Axis rightAxis; @@ -63,6 +67,12 @@ void setup(){ Serial.println(F(" Detected")); sys.inchesToMMConversion = 1; sys.writeStepsToEEPROM = false; + FAKE_SERVO_STATE = EEPROM[ FAKE_SERVO ] & B00000001; + if (FAKE_SERVO_STATE == 0) { + Serial.println(F("FAKE_SERVO off")); + } else { + Serial.println(F("FAKE_SERVO on")); + } settingsLoadFromEEprom(); sys.feedrate = sysSettings.maxFeed / 2.0; setupAxes(); From 5d351a32a277d6991b65dad804b12c6d71367eda Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Thu, 29 Aug 2019 22:50:30 -0700 Subject: [PATCH 03/21] tighten up FAKE_SERVO access - define a specific number value to indicate FAKE_SERVO as active in Config.h - in cnc_ctrl_v1 on startup, check the contents of EEPROM[ 4095 ] for that special value, if found enter FAKE_SERVO but if any othe value is found store a '0' there and indicate that FAKE_SERVO is 'off' - change the logic in Axis::computePID() and Motor::write() to check for the specific value ranther than non-zero. --- cnc_ctrl_v1/Axis.cpp | 2 +- cnc_ctrl_v1/Config.h | 3 ++- cnc_ctrl_v1/GCode.cpp | 12 ++++++------ cnc_ctrl_v1/Motor.cpp | 2 +- cnc_ctrl_v1/cnc_ctrl_v1.ino | 13 +++++++------ 5 files changed, 17 insertions(+), 15 deletions(-) diff --git a/cnc_ctrl_v1/Axis.cpp b/cnc_ctrl_v1/Axis.cpp index dac438df..c03f9fda 100644 --- a/cnc_ctrl_v1/Axis.cpp +++ b/cnc_ctrl_v1/Axis.cpp @@ -85,7 +85,7 @@ void Axis::setSteps(const long& steps){ void Axis::computePID(){ - if (FAKE_SERVO_STATE != 0) { + if (FAKE_SERVO_STATE == FAKE_SERVO_PERMITTED) { if (motorGearboxEncoder.motor.attached()){ // Adds up to 10% error just to simulate servo noise double rpm = (-1 * _pidOutput) * random(90, 110) / 100; diff --git a/cnc_ctrl_v1/Config.h b/cnc_ctrl_v1/Config.h index b7084d91..89966499 100644 --- a/cnc_ctrl_v1/Config.h +++ b/cnc_ctrl_v1/Config.h @@ -25,7 +25,8 @@ // LOOPINTERVAL tuning #define KINEMATICSDBG 0 // set to 1 for additional kinematics debug messaging -#define FAKE_SERVO 4095 // store the state of FAKE_SERVO in EEPROM[ 4095 ] to preserve +#define FAKE_SERVO_PERMITTED 42 // store this value +#define FAKE_SERVO 4095 // in EEPROM[ 4095 ] to preserve // the state of FAKE_SERVO mode over resets. // Use 'B99 ON' to turn FAKE_SERVO mode on and set EEPROM[ 4095 ] to '1', // 'B99' with no parameter, or any parameter other than 'ON' diff --git a/cnc_ctrl_v1/GCode.cpp b/cnc_ctrl_v1/GCode.cpp index 7a5b50cf..826f7228 100644 --- a/cnc_ctrl_v1/GCode.cpp +++ b/cnc_ctrl_v1/GCode.cpp @@ -376,23 +376,23 @@ byte executeBcodeLine(const String& gcodeLine){ // updating the encoder steps even if no servo is connected. // Useful for testing on an arduino only (e.g. without motors). // The status of FAKE_SERVO mode is stored in EEPROM[ 4095 ] - // to persist between resets. Tthat byte is set to '1' when FAKE_SERVO + // to persist between resets. That byte is set to 'FAKE_SERVO_PERMITTED' when FAKE_SERVO // is on, '0' when off. settingsWipe(SETTINGS_RESTORE_ALL) clears the // EEPROM to '0', sothat stores '0' at EEPROM[ 4095 ] as well. if(gcodeLine.substring(0, 3) == "B99") { int letterO = gcodeLine.indexOf('O'); int letterN = gcodeLine.indexOf('N'); if ((letterO != -1) && (letterN != -1)) { - EEPROM[ FAKE_SERVO ] = 1; - FAKE_SERVO_STATE = 1; + EEPROM[ FAKE_SERVO ] = FAKE_SERVO_PERMITTED; + FAKE_SERVO_STATE = FAKE_SERVO_PERMITTED; } else { EEPROM[ FAKE_SERVO ] = 0; FAKE_SERVO_STATE = 0; } - if (FAKE_SERVO_STATE == 0) { - Serial.println(F("FAKE_SERVO off")); - } else { + if (FAKE_SERVO_STATE == FAKE_SERVO_PERMITTED) { Serial.println(F("FAKE_SERVO on")); + } else { + Serial.println(F("FAKE_SERVO off")); } return(STATUS_OK); } diff --git a/cnc_ctrl_v1/Motor.cpp b/cnc_ctrl_v1/Motor.cpp index a06b322a..a4e53a86 100644 --- a/cnc_ctrl_v1/Motor.cpp +++ b/cnc_ctrl_v1/Motor.cpp @@ -113,7 +113,7 @@ void Motor::write(int speed, bool force){ /* Sets motor speed from input. Speed = 0 is stopped, -255 is full reverse, 255 is full ahead. If force is true the motor attached state will be ignored */ - if ((_attachedState == 1 or force) and (FAKE_SERVO_STATE == 0)){ + if ((_attachedState == 1 or force) and (FAKE_SERVO_STATE != FAKE_SERVO_PERMITTED)){ speed = constrain(speed, -255, 255); _lastSpeed = speed; //saves speed for use in additive write bool forward = (speed > 0); diff --git a/cnc_ctrl_v1/cnc_ctrl_v1.ino b/cnc_ctrl_v1/cnc_ctrl_v1.ino index b4a1f1b2..4ba52ad3 100644 --- a/cnc_ctrl_v1/cnc_ctrl_v1.ino +++ b/cnc_ctrl_v1/cnc_ctrl_v1.ino @@ -67,12 +67,13 @@ void setup(){ Serial.println(F(" Detected")); sys.inchesToMMConversion = 1; sys.writeStepsToEEPROM = false; - FAKE_SERVO_STATE = EEPROM[ FAKE_SERVO ] & B00000001; - if (FAKE_SERVO_STATE == 0) { - Serial.println(F("FAKE_SERVO off")); - } else { - Serial.println(F("FAKE_SERVO on")); - } + FAKE_SERVO_STATE = EEPROM[ FAKE_SERVO ]; + if (FAKE_SERVO_STATE == FAKE_SERVO_PERMITTED) { // only this value is accepted + Serial.println(F("FAKE_SERVO on")); // to turn this on + } else { + Serial.println(F("FAKE_SERVO off")); // otherwise + EEPROM[ FAKE_SERVO ] = 0; // force it to the 'off' value + } settingsLoadFromEEprom(); sys.feedrate = sysSettings.maxFeed / 2.0; setupAxes(); From dc6c23f88b6735b9ce342b8c0d9bd10e2b82b1a9 Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Sat, 5 Oct 2019 23:08:45 -0700 Subject: [PATCH 04/21] remove characters within a comment Remove comment characters between parentheses. --- cnc_ctrl_v1/GCode.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/cnc_ctrl_v1/GCode.cpp b/cnc_ctrl_v1/GCode.cpp index 826f7228..dc8b86df 100644 --- a/cnc_ctrl_v1/GCode.cpp +++ b/cnc_ctrl_v1/GCode.cpp @@ -566,6 +566,9 @@ void sanitizeCommandString(String& cmdString){ cmdString.remove(pos, 1); if (line_flags & LINE_FLAG_COMMENT_PARENTHESES) { line_flags &= ~(LINE_FLAG_COMMENT_PARENTHESES); } } + else { + cmdString.remove(pos, 1); + } } else { if (cmdString[pos] < ' ') { From 2ed6fff3012341365a2f0cca4d3ac704d94e3eec Mon Sep 17 00:00:00 2001 From: tinker Date: Tue, 25 Feb 2020 10:29:43 -0800 Subject: [PATCH 05/21] gb0101010101-g2-arc-z-optional: Do not perform Z axis movement on G2 if Z is not specified in gcode line. Set Z1 and Z2 to NAN if not provided. Update arc() to deal with NAN Z. Make Z calculations happen the same way as X&Y before movementUpdate(). Add Z end move same as X & Y. --- cnc_ctrl_v1/GCode.cpp | 8 +++++- cnc_ctrl_v1/Motion.cpp | 62 ++++++++++++++++++++++++++---------------- 2 files changed, 46 insertions(+), 24 deletions(-) diff --git a/cnc_ctrl_v1/GCode.cpp b/cnc_ctrl_v1/GCode.cpp index dc8b86df..3e47c9d5 100644 --- a/cnc_ctrl_v1/GCode.cpp +++ b/cnc_ctrl_v1/GCode.cpp @@ -20,6 +20,7 @@ Copyright 2014-2017 Bar Smith*/ #include "Maslow.h" #include +#include "math.h" maslowRingBuffer incSerialBuffer; String readyCommandString = ""; //KRK why is this a global? @@ -779,7 +780,8 @@ void G2(const String& readString, int G2orG3){ float X2 = sys.inchesToMMConversion*extractGcodeValue(readString, 'X', X1/sys.inchesToMMConversion); float Y2 = sys.inchesToMMConversion*extractGcodeValue(readString, 'Y', Y1/sys.inchesToMMConversion); - float Z2 = sys.inchesToMMConversion*extractGcodeValue(readString, 'Z', Z1/sys.inchesToMMConversion); + // Read target Z position from gcode. If it is not specified then set it to NAN so it will not be used. + float Z2 = sys.inchesToMMConversion*extractGcodeValue(readString, 'Z', NAN); float I = sys.inchesToMMConversion*extractGcodeValue(readString, 'I', 0.0); float J = sys.inchesToMMConversion*extractGcodeValue(readString, 'J', 0.0); sys.feedrate = sys.inchesToMMConversion*extractGcodeValue(readString, 'F', sys.feedrate/sys.inchesToMMConversion); @@ -789,6 +791,10 @@ void G2(const String& readString, int G2orG3){ sys.feedrate = constrain(sys.feedrate, 1, sysSettings.maxFeed); //constrain the maximum feedrate, 35ipm = 900 mmpm + // If there is no target Z (Z2) then set Z1 to be NAN so it is not used. + if (isnan(Z2)) { + Z1 = Z2; + } if (G2orG3 == 2){ arc(X1, Y1, Z1, X2, Y2, Z2, centerX, centerY, sys.feedrate, CLOCKWISE); } diff --git a/cnc_ctrl_v1/Motion.cpp b/cnc_ctrl_v1/Motion.cpp index 358dc222..a0b80e7b 100644 --- a/cnc_ctrl_v1/Motion.cpp +++ b/cnc_ctrl_v1/Motion.cpp @@ -237,7 +237,7 @@ int arc(const float& X1, const float& Y1, const float& Z1, const float& X2, co */ - //compute geometry + // Compute geometry. float pi = 3.1415; float radius = sqrt( sq(centerX - X1) + sq(centerY - Y1) ); float circumference = 2.0*pi*radius; @@ -245,12 +245,18 @@ int arc(const float& X1, const float& Y1, const float& Z1, const float& X2, co float startingAngle = atan2(Y1 - centerY, X1 - centerX); float endingAngle = atan2(Y2 - centerY, X2 - centerX); - // compute chord height of arc + // Compute chord height of arc. float chordSquared = sqrt(sq(X2 - X1) + sq(Y2 - Y1)); float tau = sqrt( sq(radius) - (chordSquared/4.0)); float chordHeight = radius - tau; - //compute angle between lines + // Determine if Z axis will be used. + bool useZ = true; + if (isnan(Z1) || isnan(Z2) || !sysSettings.zAxisAttached) { + useZ = false; + } + + // Compute angle between lines. float theta = endingAngle - startingAngle; if (direction == COUNTERCLOCKWISE){ if (theta <= 0){ @@ -269,7 +275,10 @@ int arc(const float& X1, const float& Y1, const float& Z1, const float& X2, co // In either case, the gcode cut was essentially a straight line, so // Replace it with a G1 cut to the endpoint String gcodeSubstitution = "G1 X"; - gcodeSubstitution = gcodeSubstitution + String(X2 / sys.inchesToMMConversion, 3) + " Y" + String(Y2 / sys.inchesToMMConversion, 3) + " Z" + String(Z2 / sys.inchesToMMConversion, 3) + " "; + gcodeSubstitution += String(X2 / sys.inchesToMMConversion, 3) + " Y" + String(Y2 / sys.inchesToMMConversion, 3); + if (useZ) { + gcodeSubstitution += " Z" + String(Z2 / sys.inchesToMMConversion, 3) + " "; + } Serial.println("Large-radius arc replaced by straight line to improve accuracy: " + gcodeSubstitution); G1(gcodeSubstitution, 1); return 1; @@ -287,32 +296,37 @@ int arc(const float& X1, const float& Y1, const float& Z1, const float& X2, co long finalNumberOfSteps = arcLengthMM/stepSizeMM; float delayTime = LOOPINTERVAL; - float zFeedRate = calculateFeedrate(fabs(zDistanceToMoveInMM/finalNumberOfSteps), delayTime); - float zMaxFeed = sysSettings.maxZRPM * abs(zAxis.getPitch()); - // float zStepSizeMM = computeStepSize(zMaxFeed); - float zStepSizeMM = zDistanceToMoveInMM/finalNumberOfSteps; + float zFeedRate, zMaxFeed, zStepSizeMM; + + if (useZ) { + zFeedRate = calculateFeedrate(fabs(zDistanceToMoveInMM/finalNumberOfSteps), delayTime); + zMaxFeed = sysSettings.maxZRPM * abs(zAxis.getPitch()); + // zStepSizeMM = computeStepSize(zMaxFeed); + zStepSizeMM = zDistanceToMoveInMM/finalNumberOfSteps; - if (zFeedRate > zMaxFeed){ - zStepSizeMM = computeStepSize(zMaxFeed); - finalNumberOfSteps = fabs(zDistanceToMoveInMM/zStepSizeMM); - stepSizeMM = arcLengthMM/finalNumberOfSteps; - feedMMPerMin = calculateFeedrate(stepSizeMM, delayTime); + if (zFeedRate > zMaxFeed){ + // Recalculate all movement to fit within zMaxFeed parameter. + zStepSizeMM = computeStepSize(zMaxFeed); + finalNumberOfSteps = fabs(zDistanceToMoveInMM/zStepSizeMM); + stepSizeMM = arcLengthMM/finalNumberOfSteps; + feedMMPerMin = calculateFeedrate(stepSizeMM, delayTime); + } + + zStepSizeMM = zDistanceToMoveInMM/finalNumberOfSteps; } - - zStepSizeMM = zDistanceToMoveInMM/finalNumberOfSteps; - //Compute the starting position + // Compute the starting position. float angleNow = startingAngle; float degreeComplete = 0.0; float aChainLength; float bChainLength; - float zPosition = Z1 + zStepSizeMM; + float zPosition = Z1; - //attach the axes + // Attach the axes. leftAxis.attach(); rightAxis.attach(); - if (sysSettings.zAxisAttached) { + if (useZ) { zAxis.attach(); } @@ -335,17 +349,16 @@ int arc(const float& X1, const float& Y1, const float& Z1, const float& X2, co leftAxis.write(aChainLength); rightAxis.write(bChainLength); - if(sysSettings.zAxisAttached){ + if(useZ){ + zPosition += zStepSizeMM; zAxis.write(zPosition); } movementUpdate(); - // Run realtime commands + // Run real-time commands. execSystemRealtime(); if (sys.stop){return 1;} - numberOfStepsTaken++; - zPosition += zStepSizeMM; } } #if misloopDebug > 0 @@ -355,6 +368,9 @@ int arc(const float& X1, const float& Y1, const float& Z1, const float& X2, co kinematics.inverse(X2,Y2,&aChainLength,&bChainLength); leftAxis.endMove(aChainLength); rightAxis.endMove(bChainLength); + if (useZ) { + zAxis.endMove(Z2); + } sys.xPosition = X2; sys.yPosition = Y2; From 12af38cc34250622299e116b77ce2b6d8cda2df5 Mon Sep 17 00:00:00 2001 From: tinker Date: Fri, 15 May 2020 11:56:27 -0700 Subject: [PATCH 06/21] Add support for G2 & G3 commands that use radius R instead of I & J. --- cnc_ctrl_v1/GCode.cpp | 31 +++++++++++++++++++++++++++++++ 1 file changed, 31 insertions(+) diff --git a/cnc_ctrl_v1/GCode.cpp b/cnc_ctrl_v1/GCode.cpp index 3e47c9d5..a1de371b 100644 --- a/cnc_ctrl_v1/GCode.cpp +++ b/cnc_ctrl_v1/GCode.cpp @@ -782,6 +782,7 @@ void G2(const String& readString, int G2orG3){ float Y2 = sys.inchesToMMConversion*extractGcodeValue(readString, 'Y', Y1/sys.inchesToMMConversion); // Read target Z position from gcode. If it is not specified then set it to NAN so it will not be used. float Z2 = sys.inchesToMMConversion*extractGcodeValue(readString, 'Z', NAN); + float R = sys.inchesToMMConversion*extractGcodeValue(readString, 'R', NAN); float I = sys.inchesToMMConversion*extractGcodeValue(readString, 'I', 0.0); float J = sys.inchesToMMConversion*extractGcodeValue(readString, 'J', 0.0); sys.feedrate = sys.inchesToMMConversion*extractGcodeValue(readString, 'F', sys.feedrate/sys.inchesToMMConversion); @@ -789,6 +790,36 @@ void G2(const String& readString, int G2orG3){ float centerX = X1 + I; float centerY = Y1 + J; + // Calculate center point using radius R if it is provided. + if (!isnan(R) && R && (X2 != X1 || Y2 != Y1)) { + // e: clockwise -1, counterclockwise 1 + const float e = (G2orG3 == 2) ? -1 : 1, + // X and Y differences + dx = X2 - X1, + dy = Y2 - Y1, + // Linear distance between the points. + d = hypot(dx, dy), + // Distance to the arc pivot-point. + h = sqrt(sq(R) - sq(d * 0.5)), + // Point between the two points. + mx = (X1 + X2) * 0.5, + my = (Y1 + Y2) * 0.5, + // Slope of the perpendicular bisector. + sx = -dy / d, + sy = dx / d; + // Pivot-point of the arc. + centerX = mx + e * h * sx; + centerY = my + e * h * sy; + #if defined (verboseDebug) && verboseDebug > 0 + Serial.print(F("G0")); + Serial.print(G2orG3); + Serial.print(F(" Radius center: ")); + Serial.print(centerX); + Serial.print(F(",")); + Serial.println(centerY); + #endif + } + sys.feedrate = constrain(sys.feedrate, 1, sysSettings.maxFeed); //constrain the maximum feedrate, 35ipm = 900 mmpm // If there is no target Z (Z2) then set Z1 to be NAN so it is not used. From 408b4d93d5bfded7d5b2ed6d7ad567179c23d3c4 Mon Sep 17 00:00:00 2001 From: Ramon Arias Date: Mon, 18 May 2020 08:55:13 -0500 Subject: [PATCH 07/21] Z Axis limits I have made some small tweaks to the code to be able to set upper and lower limits for the z axis in order to prevent motors from forcing the Z Axis beyond its limits. --- cnc_ctrl_v1/Axis.cpp | 56 +++++++++++++++++++++++++++++++++++++--- cnc_ctrl_v1/GCode.cpp | 52 ++++++++++++++++++++++++++++++++++++- cnc_ctrl_v1/Settings.cpp | 2 ++ cnc_ctrl_v1/Settings.h | 2 ++ pull_request_template.md | 43 ++++++++++++++++++++++++++++++ 5 files changed, 151 insertions(+), 4 deletions(-) diff --git a/cnc_ctrl_v1/Axis.cpp b/cnc_ctrl_v1/Axis.cpp index c03f9fda..514712a4 100644 --- a/cnc_ctrl_v1/Axis.cpp +++ b/cnc_ctrl_v1/Axis.cpp @@ -44,9 +44,25 @@ void Axis::initializePID(const unsigned long& loopInterval){ } void Axis::write(const float& targetPosition){ - _timeLastMoved = millis(); - _pidSetpoint = targetPosition/ *_mmPerRotation; - return; + + // Check that the Z axis position is withing limits stecified in Settings + + if(_axisName == 'Z'){ + if(!isnan(sysSettings.zAxisUpperLimit) && targetPosition > sysSettings.zAxisUpperLimit){ + _pidSetpoint = sysSettings.zAxisUpperLimit/ *_mmPerRotation; + return; + } + + if(!isnan(sysSettings.zAxisLowerLimit) && targetPosition < sysSettings.zAxisLowerLimit){ + _pidSetpoint = sysSettings.zAxisLowerLimit/ *_mmPerRotation; + return; + } + } + + // update target position + _timeLastMoved = millis(); + _pidSetpoint = targetPosition/ *_mmPerRotation; + return; } float Axis::read(){ @@ -62,9 +78,27 @@ float Axis::setpoint(){ void Axis::set(const float& newAxisPosition){ + // update the zAxis upper and lower limits relative to the new axis position + + if(_axisName == 'Z'){ + if(!isnan(sysSettings.zAxisUpperLimit)){ + sysSettings.zAxisUpperLimit += newAxisPosition - read(); + } + + if(!isnan(sysSettings.zAxisLowerLimit)){ + sysSettings.zAxisLowerLimit += newAxisPosition - read(); + } + + if(!isnan(sysSettings.zAxisUpperLimit) || !isnan(sysSettings.zAxisLowerLimit)){ + settingsSaveToEEprom(); + } + } + //reset everything to the new value _pidSetpoint = newAxisPosition/ *_mmPerRotation; motorGearboxEncoder.encoder.write((newAxisPosition * *_encoderSteps)/ *_mmPerRotation); + + } @@ -225,11 +259,27 @@ void Axis::detachIfIdle(){ void Axis::endMove(const float& finalTarget){ + + // Check that the Z axis position is withing limits stecified in Settings + + if(_axisName == 'Z'){ + if(!isnan(sysSettings.zAxisUpperLimit) && finalTarget > sysSettings.zAxisUpperLimit){ + _pidSetpoint = sysSettings.zAxisUpperLimit/ *_mmPerRotation; + return; + } + + if(!isnan(sysSettings.zAxisLowerLimit) && finalTarget < sysSettings.zAxisLowerLimit){ + _pidSetpoint = sysSettings.zAxisLowerLimit/ *_mmPerRotation; + return; + } + } + _timeLastMoved = millis(); _pidSetpoint = finalTarget/ *_mmPerRotation; } + void Axis::stop(){ /* diff --git a/cnc_ctrl_v1/GCode.cpp b/cnc_ctrl_v1/GCode.cpp index 3e47c9d5..f1198efc 100644 --- a/cnc_ctrl_v1/GCode.cpp +++ b/cnc_ctrl_v1/GCode.cpp @@ -370,6 +370,56 @@ byte executeBcodeLine(const String& gcodeLine){ return STATUS_OK; } + if(gcodeLine.substring(0, 3) == "B17"){ + //The B17 sets the current Z position as Upper Limit for zAxis + + sysSettings.zAxisUpperLimit = zAxis.read(); + settingsSaveToEEprom(); + + Serial.print("Upper limit set to: "); + Serial.print(isnan(sysSettings.zAxisUpperLimit) ? " ": String(sysSettings.zAxisUpperLimit / sys.inchesToMMConversion)); + Serial.println(" "); + + + return STATUS_OK; + } + + if(gcodeLine.substring(0, 3) == "B18"){ + //The B18 sets the current Z position as Lower Limit for zAxis + + sysSettings.zAxisLowerLimit = zAxis.read(); + settingsSaveToEEprom(); + + Serial.print("Lower limit set to: "); + Serial.print(isnan(sysSettings.zAxisLowerLimit) ? " ": String(sysSettings.zAxisLowerLimit / sys.inchesToMMConversion)); + Serial.println(" "); + + return STATUS_OK; + } + if(gcodeLine.substring(0, 3) == "B19"){ + //The B19 clears limits for zAxis + + sysSettings.zAxisUpperLimit = NAN; + sysSettings.zAxisLowerLimit = NAN; + settingsSaveToEEprom(); + + Serial.println(F("Z Axis Limits Cleared")); + + + return STATUS_OK; + } + if(gcodeLine.substring(0, 3) == "B20"){ + //The B19 echoes limits for zAxis + + Serial.print(F("Z Axis Upper Limit: ")); + Serial.print(isnan(sysSettings.zAxisUpperLimit) ? String(" ") : String(sysSettings.zAxisUpperLimit / sys.inchesToMMConversion)); + Serial.print(F(" Lower Limit: ")); + Serial.print(isnan(sysSettings.zAxisLowerLimit) ? String(" "): String(sysSettings.zAxisLowerLimit / sys.inchesToMMConversion)); + Serial.println(" "); + + return STATUS_OK; + } + // Use 'B99 ON' to set FAKE_SERVO mode on, // 'B99' with no parameter, or any parameter other than 'ON' // turns FAKE_SERVO mode off. @@ -839,7 +889,7 @@ void G10(const String& readString){ zAxis.set(zgoto); zAxis.endMove(zgoto); - zAxis.attach(); + zAxis.attach(); } void G38(const String& readString) { diff --git a/cnc_ctrl_v1/Settings.cpp b/cnc_ctrl_v1/Settings.cpp index 065a016a..53dcce66 100644 --- a/cnc_ctrl_v1/Settings.cpp +++ b/cnc_ctrl_v1/Settings.cpp @@ -105,6 +105,8 @@ void settingsReset() { sysSettings.leftChainTolerance = 0.0; // float leftChainTolerance; sysSettings.rightChainTolerance = 0.0; // float rightChainTolerance; sysSettings.positionErrorLimit = 2.0; // float positionErrorLimit; + sysSettings.zAxisUpperLimit = NAN; // float zAxisUpperLimit + sysSettings.zAxisLowerLimit = NAN; // float zAxisLowerLimit sysSettings.eepromValidData = EEPROMVALIDDATA; // byte eepromValidData; } diff --git a/cnc_ctrl_v1/Settings.h b/cnc_ctrl_v1/Settings.h index cd18150b..9077eea9 100644 --- a/cnc_ctrl_v1/Settings.h +++ b/cnc_ctrl_v1/Settings.h @@ -81,6 +81,8 @@ typedef struct { // I think this is about ~128 bytes in size if I counted corre float leftChainTolerance; float rightChainTolerance; float positionErrorLimit; + float zAxisUpperLimit; // a safety feature to prevent motors from atempting to move the z axis beyong a user specified constraint. + float zAxisLowerLimit; byte eepromValidData; // This should always be last, that way if an error // happens in writing, it will not be written and we } settings_t; // will know to reset the settings diff --git a/pull_request_template.md b/pull_request_template.md index f3ccccb1..d55bd7de 100644 --- a/pull_request_template.md +++ b/pull_request_template.md @@ -5,13 +5,56 @@ Please let the community know some basic information about this pull request. ## What does this pull request do? Does it add a new feature or fix a bug? +This is a new feature. I have made some small tweaks to the code to be able to set upper and lower limits for the z axis in order to prevent motors from forcing the Z Axis beyond its limits. + +I have added two variables to settings +float zAxisUpperLimit +float zAxisLowerLimit + +I have created 4 "B" commands +B17 Sets the z axis upper limit to the current z axis position +B18 Sets the z axis lower limit to the current z axis position +B19 Clears z axis limits +B20 Echoes back z axis limits + ## Does this firmware change affect kinematics or any part of the calibration process? + +It does not affect Kinematics. And I have kept it apart from calibration as some users might want to adjust this on the fly as part of the regular use. + ### a) If so, does this change require recalibration? + +It does not require recalibration. However if the user wishes to establish some limits, he/she must set the limits using gcode commands B17 (Upper) and B18 (Lower) + ### b) If so, is there an option for user to opt-out of the change until ready for recalibration? If not, explain why this is not possible. + +By default this limits are set to NAN and will be ignored until specified. + ### c) Has the calibration model in gc/hc/wc been updated to agree with firmware change? + +No recalibration needed. I intend to update webcontrol to be able to set the limits within the user interface. Meanwhile to make use of it you can send gcode directly. + ### d) Has this PR been tested on actual machine and/or in fake servo mode (indicate which or both)? +It has been tested on an actual machine only + ## How can this pull request be tested? Please provide detailed steps about how to test this pull request. +1 - Move the Z axis to the highest point you with to set as a limit. +2 - Send a B17 gcode command. +3 - Move the Z axis to the lowest point you with to set as a limit. +4 - Send a B18 gcode command. +5 - Now attempt to move the Z axis beyond those limits. It should prevent you from exceeding the limits. +6 - Send the B20 gcode command and observe the limits echoed back +7 - Now attempt to reset the 0 location for the z axis +8 - Send the B20 gcode command and observe the limits echoed back, they should have been updated to account for the new 0 location +9 - Send the B19 gcode command to erase the limits +10 - Send the B20 gcode command and observe the limits echoes back, the should have been cleared. +11 - Now attempt to move the Z axis beyond the limits set in steps 1 and 2. It should allow you to move freely. (Careful not to exceed the physical limits of your machine) + Thanks for contributing! + + + + + From 71d5cc914166ace67c305a95d938db5f57d17dca Mon Sep 17 00:00:00 2001 From: Ramon Arias Date: Tue, 19 May 2020 17:33:54 -0500 Subject: [PATCH 08/21] Changes requested Made changes per requests during review --- cnc_ctrl_v1/Axis.cpp | 26 +- cnc_ctrl_v1/GCode.cpp | 80 ++-- cnc_ctrl_v1/Settings.cpp | 6 + cnc_ctrl_v1/Settings.h | 2 +- pull_request_template.md | 997 +++++++++++++++++++++++++++++++++++++-- 5 files changed, 1025 insertions(+), 86 deletions(-) diff --git a/cnc_ctrl_v1/Axis.cpp b/cnc_ctrl_v1/Axis.cpp index 514712a4..4e1127ca 100644 --- a/cnc_ctrl_v1/Axis.cpp +++ b/cnc_ctrl_v1/Axis.cpp @@ -45,14 +45,16 @@ void Axis::initializePID(const unsigned long& loopInterval){ void Axis::write(const float& targetPosition){ - // Check that the Z axis position is withing limits stecified in Settings + _timeLastMoved = millis(); + // Check that the Z axis position is within limits specified in Settings + if(_axisName == 'Z'){ if(!isnan(sysSettings.zAxisUpperLimit) && targetPosition > sysSettings.zAxisUpperLimit){ _pidSetpoint = sysSettings.zAxisUpperLimit/ *_mmPerRotation; return; } - + if(!isnan(sysSettings.zAxisLowerLimit) && targetPosition < sysSettings.zAxisLowerLimit){ _pidSetpoint = sysSettings.zAxisLowerLimit/ *_mmPerRotation; return; @@ -60,7 +62,6 @@ void Axis::write(const float& targetPosition){ } // update target position - _timeLastMoved = millis(); _pidSetpoint = targetPosition/ *_mmPerRotation; return; } @@ -79,7 +80,7 @@ float Axis::setpoint(){ void Axis::set(const float& newAxisPosition){ // update the zAxis upper and lower limits relative to the new axis position - + if(_axisName == 'Z'){ if(!isnan(sysSettings.zAxisUpperLimit)){ sysSettings.zAxisUpperLimit += newAxisPosition - read(); @@ -88,18 +89,15 @@ void Axis::set(const float& newAxisPosition){ if(!isnan(sysSettings.zAxisLowerLimit)){ sysSettings.zAxisLowerLimit += newAxisPosition - read(); } - + if(!isnan(sysSettings.zAxisUpperLimit) || !isnan(sysSettings.zAxisLowerLimit)){ settingsSaveToEEprom(); } } - + //reset everything to the new value _pidSetpoint = newAxisPosition/ *_mmPerRotation; - motorGearboxEncoder.encoder.write((newAxisPosition * *_encoderSteps)/ *_mmPerRotation); - - - + motorGearboxEncoder.encoder.write((newAxisPosition * *_encoderSteps)/ *_mmPerRotation); } long Axis::steps(){ @@ -259,8 +257,9 @@ void Axis::detachIfIdle(){ void Axis::endMove(const float& finalTarget){ - - // Check that the Z axis position is withing limits stecified in Settings + _timeLastMoved = millis(); + + // Check that the Z axis position is within limits specified in Settings if(_axisName == 'Z'){ if(!isnan(sysSettings.zAxisUpperLimit) && finalTarget > sysSettings.zAxisUpperLimit){ @@ -274,8 +273,7 @@ void Axis::endMove(const float& finalTarget){ } } - _timeLastMoved = millis(); - _pidSetpoint = finalTarget/ *_mmPerRotation; + _pidSetpoint = finalTarget/ *_mmPerRotation; } diff --git a/cnc_ctrl_v1/GCode.cpp b/cnc_ctrl_v1/GCode.cpp index f1198efc..4d5e072d 100644 --- a/cnc_ctrl_v1/GCode.cpp +++ b/cnc_ctrl_v1/GCode.cpp @@ -373,51 +373,63 @@ byte executeBcodeLine(const String& gcodeLine){ if(gcodeLine.substring(0, 3) == "B17"){ //The B17 sets the current Z position as Upper Limit for zAxis - sysSettings.zAxisUpperLimit = zAxis.read(); - settingsSaveToEEprom(); + if(!isnan(zAxis.read())){ - Serial.print("Upper limit set to: "); - Serial.print(isnan(sysSettings.zAxisUpperLimit) ? " ": String(sysSettings.zAxisUpperLimit / sys.inchesToMMConversion)); - Serial.println(" "); - + settingsStoreGlobalSetting(byte(43), zAxis.read()); + + Serial.print(F("Upper limit set to: ")); + Serial.println(isnan(sysSettings.zAxisUpperLimit) ? F(" "): String(sysSettings.zAxisUpperLimit / sys.inchesToMMConversion)); - return STATUS_OK; + return STATUS_OK; + + } else { + + Serial.println(F("Error setting limit")); + + return STATUS_GCODE_INVALID_TARGET; + + } } - if(gcodeLine.substring(0, 3) == "B18"){ - //The B18 sets the current Z position as Lower Limit for zAxis + if(gcodeLine.substring(0, 3) == "B18"){ + //The B18 sets the current Z position as Lower Limit for zAxis - sysSettings.zAxisLowerLimit = zAxis.read(); - settingsSaveToEEprom(); + if(!isnan(zAxis.read())){ + settingsStoreGlobalSetting(byte(44), zAxis.read()); - Serial.print("Lower limit set to: "); - Serial.print(isnan(sysSettings.zAxisLowerLimit) ? " ": String(sysSettings.zAxisLowerLimit / sys.inchesToMMConversion)); - Serial.println(" "); + Serial.print(F("Lower limit set to: ")); + Serial.println(isnan(sysSettings.zAxisLowerLimit) ? F(" "): String(sysSettings.zAxisLowerLimit / sys.inchesToMMConversion)); - return STATUS_OK; - } - if(gcodeLine.substring(0, 3) == "B19"){ - //The B19 clears limits for zAxis + return STATUS_OK; - sysSettings.zAxisUpperLimit = NAN; - sysSettings.zAxisLowerLimit = NAN; - settingsSaveToEEprom(); + } else { - Serial.println(F("Z Axis Limits Cleared")); - - - return STATUS_OK; + Serial.println(F("Error setting limit")); + + return STATUS_GCODE_INVALID_TARGET; + + } } - if(gcodeLine.substring(0, 3) == "B20"){ - //The B19 echoes limits for zAxis + if(gcodeLine.substring(0, 3) == "B19"){ + //The B19 clears limits for zAxis - Serial.print(F("Z Axis Upper Limit: ")); - Serial.print(isnan(sysSettings.zAxisUpperLimit) ? String(" ") : String(sysSettings.zAxisUpperLimit / sys.inchesToMMConversion)); - Serial.print(F(" Lower Limit: ")); - Serial.print(isnan(sysSettings.zAxisLowerLimit) ? String(" "): String(sysSettings.zAxisLowerLimit / sys.inchesToMMConversion)); - Serial.println(" "); + settingsStoreGlobalSetting(byte(43), NAN); + settingsStoreGlobalSetting(byte(44), NAN); + + + Serial.println(F("Z Axis Limits Cleared")); + + return STATUS_OK; + } + if(gcodeLine.substring(0, 3) == "B20"){ + //The B20 echoes limits for zAxis + + Serial.print(F("Z Axis Upper Limit: ")); + Serial.print(isnan(sysSettings.zAxisUpperLimit) ? F("NAN") : String(sysSettings.zAxisUpperLimit / sys.inchesToMMConversion)); + Serial.print(F(" Lower Limit: ")); + Serial.println(isnan(sysSettings.zAxisLowerLimit) ? F("NAN"): String(sysSettings.zAxisLowerLimit / sys.inchesToMMConversion)); - return STATUS_OK; + return STATUS_OK; } // Use 'B99 ON' to set FAKE_SERVO mode on, @@ -889,7 +901,7 @@ void G10(const String& readString){ zAxis.set(zgoto); zAxis.endMove(zgoto); - zAxis.attach(); + zAxis.attach(); } void G38(const String& readString) { diff --git a/cnc_ctrl_v1/Settings.cpp b/cnc_ctrl_v1/Settings.cpp index 53dcce66..b695fb61 100644 --- a/cnc_ctrl_v1/Settings.cpp +++ b/cnc_ctrl_v1/Settings.cpp @@ -412,6 +412,12 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ case 42: sysSettings.positionErrorLimit = value; break; + case 43: + sysSettings.zAxisUpperLimit = value; + break; + case 44: + sysSettings.zAxisLowerLimit = value; + break; default: return(STATUS_INVALID_STATEMENT); } diff --git a/cnc_ctrl_v1/Settings.h b/cnc_ctrl_v1/Settings.h index 9077eea9..503e4961 100644 --- a/cnc_ctrl_v1/Settings.h +++ b/cnc_ctrl_v1/Settings.h @@ -81,7 +81,7 @@ typedef struct { // I think this is about ~128 bytes in size if I counted corre float leftChainTolerance; float rightChainTolerance; float positionErrorLimit; - float zAxisUpperLimit; // a safety feature to prevent motors from atempting to move the z axis beyong a user specified constraint. + float zAxisUpperLimit; // A safety feature to prevent motors from attempting to move the z axis beyong a user specified constraint. float zAxisLowerLimit; byte eepromValidData; // This should always be last, that way if an error // happens in writing, it will not be written and we diff --git a/pull_request_template.md b/pull_request_template.md index d55bd7de..61bd2952 100644 --- a/pull_request_template.md +++ b/pull_request_template.md @@ -1,60 +1,983 @@ -Thanks for contributing to The Maslow Firmware! You rock. -Please let the community know some basic information about this pull request. -## What does this pull request do? -Does it add a new feature or fix a bug? -This is a new feature. I have made some small tweaks to the code to be able to set upper and lower limits for the z axis in order to prevent motors from forcing the Z Axis beyond its limits. -I have added two variables to settings -float zAxisUpperLimit -float zAxisLowerLimit -I have created 4 "B" commands -B17 Sets the z axis upper limit to the current z axis position -B18 Sets the z axis lower limit to the current z axis position -B19 Clears z axis limits -B20 Echoes back z axis limits + + + + + + + + + + + -## Does this firmware change affect kinematics or any part of the calibration process? -It does not affect Kinematics. And I have kept it apart from calibration as some users might want to adjust this on the fly as part of the regular use. -### a) If so, does this change require recalibration? + + + + + + + -It does not require recalibration. However if the user wishes to establish some limits, he/she must set the limits using gcode commands B17 (Upper) and B18 (Lower) -### b) If so, is there an option for user to opt-out of the change until ready for recalibration? If not, explain why this is not possible. + + + Firmware/pull_request_template.md at master · MaslowCNC/Firmware · GitHub + + + + -By default this limits are set to NAN and will be ignored until specified. + + -### c) Has the calibration model in gc/hc/wc been updated to agree with firmware change? + + -No recalibration needed. I intend to update webcontrol to be able to set the limits within the user interface. Meanwhile to make use of it you can send gcode directly. + -### d) Has this PR been tested on actual machine and/or in fake servo mode (indicate which or both)? -It has been tested on an actual machine only -## How can this pull request be tested? -Please provide detailed steps about how to test this pull request. + -1 - Move the Z axis to the highest point you with to set as a limit. -2 - Send a B17 gcode command. -3 - Move the Z axis to the lowest point you with to set as a limit. -4 - Send a B18 gcode command. -5 - Now attempt to move the Z axis beyond those limits. It should prevent you from exceeding the limits. -6 - Send the B20 gcode command and observe the limits echoed back -7 - Now attempt to reset the 0 location for the z axis -8 - Send the B20 gcode command and observe the limits echoed back, they should have been updated to account for the new 0 location -9 - Send the B19 gcode command to erase the limits -10 - Send the B20 gcode command and observe the limits echoes back, the should have been cleared. -11 - Now attempt to move the Z axis beyond the limits set in steps 1 and 2. It should allow you to move freely. (Careful not to exceed the physical limits of your machine) + -Thanks for contributing! + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ Skip to content + + + + + + + + + + + +
+ +
+ + + + +
+ + + +
+ + + + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
+
+ + + + + + + + Permalink + + + + + +
+ + +
+ + Branch: + master + + + + +
+ + + +
+
+
+ +
+ + Find file + + + Copy path + +
+
+ + +
+ + Find file + + + Copy path + +
+
+ + + + +
+
+ + @BarbourSmith + BarbourSmith + + Update wording + + + + 72014b7 + Aug 14, 2019 + +
+ +
+
+ + 1 contributor + + +
+ +

+ Users who have contributed to this file +

+
+ +
+
+
+
+ + + + + + +
+ +
+
+ + 17 lines (12 sloc) + + 819 Bytes +
+ +
+ +
+ Raw + Blame + History +
+ + +
+ + + + + + +
+
+
+ + + + +
+

Thanks for contributing to The Maslow Firmware! You rock.

+

Please let the community know some basic information about this pull request.

+

What does this pull request do?

+

Does it add a new feature or fix a bug?

+

Does this firmware change affect kinematics or any part of the calibration process?

+

a) If so, does this change require recalibration?

+

b) If so, is there an option for user to opt-out of the change until ready for recalibration? If not, explain why this is not possible.

+

c) Has the calibration model in gc/hc/wc been updated to agree with firmware change?

+

d) Has this PR been tested on actual machine and/or in fake servo mode (indicate which or both)?

+

How can this pull request be tested?

+

Please provide detailed steps about how to test this pull request.

+

Thanks for contributing!

+
+
+ +
+ + + +
+ + +
+ + +
+
+ + + + + +
+
+ +
+
+ + +
+ + + + + + +
+ + + You can’t perform that action at this time. +
+ + + + + + + + + + + + + + + + + + + + + From 91eefe007ab81a01812d69b288bf5422ea0b6e2f Mon Sep 17 00:00:00 2001 From: BarbourSmith Date: Wed, 20 May 2020 16:28:55 -0700 Subject: [PATCH 09/21] Revert pull pull request template to original version --- pull_request_template.md | 990 +-------------------------------------- 1 file changed, 12 insertions(+), 978 deletions(-) diff --git a/pull_request_template.md b/pull_request_template.md index 61bd2952..f3ccccb1 100644 --- a/pull_request_template.md +++ b/pull_request_template.md @@ -1,983 +1,17 @@ +Thanks for contributing to The Maslow Firmware! You rock. +Please let the community know some basic information about this pull request. +## What does this pull request do? +Does it add a new feature or fix a bug? +## Does this firmware change affect kinematics or any part of the calibration process? +### a) If so, does this change require recalibration? +### b) If so, is there an option for user to opt-out of the change until ready for recalibration? If not, explain why this is not possible. +### c) Has the calibration model in gc/hc/wc been updated to agree with firmware change? +### d) Has this PR been tested on actual machine and/or in fake servo mode (indicate which or both)? +## How can this pull request be tested? +Please provide detailed steps about how to test this pull request. - - - - - - - - - - - - - - - - - - - - - - - - - - Firmware/pull_request_template.md at master · MaslowCNC/Firmware · GitHub - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- Skip to content - - - - - - - - - - - -
- -
- - - - -
- - - -
- - - - - - - - - -
-
-
- - - - - - - - - - - - - - - - - - - - - - - - -
-
- - - - - - - - Permalink - - - - - -
- - -
- - Branch: - master - - - - -
- - - -
-
-
- -
- - Find file - - - Copy path - -
-
- - -
- - Find file - - - Copy path - -
-
- - - - -
-
- - @BarbourSmith - BarbourSmith - - Update wording - - - - 72014b7 - Aug 14, 2019 - -
- -
-
- - 1 contributor - - -
- -

- Users who have contributed to this file -

-
- -
-
-
-
- - - - - - -
- -
-
- - 17 lines (12 sloc) - - 819 Bytes -
- -
- -
- Raw - Blame - History -
- - -
- - - - - - -
-
-
- - - - -
-

Thanks for contributing to The Maslow Firmware! You rock.

-

Please let the community know some basic information about this pull request.

-

What does this pull request do?

-

Does it add a new feature or fix a bug?

-

Does this firmware change affect kinematics or any part of the calibration process?

-

a) If so, does this change require recalibration?

-

b) If so, is there an option for user to opt-out of the change until ready for recalibration? If not, explain why this is not possible.

-

c) Has the calibration model in gc/hc/wc been updated to agree with firmware change?

-

d) Has this PR been tested on actual machine and/or in fake servo mode (indicate which or both)?

-

How can this pull request be tested?

-

Please provide detailed steps about how to test this pull request.

-

Thanks for contributing!

-
-
- -
- - - -
- - -
- - -
-
- - - - - -
-
- -
-
- - -
- - - - - - -
- - - You can’t perform that action at this time. -
- - - - - - - - - - - - - - - - - - - - - - +Thanks for contributing! From 35cce7d99c75517e2593cd383824480a468851a2 Mon Sep 17 00:00:00 2001 From: Orob-Maslow <59507087+Orob-Maslow@users.noreply.github.com> Date: Wed, 9 Sep 2020 13:18:24 -0500 Subject: [PATCH 10/21] Spindle pwm pin 45 added Added $60 min speed and $61 spindle max speed for pwm output Added S functionality to set spindle speed. pwm setting is scaled from 0 to max with min being set as the start speed. --- cnc_ctrl_v1/Config.h | 9 +++++++ cnc_ctrl_v1/GCode.cpp | 17 ++++++++++++ cnc_ctrl_v1/GCode.h | 1 + cnc_ctrl_v1/Settings.cpp | 6 +++++ cnc_ctrl_v1/Settings.h | 6 ++++- cnc_ctrl_v1/Spindle.cpp | 58 +++++++++++++++++++++++++++++++++++++++- cnc_ctrl_v1/Spindle.h | 11 ++++++++ cnc_ctrl_v1/System.cpp | 7 +++++ cnc_ctrl_v1/System.h | 1 + 9 files changed, 114 insertions(+), 2 deletions(-) diff --git a/cnc_ctrl_v1/Config.h b/cnc_ctrl_v1/Config.h index 668d76f9..ce14e8b3 100644 --- a/cnc_ctrl_v1/Config.h +++ b/cnc_ctrl_v1/Config.h @@ -20,12 +20,17 @@ // Debugging Options #define verboseDebug 0 // set to 0 for no debug messages, 1 for single-line messages, 2 to also output ring buffer contents + #define misloopDebug 0 // set to 1 for a warning every time the movement loop fails // to complete before being interrupted, helpful for loop // LOOPINTERVAL tuning + #define KINEMATICSDBG 0 // set to 1 for additional kinematics debug messaging +#define SPINDLE_SPEED 1 // set to 1 for pwm spindle speed control + #define FAKE_SERVO_PERMITTED 42 // store this value + #define FAKE_SERVO 4095 // store the state of FAKE_SERVO in EEPROM[ 4095 ] to preserve // the state of FAKE_SERVO mode over resets. // Use 'B99 ON' to turn FAKE_SERVO mode on and set EEPROM[ 4095 ] to '1', @@ -55,12 +60,15 @@ // Serial variables #define INCBUFFERLENGTH 128 // The number of bytes(characters) allocated to the // incoming buffer. + #define EXPGCODELINE 60 // Maximum expected Gcode line length in characters // including line ending character(s). Assumes // client will not send more than this. Ground // Control is currently set to 60. NIST spec allows // 256. This value must be <= INCBUFFERLENGTH + #define MAXBUFFERLINES 4 // The maximum number of lines allowed in the buffer + #define POSITIONTIMEOUT 200 // The minimum number of milliseconds between // position reports sent to Ground Control. This // cannot be larger than the connection timout in @@ -72,6 +80,7 @@ #define CMD_RESET 0x18 // ctrl-x., if received the program should do a soft reset // if received the program should do a soft reset + #define CMD_RESET2 '`' // alternate char because GC won't use control characters in a macro #endif diff --git a/cnc_ctrl_v1/GCode.cpp b/cnc_ctrl_v1/GCode.cpp index 19017669..338d4344 100644 --- a/cnc_ctrl_v1/GCode.cpp +++ b/cnc_ctrl_v1/GCode.cpp @@ -398,7 +398,17 @@ byte executeBcodeLine(const String& gcodeLine){ } return STATUS_INVALID_STATEMENT; } +void executeScodeLine(const String& gcodeLine){ + /* executes a single line of gcode beginning with the character 'S' for spindle speed */ + int sNumber = extractGcodeValue(gcodeLine,'S',-1); + if (sNumber == -1){ + sNumber = sys.SpindleSpeed; + } + if (setSpindleSpeed(sNumber)){ + sys.SpindleSpeed = sNumber; + } +} void executeGcodeLine(const String& gcodeLine){ /* @@ -660,6 +670,13 @@ byte interpretCommandString(String& cmdString){ Serial.println(gcodeLine); executeMcodeLine(gcodeLine); } + else if(gcodeLine[0] == 'S'){ + #if defined (verboseDebug) && verboseDebug > 0 + Serial.print(F("iCS executing S code: ")); + #endif + Serial.println(gcodeLine); + executeScodeLine(gcodeLine); + } else { #if defined (verboseDebug) && verboseDebug > 0 Serial.print(F("iCS executing G code: ")); diff --git a/cnc_ctrl_v1/GCode.h b/cnc_ctrl_v1/GCode.h index 880a601d..08c037c4 100644 --- a/cnc_ctrl_v1/GCode.h +++ b/cnc_ctrl_v1/GCode.h @@ -34,6 +34,7 @@ float extractGcodeValue(const String&, char, const float&); byte executeBcodeLine(const String&); void executeGcodeLine(const String&); void executeMcodeLine(const String&); +void executeScodeLine(const String&); void executeOtherCodeLine(const String&); int findNextGM(const String&, const int&); void sanitizeCommandString(String&); diff --git a/cnc_ctrl_v1/Settings.cpp b/cnc_ctrl_v1/Settings.cpp index c92fd9b3..5b60c0b4 100644 --- a/cnc_ctrl_v1/Settings.cpp +++ b/cnc_ctrl_v1/Settings.cpp @@ -109,6 +109,8 @@ void settingsReset() { sysSettings.reserved2 = 0.0; sysSettings.chainElongationFactor = 8.1E-6; // m/m/N sysSettings.sledWeight = 11.6*9.8; // Newtons. For a sled with one ring kit, one Rigid 2200 router and two 2.35kg bricks on a 5/8" thick mdf 18" diameter base. + sysSettings.spindleMin = 4000; + sysSettings.spindleMax = 24000; sysSettings.eepromValidData = EEPROMVALIDDATA; // byte eepromValidData; } @@ -429,6 +431,10 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ sysSettings.sledWeight = value; kinematics.init();; break; + case 60: + sysSettings.spindleMin = value; + case 61: + sysSettings.spindleMax = value; default: return(STATUS_INVALID_STATEMENT); } diff --git a/cnc_ctrl_v1/Settings.h b/cnc_ctrl_v1/Settings.h index 29fb3944..be792b35 100644 --- a/cnc_ctrl_v1/Settings.h +++ b/cnc_ctrl_v1/Settings.h @@ -36,7 +36,9 @@ enum SpindleAutomationType { NONE, SERVO, RELAY_ACTIVE_HIGH, - RELAY_ACTIVE_LOW }; + RELAY_ACTIVE_LOW, + SPEED_CONTROL_RELAY_ACTIVE_HIGH, + SPEED_CONTROL_RELAY_ACTIVE_LOW}; typedef struct { // I think this is about ~128 bytes in size if I counted correctly float machineWidth; @@ -85,6 +87,8 @@ typedef struct { // I think this is about ~128 bytes in size if I counted corre float reserved2; float chainElongationFactor; // m/m/N. This is the ratio of chain length increase due to chain tension. typically 8x10E-6; // m/m/N float sledWeight; // Newtons. simply multiply kg by 9.8 or pounds by 2.2*9.8 + int spindleMin; //added for pwm spindle control + int spindleMax; //added for pwm spindle control byte eepromValidData; // This should always be last, that way if an error // happens in writing, it will not be written and we } settings_t; // will know to reset the settings diff --git a/cnc_ctrl_v1/Spindle.cpp b/cnc_ctrl_v1/Spindle.cpp index 853a1d64..c7b2c0f0 100644 --- a/cnc_ctrl_v1/Spindle.cpp +++ b/cnc_ctrl_v1/Spindle.cpp @@ -20,7 +20,9 @@ // the variables SpindlePowerControlPin and LaserPowerPin are assigned in setupAxes() in System.cpp // Globals for Spindle control, both poorly named +#ifndef SPINDLE_SPEED Servo myservo; // create servo object to control a servo +#endif void setSpindlePower(bool powerState) { /* @@ -41,6 +43,7 @@ void setSpindlePower(bool powerState) { Serial.print(F("Spindle automation type ")); Serial.print(spindleAutomateType); #endif + #ifndef SPINDLE_SPEED if (spindleAutomateType == SERVO) { // use a servo to control a standard wall switch #if defined (verboseDebug) && verboseDebug > 1 Serial.print(F(" with servo (idle=")); @@ -70,7 +73,42 @@ void setSpindlePower(bool powerState) { if(sys.stop){return;} myservo.detach(); // stop servo control } - else if (spindleAutomateType == RELAY_ACTIVE_HIGH) { + #endif + if (spindleAutomateType == SPEED_CONTROL_RELAY_ACTIVE_HIGH){ + #if defined (verboseDebug) && verboseDebug > 1 + Serial.print(F(" as digital power and pwm speed control, active high")); + #endif + pinMode(SpindlePowerControlPin, OUTPUT); + if (powerState) { // turn on spindle + Serial.println(F("Turning Spindle On")); + digitalWrite(SpindlePowerControlPin, HIGH); + Serial.println(F("Adjusting Spindle Speed to Minimum")); + setSpindleSpeed(sysSettings.spindleMin); + } + else { // turn off spindle + Serial.println(F("Turning Spindle Off")); + digitalWrite(SpindlePowerControlPin, LOW); + digitalWrite(SpindleSpeedControlPin, LOW); + } + } + if (spindleAutomateType == SPEED_CONTROL_RELAY_ACTIVE_LOW){ + #if defined (verboseDebug) && verboseDebug > 1 + Serial.print(F(" as digital power and pwm speed control, active low")); + #endif + pinMode(SpindlePowerControlPin, OUTPUT); + if (powerState) { // turn on spindle + Serial.println(F("Turning Spindle On")); + digitalWrite(SpindlePowerControlPin, LOW); + Serial.println(F("Adjusting Spindle Speed to Minimum")); + setSpindleSpeed(sysSettings.spindleMin); + } + else { // turn off spindle + Serial.println(F("Turning Spindle Off")); + digitalWrite(SpindlePowerControlPin, HIGH); + digitalWrite(SpindleSpeedControlPin, LOW); + } + } + if (spindleAutomateType == RELAY_ACTIVE_HIGH) { #if defined (verboseDebug) && verboseDebug > 1 Serial.print(F(" as digital output, active high")); #endif @@ -103,6 +141,24 @@ void setSpindlePower(bool powerState) { } } +int setSpindleSpeed(int spindleSpeed){ + // map 0-255 min spindle speed to max spindle speed + // output 0-255 + if (spindleSpeed < sysSettings.spindleMin){ + spindleSpeed = sysSettings.spindleMin; + } + if (spindleSpeed > sysSettings.spindleMax){ + spindleSpeed = sysSettings.spindleMax; + } + long spd = map (spindleSpeed, 0, sysSettings.spindleMax, 0, 255); + analogWrite(SpindleSpeedControlPin,spd); + return(1); + //for (i=0;i 0) pinMode(aux3,INPUT); if (aux5 > 0) pinMode(aux5,INPUT); if (aux6 > 0) pinMode(aux6,INPUT); + #ifndef SPINDLE_SPEED if (aux7 > 0) pinMode(aux7,INPUT); + #endif if (aux8 > 0) pinMode(aux8,INPUT); if (aux9 > 0) pinMode(aux9,INPUT); } diff --git a/cnc_ctrl_v1/System.h b/cnc_ctrl_v1/System.h index 25bea189..3f0d88b7 100644 --- a/cnc_ctrl_v1/System.h +++ b/cnc_ctrl_v1/System.h @@ -60,6 +60,7 @@ typedef struct { bool useRelativeUnits; // unsigned long lastSerialRcvd; // The millis of the last rcvd serial command, used by watchdo int lastGCommand; //Stores the value of the last command run eg: G01 -> 1 + int SpindleSpeed; // store the current spindle speed -> 4000 int lastTool; //Stores the value of the last tool number eg: T4 -> 4 int nextTool; //Stores the value of the next tool number eg: T4 -> 4 float inchesToMMConversion; //Used to track whether to convert from inches, can probably be done in a way that doesn't require RAM From 1811d70eb6b7d8b8ee083f89881dc7e5f0fee162 Mon Sep 17 00:00:00 2001 From: Orob-Maslow <59507087+Orob-Maslow@users.noreply.github.com> Date: Sat, 12 Sep 2020 21:55:12 -0500 Subject: [PATCH 11/21] Update Settings.cpp default is for pwm pin to be active and for relay to be active high --- cnc_ctrl_v1/Settings.cpp | 15 ++------------- 1 file changed, 2 insertions(+), 13 deletions(-) diff --git a/cnc_ctrl_v1/Settings.cpp b/cnc_ctrl_v1/Settings.cpp index fd66cf22..c5dada18 100644 --- a/cnc_ctrl_v1/Settings.cpp +++ b/cnc_ctrl_v1/Settings.cpp @@ -79,7 +79,7 @@ void settingsReset() { sysSettings.distPerRot = 63.5; // float distPerRot; sysSettings.maxFeed = 700; // int maxFeed; sysSettings.zAxisAttached = true; // zAxisAttached; - sysSettings.spindleAutomateType = NONE; // bool spindleAutomate; + sysSettings.spindleAutomateType = SPEED_CONTROL_RELAY_ACTIVE_HIGH; // bool spindleAutomate; sysSettings.maxZRPM = 12.60; // float maxZRPM; sysSettings.zDistPerRot = 3.17; // float zDistPerRot; sysSettings.zEncoderSteps = 7560.0; // float zEncoderSteps; @@ -111,8 +111,6 @@ void settingsReset() { sysSettings.sledWeight = 11.6*9.8; // Newtons. For a sled with one ring kit, one Rigid 2200 router and two 2.35kg bricks on a 5/8" thick mdf 18" diameter base. sysSettings.spindleMin = 4000; sysSettings.spindleMax = 24000; - sysSettings.zAxisUpperLimit = NAN; // float zAxisUpperLimit - sysSettings.zAxisLowerLimit = NAN; // float zAxisLowerLimit sysSettings.eepromValidData = EEPROMVALIDDATA; // byte eepromValidData; } @@ -390,7 +388,6 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ break; case 37: sysSettings.chainSagCorrection = value; - kinematics.init(); break; case 38: settingsSaveStepstoEEprom(); @@ -434,18 +431,10 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ sysSettings.sledWeight = value; kinematics.init();; break; - case 47: - sysSettings.zAxisUpperLimit = value; - break; - case 48: - sysSettings.zAxisLowerLimit = value; - break; case 60: sysSettings.spindleMin = value; - break; case 61: - sysSettings.spindleMax = value; - break; + sysSettings.spindleMax = value; default: return(STATUS_INVALID_STATEMENT); } From aae7240335eccf5a906c6b9b7cd530694b2db21e Mon Sep 17 00:00:00 2001 From: Orob-Maslow <59507087+Orob-Maslow@users.noreply.github.com> Date: Sun, 13 Sep 2020 17:59:50 -0500 Subject: [PATCH 12/21] Chain length error fix added original chain length to extend chain routing and removed axis detach --- cnc_ctrl_v1/System.cpp | 9 +++------ 1 file changed, 3 insertions(+), 6 deletions(-) diff --git a/cnc_ctrl_v1/System.cpp b/cnc_ctrl_v1/System.cpp index b088cf60..a260a059 100644 --- a/cnc_ctrl_v1/System.cpp +++ b/cnc_ctrl_v1/System.cpp @@ -47,20 +47,16 @@ void calibrateChainLengths(String gcodeLine){ Serial.println(F("Measuring out left chain")); singleAxisMove(&leftAxis, sysSettings.originalChainLength, (sysSettings.maxFeed * .9)); - Serial.print(leftAxis.read()); + Serial.print(sysSettings.originalChainLength); Serial.println(F("mm")); - - leftAxis.detach(); } else if(extractGcodeValue(gcodeLine, 'R', 0)){ //measure out the right chain Serial.println(F("Measuring out right chain")); singleAxisMove(&rightAxis, sysSettings.originalChainLength, (sysSettings.maxFeed * .9)); - Serial.print(rightAxis.read()); + Serial.print(sysSettings.originalChainLength); Serial.println(F("mm")); - - rightAxis.detach(); } } @@ -376,6 +372,7 @@ void setupAxes(){ if (aux6 > 0) pinMode(aux6,INPUT); #ifndef SPINDLE_SPEED if (aux7 > 0) pinMode(aux7,INPUT); + if (aux7 > 0) pinMode(aux7,INPUT); #endif if (aux8 > 0) pinMode(aux8,INPUT); if (aux9 > 0) pinMode(aux9,INPUT); From c073f522bd243ee08181804e0f71df0cdddb7dc6 Mon Sep 17 00:00:00 2001 From: Orob-Maslow <59507087+Orob-Maslow@users.noreply.github.com> Date: Sun, 13 Sep 2020 18:01:37 -0500 Subject: [PATCH 13/21] Update System.cpp --- cnc_ctrl_v1/System.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cnc_ctrl_v1/System.cpp b/cnc_ctrl_v1/System.cpp index b088cf60..3612c352 100644 --- a/cnc_ctrl_v1/System.cpp +++ b/cnc_ctrl_v1/System.cpp @@ -375,7 +375,7 @@ void setupAxes(){ if (aux5 > 0) pinMode(aux5,INPUT); if (aux6 > 0) pinMode(aux6,INPUT); #ifndef SPINDLE_SPEED - if (aux7 > 0) pinMode(aux7,INPUT); + if (aux7 > 0) pinMode(aux7,INPUT); #endif if (aux8 > 0) pinMode(aux8,INPUT); if (aux9 > 0) pinMode(aux9,INPUT); From d408d1357400fc7be4a07f87489fc5759bfa1089 Mon Sep 17 00:00:00 2001 From: Orob-Maslow <59507087+Orob-Maslow@users.noreply.github.com> Date: Tue, 15 Sep 2020 12:31:49 -0500 Subject: [PATCH 14/21] Update cnc_ctrl_v1.ino --- cnc_ctrl_v1/cnc_ctrl_v1.ino | 3 --- 1 file changed, 3 deletions(-) diff --git a/cnc_ctrl_v1/cnc_ctrl_v1.ino b/cnc_ctrl_v1/cnc_ctrl_v1.ino index a4a5d269..2528f2d5 100644 --- a/cnc_ctrl_v1/cnc_ctrl_v1.ino +++ b/cnc_ctrl_v1/cnc_ctrl_v1.ino @@ -49,9 +49,6 @@ byte systemRtExecAlarm; // Define global flag for FAKE_SERVO state int FAKE_SERVO_STATE = 0; -// Define global flag for FAKE_SERVO state -int FAKE_SERVO_STATE = 0; - // Define axes, it might be tighter to define these within the sys struct Axis leftAxis; Axis rightAxis; From d6eb50c1b7986a45c17d58bb56df4f1f8c2edfe5 Mon Sep 17 00:00:00 2001 From: Orob-Maslow <59507087+Orob-Maslow@users.noreply.github.com> Date: Wed, 16 Sep 2020 06:47:04 -0500 Subject: [PATCH 15/21] Spindle pwm pin only works when m3/m4 spindle is ON added sys.SpindleSpeed and sys.SpindlePower that are set in spindle.cpp when the relay is toggled and then checked when an S command is received. Verbose dtails are given when an S command or $60, $61 command are given to change the spindle max, min, or speed setting --- cnc_ctrl_v1/GCode.cpp | 8 ++- cnc_ctrl_v1/GCode.h | 4 +- cnc_ctrl_v1/Settings.cpp | 108 +++++++++++++++++++----------------- cnc_ctrl_v1/Spindle.cpp | 72 ++++++++++++++++++------ cnc_ctrl_v1/Spindle.h | 7 ++- cnc_ctrl_v1/System.cpp | 12 ++-- cnc_ctrl_v1/System.h | 4 +- cnc_ctrl_v1/cnc_ctrl_v1.ino | 2 +- 8 files changed, 135 insertions(+), 82 deletions(-) diff --git a/cnc_ctrl_v1/GCode.cpp b/cnc_ctrl_v1/GCode.cpp index c97ca459..497d2da1 100644 --- a/cnc_ctrl_v1/GCode.cpp +++ b/cnc_ctrl_v1/GCode.cpp @@ -470,8 +470,12 @@ void executeScodeLine(const String& gcodeLine){ if (sNumber == -1){ sNumber = sys.SpindleSpeed; } - if (setSpindleSpeed(sNumber)){ - sys.SpindleSpeed = sNumber; + if (sys.SpindlePower){ + if (setSpindleSpeed(sNumber)){ + sys.SpindleSpeed = sNumber; + } + }else{ + Serial.println("spindle speed not set when spindle is off"); } } void executeGcodeLine(const String& gcodeLine){ diff --git a/cnc_ctrl_v1/GCode.h b/cnc_ctrl_v1/GCode.h index 08c037c4..e504d76a 100644 --- a/cnc_ctrl_v1/GCode.h +++ b/cnc_ctrl_v1/GCode.h @@ -25,6 +25,8 @@ Copyright 2014-2017 Bar Smith*/ extern String readyCommandString; //next command queued up and ready to send extern String gcodeLine; //The next individual line of gcode (for example G91 G01 X19 would be run as two lines) +extern int SpindlePowerControlPin; + void initGCode(); void gcodeExecuteLoop(); void readSerialCommands(); @@ -45,7 +47,7 @@ void G4(const String&); void G10(const String&); void G38(const String&); void setInchesToMillimetersConversion(float); -extern int SpindlePowerControlPin; + extern int ProbePin; extern int FAKE_SERVO_STATE; diff --git a/cnc_ctrl_v1/Settings.cpp b/cnc_ctrl_v1/Settings.cpp index c5dada18..f3ae079d 100644 --- a/cnc_ctrl_v1/Settings.cpp +++ b/cnc_ctrl_v1/Settings.cpp @@ -63,56 +63,56 @@ void settingsReset() { so that if a value is not changed by a user or is not used, it doesn't need to be updated here. */ - sysSettings.machineWidth = 2438.4; // float machineWidth; - sysSettings.machineHeight = 1219.2; // float machineHeight; - sysSettings.distBetweenMotors = 2978.4; // float distBetweenMotors; - sysSettings.motorOffsetY = 463.0; // float motorOffsetY; - sysSettings.sledWidth = 310.0; // float sledWidth; - sysSettings.sledHeight = 139.0; // float sledHeight; - sysSettings.sledCG = 79.0; // float sledCG; - sysSettings.kinematicsType = 1; // byte kinematicsType; - sysSettings.rotationDiskRadius = 250.0; // float rotationDiskRadius; - sysSettings.axisDetachTime = 2000; // int axisDetachTime; - sysSettings.chainLength = 3360; // int maximum length of chain; - sysSettings.originalChainLength = 1651; // int originalChainLength; - sysSettings.encoderSteps = 8113.73; // float encoderSteps; - sysSettings.distPerRot = 63.5; // float distPerRot; - sysSettings.maxFeed = 700; // int maxFeed; - sysSettings.zAxisAttached = true; // zAxisAttached; - sysSettings.spindleAutomateType = SPEED_CONTROL_RELAY_ACTIVE_HIGH; // bool spindleAutomate; - sysSettings.maxZRPM = 12.60; // float maxZRPM; - sysSettings.zDistPerRot = 3.17; // float zDistPerRot; - sysSettings.zEncoderSteps = 7560.0; // float zEncoderSteps; - sysSettings.KpPos = 1300.0; // float KpPos; - sysSettings.KiPos = 0.0; // float KiPos; - sysSettings.KdPos = 34.0; // float KdPos; - sysSettings.propWeightPos = 1.0; // float propWeightPos; - sysSettings.KpV = 5.0; // float KpV; - sysSettings.KiV = 0.0; // float KiV; - sysSettings.KdV = 0.28; // float KdV; - sysSettings.propWeightV = 1.0; // float propWeightV; - sysSettings.zKdPos = 1300.0; // float zKpPos; - sysSettings.zKiPos = 0.0; // float zKiPos; - sysSettings.zKdPos = 34.0; // float zKdPos; - sysSettings.zPropWeightPos = 1.0; // float zPropWeightPos; - sysSettings.zKpV = 5.0; // float zKpV; - sysSettings.zKiV = 0.0; // float zKiV; - sysSettings.zKdV = 0.28; // float zKdV; - sysSettings.zPropWeightV = 1.0; // float zPropWeightV; - sysSettings.chainSagCorrection = 0.0; // float chainSagCorrection; - sysSettings.chainOverSprocket = 1; // byte chainOverSprocket; - sysSettings.fPWM = 3; // byte fPWM; - sysSettings.leftChainTolerance = 0.0; // float leftChainTolerance; - sysSettings.rightChainTolerance = 0.0; // float rightChainTolerance; - sysSettings.positionErrorLimit = 2.0; // float positionErrorLimit; - sysSettings.reserved1 = 0.0; - sysSettings.reserved2 = 0.0; - sysSettings.chainElongationFactor = 8.1E-6; // m/m/N - sysSettings.sledWeight = 11.6*9.8; // Newtons. For a sled with one ring kit, one Rigid 2200 router and two 2.35kg bricks on a 5/8" thick mdf 18" diameter base. - sysSettings.spindleMin = 4000; - sysSettings.spindleMax = 24000; - sysSettings.eepromValidData = EEPROMVALIDDATA; // byte eepromValidData; -} + sysSettings.machineWidth = 2438.4; // float machineWidth; 4 + sysSettings.machineHeight = 1219.2; // float machineHeight; 4 + sysSettings.distBetweenMotors = 2978.4; // float distBetweenMotors; 4 + sysSettings.motorOffsetY = 463.0; // float motorOffsetY; 4 + sysSettings.sledWidth = 310.0; // float sledWidth; 4 + sysSettings.sledHeight = 139.0; // float sledHeight; 4 + sysSettings.sledCG = 79.0; // float sledCG; 4 - + sysSettings.kinematicsType = 1; // byte kinematicsType; 1 + sysSettings.rotationDiskRadius = 250.0; // float rotationDiskRadius; 1 + sysSettings.axisDetachTime = 2000; // int axisDetachTime; 2 + sysSettings.chainLength = 3360; // int maximum length of chain; 2 + sysSettings.originalChainLength = 1651; // int originalChainLength; 2 + sysSettings.encoderSteps = 8113.73; // float encoderSteps; 4 + sysSettings.distPerRot = 63.5; // float distPerRot; 4 + sysSettings.maxFeed = 700; // int maxFeed; 2 + sysSettings.zAxisAttached = true; // zAxisAttached; 1 + sysSettings.spindleAutomateType = SPEED_CONTROL_RELAY_ACTIVE_HIGH; // 1 bool spindleAutomate; + sysSettings.maxZRPM = 12.60; // float maxZRPM; 4 + sysSettings.zDistPerRot = 3.17; // float zDistPerRot; 4 + sysSettings.zEncoderSteps = 7560.0; // float zEncoderSteps; 4 + sysSettings.KpPos = 1300.0; // float KpPos; 4 - + sysSettings.KiPos = 0.0; // float KiPos; 4 + sysSettings.KdPos = 34.0; // float KdPos; 4 + sysSettings.propWeightPos = 1.0; // float propWeightPos; 4 + sysSettings.KpV = 5.0; // float KpV; 4 + sysSettings.KiV = 0.0; // float KiV; 4 + sysSettings.KdV = 0.28; // float KdV; 4 - + sysSettings.propWeightV = 1.0; // float propWeightV; 4 + sysSettings.zKdPos = 1300.0; // float zKpPos; 4 + sysSettings.zKiPos = 0.0; // float zKiPos; 4 + sysSettings.zKdPos = 34.0; // float zKdPos; 4 + sysSettings.zPropWeightPos = 1.0; // float zPropWeightPos; 4 + sysSettings.zKpV = 5.0; // float zKpV; 4 - + sysSettings.zKiV = 0.0; // float zKiV; 4 + sysSettings.zKdV = 0.28; // float zKdV; 4 + sysSettings.zPropWeightV = 1.0; // float zPropWeightV; 4 + sysSettings.chainSagCorrection = 0.0; // float chainSagCorrection; 4 + sysSettings.chainOverSprocket = 1; // byte chainOverSprocket; 1 + sysSettings.fPWM = 3; // byte fPWM; 1 + sysSettings.leftChainTolerance = 0.0; // float leftChainTolerance; 4 + sysSettings.rightChainTolerance = 0.0; // float rightChainTolerance;4 - + sysSettings.positionErrorLimit = 2.0; // float positionErrorLimit; 4 + sysSettings.zAxisUpperLimit = NAN; // float zAxisUpperLimit 4 + sysSettings.zAxisLowerLimit = NAN; // float zAxisLowerLimit 4 + sysSettings.chainElongationFactor = 8.1E-6; // m/m/N 4 + sysSettings.sledWeight = 11.6*9.8; // Newtons. For a sled with one ring4 kit, one Rigid 2200 router and two 2.35kg bricks on a 5/8" thick mdf 18" diameter base. + sysSettings.spindleMin = 4000; // 2 + sysSettings.spindleMax = 24000; // 2 + sysSettings.eepromValidData = EEPROMVALIDDATA; // byte eepromValidData;1 +} // 36 * 4 bytes, 6* 2 bytes, 7* 1 byte = 144+12+7= 163 bytes void settingsWipe(byte resetType){ /* @@ -432,9 +432,13 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ kinematics.init();; break; case 60: - sysSettings.spindleMin = value; + sysSettings.spindleMin = (int)value; + Serial.print(F("\r\nnew spindle min="));Serial.print(sysSettings.spindleMin); + break; case 61: - sysSettings.spindleMax = value; + sysSettings.spindleMax = (int)value; + Serial.print(F("\r\nnew spindle max="));Serial.print(sysSettings.spindleMax); + break; default: return(STATUS_INVALID_STATEMENT); } diff --git a/cnc_ctrl_v1/Spindle.cpp b/cnc_ctrl_v1/Spindle.cpp index c7b2c0f0..c8a198b2 100644 --- a/cnc_ctrl_v1/Spindle.cpp +++ b/cnc_ctrl_v1/Spindle.cpp @@ -31,19 +31,21 @@ void setSpindlePower(bool powerState) { SpindleAutomationType spindleAutomateType = sysSettings.spindleAutomateType; int delayAfterChange = 1000; // milliseconds - int servoIdle = 90; // degrees - int servoOn = 180; // degrees - int servoOff = 0; // degrees - int servoDelay = 2000; // milliseconds - + // Now for the main code #if defined (verboseDebug) && verboseDebug > 1 Serial.print(F("Spindle control uses pin ")); - Serial.print(SpindlePowerControlPin); + Serial.println(SpindlePowerControlPin); Serial.print(F("Spindle automation type ")); - Serial.print(spindleAutomateType); + Serial.println(spindleAutomateType); #endif #ifndef SPINDLE_SPEED + + int servoIdle = 90; // degrees + int servoOn = 180; // degrees + int servoOff = 0; // degrees + int servoDelay = 2000; // milliseconds + if (spindleAutomateType == SERVO) { // use a servo to control a standard wall switch #if defined (verboseDebug) && verboseDebug > 1 Serial.print(F(" with servo (idle=")); @@ -57,6 +59,8 @@ void setSpindlePower(bool powerState) { myservo.attach(SpindlePowerControlPin); // start servo control myservo.write(servoIdle); // move servo to idle position maslowDelay(servoDelay); // wait for move to complete + sys.SpindlePower = 0; + sys.SpindleSPeed = 0; if(sys.stop){return;} if (powerState) { // turn on spindle Serial.println(F("Turning Spindle On")); @@ -70,6 +74,8 @@ void setSpindlePower(bool powerState) { if(sys.stop){return;} myservo.write(servoIdle); // return servo to idle position maslowDelay(servoDelay); // wait for move to complete + sys.SpindlePower = 1; + sys.SpindleSPeed = 0; if(sys.stop){return;} myservo.detach(); // stop servo control } @@ -84,11 +90,14 @@ void setSpindlePower(bool powerState) { digitalWrite(SpindlePowerControlPin, HIGH); Serial.println(F("Adjusting Spindle Speed to Minimum")); setSpindleSpeed(sysSettings.spindleMin); + sys.SpindlePower = 1; } else { // turn off spindle Serial.println(F("Turning Spindle Off")); digitalWrite(SpindlePowerControlPin, LOW); - digitalWrite(SpindleSpeedControlPin, LOW); + digitalWrite(SpindleSpeedPin, LOW); + sys.SpindlePower = 0; + sys.SpindleSpeed = 0; } } if (spindleAutomateType == SPEED_CONTROL_RELAY_ACTIVE_LOW){ @@ -101,11 +110,14 @@ void setSpindlePower(bool powerState) { digitalWrite(SpindlePowerControlPin, LOW); Serial.println(F("Adjusting Spindle Speed to Minimum")); setSpindleSpeed(sysSettings.spindleMin); + sys.SpindlePower = 1; } else { // turn off spindle Serial.println(F("Turning Spindle Off")); digitalWrite(SpindlePowerControlPin, HIGH); - digitalWrite(SpindleSpeedControlPin, LOW); + digitalWrite(SpindleSpeedPin, LOW); + sys.SpindlePower = 0; + sys.SpindleSpeed = 0; } } if (spindleAutomateType == RELAY_ACTIVE_HIGH) { @@ -116,10 +128,14 @@ void setSpindlePower(bool powerState) { if (powerState) { // turn on spindle Serial.println(F("Turning Spindle On")); digitalWrite(SpindlePowerControlPin, HIGH); + sys.SpindlePower = 1; + sys.SpindleSpeed = 0; } else { // turn off spindle Serial.println(F("Turning Spindle Off")); digitalWrite(SpindlePowerControlPin, LOW); + sys.SpindlePower = 0; + sys.SpindleSpeed = 0; } } else if (spindleAutomateType == RELAY_ACTIVE_LOW) { // use a digital I/O pin to control a relay @@ -130,10 +146,14 @@ void setSpindlePower(bool powerState) { if (powerState) { // turn on spindle Serial.println(F("Turning Spindle On")); digitalWrite(SpindlePowerControlPin, LOW); + sys.SpindlePower = 0; + sys.SpindleSpeed = 0; } else { // turn off spindle Serial.println(F("Turning Spindle Off")); digitalWrite(SpindlePowerControlPin, HIGH); + sys.SpindlePower = 0; + sys.SpindleSpeed = 0; } } if (spindleAutomateType != NONE) { @@ -141,20 +161,36 @@ void setSpindlePower(bool powerState) { } } -int setSpindleSpeed(int spindleSpeed){ +int setSpindleSpeed(int spindleSpd){ // map 0-255 min spindle speed to max spindle speed // output 0-255 - if (spindleSpeed < sysSettings.spindleMin){ - spindleSpeed = sysSettings.spindleMin; + if (spindleSpd == 0){ + digitalWrite(SpindleSpeedPin,LOW); + sys.SpindleSpeed = 0; } - if (spindleSpeed > sysSettings.spindleMax){ - spindleSpeed = sysSettings.spindleMax; + else{ + if(spindleSpd < sysSettings.spindleMin){ + spindleSpd = sysSettings.spindleMin; + } + if (spindleSpd > sysSettings.spindleMax){ + spindleSpd = sysSettings.spindleMax; + } + sys.SpindleSpeed = spindleSpd; + Serial.print(F("spindle max = "));Serial.println(sysSettings.spindleMax); + Serial.print(F("spindle min = "));Serial.println(sysSettings.spindleMin); + Serial.print(F("new spindle speed = "));Serial.println(spindleSpd); + int spd = constrain(map (spindleSpd, 0, sysSettings.spindleMax, 0, 255),0,255); + Serial.print(F("new pwm output = "));Serial.println(spd); + if (sys.SpindlePower == 1){ + analogWrite(SpindleSpeedPin,spd); + return(1); + }else{ + digitalWrite(SpindleSpeedPin,LOW); + return(0); + } } - long spd = map (spindleSpeed, 0, sysSettings.spindleMax, 0, 255); - analogWrite(SpindleSpeedControlPin,spd); - return(1); //for (i=0;i 255)) { return(STATUS_INVALID_STATEMENT); } return(settingsStoreGlobalSetting((byte)parameter, value)); // } diff --git a/cnc_ctrl_v1/System.h b/cnc_ctrl_v1/System.h index 3f0d88b7..dd0eaec7 100644 --- a/cnc_ctrl_v1/System.h +++ b/cnc_ctrl_v1/System.h @@ -60,6 +60,7 @@ typedef struct { bool useRelativeUnits; // unsigned long lastSerialRcvd; // The millis of the last rcvd serial command, used by watchdo int lastGCommand; //Stores the value of the last command run eg: G01 -> 1 + bool SpindlePower; // store the spindle power state int SpindleSpeed; // store the current spindle speed -> 4000 int lastTool; //Stores the value of the last tool number eg: T4 -> 4 int nextTool; //Stores the value of the next tool number eg: T4 -> 4 @@ -77,7 +78,8 @@ extern Axis zAxis; extern maslowRingBuffer incSerialBuffer; extern Kinematics kinematics; extern byte systemRtExecAlarm; -extern int SpindlePowerControlPin; +extern int SpindlePowerControlPin; // relay for spindle power +extern int SpindleSpeedPin; // pwm output for spindle control extern int LaserPowerPin; extern int ProbePin; extern int SO1; diff --git a/cnc_ctrl_v1/cnc_ctrl_v1.ino b/cnc_ctrl_v1/cnc_ctrl_v1.ino index 2528f2d5..69cb0541 100644 --- a/cnc_ctrl_v1/cnc_ctrl_v1.ino +++ b/cnc_ctrl_v1/cnc_ctrl_v1.ino @@ -59,7 +59,7 @@ Axis zAxis; Kinematics kinematics; void setup(){ - Serial.begin(57600); + Serial.begin(115200); Serial.print(F("PCB v1.")); Serial.print(getPCBVersion()); if (TLE5206 == true) { Serial.print(F(" TLE5206 ")); } From 10b1fa100e073021f87a3c216d8fef259b648c54 Mon Sep 17 00:00:00 2001 From: Orob-Maslow <59507087+Orob-Maslow@users.noreply.github.com> Date: Mon, 23 Nov 2020 21:15:51 -0600 Subject: [PATCH 16/21] 51.29 added v1.5 shield 51.29: added board v 1.5 TB6643 chip and associated procedures for communicating with that chip and the different pinouts. incremented settingversion to 7 --- Firmware_1.26b/.gitignore | 17 + Firmware_1.26b/.travis.yml | 35 + Firmware_1.26b/CODE_OF_CONDUCT.md | 46 + .../Documentation/Download Firmware.jpg | Bin 0 -> 87994 bytes Firmware_1.26b/Documentation/Download IDE.jpg | Bin 0 -> 102625 bytes .../How To Contribute Pictures/Clone.png | Bin 0 -> 37021 bytes .../How To Contribute Pictures/Clone2.png | Bin 0 -> 34398 bytes .../How To Contribute Pictures/Clone3.png | Bin 0 -> 14502 bytes .../How To Contribute Pictures/Commit.png | Bin 0 -> 44800 bytes .../EditingFile.png | Bin 0 -> 55394 bytes .../How To Contribute Pictures/Fork.jpg | Bin 0 -> 58378 bytes .../How To Contribute Pictures/GithubHome.jpg | Bin 0 -> 76690 bytes .../GithubWelcome.jpg | Bin 0 -> 30594 bytes .../How To Contribute Pictures/PR0.png | Bin 0 -> 46931 bytes .../How To Contribute Pictures/PR1.png | Bin 0 -> 69205 bytes .../How To Contribute Pictures/PR2.png | Bin 0 -> 64618 bytes .../How To Contribute Pictures/PR3.png | Bin 0 -> 73289 bytes .../Push Origin.png | Bin 0 -> 43035 bytes .../Documentation/Open Firmware.jpg | Bin 0 -> 91291 bytes Firmware_1.26b/Documentation/Select Board.jpg | Bin 0 -> 90579 bytes .../Documentation/Select COM Port.jpg | Bin 0 -> 77634 bytes Firmware_1.26b/Documentation/Upload.jpg | Bin 0 -> 64058 bytes .../Documentation/posErrorAlarm/alarm.PNG | Bin 0 -> 10698 bytes .../posErrorAlarm/alarmSetting.PNG | Bin 0 -> 70324 bytes Firmware_1.26b/INSTRUCTIONS.md | 41 + Firmware_1.26b/LICENSE | 189 ++++ Firmware_1.26b/README.md | 77 ++ Firmware_1.26b/cnc_ctrl_v1/Axis.cpp | 301 ++++++ Firmware_1.26b/cnc_ctrl_v1/Axis.h | 70 ++ Firmware_1.26b/cnc_ctrl_v1/Config.h | 64 ++ Firmware_1.26b/cnc_ctrl_v1/Encoder.cpp | 10 + Firmware_1.26b/cnc_ctrl_v1/Encoder.h | 976 ++++++++++++++++++ Firmware_1.26b/cnc_ctrl_v1/GCode.cpp | 889 ++++++++++++++++ Firmware_1.26b/cnc_ctrl_v1/GCode.h | 50 + Firmware_1.26b/cnc_ctrl_v1/Kinematics.cpp | 425 ++++++++ Firmware_1.26b/cnc_ctrl_v1/Kinematics.h | 99 ++ Firmware_1.26b/cnc_ctrl_v1/Maslow.h | 52 + Firmware_1.26b/cnc_ctrl_v1/Motion.cpp | 376 +++++++ Firmware_1.26b/cnc_ctrl_v1/Motion.h | 36 + Firmware_1.26b/cnc_ctrl_v1/Motor.cpp | 227 ++++ Firmware_1.26b/cnc_ctrl_v1/Motor.h | 54 + .../cnc_ctrl_v1/MotorGearboxEncoder.cpp | 205 ++++ .../cnc_ctrl_v1/MotorGearboxEncoder.h | 56 + Firmware_1.26b/cnc_ctrl_v1/NutsAndBolts.cpp | 67 ++ Firmware_1.26b/cnc_ctrl_v1/NutsAndBolts.h | 31 + Firmware_1.26b/cnc_ctrl_v1/PID_v1.cpp | 236 +++++ Firmware_1.26b/cnc_ctrl_v1/PID_v1.h | 98 ++ Firmware_1.26b/cnc_ctrl_v1/Probe.cpp | 33 + Firmware_1.26b/cnc_ctrl_v1/Probe.h | 25 + Firmware_1.26b/cnc_ctrl_v1/Report.cpp | 316 ++++++ Firmware_1.26b/cnc_ctrl_v1/Report.h | 85 ++ Firmware_1.26b/cnc_ctrl_v1/RingBuffer.cpp | 208 ++++ Firmware_1.26b/cnc_ctrl_v1/RingBuffer.h | 42 + Firmware_1.26b/cnc_ctrl_v1/Settings.cpp | 414 ++++++++ Firmware_1.26b/cnc_ctrl_v1/Settings.h | 109 ++ Firmware_1.26b/cnc_ctrl_v1/SimavrSerial.cpp | 27 + Firmware_1.26b/cnc_ctrl_v1/SimavrSerial.h | 32 + Firmware_1.26b/cnc_ctrl_v1/Spindle.cpp | 117 +++ Firmware_1.26b/cnc_ctrl_v1/Spindle.h | 24 + Firmware_1.26b/cnc_ctrl_v1/System.cpp | 658 ++++++++++++ Firmware_1.26b/cnc_ctrl_v1/System.h | 94 ++ Firmware_1.26b/cnc_ctrl_v1/Testing.cpp | 181 ++++ Firmware_1.26b/cnc_ctrl_v1/Testing.h | 25 + Firmware_1.26b/cnc_ctrl_v1/TimerOne.cpp | 209 ++++ Firmware_1.26b/cnc_ctrl_v1/TimerOne.h | 67 ++ Firmware_1.26b/cnc_ctrl_v1/cnc_ctrl_v1.ino | 120 +++ .../cnc_ctrl_v1/utility/direct_pin_read.h | 27 + .../cnc_ctrl_v1/utility/interrupt_config.h | 87 ++ .../cnc_ctrl_v1/utility/interrupt_pins.h | 156 +++ Firmware_1.26b/platformio.ini | 38 + Firmware_1.26b/platformio/simavr_env.py | 21 + Firmware_1.26b/platformio/teensy_env.py | 12 + cnc_ctrl_v1/Kinematics.cpp | 2 + cnc_ctrl_v1/Kinematics.h | 3 +- cnc_ctrl_v1/Maslow.h | 2 +- cnc_ctrl_v1/Motor.cpp | 30 +- cnc_ctrl_v1/Motor.h | 1 + cnc_ctrl_v1/Settings.cpp | 2 +- cnc_ctrl_v1/Settings.h | 2 +- cnc_ctrl_v1/System.cpp | 78 +- cnc_ctrl_v1/System.h | 2 + cnc_ctrl_v1/cnc_ctrl_v1.ino | 11 +- 82 files changed, 7961 insertions(+), 26 deletions(-) create mode 100644 Firmware_1.26b/.gitignore create mode 100644 Firmware_1.26b/.travis.yml create mode 100644 Firmware_1.26b/CODE_OF_CONDUCT.md create mode 100644 Firmware_1.26b/Documentation/Download Firmware.jpg create mode 100644 Firmware_1.26b/Documentation/Download IDE.jpg create mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/Clone.png create mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/Clone2.png create mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/Clone3.png create mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/Commit.png create mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/EditingFile.png create mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/Fork.jpg create mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/GithubHome.jpg create mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/GithubWelcome.jpg create mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/PR0.png create mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/PR1.png create mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/PR2.png create mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/PR3.png create mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/Push Origin.png create mode 100644 Firmware_1.26b/Documentation/Open Firmware.jpg create mode 100644 Firmware_1.26b/Documentation/Select Board.jpg create mode 100644 Firmware_1.26b/Documentation/Select COM Port.jpg create mode 100644 Firmware_1.26b/Documentation/Upload.jpg create mode 100644 Firmware_1.26b/Documentation/posErrorAlarm/alarm.PNG create mode 100644 Firmware_1.26b/Documentation/posErrorAlarm/alarmSetting.PNG create mode 100644 Firmware_1.26b/INSTRUCTIONS.md create mode 100644 Firmware_1.26b/LICENSE create mode 100644 Firmware_1.26b/README.md create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Axis.cpp create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Axis.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Config.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Encoder.cpp create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Encoder.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/GCode.cpp create mode 100644 Firmware_1.26b/cnc_ctrl_v1/GCode.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Kinematics.cpp create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Kinematics.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Maslow.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Motion.cpp create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Motion.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Motor.cpp create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Motor.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/MotorGearboxEncoder.cpp create mode 100644 Firmware_1.26b/cnc_ctrl_v1/MotorGearboxEncoder.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/NutsAndBolts.cpp create mode 100644 Firmware_1.26b/cnc_ctrl_v1/NutsAndBolts.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/PID_v1.cpp create mode 100644 Firmware_1.26b/cnc_ctrl_v1/PID_v1.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Probe.cpp create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Probe.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Report.cpp create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Report.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/RingBuffer.cpp create mode 100644 Firmware_1.26b/cnc_ctrl_v1/RingBuffer.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Settings.cpp create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Settings.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/SimavrSerial.cpp create mode 100644 Firmware_1.26b/cnc_ctrl_v1/SimavrSerial.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Spindle.cpp create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Spindle.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/System.cpp create mode 100644 Firmware_1.26b/cnc_ctrl_v1/System.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Testing.cpp create mode 100644 Firmware_1.26b/cnc_ctrl_v1/Testing.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/TimerOne.cpp create mode 100644 Firmware_1.26b/cnc_ctrl_v1/TimerOne.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/cnc_ctrl_v1.ino create mode 100644 Firmware_1.26b/cnc_ctrl_v1/utility/direct_pin_read.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/utility/interrupt_config.h create mode 100644 Firmware_1.26b/cnc_ctrl_v1/utility/interrupt_pins.h create mode 100644 Firmware_1.26b/platformio.ini create mode 100644 Firmware_1.26b/platformio/simavr_env.py create mode 100644 Firmware_1.26b/platformio/teensy_env.py diff --git a/Firmware_1.26b/.gitignore b/Firmware_1.26b/.gitignore new file mode 100644 index 00000000..138190fd --- /dev/null +++ b/Firmware_1.26b/.gitignore @@ -0,0 +1,17 @@ +.pioenvs +.piolibdeps +.clang_complete +.gcc-flags.json +lib/readme.txt +cnc_ctrl_v1/.DS_Store +cnc_ctrl_v1/.DS_Store +cnc_ctrl_v1/.DS_Store +.DS_Store +**/.DS_Store +.vscode/ +.vscode/c_cpp_properties.json +.vscode/launch.json +simduino_atmega2560_flash.bin +simduino +.vscode/*.db +obj-x86_64-apple-darwin17.4.0 diff --git a/Firmware_1.26b/.travis.yml b/Firmware_1.26b/.travis.yml new file mode 100644 index 00000000..7805f835 --- /dev/null +++ b/Firmware_1.26b/.travis.yml @@ -0,0 +1,35 @@ +# Continuous Integration (CI) is the practice, in software +# engineering, of merging all developer working copies with a shared mainline +# several times a day < http://docs.platformio.org/page/ci/index.html > +# +# Documentation: +# +# * Travis CI Embedded Builds with PlatformIO +# < https://docs.travis-ci.com/user/integration/platformio/ > +# +# * PlatformIO integration with Travis CI +# < http://docs.platformio.org/page/ci/travis.html > +# +# * User Guide for `platformio ci` command +# < http://docs.platformio.org/page/userguide/cmd_ci.html > +# +# +# Please choice one of the following templates (proposed below) and uncomment +# it (remove "# " before each line) or use own configuration according to the +# Travis CI documentation (see above). +# + + +# +# Template #1: General project. Test it using existing `platformio.ini`. +# + +language: python +python: + - "2.7" + +install: + - pip install -U platformio + +script: + - platformio run diff --git a/Firmware_1.26b/CODE_OF_CONDUCT.md b/Firmware_1.26b/CODE_OF_CONDUCT.md new file mode 100644 index 00000000..f214249a --- /dev/null +++ b/Firmware_1.26b/CODE_OF_CONDUCT.md @@ -0,0 +1,46 @@ +# Contributor Covenant Code of Conduct + +## Our Pledge + +In the interest of fostering an open and welcoming environment, we as contributors and maintainers pledge to making participation in our project and our community a harassment-free experience for everyone, regardless of age, body size, disability, ethnicity, gender identity and expression, level of experience, nationality, personal appearance, race, religion, or sexual identity and orientation. + +## Our Standards + +Examples of behavior that contributes to creating a positive environment include: + +* Using welcoming and inclusive language +* Being respectful of differing viewpoints and experiences +* Gracefully accepting constructive criticism +* Focusing on what is best for the community +* Showing empathy towards other community members + +Examples of unacceptable behavior by participants include: + +* The use of sexualized language or imagery and unwelcome sexual attention or advances +* Trolling, insulting/derogatory comments, and personal or political attacks +* Public or private harassment +* Publishing others' private information, such as a physical or electronic address, without explicit permission +* Other conduct which could reasonably be considered inappropriate in a professional setting + +## Our Responsibilities + +Project maintainers are responsible for clarifying the standards of acceptable behavior and are expected to take appropriate and fair corrective action in response to any instances of unacceptable behavior. + +Project maintainers have the right and responsibility to remove, edit, or reject comments, commits, code, wiki edits, issues, and other contributions that are not aligned to this Code of Conduct, or to ban temporarily or permanently any contributor for other behaviors that they deem inappropriate, threatening, offensive, or harmful. + +## Scope + +This Code of Conduct applies both within project spaces and in public spaces when an individual is representing the project or its community. Examples of representing a project or community include using an official project e-mail address, posting via an official social media account, or acting as an appointed representative at an online or offline event. Representation of a project may be further defined and clarified by project maintainers. + +## Enforcement + +Instances of abusive, harassing, or otherwise unacceptable behavior may be reported by contacting the project team at info@maslowcnc.com. The project team will review and investigate all complaints, and will respond in a way that it deems appropriate to the circumstances. The project team is obligated to maintain confidentiality with regard to the reporter of an incident. Further details of specific enforcement policies may be posted separately. + +Project maintainers who do not follow or enforce the Code of Conduct in good faith may face temporary or permanent repercussions as determined by other members of the project's leadership. + +## Attribution + +This Code of Conduct is adapted from the [Contributor Covenant][homepage], version 1.4, available at [http://contributor-covenant.org/version/1/4][version] + +[homepage]: http://contributor-covenant.org +[version]: http://contributor-covenant.org/version/1/4/ diff --git a/Firmware_1.26b/Documentation/Download Firmware.jpg b/Firmware_1.26b/Documentation/Download Firmware.jpg new file mode 100644 index 0000000000000000000000000000000000000000..88e8e33178fe5e0d62a57df70b9ecb32359c98e6 GIT binary patch literal 87994 zcmeFZ1zeR~w=eq84T5w_2$Is>(%s!H0@BR_R8SI@bax{u-7N0%4fWfv z@80L#=R4=#bC1j4^JDrvGsgIjF~=OU#?8dd0&q)CN>&Phfq?-`p#OlI#aly?p0-v1 zpr{Bi004jtz{3atu+S8|xT!M`Vhg}S(=gBvatVoF|3Y&Bw^}wy0VHS=9r}M^=mU^$ z{{H1_`q%Fl0>2RWg}^Taej)G+f&U8;K!}3-&4a*&dJ1t-@ZZt};OO7daC{s900w_g zfA=Pk!@lD6%bWPWP-}j%{0o6!2>e3e7XrT!_yGa-`)oY?_c{6R^HH+h=jXW3&&2`! z>>U7z1Ezp8wB*eq8orII>tlXaRtFarQwv8kOBQoSdsa`=$E<8D_gMi!5zoh_=605@ zlxCLJwhlscUuqlaC~Yl-=(M>M?<+o*u(Yw2@piUU_g2y{_qH?Vv!D|Z#y}PHdEZjLj6Yt4=i2Gooyex+B!N=eyz~d%+bwNh|0~) z)`H*4)QZc@!h(z0%#_1|nT^fDl-bmRgN@mOgTsP{i;b7vip`AbkLE4RzqS6@&H2%9 zZCjYLT0XM0w{&oIfuh02O2zs+(f_VCp%8s*^r!Gcd4%TSmvFW;b+vo|eT2V?lleX; z^L;*zKSj*K$8lef^*`hjWc>=p4}|`EDgPfrOIXmtoZtK_?T*gBH?MB#^gk!7n9104GAnT6}{uP1W-as`DTJD>ELQ7KqZ}|OcZBOxLnA|oLoqhg~$ zeGF7QtXt^Vgm}b6gm{DmB;<5=NXTf(2neZIsA%c$F)}d{Q?hcfGO*JzFfx3t1O^Ei z85IQ;7Yz-Ufs~Mx;UE8QngDEM*l`3cI2bAb78?c*8|J1Bpn&c(B0zU0ziv+c@q>Yd zgGWF_LPkMFgJvkd1;E0v;)CTuxILw@bP*Cv+2#JVk@6yrVW8mcC=Hcbzmv|s4B`qT>r>>!?rLCi@XKrC> zWo={o(8blw-NVz%`^nR1!6DCIgo0naeiIWL_clH)JtH$KJ0~}<^g~&BMP*fWO-pNA zdq-zichAu9$mrPk#N^cC((=mc+WO~>&HaPJqvMm)v-69ue8B*4zq9p?v;V*sHk2<| zcz8H?q_2Fzz4kJXtq-<&`55TAemWL+O5IZY^zf}l-@ z4hXI%cx&fwRw|pP&l$GicEe*a1e4myO-QM_gK0Ew59jl;mb(JAd9c zo7X4%rSoC_4S+%)sThAE9)ax;&x=Dh%g}yzz{907h$DJl5U_zuN&BEwZij#Fz#^Cv zL!Xe|wAo$X6XY@x9cE%qBuET8nSD{taSpb}Ij0p2IpkRua5r~%>Q_oQNfUCHkOb@o zb?ugz*%m`J;-z%o#4}eM+@>UP*0AsHSR9@oSllSKEw#36X1Lvpv05=^5Lm5rzX^w3 z$|=bPPAW8yi&26z8l`k!?tRTOI?Se9BGluR!ojKht3lEn-89k2a!5F0RQKnmH5PJc zZg)uI!lX*78R~s1Qo}evAw_q1)}$sSUP6sJ(b@CZi_}GP*Kt?dFru5LvQkRY^>FY- z)yl30WdJe&^1NzVCKKhdDS#q)YjRTGu;v`xZBJ4$czeg)D38Jx{>eB|2Z|7e4sm^Q zG*i(R!r&PL8FD(c=&PA1DNtb5Ry$yrmcw0X5*s|3<;Z1d?l{Y)X$9mkhoSEhcCTma zHHsqOszM)4lIe{{bh1{G+%#sgxMTwr{)eCs!%4HsWB{wG#v{kf#>C8LxH>S;S4=z< zCNDoi`WyYzBPw%XN5h}S4lN367}u?r+jpkwrd=&&2xpdDqyfZ=$gR($qhifuj`MoX^h2bsN5D$@v_+HqGe{Lo%Hd!&8n~!CJ*=iRgq7>UJBq8DcKfT4}l2JFH4^YgUCzNM3(9jXn?+!Sk{EH( zx%-{y84*c!0Y;F{_cuTi#n~k&oMPgH;;{7wpm5yJFnrj)yILVjV@o}oAiAnkJg51{ zbizZEX3ukBM50a4DWHpdA)58I89w+twPLq3wh}Z;xlV?hg3|aiQf(>p-bWnibu%(0 zSi~hz;jrT+lW3Oo4T-Hdb>%*CL*^n>sAzC+^0YPaJoV_BL6ojq3ZVWuWjVgmIfl00 zq_KLwsvn(cLwSb`cFYd)Tp~~NVse+Xf<7v|Qw*o!DQ(e_!`fZ4eqbJPf6|Rm=x`$x z82)*USq;^ucx?lpXrk)qhj`w>KPS=%XqPn*W*6S|j?^of+9Z=31laWC?VUJ_UC>&( zSK~S!FWkDnlMvAozzi~<0QF;C`89S#ei!|S`yAzPQ5=(VS3z$mj=mSQ<2wN*BC+OX z;Hay^MIpJ(`w_A4xS0!+lUK@9aapz}RhU9GM|^~v^su1swfu_$rFwZ3Zd@=!GF`{$ zy31lLDrJ({N^?!ncF#Krc{Tfu_|>F~dj~i2nVj04XeZ0-!&c58h#y$`MT}A=FFphY ze$IN{l;v1hULYBZ}Fgu~;O*V4TN8 zbbQDz0kg>cNQBFL00uwT3yMvrBNqsl+!rwzw8;`0my+6R3>tDu$aqaK89Y;02G`6% zE*k77DObcV1q`+%*)Cxf>W(``!OzN zMp8=vnWPJGNT|K}K6xZwQK8MF%tOeSmIlN9fGqtpuT!F;ps|y&3u@*!y*zBeQ$|E^ z0epPaSmv}cKTyy9FV*i(`(KL=h6z`xd{*g;FafHwloKfVF> zd+Pr%!dg~&mD<|(b@XPK-^cL0S($2YkcwPI(3R<1!V;o~Qwm+b6S~yjhJSJ}Qm>ZUCq?9KQj6 zGl$0eDOkk&LXppXJ@#ShgqURU12bo&IX^Jq&7i^s$)3MMZ-N=-xX-Wm-oTzg;-0fI zx;M6F<01*G!=R#9Rh_m|Et5`v(&CG)4z{yPZSB9UuD6D!64RopR-Kx*rbOnkh}*qa zyffbGWS(37a*-6&81L zIeEoseMx)+Ks-UqTM$l=x$zC~)k13 zrs^0P3#sk}Hux}5lk}<{=m&jH|3N@7ktaTlWsaAQyH`sPS ziB7}*zwMr_C8aSf9-##4W>V(iFJ{rKcZ>5b-9Phgq~luIg1I)^V6-~IeU;EDePSt= z^`;!aOw*s7;}RKMhj%JbWW`c>&hajuYg(y*KeBFr>ZIZw!zgPnfxzBw%`-6s3g%Yue3QxUr4a z;GR3qcPDvE+k34PUR^FUMWK;5Er*?E(LGrS?pPzSdx>o1)z+N$p8h=r(_J$(O8OaV zcbD#>tWc;8c?K48I!112y%#+uWmk*M)YB}!YJtv{n6iwNa51_=AQvkaY!TzRf_Vw% zrLswTZi12b?44r~4BUiEB0oJG_qt@TB0dKDz;zOuM_@W3>$6bF$8`yZABg&W4>c)T zv6IWUt4-HuTG(LyoM8+_v*it7^<{M!L$-Vem$~Y$1&M+kg;(&&DFKpHtBNB*ZTLj>ai$53WYb4I7M{R{AWrlFmCT zjl4A*KN$OEgHA$r>kc5=;Kt3X`ZU2Cpz(0M*x`+PC=fcvm-Zo8;4Ng3T`Heu8umO4 ziMi}CyH~qdZo8k;!#l&-@*dGG-2&)kwtaHwCY7QbO?_S+7(MiGnDed6GBv^W2r;;3 z_`4`NZxTFS2_|#8&0ZN|nejkf47NH6O!H6^;SB~5`J4W3V#V9->`c)$Z!AosnvUT; z@TL`Ul+h$9d)_zW_0QPwu$3He_taN6U)#Vv9T8-vB0<`5!Eh>d%klNvjeq0S!iMAd{NO<*Pn^#GIZ;B@ zgq@ONHQIP7SioJh9Q9<-k7MKpxX9Q3A^(q40`|fk>T@pjQ(Zd|b>$Z%-h zuqI7DqS5Ef4_Fz`op?Cqo>$~rFFtl8CFD84H zo;rfgDXyk7*ikmHB2>!fpBqm*Zvdmn@5yS3WoC(O&~&m%C8X)_s+i-Gu>0(#V6Qo0 zze8hREs7;{!NbxdIxWV^JOJ3VqaS_x%I@NjibHMUW!Ec+H|zEO4KSYmJ((9X)fTI3 zbCkat)?pDUjU7l&*aYXVk+4U|EWE5+UKwg-zdayN%AQtC-=__igf)-!M6)0JkkO!I zMfL^|B7mGhMLhUJdf1{Nf>{dft`@se#HJ`AjQhIC=|CFfLP&VL|E=yT@4L5PoqKWp zvy$1%J6#376Y>L1xtj=e;m0VCnjG1A!D>z&gzqULdu(UX1;5MVhh$QyiP#VA|47TI z)>z@#p8mOW#a7@W8o+-3eKna&6Y2iQ_2cg2vpZEWQvyCOc5zH$+X+=H%-)?bHJPvq zMh|^Bi7Nkc4N^$5Fg&1vE+V|V0enHn8-gL<(whQ?k}NF3eS3i_*C{WBoKoc3J@C51jmn`G&)8dg+IlwMW}8ym69%{@%I+cH}F1KL-ky@vb1Bw?%2Ur5$m? z7w_|#$!L{MZtud^=UpGFdPRlF)l)y`Xs=yZjf_ zPZa7bA|!72D2Pd5);acXh!XtJ6Msm8>1^+4drsXo1xH9}Pb@^A6Z-*w*Gor^RN%i; z@I9q0`L{&|PMr#`+~cgkGE+)Os40Q{BS|8}Nq;YapdA*v>KD+y7A18~ileC?+5Ajd z^w!VyR0tOa>ASpt5WV`~uOdGk+5X=~Y(Pen=7==@Z@N?tvG(hAC(Ui#rP77{yU{K_ zIeKDwZ3i3A$xm;SRV?gY?j*o+b4xk1^|8~#IsVj;7Ck=ee85kmSH}OelG{aTY_Gn| zxp!EmphpuM#`-eMIVB9%+eI=t%vJs}BWPIVO>eYU{=Epzmn1wphsYBYwlnGi0V|=v z=c}I%V41eAl`+wV`tq!?3?br+ucN#z^`p;18{xAg?=&17cOIr7dSQJVYlqIi%K*9^ z8TtAKaB7Up7ASD~(ABIe#?+YtR}V=3&44)0=Cu5ls+>R6=0gRT!lu^t4bgdr7Dsns zKi1~_bUZ0>&W^8Oq(E_Q9|Fsc@1)H@W_9IN9_LFp_e^FNF!qzx5`97XTwIH(%ude>3=O zdeg)H;}PrsfTMT8V4-^PaitCHLL0WuhOkdTVIMqs$`UM=}~i=dx5e9?}_PqcpnaxV;OkE18r z`G~r3cN{`(r*~lZxrR!AYU995eezvboJ_msb1NF_Rm%<}qT^41cOhQinR(kO|LRG$ zY3>Gd=DckoK_W_(ZZM5nj|4qjN>M0uyRgV{39;BG)ssMV#I^eYkIM6_N(K^#4LoHe z>QqjcAyp&Cy~y_X@lXP7;?;>7?hXq2bD4J@j{UQ6BCgsQDln3Gc%OQ?-G>Ye<)T_~ zV!X)S=OH=U!0Iu6JT?wh>ns+pz;MLK5n-+$U^o@M0k9p<&9L@%w?-DQ4IwWJC$}m@ zY)h+Y3lAYrZ?(N6<+WtM{J0 z7=*g4CVX|SFjsVJ=;L}jc>(p5s%El<9c52m4QUEBI%86yo8r``qy{*KBz6|x{h$qx z#?+%vc+FS*`-rvdH-M>UDFV;Q23@QNS(^*W1BIN=tAtCEEGbX=1rNuw-nILaRV2x< zaP6?%GdGJQnUg9A!$hV`LKe!mk(D(h_osTAqv5(Te5jZG`O`xakw#NU7sM)AHS+8X zbV_g@pAIWWU(7OojD_F2gf{YFe?55HeoTFJ+CUMf8|Op|k=^BN04ZnCNa#9uS^44~ zIUdw1#(~a8y*~xM-l*tUvssU8Yp^K60!uZ0WGxX41xh4wRp5D$9AB@e$)H?$LdwZ= zv!=I*HT#mi37cJr!dogZu~PGyQb+R9^U<-lR0^_Y9#zqqT$Y}6HfE0n2z!lQVG%qN zG(<>#K6YSFwR+O(VHvPa7lE22?Y6aHG`dIuw~>UVUy}LBjdiNWD|m6Vq>{G-7vwoE z+6})MwnZ99$PR{?k`@=*h;*$h5UB@Au3+Wj!qA9tr$!I)c8O?F-vBT2#>1xEORiJ8 z`t6t)(c5uLp6BBf2KLP-1|BUOb>r_$@tQYVS)0e&hrBx1Xta$SZT#{Cf(z5T!DDNQ zpG_7%!=E_1bM&Dp=1ZLv1tF$4J>mLMccG$qhrA>FtnJCW6)-d3!b_X;xaU1#K4Y;{ z=EshgP>py-@n=;TMe(<_wS;}3TW;1yH$ckW^cx@m40`6{R+Pv!9>{#O@d2YP-dTLk zWR>D0TyjTw!!SiYXddZ`{!+oe5ISF@*ehZnq#s-xI~`~VN06;}+dDV8ITclP1Bh2w zm}h^2kFK98Q_$&|A^o!tl zGCUlg>zB0||JsAaH8*wE(GI8Wu!E>aPIpf;f>)4qT>m8QS|4&IvMBux2P_Q4qieyd zx`|od#;xJ2Fhy*scV4tr!*lJdne1XVwIa@Wp+s?vctnpLS8oa_@)!)U6z{TJRe5xB zy64?rbSbs6{u2F+529K7*Sd{MUWUG$#EN!4Na&qHhi>ZGhE6N#at`{wLPPFh_(bs< z4#;@62(ixwmMRO-Qe>!y{o5Z#-%;#$e+jeMS(brR@1-7qvT*^fC=xS=jJYi}e5_WC z5=-1Ixme4I0%@Wau+v7;aZTg?!40s>ddQjlr$!BOic9%6=)i=BkXldARXp|53?V#- zBaQ%9BI#G#af4Uo%F}mf-#oQ@LXq0F$-j)0sW4@kzcm$^m`zv+dHIW(loRaFLRyex=$>7e6qBDiq!iF@gz zLo%GaIa6LZ$JAuM#bM{_2TPS_H-OgcedSsBF!!R8hTd`28TOJGP7AH68AQtH$TQ@t zJms>^&H2;j8vr$bUX>XyOdyrC!7Yp%JguB#K&51m!2c9sQppPjaVE?~vrY^%HP_br z(1teVV5&o2{x->uDVsrw`T#{0%(mEuArW|{rxdR@6g5AtPn5T-Phi1cqZ7Z_o(T|i z>LKI-6LTC|)37f*>E=V?Tg%)GF0(mcOcap;D@x5bLx}5!1;3ygcMNd9qs{+x?;ybV z-fIGXQ5KllC?0O!+0il*8MiO^9}$BP;H?mJnZxoo5pM&*Dhy*Qjm6wdM=8QMh zXT|Qm^tk(uw#|L;kz$~wCL`jc#0NwMp940dkiT|Jy5i%*0a;!Bi}M@6IC@POXJ{#6 zOBBBb?>OXnVPZr*Na%I+b^40a-OHd<2RJ#+So9f_tExp#N5D4Raq(`$9>mDbi$L?X z_POFJ`cFKFI(!@Hk)uzRtfZdXQl z+{!^Zb6VZmDfe6|_~;0-IGEo!={?18YkEZM7_W${q|v&B3XNF z2AW?3^0-`7Q)>^I{eixNJb4|DpleaDE<6ToG%V%APRY&<;_-A_88b({|U!KS}#$v{aBd zth49puO81xQnfnIJHG8&v}h*5N`+7DyyODO)baZ#+h@({8q$8MDG;fxv5Rwia@b8T#KF{uMt z7kU_L(G@9J6wPFJo0mEPYDE7kBWAq7P0JYrmV6IOTVk2$SRR}gD(Scq2dm1|tPxd< ziafF<)$+9)Nt>JWQwLi3tGB4146GD==^9G`&&XM#y&w{gJ?MijsrB(YgZMqZ)epE# zalfWX>X5%=S0H`_13$P2hMkR+qKNCSmoQ(vG$)U+9zOS+F$|G7ysCy3^$rkia)=`= zO8%=vfHmTd0}=ttiXcgLqHP^`zKFX~+m4o+q(0a(G2<#avtB0{?D`BkZD6TBbkp-! z4-dA=vP8GaLN|r~GGM1)KpH9PM2ffeE+dpaD)~IenX{8PG2XeqMLflceeSO;Qfnrc z`)GwcBjLE6fZw2TdYGDF8jG8?q&NQ2E5dZZRPBL%NmwxaE&hZR;;ruuJOJ(d<{Cg6 zSr6cnYbx#4l^bg{y%5^lR3%rz%CEsN(UI!)r2=MocKph*xrE?3`bYkK_!FI3^-a&Z zX?vb`9ZbIwDCy(hH&k%eZ^h}v*?vHxsl^T(DaxkwZKO)U)K)F2XS{D=n{w%D&j%jO z#K{RnTqdNfnnM(&iyl~d%bd@WXm3ZGXV|pE6kS)NQ4p07Kz(cd-pJw$04A`xsPZTH zuEd~lWGXsYa*b|IPv=XzSncAj$LM-LXr-yxt)kF#OMKQfHo5y!(!Ekm#!``A{2-gx zxD0W!tOyaAkP_WOTl*(UYU*i*P!aFBSjI>Ylf0p9HFhB5?5~Y+I^o8`%U2Yd_Kl@) zo=yO5+OM}zkMG}sLsnPqvgJk6P{EQg`sZF5qmMYAWF!v*WOS=-|U4Pv= zCBbAS9qM&=;r)}Yz5Jh-M<#;nejDKC#5_;C*W8mqu;`}RB74wEyC!gH$b z7Qwtng%u58(DIRe`Oz!r3Gx&_$7@Fyq?Y-q`ALlH+LL0QK1ar#2I=J01@qnm5s!r3 zj`_vuBo{-B6gr=iM=)PPZSd3246Y@JV|TDI-~Bc-m}C^whX|`*cR_4U2 z2Q3jif4@_OojmsX6Lz#Q>l=7;(@x%#lk9KCS&gWp)x{0*ja~X?!|hnr>M~Va#Z~I2 zCUnF(|6S>FckYUPy{QcDll^I_^yg_RdDSZmnEbEgf1>dOBAcKE`K$H^ja$$SJOg-<;n+8x_SZyKR3r{=>BG$LzN#hg8_`=OIWbL>FVO z&N5Rsz`G1FAM9k0Y4fT;FjHPs5gIyvm+Aoy^2!ln3rA|_boc}y^|^fn=XG2+>eCtjli{DZ3Bq^SBQG%_eQIe+Cb z<^LydAHIe0wZ+882@^p52_ft$$1EPI_{_E#L- zC28&Uxtm%QJO?z`(=C>lOsJ1#9e3Ax$wxOwG3qnxQ=IJJRbG(RJ|AFN6O7^AR4xP_ z&!dMIl}$B1&vdUHp{)mFmC5kw1R&r^?}cHvdk|1;?SQs&Z-4>f7&Lhw^*a?o^a{ld z62u5|^K-nLo}?q0Vw6!R>e10d0eq~XPO?0$Lb`XP+^27wN-4qT$X)?=>$arFeDB>h z_A5GU4JBXUGy(;$#xkx__AEkFt9W{RR!)mu(gFn67hmcdc)n~W@V1^z>d-3JvHbAC zPDdw?d!eL+#w5vW(`BxnIFueJ<~qw=B(v5iiMatJ8|!13(|7ny62qJkn$dF;EKEqv z6D(ZDhjLP|kj}IhG3-=pphv$ejW*&{OxOI9tX>p_uA?=Rq9-IfBk^_CK~IO{VT>l0 zA5k$*dlpfn6Vl|6TDbBGwJS;jzO`941Di=W`{d;woNHT3+@Ht^O?yl6%+BGHdtJ7S zruWk3Ztq=$tFtzSgTslBYk|uB$M->GAHM4@tx*pZMDsgnJw%aoOEVIkwyqG zA}*cg>evsLBxF-(ZJ$VS4=JOyvUfhtM=`f21>(Xa15|NJ^J*53yNa_I?=H6_k=IuF zysSr3NV3IT2kY}r#$AA=6kRkk`2?CLPD-!*$)9>T;hqT zO&jrwT`7h;^m*M!DuD(~ZFdE8mYG*aMSWY%HDv3dg;$bJX5l%aRoW1I)9|9!T6#jH z3ecp1eJ8O5)bC+(NfRc$^Go82VgJnAbHXg-xge;U>f%A)(DiYNZcxiXDsd7js4SG?(H>6<2) zP0}|&yLR7eRSN>^!Q{Qc26E^^lT`Nk*Vn2y00zn8mkaoZpx2-)P2Y7%d@*-FqJMo$ z@vmjH`&@rj^$V-t73h~T{OUO0tjRBB_@xZLl;K|o&tF68@9xJhpW&B(^@r2>Ynb?- z9wyX4tx}#IP9l@U$;vXnO#_BPnS!=2IR3-zK;&O155)f-t(ErsO1R%; zY>caX!lh%u_zO)2QhI zNY2V80`Yyt8I9JC=wjB3`jOc3ggn{@Wo&#D?lioVembN#Kn=ag%OvbGgvD8^F+N`z z%o1NI9sGN!6rw3X{@KMTMSaR4Ae8@zREy(R1S4+NQpXItlhf{ljAc_aUv0 z(Cg^X%ks<86ZX&x;K>ldhcov%cU93%o-to`;~@h5T9nq)xjCOoRbhe-G)HKvdog0Qc?&1)w z5uNZDf0^0voJKrH0e9=Z_ zCM@1A*6-ARoTUQ)jj8l+ZE}4*H~J@rHs7lLdhGWbUf)^xdiwSoUf%@x_3ZHfSE{z0 z*Uvx?7KXD9&DA5$zAC)}Wm*qF&u_stQX*><`0coo6;AkE-ccv7^sz|S|KaI zMDAM7$;m~hhh9Ja?a3`HbYQi+6tIj3u3lJmUUiVk{&lnr}O{~|U>P$I+jz-W^n z^vaQ(r!tuYuN$zGxIGdv`Zjk%J6>oV8jr>IZ3W}b49Ti#lqX#|V_3GNLPacw&A2># z)+`~l!mVvBAs8W!oj>XMO4Gml!TX$y0U_&L;)0Bgaa<>pK2y8(*qXXX*>a~-4>+u0 ztU7zSaA#5A`4=V{Th8fNhCs*>^SG^02Tbz`-?5<3??ETD#g@oW$K?h&NouX$WQ^D= z3?rF{nmBcmV)a#D{0?(b>!RYDqSSo>nI|fNbd|GA;Uq<3_ik5ped&2(w2xVxch;y{ zR=uY=tZ!T4%wR0Zo=5NzalvGLwQG~{p{u3Z7mG?q$Bh@Y6pVw$250exAo+3XG3wfb zD*;>L`W3YBZ5V;~$m@BhcqV2(n8xz{|iu&^8NdrGlT_3k|drH%dad$-bomX(e6C8rPvYYR{D9&_e|YGjhk58q+yrgokuTTIF{^WQqb*meWaWpcTw<<5z0){eNr>KJ5@0Kq8jdZgE_s{UmU$FL~GZJd6z@YbaIMW zSmn2v5KP{7OYDg2m9f}a%NMI~P`2k~)A+?)X0{~NlwHh8o21}F6j^8_tb2h$Jt$v> zd5cj8pJEhE6t18-IgDe!Ff$W%V`67VrjC>ljp$#9iFC{JRU6K#l)68$Ta~2nI21SV zyacwM?j)uv+*c?~A4hPKB_mqem%-!)_$*$pt~gkRg=ljS&ObITU;0Af74NweaM|1W zs?*tSH8OOLmz;0^<;)a5q_5nVYT$myYM=aaiTMSLyt`0zo8~7Th_L>3>s7n@591W) zR$*X}XUpJQyq1mUautu~Kl@?w70HGA!H^l|gs7F5)>f63 zwBLJQR-mP5i@dE1A+Xb6#aY0OYj{@2c7L-Xii}&k!spVp?A;|d?}E*#v*1E!A9~$t zy?`@g-=+^^<@*ul-9^+P{jO4a(`E)|j-7Vl#_^~coh@(&0dfQF`^w=$$SjUtX&coc zb@v<(rXgG9I?c&?{G%9;JHwZD;=uyX8YRmsA`mKhQ2LGt;k@^%%#-Ss?842fUkLTt z-ecX`W6-N`=TD3dFj96xm%9Nbmvqu&l_REfN*+I9B@Tldft#UdDVUWM+O2e9D+#tM z-u}EYoX-6m-=&0yJx7Ix(y@teV>nD3O%k^8_>}BLgn(7N&nMwYF65&Qu$@PxN=f%x zjuhMS!-^SF6D-y4UhXYBkF2}(T;=b%Rl9NbndEYrG9aI~;Yh!%m=lJL-_y1lnNwt8 zL|zC+*1YOu3!Y_MhKU1vqwn446I3~YG!}2b$i2n7cn)3lrszpl2)TX$+KpTlB_V#q zKC54FTd%GnobEQAj(%9eQ3qQTNUj{OzRcU3y`8pK-}sYf;Ty=Kq~e4uL`;z+JJ?V{ z60ok9w_w9VxC&fXw@TD%T5s8eN~Gv8fAKdh-ML1R2xWI=G_I5G;2b!!J4MDV(;0>^Fqtd=3(-|$9>3~WKjg~u&IdXR8R|Zq4CTN*J@EjlH}|A`*#Ea?uvVo zCWN_PF@DUm-Q8u;y5l1F0a-XCQNJoh(L70KGb z;4>x8^STj~=XQB#whI1ExroKtzw{RTJy^>EtIPP4QU|3oiwweC*k^QFXS z5AOw1>$x~CMKMt{KW89$2ktfx4%D$zYV^4-DtB`CfK)0U;a}bW`tOu+U9L1dvn0WM zT;QSzc0!_RXb^=l-D%s?Im&&BhD4jjNt(>W`i2DXGqqLSUX$WDQMfNSh~DnS9G4n5 zfZe5bGTjuyi2z%7zy$%BtTVEJsiF)a4_}bN~xZV@0i*QwCe)_?Pa_%x#5M!-qdT zs>n;7VbOR)UHn);J1*Q&lVI)ap-0em(Xi7=$RXQCEnmCM<{VSa$o7$|F+WKm8>wG` zl6+V1g){>16$T0c*W%2PUL|QfF%xugU>oc}p4D9S~d5kQ%%!w=&ayPQF0X|{7 zV$KapoKLUrdYUU%uQew_EfdD8s@6$ZelV< zn8V6(r#IN~mK_h)?f(4vo&oO9Z+8vi`W1?lkv60%8;^&to|RS}k6-m`4yIqyg_q^- zm<&yQRH>}K6pY$vnKGd78&jWg?b_tfX`rZ#)Er)^BxZh-RL)r{`|=Zg++CGMCqk@Q z^SyQQ@+SF$%~$i%KHQlev?CJOeTOB{!r=)K<jFKDRqofk1e?v>%5Xt37Pc1^0^-$W^3OV3gX<~zWBG0{# z^I4ZLtmM0PGe(Q!*C@64;#WVW2#G#gQHM0b6AZF$c|fdFjBH>EkDE^P{CW#B+J#=} zPMkAoboql=iKMrkCQxHKTlKs~I0=i7J`cGLlCKs*`p^{FlX$YkT%IImge~K(Z53|j z=WrctdIasn+8Lk)A0i*kCM=bA^A z3GTz9C6ieU1GRKk!L2#j;6CkdP?=G z#k(GoZ<{~$Fa~9f!@$(+&CBQxZMulMacSm=Nc*LiAC0%W?sye4<4-MYv@9W$#nQQ& zhgF(Kbkxml8I67^g!KF6%^S2rr(A1Q9>!e>YVA-d5GCoj`JAmpYZ?x%w%#`iNH{=x zXefQ{FP$>`Zkjcu;ZCW&fU<4ju~fu^iVF1S1=TD9Vb(!j0L)ZfMPYlM@pNWOv!4sj zEG!)g2Mp`wgb0uN_*kBrY+=W2ODKI7C3J)F>n7vB^(juRqb~6D5!=fQe#=syMPw3r z`i>Qm)F*=QTWI02aJS5Hcl%6J`f=tK1N-jU276tbFWf zygIC4pm^$4jCvR8G4*5ewL0QnXNx*{w33L7>u>^J${zCK?B$C$qDKv0ai)psuW;}ZSVpZA1yH6D_POdX{Sg^Xw ztl>zX7*Q``-J(GAEbY{}b>1=?C+O8|X+b}6+Dhs(ZYC(PcM9inmMn7o1v=YqA5Ra; zl}hG#_hD$tcwB-n>xBOcrlb!`2;GZv3?un`c@)`Lg(NM_57@I z7c>N)dRhPr$X4-s{oc3kBy!=ZDv13Tlk5L<&ikwEzpVHm zFdIX}IH0%WKu32B>fMMNuY#rK`Oqes0%9$^L68;6)c~#^UpgagXI=^9Y+- zMcuA6d(s52f>@82gjm#rm1w~(&;kvNsj2h6ipSf&{3E?qJWW*K01iwF8m^XGL~Yh4 z|C_aBYiF985|c{oMoHZTQ**5rgZuv7WJ$2h2w(FL5rZmBiUh*B%PtG1u zCviJBygZs2NDE~^LuH7_&KJu>lXwi~nJP*zS7w3>b_r0DSt?dvwKdSzeh&?c8jP!H zD53gcs9^4kT6M$}{N<3$1ch>OxwUQ5{Xs6Dl@IT0z_PRQdG%!_!Em_^Rl z5~DGlUViX?=c?r%UTm90S?&`~zTsdNAwd#Vkg4N-CxDBqDBIe{!^7U5`@A55W~(eb zOiHwyP>_5ik*~dMZ2BBSj`?oVY7Jvz_5PROLhG1&T+BNtZNbPiZ!|9OC8>{#g81-t z#$@_5n=FM>hTrft)6thZNjbeLHP6W_-Q<41siGsx!cv5t#M|=fje!Li5m<4{^ZxSU z2!!5=w&ek`((T4hzBlhg=Koo^{QlFd5woI+Ra!hR0cyR_)$t{|;H)7>E)x0i>Y(0~ zcONUG@a7)Z-6#5Nml+`$LlezWK61aSx%q_4B~vZA6TeWq>XSb2&t@uc044{r=%n12p>%a@BaI zX>Y7QT!z6fe{FTZC}0CQ0w=h9MpE+&;re7Nf`3I+uqkV9m;Zb{D)3g-vn5^U$J`$P zJ|UQ9PMGnp?fl2;G~T9j!ca`5L$>Enp^;@;BFm+(CmX*&$$2Il|2HK3x62ULhLxz$ zb`eo``-{jKm(iWxg$6uih2XxYINE63iU)D$bHZrvpj>zVP5_0C@~+}<>@$qwq8C(R ze|UEOI_cd&5r|D~m{nv1>*90r1!49863hg&-FQIFXJf$ zvJR=ix`ugZFaQsF79s8YCRM3(s z!L>7Jt^8pC!*!}i^>6g2f6t(o7Wl@0m|Rp~Txg10^*mZ#-4V3h0=ih6?@1JWp0va} zZ9Ai%i~6kO9M$o=G{LtoFOx4miyR^3xEaa`QOi{|B~&1gPG5dyjwoV}BfyrD}Q z&;yC?j+f9&jnG@7-!$QU$V;&g>L)0|Q{!2k+YJw$=q2dp`(_>yU9%-IS}Qjw$}5yN zJkzDFes)*W*FmKR83{h@a3We1=f9(7FRMP{!5RdD1!I?wGB3qJ&cBl*4|4-3y@OO| zA3ppbiswI&Jo8&0P(67HS@~UG3spsXvNqXHpN0zQ-Gw{XNLkO6*R&T|?!mfPYwQWU z{d=_NuMwkv`oPF*-vChxH^3gnHL^CVp;Yk=K=~GWOjP9JR*_NE$L~wfQqT=Ritro2 zp#Ko+eS|qIFCu`PUE17`R&}IoWCXfJrcc9O z;P8CEgb*X_$tEww8_qkq`BO{}v8H$dP-j8om7;(olrqF*XoN24`oU+aJRMI@o#{AG z87rX!4PLAxh1_Tmd__elaxnD^So(fZLL#25G=TRAi+X#_u%fX4J1f#2@u@ff;6tdA-IOd zHMlm~bY88jwa#7ZoU_;7_x$#|@9y{8e>7dyRm`fIRW;@q-}uHijmjlU-V|_ql1Snj z<>*Ll1J%my%2Aj2uC9wjK>|Lui#v)ASQYlC{2zPT`v~onGn!J5RoYh2BfQaQgQ;3< zPNGj11-+6b7s)D#55rw5w0MhO=UVaX+~= zhpdY78ZXm0V>XOMQ8Vk)X5;#GxCx2A^KB*fQ#_w$hLh)7-c^G{TI7Zz5Ew7%0~M-* zaiSgS3x`E}^XwMfEpHIG7%lSB)3Q;}Sk8usGBqXFJ4h1LHoU^`y;NK&h$hc`?$5}N zbB$rVd|rMcV@i!1?AZQLCwn?-Dy*e%0~Mp$A&@g4mNnJc1eGsi`?-dsLd6)xbFTcaD^ z#poHL6!p4? z7`q{}+jI4wC&{Uh%p%(F(TX?+3`S#bD{Eg??T8Rsiox2)x|A{GKRO zKmcAo`g^o5GuJW;($q5>dFdxFFgSZDh3}%FU?R=lF9I*~Ry1=IScurUFAfa~^+i3i z>3E+*yym(#zqVL1XJFEnzZA7}X-)=7SZq4ClTWT2B2H#&oc31Cio&U{PY|MqpszV2 zy{dSI)DALH@ZVi*Ivt(nZdmDqnL_Go8vu#iYTCUS1<-4=fINB3g3)n{M%xxU?<&h= zxZ7ujhi@Z04Cj4hY-vxrozy-uN+xlZ`EVU9CaA$9=zE+Ol3VsG`kCYizYHKqjuzur zt?Xq}JC>)66f@$6?Bk54JSmNocGRODWJH=kQVa*(Y>1Pv7bIUPwMQ9xl&^`7QjNh` z2*L!zJa8FHswHc9O${aHGY*Z)Ouq}GLdHtDv@ybhTB|2Du$fAK)`+=`S{ZKW^ z)hHia2K6lMHM)fn+bE!h=*&`&OXOrO)tepTmzC#ddkZ*VeQb3(i@B2O3hWRhT=#FM zUYlzks06&PWJFuU*owM4Qxd7m}zR3~cz`n>3i7plSpsb_4 zyZ9(!U}oR#o_7zgU`?>*V>E-`BPJuHHMGL+SO=XzR!-CGW;P-Vm^#F zcTdp5U-(Xt4SH8eKplkcJ;sVpvnanDQ9cUFDSlRAXL&8q|0u9VoyR)0lKLq1AurkKc$1g>gWJTO zy2ZygYKIVLE~VMYakVYqLb|7Ox5@;Z^qdl7mqY{#AKB;2PaHmR*tqh;G;-tZEgaJ7 z8dKC_sXkW&;P?XAXoivEpqo`|g_Xrj+t)$Jv1w-OlTp*jXDSn15p+WvC<>KtN?Jm! z%?b>?rnwTMTyl>#+k|si3DZ^7N#34(d>DuO(1>g;vY|Xq^9X&anKsXSw}`8G&XR#< zyfe1_Sr4h3L(HL)W$T^VNtcDE2!V>~&H`$OmijRJG{tw1X{m^)MyGnpvG-XztATt* zdqPH1N)QcW+5S?AwDv{`JbdY)<#kZ1&3?JJnN7YfO|f050FuM=@wH7;5P4?$CkjZS z!&;i>+RAxw(YHY|&%mBcCKF+;{Y2DYF|7GzGor)L?Sp1gS8rvvl5NkuM$aV%nt4Xs zSi<{kCrv)XLJ`VQE4_&;WjsZo9p|>r&_C z0)8@_=4;`&WLkGty#$WEN}9U}fwW;QXnao&Y9nfBUUJ~hZS*~SDjdN1L3E){gbh|E zf9Ep!RBaN%#DB84qX%nD~MaV?V55?=Ap6Ghty zseU{X*B(6^l97MZT3IGtJj6Uo)c!g5t=U2G1>gEbdnv8f`_DJbb~08zQ#sHfPZv&= zonmOK{w2A~;rgv7$)uvVN3i{04cY(XZAf|-2%+9v=cpf`mw0;Dsr>jC`RwbeqCKI8J#T_UA55`5>Lx_sH=E19c?p*Y;jZDiWp_w zY`ea_xqu;#hWWiz2-C4fxlpIX7gJ-w)*fKn+cj)~!J9N}qF!qyZI<2aTU#E}CD_tg z-Mr&mMb`tZ&Q9*@*ul3f!tHhA+q(txa!{gJ9)9j8r1r?dq5@6#ljU)CwB$pZRg2~q zFe2DH-_$kA;E>Jtzc{u+r<&+JUnyLn}BjE3)S{Ov>l=DZd`*q_*fqC zgoF!|#3`h_N!ZjiUC1Oj>ih7BC~uyW8QQ)az`cd$ugeqYlCrPpBIBdJx9^g_)RH4( z9sYsteklmSlbUX!iVt1ACC`m8a8qjdcxF zR#>~?`Rd8yiIW50yxi6Oz!BO=JbT{N()C6pINZi|Y3qSonNl%R!q-Anyj?j4z=<%V>EN4VoJ2*gn2y1Wl^Ky{B} zQtOl*!RX%;*}leVu_u)e?MjoKNIw1g0(ENY-IMm-0ZC%=A-(aM6efZW>$5(=Pxwin zHL5w-201uzHDVp5sgte5%{H!BPQX)L7ZcaOFrSPll>xYW6l;h^T0{{2+2F|K1tn}u zd3d7&c7i4#gn_jgJx>KCP*^} z=Z!%_0uDb`*wY-O$Lry&f@G?3*%tZdGFg@-oCyI#p_Rz}DA9h%{*!0KMb&jczfI)} zlmKb?nJbP2Vcy9Nexb=Qo4oCrbJvNmloV;RNNE}>Hjj`F11c)i6RbnasMpgFE1cEc zG8wHJ9Bs?=H+NU()NycQ-ZFf+XAsmLVK3vhh3tiRScYcPNU9mmJ%}r5Yxj&bhJf2P z%D0yaIRWK}K_&y;+%0yoUnnP`HHIdY=4&D5hlnaV%saeu!X_PSWy+9+<{u!=*Da6} zc%&XS#cm?OwjHLLjl0X__}2+d**l*WSy-jlo6yuK7id!*W~fFpPZJi|T%Jm^Dp0$R zW>>pCk*3DB&L}F?wnH~}4Sd5LscAcXb%#Mp%0{BrPd;Y!T3>%S&X8A1>nlCp<`{!1j>eEghBH7B5 zA+@gt7A)9xBTvB(uK*8&2I!n9jHv5%08Wto!}1G!D&G1A;1b>e#gJOe`)e&#>C+CM z3L5HtQtZThySA;&61b+1N3K7j3Feg`P2xlkHdm1MSD~IS(hxAe3YkTY; zUcQz}A>qF3BKxdYvr1c6;t{pw?o<4j9QOq|)%eLEB_Ywf#oa3r6hutfGD_l*87R)8 znH$I3D7Mr}GhS-%uJbdz>)l(MA0V_tT9bk^*bk8Z1(``uUEw#l{M4C@vh`fVZFiH5 z6X)~KD3RYVQ`CKBQjeMBW4;s}G3ogfWl%XC;1UzYul=1q2_-1#mnZ9}Lk{Jk zgO^xJ1`?lwUx1J%?nv6S1<_aR9zFsLt8PrrFJMg1PcWuTRa^e@_#L95;w1B4;orzl z{+_?g0}M#tGw>xg;yq(xdCs3u8Yz=oDuf6rq9J3GE(h?aqI!T{FuMW@ck{DD=|g^R z;$Qtc()|7CM_S?z6xYY=l*1*r$y*4oZU7FI{{g~Rr^~z#HU(bH^keW6U{bmj&#f}9 z4he6sMBu7A*?#nY+FSBlIe4pC|6(0rma963f(rhyGvyy!Q5~SWlktb0Reb(=2Q9&G z=~8MAaR1Jj9=N&-p_`z(G}Htlp=}Y;{Q~WqL?9pxrD^@m#CJVZn%7N(4h* zw%^k~Uz#E!9ym1Mc(q9ahb}VDMAzfn5Q`lomLPgt87&1L0-_}2!ro1@=dR=6^ zZL3t|;`=X;8o&m@A$-ni8jd`J16+H02vvllCml$+5D*CcMI`iZf9`AjDR;NS1-?QV z`2j)#v?l@`&w}*FMb?hnc9Rf>p`1~daJ%bG@TY7)eoMOSPXT|?>YXA>Pe^2xHSJ`% z+9JDaz&GlQw|rc##fui_$#K*?=VLlO$gI)|tZ4q}UdzcJPET58;e!SJUmJj_2!S^* z(0?W4`W{e~(+t3~lt-Th0mMdB1fB?F6h4&MT}qsZTq9cmbdUQPE0S<3Ps&@Q8Xzf% zDt}ZiVC2<%0N!+6LY@PA0s=9#2m-Vq@OR)@iv>{kV@~jw_M?$oAd`Her;m6B0Veeu z1u)+SfOTJH00&YYMSKUJ-JJkXYJ8C|VZXLT*nXa|*wzO;%>U!l%AQ?3zR9=>JQ6Cn zs5oHPT0WwKlzzdCm+$nPQ=m)6Z1E@{{ z=ydPxUIN>>0eIW52!RLw!jlCYixfCmJHUv%&lGV;2^hCe`oH$q(+4bFbHWggm-&mO z<8<>1CG@@JM3}HLtsH`g{Ot>RuE-1<8%Er`l@BU0k*Qdz_gi$GTMAeXnZQ)B71f)! zQ~O(O%fRf9=ElIEUm5xT{{Gnys*^b$HQ!>{5&#uKEB3WAdtS~i-zTbhTy(lpcyLqM_e)Qfs~DI=bwOsXR-k6=T0mL8N3Erpc3NX(4o zH?;;iW|0S>hlB6V8=<&%5H0hp2)6<6vTs)2(pML4pJz^XHf06#EuzqL85S`KQJ9bv znnlsBmR=aHbg8A9r?(^bq*c-M6)6*iX55}}Z#y+xSS3Y0d+7_QotZQY7dof{`AyHFPC6n(ZmCgS8 zM8FU2Q)!mO7db-en7#wo(;pzlU@*&R<&=v3e22X;!Kozuhp&z(_E4g?@x0$X0M^+( zql#Uvuh()Bw^`?W>#;Cf2!^}S0&8uwgdoIz00Wl@UO>c)TsRc0HpMA}u`57N+uYoG z%$Z>0gkt}}VZDSvVO_HMeXj_!w16iQhWf3W3=FLRw!ZY;GXj6)Qcl-pwIxcwuIW{z z!MSvW@5q)kv10V(SW}2A}naPd+b7cSES(iThh?)>Y?ll)P>AjP?1B{CaVR zv~UpGM~3_^GV>Z|F4ZhV2OYEUnF%x1JP$q^%33)e+0B&nsCcPXKjpxLtuzSn7%y6W zG-|pE!eQUa9`cPrsBhf%7Ye>}>sh<-x14J@GBCiDjq|@|jI3*&HXdiru5D^fQGMTe z9%dEhuB4$-i8b~R#TFgSf+m>UsawXRR7bkVJi4QB#0B;1486m7ic6$|B0EmIVolK* zvhdk{eYwj=b$pjqrZ=3mwfoOwWlN>aNZTvzBDuna2|eyL1+ahH@jPNsZ#WjSD5Va# zGK$<~V$ZAAg|vQg#E}mFY|Bebl{rMtatqdq_`ZMZ0@&}*h13ly)=2eJKF?NcYc$M4 zk1O8McO6nDj08wBfI7(0+t;1(zh16tL&5hKbSy5)%*U9w%xAU?qFG5VJz-?mhLN?% zB{ycpz7Rpj(vo<%xIIZGpndv^OXdfN+lSj?eo`oqnK31XQ?2pM z8~Ypz({m-!9tS_PmGQ`onT#uBzzpc=Z#p|JKwr{@T7~39=kQ9}-&34i8#RlQ57pQT zqzMp@6N3XgSG_tVATb?KxzkKOs#wlqXvmH9% zkcvYg&Rv=Up00qu+oxFqL|aqN)bA(P);8(|1RWe4?5al%$CRzssf9D#WhAmM8TMdm z%4$D@;3Ha3Ev{8}2Mw5}x@H?=3@pOwvJwLqh@4U>`0qG~Lq5mJK6AxWCvfr6nzDUr zbzX1IRnLTykB8DV@cx~DIJ}n@IsMbNvQ_KT)(Klke66tAw^fM7Bf|`)4OgZ4HKE9R zy>dx8*@!0aCl^H1>~3MXxXG~=RKFL6u;SAi_sOEq$JeB;WONa=l!-C*Sdx6jTJQRc zW-Vk1stXBp^?2uH?eLt$x}6}Cy%B@`L_`8@VeiDt_sFphlBmN-HcC=%^m6Q09qtzR zxY^jAGH4m1&tb&RvX`#7J%4|&qe5o?z-H0xtNt6s@wHup)nliDXd%n?Cw^4XR-w{% z%B!^BHd`#1GUPps>Qv`G+;meOQO(5dw&TytJz78A?PmTEtoGqM;8rs*ewbc-M0NKq zI+0#(oIiX=s|aw%dt-no3;29D^n1cTRIk)6H|iR<+1qh;GxeN5+)2lSk@PO6YOAw= z+`aX?w3X#tF&XkHh6z7F(&T{l-P|~M-LM5vg$00w>e0JH=OqOeDIzr$`_}NUdpEBJ zDfV1?yPpP0N??}$d??aqm}zQ{Bg3eR? z3rTsEwkG$%pQiHuE5h<+VR!xBphhRL^x zu>_D5L4rJrINp^!2YcKw2Qp zbheoR7#dy59dc_uAY}f9v4EtfeIsSeHso}lcc*k2M`|u2*2ra^%D(UGyBN(GLU!#T zk@zRF6RFFQzOP_+KV7hQv<)PhZtJAtZxs|LgQl$pjccq5>Oa^_5?Ca)zd&>JRL*Uz z3tW{hh~!SH?J8X+#^MNs@ot6YGXZ5Z5=}KJx4ND3k9>${DYx{%G?Ul)8D=gCr`{Zv zac?rWE(V#W(GW-&K=`M^1VgKXod{9byzW_)h+I8iq*cl+87LMt3S3UV#k@SN;G|%`eN1+FXOFHsskt_sDZ&DQ5Ega}yxlc(RQr|#l?S1^O z6({-075IqBLL&~IM7poUnonywZS;Ia7Uo}e>vqz*qrXi833}&bU-c3zZj)7&)Vt#` z87_w(7FsQD>8|$8ki<==o9!;wM1CgzCs3(`*cQ>6zwGuUqHUdK_TYOtakFTVMI-sz zg3h9J$y2c?3l}@w5X~h6_kk5%cK1Pw7bxM$bEC%7L0JwIdH5^UCsWx87kjHOuAU@5 zOvMSuiN*#d`{e;F%+C&@3Q|p9 z&;y1k)z@-S_31gpoJb8Sgu3HeH+wS0nxri^!o$puzAkLn@r^)Kj=fK{-CrYQ%-m-s zkon2jpFHNk&W^QY{1zu3B~x27!9+8m=WY=G!QRl+mRQ*Ujohi8Y(o3p>{539jjYne zjey1^*8?r{amN0Arkv1kly-;Q`FPBlC-!{3Z{GD6tCO79S>#&vZ_f8Rm`?XB92)uc zWlMm9aJ=8!J1iyZvTR?56)i|JynHmsQR5U*)?*X$gGh!1g^=_`6oD=(zNA#u%P=(R=O|c9Y6Qu z7QfmisoG~iHcBP$x*ogr1+NR&A{xO-bBa2LK`hLhvD!XbCwoh|QWILbq9h(>sWsMq zcY!LoTDJZnXO+3nKscPsT4>8`2=U)cI?wi5o5AODJfDuSoP&+E1OjZ+c5T!qV*qJ6 zLmJO5dRjtt7c(ny-gDB;t+tk6(`)yWO%@6=^*D-xyqr9~zs3FSbXs$!rxs(;$Rn%) z65x>*y=h=7`=%BVg^A=xE(TQW;tnxn{z22k#0(B&pM6tD@5YxcKwypYnmXc67-rVd z^)9@;yi}pd^-WQ@I`b`o`H3bjW)4oAyB_3K?WU1Z?eoRP!kYbW-JD{eLQh(PHJfBH zE$awfmCK8bUWQ;adf2K-fY^h2iO5{m^2y7YgKY$l=Gsr^2co-)=1-(LR3(dO^Z3Y( z#hu>{bTYKB-z(eB?gp2hMGoz_2w4A07@}-{X>%?Ba>;ez0p%nCwg_XAnW0 z>)~{JG^aS)bkU?>*aDSHwK zXnqiyXNMa8;z0h*k2w$o0=U#Kvp*?I!o4eQBH-O1SxLPbpcb3QZkhbfgyghylYocK z9xT|bA(TEzEP+S>Btmyi=DOW&z3r)+5S9nsp3`mA*3!;*9)1^(Cp=Zye|xj|@eifL`qax4X_YhO5#@uPH)!{i7-@+`?* z*?dW(+G#6)=jAsm@RfI)XbTP63|PyeBSO+;jdXX?lk&8-9}24ZI^YUlc!hnSb>&4) zj7f?DVKp0;1N|({vlw>!19baweEbg)Q`Zwv0D7O0xJiG3&hw{>BG0@`Z2ICj=;cLY zCht!HJ~?zw<~*uqQL0L&&axPj0qgSOB766BbxTrSL$Fs3wyoSbWs|in8O0?T3;-JM zN*xVOu?LMNN^yk)l|=bnWc2=7bn@eLST*L;Cp+@W0Dk+snhc(G zY5JUpZY>;8Lk^;fDPj`^6J@2w z{_hD=ydz>81+^uR)KOS@*ZA_=f@{7#U#oRDW+V$ziQC8ZD87XbEwl+$r>8oX@zc*^ zdG>y(9fj`Hy2Vh}x+RJ^i&7;Jy&`71sIygaiuKy!vSq>CW)pWKg0N#u-g7jKU$=NM z%tJsO%kHr|F{%c^^Bd5|vKX|Zrm@wLQf9uW=6q)`u5s&HWk-%inC{=SoTfUAL+COk4BfqCWu_WW@;nISxzuEm$dT7bzYs7sEfF88Z-l(A z7sMHz{HVaea)XOp%$zwOJYGrk%0FtJmbX_fr_6%ky+X<8?}%%OzQoD5s;)e!<7b5z z!$g24>Fa87kdcLJ)pmg0nb!yJ>4kB&D7bH_sCAe(P3RX5;`y3b4tlhA-+LR*%1G$$ zG$*K?EWPxg_DDx{j<}%w$jyW4yk!nAdiJ@tzNNM)S!iM|fwgs&`+!K$S0m(w9?~slA>7*)u+gmQC1+K4g8> zv?)P?R8Af1tERmN(NlTScM-IuT*l(we(X3eaq^RE-WtN2);9x6xCMW!_qW0ox z{g#-uhGZ7DI`%9bGmsnFsEUKdxOf}k3?)axGA;P>fgS+#*S**NLZxQ9UTL}`O`S10 zrS0=b4q~;2TAVdW)-pqVl^agBetfBVO^3|KNzTp00F{-o*3xPeWIMErkFTR2cJ$av zHeMtf-_k@$=w;WrEo~gw`J#hV&&sFlKN~ukowm5js5z^xL0w`&nNa=uly_cEH&Wwt z$8rcyiRc$PlM1euIMbv$F0n1hE2yG)X(t^DU{%!^_*Ji?GhM$t z&+v9R%;>EB#heU8b$V)vIy{0l?>bS&(>J7Tn#vy>xKd*|`FWnIJ?Bi($OIhLi2T8dehq8*VM49ilb^fnznC~Uo~1=(|j(8WNRO?R(wI6>>5FkL6>G6lV=Qlru`&J$+gno|z{oTv?`W<#&ct}| zfaIT+mV`TIeU{@L<~UT!k1`@lWR5l{&(<&%fNqMTAk9SH+g2~kTSwz5c6a|=7bP=c zlk~XuhF|JBe0uLu6{|SSgrEJ;F09B#kjeln%FM{o>>Izx(0e{qS%5@c%bE8K99PrIF2$p}@9S zJOzz{J-7t(=lzVxNI3rvWPq=Cju?@xJB5+fGd&qzV)wYi?8EL}g1-hZVrK(K)oCqw zP{Ls%Kxrz;Zim72vt|n(s~@2FVQW=0vG8IVFA5+ja1R{R_T6B-?TA|hVA@>Dz_|d{ zI~D*S_*ecy1UV_gKg-y;W!W+dyoD%V;lR}4GzgL(psZjZ@z*~4iF<2 zKS0-PRy)PVPR}vzox%+dou=AXH$ubW)G8_Gei^Qdet>-L3y)#LVe&WMRX(bJ^rQxx z2O~TSZqMj`Z%#=Os0GfZyxPgQ7|q##2+)`Sl0<7D;F&&ctRG-C*mIImOlMXnAKhAt zQTkIw{J)fXfTGYOPVG0^2-2}sWTh!ak;~H$O;vY|cBJ|_k$9js;H^!{n@hSIn+iC* z6UbkqGMf*v-8+ZsUtI+w5ch?lz*8y03SbiFO(wB0$=;y<5H{!pO z`TgT>?iamnSAJmV2x7d#pn~G^;s=No`^E#9HBfbDgYt0n3i0N&TI50+-p1(;v$<66 z++Ni+*vo6?HjkDTc>VO0^`UV@1LbffW7(xcp=iE)vR6vVCmX-YRI0B7c&&?QLmkxT zhx&FOKCVb81#O#q$D{YC8W3C0wJoYlH?!CoVhznjPOw%eQo$(K3T>;N&I}d~K0ez~TtMo^i^%jFX#U_U2iApoc&=ohb0KYLc)o zIi>%`FPYBASYNoGK6$twRb|D`1X)-NJm;F4-pGSY=GL3=K5pV@vQ|!Cce^R(7RwjZMX+^;F<$tO;Bj{8cKMo8F9C` zMK-|7#^wr2@^Hd44tBTsHYEjn?4XxqRHiAN^L~Q4Ccdd=%9b|9u3~Xkc$+<+fts0J&;whu$_X@hBA8BB8wA99Cco%P)!F%mJrph)WI%)fYeF9 zDBEc1&%lufnVfy(uBT;EnD`Gi(W^IQFfn&N5%WEM>+s4`xPUo*=GbD!&a`2{@iSYv zQMoozg;Z5*RpYoVFvYc84^%$Ls=>yVi3>;>;Of@1VZ;2J97bV9OI@tb;tKS?SAP#= zI?J-7=1Dw}WO$g%@9`v{){DG=_J~WKT+Yj%dsKEm zKsf}h#T7}b*sGnR7bp5FBa;E=GM}v1V|x~C%@j{wop=~T-OTdBOH#(YHH-9@7P>uh zpqknmZw#C2ZC>HvKvS19`_|p?r)Dw+vC2#gR=2Isdeb#wsOGWSj;pV}1Pl}$uB8i! zd(Z9Ox=1$N`kGl;6>neEj_YXZ&&`WcxDDbB?4(^iURGvu8G3dtN}f<)=D1FP@!$*J zV;5dDh)2;lm)9T*o(DnV3C5>=V&O4!rnz-`nn?yf4*zhM?R1DmYiHr*Y?uw!NzeRu zr`*qB2AJdYyk80`cu`=Sz_hG7>WJ3EQz6_zl?fQt_xzZEu6<#(|kWd-tkYiLZzp>RB!-CzJOIE!&d-%3ajQpP+pa1HetBr2mD0 zrSvNl^a~vHul7+T3 zO}6{Rava0_>Q8Kru@!?xQR zVB*wN^_#F~KaKtR`XLCps2ut0q__OC5KG5-GDVT)K5C76UE*{EiUPHl%$hGo-Jl=n za5~kOr3qG_KDc$QappSX{BcsaeGaH(u>E%KWS?%jXWKKs#k)n3I;n7(A=VJIscmB= zpDZB0U_Z8ygDzR}&{q*wt}Oex_46@W6c?%P^FbG$#B&jTc7iQyGCHFvH+y?4v@Zmn zX-kncHw!Q2CkY6~)`QmeNwnrVNe`4a7y^lrQ*DR6+={kO+LmV*Gr&6$Edr~E7~ya( zUD?OgkmPNf{dks~1hv73TCdgyL2uLLQAiF6P8RmM=X4~dzox(a#7n14ywH@-Hf+@w z6ntmY&V zsU(YbYSnBDsTm#YW1@4Hx$lvg0Tvu-SwQ!N_lvf+hPuhX<~bcH+UAMrQGs9)I&sBt zEY@$e(+S&>=~(u*+BhpWu4I+epDl zQwzIVCV`=POFL=_(^W>sr*ef6>7NYko#dj_CN`4{LlJY*6qGd#&j)10Q|*vN+?Mj( zry@U;e%tna*whM{eo_mmtgnr+c}}ourAeYB%GwuhuVD1Vk$2Cdt;pT-LVC1@56)y& z{N|KqI^%J@-}5m^dugoinJB6b>F+@2`7?IAUOv}o6|i}jhD#dzijCHiA|&39$LCY- z&KIBNv`-@3tWKdeh`KzBHzmcEuCC%A8^clpqZrUp;9U-}d>8mz2+X66gS52|)&(`` zLX0mod(t>V#H7!I9-LI}LSEAMzM0;v$RBh$HtL)yGd+RMebY4s(|!EV|DwUxFDBKO zb1y}0_Xh}ttGZ48l5*2I)+$+r|D&h#Tw1DIm7h_q)q7lCA=ZZe(p#!-1xre(oqNoz zXs*6c&d~EtD^yjR_2@gd2dQVfdVtMEU+7BStSGQ5T1DmYY@5qY=#>wZ%F|u$L3o5$ z+4P_@v!anZ$WL>U8(NW@N|jbLe>~QQQiqbdSUmHS$niE`F8yTvkX5u7^7N;u2&uhu1U$n}rwcXBaRnY^tWU~zkPUIt4<$;isd>UBS- z=9Q^!5Pd|phIIOF^rGam&Px~DxVeG2mroC*senxKBu)qZ+6;m3lX^QW%j?<<9}7$j z7qWLU6GpL83rma~+KsK_J6QJjP|k-LN4>H0MRVQNNWJ9i(37QURNFon#=G&+t}EOL zU-$R-^Hi=4Xc#w5=tYQ5FTwi3(S@f<8sI*DD58Po1pj%iy!dbM{okU4t-}q+iZ3X7E`-+TM1fR!yJ$UP0(b1?MZu9t^>S;8z z!934DpmD2k9p{}t^mF-MYcuQRr>XRTAD}qNXYAo63h}%Lz&~F(hF)Y`Dz*Z_TgJXR zFjs}-4^R(a1p-M|Dy|Sy;KMU8+_tsi#tv=aws#n8yz0f$d}PVE2wsu6v_gO(`Zu?f zKR~282t2!>wyhggpzL7`h!7h^YL9%D<|)7NrVkzplKcb5h}v(abh|)1m!qw^8M&L? zvh`nD{7*;xc}g9(aUb?tPdf@L0O$5k=N$E4E(!tdxB%P#dI`se=-|HNEby!ZK$ewY z@=?_T7kC3*pH!^11YO)QwbG0=?;IpXjrS+M;x|_J*rTEW~sO5MZkd1DmQ z+JQyE@8jiiKdSg@gGbEZiEz3TD8fr*y=_I0Z3kyb1G=NeuBF$zDN5H_zS^)QB!RxI z%9(*>p+#Lam_K*r_!ShZ9<%O>oH@Uq>IL*1Q`=TGLI#270eDP887KNjnfK@l;k7_e zIda8vsrdUj_#yv?E1*muR90Wj*2C^_OMmt+=MMb-I;iO;0fiSo3(3k}7dpdGuABx* zwgl8IkWcR>KO#-$kh?(w9?ym!AZnm+!TgUa7V~ON;}% z*JAdHK|>Db;b+RLn~W2A#IvaXSPBaa+6Ab>%5v`XmUVgwPA0m z6#gQ8hAi<{#Wnxl_Ln71cmA9HK|c_gTk|^QcGM8Y61V7S^C^Y~8i=fbe+1-4fD9pTjWi-`xm?N1W zq>Z@d+@V8i{kdiAxBd7-L3Y1x^7y%*T=u`4xaRzKU;O*IxcUAMyd%8!e+PH`g+=&3 z#vcEOL;i0p;{c8)B`$(;Ag?e7fIU8du{V@P|E1vWzh~qB!R;t+zXbv1zmM5JgMcw$ zy#61^m6o^_LN)nw_ckSoHC8|58Vb1<(o&qI$T;xPmDFlwSGUzMiEIIR9Rx?JKrdPpS1k| zb+`bT9~{a5v?}NoTw4GiJmfSlJ=`CZzuEx*00rzuA)ZG4X)V(I0^3IZDsj<#OmhjE zkZ}q`E}1BvpnJ4O_>|D6XFt_A6;RGpD6PZBe^U_s`#&oi#n8x(rG~ov zL#4Qqzj>g=`@coKKfSC6B>#X-`Y-I};b4SB*piiiH+acOEy7F`DCHBsxb=VnRZUJR zgU%)*p~7uBz=Hdo-`vzcD}^@zMq@pq&C6Vy?H4BH-{8D(@(RiqoF;31JKp z>d#5CT36>+a@ec5`T>eD4Bg}sA^gPY;AUXPA;lcnT=~_HD23|rN@MDAfVf`6F*U(Z z^`3fFU-XCkNZt-sdLV)x3WqJ5<;m9sgLh`&;fPAP^ETKmm1$@%1q~!&+n}nhvH1#D z(wz#`Nc|>v{oO=5QlT^Wp^l~2L6#9yc%`KEisC>dFM{RMiPu}_f)P^a^{DS++PJ)% z-OL$JVJS4tR=~%AvkTIYzOs5M`H|3EXN@|6sF3PdJhhH3yVLP;vfWdGYNC_0>$hZE zg*^_Td}~YBv$hbHdxPFiLmNt|1;@Ie>*i}4N=g&v-IwPmFCWj8KgmWSd(Ny&=? z=b8jYmB$7z>Z;!Fucjf0KX6n5x?aXe$x(_Ue-ytNt z4zEw^fGY9L5^loJmTGLebCu?KIz?1y-+fM10gir5_6?$WA4neX6%9J$TFO1J0gojE z$#2C zN%k1y%XS&qI8A|cNl^RB@E-Qzy&fLaUOkRfbs1HDReESTlYV`U(jy!3MQ9*!1_{7N zkLnn;B8XGkMdord7ClKd0Ts2?$iL&U8>~3ogpaP*m7WW4{am69KP_`t4e@kzAEHg2 zz{`w8R}CUE2t7ffDuk7h&=B6^9dxGamt#=;1~jas@O!ANsPjGpUyu|pf^?V2ghuM- z`8>e-1eG+3L^X3&>_{8r?&zC0*lQY{Q0w@ydzjp5)FZ?pI_0-r4DT?cs~gC#*oh1c zT|XNM(Q++X)6RI%X=5KJru*va-D%^SPIAeY?{rPfls;~A=9jsEV{#e9+&0{*>%P)u zhxUE`+v86c1>0!U2a(Ud3lZ|JOHZ;KhIxEen>@XydQ!K1RlO|V6c91?&qA|9yW5U~ zg7dASzhBfrS+*Fc{0-cwE5Do+zvzc?iakoH!N0wu9FD)f7g0=?otgRT0kg_>j?DRK zrVCulkF}qjYxHQGw-*pKaN##SvS6&b#SdJ;#-F?F6z302#cjt`e$>m%`xa?AG6zL% zU-h+P0qwmK&Ns9qF-l>L07p=T;MZCV6_}7#r+AfBi`oIB2Hu)?M0keij!z(GYFc!P zv~D6@xzp=o08fIIY*bG`+;i)V0wpEGE6+&%`p@ylrX~ycZ70IyN5l-2@bQ-?&hFEd z+Sql^VFznGt1jxap~4Kga_cRhLRnkF%ep6f(xH2Wr4+6TTvjq8rP#6QhgBoGF_why zUy!0bYy(BNJCWW@H=C^d0Aas*I?W|zv(e+7iBV6Hr-IAS5~v3@8@OuH*00a7l26P? z(r!89{$8s4sD}hCWZnGC<~8F7JmcOV$=>p5P|TsWDn|joU4rGv*TP{A^{__3UjE*V z{}bQg=l|R(1>n3}>{}=BW(|DOjg}BlvY6pPSjZ$BQYLfgULn{TO4WLx6X3Ck}3|n4jzhg&*KXQpoL>-&E{o zy<>ULtT!xp8)=c%lDuM=N)Y-K?k}%oyJpn2CfjbwDl(gfTOu{%zqoR>1iHA5#qNjh}IN9P=;&A zWg~;UZC!sH5X;+cJ44os)I?m#Pps{Zn$LzkLvEWv^{UMquDY67!eqh<{l4Gu6d z@Dsh1)fO9XffcWP*^mWHvq7}W)T5l!r_Cd)H1FqL2@@T=rq?IT@fv;fpY$W44i@Cg(by?Yiz83N58*vEnW*THK)& zhf>_FElvo*orY4ZxDq{IrxHCQ)scZTb zMp7F|?5@EDsFFFZhpx7gj!uJ#I-znFr<@gc?K~+zdS7P>k7@NG)M&XYlmk=2sW+UL zqH@QFVTBEWX+xTf=HfeaC@ zo+14sQJDAzYEdqkb|ULo6iKbM%9M1`93do$dUBA78GMZh+w^5c^c<-Mno=L@ev*jG zd1tME?VDL%bm%87?p~R;1{%p&?o_g#SQ4s<>3q+F!?lPYqi#!Z?&=I?iwmSM9vrL3cbOQ?H6dg4ql?r2#>sdDfyOlM^;4TUY1pGSb*#v!8nqn7Qmg?{; zsbJuvdG$2a`}7GP-4~3n$Ad8+%Dfp=TUWKYqdP)ofma#?q-y$@HxMFTCTN!GJ+D8{ z`l7C-XszuF-EQ4x<9(*u8NWW|3N>r_ND0a?55MxrWt_X$KgIQ==FYCygZD7PeG(r3 z!gLCdzCllQx!O|=?;Tq8syINjx&$S}`W9Y$;84$P6}_$7k|HU8ceEUF1~ONOmR}v ztiM&GbHIi&Jx#ZUn$~U6h}206Tm^x0=BqvJ&*mJ+N)SFQ+Q^S)TLyxrj6A-8mOAq< zYYl>QM5E-W8TU4G$f`jf8u`!9W|VfwI1qRL_}T(+K+7(G-@YaeNV9a8)mbZ_?)s<$WmWsB`l5X?mOygY460`i>_GBhg&~>5kf#Ca?9NtU_Zq+s4&8jLI%X zCG*D;M2c7OIeSTlfuhcfiX5Cv8|ys&-x<#5Pp!o-ACz<*`*iWzOxW@IRgxI^<_9Rw z49Bbx)jndRic%se^INT;lsh^oU`Z&PhbuPuj)T8EsNq^zjXrk9WMyek`_v?nKMhYT z5`V$5!_Y-3y7jL2tps1}weHJ;zzjB&jw7;ZuOxr>!+XsP!Kn?1Du=r$X7?eU=O+j8 zlJy#(=Wu0G7{M=UeF8<{vr(XkB)_Ll9h$>Ocy;3ZMLggH+3w>mwIa~%nbkE-=<5ib zBqRx&IMC13&!d#?AHoy0rmb-M4Irxxe|SVOMpDkB1mp)2F+7A91>{k;ww6IkSEiKh zMyCkto6S!7F0P6wQp-B;h4xNF!9-UxZ&563pq~%!$VlBJC`v_6mztL^k?QG09i?8K zDqs(%+YlREyVW+*+%B${VQf1AY_D0YcRn>T!pb{B0umx+{c!h#4s+*TE)n z#lX(!*0h(s<5$zz=vY1SVkIZ-Z#UbGzFHJ;2X&=wLKX6^RC=4NBXSz!RiZYzYk12l zI!iNM0$%n-;gT*1PFCL83I&5!ntl4wc$J^}7IX%9EoQE`?iteta6(qGuJRx`V=QzH z)dnOrUA)B~AZM0FR|@EM-eaM@YEnii!y46RtUi!mU-#Z^%fPjxI|kGJOqWZDj|K8` zuzZb2q~yx(IKaSmk~^X7UBcPH89hCMMkQT1f&0r{-X7^YKD|3m#65n`L<@y|T#s{j z!~6oB9{cV~MX67fzP{2&_rYae;8oQ}r#j7X@^NcM?7m;fGL;Ed3Bp6@Kx20uvOQ9g3A6KV#UC0?);ayh2jDV4zoBwBqkOUkcK zRerXpS?4UtxXuXq2r5xjB{rwo3~)SN_txS!3-x9V6<6YlEV$1#FxLf3y?ZKbY>g=* z;m1DO#s-(nIo49DK?O<~%i&1(=`1qhAnO)^H>B~a_z#ztZA5)Zq3-n{Dv!s>@tZ%G zpt=&*3eolgyGTTaY z9}Oy`u&4^4JY#^{$JL_&aX84%gUiJPI0`iQL`De@fe9z1gN0sL;yT|F#Bc6BcbL{a~Nx2XQPr@61 zlSw0PIKz)E_5s?kb-k3NX>BJSuyx*x8eKM;^OZndb zi-^zHdeK*$_z@p@>_pG9TkGQay44tOW25_tu5==add;k_NL+i>&YE9MzZeq%H$fhP z@7yar83xU;@2FsIp}q4%#TJd4-u}daNTYU&!yv5p^hV9T;alyi=3l1ti{vFFSy9-7 z09Q%+tGv}Qyk&v(lQ9n`^6pqT9hl>WP?7v%#N?Z5*DRJb?2MA$w)UKHto z`E^5)6<94sj8n3;lR8moq%01*u=O<_(wk3mjmV2GVJhWJyRyGHhi~PZdHx0{PPQ1M zB7~_2jrVb^;cc3c&EMbtI-~iTNplsH>zSn9Qa2f~%Yoo+Ii*t^L=TW2bvl30GSln* zZu+B0Pm$Pn1?TrlPpGKVB;QHqF|=~)97!fGQNlQCDJemcn``40)B2MRs~u>ed;L`D zsT*Z7*vbh)?5A&ETyy=}E7EOMt_iElMJ>)T(%d4Xg31q4$xvTiD_U@gWcFhkYL3%{ zf2CYowv0ZsMubyiTlmc5OWwm2X*T%@M{k;|DxRaFu*#1VaxBqn5Pa1qN<8Ln6pjJ?xw@J2IEcYl|D#_CZQy)T_wMZ&!Vz7BQ&pT%bGcrFLOJkkima8&pbtpehH2JMEUj^?d4!5N zf6#NiE#k8}!;+QxH&9N=hMqb0-Q_fvOqTLhWrFWt<7aYJ`geRqj`_OUSXxNkYg9q5 z%g&Vfk1cKp6j|p*%9c2fGqYCafnMjr4h2Rb&jS`oLQ#6lZ&eakllkzScw6u33<~%X ze}TywrOMM_T|~oq(VbNTupP_OdsDiuP|_U#wfUpc%qKyHU#+oEMt3SlyaKBQN_z8| zt)G__Ew8)6p*>@`wnA9wX=NqK!EVqO73t__-``W_>XuNz}DnxtnS9;h-FH%@%vT@$ny{Gfp=!GbE zYQH?q(bSHAOS*XI0gkn+^VBXH1F9WO9!q>|0e54eYRM>Xe(hoF20_KmLs4PWMPRzVOOQ z!bq+rsu!rFW7cny^EKV#_H&f?jNeMD$@%gl+tk25*YBMek-NLf)pv?4)ksd!qAs8N zKFUlwiP2*%UyjJUD_{X88MDRvGhRWqQe_?IjTg;zV%#dm2_$ONHtejF?eW#sYZ*44 z9-Wu)9JJKOUn13xMOGCy<-C$U-AUw_?6eF0n2fpwBnJPh`h%RpiCH z0$oj~mI}Al3LkFR7|DpZ_6ueo_Px48V7nUZ%miER=saGj*wcAwLZDH-f;sO&6x#l0 z=t=QG%d>2=J+0l;s0@+~Sci7nr&etM08Nd$>AZ^X==IpjZ$QK|Q;GnO#9qIly69Z6 zZr`OpLUOYevsaRAsznyX826QN$_tgj!eH)8OE(wOckQ^_djczvZ@S;BO}MU`yWIN; zPmt66np88*HDcSiiDVo9btiS~BOBg1aN%Vc#~Mdw6!_sv-2I_c#5VIYzd z+BgH^bQ7*pLMecP^#}9(XPJ)Vojup7tXjJX1|P3Kjnzvr=}c@HgsZee8pa-iZ8i52 z7H#L%V200gTU;jpRpa5m*sOSAl5U1-P8hEvZRPENY33pd3Udq=5A+x@i~CmCXsZ`c z7NG9G@|?B1QK26Cw(ua>MN@Bf{iTPRn?O7VE>X?>YCP$k)BSFV<%$?Pd!$HkQHkoK z#0g4vTZ@Rk2Tk7-R?%OgH7qERk)g0yRsWY=`bBLaKcX)0KRGx zk|>$`KT@i6UhaLcQvd`B+U5ii8i5{1SzXs0HobYVMET`6U`mFmw2Bp+pfqsD=4Bc6*wkQM9}%e{ z*4SB0t;Cw0jj5sis5w6k-B&<`(Wc_t0(Rg@m$$f-noEUuzH@?v z(mMvN$6Jo1ji#n+DpI@3oDDW*=zw1`x|{lV<|9o8i|af`q7AWdhZ2djSrJ16cc3XD ztir9V!pO9yvED~NsP+3o@1WPNo`gRcYTZr`71q>6sYzU<1mf;$UoscxU=>z9r0qje zx(xXG3*Qddq1THZK#N0CyxVFGH z5}0dy09H;9anelncRmICV3~NXH2^vj4l-c}rgifhz!qWKAM(CSCMHr?(0fOQj(-iGWfP+`mA2} z9Um+pdxfTfvBHO$gr`qz1l6~RZ&quM5og#4h)8wPRl6HwtU22HBJPL4HUamzOU^w{+m=tV|iReNVbSk{oL59uM!z*OunDZUEiumz_TUkRI1g zn_Id+^g+G@r~}B*{ZS+KBwF^wEHG8DsPHP!FiB(5VV^PfWwbcXC#3I@;%2K|7<(B> zsAp>1co~^`ZgE$FWX1i~*DEsx*gjIo?s9Tx#>t@Hdd~6aW#o7Hm)-9+<4wlTMcTw{ zFaPj3Sp;*=u%naBJaI|vWuMxv3`$l~%S!r%n$32+^b~FoUPc+R1ZJ1Oc)L8^5hoJm zrNw#7Uu66-U5uqVGPr&NRDKFPJ{O}*6Y|L(gc8(R29Nh+JUR1bPbCX^!j}gQTmICt zT{0DgedbL?u1=OTW_mjp!J};5T*AiPrf}& z3&3amY-+Y@hPfAWwL7WO_N_>rw{h%h%b-!X~Ln7D4sPY_xSLtkm;*GC@A6?+OfE zvKFUeec}jSy@RZdv0v5X?v9l2G>v|;ba9c2<*aSD3d*;{Ai#o4PzSjpF^_(wnsxd3 z30eYu(n6^>7am)9@xk2b2&A6u*_3ZZq<=fk0X5xU+*Sgq#LYw94y*2ju4!0TU-+6F zUHB}%^n8oZG+2LV8T!&V3T=rvpskOrgp(gkG;o~Qr9FMN^Znqv3I{=T0D-x%>b>v^ zQD)sfv7XlO{MVxX#{BZ7_6d+efQIq$|t-3E2cLRt| zDMW;E&OhG0b1_XR-TAqDBR8Gpf-K!+i45J3ovs)+)^Xx3AyaUWb(_r1(R4uqKVn8~ zt0K&TYZh$FvPUXx$LM2mzt^}-(to9H{L#+{-I}{HH#@d!t;7ttrhU{Zv zY8h_$=$--GL<`%3hJJ?^7BjoLD@Ki>T#CA!5%1X3XW9k|3TIU>pu5WISEYx$5~2oCtbzT!;Dt(DhSsA_I1jkRz^ zn=n7Z;wil8HvrEwya$eKCo;YAss+)LM6`YM?X&mI+XNsa!>?w*a-y?S1|o0&cIeti zmGQMKFdy6NL-Rp530kdq#71EbO@{llvX&5Pi1Zy)UsgxeZMV^-X?%XwoF*Hp3ZZZa z=0(GkrgGU&9nY;U`{E{%G4mttyt+=54G$#sW#PmG*ptbAO!`?eoYlW_0{Ha=Zu@lD z4$^}53bT5#$855NzQl$W+yb)&%x& zZ+&AP7-AFn**&=!(;$M+M}unPjY6#(6};P-{L8f%$+lpsrVVTQ&LhUMNY959#t zKEJI%E0^_B=4;d?b%bMSp-#+v*oEPX`;Tv3oWq<5Ts9P+RAWT=<1a%IY3huUp#tJ`zutx0rwt z_*fkm;h{&?pXBvp1h>Gt4?XEzOmpPk(mv%7zeZHaXX(r~!ORV*;>2B0Osv4MHH*Y1 z;~U~8nk=dSrS%3~Oh$pG-q(D3VTK;72^ zF|sQ2&U6UdD!h1+<{n%hxaj$f~DfXkaedq&N1Ms(g`9D<01mHX|WEYozF{2TtBrnFK zLnWHOkk*p9kCH$bhbaE3f%u>2eEfgv%=ynug5}k>b(&swR6@FT@Dd#P%bIQ8!$?VF zn`F`V$K`W$YGB{U9;&@vpxCyn%qfyCF$%4e!7Zl|Ay`E?jeosh{DZ0P&zn7OzE)#h zKz%ey0i1V~RIy^D??4i6m3nM6Y`J=mR{0dzX?0S1wm{9ky^uZ`YoIs2#Ap(d_^dmc zQ6ybxcuhJVrQZ@KvT)M4JM0s$r2@v8kUf>5ipEA=R_W(X5uayQVz0(wcyC>0$6K_h z?>d16Xom6tzK^To-vK*`17t{!wW4FD3FD3e6q&3h9zvxDdB%6gotbU-Z)DedKo~*P9T4}w@iG9BMkJp8l6sL z-_f;Izl)Q?NTBT$>0NS^#;6_;qLrN}_!iZx$~&^p2pVvh-Zj@6qj&Q6lFBd)SfVs? z4VZqu8q8D282P$1`W5Db=snb=kd6t3P{#RFTJ)##4`s?KHH^x+z%~jGemwvtQof>! z$z#3NQa{qS{#i7 z)P>jIhi+j+O_gtJ7pBG4Wwcq8uvS;e>9)e`YiAQxdK;&Q0j|IhO@7% z+Zu!6bdDCOufn8=UJ+@i!%gAK^Iv{Byl)Il$D)rBjX$T-h50CmB3WTwc`Mb zNMq7h-WG1;IR_Pp#;7GFguw(2xHnDo>an zjhTd?2`U7#V+~zk!?cl!Ty=?@_eMzU8lwJ7Q4_SDCp-laIJhQ!*N5FYCP%*OSNg|0 z-A8Gk9hhZ!i(P0|8(uJ>M>X_|-)evTf205DANGK$H1BB>o49)(C+)a#j*gl3u&uXi zJ%)Go$2#rc_XBZ_Do@?bK?nu4_|9d1oC$Icir5!V^`FpJd)ku)~bRg!*-1n7I!eRVT(|N8YvcdQfk@so1c7R zdS_k1xftvQ(~~NoT%UGBXDRaXGq(!htdS!%wRZqDGiv>SOAJVUO+wP8-Lk5m>~Bnh zL3s-Ep608@E5h`H@m=qTVDHYe@q)v)T>UgxGNj)?Q@=VshBIeA4BiO0rYnSX9=#lX zcGXB{l~w{gQ7Sm_A1fS$egQdGhMxAtP(IH7-b|qFFXX6(5usIIPcj-8hFI>_6TA`Z z^4#aR+?=2+0d=H2v%0Hg!#otG*Rx?|Px$3=rjmTXq2E(%yi6QZRtHlduFjOyef0%e zz2WjXGf?AQBg)33N&at$4@tT_FJ;m+n(JYCu#Y1&sgWFss1=?3Pr>sryw`{r?->_U ztz(C!>lW#pMSXo#{}HMv>%@l>{2J{CLb!4P$G94c73KM3V6!FkzpAsK7u;L*i*09l z$`B-VM4di;8F04MJ`>-gvFMixzYxSKh(ID@+Oi>7Qm$^543|d7xQCIPzVb^{4N4VX zpZiO5P5*d5&eyB=`RBe(yui#Y7z5`ZA--dyq$&F1DBvkeQuA4nG&_wB} zYZ;l3{-KvImU?38hyy;r9?Vnb14xAaOuMwQJ(Sf6{Y z(22>vnbeA!@}r0KvcRc|3JO`@-oNKPe{+bmW@HT$=;z0OitfU@XnSfD%G?ydoFE%$ z!CR?Ugcvi|b5r3|KoVsT!X-?4CJh!Gnmx@qL^NL)qkT-lj5ge6Jo*?yk}*}Pzed>^ zDVma=@`S2{)!ij)tj*3(t1DHv&WZRYp*m4tJKurX^*O#Vh;gz)AP?DWbcz=VF-lKp z{~}P9yk8sZM`$uos%im`j%&#WHq%QUAkw`xO|QZYC+Vj+EMTN-K9uv?M(xbR-<9Qc zk|>=q$saV;AJvE5h*TsA4h-5w!DOc_v?0x|H~?fRD!{e$6g(7EV!eQ5iaJP z$m%5SHiE5i?*-|2c7C0ly3}3_w_BnQfN!%I*s3@^`K7hdkIK@`T%dW8(Ij|y@5Oz^$|)4;U_E)(aP~Z2E)%3Z zXDZ8}@OXuK@tY4-gjLA`P?EK7(rqZdg6Xqt(^G#CcjxoId zO=yWKJ~QLSJs*l}L3y1?_N&gJ*Cf7_C8oQE{L66X@=MYg=Xw6YPrf6O{ zB}%n3_h8_1%@+@^QgSCORLG1lX8cT8jZ?X2@U1#*UIE$y{)QUyWFJVEWYZjthIwDc zZw}lx0L)89T&0d8cY;TOwjWY$w&pgyE;R?cUkpYLcl+ZDV-oL0zWd-zj`0nXt+tXAW3HGrN3nisrWzey(KISi zCWdM>zTzru6F#OVI8y^3qf~LC47Us-D0ycNU$T-0_|A>00VYlAu$v*+yB_eAw0&r` zGAPi7G2*)zAP{!}Px8auUXSZVCiSGfL*T`?!61_i##`B7CaY29UZW40YOh37!?>T= z{50<3cdw*alHqt_9h1-Dk`ZcT7v&9j$UnpTF`x#zq;=dvsG4u+<)LM?hMc8+PCsg? zjz3&fq;WXI7&e%QD=n_J##%FF1@!?wrX6`IKf)g9OFFpUhe`ix)RUnZS4ORFiUU4< zBgIQf7eiKpK^5?rF5vMlt{iEkInjb>ch5nNzLj;tTm~@#8dH2a(U_Ljg(0$@9R-%y z%$=!gRZ6#QGt1%%!CiPsVv=iZg%RKv0!ViGrpMnzvT5SZ9=v}`oCr-A!~)D2zFnentW?*g~I5KR5i&e-UG3YzX^@8xW7*c zB|~RLhsByez6emJQHw6x8+^z-*=5&BnPH&bdU)g=BZ|IE?X4TM5ma~edEev(ci|0BGr-#ti-Kmgsb*K&w87qD!Of^G*o61u1bb$_)Ir}hyO zbPK`WA)WcQD1)NDGuhHV@_HgWk}*$EKZWVE0+6CNz*-ftngUt+h#6r6jjHM%2H)6r zymJYPOwimwcxSn?~+&dyFAx$W_wk*7niy7)X(GaIU?M3=R-yCN=c((7;0A_ZDp$R7J zKT`t#Gi>t@>P6|nI5_K6C4DHjyX#MLlnBx-XgAKwsabzqG@+7w_InG8cU5f)K!hiL zdjLjq0NSYVh%3s=ZGrdUJrP^KG<>+(U*Zcn`Hh9HTU3&BYAj4ZrQx7b){3kp8Aqcx zFu<`O88w}EnSF=nQiP&KbA|1!?nR1#nUsnM6PqGH?+$vxacH`4F3OX|39A)6!o!Vh zSqXUkg1e=uoMktr!Vbi~EB3RdyHPhaJ;xn&-s%$a*mL8&C?HxKuI|NgFQ9*#=P)~d z$o!d5#w!=rqvgqG=X~p{PXl{ z_wR#0Ta$Hv7CormZdu0b0XOE!k%b56d8cyK3BH{vz59)$e7&gTxiB{FI-~oVUzxrT z+mpLxR?p=c;YDaAU$5OCg?r-e;z53$(i$){!Bp{cz;;DOepEIUmG=s)_Fot81~c9l zS>~lOMQTjJ2Nt{>PDTS^ z-(4~MS6-#ko)Wlf>4I&wO49+HKT-c8w$AvQR{Fawb61JdssEF2Q8iIJ_*tU0K0=P; zU<>WluF|jPXfT}@ZjqAYu2=94C0KGr&MN~eG3+CGdBGA9ajkPsXk#&-P=@UH)>U2YcZE6<4faX`qS61ILez~q=BcH%H*Ay-x|9Hn~7Q1h8o`LI+QMH zK8kFgT%@D#&8g1nk-%3TIV(5Z*Cq^D7_qjRiop*%7RoX*->Z8)F|Gob1D+HBx%bNK z)jaN96^AG69q@Zb+#&luT@-VMitk_G&FJ#I$3M6PnagA zb04_gS~fHU31$?Sv&~UfHw1mabXdE!dHNgBsd^6ud%1!6I=_wK_~3XvDF{1QDELG< z#->{^#ou`TD5%2CXP;+n0ju^T>d2`J>uE=?uyFs@bds!8?ecl`P-U}QvC`^2quenj zJYFlzCq*DAjGMoQoJ_~08U1ds=tb}Jwe(KG>iugZEwNo24eZcJ6O&oE| zx7k&IrnF1|v7_I23mUA+wTWLK`vWj1>$ljAfSVV@!_))3JPQRzUaWK_rk?2N&(8dw z;L;zko*r<6xsoZvhjI&*oI0bwvK6EIlf2sXj#HVuLAF;VH$lv1&euQeLMcYJx`kbh za1GA(hzjb43(3sAJife+ESU1&8%V{qyBq@$ z{nqACPiN;j-6z77-ZQ?gJ}zt072x=NhM#cz{<&`rz6kPBg{oD9<)h#oR9JI#B<*P9 zt#IqD!~Re^Bx}oD%qeogbyRFCm9e1e9*C6jUcT8uTH!|s>?>nOYTQXdN>v0?z-{^* z6`YYRIL{!5nf9a$kFU)^9SUz^-VBuhy${37e^t2YP5dexXKee5l4bNWS@#W2umi-X zK2Ju_02OqPm@~^H3*Q!%7|!nwKHRUUjV*T}Xhyflu@puZ(?|al<24!?9m2_fuSt1j zkx~%c!9gtcpin>rpbt?p6~=&XI3z(@aFh!E&n3L4RYTy0M`)2s`Z|* zIBkokM+g;I7O;+kpM0yQvg-Ht&@fG>JJd9_wCXu z86PMAQ2X1AxJ-H1N;2bA=2RU>()O^DF@Rw`w^!!5B^#c8RPuE+=7VO9oOxXLL)~TW zEDyWH%0|l9IUgRAjec}lo+!0ldirgWQtqXy^YU!{gyH<5rPx$wfEo6{HRcnY3pgEo5 z$3K0Hd@H=-F(#G3aAh@u7c5(YO4E*YpZD$BqR~q_JszV;-i(_!;~vtG;+C4|!}dU! zd>oSf9=?ywQcz^NAXq*^h&-8IdPQ{vFd1O7AdpOe3WXlf%osN(X=hH%+$wSKuL5mq zlzSe8JgvmrvR=ymM(@5w_NZR3qsefOVmj|js;b>n++oY$AAW|F;+1-Y1&V< z+v4ozIr9rkvh_rqJ*{i~g>GMYK`Ckpk^iWxs&^_3_!iZBN$w8%r{|2b}_}Ph7$Y?Yr8Ab88WEv28&83r| zJ*dJYL#M(Moo=hip5J>p56)bh*c{bBQGjdEI5;Dy93Cpt#mGE(EFr1|*|>)oeL=Yn zT4+n{p7m)$+i&fU;G?ie8q-M=<`B7tzm8@ez#`6T-w1A+#gc*XMKaH;c!2THwsO#6`w>7+N2Bi*rU+}i zHu&ykl3{sjLU0ize^HezZ1q=!#oN4t1B0i%3MeOXN3ZvLiQXs&F$ zJiU!wgtO?v7#4bF);aTYKt0iX=h4e&x<~T^n=cvdjp{Q~29}(a&dNhuFfDB@3%iQ! zM1#J-!r@tj%1WL8*OGRMwE~X?IZ`>Pg*jlD=T(tZvQ4NEMB+r3)<1_u6Q& z$)Ok7mc|jz`e*Ad>9=EKz-KPNBtyU65~?N;Eb&6rtumas`o(5z;KF(8`M1vV=zKY0lI+&OB|)r;+3I2?K1r9x=psU927^LV@wOuMf7= zrUfK;#kNklDk^ArsH!4JDPvQ}A|7ZYWlMM!{RUv3{RVtqNcevJvHeJl%)7U-xT^}G zGsWE^RHTISXwY+?F%C1f?PQEG&t5E49ZNcDJyTTbnGAE^=Q@k9O(We~rlR3cdi#e= z(J6`@+n!_M?@rZsmxxX53??r1VNqF*{Z^9+xhKY4lEz<80b=s68xD7Y4r@#7Wd@+4 zS3d`Xh0JsqF+S?>>U~xjE^by5TK5V!uzR{Ag_l!5#Tw^Ts97^cC6_H@b^Vw`n~KXl z5qFfYxxfS_E>mFx*NZG4En!}qjWVSpZtamEV(zw>)oQu?f`y&42vRKo|9jvB*0__b7Fb#m3=0@{R2!ny#M&1vi@< z;6Wo#lDbpB9<^Epm~1?c=X*dPh)n^*TU#nbwNq38!Z^0vS5p)|(w|_|^`XCL5pbU` zbCG_qhpdWl9eL%eT7l&%!K&2;%bJL!UhkiiXW`g65L+iNA19ooo%}&- zA5VGN5(jf8zJNUDC(+4>LbkossWT)V?3t#?>&>M;-S2`kNro=-BQE5rf{a7Yn^WHE zvE_+7r5v4;V>adqb`+z)GFFA zZm5Zzt91$jze!M62Th&MIJ^G|Uz~UPPv~vCz`ZN}l~jpQ2lOVf)e1@1+M;0zIW^Fi zeVX{V;|JG@MZZ)3=(9pzJ`(|#I8UxABQ4}8td5h5Q#CMN#+O#j){qx z$v5Kq?j739-XDaVza%sLv)1VU9QE{nte5_0SSR~?9>YIq&F$Z-jQ><{{C|nvr14+o zPyIb17ykzP^1*-i+T%YlZm>Va?lvfb*;b1xq8-mu)X4Krq4+-XKqr-cU5RCdC##`| zTEP&oZBr?xdR4aqGTZ_Ex|4HYHV-1|W1`D?)AY$CRD_)R#a!4n>R$Y7Cifp}2kePc>jvA{*EN>GdN@k7FLocg@?#qPl>(y69qy}Txw4EmQob8& ztOCYn`#xV<6W5217D|0@YuZ&eQp(nr;X_kU0AGGpUTyL^p3V{dp(Tbj^>rDEs=-`b z#?()g4DIil==<;8wg0nT|EE~XfvlDD82cI@VF*3Vua@Z0Q&1o58h-m&0yxXw^O4`K z{)V~AD8T00_J z(vs=)*CVSt761r|=tm9FL77q}tShKiT-5;6KPna!jGi+&VbOfO}x>T>5hBA`+4Tc zO9{oxJpEp^$KYS#i7#Q1@JwF-wvwn;{Egp}r`4DX~t2xWA zy6VoLSuOa+EJ9q!*5Tr0@iBLHlde@rF&&BJ79+WY2OhiRJVG}GKTu0KNg1XPnpaP{ zJeLbwAAAPBKh2yStJ6Q4=^C1q1T1e;l*@4+Y8vHW?NOx@YaO0&`SHEgjpj3AHySfL zA$D_8^Jq^x8=*z1z`){^p#1tzAdnC9T3vU5g%vhn{uH;ICvMSeNAFGpQ8v%%(dlg+ z@}VwM)%(@KWSL<9%lvQfu5>~#l(&B@xSr2f?%R|#>}$gJpYgI#&igei&T}%e(Sj>} zhZZ#irO&>+AbOXm^3FD8ZP2Xs9+aU(?uF6T$;@5SlIk)i(o8~XY zO_P7|&LzwAq1BZd@~uKI?fC}nNm%Y@XX!5s*w9jRYI#D z_|~A=^GWNR$vS6c^Q*faQh)vcvl)8I*LWn={X*Oz*De^uxnEboRO?~r32s@TdMNQ- zJNkpzj8v89*cvz(l|XTBhHqnAC_89Xr?gnfpy@R9Xdd<{27jX3SHgTPS)311MWMfQ zNh)+RaEdB@A+6dtN`4J{!H601vr2Z2v`#p*%iw^J6RdYEt6pYmyg0%IlycNpqc7a6qfZ`PJvV83=WNJc+3pQL-| z#)R*UD)+zK^hMLI_6*bT|177gZ;IpQ@{@e+8-hn^A7;?x?}bTzGrqTDp zd*N)_laudaEJMZ=bWQ0lA^C=Ao+0B{W=%H>p%x5%>FM5kqc0mPu{iwmSJd(*neo=c zFF$^ak@N2|rKw!EW0zr2+L}QTB~yEn5=}?ZpYLdkc1YD1cfDK7pBkm52+GhreWZV! zsqYkfUYXYkl@#!qPj0cc%;?dLzrhD18~fiLq7qSa`G8m#U#%l5MJ@)~NOEWk+nMWS?Me{)abJgMowie z={OUUN4sDt!6&>b)3djsAq75f-$EG15Bvu70~5hT45*&p1LMHBo>d0+o}atdMweUL!k>mh?`!SrRPnoLvGTm) zcY;qGP8QXe%9oAPHMfe9WcP zE9W(O=2XlwF+b)9{_S(lH~4Ec)v>UflUEgGV5}?eFU(3vGzKHL4HbgwO=ApmYTddsm=F)#8r(Y`;Fb9oQ!6KQronv%eSbI0`7~DZsCiNpJ%qw zF4TzPdpUP)jbB-(QhV#PrqPBkZ?jOCey6Zvgt6bv<)wax#hM>#1-vZ?l5Wd-?{xu7tkm1=?={!K`1L^e+R$g#ob#isfD5gTq zTDamlh{JDRO)a847T9JYxGLlX8g#eK2vgtJ;%0k!vbp2j|tb9WN zceIJj-~-XR-F;fk$E5KaQ=|e=&iSI9P@LKA$8`3mKAa@_981X%PZFqQ`HpvNZ$^os zNxC(`+p4=rVOU_j#Z>19o8JJ!wCGZsW)!P8z2mij6IPIfh013&rwtO4s zzp!j;tAlV>vQRzF152YMyXRjPk0rnHN$lvx%? zZ}j4AesDhF*&SX~DqC;!)L~p~zk%%zwjK*c7nw-3?w>iSkfXr@92GI}Fnyy(>ot@N zX#AApOISskp;M_|@wa8DgMgeD4`(f!-R_|z+B&ZLrd_%Qcp0wo*Rq({9mZ$<;-`8q zVuW}hZji$&WF7h6K2w5HmAJ58>LF3ihCPiGsiyYJnco1zKavIh;oG|0vH#_`QOAJE zSaC%P-&EVD#Vhybs(Cg-GF8=I32A2d6s)z}ep0qXbWGKROncr8H8N2i)B^i}8juIl z3y|;LpYM)M9y-x5sAN6%j58yJ(`BhPDXvas>sG)C_g@V^ye*@_#mXuB-PCI+Hz(krPQ~ zOZ@QQQ=HO{31+-iM&O_4THXS=i%Ow1ySH1f^z|c|T2C~6I%$3UaM+qq9EWg;Z+ikt zeq)t#pN42PQEHnmcNNY;>dzWoPoQm^TwyNgO3q0InN8kZNIXn}g|&LILDo>B&=t0m zJG`!cbp=WjBl8Qx3;HanN2aDH3<{gS4lu?!E3s5fmtMeDQ^VplJWP5w)efreQ7ekm zd4K!7XqW}=zj3^%EQp0azp&NcKJ`b2#Q)y-f1i#2eQ*39BO5hRJ_}#_W6o|S{^v0J z55)c@lUdK<%;G{`vhbsu_ZRiv5nwegpF)?l)lG@HS<7 z+}KVAQGpAm^x|ldv;7U=SZ{>XjJ6HGVp}$?r6uwlq`kU2VifLM`mFus`^V(|ym{s( z;5w?zM~Xmi^ zN-#%C&`6jUz0byfYwx10n5CdvNU*W}F-6c1mp@f%zLkbg)N?sUqOQwcKYFUsWZM%;^~7XX zl&_TZ2v6GFICr9oS|i1x{xX(Ue;csdFb~W4W;czxHJ%Ef?Wicp>YMTf&+b#!4Xu=( z5pCx21fSbE&DtX4+qaqM{#i8G99DmjzyK|Ift=x8oYu3fthwUjOx@F3h#XaWQ`RQP zci>BJ?Kcnx85AJZ=}HYJcW-q{zYO+aBjRT{mrF9^kr(XcjtiRr<_VeheFpmm?ttR#szC?z zz~&Iz0$~vkooF-blRPQh0}nwa=e+ zLT6_#s6(wzDXiBycc7PV?k@`?tlvG-T8~p|wbZnJSqH{?YRH;r9nY>y$TEAj!9wJamUBG7~ zVY4(c5sT`n7u@pI-a{PKB#wQ$U&Juthc9X>nU^`dS(DDp`!X; z2Tb(!+r8$KtT=q$!gCXYq+0l5H{Is(J|?3KAkZ9Qr(&yDAJ$}7W_S^d-b>q7A`-ka zOm85{V?P&#rd(Yf2!&>4a2__$d@b>A8xW-kpX6{D6zZ=~lKE+H`3j&_x-t1k*GA6r z4a>#o!IksnRs0qHqsMR)xJ~GxDpFLhpTM-u&3DzJ1SSx(gv4P+^UfTmo5}Ja+xxso zo4#t}S9x7H?AF)2xybGMG^q=D={E_>c{x?D>usmNfpYWR#}~OATQ8;RI=yG zf&?Fe2&-G{+UN42M!)P)=PH-t4yC3D7lc)Ro%H1UU~)B|eW_~?&VM+kd~Gz@YhtlT zR9goVXHnN7y3Kb4DgFT4hV8o}hq_y&yKLj7rxeZ$#a-W(=hpYC`?+{T7T(w3oC&!*}l=Z?%`>Wp!oh98M5iQtE; zC0j0D83A>1eYNem%Erys8*1}D|HJLKPLPW# zl>GCH>JPF9EXni;*0InCv09!VUG?;K&aHkG!>(>3x~hw>+^MTpu#1vT=zYg2m69Qh zLoH8mEpH=pMxh)DC?|{#z=Nf5Pmwr#g;DC0m)QYd0PA|su?9`GiFByt;XT&VMyfIBa;Cx$|Sr>9x*YB34+xCDn0Y()_B32DUtQA5NmE`#O z!P0V|t?d$pX8h6^$U4p8k$n_gZJB~j5JEEdOb`;&}v`=z$L5&L$ zHyI~P!DlK6+TAiYhpYjP0-$SX$Vh}KstNKtAB@t~oV)yX$HntY5Nl^JmSBxe_B}Du zKJ#c!-QPSe-KEH7!*t=AU<N6h-y5YU29GTdiqP4O(-th`=WS7zN*X)rFU!&KwmW~$H={IfRNj;NupK34?5{WL zy?$F5J;Q67Tfd2;aSrucdaq%hO0FU_zr^D1;m_+1I~@Z&HypN_1mp=1I&5I`TsabZ zs5v3NBYzterXPWv2Isfhd_=J?j6`f^V-NRqKAnnxLbCwuJMSpd3w7SMJNX(y5#s^} zly~k)*e~<2evxo2OIcEj3|$)xbq=7VV9UkDCZJR;vGqIl>b^;1CowXD4OR8k2(9#5 zjeHWCw}4~cEw{3+3iGJDJmb<7ouDa6Yk$ zsUd;nzJW~Q;N@`|d?(#BAOjQq{@O~?Ll*&nXYBFn5#^b(1zo)<({8!0gk?f+7p+(C zn1QT0*fiz?gc$$TA8%bt1k3bQ7oGt~yUGn9|D4RHLmSKkD(CxZtI}0lMBD?E24hcH z<~5PNfy&IfCzQ05Ym?%ZPZquAeA8o}5DsDD8RDrR01WkC@`SxtRG&}+H@lrK=M?o? z?(ryHMmY2#omP~dIm&h}_>j-rV; z^;B9lG5CkW?squBS{W?)S78C@FQ4kms%@z-wtTZ7D)&`AVB<^Du2*+>v@!1XV&U=Iv(HC&9F`PZ{`bL}%B}P6%#j zl=NFm^RJD!<2ECB)JWbZhaKB_hFxuzx(xz`vxb7GH=xbL_ZA1X$Z5#pdcr1QQ;Oak zZ~huP35{58E9 zT`)h43zs|;aj(nbYLkIWxRWRqO1~rtN5jsBfu|mC%mfW;DO@4`#D8FcE53}T7C9?w zp;6nWqLd{Rv6@u0{bG@QCnELHU;+3chL?UAE1QMRtez;^+3rFBLY>5@c#OLjrhMxM z6)NCp{@5T*a|N`*kChh1fTb8|N1${g;N!(jx9lT;6$@rQv~@)Z9D@c9~ywbq{l7NPp6`K9nh>3-l?qmq+52hM1P(QmUYGi%%xtiznh;z3ji+4|oyF;{%OG;ofCgMl(a&%=D zvwARZ$`g^FvV1uFZ+8Z5@^OW?6tjEp!n`#UgBcz2IUKm}-=7OEmcs;31TprOx=>n+HFwpNf2bbN$q2L&5f1JdviGGBZ@0)*6f42O8PFxX9QhQ;@gA zW}X2d-e?nW^@~p>xYCO+O9rhkY%;vv(YC+{uVB_tXg~?z2fuw04#{I)&1u=}bVI(`79U-;9{gKB&LA>9*;XH7C)tK6b18=}Msex>H(9W(Zd{*kH8DFA3`JYA^}*uex6Z>i5AZ8;%~v6JXU9?i^?PrRwo&uc zNf%t6aiIam--TK!XyI2B%VfROipEYjy>Pfag_3n8?J*8W6-KKxDtH>&3 zeNhjcHgh$TMe+G%`Fq^5yYXK32@Ay%IroMyUp`uJFqF%DHV^k^ZJ+#XHs&sD8Fm zVO*0+_L&f4B~Opc$-6(;azg(S1@1SPVy~6TGtU7>>4Ye7H_>F)9^AX{d^Ri4>P_jo zq7itl2*U|Dwk}4jE+J{g{vk;@F4-;vW3Cdr(tVLu+er<==Rv{+Mat7Z$a5iWbqO;z zJ_F^7uKgy-^n-x9#f;%Z{C#`(lKY-|dp|AHy3Jx5Zk&GP*~{iaacLg|c~S7Si~(wQ z;LL>*rmsOFsH6hNd<_<24~o+2_{{Wl;7?OQCXJ*Qa;=Aw>Bt@7_dTsCr0-lbX0yIX+&rnK95e%1mmXO*enJGd)(s zd@Ir~AN!mI!z7rM<D9nwbSp@Q(gEwZr+=&#|*X?wShm6xHffssTay_;81(&N*b&Z0ly~D z1A)E1QxS4S-ZA>allM`r#LJL_94F75c)hi&+;TR}1ZnHOy)Atf-v7)US;PHuRQ=*esDwahzTgf<_n-vy~|d z{{}j9h6=_^D5@wD{fRdcvlnn9X5k*pP>*u#nZ~&Ts-XE zE4NL)SlmRyFW&mGw2$?&NaB=;$3+&H88ZmRVJY=(CO>BDUsog)9U@wA(7%w zH&wD-vh?YFT;cg209Xq0LRe4A-cYX=A22_=Q9e}SP#0=nDp2AM!Q8jH7+#w1yQY&W z=@}s*uBvZ^s#bTlwlrQXevKenvk@weXH$s+A2TLx=s*2kQcH_>GKaQdUB^`px7zRwh}5(3Aw}b zAfZ=f*RWL5N=!dda8Qz@P{7Zjk#Wd3Ybc?`xeWdJ!{|4V*dwpHFM<=Zq(Feo1H@Y* z#+`yvR}352QP<i#*-2SbuIW5l$X_^%&m^uD|QRT9c_M-I;jswo_C*mhs z*}UEI)0kF7r=uL$PCwQk+~kWrVT9VWkVO?|)x_FB?Z1I|HprQZ3Do059I_w>U+?QL zyM1uQSv;iWS*&WX;Vdp3dl)(CYknikNB9Xk^f6D+vXm+1xnOJdMu!MPjp;{7`#a^< zrUuy?iFxBs&WbS)*|?g=;w;BNIV&rv_oZivg~i^ivf~a@ukkaLPjbvg5HUIuJx5Yw zIPI#8?R0&85Bqh{794R)NldpbG!Ndo7G!_o>d=tChHtq7gY zVTbS0kuy85g^7;IO_d>o#EMB*c6qcnl*_8N6+G}mikcbmT2U{jtemV+<*^qF){=m^ zs>Q~QHqyG{X??k-}!FDF0QFVE8o$*sD4R zN2Ava=~+3>RS*58Yh_d+xE4H+`B7Jtf0S2_TzB5D#|;Y0t!E#b33b7F?FfWksw!OG zsMuPpkG47L<5vnO*%w+F=wuA5i2{+bv-@r#g)SlP=EhOPhIJ@F{d@o1TEosP^)bNT z3pK8tEE2p#K7UO|G;C~i1u!yBrhfnc&p!pc^It3ne@hM1#haDMs}cG$oM3}7D`HG2 z{#uC4{<;eQI0HT|pH#NXvPep7H!q>I!i^`gyPQT3ZC2S*#JDL3xML&T`i+;w_y_$-ZbJvI1d3nD=eCW! z&D5i?p$>BI|DVC5{=rF@gw9PN Y6S0^YxyIEcO~KO)rNAu3_-**#0A@A%w% z)%)J(x#NG|_{R5se-C31Ci|?Kzd6^ObFDS^=62$C9=P{ZN>&PhgM$NJ!hV3;g?mGi zZssNcATJLv0sw#tAi_NY;9(TvV*>}k-yA@M(QvRYo+c%K{|zev-21Xg3ZTG94A|cy zunQpF{M$F*>EEB<2>eFiHv+#A_>I7C1pXT$fE0o7M+AWjixfUaApW3>q9XsG5jZ#i zAS&u7{WF?C4f&4O?`Yz`q1OCn`8NW;5%`V3Zv=iL@CyQ*>>PZ8>|BBzJd_;lf*ibp zoP5Ba-2;HffC1nDt9iR{2j9%e$xe`s&Bl?{z{vKMF{`1iHJh7(9UBKLI~yP*>SkwP zXld+3`O4VT+(wvgufCa%(%eXxPMt@dUEWT@*vwqU!@>Buhr$a(4@*M2>E(oK)-)5r{5ppmx5mb31_4g96zl5p&J{DJ3S5{Xp zR$B*CHVy#+0XB9{Hcn0!SP2$KcN-@IHx?U5>c2Pe#Msf$!Q9Tt+}4KjdxHkAY@MBi zshpk7jRZ{$On6=y8S${ZGT<^|;ovYbU@q;dn*$_wJ1hfAntW z>|pgr-$sUP##YAG#x_olFf=&WsM!8C=>J`P!XWz5>7T+6;}KRyP{P63z{&Ut>=OAd zP8N1977m^l{}3@N2M4DR+y78bi0wNVzYO$$@5uj4Xo(0J844PHAG@u?-@1QpZ2!L| zZ7XvT*jC%$n1j)OBVety2bYnQkd*O1{@i{Buu{DrET zx`w8fp^>qPshPQjqm#3XtDC#WyZ63+{sDnOQPCe_V&gu>CuC%1W#{DPDuo=E$hG)Lbh2c&{7= z(eY`x7ibT@v-SsP|24*Z{--$m!Prl}AOHpe987o!*nlW-f=-{|jZRPx$n+C9)Ky9ekmFo74wDu**$DzpHkrCihxXoJb>_^q6i!><6A*w*8+|0F z2p^*%sncNqLTgDL>ID|A2j*I;qc@*Tg2wP;zFFo|fAGD$t#Y6N{-y|`EXZSU~S4jKx^1R}gR zb%K!Z&}tvvz?KMm*$_(=&ftu!qp>Z`B64LsVhcxd*mDfd-dG)POhr7tYuW^@P74#y zfZ0`^XoF9Q91Q$->AJ6~y7)~Ym}uK(TH7QfFVqDV*|4YAJ!a!^T1jI$+quU}#OH9$ z3`xdGU%JOzg?SGTx8G~=EGS9)EMe(N)>s1$T#2&&mh}<6KA0jtyhjk@^kL{NP#UrA zgsY}_O-n2~Nxo9b`^1lOWyzV*i2s=nr$CpGop?XHoyBDjQ~j2%b$XqpwwcZQI_IqTsfPYWvMJ^db5Y1&bEgmPA7Z?r_rrtmouKV@p&Gn+Z*Rnaf zI@+z~%;39@=zSy-)=X(qi21H}s<_^r1#D>6fkKNwWlmGYCi;x4n}e*z+Mez-GB0ic z61=-BIgUpH2=4}vy#+lO@ZQlIQ~GeC?#YQE;i{5MZCKICnn?1}ypqKw`&Rwt2=r+< zWk!(xC?l?DFdZT}C+ML;^xqzSP&Zz)4}i!D+E8&+vp~VSAS5<0lS1S7(Y0N>^f%EWRpP zk)8c;JL(FU4iy6B8UYLWS5hS|a}%c&N3FL2h3!G+6?rSv4YafaacurV-G0fDUq5v5q7UD#^<~B;yO4ASb!_EZejx3S#}GgP@G?ZLMeU% zRWy3gwg2oF6eheq1Sj4?fB$!qq4p!0Tnv{nqrroVeMK zYK--I=MnG2OEXg+PrI016!qU(Nks}FW3zCMd2X9Cv9)wzV zy`piQsv=mnZII?Clj*vn8;bR_#lc_ICtP~Gh-V_(OSlB(gP2ooRqRZMl=vi7p|x-# zAwRzm@lYDN=$}E$;}Ha8{@Tz_Jyg&8%R2d+j(Ss&z{+);g(bV8#|p$x)*fKmk)#vN zFOiy3!sSYpQ{O0vgn>Hpb=N5$c=FPOx$uF~v);8)K+cp}(|qG`{pwRxAH38%SbDdb zk_ht8-^N@4>=9qipJbG7DWN()WMrp-gK6yvUNTJ}h9Yx+c}I|Dav1#Ek?08}guD_% zr33k*H`IfRRinjsKQw_LJw3is_i%ebSRzY2-?U~Sb5D#bYW-H(r{r2G?XYsB-$(+A zlDIHq_LR^Loi=yRcJFX5(B5@mP)G6qxOYU>R1((C$~lbc>L)g68+Vm6W8KADwKEagJ%j;VWl7kj0}kYo3rE+z z1uUh8^`~^%!{m8n&E`8~d=BeA!W1`WmT5$m=&z8sY^fg=ZHqP+X&71B7Ko|%{HC~RD z{yGk5NAn*>@A4K1B?&v_Kl{cLTuglQbcCnNhQ+ih3L=0MHtDy*NGvs1)rFE=5HFI< z*i<5}7adOo>RP3vJR=^l(U}^UY`WOaQK3)_vZ!airLpB%eFDzGf$C*0$PQ z#L0*nrNpYL)sJpB;n9$PP<%FC0ZQ4b5%?SE}hJHezxtII>Gd zG4DQTEQ!`r`l8Er>b%p7xd{dR;h0bUaLhl{Qep%@f!x$!{{qr0Ra-01Q_6C@Ze8+V zq;jPm{W%@IL`g?4I}HvNsl9GxEbrmwJ-u#n8^_RLpQNatMpN5sJ~5prvm?4 z<6p@lO`CMv!}*$vKKR9yRkV%9oBmvE)N0f-=c`*lWVf+Sb&5XM=L>2n>zh%#$bw$c z*!z7i1*|jQM)xCGz+C5#N&71o!!@`Tp(i2WqpatG!S}dmEEF~pMV*@`PxrnZj644M zq>mtU;Z>PXIC#8iCG*w3{875q&FG1~%?t_|_p6XTPN_x>Z^nti(!iGYSPo0qmfG?| zl8Nr0*xl{lh6Rfe)2CyrdeDC^q3&=|cj2?ngG_C5wm#I8b?VK;_*OlthVrhKkjATq zV@>F2dQcth@KMrv5PGAC)VAAh@*-2}JsGQFC(F*8FA!#YJ`?`g83h#vIfTy_e)}&X zzH;?>G{u>m3Od<+U6c(pr*$U0OI_|t=|b{xw2pD}#q&WXLIZYNELQ$%naqUFwI>;Z^*q#F zCGW_;yS%o&NJ>8QSxZ!{9kt@&1~*wt^4u|ro$3qYWbv)1&U0o(-xb26jNIriiA$3- z&yY9B=k^F}a5rw?e2nPG{XUjllLm1OPF4t0R)9_~NDyX`DoI?S%_S?Sm3dA(c$K#R zmZW7iRi;<6LA5gOGY7|&5;!6ON<*PT!Evrz0F^au+`(d?2vSmGt8zdWtjJ`A{^i?3 z`jH&3@)XM|LULmq9%N8jJ7Cpm0F@`K*dT8p&nsgQv7Qf6yiA_9wPU-7k1VK35B|Cn z(I^Uyn;A+Wi=UXTIkOqaXtuNR4zFaOQX9UgTtv5aj?_xS&Ly(aq+W|23bW5$m^k`= zY3s@xgL6|~@y~X!$WFpjZMiKeVn`M759(hbQbvdNkdVDU)yI4Z9%AL5N<2-NU6Kfv z02$d3K&Hp*gzE>H?$$q_Cy=CaItV7sSnMN19w%NLm?dyDIy*tL?laG{HYj-=1w z&SamTAD6t588S;@h%^cvDWt~mL&>AADS?j4GoX1R^92x+7csu zn7&}CDI}fQYncVPL*H-%b}jjiui8iR5D*u7JAFt5=^ z|I&z{bF1$Cm8AqSCG~z+{OQ2|$;ST%=eOqko*lnU$IrFOuYq#f{~^1osa4|V%<_2b z@~*;>LTz=BhU(4}X$KjlGO8!`V>}ySCxd?#+I>S|GFZ^I)U~e)-ioi%mF|&wRofVJ zcb{r+k&Dz4EMjOn9{zN?aPHS=|CfLdPAaJJ*C<+X+jH;l>zZ#!jG5$-HVGqjS$?u5 zx`_7im`~8&#)yZ(QPZ5zH36^RZL6%iDqGD(B_0 z8OSPlv$t@J5UrPMP-qS*s2w`FqdiCj*VoYdaQe7^$bQJ1rNd8SbSdU(+0wG;lHwr^ zYzYh7HGT~`*?i=JPx04c2L%j|ZUCX!y<|uAFgnp7MSRqwd<+p&1m(Sc4!oXp}0Qbd|>-G^x zh@o)ZEg-mE$p0b)ibKuA5(JfiE$St2fhN(*0l#fj++Y!~%gC};l$ zTTw<`0K4o9PCwGOds_J9KT7?ixGnH=X6SIByRxsdt#jjMz+}R1h1_r`k#yI``d3S^ zjehB$13%xUclKJatsJ~SGg-i+hiz<0lUJ7Ick_{ufvC@7+_z99B@a->* zmS`}bJa(ksUS{xEREiht&1aprfL{1dG8Sz)!F)(gHccbdLdX~O<4dyMsz3xf3U(CA zgOK|?fcP&${Z+st$4ZDlVf#t3%#66GIZXE@M>4#^HA;OcY@zz-0}lGKDN0@%>g%79 z{gtJPDzS{z;zDsBj0!wH=VPSv#Qd3%k+18;f^!CW}b|bD0`F)$k>v zo50cn6n}#93qA#qE%@CfBYbre3ib{gmy*w|c~?_4lp#w*ds=^`7pgnXZmjV@m`1E7 zF~61=2k-Q92#(l=;%vMAe=OGj2~GH2QcVo+FK!9v9(Z zuTx=}urso7Uwp;-FZ34j+KU6i;nfkUPvzA< zgb=BqmE^21A*uCmC&p%zoyI*Ri>K37bKcUvY=mP(YX?Ms+Phy&Ummgghc$cEZQR9* z%mda);n{Rc+x(&<^8oS#Di;tPtv3qMMMdagnA=8I+TDRaowK#6=kiYa+ouhD>S@f2 z6Q8YikvbF9?G&j^4}J%%x_I{L0&f8j-exZ?KD z3s89rivDTa`C7UxD_QDlL%l0K>ECLMX~^T%mfuj7wlGA>*fuoUU$4WZ{HZ4rZeCgu zowi+N=-(o>I%I#LB*(E1?1^FjG*iD?tgkw5t1`t3841igS^f}Kh_Tcg`=B_f=W}Wa#?y2v#>)6?I zRLlq1l{PaRVVPmaaOHpH7*3L$y~hV^t&N=>%4N#sgv5EJI!Q^(486tqQHUhwG!`FL z8;9=CClk9q%CxHnn9!K67JC=O=uT1>qs`avq4 zrH`xc+TP6*Woi7zcqVoWVB222!rI^68kxt|g$5T-ZdHq#mz(q?SF}=2(Xh>EdQu$H zBS;0&r@;pu+_mhO6^he8KslxD#ut?D%?c)KkYAy6QF>#{{APpZDBM6(2^K#u(p(C6 z6yvA$8Cq>d^;^G0Crko38&aed;?uCw>5FdQPj%&5J&aE}23bb4o{J2=t&O-J-Zth7 z;Hrx*iQ>pDB;yMd?GPVc9xgC%&!fPtzTW9Rp1%dyJoc@{q12Uip)0e+`C?;3y=(2{ zMbr>w)l?%(%ASHc(llxerj%l5c}QPM69QujC+q72pAFaM^y5CfmTSQSdBm+ux8?r^vAK?65Kzz6vLql`0CsM5RnY z6)rTBmDMGGL-juIh12rzkyh?{pT$ejW&>y!)Ff3o{QMkrMsSgk3ICM7ly&?B3%_;o z&d8^OHNS1^vF9sOI`TN(IHzjJoQ~(;Q1S-#gm3bf6fYUb@os_7A3^7%9(`{=Y*crw znyr0oYceXwijw-=%T_KF1eC*$a}oJaY(K1J$e>-jL958~bEdY4Rr^yt2wNP9LcdgF zVx<={r;ik36k=d+DHY{RTh-9Lys9|uY|b6?7I7cF#vHq#p}! zggZ49i8g{Hm$CA3;b=s8(<6uYyF}HfZ-Kyq@eqhh`Au5afF&~%MmuhKKp{@?+y1%a zx5x9x-S|5Ye!~_MQ^PoG|LBVs&F0~w&3o^lxNu)L_{@#*bIC%d1(Qd2jz4{l-D{Ad zAjI^bCtN%3E|!1XA!my?V}6>r9K|9qA8dB9aqrecOi>7$L%F8E zdiJImwpgUtFA?I!;dgf3#IXts;@DDH>dgZ@>QD~3+bGzErnx=#tma% zJUDi-?}4A3HVf~>vsZ}^GEETaU&=1izjE*ln))%$ys7Pwioz$^CbxhVhBS_SnA@5+ zif|qRvW!ifoWBE>4+)WbJLFsE=}t>?pMIho)l^&2lsQ!4MMNfhM{j=%z-Pyf zL5CKW{l+x!%f_TkVq@*aN_F4as*=SUxycb#gRO$G&Xxaxh8SsXfSx55Qg7~Ea(Vgp zO2wZ&O;aA?h|o9^zaF+;N#Hp1Cn745li1%r8^bm~t9yQz*)7so&aE=v${N~lbwM>V z86;)IOnBc%^DP36dXd+^^zeB078u)rz8#ty8xsm|C&tUb!kwHxS6Mw$Hj5R8*Oup5 zma%@1UP!8vvEy$U=n$_mInO(f2@Y7Utpp#$#@)me=;&;Ijn+)mCNd6_Sf|bn)uIz|IBr@~Z6ZdO#>JoNcs^<8lRQv*-R0YAW27W~x1|Md z6v<`HSEKju3o>D+UDDQl|k68X`uEV;q~UO_cfbgKL;Wu|5* zhR(SY8alUtt!{GiUESN1SJ`|B#Pyzt_;8E(snsU)h0nnQCkIT*$OMf{bnH zlOtBNDIzs=th76o6dp5C8nmIAF|L_DMa4u9-fp6{Kia{@O#H)8IU~fzwkoCcEHc#? z+2_(t?t~3JyLkD!W$VzILU*LDK#{kBCg?NGpzdRQ17qs0!Cl?254%)#@R8itz1%iM z{zc}Q1qMT%!pO0#rPfib0%1uU>yt>Y z!X#Eoza@V>)tdV;b#nq)+H#a?B0n&In3vxsVJzj+9i?F~H+Xy#WLA%;9A>ZgGb4NX z`EEP{b|nY@RqpBlg^#HL=s6K7&DCA2SAGra30@V-89a%D2(yuj;}pJ2&Uf zT5bXKA7d8l*P41#QROd_pi9NBvZ%;ioU%%URT)9R-#_btN&lZsUzbv2dpsX4mVl_m zJM4oxUO}>xD*`O#AKuWM?&EB^`mMUf{!W{Q%QWi1)>D&!uF|+3AC9u6Bu~%h z|L~0r7)u7Vb?=^54W8(u_2x}O=z|^}M$W%PMz9rirH0g#XuB0#tB`oQ?PMyqDbuU! z9NM9f$!7nsjG6zCn)jXmVbdU2o>P{5bXq}rKXUpxSM?LaB;+*&;ZT4$HW@$P#CnxE zmEFjR-^gIlztLcm7{8($Z)mgGx~9^ehP@j-qgvR01eW2$xc-lU{tO<|P`T@u@-_~p z8*sGijkq0H(IZ=~nWzM4tU-N4l#Kxc^*iO$V%_+vGU`ZvcZ}#S&=4Iw5VU{ztsf3k z356(kLYFnw(IZ2=u-$ASXyZ_VCaiUJh8l;KGW-KWXEjG)W@Xr;#H(TonOF)Y1&(&6 zDQ*Xyp5^7_R(oo*ZX5RjiRiI^wUkoxj_SmcVR5uEl@KSemWNo&5I@GOQ>)o?N?>^h z1*wL70`D%=CtAy*h*`Icy0SbV-+8zs>3Zqm z!_?cru|xvG=qoZS*S7G8DGt33M0DAYf71(}grj{`+mBM^Q6*t(Zfi!W)q+bU&AP~a zr#756OfVXjbHdk3ZCT7)y2zkga)M@S^lk?SQ;iZ%Qu&%1(O$Q`^YTjnaualnob59- zJJMyH7IdF!FQVhEEBGu-Fa?E&K}m)N{>8G9QyQk+Vv>sd{(zc{a&mRsgmUy-MjQ}; zRw_7nl8XLhe9p3Af6>48EGd=$f%8{mChdSwgxLkEF9wsf-|isqYP=o3!RAvvKpF?VfS4*_FaaIz!U8 zb`p%HM1&}WYeb|c#|88VEl|9339S*Egj--|yw2nUp?j)ne1>I4?U#LN1UkCuxBd2e zxXNNk63(X9UZ_E*vrGZ4$Y_ixL}Zv)_Rp2YC|EZVxCL|HH%J%j_6gJthklawBXnf; z)o2o@J0iUtufC=SzrPk4w#DGMDR>gamufcKQ&FSJGUCmTP~}qjN0Ky3!1?f#@oR#m z_-pwzX`0wL6(Ze8xjdHMEN>8+5R|&6$ecv?JSGpa0a5tKz4H+H!oU~R2jgbV&>L;} z>Xhv0SQr;h?@Pb1s6utcI}z1NIULhLF@y_M*k%c)Wyh)Ok-3X2EKlF{OiOj5QBIS@ zHc5?73GM``)v#&WwG^Y_JYvYqRqN$oXl3-5{jcTIj9)aSq=ARj*e`LP6cv=z2sqv@NS`CA*5q!^0 zoSW~RC!Dp%opu{$eT~iz&B$Qm>;==@Fny}qxAAvhECgZeXk=R4V})%( z_M zO}sFKics9NLrt=Bu)gnqs9z*}`rzd@5NK_s7Nz{7b29MnnaSL&Y`t_q& z4$Ch1wF5nANea~*im8wNTf4%JPy)>OTR?28`Dz2ykr}-t5<_B8+1npKpL;$YJt|jv zl6eDBydzJwki0nc$#PfNA4;GX4Xe;Q*C*N$ey;1Gc!R(O;)Y>+5TvT|6;GVz7;w(J zY~-@t2~me}*9Yso6m~wIX1uqW`klE(I_TTD<^)ivyUMwvj@xzHU=^}Ly>DUU#bTZu zMud!E3UBCmL0yFOyt$WNBE#xL*WLwr_g}W+)~;DO%yxotu&mmY7`8=oW~i(dximsi_DrW`{j7Q+jN zQ4$UBe*#Z?^8Hf%X)56{SgBRMq2+`L%CqR~GI#SBD%xMbZ(-H%KE}!<)wDG6?`2-N zS@{+8e@Kg}=sM(Cd3w#`lI>gc5Atq-1?LUXV~ob@VVItmG>>AP6%Srme zZd#iBwZwPr9M6Jf2ymVqDISy(X2gwd#NCt!!PNNQmxDot^*1>W{2K}3dg*-xS-q++ ztvLn#sxhL!jIo10bMv_M$`B8xzOY9$zHAMF)`>hXa{tiYp9-YMAxWVQQ(nRnnDVCn zs*A}K9bSx5UpC^Bxw>II;O7^E#!}DBi+CPIGq2&t{GF9wrvJZ8$x@hj{u@m4@PD=< zhl2E%#q57KfvLZmGwy$~BIA*R(xc}7r>k6bSK+XYmS4mL#5c;i=zcuo=M*g2%?sIvw6RB6b_oA;~UzJ`gVBJ7PujSq8zKC8Bmx^w+G#?u|Pg+8`qvb|Z#ubO@ zn!{SubX8==$)8y9Pi;>79e);Cabs$E>>@p~@-g9Kl3@OG&rkVByUlCwMbBWl2?yNI zt!-X4e)8L#JZlxQq_OtlV<197N%0H%d_0h_o)L73aOnNFCyM{^Wbx161#$XY(pObB z1-hVOirtZ3!>1r@RHTncL^ShodJ79646|93{h_TCDpZ?E37pnPT!Sw>#v|O^m9G`E zi)tpuBm4$(4ib*%LWlaRFJI8hR6h#reB4TS!=>YF%Ruice2pH;sLH{j+c9==LdMsz zj=yK!6kaz$YGcmc=Eb4?M%@?6V2=4x8EKPEH%*oZn$d9BE4fb-%ig$J>rA@s-4&Dx zoRKk!emT;acrE7pnsZO^Cez6M7Kn{pJ8wq!SKw{nHroi}1apQ_4Tsb*z44b`u=V9r zC#S5DcO%>`nnMh~u-*u_*yKqKfMC6!Fi*e>nvo^wQDbJzKOS(@B?vEZX3|HTmCb%= zGJz1Y89W_yFyPPY!Lt{T>1DDpv|{|+7XRCmtTlnYXCSwvwc+$ZWoFVP|JL=D)A-r- zX58b@H}mF@)0FC*=Vb(sBBCeuIdq!a2GGI&RGLmX)UtKaEcZ4@POq8x7FA9DptSr>*LEk9t zIv}pMg{Ffj)?O6sG++8&gOXjP9akB*WhL=8AjV5t6X()j$MHKRzCf)ri8$*YEGS zts&&xm9t#95hxWB#TyyUuqeAv?WZ60csn>u(1;a8Zq683cnfIj*xnVf(NBfS_g*CR z;Z?b&mn5bM_gzG?X&n@&2izk-gO-OA2}PhNoCLqf$}SJt=t-;uQ^JzMUx>~YR9S4@ zDBS`c1tYzVS|C(qU5aD&0u%3kwqTiM*hRi+QCwS^- zhxTfwx9Xs3bmZo;gs8RE=|zGTb|jPsCAYD1Whvsxrt|3%NvgknE+`pJ$xLaqlxug~ z2+TTnps8$p!He1=xwvEy84NGfq!D>m=QO_<#{-dTY`zmijNaG19&_UiUb}JTuVeaj zpqk>HdJj1z))imLD}yF^F&-X~v6kM4qw**z%5k9h!TvM$jk-<4alF;yJaac1 zvXqd~b#VvBw;@#mM%&Vp%XeP}lE1K?y1>%ZACX$)jmj<5-vQx1gl)>&CNEZK()msD zb<53NI~cnK&>YOa_)X^+|-DSi|Ui9lIXXK*Nt z|CYUDL9g!^kx}nCF+X0#hOyxhx;Zmf&Y`a})lB0CYtJ6#f$)#*C`D)Oky0=GtNcueiR#sg;qnyyA;vOQso2 zGC4^C?E5Y(v_7kn4n%&c?~wHPH-cu$%7=~%w1KBuQ(HMAKGpn1xw*cK4DH&d=b5;xTyG*^zE~BO>;}1Bz-XUp*;cqUAWv@95 zEsHHP+-)$EvjCaLO;*_f=(QavbkSim47J(kP-Oeok?7&x19_<2^A8zyrRWkFv*$zo zv=uc`lS{8#9T`PPnMhM3kO|4y1=gw=Q$lk$1Uo*_P!CkS7wg02oat$$e3&n#k&whyB|^d*x)!|!BJ0>L&r)vzNgm^KkgVWpqh&4{;$zoV0q8wA8mQRF zk(Rv3I824RCY2rD8%Ci*W`0TfX);Zv+^TpH=54sm~AyOU9FY;aLnV_JR8(q>+ zyhc!tc`P~cu+4;Sw$S3du?NefDyr(ZCA7-jh)bf?sqO1|FMI9Oeg8SDnbTn1 znts=64p^?&u!EcR;ROVL<@rc2c&qFtoD00kWo*?0>tIyN9?K<}nlQ;xjAcns&V|iGy>Wr3Oj$lXYi%jiRppK2Q!3$xk91ICuCswp z04=(s?@lLGdg8O8J*PV}a?%8LRUvs5?aox)jieDp=mqo34g!}$YjU71ZDKDyc|L-i z=0{A8r4>i)W+l;TgU5wrQmu;ME5iZ1GFj$QsvTvj{0Cw>DUGtHEn70Lh0SlO7D+@o zZQ0~}%pW}R)5!ECsabnBh3iR1=g=>}cy07P?HSiu*~ zN!1?6Yx;rabSb=;zymXK#nNt)XT5F+`PnBy+(aBi+YhYj(Vbt-J)a~u7jrXheyZB7 zd&9W3FJM8RQ7Hf)#3a``ep+W5z`VyceRr*Rn>yVghS4NdR0{1bC3krPSZqKp-5l>(TD|6^^9p|zUr-s31RQ<;7B#l zWDFXA1M+SDx*3bFGhMzLH|J?Jn_%l0lTkhUH!zxcXBcYwy2W#tKafwWNm zT1xVbq^ABIjVZTq&5EX!MLBE1Z_}9)Rl1#BVgiUxpn=2O9h_?ryc&LHRdI1MnfkKB z2X&cQvdR(bahgNg2BW1JzvZo#wqwIK|QS31g10CHJc$_m(SP6W?cwIA;Hm>Pg3W=s}9G?T3RN7 zyoDq@m8T0IuDiA+u-?STXBV=E(DIqZSE|M4X2@qt6*~&onusz|<8;ntn|w>~Nc%vG zVvdBX{465(g7bnL6bn_`Nii7)yKseEF2N2JM}~SAiL4S;wcn@8X)F%Lr=Eow5MH(R zq6jUMj^pHYF4T91@SXOQV3kIVhFI_ogBQ0w@a!y7Ax*b{k7E7a*0SRV^_QJQ_F~!d3#bIheBL{dT$%e(#nj0dP5;i*&@ie`3AH_G>3&V3owR#Ie zYGVd{Wdt4Vyx@cA3%LIFM!)ZG_4}_}`LK5aEnQ+=t~d85sJq;EQGbw8heZbJIw=H= zw?H3P3dt7f!_F&+^#Yw~W3oTk`^tn3GSC<4eqQLNYqBI9NZ>HH&7Tw!%oWHNrrN2# zI&O~Mv_Do)lg-hTSYq0$tPEy17lklcC|PMXRPj%(qxCZ-#Hk)&mS@fJwC}W!exM~^ zFp9u?R!smLuT^|2&~a?_d^B@b6=&?ZmwPP`DCwjJz`Vkd+$~T7d)HnXkNLU6=~$=u z!Tn8kuZ(_K>&4_p+a`80XJpbfxeSMM3Uk3_%B_s~vOVL?^Ck8#)Q$5turkg?)xfh4 z-|kswgOfevNN9XDKq<8)yh%pco**rqo+={cmDQQti>gZ<*y-6PAfvj0Az#Z}YjaxP z5BuXRPy9VDv9IhjzzJ35iHtKxz8RPx0espX5*=PKv&*d5&&OnQ@phwS1Crh|q%24+ z`7}B&r7(AL*CI7}@A;LmAbJ63B!c=Ydsr_0eEN9PS#RIt${!6C8 zlisNSRv~5b`uui#Q?`$>E}<@;>Ux`(8NH*)2b0$D)^PI&l6BmY1k+iy=ibClUN(LS zqA$i2`-?>(LjAe)EkLchcH_ne4GC+srV8VY%#>7%1PdtpbOJ_~Nq~sAdem!JmULvn z5wrp3D5a$J8ub*I&i!YNK)aTsAwl%>zEp4V`InUP0@w>+|Iknno#9xWVJDSKSrYFU zW#up5=%vcqJQjXtG4lepSkMxk$&c;$0HxwzHp|weex!?POkIw*ducrzc_7--Z3v?3 z^twl+bKUjXYhjbArNC0VH<)P5QXqwhAd~v#xbV~0S2p3=XhE0t7Ecd6GY21@GZeEd z$gr_!VeD^fka}_GhJ`Qepe%&NJxtG^E&?07JBS!UdxDPmo9Nwgn3PeQ)BrUl3D*7c5$HLmJ6!`a*#!IZ7=gT!`cqwV@ z387n_#L;@^&sa-ARYG)Lq)7cIj}^Xoy$Bf(8QTqClJ}HQswUW_Cc}olWT;bMJwASz zB7#TV9i%gp`oaU>f8TF@^YJavu3p{~G&O@4ICt{!6O`Gl334u(w!vCzi-5qCJ4557 zd|aZac5oI@^)W=?=H8?y{g!7EHiv;X|;474}Se934F8noJKpae7 z_og}h6IS3J{t_&)jGj$hrKL6q_7Hf411dxuk^CbMW^VDcC61<_-|VP0^e_2q)32G}ZDpp z^*dy1YASvkofJ~fOIGW+oRBcTNvUUf`4%;dXN?*$$}u`AO2HC8DEQ&7O@RVqcOpR( zb<~=CY{%G_0R?bPgq$FRDV#ejp1IGP(+(M>N_E89{Dj}iFqvA}*oI|^9+g&{j*hOB zZYXc?agaoeX0PkY`P|XS*w}0FhqZyM+txVi+efS!>Ns*$E}@gJGQ(;Rvh`9swTe6H z4GVf=J1pr#EXi9d#KbW)Ors{(5Y_o4Szm}+tL)5yzCo%F@kLH$@HCOslo9$(4tgvE= z-K`Jvl72l(%p?^(m~`+VZI7&1%OssOra)VNs(`!t5bd4}nu>G@YQEFXtF>n%38&Li zT4KF4Hnp;NO^1=w#OacE>1vi#l+X23zm7DHo77eK_0K|PJI07!FW{9~5eeGR#s~5* zmEyVR6X`x3cc@Oy4KAD@z7w2IvKOgor#K72dhIPx;t`Z0lfW$bVmI|TG*}e7*E*-g zm?t!O*=2~kjO4?sS1ch*7;vPfh}ep-=O+q|w+O}$C9K&_ePU{>ogOlv`()SJ30FmVP6D2qTm3978Myk2cQtdYsUep1$s`}A=~5I+J<>eqx! zN!%e>O>72%CUXLo6U$z029}o}i&UJ+#>dIy3!IcCBLsM(Y+q&sF+}MPI=fd2E3*}6 z25Dkzx;#ZwA$pqfp4@*di+B*+SY1EN%;L1MGw0D*|8y$6CUU~?+LAL!C%-;{F)GAe zZR!@#ci`TuifI5^vnMn~6IbI|A`caFzqY{*h`&|e6Eb%6NbrtUEK?tOZv8c=!p4DJ z!r}U!lpX&GaxH|>ol2|ig?#1NE$|Ks%XOOSQ?cA4A(2(%APcc3H5Tti3MM_;^eR|% z%QzKw=vBoQUz_|A(UGlfj$SV%<(T9-#)CWkoK`I_d3fjC`b?w#CZF&0-cWVtvRCfT zqcT^UDKJq#N4Q1JYh{nuk`F(vh@S>hao|CwI94vaxRRFUiVc;e8C{XIGOAL>u6Z8` z6Kl-xXQ`c{Jgv2?)tHk8IZ>MJ+oio;*R&r{TRz4cI1hAc8@C~VJ<}P^QOQbJv4-F> zE*3s~b9q`Hd?)8@vkfk2TxwS5X74zKHceWc4%s3uXcJK*I<_lkM60VAODV7(OjqS>@)0X!-rb2tO1K}> z)g>H2T|*hEw#Re9>U36KT~S#EjumIlw9ip!s~+Y_qUA(X$a zH^SqYECpriek{$b+(}H>LWr9F;!sfteK@s)kL#wz=K;CKHz zccs_=!hI=nPDsrd*CE~0BKhhKdhb3g;>_z}^dxC6*Xy)j7Pl`;ozZ!CY{Su&N1tY1 zxf?3CP>>J_Py3vy{O;}U>fLCK($o2oQ_uf%WcH6pm6crQ^rS~ErAWfv#hzbaZNbjH& zDWUfs1*uX51eB`u9uPu@fOHU$8hQ)8Ce#2S{$9Vm_qpf$_SyUFbARXDyYCqLk9TB{ zgk)vDYpprgGoSfPs;4Y1grDaxN;(_CDH@Y2jCZlgyjmlfr#t~yO6I~GcIdhcvqjbQ zsy40dKLkfr#LWq^r@rat%u)4ReE067BNaW5l#*jjUHS}-be05LBCDKq+UHm0T!l;F z8P!Flh_Sib+babkhfz`4MKsYJqS5z1F9o(odmqY<%B<9L;6Gi?8BHtdzQl9M(@;-2 zKaa(KyJ=!7RmYgZ1vU}`k#V0fTtX}a=2q4x_bgjg`9~vQzN%r>v<@_F*mukG%1TFioY-jH&xJHgyQfRm9>wU|vU0Q~imI10{UH{nW zY}*oD_WLDqC_nO`1q>(e*LD{|gB^xcNRT$KfG+NwiJiirb} zk!|%~0~u}wX1jHWcjl-%FWyN~tFM3$+u4~n+_e(jykiP+AXsq$4Sc4Ik(YgPL{_5C zS$d4~JUdNti_-9?)(LtJ*PFGbNzlJ=*M(^HlFv|Uk=l(<{$>TV5hsI7?2OG{*v&Jb zK3Vc&6vuZ&I4Ld8@OKB$B8F|ALtZc4xUb1%e&=}Dy!&XN=Z25VGr`%f`I&Fy#x+v& z9ISk;8-bHut{g%xEh@%DGLI=%b zH}hVF?7Lq4n~|g9LT-JNm5A&Q-kLvqvX#s+xcA|VnZNQjn^N9Xt=T26Z^83qzSpwkWwm|dHu{y?8=2Q^ z#y8{i*T35APa2v`Gz6-XG&{y(qI%R5LK)n1>X197aAK(}hFg5mgN}}5u?#PtZJA3* zNCN?9iRGY5f(h!V0$~4V4D)V?4FSa9_JfTgzP2c~x0krsmrx=G5!~5vUvF!;#DA!M zDNmuv{)-IxA6+~6TL6YQ3M6_=NPdE{*kC3w*598>d>T@9F{BM$KS9&TB4D=Gs@d&1 zVl@L;07SY^2#*J-d2Q-I*^grz^ZrRLbZ!ESjW{agDcaN~B|jr2oH$>N0O(vP7(yK0 zCgb=>4Szf45C5$TS63V>Bs^jwtvDO_MJN?pBt5|mgLk(waPrLPT%6ob5IEWD{2bsN zhQVwzV@kA0x1^b^j?;Pm@V(##RcsI*Dm-v@#tGCXn~cgc8{{*Od&v&$O6%e&=EA_M z`vB7t@fC`pfc|bwjfD}i@aNz%w138|7YxUZxCtFt`2TL4ALTz?pouQr9h?PuuA z`7>|>#`F)r=C5tRbvpV0-`a8n^csvr{g zlDtlBSDFV;5d-MO90RBRUxTg#FFe7<@M|rOz;+d{~O}>FJ}GW ze~%5gPTL>gJHG(~SujOs`vI&>aGmLIW{nyIEUDO*v3~}zWPjbl8Q&5Lf3wd}^95gU z0~&_akYxw%_l&@A_q$^aFbLbC+Q~UUf&F!t92&UyvLOeL`$Q`oE^fBzLjuW0h{FDBFL`+IaZ$jQ`O)9yxazCx07Moor>a z&kM{tV8;EGInwWB@mY*NE{;DNxc0~2AM*zTZO&Nd97Y8FUof^C^jj>36Ng`i{#t8d zCY$oidcYFEngC1SKc7u8#lX@6G&PUYfpz$M3n-DcnBG!Yg6|{^GpGQoiyr2jnK5R2 zb!l9o}g>TM7gMbCz4*mW1ruc_#if1xE zYg3!xUpD@ijsKUk{lDbc{xy&P=YxlT+4x^J{)as8KY0-RuX+5hdHg>%kG(qsr3nhX zboFW)M>s3uxcMSk9&8zM{5V$c?15AjRWonUqw(&_WvSCM6YC3QBj}OyG?~B%u6#)n zx_>Bf{EsA;|Mi|{Aw*Y{t|d;zN53W?89}Qt z_BFURPh}<$WSP@mvY-RS{nZ!19HCa;yn~a*a?**rUo9dYbci0jkYqO3`3pfhupd9H z{<<%3M$Y}FS?&||8?}rIiawz9zxt%V44pe(m9l|Uq%E96y}&AV{BAx&oYETCg##@Q z_39b{$F@5`p=6?dn)FT1PhhS`E6p+3IEoV>Q`f`zrHAw7Gq8*+@Ys?DL`qjNP&I; z0C~kK>H<>F+=v4Lb~T>|=*u7X7(pcy zP2^rS)B(}e$?`pWNmNNL4w`^W*PRj^K#z^H0#wzIVgM5(%GeSj5FSgtlNE@Dg}M6+ zw7X!z?eWAZF#_MqnmS0n-RPVH;T0t|jkmoA+Hdl@&t0{}V1y;Z!eU2?Zaz6DT{U)m zC;f;y7$@Xe*!5+SvduXI<>HjJe}30-XXX@Y>aBBJ9F@#7aDWIc#|HNEsdXk%OQs$6 zgp<^!Wra*LJ-k~$(+SlgfiH~h; zDah}p2^H8#yl`RxV)L|)elW`?VnO;jVk(1NS}Kz?nVw}bp=(2YK?oZ&R*2J4`6S?X zH<658m#^RrMRa`veI%LG{EsTN`g1!{SRRgi(7Ke@@7|Cj!hg}XXxn4E*2cksky7o9 z=9MDxUvaY7H`z9I?lWz5OchOn5b5AHvKzrlYZA;bII&xO(B#T$JNV>|58^Bw zfQ6~5513D=4(3h|-U0K2@(o4}uapkMFGAPaOSXxE(PPO<%~Y{uYG;8T0+79jgu|<+ zbQHSD>tn~v6ap|uIDPL&X$eOmIf#`bYs@x>Ps3Xm#p=D5zO#W~1Jwo+vEVy(gCZ2P z5!U<`cl*ZgnYqY*I5mzbiQb7=4q(P6ueSMI57K&&oc6ZQ-UHOki)fFYz`qzJ@l_qc zsi6>CzAH^|^pV z$eozzdrM}GhyH`5kn7L92H>71Oe0hJ=-IUVnrp{8>ueW(2r}R+9fHgiBKD^?`_wv3 z0MW~X`jg6S>Zhy%4)!T_6Lo_g zB3zp}{HpYeSGCYk$dywG!ABMDj@czk zpY`>t6D{o`lLE3mrXFI`>H{**B#+N&wHvO~Q1v!y;> zU#KQ;Icj(GA~i{AOD8THaVS3u)rh|-n5dzZ(MgN5Hkj*TN|e0IGXS$_z^q0(Rz4B1 z`ugJ_l>=ocJHc-WZmIto$#5>y!Cc_SGgQKxzWUA4J=?ad!1`6ha{m$IM?q<3JE*em z*A?FzlM{@GfKV!R+kLN;Z&b;_UBvF+bwSqyFwd@b+M%IzYlX=b<=oRey#X9@u8WA9 zoS_HnG|*Ri-T5jN4IkSehXB}LG`y0)61?&$P?0Y2l?;f09eE2q#5oeLi%}hly;JVi z!8oHs!J!2OcWF)T4xgH??%h4o#Ww&gn7+@UJ!+)o7Z|}B{T6X7U(cR2h;8sVG@LcB z{>rk@dj)+f_4sCS=Kmg$62+sLpT5D;?E-rvs^9T+Wv(YRClCBxJ-Q*gQa1)Ci3awT za2)eR+vE>Nr@Sst$cDxqM!8Id-%;4CE;F@5W{t1=hy}V4XOulUQlWV?tt?h?z>r$b z`FZ`B$<937L!r+ci@-llbHq0QVC~?mnr&wJCTxs@JA%T*ST5&j=a!FgWv;Mb(CeXF zz2tbW#k57!5EI5>KY@Z->%p1z3OO6zPu2DDWG}BywuE=d5EX9-I8W!}lsn~tDXlaH zYzrn?C&}xOWUS{;5c}q1z*nf_`pj`sfal2Q$T*?^pNZIOVxxTUQ1nw2n)BSwvr^r} z7afF`qgy=>xr0}E4u>LR)#T5;)BKtkhO98xCAX?*Cf78pa;mVnxlWdA46`3S;$`fH4a#Z(aA7`0A z3rXVZR``?|D6|&#)_lL%SobM2iO4zAaqBVl)ofGal9HLXaY<30ZkB+!9WLK6n~^_8 zEi)gI+(36D*t^i!m9kjAC%V{|v~4~>q|G}029(YQ14);xsi}vwthD51_c2gmGV1PS zGoTn&HiwD>-ucZ$7C6>(LJ5IBX>rnrSicE zB%|Hmt6<|oo{Zq@C>oe@snBA3swb4>kji=AaO)H4mm7q8>;b~5weFW{E2ShcfRo4a zwBk8yF(e(edFO?CaD8?9{@8o9{r8G_hW$i5j%O){O0y-rix)jOYq^9>Eay$>u+Ua& zS=MT#0KS*EuDJBwQrC$QNVE>_N&7FE!cbX^euG%F)mxB5y=*|kTI5%^K zgnbzaRo*=t`n<K1DG!xY37ohKd!LU&;c;ez^nDMm;e5CCr&v!ps zpgH0VtZb`tBRVF0DSd+0_{*@8W+G?c6Pa@!8=Qasbc}!!S}lw{tw!C~fiDYZ6n7cI zXR-BIJ2Qfrta(IQX@QXmoUHGDL5geX?NbZV?1kdM^VOU5j zU5ZzrDLJ<4iK$i``0nf^!N+a31H#&$AabNg66iUk$7>ABVXgeSxQikO`3>q#+3;tskr2vpzPU3K_ampMG{#y61)mufKvC z^e0H2y*6GYUw*H0q7l8#9~o8o$Ims-~*bA4X8!RM0g%Hk;JssLyTHuPERFo;K*yDiu{;i z-Z{|cOk3IH3Z%i@oUN{hEep3pQ8_N2D1DoeQimLiiNG6r)0ws?(g0>l|YP9MM z;gl9Oxp(>JmFz7eX76vQk8HC8?T9%s6d82~2lytB%ew-drzh5WXl0;Ptrx7ViOum7 zdo7h{AJBwnk%rxuJf`Oh7RbG`4iG}ejlnr?veyRtgXU)>JLISCw=vm8`*ob8fWtc% z^yY5z3JAEzT$4%5KE8S-|LfC11wDlZzrN_8>EUXgh%Mv_&+L8wVO;cNjQ|tCJHX6m zoZ_KN@L41|%8o3? z-rPWIMQ{_`b>uRh6;F`onZObf~j$e~0lqQV4Z!7d3J&6+qc#$PY&YEM=dDf-f_hbP7ezM<3!^{JLM7DY3v% z+f(V8iG2bBopL)V#_brpjGN}@kle{kFQEW!AUpO#kY!{+T&yWbEj>}vPq9V zDzj%_ydR3Kb3M$hf(ncVf`>s%j8Gp!<=hr7d0fa6jSYdj%qxAbNSH9DQJHt&3+I z6_KJ$Tdt@ZezE^G(lvyZ26t}#t|9<(NI%9ia)A1)Xjvc>U`@U1hrBzdLn$-8VvSx1 zIetp|@y+ow*Op>|U>)jY&!FYd=K!}-)0c;6H8Sf(Y*5f-aCS!C#@i#n6L0;B`TnEP z4J}bse&k~R@B*~k?qYha*x_IoG-bF!RbkNowdbj3hx%)N=a!YQT><%%Xwz$l=Qk8v zBz42wNi^F!pJ2p}BvduzgztQl=uJ%(avB`@51ZBSY3HqQ1?Z~&CywkYg zNIl~f|1Gg7f70}|e#A0vVBzT$5w);3*`z`nUn)GgnE}iN=(h^pJOGVw`cAwI-7ck^l2vOY# z;v|r*>G0n;*JMY@a&5RyddXFuflSVH671&X#rf)Y15yJ-G@p!0n`f;ZCA(L*{she! zw3Tz?Cth0-(5}ywsJXxNF7-32N?aLo8x~eE!>F*^u_b!q*VzaO7^O-)4ib^O=g?1T zz8-i)*B&X^MiWap=2iG&iD@femYfw!Rm}%eMduZT)i1<>f{D1zF^4A*+KAL3`kRUY zJW}ljcd?=0kf-Js>b#yrruR!|p1jd-x>_^B-^4tnSfoEaWis_`Y?lFZU&x+D;{wBy zd4|ylB2cAz^CyUKpAI_=$eiv8;Yp$0;&34N1c)$euVA>R`(S{nFRSC}%_e>@Ep+;- z2zR%9^oAPS^7!WAy$h51$AhKK-a44MEpSrbL(mu=Z344nAQ&p}>s3!v(r}KLJ=BB3Z ztZHdiZmogZm&Sh|(|7)g=-I$g;4Lobk?jncvGOQ@V2E#LA?|8c^@YWRYhTm7SoU~Q z(ueiYYEdFGrm90$qX$uX#qsSnLBjWMEI`8;G6t$70EbSAFztiJ-ojFM9VqY5y=C4b zLV~vh#r6#9W(6@Z?_BQa4S<&B^sWLgzgl5pHDG4b`qrq)pLE zcoTOg^2xm{pCBB2P>_)|=g)WC^=5A^&EfLT4VmAwb}lO)3Px2$-$%uF!K z&#t`5P`@v8osZs#Xdsc^*Dt5eYBFiDBzPrjfrfQ>+p6w^>BD7~$ok8)-Oby|Qi@2R z#hSTq@9=??!F&@Rw2K;Oq*nHwxx1*blylKPc;!pB&DEC>nO?=BM{LD{Nq0Ys>Y+X# zXKgEv23Sji6;EzpYf9&?AM$-_7NqLT`v@Oi`yTaqTo}C3S83_IUTKzAxL$SI5$~R7 z!oS9EF4!db+Be2|tj3;A6T|stn_OW`n105#V{QrFG)&&-%KV~xJybNcVzWDwU;Q>T_Agsas2=wCT9uf2%XOfB2Ew0v__=mQAN5y759zf z$HP0aDn;8$k6nn)3Oj+SXo=3D`ZURJbIQYfTfD;-RD;FVGOs&VRc$mb#)A>S;j0*W{yGpq5>4CT%9zC)%I{<E$7C6NP8zjMO7wEd1*gRasA=UX+Xa0z`%i35t1Hb zhT#ifuqB!cSjrZJ9e=D5$GypR40DxSoN7tuvLT%z8~27_t56X|SAt+(2$PCYX;XWu zv^+g<3M3~xP{DI+=pG7?vr3>{w;i#h__sVC zN?}0N)%(YDXy$VwUG4|e2QgS20KP##W=65$!Swjrj1@qExA6a=h5Wyl&HF#Q5nYo+ z;sOCo2BG(|&?#5n4_o>heB$--7=q66Lli?foss-JSgYz-KsH%G!3W6In`5T_#G9v^pM-FX<9&Vvxy z&`uN-DTHgMuwlkv=MKOB1PRK6+_nCLq~u?29HqwQx%E$wN6DYnh%a?nXGWO)m+EHz z8HgMJO#04rPt*{KjDxN@nzWdJF%Y~$ujA>S+BwN)5i#yjTR%`^F$d@ga}`OtJy$E3 zZ1?(JwfD4$hZPjec`0%g?vvL_nO{1mj=p4rArrVUKHZbJ|CmF6`T15+W!w{bxusi^ zADb@T^m|-|ULGBZm%Hno>-Cj@=x#iMo;V9#(Elhi{6RJ7uqJRG^mwQdlc!0 zD$%l4P+rl#H_F|c1XcBcpVC%pAuMaoOeg%p0|x7@;>&ht)}w2WO6yh8f>6Ruy4(s! zsHOX>`p?mi_eMK};%HsG4}_mNzxDnk>~zSZl1O}NkZMWkF`zJVNE4YHkml)5mr5OY z#fdccLGGiR4QeLn#Fm5Qnb_(1`wDO4fFnXiQd8xkERkmpV}=RVMJl zEj72q5+yokJ0vm6ZfWvn)v?9=Z#~(GXugeqIOXo_!>YS6#BFJ1md;w&$yXkzjYO34<%#AlJz}jUE$c1YB8l7{c#48kKV@J~OTG=j$L}fBH7E3^ZK-1o z^gArmbtc1zXu(kgO4Sx}@_LEiR*1z*m&1z5rPv)~_bEFTuol`r0#44(gTIz7z$*I3 z$rp`9^K-axr0F64C+L)45@T=#3xe)(8bgt1z%E*|nM8>bn(6|IHK?;>03QHjKWom6 z_zRulcaImNfdeW_IAR`rdb3ocuJPY3Pmt;V+HQsa%@w|uEc|;5robIv39Z-J_|pb_ z(Lz{VUJ%$4{@ds)|3^N{3&7G~C-i)X&2I3480-a%84Fm6&9eI3n-d>$I2w#+U9^Jk zIF2%iFmh!!YA&cb$7#na#NFbJl2%(N zlH!^8Tpi156)if+kkm4e-)Y|N{lRA?iz<{qI*Fz%QB81RyrG(5m3B*NBni(p>Mk{9 zSicDq^?gu8d}3RFF*O?0vN{GoQcFJqhg6#yKW)8(Fa$_qIJS%L zA~AZ8U!XXhb+&im@~#FX_<{mIL5%QeWBd1|kn#OE=T27FA68}SMiQ8SI`@I?H~Ert z6nozbBknf^KbTY;(L$z6VK~m=?TstBL#;09M)_tBuARN~+8i+}KW#X%&+T0{FV)Yv zs`iPS&oVc8pTF+lBn=h?gY%IMv^sg2=zsod9h!7xx2TH(p?0k#S~la28IV+Eeov#j z1B;V$Kk6(HV#L`CWX~Rv_B14^V5-9^A-8PufI5HTWA#{O$6+UNrf>OoY76dEi8y<* znHKGmH_@!p>~=mA94c9u8az3zKRyuB&%S+BHun zw?H?{z2V>%nyIM90o%tIld9x{9>kbIZIBz z9nU*{{X*0^qcz9onoFeJ8SDoN_AXDOx-tSvY$}?eQqSj6J7QupDSeD*8{V$WhU347 zD7{GIj7|OEbg$)O0iok1bkwbM@v)$^L9t*~zZ)Vv7?yk2@|IyIZIYwv_d;Ux z>111S9b~m>!zVK?m6Vy;qd`B!{F*xxOZ1cm_WcoGR`C~oeS9BVaon4m;${PIE$2AU zyn7LyNxY*C%**7I-VmZ+%5NF1x6SW|jh=oHGCM9V9f{ZOA*I@UXq|JW;av{8gs_V7 z1?4#PRr8C+-J8e;vX@$N3#Rf3Xdc+OFim8-Zl^TewS z2i7HKF~=FRtXd9WqfuW8Qx}eiEUt-8Q;~po18P_fdmTd?ff>8vxFN3Y2SscWc1*>3 z=>e}vZF7`&hNPrYD;VN;l?>(e_2vsWxNBJe$Mxx#2l|J$)_(cC6J36u;A|-{ zRdbuD^J6EQw0*zVL2hfNt>)&fb%^C%(rH?)Hm*uV#dG zYDsp$XVmB1<&%p37;+`d4Z-VmO0}G2FF<$=(w>?z)+z15^HYG_aX`u)6u%sgjWb>F z12(Cp&JWXAU4x49x`vvsJdRdk@zQ~hU&M4WF!@9)QpOq|gfnHK5eB2v{hUdfd~c-Q zo_r$ZPRrgOi5yF>$o7(YIC_x6UCCW)F+wIYUhn?on89H)&UNZdyA2)8h7US_$7SFG zRc%4fAbe-eTe!+ZF-a#XJ*dEz&Uh@##(u>>e_uM?EGpINiv;*}DJFo)#s;OT&Cdjg z@%-THeO$8tzB#RSGbW+&)OEJRMz>CWw-rjxNUUrx%JGoaU?JzeUjvhm^JK1GaJLu# zT)5U=_uW)@T9bgT<*;g_owq#YT5`y{g^VlX>+d(~EGA2q7ro=fYpmONIy{0m0d1J* zOt=}=|4Zv4r0@Qdbg!M_fMK%%wkvM~{wY_{{9;^{xN@|1}6BsV1)toy_A zmR-B^VJekq(NCPMI(5n8Q8pzObqf3RQrdO){gN--b~P2}=Wg(4E%e<#1>as-`7z)! z>q;Or|58GnR;um=MzK0-5)at^J@41Xczd2~{85~tW1)0i#7=`_md&ZmyH4id9pUbV z^Rk(DRmt3%>9x}2>tkhpLKkhtFzY~&qNB?(-jGC1a&Iq-fVa~k;vR@I$H{p|_SS+{CL& zWOJ*NV1l>AD_&*g@l(Uz)LJ8}sYXt14qvEFt#fm~#@9HUPgT9AVurdgX`tJts$!dU z_3qVZu32@8mazAQWU_107XhhNMVRvRuv>+1skJV3=aa_r+GK0wmQMO}v!XcKr#7k1 z(OhZr)Q+35lUs^c@0M$*c>t$vF5vEL~(nj*TUH{!OHo zLbgG@NIF$!e5CeIP?10KM{{PWd>(z;D@Mtom8+9BI_#f3iMq|Mct0QSJ}5d)r%oRm z+Oys*F711F8BklDuJo32?Rl->HJ@B+QEW*k6lc#Dsm$Zw!0hu?1~FOO|Aj%;Rgch7 zod3S!%v3$Y_Dr&#G^_J{o3lecSz31rQv2)CXBq6T#UEbi+IeuCGr+WbZcwy-Zi9#H zN}S#uZAx=>ExMB$LAAWR=TY(EO233i0IF5YIuT|m)0CN{du4)dq?#6 zYw<8gG)2XnE@A_^Ko74(AJy_6dn6?#1}NuOdy~d>JSd6N;&JZ0G;G?8g!qdj9i@MC zn2+g;V-{)AYUT*%u72$rxyo4RpRH;__Vp`(Z>)?qy7@4)Q~sFpGIRCLg*P10MN(H^ zx%6T$>^RcWG}sv_t!14f6!m;~>qWX}h@en+T91>$#qv%WsH7i;bK}sy`f#&6 zSl+mP*g<&4=3ui@O_uwyolpX&Y*u**1a_^TW8_s$?QkWQx3sD6j)}&b@{ITpGx1~L z6O;vTY%(nn{Gy?n4L1OH;y(4O8+Lx9F7k9{s1}WFadfCw^U#lcCE77YqtPjW-&VC; zNZ~$6Ggz^IHEPhEd8;e^Wn`$#Gd7^39z);_1#aIbiDjdP@De~=&(%$5J0_UlooN2v z>;!L;DhoV(rq#%9LwC7(y<@SqB!k2zQI`tOC?*>FWOzffQ}lq)=j}s^)7MJb8|&<+&cwqGz5PnF&vPie@NM*tNZVu z(a*%Einsu=b60?br~n{6%uzo`*>w*Cs3t1CmaNk82^?>o&3$&BC`m8ID2Y$FC^bxp@}iDR~zE9lkvNB52#4remz zx5u)F@wfFRy{_A6w79v8Z(CGFTgs1riDB3ocF$hmj~C!h`qBD$+)?OJSsP0*Wsq?Vb{K{ z-1O|8+GYf5t?TbHERXv0nPZ> z`)_&1V-c;htizRu7|X=Z$V4{lxW0J1-p<)+1)=DA(+b8GqP+b!)vCS-9xjdJdoJz&R1h4 z7v$%Hx>+1LpEsUf>mJ3aec7B9_B}V~-&5r^40{<)q)$!|gk)54&Onz+Mkq&8wQGIn z8Bta46Y~cYXUBI$cIj-YnMjzJ2ZzKfKkfKIntgj-n z4PQnDr+eAQJ%7n~^OZasXZ+?6Aj*{>o;|c-C2gtH_e^I{-v|11CRB5{*p1Ih74BPr zpJv(1j=LOlnc3Ch!W7duC%V8-X|X=dWYscZ`9S9i5lVD`n@BmIaQRXsnUK*o#R=t3 z*Jb-YP1H?0(K`mJo@R5`hR_me4JaK_mJnZnawrp4zi} z$}YwsPFXT<#0eT*+_ZeTCV@`pxF{eWqmZJbGehZ3i}%G> zI}wz5HyRx&0$46^%oN;waiZ88?unZ|^?6msRphKX-9wpk+49`RybMadZaTGxjo{h^ zS7wJTPQ>~pe8~Mab!-9Cj6y`IJKi)%Q)x|NGMW;uS=0|1OyprTuTJ-p!2qUC5HB*! zJ3LKRq14dbpBr1R#{YT~PhgLYO=YlPup*=>`3b^4tvoY? zFqe1oRsgt7KJ?2YyEty+9B0~j6ym$8v#^HS;*fD5P2u~-x-{X*(op-XO{zMZ5%zd> z>mF~+?P56#lE6n~zWbdHca<8{Ejizbs6Lkm$9lg)E9B@py$WMtx1#AfEY*pSNwq)s zhQ6QW&l%Pk%sUnZ$Qf>voZ-9&Q!=-?QEAD&8e%RK&*dH#-n;LE**+{ZNGx~s{yaYM zIPR+b4rfB|h00KtNLOS;M`nRMx9hFLh}6_HQBjd?6B5n#_zjQs+b!&c3r3)EkPn%Z z&*-*eTcS@wV#)Pe{UyEy?`nGUL3hSz#AN^m^(InCUcic;V+v1rLb@p;AcmVn)WXhd z(+se2KjtQ9T0YcV&#MNjtAN8QeQV+QbhC>?0~&fB4Yyb= zy}CFe9JEhr*$LWR+%%4y8v!N59o?}FgI^P($qJH*&3G_4*|Grt1cd!P0qw*M^W~GX z5XP>Ds9@aLsJ%ejX+Y|v#)sNiUiYh|fFADU*udcC8DzAA^A03FGscQhp*(?1$xvQ1e!khL;@%-%l$on z`p@{eI_{dH*J{+toJ@)akwJIShBPqQ;&oEC<;O1w^AywlVb zJ;W(jC6R4M(`JJ&QFxy&aE`N2NMnI*992VoZ0GT#7uVK9=v+qEyhitvDGu^>!OcfJ zKS4Csbpel&5#PbV5+cE_7{#YCc$w|olsPF#Pkw1|aNzV_Ug{zTIy>fZ{9?t@iGk0V zgCoB2p)8N_&Z=4{vnF1oSws8mntvp?663hd6hqw({pdaEq39nKF+q}CzH;@Mxh3DxqzGaA2c#8q?HP(v&L?B}tRE;P2;VFEoFF)!$+a9( z!g8=My&L2xS|qXz(KGNc+O4XHx#qZ#=k*Ufm%;RQsQ$aH9j|@O1h6_j zAYpoPrp5PSpUr($dN&IR%3dyI`mCv}@El{4lv)uA_2+JX1yjA8^y+=kgfvxvk5H)` zym~~Ph)OtXb*6uI&vz7Y(>6R4>vN_KJ@E`qliL|TQCxI3p}djdx-i4miWiiMtT3tX zQF9+){z!Tm+8_leN$DMi00RuT)|{hN{F4(JJ{fdY+f{g7oP=p&wvPKHNP}YbI-Rm@5;8wg<0hG#=ItsUb8FdzDCRbROW4aI zKc+?IL@akV=6mU7@8Vt;#0A!~XWMxi-=z?>18R0V0GU+*Z5nzQ16uEO%`xB|9`7(% z6xX(xe(pCF%D$SMmow+MSCdc)P`AFX!{FOOs)Go4>F!Ov7tFHvEHvZaM15XOF3+-WQ+L*fbFEO zGamwjTvJFt4#;>fBYem^f$fzW;d9)v7ij3JT&P=b_(Yf}v89_HnhO!bQ)L7}*93uT z&k87pve%C_kS8UE{E;)63PoIIgA14C%cS|B5p99+Q`wX}Y*y=_p3PX|;CE~+>zn7` z{;cOAz3T!mdq(mvyb1Ed#_$r@L~E?l*}CN7DM)k zw~lYV_K6;E1{1rAp!d-L6hf<@) zhMi3GKX&>`^9tK3P`e5dLzJi6gv?Ri!*eO%NCW&AJMHh1eiaIeEQ^#ZqXTbe8HYvE zn9g*@>=s7&bLuQ+Tmqk7zxa%lmZR=R=@8K3_eDbd2|h`NSrK{A7%-DNxNBA?e>Qc4 zHlWa(Ijn>ZvnkGsuI_X%A4=-3tb1N^E#t$L81YjFTG-3Hx~FQ2FN&jd+kL3Q1w*w) z`L>szUk$4=A{bt#6@i&RF)FQf>gcM1k`xii=Rl}!Oqg8V}U!cB#4k>MG9YYX%&)hOjSAdM8U{OI)98fDaV{|tJR%(+> zl3zQz%LWfi<#z35en7~HE;?K`r94>YgKrD8i8;6W=1v7i8%l6o(+gprXR7U5Pfv~1 zsxIW_NgI2IVkBr25|&iRVQeeBZ+^F{&F6J9IaX)Jt25+FImWTA-e0$MZ0wXTAxy`b zGQr|wji+zQ&E!L4vxw^zPr=$k;`pE;KfC0sI z^(qZ>-n{E5{tjX{{|pdURXlX*=(D_%o?wWd)roA(_-8P^8hJr2(aC=OK!!)BA!|M} zIK@Pp=HioPrqo8CM%|b0)UdE#x~1%lX`*IH-ll0PCHD4Zw@yW5Kljvc#AIzOr#KT87&8?+F^ zCA)X(%7#&OEQTdpcth3nlm~Q^7VR8ulet-pv3J z2xq)4#hvaeRRmeTq;53%-9)DIb3Y+MO?kvI*yp=v=8)m}U5W8mT$4*7A1}mddn}>W zRVKe7Yay4z?Aztm9XlNx7OhJ&o}#b73zhQanJ4B`)ZViX4zOy*Pv0c!xZ;`|qYoT6 zvaHt&>EH2e-m%Yxa5uDTrn)#uVLGgj-Z#R|1^qP;Y#D4{5er#ob*Z^u3T-4GJxDGs zxtv|mzLITEQS7l}***EzU30boD8|rU$T+3pL!g-eR#Fs_4Woj8M5lWm6pD{Y2B_TE zz05T+9`#fSS&v~-fm?f`I z2`vyH1_EjE3p;?OBr`g}%L*St?1&=-Sf?oWZd<0SXn095azggDjc0Oj<+Gn4OGAk< z34J*!GBeR~@#eLww`-iPuH6N+IoJLqp}B?l{f7X0hrb_pB2dXZBBDyI4T$3_R1Rr~ z)p6}@j<*?pUftSiUq8R-RiZ^Y(hFoe$7vMSw!hq~3vj?vLv zTk16B$lxa^^pND?Y|pR>+T{jrcyBpoL*pA{}VC|DRW&4a#Y~vE{fEe@G9TS8=7Yz0pA89p=IvDt_C+kY@ zc`+;J#VK*d`6R2Gq)DphR>}%cMwdh+H63j63HT_R92Rs0Z_6|0XB&{kCC0@*;U?i@ z%@!mP9*z5zI4qt1d=6cj-ejZ1#7)rFuK!GqFvlk&Fo1<`Tvf{G1Mdu5S`5in=P8oJ2+UtD zn?jI$H%hZ4Yj^rU5|Gp-_4_)iMs;*c)ajE(JIYaDnYQ`++w0d+5r-Sxh6=i(`RG1fef$`f(JXo@_iLk}=W6O@ zGX!>>09|Bq8w)jOZuJKn4cb5Tbe`&z`7t}NQlMTlA9saR+M~}`m14Hq|B%DRk*yP_ zy+{nbV==We3IrjUk6 z3sHp^+K3@0sa|G1CIUGq(SMaQsab=JTW8hyq+6nAdp28{Xo2nzrG~242F@@yrX}Pr z#Ro;#*Yr#3vZ7)b)|>7i-F&BrfStO%g5?th`93%5y1z`(99P!%ow^&R!l&u}uBZ~B z4ki-Jbsr0AXL?_1tFwo9S6L2PnU%lHM_nW(!!i1c`Vp`XeN2t1na7pjeP1;`jNpau z%X#L-OA|I5*!K-Y?+T|qulsJ7R~hfAec}-i2*>d(h6m7=th`&azrSnqv74eSUn&|T z-VF+R?Ly)!Ljl1W9#VyV@KWwSYySx%nX={IIlc(V)C+ zILoFJ>@GF|waxF(qmAy7^AgY=y&g>6+f!G*>fuAGd}wgjpk}x#F9|1#IZ70s;cS(a zU!8L5Ua>P3ka)FOFC$abgt-Ab4_Y{DRNLBiJ+hctW^HkJu-Q*215u7BfNXGBe1~1% zgrZ}y9!RY-p2_piNuspiM^XIXXJQ*(`CV#NDHdTwH>qDo!Xex>f>a(O7%Nl;P~Y zT-o$g^-kNyIBoNB!CKbV-sdx2E1CHLN&t_}Z2EFU{dGd{ow+P}9JIthYWi%H`kl0U zuGd3|7o3ZK8IthokwZkYIYDaKVQF#%M?RmJH2K1AbmhR+-a^r=%hQ>d!K}So&jjmB z^?V|ZeZ3P`Cb@sy{QB96)aX_+0B!OzIsi!zmj5(n`&$&Z|4Ji5|6 zoYgI)Vs6fv6`;OqtR1V1y|I^8Has4ad^)x|^8NvHVE}xQLYKE}Jr`F06C?vBpANA@ zaaEHfRL>Mas^fm_7DJapHUP#SqF)k$8aQF}697^$p8@`D!ittodhgr{!Vpg-A=`MC zVc9##cc#>PSiZ9>O^RxSstRR`c~1JNIOw6+d4hsA_X%QbS1Z#lp0y%Ka4L?4L~)Bx zdQX(NJhVG5h_9zI=zbW~_czY3Og~y5-%Pa46OnkN-DeN|1f=qCq&gUd7*|w1Bl&Z5 z?;~MB`DNvh=eg6E5$2~Jt8WZkyb}BHyn6bR-{WE9ll|UWOVr?dw7Y>IoT?X`(xe6G zyoSF6owS$r>YVkfMg|xcm*kvo47iXPOm2$K5?z-L7cRKfI8%#5)8Iv7ij6lA=&yDM zyVrXiDr`J13NmcJ4Y9)=;JMu(85ynum!dIov%g?I{$9y^LMR#D(=0j#C zn?%)xTLl}FmQ^vOm7j@TBpCLuu5daMMy4JzHHw)L3*B7LhlUS_cY>hp?ohBgL&Wv3JTXUy~mf{wcpHo}0n@ivmP-B{WRbL#X z0(H2x$8XdSioj9+0m!x{4*!Q85?R4nkBRTUo*)=c9+*(Ruj3EI6^u}mEREDu6fW7+ z*R*%{ob++!N3TLKJ=EOHv@&e*?Go4fw>+sCMmikRBnza$x;_f!?B?ntoO6tYU9|5l zU7m^K$+x>oU0d<&6+?cUr8Y^o`iD1&sP06`X*aX2bQ2<8Kt6s^_v@FDnM;cm`p&k6 z(mvfn24OtSW#8&K~-(M(k9cuJ*op#2174rCYPt&1E7R=GL_+3E^SplVjzf zQNQS89eI3lo!;?oVBdLborO)9op(Fk22gAB1B{a7NoTHw&Z>RlO_S};sv5zgYbpiSKAK%JN;tSiWk9uB8 z67pN|lPUF9RdXUDCw`Q!#YJR1u0&WrGv8K}-quJZE4Eiv2a!-1wX!_;YsSuoRAi4< z@?-%%m7_AN8#OF?*Wb*nzR)Q6%$j6=R|>Ff&lC_IM=1RVu5v*0a){Zo9J}``Pqd%% zkGcl$o_--p-OF##3h3-wJ9OYqf)IoimO}0mGPU$MIWU2^Sxc#mLW|~6!xk_VmJDiLsi0~E_B>#N%5XYf z_KD!(UN;9iGC6cQRQ<8nSVfwmbg310BjJoPj_BK~BV@ej6YLXE_MwR%Z8T>a{((~& zsLrG>Zx*=Ya;YxsM0xvfjrSL!8=SaG>xb@5B9wVWhVr;c`em@C*MAOP$7y}@KE;%P zntEE)g&}VGj%kLL%$zXMB>&JwGGW_Zx*uHmu4CS2Y0-Vz=X8gXSG!El0X7|Bw(PEm z{I%JORb>SPR+n@nc8#quV1i^UafzpRGbJ-c6k`ea~RKBGq;SYW!HX^q&h#qmPbtD6fR3x2kR8_1xN`@s9UGY zE`I_glUC@eyi<60qThca)$1CdT@1Jr6ZC@BOdQ!uu9H;GFxJnNJ%;z|=!JE%5Pc}Y zO|AZcgTxSoB$43K=!$?2B}}r}0om#@MZ4o*)`x&%f_guyfem zkZj=dELdApGr2WQE5K!w^1$bGY|rJh#_`myv-D$r4C$`;T5ztJy*&_Av_vLOD_S}L zKei{%?ZqHEcjxt;W#KAl0aEN?AD%YtY3XJTT#GzH3k4r!6Z=Eprvv&rvJY&=uluw% z_vDNCIlzE*3`smivyDSv0fg|`D*02u9WJ|;&tlJ~Ri@MoODX|@%`hV9bG_;nRtMDE zFBl~2DIW?4mOpA2$v|xGvC;}?jT!2I!rQTC+!dohrfgze?3O^X&c*o1#*@01#Z2C= zYVn%T6BvKMQpfO)%I!y{a@37ChyH0IMk4vDd586B3#~-oq_0JT{2zOfJ*j$H&%ssK z`~^k=(L@!$Z=*j)Yfjs;m6ZeKGDxSMj+GRNIdOp#{ZV3*SxyRNdwk2Bs;88(-r|ix zQwMq-^&H8fD@f%2bWbO2!fJAEf%FbdIs5j9_s4%`>Ag?-Y*-jXrks#>JkxsEKbjLS$t>WlQ3Uk;udB?u*P(zN>Xz^0twul+^P z?45~$-8sU#a3Q!!?&TOZ)H>_3%&Twp$X$j2<_sB5UPq#2u2@?m#rBxnM+c0yIRqzB z@A5V0HuJWWg^wECx$a$#a&(c!#pXjbRGq%z%8h6NUm(2q5e{xqA{Rz-Wnw%h5Nuow z(CsI&yY}vmXGz4gfK6ifQLk^csSm!e%U@-^9!YxBuj@`)A6&R(O2IL^on)x691&Qk zD@<36j_QjAa!NpFg6 zXkB^erKWiDwI&qL_q2(@99_`-$AO?Lrmh|T8(VWkmnU~2JkmitAIS-uYA<+C!R#t6 z`tY&+^togF7-6hAS0%~h=~Hz1HO=?XvWUq}R|AxL>=j~(_?Q%1rZRGOFr>9DHBM4q zJvFWb^#L;G(L2~+P$pZ5=a+p9c@yVEZ?do-bRbHpOld`#4F%t2`fAKvF-!v|LSUXd zF|sJH9W0#VqrV{0XZ^u9v0Qsl*oD^aSGcyJbK=O;01mA#q0t(#^)dT&se|Ub)Cmhe z3Z(8FS4{)NEc0r!58B6Fid0nvZ_NEfQL=-qj{Ey_SPmZ zHNC*V!3GPJOn4N9&$D0oVrx$J4u|BVT?}|EkIOE=j{6f(-rjxj_lhJj8!T1u_|IGaapgfZDa}-*BavGw=LatY(z{ zu_~t_C!d3YKPKc@YAry?4n@t|yqd^#B{Tzzk0yNWkAFw6MB+o4!L{Fq5NKAzpuw%> zrttE9s-*|9Cdtofg*pY_Lzu(dsaC?GL??Cr$64 zYsFc9hn>GUK4#DLoi>DD=%N6Zc!W>-3p_y){K|sQc*?SA-O3_?5mj7GZ5`YzQen6e zNoTK9LVnQ4w@G*JhE31xnr$lWb8hPU@F};fDB;`PwYK(|6C)T?%OOmeO)q3fiHea| z`g7Gyl!^^{eK$s>U5%Zkr|Wnq5~0fSz&cb~t*OvRnVW4T)#s4p_1zC`^SG_j^i zv;2VY0#mjh{22T!1TmhBG*Du-7fftkv2!b+Q^^WyFVlfz`ot+c^)GRJ@}G$zM9j+ori_^ox0~$C`hRZ6c$iUPB=0Sl^j^Og28fbSh~UUm6kRB$qFRYI zejjnxAa*ncZ>xv*6PE|21cbfM=lW;K`d^S6{_hRKfAx12#nYC0nWOPoNQbM=2c%sw z>|!v;8d1`Z!^fYV?9WPSwa)viN+9a2%#y8jPhb!t{Ha0m=BlGF8ZP=5(%loH#oqyW z=GO@mHkgOI_H;a)T^OkmdoVk`Y>0n>Re|bDGh3 zDo|yw^EkL-3zX@8wWY#==O`)Ft*gB+mwSNN=t)l?UXTd1P|sg=7}7CvP|~p!VzazP z*#*A}-eD;dc}{f%w;c&e!#A^!j@HSZzMrN$Mr2eGA342V+xfv~RYuaPTR2Q{uD1eD z8WBpftWHwMF$b2FNg=y|f*t6cc!a^-8_OafT-Drsk!09!hbV+Qq2^AQPV&&r78$vi znzCmCby+=J`MmA{qB=SbW6$|Hym;eNA6t`gkOE^{N@)Eq?RRBEW5USDFhZKJYu9#UZN(wFTn}fKN>Pr+*s0fSk443o6PI(=@L1BW3WJTu(yJWiAl>`ayDr!aogdQfi7oy?8u4he5G z=WyTC-R5^eZ#C35!m<5!j=DBq1JCe9y?Nq4fOLJ})?G3^K@94c1KRMI$Eel52t25k z;Q>R15>ITP9GKq_%R7+}t6k~f;P~_Bz7#2+j_gSoU#6snAz4c((YK+pVMHGuUvL?l zw)i6x-HVVhc?hrinO$_jiW0z;zgzXSPLim%FqoV5ZIC@Xnavti%30^m4}qexbOcCo zU&O_2l)opQEdPQ!YHUR*m0m@{A(oZfM1C~FiP=Z6RG=xR-|yhvNRovbZv3{s{yUbX zpMfN3?OrawfkA3#Ee0y@K(4 z;Q&@ys*#(uzG9$aCP|D-)F@+K0lf#$w-!#5C2XbRFN@9%8NKbj%&iqhh1PW^uCK6fAa%RPxF^h=^U z-48jx-{-Hza6D0ij?#URs$`uhDbM;cOBeR7omqRmeNk*BCoL2xKct7rvvTy&WhWqL z$}+l4XF;LBVlw7(3#{r8ldk|~e|j+#>wr6(1?n%A!ql2JV}F3N%1SEX8g;k|Z zz7@q*B8eMwKRs?NG$TrMa)(m3nN_0SsB*?4O4Kq%kwq+|#&8hVTn=3iO}$Uw!F!jE zHn-(WAl}Tb#%P&PuE|?=5u=80h&TcL1^r`W1eT+JMi|m;ZdKmd_h^n}f!|E2-vXow zss;fppUWM8o$G&0k6QO{V4@>|U`jk=stj^KK6VKXy!4=aM=aDS{~~zf6_S2#6`B=B~iRa3O{PNKJbn$)%W z*RX>B6Hro#U{xcU=CRd_&#eeVsEpS^*I!6DXS^LZf(KEg2rhxvt=d1Up8wAGe<${B z)%kbx?d@LB+v{`5o8G-~Da3GmP~!BT1;xLA|F6U){A(gf1;{N)#OFo>hlrj%eyU8D z=8RMAfhv%a&{ll-7xIjI=`YXx*zwTPBdZ~>xyRMh;_3nZvVx+uQG;ZGZf@9(fFv() za5;>5BZam76#Iu{!=D+~FZumU{6W(3CjNy!lnt_&r3V@ct4sB2zx|km9|OI_+gb&Z_FvU15vZ5X zd?ZF^o>GXV@ibPK*D?FSI+DfWnKJOYy~Z-e!EK1_PJ5WbOnIhbiwXpE0<{q2ggm10 zlV9mHSQ>PHu{$BA}3K{yH&DgU=Ud`fQ{-IeGAjyW_aJN164- z6U+m-xhEmJZ;5_K;RljMaD76Ak9_Yg^@Cb`L}D6xQ=!#;P@U_wFVCD(s3@GAvq>E3 z9xAgo{&MLyP2JhaU{yt~Tk%nY3IY8iy^iEns-8SbnpSR5pfMQ|$=2}B_S!8qmXU2b z{8Bx*@lNbAdSje#svTRIHh9kURk--K2IKzcdojPDW+4eekM9gG70NB?iaiI$pDx0V z4mnPGU=+UsIj#Ug8Ll#1OOh`}9h+y(FD*OBv9QACSa<(ILfPH9)m%@NenT-Mu`l6x z_tR($a_Y3hXU%6UYe^T2*>%M9j3V^(%8MTyS}VHq#=2C006vK_MEs1FHj|@M`mXfN z7cSSleBI&a7Z*g}0@J-4xmC@&B$zr(w$Hb7Prk8)u{~|>l3lWg)LZ``=8c)8Ycrqa ztg4v_#wPZgWe-j5bHaE2kvlsn2mvoKgFzrNT%H1)u>VGR{K-1f`OAX_0u#lM*Pn|<1*#l zAbW^4tS=i}pU<9~_6GPZ7SBk*jAo)qo1XYo`fIoACYoPZX+4FVvmm6T5DY$?uu6W1 zVlZqkkX7@6DcqY56{RuaX#}^Uu~Vo7O=*rMmVbMyCz(kT0G%c>zaSE5!1=;WBQ}E6 zzq2@uxjYV#Wv_p(>)4@!?m46-g_a)98MIFAPc4Yu5GCUn@}DHr2hbM84C4F2qh6zM zBdzU10Jo}2QBz7S6-SYVDrpu9^9Rj&CJO8BxB=f2SOWTUNCpSW;FdjyG1xwsuIHgShgc3LXDq6d%dY zV0*LsavNLD(RW9Q4V{09p z`=!?b2)x7#+L^C<9B*&%_-xj@PEzN;2AdFru1Zb93Xdu59Okam_NH8xF)x|5Z8?Dp zCy^r(TCwt6zyaiUW0P?ty6tZ^xkFu*4pnjX>Pg9`*|)bxB<+)|bXK@FQ7Tt=$Sr@X z_{yuV%n;2v=-+jGSI%;Q@MXj&+kw*(Ah*xiTbON7(8XU!yeS84uskXbsQ>oI=nfw7TcByn1(vdl`o69%=LQXJ zUG>4IQj8>&@-JFU0bbgb&yA=XX3qE@|47p! z)W%AV%@QCH2_D%n$Y8aD4=cAf7ztVSiAVyt0b%GK9f%F;^kLb zVC6@a#Li*37|9>fSR0`CE8RfAsMt-59#1mFF>L_~DX&w-7=BB1)PNVVIB029yp$i{ z9L425*GmxOd_Q#{U_w(hTgKN^rw|7NSbwdLqmNbMvn>^zQ~eCE!w|VDKb<} zJ06faJJc17`<-e!9J-mpJnm=gLD{}g-W*1h4bAL4=qR5P1}c3@Eq6`bnF4o&d9tq% z!|jNeQ*zg;xm{s@?yH{ws@*>|pGTa_*d|*(_YohH3Zw}&b~QzBvtfDR_wgtWLTug} zyy))z3ZZzp+BIc0R*caXSwgbG#b-?oTzB`(`ih(*g-q2J1<+AuIjhYkl-b(8dcy#) zSn6oSv~YXhvKB@;i__P|S2q6J`dGFamdgYml@Q`@<_`SwiLIrG&CF#Pf#c zKO9;A|DZv!Jgr~l7f^Zl0-(`7(ShQn8(9fy$$>ftIHa4(taM1i=Zild{U0%T*XL5w zEd2|U)LxC{5ybzHmoSLTyW4$!rQCAH7%LgYSedO}=gX@;mGtJj{!CvK#;KtY8p`vx zbo&iu1|My2OQIYAWwu$qZ_)zH;tidH%5(<)gyX)6jOMjUwlAn6^}2ONqP|K{*W_ee z8FWfChOBT}pY541TV(T0-7t;kDc1N6mn7dTjzvXRXF=6OmQ zy=s?)4oXK{o-I9V3lw_;F7$`&H_O7>53ieG7GHQo|Ngb78j!WIHo( zi|QG^Gh0M{+bBjU5!s)I-$9T4LglGiMTK_=#1Fe<>49g$sfVr{7LYTr!SCT}zu;2m zcwA_%RW#2U<}+=*!WgWcMesLd~r7?*Rbv_PTOag;v-wQiu+#gYhAK;a~3?hSspBDFmX!M0bVdX@ZxA-4j9%7 zx6F(PSwwN(kMVlYi5#3tW^EB>?jtyhxsFvgX)v~3sep9w>UOpBcbo}^#LJzL8m`Q* z+L4HX0*RTHc`*x&R0M~Y#S?@5rG6ifq$4LH`sQWY)t_(6U zQeN>tP?9&Tux`gJ1%}#VEi6Iyj7N32!~CDW&cao!xd{*0jn=xc#N! zVdKen!}Rw)yT2AAf7zoW`QD9FKf(4}RlUKt4V~9s)5eRk5Cd$+9n?ha9rY#Vt*e3l zVv5r22@aZIdFYgNUgUPQcBK9f4xbqzN-$DdiMyKn%6;lLVW!Y%JwC`5q@l$7E?#y$ zT{dfITy0jl?&*NFAE$mL_T<5T)qy%AD$Fr$;DKDHIe#v#HQw-!V{+hY$fr*KJ}!Ov z&9no%joLXeX)r*kSYO6^`wx`XFi@X{yXbApo27-tz87NvWX-Xfa#g=*6tz{8Mj846 zbUWMaWMO2qVqyp#<8t;R_qag@9a*od&Z;)h>)H57smQ9HXoc#hR&7UP{CH+=7+JV% zNTd3N5Ut!A9@<>#@*YCEetMi);`#6lI|nD$kO|<3>}KpvXg$Ag57^a2Af_Aitk1#$ zPS{vzE1+9^^WA*|Uc*S$Kh5lI1+&SS_UxTW!WG{_6L{Y`9Eofs^H$rJKBDeVC+reK zl9f(ez5OKFRs58Qh_3D5x_`bA4G8*)-Xp*j8Q-z$|FfU3K}4d!l22`UAL^jQ-J{6% z7D9806y&7CB7Yv_r zFH~9@f`u*^{1ct`?__n-zlu>p#g=WT*T`E*H6v9oR zCfo1Z-!5Q&*%y`YTMeH+ZSjqwRHoAiIx;{+bjmwuH3t6vvMo;!?{nn#HV9iKty`(33oVnzo(jRGyTjR_1LPhdlcEBDfW0{tTUr`MNo#rByLpNk{Y1hCWpaqfjQmOs<-C=^9SQd)nkbC4QZwRC$_fS+>i(60vyqC7OLjLoBD-$sFH{7FzW&x{;O-!sNu5=UT?f8NwEmLx#* z7cdKI-L9+3)OvE%3BJ6iC}r(we_wgp8=URcyX8mgk3CBB{BvgJ{<#6T4yOb>)WrOJ z{bOxlIYD>)ey+;B{2*@Cbg)?w8_7lX=(pR;l1NUg<7=)F?n4Yp1s~N@J|EdlU$Y(_ zk#UC!gZT5s4-UV*Z|wV;x>fl1B(cO8@;#zIx29`1Seq~h8Lp@{?aDRVzr8)tIbE8}9fImmN6uB(OHmzVmH1_NYk1tq*G#l(GbE*xM7;_n zX8yJmJI>e?uew}J;l|r$#IBQj1U1|D#WtupLyafO0k`kvuN6NGbeF`=hXwb*-cr&} zaPaM42e~d2`~sCa-WWdmhE~wtnpU(YZsb?To&k!enEl1jo{_J{hY?wC*A>nc0{Ilo zd%i)~xa4+Jt0tfCOpajy)+UIZT0b9$S*+@JG!!k=mWpr#y~?w6qdp|1JsqPL5nOkw z&jHw*M$8o&cspUSXL?~Ok@}iPeQDPffx0H3U!OlaO^nEiqoPX2RuJ+ZWTP=KLNz0@ z1aqh=Zs+t8y)4~SIgAX9r^R^?ePy->gz4!$GKMaz*@if)rgOc3zU_|L1S@As{?l88 zTiYMXZ_hs)6kmL7sTAo4h1ajAGcYDTwsoB1(j%YpFC2P_x3}dhgH8BC30j;c1?GsU zPaS-jn}b3D#m3ebBj$3I>7x;HQkebAcEUz*+qX`opO&dEo1aAj?<)`pH3MQ@gNU^E zGaFNEWl4tmw(NOqfj)nZLN6+})&yR__pHwkVeNqomtH6HCy%8>t^Q>>R=jofDf7G? z!WP};u3~R>>c)fNcH7Nyij1fS0MBdy7AcXAk>f-n$#cS!%!le(4u-fZ1KFg>qpfH+ z!aS!pH{%r2V8}6|Vaj>&%7P4JSTWJLSdJKZF> zrb75naD0QhjhmjwfGqb4QZ-TU@Vm*!N+K*cv_n?%%R5(5HZw)BF~XHUz|If#XResp zwWnUV(|fDyA<5ysbCpSXOQepI7DdY3hRvZ|xWjQv#}9zE|YoiP&ZM0N=Wxy(+#^2B~Xz z04a%g!d8#Y%DT|f%_K*T)vD>JCT@ay%HX zKA-!o?T-QUZ%x<*5zoX0ukU%j*1;zMB+b5x4e~c9 zK6c~95to9r3Cd=FYKoBYrax^$AYJVQQtiG2bM)Y9zh7zINbL!g)>u!Bmn^O}fdpP# z1nSaR>!ahxMs>7MK?Iw>w2tZazC+VELyab^O|7eJtu+ zq(OVD_Rno#Sd?&JPy)l~zRsFbEK|Fir>|sKU0Evwc;0$);m-}C-8QwyE5!B*w@R^p zSzB9u61HiAr?5qiTMyn4Mswq(0R^YuL2aw`xeK~GzEId+>ckE5+FHulT1;f{iM~an zTROJifUqJ4%Zn|F<)k0j$p>Oz3h-{eNHL?2avbAvo_WbKm_Lk_e`8?W*&wL-@y5zQ zI{-N@4{hfQq2j=rWzm)?^y-?9j|BGDV=kAetbD6a8RZ9%Hk5r zu`h@D0WKTGYZ2UUNC)I%wTHAXj-O0f-L~QcGPeN9f(bT6X*$w<3>zBRb{HN+IrVbO z?PCAVNx2BJGtpa$FH|vmpeXIGxvAWun36bNI=h4bWxA6@G8!sezB8V`{_PvxV3}~V zcOXymQ^Gl`D{op%_!?8$6$4_ZHd7vl+JNmg`2#oAkjzZhXd6vv@Fa_iGwit|Uh2Bx zYC=(R%kSrNXB>i3F@F$MSEgLB3YgY6FyJ38Ott4x*pvCBH1e_q>r-Sa)?)fxEx$eX zV6lzbssX?tC{awUmZ5A86{}3T6R+oK#-*44k^AlSjiR@&rz`t%zFUndQ&Ra*#1R>~ zzl`7ME;2cmxa?`c;axqp+ruIvc!@S5t-htebkx3N5Ns4`%fSJM!In49)7Z1=?A%tc zQzX7N{*DrRrH2G-fV5}sGQ9_UVqjeU&VJWW=WB9AUJ6fey2usXIh$MhbHdCDR~IG zMMB8DE~yFu4eqcb*vHsE4Wyo<7v*l%l}~e>8Ij%b8SqZ>EmBxZP5lhpc5O#P*bdBM zk)D^@#c@yTR93Cw^a)aGpokLBcHKLe?yxHHY&x=u#vZgu?jM20D!0NE023<6QVN!R zQJC=FQUYv+EGhMhf~~u_-viJkL53(RS{yCc;VdiON>@bZy%wakbVm~zG#H87DQ5@1 zHdGj^fM)k#AC4PU@L=I`x4kVj;yEOn(yn`f0k@MHIwBs|jPk}X7GV`l-_NyV_vK2H z>iNPINw*o5B7Hb!Q)}?5OhhLcTozAU+l?C-jybwrKG_oGaTuXi+wjzKYlm%#=;i-# zn)4H$si+Gvn1flf6|_7E)ss@}tYv*47liAbJ4l=n_wfjRZ}2hPAaNlxKTHNn0h)5(HfA;Yp(iwJXJE3)%T&De{b&V}o0; zKPlEdsjS?Xw4@(d=kEnJ@z0(I(7*(_0KvstOC2(sf_w zeQcQOiTA`&CLdZ1+8BJFV7^JbgtR|>0iN}GMme16YKK0`V`f#97=kR)**QGbV1oo% z7F~>z+rMq)y#7K$Mu1C4(sn9xR))krUJDBBbZuN=CSa3&q*-Xf+6CTWadq3PWSkXq z2E)Hkxl)Mdr^ptyMzf-lC3G0Kg2ZNSyp-#%9(8qTGWzY=JCYo$raq)sb3gxi993y8 zSzJ78xJ!VHmO~#opXIsN#|aN$NmXwJlg`E7ar0(aB_{<;_{Wgy2Q5f%nWG5z6N^cH zg8Im^X9bqnC>PXam2T4+8g|kSzKP@M{1rIxHTK5sE%Hs2@WSMy7)&(K7@*lw_wjta zuGwRO#^eu|6x_dmY*eH7w*i9m?&USe9sZe{Sg&$v#Q;v$xEs~jtCRfDet39`56S!s z32cAC>%$-zQa-ogYp*$d44K;5K#5va^)MnxjiK22PTZ9xup2wr&su!oE?`h!?E)7e zIsQEj&)3ycQh3Nuby)PX)JE5Pzng>{uY1Htbp$uqImY~Sxws_y$(Fe9tGrp#*K_+p zVIekorm(nOImP1>j@*`}y2j>)C}cLa-+gqJ78XOX83WE4Kl>@1nh9s`pYz1TeZ{Xc z#@&nbO-JGgEo=OLWBd^{5Og#Dnk6l~{|90)I(ca^rQ_y3oc@rWjLkngH+n3Ej*6=- zh2(-RDKb?!h_C|3bp0zf!vB-9ApHm7I%krh^w}iJu?Ta<4E9`Gb*t%y6YwlNtB>Hh z4*KhvW^K3QxOA4>7m);%bB5OH!=`PD1WP=a8bCCLqqkn!c+94X;g%BjsV>a>q5Ztq z6+ZQQVmgKNW+C*#4vJJql>?F~_CqZ|m0o^vmV-W-I=in{;buZh+-YYe-gW7|c3_60O~CTMx1H)U*VJoa zhTf&&#(gl)uWZ8SOXVPzD;C)?qR+Qw>;C2M)1arOO9(nP(V^jW-dWG~a zq~GElhtK@$rZ8AEVso_&THQg2KqTwx$Pv)eC+O3&{aLwb>CCh9((^1r-83F}3yRI# zBopa_b>})Tn|oKOr9`@qqD3%c?IU6DA+!qu&Y@clCGP?&9Mv68%(JteuuYN}gLmE>_!-Va;5f8X^I#6Wybq zh>WolMy<5KAgu(*1ChTXfhd!M34-S+@p>N)$op+mro<-eph^Ygu$;@Gkk(-k#@zKN9kASgJS2dl&Xbj%CBn}|R z0F!?|8%^=z>cyg!B*ZhdLj6`KyJco|;`iglGr>2>p#DTaMDX~zxCEk!@&4iWKSXhr z{7;It;-ALVk`yu1W%=+v=C8G{a$|{u+zyY8(EDq%HR>|OM16gESB;EioER^ND+B%G zw9$&xCKZ0T=}PZ^fZjj1N$)>_OoA;PMGO{Or{0j@n1|$96F(73Go2DLH~=Yn{D`1+ z2yQ;MTg{3rk=+vg`-ZnjS|}WHE5reR9A1-aw}@kPnNl3atGX7Ibq~5mx*8^Y7U6mb zkZK&Tb?hYn_TvEhw;ywEPV!dXk9fSu3hK`8bwrzZ!mqfcAP*BzSQU=HqC@1CAb6K0gYde#jOPah;bwe!q;qVdirQ!T0Ap@XCh5_L=-2%lxdu& z4Bo+rT)HG)k`&p7mzgTg@sX_0xRR`@vlGIWO%z!aAA%e@iQyke(3UV}=Aw#edpDja z<%P8BTfR&D@O0TeKK|?rk33)rb+uq=@-J2=E(o1nnhldy)VW00(E{)Xd|3ZR-8vU}N_N|9j6{4rl zMHUDVDIe8h5WBjCv$L;Tq`g}@2CF<$VuaqGK3t(OPe{kRWjUyhh})>ij-rlYWLBaR zdwwjw6`KW*d@b|WKX%R&{xZ#2U`<&E9emYttLJxNhEHH_;41#vN*g zM)0_6v>AqKeO|}6)~tooT}@xW;==D&6LC$X#g}_)Rht36?KW$XEkW|)x0mIB?m40~ z`^c+wL$dVLu6fwI2j!z=jtCP!L4}d-2y)AgHW|l)h1J`5(`2=o3ftTUJu=_A2UrLq z>&?&Yy_{cU;wIRDth&*)YC+w^!o5tn$m;t0#e>)R!K#u{YEY_ElAp;&CsRyq73vaB zW;PcEG;L;vbmv5Q`YL@fJ@x4KG~UhznYb*RLB4O3gP>&K^(KHzy>^ZK)V)LXR&x6Z zV0Qo5F@8VwG)lO0U)y}#vB7R2&b=X99mQB{3AL=`X6-3su!WX-7L{Yn80_}h`7)Q)S*|%V3{!Rnc@A6h$-|`)C*j4Fqg*e-`ZjQk!F_r zEjDir?<+Oj7l>4N2i9;y{b@v-Y;hIVoM$RqT+MN~AXdQ%FA%FCa^r$I#^pzG$)O59 z+Cbmr8uCY|D?9L$$&fpLGLy3x=fZgP4Xu6pvS4x6?+fBaMvPMJ`P?{pMv+hzIDi%n zi7&?9C=wc?p`j5ANhE@eYF|Pa0tb+7GXG?#yo*izdqp2B9t6|{QkL)%8+82u)8q6T>1B+zR3zJaRogm5D59q z;32gxF+)iIUBh{d_Xmb6LqqgaUZK8?nre|^0nDI92}oIVjj*xzykjdv>2Qfoz0R;? zPvb*4i4BYdMa?rQHx#rKD5(p=fdgOKk+-;R3KNd|lrHDKjQS zgmoemndp%xVxdvqGYulX*YTxB^H!vRhf1CW<2)FP{f!GeBCjlXk``~qk+;_zWhN0` zS7VTrL1|_p;cl}@AZks?esfT!Wa!i%xDYF(bucBs6=t6XS}+)syQ)P zpoJrUkK=L=hN{aA7I@%u!12hcznC^gW6mtY*{kCM$g1^)wKLC0>JAUQSrnV0qp%O{ zN5^;F$Qf?McB=^Db46=@Mb6?3QF5he*A#4Uhj!o$zczx0TaNsmC)UU$87y0L+a)fq zllF|Uz!%P17|2f+VuokuyVg@qP$cSqORY?jgZ z!PbgHa3WqaC24rBMZDF9$1&0;{-~hs7>C)_*x8l*S)7aG3W>J$y^QwBO`NOZSf>0?b+ub~K%a|8C zakETI_HI#e|7u_I&tv~@fASygPtK#m1s3@MqCX_(j3Z2YFtL|qU=&HzNg_2u#Q@R`gb(uE4Y%$>b{>h`rc{V60nu>-k( zBJHN+&PccFQRM8vbg@70P&2UQGaJ6b>S3@2(?j>w{nc8py8UYCl`!MqS@V`fPm%-i z8}EK>%@H5m^Vqc^y;&arP)qLp(I)&R#4R z>(dRPq6~ZzdXzWK8MTndTWhkYT8$o@{U6l5Wl$X9z9$R`5(t5i;7)K0!QDb|cZU#M z26vYr85{xxcV{5L41+_0y9_$`V8PubJLlHjw`xz_yL<1}`{C?|uC9K%Yieft>8Jnl z6JKF)PVuz~>3KV+-{o!4Ydf6V$frxA)RpIRQtde zf6x`Mun;iLJP{yNeiMIUv^$Z8@^q%VPDfSz7ey6v_(XgH$&0u+ez$m?(#fMLixYK+ zXFuBr2^(Af42~3hXV#Kbt}cP9($?MxJEYpavJ4~XGgw-~-l#Iv;WeU`4jZm8Cl<}w zTKx(2cF|uL_Vj+&i=$|;+=6QApZ}mr+`*o^s=kPu=kg0+5JIIvDL{SIDIGsE?6cT+ zc9XVoFq^dwD{`!)!YR8SeMEO7Y!?;Yy1uqaj~OjFO#gYKxA7MRR8#m;RTKa}sVq8BC-5kCu*eKbg|S=NDb<~jy)KP z=$fPTK8cdfxHeo`F~U2F!jaI(n{C+u#+aV2>kc}|Jnb$Aj+|QPf|uW)>vt-N@nhtA z|EZeyOPTkdtAz*9P81}WZX?b%am$Ta^9F1#Yr2&t!H-092X`jLUX$1JLe6e}d41pO zG?bPpDblJ-?&qv-GN`amV#Nuj6yMOd=e=@e-c6d6`}yeLuHF%@3@dAI1tc!^S-Kxc zfK=$e;i%Bplt;hh;p#&1W^7YJ2q0S>&>Gx~68YeUFOIG8qF0p2OqH@zLUHS>m7!nm z?7Mb$^p|p*NXGNVWxJ+{vtjGB4XP>PM*Mar(3sTVi6LXhne=D zB+m_<%=Gqsu+FnX)=v|jhT7ao1qm;x!;q!zgX0(azvV_IZ({?!-6WLt_*r!$5-b?X zMx)&h;^54MZLoun$aU&P4S?gAPXA~P=%HsoXeHUjon7_$8tob07Z$Rq<>NPpAcVt@ ziM|v9@)-rRa;N+^7;-;L?a5N(Q>^FwK!@$A^{>esGIV*3FNV3E6{*-LrK={WCuoBG zS%PPls`o5{+R2d+xGl-IqZzjP<-lTct&B^48EnrA*q(RrJ^Xfl0fv3qxX);Dv)Cpdozh zpF<545Bc#@Vlq^pxfi>I3BPv$a=(=s4et2fBfv7^)-P5Q#ji+WFE{UI<_|dvnlcgO zK1G=uc9}AgWXd?N`YXEDtSfpED!2gJOMTBAaTQ^1=@o`467BmAulNp#)6gAEvmyRi zwI%WhF7-VV>v>UvH3b>6NV%SaJ!PFa_X(DtT1t$*0glrj;)xod_D>l%RZ*$1g_|}| z*j4Q|rtiKzj&sU4_$W}mgp1csFT9fKS~*;5wCClv_d0G0&hQ&tm!K=@CLCXw;f#1i zcCMYS0-iar>5LKwRO>NMl?rd64m`-9s9|K7JN^Pyg9_fsekVcbbVG5LaLbza?5ttc zHRjEch_My@n$C@NDh8{pkj@Wu+iR%fpV<%7ozyL9f)X#kaQDb;6H!ttI zek-FdExP{Pp>%UKG0g$(8umCaCRHq~7Gbc?La~@>WqQF)w3`c;yw_wR{RP zO)WFjFP+E&lMC_Kl;B()a27KadCM|r4dUa^g;$^C3=iK5cJCaR$84^N6jg6vBS zOg@f+HglZTKJ*+?Bx7MrTM1e*<c# za`Y`yotWe3@)h^k-uCo1RvA>!r*ruWcV~nYXT$~8?6gY3Zv9Knn@c=9(lep)!T#ZK zQJvJ8i`mY5>^-8=W1Ll+x3w7&>+wrFvFE!gFwapY1D;oOS`D2a_!okPU6OBYCL2@2 zFAIE8mZha8FMZdubf&7EOQ1rLN?DdkMG^;TnA8!%_n)R93Wqz>;9-$LK>Q#2Ca3}# z-Cl7*dYOH@3<@{NyT(u&=(l%3KJ28v0v*XeD3s`$^%J~-{C5t^A_{fjR;0YJi73%P zvcg!9^>d~?!->KWntQ_9g}Bazg0q*$T)q}ghl>sI8OvjVz7-5%EHk=3$uhcn>U+2( z6yf78k~FYC`4}o_dLO_7`1Eyx-E`$v=0~serokWyeK3DZdj#mQnKo8Hy}BZ4Vm*}5 z35Zg9C!58X`k29(XMY#em1k+I-3#_G`OzmFJ1ur;!Tn7*Jj zxS!V?*Y3M($g7TFxk5Hk!&?p>jw4o0`~CI@h-#9IUcBH%*Z#cb@{RkaPNLuUaNaz`uIUkoz`6P8}Ul*EC@JASLVe8y7OFlKzsOH6d|4;(9 z!XRdl>&={6VBxM|@zwdBpH5%~o`1kM_$1sD}M2buij9 zk3}|r`JWiWK52YwpItCNbEzX;EX9k0UtJXx&o7%SZVWc%E>OvzxbfGKQrziA5O_BE z64ZhLoLWuLJWZJ6F(U+Ub!IGC&&#n_99yyGaZ%CHYY%`gElO{;65Br1L4GtMu7)}Q~F1^a&!qK6I=Xx6S!8(wa-h!gBS_^ww;yxhB*Z3##jNM8J=Kh~9~K=+fv zRcCt=e0ic$Q$}u<^U+|$>Q$>Rnq@-j)mkp*Db<6X)M@yWtP%Cynb{*&r9$v#+@HKF zBm;dRx0#l4w-?&_sAk`e?b>j z88(K{Ka8~T_!b=<43^v|*xxm6KybKgL2sIicTY@5DYHnRl5r7$p75mA(_J;&D7ZLn zFSgr61$I%gGP_@(y^gQjIUh3V1DaL14cqz4sdD>?h)J}p?ph3_sJ18f*3vaJ`D+8> zgnN1ko7Nh+a^-fk#J^Sc`%)I|rpLIm9>u?PT3_;u=#yWY1K6Pbe88HHofQ3|1ol`e zb}~6V6O$vH{o`Drw5DWdB_F&_V}updyG^}9()8=@aTO+}qP;IzdM^@0%+tL!S;gGj zSW5-yY@6wDaOUZG8g#wttiOHpSQIqQWWL&3%6~ZyQSvU?BYGo8`4~6aFnCR5Yw+?B zm10_nchc0i)W9Ocj8RhFQ)u&UyJb{X9&sX*a^rVq2RL*N7%a(R5q0N&Xq6n$>0*jx z;sY1YB#7rQk17qD?RuUcxC>8_7npn6*9UfsvWIqLP)t+XWF2(comrj<+y*(p zpk6#sF`jr=6RHySOues>sljv#F7 z;mQaFlNqVA1SUJQ)7%Y^nh4}!*n?(g*xz=g9cgtGdOg4Wr7_oM%ZE1kQ-rttz}K&o zNWcRt>!CB4@;!6yQ9gt@u2?D&9Z54?gvw)|7^JiasSp_^&OItPyQc5_qvx)P&4kxn@LY{k{S%YFYbV{7 zzKbo_Nfq)S(3<_hf+!!Pyp9ZF-Xk;Y2UOE`LevSwU0LyJPlH77=L+p|#ZI;>LWznf z-UPetT-%(BQg_XTU~3pRbbmBF@b__CeJkVE>FfI!CF5emFXHuNtWkY*_1A zYsat9a;yoC4u)`VK9SaD?fTD3Xqk*l?Z6tpBatTye0e~)OeVLT#$YhNpd&#nb;ahB zS)6ZLI|88AG1{9v6B z1)iIEkg~I(egG$0-r-!<7H-6S`DPJouJN(_;#phgI)9{c!~R>&p`zg!y5_xL&K=Vd zQ!hsEoK|Y{6!j|)v7!~TL?mE+$lo04-i0ZIc;|R|$fVQM(9~K7QJCz7w5pyA-1E!R zN$Rh$)o8yFxU-xS@!#xqW~^{6HSR52-k&g*ah!FUYQm4;_C-|+Gf-HBdXx64_;KiT zz!07H0@-7o);TsRUvcVpP)=c)L~(w#qaXbFHvc01LhnZ7R--|X;YYH*yD9Q$4vX%^ zXvS79Wm9Dt?#p>EJT8}oUufEZvR86Q2gl~HogT81nZ8VbqJ8FZIKTh-qW@H2ak{kWV*hs(*xwT}W3lTTPgvg0UpW6E6bktVu zwT!lpFpvqo3-^1E>-FNxM}=|e*8Ki}3*?`G&JK^PDjt1`@GZByO4qI5-cWNeiUI46 z0Kd4j0@w9lSCSuv_A^!xtWJ%GMSQ+pEk}!P}>cBW18?bVVf1n?l5cke2F) z1V|4(eTmw>9VXnW$7TeG+h0XQ3;2TLNY}vWzzX_ebZb4>2bC#&0F8pm{;Q$IywA(u zS>O!Ia5Y<|_BtTW;8R7YGaIS30jY7U4O=1>;qs*HqHhrDrppsUvWoSb!VK>u$k5Pm zg=cIQ?(|;o+Uipn7Q*^7RzFs2c6@5XI=MXPVliXAdHSeh!41~dl2f@jGz!rZ*N+z~ z+B(WlNf~oDx=;rri`I^KTEGT}XiozV5U$86PJ-Jx`LfuCk*v#ThtN=ji}3~e_-J+r zm(D@siro|SB*;T#U*wSAhd!gU-Urc$_4Kp4$1$+m?IE`3cqewFy)dF|{pR`H>4WOW ztKUazuY78lk@22&bDF%xVmR{|jNE;W{gQ-4^l+@BV zuwQ*K;1@neEK2bO;jD%XSgBs=2p4qs#PpWvn`@Z^5u9Cplt0hw#8k~4eE8<0cwm42 z`$4S!faU`SmKum1-+<0VH#(^Cr*$TrOwP>84SKin*R#Z+ljPod48OXK zGCth80()WfA)~!nWR)=O(;L=f-Ju=QTZM~)3l2pwTru-QeY-R9-Yg`GEeR$>5kAJo zTT$z)e~_bWT#MB#!lBi%67&gb$}m&wIp7(S)qZ_)c(#2u0a%2EaNTMD^yxN*%)aL{ z3Y1Dd+eGDwhT(;VruMC@q{hhT(E}Vv?){+K+urTh{@0fRwQT?drQ)oS!{euMw6U7g zHhC#lDeCU70Sa7JAyKoMVUSFfc>XFNLbPcUKOej86#S}b^QzjAg;~Zi@|17$X#43J zrgP1`w@*A=&0k($xx$mq{o?zx{))x8w#}<5xn5ythSRVpSB#zLd{O)?eXKZFQ@(of zeWH9dkOiqX#|n}0SJ>aSTk(m!d$b}}vg~tAPx81S928Ss3)xxa9e(A7tW$#hjclU3 z&aiOYjrv)So}-3%3JP9S-!X5+fj(c&P&8-fJgQ)ME-U&v(`W7$`)}ee@t}B@(}co8 zUQlvPm8!kn8zgM|;*)hSRPj~}th`q>=}kEJTnww%a#D`n>!-hc#cIam)}ge1`}9U6 zTl3qYaB*Xek4f)rDzHOv@{D!Jm`jt5@L3d{&b*N;xEB3?C1&~OYyMSZ7-XV?>)+Rc zcXb`L3FNxJ>F`NtIy5EtGdVE$F4dF%gIIKJN!4Hwy^r?%3Z>zw#N@U_ySn%W5(bxd zT64f*BrY2;<{RdoFiQh5y7LyKRU`PNM))U>J_@KI&m!|~0^GjK;y=al5)KqWD%UYE za4@_})Fd;Mmj6QbkN0aS7gDG$Q(9j7-?T$uuVK0#%i;hnjmWVDB?UHglFDU2J&u|90EwqW58+|o}x!Px?r>&@q+rE7^C zQ>3YXr#qX40+n5v478R#ML?3~ZpIdpL0>~cp$_-b5Qqa!rf6Cnclh|~~;B(IF= zCa(xqd#MVrn8dw5!+uzPR^!60Dny)ji7YvU;SJv{d9~Lr?Y6|FM&{W$h>fm!sWqCC z+m0<+>4XW{h}08Pq6(1|cg$XDRfxq$6fdrfJHJtIbE;LwB6VCRh+b-NQIq6~_pP`* z1CmyUtBHBB_8Isi>|hMp)HlQi?x+ZnT$1?GUMa__+Oh4=s-q$Nf5iViF17$-+b;{;irt zHGDa0zIzlO0Vb^C^a^Kq} z90U|ZN4{xJLAhpDAbHlvYlhvJgprE3_(uMsQ;1d@ioY#zUnwbwE=P*;{0~e2#~Fa9 zL&inm7jg%Y!LM^fum#c#GZe0G-8D-QnA>`!gU3Mexx^MS;l9ci)l8>Pc$Yn%nthQ*((X+l7Cw> z^pECs2w}VSv)$bydlP7uAVkbO?>Fn_DU{BzCpJ=!FD*C`#VnBq*fp~BT0<3ktSd>? z_Qb+DV>#8k69y*IZ&W+2TLkb2V)X+N(bCV#=$wQ|m>Nw})`AZ};zrC)fOk;;8_roa zCDdoKf7DwlBfE6Z`b1*0(?FN7#{DzWgvvD|U<5@mS@@uq!x@)-DUQNX*Ppa18HbGTYzQjf_vN`BioEg~NVE z3aGDKARS3cI)KCdVn8$=&+yBBE678rV;t%7VWZRc7v<6*V(a3zV_U>?9AYcyOlOB! zxzZ2;`!ghIef}axkL!A|-MlRE8xCn}Q8aV-xdgX+g8>DKP;+c*yzN7aH>vLu6jCn= z?-$k6J9~7#dkaI_FNY|V+*BIP*B;jZ0Dy~DzC>_^k7W)v)u%c~DuXU2@*j7I241yq znL!oh(F|GgXT@O(8~nocCc|WfN8%p#MdpjS5q(mmyE%*}keR3QYvIF3(31G4#(}ge zSu8Rk4D3P1s}-(!bkZG4R)EB(nWDzzZi89cX^(T%P;~>6QY$*rWR*>>{%alIirH1p zezO~NyWqUr;9opuhI6%^&Ui}v8B{rCCM$1>&4_ZQ7l(dXM$>3aP+&T~W-D%*4jQdm zSZFh2fGactmMJA^xsF=ngBPle)Lz-|dX@&;?oTc++PV8CzMH>wlNT+E^-XAtbQE{1 zEQ-%QEkRI{LfVBsNB&tDrwEfjA`~E4tNLu|rjg;E%aiM;BSGsqhXj0c1eih%t+s{? z@aYAxaPUbbHr6d!-z8GGfLbRuFl$&#jyfyhKjx%h04FklsgjV)QxR)y1QY8gWGSaC zwCe!ZXF9K2qcfVF?*-GDIV4v0s(_neo$ra#CqzwFYpF9L$d(cMo-KU(! z#MaP_=k#mg1DFuiKmI)LhIR6~SBPg2ZFUgyoEJhE2Eo4WRLiHy{i17!gGZ&H@mdFb zzV=MppZpb`+X{ru9q$C!RhoS*&&FVB&+V(ueCREKFdt0i2u{R=Ie0REnmuzCL9Qh8 z$!mO&ksve`y}x69px4epSZr(SvZkPD4}X5uhz=uSBcZO1%xp87U7U1s|5~ss}f!t?u#8d2Dyk@ zoA^hFn4w5a)^?+{4@eZ8Fc>(mv!aUE`bKE;0#oKsC&OJ7{QfVBz@5I*@mu>z1D{A$<54D2E&I_~WQNRYlB|pO{M~`7zd2LytU5f(a(dCiLVnAy8W-JT4?7?fr*w0~V&(g1I zI$aTzn1^?chJe(bv)2_tmZ?!mv@hAspT&oq9C1sK%?YDv$$+}OS&}KuJAEqoziVNC zk`$6aw(lM*bIOp`*oUu#H}vMr+f{^RZIeZ)S&A|El?N6VInHfZ2|RCoNr-<)&=nOH zLJek@WtNhLKirQKSP?uDB+G5v8~&S}&_CyM|2Y0ZF zSLhw%ff!KMfdAIsxxkC1KI5K8qI;8(#6%VK;WEjfx4XpjBc>+O78OlyKbAJWj!pRN zVc7RaKPatr5}0;-miO1n(QCX22{lIvQ8-cqS)2M4DLJFVZM`&1t!E#`YFTT!j=rGM zJRW=)CmC~y&rJSm0myt9_s17jh1j+j>TYB83#jK6;^v!0XPFSbbT!k~im)MP( zNJs}a-BYybPMngQI=F%QhF(*MRXaNQu2KtY$`_bWGsThF0E@Cc34BM-8`@?gBX^<; zPxT!;`ZbLHeZ9}8SKmF4UyE&(Ebe9wvAz!dRPhz=GbS{6ylYTCqrUGSRCUo@U1iQ- zP+DZg!D}QqJnXPIFdkSSi9b$Kcz*7^L~@0OYn(qvE75;l=vj)DGC#a z-XLA}%W?Z?(8|3D&HiTb(SI4 zq8Q@}G0tOm36-?R+01OGq|$`fH@Pp#Es5%um0c>8d=&<1Y*Io*X45)LVvK|``=!I! z^eyqp3w(D*%0!)CY^i5^u!^w>_iKmCoGSaprzI-@(0Yp$LUb)f0fJ1~Z+Hw}*6g;3 zMH~cC-5aTR^E#0o5j;beUCGC3JkNHMywk1C+*_myl&~6P;IFM|@tT5rA38-uog7A_ zhg}N2Pwc1zY>MRcymY1eEEl`hh@t9diQ89x<1P=G;RV?p88R0)hElO?d+9`{qol;Q zxyDl4CyCnmdE_WgA>d;M&cL@Hz!4v$=+o5mgoO5dF_UyWI8=wGy0z=4Res9_V$&qQ zm>D8;S@o#jDFd;oPIX?^sp{Kk<}nWP9<>94#X3QRS&GLX% zow>)C@LGT6Ca@Z94j%hkhyQ%_Bk*c~Cl!}821#$D@Tf5bho_jH4oAlc4*H9A*6v>z zA(dcs-TzZ9xPO<0`48n{{$*{=v<18pR}B>aZlN1VUO(TJ7KS4AOhxH>gNT|=RtjZb z!sQi!s;koaA3LIEJgQ7A)clpE@yHVf?&e}{@_wfWQMA$iN}fqL+IoJ$x2IlH+HBQ) zDwL*wGUdrq>wfm3m${gruqA=?rP4}rdi%SH_VOYKLCi-@%_&V5blQ?)-bmWgOxMy( z3o^S`EXBNEd0{Goa~4Q(-SHY_sQ0hJdaWh5r{ATT>U!2-+p)G=8VL0oHHLVtM@z&V zVZ*n2RO)@a5`VIgNV7Wl>P(w)}m7v zS?IC!`k!}*z|+K8abiv3vR!pt6(~EOY_deJI2yY~M91{JM8zW5redLFCCd|i8Jt}_ zdxnMI5i7_Sj>sB3@B}?`00{4BBpNG=#^`=Ce%iVniI3@@{i&tj-Z*g#0kHmd@Vx|? zn8#0XGLJfaj9&Wbh5t<8dW);Ef0$+M3U{OUmcvIn#5!|@l9_ew8M4s^kEx7eX142p`%Jqej_Q#M=G)W zLz)oKVj`}S12O!uqmC-POr>TuFmuw$s=Z!CRE@>k6ZPRRngHzyZE#?ay5}xRDQB5* zz(@_jA+0{;cVyn5B{i_$4U zob5Y?=_0Ct9`hMFsOU~CW!rKmIc6~DS@V>Jaogk`6uxNNc=x!KJa5p=o37FQT+Qu_ zr<|jOJ5(;s9fF~781H=JcXX_EavxaldR4xiJ5xiWEiiZFb+X+P!ZKV z&3MlspZNNv2s$YfisfB0x_H}>h>6-0;qcP(P1wCgrms0Rr^VN5_V?PBzOF^oF8UW; zy|#N~xmD{5d>BpBWwRD4tcWMRW+1)o%DW<4uF6+Y!Kaq7o+U1dJ2o1|CQ>$7nMXcr z(Vo7>tO-4HEbB1|Z#(LXw4pO`u|Ihf7z^2TEK=COGFRRl;IJj}qwwv^$sg=b;*o4W zNoni27pvR^j=Mil<$n(1vlp<|%42tG>wIfE^)&Uw!w@%3%v^?EkSK_`$J*0 z&>F5B8i81ndf6niIXn@Yh=pRY-8IH0pf5apV`GT4h-j2?`iT)~l+bV+>x=VME(uyD zh*`_0NIc!AAMuLAEA_(A^S)8UFk$@b61gj@?=SBk*ROuL$8OY!?f;mquF(YG@>H2} zIjnZ*QY0kRO^LdOPkW2cr|VAFUfjpr(6(9=-Kpiq|HFQ>n+9C-(S*Ei81Obj+zvw9C=lxCX@>glF&drww~KE|s=gd>dE0 z*f+ErNkl@dW7on%xK(YhoUWR3Sy=)&PtMNIMP6oA`3ow~rSzgnR}HOe2Qenk9>K5h z`Eq*n@ZW}<3R;a%>v};-OiW+09F)c`>kn?zG#M9{Il)>f@q`Bc`0L^p`P}8C)}y5; zHHYg*lK&`}@AjpMLaP`@!|$Iaqa&o92C)Jf!Hv0oX2JW-@JZtpkgr(wplwU<5ZLRG z_6&dq6R`>VWx+}emAWj?pW&laRl%Zby{GA@x7*?Bt9E;qm+m6C7Z~*YJNew*{*!dt zJ67YyxvkCC+oFoX=0I`M^;5=Hq0Sc9=dyhqbqKZP&F5z}@!9w{)579qwWcp$UPbOH zIfQn2x;nl4M3boH;5;CBzc4O}9gu1I*ohx#Zo))d<HtXt+F1~Lz-f$*rjt1jc`mple|LFkw8GTf4*dxs0}Mbi{pV@9 ze{`=KbUEQcSme@%L5H`&86NxovIpRLWQ~HHSC3M>p#0ApdoO{OYj`UA6yoLLz}u0C zj3EHq8|Hv)0IHj+9G{-*97LdQwg6V^`AStuel3~BlY;}aBSrTic-hz0H&n-)`Q_jS z{j^7OCz7i*b_6`PtA*H70ko7)y+BpFUWOiXDJ)>{Ctoe}FDo<@A8@e~GF+!Eb)k{( z+ce(S;ZGl4T3GP1pNr?S>k6)hb?7Z@+Q5UHsJ%&U+YP6Y)@7GVe=bej`ej}}Hg9us zy%Rhe0xC5vH3fZ@b@5w-1u95 zayrqS&@iDPoCyd zQUvi!)Ks*Ql3B5CS9M7yN*64Od*E-_qGrdbZl%=>y%PD$R3Mw+dMxHLnxl8KW{=g` z2ko5-x{zg6*{HtPgQVT12_8eP6W?fyms3~sHs_~Wp=H}1+Ir-rU)8`jZ?3ns!LAjYt#HK+3>Wu*SSY~Cx-j8Cvsw28IX)QF6cPv zr(fs;_mwYD5IOBnX1tvQotn-^=e`0r5@#X~{^d?H@D(YVc-e2!2SYA$Yxef*)EfN4 z+NY&u;<>PW0rSkUk!9ohD7Q}FkAdHuE>+wWPc9N~qO=+~D~$~YMRn_b z(GP@uE|uSkK6GA=jmx*pOFvrY(7X*|5aT@mhf;yp`_B%gjRr*mFT!M_1y?E+P^0(5 zq)4yCQ#suHa_h=%r|i`kCR_M30aY>#L!8`$>`58apEcqM5o1GZLbYzD%m z0PUX*ur?_hsysXNO1{hncKoksM@}vx({FdTI!Nr!zwE zdM(JZCpDG4Em}%(wfDxdg0VZ--Qx>eZEp0cW&9c&?8%h16rL)mHp2x-MP!$<1KC)q z(e0Cas~djM0w|S?i{rhiux?#mh~ha-&*+O~aR2)9<&aro*X(S1ryLY5%H!+0Zj|tv zy>Z{pnfcpH1{CR0@|>i9L}a%9fq%BR9UO_}xD7mdE^LAniLH$F6hUH}m!H5(2x#!^ zrrb+IudNvGhWq7Co}|L!rf4a5`j7hC_;qI7+=`8O8i|4+O0#Zg3r9}e=uVpEl?2x_ zE(SqN2iITS&lCJ=tjaQy%LKgA7BjT<Z@c7aMjJvYAYoDf?}g;qW+npVmfWXNXKd1*cLWbv1ey$IKwsD zeBgLj43eCY{w9(>q08!_V%YqU`gct?qdg>Nr&RLa4Q)~WyL-KV(u6c+Go3kce)_au zdx!KVdnBfGLv%*^`%>Q{E^P9V_?^u>pMP`^|D#RL^{Jo}Z%4cGu>UUdK_W-<-%z2i zkWOGB|EbY@g(p%ksa1EcWbSVA>F}8)uZ9fQ|BPADrF^ZNgB>SKdg}YS(LPlC$yZ^l z9%nd}>t2i#%G^q+e;WbV}`H2;O>QCqa1Iro59>foEmxlkjqQ*2Q?t>-DK z1I{@28A(-WUcWf|i$d3H=RYS0@}bt9oQI}f{g6|5M?KX%D=WvkrxT?v`=Vxkh+9wj zcIdmkMmmR#HRV5|_`!dU;!EO5838|wL~IIUVPwj_H2_z);?>@Hy1x(*eand#_Bp;f> zC0Knp;Y`Hu1a0p61?&rxs>@mo!y!6)X0dEwkK|L>^mBxxJ^egVfub-ZiRN0)XgFLp$NpP@(g<|W20cMi2v85Lh)Es zhF~&|3DE)GyjOOa6xDZb#*BJjilHfrNwwD+l)(Jm-ywp8PWQ^-=`@K(nf5}!WJ|N0 z^d6}^-3jlqh~d~kt;*zLN>TYNiNw%L1<4+EO7rLFkrli zReN^Q%vE(q?b|FVZCuc#ZQPZvwctlRXYn?_IWD`x)nX)h&BniM1xr^ct0(}6 z&N#d^7aJF{FsaI83;a$ifn-=uR|J;A_r%TMX)2R%G&WKhGhNrER-D61zy)60fF;34@px=J6acC}w(Vn0a3=5SYo;r)b{$#?7uBE)DXO z2eu0^3p)CTD?=wd?v+w=S6Jv+duPy&w<^Tsl@BS^>?aFT=lumuuVnR*AOp2b>Vwgq zLMt_)E4Cf4wXDYQqe?Tn1r3{CDbFTF=;Iu@VKt*}vPcG!MzV2XN>sYUX(zp-Gq^YTk_Fk)wd{PAU>;ZJc$ItGdlR|ow;wf@!gq22D6Vp9Gwl@u%QGj|mF#IV@ ziVY6yfs7-9VJnhUwnyZFJqa!Hr;xF234!NKRiAD6YGqKH6MWYJjCTwQ1)1Cp?Y{?| zJ=x!|H4i8L`4u9xX+t#)Tc;%1P1fgVt8ixMhr3cvmk)AYPljVi=c-O|D^V5i*aK0< zRGzEITYUqyZDuY27>M8Sc33L4VlNIZUoX<1xexN;W~~RZDQ0X#fZnMaT)yc7?#A4- zd(oEG%x$>D&qH?&FVxZbrW})J`xeZ541Kj6TNkhWwJXnaedygYn`H>PkRhbxe-sS- zV~lX)FA7oTrXy0nqn7?J%EU^0*#FAb)+N4)`iATjHFs*eOjlh;%_ajcQyQ92%0K~f zCy~vFS58wq@^$y0SnSJ3ciyc--^TLbX&B7So-I5uP629&EhqN+gotU@!v|grY?RmX z7dCGw^fIr0I`T_(ov09+R<|4Fy@csFtyb&>G5#&jQk#P_I-u-J>tSspFQra zmY8Yde!TjN(n5EebUPO_sdX9bo%YCaQ+7udY!`H;BP5V|eP+Mtd*t^WPPrX(;;soh z7Hw>GC|@Y}*8QFRbX`^C6t<*0mX78{MH$|8-SRbQFFj3D@UzcX=sVG;;H0Zsg2Hba zZYlz;o$H^=e)N4WVwSc&JDxi1hzV?i@`H0Q4BE_yQi3As2zrdeADFY7A40cV*!CBx z32g5+y}XHejO945zH^N_)_v7MC6&TmxaFD;gs=SpSz&UlUOv*h!g^#gT{R}5b0yUs z`|ZK6@HCqoq&KjF`f>6Wt4d`ZM;e|JBy5IAn&d~qRk?fKYJ1EQo4%gBAWum36m%*| z@Fur0@Rki0O}HWST_&XJAHSP>7)vrl%g)WP zOJ0<>*_|$U^;5#{wkIH)ymZ=A@TQwy?P0bDB(*~i5IDHFiJSxmBmdd#_&<&RYYLeE zGs@OLI6aa#PDc$6dh2~X@fkQnPyeC}rwH7)P1F5qxpfS-9+6mMY##!4 zg4F89A7i9jMKw859nKQbbC>?21R%hm4&uG~jl;Lnc;!qI!+iU^nm!o~@|!nS?F+x> zA2?tIzdD+e-5+Pxg7bd2fJ8pRJc^$UO$iP>v0HTtPZZXrDkyn*PyL=OI*~!sxHPEElQ$a`R&{-H!(qR@tF;?RL z_ziLD?`jpu2kHfOB^xXZx;Dxr#n0+br=m%q#k%+s#@IIOp8jd6DJwP;gS5dzlL;Vp zC5_1ngYjxCs1|2Yr0TAn6G#(4nU|lC?GBgy;QhLxJ-=8NGuuqKzWpmpBA;b**p{!w z3PBYwYe^Rap3VlHU?oy;YXnqjk|T~lEO^E^G;=(pwD{=02xToh2AH=#PgV~dCtRGA zL$;btknL~5SEf9O7ku}JJW6fy)>C9N9g|k{Z%hW0wO`~&=j10Pw;gwl^R-sl)irjO zaT|yjF~lvs@x_XzdvOvHpV9w3K6O$Gk&As zx#ZwK&L;Y12r5SJr|n0LZe+%|mxuj-der}K&i}u$JpA)=@vnCL-vIi{5d4`70A}%2Rq#Gv3~VK22E{3Tx)-*4*Q4UfUtr6~Re2;5^Wk?0 z54=LD#QwD@L-rN1hVfurq9{9M2T)dpkA5JPrQdV$R8K~cb*V+S$k`{&ecnXIosnPi z;*=aM%!PBG_m%;3Te#+-@v?0bSg6-Nh77q<^t_XePnzJTT; z=K0HCpqOK96^C^rF*nkl)3MglXht#={mPVanpDx#Q6~D-1&tz2m12nEG3?G7ov2@LmZze&4wkm0^zxDr3l;FnXnft7~d)&xY~6ZOj-U={x3O_DEObJr0Dw;ZKiOtHO6kfWYji-0{hpy$;# z>eCUAT84O`M`=!GAkae_$`2*-eucjIMvD9K&(_Ck@%(cQE!xtYAIN9-#eY`e``?ZK z3nTLXXKmyEiT(c?*Z%JffAdhEA-Gjh%#(w_Lu|9EV>`dwHU7YB>PlA}Oc}y{9RQqm zqF&p-s)Cpi)P}JSWkL@Q zDoblA{bFoi3oE8nR*@Yf%WB7D z#YLl&t-mOn8h^A*7=SlEf9Cj~Iq){e%hz0zY`tvFson>F4wIxqq2iG#hQH6MBnWe` zEop<%#|$K2jG}`h>feri{6O-2vWcmdZwIV#P&?PT5q$mxA?xQoDq1|LKU{Et4LdmB zB=7kGJoXKWVDFSHT?xF1F#)-#Yor$GG!*j4{Vc6~Q#s$FYcwZEsaLBYn=wFtheXUJav zu3Idp1&ibMR%ZaUn<~o7?|z0wln!N@X{vArC$kNo*j9WzdLh-Dn?0*uo^&tYb+#(+ z^#WYqbn#E7V;aC8Vrl2pwpK~*MF1e##8p+%Pw)N7U*KBVT}pE45Dn!0i()%sKhkP2 zE7pt_d-(;!Pfu7&aq_7V@)t#G=KBdOk9XDSO7ZAw($_!?-ync1$6XfIfkYY6$|J!} zXPq;?85^WKBv-}h-B*op9K*P=e1yVQ8VO(nx@3?TI=F;_DWUPlemO73alLt}_Wea< zQ#x*$Dk=&fGXaT!z$XfXgs?@3NZ1KckX>a5 z0RctX!oEXD!n@#i=Ba0V@64QczBAuD{*{~Vy48K_R@d$B`gN6Ztu$+WqPV_>WpTcc zG*&oCvr6ze$=B-?SNIE%f899?EPQ*aKy-YV%jM4W zlJYp++ec((a-a94jj2qi9&Om8G#2(Ao_)bdDeQK)=UeNb_+Nlr zZ~H&oIL>vg81yKtH?KN<{6e)VeY~4Ds~`45g_CT;&+6$7*qGw|VeR-%HMAh_3D=>P z$-5M#6{NH0xdE3;t9?IfW${pALe$!zzscIPpPW)ime#vSjaAu=^&RoEhuqkuv`2M) zy`$HoZKBwR#@uG!#CxzPH$Y>#r*}{du>m?ZLVPFukVkktuqh*<_Vn>e`#5c$sE~oH z>C89HxMt^%E*_>`!2YyeWT`?X*02OrLGoG0G3~3|n$OLeN4xOnrK(duJmeqq4jy(| zV41#$flcp7{?)PncXn`nZJ__I|Gz}^l5NP4Rlrt=*%!0?B-jy4o#E`GLn!pLN2iD) z*d$pcP5(+~-V>YsN8{9$riEBCof_bZ$^)HA;20bRdPZJaTk$2lz9DLw`{ltXKHW6m zYu>geUUdYUmxQAtM|OINgxnr)nf1%X9_&S)y{pKlDs|i`!|AAW`b-q7t&-rb>TmX= zTnBxCzun>K(-fYE!Z+`~a?P83{PNVns65puyQG@S`Vwy!MMYE3z0VnLV=d`<)S*{3 z0${#Rti}&1{pRA;A{5v+PIv?yJ=XTUcQ-szuG+yYMMY(z#<*P1TE2STSyk?#@Pj2O zTXa#MY_4nM-I#c{=RY-!k`FtY81?Kjmw;fbfLIIf&^p72su6WnnNh4@yG|=%TI6Yn zP90*1)J`T_lqd0?%BxAy&z^T151%N`u2pw|YMT29ADpx)EG+6A zNicgg@aQSbhuv5N^)23s ze~g-YKb9I^>)o5tA$nLstFnahBwrrwZopa5l`URh^)r}jJIAVLpTK22vO77dYhT|3 zs%+|@sNHXP>YgdL<8u*2g4~15I)|b&x@jlwtI}dd-1+WSkEnChD%YSWri?q`{R*Uj z0KdnRf}8kt0e@|Mc5{gM099ET&cExnTS7$;Y~q~3SJ1cDH> zySWqSw%(aW>o-^5M0)!`66B6r46TK}y>moV_2xNIXR80+awF1hJ^iG{#@lkPZf!=2 zPs^VcoO)(^ri6Yv+Nn(N{=HXryAv3;&wa8Q4xYX7V7TJo34tpoUbiz1|;*XU%2FU(Lja^7I%B?R8;2n&}eQ&=fTU7I<&c< za7u=G?xeNAYx%q5&+9x}SW>Fd-PU=1**dVOz4Yh6)1=%uYhif)(fv>V zaj!lf*a@sleikr9LOL0}0aEM8YoDO@x<{Ko6cd|~TDbBVvLswq9$|Th6X%^5NlGyK|bOepdj;lp$QVzF0-kp(&xPl4#qen2_e<+V-ga zT5_D&_?`Jx$d3DC(RHw%AEYqMNIRk4x&m{g|F%FK)Va zUHz(ewa6a-Ia6qHVd(A{Ueooa`*FvDh_gU$<7So3a0Qw<`mQ~<`Ybvorz)GBvihHM zc@M+Xq({3!L%7)a5yvEzJn>kidyS2+b>#eu)D6g%5g6I96w|_{orcu2`d;p%@@11w zf$gPJGli&&u&Q)2~&|WEuf6K&S>4>NS^$I@ns8oaN zD{kib$1kp*c3!EscWZMi^{il|_$gjdd+?tBS5)ljGgEOcF%>9f4T7Qo*y4zf_=-c; zoWZZ4XWc%s=?g@MgtgWi2(kaHaV7ruv74516pvVC;7 z@I4BSz-gdw?KMe%0{B?vtn5>(-xU?*-y&{`PhUSr>u13rsKj+zR>m<^X@i0$)?f#G z*$-XLz<{DLag%@t%6ADIl!BaQ<3q&0yaUHQmaWlzas>_7?ips!&?Py)bNDWYznwmO z=^Q~ceA4a(?61MQy9)>RKKCY?`^^$_YF~|BEU}sPjIis ztkK=TN$|0f2_TZidyCa_b|`dB9tg&D0FgG^uGJ9;eGep|LJUqWsQ2lRs7Przmsff; zu3Jg`M!cGMfRNH5>N(5%@7fCb6>b4OS-(5I-_YVn`_Va&8N+Rrtp`?U7qokiu~){Npvm~SiD#8A*H@k`_KW4 z3PJdjGr>nGks7{~XH{0B({zeiIn4gV0rNZ$b6G|JvBtzti) zKR>Fm^n+PB8%S5c2kf}zGg_Bv%TUW)*co?=b>uoE7vcg0O<&6CFgzg3BD1hv*e$9~ zXGxxf;BI!^gf`$7e#3Gu1n+2qZjlnE(38Q1mVmaTe!-B#t9gsmaf_`fptPt>N=ncs zR}!GI1zRm^Y%(e$)PelQ)jV{0HhHVL4;V><4a0ltPWz9ol$ zN4Wq2cpaK8KsO@3)!f&w!`o{$Q>VDRBR6llYd~MoWR%}?{!I36+5qGfLgh7=iV&z9 zPkMvU&KfW3e!^uwZEInuTn&1*?~(5a2GoP6DQjDrDsV8=V8I@-o|+>eP#sC~>%A(O zHikRLh6QE|!5l04fB193hnGA+B)b{?<#T8gKBG68Mn(sktF%I zF`R5rJ}l4x#$h*wks0!rm^HxS zJtPPP3&g32w4dUGYcmQqKnCb}fPQypxp@T&S>4&SXjYFidM5N4!wt~yj{$H@!Pyaa z6WXx93+ci-YCRRp+%~aG=HoNMVX0EFOzY(Q-9%~%t=xz#{!A&Y$>!J9=DgI_%M%d%v08wzN!b9kfbn4)2u;SV{1w~Z+XIO}* z<<&?C?!MV*wRaamHpo!`+fpX8&>Y~Obi;1ql5B7|9GQ|@qZi^2sN$H3z}m<~RijXe zs1`w}Ru;MW;&D-4P;5mKpi*f!%|;VA&b2RNb>%))`oPEam|BtH*cN}8g$YNAn2Rl{ zyMVg$j^ySd5tCc%9am+8BLM#Ds>WH~-AS9b0aZ9IRby8b{Cm4aaSU@c1f8zU2DUw) z-X4cl)%ACnJ^z?$>BaBgdLw_uM_@LfU9!Y{{WWG)(@TX|r?5p)Wjx)HC#W%juLRSj z(&weZvE`2BaHX&gBW^HIK8>&3S0mTD#g1ZDWu;9-v^|^8{J^#Za!iqcM*0@bYD$DM zLGr+LFW9X1AovhxT@O%L8{GkvD45k$=biw@>n@q0DoF%o2bMBMj%2iji{9UXEf^z5 z&DETx%7kMJvdB>|c$YR)7l5FL0Ap)Y6vdL{W;~(oUMRqOOi^HM?)+vy#?%GYCX#%B zv6u!n8>JrIdU%SEDdt<&F+n$=)iB?&& mT5pPbB+7mfHfzlly7~T|S<;wj?F|qD0JAZEki?-jdj1QzSiMmI literal 0 HcmV?d00001 diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/Clone.png b/Firmware_1.26b/Documentation/How To Contribute Pictures/Clone.png new file mode 100644 index 0000000000000000000000000000000000000000..1a619480026af4e20ec6ea8237a430c40dc110cb GIT binary patch literal 37021 zcmdSAc{tQ<|1dlVMQ9;KsJp9DvXq^yg^FxhnqdqT$-c~xZIEkHskB)ldv-H~u?%C- zB3TAwW^7~442Dt0l4W?m({j2x_c@;9ad3Ri%z1v!^Rut>*xJ%eL`X^q z1Oka%y>i(W1mf!ifp~Lw3jpu%<=FoK9z4OeX2u{)_t9D4#jd+X*Ns4+4~fECZv4RO zJpot1!61<6NA4d_n}5+A5a`8)tCx-J?z=3|qI<-tQH$$aZ_&6=O?#(W3U-r-cbXr1 zvFp#c$3Dv+FPu+)+}wJ=_~Fg{m#e0)C(p_0yn;kRSr!8^qoj9g) z?&iaS-Y4JE%6m9!{%K}irF1Ymvk9ikjFt|5R)4$OnT=AuuH1m^tlLBHHXu;-cSJnC zRS$PME^e_ahjnwR_tKUc*J8~&I}OtBZU=112`&yl@uEibmt8B552djk=_IO)T%*6L zIqU_NXR=6D&2Ns}oUiX4%i8#8l|J0G$_UY>fddI4_6lQp9(LiJG@U8YhE5iy4pyZg ze#^-|htbD8`EQ{hyU?Uk?U9ClCN~|(M^ibJ5(wm}!M#h*8VIt|IATCa3SZR&w<3Go z5k%LYS3SBL2~W2X)H7Sx->#A?HxZEaSZ#Pcjr?t`=tz$ z{692c;(WCo3?3eBRObi|wv>c9g zDN&2wi8xTU0x2BTQJCw?Xi^OCVoRD*nOJ6m8d^6EL-B=|M~@Q4GWt8sYsS7dy^V@N~iYb z&RmU0a&o*=0o$iyeM{23-khP47W(7c!1DDkjNN-w{GZM{*={8MenlNsiNa zvoKO0XR&FqWs+ECqPV3|wmng3APsfsKq^4iNX&_MVZxoi9tV~`SiZO}p-5<0RBSqg zw}etw!nddkOQaw&v!}8@#c+EH%aXqgyS-T2HWNl-bZV9^JF`~S^TQ|$;Niv{7o7Xg zX{W_U#+7uZa+}4B9p}F+3m!r{nhL#1A#9K3Y-&K%1wHtALk%|urAum$S^k=T_IXp` z1&XEm&i2@D?Dx4Kd6m-P59xA_tY+NXBz2gO$aei$R;A!irGa(9A2>8Qc2LaMCe+7& zpQdCg`PSB54XyVnZ|UBB*Kc$>5<(pNbBmILXs~jtI-7NPG&3!Zs;fes;ArdNksVrXtM%LWzd^{?x$6oc-k8 zRP9@RO9itWUbJS)E?+yRW|fr{lpxY9oRCLrpeDOW(%hrma+EDcRxs5{MJ7XpvZX~* znb38oaw=AZsduGZGA()szq}Jd>e*uAgH!%8OyTu7b(MJDAO+*#uGm3?UvROryGt1W{14)!TaZ{%B=vRXO|r^r;-~6^QUvdC}Tn&ATC0&zX^bwH{Ihn zE{1aEKUw>{D1Gg_a`fkss4>3YU zfHmq51j#-W3f+EP3~OI_g|46*G!5pvma;9$lXHR^27k)m_f+#jnT0l#9$AfY2z5d= zY2Bg8#QXcJeDFv%PD@T`D62rWQ5PR~6T8x^6o>1DW!0#FuFh0$lP@a#h{xG@tEfR2 ztuD1(g$aEBH}VpS<=X7r;C8GFj+qXgU9m3bFxf2S8kJ4nBVTZ#L?WX?k_6>ITn(m4R^u={>Wi=+>Ym_ zAZ^2GT3zlq6w+&=yZcASY7_$7Dse-mlxf==<8TeLLMITuJ8XW=FG3 zzqiU+J%T{CZS7>4(xA{ExI_p?e_b%i4SOV?H4yBpV#_Rw#>*Km>$d5f2J@XV;nU)* z;{ii|KR_9AX1gllT3pnu`5WEs`OM_%BQI z^}`Tl=#_4v&JDm6@V&dYp_4VZAUU#;cMay}fhs_+jquaUd`F`>z23EpKhdFE;N{Fs zzM6l>QFhQ+a6aF4GFH<JRhSdV8Z+CHSo$M{yZ{ zg-3IXCAuo5@a#q7zzvO1Jmlz}j{YkSg#z@zgZh$KufB!Q?+O12)TZq(0SB;Ba$*DF z8Ghz4E1Lz3<=)PX%B#?N!Z=4(O+CoOwcxMtYN=%6Kijys!#nTt_&Y3oA|xLB_P?St z-oG~iTZ;_$r~aktTsUW~3AbmX|Bkf8P1Yr@^@^LUSl+uN2DSPR+DKqaN!#Dow0R~0 zfDiw#*pqzo|H=jS@w@26bY;CCzEw*R#B>Jb%gVq)&L+0RBV8~H*%_&E-)Ylp?$ydF zBKp+ECMme-_MuwD5oZ^y^U-nMUj+U9&AK!bqaxZL33?Fp zH=Eanw(@z%rGN9F=!@5PKK7e@kLho1op+6EX-$>q)GT+>7vFCBRYZ?fd^)$2ev+>2 zpzoh~qX)a@)O7zbcbe~X_~>3*@!tooe@k9EFisYXRj zm2%GW`e54w*A_ULo81@K`F~vA-hSsl4AL8pgw#S+hc9~a&3Ae)|6+7iX~fKJSPf-2 zMNXgi85IOcT}e$!q`7}FP4QP{uSP&RbuP2p$thk%*}PA+n-2 zq(g?X)KydT{9$9h^w+CDv$m!LJ8u&?`1**xo9x+$j*sYX{PbV`6FJAoNI0Q9b#wa*s-v;lM~;p9zVyEB73E&J zn%wOAV+h(YtvHYI_H!?Rwef+jBl)L)1*vjky~Ti_xMyK7R(r#C0vUZIiC*ioog0(+ z;b~Em;@?@Gx&sijoQ6B$yznr)T8tV|kMrz3zoxy$?i8GOqNZvPZ=Wib3t5SloB~&>%i>XOtVM7-9Q@Sc66}1oTw?Z&C_(%HDudGIP*%zK}&?~-!`P=gO|KYLv&Ti(8BbJMDSQ`mS%?>t|Ri4 z)G||*PO4Q_T|4u`GGgdrg9S95j0%4Yrgxvm97rYGLl_#-+hVVVUw;$n90PmlFVZx( zQU~cR3`%+%Yb$avDtCQ7lUcG5`nH?(3L3t}=*qBaBfb>vG-o|E>+D{91(i+Bqb@C9 zV2@wm57`MXf&Ifkk-yfel)j4nFlmINq)#W%v_D3BeY|r~g%S-}PZg=d@_V3qiW3Ma z7DWA3|H+;VnN$Ps0;OJdByr0GoQmH2KI`35D)`mjjg^r#O4=sDr#z8v7WV>eMOQzv z*CKH}uc0$;?0I=KD`HGlY&0AS=iFs+Hh<|Xu584Dp*1P9t0&p>(?99B2!gMJ>00z? zne*zSddsyB_D53N(u)((r=GP0w9>3%dt3t`B;hVA>p zI-=M~bCCha_smI=(ji;-aSJ&fQW7!O+m@257qR9}!L97}|EMk%8>2 ziS1;0I$a|@TA4a+DWreO?jJ_X)2*OL6a)9fXr3$mpF3TY)HDwy+y9T%N=1uXj71Ic z|Mme;1HcMhkIOAumHdbP<9LH-Hmu3PF!IRCW@o$ca>bR2=7-~)C)miWURt8xo)OBF zdPJ9BRWwyVRWm@^1ofYc(ZuE%;1CBHV{HUIcvOY#n6JPBM_5qf?MX3Zjf6~^-*edk zsiyK$H-7qO5B9`^BRUS#+B($^ENpq?Og2~&>f-Jqb1t<7uW*)SW`p?$WSfK1t@FKc4QeVWREOaHrZ>E?Z@-=S?+Qn_v)DwIEKfLV$Ea5|rDM=k$6DN(C#tEmLg z^;CO>_$hx4rl{E4oZG{B<6%=Dhr6yuY_|Kdzwrh4=Qp^nUOpaH01j&&y#Vhivyk;a z?dgIHiG7Q1lXEByN;*Vua7ZPuZjC8A! zx`_Mf3a^jUpA75g-1Sd5P!+bW1a`cK~&AGWeVm#ua>0r8NInbIh5&gP^0=6;7*27TQF)h@qAB z^o8)@KH^V0{1cqQ7PhQv*yTqK>v)SU-1L^sn9$QWq0-hdc_j#0<&_x*eoYDv>*&;@ z7PY76y2FFwMf$~<3Gr2QavOfQIP+b%lfrCH$Ov ztuz>lR#EmR5$#VN4+^;Z!MhS>bL^R4`aRiaxO3D4sinkHoVS6_l!t1>^~kV*_*TS) z47(JcXX6Xq3J%v31WXlD^~_1JVdz1B*jCSkh>c{>n)5WYGJbxm5ceU16apO*Uj0(U ztcjK;AN(J&QMQm%4I-0D@&Iu&~v{eDGo{VEJSxI#YL={Fr*#DI%`Tgnd1{DK8N+kxUxdu z_($HqF?j4Y>bCAwa9zq5gIWoN)YpJKOD}Lb_}E<@gQHdL(ABpmSC?|1t%f~$UDa{R zY^$!bdA`ZewW2)ppYBNf0)wUooI}uXs7C-)RSH> zYjzfF)_(Rx6=9VBp`N?w4vvC?^rDE`?!eKXcSd~E=i2|_5dhK@$^N(X9#7_e{vTdI zxD8a(K_EkZUe(|K@a*#V{p8&Z6y$-QUHejbxX<0kRQR~heTJ^w8a?P(O!Hpu(-0JU zg!_yE{jUJ%3Dn;hNKHst*a1M9?gK#f1U?sYxv=>>OHKo4or|eVoYEk0)a&2>ql^duoI)<%zdEJOBSsN2mX7s|358Pcm=gbHpWjUgB$M5XjevOX(RyLeqWnye_h- zOaK|BT`vLZ5#_QdMs%6-*4*Zbe#EvHP>TPmY+&KX531(lawD6szPSuDaF&B+f;R0==(vDx5sat*CKrbL@DMRfL7GR z5_v2wi*RG^$wF(@gDO9+%=H262~TVN@w3I;M$2KHRzdEY#~2`3mFqK8-?_rr3@~#B zEYyOrUuT@|Hal^9Gv{XXrW<69{9Cw>1D{@<3t4zjady#pdO1qjrJ$HAv%qvlpgdc=o#ekOlw}KrHK#X}cvP{m4ma&NbNHdw6P0=yrDKSzkH-j5AU7 z0Hpv(8;^wBy{@yPZwbvv&OKbH;pt5=(Gi)TN|u|Ztd#pX1^`%bsqtm;;X)`;U;{NQ zV63MwGAsP9Lkwj2w0UoKdEFs3i9EMFxoOlbD*FKmAoe3J12SNZn&KH9dzMdVHm5Kj zE(9~w;{hUO%W;)q=AhIbm)M(pk*FdvxRz;t5|C~{II{igVi)1t+w}>Kd91;?hiC_e zD(e0ZWm-4!8V_h6SHF5rj}Whsfi@ji>kY?xTwVO$_;BEFaIQ=p?733unuce=TRgw7 z08ruo-B`Ssot#eW5=_y5f()AJukWy#Wjums2qf?V!tM@WZFpp7EsT?OL?{VKaLiLs zxXFh%W>(ekt(|=To$Ww`~JvwUb52Q zS&%2!l`QY43TYhpyxw_u55^4jzz5qryjLjHPuv&fqt?Apz9g^=bQTknwL#UqfW_MQ zQ~G^Trfum+uc~C1ayQZwXN~LeLl|q(!LShpk1E7+w+uUP5+XXEv$cE zT0GGp(OI#3ZVs~)(NPh}Qw{a?&xp4Z4N(G+JxKvr#LNp@M(O^La{gDHIznu&J|MxIbypK@`hvhPP8))Wt&Zj;tYG8!7d?$_-}Q+ z=C#+E31Hn@3(V=?$^D3OU(?5p9{M<8de;F&l{5@@p)Tk!g>&RPhc^}O@PTlG0Exoi zF>@i_84W7p86V612K=+?fhr^dFWfnoyD;Wpj<9vLeiUfbCf22NPGLNt8xi`5_g)`v zzRtDOPyyq;8~{mWn~qV~`Q_|--gId>k=S2I_E z7+La_o84zo?viipb%^yZE6V0RRgA}bNVwH+)*WL8qg(u-WO1%{QPZ-6X>c3DNlUHFO z9L%^;MBX6pUdw-MTxoDDb#(34BA@i1q?|#$!cAinrnQbU(_hmUrV9B4Km|gg7}=b- z`_yZcC$=4x(Xv$~ql`T4A#`?jiPsyP%iXB+ligPx?pxkC*1c)`8TAuR^^;8H#E61s zEV$&_uOlDYQfY;mIfKl}MI1rrt~9(fs$Q;xhtBTf zJbgo%Fy+M<*JpkdTjrkoTVD4gwd_liMVC12GbVyF+nhN?{_o+&l?wa_NJ{Tnp*#q2 zF24kP3gk_2_EY}VY?_%Q zLk-!$iNQ|s7>065nH9{qt5Mn?L@Nu{i-maNJG?)TQ!e@GIfi5h_ zC>gKIl(R?1z{4@=iC&7mpqOrMxN@22Rvon3TSU^Z>dgBRgky`=CzKmMgqn6#sLTuP zK-`UWD7=I?BpCxOt(3Mprq+`|w_+EsgFtXW!0cvULEl=b(NZXrzjFsAkxd>U>Z7`+ z9935RNjjN`vGDqP>*(R|rZUq05e~FY00h_PRgF1@6)!n?Sun&aqjwB`d|pn7pi>u$ z_7#$Zh}ms8QD;MpFX*6{$8(~RDA&!HMHI*Aog~rvXF=%pm3e8XcdbDpaCZ||fqn0- z-^b|?eknph8P{^uH*yy*N6O-N+@Ehd7*b+fFoGry3ITe{k!i`@2^fUjtNES2b7Jd}mB8j00e6tO-qw_3JvHN`B*DG+wKL_rgjtqU0ZT|m0PXSL>puYOb= zFFMZ|gWGfCnl_yQhuKPlO6)epzm1pEjg|M7o_nMGx*F;&O^zh@9S{M{?Bz=LF=R)R zD8^fxXd7#o7(4;qxsbhYBcn#fS1e;+n#2oQSa+9Js1&H@x4!~;?GG00_tN%L`%yAI zm{D5n;FX<4mP*6oXU$LhMx4zMI6tDC(La1C?&;(1x0J{kZ4iit0_6LIh2Roq6ERx< z43{N3De))b7=~~Os*A{Ani8)x&V(X8MNzH<$M`0npyB7&ChA97BpgB3@tsGdZ1682cs9f>TF;JOq=gs6g{)~ousw@v1If&=oP`#YYwfcl zel0!IxCb?|H;9jhdf9*QfQfng8xT)+xdBX(1Z<}1BhewKrjLy0Cj1Ah)^;|=2~EUh z8CPEuoYG098sWD^14&n`$%rt#{6Mg(aJ-UGZP%$29 zxgWmom`vm*O{-L>;5~;$CEhsTG*~e6nc@RU@|rSKU>& zV722FK_*D)8s6Uh3vW=37F|nF1Q{}Zlc$HLMzn@zRA1LZfRB&P$N7iG5RLS#Er+uq z53#iRea>j{SL7roSU_*?UJ(8nz!l#DJ|7u)Au$6E)ny~M3v7h=(=^bXh8n)5}p3Llj5`YOy8`Ym4s8yKNRbJie?kA&pC zo-1@^gYV8xAdnPbDPlBinSMG)6`JRCqCpi70gUsc$pPKvOs{_W^5XVfxX5zB+6J1G zKPF4x0=CTkzC{q@>?Y6Yev<|uNuXIVpYK$emMnvU^wEyn94F3aAW_Bt$wgaSCsE6b zzjM#UuJ;T-1l3GYBWd(tBz{k$orcYVPRn$yMu z`pz}J(z75e6y1JLM}@-PG`NfE&N((^{Ito=#xV--h!n2cwyf1E#ex%mI%Sa7uHNX# zHO3kP!n?3NBeT)kiB{fl1nL3Dq`7SP#7}uCm5+nQB^vy%?oRWP8^sEJr zWyaL$w(um1^jdxbW6$qWLiY6$?Sc~~f}gh+4f5*6uMvSD7+pK7QWj9k z6!+vPpBuR??z+5P6p4cxnI?vkR*C+WS*7!tX4AC}-a5FlLk#%+RbrHE`^rId&f0Kv zB3A4N)o4cp9ldv#0BD*UwVjgkJWb1}fx=_T_-;`v|D@Y!tq9uK=JN$#!I8mkCd_!_ z0G-_pYgYNqQ^sLMNrNe(A4`@S&sd-NLxy8Nl9nObKjY^|>)%KsKPgkbQSDNX_!9vF zUE{(Q&;f~{l0pKZh}n=qEvj+4XmPlegvClZYbrRgcR}bJLpkZeBX1FXan#T+XIn?? z@~+)jtwJZk75>M<)bK?Tn-R?1?N%K63s&t3{o#}xg>zvRH~5c+^MW`J0RdFZ{*m+I zeVnySB#!b4o_$Y}|CC-d_R!Tg!ERLkJ@)9h8cx;NT;x1omFBvx%oVKVdpNP3X? zz^1|Jr<#G()*fsyI(VC?o%rvZ#M3?-(7D z<8+l+$S~GG1Y$JbY%CTE9}g2xRiMQ6OCCuR#2)g_@LZErnDJFQ)}ZWKo!IA&_6NnN z0OF_i*4UC_R3vH(m2?iRm`mw4vp0VakxeJ-QDpuIwtjcr&9S41!lFDM^L ziV#$?3lYTFi+Cz<#4LNE#^prHaFF5Ft+mP4zo&1MDKzkLdl|6I;Xb&249~6OaN4L88CCFNU@%Z2Euk?{70zI zoS^bR9l&oyC{k!JC)ubgQ8wOZ)}a;-1eDgZ;ZZpgkk=6}T~eCv099SUcYB^io#7Wn z4Zvr-E>qUgLSKZwk_8UlP^iY_ojj8z+$q$GZS;q%LRk1KuvJeEPy+qEiGR>qxPrIT z*g=o)VzCK0vD{tF7s1~xZPAG!_|RQ%;V*Ysbv(v=4P1jO0(DZZF;2D)z_=ePZ=_i8 zJE2CbK@6%u4wdrM(o zsk@55nr~N}^yR&tD6#TLpHafT#6Py5L$eYG5le)OZIzO#yHhR)P+|rb2i>hT9-ypLQTj&8(-HZah;eHh@70ah7TEqb2jfbSbBdC zq=n4%f1asqSWw?wYhRn)2J#1Py5)HSg(_<#PpGF;*D6%@?k71g}MN7_AV^Q zsX))71P+p_Uv%M5V{2L)vgYU1h4w&1(LQ=R{)Nh>id4hG-qrG`@){oBDbNPjlbObd zeub+X^2#X7AI5s4LY#Yq5uZcQLqZ1C$=^vqM9A~wkeV>q9k{AuyaP6~!4SFZh^Oi# zvgq;dE4(EuKotj{02EYD%pNnz>ESo!ly=Z8TgYN9LY`z#aGf6&U~nk3wDr0{pyCQv zfbLSD>;dV;6_iVEPk%RIr$M_@FmP&$h#%qobgu6aeA|N6o(|AaAZd91o?c;E*->?dyA(T>jxp6|E?z+_+J(-AH{5AB zM0b(#DH*O)Rtf*fv99nnty3JRC<{&&Yl>)b_N9nv*S__3qokbJ7)B61bm#q+_kpZM zxL|FsP+B~3IJ|nBfu@sNeJ}N+kqfhKbT77Mt3lZ~{6oGCjOF=hd_v1$`9oM2hAD^) zY;j&MiumXb7Y&}fJ9PM0X~b;8F-@ruWxobcT0DU1?K5>n!+D}Z_V^&{JU*-kyfCEY z`HvCj@aSr1@{^mw{AXw|*u!Nh>O!5(+(Qmg;|{CVEv!foatrI{Y4F}f)+dzKA=WY1 zby=AQ6vnj}`S6~?7hhUj*u^J5WU_WvMhQ-P8IkLx_F}%Bpe0_Wyp9l|YHv0-s|VSN zBboQW_6fI@LzwVF)BfR=UpFt%n~w77oQ;2Ia7ONY zlaJO$srkbYclf_h9)GXs<-wYIFtT<0^vb6rp&5B)EUHk46u&Ge#)X^tf<7*du9x<9+x*`3EwT=J9whf1R84)%Zb;^31Hwxbd-;Y3^qZuY=WxzML$?zPwHm`&kvo-PT>|b&$cQwaihp-G zJpaYn^%|!Z8n@OBQx|+?gjXB81Psw@#{-1*=Mwh2miHxhy%X+0Q8!0ECM2kKUigxn zS@~6Var4$Ts%B1F?MSPvz6fYWWFux(4ZE9s;0cVIckj z?Gbr6ZTbw!?2Mj#;HW1AB8@Y=lHBxBj_@&>7 zoi+lWfDtygtv|RQ1%dX80sQQ#Rnwv}uS(8`rj1NPNRiCW{O`8xb)&(q9kPIF6QDhV z0G(r+-uLE7sF9=Asgfn3EtK_!m1_M`@qLK*}nJ&@)7YoNZ08NX*pa?c|pqn zVAM-f?mm9(mlD)Xx5ZQu!iuRS|EF-?iU(NZkQ3e{uzQxIO2_3CUxxbN5)m@i_#Mi2MK2<6E`~p!D+gEEV!kfB!H(#ioI(C zP!i-Ww`x#X4(vBB1?i0VeM)=SecexkKOCrCDFFpQ{yvxlCUq?2rgg}2zLA0%NDv4J zxLU5qyd-@Yx?69v}GN-Cw8&kP216ie6qms0CCRyN;q91-I`CIp#*kT82*gY#p@LQNI7jnZ1j;fjI+; z&WKQJ2$tWrc&dPm>0e0s z?$U|p7xq@Cb&EJ8u#yrXs-NH#tF!mi{IH%4`|It67QAdmL${2H*u8TdYIsw~#bLl_ zfffMq*cT{B5c(ul@0gO8>=6N`DM7RS=(}5HEW!!o*M^G(>wAh!Qh4*V2Z(4O`e>2J6{JGB7c9(vaD86*@PY0 z()7G%p{uAiTKx{vBWo(l%2{6Ngrcfq;aKFaz#r#nH_7ty-h^xit7?jL2%*e9Ly7+$ z$j}?$j(D+zg`nH4QnHsjecb21aqRnpOvy#qbKdb`0`86g5vC~6+7qSwLG&aV_$_po1nHx@gjwsgf;}!aB9csOgJb?v=q22R%aUE|-b~3mG>3OFbVyi=t{VPyq+#zv%tJYtHwV`N$?XlR zR;D!JQf3kcTs9AY4E+JIdsG*92q=76U90Eufa8$`Z3rqo)KU7N&>tBPp%5K8DxyP_ zR`}YS_Ff`H-L|F`1L-0m-~nGB&WR~>Q;{4=$P7c9CE7>|TOQp7SF5A)B3`o5lP6X0B-$iUp?DvqAq5N){y8$W30)v$Q3cKqYq)>DxWiON=D}L{IE&3Qr54Omgnz7w8#8aal2lpwbO z=yTp_6LwA%k%n+of}L$}j>gKXn6c+jcOt^-7zZ`;)DA=R_@ZUB!p_ev$>7ijOC5Be zmvRJ)Ota*4rp*X9Sl?Fs`XsU2D_dXGVl26hBaPksuWFKw8TktIYeC?NUw!To(DRq0 zeI6=_XwKKjt0>Gzut(3>`zL(BJz}2E8P@qw(ktmB#Wpl3&u`|l%iA{}t^mwH^y~rd z+#>+ob99OC!=@7t6+2R}6S8)FyUBU(0F)w>QEk^og`E-W9Q8d*mB2Md+&_DVd4AP6 zGCex0pM9vDm{!~DT{lN$20;3z`m8L-q+4YUKaCFx9`Ht-*;nfL7_!;Fk>d9=n2)~% z_4bCkbwUwpUDGi)t1W1{R%Me)YTf(W2xp4`3P!URD$y`JrC5^^|H>Lnao3g6@cjy} zHDMgsY{7{m$zD!X^dQOvstG?S zVaIMQ2ptq|Y8kHNtr|Poc=*jiltO_drs(9b{#90^`!@QCQ)#?3Fw(T`D}Hgse`fWi zd{+W*Bl4^{As@YN9?BPL1g9ClmQ`go^dJ`W_BF8NjSAN3RrRk{e|K7~N-HwO3ytW0&W+V1OB#IC*k zuU;0(_ZL6{$xBWb#k5Mw#*fq;&Co1sMjNJS&ZHQKggR|B6>o|wh&HmquCdcJ{ga|$ zQnuNNh37{o)25{_{YKKLuNPsDyA|~BFWmwkv#gc%-Z*X6OKZaLb%!Bhd@(Y(ZSIRk+d3(nXAU@i++{N z9SfrPhBtPrt`_#r1LHY>3`BMFyC(@~_gT%>VFpV)5JXWf95SxC%)uEo0)Yh6)<5rr z&)I^7tGp4b9b%op$Ox6QVeHKpg!}h=6v+^_Ap@3tv7>&^&0%%~=Yi<@50H7tQ;G0P zwWSijRzk1k*_8GXXk`@(IGcEZF(68n(qqMG>^uZwO@MWV;!lA0HfUh}nGVP3^pT;X zfZ0Pt*T>d~KR_Tqm=>)1JMIGk9aG+?>SKC zJ%j-iG{12yUUw^tV%3=M?$~c^SStUu=wBJ-Wyy4h-M|uqYv}G-qb6L=Z#+Ol{}R6< zUy^LA>4$aI>`RK!0%~J`VE|RXLE?P02&$zwcEL+P1bbnS;U*y4AkUl=ge{elb5d|6 z{}lkd#PN-_$>|Nt%MO~pde6DB`QanKKmE$@A~J99KNAHE z=q=ymW&iLTHSsCw7mSz}Nnw|}X>Cc!0*Yo;4-KcjJruLq%QmOQ_94H3D4J-|bwpu`& zLAz7x^7UvY?C*sNQKG?ljMsdB6^}s6YMkVi=5l2-#(A-|$RLnmG~i{qNdNDdPXz$~ zuMN2V?+0+gBcOv<)ob~tDt#iO;Ds||9;Q!unnob+J(bch*b|HOScNKdmd;9QJ6{s) znrooHb#F+!IFU2u!S2)cXpHhVW$9^oYY-PRfF4Fq1|Z5Y`=@x>MZE_*UqLUmV?VeE zb;b=JNFy%WpaAn!{^%a8XtQ7CBqK z_f7z!?E0On04GiX)6-oe>l)eDUEEghPn4zb2BTWg9;}%U9;{@#0L|lZGG|7@BRVMT z_gL+TL_mxWpAU3(an+C;_Dy~&?Okv&qNlFYd4FpB^YoNt)kd z&{A?kWAWy#g28)j6Y#G`X-n_x7dG~+*6g7Vfq`#(2u^OM7|-voistYJqoX>D9tU^6 zQfy0Li|ZkWg{oZV-h0ZLUVrCzsBF+Nt*zCl%5P%1PJumh)#FE$?TUAD|;m8 zRQ7%2EGdL^v(`86E!w?e%T?vR7z^t3?qPB-?xP<|conhUvDj`X`SXwWrfi9n^wsfE z5s%)o^v=Uj1J`#pzeV*CO>++)S)$QrzI@JiZ}_MfsqMX5b~U*nV|!#} zxQpuzUAbempc7xj>`^iazK7HO9ORz+D~NUSX?z`gp^JDN=C&B9suj@F_~RFRb70nE znx`B*bWqSkx;14{AyY1@Pd_X3#GKc~`=1*3T@OZUzn6a96FPMV_5B3>d-MLPu;R=q zkE(NFqHDj*G+C-l2ZJ3i*&857rm zuY8QmKQpt)v3|rGwp~qA`;vA(0t#_gB&BH3?UfXSo8p^}` z+0&)e+!v6F+J&$Xlj4NByI;GBrRLaq@uCH0g%ztHVz_F!D<`&!K7+BRYe@UFbtb}K zU9n*!7VIKuP56$3_h904#&uEj<1wO{rmWg&!NhdOtc-*4!CWfs`c0*Ri*{!MhW4p@ zzt;9rPU5HYmHOOIb4{LK`S^2xRd^+y2rx3+B7raX%!@PC=<4H(U)0TBbxeg zlHmN9lFDYS*n)=nJmR*GCn8a<3Jx1&e`ahB1!#X4q%Ucojn2UROGc&i`tbEB`lO`L z%gWhz>dM6?Arq^UlDi5jNay+%hP#vb={-wJ^_2BG^ND6@#wd_CmGqs-8^$&BvsGFm68p1UrYF&H3gB~ zDEp(o9`glhlB2k9#-H{SldrM|d`E}gJz+5RZkEYzn&CVaI6$*~K zldjU$t$!}eDiH2M0#y2yZQtBmXGDjDG(cH`5&60k4 zPvdr_ZoPY^Cc&P!YEY8qvh8w8Z})Gr12nZjPg7lY+c}Pag?x}VD<|%i;GHkV4`#re zbr{;{3o2r7ImEelquL(RO1dJ_e+VWnXfQKrM-0pk=(kzCyX(M`Q9%I>mf%j|_5r(m zw$Bv%shDrr1%0BHP`}1a%%JNkb8EUaCM>MD)z888IUoI*d2M=L{MuX2>c-Z+yXQ*n zemqAueajFm%l3hNq)(?$HsgKK;7~(`vSeqwjFl<0*IT$#I z9PnG%tXls84qh^hj97>b`#KLU2~I1FU?dXHYaZb8nA`0+e14+YM`rkr-;L&_kG97} zZER9*Nsp?vuFyY%GoAonEALmVSF>GCWinDtq!Zs@RsNs$-aH=4_Wv8MgeyW_g%(S$ z7Rs76J1HumvSlozF!n)qV+=`(P|3cG$i8J~Fhhl8?7Ly6$PC63V`eaB+^70}fA{zI zdS1_ezvp?~f872Z=XspR_BlSw`~5!pZ85l(U*1j)OAp1ks@ElO>vR0SW??6>+0Lev zKq=l2NtM1|g+SV}B1W*;$CM|2aD1&oviVKJI&H4T0?iqzhiG-s^QhL+2g5XjJsCkz z0BZrqpBHJZ7p;=o1l?Q*IB=HZ42re1oV8w89^JC%Mh~27cb2vYV9QQD+II*({1bWz z$Rh41wRHBqoOAohplw zERMJ%SCiwaYf7 z&-H76l$ItDA1e<6=z@r&LOHqn56ZgV%L2tj1paPyNbAcwT~f?yoQ(-oG9AA%@fJPbABO%E|4>!Vcl+2FZXcak4H#`zVHkofyJkP?kK+0I znZ+JApar3gll1ov6~zN9R{G09>2Qljdr$SH!j>!Z5Gr1iXPDgQ_VKTv7i^#d<)2vW z2SEFd$G`vc(1CJb(T5Anh70JFencD$ANyBp+&ShGm;*ZG|6C;pa;U)O7`QGpaL9$9 zCVOBY1lT(+V!SQ~Yq=PL2V8($&4JouoV5o)QB3XwwIct&HS3#rlGjVg5HjP~`AWpS z(+1O4rhe}hRJUdstk5kr5un^OV#U!QCFk3q=!K`rin=EY-;(*T)o<>Z_S2|KrP1@v zX$;Z+NwGgybVG&{cVWhQfI6UW_BO5BJ1W>;4lTV_cQ|G3yM;nvFf|xTgPB%Z2n`4< zGnCxMF8Rtg2?dOKWMkSqjFY{lZpjK3;{7Xa$!;@%+sJ-mJe}En^V~ukmqN*NrbYRb za4ILgLW#S;xSFw61=%eV?=@swr`Cmy`DJ8JYNtg)s9$ap^I!ExJ~}<^Dw1`z{neR< zk~jvY2GYONL98dQQ1rWIe6hK42H4loZ!?0Tiaq+3MU9?&8_WIQ-u`kJ6#WZpB@}$=905 z88%0D=m>aR=~3=S-JjX>H>J`Bctx&i` z)NbxCcdD~aFY1~cvX=46H36U!b0orpe!K{NWW5UtQIfM96~sYVBo@nAJk=nuw&smX zTUdRsVggk4@pQ>GMel(!>k}cOLlk^L8&<281kgv_U65At>$fQ-JqL_Z5CgGOwL70% z3J>|N9<+@lJGA0%yNUdT&5kf4*5@}HJz7hId`myyog}9DcPdq@pD=~v6k+~4WAL!+ zFbc|pom#_AImTZS9Ntluqj%J2>{$)1(pf({Rf+X+U5SRHA4si65oz#{ela<|@d$HB zXkRqA_WWe-s+dD!r0Pj7F}L@U0p?aV%gW|5_$}~M-KS{?$%Im~qvQHG5~Y>i zc>xxV9?n$MBaY^)q=4$UX#R0BQ8|g$#I%deLkcIfyGnrrY%+wmRk=AYc8#AJnEd`exTYZiSvR(9 zQoyfCsGosMN@*t8a=7zeqImKMUnLW}*2cG*l~Ys3qCXo5-JzwWh$2rD0+YwtRjFcg z;CL3^2{~8sQ%TE%&+M%@Ju-eTHBmkLE?yS4_rYH|jEC{5vfVVZfR{L3{bcR-{UErR zU~5x1sz4?rBY{2p{kMRBIsgW4w0$Fm&3EVANOLA#q*kwn&m{qxdD_c)=kLc$AYX|l zyXVUR0vN$W>@pR%qPEl;tyEEC#fW!Ntsr>X1p&}&wI4`CQX5i#7ks^9WH9!EIsz1D}|Fw&@87*yv8*Xgf zy%FS}N7QDfsoUEbYYlf|A3nCjzXer%9;s;4Xq0YYUSm1mAMIa%)j#@3821y+IgfJP zGn-Zpkh(hjcCOQ@`7PsOWm5suw0h-aLkEa%avI4no~+Nu9io_d?opQ_>IPYcJwFC= zYy;oU=QDMDU@~g%b|tiYcr}(Il46Gz%6wpN%;~ZBq>t4l_)u0cOVeH8WP*{GHL5P? zuH|F8tb#yVN=xUCo_j&YMVNnAW|yTp%L+4EW|p!&0*l@O_F!=`-jDAk27*xe=(jv29|LdJCidqsrU81uyuPsKZX))n^m^eP zKkdLapP=$IPtmz-+Rx4{|0NxF&_=Ia`)V6$D%kq;%26&L2ouamkqnt{B;5+Q65?q} zN)^m4ltQqA&Ll2V8ifa}U^yzSLH3rrI(;@AdXWAHjIB6><#*qb;HjhmvR`H8a%(L9 z1YN6f`z{fOFUY#@qB+p#hJ9rYF_G6>8d45hL@!YDN!^&`Y<0Yt05*F*fBrk-T#87Z z)AonS6Sme5w$DJ)1>9~%69^$Y#Lq?YVX*}xiT=#Hgz6CHERf+qqa6;mjkL?a^YUnZcTwnnr$VBEb2BR zeq+7}KK^XTmmyCRUf00Jj%lxOrd({Vs9klPscsOjd1$7wbz4SY4XI+%JE@;X5>Xj0 zo6eX{Z9p?9X>~_)vjw=Z+|h|gt`(0z>};*<@NU9Mbx%Ym1B4wt7;+Q+@k(lnz$H$n z;7W1ljFN{k=(6#Lo|8ra2Muf`#3v(}KQ-@TqIF0v>r80>7mK0BJ-RWSdBrJ z;&!I7G+!&h;qBsLc;L4UIL+LO>n*pZ_pcPPT%9DKH0S9JGkKTnMeSezPFnI#@O*-g zl((%%+`-5w*vm3-M&*n`7u@Zqk6Rgqo20Nill4j2g(VDGc()*dzObVT*`>xN_J5p% z%#>}&?mXt~{pJ()eN^%7+(Ek5yH@eVVEQW9VpVIA!AS9?X}cCvb3L@}_YhxYC<8t( zK>dc~2xbeCA8|Pw&@_oh3|u=z@pg^Q8kUxydb4aKbAupa4lROmhPdn}IXdquNbiiv zwyZB%4{Xlql^3WrEacC}Vina}7tR(Bz;olYTjyTNmhzX*2G<^RBMBPyto{;hpx3G6 zo48W-0>m4=Vbxa|L;a5e{{pOV)8KdGbMA7ro zP~%BnO;2y6m9w@)Vec)DygLDki(MyWIf)7(MiG4Kd!H2`q^qY-o%h`-#+;|=Jqf55 z+I3A{Eu_x@iIRxoq=s8?-oQtDoP74SXG&%|MYHN)&347l))I%T z-l@P3DGt9htK{jzx$O^E(;WmRdRCRThE;3vt9t@axk?cV?Lsjd-yUm{V%8+<;&?VL zn^Ex~=$kE}bsKBLVTBYd9$zR81gKHO>MDV9qN`3b&WRjhXlf0cn zd5`gCHa6fyI z%~W)2CNwaUt>E5A1%ZhlokM34i`4-xKllvlj3>r(ypH6t`NPi9KF+94@hCRd@GaZl z88)5~*vT=!cb9i{mv8L5{Jm5YZLQ<@^%&j@)VQU|Agf^Y^i7AD6t?~o@B@eK5IbxN zA#vTDPQ*=9gn?h%8!1ji`XYlr9tigZrue8IGOY2wTi=KZtrTffwAPY;3POkcS>so^ zcV|E@i3d#_(J+%T7z|liP0V&)dxD1z@b+rtXx0*m-`KKze2#6v5MOFBxACRvfVEeja?aRbjc*U5>lAS1`K_=RVWK`oT?KQpFk`UX!dl z4|{h@GeOp`&5BEQlJToH@hs`4En^z9$K;pvCCtmuPy!z_K#{|!kmObOK`qPVT zOw)Pty}x+9RGM(94J(e)kyxhblCO68vZhh5sV$>&L`&S=dW2*@UtJ9VAFY-77K8cL z&Y$JMrjbo2H4Y#0`fiw*8WLYD9?7sAHxCZg?9z5Q714BL#Qbp!>hIw522eXuBfs-H9*o2lOe8%xOTJsv=bvZ(YrwOE^5FWWn5Uk-VpAiz^OP5-#asMV zYtN4NCW^LIdr;lb?0p z#|k17xjARJIbmQbdf_Ra8jMoG+4ALbJ?M_ zKE&i)yO#)U9xUg+uaZARS!{yZEcFpo-R|v zBb*+nPOtAsv6wZaVpW{Wwr)Zaa9q)QK^#-c%+;61OG?SNwe=Y> zvx1eXj9-eHT|;#cYN!{Zj20qaUmP<(+w*(r*h;~`b^ShMpQQd1&1h%%s_Wi^-J@T( zg?gt9?hr|SA;BkQ3yn_<6%E-=U9|2oLskwauPKWsb|@=;>@S;6Wwn&8`)b^8(U^9~ zz|zm<_s~oRHw|Rv$Zw%T>~W?)IxB8rI$J!k1eK9y#2v(H;k(wt#o!X>J#z>9cvL*t zD?vDb=VZe1=bOV8?fzn#Yd_#0v=_!%^R(8#00E>G#DfRqn?;7y+OoN0%|eh$E9)_L z1^RkOMdlpxdq@=OcxuLDAQwN&VROb>dEj~n#~R=Bt00VChM%nu#=*JLkZ;h$fW@%gwmp zowM_~LFpNJ?KYp-wBD^WDjs{z$ilxI?tMCIFFW5O?|V9k&2?dYRXp}NZ&_T5!H{&B z<5!V${jn)tZaT@EFw218wpEEdU8&iK%QVO3cez=kJLQnNv)>(yRqjOs`e7r6!xPI! z+94IvxZZzSJ4bRZvv@x$ngI2a*^Pl{_aLSrIN)1AiCzEz2|l$%b6m>+iS}@uts%2| zpqj<@O*U~zcgPyqYFpkTKIy5Z}dJ)I%7ui@XHadJj)7y z;oNJ;bvgh&S~q~ePX}K?M5Q^wOZyJKYth;f>#3~PShZ*S#v z(ueH%tq!SDKJU4swwLL9V^VOZVyhiMl}&svVQ+9ZkiN%9Brtog0kXObWUn|2`gVI4 zu^k!=-{ZrIi->xL?Je$g?`AOe;F{`g<(K`d6GO$btik0sb!saZhb1eJb}eSYaA>`=#s2zY)= z{8v--&hga2$HAQ5)FT1Z74PM;0X!SXaWc{8*J!Qh2svOX?PO|e}mi|P$c2>TE zuqx~VR|!`YhB301PT0;MEEWxg&g}B3bp4nalN7gmx%8#!M7Lzy*ZX`NG~cY}ZLb8} zhYlJmo_XXHII@q;;jBF`yVRMQNzNK8^E5l(TVU;_-aQb(-{Er%AS0^AF%6w35h0i+ z|GDz^*HfPPIhFQs`dD)>ib>9uJvb1ulm8sMI(6#mVMy(SH=p-r25eF0-ad1f*Tvv@ zUqV7NInIbF;@b4cE05FSCgybdc5~HvW83smb6Gz;q(MxsunMtwR9j=?vxLp_r-e&X zqBdvQUF(RfxwCsN=)KndjH`)zmK4nN7AAeqbJeDXb*qz+I$5WI{Ny>})`EyidoqlW zLp}^jY?|+2AJkys6)=LCU7$M&qvWkscfv&-l`NVUjZ(6en7eS{KN4ptZ+v!k7bUjB z<}hKOcNu#W0%zpBgSrTL;oc(ZQ8RRsYq(;lQoK}aJrMZF|IwU1a#$(-{y9Yr%R^VHkJ1N`?(*N1vAA<}1 zb(uA#6`g8etMXDc#OX&k0$xPA5QGWZ8bPqkMnL6If|RA7{C^}A4INItt3jP4YdF%+ zcDNn6>9D(s&kdLd58t&a1+_5SLil3kOiK9OQT{nngTPLh{tTN^~6S*h1j#n-(8lE89r!Q9A6E2vQt2PK6p#`Pr~t9~Dp98!fHaUVF8$Rx z(1d5QMoa4|!7k}NnAPCmNLyx7z8Zha^UWEZ0+;iHY-jzo`(T~703^VEIvCfauPBGJSHB|p;>w3U z0tjI*GUc3nH*~0Fsrm{3;`SxEKvA0PIAc-9znX~z-{e-1Z@NBibj1;-33crabGZlz{4d?DwRM$XN zIi$NRBiGY?;*7tKPh9Q4t<(N+cNfj^077{y_I#VIzi1PIj$bJ^n(XN zyP>|~1IQnqP3UUK$23aXSv;iCM7y=@_Y-w4Zq>3`n0BE%kc(3!k4dP&#Nzl)emdyg z@EQ`V(_A%n@b@5xaJf4G!fi0F_4!2F##TNfHxm8$meE!UmA(~ao%q^D4wh`9(%>m1 zfhQ7VS=O8>Ch3}kbr+#(;{NaL`R<7KE6NJRLa)r3)Kmx%KfCw7E0&C@tn>~_Oj951 zGkBu2bQCJd*8-AR&8gq0`#|j4SOZ%qaS+Ss2g*OQ@-zDqjS@o2$L=sU?~ezN;zHu3 zFoL#<3-B%O4zq#HenqlhPr!U%eGN~eB zIFh(DTG~DJ6y!SjzHWBR2s8glWHZj1zwXlqy+?NTifq=s%iHTspMNm;u{{X{N2oP= zbXhk0eC9M-rODp>uFCxYxNyYwLT4JJTShyCcarV<5s1@{>ay-qs?v z0SH1}6R57Hl|~#S|Ap0S&Mw={m2UD1*?Y*HWm&O0&Vnu8nOQvj*U=Syd;LLKg#TD3 zX6t>^6YBYxlA=%BvBZ(Zk#@zB+3F`LkndMk8gEo^#CY7nlS>!f5f8cJKozUhMS?$T zrZ7weWv6Y+zOQk1bLTq``^A_i9qm@khmi8Z$oBhc&N55959OlAWaUiXMykvN%x%E$ z|D_zM{KZI`?-d|zX{B)>G z%}-xrak_WqkPxp=+1U6q zHH#!>Y*?;@;n|Wo^M^9niKdk zQ&VT;Wn2gvYl$(>!z|W_8`!%TFLCph#?!n!qH`cbMGAKNaH+h`^ zxT}ugSy#saub;QeTyVfl1>n18P(K7uQY*^j zPBLGOJaze%RRtOOvIuG4SZQy^0&cX@aAz^uahj*q&AxtEt2WGTlhNk@k-94Db-PZ^ zxs}r;Eo>SiA*5M9S5^J}!_xel%4l9M37%CYf4!=k*L*SeEbZ+cDH}vab};HjVTO$G zMD^q^j2AB{Sd?dg$gV5Y`s5n-+hLvEgI_ysw7bft&x&uCF&~{D$qfa(8A&{h-8HL_ zw-%^6-#iQ{0Uc*8b;-N8+7Gbp=wMdBBTq6#bkmS8&cuI{nViwFts9PPE>?W_P$m9p ze4l~6{_%*k5{qX5Z3zoh`Cf&MnlJ>jN;5_Nx+C4|*CiakdK4QU=B~bZ!mLct1z@$u z{Dn2E`)7AF!D$RAv8N5HY#D z7j1XVB|m|Ib$I}kKTeljvda)zxNYmhpL-CzunUPRDA#S@m#zBm|CmCTRRd41JvG|W zl~xQ1*)bIG#}TI?M**na&A7uvQ*9=?iQa>ZHGsCv9jT#a{bCmV7$Xy#Uh<`v7wR?C zRsMybI;0(RNwS;46ahLGk4qz37wlp|uFNLD?Qwcf~d6qwEutNCG2X*pf_J_M1nP1M6-iw8X6U=p^^OH=-zA8EfVwUbYWTP%(;V+nN@ zn7X@y9*R%LAc_EW}`#K@LDOtjCsDvS3;2ES>W=Knnq zf^^w4Jh-T{{-4K8{yG@D0_--@Czt8W?&8$MOHmXXa&b~UnBi!HNn zuQF6Aqh8D}nG&$RMmyLy{GLHG_C#P&Mq?{sX}ov)XFY}1B=Q24U?Mk;ufYqo*jK{l zkNAFG((9hMG9@R(tQnO5YUxsZWM!u*L zGql50&|ZJ<1nzBB_DXkqnzTFsL6-W$0ym~cvzQ$XZ%M7*Uw6N=f~?}ww_Z$&u+Igh zp#`GmhpJCg&8Bmas^!)6$7n0sLJHQ`>q~!S$XZuIYNZwu>&5eXj~~@3-JD`|@b#3e zp=mQe1?+^<#zdz+DX(+bhOT_oeyvS0(?af6(KA$Dc_N=X4 zH3_x)(T{k=0XMQ zgoL$1(oXKDf>u_9bs}&L3Q0tL1{0@O^yw#?wlQ(Cw3_tM-GuJSSm%E&5|m=y2T&fgbirJqX#9FWnm2stJAXFQ&?$N(g1qM&>;EBf-VFV_?~@ z%{^|nD}q85;b)1WF{Jrc(Y?CXH8IMxCf9&qZ=YAxXGg_eB&x?NgQuaOz+Eyu+Hawu zj!}Gscp8>rXHs=h{fZ_y6qlqjhMQl{*>0Eg%Am(IICB!GUGoXCr8FvB^~i8KCOT|Z z(}4QhUU1}?hdAy1&DF!Dq9a*EdWu0`J$0%CFb_r909Ly9?1M)i&B7XM^4m1F8ASU@ zxEWXJu;&D9yoHYD2@PvIdYHHzZdcOMX0sGxYq!Q+&{bbiP5kqW zj_p7&yZ*O*5~RsKb9(ixaBp$3nra*w;e*zw-Zv7K_VJ%qNmyx<6?yU83XJkQbWN8A zr3C~Z7BjL%h^IEIV6xOiw_XQBH{cMxO;a-xww<)5;IP{kO5PdD0fa5>8s^HrabYd- z1jwqevmRu9+OBfbhOX_h>Oa$tV7&_d@|@JH(6?fw-PJw{mIsHrnK&7i7pQ|s?p?Zj zttw*~&6vzkpJPk24mm4qAMlONb9D@0DOi}ao>3n%+{BH5at(m!)z=kN2F ze_KE(0n_qiHp#_aRuD9znf&opz!4sff^$3{02j^-Y;Tcuwb@eJ1%2)Q%xk6BWAxtD zn6ZHm#%omvS1u{&+a`C-IHGqNeA+b3g^sybY_}(P~4VVUzNLml(qbQgdM28qp}7*`HG3${bBRq)w2N;ljG?Cfl&WG z6OckLmynBY_D}G*ESG}v8#n#^#D;Ba$Y`b-Tp471a(=vRvE7BKqbywrrG7rIEyeN9 z-2y!9Bi*x{5mH%AyS#|Zo+V*l1MhniaOwT)8%hs_&!qP6?Vk2E%!-6J4XHid`H0G3|3f{~0O|sP)48~?XhnudM*TG{j#$ij^h?rrvdpGuv;HK_T zp9obJ59w-yg|?tZ>Fzdizp=W$=i3aOCTe*#p0nrCM|8d9e?tl5kK){NiMW{xUi{quL;=ed5X z34M##;n%+Rcj;bEvh>j2M)_|yBHs=ze94M|n|fK4K0nD;B!EIF5cyG|)T z>tzJh#rz3o+mH#753W>Bgl+iGZ3NGMk?c4y)J=-628O02Fyl6IxQwzki1-tz{vyrg zy!$g4jiIddIK* z%>v+6+F&MUzF;pDrnA$gS05HC;|(hYkUC}bz%(zd+VT}j=kLKv&`y0|!cOE4z<85| zC|DDM5-E=?lYXMoLlMV+>Suc`*9Za)c*m0wO)r(M|En1jFAfO&4PBMeYbnD4t+{DmQ8b=? z#yxu>w@qs2h+@NPNuRA+%JkEHn(v>lhjZqOrco+29zlbFtO~su@>v*g&DLNI;A@Uy z-u*@pEP!+09UspqC%4=KZbr0f^(;I~FtNQNx;5Aw!Fb0>qc9S3|rN0b%k=pdEc8;gK7XBqFdkX95$wyLvzpEix* z1LPL7MTDQBAA`x`i8zrd7rdYCxNM8Czo0O(rM}s6?XuSRHeg+0d5e?tlmU}maxD1D z!ZtPa!))ZV0))QAn5`(x({@JhluLJzUWzn8V}pqnj5Ek7i1IXur6p{mITK1LJl+0} z`Tpwn+1`ZMhs|gxTqPOSj?}}K3JEHK;*9Y1K#fOsp^}p#Z$058O2Q4C#U!g8>Z^{t zgMyi4I-s}b2GEO{liTHs>&g`?PpIVE?t#HcUU}=Tf`xX$mnLOhVXT*`$7fXV<14j{ z=t`s7;SsIDRm6;94IRFgzG64N*?6(3mM{|bZN)_YV$VewXnoFZA} z&nup1@n2WfSa=iURh3Y8%g_Vqf~j3I(Clqjd0|Fo!Zc=3=}uF|oD~`xZETb3J{1y;-qT}ER&Il~`qLu&3C^7e zcN0ZVO(?dUpxm6eEr~$#rjb^+(5k1Hwyl4x!(w+^Xoz(X&VSxZ+bfh1y57@&vLS(v zpKw{tPJPw=dTPvMV#V!lwWp|!=6EQDU&UlCorgZbG+y0qL-nsfK3gX>!9Ufl} z``U}iR>4E+DjAtg<0~q)CVq^D7C50Fc{OjD)usuy!G{f7SaJK}Yhx&{moa%vH&?Z_ z$#d|vgbkDab@xWxD+I6BOf_SlF9hH#S)u;I@6eduX>!AbBJ29*&~_2~8Ps6QBDBW; zF=cuyM|Mql4b|we#TZl|;;p?@8g7(J114%H0$kkD?8nIHCqP$OZ?ft?eI)!nyTtsL z*SG9@Lt1WCM@?1^0XJOtC#%MmD->I#$3WxPJg$P9oikMVA9A=YqHi`#V)!a*D(NgL zgk+u1*1z1gTR-XTz7%`d2r=D|=akz8?-iad*`@c2+(KNfy(=HHA`VuOLE=3CDHC^9 z@Zn%w0*!Cpwm~*Mi;!-gJs6OI=R7Ivo?+-oslRTUZo>3y4gO9JfEkCpI=q%RrLSbN z=-MUSKQCsgch}5WC zBM$r0S3HKiCeB(t@!!^}@4b@bXEBkeK|6PYE64OXZMZ^%8-mA+@r?EJ#8|?VlW_~8 zFEfF+bBPbDmNOFW2wbsN-674jw9=2wjSazr+k$F!B*+Z`~$ z!rr%)$(7^Y_K*m{Gc83jNP3qT3b^%^{dslQ&3uab=+hMzRWt?sUwdB5xgNiFv3X@% zcS6#OF^Cq2S5Q_9(T>@$yxp+*gkfb%JvlQnRr73b`*6UXLqmTIQ}@B5ry1p>$c-v_ zxn>4&g)!Sh!e&&KC7?q?Wk51icH&U&6_PGEIm}2CG>u_-nwOl$VKIB!dvG6Nq6U$* zuOs#Qs9535=c=rTwJScEJNK)|H=X~6Z5z%hTOy#juem%lgwqnyJuU2SYK*!Q4{#9M zE1s>kDZ{PJqOrb-Yle0P(@DXv)OCzSrJC=6D+R23EhqivhIAKr2r>P-WAZpw`C_-O zbCF@d!nw&lLdu?6`d-YwU;FqwuYWiC;*s^Fh{-Wv6M(Ima7ynLwz~Y-KMN(BX>~bj z6bQ+AyfSasUv0Maumh{!2`Dn8mER`&g;>*N+zDn=#83IMi%@U+OO(>MK&q07N)W~D z$_g3nh~9Q+5Z!v21?gn<66nFhFVN3y3gv80r;7T3g?<_XD&Tqjk>Xh2(zRHOi$t?D zCcUb68nr$)s}}lm`OQzz=D*4TyW4JB66SQWA9wMcAA|l;paqFC)E1+-ia|f^{15IcPB)TFu(0kGahH`L3b# zIsj>A;kpS} zk1mJqx~xJXJkfGKa(B|R8?Ku)_1t84>!o9OIgnvj&z8f@00pmzCXWHFX2i}cGk;hy zCf`%z^e+=elc2lDBMaHrDk`|(p*FjKovDP@Q@y4wm9TXK=&|aNoaa^yG!mhWS6QI) zb6&i=qOtVQvB&r-HAI9s$2QaNp79Wd9oqXYS>$o%zaH209209 z;=Pk$opmPF#6!k^vZC;h(Y_xm6wzc|qQ^#IR|nT+4ht9Ue?ah-$=>iVu>bdE@qeFH zKKG`kms$X|*3~M!iS6ib|I=rCEAJ?Rg$dPas;7MPdf;zoZxOh0e-5f*(ukZatpOH^ zUr(FAi^#vdpKB8N8~c{6K}J+iS#iqyx8phb%JX^K^#9X^M1@ZGZ|ts`V%%kHTi@B> ztR_^b5G99VFnk+wZDg^gz#ENzlUU4>C>LZaA<)5wmj~uBvgzDyZAaDN0{jkd){}qk=jssK%8%v{aGkb49sg}EjbSjFaW<7P`M~I*_{!OdGEl$;S${=`U;VHzT^t@ zuI~Of0-V|MU1&L1e_=n;7o*7BH_(n^weo-rORXpZGXVbGzXg}lu=)}yMRG&Nb~&V0FXUq-vyd*{u+MS z&;RuvOKWIIf&a*rwE_astm&9AK)nKJ+2lcKP1t8ZpXeti#M14yS*aphlrFe>i~RhP zJehr8=LmRX;jcX3`~G${qOWW&n@K7T=1w4L?LLgNkFj0*JqDXeh|oFF-u;QPy0u}b zE%xDfBbCv&gepJ&_Q<_f1KW*Zwocd9?<%c7{wxPs*8_6?-F*>$^$)xCj(Mv zTR&}*`Erj!t?Y?V)eM`Z8+91%tPRk=IUtILT^{aL?VhpNEhWxGL+P0{0-dGss_oc8VyO9@7ZxlYDhqgMiU|XBonpx9a z`%ImMFt!Y=C%0h6P1Esoy>9d4dph-h*b+EiHvsnTV4-sH-Lcdo*xpgTh^D)x4a@*E zEqSf$3^&$ks-@DCzfS9lPARz_^mcTkXzXjqr&|5lvHpjbZ@7bY1^k=`7~km<14R={ z0ep@?n7a@n?s?6&y40Q~l?8BTjVn$9&Gm9__Hti53_0ZMOSQF!Qd{aMbq%{s>3}X? zu&v8K?Djmz3eMSj#n$Q*Ew(INKVBZM%Sc`vWBhm{n#}Zghv#lh(E+S!xJ=-5i`?98 z%F^qr0L)m?bWG@WMZI>U8gwMqXbXS|FVPnu;4-bP@_{{YI~ zT8w4g@54OIXuJ&&JJfr-7eMrft$hF=W~<`OAEf$B%LgHxV}bNE^iH7mV+#}b(DL96 zK$q?{Bu$J9_S2`87%`lHj&720MPE9Ac~83xx|Amlz%?Tmp2Fe7bBjw#WvVXVs-M!I z-@QK%nb{3Wi^sS}2D`!+4``;R063^a>TwHdj5BldN@K5@!m5IcC(a|| zQyR+T@{*%bvC7IA@j#8!U~OnYuwU2MPv(&#Qr*uMai3e0&URs;5RGyxfQ{a+__v+t z@GjkNVZx%uaqNTRX&JdvdM8DE-Lrf1QbiotVNAaN=vuCZCqePSc~;O265aFDYiUx$54)e4Y53z-Jc zUGqm7XHvW>Ju_nM7?&tZ$sL1=J>vj_Kw+{cUt$ZiJi1?q?}o{TjU_@TRhw)V-E9G< zWq0c~gtoI1kVQS@+o!hN1I9CT*`8j0b$R#7UyS!W}6$3){IDNC9M|U7i&M!%HDQI<#NV_v(4e)0~r+pKyk;5u;{xb9o)b z)7Y(d*>FSipYZ&|&U0H2y1K8=o_Gz=6hggwbq zmy_1CkY3D>G(Q{eoR7*$8LVw(1FJJ}xg_b-6wz$QLSGG4`+Ckzn$A?#o~;%kDMh%q z=cHGdq-$CqP<=Li{zME$(k4Ui( zMkzl#%vMv`xjnk0>>o9G!em-#Cb#Vb7na(Ryi33F$Pu6wbo)*@dC4XOl0%b6b`~Vj zg;80M!5hu-jp0g-IH@$Xu9lp_xcYo{V$^3l(B1Wv;1I@@%i!dYzCUD%Znrb0Z|R-V ziPu_wa}k{G(XyxZM5}QIEk{TGQIpMfHo4k%Q*a0uHdcG62bJt;JS@7;1~{vI3%6P{ zi+VU0cFDQv-ECP?HFZ#H_17hZz{eXM4=;Jy29m=w;#y0wwLVZ0%J?HNeq+^{%R%Ob zQTHSNrb)Ayp8gv?{p9MVWX_<`(Qj~?|X*)!n zC;o=@H}B>Nv@9@ruo*m}fcOr6dz4Y@n1a;zkP}{YFW$(07xm@^yw9if3R1xtzS%_g za~V&BOm)t6*IjKzH!Vr$$O(ZkPkW}n?e9TfTw->Ohp^?vgwluO9QEmwgYpv8e=ZNn z8z#5Er_!i0)An|n79qnmY&O6x1&xz3=k7@3G7AtX^qa=(+iryZpVBGv#q%~zS|x%# zhiitw@h=BZc1^r4jN4-wSI8d|+NMwWw_BVWRqf*{;ws~+4f{xb_aL^3XhL!!^J z2<3JJoBtZ&(wq61?jgJ-Gj%*&Y_DqPx=y+4Dq-Q9hug)L9+Bl{L>~FjkGt(Ze`MW{ zwN|S&dzShl8J0tRP;N_6Nz;pDH~rX^Cjaw(besV(IwKQ4?`dnMUl8fUXp zCn!6PMs{1vI6deGZm5l$tZCV;O}N#GvfI{j&rYNkd{bLKFW2z=dNE-IL{e=Y16%F{ zOJbrX%+H^Pk6Uxm)1!?S#+K2c_llit+OyETx-Gm$Z5NXm44YfIgj4X5dwK25V;RMu~G|L~Kp4iSnT>!%U1D5qG&L*Yua@M2u zO`Gm?nei56w-qqvl@}*2!t}R#-hD?^fKR3FIId>~#pT^wdYgseWmKmGwrE1)>%xyG z^3H`dL4RHuPimP`o!ohODas76(aoRd^)FlIV}x$)37OU9nxFo>uYs2DcTO3&L*}O6 z>oe?Ms@W!Mh!@!l2X6=7M7+))OvJvM1$bDGE)#7tqIA6bSe*(ZT>Nv9lrtYT< zZ7TYmQyb&1%B4I?Z2z#V5r;%cs8-4`A4Uls?(}5L0J%5q#0Hu4htB*MdS)1@yI9XN=#I4^E)G02+qPpwn#DDR8Lv+h zT+sC%DzSdnZr>Fe&^LQ#@D^uI_H&S<=eFsbqgVLQ#h%)}pv5lL2+zKhuoc#P`tO4q z*cPcl$50DC0dORMUs1I?JpZJgyrH{HOQPTXY84Hi?8#`GHauC)|APOO`;qdn*ue79 zOd?e?(=>rZ|#)Yj(UZpVQ^VSX*fUqh@ zvWUBIuSVTm=;5Ogc0b+qmI>B-=;!q{y;67gZ7=S?^M@$6ihVQKUU!SWlPskn3q(29 z_Jy^9zyH&%P10yZ^P`x~#$*ZDK+MbszQmx^;i)YF_`ng70cufR%ecDIj z$2cD2G!hh6@<9@sy)rYTjT+oCnU>2N@D{*T)V?*gi&_(R{lk6et!}<@2A-^}zN1>u zreHjZw-FQ9=ESeW?W3YL5NfIO9~kJH5&;!JVoxY6`7n0#Ef zb)8nxC8zvuNdF2ah@2|WNXrl^!TZFsJEg@XkNr7w>1DN3^p%3r(J8g$?ESG$TMp#hg zd@ty$#xQa<%aJG!9cs z1POeyLR9`)yLt;3;aHIBvKl{&UJ9^aSX37UeE#@6UL0FGKp%`*GYozwXxn93C6mK; zVnh9pU0u3jCpy_wJf1yr6m0&bR=RDyP_m(aVP{)1B)Vi<&!~v8*qRJ?<^%L5& z2(pm&vxSZ?w7I1&YMus#s#{n!jcX{j_&DKKNF@unZr7=vXG7YUO@CtyG)x5!SEdJ| z+$~32YyITY6ZxXX##aW3N^7+xG#Dty=Yz5}N>vpL-W!Pi;w=caOzb99T1q(+3SAe! zk}u3FrY4Aa*Yf-DPt2Ry#zw14bOdgfWY2@kj9&~`gjFlt@uPk{JSZhO7-)&FqC5!q z#t$^%NARg-)z)g718q@~W{|ja!qIAp+bK3{cu!1`Q|<+q7h8qVKg$jyP8Tkv_(>S9rp#}|xHYV7 zHd=^Pq|O9ctXAA1RR9u88|;Nj(P}5Y*EnAG#dUuF+HuU&(IBWobB3Use5r?XYxU~s z=PwEt(p0BM#ymR<3sRbL^KvhpJvw`bWb>ASp4qv~23LX6S?Ir`OTu;^;~8KkMLSEC+{B8+&G4^v5H|m(ImOl{!WAn5u+%t>47}Yub%61r)ks z-Fv2(MacE`e4r3z#~)PdXRVzc93rAJO2q0pmX)cFRbH2W-Wl>sI$c$&=f&G^tvzyi zt`ME@4gD(o@}KbS%bz!I;%q6hI7O1cLy3<|eG3zKM>Xz=fsMyuFppyyf&*<&7P55H zZ+8UDzHl81gifen0|mcEvsv#<1}AMP*@Ty($NZL@0kyez`%T!8Y0SxNIb5x@Fd?WF zQg2NaP0OdYP+bc>yZn@qTmueTw-_a4+msxrVA%t59xhGX)MBO9Tj^rh&|wUFsk%1a zys@?wDqw1L4ZCq5Y|NCn!uXP1kf)`cw_x`ryBI1yku^rst&S)yXOx`3T@6qCI6EjC zuoE#Irf~?@L=mg8h#zlz#!hvoy;^mo`<6*A+Y#dUc-wZa&2G7( zL9bS2rNUi3O)3CC*LE*x7^d7dcg!`TRKFBVp4aAf#D!2h@DK=F!n`NoJwClT%I4+s z=>tmJ3o!GEViM>LN255#LBxfEQ8$$MT^LaCaW0W)2i08qU zQW9E z^Ob8C2iL0BB$iYwNMeT=Df(luJmAmvz)c^ep=iKIJi3<${&2|(u43pS*7DHVSGTCh zg2yorqF2d8PI2GH2d&8)8pUd~M#;B$JV+=(%sQLd4azLOl2uCDr$!2Ne%*hTMOeyG zaHV#o%ir^43uKm7_cm~w`0*OQq7#2?N!a!2J}P6LP?Y#(BeVH^rO3=!-z2@`ST@=# zRryboWhT8^zglul0?TGUhhfuZtsQ%!0}s(($@O7(ReG%(4I+^r2)nar;gp!AUQT;> zR83%Ry5J7=5Ui$*d>P5;*jKd+0er-; zw+Q#eR2~`CSIddQLQB0-4q430qV&hlT{oWRhSg+6o^z2hPq!WbT7Ron+!fo(gwX^2 z7d<$YsCaOy=Br9+g;(sgt?vlOqj!DbquEIlL;^e7oBvOZo&o1o`W2LXYg4h{B~q^~ zR76?t@DGUeHqOg#7xXb@A`JfxG`jNhgO87QM+3%dHhVI&^8>CtI%oER*+6+k%^OGG z{phWR9djgK*e+sfKN7|(;`sx0ol@X*%xwQL>Z1_@#N#tSE1-p^`u{{@-Ls-tC(RVq zX7Jak32@7d!H!-j{lqOEl58%z!b1;}QMIp?xw@`~zUgW$6$c9#Wfr;pYu2warK{s* zr356JnO9yXb|r)Ir`0(~YC#_lNny1lHmuU8IgS_<{{WO%-1UO&+*J(1kC3IhtOpd2 zXeYGFN};R*)48{ThnaXimzY3)U;TNrZYUrin&>_Kkn0{B;{uKK5_w+&&Q2PYR|i(C zP=MZY@kM*3Crs8ttofFpg0)&?iZ>V&sJ8}#QdY)i3CqrJagarU`Y zuezOUY_QekDS1+I)Z)g}PP}Blmxnj(o#ej23XUGgpm}#!s@nBo=IP3Vr5a_n7*BuL z$B}f${;lHEGUtZ(g^(5-`)`-wEYL3``A#=?lmCxxZ}%4lJgJp*i`I9AAs*v@64Uu)_57?UT`U)jHU^<5IpIYNc)o8#VU4_EhUhNO8g^ z?ZnIQ@7bTE3z{CR*5B?{DAuo-zSQe`rNZyh*?KGDvLkA>pE~}*>b4mo6jKqYmocn1 ztdy2XwkwMsa#hh8zC@DT#-f+#x_Mx$r}}J(T=CPY)7~#{L06j|sG7{AjoeHir&y>N z_m)36>;K}%@tMpY3j5+Q0|8$?>G6K8EHuT{^s z-r6be*6gw$oL=^SOiW|H(>w0f zN%|t!&yDDMPG~O9-e(`iLOO9led7~>*ZpLC$KuC3aCWjF=g2UZqePb5rnP{C)Q7oG zcBF0_grz2aPoN4MQ&T8oSsBByBr{}ADbC=YVKlTUkp0ssw7$@oSFZ-;75_xo5aYda zdlnbB{(##`1`k)uO)F3?o>7*12#pIfk9fc_NZMD+QjnsB5oiV@l0xbapB&M*m{orK zHmoM8VqUGPb1mn))DN>5lXCN2M9o1H-q_&1+fWS>Xv>o{I(+en&99T;%m+oVSpzmk z@ulV39gc+obH?aJ{;-KBY%J}mHB{sYS>Jl9r{ph-GH1tpqOeFvw|mPEo~uy|*^Lgt zR=+IB*XF}=_k5j8UCn5b~yQd zZg`gj{Nx4h&Og02j@6)wtvZS9B{G6XbAAq3=wmmykNx}$Pakg^oJ^`v!hX1DoU;nw z01{N%q-;W*8JpWHfpv}p2fX9&6ve(_{_B8x#U_r|P>D$))&u0p)XWvr{RgV*ub1+E z6;&zua;nDhMnL{ExKz@qV9Nv3mH^Hp4T5Kaxbi%=7w?1mrY?+QdKy&4F@2{a0q9O@jF7cQ1rX)$Zw39yQoKu7b=6Kzq}|Y zQ1QA^R=W$_Re>~@IfV!rkNiei4v@JlhFO|wq87V7w7=oe(6=~$U#0VQJYxQRkda?a zz8s>!JKXzXbzz}*lFbP#$LCgtQ>)oAzq}scfoV?eD+D%4J_E3Yq@Lhq(?pFMRY;wx z*B7=B3wayQJfL0Rtr6j6SThI<(|VlWwpXe7Ok)HJiF*_PX^@6ins?Fr@dn()g2MeTx^ns zR(b}$8mlws<|R{4v8{NMOi0J9`~nR8d2EvyN3)R9WM@|nFK_E9FAeQ#_O!_-7kH8f zNVJ1E!)c1l4K~kr!QFiW+mjne|Ar=#$WJomlmdv07@l=NO5{zgp9xz|1B?8)W$$;itFm0s6=?Bv{RxXwN_HVG9bV> zkcQ0XEGP(r287ZeT*YYj7m+gN%E1*@y{8`ziHCtkxV5t>3PlStx@%|1KIf~`Ad_#!CUDKW{85PW>V;3uQ>0|2CRayHe(fe`|yq2Kl=8FO>i zXMV6g8n0q3e&N<+GMiF|R!J@9Tc)z!$zxVR=8SMDIp`CgKRw}@2FZ3^jms6{;qd5i zhYVSheBHi`qR3kgLocztljn>zyDIcNAM+xuQktx&wX+`cY>E}HC3Bhvzyp<58kqOt z4&*=TCn#J+zQm9Br(~Qmtq~fSCy{p<=O?g7m)C3i)sYvT(5l1V3n%h(I7@Mq;tr4M z>8Tt32245@Wn8A9ch|mzy*y!D4pDV@7$S|3kXh@1!h?~R5_+wtfSTjRO zOu9b1Pd5kV9RN`}+2X`_(;1A}q~RW^klNBn^sD3>g{;Aa1tG^AN89N36<0 z%aNb<=5H`uS>Wry2Gjx>-eftEOae%TqKBWTMAG)aM~ylJR#pzpU>u_UM~8 z;X)|6gKy=+SMGsk3|IoY#Bz{tuIT=+10`2`dgz9*tD&2Cc2oWJHB?=GPVZj`^Q48n zB$hw0gK6|^NppkG`Uh75PUWBG{3NTFx@!wyG$@0V%ld+x?D(68zf3t`2yaCF^wHr> zhdDvNJIESL{xYp1*ekDpS-1acW8wvcG5?%hto;9ioBX!`eBTdK$;8C+V~POt`u{*~ zw!7e~+yHVx1?PH-NrYAQ(P3Q5v))%o`E?#349hBWTfix^%00RT3~_VnWY{~twt{N+ z(G$HPdzeHnSzfTEV9^O>5v90WOblSn@5aQRLe5m}2Yw$spCMckFx?+rcO<3ya>1S} z4O;cxBv;$zN`o33**)uFO^5v@Va9jI&RxGjSKv?+Q?i8`kB!g-n3!(p+foHsZ8l>+ zfrx?g`@eCp%6@yVV|cr-S55*`r?##cC7>eo^ysx`9DO+D;CblGYeF*a8a4UPhMPvo zd(gl>M~6Z7H-*rQX^|3^4%0;tqr^j}pZfCvZKr6}Sl29+kdW#{7SEkJh4`H;OU z$GwB?GcTE$AhMiyM~?2pT?v+WY0ERwfGx!tFu{Pckj|oN9o0M9clmZ=f4=>;SopL*H@}7b|0%4zB~4(m%3E z=iuq5xj-~^7f{Z0B%9ZbMPg>qfDo(f>8D2_Ic1MGEZ&qo2R1nJ-?z?|J`OB`1endQ zBG^X-BD=HDR0P^y+I{Gc5n|cHcpts`@9!#_t4v$T$jdFh#?G(EmuAeXqF+E#ZaWSr z^+`a4pP!3hSvUk@1sOAKGItlHo#`~+{taxmj6IQ$J{hO)FnyuyRu77&J2bDV(GZ9mQC%w z1W|u<(6_7RHMKgc3wRB??u%vh8_6qm_hUwadm4x2>ZiB@0d zDvT#mbNbk?nVP7wQQzCQIhbn|rs8()4J|Dbvb_efq;dLRqn^gxi?U88my5dsHsk@P z<40qW~>=IHD~Qn5{)4T?68nT)93YAJ@7QsK5R(P*`$P3#81dDohZF*1@)lWHZWVbq{< zvpbN2{CxaL3TTjK9B8Sk6ew3Y%2;2KB_c1X*cRY?E!~Hay7@YFdg0cJMvSB4MV37% zqUXc0AgTm4OJiC2+QAOL*t{B53=%M*A8!I@FQKQ2j|a4^U>W;KA2S`Yy~Wd?2Zb0v zt9;`;^f|lc{kbYYS^w z11f`u<04rAKtvmL3#hhK8)Q&k>JaIHS52}zrBOY?VeHAL{C3nm%Zj}!f_9RwNndGb-r zqt@h%5qsn~fpb&X3S<{%ocpZbyXZP{6eo5@mMC<5QV+*0tc~?x%cei&twt$PWTr`S zqjg1ji$iJ$g?G$>QM99S+Pfo zv1v11JL}eq&(5pM$8S2mEB+w86FjX)AAccrI8C@_RBn}2`#^hCwPPmTL88wBIpG#t zf8^=WSjssJa=~1Wy{9y~U+0&#=ybA!E#<+n0^PIW%R(>4T+7g>gEy?>MS~x%RCMQ1 zhd&v_rIv=cYE?Uvwq_=xbF@u}UDacW^5By?HJ?vo6d^ugpc=kyGkrWR&s)Wce8To7 z+%yGWM^5v@#ysSgEQP-Hi4JgM^(w_1{5Wy9FY{d6t6(@rLoj$!JfP#)8z`bOSB(~-mh5?A08Abm zau~n&!QcFOJ+-@TxiMWue!)(Uo9NF$9ihMI0>|MB;L$i5(b8R>>gruqve59Qp|-N7 z;i0!RZS%`g?|rD!*8;E6#AJWf(Yo!>6v)LjyDG|~~=+>V|sA*eAZn+pm!Q+!i#-#&lmt2hb^ zS^qvshQ?&uf#(h(SQI!P`V#6w@(XvZZD0wF-N+FnxJVXY25DFzTZqq|+Nqh|xu=@h z4z_F^VvN}4Ld&RFZ}!z22SKj`W=U#hqL_!{{l!#1{lDyxB=!W5jk;loNoF@2T&}-2 zP^?50CguLQQ^R?Di4U_$;^DpxXnB}6H?IY!`|K1!<$Jn054`*on0>-(g0fy-Z{K%G$3kq-J zDx@qT&K%jznC|*=&ak9OS>;mA;D|O(=V$){8|N~xM3$mKOB9* zi17X5jT2}7wM+lmslG+9Qh98HPDk%Bw0Hqs?FZZ;>1$=3xJ9j%>c+bLP#q*gC&@Rh zeyKI3ZzKWaJrg5tg|zZTExUN@A(SY!mb?D0uW-)1!8f>sc=nT_`wGe(z#hBaR|pRDdKvL+Dq$JEIK{%^%VuRzNz=vC;TJC*MTy`Ml+&v4$k)zyKrO-|*l)Cs7K$ zWyBy)qoohf0mGIukP)=}d}|I3lPqgs+>|o|yQ8LV2N3mplF_1Ax;D_EHt~furT(nz zV1h#OJ!_pT>4-vIyC}ix2oAwS=YH=vm$n__QwSj?zO2iq!jteP><+mSn{rHcBoS7{3T zF*bjg`yPCT>?h5f9T)S#tk)KqD@ZjuX+B@v`E7JHF00X>TO}g!n+7 z*98LC4Q1!cb2Pe;tmlC(jf?)HVMl)Ba-Dy>N5FW;&g&kv9V_>`2|d}vN|H@W0*)%% z&4Sx^VB5XTMCe-J&TPaPMSV|R#SB#&Dc+02%G@g#vuqU*($0~*hJWY}l%1LJlv|oG zay}i|gPWOf)g21Q+8e;-T^E9=j}1>pH1V~AUZg>1rX;(V_kpTbG6G z{-$V@4^+u=_)vGE8==V5PIXKL+ulh7@B-cefS%~? zKd99U@}HN}g361?Zw{ElOSHJ(UAy(3)6uNv9VKp(G)V|V>(>Xmy!F0dUD{nRWxmGb zGS^lj1S=*7Y}^5`Y-iI+HEu#66#nuAG%R4N#n!mDEfL76`Lqg(aCwSg?dGOW>n?-N z!A52yMEu5RUPJY?o7B@fo+krS5G_5{*tQNQ9wq->5?7Kl6!N2)%*sB5( za;2`V)=Zk={%s!zW7uj33sOLQFNdJ$i9-_wU_}Au!kyZ12g3TcV6rnOu{G(zR1-=+ zwg5*NS*`c;+j%}LRLu8G2Y0DF-8+s1VX=pkiP z#T&A~tbfnFi%*;QZlViHdoFHl<*wDKQf3x|gNyG2n-djiUSHgzEQwUf5B?n^0x~YY ziHQ(6N3Lh^qDItjk0AXhV;>5AF(+a9@;N184FP+pM zP)M#7*5FvqWx3OTtQeOhjy<9BF;?Kd7ETx4Q~YU6^>Q4eWZGE-`${$tEgT`wQRkf- zU^TR+wOrAUd>bto%s10my`s*ovYyy)c%XKA$R=FUEW(-`A+oXF+txFozct2rX7geR z5Yi_Kr`eWCfgV_fjLps#%3|q?*68E5_X(lZ>bqNaNX6f3Ypb9~qa(DIG;zi}l6Eow zEPKUeC#cRQ-*1zCk;}1vy?NrT`@@8LvHv&z^Q}7&{_*{Lzi2vo&8`&m-|Fvbo3_3j zlG;Oy^i==1p7f@wq5Hq{x$VN8NB-%ZO?-CwBwGM0o!iArre+9$OgSp}n^5>aND=%; zNap`rV&XsfRDebZ*m)ef+zo|dm-jHWC!i8%TyLpghwIxh$6Wsz`W8bTsID*Cg92CX z?2-~kV=Y%IuiF~03a-m37BGHerrjWHZJR?B1CTGX5*x|cWfC<0->Rm{=A|wk2hdRj z=Qp?u0D*VzH!~9hxG>%;s(`NoFfOoVoPZf*S_ZQ8KPjQy7+?ouICeRQA1qWDpuLZR zc6lzB!(sHr@6C<0+wIsSSy{$19Nk`OUFR^-`f9mDIHNrUf)XX{FxI;2ciEtSbrTOW z$Gl4%f1t%p%+ZMM?18Py29QgtvkQS{K|sF$=Ulk%*_C!}0dH*q@bTwc@TEvX(8vxU*~ww9tp;%~g*?kF}dpKMcOyysK&)?A&(3#UB6d#;W8VVc6& zM85)P{waV~+5x^3h^+yqc;3J9$$|WlTGn!g8_yiSl5e|y$cC{OV;A^wsIF%!uk@EE$jW?i= zIJfFip^Okljq-B)S(y+y)CyGe@tT$T zg}e)cxE)`i-Um!Ks5k;89+S6hwNGS=yL!`s&$WKgS&}~}Lwk;Yg$jRXBmWD=<2Vno zE2X-<(f16&n`#YNXwf_SZinL110l7 zW~EAaRQPoy^5@|5ej}nGnq$4G#u=D1z+p=HJ@@6>2zs8NCb}#-9`AdjAX-_1+QWAa zZxgAdG2_r#S}?yJbs{1F#D&gIUwf~s=pPap4)LqYR!67FL1Qt ztg_EeW&iRlOQ_ciCBc#4go>>|XZKw)U32WWJL!bjaf6nv3Rh+~_XQaGcDTV;;ozRI z(D!QV6C4f?qPwrYe;`}}wK|Vyd}vFRYTS}Q!xBcgIJETA8Q%nWPh!=ICRt>Pwd?Mh ze-}?e1hjP^kx8DbN#DUy^?}h?bVXfFIy+o4VKcj76t6w3g}D%NW^L5dR2s7A2Y={E z)lS&=sl3$ILkU)X-@!kr%rCKMfulQmP#Y&Kj!~50ES(UbH|zG%_QOG&oq`VGRw=YU zt;LF*f{ZQ5i?kM`PE@^+-vJ!%DjWyS#iG^f_h{H`Jh$>O^slqi!5RjRIX==iGHqAi=60KVGU7>Rc<( zgPF|?vfY$!t^!P#>R-+%#E#vC&@7ur!znqjj;$iQ`#oFFKJVX59=UW*q}Gp8XlmCz z7hGv?Js6L_%cywQo}8U*#Zo@Ei2PDY&{li>qGwK=r)T~7*20(jQ7&xdIU}gR0xLdS z_|QPwWoZjfb3x_%j4DVoa{9>`mFl{o3#hq;>8bf~#V02KLQv(mUL7|?#DPuhSxMOh zZE(*E)B4XE^<0j8yunS z)FivdhqdoH)vPkCJtx~?bagF*gI?lT#is#x-W9+1Lvtq*wv{HUHZv6BbPT^xKIUA~)|QQ1}H85g~NihZccDr9~kLr-w>to{gUYnecXxbq7_` z6Be1K*&P~Xp`_8EMI0lNIEqVULQ-& z5;t1{ABn4c9qdx*>S>T>(GsXHYQBN%M7A|IwB)~ul1y;(iqLi~XV;!mSXz4)>HsK- zKsv9$BW;c`F56a{va`U}pAH=Q(7q76DZ|1_mTYz$5tX{BP`%MqT#%9IW(FH5w#P_@ zPQHyLuuxT{@Yz1H)1%0tELVXTX~Ihb#JRLlAh$%!mOd zq1$tpwYur#C;v#Az53ctJ6ps_L@c=ZTIW~&!=(4NCp-{+O}=F9v?``x*(YwA?DN65 zRK23;0@gNd@fZ`+*iUgh-kUvjN81xA=lXomXg(Ren?z&k|1}4uBcdl`#kzLtS2DV6 z?&Io*01M2d38d=)hVt>=JoSo75#bkJ)+ij{&6rLB$+q3x3G3I`$n&1d%W=keHTYTg z?f|#H5Baf#P-`<>{2)%OOT}!>yE_GdoPTwVyuMSpZJcM0o}NpV0*3n62kjp#_W|S8 z?t2Vi{lBJgCWl}b#YRPoZ}XU!`@Hf(9XCZpxCdAYY~rt~@05~)n3$G>zd1=bEf)-M#MGhw?Z|wCn`VV_Ll+f`vYh&9H zn(km%`W0#FC}k-n3s02y2TFVScqSB7l`STAA;z!s$XQ4!-Eq&CE<(9(068frV!GsO z47_RNA*l#S>E%JLed8fglDm7{tCf8Xu8(cpu`o$m4Ig9{;behK`>@i10B;W{6SiOm{B<5)pqh~7D1E{u%T%H$$6r*c6JE1;uSDE zUB(KKFj6?D5U-SIfm$8yjDF;41m6veQ!PkRei0xRKdcL)X)(pLuGz4o?0pG`d!ukPSyF< zTOslyQ)>5*rv_4jF#L4bayc4J{g$GpaM(z zvI$~hAJn-*P8j1kA8udtPFighv7oDZ&TE1?4HL&lGlQ2&cj-w@Td$S#nyYi>*dud! zTUGq3w_Nn6dZ*^2N%f?rpzqBYx7mvld%$f26lQp^`ohq0?2gCf=%E~mj1HB)ba#oO zGDyhTRBl;lLo+Sa0X|f-Iq6fEYi5j)8et^Oy;{?38)U}33->USz;@vCLqde28-lPS zrELob3r4BA3x_ze!?p%hmcOd1WHq;{9fFrk!3cZkQRc0BL#v4k{Dk9@wh#@ElV-YK zxgKOlHL)@GsciEk(`{LAHMEnZLQXu8I)p1z{s3A1M1={Aup~4O?m0#Hb?Uh*j=C;= zCV<=l0|Z+3Ue2^Qk~I|RNDREEm}*g`mQRioA0bzl>X($K>oHnPJZlt3C9x?AkPf_n zV}f{Ba%}>bi;JkVve{|7|AuP;2;DPam~=QYgRF#=aPRj#kzkqT)T2s5Bnumg>Hfi9 zI&qc%_I9jyJuNQtD9mnk95x+hpOpP3gmPpM+!hx|w_Yv^ZkseyIG@Oy(8RAF4u0p7 zqzm^x>uLuBl-+^`ZCAXmR8wGGb~b5oV-6@07pNB;g{hR_ADVes+9n)pq^cfkYG^*oUF{NsGdf4|0yp@} zOVR`Hl*!gYqL|6>VJ~(j`Y$}l4%l!7jl{uh7oP5GYdzXKLnAlqq^G?!eRZ_GQg5rizg6kz5x6MM4LdZSVC9)JHf#llUlqQ}KTorP= zW=#$``$g)>GQBj2mY=DUa;@k92%&Z-qCt@|oM}Q)I%S_jS7KOAvqd_MKe7c18$)32 zbMsw?r!R?dta4?T;Z?AH4xNRS?0pf3miBz9m~^~?^A+;%*!L_r2CfSDpq0PW1|Xvw7pkUf1TGW5$d+@zq3+< z2_fbiQr+34Y^u=OUe^x2g#*6NUwpvqn6HMU;s8qU58y{zE;t$LK)NV$6d&ANXPOB0`BC4{@FH zP8zSV!TjiW#1A(S4)^9jvX{6U_BWY}xG83^Lj;U2wScy2vhKguXRk{)Q7yc+r&@bW zO=4Sk+U;4IX<(vxl{JD&D>u@rH8T(KGUx9B$nBCmU2M$weF`{x(am2QD?J|-STP$B zYGe(TBItR@RTmH4~V-Fc=d?FY*cv2%XOqWG?O>*l7Hi-m~|61lPu%u!S^+oXB|7`&{xWW1he*j(*OIEnu zKD_)YKmr@RJ%2Y}+BLwpD|D8WzJ$xDifTW?)c&ikhV#(q$#iAUwew`jhuu8oKaa1YJh%aH)y$OVw@9;W*`zbxm$nLXHX zWHA9<+I6)9c#kRf*8$oyaIctUH4=klU`^f7p@2{N3)-;83-n?bqr}%_4aI360F*Js z{9NX~18*tGs6u3MGt!z02JFt?y1>jpk{DwJJ)dslUB->c`6p^M$c$}%Z$03;TQ~m~ z9E%tDrVTteHQqH)_aAerbsz9aYQS{emhLMKQ!c;5fq%g6U!>#jRqdvL|2EtI?dttg)BjgY zzZLj@RpNhD;y-64A}ghbwtMPbTZEyVH4 z^49DkzMPJyUJTcN;FS4U(Hg}8+`ojTJfJ|4T^#FAnhra>o)62pW3Zb=iShp03`F5T zt>!|EB32F!vPV4{u9&n{zPzUXlfGUG;P5KGGd9gc1Hx^G*Fg_OZ~m*} zJ`W)LGXF8lqiCbKu$n3>3{%hzJ7%QFD$kLhOVhi^xG5H z&8z5LM6d1fybAPqv+ybR&tD4$1nQ);w~9^U6Ei?q{8a_~$pR5q!RZI8OQGZB`LCS# zS;(_%#oHp9M#^?>5DCxYgv^qdGsS+Vq>jb{qUF6Z3OMthIjNZce<*cLdc0JU_&&vq z)4IuW2|@+5*o$nPY1GqxY&X-y8uH^o1!?!eae-RZTC{3+ws5(GMz)cGSe)s=r9yX5 zM-xy`Or4C!Oz$Rqp8BUb*bU-Z9pO^NK6a8R{btFpEM`)D?@7eJ?%M2>2bVgx6+Q^J z>iy0MDkPmpew1&x8sCxnemi%uHx=Zd=UCB_gFQte3FNZW)8N6N8c{fzWz`iS42l*Q zjrhpT&&9Cvg>H6^9J|b%QJV^Os@<-Iz?;wy`(e-t0ZltpA!Vf7(mfuux~NPfHR} zalKQli7IxBrxRgVy4h&6rp)CiCBOsAk`^qB43NpBpQ=&ah^}HJ9MC^pN$24GQdoL< z5J=zc4!>S#3@lrGG*Cx!`JM?ddN?cue4znZ6gx7C@h za0fw{eY&O)X)z|>utPMC9O0e7t((%R)m7K|h?Lh?f8O(kT<&IWzLO?FG!Vsz5J(-Q zns}>lT@cbFR248!r=5`qd>Qwt6e)l;2ASk#SQ*bEgg2shl9SZ)?BBs^RnPKVhj#1( z2cpbd3;Q2_J1pAp{#vQv*PAybpG(>bjFbu`2y(~k%}VZbyltb(Y12m2Zq?#xU~h11 zJf6mT>9}sn8+AnTb^Y61=Vcz=#eMU>45>Dx%IIJ25S}W=pQ^1NLNx}GZ2(f*@uXt< z$4)2q*uh%&#udjj;F`{TbK*umHnuU17Wl+X+QqJ7>~Z9InS2fZ5P2o1R4ds*>wC?f zO8WWMUqw@^z1~S=3xhXr2n7spsmOka^2)~hGxnPcl$ar-J~Wt zPdJQw1c&^=U4yL2$+KJ;D>I+ID)aEhR=T+L>RS|=t*7jcA)VF~hkfU`w%Ln7wQ1^l z6&ruRdeo83xHY<8L7Y|?9*y^@0w&eXmH%Xcu>k+yvz*CzF$_WIIrTFq)22s;Xje7Sft|Yj2Ug)t@p4H)%HlsAVNTToF z-+*bQvI~X+x3buisuz?#9|@yhPSEXGKF8B19Ou{|?3DhJJG$S9x5rk@>;t1&ii1_J z=)*IMou$N{7`8zDm`{Bn22)-Ux5y_LXL|#Hi+e@0A)kqA4C6dp?z@T<`uMdPhYIgQ zlE>A|6Kr_Lx|d1Yxz;NkHUW$K$0Y7l+Yvi5t@6_d`uXP>>KvbNf2b7BxVhp@OQjE} z25*0t(K}Kq4BIQl#=4Qzztrgwn9t`p%FHF>bk~D^0j^n76O`xhzBp>Edwn%;LCGtl zWlg<4y)TeuV5Os-cDYx$NQhtZHK?yPk+~q{NUD>2MuT3*z>-gd{xjejnC6tP2an@u zVyJ^&Me&_4_+G8jJAdeTaXYT=MgU8f^QC+6M_~~lV+4+w@~KvXVtq_zN?h5EhuDb= z2}b+fS_!n?Ts!JW*H!9xSJM|W-T%#-`mNH2aPsTGlQp*zJbPC?LBv)j%X93_Tv9e- zYTNqqJtW-feT#sN8@#>ZGn5ya_GHa9I27y{2^|vWjS1v(V0&AMdI- z#ybFdA1Y*@b=WmoyuSA3o7C1d^;y;TIF*Ybx0LmD0YANI{(|?J;Ta1XLjQ+c}~ z=(4rH*1yw$^d&2Edbw2m&|G2 zZ=Q}YTZ^wI{{iDT2Q%tM9jQ1Pt}mH{(J<1VsX_+G5VsZ@s}yBN%K26LzQQ|FeTxff zbfbW;ZF%7&a;I(P}-@T`G*WbQ?1Zv3`I)r0pDXWNe-DJy``8U8zSDp%ZP_T=SK{)2D%GJPUleY z{W)9SCU@l^Zes*+u$pCCQ|cYzU^F-7=`#{dn6S@rOfWfHK}yy(VeRV8LLKD-_{8St zM&$T>{IFwbQz}gV?JP24Xd70wtbDeTePfKUF`JKy_U1pQtKsgOe$*X(7g}*?P2&i> zEKAz2V=lgFDN|ZdD%hi%m9g)ZYRvKeoknu#SS8QxwZYZ6!F^6z&H*(hxr}|fJ8eb! zs$aNPVqk#*j*BhkVpCI%aRn2H6dZQiYy&JZdN&j~#tkHKE9~x}uv_<4M=j2r?cqr0 z3*EVrroS2`jOYYg4p;#fd&cRqI)6l0g9qI*!DFbPmhG0JCp1V=#+$@2yx7upds`u| z;fE^310Nr5&hzMaoy_6sEXMfh$O`gZ$DgjzfufeV${lnl-)^X!2(%vc`2~@XK-FK@ z=TL3k&t+d|QS37g4d`1aReae_(twXYhaqj-a=hr_pqzF1cI5|<`glWyJQ}SXbxNmP z+reTsIJ{D?6!;pR0lGl17|e8x#Q8sEEW zLp3yR&1#0P+p3g>V{itDwCD?;dBbW1W(=M?DqjB}9+)j=d**msIHBR)PAG1t_d)BAndA!WnvvC$V_(HY9uw6nJZ5gjwH&{5ep8LnLOP!_ zwbIg?er}uNof!p{BuqS@&b)sL1Q>nE@>hou0^2N>m(-anUa85wD^nB5kLQcEraQzB zC7M@14yNA<9AbMLgjURyvML$J^Rn+LdoNAyecQe9_h4@%3(?E2;4exn^I$}zJbRJk|{}kYjtE&tRk)4GA zZ5;6-{>%7w8p=uRW?1$2!ieJEu7;V*9bs2G(uo zqV+&y^4+q!ZIo=h@(k|D>BiviL25RmKP->OkwSO4+qBs`{@Rx((oR&G&ri{6k@eA) zf}!pFVKp`;?aNwAd*I3W>=g!6YU`6%OOjK?N+u}qRunU*LYpUacWl zJcM;M*?+zY`XN|pztp2Rm-i9o`fz6bc;YGU?~g@^4gp3o`nT}&y3eHZAkJ$;Xu;b(eGEQ0TXl(L%5uDSuBWvP>g|F>+LHH4PmD0 zVdmQ3jBeJkN=)`apF6s>fyXk2DC%**Uh$E0F<3rvi4Udg+gb_0c1d76gAycFKNgJ* z!eoSC5a$y0z)^mR(!RnR2bQ&0o7?_A6el-QTNq4JMnd(J+hV$8KxXAz?*g1?Un6Rq z`nE1;b?yDC{n45n>72(k8L6Izpo%vhazx=G2Rouu9#F0n^G=$)d+l;?z1)cApjYKN zBa&Iu0ei_KcS-R{7Hmu*hhc!|`#4)Dos#oMs|G;Z{;rLT^MH@#%`tq%j(>>h!=rk8(4hu_Z$h6OZ!o#D~(MtIJy#Y(hU zA~5;Mg#Cl$H+<=@TD1sLENiAj;TwI3zeQ2Y4H3LoCjM6E^j{&}OsxSr^P?F+asDXX zn)?}Y{=1PX4JC0LbHcdzn*2SV0DAFXH%v=k{a@{!c_7sL|L^PDIXPL+Y2lPmr?O-x z$zC~@>=7CakzL51y_16@*_ScaLL`igWz1M66vhlfj9rSc3?{}HW4-TDozwZ<`^Wv= z`{%uX8=vL4+egV^+&+)(ow7jb-Z14hENqs5s|2zd9HZIeQc z1TSRWZw+IQ&gwgS29sCxb{Oi0!xZx2e?YGHTUyD*Hxg}^%kDg(i@0r^s~V1Tb{Y47 zK@j0GWTGU-Gr5u#EN<0|)h>YdUbw`k8tQ8FLh{J0c;1CWnd>PoByWoh!!+xZ{A4Ts z)P-8;3~Qs+AZV5-2eFdu^rMMm_FfGVOgHg`wwtZTU@$T@6Mrx=rsc_#@@BTy1vv*K z(pOyB2+~!6L#FqJFJ_s(H5)$OAU#x9a(&QqOq==nKf0f?w3W!4FdTtG zz^z|KGBn|`g>g@;j&3gr6Vh6rl}ZvYV@>^dvQ-B3xiuW@ViVFF!pFf4=B%~ME3bQf zO&MRpFh`=$llnBfZPG9v9c3Tzt9Y!RMGmVE?@1|@Of%+YqR&qB7!f_48+sQl)`Wyz zx^aSJAmbRh%O{+7vGGx0Y1!R}El=#O+G-w-90r8~(4BKWN7Fpx&5B5o1*()TCI}lRu@FnB3 zL5%$)x!?Z526SfnU`J;5plMVW2i8a5R#W<^)VYY3MbID0>`5`WD@NcbUP!!m!1QKD z(ly(4w(qmn-#yjWT>Z)8j@Yjb!uCbN0oRC@C+w_MHvj4$k?|HGlsY9O^G{xpQ}(_K zBBQ|P!K$Y#7&7^R0`P`5IdOo;V!r9OYx;>3E*uNisozbppUTvq3MBL3>q=+M;gUjR zr_RV({iFee%f#pz*~9Bf%d7i>@auhF)^O6z;+BS0o%weR9mqnanZTf4vd64JzLZjV z+L77y)FWSvmi3p)>$w665FHMvJRf~?kJv@N3D;_6z-i6}BrV>5C5_C~9DG3`B<|Vxw8*SSR0Qw&;yA0*(69)-qbPY$|eMshLH^F_`o*O@t4LF z&CS+2*j;U2%42`+{dD9@=iB~xOrQ*L$A@257v@}45!8GuEu3$%MNjgIz5Hh}u_x); z9=*DXookCOQ+@E1?=PB>5(Bn2<9U!)`cIJo7u+i~S6})9_g{EDpO3_o0K(;G0quyOUlB?m2y# zyLSZOr_nei=T?#`$)K?u2&7}L z;x;_Irxx{*zij~KSX@Xnvv3vjZIT#74yTTrJRko6H@1t~J^b8v=JZKLYx?HM1$``U z$YbBEy0J~w&vqw!Ulu=+Rnw@s#vM-)(NB&v=Gh8rj;wQLty#Q-*)+Y0ZfBxT3_}ua=486`ligsv75+;5n;c8A%z1^ z0<;Ttys)%2b8{H%Q0>E@In@Ubxx^(yOxL3{2MI@5M^5(r9xVp8Tg4D1v5Zn#mNyH6 z1r?mE4vq{-yxjmDgA7i<};se!xJ}kf4@k6_(s*^aOc@lT%uAIwo&1(JI z&BjmNF%hBgv(q{DR#w{L>wa?wy9C)6Pw^L);!64ycf+cNTb0cOpRgA{=W46b*FkW2 zBtY`+jQ-ePq=|B()$GXNUnfo&hT+fi z-@eCkQ5Y)4=2F(Sx=ex%X z$Z{tl3qnBqIbW(HG5F3?(Bo%sltG3Rh!UneugJRygiS(hwyCBWTzrb>*s(;=4NQ;cc zxtqgvfu#+r3vQ%+#~bJ=&~;#60%ZdkVFJjtIwdqVF>U(Fx#Ogdnzot};1j>2_|4Ik ztPG`uRpXvXg)?Sgs~g9#FeX1D-NsW0mVmx)4fNL~E)mgC*P^Z*takiqh2Ijk*QFKe z+vU3g&8_|78upr59Cz)R(*-70k5NOb&D@nbheQ#{D8M5q+M&ILO)~{v4)e6d zF~(yEah}+7c~%69K+u8geg??x)8e7^PNWMU-)r?uibtMR7E~QHqxcn!63)CZ6ci2% zdSj@vTFigYH_%9s*43PRLX>Kefl{M4JZbb!ZfJCaiFAZd>}Fd@ueb(McIXc6_;A^N z>+nx;&da_{8z0%wOYutjF$18e-u@)d8KExeGYeINC4X2KQ1TbcJSR4ru(N!mN@XpC z$WMxmW`_yoZVNEBsXbjZ2}qMn4LevBkw6mb)lXML&|hEmW7a*^g|D@`i_x zJLvmGLf$gr8`Btwj{~JC6zS9xjcf|33L%fe;41AHCkS!CG=rwd#m^pXPj<;cP{9%v z$u-J|1yX7BzCPzkB!s?(fS5~+=558^15k?hm%4U$@;a)?j(CAQMhe4{%^S)_14pgy@xaOlqd4> zIPP?>Qo{qA#Uhw}v|-bAtkli7GPZZjU3#lavfr<<&tGQB}YSg!Y7?b zHs(z+%ty;TKMU+Y6T9oAX;ioM1>UZ}tioxGsKZO{-&uW5=(Y!>{UTpiEC)1I%&HiZ zRub~tT`n9`N`kzAYH7IP$f0Zsd=$K7oKZ$;hJ0NKd%je`)$bxRZ&3o(!I}C@rbj{i z&I!^$mDUYZI*5AoGj*!EBkWs{FPyU&ZJke6b_lPQ1;w{;(`hT-gPl*Bd+$?7(3uuD zbB$Rc_r#NjdQu&my$xNxU;6&4pf)m^QyXMw2!=74-Cdxp^#fxnkjRn7>6r5f&yg*7 z!Eu5i^8#lCuXHZ+b>ZifrO1W_I>LEj`pIlcd9EH>Dd{Q>Zx(BM{mPO{VxG-U+NmK9-xny(~o$V8=h1POw7LQ?R81~RaoZQe27DJlU#w+IiByryKGi! zrpN&08o+936cp0rqdLoIQ`LU4h*Xa*7F?NrZwN>bzZ>QyR41>fJil?vnJ0cxkjL5_ zqTQY|Y9e@REA&oIamo`*Grvr3lHgLb)8I8?3De)B5y?xJZ&v8y7fSl>+TBXtcd_O! zeyV;0z+U`i>P3q^scfHI3JbW2vV$xMq?Zt2G4FjywiUgEwwWB2J=*# zUZ*%_T>~r(Fo6$?L-t`x+U_Z%{G_MawWlty<@En2rlr9*M96J!T@Wt)`S{6~Grc3n zpn*Z?CvJH|qP$)lF4ii+WorucDb-t=b*MoFL!*rPH$Pr_O176&8lz@QpkLbC$mZ7KN(^zM*vpUUB>M`@5xGG6`M^EZo1uM_oL9z z=AA8ay!KF|TUDWkL+rTA!HKQ?7=uuR-_rAPi;Pc!&8Lij*{3D1q|lDBmAox*nIv zf1p27b}cmOrbn*z9;`J;;?7~gz2A6kJ#d^Po|T?8`5>NaZU93se93|tslKh5SFT=Z znB>1xjQi7K8OXDzbcGI+3t84#(SO##l%SZsU09T3Z?x8L z>8J5^L99YDc!IkqBObwze#M& zcC+a>MG`%6iWQ}oHp`w_SAd?XWTpW)1&|i2c*z+Cw&Bd(Hp5h=^P&+E)ydpD6>O>k zCRHJT0>zMr1K!7|HYveS?OZ7lkzg?3xeQ=j=iutmoVYczlPxB7 z^^Vpp1*;`G?KP+<7R%U#tVAmBZV5R|2efA`^;NnBKmZCTWNoG0(efX{h%M4xbX;OZ z@gmd-N{`Dzbv9!4CIzo+?;68qEpv#br>cfgdk=5jtH03=1oAGSj!qCWq=o84z2U^x zodm1kaWQHI**miE-)|ST8oqlbrC1MUZWBD7`o>U|@#eURxUW|eJwm`#Bn`|~i$BfF zMN)cHx5N~M#0Xz~QP;tp?)oqZH=-vYb!WtW%O_m=xkBK{oh@wGE}Kc>WM}|Np?q}4 zX^-X;xI~lBN4JFdue}gyViM65mPX7t(9oaGqKhSZP|P96EROHR5a3vC4}jl*V-rIB zZ{==&>L<0{VD+K(Iv9V|lgmZ5Y)@=a@B=1J8OFDv{s2+}F>ks7)(&@0%3ezuv7G#r zd{hW9h5$mM|MY21-FxoT`Q`|u@7s%2;veVytmNGgA~?CX)-1$YU^@G*n0y^Ns0W&M znK31Twi7F#9mZQ%m+%tut=Sbh(s)8~FMd1(U*5O(@vNia@($OwPB%Hc z5?*0P)_3F|_sJUL%@!-g#LI{7IWm?g{PO+Pm&p7sjbYF6??wyNU($m76hb9_y(8hq zMQ8F=EN5yj6yV?44%ANs3dx89#e0S~xYIc39BeRcy7eqhQs99R zf9PU>_cCaXCpQA5(ah^&&`HmTm2G|Jw>4+vrDB8X-CXTj{irL6v#|-m-P47(f8(c6 z$$s~SZretEBGbqY{EVf$j@ILjK}u_fe!Tuz&M&ZOAQ1Yz*Z)I*L^HLIHE@0gt5n<` z$%t19_t*_KGgM}z!i#>~>TTzTu|>@4?NCgyNAnBrxMtRFHFDWoe6}jw8(&xhfsJE# zxc`=q%wpeXhJWW8+)-5p+jQwY8K8=<9{nn39yrkodR^wQsEKu1DoRko4|hKHnZefl zlA3Osmv|CJKA(l*C%?K!S&^kY;v@`VyfF1~_0v3%I7F5N)@hPWuQ{HrYS)coJ2*6| z13OVs@EDb}n+3QnOT@YLEUa^h!p=GZN>T@oq~%OU(z(@ltqGYfo6lYYoQbT41@)7q zXNstxwR=T7(dt5F*H>wyA{P967nV(zLTms0vS)Hn+M^(YR71 z(qXta4>_r3i);XEbHJc}$0-1p5FS*opw^UYZXF8cmb4V1EQd{IR}iZ_T1oGf+e^Q< z1?r&DT+(gorT*Ggv*&I^cq8nTxUoN6hud+Sx{`DAt{z$`WaE{BVJsAR<>khK+d&FY zfw<-80})OxmBG|s?NlXn3U&}8W9A)`Arv`{_^nP zoC9{RRRE56TL$PCs_i4bakCl`!g{Ta2h4u4<@98jzW3IGpYyfBv$LlfB^nLD{HzL_ zdrB;c+(gtQOC2$0FWKV@mTilzz>Ui>h8ZMP4pz#hiM2K26Bx|J(8W*)@r#P7P=yKoR;e3@Y zBi@Z6_UGp6A(dULKQ~o>a)2w$MiK72#v!UWPYfEn!v>~Z#DS~Y)XZ)^Nc}V;g!hoa zO-*dl%h1%WnPkvLRf{qOSmD+6(MW|rzD-ZS0u&}sc!`fHVm$=-G7-V=`~opNK`Y3k zfgjAV(p1;^c*(2=&NyzzoP?ik{vHDiOTgW?m#c_GITc9aQop~*phFsB{0^&^U;o;g zmH$n^B&Zy$=(hdmyv+M%;>H3vV5)PNQrqulIGOW*u8$8eD z{QT{`_d}x7OfnIyA8(i`)5T8K*NmkM@?wRsfpfq3z<()d%WTXGf`bqHs}^>vY(`G? z0L(fd;@QjnWTxgFDJv10)38aLVJE@Z8hjAqV6a1yZMcW zmMhH#z9USw%;_J*nx5nio@Xmaza{RWn9yBHOwntQ-?;NiPaL6W)3Chq%0ax!;yCS& zJOE8yX6bo}kaA0A+3T~N4tiJqpneVu&JRMtyqK}8M=|&G6`cD(B7hCjdrgT}SttL4 z2!8CRT|W_hYUlISa5gh8Zhx|SfW3qp5Z+WiWjWh7T1H=*+~xN$y#84FtA&@&B1Y_i z>|2eh{G9pOHF>ySoi9jD#4a_`Rqo_^uA#~Gp9DMb;o)xy=Hu1D%R3GvhX31_HAUMC z+qj57!JA$Jmi!q=Am_S@MWPYC-bGsXRFisF8y%s6AU7PU0e05;0i>mX3;XEfpOaPm z0zKX{cNQlOS`g?--AAC9zF-zm9$)xh{f!B1NIaH>QI_BTyj4*_jR3E(kEUY=NF6cy z&|F?WYjc-1hZHp3FB@0SS+MyJUFy%Sl(Zk(eAJ(Yy;U&JLNajC*lKN3DB3q z_c@UL=4j}_R{x$n3T!Z|Y09bzzh@bgjBc7jK{GK;YD?R(K8$@`-Tt(wjD{y3%WI6L zcY50Fm5(*-I6~G&HQF2kpn{Fz@0C7pvV5?OkdtA2zWxEHF(Z2a!KyRQ*nnjiM&LCo~%pmxLf!+vul^ zv-oRSCM8CFg9rfajds}Thi;axiM~(bB^aWdM1uw9Q)4|Qz=CdEx>S$SB3jTFhpJk| z?viCKyS)8!XqXXCH;PqWlo1q8q|PcUYjFxFoi3L?3y^((;}a93V$(4+!*UpjH&Y3p z*Y|AD;%C2~YM~)%+(T{YM0!)Mg;rynmzVjDClDObq{TN8qn`a-2S3iyoV|$nQR@7J zcaFioFpGt@`IGf3flD~k$GLs0FD_I`r%$z=8h1lX!VNsMcFsJaTu%9(0I9vBiM?AI zd^_c>!F-~lI4*>RzLBp!nj-M~T&-YX)3;Rw)~<1Q?-Xv`+CjY2VpV%bBic>~`ziZ$ zo4$7Fca+D%u>8py{q!q4!86B13rY%`3WCX>+{@SMC;xnJ{@tpGmkhcisgmrAY?u#7 zWrTURYK1#qoFHu;{BbnwcKmN zC3K>Xq-<*@Bdb95672aW10LsX|K|4%l+ApBfguM-G;QG;R@+vC zE+(W~mF|4q^&8&=h`K<7KmKi+H2n!~3>Ji4xbJ@5^}8h$La-DNNU7-Btq<{Q(G}Tq z>(pOO)7Z-pxxGgm^O-31fZMv7n+5?+p`$phchKbvrDao%NK^U&s4tpyK~+L^m>S;V=tcRYD39CaE(mvyYce z2Me;>=__;fShCn1VP%dL=7#naZ+cAN7>{Uh1yTf0?JgAKxnjPiuoNSos~4)a1Bdn~ zvi-^mY{54wS4@KRTh~7IdF1Ks9jv2Xg>jS71FPQIOXB7x0(F;t^2n3^jO$ZikKJcm z0pQb$w8hKh)>o~KoeAb5*1~#-H<5v}(G~W~0pp{D05}_f%YS!m^~!?2!r*j2&#KY~ z&!o^tc^u{D)|=s5ds{ubXH3Dpz&iQ{1Pj5(t0+y2vhD4`Th_2eJznV&$0f{@BO$up zA$x{(0d_A#o_z-EV4p?B9N^V^E zfBeEY-pX0M5__3U@ow+mnt7chNmycReBeQT+*NTLiKXx-2`E>hIvql$b&yh}Da73D zK(R}06luz6_|=QG^2S~zSpq`yC^15=zm zQm_#Y4XCMdmUDd06(;N%9-?8VkzW{+yoI;iQ$IP%ICQoc;a^ zW~!AkChQ*udLOm2)R#-TTi8;C9t*GN_Zo!Fp|bbK`_nwir==TmDdbfNVlcv~}Ql zxuxF~KhIx-)Y(TitgTMw^sA}(-Uj)$OxqDx5J)KaZv53iZ{~-~gcc2phB6Zixer!F zd`^l_05)qK`>CK30Bcf$hqhk#QK3*6QX9cZknYHcsLaM8MYTwH3;Q>fkI4E^FbqYR zSQdlCjobK}Vp$X<2tJgs$Z4#)shQh!qjqW|qxa@Xs2wzajDhdY64aFZyWObgpxItR~(YFmk?3*eqWsCoze^$q(dmwK|5CfNrD z8O$(x%xku1=5tcd^psY(5U~e+Z9UxkDyU@Y%8(wHPE#rxGSQ2G_IhJJleW5+mn#>! z*@g0lGbV%g4zc?D{Lf-P9z3X4qiXV`$*&zn2t*_g49#0l?S)BfHz9ScGQ!shVS%e@ z>Lo5g7IY(_+1TO>l1@&$^f(C=v+8ur?xL0|6K2X2kUT>RtUkzl=H?lBq15}N?dv2kms2Kf z!=@UsMMXK<7?gQ5#7VTQN4b7{@sGjl<-rN&<<{nRZ6~T{G#Opzu=?U!Y*ouQcRv?2 zmQYXp>oby+Y3n9%W8ZapPkgsHp=Hc{h78bMTKdg=j2$R^YA|T}UJgHx4KZ;sfX*j7 z3q}LRo0rR@H7Bg9?vOT-Q?6|O{xX#AGpunA7)H`iS2`#&ale7u;_l{hxwmu>)m$3-b?74zpIJ+pAp3;6JbD zv*G;U)vE_h*FS<`0;b=QRJk%Z0WEQfYbJX(IdFb_&N96KV9*SGk|Ae^E9>Whenbj0 zIgC8CTzhK}} z?7B^{4Hr!w^N%s^_{Ck{}1s$EB)ia ziL8S#fuwhH|L;jG0jk1#)!TW(_`<*WRyQ+lRBGXGBE^0QN8at>?3BTY{PXWCXTiy^ zeQ)Syv1&mAo}rGV*$wN{gdGG+=qIJcLJ*LCqtC~1-Pq-?;_SWfmS-my$%!=#b5bc1 z$S_L3@x2=+ki4xzN;52b(tRN^qqUtA&x~V+BSHowE0UQmAR@{6~|u;>eFj+j^0PR@EDA zTGidPLXi31E_7Z;%y*#q5S>-$VT(cS-Fz+7VB;Gcm$;R$=PGcprQT;|zx!tnyeXdh zqwu3j=4QpNzog61+~vV@WL~dqk+a7-U)#X6V(VbEz zvu2$BS`flO{W^kc4+V(qJbcvHQTX#WU%HQH&wbQ`eS-bobE#vV$z%AkU?tjC&3V+^ zHT2pCE1X^SaV``|30IhCTqETvSCIyM3>&7O0oc+iglo1F`H|@Bm)#MGITei}S_%BI z6N;dDruR|yX^FDQ$_q7y+pMjWYi%L$JHB>eUT=l> zVcjM3d&71U=eJ4Ev}Sg=)QT>pXI~FtMN_ zaC3y-QGk_YzIlcizVq)o8}r1YS5=RlC960!m`5>ncAHOLQty9gcWD=Kq@+)NX#$`j z7<1`rV~({wCA=0zwMpeJ5LtNW9>;2NPPmr@i}3l)O!~WX2^!!iUa4psbDbu$zYjK& z4n6dgMYdP|$0>S7tL^YiGj9|JuRLyZHLeZA@eIi^(~Q09b)~e>?d1XMS1++XO?D{z zaT$jH{DnS$4NJzJI3xP~<;omn1A5qih{##C;x_uJg^2v@Cmxp5&pbT}&)yzy&7<&v z=K!coR(>|2ezpN8L8-r6yDGF9bxqAdGGXHCy?64*z%e_#tWPt1A#jPVpdbf^>uf{h zawf9mWC1Zg$-1;jWUsQ!Wnq1k36aZi&!_T`{r@OllM{d7-cP&|THa4=cqQg3y+3*( zalVaF|M|>>y58P!JTr#B7p8d5B(v3Uh}NZUm7CHj?~-)*vATKbr9E!qNptEB2NYXc|OnrPQs6~kY2`E8^EO9cJ9s64nz{dRAOyrKN1@^>hZX|6tD}0 zF;9Goon+7WczQ?Brw)Y%ZQy195jKt>vZsf?iaJNP4E>{Q+=`UF_j{J5s-a+6mM~8_ z|Cw@Ki+$9PG1;0YXt>HeNBq-ZoLe=D=Y?kpvGzla#BMjTkJvKpRzR*f_D~H(5f|Bf zwmq$~X&k?Q)c?VVKyt@iGq4WxeyQggqguaq8eTVban|8fGNPw?bzbI9*8%jMt{=St zAFj_gkf#0uy5@Z&)Qm2TKaC1&5F4xR2poSXf3(8K>!xFm3=?R4;9Qu`(@COE6QqM( z|B&)4FTCJ98dF^LV0Th?SK(rIXhe&GQ4y>sk@t}?*}_174Ouzm(Au@yedIAHB4Fhg zF}s=0!<2@XRUvLmD1tZ99WvYCao|RpRtu-i)1~2VNcN-57Hq1etFa`Q*0z z^^po!idY4Q2A$hYWVybmg565V$njqG*{TS;MGLJ1?LD+pKQRy5I&f87yyW(8M0boq zR4PZ(uG?0YF>e)iFI%6<&ci#OGy|BIH)1Gz-56@n!2_>jK>HE%RJgxSS^n=F^2Yqf w5C1o(#QpyZ>>pbC{|E8^WFp=2D%cLUERFVby5_yhoJlt{41Pykzw_vS0Hul!g8%>k literal 0 HcmV?d00001 diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/Clone3.png b/Firmware_1.26b/Documentation/How To Contribute Pictures/Clone3.png new file mode 100644 index 0000000000000000000000000000000000000000..e571f35ae235ad48e4df0528028683a147681ebb GIT binary patch literal 14502 zcmeI3c~sK*`{-?&8RuJ5&P*0FnKDyjX_{JYxlhxgX-e)psHH}xrnrHCHH}$1%9smo z=wvFXDY*xVOqN-Knv&v*nE@gq2_k|B7iYWo{&CN_=lt&Pk9*F1&Jq2#H-N`~H0IKb0m~cmB9Ob}u@6=8x+qJ=&j-9Xus7 zqA8mZ(TJ65K9o~#IieM-eKap^aEKK;Z1&eP7-!j0nuD=(T=2b4T>$4wz@H80I(}zr zL>oBN@2QK?8aVxD%Q|SLjQSL+Te21!KC6{>0YlhiT=#R+DeSv@d%(=}C{3Kp3i`PM zt>|45$~PPoZ5I^Ma^$?ujTjebNzDFesT@c92`yDc+mTJ%JU=w@v(ra@t4sQJ^MC z^BvJciEKxVvTE8wI(y}bYUN)_^f6(fgLgAmg0QSID1a@`fNu6l*wK{Teb5>!1ya6k z#;|PoLs^D*5k8=?3_Q=`Z_sW7j@UT>;LGW0#{KN_W?ROPU7I43)hvITQ9tz}_`<7n zsjrPB-$5zD=zylso1I}cWNTsyT~MB7+a3`-*(SlT zC}J2<9z89mwy*39EJ?RQbiFPfLYV=$$g~EOOe$RZ2`In*?$$l&oj*iSc!lL|M6*hC zFUK^Oneuyru(M@XQu5I?#WAG4gYqXvuLdeak9QfzoTn)15UM94tt~1xpgVp!D}ivZ zjKF7Z^ilE&N~&)%7JrJfQj+#N=b%q)i#&+D1S>#ZwgQHt*CM?qsQ61tgoHPb=UKQo z+21P#4KXDgW#Jm%p~yn9F?N35K_uVFs_mCbWDw@Ay zB@)4>x=E=JctYZAg+}2sVd`(?98aF|*ygg>0Xt|HrxceXBTf^$rKsXO ztbo#(d7RSODXCQI*I`Z9rwt2`FvysL@*17W zYJa)00qB*D@$^(0c_Qz9m=*2}-Tu*qNcg^~6P6E5lFu7`EY+AnDALB23?YV9_Rxfo zx|}Y|eub_gJR5d8o1^6xIfWOC*!U0GAuw5=<8W-yA)IVx>i6h|F4hUqZ* z$=yU_Ui69x3(M zsk*^dyEAT22g!tU=mkYT^EAhTN^M&vW^=I=X0VPs&9Ps!4&RJ_)$e$slwj`riV!Fu zAfKo3a%Nb=LNIk=S}8`N+oC}JLTibm8(RLZkk4|Tm7|Arub!=!OC}x3?1Dby4l$l=7tJ(~faea{-&Fbt@vh>=Sw)dWDw6p9>!6ZFdB6u%!#yYArt zIYI#lzvQy#%h)Gj1y`7G6z>oX4ov7a778sT;UW$~2QC$L*8{g4hatW!{%M7I@f~54hUZneinkB*uUNEWyqY>>3{zNP z$Ggb!|5<7)8`!J>GLru@lW02<3udA!(j@7xSaG!Q3*CAv4}VJs{;<^ZnG zg;L#GDXe?UqT;A*9mG~#0h`Vg8eprCB{BBFmJW)E8Z4sx9*!CSlM&sF+NC5q@_C#8 zc!}=!01VP{F-V6um)O2S^t)CJ<*46g4_o{tEF6$gz7lWKvSW<`Ij@*=omD%wia zK4bd92O%Q@`un7_T{PkcN4z_y^gfGIDtg(gpZ4|ZD4@8+my=+{TAOU^=qj|O81p!s z6F9-Mu4T&127cubZ6Lg#S0sTj3*i%6YNx*w#<6B_4V!Qn&WYhJk!&oTIHfW?n=oO< zL1laG(U?(z-oCiz@#1qvx4kXbKtBsI-Z=}mK z2`4?NZG#UyK7e`9Q$_&ErG=0JOLRZAAj_*8b{#fJbV4`C`%++9Z_?gyO5ItEAb5b%rlTHd3g zm-q;dV`T4|%J_R*AHOZ7O$)H;&*%D?x`#l9`;u(B(Co*&t>7OcqKmG@$59 z;G)~ne~^@leypS#17$}lW=znnt;I5p)iPUf%f&3i%O${~GtYn#@uB5}gZgw(i>>3c zEmV8If%^u)E|X`VgEMV1Mu#|ua{8NXX@+AxT~`Mvg^uR9wT%xC{@^<&!m77wGq~8{ zY?Xw<{Wzk7J8`{!MWPH>sn;?`YgYZ3hVhP;t&LoDo=x}v6SXeuJN{pCqN4U!rQ@Gp zI#Y5tp!JR+?mc960saRIa<$X_FW>#EDXyxUmtXxwq9YK^h+JKrKl`hqsJPR`_Rmo` zrKxbVFhw(BtA$*Jic$?%{=(ADv!VO^-~C0avaBA%=I4J-^3E#YzuZx?(@qhHzB9JF z;wQX;;2=(fxat{>XIr{G6Gs+zoMX z|62WA`^XbkY(?LH_FRaG1VP5ji=wHDC{;P z;jOYWh)71(Je?wzU9=9chse96weO^rh8;OqIh=keg8%`E*w?MWKrvW?T^-CAT~}Hm zPe!lDk!_W^?SNiN*-(Z6&nS;APyz)PVn1&yH!ckSAjZ~lfT_BhXt`7}QuB_8&t$wJ zR8Zr^$lQ385B>-kWvm^oeN#Ck$r!1TleDRlStW*opQFUovmt|mJhLYTgiB(-Zs6Y= zMXfZTf#lr0gw+Aa&(9G1*n5CAzKk|!=y9eaaCbEzKv$U2$u!=vI=Gsmvo=1s>f;{L z;ZTTII$DD@U(4khnU&~-b%(k*#DUO3`sb7un+8K*tV`%eQAQB#N~z<%z#I3a>XTPGNI`2yX}xAc9XfZ#MF<5pTIaLwpX<8gdz@VtZaYsU$dwiIz^bi)XfY=Q+ImDdup4;OYsOZ$If zhHJf&9R9m=|Ach-1oavBfkZK4{nJ!#`MI!$J~#LCvID?cOr8bopY7XyLw&uRu;xY-hAZjK@` z8By8AW$fXuKz3DI#?Q^j!PfTqpy)yTMU9&Kvi$uMwWra`*G>;52K4Y6J*e<7-JfX z)Mc5^+~1#0mUbZ_e;sF6u`1teh_J`++ePJ?8(!eO@Edg{xm7>NSd6-z=AQp*@r9q# zO77-<9q(HN`_D|mLf)7>6RPwnSYA$-*0w@TD1%41lIZZH`0qBKzDOPk;nhHZsQ81M zTu!fuC467{EAHyCC|*PeyaXt4izP$sl*30Vsye`E5>j!Op#8_e9ahT;mq&o&yE!!RE5O zMEfHLJ@GAOL#>9KzuO5P!(X;^fq50enpK9q*g6rqjQ?Lgb!!YAtR@Ef4|2^L?p(lW zD2J5wgyyopO*7U?pXM2ELC<`-^!Gfl-|S^i++lyi2_nsuL`>sgy`o!OS{simp99#u z0OW%IF&(WtVcqCv2z>HNd0btOErQ>Y@b>NfqZ{q`@J`AFNhU{tLg^KqJ45rMC|`tj8}t;lKITinCUKWbJlHnkj_3=Q*wen z&5=+w{7yO*DVo2;^*~=&#*plMYuFJ`f*mSRdTQmgSoG>yZp1^u78kwW#n<5&nz`xfp3s-+=zY_Ono$2S z1tmX&NKG!6tgXWR?-8n=zTgElxU6)-(Y?GvOb320s@DJ$40^^Q-LaMbv**M6*lcrJ zYWuz+$8=)XH-6^9iSIj(cFsSGMUU+V544mdJ+`eY!-NnVQZ2J*y8LoVsR`wM<86Cb zW~pw$7dix(no5vwfG8#nR{;GGkG}7Ac3bQ&0DSzPy?u9#Mz_*U&Frx~j)@2b7vGM5 zr7b;-BU<^`O2TC8lYYmSExA{RbEt=g)G6nszwlB4pVHX~d3n0j$9e)`*gXD^JPE=> z!E0P`KIplQmezR)AMCFKb$jrjS032gfoy0>n18d@ik93>FsJxnd%BiV%6-udd!U@# z1yE5Zq^cf!q|oJk=s%n?JJi!9Z%KHNVvBAeAdkV&L9|$u74o+t2&&_8CwFAPw#6tN zF3o~|=$VP1aK7|_yOy344uIeJXKDuxX$MbW|GxcyOe(5b{}+)+p}$QPv&_>|#W>Zz zxLBmR`Sv%H?P_X2{1B=Nc;2|t^SSDSZRy{rUO(Dls(SrcGeY(H*}q@-ca{DXjeqsw zU#sz7HLbM)4X*-p?)KOw>F#2S1G{x`U3A2<`{+?xDaK;W9XlPfaXsXFRQI9STjpFo z0VoFTQVU7ajJWZM2bNKMb>Hm71qTC(an1dPvtNSS?8vA!pOU(B+1b;s66@W^9Zujc z&r%8+nf@Q0ZSpRXl%ZZD!ahAGsHwNyDB7)7`1RH@(b_)@Cds<9gF&ZDeQNdwVya_p za`q4X990Auzov3(7d?u$?R$A`r{Ef1Fyv(266+e!UaLpK0d$9c?dkem?%dxH&9GV?djj?=m!C*I}IH8Y+)}!sb5c=s2f6sq9 zsA!7n8_8rD555{^T|=b9&1Mvhvi>?@%rvW+;G)%`<8%veoHRW^q>IhGesOUB0$AmO z$5h>H7~0Fr<+L2O^QT2F{3s|b47LmSrBe`8l0ZzVzmb#n34Ng za9y@DKgqrgwo85F*L@6{Xtmkj`mUG{eY-$RXcNCx!G+b?mMtQ-k? z#o9&#UD&N%oP~L$wvf^D`QsnzJVwb+%B@mkkY&Z}*EUMBIri0JT*RX4_*@fS&tAUs z!7ClUG)P=ss|oY>jRvXbRJhDqbgwNS-I0>_g!-emccB;!Y8L&|FD+SJJ_7rD_LPf5 zoG@!xLahI?kLFo6II7M~l{mR%395>&AFCQrcW{dAuIDJjt>M>G{Z}n?$V|~gxu5&H zPvhYMod((`N7pCug2C#!c%8tJkfw6UzPM1GPN{#>uCZ#|*{8}i_DsS?K$8Nn-2NhJ z@KTjLhPO8`>zz%v@nUpaO%cP%{HdS&jbzP@6h6}|VJ$4G>n>_vG`-$2YsIq6$uaV6n(YLr+Ulo^A75xFf`Gz+3`?_Z`H=Cn!k74Y~b@Zt3U$;HXY44w| zt-O3~@*Z>9!{kMywu@HQN;@tm1LR+ng=)p?k${ja4P*Ab(yX^{Sw;o$sv>&=Z!Rmi zgTK%g^iqA~qWeC8>PUYW6?APr#lfo%e&GDGz7EZBiF1kxn0f~4#Vh${tkGjI+xZh-!|Zc)o=)~d_J{u_6beA zu}}{Z$s{thYCY;%DY$9=3~7>eC$SCJUNxsPrFBDk-(NrJgCwR`BtjREL2Mjf3K_4@$bC9|1#~kwQ9Z(N9au?!thSd*Tf<9uz491i@ z@jA=;gS#>9%g$3tk^rR~Y{(qa%Bgm-gVf7@2%S(E-;!vmiOz4?8&my8y8ZxNpXzU? zpn3IP`ECacZoMSDnGiv0FaeZ#yPv;$Or(ilDC|F!m->tj#UG{7^^b{3;H!3x*};Rl zCxPzKcEg_Dha&@vN(IFxPvxp7sD(f$4u1Tz#84f1V>0iNTQRu!Q=`@LIdV(tEtE}R zw_T7S2#fMCI<4aqleO-Ypa?k#{Eq;h4f7pc8;6C)hZ@g1dNwc?u+WhGJn+%k7SnaR zZ6R)|)56XwBR%?Py&0%OC4y$AEf>>?*4jxCj)MWZ(2*~v5yga79m(sXdBcefo_pCi z&jVzmy{rgfh8md~{C;u8yv1nCVKkDnLHT`G>T@(A52Tk#IU#vMv?(l@S#*M1yvAuQp zyd*?SsR8TBrY0L~iP>)%Z^SS2DypYXM>aRIEK0*e%b9CeEWJa^g@bR>mqiN~(N9dI zSLEL}tQ;O7B<3f1v@@RZJ^yqyTnV{TH3CX81Q+l5i<8ShSN!i1(k}j z7f9FUg($P$iQO#qgMq0P&32)O1+i-E%s)nK(8#Zb*MwW~1c`x;X#8fM{0(U@8}0o2 z6308+CN`aTprgfP2pJ5B3N0VBjSMK-01~YGr{MHPp_h`~ZcqamhA$?w@g3=Xs&pr6H`3iT;Et=caA85?rFUduq}sJeYLb%I3ng((XJD=||N^l`M}YO}WE z2nQ>u*_bPS?OAru4%gEq_Ok}!j?NxSW-kD~x&d|n!)xvkU0dBGv9xb@rfrT~NHicy z^OvB(fN7Hr&t_nDPf#PiCx~m##2JsU*)w&Hl=JF`XM!3?w~_A>go`y-S4gcn0f4D) z$qX$uSj%ppXIh~6B;?eVM83~8pt0OZ=JfUcQtsWIUc5JgZ)Or|C9aej-!FjYLUqnZ zCILj{PZQ^`5uOjbLFvSK*$3gLp-&};u$B{b#-@55AgoOx_Sq!nTm}N!Fq+W+VRPrG zMTt-rt){bo3mM+@ibJc7lj|PPcv<%>r}muc-1~4bsygEOVlsp9&VMPLm^feS?N}q( z_I$iR$ZOGL7wW$-=!hmZ)M$}{p~@5|AB98-6+ADLtDjP(HCcybyRWG2+qu>L z8QrAs=!Dd>E3c|U=I63D_jVLEesXmQv7c#%qeEJnD(_r7Pqje(+UU0Ubr!`0RK~U! zXP3rQFbjMh1w1fe)a)mG4Mu}jaL6~7ib2+0&xf%EkroN$n?CSNiKb&wmW2O$>=<r*aEKe8rv8MhWzI!KHTIMruKAB|fV4NjLWUi{!k zO6G@=hK~mjJ~H>o$7T1*Q?bI~1TnqxjM1!zX7R$E=|dNbc6NXS#~5?`oimM7Ig!NyxcjrTVl2{XT=jXz!-9oPE8-zL^>7q2b<>rw5|SkJL8Cg4<(-(3$F{$`nB$ zb}i_MeSImq;9TaWm!V{FlWcEtl({EToz9+zNyrOo7cg52Bh-$8#bxi{BM(y|(EN%0 zWVjKT+$KZd_6{vMtLLD9RWZXXS)zi5#amkhjW|(pE-1fOr0p77_mO#$sHGJaeVjiT z#_SXMu3eb^W?jxb1O+LsR6yQ~WS@&R?E&uXV%ek{0;3A^t+jGd-zfCQ^bKlbu2YR=v543}J2BCKJn zzdyGR=+x!guKUZ9Yt(2>UgsM0s>!O0msymYi z(#fc9Fbp;&-8!jef>qJ}S+>$%?CP*t(V%>eh%0PSdSFIiOYqPyxK5^&u4>m_sLO^kXi3qDC`NQTaaF%U9KGKcs?X@Uz<6 z`zmG+Ih9>Ag&nF^1@Gx>`OHW|)G#Xj3pGRg|E@?F%C8++O>OzOUGf2Zlw zUS~X9Kc9A2amz@RBZdJ(*qRXwr@iD=lrzdx099g?s9^%zVY>R=QS=C;Qu&*zBID(> zdXZK7H?lAGI&h7L(_X6*#g~`2)5>~2N8QP+Sj8?lENqntNw!6}h2FM5(+iThtO65M z;s4?dHB-FFX<+5MBb&N14U#GqOher$_AI)u;l7fm_-a!5Cg{Pw~VKG%We4z35t)tT{j3qRVTIPi* zZi$7MAqOoNOEel8o@3Oj&hyhh_z&O8o-TK9mYMS{3XQ#eHA9Vsmt^ z^6{Nq(I%OC$*4ukfjo+M6E8Y5*;VIXq;jh^?N#@wtonVTv^Wp_#_6NZ8%+sqe7oZ% zg93+N2eA(T&pLKj4aFw81=><-Q@WSljLJLOb|itjM>ht&!&Ba8wML#M+t1)%ZA8EQ zu@$LiqB{THux|yhUtzH2a0416r#jqm!+_?CX}oZn5uh7s%(dm?TgrOu~kLG@1VwaT7xJ|giZbRr~?TzPE_ zOLB^|%Kf3ukkwq_(h+D{3+6e`Yc5>kPL0Vr07N66=aV$)nf>GW*x2xZCW>AH(U24E zUNc#Kski-6pFiqDY1n4pNcA(`$XnJ*+c#Jj4qNt_DA{p@UHPQ&lDS(k6TaxP-@ti( zYT(CjNaeQ~KIxrF1U~|D^$BWIs6RQ?hcV&Yv$L(e1K7AGd2hOV8OO8%e<0`_tFhVe zpCq>XNxX-u?ci2f90BBOCz~lZEy@Y^*P`KNRX4b>Ns^PK66@cCO&M=E|womb_TK6H|P$*vmW9kd4*)q7(4 zFz49PYjtkDd_!8jq@(}M755^GH|h3(uEgGyh9A8@*D~tA>{S$tB!$a0Ikq#|VH3U` zId|BMfF|*+gxa>Ri5Dy~Mnyc5{UJzIbZO2n*rm8=$0AYE%#?N8lQFWYs1y!<%KHCSRtxxVYI;X+(J- zE#U!I@HlvPm4+HU^x7)Qr;%k;*hX8YWN?|U z=jRVDtbA>e${p`rp_d)OHivcR-A;s5$V=why0uk7sgrGX(M+YkY|YIirj(t_?Ab)p z>%-vIsp5e>(6_5IV;|lwq&5)AeVIMPPQ9{*+{rP!ig#V&@pW}|3B_p55p}sUf2X1` z$FsBkD?3&8$tN^snIJPi9Lovw515j^z)xj`Cf76e4@B~{j`D3uWj~Q$? zquag0)|l1Nu14w9vtEm(vbamB95L5$Gdz<;+h|h!UO9p`>zFpup6Z-T)5ebiA)fi0 zW4C(NExOiD1q{RO;^9>rKC+Z&xe2x61PifQLA@iRDs*caD#yQipKRibspn-$J|$%&n#~k&giM{d*-(5mx`q6pqxgY=QV8haFVJ>dS*fP4$0v>twgHo%Qj-H ziM8ErQY_U%2OS8`Wl_vF#p)<+7p2s4y8#=fl^{xi{jlr&{l996V! zp<>GqSnq^+-x$Mwl599*pZa|?)e;uaeWHPx5F$@SiFP%t-A> zWFDKIZaK#IE?JW;oMd_P8I^7X6M%L11BpkATKhNWA$zGF%*RoquxLv|0|@U8@vgwK zJmK`?F*&ILGzYdv5vPr!4mWNN%oYbRe>1?6)b$~;!8!xllu$oRR1sBN7ZYK@?R+fC zWhNiVY0jDb>`~mUhNMw_CJyfr8O`(6V?3C~^dgpQa*fQH>ch314iJDkHXd6b$MrX8 zJ=)8&Hbc)OAFo1JBp5|?!>1I-M%xFb@J2)MiyhFPOg~o(A*uARJK4z9IuV{k0$0fI z+>ISG59}D}+t6V$th2!bm`A@0Ow<^WBH6#+ z^TYOx7nqr$BV*LIXy=BmV6m3pAn+NStw3HLNqn=}Z`rtr&NNl~@KD8a|0Xv7&F21_ u!u~gJ|8I4}za<_2-_)^$+{;(}$4+C4=JEnMPIbCgJAc;gOyiFsKm8Blyq<{w literal 0 HcmV?d00001 diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/Commit.png b/Firmware_1.26b/Documentation/How To Contribute Pictures/Commit.png new file mode 100644 index 0000000000000000000000000000000000000000..2f37f1c12bda414ff2c921e7f9892437c50522cc GIT binary patch literal 44800 zcmd>m`6FA~*LQo}(h0q-R#CLo7FD7IHFu=unVOQSF=k>Wv{kgF+?s+Isw8GH#w@L| zMFc_2DVmsPNlf8Qd++yopXd1#-uDNQoU_l)-s`Nr*5`cIXXl;1t~&c^-qXj99b?yc z`q=Q;F&5mhV}E=;$;v#kY^&1C{C6B`sQ&O+Y44Q<=7&EWALu+dcC0+^%z@1b=I2wM zPtBpnj&Zd9`a9m~k#BeGSZR{R;|In8pcTfM6fToy%9*t-oKj_QuN*vcEnS`fb)dQ8 zReDG2gT=-`mgB*}ZjX%$myhRetoNXn*_C;v|EQ=1C83C7EpOE93W#+uvUl8y1%$^0_?uNiuIMZCHDE z?%~O6ZMg%OAW&zbgszNB`$)-#?L3xal5m z7sH8M;C~KQV40E(Mn2b-k7K|UVIG9X~@5~w;a4MG(20p zwG5`IT)pcqUR61kZ}Fbq3Jnc>w*vj4cVX7ls9pn8>7IBqLyKrcm+qA~9lZpm$$uI8 zaCmD){g?H+;uStalH+^4s@W@zKSG9o403*H$lQx=yO-UvQ+@ey6iOO`9R#83szWr$ zGXF1@8#gbs=QDYHk}#wXhjC)0@eO?ps*TjkP9J5Y2&hREh|?HX zw5)c`aTb}v(o}ywt?7DR6XxD*Zg}Qjk5foisDLClnwLh{B;S_8O&!zH*iT5Lq+kjY z7X~qMUDHQn{)1k^qr2SJ)5-KqKT05GKXXWqK<+8aq^hj79A7=i+g9one`nh0c@7{= zS<<#qSsRLXNRc6g%=gQ;<{?M1_wqb!7Tld419OUyW87BWN!FelNq#-}hMKoW1fe+J z?&OQ5ZtcXL>O(Z@VM4K=qO!9pF3m+zH0!k4Bu#1V54rB3uQ$!=VT&v(xNwgB)QoZZ zc{8FjTqt(I;whNXisWASJ3pqR+Mu9{>!?SCQDPZa`MFu{OMT`*<+s5Cfuv4ndV86m z^N9yF0*+%JJ8#V`e900ZcNK+-iiRDDd6b$AU(i))6<>>8gW5O$c)?v-vE-1p7dv1= zG7S*#q6}Rkr2F8a+!l^h_ueE}Tjw|F#dIxozy0O-#_#MT#y{uUj%&Gn*J~onbD`>D z>`ntms0&A%Gh!1j%{8TPY=U0JmYIue>%xAjIqfeScyA}61=T4}0U8Mp43v19w?f?CC3{g8oCw=zZm)&huc<J^JHAB?G+DGHIYNb5g~HxXZGY;FQVCm1o% ziQ>SzkjRxag8WL4O7DF8_@e=umoU|{61%u2Wf=U^<5=Qv12q>d2?{8+z{;HGC~MAf6@~8wZZA zxeJ%d%QiTDWOg{dIlRViQV_B*kzMZHogQ3cm01Gw$}x2N?z(tI{R&Y=Y86{0u`lC) z+vD*}ciE!?m_5xd-R=%`*e%r_XSHWf8cJS#6gYe&RZ$4w`RcuUb{sr@xH2up&`>jT z_)h;zd{I<*F zro41W>>18kksgFS0H+WIF?odSfjA|$98s4`l0U3M?^7MA50kp!G4aXE&I_fOIF)S6 zQSzvi>-5G@a!*O-qoE!br?H1Z*SE53jJxmeF+h_!e!~NnJlOR9#SG~mU(a+Dit@+| zMU#?kR2j?Q`Z-@MvXSq2-jTiEx4$~;-54gB_InA*#!Dw4r#T6K2M(~m@^&+pDB1Cf zFG5S>q4?w?@ZP%f?I}(ZS|z?AUy^WzqG4~mUm%f0pJGV33;{d4moLgyY^*rn7IjM^ zA}EH$kY}M9a%!P|4|{JE9TesTsNVl|gBOeAuenFZ$GQQk9o{#2>5iEdFavEoYrfQ1 z-hibr`W@Hj#w~IV!9y<~7~`&VXT|TprNH)CJq29TS=2@w*b$N|va{UcmjD@i+_KVdtk>mHUq=Pb+h60-PRiD}D=7GY1%W1AG-~ z&@0W3s}W!eP{=R<0X~M}6V1z_cBl2EX?hWggAShn;l6 zwLq1G{@4!>Q!xV^4xGvMi2-*^SnwrjiiM`bGi{UQi-xo+W*GYRbcS-KFeB-^Ss?XJ z%^p&&3#nasXvRYwkVc~C5RAFkYpRAJ4QZO1mTs#$&;l2gJ6N&c!4Bc9&}5gb^_%Yh zz!fIKxXCVyWZ_gUlyu?k;vBfyenv;;p`y{WPC_nYMKqOSk*YE17s09kQT>gLx-f>R z4jSPwkC@s0kXi?UyFK~JCTLV38WuL=AZPx^#NodbW@+;s!{3kd6I+y?E zzk@h=!hwGn-T$8nF;BmbPIY*rfb}UCju3h?re_5|Ih0i^@z+BQ=ExF{-#vLh|FF&X zoj&8;()nwNH<;hRb1wYYo5la18s;iU;-bdO;j!f%!2)H9w|)ZWt8xRX4FL_VgI5(r zyhy!-Q;%+`lc(?uEIxJC^@nZ=%i!qHVff3vrd~bX&^W4Mm3@GCl{7wL5lp>%FU!6N zc<$uxbJK^7n!X9*V-_V=!!NSWVp87AWA9w~?anNok-1m5TvTbr`L`Ez{oA#XECJ1-}*A9!+k{QPoFc0JZ9 zc;|${#G~bWvDGTeN!Q^&`Fto|5wn1$@#jL;0o!53@XzZ`S2MDxhR;GImtyOx`qlQ$ z%fs15K6%yc)W~vF=7cV9L93~6wO?sDPF!As*-c$OsD)EqzD21A@(k2iN;Gya_=R2z zNz6DG!OxYUJ_onyjZpU{kB-xpZw-0s(AEdKACStQhu{r&^-o)v5!yY}Cmx%u9 z4IFE=w&~P6xg=Z=cj=a53H|HFflk@0JbuG(Y+ad)T|jJ*QA_jrpn&RFCt*U2zFP$I zA?Rj-wa!*3_oS^5K>4m0c=YS`8>i<%o>M7m8>^Rz&pRm}eyV24-{PI8RlusyT7ZT- zQsv6^^E+&=KEQR89rymLp?0%Fb@%KYKM9m|Jed2*+Sicf%>AMNTgY)OQf52OKdm6B{L^rJPQ9OY z+`z*2*0_DA`cY>uk8@1|U&+@b4PqL$myUr2#d;BQ-Tn9#onC*4IUBHgAfMDL*!6jF z5=c*N92s^aid=gUoX{j$uRbLym!PiRZ5d%b@a$q=yn3W`^|Ar(al_yDIkdJ1Jo-cY?@tiM{@vLOMI zTaugL{A6j43A78{|M6gVH2Z#+x{|89X;HuK2t$c){%~(ydF7l(BCppmz!nQ_X@o{!nQ11>L)q1-6EkL%S~f2;S@ET}w$vObd8} zxNZ?9oP;mVJf8E~?X^C_P5*12@4%?ypnInU8^6eQ<#vgzO||lp-ls3nkRN$sY3&Ya zoQTHj6`wwy%8(o0OPB6*kSi(UnF3lS;P?YGsk}}16s{{Q4*m7D4!Lz5$~QW)^3gyb zB-2-U?iOM^cV*qG-^=4eb*V(CQ(DvAuwmZb1)C-{6_+Khx?G5<0%0XhB#u)8?hE24 z6Xsa5)0s&j`-X{K+CJF3uBm=UMwmge2q;ph>tDSrb5%8g&j|S34Fqbe@dZeyaIpPM z`_2>K9SZ(5^VJ#HSK=dCvK6cG>_wVg+8U32=c0!wp?F1NayeJ*^YNWp1HXsx0aTsj zOMG5`3y`}j5dm|V53X8aE-Y&=?_g!c_lpKeXaDF`np3iDo@wer&lxU0B?jKG&a01| znNvD=e@fQ-hrD0k@u(5^h=U|4oH#nHz~@l^l8GKlJ_J>#M^|=xo5|+>V9KsTd#jDy zPw6;;!(WbT6qPD$mu@)`-VmZ0Ixgma_yNG-%E5;PR{YrAww+@lnpSVMkWo7@oUHNIYhB}CB!Y*!zb^KvQm{A zMPj@0%AuovwITJ}o6D40&YH{|@42@K$~9%E$AAP@NwFu3E6LtC+X?9+TVpsBYN?K>s9<$`cx|@7}by%d*%5Ayf_*iGWTKtVU>E z8DW!+R)-ml5P?e!a4#?}5i;ej)v*ujB!kWmI}om*qV;uuuP>$nk*oxp0Ky*iNoQ5z zL3f2WU^{i$!P{HfP*^Qeihe%Bl8^04csGU}W&c?3a)6#n)BMPE-SNPMuZs`*pFf+c z>+A(cRf+2?xObkdxVFpvYSIh;XTwvxa{a-4#FK=rKpgg}cIUy)6?%xB#G$g^==VDK z;WCllYxPWjst@S0>laRIAZG=SUxRf%%ZWaEDI;s;7A2yan~VzdP_*g$c?qv2Wc>Z= z)y7koK=?G@;p$RJ)%zZmiw6qWpEG43G5r7|tZw;4#FR`b!t{2{!TYmbUb9LNERY8XL3(1z7KcS4%-h#PU z>iyOXYBQ-=PCe}BKbhHClWnek^^HST?8C2((82oHDS_kJPlw%R_*Rvv&ydk}u_RwhBX}sABvUR4lE6t&)*tKAn9^>X= z@jN<(IXaPlMu$DwLl|DyMJwFJSq!X%N(f`FaQRw6PEkIaal;4OzSD&T;LM>M&y>7l zW$+rJW^NK}4Oc)v)db5Gwerj@skgIxngaVkC#Nz$==1)fb2JJ^fcuJ*(gN;>hMQo@ zUJJ+U^*4UnX$G1td?UHG@y6_gVsl5F1LTy`J(dsp!-E1uOD<(2FL|GfObenMaV@Zw5{=IZRE%c9i+)50zge zg^VqCj|Zi_s;kODnMayy=|yaw?|33oG?q$4_LL=70TRKej4IA+gY~~7DwDO0XFVx! zR{CKzv37h-Q$`X#kmkTh)Ol(FeW~v_)LSnxUh#7*3{YdQ#(ORC&Tl&x=v4mH7>hbr zD2SB735b6mKJ!+x=cI{Vk`+9t4&GRqM)uZ$uE0heSoSKP!7q zuKXf-vu_|}aiOWG#KZRcyQHWPm-p78r*-IMXBfjgvTf8CpBQrDBt-^(ywCsbPCJM-`pY^jxYw!fzp_V0%-LM?tIbTJ$HW z&N*Wtf>qxXMh}12&t-N9qc?Lnw)jbFt^7d>rT!mS%x{rd0&s<>!yRiRaYEdPj+P>U zVZYGljb7Cy18bU(S$^^e&VNG6(uZ{VRqKv~Iid%;j#k@fD94g(nt8-Vl#@#}?w;nt z*(z>XH3T2`2w9<1GQ&2Z$&;Kpyfbslzxj%#+i2CHgkaqkaP&5Rjc>VDCH`kSruV41 zopvkO1_*fYh>B*;mG|!@R7&nq!i@2aFlFpL;jk6g8s9DV3f3@&S}Cae!3gYM5xI zS~M)`F=Q%L5Bi#2VXOAdz2LD-VY!i~sw_%B(?!HnDR+m_Yxnp{%7Ry`w&Erf{bL2` z716v~yF5fEWscq`!N6*EFX;)+k#DbZT%VZ}LjGRyr(EU>Y%dU}WdIKZ8kPq-CIWLd z1-#dhvhy5B#jmWHeos|E#$m01ZwxfwF&4H_d)tFLe0iAZPWB^LeNWpjeD)0AK)4le zuzDb*N{#zp+`pI-&@@Nb&~z;lDS5OP`#tYsl5Jlt1#!WkiRzN_w-(@b_utKjmv8)z zDP!5(uU2X;R0zv4-tiF3Ed9x-fUP4kWJ z4N)@97c&C)4PAWfALNG)m4?4Opf)nX<@Go{mNy3QSm1Y&!(-5b^%qriXhOnghp+MabHeSGBl^RfphT4#&j zA80{mxxRInBO++KS~bP?c>1O`^x()kj>kcWuM`uW2p8mcQ_k76_R)S9q-PAZ6fIH9 zf=_bRthNfzEtyj(OHjS>m1C19-);taDwQms{vFA!Qz+}H6ct`B;Z(}=Qx5K|_Z$Px z?8EiGui=rYio=|rJt|s1KiHy?&sbUUI3vrId8?LER1&yH3P1F(kLl@?2@)!Lp+BZx zADrcW=vy2liK}ywikB{{GZ7eb@AD<2D|6IFmTS^niyFQrJ?i9_4U8C{YW9l2@vGkO z2(is#cc(tpnh4yI#`Q?%1Q{wLD9UkycHz9jBTjNl!EqUasfA%G@=~8Zj;{ERz3cU? zt91k7gwKBG8FZMmWpI3;o#aWtBrZFsqg1LitZwJcd{gp;Jc-gpM&W!TGTz=`3jA5F{Y9;0d zZ(;+_yjYfRrTJ3kH}I1Kc!8;qQ|+Z!YhShX^0zjl4AcKmprCH@+{ zcGTQon@^|G!Hq3*LP|HFafX{mInNL!zsDyXru*>$zxj5Ew+qU=3wbfjUBNvK(al3H zU`OqK(&9UV3jB64kGthj0yj8cbx;p=i(?&AUM_>)`kDMbSrXR}YiglD{By}Sk#&RM z_Pq$V`!F9gWT0KyK#^5(feQ|`mVQ@tHn`VYpgvuHrD8u&*37^vWQET~YvM%xJ;(Y6 z&T=-AMY-+Y&y@0sXv-s*0< zHB#36=)7YZeTgp>5|(*4r??^P-Lp@Hsg!T|0(?o6Waxy*5;p^!4}ZjF9^Mi)Z~u0G zblPUOlf5$M^SyUekiNI2Xrn&KKc;dD9t-ImkHbSs@Kpn|NlCT!iJtxtG70)FEv)uv_bap8rOr;l=+4 znN`QMYnCA++ZuJWv2K3V!KZw zFQDYZpQlx_{mYDJ`?LTZ&uK$xU;dFSWcL#aG89j$wa4UFZ{^|Zw_{^zI$&2L^v z=K|>_T`>wn1umUN++EgI^h7JW5u0MmR1)B0rV$?L_ArSQdp_$MBY!c=@KZaUVM|-< zr~^|0>bs9xTSxfv!+pK7n|0!E`~TA3QYY+>mNuvpo2tM7KH75UyN%oZpCgssMrMA( zeh)eyDq@NHmHOvHQ8LYAcH_|FnAP?LSu@=_mQ;#N7R)7YqOSK4vaTu2K$it&8>LZ9 zN1Xv@`J5`HgNR58ovrr;!;D_J)8kUOIbA#-c}RL?f}u8gT~H2bA%{b_t@ahUIT#Hz z-!E^x{=4F}XAr5qg*ATyf%tmY-oIXx`=x=U5C*4-NCAl zuw zdmEGKD&|4f{hLjJ9Wv9o)Oy8YNM+XB73@p z^KB(mzSD*``x$H$hcC81*x8&*k)vAsi?4JcX|0Ic;$s?-^4MjwF2Tx;p;N=cBoCU3 z?Hka3IUdAf$QA_v~#MoMp0Z1(efZ@}Mn9 zH^ptXsoXUUGMA}JP}%gd9T!wq?5dxOTT<~UE$N9ur%NjdHlz7J@mQwnlLQ*(1~_!K zgrhqx@!4nGv<`PXFwGuDQM9h=1(5nkoxg-@@1s;04z*h}e?%zW&sYQIEu5{yKg#{a z1wafGjn>X}W2BOa6XpN-35ZMX3m*tO5D{Vc?6PpEw){{WWa?htfp$eq4@kLq!-W2( zvIH?q^5e%`#l|$GmY}EXqR6fGRkV4P;Y)Ro(w4uTp;brLSlvMclfQmE)yZzk)Z^XU%^J>vFNCXwfmtixV{A zGiu}Sf~&s*0ZIKC;E@{d_i|r7M#?6m#?KsHM!!j=JZuo~F8BamcFd3)pJfR>kEDi9 zt%tfoqx`B@jfOE5=usd#WbV~t3uG;VoK`Fmm3RYn@V+%yLAKo8;*mG zBATAzI^`Z%>dTo0C)JDzEN2SVvUxiM?3}-qrDg0;TUYDa5CalTuBLpPb#nH5taaCIj zX(@;6Mx_tW)PLvE;pr194sO-9tlBH0_*~G2+9aD*cFtuv)QArqZMk{Y6kvJ;g-cSL zg)>#hRc_Y+_Q0s!iEmuOd=3TV&1LaubxS;9eXUHq#5)x78X@tAPXc69sw z@5z4yy0EU*eoOC|i`{yIddh{7aS1WBdzt3CG(10Y6{Nwe6`40Q?)z9KadJx;;81~| zaN^|m7`f5-D31!Gu%N&hE#$LIYd$6g`1y%qwL=>2(uW>EYi!=da`!Q&-wdrpVEI32 zYHtZcOEDMn8U^1pc_h?VPxaTZrU&YE=ZXW#F65X zl{n7L01!g#Tl2p?R`u@a{DaVbN4v+p7|$|=Z9XD`;yfRv;Jt4%yp^b zouHAfuU(o@m7U*F_sUl?VzaxnW~?GA?*>-6p{%K8RizNCJa0Oywvk7zQMQoAS$M-D zWBfu%9VdqMtCaTdDLVX|si=I{-H~NS>~Z0F1lZS1b2GgR_(Myt9VM>^W!AXqW$y%k zwp@Ta`s2|mPc^k{T5pX^awnRz8*~~235`L8zN(?MI2@mba-P+*%o5~q|53t31sO-9 zB!*(t%ar!}X4OZ}kU>*OB&k!cE7gjp--W{M@G@F^3+3;6u-i#-NV@=k9vlvG2bU=Y z_o9Vnm86eis1^vHAan?iU7B9yhS)ZCJ9g5qzN>6Fb)m(w+BWdX?^r<1xxrHGm?G0~ zr=7iW&`Sr}M&ooC{ae}_Fz*eR4hrz?z2EskyR6A;>fF*IXv{ZLC**}DG(dxJrGMMi zCo|lQILV1Iic)roZh?)PHIUx>0WQ6#2|~Tx3sySt6w$hUMhzqE$2H?m`%@H%x4?K--B;ANn^25StvwZq>0 zFMqoig_2iTE7pQCK6`x>cRuUT4UYxf+2Yt*r2U2k+4TlDSx1T`Z#*Y>YYWf+ zu}gc4Pqx|e@UK(!;BINH#>Z#=85oVoL?O^ywda4y6yw|e!8>u=(*NQad&~ccPJZ!| z{|ht86RsTT*bLT1{BLAs^S@va6Mp?S;KbwuUh@7kcqS%j_eRNo*AaT75a&~lo^VYa z_{^Ems#qxynD@-G=C{~0oBtw;C;RM4LOT1e2PdYT3IR-5#&ZrO&-bs6!34}ic2ZZh zp|byqLJOOjxXk{33dQwbWvDTXd2QFr3fHu?kd?poN7wW)SiVDl`yuiw%gW1OPXCQr zh%Z<55D;yS9hKnq{J?NpV@!hG;Ahkqs<)eDXwlG6$S-N7wVZPm>|i&mE7I)q&2H7Q z2iUqPmC;R|nM2L(-K@hG#3P!iFhg+FvcffqagZqON}QxuMIt)t%f1r?{KlEm4phnH zdZ599h1Tvukh30L4iaX$J@J}ob;y)TmX``7%nT+_nzjr1L)!3GnI?1%FF)f&^+mlx zPDa@GBmf#8 z2s$GMvs{Mq6vJDVq#$7~L39RZj*2R3KKL`Jbd99E&KB&|AKwN`a_X%-v&Vn5Loz?t9q!X#l^Gx9RL8Ep4<=zBtO9;<{eOH}T1 zluq=;a;W(y`?zt`QY?b0B^TfA7a?=^^n<<=l=ExI?FlXT45GnaM<2+_zvRtXLUPpDRwz=q4M-N z@85Av3=o3)v+~_^n#P7rk~6~*JZf*o=~oHddqLo?>8W*)vgb+)wbTww(H%I{C! zdctPKWo>Cz{-6x-u6}4DfDAZn7hqPCGFCt1VKxRf`wULiYA=7iD$=B?^4-Sj`nQ}k znalOtg%4!y+CE^2ahyJsVa`8*eEvIkg)gPr4!s-DPggA+eU5FM_YU5VbBSi<+Blv_ zOX4lNIaKZbW*fU)cu7ue%92suVDlNeGdk(ZhpjqzpybK%QBnRfIXbcRQ7LMQ zvYUh2Wgc0LLo8W_z?_2S_tfKkbS48yYmM+DlHJzzVliI19 zxw3ROp5&5hOdS1UlH;};y>{qAA*U*oe>fXWk`eUqn>&SHA{YhlAoQo_UJpEV)`Il7 z&044E6;3yOAWOS7#|$?Z z?8ZnmUINUCR8dW&?}w`5$R-wL0R?A>I-LuZnRk8;<>eq+TT4BB7TVDJHvn6*Uu zEWYu_;+RK~uEkPLNx>k!rsI0OX{)4Y3_8eZC3vs8=Ey0hV}i2yU}G(H=jDDZ*7M7k z&lQma^fhsR9nXyf8k{Mk-Yr5O*`48*s1nW$Xb}irE`JOmi5XmJ*U@CTR<)HRL%1T* znS8gIHd;>W=(IdP>vxL@%BUy2#+4H$;4uzXGSBMv{pso~h`Yl9-PYnQRC`{IL9wLf z1H1WTw7YkBZV?-&zk?NvEDvT2(AeW9%+GgQTNn~1LN;TG%MDqIrlHFHM_S~je8WT8 z5AFZ(5w@&cR$U9NACDEBLwOP;ZauYke?o;lq>7)zFp-lSI1?`Yp7p_LvwGe?3&VE! z?o1!nj+%gi!Jg$!4bB-2*FGIj$oje-w73hO{L$qhj5HEonBZk%s71>s_QUrLRTdcn*CmCS`jOw1N3aipzBZhRcM#a!rTb3~8iS{#uSfWRxz{7)5usWMdG46_A~7>@PMc9TNR zg}s3;7BYCHAZYNsS;lNkgmBOvNM-35uh`*J{EabZj9Aoi&c zS>}*YQZ*E3+$&ki)#0%cY~g!niw``rvR{bJoZUCZYs|UpTuh~yfdbnviCfqq5~5d$(gcGcm!!dcI+T!Ha=>0uiCcbhK-oVQJ9+4QCn5b*0BpS0s z*2z5j!z6`O@OHw?(gCm1VrplBv_pg9Vd$riH`tdGBUcZ)*OL)V`g?^gxLBvZ^AP8P zBz&I&1Ni*$ZI`ACm%Le=G{O;{=gtY9g+S1y=HpcNfCsP-@JlpTH})v zs5ck7uuxMCK8jkoE~*XFmlNj_E>LL+3H*NS+cC(GBFC6+m|8v#xP%<7k+iZm;(;B? zoHSL!Ek_3S?Y8pqH>ZbM-X5YE8m6`YTk6?cXQ>EdPSD0yl$UR#N4F+Z>Z+29FJ2FE ze&i-hy-;9WyO}yDtVzuduwF!$cFRp!n;Td;-VadSy6tPdm{MkCXsB@5aQ_Id5XF`J$k1{LwOZsM z?vFAg5jQHTOl*QXuvlN)$G$WBrUg5v#puf7j{xEPVZv{_3S~K$CbY7^&TBw&;Wr>Y zQ+Zrvf4TB;)8XFIaE%9;ZZ^)m>uRRe$ORZ8*imr2VfsTG1G(M59qPBb9e06Vjkpw7 zVXc*v11Ys0bpwz4qWdxV5R7#hDZr8|f@m)+83+#!D*j$5wY4)zCutwO)&HZRYFOTiW(`XvCRRPM=BM0hr< z*2XI%`G|!ZE1XEB8|>$9!XD^l?A9XOlFbz>{lWV~eUTF}ILd_dWT^aec?j(VWfot{ zQ)o!dIi9##OioFA)&Jbwx9F?3VeMHzLxt>?S2M=sLB2{& zZY{#ikj2a}Hx{0$>gy<&iLgJTZf5L!>8bfhl8`ycxpfiksIkwb?&ZsY8{6@zE@3EO zO?~F;iOsnx+4eEbcj_m#??fRQ*?Oc7V+jXERVQz3~i|O52 zs&JBXuxP=DR-kcSnvF4k#B|r1%p*0fP58eK*SgjHW*%zT?O6>}3MJewHH3+THuK-b zF`gyzN-5iJV4dE6CB&FtL!ZlgY4ES#lvR*(0w@%7Xz;!T8O_razXhC9oz+ucuP z#l&RJQoX9V^c=cWUAUQ%k=B+8jbMfh6sBMse zi4s4op!;XnP6wMhh_|dDg!5qft{L3oeJO%fPnquhBEWL$PkzCGBwi7SXDA4(bw)Y~ zRCuA?Af)}BYIGX#?o6th_&Z|;KQnMXp?(|`HWr}5CPNJC zr<-p;Od{Od3VKwui`XTaXUuxbz$MZG!cU}fnT0VksZaVENmFm(Hf(Z&>N`EVcUXY% z)Fec~jSLkGkwh0H5%%nopcymHCI50g8`whS!^&y}kAN7iKA| z{on>n4{ms{-!QmbW_B4nL9dE6Q_uutMlL>pO%Y$g$IP=VHRaBF6fvnaPNnsiC7`DI z2#Ln^hl-ougfco}`IlO_k_C_wfjf(=9BzUIdAdYh=!c^W#(pn;8XG8Hi zPT~8xHw#5qZpU>YVfdzldY3apHR#rW4B=D(_Py=KyeZYIMmhCHyfztyJ@xWAwaC3U zw1vpj0fWhW@P4ylq2AN9n*(3!#ZiyLEho$LQ<-_{vAJ~VX<|=qX)cDp0j&q>v~eXgjTh=Qbt*GVzNNq zy1h}rNC!xzxi=en3-<#v1QcUd7uvAcBzL71?+q=O-jejwjYN`Ui6ODceRWlZ+ZtDx`BLdFzp5|MLyRyD7 zTj;%~lf?;+ zPeg+JzJP8!0{E01-3%1+_ZF8?@`s8&a25IDbw!-HA=8luD#Vm)t_UtCpC*|H%`vLo zk6moOldFv6I|&0cx8Q!=hBY z)`grH>Nk@}pF9$e87Hg`JJwMCY~!#{Pf!2OFBh|JROG9 zBEqb5R55G5y_i0&aiFKp`|x-qUJln$|1Oq=!*4C7Z_eFtB8ZDZnua?RKHAgS$ z6gZ?so#io<>>j{}9YPVRVWD3oZPT>!)BjV$xHK(=P;UB;^Wb)HMO+%&ISyNHbFUk< z$?`Ku|Ge_;q@euNR8N$aSRVcR%D4iFb>DpEwVea0Mq@H^eB$5^#wd}vjWSP)qxNnLI~fbJNV4N z?87h;=4V{@f>^N4yx#JJ=-SU@M~|S+TPy3E%eDx3a8AbOUgxw{;}p`~7KZ!RSoEI^}FBD?!95tcKfd$G^7 zckk`Bq~ZX#AITUn?O~>>T=+a~7W+Nse-7thy8f19q|B_6@8aO&1$t^$=pJO>X>zX( zs1I9+===Fux9HbYNcNfQl=RO`5z$Xh*sntKHRDufUIT~hR+o_0A$FNWxCx;%tF~4H z@@cPMIBj&wrMBr@^UpKBn%{x`Y8+WU0bhY0JI;?(fa;FoP?1P*hM>b!9o!>u0&ay)!10}I%f>sU-9mi zNTIy!lXNUU_|;SOG3I6+)mUW)tV*zxc%bO5S`MJf~O+<+vXEw~;!s{X6 zf|dvs$DXLR+lz^sY>?Acp4A>d*qz($dog&)IpI!)_YfNmu~b^)(Y$+0aNy7fwUm=X zE5RO+0krYEH3|!1*(%=cLs)O3(KD3c^pM>?ZAAi5r1C6-^Oc?oW3Xc)2*KFJhxJC~ z&Mv7kz7MS=1Dd}@-7oq2d+b0K>TWWiSnue#pAV5x5{%wjZijQ%tz#K09O0)|$K7BWK=3*5xFr#>T{-O5e_rpIKe8_Q&Yob+O&{b#$1vA*0+tYPn z^PCv`aklYm>IXfU0h^*kK(1p})>=!|ntwuGZEePh>LONZ3MJXN8@LpJ%-Qx!v;Ye# zCiITfXeJdT+n1;v8S-{z9bIu+fo3Zk$a5+$jet?5fP-i_?D|oZ3y!o z3i0J%46}j|&$^WXum@e+mK%Fvt-^dOMQALB$@F2Q*HjxM$BW5hnY~t&n_47X=bc-? z9!S^G!5Kh3fVcy1YW^0dL~HvDn1qAPe>$)zpXP&g-;;A%uY99=0EaDailNK#D&xyD z^Q(I>EW&P5SGkqrVBxRTZY!rFBulCDU#gEGd#@q`HjpQ1~e>g!tlHs($_DP zc(PBpW0wTrVMCqqHOci1-V~+7pI6LKo?kwH?Qrv-TIsqaq~x{9D9zN&mQszn7Gw^7qphuY&x^_(EU|onQ9+6xzy3#J*4&4Ha)L;9wx9yfP z*ipzrWvRBmETLIV-lGayW`Sw`olff`W6yWPhg_D6r?A?t`?+7sS>v&LRDJF+w4h*$ za~XQcY5nhMnt_koDcoQ_PR@PoXD>QL1V+}{y^vk5-&E!BXVuym$;$Enu=k#EO=esB zFdjy%$c!BjQ4tZ4B2~H-q!%etqay?YgwP>Cf(`!@TgR4>wdMqJ$l_X4Lm@d)iA{olK(&G)+Q5#UuczD$&yOfGeOVDw%lxnMKC2 zr1dOQRj-OeEYQS6bZeqJ5jY+*_BSb838tg~Zpn^<3aietzVNJ7#xnUCeqE-8;%ZO@ z>}du~dmoUAa=_}t1<1!Nq%>n!0w-a5wF-sYb1i87gfXOtDH#LXFvX1X9g&l>^VI5S z_^?pb2*=yny+7|Nr0$2RO#2jDQQbb+*I0vpa8Z-xOL=?;R7J%@al*RFy5MD~JwB`& zGb?j=Ap6M+J_+PE=|or52fee1cBph(RY>;?{mX|hf6fuP*l>1< z7Q0=uHgpFe+n@*5<^4@(=JhkT)9?fhn`^1Xd<~lF1sz#W+}zO0=PWrc*DIAwE-wa+ z_+f=-F3XL+f^-J2`8YZvAf3L0NxVdwRRm*SfpHK~YRq9J8FPmM4?w1w^5zK&kbQZr zp&k#)A6b%xyuYrw*B*B__8 zCh2v-wYk92o`V1AWv(apf^Ov1cJK%T=8F($WffDty>Lc?GqNA-hxhAR?Rw1RIA?CAIAKa%L z;W*~O(6|W&wJFhcO^fQlCtT60h=vpAd!P0F#{b;|RyUO_6+|DTp1k5PuU#dIoY$`n z>gH8hq4}s(j9&`%UBCqrMK)@tQT31otrCJp11?4FS*N^>9TK4yS34<7a4-bra)@@^ zR@Xzv^PerT1mdQW(WirwtlCZNaeLMK+`P5lj(Zu#OV(OsEH$Nz+H%vS= z)Swy^z5fy{g*^-FY}=Kad^6RL@qDX31_%?&?&#a`5ZS(DbfnQiuJ=eyF;fPiD=E|W z(kQ-BEoa@T<}3^;&9FBxWn{JLt_@zq6_f7*J7yzvRw7+hq(C8weheyU>T#JLaby!Y zffYc3BRyRHcu}XF6CjJC{aY@KrQ>QI3YDMkay7oDaV8s4({(XN%93EGpPeM2GZe~g zny=p_H}X||I5Fc;6YI~|^b4$tioLU8hVB zF~F{ltTu$R>0|Sedk;ZBm$pJ%@=xsTna_YO%)6Le*tM5fIa|c+nE&c&did8VuWvZLr_;1=&yeich?9r+{X z4m#J1{Fe$p*1f>-Wfq5%?An|QO_T@vzZpzh!j&*ZgI9H4$wsf_DoB=#)=6F|dZ~Qc zT4zc1a?_4PWu9IDvr`m2^tFKLdG(RV(f%wqlF~MQnOYp-&2#^NdNf}zdc+*z)+wX| z0-9fe6vt&^rAwV>x&`7+lnw7A(p=P*Syj1SW$0Z^wlBl{h)71STr=G|xW}QKl(-KC zu6)fmGSx}S2h7?{7nq^wQM-lmsg9b#TqWhzv;A31(Ak&Pnqkm2Tl=yG@rnz#^L1Ui zT~q%gn8!oB496@oI$xe0InxPB(wV>am)>}`0eCaj+P~>s;%|U$;g_MpXfT5UN|RP1 zJq#Ywyv)zlI=0@`e;*fE7TSJ2-!Ty_(vLs9+Kf9Z?J(^=*%OjJrJb=hn2QlZibpks z_PH`uZ;$P1%kZ+BJ>4}F^mNE9V2aw2(-2Cm(l|JK{m3r#!%R=*73emv3+cVe9Z*BJI4G*ZZK9#_5Sj9i2RayK7dv&&}pKu_;Q*y9IAL(FwE`qAjI; zt60uf=0@*|4F3@&>5x{(Nyn<>H*Mb_kb)PFMcv$%vgBre!X!O$v^A->K2VB%j>5Cvdu)wsEXoq26ZJj= zs;ET#X*VT4jQG!9I#Dmg@jAAM}?cq1V-G~g)+IXr zoX%^lJ+Lw@1M^}~v20()nr&u7p2zivQ$y|3H<&pM_Fj0~X&I*4IK)sieyg83mr=$9 z{2y%gy7URBa#+!@d-Rww3!$B>S#0WvQxt_)bb7hllzDX)|10g5;p2@48oQ?Er^sZH#DR!PUL<|}sF zv1Y=bjd3gAZPadD-9-jv#)8k;lsVDCHkFoJZyHi+T;a^f3tG%}zXjv&k&bJWvnVYI z)*oN$^+P(^)b{r5L}0=nEQa6L{IfWyJ5jA8HWkc&d&jdB3|$j1mjk7ZHU4^8`(DYO zXW+}s$PzgxoteIKHslfa*}R5NL=<=&bm3Sd2KywBPXw8N$s|nPia*R&>8|;pvT*O> z1aX)@MxI;D%m3*(h%HvkUir!y_#0r5qq`sCVtpoXRbaG~TvZ z4v^)ae`?xFq)fIYl?>zR)O8g-#}8Mti28sB(iE0-Q}vK@f0LjvzqPW)caYon?ew{u zirkPJiOCFNMMZydL-^CgIqCRxA1kfPh`!223Ob-06L4Zozq3DXj@HJfpc;;kcomIR93A`V0y1x+?v7~5A$sAoB z=dS>lOcL|iK*7*oD~T0*nX+CZm~-lMa%~{);E#AL2Suy!udX%xcrAn3S-sUc|5hwt z@ck1oQ|X*kfLOLzj;+7e#>kLo?W;Y#?HS2Dw_5KQt}7?xyOiEk>w9;kn6@NT9x+fC_bVz;d#0&fo!P3)(k@S-%>-Ft%WZQrB9G>bdjR6-c z`wb3uUU>$-r&N+XnB?nbP5bi5#G82Gs-V!OOnr{4UgdvkcIfLb5|JtQ#9N(7*C8mNklFoYLu3Y-T#So=?6Oc6Y6FG% zy>gA7F(+kw<*1h>THuh6#AlFmPwfu&I3SSBPnCB*+mhAe90yorcYo)f&sYHDo zfqE#?fWPN#MV(|7y9I@i~3gVmYMKAK;x+0ZWBF!Z2xB;4V(4-!dQ^#Zwy0f`<@ zfOV7Sv7Om#2=d#LeV)v@J{kY<$WueF_0G;J1V(TJAKsm=Y@);c%aM^j6RnB&PV!sUwP*SC+gB1i zsqtey@clqaih2gPW9G?R1=3=}b~(R@dM{f<&DZ&(JSd>gYOfeT6)?OuS070GxII)} z%l#BGtlZw(%k4BK0)D9o+=Al@9RZ~9t-yq_X4>2;%KfRkZ4t!Jo5u%ZL4Iqtk61EJQ8ZXxRc&- z>mR%Me5b8rljRSX_pzI(DkUxBhqqGy?Yc%gO=PMS9)_INmMh*8x-Vl0~ zRO0IRu+=nJV}B_1a}X2*Sz*Y=8Q_MAa2tk$eotmdmu@9lYGEH3y!tGRU0Mbax(+{h1Z zkYp>z*F!c9_&iA4&6$#Zq&#l`aI~!Gvr-D56*@RAARl9lipZZV=qi)gESy% zON_?L^-1|%21J5qzz4`q0~MbNQksTp*TrayH)^I@NvXOH3oVY@j9H}I)|~BX4ERyn zo)N?Cj(61jG2wPiSOsN)EK1l;@1MHQHCmEZ8LI!q)08^-4KxJB(o)=De>T-hX}X%k zq(l1Q1^b9Os<$uIERy}?wucs{14kV{9;$Df_dx!3f1#Sj-tKtu!p{wzvue`#MWnWs zUv6Mk^%vX}cGUbnO@!9RxP|&PzgkI}Q`KEAIP?I7+)6_9R*ZTzx@K#sZ43fjaA-%s z(8%p8Q4P#(&)R*b2dzb4lo}h|Un(}EebUtf+_TrV+fDEISR>zFy83bj4WleHOg5rk znCTq@R#tdL7zOy~wi$%2U;PxZ08Y0>mN0K2-(mOO(RBVU>ej9Ve2BdVG_P>KUb3$a zDJu)+M!XN{zwsv;W&b;o;2FM69a{-4 zeuM^WoUJ@5t~B_f=um@Y&Oe^o2811eItmc9hAklM(Usn#a$Ps~GyYV6|72+Ct8Q%| zfRv>*$E}?2y9xlwVr5ckA@K4+oS4gzT}EXd4HFFv_-SVc5R{mKJlWm4qnaJ){_r;f zMX``0;kfEiWQe<7+nHU?W}d(^e}ylKW+m3x%6lPci^)$oCIL^TW@$B2Gl{g#I8Zjk}AYxsNr_2cP&+~5pnKGErL zf7gNku_V`e&WO65f2yAGUf07V9p@X1SY$1pFj6Gqb~o$X0ax^%OuvLXyjJDyKFtm= z9krz7|2fP+{o)+2^RAMFQ-i4U<&*^}g?3hTQHMP7%747VNip=lhcV!~)e!cqCD@Q96nT6VW@riDdl0_bY0*d!FW;JSnuk^LEEv z1oQu1v8CW~2|nNS&I`2;h+w=MS{%Ubr^6S%JdIL|fgS-~ZMUw&BX}-`ueefy4tE90 zc`tG80eV1I{%^DX7{d332QXPsnbl9?#}4Ih?NjBR6CJt=e7!s);Z^fziTbHxWiP|~34}#mm>-(YhgAIsUI_yWiW^k+b{n@1QZmes3Im}U@ zv3h~^yd2Ksc3^i8EZsAQFl0j5Lj+6UZBA{v*GOoZt6W3fmq;!H7LF@Ohj&Ekvp^5^ zEiGu?gMp#uWeU*-w}x)G$^adubaW|MZksB=brG%IY4ZS_HI>?>-6{x(9a4Bmr({Ep z5z*I&Kv6TeJFeR!-z5XTnZ|kR8mS%&bpBApdO#mNBX?Fkk};hc066pu9+?Fm(O(#N4g8WuD&$e#l0%AG5Uo!e);-zp|3STqS_R=|KN#r@M~=CDmoPm=g7 zC>)wP-S1;$;Oc-+AQM|&dA?cqT0{+!-5Tk?W0cjT+!+egV7&7ESuaq5(<2*0ATG-W zfEga7AY1P3xM%H1!|WS2FNnsAohgk1JB|}Z-~>nYZ&K7pSOj$9`}U!Li@Rkxt*u^% zjqv*!PE%k#?pguN({j>H_1BFr&at)Z@_6X6sAy;rw|Uh7`PT7ZUXt@u%fP-HJ5f<> zA!Cb|s-L{~QrFzx2|JbkX-?ULF+nV^u#MAN=*S7INA?;oaC5aUHvGxrd;>5Q!J1rs zc%P5D(=q~6-{_k+;zQXCdvV4cXA$sQe?baNv5zq4$P`sQt$(?pEq~LXl@Ql~04gmD z;8*41W6|;56y;3L$z(sEGE##PZu2<$Tv$i~#&ZJMT&NpV+EIe?Ps5$jhvrl?u?`TE zpLSr@;OABY0D3We06j%^G+Gqt+$^k{d?jT+EW7A1r%oRVl69D}sGq~#r7W`rv@Ls+ z8#<(JKnyM@^*jWbqX9%!TULlUyD&YmF<5w0#d=K0r}K5^TeJorcD4 zmQ!%i_LVD4ROt!6HZD-6@(!5Z&TEPWa@nJf_~E40Sy$SLxqoGf{jqz{A^etF=l)$L z!3ca^9;A^OL%*q7w3v}H*^$=~mFCTpcVmb5o~ZlPbKTeV z$Ky0vsls>Dd_&~yt7fdWe&zk{(K=or}Wh5?V$1!l~!-WLQ z?dp&tUEknqGLsI-OQ!G-A`-?JZ81?Xy#bZJM-?cmouu$}KV<36({2k9?X_qWexhDy=$>DOPrj|o@>9g!8CrAw zu}jt3r}SI^u7o+0E!66o;vLod&h5@;RJ?|q`Nd%GNf=d)V={`4vAL|U@s_-|-zhp_!cQ6B>7_>#!8?BDg^NXX24e(-c!p>?P)&6X8q>(?Tv!e~`B0di zpP;Qn?bf}idb+#@{FdliM0O6Zmm*JZ)E2(N4}DAa2^vV;mtQlfe9RHT-qU+56%5#} z{_B+z*!tyU`{Lm;SD5`(QvVD%&Gj zn+o8@M(z#zatv-H(++nF@FxPpmCbavD$-TxU4tE0@BzOL2(`tLZQgi;9aosg`%!!) z&AJXCXQzZeDSm25)!B`%$00?+XUJjS&0Wv9BpXz|l$br!AkuUrKrQ~otG0XvmQs_g zNt)?2^pHW%n0(gMfdGAUl9?ZRpXYH#mOw&fV%Uc_`PlEPE*6PwzWQi!pA{;SSAh+`xC zhh<=Lcj`tE8ZFIMWTe$?NrOt`Iu3E1ysHHgN`-GLya$SWu-85>b5#0XDxx&T>F+G5 zSf^T*s}5ADXgR~9(CT+bfrtn2yUVqdF{L3rrMM3JVut-KRqWc}snOhLgn~b#XRB8! zPT|dL&=Car@*>NjpKBm7s|c{Oaia2V-C7>ESGJXqu{y0@zwr8B{I`Wr347l~Dlh*k zaG1lQyn)wE2iZLz+W8~rT2i7~Sj_sWM>;tgFZ#nQ?BC~oGeVU=M2Yw4k>@VwDu>Ae zpOk_rJchXEcG~oeC(H<49q*oVwzG7Yn+elKF;?L=+Q*!Q7U`Nty{J~56;=szpH8O` z};Dg=dySWTU-)b^B}_W&8Oq zQP)Z@Z|HM^|BK(ywZfI=XEt7s*i z4w-;k)kY)Qg)in|#XkzI>8NiXz$`CaNfBtgSan>VDJTa6fN_P~!g+;`wz&3(se$)n zEoO;pU+M~BGgy|M8crCGnzPikn*BtzpuB4jmNal2yWqr~TADUyX?C_ZvJ$LCHP<&2 zw#4GiG3=0;rJKSYG^<$vw>{!-c#slUm(gObMac6!{}Ao2h%zG0L~lv=t(RqC4xzvH zkrYkqwC-qL87+u66SZo9HPX{>vhuVO*e~xTi7S!jD6H5{eH zl_v}L_P|0*^ zWCvyF@o-M?sM-EB`scA&e884V=Cbzj?7;2^4vKy0!A^Y=y{gXtVp}-K1Xx#r`70eP zb+1DQhx~9Cib#pkW3de_qzlC+eI{sS=pl6iSSvs#Y3^2DH$|I`eP85I1Ggw2?OT|W zuBl$@CSt3mNhd(Fo8kn6#>%OwHv1xcSEVG5nw;`^wk}Uwz`t}zFY2v>)6*dfMO-n^ zGNjt8lweoPXnd}1W57I+BsNO!&dehMoPtGln;5}j*p$_{JH^R$Lm!G}iyd7K)~67# z9%GI6wYq(=HR(XU-T-kabRyrD$||+c*`SojNnF?arRVUgJ>5cu>%aHSRR-=>`z)sX zSWfP8a&0nJN1E%;BCo(NWydQBgd*>MRH9214n?>psacAp zd~@@utuI&HUfCHdUF(g(@4R=Ny2s3PsSD94b(+W-JjqokQi^bDNr2o#*<;xK+FBb$ z9}7AH?8rEW`XqOZ1yoXLe}A_P2=5!=YF@0Vu-6?l1%fZ>zOUQ^|8pYplDMXgh3HXM zNmvPkdGzYoy7n-UfSNNhoI3$R&=O4j4BwsrDJG)%6W&3H544L&P2z+apEV#so}&Ch zUAI*#?zvn~{$_DZ?yd%{e8+kUEG4H0MmR2_A&2sVG94cHg^SgqMppYV(m#TknicZ%Ehq^Z)dkl7tF7u8X_unm+!&BEH9Me+n0eT-UXYJ2w;c zFP`i5e}_>?iSS;-oP+s5Sk~|QW-jTkpe<8jjs);YSSr2?*>Vg!d4eZX3rJWyKL#RR zgEkZyCK>GbOJNn zL8qTX7#{<$e%!F;PoIKC?f~IE0By{gJM`BQGE9)3Hb|bB_AuG@AARtT4?l*;_H$2H ze&qB8=v+Qc3)h&qw%uyJ+pPJ6TJUEB{dK+%N~h@Iuxr(BQScODg7{~;+y7d|tA7Iv z;~0ar$U9?tWp`f?Z~;@EI4tLl2UdsMGXHLBsyX2w4fi|%_rRM3r?n}5T&}8X>tt`l z=SKJSSsU;voo>807GUYv6ukE){wFa4_#v=6Jo(jm4>=rW^Ye8|f^+QHm~%hWg4$I7 zAD_c{M2T)ZIBsglu8kVK<3qpGlS~_;QybAFJMenW)v4x5_ZUdB`Dnm~R?Hd(qbL6P zFRBW_A2WL8(o>oe771(Pa8=ekeuh|0uC&xRi&gxaQsu9kSsVN9h(F-UyBq&L+_B5y3+$p9GxEop%B1nt_K*Yj zE$TXUCnfyP|Dcpet~wwk;_zS!*ziB3M*)JCtG;p%*Z!Z6V1%Z9v5x1F1*Nr-}s>HOSz?uz7b6m!N ze&jziW?v}U)gO_vvH$^f=Z5CDA&Em)8T_>i4X!N+fW24e(NM8_<=`W1d*wZ{HgR-t z4QU>%T)yazUmg)K_Jtb{MXMM5khzllt!;{cR4Q0-W)Y;*&RKkY=-4EIQ2qwG-k0IW zU`{utYT@gGxeRP7Vzq4WkII(utiVr7#LhEez2xERo{PN5-w8$yt=g=Go=;U8x5hu1 zMaZL`xnz_Xyr81HQ)%mGuM+~U+siz{B%0_cl9=F-?$e`H-MQvvfgYx$RBjc&Fe0an zy&Cn2tx=rYU;$$nC^Ou+?sQipdnir*)cdLj z_+n4HAJQpgObZo@{x}xa#;dZbUbr7BaPo|5=THVPHqB$F1e}3%30xMdW{mcb`n|4( zLLHe#e#3X8co`=^rSA^ybDC|cV30h9jpC{*yFTwMm}rdm_IPqL&U%FhBLmOZi&(i; zpgA>Pbxo^quR#1EiK4S>qxI17IdNHsWhD2LzsAg;Im6nbV<`dbF>M?*f7pW(S6ls^ ze@_~DOmoR%D@ha;hzde&F4g57KjPlJa@hfHW*5rY6Oy|NEfe~5c zbT6LE5SlLBd~hM$H!22O(F{<#UoR9yHOFc-7^_}4$jhlK7TuYP8kfyzYbX-xP0EvbJCYgk;K}m(*^pD9p zM2q3{e)eJScB)W8Qt$EPML|bM^2(2t-_^N?NTSB;Z zhR;K4YtOpD+_B=?Tz_jseMgkisG0K`O%CLyIy}lcxOZ$6X+JA%oF{_!De_Lc=Rz41 z7sbAHI^p zJ1jBPZ=edA4594fAAA5!fE|R~Q2#+NN13W4tA430Q2?f({H11g!DszTjGx^nOyxI8 z*HLC8pZqEAoO?=!e5_na`@rL@h>>%bhcj}$JH;Vpxo`JnAV2l9U2;evkXRz9+BV7C zOgLF@T<=U!Hpy`%yPo+~l(9pUeMh0x19CA~+4w#Qg!rC(X}x}BrRi~};keN0xzADf z=D<~-UN3cQcUPt*P0uir&ABL^m$RFv{mvJ&h z8^|SgTc*1l>5W#pZyj1FVmVqcnz}e=NsRC7SWT&)Fp8Md%{LB^Un8hixZ{hvb_I`> zK4)%N=prv$HK7p7XeJzj7O|{?2fz=vLyI^y>Bt&V*!ThaZH9!(+i}%9yc?SVg6k(L zx5OjL10kQN(pN&mGAtn(W>}RQLMXnilzbF%@*-nnt9wjda}+!`c5rpMX|kzmocSyMT?5W?VM$%z zLanD%p`u^ZZ2Gq!6^cQn&{-6iBumeGkmbYSI&2_LapH3D$6H_mUysMYxb7+*sKL0; z-`iKR<9xX`%}O5f$BuYinWg-p|3xCXv75uayb+6@= zB7kvLb2ae|6DP3IzEHt9>d8oE(((KidQ_CxzoZ!Q+;P_j@rhA#j|L_J;%ePAWh`Q~y~qst&BTNY0Wk(DE7qgY7(uVe3Cn zk#*T8O=ckO2`!xT8P& zsW~idW*D8dHQ6t4$cHF73Jco;kX1J}?S+%6OYc+%7ezC?5?pnh1=>-w$+c~%k+Ywz zUaCmI*UY z@cU>`aCaJI+J@_KlKJ6QoVRLFZvp#-J75r`odgUDEbTu};_oc4zle^UvKit;-LOB7 zN9{HXV=dJcD(&zx&83(mJEzf;$4;i}J*Pydw(jng0?C~m>N+}B42j)%R*`QDbRSEs zp$ZwnHElNWsFwuPgmioBp}0enb76LSrzW?(TY6rm_FIcrTq=9sH67Hg-CO;`BL@0# zSc^H<1Kd$>-`76tv@LEG(sSafhGB{}Iy4I2yV^3Y;Q5-n^Re68A;dgO0O&gE9y)mEVOPFtQ2&O%TqaY0t_%O5ZNl7flm_OV}Mp%2Ji4!SE#$T39du!@OB@o(Q@nzXb(dh+m zn()2&ZZo@(WEzn=if9q4YSmUxW$8s3D}(fd#Sy`PqgHJALMg|QVY zH;8r!08Qd#QrVb(=g78woyp{LPzq4V2rYhD(QC)Zqg$xjoJDLwHr|v@%%!@o9hkaD zG;uLWiUq}%hesNiV7K_QVIFpBYO-#WH3A4b=0TrslTnKZUI&_4k z3E5wyRNs@)te0yL#_iSWKvgwXyiKXHAz;_gGR#8^@9EtheQ__bx%hRN=$LT0mf z4D4!(6$%$DT@7ry6>RvEPk`XvkFB>To(V{myS&%+^Y1V-{okm46*z7M);csxEUmCI z;ZBG~R^s1S0=ic_m7hv&{Pjyp&hP`<*3ijJXkJ#uS|ez#FJfet=7G$zBWg?b; zsNCbSuXSj-UhCgI$Utp|cvP+c-xsC+nQ)`dr2hB?Klh;w#mD^g4GEfa#6U++iS#2v8OS?x-lWxfMlNLCL&BX>wnrJ!| z;fe76Im{N$vr0}}3;FGSw^WQ-Ub#(Cd|oE~P*(YT^h578P?@}$C1D}W&GNv9Dm<4zy> z`BsMK%|b;3Vxv66+m#bcL+`=zlm0cLU_bD$c`R^hvpcJ@$lz z2|Qq;{t@&7e9=FrC;p7(|DLg!)%GK_uNl}yR`6u{{$<#H9KFcL5tbxx9aU zj@^Ir%YRUU046_PXJfozh8`p=f48;-}CZcb+M};|En#3)E;&}#ea>(e{JP| zU4`9)@Lx~qN7CfKp3?u%o)V)Szla|MkV0}r=5jCJ104Z|mSjOK#*%)tjd8f@&Z2r6 z(tB0F!LcYEcQ{{gS2WLwq|&6`1JLFRIiUbCOqw8joS|c+#HTmHBU zo;Xh226>UO161U9f7jgwjGi>24@5p1X@@FmN#)qS0(EANc{YPjsuX&c6eSIp_-X&3?OriV&^+WPJt zcxGqhfw`n8JFqqEMsjtT|N4ONBX0YWnDkj6$j$Xm63~fX;hXuhXN~8so+BD8lfzVO zRj5YuA11- zNwuPAz<4A36IwN4cxEaxq}`>k%pXor;*ET$>*cNwuW|0O$GA# zoQ}*T^N5c1yFjPG?ltE`pb8{~&sny~&Y3Bt;SyK1Z;F_YA7z9()yiEp(F0}*{B>0s zn$~&uF8XE9p%3vB7kXdkWf-lp9aJOZC;Tn{erfZ5V8VBF6e@3^P|*-!PoCc9jG{)f zU;aFLdcbrG)n6$c!syciSsl4c=1)7;Fr>fFTcQ$)_0k1)cD>F6dvnv(zM&$YUwGtP zot;I9fvRS>115(}SM@Z|Je%b{%S?h%0Wm;iEs|~3<*qt~8c?2;N9WRW6a9C)`GDR` z6X0GAl2o1ME01cIab!kJnLQ&$uHmv9F zsiDS|2(qXC@p3k-9@o{6+_ddN7F>4B6Q$*B)nVk@-}cT2E34@JK>z{@SBYU>*Y{ROz zc{SKOLBkv;_UOBPu3?rHV}`TQTl>j}-YUMfU8j7A!m50~MUSzd7{*sc?JmyK{n`y3 zR0}2i@o;~5Om!jzxw#zBaa=U~vxP?1w1sf*QfoH*<)rl>IaDTK+f;iRiqT{=XS1DB z!G)(n$a9WWe6-Rx2?AwuKb1yhK_nzue;s^-wo8l_RVp7iKF|~(KbL0?ycy85yL(Tw zP`gx`HzaV!HD76|->`1&FfQ4dc*Ss10t;|KVJm)XeCfYxfYGcRI8F|p&uQXBxpC7P z?H#YJcS&I8Bl~xlO_!pm9q6Z8bT>WJcWCvGRTlS^4^F zBhE-}b7;P|0_pb}!U=Akjzom$4-C}$lCK%MGQ%k+uM9uP2#&yNu}L~YeYc$aqXi@a)V~!G5{8B_vH(<_V$F4 zJvL4pzDe0<>V9=5S!v0{&R3*Ct5&&hf-y+Hkf8Rxr3~*jpdYxg687K%u>9iVkM;__ zrXDkH`D)gq9S_j^G?g>Gje94_CO?&#$DWz=z-yW>+g#^ z&FP}nRhKTwqEZFQME^c?tthYzi4(V#auxzvkCIbKJ`*f~8VOV;5hVt$HlM`ctf;4` zuhrfK)WUo#S3!$c)YfK4NLzhwHSH5srS9H!K zAIM8UmOOR8Rrxlv@>7c%`Rof!-+j0XdSgag1=MIhn$5TgkD1dp2-)(d4RQ$; zDqHO{EG5C#naUDid=wNNzo)J8`k)i%b67&s#+$s#y0pR)z^FG7^=R6 zBnyhH6cf^^(5|-;hp52(ueayrScnS>Ncf}SA#EKGyUs6p<|~Ih|5Po7_iKeY2^;yX zdIs;wtE3FP(T{swp&4q9ly)e0RLHn{Sr{!bhc36vM>0Ft~j`J23R&KtuoOr0QYqpx7^03@cUIf1lI1cZkxG36EIGV)Fj2 zbFTG-eLa?PqWxp#YSg78HR3RIN*%ihW6ObK^GrfQ@h{ds8{5w(nCcJ)O_fiez=AZU zX!ycaKBDu>D4U zubd1YdE(u^`z*lMe7A?yI;y`4$(p@+s*Y74W8n?nj%(?C8lrYOf2-s;#obm{+JmlW ztoV;NA+k+y?by+H5j2=2Pn7ovw+b)VD#IL2zDB$&P*MFlrB|^d6eK^AtOhC)?;;t# zB{F)BjyL}y-b7LwjBtI^>p7qz`!>p#h^sY~Ozq2^8gzU_28BAKv681-yYs94wQsde z!@qu+;qI6QROfYu!jF|@EL+s|y<_n|n`1paUtT^rl>`}O{vkuF~`k-_}m^ zhg2g*Q(jPMxY zMELOc!|#yM@cx7rMN&cm(oGauF~|Vb(-b}G%7B4fU2hTg?FI))7dFCgmV4AHdMr%Y zZ)dn3OVNvZ_ux8l(Vpqe5r0^_2no&bhOhd5%Xfu-5ezxd-_Rehgu@rMC^(bzzxdN8 zs`FZ2!_ze8+lRN-)w9z;|1+v!}+) zod?3~98Lt=CA|I~z6f#=v>8RbpnokNBR;~b;M|SUhjtW@k z3PqB}1tUL(twOaPXCup=b4ej_-%mdmYJmdRYi*x8RX2HfF}AoB4x`2tjivLO+5c3Y zgP&0}?g~{DP%YD-aMZP#WVDKBg-i(VdMk#J7b!e^csbS}YAYuIa66KaD{$38fY@(Z z;qY6*{YH3xLbN*UxN0qClIvk_X+H_jC1DR&L(r_}MtKvhUa!t~N{b=msI$U&QkFRB@4Angkx6q)DUI9HQ%~_K%!NfxBn?#S-sq z(X%V3*>uOheaUM*rPHa+(`aE(jhfH5muCInvCp&?hopVN^#JtF?jq+zI+Q%jWOC;D z|L7f3fId~PwGOL!@2zzP2yu>1`XB$dM=ww6mJ?;zJHM%PT!0Sk4*<{R1#|4Kh0@gi zf@AM4#xr{v2qC_p%@4iArB8*;Fa+=LdOv-iSuh%&?=9l6^2z0YUF)QxxW1f z`jr)A_vua{ZZ4g&Aic)@jSR{-U62D*FL&2{6??nq%IwRb+7Z0{YoBE2LW(En^784Y z>Ivm(sui7!5{>Zi-`~UnIN#l?|G)OGGpxyMTh9zf7!LwEa}<$gLllHa2xI^O6@`(2 zhz;oqBoJDJC}0RM4kIchN(+!k6GM@vhTft?KqMhRq$Px)NRTE&C|Y7Rr%iHCFB`;(4$!%;AuwV&78%ta#>5;AGL1#fEiFe-%BhnE9pXm=N)2aN z)VZZM<(xkhGjRuI;j<$GEK`tJL8&bXr5*@WJm8p4dORqU3P@lAdah3mHl-1PA`B6_%uhTEGGOg8YSiIb8v?9x2?)1?sOMT z2Jk9NdELtJxa6hQ3uAg&?y=UsQ9|yQLIAp$6V~S+`mqEAfC$e3Xyf3F^(+H(vfH)e z24PLjfj9Ul2DSWfAA?LFUhEp55>gMiCBRO9fuQMIASDu`<>1$tmySIkW!o>m8<~b= zj%khPTLQJx!oloT)X}1odgeH~?iOw*An`fy;!M5GDq1W5l9JYM zpZJ4QT4O*DVd3A7P4wnv>uokPzyRSvqE1^JqCh8@ei$--a1=cXBSk+4`Y7eTe3*!y zGJC5ka!t%n*?K2IJK|H2^kXgK3$`AAls&Q?@@H_y8l!y&KBn++-yo8VxwnZ(>2~h{ z;QBcS-Hx%n9M>ERQO_MdI~HWuw{db~}Ob|sjspxX$y&wx(>JiXEJ_zzQi zpS8x&ikHHpujR?Xn;B|>2}9k5w?xtNMKC>`g^m&P8F*16E>qeVtXw*;I~>@3mkz=` zQ&+k?9^Lj8tV*bXNEW(ZB02Yw(-r-fRa!5=>{uG;iOy{niHP&mqvaPBznt>)lo@hl zJk75yd4Fu8$BqaCzrmajcE{dQ5Jesr+96ODI-LilaJ=)=s#_wY>sp)^!OCU7K8QU$ zKYiRlP3{P)CO^}k{AglNr~T3UgxXoCY)y8ZcIj<7EA`q1jkLPf%6+q0g9*4L6L)dZ z3CPoxFkKLG{juZxN7hPL>nZIhup7qSKZzY^39-o?Y$@LT;B=S8bu(<-pG znR#-kjPZN?4Vhs6uCc&nhBw74%v*3|Cagy@tE%S~rG@^S{{b)P=KD}7RuC@(drWvm z`f4HGQ)i#Egg$x0^>45zKwL+c9(&aXtI6^z^R&z2$XE8Dw(}=2 z!F!dR5rH3m9ox>LEt&azXbaxQ9CMLNgP=Qnm;;fc^fK9A)bs1|ligT;? z2iEOYuB7t@FImcany6}M1ty0e^ObyziuC9n)FD0a#Ny>q6+C=*qHIju5nJVhwzT$lMw>P<6px9AmPC=%GCr8 zW&KrsoCecch???Goom_%b|t`ZCR7DkUJ*tZRtQ<;9co8GZ^cFX8qiCii#9Cd%Reqj zR`3J}UKV>E;DKnJEJT^k<`}xq&?awr{!Lm3C|^owwyiko#d)#F=xO0D9K1*BYRKq; z1|jM=e+=jy{uQQvtK{^L9qqtQzbR`Tpx{Ayl@&Bk-ZD?FaC6C2BAHz}8pjm_$o{|K zW=H7T2!2M`j(3~LIkFKxy=5vCS=NaK1v12=KVwBHcl)|gwC;;nsB^SGV29YnGM%)o zmAnzyx7svhl8Ilp6}@9*l3m&aJw1ANW2MhuvyEt)frMzdKre!}s24Sh@iX?VVCGo@ zz(e-0Q5dQX;Kh zN4eOS(%v!iS+znx_@=>6>nqUz;|%dt|H;vbb}&9QF+L~N;h?&)#zp1zQQef-On)3o zuF!r2@2QJkDY>wItWM@Bo)kZ4+ChBtOtOgw@V~upd2R-%EJcDPzrI2?Kgz*TYVeFw z?`rZ^yd~qB$;LORZPR4(feha`1jUqg4$u`|R6qDuY+b^lUx29A&)9HC3IS-ybTBIk zSmX-#!b!|T5%za>?3Z~Mg8~G?)0t;M>rz)nde{amV9|y&T7>q1SlX@!GCuO)K7LQ@ zQXCn#wyRtr$SWpwtpl;}{$r}xbQDT7d}F^dp)&vzB(QqZ?b8^$7+^5L`I zfVst!Ab{mi7{%u=;XQ|54x4ps@weXz&@I(#A@PAGK5Ld^ftLC?Ne2e5_ff%WRuMe1 zdve%awyqk@b4?|k9@JK#mQlD52(?4UrLE@pCTbp>g|WWu^%ugPS4sFdj}KvCK2?>% z2U*2QVWm1o<7+CD~345JvaG>XujT9XP7fZ2Nok@T`!R)co8&q)a za*T4nOHKOI@cH{#tOxiVxwqyY1x6wX)1IX8n$j^{a;`u_RkwDCBwgVSirE#7&Lgpe z#9yzNhtV2{09DPD%fFfFomXm%KM@YRuxO8>XpPRFXC5XWoon43&{+ztxV8#{-&f6qKC&!_T9x9~JHENTVfLQ55V{KmJ@nnd z=L-bedCj9!<68|G3YwkLQu&CqkRTxGJe^s(2YcMM;+0*aAuSzBdy|9P?4GRBpUvTm z^v3F<#k3TZYkh>~w9kwi%Z){Z_o4lnp4+sb|7-3sA#TuIqe)+32zhJ2K%kW>rK-T5Hqe1;}j*hDWZ;T7X zAaly5t9R-H4yKHohoX0RN{V8K3lk~4!x^@Aa%QI^pmfRV_vCW(7D3oRhy>5I6Mqe1 zZ)`$Rc^7J+xq6BG=E-xDkhPOXGVh;1hYk0@$gjYeL!se%xX@3B(r_2@%MnfY7{02f z#hn0u0QxC>X@lNvKQfz|=gZS+b{kc(19xH$*cxk-;ItuxJKTH_`HG8hguOSuJwzh0 z4O(ibxDDU>m-m8axOVDNFKPdvoH>F88o}qyHC{&L2c$RE~gr7wR@z}YsWggPYoHM zw=yy4ztp{tufvcrA-3Ph{r-RoFt9Sput<4m2+r@!@jUmtwKEZ(f0Sj6S#`hTeZ*K) zodND`e*+9o0bQ?-g{($c`fkN-Wi58h+T6Q}U&}T&05^Ewei1$VwSkEU!}!X?y;XE3 z7IM#hyEHGXs1Y__{~KNd>J5O#>)%EUlqds@ZbTr=Eu`r|F;V_kOvv>9A3uZx(of39 z{P&Lo>MTCK3>EpF+K7vEztWaY;D@6Yvukb&TPVnF~MUw4@DLer};$XX&2=;aeH z{^{q;x$_&b06^3mS5zExPH&V$;?jTPkwddqgHZO0Wtd;$!7}Vj<*Lgy|314X3W+jPv+<~M_TyKpxjNsE%i&oUtHcuFg~uj8El!=C3LwX2-wdY< zn9id#2ag1v2Tz`^{!6X8 zb8kx$t%JrLwyE=iseQD_q%4Sdm^V`w0t)74Kj+##yf5`>vb$lCmK#^Z1gH-FE?BsQ zEV?j199;}8^jl@t_>@hsCv<(@OSI3KFE`Yn_LAq_i2>*mt{i33n@{uLUeQRxsX6;K z6_01;sGZkOSuJksd z4%XPN1`s)57q}5<8?o-`pakmq?biLvSm;>#il24OzNWB5Xcf0-;1N;kOA4=47a87h ze=1Y|-Y82k2ZF_fa(^B&uuvy{uLqUqr1*Qm<*~OcSh6FHGJH=je1TMbmp*zNVGUpT ziR$PU6lLKPs>{yVqpcv<6!r#X75VTn476lih}0x9PF&uPx->m9imgvSe-oM3%YUKy zP>`t6_mp#KA?a~mO*q=r*?ZZgnjW_3%5EYlL+Kjs>5At2j=ZZ=`exo4T~`R|U6|le z$&{A1Yr6R)ImeN-TLIcsfVWdj+d-bG@PWK_N8V3Nho16x>O@_Emwi?Y_ND;2a)3xm z3a#8}?LS#?9|yWh2-jCjlu7s>7I^3bUY8wMc8!lQIM)(mR#0BeW%K&eQY*%7VZ`ky z_hcTZu4HifOC)JVuq(yI(6!GTm}|8o^hyDGxTmSp`Xud#N%8{YpE}DP=#s*t$Uy@l zX&65Z-Jj4H*=i9Rm?GydwqvyA$W1i#aqCAGn%iq3p;z#zbUU~emEW3N`^DL z1ERE>tqo1#)1ZH$;Z>yz^8o)!aSo!4Ch_LbcXoyNOaJNjN@|)brvATu#2P3NK-mbi z{04-ce2G#V3i`4Ewgh&Ca-$U%f9&Fj k4*#=T{%`vK@LqxP%#POrg`SHG!kF;%sWT^wPF(r(-&SdmQUCw| literal 0 HcmV?d00001 diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/EditingFile.png b/Firmware_1.26b/Documentation/How To Contribute Pictures/EditingFile.png new file mode 100644 index 0000000000000000000000000000000000000000..73b30fdc566ae55e95f9f24563df42eed9c94db4 GIT binary patch literal 55394 zcmcG$2Ut_t+Aq#j$FVTNsG|ss5DjN8pEq7|^ovtb+4}6m?`Pe}N9R;jSVE^0$9yga&C3vffc%0+l7nh5 zgr92*i)^1amNYy>vxC^_HT6-AwIir^2O7=&doOmw%tM+gcc1;<`TIvb+i$q<-kp2u zr3=nH*Na_odf8#$S6hxn+`dVOK7H=T3ywaou6liLzVS%K_uti4eWk0m`-Fv~>t_?p zaJrybJ7;=v7MtG2xsfUm4z2Oqw=JTjrPJMZe_|5qIA$M4{NZ?awZq`knM(YL;O&2% zTI1C4jidb?-4J;U@J1EmOIhmDAYpXDvN?~!$eq;nK^tDBB2(craa0Gg=~JWEyho<@ zwZ$*e89B0%oFc5^B}D8{i_x7k=wW)Gc;0XAmg10LFS0yIkqT@9!9M%cEMPD6)T%#~ z>)%h~0A-vS`LuviyC}Uyt3V4O(sGfI15pI#`J!gal5jIT0Y#S18|28U#3qUv2@@%O zOS5Eu{;8+tk-@>i`!Nw!?pW!Jejhxl;bK+_To?WRiuMr&`b}9rgJOGO|wGCN+b#m!tXYTFld%pP{a|$U$7BV>#anTO}^+*u7)CCECaNmNO_AHFld9dWOptw(x%Qe>Bq^kBWoXqd&?AV%kmQg zk%p24DlRN zp~J%}xQe`FO{m`1$d)~_$@V*JKMz!oAtE-k{i+L0(>1kKS4GB+D6g7L+3j4s$m$c| zGj&HiDkIkd6(N%aacS4j=vR#-nqF9oi!MT~O)!%eKdtf&-&d;)b^M=hRoP`e+o2v( z5kxTyC@`LOk_FDvpf71@0~_*SQeF?i$(LB=H74k#O`ToGI$fEBb44KH8AEZdp^jca z1MkukIfa|}uH-GaQNsIesflk}mA&*Gs>HkNH2>;dc3lF56?SX3U^JW)ST;-jNd7O) z?=qlg)o~&E(34DcgoK2^Q`b9_7~v41AAm&5=wD7}BIWu#eWZLFkdY%Na|^cR?#~=p z_4g?2{@n3?eUammE___b%lY9^Y-|{94b`RyZkvnuqRz4{Dz|!t>x=Xo4@T{h2vL%V zyCuAm2--3-PP+xAJ1#5%3<{m@*B(UNsNPla0ikf&~ zur*KA&McRS%TtntXE}KmJr)wy$ubS@k?dqj02%T4wJEtj7E9Vv0^BP}8IxNkyg*GC z1aiRL)UC0lxQ3DipsB)-7R#9g8~4R^G0})lsz3LeYJxbXX=Y>;wO&>5#fO==gvO*5+0dgUYHg0-c zO}BQo#yTPc>PAacKLq{lA?%lxAhS22N1AGS531RdPUM>$=GI=Zd2OGekwm+N$_Q(@ zMIF^Qn=nm-6y^f)>cJH$`RtJtM{IN70Kb8<+_+#eN(PB~fvQEI^#%i7w$>aKgR!_7 zwNRId{uXeF!Jy))dgw`iyyQ$S!RPf}s1vvdlAyrt^ z!BeG(IC#uD5)sh}N#)bb8=(r3rED8usF+4rng!&!9)I9+Kcw~{>BL2yn2@7_qGgSZ z{mT@Tmuq^@@R8o-s7Mg+g{zv={kpM26y!9L9Dw9Bv#+6>c5{aKvCNB%YT>S&h{89k00ZLbdvEm}?+TD#X+ z47})-6I#2;+0e*FL3`vyf8C-oq1o8!C%1yaikRxoECao@ygcp zr?BRSonf;grrM!_smw zKG*b42D=p*u?Xkq`nr8f>Pv=`=(SMEJ$T^PaH!aX4f)0dF)29xzSa?A>?M^xS3vpSy^!N35J_A}hv( z;|Z(z_PAwmpHA>5!yKQr!+$rm>$rWB9lT#91spyJP+w4c@LM{zT5yDaLbTnNQ8H%d+) z$PKTJy5>|h8tQ)hK?@|W_5$eIarW+L&6`*0=!u^u^t{b$qo(V^&Djr`ylu|SJrP`M zXqU?o{v5knf{rW8CPro)qVtVqZ|qLNDzT;D2$`o2S@AFhTPx1*>yM@6Jc%I+i40bq z&Nh7NqA6Lm7i}8SGHEGEVJI%=I~^$q;Xro8Ue3NU>>PY*j5S6U9^D~1AoulKl2dUN zhwpc0n|)mHCmA(rc*N3nLYN32(F?-q1BGe%?W70!EQi!*%aYG8$UIow`@5^Rl3KT%w@ct1W~S~LdXH)?FX$fB zjmq7siKjPkwPq{Io;CNFN|&gAT(_lXgX{P+d*ZvBZw)6GMG<1W%X5CsyCi(MGlAlf z+^)q>nHnNwvXNixq3LAB?CJ*OtB)&%;e9Hop_0`3E_we4F}xHXtGzPi0F@2vq3Gpz zeBCC-vy#8K>z{a@@+&VadTW`6p-fy^IT?EEMfKV#)=TO!aKYj3)BW{p?05sU4!ZsfTEx?0@iFzuqF zjjBTR>!~lrVYNgER~|=o{eS?Q*CUcmTUZxBXHbrWx9`u@cAFo^TI9jPw5v@wgR1xIfTx7#7(^uCY(fbyx7LV5yn0)!rVl{UGK;{YiTD5#!(lt1wE+`LveXAl_=F zm?9&q0-i`OYUU8HM4l1+VJ&w47Dvmo*|qefBVy+5AEgx2ej@#3bX}>e{SlHk2He3! z*~PCG7yI4iQtH2b4Bz@wD(B<`=xjX#9(`QM-+?cP@@?x!IXKV>lMq`$u$f95OowlRtiIrZ)dvd3SJ-0vf=Bc z+3!A|$9Nk3qhRh>SRW5kQhgD*9hjb9Orjl}OoFoew(3k~bd8y75LT@~Y~^v#~M zx9H=ND1jl~cGu2@KdpJO<>q|tR3nJ?i|~d?>b@_Qm_rwk=lYupZ+X&DEhPTcd3Hcv zF+d&{PS4KDWm6;?D&3%$P^V8qUl^W11xAOnh_~+8Glk(@1(rP}b%nLC^*slNSB5dK zW7@TMreH%;hld)pNT|?ZVnEnV68ncAbQY2W5qo;-lzNrIll}eDH-AEC1QTznIj(GwlAiK}G>0>@ohHgXr z-iv3De(B$kOkSy0P*>U!x}TL=d_TTy56SF8UkTk~;B{*7Xm1_joXyIsMxt->L*jxs zbk&-p89KVOa`0vO82@=gmc^R;3&s&%@Y=RrjTNDl%ps2Dq^!8`*Oc?1 zA99|yX5BP@+UvSm^p%8+dA8Np*Ip!Mn6AnAQA*O*-w&ySu5;`@L= zv)!njyDhD{4~|ilYq-sQb)zuh;%G&1=($CI@qT`3_Fd227xxq^t(S*`yGw&O7fpyjYwhv}@_xMHTK8ztXnC>hYjhV*YCAJuHzF5qIT*de9$1Rv zyi8HBe$CXdVt4(NivOabsN~PnsPTq?0pRP1^e`lWFNyC{ee7hm@mrL7WMNNa&y-|% zL61T8g>;AqcS%Vl%i;!U%uv7%gXz-)viyc_&uH21onIf|7-udT4u{L@V{g~Z`qfVC zTeBt|M7eThXUBN>%(#GkAx#veQ)9^cY*Z7gX&2h0O-YqRBFyj`OW_y5_{DLqZ%f6)XETrRc_+7eg)a|8jl$5>>zAf1^ zTduo;{&@xx^q{g;!}>&wJv3i==4XIh%M|{J`Q0I`=^k*MknUeVrmQ{m?#@)ggRQQW z#H^IjlP?E=G`8k*1`EDnmh$58#b~|}|2qJDdw+HuPMgPurayowPRSa&+=6LOO}9dk z4xV-2-?PcKX3+g$3jSgR>O%eU@euBhx6qgRzMZd5MzauYve=)oEi!Z8-yZnwG_nZ0 z(pMV$b!~Vf+SFp)bb@;)CS7Kv zV)L%m{LiCxz=fVt%wlqhKV-#}ampweeS{T7h}-Wye0tVSN&GL~!&K}NjdfRPv~O4g z8iERb(ss2iAn!}PKVU!b!6j4W9lLvql$ZBN3C`E+I5p&?Z{QWTnw$T+Z>_vvc9bT* zIK>Fd-V#XjMhd>GJFXEEa~S-=KE3w&8!{L~3zIPLZC@Vy?(aXMn6(x<%KhIiKdn@@ zZ$2)6OTV>K#aNru0`^f}2#EgxDw>ajik5m1+F-|Al|psaW+f$u)bK~G$ViSc=6GG- zSomXpa7EzGFPzlkWBllmkFRB$e|+kX^TEKkSYg}Utd?dtI5MeybOLDUsjN}AA5qYbEDlK*6RH3ik<-63N9_yt3M4&ka-dn%q8%S$ZZ2>>% zrC#jjH-MaiQWq$@4o7yR_SFuBHToq6gcSlQ33o(Po0${N?|kzA`d}3PT=! zSqAd%Y@C%`7E7a61PkeOCiz{-o4dvcty*JtGrw!hl!WD;Bb*>V(shI=T2Ldbf;K|d_zceJUa!SQ z{jz|l$CR5}W4mb!>Be{PqS1TmEotnB`wEEzHP7GRz1^#>W}AP&nZF!Dxy*#CqjG{^+nyM0r1!RkaTG`dtb!$9b5F{7stu{-HWs{?Db9sN*FVK-x^6USojVhRsy+8 z#R<&CThtqHZIhQfK;GK6mw%S$H>V2gk|%`gJ@YEMytJQxX@#K~mbBKWyPb?@H5 zG2q=?9N>#}5o6Ch2bR#MJ~s$^*AO?RyV1vTe%{A&yog{afSAWDtUYVE`bXI3CYD~I zvyb^*w={TSfX^EvMe>+%1eDmmd^2V4K_Mg4g!*VwwwQ!ZqVNN`#WLHMtRcQ?dFpf* z3iaN!6#j8R4)wgGW86`1&CGxz%Y^>;=XC4Iv=s_ZAZ5%l=0lJ$#n|PQA!Kn8-Uh#ytM0_E^L7oJ#qqzny_p!$bdTC2M?cgd~QeS zzu(XZ3mwHaZ}$jWr`oncBrf?E^%?JXDmAK?FmyvHj;z z5ADN9Z{Ov{FJD;0utI`aapcCcEs&&_2TiuOw5}F`paKX5o|)>gSlldG&u*2yD`;JM z-P)S0Xia(l4&4H^q&BVZ_{GH z;LF758PLnf4CqFg*i3uKQx67N3oCLZDc0Nw5!jdPk}vDp1$ugY*icz%$A}4rBdnnx zEaaI%)~}F$IN?`#`Z)AY(0$$bRGh_$nQX;))$dH@lk`pSLIB0@Y7%%gMNJP#0DjO4 zDW9$Hm0lOs?+1w|*t4>7Q1csrgkx%tAik7v_3GI2(JH*ukUs(}w0=IU z^XYJfZ%6!v!hXm6nYjUWQvYV=&Y-lH?TS|}CM7exTP5WFR2DM6q{Uz()bft_Rjod+ z)8B(h(Q1Unv2|zN&6Y%uHjDgnaY8MQ7jZnbWqcn3cQF}(zSWjln%I-&gY^jpm?f&c z*gruBl5Xr(!&ms>5aI_29CgNpdO}tYS?lgKm)z;VfuP;41g+iF4&L6_+;_Df!srDM zT8(`ezBT4jFx1QmN-0ySQt}AdYP4C|pqOMg#U32D^~{f)`m3SR_zS!)jA;m{*oy=~Vd zelMk)W1hug+?Q(E2kFcQ7uj7U!kZ3dz5^^+G`i`mKRxlX&`98f$h=rDK0= zgj*KzzWyY6@y>)Z(Xr6uXuH4}khmNyH3jBhVxvzQ)*Dm^dM?I7!)momL(CuaSuC~& z?(6oIX%^S>%Le`WdE!Jp|7w?5yM$hPH>DHty41(u` zy%Zbk=zQYVJhpL(G(N9fjn!9#v(ygoPST$6VF58IqBR%2*lWEoa+Qm2U^Q#nXP=4B+R5U2gPx%hRSt}tb0mbh zGjT%6APciO%oTm&j-~bO>U1rq_KR|qnBWVssmGDj@VSSi{i*q7qzH9f;@A8NGnm_` zm?UHA9geKvg1XReh;k?}C{R#S+Kc-*&A&f zW@UmC7_C{sf2{{CaSGiiv`bpU)zUl`*O5&VZa8r+zQyUp8#L?)#D4sbajbV5U)=k+ z^==gVvTV^TVY=K_T(vGAPK)BMIW?jOtVKbVoRy85ksR}9gWxT?o?KE{z4M1GS3nqm zY{~X{RaZ2x?w7&bpeS6fwnhd+k8{GEVo8y~z-`B+D4nx~<}H2RF7 zD0kO|p}IYTltLd`fM+}_^vyq%u~aSTz%d-kPhM7_k2<}w%s4BVxMe&q9xy#Fu;gUM zup+M`lUFFWE7Txlfl>%3QJuD1Uk_K7=)Fu?aGxX=wE_LN?v5u;P=rrx;ZU_2HA}%b zJZaI+hYU!_i?*jNksR|LCY(5N$m~q$jeTbPit>KiaxKuZ$QPC3-+gPD?ieaw;xj;`odoX^G40J@?@d<(n2 z5x^tc&rXd(r0II|uF#D|Jz}C_8DUJ`iqFM~5og)9C6t<+p(63Lpcaw};~nG|pL+~~ zf1w0d>_mhY^Ll>CiSHL@Pp-suZ0VC(b&~7+!{SFAX@e~lleg(NyCMzA z9>oBE_uh(-g|@KgR{LkYmR9=P3$Vfr=2Q!Axv~E|iQjtcBl~3|wOMI$cc0df*M!HnU6+_>evZoMr%P`^Z|8h&s3YSLg9)c>Iy;ml$ac=@XU-jD2w z_GB}|bAbooVRhG6-GWEZf>#RTHn+x7hU8D#Xmv}O29;a)Hj;Ha1M4qD;`l<-X#UE?j9adORd}vBlB> zvnRy4>6PAzLMBP6x%}|N@#G#56w$o27~A*w^r$jD;)$&h*CmxyDP0O^(S!Z0ubt9b zSr*B3y<^^>`UrW0lu})bk=!jCGUgB!eIcI_;L&!=9roUqBH?$evU9v!sp4==E3XV_ zPl0&Sgr*Oe#1?DgI#QDs`^W~S25xIjU_ITaJwyO0+~8OM|eTE@BHPb@V1$gOk? zTe4S@%S~LvwTG+!q4o(yyinSlRy}d~Bsqg=qgM`*4)Ny76bE-zgF~45q;c+Ane^bB z!GMI2cOAG(d3cMbylB2oj>>JEqhsKFQ^oD&d9i7vIY_8C$kkG{+LO=IK)I+ED7gyXmfl(^aT9X~D>vx>5{>%b$x1mMwP;(G;AH(?3Z_kjOTQ;MNo`Q$>X`fGMmX+SIcW* zgx+ay@m8}4tjy_l~4gd?V0cIJ{yq{4iE_SK! z@1qsvBG=oc5k>F?rMkU+;*m&1(Hq^rm&k3wFUJ*j;B5SvAoxT_VP41GjyuntvZ81U zY}bazMUFBVM{ESNU=_(L=YPQ{Oyt+Z0~oP~+cF@;tXMMX7(Thc-@y@8`iB$LGRRP& zbh*LryU1>kmKyYj1Ks ze`iPzT;5P~ZkYGXA%{uXpgN#k-)c` zD|kFSTI-%~LRgKnSHhzX+&T9JdhUjmYi-n9r-Py8wFY!gWkMM191IkvNP3Kb)u)-< zrRG4Hp_xCTrKr4Y-i6S+nVBFQ0aaP^9!)KXU zN(o{TCuSn{*PO8nH~%q7YRT4e!QC7O-M<9!D8`ya`!3QCP!lFhOZrg!^bw2REFaMo zXzmG0V%xn69JVT2yfN$@t2mXx zgdkU4(6Rj)jKXNz`7lWD3RH<_8%t}&%VmYkg?Ud9R|+ zWM_tHQI7%Ug|o8Ip^hJ#l8oJjC%ywGdkXVAHi`FKe)Con;FVR2In^nnW(oYKaloR+ z(yV%tRnV0DnZBN9Dt}VlY}z}wJZW*#I|pbHOP5e90$G1ir<;92*-)LvuQRhN-Ijo2 zg44|wkLfPWQ=PhcW}gm8(sf~yf(hU3ylO9FyLnI=5%;8nbI%^jKEo8ePb8zIlH z!X-E1wxR<1SD@PM_shpoh00X&R$6UPOGS?7@%%mc9lwJ-5*)pN5H2lOMRu?MzS%~l zyF&k+v!N7p&orv7y+HtuB+msLpi&97i%wURX6Gel#46*)|nF~P1h^q%yU;_u4 ziZ__kbo6{TgC=>YZB7r&|8kz5Ho?mGcX-zdrTZH3Bl7Uk&3&$3P+?}WiIUSKV_MF* zo0+-3QM?acZ(AJ%W-|E#>k+C(5{+4d>QfxADs|OL@m?q980OL=CC85lQ5ED(fgjSh z#`mu%^@u(2G>@%UZx9V>51Z=bFU`K+t_)jLDHl(;UgyepUyKz!U>GL~0fdi3>cTAg1_T#u=GQ7yEZtoU$4oD8?&flHE zU6ocGaLFwjz5;q;_yX@+op96?0dsy7ci(Te)KO`` zTudnK9)yA(@8mtdTrSj#T;71cs8kaq19~#wrJQDv^ZD&_ygo8F=g#+yP%g`c%d!n= z&04ybF1D7w8#Grsje)?sMe_u~lOjAgU5Rh%PA_|he0 zK&AC+Knt$Rr8ns1n)vzB#EI0^_HRX%N7R(D53}!;h#akZ&5E0@B9@N+!VY_gvqbJc*-AW`yEH;afjkxmMVs(33{i50-cN~@f3=rycV zJ=q|H%%D3!aL{jF5&!aEI{})HSStEn&qee#Y%Z6fJj4W(LG+=UIlKy=uCFSQ)rPZ0;;ru)c z>Qw6d+!ZD=zbM*14-ZQ2?03(+*p~`bEBwOD<{R$4wTSL0V2AE) zL4~Q~Eh^4{pqW>3sE0fy0xmAX<@!(*hhzaR%4}H82R_P7NgMU6$vv8X`OUT9f(Kc4 zPK3!e#UE#eE$hX-Wz}yFtAt&T0MeM)g zcq3(mnJfUCVjl6Jn#%!Db=KmJ9&^#b%V~j#FOfx8XLam$;Adv1HN-1AwnKsA)apK} z(b9|gXQw#INGb4oiLE#D@>}5-PB5p|%v4n_Ya&5{1RtWq^D(N27Yu5ZMNV36o&033fWh2 zQXWkivp^^c!*RVjD*YiUtKko>+8VsB<_M{={391CMOS=UDT${d_Pb7*?-iynbv+GQ z3D}k7H@pVLiS>{G7Nq-xsyi z)uxPW`KxB`idsevXEAL$&0xZf%rGy&gTFr)hlGes+)e8vTG(Ct9B?#l5e~_rJY)=* zcq%>5l)C9T(v%;*<+nz7s0D#Mzg~a$M2)Q_RP90T>HJv&m=P*DUeI$8>IYx5g9S5D zL{S`Kz_jG-e`$}oSK-S__c+)dz`QO>4$U7S8G)CR*$CXCTs1X{*Pc@wtO?Kne8RUI^`H(2DP zoSdMn83V7~*GD_kd0vUw#G+kQdZGg~1N2ZwoEd)U%pGZ3d?04Wp0(yHRArRAudFDg zaq}+Kfj^WH*py4hnK)gTfQL<(`9}Ania-%t>P(8A)DZV2ZzzQcSX$L0C;22LWu-j1 z90&56xV_+o+l9xX8y)YBb<}`1g%;rCqqg7voOoGjaUfdmxYmtMB|h7&G7cw4^P=mO zm4i5<7X;Xj*mesmT{eL$mdDJ2Rit7emcO+Mb8Z;7nxSE84;|Zn-rsvM*(ge|yCn^) zUGtpFw%Fd17Uh0&E26CRgyTEk^txTBDeIdQ!*R~0P^GI%^P~Gx zWY_~JIKJP^2kRV5D*8D;oQP72ddZ6t<28EJySkdRV|hH(!h6Zl!bh`O5;u1F9|GDZ^}I~ zkg>;pyyI3(z=UZ?%r^)t>Ni$Z^sQz2Ddq0K^`P<`Q61ldQ5b}YD6ck91}#?>LsrT= zNbFgg5Wr{k0&6JMWRCv=|2D@F8Y2i@Q5N#9-o3o9k*E5CJl~ht-U@Px4aYkx{SG>I zxctFbAqcMPRIJ%J#R*tE_@{BqXuvR^89F1Ge4VMZ4j(1|yB%(X&%2+v1tb-c=;v9T z$J>m*&IP@jYA9!&-=rB?w@ZmY&i*4=dKjkCoR&5#KCMj3UV8broa}$B)~amuz=(%# z{`k#rfB$)&(?~}x#yNjpP1iE~mpeaZYbXH@8h~T+k1k#2NG50PZu~vP`{l7x~Qrq5X|KCZC~BLkLAYDH){Bu z`yB~te}7BIg%kO{fDy>u@ZWBHnZexjJqWh(@1veNvhSX+%n-8f1QZHn?X4tfGN6$C ziiK;-<%wx+XvOfdx6)k^Rx^aOB@h45@17|G;eYSox1+bd(Ss?bD7E5s4?8$bI!a~= zq}`Cykfn7?hPL$0EORIIy}OZ8ohhi|3hcUh!n6�s6IP&IXR~q4*_jtySDX#$d(k zh;=Pssf6D?oEFmFRPxekizaxQkf{w*$kH)S+LX5a-v>ZjN(Dcl&URy5 z>_qtrC)ApV9kJBqPLXZE!UgRs%J(nTDx74mJ*3ygy=+B0w5z3KI_HtFw5-NVLy+u- znyC+`_&8b#L^o3A{Vh&Q-#KtjV-#&@SK0Fg7E@n7<%ODh#;FF&qd1jdc`e3;vZNg4 zB4_oab8w7< z?3F(ak6wZ&NS(JSUgu$jfsRT^Ym;2g5@};jAS2NO3OgPt zr@apBRjaHVJQ_ms3?pR=P-NrWQf2~r0qE`&>uIrsGI8WB>vjjE;2^Pyoo?$5sB6oE zfDBbsj?;aM2?Y=74Utld#8ikZsy0gZ--P7Ep?a~xPf8FkYD);>w_I9ehd-}tqMFB7 z4AWlKn=iddRh*G!AW^>TpxoQg;8%J^kv%T6sJzE%bouBbretv5JFlGqk@Vg^7q&h3 zyZq3T`xwJdLFW;vc2cU5Fy@XA0Inw03s?vnZ^7Z7$yls1;4?L?E!EJg5of5%jDRJi z+&#~gG`U_}lroLd_7W=Q$u$C5FA|9M2>x&CLg%*(Cb3A7CC=VJtDr6jq{YRu7hv$} z6|5&mT95GINKqcHY12ZvAyA>c4(HLN1sGp8HD7wfsqfU(OBAhOkC9rHc5=X=T7C!D zA&AAdVmF62D{~c*oRl8xyN&K{pEm_8o{IC&TTd898WFoSIPY0E{qP*IrJE^f&Y=$D zh?3ILc(I%)-SM9#0L5{@oSN{HT^DOBn1V+LDT$85$OPp@mzRf$bC>%%Or&iHxGLst zBku}lWre2@xhZ~cLLExpmBMk$wwPYx^K^(kI-eakgH1&BjS>eS!Q4edSh{JEe}78U zRiwWYVN6)ur?J$9RR|c}kmf^9K70r8I;$7^Eq1+8+XwP~%rfOa^C=v&8qPoDDIHf~N|R2GiSnOW} zEXQlh9@21f`3A5TwUQ&@sXpSu+d2PPxmAY-1GC^2D`1+os#KP1(T0=K)tpBj@+l;a zNL%sd^-V2)dX^6)6kT%hCO-h(o)$Mu+XWY ziJXm+EN1X1)m8t^Tq^C(_vQd0Xy?W^tTGg)%9%07%~gqJ)NX^M$=D1HgkqbLC))!% zHpp*^J1nKTfQ~?s2vi~@dzF7yjsZ)MIC~VQFz>(FC-3a{W-y3&h_?t4n**DWD0kTm zQT_#xgQZU1^q>OMylTu`qf)TCAl@dJ*Xp&V7w^%2*G`F^+kR7J!) z|3f^&>SqWs1LPX*G>#i^We5rDi_|{NQH*T?lA=+xq*OKh-_78cF}t_963`0@0k#Gr zWMRBe3rTX9glQz&Yhrz?W)cYP)m>>I??;Hbd0Y+1ed@e&Z`uNvHI4VH8r1n3QAxCV>A_dwubP@A~0*vgDYZ-NE~6vsKW)jQm(BW~3(v8VsHM7i6F`{nEWN z9N2%j&f9CnP?mJnk|$eV{Iw%a#a`#X3dsL6(s6JhM3Xg0en!mT!`_+9;kLo={@K_@ zp2Zx<{YPQ?FPpCYbHY-;J%e{n{}rM5BVnQttF$yH0)>+ZIk34ryy0&w$pm zYnkz}4+r()xP78OO1THMkyao3d~(}er@l3?rZf0K6E)Os`tI|K)=uJneRXr8?seb6 z*n*sRX|B?r|eHSDW}MW_$TR7W{SWQFmo5s>Zsc#!u&;liU1F_K^@k z`qvgkmFpjK2_HMN{{LLZ4*>e(@xR%^@a{$ivv!P75OKJqrYO5J_CeDmAnt7Oqcdmb zUCZX~^|QDoQEj3VZqG75Tm8UT4s^w)=oSOxI7xY$EM&QDIL>)~=Yg zi8F5cDP=tYcf7y4zTJ+tZ#H~bwB=)y7nf!_c(B?XYo02SQM`Ru^4LOR1f?857k^(b z_qA1tfu&K1+R?n0Vh_EWXPczTFIiG>qNYW(9+k!7@U*CSN$gew2>(^tQgTxV05tug3`m}TDl6l#wU}$ig zS7v7~jo?s9M&;_gcZgTnvt{;^aQx8wQVoyqJZ@x}c%27}Qp%3Tn;4Z@m$0V%#u4R? zrM+=qlzun(Y4Q%0P7nARVPuGMVg$Cn6{uyI4QiN8{W8=k+W3*)>#^+}Jga|f(%pRP z|4fGe#!^jaN-$%@_2RjOF>s$Tl%ruIjIz-G_23kf2m>r-m zguC>eOx-~(Fsjzg$H**YRYejtu9pdM`E$gghN*R-G4F_b6m}oGF9!c^p*nBH4K$d# zhZy!}jDF8>MK14w$V!;be>A)E<0LlcW*7TT9NZbv@)CkH!30C+6C=&@cje@XesBCL z57e{Y>|j*zV0#ctJ%OL>X=zp&bN}H=*tf)c^%ufz-Cg%JmfhQ=57S_~Xy0|Yxr-#W z3%9Y^!~`jN#a;J0=F(abbT>lSMQv^YcW+cd>sa8C@E5z+MqEnH6@j&Ypqs12d0HCh zma*HiE{u;-1B0(ImQlgXwe*dYa^#V$H|PIrm<7HQbvq>Icu*&T^Pd;?Z5)g%9}QQ} z%yk{IF%Cmmg#Wa7PA%+Y?iJFBQm1=$c#z-uu8{hmwwPLr5|D3E{3Z}M)9>Ni4ag$n zwrJ9=lFb7nV1p1z*i=KyK$>-}{tpjiLnsAz70KC!hc*nIkX=5JlT&cUc-}hF>5@y} z#I@Nck3Cs)<8+gc^L9yB)2P1HZ;;_yUd!tUCIL$Q@7|LVG`O5sy%}U+F=9U)$Q@T-i-b`lW&1T8)qk?KML_L zhI8jLm}dg+?7};!J7z7YC*&S1Wt2OOI(M`rE+6dMY6de?i|eH4&X??j(95FErP8SZ z(S8pX8z>WcA(BT~Vh44+-i5KVieKfLN9u7%bFS+%bF%Vt>a~y<7GB8hz~}o9 zHb3Sw^3odS2?h6Dqp-m|&b{LX^gX1LtqTQmGt9yMQAEAs{a~z^wP5em?moCXXXlOc zy08bb*6cM3W64PiQhTO*4QIfFp8bg~N&hTzKGD-U?@8Ye4 zs=3rZ*jAn{N2;?uf|Fx5-wb(cr}dFXR0{hq^!sWa{`5hK3;v_7`JZf+`x^|&E>y|` zBiO>b(V!q=+MgI+S^@;P4GuDjvU}13siRFwRB)vIho4lRt{ARJzx+6c=LzE-yx3`k z#m}XM07EZ6F~YhC7sd-Cm*Yh#a6R-YjT@;VdoW03{H0=FY|mhB&L!L_il*M{@0)S! z%4(j7u6?LZ89Z0_yyo*~H_H)sR?PU)58wZwqH_Ldv~oede-d0{;ZIMoo3>p@v>^r2 zneo=1>Q3)V-SSHc4sR^&2^i2HtOK8{Sb$r# z@=FjRD+@C7XJzP^$u+0qC)zJRyL6=V(_8+Dh(PzBUvWC^{=*vF? z%lXU~H}H)a+#{p^VO|wI&D1jv5q#sr)93&B^y3dBIJA-38R1VQL-9;5x{H?rhQD3P zF>Q>VM1KeBQzE{oD(*)vQL(p<4o;}YQOJJAjEL8MpQKqu<B{z$? zaLQXu;>2`;!~)pdcD8#MM zM<_?Dyu*e!^UR)$+RBSfLG9D}q&;8HB1(yv!D(?sVCQsP4VaS@XKq!3!^@zdwGU&B z%KQ6R%?8;qvMKT5Ju7~!8lAqli4!vP!fin?d}&3nZw?Ipb|pho$3icnH|A?&inlne zfM0m@OmITmnMd3Re+=aUk!5)`zFl@G|2q4NL)dv_SZJBcQs;qSu$6REJ{ullm4gZh zMP(~$GJ0&huuNcb=z5xfA6&*!?mV9D;C1q}<2wQ6 z9`6-MLQsEc5H41gHvFRmU6n2UaTJieJ0SNl@)ump{l3WwRg&L?8|y*8yWU{ zEbDn7FD~$>)8nn%-INM2bZdWrJTh8@XfM_mxl^AD6qzIEtOe^8ix*8o>6yDOEnj<@ zcJCcFiqelE85TlwB_?3UwLblbV5Dt7=D{Q~va;`|BbIW0GGz!-65R}l6qHgq}5ha9x_1H3Uhm<#VlDo$4LDoZWSX)0EiGF(;# z_ZEh(TVo#VQLG=hS}0tg{ShpEM}5iKOh!eUk4Ih)PzITzwL#s)$-x@hs)V5@iS6>} z674+5Ik=dLa=WW-1x_TmJp|;n#f2~B@rrJVejDd&VOiZmAl z_BUYY)wJP3yh2$ur=1=v3vQWoS35gkDh}eLB53=X(dQVLd;Ij(kVww|qU}4wn#$UC zo$6RdMi>hsFlqpmHh>gq84D=V1f-WJ-OvOCq=Y!5qcSuB=_P|85L%>!PGX@5p(rhq z08v5+5JDz_1k%q2e4TmU>zs34-*>)~UnrZMwbx$zSO%sj-hXN>nEFLe&tX018bi}jO8f6lGb9vAaa8u4qxnh!XVxD0j_ zN1Z+5HSolaePf2n?q3pbuvLARX;sq`!6;INha+`80Rr}1_IubKKR!ReQQ$XQi~Z-_ z7)-9=HDRgTEbyQ=&k!mop2Y_fb5owVs5wGu?kLC^vzXd?vpuaUH_ENQggu^O4ZgTVQ#gd*$IqrK@jU(UlYM>eg|~k<7Mr{&aBDMk zXa6Sc&u6)4)ef+PAIwz`MapVDe-;>ZqwJ|XL1uo<5o72@qaH=%+!m)0jVHxFP(%C$PQ?@$U%lH+ea_S4z`~;ZVz}_5ve#gBIqgHO zJPp2xLdL!_6BbH@rG*=w7iOHsGT7SA@v|E_%oB8Fl7EVPS|GepyyqiR3XAEFWUf9V zG0o7VHH3SG@}xk}zrTv~1J$}ZZWLn!Ch-dqg#?BHCxKT!B$1{SzwZ!M)YXev>yFQT zqJV3Ui!V57+PF1N>#kXk+PKye*!T@G7gOckuN zN$1F~A2S!^z>6dpVtx%WwDG<96sc?PTet~!ksJiUIXw<9d*V_{N|+$6J(E2e(>=eA zouNKFXe4fPBN_H!Fikx*N$TZasduqYbVb#Sd&d!u*AouWNJYXEbefQB_{-)hxRWqW zuhj60KsvbkaesODW7`LlokgvG(HqA3-$A~Edh-b;76E&gMf_~3o7jQuoaNP*@AN~_ zl|x7=b#m8_^Rr4pZ)rM_nU+g)*z2Wyr7O+F7}!GzD@&e7q*BnCT|Wx3gq;`a1wA{@ zc?sselM@e+rLq@DX++&Iu8bV`8wTqfPhBlWKXLm!wtpEOnuC~G3z~aunT4l(g4>Y5YDWym1acV{Fr3y8dK{$YyvGD3`=Lr zuLz8DYQ2_u@^obg)+}F(;9ZF49yrL2!|92fz53QY%DlOCWUAbr&O)L6Or?dhN3dh+ zitv;VkB~DC-sJ{9&z9%&&t0j5n|*5*_GT^90^^^R5jx<-mzaP*X5zRIhCxE4SXRgQ zzT63Py$^{W7RFQe6MWmvQ}TH%$_V$yR>R==PI6UPS1^u_t>!&583tSXMRMcyL_mL` ze>y?*?II$)CH~?Yj89OA=y)@%PBb`ae4Ky@uSNi&ShemnyrnYh^0Z2-_~hNUzrLH! zUhO`9d7s7dtJ3e=#D#Jk76fyIxW@hP$Rno|R%BIUwLHd3FK8S^21ljFTq*2OdZ_#s ze1lb7Lp#F%)9NI_<>;l=1`Aiz?l&sfBT~tUfn^%t7O0ERAfE3+k-Z}-?MaQ|z7Xe7CS%0!n6Rm7xtNx8*wrV zyg8VZEMx}Au&|==w$zC!j1UgdG#>Dp(#JHD504lphY!yL77S8J@P31$*#(d zClcPn4|1VOO_=Aolet#hdN@C(dEy?Y8e@otpTcq=3#Fpu2W=6L_f!cY-U<(fj>D19 ziRQ9}8SN1tPg|eoJ3w12CeqsEH;z#`CCcUS-v)Lju2hAE-)tA)JEsP}?*wO@$!g2x zoF%Ka3ub>?5~A4Bp1ok|M%P9D`ccB>Gjas%5E!Sxx5oDgvTGw>XAH1C+rZ*L$oLg# zV{7_5ahUt<=ILA>9-ojbuRI1uviKelI|@+1K?RSz`4@zY?@|#P?D6R#m4GITFk3dT_f7DP7I>MV!UTDFWYr3; zQj=`B`^5@sn0w%mD9&6~T)-RWSLgeS%To}}9&&r6Pf)&W9st4}g>z5YMQq^)e#Mqw z;=e2|U0zzfx`gV5)9*Y=@{&6OKJFmC0qk?)JGbGBO$Y{Fwlm8uNAU3F zrElA&9T@G=VNW2}rYP>w9d;@1K*Bg^`v^By!h)vc?P1I7Qk99jukG8RtcmT_zXHaWPq0XT_#D) zdpxl&SRRYN=~u$0RQ>)2911JKe+a(w=xkHJO|O?=0k!?O6>g4WG~nSTd#h^MjmqGtWe%KehA}34s)Fx3bq?78Rk+#Ak8$#BluJ&As+(1 z57KKB?A(uYi>;)Wg8vA(bPN!JGQGNKB*uorzCT4&2EfuWxYa&O;7?}cx3R`}-TwQcx9b4H4KQO!Y zi(1sdkQw-{PA9ck{vSY(G+#aWCR%(1{sKO@^T7*hHfe+EC&X6BKV!tYVN>Wo)*`Y+ ztKaWzm&B(kr>x2!nl=%NqIM(1FyPEipAr54uCP3DTEpziEBWO#R~d~csTJt@=%SQD&1p#2 zhZ~|q>692a2R-)8%agqv=wc-Lg+o`|K^--%zbg4`)RddX@e6{>NhSELI>( zG&PcvS$HFX(PSbC^J!)K4^-|&gQNIA<$go(i@mgVxG!GPC#4Nm9HFv(MYld4)u_|2 z0^6|*v~>9~<0@relD) z4XX4yU#l4`k>&-0JvNL#5e#|HJiL9@yXGJKH}&mmh3h`w(xOGo(^_8a>VgBOwbXn} zZ{|u6Glva=6m&Ao8oukK-*yRBr&tv5yqDp@6C_4EJL&!XJD&C)S4Mue@hBBK6A=%u z%SJ6umU%YP&BLkUK$mA`XI#anQ`{{Eo>un%A3W*ICU7%dF$hHh<+4k4Q&EHt6q&t6 zUa!@Tf|J(c81I78)%rLrYT5io>!Yxg z)W-1lU6p0S=*V0HZF)pCK8EjAgzcSyL#Ao+2H>#VQvL0){6ZlVNP)GQs#dM5t)_G* z!nF&3Y*-ku=!+K4V{@2}1J7ND*-gGZjvh~Mcx2HOvjd~;!*qc%>EdAFWPy}$we*5# z7ifG6c6oZb+M!1j&|t>KlqX*-w4BPFOK9-0VpT6m=tAiMjS%(lfcMmmh24i}x=(dH zyafY=>^vU^$OcV{)Eo?Gese?~$kyH6$<>>J693K9) z5qL!C`d7*}^`%xZdU=!EuX94ygg6gBue@k_fDgKKqdambz|3Pza_1{S+uB95^f%S* z%3@2Tq$9tB9E8XSZ2RTT};<7B1wsXeC&l zB06W8@J_ugn+PfLjrbCAiy)kV@=6}g3Vo++sfR(P@$7(2qxUiYM0qeP>n@pY^@ zfli-Ac?zGkvjTgtDr99t;$PSJCmA4OmC}q93WkeW6^-SdEEgfqhB~EhY)kQ50cx20Qjp|}*UK?#J*l}0#t>TA zT4=^xaIl!mQ2@+BpNW|X1rTX|HlDc(AX5s2a+6`kxh46t;Cf#34|0&LrSE2V$+9|_ zlIp6eTQYDBeFH5iMG$pHXz)k+uJI-qd3!?-n7ugu(i@2S%6~`wA*W=J2Y^K`6+&A< zD`j@mmx{l(xS}=b)yFRy(#!3FPJ&^e-b;;w4k7iZ{7t{-5>+};`9Y^>*285nB$N7~ zU5KDAbu4Ta1Kmg`L#H}(;8rj)yB>b))@uJjQAMKJEY zv~8Xa!mYgLh0kWVYbZcYR_{-=uX8Ix z65PtXfTYr;sB==FJ#PB+mhmJOTv&yU4wBjxka0hvIn!Us>NqIcCR0gkgJZUPKM4!c z1~Ho;y|5zhKR_my&OYaRnqg3}t>1bozrZZL`_!L=hw)V#ttz-6@B3x~LVeJfehUU} z_F^S_->tYa85Rvh10k7{d}>tMn$OAXt7O3z<;?~tXbyh zHX+?2DqbyltSh3!KWyczA2bgGj6~X3FYba`C;AT_Ctem(hZMJyTq@A!a2FJnRTZVE z__PN&U0{gsy{*mdR`9>2r=K$4|APYOe{Ujs1fbxjgU5W)*AfBN$ia13pXkXAEc4X| zm@7gPP|1GU;(l&q`c(&K&1}+CZy6z*S{y?5UHY~H;uG_f|9AFo68djKnr(6u;P~ig zd;v)r6z%<)l}h{wY{inBM2`bN^nBj4BY~R^t-Fd#hQX_JaJhNOf9ZW12|(`viBrbO zLhVcHVilQZ5!REMghhtouLO~r<5r7in)DR$flB;w5rM&w81uUzf{%v^u%D#P@}?%gm`jgX?z|XY_i&S&3$8v5tCV$?j242H1-7Qj zu1cd}J)~>4G?tBGWjP<%!h*J9D;DM%Ojlb)K zaKAHGxT`KBlM{}F>%M9_xXXd^=51?7@sT(@G(BxM9oV%mrCU?X}tZ5bpUNuab}sz{7Im z%DDCY^!n}fnEeJARX)XHaBi~FsteH_^(gt zNCSQU?3z~WI0zld?n2C53hF5rwR%LR{Wzn(Rg^3(DZVM)DoQ~57tGL8bSXf*{mawZ zE8mu7DJ^1T{}h>?VV>lhJ;}Y|#!)3DHE{GVC_1zke0mHIjRRvr>)|hb@g2}~3jRXd z!4rMi?LfoH!C_Vacf2S4hf&7a+!6oD_Ck*tSP!(O!{xW?3P;YKN4Ij_-gQ+f?mBKg`zF8O$WL{riI(L) zwpTcG5%VWIQ6mq{1NI;L=4FDs{K%Zmj+rjUyUju?1BG3uQja`>29o;;#xI2t@flwm z62TrHX2H9!XBSzXJ`M{!dM%zQm_#bB zuq;IaTr)@$>TB+~r5`~orXB1HX`QOKbjRsjUe53~03tsFVX3Hi&OwE}ZrwRuM_V9xD5K%#OYc;+@5Beq zBU|BI&zQ^J=t&}+OLpIKL*20>@BcYs|D*odtVV)$p$#sT-JWF!tAb(+=~q;JwX~}M z`N&|zx1X^O0#JhK;%<3HwBE#mZ+(iR|E8+#wXAMS{nANg+?VL&clXl~TVjVTNy(?M z{Nk;ZQXOvskQFEo^M(HrtKTvh+maBk&#`^abs&oSE*gT-F)5V>CnBmGa3<)$IyYoZ zgK)FMYU^`BW^1ZG{p){7bb9M1K)U}Esd+K3@gIfMOa!PYKhxPyXLK_Q_bW6$HmA6_ zygVQ!rLb-l$-N!qAm1I+Mk3`**frN=*bvA1VqC^?v9I%7W?n}hg>+F;;0+$VUq$Su zuIE7M`2%c&0PUL2Atj;ttCK;-p*>509;ONCok3Kxzgg;;<0=J>c`Z6w66h09BgB&a z{ho5U)fne@VqUna{sW32XM&KfMjD?n_7k_)$2reTU4n{NE0Vv-;TY6t9p$&c2`ci;$ zY*i1_doVzJ>W#EGtYDv6bP+f6TW&s+|?VtncfTYy7%DirZwpf_1Kqr`JH9!`O8{25oMNcQZEi zq><0EaF%@GuO+8$ulh?K3itE1T`h|?3K?*kRL=|=+?#>K+}s_6nv`*EkFP5#R45IZ zD3~mhGAp>9lk6~X8G12@Z_16ybp^L~P7UPdYWwo{CEU9#Zn4!(+Btod=lf*wR%$qF zV`WO(Y((tt7jl+pKG`N=dDh1@U6@aRR|5o{yqBMOtI#949J-e+4}ilEy@d^fQn{Ul zq?eq&WwfX8shAy^e)MKm+EKA^D8vqKSE_bty#!?M-Y3FG)N<%_(q&;-kE6GMK$gWC zEAq;txZJro|Kwwf*q(fJUCb@v18K;;0=S~H8(4nW{U_#oP>{dui3>a}mi(a%ic*uh z_PV;bxWu7)?HTH~Tzb2vc>m@MwR{bT&NA1tmC@C5Up>E;zu&i3r(05ezO1Q(s-g92 zDe8)*&9f1e-avKT3oq&Gx=r&vcxT5q94S~sAc@eI9QUv*(Pri_|2@pn;`pDTQmXth zUAnJgfy!H2OHfMUda8Y+mYY8`+5*}GUEUZfPtL!&h`1Rq&KK1T`kzies+}gXWPqo! zJ4s19fd-EH>yMaHGGYe=S$&@owuG*g(CyhOXhW%9>VMBrhQSuX<8ho(^jM!(ZFSPB z?iltgJ24qGwxKO#99{JlmvczXg19!fvlvR%A7kZbpBDg~*&%nCKA;phPms~1J9KZg zjQH3vm_jWGsqs8&(q#PvG39ZGquyKD$HTf?K@-dGu zik*-$_-YyA-D{rOcj8Ln{W16xZXU@f5)3B2L@E&at%V?*t?FyW1_nH|&F&S>ATpee zUKe!r!i$HQhk)gQan?C{mFOOU=w-DzDnUQb`& znKSs*5XjHEHFm=Izj~fG5*Jx(-#0OOR1|M(DKTP?7`b_BPlK~MU z(IHzaXyH}iE3z_7bdirmqQ$@BQq#N&bDgHweTI48YhxsXhR%xjnOE;SIr6QvR9Mji zmlm+x{&y@pgylzJbFIOz0aum|FMfZ5x(T!0wY%NeRhe7dmV=~}xiw8!P-ZXsRp-e- zU=2Z#tl{=>d}=VHGJe`AOFOv8+nL>~afWN}#7K5dioG}UgV5ejIePTa<9A>O-n=$> zUhhRvN$ajiNf45J!VEZY?!q|FG3q|(qznDgTF7m2u23cbo?e@8)^_;|TWc*joDbm# za{1}kPrz2J56{K7()|&!9*cCB1XL3F1ZDj!wv!zaO!CjLUJ&#n5yVS_0Lu># zBhlDP%sbqQ^D%5pNxgjZM0jLr=Hx2RM7 zmgz9k)TkbfkpEMZEcZ1iV70Af*Wjdwq;aHhmdXpueWp3C>&1bsN5`E7r8x!#l*Cj0 zg7?uiThmDDnKDZ~P5Nz9B!K_FCK4Sk&7x}b9d54~g`e%c#Jd#yfX?^JNN9aI2>v?V zzmB*BGoMACHYkUa`Kjw6$Hqh|VHY5oN@fpYCRrW`X2ub5mUOR9-`MZr7K!gu3#Z78 z5X7j?WXqI8Qv;=+h$N3v1(CSg!P#mLzy$|8MK3Afb@w{n5zMc_W5mLK##8Np(E=Gt ze9&G8EO!Sv;Lp`z&@CBp-CRLSMCGfL2#A<=i>M@&GMISBLN9Qn`G;8YGRyV8&PbuF zZK`kU*0Vs|0*qg1T%J76~&&?kg2sUFeJauBrrzXcf(J(LU zfmW5nj|>8wd^1B4DKFo99}~-QLM}O~y^HLctlT{7tu%ntxtsWBE@&=-d*KxO$mW0E z{q_IE^!(pTY5z@{tKB9a=(stk1$3sk;v9Lx$!a+aoAY%8o?; z^ttusJRrqGOAlV8{ha|BByaAT2XV=8=i$w90iV0Yg%>^TfjwesBb)sRN(U-mpsAv{ z1TabYJNFWFEj{|Dvhg1X^|(vOK<|!iFn6Hmo$xJhq{YUkTo z_EE6rO-ANcbke_Pr9f&`LjbxXbnm*P}ajSmBgX%Kkk}DaxeDGT^!$si*W%o#y#n();*#GS-6?)`?dpg)!~vQHbsNO zRiYpwIxEh4dBKmCL1B$IBrz#P{pzFP40_pjruqpUW%!GOf-_tbPU9kZXmZ+|$^;;=} zY7$%7v^*t!A*{M!(!P_R)R3{pi$R!hV@P4Et{A^RD*8!Ew#zwvSFHLtny&{{tsQG4 zwF>nygCgyONel4JL-_a118Ec!A-gV3`UWNJY~)PvcUO|I zm&MX)tLhA1IstwxE{@C*LLPTP>4z`!bgM*#DTpx>4+AgdNTKEuHti>J{gptDzL@B3 zINp@WvZJ1RD&)kaH|6Fg))y^a=yd0X*LB9DqJ{fm#@H|v#K!>E2@fu%OOxBr7Oj_p z^BXK>`&d%M>^#1@=yfpn{1f~})&Qq)84lXSNoxND0y!yWQyy=^thn24s|qA?K{Wsi zQ=Ok#XmJL4#*dmKW7(Q}3a_EHWa!f$Sqzhn)B3SxR~4zcn-*eb@GS~*s;Lu%gSKlY zJP_pHZh!@uUhPCsM|%cqpMYzW3}V>u+}n>K)H8kG3&S$FFYVZ33)7}HWMJ4_+hzGm#>hJPP3`z+>yP@U0R zs}4lhVwT;2C}^Z6&07j7vYY_7b*_!ayLP?}B>4yqQj=COPe_3m9+G7hDLVaq8*zQD z#%5GWG~ zo8Pg!ET4)TmV2Iu%pPljeK36<(I7qBzAJ(c$;zhJUg|X7**rXrok10*xyefYJ6_jHV@@2T5@j9w)j(P;zw0Sj6@nPG%2(6#N=MNcJVV^Y6-PK@b+ z)Qhhai`JXK*D!u!7#dJG<9kOi*-NBrLNd`Dvgl<~6aS`U$CB_E+-Eu}<-PsBR?LA? z2!Y)5gkAtY@9RMnKI0AhuQ@A32>V)$OH-_mMF`WIbbGkbd&XVYQT*%;SNb>&tqZHJ! z{_nlL9;6Bnn3%n&9;D4Gj=1}-+?<=AsFi8o1^v0NHq2l>I?8$OL1h~p? z?Ny9042!NHo#a#^4w5h}+(v%Z#dFQX*T-#aGpF0QAtGj8LhBbbHKAAe1(=L`5V_dN zX8I}tR_pA+z@H3v!?Ebh%1*~82f�_i0__#Q0{|* z-K1ZcDpRC9#)tHWDC+Y)NGgk7qeFQ;B1@Sm*)9Sj1X3sAm)l{(sadOv6(+dLvr?@4 zRKoe=$M8E~hWnPAJV2qrG`HVnsc0I-_z#itW%-SvL&`3ggVR7dejWpV?=x6$%Wp1~ z8w}gb>W<>K(#w_tQ0NcsHpWNHW^UJHV-jjx{ZZ<7Cz3{rQjA1akpjp!>2V#^lQnPH zRczYwp`KbQm$a>1$d*p9cRTE>GvmB}9^Zyrw>}5!dH03xM;+&A8?n)im6k=r{L#>5 zW>h~}T-h3!&@{)UJ!-Ju{O%7=fTYW++xdi9^gEAFEW)w>9zF4&ybVJ?pK^ZCS4%39 zV!GMW{&&i_2^^UNU8z{GYxP*9D<z9t*1r^N`r? zp5Ekiq;i4&@%&7~gVzB(ksb3nx24|!8i_OmBE(7KnJ#Ld5luZ9z?x3nyYw$)ujO!x zfft$=4G=iLyD)qICAe_gu~iPuItl_l4qcwE9(x)GKbE@V=V2GwPar8k+K`8xjQ;=h z|0m}-0ktU5n532PyGw0TO+*u*+{%eK2>s}6eDTK#XiQ|;P@u&;h5zt0j^;i@d7f`= zfwjU@WXhqsj#5!ab8?nSqPg_Q0CbV{xOZ5Y;;K8h);#rQXZ1oxLS77h@r1jmwi=-l zGNEC=Mc)YM+Z@Z`o~@3k;;ej4=eFrARAGb;E=JQHTdOL65(=u*$*p4Fe#)b|fov{% zj;GHp^(i^X9;(6IbGH5}!E7;=C7iB}bMH8MzFy$lxfZ|>-D9Ja-cUBuKfO}W>qux1 z)TpT{W=pyU?6`hF6FJ3K9P{Tb`@Tlgu%4lo0t+@jvd8s=O-W?3bQBFZ(r9`(T}z9W z=QGxn4I9j?`L!^JI?fB*ViYbCvN|wF*&w`_*EMhBJACFvjO#G zE;~fgWqW-*hy-3$VwR`o0EpD6meorUmH4l^iw4s3v-(;J(@Xu0QngM=I#cq~7bcZ% zfsoA*MIw&nU>jhh-KTE$9o>7{or}^z5MbFL8$H!#2~b+S--K@vwrc4(D2*C?oQ@cX zfYAePn)h~9a?!l{yDb&sP9k$%Bgxu33z9w&@X)NMbihhJ6zo|V1GtbBrn zy-Yr(T4XVvCjZTK_;}kvE6(SETpziVp2eKZH1R|_4Fi~u1L>H-k0cMtM4pk7-4RP; zdL;1LVCkxtBAh?=U5R+MRLJ)Bfc5yd!Ds0>f4G%+ClOMaC9mgdf01)TbmvL!wbE}p zyZS>0KV+^}jh}O=OyzxwF2C$N@mYk>i_9B#($;b=q-frY=m2}zgXWhOb7HUOQ3~SyFHT{Xog{|Z^Xh*wndlDe$V>C-T))hE6Iyo(W*VdJVH@@#=s zZW0=&@UGmk!uDcWQB!=o=L0Vgd@TLFhoo~PiS-aMG0%>dHGAJG{9tT-rd!qEJ^UR< z;w{|FBn)Jom|ARjI?;!yGK!YQ|00E7)W-4Q0=o(ehHU;&&hu=FV9q;Y6 z3hXO@B5&I|W!LDIbqb^ApLQ`mKyxtreeLJHqvhz3(%-fypZ7$!pZ_5uviL{8sP7oi zW+~De4-8o${9Q7_SDKfhG;d<7@-93RnERbtEl6N8 zF~{wj5Rn$U_f_P+A7v~P%gmmRx)&{x9HMKy4y%*i5_2H;@OuW@+EOcn3@Nft4EKT* z2SXbU95Dc1fQEBA4cQ&yIi7uH-x$_+nfEEn+wsq3d>q~3cPBdil5day3B;V@>PSN8 zZ)Sg@_Yjoo)*?CFyx?4*V1LOPOv3rjDSnG{Mt3%$P{hjiTCX6}8quWtj0^T17D+*} zl3!>jpOHkqi#YKmaZwQlF8m)&5nZ=fIb~ikK!zEDMF##A3jpd z+0ImeT{>JR5 zXOi$NK=}z)t~)})QdA+z@e!C-PBicqXInJx2Ir+vAZ+5EtoqTmrMtHV9=u`1{AZWb`16O<1$WZ0I{QP*3K)MZt9nx0JPF3EbVEm?cJ5H z%#3mT5#4!bG@nw(x*((uO60-Xg?YW}RU!;Hj#5iaIcJmnnn%2uzI=P#)wBWDy$Vb8 z5y5m{*})h6La^K8cGK93<3A5sG;r2vE}nf29rI7IrWn%^q2M1;eMk8s6y)F|`sl2& z$6AyroovryRtgd;cu9j_`6hFGdCu zuAy}2Beb}L?cH}%k+m5>9s=gUfa3S_Kw3_I+5lbwlc$+6ZoKnM^pE_f z8QBwBpFS?x&spq0IXFHSSUEv4uPZ7-HZ%a{0sXo|lflOC_+UG`W?Na=nFl~Gy&UVyg1OF8JQUB;ptcC_2Y(h~e5OoM%U&Z=LX4;^vB5Ni^JG|HgQ z(*<(O#>DEW6nZ?22vOuk5Pm-aOCyFHGRbCwUHEkFN>W3(_N*v?YOeZ6z|7BhMB<=_ z7c}$>gSo@_ojt=qL|YX|$dWvPcJ_S$@PD@|=#ym6GS^}{7>6HZ|FQ0vpXpNI=&60( z`0Pq{SnF9@tXJeM8H;*n(sR87PS#3LO{CJFy<^S7dZG8q7^!23v3Ie3vCR#@!{<$5 zYsrurLm|PHG#~RUxeIn3W{nWSnb z`EwIunnppciR)zf8>x$@3$VQtQG&He(R5vazuLrK-`|i2m(yjbo}<} zU_0{FDKu{U#M7yZtyL|!futUu`;)@DV-yE1r2t(|o)D=O4n0oM4qm33{MJAKe4|w| z)|Zp>+tsr>>z>ny!ZAGSF=+ZW1{-{e`c#)M6UNJG zb-BLc5mY2%uxn|kFjU!$B@Au$BGqIYc{ppO`#^kJgU9l*cHz{GE7NU_)_8vid{JiF z!7imHJkZq6K`7}-ZV%x~6P0@5)k4z}F?;wSXy%#R4C@5B>WDcD6G$6FAAzLN-CqhN zE-oz@1ow%CtKs=GwJJc`nXQa}G+{hTwPx`E3B%GphPZ3Pd>jQ-XC20SLq(eL^AX&R*j~VFmXCJW?#bikyeeHac6b=l(>??BppZ>O;>GPb1?Q^ zFh)R=`Kt3pbrtS8@v>)i-u_diaa2eAANgN&g8g94Df2xw@#S+jFW3~dhNidS4?XNl zF8R?T%Xti)D=-M=uP)@{So3}PYXb_x8zFD5*dkma`XgKnd!Kc4qIO1#?TwD`5!U5w z8Iwf_Y}HAyOoCKd?yB>?70~o}8T;;`MmPNZN&Lh;)07gF{5{B;60W_HuzCue9`iu`0YJXqK{Cs0O3u=Mt~ z%TGS6F`wW{wPFDDjQm!l-n1tbdrdf0BI-4SOM|0riM^>I?{;Ds;0tI8V7~s625-5; z0Q#%sbzO75U>v6M+wct|!;ZN!ER)g^;q|mHdt*t_jWjjpYq)@@^2sWnIv<)LWk<~R ze*$1B7MfR1wVx23yh(nF<6qlj8>6e1xO1xkjU&hhK&YOPxZ(V{t1G>!+T*4C@ zhJ<HNN_Kd-%FKIJ@_m96$0+-IKv8@!jhw5%IHjUrX(&hg;usfgPNs;eG*MA^py4 zcAUM4KcmOf6Mx!3yldO_mVo*{-+*dv%)B$g~-8&+#VP;p7xMSiw zRCThFBb2|v{2nHju7v@YcXxOz3F=$5E0nIl_*FZE{+9aX`x=UGnc%nJ;J`ApkETI+ zgt}BmXqt&1+K1&hH?29V>)Rd1CyddnJ&G#QU)Kj^=f8Q8>>P0-`b)ZXS`$NF`=?Z` zx4omIidfGFw6PjUgK?Y06eVnQN!8e%@e8DUEF?V<6E5XfKP4o)tG0Q}m)Y&sAfLD@ z{%##?oC8{OzW(6p$&8j2R}D0s{fkyZD)gI!v$_)>c_uz7jC(lst=nJBF`ry1(V26s zlaTf+W@V6ZCsU&7PFbub2?qAL-F$S0k#C-CmeU{#n=K7V>&lr}(jsxC4of|C6dq-Y zB+QeyABehD^-F=VJ=P!JGQFNP4eMh@hI-Z!9UL|m1I*6{=n*C0#j+zkD6aX2WYx-v zFH+bicVyhx(wbQNK1ryp!S!5;gJ-L+aU9>wNyxvEzobdbiCD8tnjT6ZBxi|6Rz#r* zTCKZIMt#T%YD&v5XGPc#YwmXrtfG~LEKgDFW!7-B)E>^Uuu+FvS9CeYBQzs)jZ=PE zbLbQ#cuA`{urW%W&BH-I#F zTj$x6&RvTUJX^w-i=xTYJ5X7BX>6oHE_8qJ=Ku{`OuZy8@j-R z`W{&ff6};Z2&L!a2&!{|DoUdW0l=v@KlfT(K6l9;-tqazh5sb|w+{ZNC+L6FxNHib z=g;xc0bJG8QSZ52BGdIiQWwmOI?ETb%3dkh3N}ikP&(OJ*FCT*=(X0;AcH`An z_W234qErgV_WA&9l?nDmZ~2+6v84abDtC}U4*A2@swJG>s{Xku_a-NuqL=!AW+K`=2%t`%(^P@N*16oead{pZrejZIQLaze zZR;pVnIT1}X`rWA3i-M;N_IXYq4H4OsAa)2QLm5|)vvHRE4*o1URzEjf$Oc;-@oVO z0cLdQNT^2uV(poGlY?D*e2~n;BxRw9Dh;HXbe->(EaUG=oz1 zhtCiwk{1xK6NCYEs{ue8b42TuE+*0ITI#ByL>yoDot}TM9@xEiMy#b`QKiwD#)yJb)v4pd6RA~>Uuwf&_c>I<2-a8R@rifK&oT6iq}Jv7Ts9_{cKeEg&w^BrU%(3;-0&SxYKBXj^=>pFF=F9;cxUp!hSgaRk#{N zu^+LsT)hJ=T*B{^aA|#{tD~b-5I?+fL-pPu_ik1sf@OAG>9+9s<>Nu{8=CAWhxav! z7jIhT8U|(CKQ`9CBL4*9M%i$(?d{7U*Az3D*%w7)@uM?l^({6-C3uF`d&XoAxP%)X0Y$OSGcI^+= z>s6#Wu!R>E7(dyS!^693t!v0+Zi+lvj&|?Nx*x_|BG$-qoVkE!)DObi>LhAO!dCow z1YjtI6hiFF|Kf&Y@YykQ^`*Ol%*wQy2~ z`eWZ|=wCX%XRiEK<2K9k*zo=(lh|rwaMj?f4F@+RUHod|QooKC+1tqPr$*y5u^`J* z@KQvE)Ki#bJEVT_MZN(&aGx#L(_U>A{_`B0QA~iGCM1ma#Ub=KNUPdkSOXlp>Li;S zFC!A)bemxdf3|GI@*J&OMN3FMf?0K1(jK$B3LcHfC|gWePo)0tFJc;=F{}x|j>M z+xyvxoJIQFk-03Jacq328Ye@;_{uw(RXJ)%Se%|PWCF=KfV5U9fnS_mwQ+pah;>pU zMhXP9cVJTn6TJ7V4&dV+2p?uNx6*a-=NSpPEtremvIt-95VsISHn7irv!OxE#!cO7 ze|c2C`Mj+M_dyWCeWl$vzw}vb%4L50-e3ISS<6xIl=74i-Ui?c6O_8Eb4ZQGlQoX- zrdFvDQ_Ocwi{@`Us)M;Cx(LZ+rRaF?mK;384as~*7Tg}|slLSLWpKF}r&`2g+)=Vf zJwlKyM=t*`2FcRKA{5>jtI^i|N+RPZE^4TqM@ebqY&@oAjI9oX?Lmj!T~%IR)mr5z z>mdM0HGUe)3=ri59tV#6-fvX0pjxj6?9~_VME!NSH^wx9e{PJ2DlR)ggsl8_$XGSY zBA1qE6{LI$0y!Em@BvSuwXJyjbf$3eD$oh*W@O|nCH+?yl;3kpEAYWX)}4iR@+6(& z`Y`_bRl52C6K-sGa)wdpz)rg$7|fGKcI;4S*cBI%feBcl9(~Vrm6N#nu%kM)*}cXn z>{!6}+^&tv;fji8?ez`6Q@z1KwE1ppLgaO(S&^{02M~BdJzV3KnfiX5J@=(azv}<5 z>fSr9sjOWacC4eQj5-4%B^Cq~1OXxRjEW$FqJngY8U>{zy(AfR6qOPL1*w^lUL(CH zDkBjBM5TllqDBZLgcw44dpA1HbDr~_?{~iQ{@(A8Z~w&#d#}CL+N<2_Ue|qHwnV4N zkMZYDc`U})`_$ND5%*K{bsCXI*nHTu8ni-GQd|o$V=^*z!OY}*$UD)x9_PS*EgJ|r z-WTmGbyJJ6(pU&o(HRsz;R<&?vao&_-$+r0r-cp*9;UJmL`4`FG<7w zQV9)6h)7&G-ZfN9p_~!c5z%ApY%104rwg`8hvwjO(rgHrtBR~�JO1oLe{=lmbl5 znMVxtHWg$q75oAaB9Kgh?u-fo@{xdd^qOC#<{4EMVY91!IY1eT2^k59+Ddf)Wgr== zRd9&q0^PkV-)hF*y6dUmrD5Fi&+ptR&Y@Kovxj$YHHfNE%(#@7FM4C%q_=5!#LG2F zX64dR{pqjGH{ju!JkzMhONrVwDIkhCyj>5#E)>%tDh;AF71c4po%2yV`D=$!HuAX$ z@79U2S!6pIa{I5xTIB;Zqpi+EFpQp!Hq@?fj=)bwBWi> zg`2!7Wk3HZtx=!%GCv~-`V8@oh;e*JEc;95{9dX}dMX{OCGRB20;$use#n@epg-B# zTdlEcQZc(*;PDnQS`*lQ+r57{2ut#*>U5loxPAhIb5y48Moy`iNsCAuk=9%J!kBaN zQ_?B}R?jVJU6T8irWolOxQU~9A1QltFE7q~zgXlR7(;Eqo)5V$xj)7|=!rbs1Z+2} znwlTHn_0J`$^#FEOB@YtN8eo&#g`LlUM!x%IErPSVS(6%FRoHZkPc=DWa&dVmE+PK zGa4~8%Q;KLQI@PkQcvcF^>p}ZON6cuQ!v%ks=FfX_O3~YYq6en?~;|e4+Q5V5I11- zr>q%X*nN=_n+4APWR_{ialGY-b&I!8&!05XOEkJ3N$cDJcC0Q-PvGHSgy+oHRDGd5&j6vFTDS_#imc z=?$D~`I7r?Oy6LI^y!D=enK&w+sdN$)f ztbZs>mmFw&RxDB@T@`QV>LBz6H*y-p!Y2paFE*g|;f&K*G_9qFEoXf?>E4~!VM0roq-B=UEWcAwSaVB80W{Aan$nTGP6 zX2^&Qh)d*ia+?-@f%2nvfhK_;*_a?nMkgbVLeTF4b^&NBe6%IeZcgyv4o>cgr7mnz z=eUTcZbqpj6+)Ach-M-VaH_5_`wrLVrqbhjDytiwnjt>~6lD$I*KPjE7rUmMVg%}2 z!s>#RSzhmaU$L|6oct;mqi6K^t>YtU`{W4JA&)B~D~cz27c54xc|-O2(VU)NTEDn( zjg&R4M*HG>L9-e1`0)u%Lu@}gCaV|vGKTQRN``3Hzt-741MbUYe=G#~NsLv)z6egS zprRuT$>}DGuGnLTObW!Gz zbxX=D*Q&%>Y{L5BaoBVedxxH|4AZzOPHk$n?4Q5j#d&J(h3%Pd`aK#gvFtqrKJK)8BJXMoz-6U^MxB7m z+L)2RHd<9~A(fs01fWFb$nx&(RXJS6<(!?LBq$%~g$qoF0?I+Z1irXTi(;Qk-nOzT zz)z1*4wI1ZQR?Xl7$G~#5bNZ!EDN9z907?SCv{3b)vXDd6-QTMfMRmqnIdL6pVn%u z`^lVVc2*`j46~_)4xGMrDiu{N8~BNiE?*$h8sEx_Xihz}ylpDbn)dahTSoMo;7oxH z7JWDJ5cDVt=PQrIK?v=Vfx(q&5W2^j{K6F+~wnHao#4b-i5%u z_1>=D{WTO3@%GK7=Y->HjwX2zPpql;h44R)8O|+;{VY_bqOF`!`LYMx&|}zPkStL1 zqez)Mqyq_$D595E83f>4B z!K>$~=yO#p>nmam2>0qGbzh*o-m}%`HCFYqJ}<3SS^Vcy)uPIf0qZ_92oNy5*$n*o z4*u|8iEl@;3B)=MlA_3#(o!)t(v0mS^mXwjHY35^SA2n+X%K{}VsUg1bA^xFt?l-U zoI);mktjW~ZZyj53U!~gtoj5hbk7u0T8lnQ{>FTk71-CA_4+ zL2>3lF(4+x(~Kc;>*~5v zy5P?aSR<<6at~I?9&s=t--}xPl~IObC$~#DpD@6Wbw(Y+??8)vf{=-?q|Wz2kcgpR z*(Jy8;#LtKV;Hc;vRR(b+4st9df-6ceG~>u)n-W^wai%YbMy3R;uC1jkXUNXSY-;= zVPpr#i1+(AN(4WDqM;Htw@=GUP(b{QUElQ-P)yKYpP!&jWyq*-g%>kKL0x^(q+*;VSn$7UiDO( zE!ti5*>Z-e1;T2Rg57%NQ7D29_G!U#+Z$tzZEn$tZ?b`H#Hu%=xdwM{v8Cz>iAem( z=#$&4xGAln&8qaXi^;zW^-puS`{2D ztn_R~orD$a`6sx;1PF=)ge+!C9Uq6Z%ml^=F9i3Y_cvFq`^Pn-{OZ1uD`U?CXE4D1 z?)NOJ{O>XW;Ui8fh^1tJrwvZfyeeE_%wEx2Ubz5t-B)H7$9~&01AfeZ;r+h*XtxZy z81ErM)oBK+wtssB00VxX^WO_$E-yVQ{*7PT1b|m$lr-ez8o$bRSLgiOWB(rjE5c5G zkM8YO?MMVl_~CKNzoYt6XI6;f`euOWoRD3Fq>X!^OT@uJOM~-EWQrcTc7RTz-7mIsY)bESHe;0&Dwf(dI4i%$uiHUj>uE8Uw0@?IOfI*aYiwhnIuTS$%^eu41R-J!}X>G&>d{ z(Z4AtMp4q9ltp9qC+%uLn1;$Y8)(-AGNKs-6$RJjbzsQm7ZjoDnUk2Z8q%LEhj-T3 zvz!BX%sSD^399K|E4>TANQr#)JsUj5cA0tZQN7B-`9$A=G1I_l8|G)*ft)k%p1yn6 zzAardr=#evl&mYGUi;cLo40d^bdLHJ({JW4CEp}X7yBCIU41q?n4&a~_B1w})FxEs z7=(Z@w6oF~_t>o&(VeP#_E{DU_ED5GfdE`lPM>LBcfp@i*uT2A8H2)%v0El5KYr%T z_(}v?c)Q>>iQRhSl~iQx`L4{_zN8z6bP0l5M zU=zxrL2`g@@?n%Rn$!@{@_t>1?}oy31lCb-?Ll0^okm+`OaIzQ=qByw*fzFL?XnmKWZX$dQl@ zpKZ@j@;#bVD+{pp!{F3$uy58>wPr};@k!c9DB6^4|E#nb^Qnh4{cEnOQ`xWfXNM`7 zCe5LUXH28sJzd^0DF^LH?+z2m&;`?V1kj`9f#I!N_edF22U`4eb5(^s10Bn5LfeQ$ zl}A+lNs_22{7xP)$f@E{x&$`bK+LFyM;|tB)n|3YV@{gUr~`ST<(9dGqGkw zQR8LtVW8uM<@WreeZ`Uj5)&n!!38sGPCDyec1xgi{gAFNy7sD0L#(d@o*l&#}7ij0C#?|2#dW z1Qs5Dw3Ow$FA)S9=YXAu}JOq?jj7pv@uc|E3TqS`(Yw(u z86JO%Y1C?IfXK5XwE(*`BRU8KdLUy>Kn_b$p%@Wg9a6+c{t3Nuv8rz&9&Y(-jr8ty za_+9l7A!a}&BImrC(PX}=_^g>dXo!RR;V5Xpt3{0;4CztdhgqJ=7fNO;FKQsMaM<| z+$H=nwb}S?v(t#vc7;V<&rC@Ty)4vH^}!iuRYlc8B;GHxXWp{b#0A!6k za{qvE;h=Ugi*0a0s_HS#61l3OfjE&L`Iu@|2oewqSI4=?%le#D#1hpQ$(wd64;RK5 z<4SakYf%do*4E49`e%yqhf5%VueJLyYf+ag*j-=A0DfEn zq8eTFH!=>ikz!=Zy>1`)6nbsej9y%1r5P0v+HJ7s5 zuepIEPA)x*tqGMZEO{<4E{z83VM30)pR{9?^==^pT*9GVWXdU_$hM-b)B8~WnG)fh z-G4F({J_hEFZwYo^b~CO#-D^#m8Da6pNS(TASQ52RjHSQ4LHl;_VDOo|HRiQK*e%z zzxX|0H0zC+4h30Y_gY&A%;ed5JcbvVA#_TElhm@q#cofpdI=GO0&)zpQ>wM`vaH+Y z(Gg=pt`u#Gcoz6KPcW{7)!2=4DwkEr$ok6g+RzF{_M92^84cyJ$6ek@&0dtx2@4_x zZ1qanpGyrr_&KS5hv|Z(+TdEkG&soY&zWsYAcrYgpjyHW*m9y%kbb{zSV!l1*GkE! zUE}xZV+;0XP1F^pSnpL|p*k;)OpTlWnyv}jc|coV;?}LNT?^gjKMO;mNHdBhd!P&k zEKoQXy$>a?Bdo-%o>hHtQFFx4Io>Y^0L|J@T}AKZTbkgM0Ltd^aB1Hk;(JKE)U5}~ zW)*j>i1WR;dlHan{H>}s=Q9eWGVg& z$@K1T-M4FoQ5}b&7L1^*fM)j!0NU9_E>G=9{9~mIzy(01z5!gU>LwC>`onz8FiHPX zMiBx5#5zss;}weuO)K&|9=)(1fMdE^qhG&1{54GY+tm9-+ws~cU8Yj?kt_NZzyR=f z1p~0#=%$4)b``Nd|NX#k$(O%lZoQu%J5Sq*b1Fq$bXv{C9M?_4{&v_1FqphB1*BU_ z1B5!VkYRu^NouYT_n!!RRacDse_r)}NsO-br)bWD-2RxEs*m4Dc=WQj?O3TeAZlsi zY^0t%b2?a+5p+#>JWGH03V>%*J*1Z`{OkyjYIe(CBWp_Q6WjHmsG2GCg9jOhde1!Y z0-Wkol|Mf(H0Qp5a)UP=VtsMP5K)#_IlQD3Y(?e=*N65Q7y*&Y@9=Z9?1-Q~!Y9$KsszLv(=Wb|3#9C`B(#Db*e$a@cvdZDB7T85{L(a7_ev%4_D^Pz($v6o z1V)s0^!(6^ontjz#6tW_#@OWCG>+BbTG7w^F_qGn>T+=p zyofqlHojik?n)WHxl6&y?gO)8xdQg2LVRr;`SDhsJE~i^N3f_y8ZN>;y ztcpj4htdAo^J`84jtM4P9o81@NSa9yoxsNWbT(?T%?dDl$`7lz9)j@2$0E8eOn)nI z<%&vX5x^<|1cf(6jgA8nTy0K&ZT%%dL_5kbMJe^cylaf0Zid-^piJjp>qTGr|yD3_0-tU$c<+ao(EUd|H-Mk zw8t)9GWJ(M)Pm-6yocSMBDp9PNfX#p=&+!^3iD!ru|8Y)h%d|mQ(frq{o7E%Pzh)M zO-ZG!#%>XRVrvDgrt?r;CH}#J6RBk9NI=8 z$`Al^xJhbGF)(wz_+opuI%K3zQi-$N^he=Qu9mBE)r9$p-!D#uF_F>)ZLrp0D#M%N zGJ;*~OI>XA)(~WP%MH7#27XUh#gA&$JHaD#uH{5=trtw*Nx^Y+*n~fYfVEe-zu+W# zFR2POT_$$esuv?>OKXFQmkSc^JPN>#`-YgTp45JV@0bg zkk8GlM$u*u!X@Grq8O(-d(6XOCs9M4 z(k0G*YsfD2x~x!3AqJEH&rW(1T}RAzk>5ASyj+UN*c|n&61^N6cR1Z6hiAS!_z1bs z6S2ury@0oFP+m>-LYR<7GuV}wmL|EW;U!^Bop^pQ6Ch3(S3a`{hGoz^ofs#iYL;Lb4Q zWlU$Pi`;J+ccl09{F<&1TCSbgX<1D^AY&O~FA(7Pz80cyS^`270&$pTBo(oi(yxmR z0Zn>Q%%xt@c-=Ef3+l)6X8Xge8Ww+pVknvbP+-%UQ^Y8TiGV>d{kM6}*K#edx@0x^nT^BU6ABnd@JfCOfbSf0i=Z+n-8L4mA%ypBSz;Y6Kx* z$gUK`j6xfN*yhYfm~BN=oMj;~;dd6OT?bV%EmvQvES=FcxY5z?9W^;YM|nbvCqWe1 zPh5Dj-)|nOcN1kl{Aoj`sVKx}hwO0ra01DHb*}=?@)249X>d zC`V77u#G2d(-uE?G8q$hsu8Xt-B$~!tZiln`q9Vw%nsvwTkZu-T2k`x7$@O4MKObR zrsvy)mj8Wa1{7IGH81#we2N5O#dH2vV(GhRflnCqbKAjE*|f?CLt_b|e(`WzCZ68BdlY`T~0p92>b-RtH{| z9_U^v7op@lK{=@g3IIEWf1ZRuq%V zhpuimlPJFFaaAZ&v#v&TUth*pCy^I3+t=fBRlLqx5XM@nhSj>yhM#y05+gqN4poK? z1_OMBl`BCUXQu%*rX3qU6u%jWnOnbjdI&r!Ds73Oyv3Pr$Y`~qg!c%;uNCBAt|gqn zS;raj5@Z|hmVdRJUtF`h@{8#Pu8PjoUrkRvjwKNvKSRppOtMwlWM6yvWyL-nw)bY! zCDUD7U4ss^t+{?_e^2jP#Seend9v`!M*j^3(;rrW$BjPB*gd-NsPYrarqYYY3F%BQ zmRCOHYLEIi@A4Yz{5Z+0`=}a~2TPPp11j9}$Q96)cj^nkvV4)?w{xve!V2ffi;F-0 z6W(xq?f2M#OM6y-4?BMT)2;6wTlf1b4}ZOMuXewn{~13HaqB26qgO=pJ26{(+1(#! zViVm!lb{U7=yzJ#QNM;4^vk%aXmR!s&!M4U;~!W{h3~J7Jz$auYr=fb_BZI=)HPK} z0XPPB(+3GJ!0De?EB3&r-L2Frr48WkWt8li(tf^6gEtb=f}7HRzOs)2t`9HAbf33V zn3c3_y-V@szJ=(@vMJIJ|5P&eNOJm^Bw_BM>##iGsI+d2wI|#}nZS-B;s8nPiH;h@^qsdFQF_vIQ$gbxIbg z{UM})Az<+7G``aa3C;X?F*YwA`ih7NT*esQP`9(dc;U=^t60HkI@uLmI2w?A5l@4$ zJyDshEav2P#+PW$xqf|6E%N||QsuLx<&r~pkZ@Bx}SevDN~md!Lu-v^=ZlmT9Eo!4Zg!AGqo)Vfh`qO)g8%wER4O3ORRh9+p&3Ib=Nr-1wz(76?Pb$t-pF- z)ULqg>648=REMP{^gt(H8hP7|cFOn(ug7Z{q zFeWlE4u^cmn3UuaOOM4zKp;u9rlT_sJW9t`o#IY)Rczfv%uaXpUAM--TdHLe>)4`e z&kx0`ce0lvo-$R#k)u|KeK5Hk;=<9&KmT zDUZ$KQinqud)bAP@f#JA7qp(6_g8I^L`9Lz_`HsmiuZ_johnN6k-{wJ`@GBe0N{1L}-a(?7|b%rYO}s zRhX+dg~U2axV)PRu<_FY`CU6H?a{~9CFEW25B5j@Ph8drt zf|cRZi8R?--IG^NcKacp;@kD*IVQT}quaV_YWmV`nz8Ryvuz4w&hdjv@3_Yo0V&KT z+{;((vG9g4OTDR2q%C=`khopR zmmcvx;n4dLr^!Jd9Fszf6sK`nX&0oa(?Bcb`BlUHMp!>O^C`>nXx|_2Ns$aON|Io| zxhHb1+rCyr2$l3s)P6NyGIbQ8Jxls1)zy(NOCTeV(Ou{gcHQG-Ug33gDN-xy$O1a~ zz%r?h_jDI1`MzXB6w<(TB0{fq&QASZVN}kQ{9!)ZxaV}j%5M7wW&oIzQlVU=UT0nW zm>aQ!M!(jI+@JKbaw+#XUD9(_H!b7twGabi@7PoybfIc8jrS`uTvefASroYkl%1+C z@zdYjFdWw++JO!!$jZzGKB98vccojLnk)fyw?@Zis*ods^B$v`R2_XF&iME$kw zVuXWm*XiJ0Vxzllb35FIZ*(7&mS?u|VJh)_BM%5w+Of|IX|xzxFZDYYgl^+n^a-RW zp4?(eJ}l_?ar3CRw^7ek`OXUY!DomGYn7QnBIeGo^o+W63-CZhCETwO+MQx}4Ug9} z!0{QpXH2aL|4O9ppTnU&6UZh>p18B0_U!O`-kF0ls`FY8Y=4vY(N`wQFPBy(@)S7ZUZuj?&kzt^U5dxG7Zdl z6Jn~1oPVy%5^~Y0470`*`%;wO`BGF$shiNvz!f5XS!$AE+c@oqRx5Fzu_DJmxE(92 z4NXJoOZJ6@i>SMd*;TK)?)ntiitq+|<;!0_vr`{P;<*!R<0cFpM?>=s53qhw7&Idug#xqyGTXt{K@h<$~SKv|FRM8XBBllP&utYT_rMUkLB# zA9Kz_GNm0QF33zicoboz5{UNTTD%&TI&tMSEJzLiI!>TRK*+efCg{2&5t5V<`GNV? za#oi_(G711ru;Hl)qn6=t=+6Vw}O{5f?OYr)d;7&!v#D#9A?vqyN5&V9ek&q_YgVj)@w+dIvu|8edEu;gJAL?!^w4yH!`tu24*~ z*ttcadNg^A=cXnuT(hR`Cpyn=)kpt^0zGTko+%&Y=th~)aF2>Wd0j^zN^CFh%ix0lOAc41_} zDbZOMU$2<+i+V&~NN5`AMoV5p&Qp2OAYP0&r#6TylV*yA{5!wBbQkwC(46~?H~GIj zo{-N<5;!B{m(6;tA=K2-<%u3&i_H@)k(oe0TZJ(DW`az;N%HeFBw;7u9gx^yw?(Q9v3c1Ui;vy=@Odu;?Qq#o9{eEHGkth zc)s_)GwS|p^JV?waQRiM0vkLoai3Ezc1Q^~#3kd_ z{nps5l_~(&bCa(N?xCm8&=LE?h7qG ztByPN_wVj`;g<0Vw|RZMrRq!a>OaW zE$~!^X0M&WPwxBe0m_-QJew^fp8-=L$pMg8bZR0 zuVe95@+L(j8Vm{%&HF41DOV)>(U-erUHACA_L2B#65R{V#G``M6J^suiiA8>d8SO- zB^t}BIOueN6w%ibMKM1O$yXUy5P zP=1F`6LQ?Gp^^MzdK_BsK&JaglQy$k(@h{Srm0L4uwDiuWb%Oq`n) zZWscZ)_N{7@QIahyL{)=C`;F;ZG@xH$7&S1DfY|~sYNtl%1XQS(2D>H?O&d57Vf0+ zm7U3-4lSJ~=6Rpe3hgiEtyzZ$N4LX3j7Zw3k6WQ$SL5L;Vy_5F)ObhqMn?1e;h*Jc zzXl{!#|>To$z8n)XT~Qv$OX3V7uE?tbFi7Ld$2UMUL#0Se+rC(zr~rZMZF0 z<)e$7rMP?qNp6i;uf#)EYQCtE0K+^Faal*=!+J1G(e#30!Ewo6e>~e|KVFi0%q4j)ty#tC(*R z+88Zf{MntUq-i(w$7zA5v>*uosi@`L#=O@~T}P^wbqCtGSB`f1IfNdT&!`%4kH@Fm zwj2pwy}?blx@Wq4{=GFbP-%&9drkLU81k~a{?Ge%hV>Qs9zgf)h%4a_tsjq1CeQOg zT{z+$aLy+geW{q{XvVd@&~Pc3uyck*mZu7xN+F|&x-Y~|^SXFF>rvs@eKv9g2i^8MU$`hKO{7Tx&vNTExjG1mXV$SthLI#|B);j+3*shf zpzaIfDkRxdjuQ&fBp7>S30pl&%#W24Z=e_R1Fdm>P4fIzHwOFNbv-K4VeRr_;sz;u z2foZ20<>7%*|n}!=n>=ym4<^(4(z&hF+PR*X_QIIERJA$;d_S+t z-TkOS(p7_t`nmC;3&Rk_HGvLFr{IjviAeDv6rc!}QTMVVgI{Vr-FCy~!|sU0zE7`0 z@7@(IzxrZWGi2Nrt*V#d-zcAxHj%hK%|{A6O_f>5yAtgo^mW{Ugyo!})mBR514uC` zrOij4GbcBCkESC(x{HlxMIT?h(T*9sF4vGuwH7DpETb!yPHMbn{~}bJ^q-NDpAyO@ zA!W#c>o@}nS5SBgnaWnTHPfSqRm%LEi6dxe#3W=;HP7xePc-ns<5GHPGr|+I2r)`? zN~5Sc3RzB4%$jfWU6JaF@z>*3(E%5Z72r1gfzwyA;J(@$S9G|ee5bDM;(YK7WPMht zQeNE=siX~yuUK{d<+~RH`F9!jmHD`-Z$B_)CsqqA0zgGDJMTvRUU1L z4HQz{LK75f{2om~XpOB8#oq0vHD{FlkzmS+SQ+ zJo9(Ym$^uPhs}icdm9~P(kjZp>pGTUn>AsP0g1rR9Zm9-G@J^x%1xewS?vx>R3|)A zOc|gqJNf+bRbEm(@@$bonf{2t8z77LmJjSS-mMk?oWE_i0H#gOqaNQ3d>^ z>cb;WPqV^r$nA#?!x3o%`kdv9tAIsNBHjGA6J-b^gy39~`s3!^RtNDeuHx=3lIx_| zB`KhWWJF38E|(dy$63EVgJF*GaQB@Vm{El0-JO~jy*#eJ+KDX0qbD0PEK7rAe~ccK z#)n7sSuD^%3d1LpoBjUGEB4XX9a>UXuDuiSUNXdBh=XLY7bB*_|FrZ$4)K*=KF~`o zr^Gr`v>ZV{e~j>KE+y`lew?x<(I8;yJ6`f1-4)m?x5$_dvychodXl18?k?ic{i`L; z96MR8@*k$D117uQtEn<5;Xy~NUmX^+h6Q;V(Cir}0wO^;!MKnRx-E^1so>?&5UCwEe8?UA#$=&CoP@c&O~iPArwGxr_;`tv{d@BV|K zQ-Apq_gvQkx{5sH%ysEVn08BA7FlmGMfBujdUa2m^}S5X11R=%vyVO z6_G~u`hH3t*zi%c3cl_i|J=_TgV#b!RvIOVz4q;s{}n88+i@yX#*j-yN`P zQpoapo$m(O0DN`T<+W#H#FDz6Yy=ZlFTC3i9_dS!Ip1N@J1h|0nY@CB;i z3(BhmPx_9!9QEq}yG}yoEbIwm#DM&*g@0@!#1xzM&x$=ADOuCrH^HQR>s)>J{UiDo$#8napkEB9&k zwj5FJ*xeg;wz`2+`hq@{ax-)1w;a7zUT~E*^^`VpYotx(_cr^KuX!yU?tiU!$}sBe z0;lo?J^y#-h<|(H^V^D@<=}rSRYk-VwA%*PZnOWKNqs~}Kk(K7Q|+QDP1~>K5h|^e zRAul%RP?l(djTwD`@XNmNmPiaQ^@eH{5r^iIiY5y5H~AUSA8o}i{VNwN;a(wX`oV+ zKJSIwn%VK$f8VZYFFT#K-j%wt`}lf;L&HA<`h{uNi-4f?zyDJfyt;~w{C=AdA>iZW zK9BxR)5LrD%C*3*M0y?Wza$ z&ebyE2ZNCiTyy9M*6Xv*%GxUY%`+_hTB>43!T;Nr*}G+Wm5S#TkrEFnhlm~ll}RY|8bIyDv!Kl^VQ2jX-+=~FHr;N~or%)tMtE4} zjmX$E2n|Lynw*j*J1*AnEn}VJ6*37mkp)HMqof=fs7wlr;#(w8*yls421^I7zzxQ5 z{RnH$d#`As6gx7`tGn3a8k{j0DernVphZx*p|s?~&=A)44{TtMzXw(2V3nkMKJ9Zu zZVfV~Jr3>((=T<-1wRYwl}$`dUBo647_feuu3F>hSt6ANpEv4$9#mq;A96Yh3JPe0 zcL>{pF%>&!o)I5kz_ytESS>p*J+Ii_yKy!oYYAK82qX2>mF(CAd>Lt1=!XMprSL#s z<`otp+q~e_ov^N_QqHn>)@;i%tz`Np(^FQCh~!V}(uq-#DnEUAD^5e*^oqjgz5aOk z)`%AQSO>qyu6J_L?DkRGZ+~rq1-e5r`OlAHOmPml$l&<1H{|aVg@pry8+_h2PKMy! zcl~O?m-F&pPq%?yTNQI06P$!`uyf5?rWbc9mxMo_1fiLXDUKvgk_F#C6p`(XZ_Anl z^qWyV2lA{7mnWU&dU-^?iT>&;q-^Kr9x&6Uq%-v3&{z{m0~jKm82%QuyWNeXKArcy zhiC6;B{#kN#QyoZE;F=+CY~-7i=vjPgoHzr;$<1Nh*J--3!5dNyNyS;qvSt^%dz=W z1W%aGZE!OE@@3(Mm-UI47V1-X`TG#;j#_{=i06|geF&_emJ9IrlC?SZD$v|D(Hi1#eV^*;5dRNA)lVxU#Z;sKDw<^g$ zO~fyH<2l%2#dth&{?ws8X5jS+F~Oo^zr;n0iFd-%`8S}mQ@(9`t;-B^U z1g+Q*jE)NbNj?@w@BW3%RFG1IyNMgQw zsxR*h6yBeu-Dz}+ft0~vf`|z@1Fa0d=c}R65k8?fQ4-fgIw}qO)KDA)X*%NzqeiAX zg`eG-4{pPmEMcRu4*6eO@Uv%xhC|jQ|K`*a*kg9YN28KU)|AQq^{#m2+4bQ@?hfF{ zDeEnRJIm+UeikG%hq&y)-XPKq5a)sPksY5h)l>nS&qCB%&5%Mefks+bzFoB3xn0cg zZ`8Z=HbKimgHgy$lkfIDg>fk3S7*mHCrgVIs!wV29miVa=X~;X&m}1Izn7gX<(o_5 zsuvBp>a>(~{ z4dTqL$a?U*EgRzW2BzvFErfBp5MZ^iFm3yAz#5Zc$@#qApkGW6oAqlnNC1s6HJIkTC*j;_}; zx;oGLsG+SPo)FlWW1BlK@;fJE;9ajcFJ4_Jg=zN>x=}Y(8~Pihzi$eEKk5US<0mzO zwu-OTTkX_V#-FAhZL8h5P>A5heL)#@$zmc2XXrJHEmya);;W0&@{^&YOjqFq}o2W1aO4D@!3 zukF(xJpDsDclEv!u|^y10j>Lhmpmsjr{rY8Yu{<1!qSxNeH_QK*}nME+KmIUurbaSd4}T^8pI9mIazF!fXxj%SDSnjY@3_Y=?6?PjXO`>fN&7SQY#)@ z81ZF1lh=J2?btlIthB+^2_3~14sh#y&!xCT{jg+1;<}vnf$Y%gez-mzR$_+oC!mLXytYnOF@|QMgL?2b7QfK$sH$zO9yL)v zsgUGcX#MS3sOx6wHy7?mDLUdu?gilvvw z!1wSy)+ZdOjnc$&ybpN&6)_=O; zMFju5-a^|x%g7ot)JdSp_Hn|DLNW}zB#!euAJ0O?+8E2{o|EX!0Z!nIDMy}Y|0MZ$ zS1~@DPPlRWP4>Z{^-lSeEr0m7T|r88hT1OViLY8i)Qj$e*)pN>9lnh-kTn4VHuvwUg>9QLE7-^5|rB( zQB*`wY=|{^!QVc3ig5DW4b$4Q{CKnGn^EDG`fXSfNT`;r2c~e}VAkZ}2cWy-ZM)sD zj|~02{Rd&aOSDK5j>C)!$__#1XD;7WVIDOBc?WL)=1^^Yedpudf!ozT{WkW-{q3gf zUtC#+)`CAu6=GytWhR_siGJC#mmfp?rt`Zla0LHu3G!oi2TxD5G4`H$affmJ*kJu^ z4rPFH!}|L4Y(jU7jy{Fg<@=wXnY2vbis(A~<(6XQIy1tiYFWttE%WoM;hQW0PQre; YUo-wmVcdzovIDd~dDf=(_@&$b3pQHwlK=n! literal 0 HcmV?d00001 diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/Fork.jpg b/Firmware_1.26b/Documentation/How To Contribute Pictures/Fork.jpg new file mode 100644 index 0000000000000000000000000000000000000000..d2c2142666d988783568a7d1f21f8e27d12c5587 GIT binary patch literal 58378 zcmeFZ1yo$ix-QxT4^HsLA-KB}9D)Z3?ljgk?h*(DcL;95-CYC0-Q6Wvkl;ZAx0AKj zK4ICQl1b8vxAL(sI%O7#J9U5%dFi+C;&# zbau8EU}d#+Vlg(eGXb%f+Cf;|jqO?4S=d+sLZa^W#-?D9Gr0-K!pc^d_O$ggExDDM zFs&xHBAcSU1jy1#*3%KB=BcD^>IpXGH=`95L3=LbF5nKahk%@o$=x9~woU@>!j!+Q z3qY@bC9_hB2sxUW3%rq({!;?_OPKP{vbedqvAA)v*g0CTvh(xvv$Aopa&Rz1C77K& zY@LnWnQfh@{xl#7ax!(avUj$!vnBs!(AdPz#aWor#l^}@z}(oJ+r-R_o7u#e(~Oy& z-OQNT*o>2%*^HCZjF+38kHehZgz``KW~P7hZtvn~^V_$XDJ#eZ1OeGPJ3-N4XQgEQ zqtO3VKA{l(&FTLXerO$`G6E8gAY*5cB=k>&gN>b+nT;J<8FhAc0WLNHE?yRXJ}x2F ze~=Sm{RPIqE9if1$^RdrB_d>IDq#An>~@ZSxK{%?{O`54jg^SFvEv_=gI@n}0ksOH z95OPp5bM8p_#YAYodRVXRPS&6gldxizi|A^$v*}1zu@{8T>lgT|CI2**!3^C{wW0h zDdB&y>;GeL{o5E9WD6bGx^aKwNkAR4Zga|z_P*9Lju`sZ) zu`sZ(Uf>bqzrZ2F#lj+>ARrd7qI)VFqD92STL|yFi$-IVgL-_*)v!ez`q@^aPSB)&k&KIxjL8t7}#ge z;E~`Fkr7}Kpv8wu!@^;~V>Q+oTxtpbuIcYDYd6nmcqOG0HC+Ne>_BZ3LFW#?kAL$F1GNp00L|mWg8G4h zfk%KATK(234jU}e})B% z1rP~Uh z++M36(+-+C;1O66w=`wVNa2o6@^ylgVKj3&VdeMKP4O3PIiw#W~qk(Wbmh z6aBDnT07kg zOvoPpRi6ZvOY<5Jn_qX;F)v>GP@mr)aITUvt57f$bgFBp6?SR$Na5GfEV@+XmIc16#BdK zP7;loahaO46qdZ>2Ij#zgv{r%c2k5=t8=mVh><*LqyZhn(Hn2W12;IkgDi7_QmV?r z@GkOBkai&@hzdA_7jKy){Qa81TcETRS6^fu_uYt&-1evL;!>c7_{v3wcX=}QE0J!J zWInqEIeX1st3#`CTbE)J=cZ#9gHZL!v3+aG7cC_@B>_AN6EJtOX;c!#O2ddYyuh~@ z@I)4`_USk@*aS*6gJpsdB?R-zle9oi;StPOcckkb(<+|Ki zs76fphD{{X6C=l-`0=t7;qmF&&b8Ga3#)h}lGGd&kikoFahf_c&Cj>T5p&1mi|UXl zlAQaIJE4TSH@sm^X{ZSlrpJBWCUrU8fNxxX!B?Nxkx6{!@1$q2?W*4nGkUOSo2n+v zrACk+tkw5flhLs~34dsFM0$%qgdsO)LwS91H?06`!qqopoj-*|^tSvJDWHgGSNJ2PWOYM=>aHx0iwV6l)98Ji~-Btc(kiKUi|%Y+QxSStb-FDU|ydyqr@d6QdqeBVf7Hxo5(so_W){` zG4PI8z^ew84e9SN?f#daUu&5&>xWy8x?(7+GA-zX6u}CHG{^53wN9P7*rUBBO<3b? zuB35&7s$UWt8E(cc5SqIR#`ow9(fUTeQ#52D&SR<*McYx5ds4RKflsVxJP&^skicp z4_j}!tb$b}Lw##XeQH8;Uc)#!(Ci~iVuXaEh3XiksYGf&A0ok$-X4F21EC&FRlb9# zMG0H^V`X9ELNL;opa+q3pKOmE_pCev$*!Q9mInT>aRQ#{5-1?9BQTISWjBPoS)yD> zVi7WE+<240{er=|E-DFU8bVl6!EG-_Lola86l5F+Cf$?XU@eY8lvF5~ACfjs9Mbf6 zwCgDR@@N|nD6AT2u;P#LZgjZ6n9E6#j%@`Wqr0dy7nl1-B$(QDTvNS;q0j&RA$f;G z@;VKZJ&G5pHJ$%wQqCYz@;J-F0!R93+M5jxjcU4`4%xqmvgTmo0i%pqz_SdNcd)kr+ zB=pS}1ePTd#j`GwSf~`0X_$3!1q<^E5>*4$Ryba(QD3Yybk-OV@PHr#6n#D9h1s52 z&u=?0;I5?cFT6=n#*F&f>CYK>MUk9#xvGZwT?ioST%K)-yX-@#6~rUtw)(}@qOw<> zs=DHYA#XN2>IwqmKchtpsRWNLhU=N4I_b?xe&5WZi$RIEM^=`+68U8n`OuqXnQfo% z^<+DViH?hQDBgi;(T5ffiG$oP!~@y2`sU!3x%!cXsd=`+ z_*;_)jf{Xz$#>lt-+`ZJjV^D{or>bN(^yctUd(d{! zc2ELo^rDCESAb*zF&9INpy2}D`Vas64P7E)~95T5p$Z;?kx2<9nlHH zk&okCUWm(`z%M5-R2)$QOgna1Ke-{V3JGD@Y6?Wh6~8-@ z&i^uCsJ5m4S%Av|1o!8I?WdWvUyh2ftsRP4AbJ6w)UAB>!E%}$Dl?l^*6MH>0@S}(hl=Fav ziY>~eBH$3MlYxHfX~*Wfz`abCa@HAwN~b4)*RQ(PKLJdCUCv!;GUJjXl+?Z ze;i9#gHaX|*J2=HvR&Ej*mwfq5RnzJ+wMJH-+t8D<=te?`im9H?_!oR)T(mNzvlItnDcmk+wEjQCb za|(;t!Rv95Cjff~c!FP0P>wG?zOgPT6fx^A81E$O)GpOC0Pn>23b@;j7~fdQioG#i z1q8p`65D(H)Z1G4+k%7b!4p8W1MJJz2R{;bMw7#VJWdZV{7OC{ED^pC_1g9HCzba+ zQzyHoAblY!+)9${vTx41X%KJUeEs=iC)TlZ#ZnN){h)h{NtFV3vI|R@pimTl=1Kg? z4a<)?{9scpy&ndQQfLrd3CCg7@>V^eJESH4MCEv1XhHcoz2u;Zg#MdMeYz2i=miAv z^in|U8iTi;$dqiyn~l`VSs7*+?TSSfR;<_r1fr+V!ovVg0r|n=St?^w1}_H-jqo|- zdi=+GH6QnFMg76xN_(U4@qG)NQildd2mq$51HGU9aQL z$o+IbxwAl(ss~ejPpP*glqOirl0xCV(EZYI?t)xv&S+F}h0V(r~e8(k>Pjhn#~?rkDwy zX#Q2xcxa{Lp{?_)Rf11}yP42d$iDBptrUaWpx#n~7FCIw)aMXYw}q_jkH-5Y25r1w zdcVNpi}ARDl4<|lS%=kMVwa@9^?sWW+gtn7CX^e$#lRCDzx4j)`oACWze4E`#FONV zqj+|`zSei%>eH;>ewy%+2zOJyi@Z?&v%{SKCWnq_z$|QmX=g4;rA_# zNDH{Vh5*fyx!NvKPPI~n={l{eqcx;-+0zI1Q@4;z*VaGIwWfy$4yzd|E17T(Q7)#R z^;PIR0shV8pA1}IhDC0uF?hNBn}9A>|5xlvdY17!P)L3MBIREc|NjYh|7-$JXt(=| zXN^N4JxZYT3rDxK3zpADVmWvJ5b@;=g}B|t)vtwEJO^^i%fYLP$Rab@e)zH1dW@e} zS$3a&MF{^#C>s;`gd@FdB?9}#U1kZYBUtntZO|F++_vl`7xVKmeo|?p0JNPsaw}b+u0i&Kk2xF zN1>});XxHe$OY3MY-4rfU@h@2@iJn{Qblm8zS(Z?>2J%}^TbFVyetytQ&}+joFJ6p zUmHU>ah(N*ze0%dY!wj{S-{-P#MchXWZLAN=>$t_E>GZ)6q8e zTGX#YK8w(0GQn>N!=Gy7k0T_bS|2312AoT!BMSyiA=l6DnfzEq1HF`{!WFU)BN#qc z7m;2Veql&;GPe-al=;r3={!hhk$O|#i3JoR^fDS5ic8W0Pg%ZEqQJA8aP#+B*TyL+P&rL8;>g|%Vy+pS<6;hFY6a)pDEF1K zWA+`iZOcWUZ|0NM#SCO`MUN?8pkmhu1mlZPUh9ug|MXj4Kh@6s1q%aRB$vRd27koR z)-8%@g9XXXWg4I$Gh&n1%v9|;L0v**0Af^_)^?(H>hhrD7j9+2SJkfHmbP85f{Xg9 zJw6p>GPJz*GGvRj}-$YfXrjHOD~*#N&nDv$Yf4 z6W>U(YNKsXCiE(i_%KLaRyaIZl!o>de zA=lDos~cK~&~>zu^RTL-zBXP|OTwi(--n3zwHE9%a;39~_*#74*%WYO@iDp_i|n3l zQa{o)E@xkG$Ic9w`UwS%5;IY3t=zoa@eM2m4a+6b<>L(zLS%2L?C+nw3DdE5{}hB+ zAIr;#ARi;L{&Q7`UPxz#U}m?b76+mY;g%B83*slz8zw{{IBK+=Ps_-&VP3*VpYm); zrAyydhNaC<0`s&D!F|$Qx)zb@qUb!v$6KzGwK9w7f63#D_m$cCmA?SMa*-E6AZ{1^15-~)4? zbqT4KZQ1y3emwrdzLX@ds-`rp!l+Nr>(X8B2oTx;Ao0`$%+=1$iZGOH1PS1fp z)~at}2~?e)1dFUq)OX?$)L`@dCfq4!(C=o>lCLnA3NThuO8M?h}KPC0HH1~^5NV;E2;2a z44Dak$gSEF1ts<>ODVu-0`h~b9!kh0F1Z%mX~A`p_S&NMz1y;YZU7EhZK_`u`osX0zgyC z-l8QQ+Ftu@5|u2w>-^Lkfkb4pID*0$>19M78J$rU_givo#mH+L>+x7=^Le6Ipy4Eu zJSg~gJb7(#ntiwQ602Bkpvh-iKC5J1@DsMp8qM+oHTEnXYMwRrpQ^$>GuXXV!uhIr zIQYf?3&TTkyEdO%0&gkpa}=b~^MWh0O(pfUvUEBo%F3a%+4w;I|HIUtKYs!&J^{{Z z@BFua7yE!|a$uywrlCoc_7imZg&K!zOhFnAzi0Q0&bH11vB?0-hQ|Q$?mX36T?7hJ zC)l|Xt#tAyBZrLA+|0Nn8Fghwr>@W#YpuSU?T|?Cflz*i9G|*_NG2`+WT%#a?bbr) zh|fFL>!QUY7OOlmB6#*)k6M-Da8~1+r-9f0e)Pim&8+B8a4zjVzCPfk;}^TD=3x6 zoEZfx_w(83i7wO|`nuF;2~!Q&)b=oASjXhH&3fDo5Mk@}@B)tMe)`ZXgnZTTyU*A? z)-L0fna3{lL1isiz_o>LLsFx;#HO|T)kesv6+>MXZcr)@pYg;jD6*^Onai%6fv40v0Fd+42Jj#V12S^3=T*`d5>R>b<%N(H>vrXlIg$r zsG=oh_`7W#fALYw828;TO49%4Bm4)A+h3F{{7qv#tpAi6v8H!X$Mi#3u`cn{q%tnI zSV78JbM*)Tv55o1SoH#=YT;CElssXiR*xf2v9~!1NyI1Nhhgbix}kz|MTtIl7fmXI z97TygKTKh3^huYA%VB&CzV)R&(vYs&bu&FC6?t@8-3NvNRZSjxVqbRy}U`VF_;J6 zEaYQz(s(!cGB;Jhdg(WLSNP^JSkYS-8A@m<<6PFrl*SPPQ=%c|Cg|Vm$4C2fmjiAw za+843rMc%~aTB3tSrTmg1+i1ZG(d%$_P(!UY*leSJ7r(K0fEGjD4rm8KkjnNDu6A3 zWk5vh2@uXCgI_+SCy3Ew&nX5^MT?W5kfk%!Agg_hVFse2gKt$@i+ln|dW!a(*%(S4 zFrGzVZcNMe?G!lQ_3xko_}2!8lpb1bnBN5^^spU?Vq%8f5m{Hm7DM&&5RsVaV4fJgj*H35TKkSO8q^%HQ_fP0GQG^xQqAC!01z#rg9*=xs zBG}Nbdv9TAiD-TEQUar^Dng*8rX>J1H?Oq9)w4M}g!`gpXLZLr*U{}V!3Qz%3DC1k zsA;&rCXlMbqO&516;zXhLS{=7%-y}XY-ee(GH)onb!Pce3NBb`|Jxa=A#j+46i5R$ zR-#?14gQv{)JM`)uxEX*?k5KK4E_6CM)b*YlJ086ErNHjfm3fqZVQ7FB4XBk>)}2l%;fF^0a!A``B}1)ZY$6%>1>f#%&#m zHjrt@trCZ{BbF~vIvav~eRM7#ijXJ`91x5gQxYL|vMKN_NDYqs+v_BglO zd9i-@b|^^ucjsenU}dmY=9KoDIXI_Bq3Nljo1<6nvG6RpF%A68U;i3?$RIWGZbEs2 zY^2ikB2s>uL=tB$x^%awwDW)pBZSZ)OhWCoaP@gEAkLEqhU!OtJu2FHq~W6$=shp?L+c?%bwZ9RNrKITBGuo0U53!+BW7~( z8qzutW61)~&s@zgMPQ@=oLDm!ZXP33%irBs9S@E-WoIZa&0W+iwAw7v?@&0hu4f?=+Em zEUUd4l5o09wAExZQOtwh+B)g+ko~;>g8tiN_#Y;Hm%kV1hF)~MddY-JjsnvNntvz# zc>V-HxFs(yitm_t0yJ(aN@iRa{`~yBejsbja6>3QR%??~G`t2MeJL zRWivCS)HN%xtOjhtxxe2!0t=xZy?^`g8y(&OX=(3>vt}u`LF!{LVUtS{=%0ocLZf& zJGp+xFdt6m7xaG;2Fk(WNjRc^rTi6<|EHl*G3%l}6N_wpXj~Z4T!xYOsxOIeF=yw! zqbtl<{;#g^@4Goc_zAIJfeh_Ef5&-m*7JBR0pxppW_O1wF}!~i|BnXf$p7q`3jUN; zKqAK!>)1l;()$$fD>%s?L?Y!(NuTZChVy~;ETx180JGl6QsnqL+Vth1dt z`;Ny=-^01%?g+r{uj5Q&$kt(8If1JNC=%%$iX8AI=t8*r=t_!v(>T+-%j0c_4eiD1 ze0$`pPDeW8B6MCYDAMlRetW@Y&mMHy$_5mfg|1G2C}zmJqzVf2mnYPCvw(cm6V&Nd znF3x*_rX38%~O6|_eO1&h?zJnh}lIl9-lidSV&M4_fgwczX8@|?CMyD+kf*;F!xf6 z6c?`~EDQ#fnP#^;J=0NX%I7P>+pyc+MlD}ior+k;5~2}DPwTsfN#n_JRNG=#>4CjA zAX@j%`*B;N22T%N)VMwH(H0U#-i6o4isBEaHlLlnW31~v<@FVAud38Ia*`GLn`hB& zL`Gs!=XgHX(j4F5;kSH_*uGMa731b+WH5ClV+LP0SJ)eYQYUS_Z45Br{np}kI00Fwz5D+i;qB$PRzmSS-1Cih#`#347Lq%N zI5V3PPi-;5Z39I?5co}MO~5?U`4P=jDiW4p7b{af2HH)!KFgZPB8@D z7}v+VQx$8BDLwHl%rg6(lY%IEdCE8$b5@(Lfj5Gw@aeB^$r70<-6(rS zsrU~aSfpf%F$FH__Oe=808wp+kxsw1~-eHj&46!#SbS4%Q%X~fstt7mjDz1B{`L~ z$!t(_Tt*_5x{5mPg$&RXElxXpz}`!&J{5hW6-lVS*GYutN1m6YaVL9^!8Z8Sg3`%5 z5IdJNJ7K{!Op|Rc=neuJ@S$-NnvUDE69{m645271F2Pc-BUsqaUE0|8iuK9->KJDA z5*t}(;>Vhnj%ERFsi@{$LM>BoxcSpCh zOyQ-ht69{)CXfF;W&{)Y-Zj`=V4Oc6EDKwwF>GZhwbiF8leUP1!Q)v7Xq8%-aKnCf zuE3~Jmy?EC+`so#D-d3k4%fRPB}T1hcMd6Mracnf9d%6KyAuSIy1tvLu(VWsvF|~` z`!a^VGC+M*Hz0Ba1!C%zcDb_pnpCy01sv9jT@rv=?t(&R&9FaMn08gbDJhXLA>Dl3 z*j7HSz*SNU*RL;!2FHz4_d`mFQGM$M%ptz9ss{nG*tH$u2{ZDeBl=4q`7;60qG;Ae zAk@Y=w{}KANVD!2foDyJo^DDEBydW}Z2e`>B`vvT$jw3~NG5&S^Hu+DSSq5C^T&D( zv_$v967Q<%K~#GlwU2z}qi&%6TKPsB=nlKs-Qt}5R2z|0ev6VX**4;C*t*&%W-oJ= zW`RJnS66M-8h*T%MwGd|z!5j&zuTSW|L92FfBY5L48PEPkg~iro&+1*}Vql}s>Pa}cK*EQWL@Go{1VMhP1-jT(dZ*P;dn zb!lKe2r06(s2mc6c&GUkdI{>+9Sgc9tTn=Pe#`StSYQFF-vl8FSj+Cv(hhbQ*@2Jt z#Vk-tqFPb&%fn=MqH^$F&-clh2Bab}(^>&N=BSj|1=?7`(Gug#dk)S#1w4=~UAE&? z<|A7xSnDlPVP63N2phccQ|=T+rrJX6LvwAy*~jQGohy8X=_LIri0Lz)61_$_rHQ#{ z*#)U_HnY`jBNq}1I(x_lM68TTs>i*qezvagJQN2^s;?~KG5l>3w9=KM2nRht)HEu) z{-SLhYxe+qM!Sd9$u7(fmXDZJHZ8lgF})w<<{JzXPS?s%sh$%AoM8p2JRd}6Ey5X@ zYuV~Mtsm=#+&7R<^yi^E3eZ_QpkhBK@^O-!t!XeuF>x|wwg=Vw;S1IB6N*_1rsL<8 z>FMz1R`VeA`WZ9foN|Z*B`{~3mQEmPRYyRXSK7+;2-O8z8O{V_C;_Uo0)b88g{;M< zrW`L`z^0*kc50E{XH+1Xl0aIe)07MAk6z5G^3*iPPKe)T8SJhhgqG+sRrsevm}dbB zW-D3?0J}qtOLg}^&SLNZ{o%oin6p~XA_1gMzXHx~saRBo%k#CXnw;Mzt3Mkor3;Q! zWHq%GsH(xjJu@x5X_3_1G;JwiZuMnIRxk zb=~3^Sa}F=T7xq1>y9rJKmAoCMew=V$EJd3Bg9)x?{bjsZ}n9MU5y0@5vutqxN)AeKo8@&9-1b4EkvE+8Re)49$2&21#iO8Shyo~U`U~OKk zI?+YPKJ4%8HY8S^i8~sNSk1NVUB>99FCzEm+Es}1h}m;Bb-J!F>Mq{wDd-{0(&vOF zbMxW>mhmSgp%I_WWXNT{LvIE}Y`5yA{&W(iAQ32lpuGjG;(Bq89atGyZ`-dE{3Hk0 z+F>+|HX@oV1KRyrMs6YZ;#bXdn|uW%;ggOdEDc0MK4!6C3Rm;J$lhqkoy2>@HT={A z^!P2(*piY<(aFncsURLT#mECr0A?4-K-_cj4asRfJqyxd7R6JeIx?v@rgxB>`i^LO z-qFB~36rMiuXvoXUleNI%6gD+HiF3ruh$!?^lPmQC5;x$$pVbko0MKip`oEMnFx5g zYY`1B@cTV_?`0tBlYF7$@&$bA{9fdO!-aEHSQvFvO9a3d+B2W3{D*z3QI*&HPkbALRq31QUx&nXnsBEMCIH<4TGzx4J`5|-op%a$fD)GMwrrsgll`MzCtSUNt_58T=|~(*Jo1P5(`({r9)af0YMts!w(@ORBNMlm-w>qqd>6(zAGbr-*Up{jR^i&Shfj&LY-AUDu2p%qq zF{H<}A*|;>d8Q{Ekb2LgnPWt-`y!7(-Ms=nL~Y9%dtFoQ^-nX~hVEnZsK6BH%nA_D zM(VQn<0fZ>$lD;7Y%)RuYZBGd4Vk*^OWrVvM8D9?N!y#KwD8QdV=*V`y3CeZ<;z^j zGXX8rcX;$A`(_^mE~dujb=gGM!3)=MJiy3saP#43zeF0Y9W_^18uQ2 zUA0FMTY(xUnkltS43A9T9{V^eD@>k0i(*;(cT6|PzoRAI%LrovV=C-kI=V6z4=H)7 zDySv#nQAfxgRp&ScICn)kz29qsLV2@M}i9+V8UNf#yI|2gftq|YRTZRA{(`rdsPEl zbAR=U40ldhfzK&fU*=OsY-w7}Sb#KbHDbDX4TePXq1+#V+x9gx*^~uv$9ef_`IJ_g zdhziq>t3bA=HqntWg~LKqh_v#AMf!{Klvr_S0rJ710uuhQUq;U|B%TSm0l>7p_ncw ziCsBz@uKqb>8&IWI3Z`Q2rG$eNfanyNM^9wAxvT7K&_hhR zR4erltsUmGX%STBycjsY!M*{;$?a(m=_60`pE1z0KLO+x+I`@;jxsJkx~p>`WRLKI z4XNKvM%^#h@@(0(zr=j|x0u(K#I5*S%&WqK{}%Hf#dQ7_^PvA5g|M z_VGaTBkmKR3c7Ij@dC84<~$Vp!7L^s`4F^2oSvy79ts^ z-lDH$vvhMh{4UK-EJdpFAd^$y-!i+W$SOrseHw-E#bE95%G|Q~^6}!SdR?x9cJPL~ zIYm(4P%%3p)olIFVm0>43D2ITJ((4ZOTUaz4h>Zn0_RLWO7qULs%c(d)&3bpa7XrW z%G9B5Dt-|Eb%)A12fl9VjaIso+$I56J)iKaM6KQT%^9%g{LvZJO?5G_fuT!NZ>dlV zJec+(+#8&=3J(ylSL9=ex+>Pp2* z*o8Ey*MH0Taw}zKVz1;wE2A|v%g_|Yjed-u+gj(T&QZqh=9#woV6P*?``XCP+mKSV}1E{=CL!m^qPQQ z#nP#OqpD|*i@(!waS{6J-1E&s{+XTZM~|lW=VH4(9&w z1q}FW6|G&%y*l&d`|MrX0rn*~1nET{_8TYV8^2*U^fZH&Yo&g*qrs)k**eOu;rte1 z5@rpxYD+kry0e+Fdx6m~<(T7Tu^WB2(kXBBm=W4aBQ}B$kv4V?2(RSf{ix&Mk62G@ zGBSPeIQzV{Kk7UzfpXbZr!++I1FPR661gGprEtU$1DY83D^uLN4(`6k&kRgzONYT3TLm_h64wTdg+KH@(L0vV7BgI zQ(;Em*`p7C0G`yZuKB|3rp~*0JRqjdD$kbE1}N|9ZASf40(3na*u>??};I-ccd6^_dtmPd2g`J0J&^&U)K0*YGcy9`ESp^l8DR;^g872G?9` z>-dJy+%q)p$$mwBcxh&NIUX`W`ok1eD(%vQ5e(G!BUhkd9%*1g_nFS~n;DLvmeitY zS(9`L@^|IiUiy%J^Aocu%3*UBr&RJZPKbl?_=Dyj09nb3m8RdPJcRXGiNtzF)nbGx zh*)KpWyF9@;{>b6-7T+?$9`5c525+JL{R3uNA^Zc?XyzC9;KYTJ9_R}CW8*Lp`lfO zBVUpcDL72ZY6?l(f2ls{!;#xx%}@6!zvu%&hN?W(u)MXgO%Sbcc3$FQw^Nyom@ZuB z^N@~y-<^Q*x`K+}$%@d;RPIly!t&qrq}3$eZ^l%~pcJ68Izxl9n`mD6gqLRZrCRi4 zA8*)~^zHJ2KwSVMr#(@sjbiqqNX>wN0L;OHg2Q{dtctKE^oK+#@fV>>k%o zn0_CZd>6rXk;*FLE+yI6lvop)@W!xED1Yn;pwXzZ`2zw6i3)}fN{GY*8y7_Sxiia4 zJCBv<<4g%NRE%o|PK>JD$@KNre(c2qcThrHN#5sO1OsEl$BmaXgXNW_zCBN6;wfob z%1qQ*$h_rQ05MYo<44DJ!rOEXy-_3ZCN zYXDQ;EH0RMtyAUND3TxhEV=q#X)h%ih}IuJe)89CP0cif*$q4=yH9xnOpnTG3l<;b zr$Ap?G?oA005G_BLWyC05TB+Krc!w;h~dR{x7(#Yq$X4`Xf318KN=VfIHqpsY1nMU zUkiXe$eqk2%*UCu!XxxE9-C@onVOW-Q0kX@J0a)7w6P+<594GjHl&9{Wxezhe@hFG z^An#4W3HAnp8>vx5_M1%o$d>((J}Y)Isl4cGSJDtL8nHFGo9C;c?&0=ed^`{xH)lRHyg5t99WX|8vfPWjH~jdL7ZG%!G8 zii=*OZVLfHz_%xW`_V$c6c@fc+fVjx>oXx5`dc{eY1OVb-#Ii6qcr6S5p6tb0Uqb^ z%{C|_-_w<+3|<6H8#h_xKnU}4@peC$?xRC@yCeY)6e@(BsBzsEw%`=8wsHoqKGD6ogU~D5lHoL61g5Gj&uMboC86X8kSOG1f|BMAvIRohu1jE!DMV*&Z;8dJ}OYDNJh-w#QOtmsH3h!5^#inPNZM$CyiCr|A$(tNe zoN+W-T2g-d8S|@muHe;X%c`qFLxasS=k995yw;I~*co9I6*CV7oSHyhD~1D{qq`Z4 z^9T=cF!s9shTCqS3_{pXoxx<0reDzY?YoV5jt$nwxT%>MwmZ*I64LUsDmMNKu)e*{ zoc|OLmc2)kjO9+kRdQZaU-qO47tZB52cp1H9LKpHGI4Kb-D#691JiZ0lff8~5=u_f z9EqZ$=1Z5CO3aFys_b3?A2hH=q|IBt96MC;0{o=6o-d62sN-`1DJr63t4n`5^t9I2 zr}0AbYaX?o^63QBSQdE3XL0u<^~dAqEI551d7heRfjF};_~x-~oIlSEOLV{9n|AVn zONTM+jX)ae)hyV0fiZ=wKGA}&4qunsj~wencZ)HoKZd5h

zbm_R1S(!=-6mCYY^6UC6bnG$K$K+uTOMK zn8zm5s~5KK9t~;J#r6-2`g6al&%SBNObmHr;t(FIGRM~;)CdfST3$BUN)vPT&yq3D zBgkN?4{B4?^Z-Q(gbkdXRj-=T#VT`e$6>0NT5 zis&2=Q;l{wPJLO9GD6}#SahC@gfITW-jtV0OjDBhyx5we*eU-j6}tm0>i{}o$mrxq zI}FaS_3Y4z#}nXmx4L$d^cf|qAoO+D|M2MPAD%@0-A_Kjuxy2M^6&?=M|twn=L`-_ zLOyYPzPkaVrNRU?SvW<-lMsrc$wSYU01a*?b+#E9oE`0HwQn$NZINGFg@-|tqnMq} zzLF$4KOpoVxY&Wg+E&3`XTRX~6H)rUd$~sx(2l*2#ainqKQWp1O~r*=I1xI@{vJlQ zD;c#`AAMzRw?+0mB9|OvK8wH&rl`)!X*EzdCp-TVB!&i8XF*WLoKeqQ#PmJ_*>_2(;7*e3_hTs+!DPIOhsW?%Pda zc}hr@cyKW=Hz=ptLk}zRvB!sKa<(ONq25d}N<00Y z{X;DEu2W3x9WNr#!md8af{oFwcu}5hZ(#c|P^y$9@3Z?UcUNekX$Dm=9|tzZ-6!RS zIOX%`%aStpfeAMd*`NVAmI(|ZDB+!y@(4BTC)o|rR1D^xpQ!tD6#276#@x1)EAJGP zgv1#>oyAdp;pn5P54V{>7PPCk^)&U*p!$;6ZKy?mV2*Bc))B|wQ%*TodxO;`m|XS* z_Oqd?NTCiB_~0gYU(TCPV8wRbCWqgga{CTFVTdi zhWcj}-{@WY*)a|eERL|+CZzm*yUK3xcSl(rihlQ{tWH(Uwe1I6<|VdIOi#-$qB?vT zHFnY?<`_Ot@d7xW;uC+PC*g8fr$}gAzmxH(xT{{0zlpjK`!KnRmHUPL?!ks2OH*}fVvvq#T4u-Mb?QxbYS z;4&b1YIaZ~ceb1$pqNOX>U*KQ;-< zo$wUQ%}sn?y``a)UjP#6K;%v=_7P0q&)f!w<3nJLht?unUCUhKer~r-zZI10I9sz6 zoPGBxU`*x$WlVH)b+mZG`oZ`Ee{w_2R{iAXl(UYCSN#|cU|kSzp@NAwuQ*MYeQ5r> z*aNihZA1vKc{1H#bR|V@*%iAT>b%QJ(r$2&-Gt+mICzy<@xPHPi{HHX!Ki}3FOi5ZG?uMByqSr zD>_=?a>{zX_it)Ui_g!fio6{#@@c3QbQS1Nx6_>b`xT1+%us-2Sibl&JG<_Rt)2b$0H z(AUE<^ifV{v)(5SiVC#gua}C#vc|1*+Z^(Cp*mavH=1lAzIJ5CS!s<{H9tciPak#2 z_B6%suPin|=gMOhfj5Waox?kgZPhNojb^Mq-==lAm8Hiu(PdH2y2W=rPXK4H|Df^t zmqyjX;6m31J`E34F)ht-x&Pi`*ENlGA?qX>44*3?_rdBVS3QB0{H~euz{44TVBrxX zTT6RG5jg-s>|yArT}xUu`eFC$?vMj?DzdSomMxh+5PY(S)$ol^H36Xz&NAR*2@fP?E4+0SL<<36AM| zt?l(l^~96lda9dEnV&^tfKkVr>-*fe8-Qc0tBhl3l}dcl5mOwcN?a21mv0c;*yHC^ z`k9p7UO96J+BF5PwJLK3E9RM#>^Gui#VTwp)|IrRG2;rdS_owFF3bvaF0J(*$x#^l zP~XvXnOuVM7v^H;w}@2pB#?^}k}JqJ43%`IsicHnS#JR9KU3sfFR6Ix3zcOel~AFh z#%3RlOreD|H3^E{Yo^cKarfHmw6v_t2$<^TLNYDX1(7l{65Ndw`cCR>Va^bN@zD2m zY@e+<3zX!vO4?g5H3rY98(*FeeP<%Rk)GPNt4l}_+g0&Y7Z6g!&wF@YDRsCYY8OU3 zyXk`WcPGuv)zb4YeGR*aUZb5mdG`=qIUWKEZH+YqkQQSo84)_x;a4(cgUrEiJQQIy{O z5=NH?M?GNHVmSwMz7TL&zW%}Xs1xpP1NdIAt*+E-W5GLq{`o#?9GhqAQX1&74Kt&F z8lEGOPP7cqzKzDtDr|bRk{;`-C1G-_WBGUu1A4Ru(R{?zp3n0rLF*#{h;P(4Nmp1x zO~l{3QA-7F@IL1aWA#{}nlGc;&$vi7m}|sluW`C9KS&UdWfb(%xDURappYiD=uELr zQPML{jP0Ya1xId0#2#r=Zut`rtL4r!N(=HddIP5LwM2^|uln~ME>yY{s97g5~ezZnCQo-P+z4Wb^(V6QA?H1`OLF5&_ zv5C2QoqAKLHPY^zAv4nfGfVR{Kx5?ln>o@fMh&WH2|dD8im~D#=8OjWIzH`>hAI9& zz2J2>j~R_&3R^3PF8QSPRBO2->|PC!h`lzVAdXm=beLk6vZL02>J}XZwOu?(T=-S0 zx8@G1wJT$sN}|g)G+-{boOaVb6N$U^eakaPA> z1QfZy#yx#)Sy>b%y&h%d(k0M(O5D+*OTk5JURgg|SApKH+#4cC6HzY!tQc}iwrdC8 zEwkp;I-|StyNnmbe(BrTfu8d=YWwjXxy|0tFNlwg4&B)@0BgsKijBOS_@Qf=YyRk8 z7*Si^&S!diX~5^wI8WJ&XQpN(v2x87kffH#_2E^w(o+BceU1WC2mSj2=)tOzfK=jP z;AHE1Ju!l%a~a17h&}FJSlyWIgHKj8_00GZdnoeFN~B3-bevV53UXA(W~2|Z4Kd#K z2sy73spT5K?m7ZH2tZdS>eQzwWQYoTjq|%1%OI;#{Lp?C*@ZW8!L{6?jTB{zwae|+ zyn-tD}U7%9j7F3m0FV8d%~AG#7c$Ge z1bhR{n~4b6QX-ex(S~l|?`x7gT~W4T-NnTi1A2N9046LDyR@_jZ>G}6z3u_0urp!h3l3X(n~JbO_UqhYtJQcBm|WH)Y?P};7Vj&aA{y844BO@8@=vur zqp@&2F|oRL*~Ij*hWmi&S^twE@S+kRZAWGV-OYG> zu^8O2`QOcYKSvQnRDXgSftH>ri@sE<5QP6<+i=Z-|5Z&}va3uhUa--f@M2 z?>N*GiPT4f(wg0pnw{oEu^L$16g!(v4slm6K0SvkD3-)`p~mu!B#leOAe*G5SiK=z z)H9TUwjRp_uc5<@Ya<@Mmf^d z3%UB?+qQMvH^M*LJg}KqqKyTCCYwhf^OKe_>7v+O+j9-o%e&@*Wg0MYa(Px|1tom5 zr^)#G`U;^D! zlIXfd(Om0G9AK#h6$AT>&W~NYGjNXV9qP}Wa{V#RnAoFr0l&-*zTg|O_GFW z_nsA)&P5%H4%@(L&E41_C&yrjbK}RlNlZWqnZz~`CJU1&d0EU|nPqi}cik2o48|{yevt(#g%QwHmIjapcWu!Y@np zMC}W09HHet+C5I@C}W~G`W)Vi#K*T!N)BLDGGf$B;qlWXsit&CjxQN|?((z0g>LYW z){Aj)KHP)Hs98*jTMQGDV-<1)RtsO z{bhx0(3E?VqGcRB_A`+lc0j_zLld`qn%?H`aE^NNW38sx8EkYoH0Bp2ky}bJkPKZY ze%W-l5DIZ!J-YAx?ufa7-f!?Umk#|v?!jd2d+x_P8fOJ;PpB+<;w>wJ2!uQsfMzzg^&^)pt5|B zP(cMGg?%S8Rdz|L9#E?8fl4Tg?jK>xF1}RhT@9$k?wLm#0ogn=d3V;D0My{0n!sT6 z&zww>cs3WeV?NUDfFR&eH@0Ytqpx9w%JNYVoZB_iUW2>vDS0c>BnN+gDXSR$hD$a0)_f#y zVu{r%U5QWf(*o;~ET3?PCju%?Kj?ga@b;NYkl;pWY)@Y`h#wdMM&L&@LIC*fX&h$= zN0WB3ac4*qh*8?$6%|Ls@%3FKHNrzyF_y}6(I2wVrB zW0}CW($$gJrzY;FlzF}RRXlRd)|7HsM`7q=f$wDs8Dnl_UilH>2a=e5G2G<6%K~9C z7iRLwQNGHFJruXNUOoL6u#`e)?IGZ3@uost& z^T3?@a+f$C$Hh>1ZPc*)`A{6n-$SBD z+mEj0@x;Ezm@j4L4Wq29tU>&Ky9yfg#>8SYLj8XsV6IfXhgVI) zDeT_&l|f-=_h$+U2bO`sRES_*IT^M5tc){X+>)Z=b5NA==RT|q3c9R%nS-25LVzAy zLuMra#3gUn;V4|n}{AOG)Oz-*%@ z))&v;Wj^CtFrHyOs0{P9nDLGK5z@6}haTWWbN+{?|8a-{UC8MY4bkN7?8~xbQ ze)@v;?ezHvaQc}pho{k`P^m?fV&Mlq1DZ0Dofb)jSBgOcVoh<<7iiEUXW2%YB_bjN z_;R|5d}&IKv8OgAeYb>jlxBFAlPrRB+&bS8I7&TlRCW!%?_AZ-&0;?rSx;IS3k7F(Etq(UihWb4TB?WP{<)1o;|7M^-Zd0v6Do|*gWude?d#B4so{LW?QUL}+K?rK3Bd99oSk8JVtFWCZP^uGDBf z@eyVpTVa|~@a!PpDq9Knoidm1gd%Qz5IAK53*D}3!GNWGsMb??`CYyz0)0M{@#K4- z8hMwnXtIu~E2xl^vw3%JWssJ1r|J+DFe-|cz!Nsx!s26rniQQNA$NSl5{}djVRhV< zAf^x1lv34r{&nB9z)U3;D$Owco{#(9Cr@RQ#e1Bkt$z6KL_^(sE_J8i6>1QRhJuFf zS90^T6oLoAsiTdkJ=&kB)*Jsl4*5o+*gQ7KtOo<<3BRI-MIhw|Ga}YzrK?GtA%3t;M-{F zUkGpmo74#W?cmwV#-$JeI=pB9^DjekG5w#qOgw_^6iJ`VmS|Ko&&j+T-Ppr9m6FlE9?|0B)OKd)B?n}&W2-*xNidZvpE3t{ z#cMFXjPGodFC(2L5PL9FwUNO4yhAq4LY=#sS0GprfVWXTHHz~TI}5`!iG`e^AKE$U zAQD1vj4t?-SL^)GydDCB3XYTaH{qGnB_bnPI44T#nL8?|S1g>uPYwo6J+o$I`-Otp zIvf}a=b(El0Tuu3`iV!OizM*+0eezu?3}HXd?$nYzULNv&P$ zZ}Zb#=AGHNhbbmN+VI+yT}KWA$S!XvUH_J8+TXqFr-h)%7V^ndu#eG?@DZ=f)!!Iq z$~jK{3A#@V#?EO}lRJytXkd8ts5wg7Kl!&4exmP^6aF`ZvBP-4S_Y*8j(Bn-( z{W_q_VWr=&%#Eb;qQ=ECO6%XS`U%}+?s4oYjLpR8(9sd9xqFks_8)TLX?5808Pmq+ zwKERE#Hloi)u2s}7C91_|4&H%d^Vwhk`@k5^tyjY#$e@wC(3hWwk~%o-Uv;8gT*AV zDK9n}37!#__7}pypMre8_2&RNSr1Bz*ZDN2C6SHh+hl^^74ofAGZgUdOOjO-;AJ3T zxsJXMD9F9>^~d-pEDYu^MDO?4%`yN0^HJu6?^poZFg`W(5@%=hhyWoC|+keU* zue8uy(Pg|iv}ORq%zRC#!@g=oeSq$tjsZTQ{PP5x@&aA7PK9&zsZcreF9a#GhY(*2 z-!I>c75@?F^JA?RvyJ60UE`YqJS^_rZ|$5@$0mHcr&KxrMetBSS@t{kc`bRvh0VVZ z5WY#c#oXZTK@C_`_UL~cBM&sf(w{k1=}J%nc*gI-0px4Z-hbw;&DhQyy{fQ=i0^_5aaOlT47O$$g;R zMz(kHHfC~KRSxJaB_+mfG^aKt_k0(%F4)K+vM1>DK1wCjzPbL47JQk@-!~YBc>%(3 z?0-s0LO1thZGqfOc-fHyS=(;Z6r#ILsglox!Avw?Q4_Dk9le00yYT4gqWO~E=$JtH zIQ=UU&?U`uDGN09 zn_u@-TH09tv@&JfHn>kVHMw`kL?-v9t<5^;Kvmu0a)vjwke8AzFS4L-(+FHQh!Dfs zAVG*6^tdlLGqA((}T?$Y$AgTtB2<20GC*B-UQjh)G2_>>aVu1vpW{s=rSO?14{-cSl z%qADtMxi(rmej+3@!Gw5u4dsgi2%i>+j8KWSfKu-s!zu{yt=OIq@k5%i}zLN@>n&z z;sBy;r^Jpn2&I7kTe4oH$%hZq)p>X&q2~_G`q2LJh+cG*dMgA%$j#H%#S8XN{3EWp z)rA<4jP4in=Qf;VEYmaKKJQ%vx7^xFZ zX(73Z6|Qe-^ZB{k7Ro3O@9Hr}>U5tv%E(xM?I`eMOsx_-PDX!i6Jc!IW_amL@?y=e z!7H+^+^A{zqLd$`k{_oOTn(C4dm@2&5^Ba7uU9(=J~d~r3+U!>c6O*~X1LyMZqy`S zz%nCaDu$#`I=KO(5b77XAhm~3o!h*(2-UdVPMn~^X^PxUYg>t-e>We$9O|-B3cTRL zE`OIKR2!804xz^?uNS6A7$Oj{GivH+f?wK{yTlwDbNFsla(wnc9N)QxQ;Uk3| zk(REOdI}&RhPJPadLrIp22Xgi=bH*npE-Td+HmS+NRSTF1zQEsVMl>Jk}sS3QB8F~ zMNs^(yf}#K${Gi_yi0M&S$HH-=t~PGLH>AU*e<&wOv8sE9rg#Gy~`V~NI=akDpcZE zZ%a#x%OMMl^os0Yf<~co!utq|ka*7<1{*yK)zA7t;jH`_;?YDwLBbxpz1s7pWuCAv za&fB6d!39e63DT(LAM9Ovd2kUBP@N4l!|pi;fA=nPTfe(g3Ys|88(Za;fRU$Iw*s? z4@tQ^6UdeHjw$2=&La9~qfnnEZwF4ie=n<8kUQrZ7+TlY38^?4jD~!4t#up4Lo@LZjz6na8e#jEzYc?QgV?=ub|zfyP&*}e?XPLJMEGQd)`8sO)1ly@!@O@}($L(E?FJfs4r(l*Bx#uswVX&P znHE-I7-r02d#;^D+b7uM$E70}$Cy?@BN`Uv(EA4up2?N@C!uGz@X>?CX=u7kN4&JR zh$bh8Rh3~{y@aXC2d|Oy15)}{!Tu-}!UExC3f$JWx&{6fqz~W5<3+}s=W#6ajcI@S zJdv(_G$M7a`9&9>ANd$sX-udtMd?Z@#!&ulTTOOM6*(fXqiyXYlB@tF$+HccG#fj= z`n0#_1WH(irdA;V?zMMr&%9&cz?#Qy(HxIqlJHzwmL-prWPDeVxQSC{Hly}jNrfSX zpwtx08BN3)eds88G2Q%A{lzDJRJ=MTl)yxaA2A_84HuSwA>i#i7{Z+T3*pCmRr#NR zW4($_xvh>bt_GWo$R&U-wS^BH;b#z>9gO6tBBxP)y~`?To}%x0g(Z=kVQxuC&iC+Kg_? zCJk5g)s8DqRfa|x@3wm%k^hANJcEb2e92BLeuO*Da4t@Gs)4q?u$5jj{n@U6+jI(c z74WNrU%md99NLYmwYE?vMyo(}@P2i`|EpU=mFsMbtI~ikhbQnIydD9c`A}xbwTLPI zXH@^u)qfE9-?jYz*wuf$#Xmi}sNn z$Y1dUs)$o3NN#YA;ii4NF>OB;5@)zw+pqjw4=?1&7r$X>_bM3qDjWBf4gO{lWFGnI zzOJ+N?ld~&F9bnh$jwpIUkD>xU*k^$3ftS}Ki`h2gnBm}P!R5TiF_$LQF*qO&9}Z9 zXc>q1pZot$l24M1w9BcY<}#T12|_NpMRDU=M|VX-P=_^|!opx83fW|MVxh!7>H zB~a|NKhy1g*#9sULbg1_xS>lOWt#X(HArnZLTjAxK%2p|lwv1o)wcJN%LkAs%YA^( za9>hJ1<<$4%Z>g8bAGAiNcihVbHXV8qgse`g(}YjI=WNQjX#phf2}M053ez-&muIQ z+G@}j7kla+Bfr$=efe?kWx=lpR-#w6odR)==#*mMDR3vj?Ff#$Qnk0Tc$#>ILvr#pPDhHZi{=-HGv4?6Cf9f$E zFMkv-DN8uW#GYrMzxB;j+ZHcq;AInR-7XHDqD^G@+lr(0gL(Jf$xg;^BDd#Bs6=@4CHBY2j(1j!$Q6-#2wTpsZmX38-KJG=EY{ z`>E%{6gS^7Bi z1A0`Fdlzjo(jU0S6ez1VjU*cXg}UHr6#&*U_Dfw(TUw^2zYvyn6<6Y_IZR{f3;CfAsB#h8i%6JylEO3d>8l^%zV4^l22jX8IM zNno$=ZT~bCsj{=YJe~>OS5~an`B_2ML)xhrsK$U7`s2BuCt5t}N4L$m#Y8$BZJe-i z$+p7@lMq>oyv&FxB0W=7_`3BmsPAHIb^kCw1^4_>B3p*@`x?_d1HJQRh0eg$0v-Y? z2%1l9LHoxR>m$7UR=hOyT??j@LG8<`6U(KbzW&UlT|DA_=)DVxCWy7jcXz<@6G`Rt za%V#|*pt^@_gR_hksjPvQWbq3qgaEU)|X^s1#pWsakGJGc@v(6`fu{BYn#;(^hRhs z=XF=>!%FEVJr7K6Smj*Kb8k11A!r&@eb&`k9J1qPIGg4Fs%?Amr!8p|`8MEPe`xqjsU#@bFramwNCv#&EEYL}X?n&QX2IAH|;i1Ba7EQ@7&5_`NJVg4U$qgF;gw zpvcZ0vSR3X;sr67e8Sgly8Di1-At@8s9K=D0-SN+k%VVby$sU6qnUyo;80E+ zKFP+57!CW-R;|@6WQZf8qf+j`m^JsfwH_;-5K5mIE&0<+|I2UaQc%Tx5oCHWKl;?g zm8&8xjaYh4keK&zU+WwUk!kVX!kIHgZvU4MsJ@846;o5_Nq@Y^tM28`67l9rl9}{R z2|SUJuGPj64{qjcT~$o+R~Y=bQQNv!>C{ljnWU`aKvn8Uimg?Ff97#(wIEDHSo*Ww0?yG0N__%g=a+uExZqZE zT52!HKW$%peq2}-hJKVqEITJ|r^+r|HOMYe>rQv`x%Rd5dt>cLPUhg}8~kb*CDyq% zAKqhGmse9nf@Ats0DF zIH8IL-$?ak66rTR9ZK;kX>?BKa<6iT9MjTHr;qQ3r`<$eCHX5gEoy%$L^g(=5xZ(2=Sf%NIA*WDyEZ{ICu`v1mk;>vN6TCi>SC$p*qWJhM=<=$!_$rR8FZ+)F zc0=83kYrQkTiOTa+@740pe$=GklY|a12;_iCJW-cYT4>2CT7ELQK9(+=4&yD0b9GB ztAA0yd7)i4-c!F9nwn+k;uXK2u6025`l{y_+3BBTC-S;KQa`ngW z3qk3TU>!BD)K~aNt-{(AhYYD19w`wrLaH^29r=EtoOZ^OGc@PY@%$dd#=sT@sW$;4 z&iV~}(i5IG-!Q!&*}rR-y&|ZyH7vIO3n4={I+gC$3SRI+-^Yv&_O6PG>FC&@C%`CY)|#fA7*0f^w&UuL-o}hMnYSNzt>xdJ*N&ihKb8EJr!~Q` z)YjhRR&J0-QS{ud;0%Q0bq-A()6b>5{_OF`qSm{O?1ehRt@dmAs$We!0YEJ3mc+q7 zGaCQSU=$wwJ}Wb!NkBKP@vD&$+|xC6=>giwb$ zK!9;%=m%)DnQ|yp95lAp56nSbGPFWK^uEyC-`_7eC@2X#iqj%_be8Wghn)Umt`Uo8 zutem&D54OM**(~g)?wOoLX09RHDNUO4vWs8xZ%a=p(Je_PkZVZbN))NTEPb~;-VsR zewTA;)IsdDqB+@}#xB%ie0{rFZEd^xh6)9_<@Gg;L96dHIW=MWx`4c@<}dwPgo^fo zBj#}X+H}s?1O!2Z{93n=T6n5Qr=Cx!t$$db=p`!%V(J=LkqnadBggsd-R=8i6r76#N(XD!`ZR(&QUwjEdS$+-?WWsu=WKt%3J53v!^ zrH5ZP{Ql&i)x?}3QRr{X5vJv{C?>HZiGi!FKj z|T(6%j}{JIq-JRc6FVAn}O@yXmho zgL>)t@uc#cGl|6X?Jj^ScC-&&1x=SOLZa*^{9b%CZy2I?T6y^c1I&!yF@<8M5R|Ew zOA609KR6)M0!pS50{A}Wb45bo7mpB*(nqf~-3lKY#lw)dML)9qt#cHyhcqFy z$S&NpoqX;nLmQg~e8`;e#TstKPORXEjU$BIPu7Px`H)BO8=b-Kb(AA^N^9uOe8WX*9A(z|L~L}#ZT>Fo6IR|=O*~!eJxa|%irL`0^J=kZ+Hxb$ zG^Oy9TI|`j-rAq2_+dGijI~YtT+)UV?C|6rBV)7sGFtQu;b(=Ay3RS=F}b!cI1QZV z!qj;h8vfOVkyF!1%C6Pwtz(XU@nj5{MRtp~<;ku7OTQ};Sudy|)F?%o(O?)tGphm) zGG?(G$e*n-0?psG-Sr({lSn%#l9wlvnz=r>GBL9N&B~SfNTUMBj6u!;kIABz!y&&9 znO24DKaV>W@`eGAJ| zCDCs+65Ovco}_+C%2DOTOj7S1+Mb;ex9r&!mg6(%2sxBkVF&5Fa0>=cWLAd>R6!`| zH_a7bgZ8w^?2)MB;Fp{@A}Hg$a2x&ZtbPJj0qk)7XhPN$$3Lr@Zqdw>hb&+d41tl( zq3QFnN0Uhp6UD!q7{Psq4X+SVII1M2#K<8693!Li(k%jAHeG-WeZ|jz>OlYGhk>dz zagx8$W%29OhaG?qSW1zycEvFl$jZhJd&I{s(j7f115yn;9LhwH3(~Uj@F13%=Y--q z5z%onUPVG<0u1vW90Bpqe;E7^2liw=JWQfIWy$O9`#b!SnRRV*4Fd!HiDU&GsR3q( zgoqCY{T#2WV3)Q4xAK2HsA^j<4b}`-Q9Q5$^F7@iq_uzOagiSi75sbv%yA)btkVgQ zu99_lHNvJPT3c5GIdGj(iIX#HQ8qcT_cdbS4%_+MXmYL;1>COYh0Exza#zK+c>S4mIJPvq${iJXS^Y$)WKv17Y- zA`{r=`1?-1b$3fNLFovqzqfQ{(-+Z{M*jFx8$p=8E$SQ<=@bNjZ`~6=O^P=%Z@+GO z@Ygieg)0CV%4o6O4T@cEnHR{@Au$vC&{KJqFZ=Q~WyYT3)*rVd6` zHhiy?yOU<_s3;aYEVHa`$E&gkR(2lh|2)z-WX}2UGu^@8j0~$Ay zc>`CTn1tW$XwWy}M-2aFKdG$%_6W}NtT^R6c#ebR)m58gfIJjk0o&CEB?23{uE@y8 z(f3x*cfy$}af9GCETuv(ajS1}V3FAG)E=xITjvcpz((597x)6bVlL*UPOVz)>fb7w zPM10Mezb7zR_=3pd%G$$T2OZilHhoXJJ!#;!(>qIfY@2Mh=^c=1^7s9)?jcLhe1}a zZ^yR(`I*rpKI8Vl=s`HMUc=v+Wz1+pDo++unLB4*Pm322&aOPTsziQw-;^I4QemKh zUM0{D-|$yNY0&}tWi5rB4+M5dL*FuPc`;;xhF9fRjYEupa_$4DGKX#^C~Mi<^;VCK zNAxZ?J(W7kn)stI=)adh|A$vYV;0`rB#A%FOw#40h;N!X*q=U=(LR=qybb;7V3=wiK|KYytZu zny6V(qzU9d$=Ha4uv#rY={oRH#7R%RytB9oJjhIcPG^~~M**lPr5eqk1#(|FehI9c zu?hkx<$rsdl-4NEN?YjqIJA&>m=9~y{M4ceN5pBKa*L%e1q>}p$~y_bC6Hn>j_otz zZS6>EDBMD_O9ya?DwgvJr+9)K-b{Bd^mh@r`dQT@g{KuS8mK6#Dlk4yBP#@Zng%`T zmwyGQ{3U+sZZMO)IXm`Ju^dYWs^n88 z9140E&76XE*+(8bk|_iRRNCehFo8qr?bS#usnL}b#nJ_z%p7OSk_!cWxE`48)d;S~ z3@s=wN{r^B`2M(#LG4F6q?M!PZb6rf@m(${{cNQvXa_;FH^C zgRugWs2*-1=a@KtT1t!H*C+4P!i{U|&d!K{(_dz$Ynw@5+z74N)3|t-hD;uj3VK2j zqmBDws}B^r9FxVLudUYB-WPt{*j%s1QxXgxC{rO7oD>vya+%bYJyC|b+m%3eKAWc4 z3hbGtKYO?$iyZ#q0<@$KOf%1`GCtMn4}YevHq|`UES!`Ppt+CI+*6kiFW|e!s+cf# zU~;(mFZtPHPAwDlsHr#|3%9b= zR#@f40&g@ofTXTe%yOz)O6i8!PX1p{TG(Dw?b?W;F4J<5xbnC;et9$9`yD4l%}U7g zfl@#!%8*$}CAOTb>W7Pin~6C)#?BcSP+|uDT0#>yfayaqy1hHK7adnG6`zC~V81jU zvM!^qNpotvx9*OUNuu`Bs{X+EaG{G(4G*qe?Z(<@EFUo~e{pXm1NMo>Pum8PU z(Cp6?<&NJ_O#3pypDU$_Z>1Ccds!r7CN$LnRa=j3E|eAY4U6nLKe6HsQ8379&&^abO)9f&c?Gj64BJ~|`T9yl zKhcj!`VAH(oP2>#4}u0m)PU2obNAq7hgUk#TnHU&d?qFvqsh9=wyt={wVaZPJFO6B z@ogU8;Ep$#eX$Okqw)K|B`hPknu_a8m74t# zJ)z|N4$0vK;jkZgwEhkP%m~s^!m5yC`BZ=$(vsfG7bqc)wv{bbfCrJiRdWjLO67iS zr03NU8;9nvN9-H5{Yw;de|tI+B=AOE+7Opf{vx6$=B~3G*WHgM+Yzh1ylT`8ns(su z)pT|M=znNl>AdlP7;d(zKlMw5N#TrL(PJQ?puS*fgOd>yVA6jd5$&rlqox5{Cw*CI z-nLF*A!M0e661=71g};fuTDEO>zQJYvxO`7#dqWXZWHYM%}P=al)MsV%G@kN^LQHg z5mTL;E?mp_8n%+{=ZPXzC~~`xg>^B5s|A!O;>AA40HJ-Ibv>DXA>3i?$c4TM4c!{} z%@|m1`>K+MRR|q1ovyQ|1;iIXu{B@en*k+G+e~8PoP^}{7BACh(LhZKK#7t=mTciGJWS@$+#W`dr|S$C$Azl{VyMs z)y7aR^JNErX8@QoN+cRYJg`t`b1cc=*aE?h!a=@EUT&3B313gV-$u%|zZDxz&{Xch zAh^fmnPT&(S>riOVf&0naXtEk551yBwzXafM-D?2`ESv*D7yrQX zI{xRpxtL+E9G`vNj%MK)PVuuhSsz3F7`e90Ua0cZ2Yx4Ly6>36T4d%jJrmDe7bK@g zI!NFw8K5uMdMMR_I!98yqiByCwILq_y&j~GtN`&gWwS9WMGc=FDv+H2X2+cIa@^Jt z94VnaEE{ivAbhg8g-aKjdA(l-*@Ot$_A{RYGI|)u{Dvrft9z)cR-JNZf0Jo{ z19d003Zo>Cyo@9n*t5rfl(Wqc0AQ;la+y9WtazD9DTwe9<3d)Xe9DzcGxN8;iI`0V zt^7tQUD+06#ESG01aLVPN4+W*KZ#*lD?W)Ubyw>awJ$a$zoIv-A@&E^Qd?vE_B1i3 zEj$nuN&yW8NYHP35b}$CGIbUN7TJxi9@OA#sg7#_8Gt-;s%RfgAQd~_CE(=Wgr_bD z*A!zOaQZfvI9ZOk%EAbN&~emA;^u*jEVl%bVxyaR~~^uchg>Qgloc~MDced z6?}Y8|7<8)=lMZ4OK9{g7D?pMjmEw~oPhY;5JtoN18CpxBEr_$bp^urgY-Q!*gqCf zP^FMYSlXEzDX42<`_0y|npuYne|zjxi0}^|@b`<9b1&fk=HfvM#0WSw5vRvMz-t)~ zeOtkaWdH4c65|hNP55Kv+I{;}Sd0dY{J>+y>!Q}!BtXO{LW~NiOW>>|J#rnl$XwEq z-16xaP|3r)(^qD(PR;+*Z`_mwZk&-OGSsQZ2TMMPj*=0vc-|$!yj*>`XMidckg^s( z>(azZp@%VUvxU$8D3pr!Npjt9I1{&}=`>0G(oU3T6WdM?Ge@YKtBaOi&idp!()bPI z!K5T7$J0T2H?6u!KV5qW^=8ddiNf_SPliRU6!lCgLhemy>d^dLJH0`QIV4QlJiVu$&gJ!)$5rS5F{0hQm|RV!}J_L?~*MVTicjP-<`lR=;pnwh&~dE-qOqsVWnWNma~ z7#a%Qhl^UY%AC{e5Fx4gN}pZ1+w_B*orYn)wwfdTQ`THZv*&Vr-MzU3JK-WL3PGRz zlX%m9Nd&V@u%3*c4*YI^m2B_`1En=rclAEU#j>12h$_6^XK7lYkdZO%B>xTFqVjYs z=r>K~eO#iBt*@DNd7n8x6UukUd2hSjw*D?m_SlP49$xr9L`~Rgo*E0;FS$0{U)T zi7ADF#{>-ZxV`8K!$hCNL1zSAiI6ku{S*inl;`+& zqXkE(DBSe*R!Z=sIot@vkd7m|^nuez-$vb@;wZmIMH7wbJ2cgnt3tA>OV0hlEniK= z3Qf80(^_`RiEbX&C6l5#yntETGGtyH=t)S9`R8;ygU6zCBhtN|C!BITG8-DC>6EIR z9CD$}0!lrc*EZT8yvCxQDtDbxCIAIR^YF*G2dwCDw$_`jL|Do3hA!+YTj2rT?Pdhm z;-R%?_^&29Yik{zdp=krL0@>b7}>%F_uL@ES1Ug#r7q0b<7-ClgsSCeXgqk;uo*dr zraDRyQ546$P_pn2w}lZG$5|-gHSS`1stVH^#esAssnDrO)%U98AyR;R#_4fL`a9=* z#&S13{KGB#*3aHkzlMJ-khYSrH!|OAQzH>lotWsN?+=YGnoX9>XgRYR;e7;iXc_@U zCL_uPf(LT?=z63qoGI!~%w}M>g_?4Z)te>`AJ?j18p@XB6IHoQ{Tc%4Y9PKYs-yR$q*SQ7nOAR0axfK2P8d3 zP*$mvn8sfF+E<#e_sI}azEWJ0E;<+@_x7Hg4y9szT)$-vRz#}1AOa_-Qtp=>(6Pn7 z?=fxUDm#!;U|m+?cMujdgK(O}i@aDsxtwos7i2U!I1?7|V>uWxkG2APc!$hbuTW@T zH10GBw4K%h$}9gZO_colR-HF;auW1==W+6|3yrRU9K0dj55vUC4SbK$ZaO~gsXL64 zmc*VVo=*bfcRUYh9Ne^!L<;N&JjhC$0WKbMJ7`t$H!2d)&Nw z_q(b84M-FyfzjJWB_h0sql2aCs@cp#!?fPzqwT)O>gE%&Tcte(u3Av-7Z(PV&Tl=3 z70R$q2;6W|5$TQD%zsHsm!m`_ud%>ZnVv(*g?p4g8k}0&V7eKX8Qa3fw}h`(z4b{1 zXC}o(CuU}5ydubLnrA^z)JatO5?Jn76$9$$;>NvJFoVQhr+oRGqv&;^4Gt%-LpD0mMUTDB?EHT3|U zt(NKEruS-8RTNI_uSc?G?>0F72&wm?Ej_3a2s)<*BSEVGmf*u zNp2nV{?gJEdoQR{MD>qWq?$UlMEZoL`Ab>kJ_=kJl~ zq_J9}u)&a`$4AjW(|{#A!KduooX))ExgM_k!ADZfvy&F6SC2X+mk&KFS6dAuXEywL3OWOZON= zvPUPNmaJ9i%2WeYn>aWMI)vEAeQWxCx+9GaJ_Z3dbC+df|CT!@N1d)WzKi;oK1b0{ zVOiF0f}Oq=`rDT+p-i8M1r|)(whi+;$Om_A6=PMT_?1jcTxIB&cyH`+9j)AJTHiLb zEtakPn-~Uu(wrj>iLJUbv@Y!}d(8ks)OxNgY}kH@_b-I4mi22s6%=!uI^nbdRs&j_ z=XIY37(6`F>`uBC{oME|Ut6Aje--|CDX7=qdnX+cq@|{r_GEwS|7!26 zj-g9ha_AUo5RirelxARN2!|3x1*Ahj8tG1{83qufK}tfpq(e{;1Qo?Q@PwZ8+|T>D z=iYPQ`^NbTHb3^>Yp=C-thLwvu5>X*<)eFV$+3Wkn0J8NHO65ojMFX|Kz93po5lhN zq^q|Tg2P$Te|{ByN1AiVZx-=qL$^@KNJzfRPUbDXPVIHXvtHzKNNl9kd}sXLwNG|g zlR(zWn86o9(XeKij0`R8&lyMl;J79N62QzMglgg`dQfh7_oQKZkO}_y;k}$6ShxuM zHjYkC##D7iM<3nepj97q!fHc7QpQik(F$2i;X(f_o4_#_Wq*=&V?J;7PtCv){F_e; z$;{1!6)6;@Wkpqyct&F={NPK7S&OV;XdM=5gFl&%z|SKIfrUxIsAhiB*iZz0CdZ-! zJ+o_X2Rkcm3kLiLheCrES=rpe9W|sErmjtW|7MAOj1NDQYcdp>o6qZ6)YCD)$KhyP z_j8j=w4j*Bg!%?gEhCIlRE@TyEGNweVX;E2d#rJr%z;ptae1}O&irsT#bbrM?1TyX zg6YqPj`Tu5ux#cu8ifET7@^`%J=KT%m8)6EA?lLw-q}?;d@^m|@we3djzYHlz-s3n zjpsBJOIjDLMW!Jw8bQw29-hFznRNcFURaHGB;>;5-szbLLxFe_#F*z4Zm#s43TOh{ z9^Tys9MVmQ?fJzQGvMlh9FC!bhw{do@HqUnC?Ym^$GqoceLGW@JQ8FVR9 zHb~cYY}F@YkA13ox+ZqiZ=`Sa2_1QD7Hy|a@-t+6Rs3_d_oO(x@Ca8!)Jiw(%b%_B zl3AE^disGawGu?Xa7VJqjcXn3YHjve_DrME>q7T9GaD9NYmKCIbQFk z*3;`yjGKeiwkb93hJunnVc6GyN<$N_03#&pnB6JUEUv6dFlW3As(_G2M6DSE-4a?lTgSzJZPYD{@1CS6jG#UMMRao``JPY&}S)feQd*|DE3%h+vu|G|FJ?abAmm zE@iY^2)jG{`Po6{^SC;G)uHgqC!Bj5oAgX9-F!7yBi7=NV8x^fQp?bY%tlUu=Hof| zb0`c=7`?qt?pl*2I)pK4&po%aj>Ba2-=IuA#K7xZxN1yVJO!SDl#ZT-LjyjuZylr? zEWGFTOdPuoG)2tv5zCS30=hD8qm=1)MpI-?rU4B;Xh5-(gyT0WAjZnZc=s=wrJ>ZQ zY1}Whfdtk9^CW98Te|KVY7St)XzB#?Y(&V zjcOqsx%dRn>4GYZxeRmE~q^?7Qj9noAiFj>Wu+v8$8qdg1X`9=$&RVL^+)WMP-Gg$$2ybthl3%RkC;Y<{wNjQ^pugnyO8qo+(SGibQ*ec9(m# zw8CF@^mMvV4gaDO$d}-$(TRyytoBDiRgl?{O?nW_yp3`4Sfio!Y`xPnwuk^{LZ={E zpr&t|cU~JjgI!yHdWaWw7)Bg;71nevyWhAYpo<@AZ0mW5NyjDHfulz&MEndp^QASA zkXSovm8dufc{px_XERt*LW=-@fVZt6>;vgoq3`-*UnDa3%c_E0Uyak$T`5xF<3eqoMj zaSwFimdi?VmY)q15LqDKYbtFYTCji)^!1B%3{(>b<$W+CL+o64w_lBsY0o(b`~qa)M6D#px9<;+h29s!)cxdBA*Ae!_YSm zCvJiC4Y5l%{4d>C2?87Q{zAh4p1JVfG{ydD&8iZ6-&O}YOW3i|AFiQ>8zg5#Fz&h? zG0dIb`KoEXFVowu9RALVvnWBGqFp+xO<0!S-g^r1VfIRGZ+omslcs%u6`&wF>sec0 zokp9zD8LMmV&;Z!X>4HAsrzLmsvO-GR8=t=f{Wj9DOpV?vuCC2G#FDnkg(`D zh~R23gF@|tczHimLZHER$I6dnKUBx$`_9Uc75%!Tm30>&YgM+Co!Lub4xIv&JYnoW zkxAl4wk|nD=A$HenmA)4J;GpK3-bHqnly+?p`;jZ$3qADCgNQm^BZY9efd=H*<$dW zPSmw(si+^;DSmz^Tx_iJ_xSKiKYe%qkQ*=W5xzmsm}(U6H>wL)p4k?dNMsj(hUFEW zFa#L+WsvxJdKEQibA4`?6g(p+4Pyj+;}Gbm$Nu_gXRmY)*9jsY9rfX!lZA z)fbBqIf|hzx1bb${a1Y*B|^8qnsLQ-mwF~t%fEN1Od6K8RG8q{DqX_P6|lP``Qkx4 z-Xxj>0^GbRP`Sl?C8-6wU7MYqadbKHsA3}G+B5vH`ZvSd&!#RxgFb4UU43hZlRj8E zgaQ18kCdL1dJ|KNpuW$N+q&kwYf64U{2-!G>$ITW^*_Ff(g!&bvYfXp+K}VR+UIyB zRp5ci5h+gpV&L0gw$%T0RaOnYn*0K>R)mhOgKz(4YL62kxNCOPHu#)~bK*d@ep=4$ zun`c4CCJ_X5>Ct~`Gt)CdhJ>$Bz@`{RMV!eGN;_EN_ zX`nvg{YlR%hn<)`v8%0SHS)FIY+htSmec|O1F!GSS}%+Rl9XHEEIH>W_jv`zNt?t8 z;%D{1Ea$ld&1I-c$ct4GoV_1ddk%`6g=;s$+bK(facr-N)2v@^Gy5KBdd~bb3|(aA zaB<>jwdp)47BMjq7M3KTC+G1Rpm>;g>{8>YXiCVyY$F8V2 zR+c=e0?TZdz0Fg|dE2@;%n(Pon?*mG*iG#%75yKBz7lZf2Jc!iRbmG{iBoTxt2%Rn zpshD4t}Tr^6+9ML6Ah^Yk6Pm^T}}RDi;PSa8MQj8%$W8QNIB}H!}I88ke*jA|doxe=K|+A)Q_{ow2xP;oS6u-!C6C_sZnR zyrYPVW1Exa8#@GV!q{@-g)`zt@TD)Gw7xA0N=POkmZRENz0$I3hYfanX+4AdsU)ga zfuj=!sH8^cT#`X^BK=1?mBZt9A7~Ulx$-ec6-25TcCb*{0u@;YCj+7QZna^5PC=Kd zj zTRt+ov=7>RLrrB~5X7@%TWRmGZ=}APnl(uaKOT06+Y-!uYalYH^2mES+4J3U;|Z8? zD9sW~(yh~UozTK@g&Hf_{yLcw3)Jis-2DEeV$L~-3SNK!aI%Zg+s&oY1VYJt%AZ`R zPent&nn#$7XcKO8HGB`vyD`28eB0|3|2k2+r(eLEFY=~nqRnSyfF;t{T|C9qK~$n^ z5BlgByES$=q}sq{+KUd7pHo;w+=3KFCbv9CBc^#m34>?Zhuz2R0h ze1kV4CJ;uZCXOWq_j2zW#u!>oi%CCmI=M|CH1zrbycZrD6e{C1E*hH|*Af^TQzI^3 z59?R0P;G4B`EDBeZoTAF0BgFV%X*yB{A+k+VuocDtOguo=_e+Gm>`MiHD;z};h%z9 zIWfV_OJtSK4lXY_iN50Dfs|~q3y+K$j`ipau!V~>Y*$~>MXyT&_o9t%g-7xI700pj z&BOq;f;30g$yGaVaYez<3IP5kkA_S~#mI6YrZDYWI}s4)J7OW39J$UOfJ*;6-d%K& z(SB7@(YuAk!mo^WH1K?yZZ3Bh4nsjRyH6eG-)~#?#!S6HezZAg2S~^q_n%w=RCu`d z%w^cj4f>gYEoDiQKE4tp=3f#fP8tp==#!l3nez^8(dgGQ5mxJmn6)v8qJ(iX&=w1r z?0v!5Lh;5uDnfbIW%s|LQ~(?U7D>Y-(x4&taof4zZ!~_9=GO{B?^)j`^~cVnJTts< zwyp11M=Y#)sk7vhfudaW8%h4mG1UsKdJNPy25B1#7MKjQ#+tuOqW_mf-G3LJ_rEUM z9(+8hi5oXEuB~aG4S)NT^_mmvu$gtUbqG}hG*`V{6&hMyKQTIPL=z=GK<3pt@R+(L zT4Na&>b#1F?+AN>6J15rti+-bq%cM!BhOy8PKoj(wlq4i|7iZj&No_i)~hmk4YJCcc&~eKcvkXb<1Keg1>JxZzQ1ox&`Hv^?5^PpfZH`dO!mJSkJ%VYc;zwpj4y!)&@SKO zVDF-qTo2q;D_d>{MaE_ZN%8V7TeoB|f^sYg-!mRFUm<2$C!iyJ0tG!M;0oo`qjG6@U&gF&@*)>6=oEK(i!yZdv)8@h$b$kqAx^4T)m& zEH#O?dhm>z&GB@SV>5PcX%SpNzgwHo(kg)uva3_+kyg|*ztU|H8x$#Ro0b@NB{y1~ zu}JtfMrzm%?+tJc;o;f7XEyf9qHYr`%ilU)mHqWG%FhQY|IphNRUJl0f>$xwtO)<0 zRS;m5_j4)0DL*sL=!;6i`veb9hk$zj{Y4izMj`GKL8O*kfO#H#^ zH8?a+mWPnr)Lz=+e8pse??ZFOt}txvd7}fHzMXnoS=w%}ak~g+Okm9KHtw?XbN;X-S{ZmV6362HExy&vhx|ZcFTKe0bCd z65|irzfu-;9!uI9GZd~Jvx1m-W#nvbDnL#A^{IIm_E-53zE+lE0*s@(wxu$Pp?@`Z2F zzlvhLAM4pA1+}zrY!I3wN3FSSgKB^gl}u@_leE^6qo>x)aedmZ>Pqv?xHT2Q2Lm}*qo5b9E3h}E@}_CTlU88b3`Y1 z76Tuoz)P&SnEUR5;|qzI&^x{y4_o_ynLj5W%}W}taOLpVjBj=muuWKT>-=weL{weM zo3rrW<8*7P3tf4geKo79G;XYwXm)ymBeZG=Z+LJ7bcSOA;ocJc`jaFjilKuh-nddvR3$8 zFqFMyJC2d|&I94eFRH8ic-cs6Xk_nx;K+0eVZ;lpH&C0gf!WH{0^dFo ztbd5BP^FNwuVWdY6wG1~xGYi7R7X-+f_TQb%Bhr~RIS)Xq0lWRJj-p!;Aqe`O;|_Q zWykCF!QXQp`x|wpWq?Uhl|sI8qgDum9O;$(bWLaX9Wxdlc6Cu!!oXS3siq;LOnA_^ z_9Z-Ems$nfPG@$hnnHv5lbtDxerfrWk~fVzMj~gq?O%+NZdc?__3w^pmeP8ly`7>hGyiD91b_HZHwu#9K$uX?}Yblqfz_?$KNX zQ36%4Q`k4_=F!s()S;#@)T+KlrSg2roxMnqy+e)NZ1k%g`b%D^85YX(&el8 zxE)ar&Yj!gY3(1+!u?(G-ew29Ixy@8VJkbRmH}!xp?(bJ ztLf6EEAdY)z*E9xr)Kc&c{wUTdnn zp2R;lr!e}(LU+w2g!_k$OQ%M!a|^vb=#jVjpJKbZC9S?5E5dZ+;jWoO_u6BgJ8g_c~|zm2+;Bd8vdm3Z2l&@%*A>~eP7R&$w0>D;YYrXZN;7J zGsnFnZVYp zTLXmE7cRBO)O+BYA1ibG+R)gPTBIPd^gvRqfOK&805#-P3lp%a^BzI<2@CKMEZZB2 z)ZaMKWbX8C?C4rNkpuus@9G%3}R5AHlgozQHc)_sn4O6G^(Pj?nl ztUoml4UTrF z=lm@$9XG&`uUcwFA!nqlMWmfM>`9F_#|lbl;7QaYm|KI(o&tV|o^Y}Y0rS2kNMLSH zO6~_18b6@f=vn={gdXWnw!9+WR1-%PP(ehWsOt>c%Sxs#r_kbndhl}9?DgiwS{X?T z3o9Kt9!$_s~UETwU+;hqO>@50>?Z$yY= zY-n=)xJ(vak7L{b*UJ}&FTNK#3Dl%66Vk0y4mnett)!e#hk-7BQsHQyM&6mfMSlG~ z??VqIm6zzk@7Xh>=fLGF~^WDWW{UnPu@~nc7_cr)~ z_wP%5GB9e5q}671_m6VR5bod0K*fX=;$Z^H$?2l&5e7;w*<$om?8Vd86HXqllQ(w< z&N7VZ(S=H*yE3H*5j#6k98m2}kblIY5)eQ#LbBJt>Q2N~|1~hIi({A*iQ2f_wiK{e zw>#75{k$V5o8XftIfzQIpRQLqEe31eUy@}@HBSGDhIVOjy4KCApetMm3t@Mz1nD#o zYBl-f|S#>H}k(+Q0yTR15?!*AB=%&$qe1G8XTV0g>x{(BAN%8<$a%s=T5rjV$tMLeo?5 z9mZh~(qS-IXmk{g;>b@kq1&x@ElofXz40*7CUk@a%igU=6FqXRW?x(UHaT18Zc{I; zaII6TZ-J5sCJ0E^={uNhk|gM~0PjqWs_-#oh<)6XMo}Ke50~^3-7TzD*WqUDnbfs= z)5GW5iyua2x!Wv2_wEtNUdk=d6K!r0Vtx!DhNeEjWr}@q=L{wNyV zR-J4h6Q4*9q?MAYC-Fcp`8G&2@G?ENDdJXvwEY0_dEnCCsZ%dIqY}l4bD~`MLhJtXwCoJC+eydvLDO|%WeRwzl^4SuUz-~jzEvP< z1iaQUxbgwo&bhac!XLH|sH(Ir>2SD)f*4a#N|If=kN%C}VA(OPh@?mcy5jmJ&M`lK{?gBS;r9tnh~Ri-5dg*ZuK? z&Ivj7A^i!lZI9+5iJM<7T@OM2zx`4A;y)&s3>8uUFUE~t7xsJ*r)~UKwfp~K$-lJZ zUlZqlY*CogBeW!N9Bo=FHQ`g+naPZGM`&=&$#X2$=HLBmf-<3}XQe-|mK9(5SY7*W z_yeosVFHl>JL}-z84wr6->it3$Fu2TqjZXU=Ddm~AF3-nWu5a`lrX-MLEEFi=$3e? zbgXUBl=@MHQHl0pw9JPwG60mU&CNf`-08?)tNh*3LqHc7T<%Fu@syIqm2kx)u49Du z0+bvYhB)NYJ8}o}X6VI=0z3IFSH20+%9w~t;YrV*GQBtwc#oY|KkW*L(APHDNj<+n7*O%Wm_W+2t1+fC;(k7{!-JERt3xyDnRpD0Sd!wI!7_Vnx6 zY^-qit)a!FORw|OFGfI4g&lR|iE0O#jBmSG2LM9&?P2z{yez4jKJ(&>%T?30$gkM> zpAru`HcW5OtKyOi8%u{Av>mrnyst|I3#>Lc10qa0Mg_QDm#3qRRtzT%u4)!mrhxZu zU1zJD7Coz(s~j3Z%FTo}M>;=HRONoU0(YesqRs#O*z=tR0 zO2>}WiHw#k%YlzWwu>a6*i8p8uB6jBbnrk6$!zMh7{5$^T&^S?paek%QUQC5b#%$u zHi>5Q)9U3S>1ivKa6AZa`i4yI$h!yel=^On<{sM~L)PL+a(3yVhPDHy_cl=(T+l15DIGNR#+SNpmbH7j{+)xs&)f8W z!f&9l{7*s{@1#I_kI{p|rOq$^?ydcQ{FL(BJI9)R(Et_i(6hF)&s&6S7qIKq6 z>m0;>V1*qT{*fB_mu>NPpIVC7?{k#3o1L8q^A6=N`yt6isG=3`L#HR-u)p9g{+6Qg z`tK{ry%^h7`@gPcf9~+_oAkb7Fft!wGLg|0 zsDM)c?lty#5j6R?18TkiiS#V|o~5`?x<;mj0iBG}9oN%Lr_Y_(JwzxltkVOVo`1Nj^7 zWKdFME1K*1q^Hty9fFrcr1BO$zTpbc*y(RjNPu*C5WjCuzkWqyNUK8}k0<4=ntf&;Xt^tmBQ* zb%7i59P{CIEH&RBzEVVfXI%F5Or+8uyEWFXsYh4G79`vw?lwJYO5W~_;HU`qb@ZVV)F8{uW#FN>^ljHxG`8P~d#w!2- literal 0 HcmV?d00001 diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/GithubHome.jpg b/Firmware_1.26b/Documentation/How To Contribute Pictures/GithubHome.jpg new file mode 100644 index 0000000000000000000000000000000000000000..c5ceef580aa5249eb3b4c70bca00643ae31e8607 GIT binary patch literal 76690 zcmeFY1ymee*DlyN1b1t^36{p4#vOvYLvVMO5HuvX1t++Z;O+zs?ykXtdw_&#^1h$n zHEX`P|GoF0HD9r)s;;x;IeR~6pQ_W5zn%*q0Q2zxo1nA)1VQNA*_w001rJ89{lqqH^?q|@S3 zU{!DuH@C8u@o_O%^HEec^|3YOGouq0LVpJF;`g$5vNv}#q4cu1b8zMN5~TiZogaGs zbeV-(2;yR9!LKSI^``{%lOXkuBI;5PHxtY4wO#@O3ihFaxu(nVEo1 z%sAM=taVsQ+|tX8Kp}PVO#tzkQpTvY6YM+nYPMxk97C#zM{V2k8GQ zpU@Ef)#?8*{Lnr^W%$Ki%uU?PC7}O8?5u1&U{*G0XVlqP`Pq5-Svi?`x%nV0|0D-t zc?!ng0sXH<{{JXiLJ%`ke$yxHjxK+=S2K71pUbwLwUC&J%O9PCp8s(IwF;#i3JMB@ zKj0D{kt)Bsp)7&vU0$6f##0009I2Ll86+Xe@ZfCvMNgp2}hw#5R#z`?=7A|Rk3 zp`v3Tz#+f@V4(uoh*UUiNVs^SD)`juCh^GZs%p-0NfVPa8gCL3bMgoXxx^$xLaS=J zrieJCG+&v!xVZ;aZ=Hf@Il09pOwC+_bGtV-pVRSp^w9I3No!f;7eJkn!T_L1o*pUw zy1~N1K+zyU8@aFnu&_`pFo+27(5p`}FtFHgI8%*@Gfj|Q zAX}JI%05J5)HBm)$9M6po(WvroP4(wGTvvTJc?1xezJHH33nis)~LFCmG7!5vX?T% zKqQ_ryM1OUfZH(L{(-KVl{s@nN;A*X*Ev9V`;6)c_=z#tHtokFp!zh_;8S6#|6*Zk zZ5;-_ySi#Wlj(ErdLE7#=56G40djBP6qDfOBS1q`N!>vE*8ITWMR|@R(3^SlAU&p; z2PPE+GOxPb@2#g-wKz8{hFjx>z0!qQds6X|-o^{Dq=|>Qe)AUD@oi zhSCHJrhyv*jjnJ=2=e(lV#2Mu8i)c`0bY4eX=dJGi70ga;m7YG3pX8LVZ6DD;x(_xbLGW8f%yjLy@z<2(FRo?=f+2=aP37sc!B zJKx{_4m@`;?eWr|$h^3BkbzwdZV*lq)v;lz(dt{gB}0QJY)t9gSO?PP-!`p!ost)j zl3tO~@~Dwk;>bKN0lSvy{^H|bYpUuevXczSVvBSc=oBHid_KcvK^*xix>6tDl^YY$ z5)OpR3UK`O{PwWbVJqs>hO1W^267j9-ggmF8dA$9DI4zai9VWW&zV#tGuFeM!Qfp> zBJ@7j%(n})MZ_GmC4^W8ZXk~caV0Gp&kZ&&j_mZWz+K1y{1rZDlDo>31QPBjyEmq8 z`ZT*WI$6=THXEM<8-98xP;sd@Ix{3#WI16O@gD5<5~4Asj$P}#PNDM%xK$_5V5D%^ zPtWtM*jzDio??A>`z<;vaT-yBpM~u>64oHh(io+a7s)B`#R|n`@Pt%rWqh!_ffbW2 zjkR}?pHi6W#7NgCKqJNjQ%Bs9erq;jfMoZbb+*#f<(r9L?|QS?)@PSa zC-KmyIv2U&9XpanM4~xiz^+|n?#3MZ%fRX{g2gl2F;guEu0OS%`VD0b*Oz9cHS1zD zJ1snqVa|n#L!2R6n!!RzTG4i1PY-O)DgHw=a8e-gZ-K44R)VNXWZ&FJ&4Dd(N6vD;-XaNtfnuA6Pg zJsh1b`$d-dPpj7H{dBvj_DY+^O6Nh)XJx(`cB)?9<|0lUsQ?TfB&1f@!R_~2t9P%T zdjDirqqvf!_??eW8c8_6MW?CxEsetxyfk4+9LoAnP-;l>w{+{itC) z&n3%F{Dr^9fOOk$x(<^J@%c+)-jR6O&<10_;hgUJBxtJ(oItaEyp6q0R( zMCw(;3888?H3)9%x@dgeZ5!^P`XOL&ySZ|WLPvJG<&!1MYh1R*&gE?76#(cvS8)Sk z7{!H@aHiH3Sv)_zuLgtjTcBWg00kNad~#OM!SD=C9iF?3WVkm?_4hsJ`@MSOU+ouBtEqVe7)A zma)7i55w6)WTtoP5&|CCN2?M66bsJ}LJV@65L*58_4Rgn`&|HgGP+-8-R-~2%il_4 zTXiz`-Hv$%EdY?kumB-c{|64w0PI+)BOutF#!wox;a*1F%`AF0WxR-lqZuX5GORg=Uu>G@#8cB+KA^F~>N88WUI}CS zXqFAYLV&Fisje)z!q?;lC5wM(n?!4Q1mLU&i#G=av`3Gi;hdhH)r)3$Ih?4rDa%Sa zHFP=GYE z8AUAf@;&n-;5zDVw#s@qQKg=@Si6tYq{21@Kn{TYgfp{5U3_>xR~LW2;nqm=?Nsqz zK#1MQ+BJ#qCYE{ituWDA1-VFz59NbtK%IX?tQ^oZb8Lf`w%QV@%W;~6ck9EVb_(zj zFhFSc2CCmD*Qqe(r~`x!{;>gU9lDS=9+yg!Jl_qFYHGGX*RhnA zeey??82;O&?Q9Dk!qA+}PVC>8t&*77nex$2qWN_hec^Zt16gJ^hLJTuQm5i;~Plf$WO1ooAq=4^^K`Oc&?4df>5RrNaj@JuDue z&IC9DppXGvQIXNy{iGy)TsalCQUK`Uw?Ms4XCG_E_1{Zzcb+15o+|qO)*<`D7pbuq zC4di&?hn_|U)Lf(EQ+A_Ehn?$X8rykZQ=M7IK)nvYF=(O!Zv{Mucg#_g{zfbzfO>f^PCAC%r*VQhhB ziMRuVt|EWd5{k$_iZ0&M7;jgXASU)TcrL})GD|>hLAQ_JM3(OwR$n;$iZlDnr{SGJFlu#M*WtR$Y)42xs|%7(veatXqyf zUg4A}Lru1A!SG+$7C2Az`Wx+a^2%@4ma_dT-#%Vj_?cx*A_!m}eS;EK=wD3y|DLdA z(_h!qL-=}~c3rcsf}{tq5J>-d)K|otX5IYGn0yvNFt zx$Y;9>qiF;0rLKSMt-U*GkdU#o!Ol!x{lmsb&~di^&3iBTxcr_YSgc>BYq+MY>5d1 zls?T$f0@RAEA1o0zW+->`U{0L7f|?tA%j#llJ=wdD4cGA8pbCrY#R(4rmV=FJiuD zK#0bUYGQQTgMctdj(AlWmOl(Wj7(W{8O-ypCC>Z`{cD;~(WlP~o_gUU+v~S4sPxM? z<&Eq=6TM9E5umJHjx7m3KNGc!wj}61C|M%%h6ABpbgI1E#}ySkGUdvAGwO_Ph5vOq zOFRt_^%oP*E<*qj{SGF=c+ThBmKV&J$F&ZX2lV{y*aa@DEoDe#0UqDa?u{^x{cjBp zEC>Vl2J9jsFX{SQDO41`OQPEYr?vP!_)$`HUT`$L@Ks{VlAwG>Csr{h7D6WdJl#KX zQhK`sgm}6o^brX|n13&hxH)YK5iLWyOmNu`?#GlI^4^~P>C)k4WON#GuTwvsA6wtV z@FQTI?(!s>NE{9%xSf1Kmnwqg7Oxh*lxN4+kfsx5y6uc+7932i?7>X;e$BD!rF+3p z<=BM6Pg0GUS)=?hGPN(W@GJ5eooWMzD2SX|N zoxh}O1ByvSG!17R`<2LtR=$;w9B+!?C|P$ue2Q0 z#dyd3L*vC*PDK_m(VSp~Z(}+Qh`o`UhY(0eupS8LB-=u;`0m*{q0h7=4s-$h0NuAb zdZ9;W(K*#}Mmpn25BZ*jn)}5Hesx`U%_QD5d4UwN9vOokK@sY>NPG&q)(}w5uOls( z(LuGFX3pABBhybj<>sl1n?laAxOgvasOa3idGwk41Tw|+#jW;cZhA}$#5p|^%dXGY z6%{%GIpanDY$!5#OQq8y?tB8e*33}fbmc8_N~~pVWpyS9j^$Vnk5*vvL;Rp&{yZ&L zdQO?Yw6fB0ZniG=U4&^e(F!QEI*=8(ie@QL3y=<~Td+(n9JVgb*wG>Bhr~t3_p}T8 zO*Li1pSBZ!bc=%!v_%_JbzZ=GmZwtp0HQ^RM6J*}zs2n8h2w@-1igP5R$Te1utTFM zUhF_~OdfaZHMZvp>l)`SdKcwM#$7#a64&hEYWI&y&Ug!(zOP*<2s=W|1ouDR_Wyb} zF()A_D1Yvxlp@dsvM>i#wM7?FLgF`R0NX(*W6=*Y(oA+Ugt(Hk)$;n4{t%82eM)E$ z?@bd7uPrAyO7r~4qt9PMKJYQ6B0w}gV?&Od{SZdnoa&-{Z);j)2PkN|5gA^z zZ9%T-azEb)b7+3hMmY9)bO4hex{^zb-K>_LeP8@S@or6BbV*^f+`#Z=RNRO>XB2!} z{}_%KX|D_hCb_NRPz#}qmWgxncLgI0wqe_kCHCz)X08Xr2R5(P3t{GMGiDn`FV4lK zF?h%I!G_6sd zpO^P(^6H8!L8UHfx;*Z30%a@p*u*OKLtCaY&6p#W*TAdx=B(8pCP~+~nIQNSePe63 zco%sk4}W#@moF`EDanSU;k+0kpi@E&~GClE8MFE zz_$+x{N4kcLe}bd*5wcLe(yj2r}_U?SWw!GI*J|vbriiSi|MDd*P8JPq{Ap??Y52K z>1)5f0K_iCY4!Onw5Eh|dGGc@)f3mR%8OXYY}2F8p{oydh7+^COjik&KCe~TOQX}+ z1>hl$QK4HvDQUsZ4$~~?T&%S^xvG!j%cNZp_B^>CE(K+jln5C{uH#mq1L-V({}J#> z_yOj@{FQe|908&*9k5SewyL8nu`wJ=FDlG;9Km5j(xo8z4Cuka`0S?XFy&>RNkN97 zUbR;kPd|qD4gIf}a`mWWfvHbi?smDR8}HI`GBEN5&bSqBoZusms#~v<{q(bjX5zd1 z`M$mxVc~Pee$(rx^e#*>n_P!M)*&RBcSufYyr9cFesL%mSXke5MUAV<_;UK#Hh9~% zM}Bd(k*gH~XlQXkRs~OgfOE>ri<{lE;P?W6>TuKAEL1Jc8je9w*VIMTxqh-G*d@U* z!kg=;s`%1h-b?nZpY}6nuHt9a9}iTm2FjyIRM`m510?cSvw2nQI$*b$^7pmBw?JW+nj7+hi*^oL6^8@zt|+u!p11<< zT(&4$pR;-eC?T|1MihZV*SAPnT|_Wq)2|DmGh(90?>%4xrNhRt^TUGl@4W~H*8jq0 z67@$wxAZN=XfBrqc(p-EV@lh>zFt3L>_$*F62jKG3s1h)D7eL_a)P7K9}Xamg66ss z-4)fKkp^i;gxt&AJWYW|yaY^ASkXqQHB1Uhx*F%V`?}K&UxBv4ih;F0KJFyVY}@ih zNk_iOw5U<@`d}c})S~2|hkq`J{TTc64?J7W=h5bsY4amI_V(Zx6={g|K)!gm*!4$% z|Cd;v(St8cq)fp6W3sPaCy6klZR4T+a=QDsnKRQy)~{0E^r8^?e65@JMIm+BbY!+o zYVNVE+iNjDUa>98Z6sV;wb^)Et-7m#<;;v9J?a%5u-mRUGP)YuqGvznL#JY3#bCQ{ zDC&mKhC(FsZKuT?TRz84l2+Z_tyx&9O9i)QD_Ou#!B?LTOJqQ(7RJ=G!}C`9cD8a8 zo%SOk%x5|{p}LH_S#A+>sr~0y#S~L3?YjmA1x3v&3NrH*6N=_Xf@*`-rae-+zqX=U z?&r$Nr?k{{ONyE%B*k?=CR1wtJi7B4uWkF^e2D?N>WzqsbGhMPs7wuNDb8^duMn|I zk(~q^e6{RA83G6|#jj`WS#t>*HhtdrHLzoe-(=RSwMjG%=fFY=_|yZ^5@*P3Z=tRR)^P%0`6?y-eJiEechV?Iyk#SA+sLCxp?)+<;;EhG9L=*w)F z-Puw`AYdm?bs`La6|wIa4|=^}XBLqSl^@3!U=_rvEyl`KAA&4^H#BBiy$}*KVb!qI zn>{DMB|x+J!%J!pRwARR*981RFpScz%v>M80Gb4&xxr;0Sk$B#axd zOf?Lgtg<;64YQB8P7RIUkD$#jYW^}8)@knjj_!kl(2h>HV_-0A8qR8=}A=lGF6O%`F0OcZ_W(E!a zKxaKDC#R+hZv=@_rgL4$E!~P92B8)&Fscjh@GcfE>(?a}GMtc-XW`7f!ae;V#^phW zb%(j27{GiU)8AgJcCET<`(nQ?U@Bn9F9gs(xI1O@v+!r4H{{OV2-=uU1zU+m^9GOq7~POfaweeobRdcM zKeq^Mk{4uAZT=5*1U9cis{!WQH$J~38bjCeNA#mTd0gFMbiAmQ zD_~nzP%CBN(kM-8?knSoV)w#hv}-;Cn6Yl3wEAgM7CpXMJ45?gO=hPNh$W7K;Qe8l zN=cmMAZ?dv__(0tLPUXM*IGNnkx}G3t5t_yWoAo0F)0$mb6r6_bjV>yH&lHt$BgR#+evh8b_oNnWgFUKgx7pQxQTR)@ z=!WZXje%b^;0wQ_VO`dh8y#bJU<`iJnAM#^&iM#!VRfXq>JQ3-(h+sh@fn%EmNINY z_h?)BVEN8YAzqNpuY^W>&AS`x=J|9N7I#w1(lDWVZh-8jYoqu|1~|w!M-r4tt+`csopeij%CC(YQ z=_@ibhwlZ2EL&Dq9wJoHU6A|JFoY?ZFT~_bDZ`VX51Nwb%|c%^@F&-RT}fEeb>m8G z*1(s{wgzF1*kA2~v|e_TO?+r0HG2VzNuB2|*{gH8GIadvyD$EWIx<7&FP+_omUE%< z9y!yxE_(h7zuHkNz}@e1bIwF%sN4lM!z(vTHX#a>eC-}Ty2e}t75Mr4q~GNzO=^JA z$s`)y3u@GxphKpsW1AZ$7z@kN0LS>+{Qc(wp%C=i`Q1iM85`YOuVs-2D z14BmI)p1d9_5N_Ef|jYfyExlMxyyN<2DPF=;uq#JC#+bnd=s5I820(NCAVjPM9c=D%-yIY*-Q%6~K`rk+Ha z?Fj9{#JR`Zdeg&s0N~o(i)1z+CH=0*hRj{s@~GS$Z*uUZwO#^^X$%)opLWdStJON6 zYpe9Tn3B2fG^tr7$40Kg#i6WDcxGqUgAgz{RsadK?bxj=I;uIvJ{p|Jh~O!!UW+A^ z)joe9Ut^moWldKR#*KuW&O)5p%gR|ba<#pM%K7uTvZnfCZo}e1sh*J%^vkHZT+?9v z8`dzc(fcZE+xNjJon6EO$gmHg>Yr_SPe`(=N6<@iA`9cSGdT)lA}S--KYYpJ=31+B zCUQC*7%5I9Att9EIMWbH{DfZ*W@Vyh^yU0iQ5ZO~aChD(%cQ$Wd~X`$glEc?V8<M4}pumwA%jxcvGJrw53%0F_riR%GZDfB0#MZ=ZmT>X!U(ONd6i;21 z=jRs}6;_twO6^Py3TW%{if%d~N`+%_k4ky=+K21w`=tVz>!(+b{oHH54v+y2G&nU_ zB8r$P3B6mX@?3-C`EmpIiILSwvJ&hkMD+}p?A0pVKC5-q^J~v9fHKS7RO%`zgS`4= zI~~2%nrSptZQebL*x#~Kog6jJjLb}66$s%a80gkr7Z2N-#Xy!?*H#Xpgh3VqVEyHQ z2QZ_d`66LUnvrb4}sfJRUc{t^n!A#WpC6vK*hN~}eS5WxTHPo1 zZfdU25Z%los4~olFNC8x#DzYW6`umefI4f9J&uLCIZzxGGqUJ?Kv)5G)du0Kg zfUCx68J>7*u*c~$&b+;yHyly7v_(j93?An)V?RAG@5O&bh>%V zNDr-#fJlaqEytpTG=Y%8UElF>j0MsQa^&JqrP11hg#ahPQAcf75x_RkXLMc!EzIoDr^xcO*Xz0|cnJL<)1O3T}M4PlJZ$YZRHKzr{T7Zv}H>{s<__ zJ_{vF^z(c27VHrJ);R986-mtSp&>w5^Q|tPZUbp4vtv}3 z=H9RsCO?W2>9UL3wR9gAvBhsYC`O<`vtyhTd_@xk^DgRrs^7FKBnvVK&v;A7GHhEwfb($ zAuOzVK@F&6$AxIMxUv)5ADqT9N%ja1tkASElhY@rH^JeaAPbI?(y5%*2 z4Yw$`kpqu)Z?g4I5n(SETzLCld-#2IG0&2!d**HU?PhcLhgr5Rq{`*~!u6pFx{7Xa z&FDEJ*01@@V!EB)*p`}Q)BCN==3$FT@b{e*eQ;Dk{jlod7N|-bep2dHkC*wk;LL#^ z1Ve)QY7UAWD%;H=l@E8(Pxj9Ku=jVTlVJlk*`xxFm}C%K-?6CI0N@XdfZCx8c`|ee z?$iv)TXVm-Zxg3jw=3ajW=HGsE(bY;3_M1~6<5#r)7|fq4JbSsJ2doi+=r^I3gadQ zfm2OKPV3IwN|0KI=JD-DCF!ZFwAJzDN5C-euZZt0EFZ6#Wz9O5Gmm{%M>2{cnuL|b zu-byh;i-@T&=>0d@qmC`_6RWk_6R`F-bY~0<$8Sx?AYM=Nf}5#AclnmRs1LUziGqi zXfM#Xl6PJ=V(ChWk|TIaEAKV=JfC*2OPrar7j}p*s;svmHNY<2h}a#?Eql*P2_)c+ zwEy0D71WakWEG*j!Gjs$_ikI`ybt_h(|Ihg9N5^`d%OAVU=jOm+w zCAq-A+OJ5z9pR7npyiALDW$*kyon6n%{W;vzzSrFoJ^cB+HFx?cEGDB$xv5U?cH%# z9Uvj?m9_R7fTQGvi|V%4$tkw{tg`T`X?fq;+S))iOfVW(Vx1jiJHL}qFCGZ*iSHl= zDEjr$UQ7|W%z<^hZTdJXw7RxOc@IvHG)rE-CX5xx>+BTyjY%!1ypA(gO`X5uOq|QC z)BPhMN#VePD5WJ)(tICV1DCBBpg`r)-yzIGLB*qGwkI%syTW&6W$4a(g$inoDsd^t@5u_ETx-~A_5Ze{!)YrFL zG$rQB+;W4hKwE&OWySv2Ts~ree6>q|Nm>*_fy~j$#x4a?Mk6NPeV^doE&?LNvBBXt z%qK&M`ID#O8VWjseeLz7$OqJRHGIL;4j3$473csb9smIG;k?{R1b?GoKX>wyfQ0`( z6zFj+HRQb+*Jg!A1k|y%?E)_9ik_+{U%J~A=0#@(eRKclsRD*vh=T0hC0qu~eD!%z z^>+E@U!a2r;hr6az$m1P=#E$=XElG5mY-D}x}yhKs@_Z?zKs}`Z({oxxQ>D3<8nkS zHpECoUv`YAHm(4fzEW-q)4UpWjw_0QF5|wBbC^d;8LG_zs4wJNQ9`d zVSm^B&7-jky^PDI#6*Xx*Jy?~4_l!o8g@2m+LLGq-ls)Dn@z&sQ(WI%IhQ^3EI5A811b!97j=UFupTye8e zxq%7Z4QuK}J4A%7F+mo=x+@)2dR<>1=2Kc~h_YE6t@~<%hJv(bQ5sjDFZxtnV@`5% zm4PO|eZ`?c`<3fz-{|ck-0~{cNmErzjmy-stUxTAy%?I!5G{9TvhB!_Z|3R-80{*t zranV%lq9Q=zQ=$k1;cA0oSKVS=swM13xaPvxjIdv6YB0<#rQ7ug9KGT&S=qCi0pi3#>eFYBKRZN zMTMWcv~6s&^;GoK=7w&XjyHOs!+AG;s|Inq3^xskOk+A?j=cTs3u4GrqH{I3s0Nd% zon82+@?^!5$hc~*@=fOrpn^4}Yv+)o(Z?gQcNR-2dp0O0MSfF58;YcK+N1Q3NZ-$p|nzoN+cecJJZ00k&sn3z1?Ag+Mr_2nE z=Xo0${GBxTJ4!bef@YrR{PU=vo{69=Xl)RnR+WEf*U%hBqSXac5?zdJ?kZ1fY-MeYWQWLUY=2QQO$o4zE&kPl^fTuX zAW<;s(z^ga5&#BaAd8SpPl>AZ%t_5T?IN{$RVd(7fv#RGJH;(au?=tQc{rcd1hD4S z#6+c^g#v8x@n3kahqeTv2<-BX3CB|N^UL%R!y)$i-Qzb{Qjqd&Jrm%)UFaZEh5>^i z<)#$4GR8f=Rp(#@G6tdpUA9QmX;xwGVTVy6ZpS{nKWu-5nXVl*)!x(Aoh5*YR)F;H z$dbCF07$$>*#iPz_a+@~ZCN~+NdI9SplwV=v(Vo+a@!sKhY>(Ej$nqL-5T^p@wcD| z>OTp!`s8w)*Ezoc7tk{89#*)Qw{d3^-!jw+jFX9^s<+;Ri>QNlFGoij zF>Tak>tHrl(6=LiKE`wz*yNYId*(SMF-ROckTpKX>hsoC^apI_xgR-40B7Fdsn^Ku zWFQUwo|V-BV=03*RhVuO*A=FzlR4PRR=(9~_RTr`F>c!8>(k6%5sHv(q{y`>CM&DW zccL`n!{OAs2{8%ua9_1_vq&p!U55&dE|(MYrwJM5EY;Ms#_*WOQs(T~S)DiH#)u5M z8}bBcb#%DYXMe!Qx3(?gW7@iS3cv-%{j{ld{HPwFMK{~7a8FpO>cB2@nqA{s!b1$q z8ZQ4{Q7B7Jroq%GZv+~JX$5aM=yLN?P`^vQ(tF_;E!Si?NYp2of4Eb#8WZcuymU8X zwI)*hP^nY_ms>%)hfk3-cvX>Ib+?e8F$aAB`4}*Ipj$)}qgSUf88uygq&lpmc#RF0 z8P>?PESkT?JGx)Dc(3DH!l5zxgVmsO(!-bzgxTGq^<67Z5H|0;NvJM+_LGzkg7h~R zf2$8w%?n`mv`=%tA|C`wN@uEueO_e9PNL^Pp9&Jaf8x&NCTV{8$T6B@3NB%*4Y8X+F-8h8GN7|SQSp*g<1n`ds`Y5A& zB$nHkj{q44_rKi!p=9sF!$?7I_xOVdL%`(w7|D!O7|Aydbb_-3-6`)^U?$%;tq04KQ9(0A{tt%9A zx~CUSs=p+9&zTdrY63SK)dFO`w4bn^NL(@!0)D#GeOPPx z8}2x=VSpg*ceeW+g&#Cn{BpBqzXqNZGgC=dBKGi@VeYoSLjnfWe#v|Zp46;4ezMx@ zVMaEe6)1MGvCpCFssCha`ZBemr4p|rp3U)}t|>QUn(fVQ`QzVRFaD(E^% zWC2jPjmdA_I4oW2%PSqE?+2f(H0(7dUQzAc!G~Vl+!fv#-~X_`W2TKc$lQPZyD_eU zv>;n#yglHx`pHX*fTIq{-Z#e?`@zCB9&5RqQne&Hm*}Xwr#A|h9XH2Mb{!AW{;G-? z=KB+M_s5Nb+n*HC*NxJij$?A zJqsbfM)d;TMOb=JEyP`tq3*6jaeZ0ytN)3QvvybLW72>44cg(j)rhuK3K6VU_%*i< z`Q6OlxIOL*_>Bb8zqRZ&CVOs@MUdZ#o$}tuUbbZ~v^Y*US3tiTmM>WA@Holcln$Vp zPd!m*LBw>6kx zzWPP$(yyo}#x*wzIm??@!F%%)t8YKy#W+xTW%z#dQN2GCy>zn@+QUc;KmLL=QB`r= zJGvZWN9C1%2W{;?gkGB{f2~d^_c{Rl2$1TlX~WfI;8>C|q!QXwOoI8D`tgpNtE_E& zg)wI39cG@X&RXF2qIAK|(2cc&@O{0Lk&eCjSV3s>&mRpxNlE&rMbVn|BX4jB!^4|N z3k>g{+Gl%KP$!Gl(w@{$Sb3Ju$=AfrkgmioOKx_cfRlwwNehfR@F=AEV!Q)=v&5H? z4Jpa@43h#L^q^fc^UdK`7j7YV1mu}Yw{{ASQ5|iwV82$UlgoaBEG-pt5VEf(T=OK5 z_ou)#3l65+pM8>+Y9NPpKjx|X6BRdapWRvKEg>5+{Cs_<@;f@VCQ~)=G|-t@9j;jz4ZY3>Y({3Ens*YS`!7%Fx>}yB~ich7qut)R$dBAOU0!Z9Vd~VIR4SS0P6eJF=!=C zbbAC$R#DV&LcIo0-N=*8y?;GXmDh$#jzR-X9thew?f%2x!7qXq;?AE7PuUSTR-O^8`Pfc8KlXzwX)X}arxUf;%<#=D^KU( z6N%9!!O_t5g`X2EEUZAoCu*k*AE)d`WVdLJuf#mwc$Zraz~DvSY3+Sx%^cF`LT@Rqk7!#_-~JGx4Pk>Mlpy zOdEU5%J3h}9fgh^$!obAcgY7*oD-MMsJmD<+HNBm-Y(EWA*||5*j!Yo<=Va^1brDd zUO%0Pk6(I1oh9q@eKEhOrvP+F7bolqPOh*B1GR=dC!85tPo*V%UdFHAY!Zet{G4ce z(XnP&(SOTMnOOrRYL38au~1Y5&B0mj`-LB=$M7sTF@MJ;GU3aDsFNqI)U2_k-#VBs z?itbxLN7jXd2iAI%8Zgf$a0c0^1vfJaJ@+QcB~l{%5Z41dTTwKF$+xYYeX;YG zv%_`-+e0_{eRG;M;jV4gF72#q+xJG3mxivOwSu<&3XY=Yf@bBdA!7Cl!{oi-(ed)@ zpv{*SH;QgUt6I>?!}eTfeNet&kX-5Go{_-w8`aD4v6bJ~M{hLU#)Un>Ym(wuj1133 zyYlun-_AS&KD#^uLdGtGeq0L9WODv|Xz<6!oNoTqR94s?>mxHWr$=7aq^dq4YQy!? zPFF!g84av{) z)MoA;Z=uCA$)ZhY)HOH5moO(8;8vbf>7G;yN{u~AQkj|K-Oq7#;r;A8Wk98u`@W)7 zuhsbEK%McUi(FRAG=HwA%+a|zt@2JIdyAz7zKrp?X6O>QU_KxC?dyb_gCWO=jnR67 zv$*F@d{~XsMN*?c1)P*-Puh@0dN}wElQKakTqH|F4(PyeXPKnF}^9kDJQ>*d6P@Mohru%+Kfw<3MZD*lz^sZdi_*`e>}cPiUNxMmy}&A5;<9GZAtA-OmjD$x;#Re8k~-7E%fHNKeONdTD{)kgPQ=XBN0&+5Tbgs!;tY)eDKbCf>kU|9TVfc|8-CKp#W!(jb1hy@ zh8;iGc{@U{xM0bnkVEC~FZ|Fil`D{_wW)rO9eZ2t=nRWjLzwuj+n--r$9 zFO=E^h#mo6hQf~ki%fN?utr|X&>Z({m)VTcn(ygt5+gv2nx=HGt5b>{_5M^oko0rz z+=aamDpcqXf<|>=+BKFGFdJiVN;DtN-h4NpkXXtu*??)G-A^v63MkaoNY=wsy7^US zRcL!Frn+PuO_T;?_nppn8-W`^osP72@Q%-n+C&O>E4Fc2^z#Du3b-nm^?d|?{&3)L zOQsh7M(ShE3p|G;JBOiV=}j>%QgJtjj4Kn%GRJ#78+01uddGp}gYE%i1dBYkG)@yJ z>mW?L+V;@p&On3`J+OW-Q9|^0RA%d;@on(SKIp1FZ*uC;a6R!$g2h+Y~WYw*iSHO5QH={OW?R~+WeNbGE5soRTtXf+SJ%J5oiv{bZB zeCujqwo4gJG0QDe9vM_1$E$d$Gtg~u+pyp=NXBN$jzKVjG@E=dyU8AF!VMSl(PpJ8 zHWB-V5`IzObHm0J9ag8lH=VN@#`SSr?C^~EvnF<44#BllGaj-7^V**E&<|?CBX6GP zJN@Dc8?d7cr2$iRtrIaMY`&mlA{B&?DME%edx1C(q#9S5AWt*Y?vX0 zDx|R|*?Q=*(&{Fnr{R3GAGGQ%CZ(J<&m6SKU*wTzwF|adiIQh4)9&jm5Lw`-r4d6^ zRU&54veS$v*6yY@c1Vt*TMH?};%$}f!NCssmN~3K{EQ31%tf0?5-t*SG2)==u$`3n zHX$R!Fnc*954_;Npjs%}GORbi?4wq`s>} zO?-MbY${h*qFMV~Mw$xiE3G!c1D~E#p%^!`w!zNip@`sOTZBIUCF_YE&km?cCzqOh ze(tIWI#DQq77T1MHQ%mtI>2GN+Wl-1IZ7^Xo?5fVF|HKdbb8!59gg^&*G0%#m047B zViXa|JqFULiL+f4?VON7wvXo zv?|>~f_HNG$$+C53en&ssd~(27Xy>)XX#PWTDaVhq3qgAXR*HU8MbQ3ZMpXrmUc#J zXQ)6s3e*iv;`4p6M;!k;N453)oz_l7=##eCCFFKR!O zF&}g`&p{TuUg-8ao8olQ)He+cJofCqBuJ?3cl>C)0rXnlaCHc)ptjD`qJbe^Vyf<2 zHpUQjck`<4QKOyNp5r$RI^$s&M#OREVk8vji-(PxRSte>LRy{!F#W&Sdh4h*zUbXM z6p9orUYue@i@UTyf#3w!LLsIMg>RXhfuZY6uv#xk)1kHxlnm=Ew#1yLu?!)krjw!Nmep&&Dlk)Mhs5BY zGrW~=DYtJW{PWX#UT_$>6S5#(Qs1>L1%mY|^SVTzd#ICoT0;ALN^ZDr6uV>~cyuae zaF1rFs?AI;Mu8TwYdW8E_LN+$Vs)mwZD?`_Lk$C?%2o$2u&C+p&F_|N4UTmFO>q%YZ7 z-`WO83`kVqOtj_M)uo&J!}CreNfik$8HgFAF06x7SF;$AS5PiElcTlD8pcxs>)7>d zuxXhXTMG>&pz&j%I3p)q0VhbbaG|15!FId}v9rpR5!C9tZgtcyG>)rLu+AXZ@s|bH zs)Js`n~C}qZ)Y(svYeeH{`!|ca0G_9WPux;Z^BHHf&^Rd9Fu(nc=+qY@dcwanm6ZX5<7QM(JZ@3-(C zAB~sa$SgpDCIf@{umW4(#AHzj>wZL+a_35SY~D6$gN$%_0FjHkLRwa8nA&zG=$0M3 zh1-NUsm`czy?ccC>oZtGtGh8~d3c>H9*KuLF=5!?=XV-3!t-pY)tF6D@xzAV81e&l z4iQ%L;_Aji5(%QzSL}Ptq3#bQYH7+5g1<|Zy?v8KIDrRIVzwX+V6#nzNu?f$KaWcR zxSeYC&I9LH9ANu-nSy34yAjp2G5m;nW`xpJn!Qh|ox>V?%N!rQOQI<8XV}m9&Ot+X z5>z3lhY#?FQ-7*yz4$XH2FtW{^jEI{5`O%ZNU;wicW;RTDN&ZEl>^Ut9OP zQ}dOy4%87+`uV1B3o?w3EX@?w!$%Fz(n#ukt}mNo`=Kt(adzI9?P0ds zU09I7x)Fya9rM~B`YBO@ZTiA}LGbnV0iBs@#OvaDM-r%ZQ=}`@l9&7l8L5WRBxbTi z4YMW_DERSmTCbV@uA08!Qv>@_xtVPxF&jOe`KreR!iXBepK@WwE^AaZLBX*OnLm z0Dz(4-7hcZZW^al)sGiE|FotTMi<9x4G2!pZ-jawkik375&!QD>3{iB)Qwf2`Dx?lV&)8XeE0`= z4Hx{yg!{(i9=H&~OJbCiEhdsO=1s;|aok9{43RhOwTNNwQdw44$6}$}t*nx}ZV%xR z1$~nDg928Z^(uB#&+1%L&5Z%3w^5=1cx4<>UeCQqWWW8PXFA1IorYM0 z630+p=yUh`F7YJiB!3V;@+Ffa*YkGXh~T0-u3#Y>N@FG*M|1QxXC$IqE13KJ{+rIM z{#77$w-*JAQXYuZcG$3D!L}1>tCL4;9cIp)B?atqK49}O=w^+hT;O;%6UxFJUNSHk zd&g`-68-GM>Ww88mksZ^YQb*Kugsy<1&pG;b8?jxowqtwy4n;ila&s{yQ`) zQ6L@kfMR0#6QX%`d+SpXEggSeLC1QxL4pOxZIRm9X*Oc(g+yzwv zC1Bf0O!^{>%>CP8E!&Vp7zKLYu~@8CL956Pu)*=x4Ua{>#ky?-gFAQu!!gx@Us&na za@fYfi%87gJ<)YENQ1zqTd{utAOv%wQSwxIH-D|nxux>ND?ER-39RMP(Ty;sYkaQc zx(c+uRN~`ahK{9prpzuFwb^5^>J>Wb74q_T6&hwP1|e|kjA0UzR_+@nK}sTT={b(c zE&D#umsr^Ccxi01uxBEYqVv&&3he{BYR?Yb?sHUE>Z}-X>oeHn1AnEWpH2cdb89GFrCla zil=D-moa?`b_}UouFl5BmL(7VpMu2y+T)^A;lzRfWZ#D*m3ULvy78`vWPss$Ovd;M z?x~*!UX1Z($#eC!qAIw^I*7ZG8(Yj z$CoE^1DVCy(~z!hORR+ED+bP*39ns$SX=LbN0KSN(lhxOB#w%z3{FQ=R~o*CBowNe z#NGA41_F=tWUwfe?<#jG=#&gEAA@R53U<)t(&8t>K$=2ZNtq z0`ep5mQ_BpM1rdVQMX>#9Y7w1|4LcVxq7zHh$wi_7*P9cjhZq3B?W;UTi8Yy^LcWD zP!j97^T9H_K5Me}oS4ZgJe`Z3Tw&BWAXck(p2d=(TMI5(NR^3BBcIhzVjJT{T*}Dk z&9XGa&|AGAMvn2hAa|5w4-Nd&~$JCCg=zaEGD2OAM9vGD^sh&u+RekfaCnQ^N z=lgw%dmZ&3f(HnYDm+J6X;4@>9Sc7OxdmngammY2lM+jUw3`Kq)k%fMZfQwy-oAPv z5TBOktWQ7#ww+3_kG`);z9b2aJ3+XS=Rv>JC3dGb?&l@+ZN-_Jmt&cqes`iEa$TU! zc}pfdNym@PDL9cpDoXI&Dmg5X=O#pX^qH-QNAQb|GH2SH<=?ysY$2p+PI3&*sq_~y?j&M^tlg&KivpYD|Rg2c>E}Vx@gZM|Uoq2LR*9?EZTPi&bn6p zX&26eGX~hlb9~~`8Xofl+f=?w)h_oatz&cRPT`H$rwLv~ZTHd$O%;4$B`lhpUck-^ zjgMu!U7Q_dC=} zn(=>9=w|u=80BEwTMMOcEc%Cyw#ozyZy|{%~d#5b}ME~v17V})R8GSKR|EP`Q77t>0{mFSBYm63;oZ7PmE)*1gYOxktnj^PU1xc^CZm{E9@EsZna4vXzQ^|j0K(tT53%!EVQEM$~WjV z&;@dNN@8m+_Q+1YA&~%4qs&yrbFSblaY=4m*GyjC2~=QPjX46&XB0up0a6q$Ck6Q# zy}}3Y!iGl0(*#ps-?(4$Hw=$J;q)xY&79_XnTATYGz)LWfHW10+6

2_zYVsu?Gc za=%h07R&XU4g(lg1!CODflV&tAv}TkYv6kokfM;9ysLH(^OVy1;8uM2n17-xy1SOO zkZeui0E-xT=$t6l&8w2Yg!Drde4I+Ye*h9MLgeKaWtbrr^YAbD&#bgcHLObPe}HIM zA0y&6eOJ{zW}dmSVZSo>rEm^M|pQPQ}dCF zZS8-RKSqwYq#uH&@3nPBUQJQd{O#9(TgHklC&h~{W85=VtD8^xr8RF(`TXekK6JyD zeDEmCOOW$3P>yXHTDYEKDg3;d8jfbs@ekl|n>c874;`)fSoasr=OID^?wr0p@`{&* zYWfZ;u})tt5`cOnz#Eq5(A(RXlRMH}kP}x|_g=uS0fs$GK?vQS`9D`4txnyDJcOlxo5{+@EEYa9_ar;);igoUrMv}?e5BG=o+s`T^> z9{Ud!5*%NKc%gWP1+Cvc+=h4gSzE zbyhg7TE17ATQ*}5eHUu%mGRli`UMK#=Kqn_fWLM6Lk^0)Va{(ApmSB4Sq0c_;Jzp~5Hj zRZW=!Gclz;9|jUWZ&GjQmC{0NYo~JeocCOc>g1J`Jf|HkygLZqeGGW>hF^V+}Mw;-H=B- zrWDsZsjy!44cO-+t@bvvQzQ1-6F4Ph^0zRbUXz#}Re;H&HHd@W0sDz?)Y)unywK?oXY+Hgu%h1a-vufk zI~0X@L1F6Pc6J{(0v=K?Hch4)k(XX}1)JLne=yuh8KLbn^dm@`)3e7H(Av{nt^lr+ZhKx@T6XhhdA2o((R!?;9~G zL{JX5b4j+P8*Hu7ew#5NWf_z$J?Dh`w8ilV8li&-=#ZN}j4r*;*eY}4;=S<|5M58nI*I?=no5#W3H$R+J#G@_kQ$OX_aaGH z(mhv@-r)Ig!k#0H*r|hDh~+~H@ZiOXwi80lC0$5RO4Eu)W=>^Uv3(qdi6eH3>sD}W zk)=87neH6XA^E%pIrsrRMca6>MBH^yF9Sh z+_FnuU0p|urI2qx>E8aRpvt+?l(Ksh$tK|~wD$bh|H`bV#Fj^2RMCje{s|kj(nh}Z6^alV9 zp2dPp*|+!+E8HaeyJ_EDW-f9?{{dl*f>%JDI}EPya!G4hx1I#wvH2UG zj{JIj>8zQ?Z`ZUuo}cG5XB7GH5YD@yduW$UOy^~EvBgt2W{2?_0gW0!x2B~74xZ^t z?ZJiD0d2UX}X#U?+;vpuFJSWAWGcw3?0fJQ)?F6yB{Nw(L%q zIz1%qI2lCC35v}$g>B5LS$qT6i2>@;`p?w_n^!z}*T zac+FCKH-y%<`)yOyU$@)nopuRr!5gfRq{ll5j8k?ldvh^o%9cIFPiud&`NkgYRc-h zx18)$Qo#y5_6wT?wGFu8c3ml!xCNTmu>AwneZF{X4B`VOgCLJGTX)z)A{4iW9#4sa zLT9F?MfnZhetv!i_lJvz#pl|Sisw0JovxUBSUntTK%{eUn;x!o&H;4B&_C&1durSf zifx^;-U!+x@UIp*9d5Dv!ZBRszC%VsRi<%}ZckmGqBp%_@Ap-U20ZG>koYB}({23) zO4DBCixer6jyKq7RcfUdynWf^rn=dn|Dz^l%G=|MngznH^#+`9qjax)FDBlS=l$nD z`y_^Wh*${hJ=HPYp>nI*xYhw;k@}|e)^uBGy=BJu&{%+8(77K-6Fnqx+M>#3vMij? z+y)fj6R~PFidv{OjZ+fM_=GFGoh20OTwzJem=Trku2HgK=orwbeqbCT0X57=7+_)! zE9cPA0o#OyL7vOqI7*A63SumNKN5fnsI?W}atN0NvsuBcK}cG1KJ8HXulHd(HAR;q zU={&k_NjeehLTcU%&Buc9>e8E1`M6B}h1S|8 z5(4>>_xc?|&E<5A!pTA;PN_a*Ghar~Af8BvEn7*!26bnjuEV>B*0erq144epKS0ZC zH#W7|+0fiuvX7S*+Enn@hCZ=UZQX!=G{eq6OuIUPFwUxJar?M~;eja=FhcvoOIxh+ zk?6xQ|Lg>kLylG+L}i=9iGWmI#reE=I;@`pGuj4{c7?sF!BbK0>}%c;s8W5kIDaHc zkHK}G2x$4zQ4qVLMmtbe)1$9VMnjgGm#Ra#MpJuZv(`VS^eW`(P1h#1Aeg^=Zl-2> z@vMO`Mu~mj*`=iDd#PKDkGuumCZVkdZMtRn7T3_2-s3+&C_!uY8X)22I@z;)V>7Oq z#DZz)Q2@c$={lWp70})XTEVk`05gyGn^y6FTOyA}UYOxc+PJ>G89@dCCfn7>#2)P>=GLGco|Is1-#BN+ z$C4lTUnUI<_jGTHHox!hW#QoQi?ieOvJ|2OX1}2! zJVf}D%~#w8Z@zO1cTypY2$i`{O8NZ0M1`8MHAlsfiTXQ^G1^ATdF5A| z&l}D!_Mko%{{Z1;T(!PGJS`qq>N6N|qp{srk|pbvWJ6Yb zj-s+bal8>a{Lj#yyMEKPJm4^9BH-26nrdn;{cg@f^X_xmb<0!?i0K=(I?~w^+T+>( zBBC{U*n8lau&Lu7Vp|Irkd{jIKUdSJIB&KR8?F9_$+FBH>F?V+N5@hg`{fxuZ@R9< zLkW6%!-e~vnTrP=I>Q_IsL_wSL%k2;GN5)(@=2j^J^z!bApYWvztw4Z@QUwglS@Y& zZ+1LXX#OyBx!LXVOC+<{Wm2dSOOdX!JNlL4I1}LgC=H)(AdrL&eBGnhWFR>lb|@Eg z+U)ws!k3rh2RgeIQdNCxg-Vx(U`bknsb|d1@t(7|Oy5ICl-W;wh8JxCol!E;@ptH7 z2i6ULEJ9ulX`d_aAHImkDmNMemfQ0S?dy26U-#ak`0iiK zvIaA%6F5i4?b&E%Psce#&qZjCy1}FLG;Ky`hVHgJNA?mcc%1PNCnbLgQt*1p-3rX2 z{N_lC4>@J$k6Z4^V{y5&>X4NsL(DhRw7u!=n(6r-NS9x`DrhPP6W{CksMa?qmiX+Q zv>s83E?L?w3CSthjBa8KAE|Q==(3+c?bY@(Uk7+a(~NNCnxU4W=EOTF4lW(qE3kv&k`PEHcBAosvwFf{VC{0WwRsH!Dom$mas=~b)JA3fVR$P&X|%2?#6p1jQccFWBHcsc|KBpY+^Y|OtbPQj1ZS;B3W zm&#s{TBRJQ61^!~O>p@K;1-&fd8r(vykkhUWi&ZK#qmYUBLNS9Wt=WZu)Zl8xy}J< zb8i2*pZ5>2+u>&RO}s+v`}MeDgf-B$V5_PnLgKX;^EfWQ#Q9zzKoaCPiPW7;S0u;R zC}t9x`-V^1xN>q~{)=kOm(zH(Cvz#sds|<;4Pj`{0<)uMu5$BOy>%1oy<*NDy3+wy z?s?TNfB2HKrSDv3+X;h#1}uA+GHz%})P>=R6dD$@>HGfxdWXh6+>J|Qw!T4lb!zDO zF@zLKo4gYuH)U9IA_yrol+{=Jb7^7D0-LErWl3>L0v*=6SGG!$x%eQ(1Oa)op_TT(UKK4fXx%KO z89(bk;~is_yy*xBy=iB2JP6!1wyYw5N;)yEq_UZ{TP;xI>!I3{>ZG9CNI~qS)8dwM z-{vyS9K_afHaBCa75e`fbAu*fyPh*Sa?ZVX>`y(AU~nlilerLkXLzrAKs@7k>4aI` z`av00)bvVjgh~vvr4#z}ELy)O5KC_=NZ1$wDtwf^W+_I9mIVZwmX~|2?xCCD6k$o? zxzRqfLB0(y`zLGx;+{&!q`|)&cFRy@LXC(bzfySi0N0h0*==iY^C>71VH%$}C=DtT zP8P8}HnltSTZ`-&iJdKEgG=0?c!29nRHfJAfnoVJKvOIYCIArIrEG@_}@{7tI zK;gh@j(wtBm&x4H3j&?AA)KCw|cgJxwEX8W1F&R2J9TOite5_0p6& z(gwX)B%BB}=qdSs~xR>ieZ%J_2O>0-i7KF0@U}N^~rqCY5O`XN%6`8h_3`hG&lqxXq zFissRodIEa64O?7G+XQ>A{CwrSQ43hi-U$_k-a5m9kaCy3BE;>Jhfg8k$v7(Zt)t% zQ!_Q0{{R_!L97(HulO$X>7u-Ld=z2#Yo+^kpUS`R2DobvZX&r{TyVc74{o^z$j(G$(msA9ZLk619;Q$?ZK5K(|#JSBUhp&W^Vt_w(j!(4L8Sc1qXi z-BQ~ew|*fsMk!%_{On5m%OdH3C2~e_3jZmZYuwwEv*RgensCD#RjpM8r}+Z^BZZ}g zTulpM&j({{tKqqdjaO!$Il6Tu2-o!8*`PPM5MZCGn{tgq~;t|Y6{CT}+K zK3(n+U#|Cum}Up}Q{-&knomh?-Jpp+k-J<2m(7mEeZ_2nk>_PWc?tzC)`0|P~#_?+0{j5C(9QNSM%YI};b=xTqK6(-sdJt(tVB*xwuU7uN#qrx!%JnL)H1qb=@CN#d%B!cY9s2IjdzMIlc-|9o=Uy{NzQ#H-={6vT@O`WG1-%~|TJd3<+h`PJ7i7OSeRwUC zujyrWu-o}WlE>_Gjv5Nu!8;*YjW9oM+|k?_ExMpht`23wedzHmNa5_5?qea=wbH5L z;A2(}p%SC-s*LB-$H%arK`#jRAt$%MhItg)dmwRx?~!=ySTfRvEp+0I3GRJ<dbE}clLWI5ZZ?pV`D<|{QAM|`LVIL0qqT0-9CM;NdJ*39 z<`uhF%E3uLDu+bE$|8utn9&xL#$@3|^S_sNf0DV?4K?4T@kg$O+c(Hi>VEB+b~fcc zyTa7z<80Jja{TsOO!+b7(1gwkx?NynPP_$icu7sVPBLUC?D(Sb+Q=iI^dEo}m2uRm zscrN${41gR^ad5ke!gT{-yf8v&?4ClF6jb!mlf2H5ybzw0qZSaLW?s(<0}0safJf1 z75d;g2UG*Z0?Sp?WTpXXpU-f^jW|^7E!TdJG}t|!T;vk9@g%4#XZB2gkk4|se6~!K zWWK;Pfxuz1`X3O1=b=Mj`^{h>cO;=VN(zH1J8{bedCAezg5}m7-=k`?zh~{8vv>x_ zD-c^8nV$#q8<7~*?4}+?SqPO&-m13nn-IC6dS?}~zPkXCtEheXeM43{NBB`+%m-aG z)E5r|oCiGX)r+Z`5%dczBW-XlBdx{qT`?Z1X%`EdZGL@Pu8`_9$QDP*uJQ=~jW1^k zhI(tT(6kvBIDD3C#A2W`ndI_T*DLi;E%g*d!*JATjIS9fIo(~tS7BdefH;fPHxqU8 z3*YHz?dq9|vy<8{A{PCWV~qS-Hj3c@9r=Nc+ON%aBU4B~v#q41-j{$jmQ(}?c|u3P z23f3Ag0Sl+ecImauW7c}HQzNnFx9j>Ln*)BxOUpJ6xfd$J z!o!wY(gKLtJh%44*X?D1Q&@!RsFT^B@jca18v-A#8xqJ?*vcfyYLn9aP{}C)^y#keb9||Mvu80On>=D?4+jdfdu_V; z*+ab^t&+n%g5*($U5w%}W-KO!CEmkEP?NYFaoKuh-tr_!^n!9q?I%?i-uWVJwkdbj zBIQ0R<^RMjl$uQquPp%%iLlVuzTZ*1G{qVAR<)o}=q-5RBZQtK+^9WpN$ zlkt0KU5RZf|V7g`jh0S z#&=Ss10{AV+D?ZyB~ZX6l081t0Z6^YY%_rS#>uN?%&-@$O@`l0q_wlE&}pADj|lMS zB6z!7MZ);ID6S2QyAR$r-(<9oSnD76|4BO8g}J)gG1*D*l=VAvLuIA*^s- z4MVWHwCz82N-JxoZBdC$O1@HIin=Y{)ezy{4g{YzUJD>Cznq5E5UzH)+>c#bJm#Zj zG}afOuE0Wlz4RX&SQPlp8owa^+2rEUHg`KJ>&1^6VG(3j<}H;ze6n^Qdtcs6U#Iv&Tq(kX|Ar=5u9I{ zJ}9DsAV4k+F7Qya}# z3_`-@Clb{*0F^U5Ot(=$kmcN}EGZ7XyhqNbLtOZ6o)z&dSzfW7N78Lw@$9Z9dK&xM zA<+H-yaOAWCyd^?PhB%T^xWiEKV&W|5?j)qn_jUP%>_^dj5Ofm7DS%nQ`81FGJv2>T*a8eB8|ctudQ8Eew%777QG^pZzUo*mX$x zPJ%vDUcX_PZB&N;+HS({-Bq<_?iJx|ijN|Kdtq}b6-#EBzJm7qDV^HShGm{Bjb9}` z5v^6IQ8C*~$>)B~)-l=G6i^d%_zj4pSE!}w_^@DlIfc5xF(r!qIj1To@bH1%Hj7xee})m=B7U0X$wD6xE~FX00U241><^jD+)i3!!nGZd+z z$o7|@KJdStM2w%2KdZ1}Y?y7>Q;Wg-bS;CbhKv? zZb|PLuFPCgD+7`y_K&-gt@I+!&g8_(WnewnW9}^lenhkbLvL1rn3A8%GZkZ$Ik>KB zKaA0_v$In6Yuk)r`AvfpMj~VQC1T9&F?}l*L@(YMa?1v+>q6#_ExojxhH>Tk)s%cPMw^R<{1V z6)R*}Yo+h5Rs+N zCiYA&FN+GR2-DGX=F!30Nke#J5qcS`1LSR0805*nUM|BXbk&^7W7?x1KYWk~OK$r{ zq*ygu*(UgbXofUhG^5`a6hc+pke@QxC6mF@!kTg;oW@TNS~wDX?5ig`4IAD! zc5M|sr9S>PUp|9?oY9u9?thTm@*gm|oZZN0OX3)simj<&q+dM@dKjV$qs@W5`3LAL zm6=c@zdqzE^whlWBOBW*J>Z`8%NcQlei~#UMo44fo%OB^Fc;;3)kKtj-y5}v9$K{W zi<$PD_FnMd3@x9E!3m;hG*o6kUd;UiONV4x<31u?WMV(S>sP>qxtafFyJS;+xYLU%>?h( zlaF+QmgrOSM3&b&hwGhgYoZCf_2_4J|J;j~It$G@yvhElrRZKk)OK>w|01$}x<}6U zM+H1;2-@(5D0pP2p!FsLX@Rl&&qLqL-_5*MyE1?8NDw<+3I8}C$B zq_|NFz_!KvD&CZx(&65>rqXdwi=! z&gFUM#wM75WoZinstl!38n*4Joz1b7lo-fg)A_6a|}=;PFq4?1Fj7iLa-B0`mP zmm?HYHd^baQHJsjZgiP&kJyHy9s4$*H3BpwXG)qU_BzWIO6<+nN_)2xKkewkr@HWo zRgChKRVv2;<{N^&OlN${(=)jucjF_A5csISaT~P@L7IxudA+lFX_**(1^fpPEl~lx zoDOsU{yX11e=pGt^3S=!|B47z`3*a&fBQw7Cth&H*srehjxYEmfqJbeW@q*(t`cI; zUXfes#LQA?r7f;+y7>CDe*)Ej<(TV+812$$c(!zZ5J<1c1>NmFKhzP=J=)z*bl%>a z)|i*sSrWNPy5b|#1s96Dev48e^zT@;Q zsT6i78F{Hz6+%`#lP_dHr9@w}h3!;P&L8^^*ZadWrlz>HV~zXf?L_+j0cNLG@Xlti z-ofhBMK5#=IV@Wzn>vC|Sfz|ns%2I&i(hWyp8M~qn81do7`^BzeJRrt__1(Azx^J8 zD}QTvyn_Oe4a=qLS2&qZUPq z?-4tRT{{|@hk$rA{##isMb@UGX}w)^ApDI*^E>M1w;pmPYw1yh*<4$FUpn4f^0-Wt ztO%yfhRPdzd8xn+-@9j@YYUW1dBl38yKd1)&|YTSp2jywmo^N2E^>O_I59v@9Y0o} zJ(cd>$;PsDQr)jxyz+{nQKd*wlIOLQjBRvX(9$59+nqPPcmzVN5~0(yP(iNtRuZ~I z#%cFDB)XCpE5LFj5!?4JD4w)pvg5gsxS7G4*0o|Ow;o6A37Kh%rtyIynNFkq2FTn+ zvZWb|a?RXTgd?}0yaAD`t!eky;fE90vrUK9hP*Bom6hKFN!FcE zs4Q`uSad;1pSVRA_Ae=Zb~tpGI!C>IOgkp(xA?lxy*`k63D(c>Dp|r_85#Xq7HjBf z4xfjA8D9}KuGBO+@iPa_PARj7*j9Ru2Do4`gfL&wACs@1e3QR6+R|7p+uzDVta7=I zctr4Hlc`>PY@WZxO9)`kVmFX=LbQs~B(N+zH+K%^N4cDF^Yy~&owg(DSvC^Ks2Ssu z+61lO*cPJOHHzeJwW$$!@gXTTICzA3$9F+uy6$90z+q5a4GlNOKRvW#KRvQw?l*;7)1_5FVCJQHvrCTlPl-J8M zvlpCg;P_?-Yrn`8)&?i77HJ5UAmF}*hlTSc!6^!B?E`Mlg?B|3(Bob{hu`-Q*61clUUkPA&8EorX331Ed_uq+pw5 z@(_L(IVx#@(J=u|bd#qD8fBN$_g2?wTAjXjN;B%0B9y0IBi*Z-X2n~kb%^J%m+<0` z@~wNTp&OkN_{=tu67Vm^ReC#kgQrvZ7?rV-*q}#8e8^(KLy^}8vAxP(RO?~Z2y_w0{QUy7@B2gya9+S)6 zo%r!@y-!3+QX^mFDl%OvVKC?mw%Q!CJo}i%3pEN8BifnjbJ3PgA`@41kCwftk@ko- zAnh0K#yvS&q1~nD&wIylvwmaG8+;@uATZbzHLVtvI3@E38SrT8>n)*u5nv^A?UC5G zhFc+Z+Qs;LC`FUVy__9tpzCp8!_ePqJB*OAkP4udV|gV>zXm`zgit+kVvPKkkyauM z7x+;O33kfdUkW)H;W@ay&Jj6ipaWWx#kpQ}^evVSPZx4(=$<x|x% zcVwRt$14)rPI?&~>Q41Pwo&NWWB#dLE{eA{ixt<``pt0rH`jliOf3yAdM}vOc}A4D z9m2rHbgr9&65Qqn^p*8nPMb9|DZ%!%YSX`g{_oN%wmk48CCwx52Am=uQjETQvG;O9 zUQJKc&Z($VJ?^oQpD=ac4B9XMKfT|`vtL^K^ z9|? zJ^2xe=ZgIXW)C92Y+V`BEiqie9v2avOMe{`nwuKM-xG*8QQl9kGQLWop#is^?}?u3 z-mg%6Zq{1$_nM5FS>e)XY&oBT@%D?MXA%1rldJIs)ti80AnnUe+H>A_ zeuFdze?|bFmVtD{yCJk^!GkyXmLCT*+7FM&5?WGyBtp&8ei4geuU?SgHp^{uV<=3X zgl4@P(<`49_q~O4owNwf)GGEW>OG+|p}mc-wG1D(#ejw=buGwGAFQbJT&}#SB+n>r z(bAqW@f-GOi}U=j8lcAJDz_|Z7C_(|Hc9)^$7;ejzB_8+&8hY>JUDvg`w*Lfyo=bz zhC`v-CUp{^b2+K&{6OXdf{BS|Qmjp>gfcJdLN;i}c-I%1a2p@#tN+3-Q<4kD7TNzh zl5cc--3KG^xnj}8OpWmYT& zdJZOfEG2dF6_YvrkN@yW;otw0cH>ZavF?|t3}}?H{K0sPuM{+~sBX=2=wk9^)|7)D zjs`tM-liwlAy2_z=KoSWy?B_H0eNdBxDFfgzZ`wq!^}%P%j> zoJN#X0LTF=h8wQ+<~t z+xo$g(4?y;!t?~#x>uTGg*Ky|rN6tC)Wx}J@HF2epUa)>FN=SW-))pY5QWdX=dy>6 zBrFWq+Qn+Y;EBnt+cZQ!j#K;nlGiEZrv%q^8=BAc4qOk5hHSDq6hBN(a}^ib*#b5U zU%Rl-JK8*#z=8t>GR#ufe)OQZ4S~(MN}&InMEW1qlvgj2nuR>U0NoJt@W8!ccFvQ{ z0bUS3S)0&qXpR4h+v538gL90y(tvo7jvw?N;Ju2Xikz#Lqz(vSEARMf)0MGn;CJWt zT_JOdgQa#cIB>}sj#y@F(vm+oWb;9%Tp2_8MHqG~vIS>kAGPrj*(Yg@Fl;!@?&VwC zk>ESw2QlTLN%G?3vxL;8H{hg~+`2*}h60bi+tOflPiHqCkE}gWh{+ZNxC@jVuK)|r z+~eD^nHA0z4Xz2D&V7#mspHi+sLG!pAM7r$)ogr?>r@V(J!$U4jYpB{@(kT}Lw46i zr1tKw5Q0fN1yWICzOL{)7=R$pz4I;1|-q%3`f_SlpQw>I{!X+ zMdnCM(R<4)`ON#aI9KqSGg;p4PBQ0nAG?$H59pEQo10@|mQuqt@q&Y6KzP7NWnC3{ zPBssPK3*f_jAo3k=zQ-AEOrnx#ZBH++QRFVN+HVux3Rrqc7XAtU5sCZYg9DrnVmL> z7{@NLn5x_lnayH`9HUj!v~cQun@#^K)X>6gfx=us=VBlSX5*aybVoiv7uJuul7_u&gbjZ;6H$1$)4w41wf!n zt_WUfWpVq)iHnTjfek#yGxy?e#jt|8$-Am?G7{HM`fvl{ed#!Dq8ljGt%*;lP@)h>SlC>OKsyA+9pLP8TVWzk+t#h zne(T4YXfE1uii#$VCD|K)6?B1iRbY9bt*cS^&Aj=8U2`9;SW!f2Z4^+86#P?^@M0iPU`Xd=QsaZ6 zhN1GUqLgF>lP3{_QFb70)(}&y<@n%4 z5PyxQnq91!?FzS=cK4lU_ASW;;ay5ss?AJqr_8e*zuG&W8H$A}eMH2x-mlq)Ge?W~ z9t8kCP2>F}>?3HceuRgscJ_t!vfZeZ5?`cSU7+E%kHjt5%0{iDty!plQsr!jc2a0( zG0|wXD$xzUtStFN`ekVMT4u$I$J6ABp9lA9VnvP~8cvgez!)Rz$)5wXItj0m$6cj; zmucw3(?)h;@jJK0I2B+Amil&OoLo+qPK#6I@;ds;?2RyeMrid~ zrscj>Di=1%b_gUVEqO{oiF+u@aVx|ZRZtMCSJ=Ab6)NOJlO*Sz0H0BH4W{g^9Miz! z^6lM_bnh34y|7fIfd%oIrOMn#!h?p>WQNHC3i9Cx=*#U(x^XJn0mwOa4sd={3RgYk zf_PWZ|Jdr}vFpsF_Rd(>vqg9L$ZT$UM)jbG+uZi8+Yo~fUXdQHTHvJ5V3m>ko)n^; zCSv5}E}?KUksQpwYwvE_?Sz)AU~_4@<%6|d=||BBb~ew-AY6li=H}M*U;^Nchq_k+ zY}&}^fVK&=RO)n76(SzdBk|Qo?*f|AGEh$2g~eGs?Vm5Ss-{Zb#-!%W5NZ0Uwx1*W z$xYM*cI(ly=0YZ7-1gpT~LNjk82^)Z0~-f0y4yOKLEcorv=A#~X?k3P>w%@4iHUbk6#tJqfUQ-`1X+&rt}hy? zn1H+<^jt#n$lS*k)jdh~RUiC+T)kyf8{Zc$914_D+$~UOkfOyQXo2GHPN6_?ch>^N z6Ckv>dvFa>+}+)s;ze8N&F_EjdOy5hCNo)Q_Bpfn%&aqKKl^#g^Q`RG6Mru~ur793 z^$%G6c$m#ZbK0g#k!A(|VVV|v{B+o@dg6Pn+PVw3)y{nP+w~e|XGk~kRZ};F?UJC| z)fGN}i~sTf`eh(NsV!^DNxuC}kR!kOpF`T;xl@M+754delO~d1ynUYC=c`1Rg2s#X zCr1iZXK(3_H1i=($Qq^d#)?2hJ21$xQG9s0O`Rt*+dt6#JN;dD=G)QX%INpAw;Lz$ zsm=qqeNak+>F>I!l7mV%(A|n|G%6-=VjPn7Hpo8EqkZ0~S$60&)xCWx%;#iGOgxa! z`s{}gn^VWaqq~0t+=Qg8m_Bo2Jnw{g0*~i9zl~am{S#V+e0PT%Fo*8vr2K>vA} z>odK^6C=UlHC{vq8K80NaQFJ?J%04qI2{ypisaGPdor{UKMmcupX=?(jJG<_^UF-| zKhLC|ob>Fe_2N^jlP5`PTya%Pu_<_fVBv7ErUMv||YUBkxfj;IG-NAzoo`Z|bR-!H>2JAcL`3 z9UxeasV}~Pmr|6JcI~H$mG3DXd~d#HuFLXQ$aWm5NRFJ=Hg!|} zQYI+KoKgFRFijEEngWU=%JKwfmE0G(Y71uBkU>>;;dp%BJ94{OIs-T*o?a@YWo}J` zafV!rV1v!?HG@;OO*I5f9n?ROe#&4SCn_e#X1A0qB%}ZpA>*fhNB8)tZKN zSumi~nw5V)XO6^uMAPoWxdK+=%DA@dyg5YKvKilJ=b|W@jy}f!?gPqos_Gq!PINq^ zQfY$qW90A2DxnE?XAF;}fIg2e#f64-^1^z%;>95z=3#Y7^eO5mvvgPm`(hS0avyMg z_O(xxf>|Y4vWpZyu&6X||J0hrW^nzxy=(s`!$R6kvlZB|(Gtmr+d z`RpNaOPFd}F%**hY6^g1(n?QK)KI`07Akc3e=0Jju}CHs#{Ghk7kVkBbmkvGbKxE~ zM&b6=Xi5?wozAzaxI_jEfSF?~-FE|BdMVlNUc)-^w%P~pnH()`cdl46Zbh2v&E#c9 z(WyQ-`!%u1$8WS)AI0$6H*T%4e%P#j008IJKXyyhnrqjo9QjzTq?ze*tWL-4c+iM! zm+@S)Oa&zZ&&sYdhYtn~@fYve*aXjN#}(tPl%zpa#fjKOkmAI5TtlzFSfGQ5FkV|K z#-fAB7n!lG_t}lcl0t>2RTT%1u*=8=6(TDf`&6`WlKGsx6$ZW$?mzUI3V5_$_NuK~ znzN%&EbXVDI|Jt;Txz2#6F|^O)(Nw5oymbzSCyiev~?JVqJ0I(UMGvjkZG#x*ich? zNIU}IrRkSh6E&B-Lls`{4DeyP>=Ys0rp2Sj%TdW&&c;3SyU6se5fSA{*@FdknPZaLt!cBd zNfhJ1lII2(Sb3V{IZD{0bLH}zJ zA~`_Z^HZED^UawRWZ+q7=bq=uw)2jA5bv+Y#D&%4++i=_}lbJOysE9gYGaI#Jk z&u3)!YEHI=q|R-j(&<9(`G@St8ISpRkdZ*brVH|-$_R4FuXp|HMo1@ISxbztd?oyz zWF|5G0e%?3I}UuK8H4$v0!18}{{gNlAH%IBz387*gjFZ|v_K9@1A)kCxL&sGl(eCE z?W=@yqNlgVQ8M8iMQ$il9(qsfkyoInw_S&g6>;a2&mV&dj3r)8hG~M0GKsZC{sH=5 z$^LhSjkuHt_w_6!VIAX9dSNo|)tb^)N;}Gg#w($kif7!3e*lPt_Mh)>)Sf}`=Ah8) ze}FxcM9J}0{}&mMeWzn>@Wk=%6R~)qzEg|w82HI3=`ZrY+J(4ppeldUD&m6c zu~}Ri??{LG%ovFmuzK?kFpP9(J7c(K?xyg}l~3;aUSw-l%YSV&2>p_Q=f5s{#7H4e zEWfW_ue}=o^*4*?=p<+PIrjIS=u=t*YXf!)dvR)XdWpY^vj`JV1ApFkdw&9ngx@rq@`?jw`t#Xe3UR6PEHzS%TJW}$T9_&X? z3oi`Yi`8OQ7VV;B7$J$$Y3R;Y^Gj#X3Ue1KGMl1BPh(ibEwkyv(zi79uD(}+JDDKs zqHYdeV-utC6J2q7EY`n_AUG1&<~JT~yd{0UCD(9_D7DP$YzEOU0rgu}zU~${XC2@! z#lB$jF0z_NaA3G4O-SeCN1=fDql{}j63f!5CTjzEuI9(u@+M(R57sCcC}f?e%aMMc z6Q)#oat1`A587A$etmy+!SQn2?dy7bkNA^rE8aQr&ymj7x1~VWl)5E3Nqo9%nh^nQ z!3hTB8pHJFrfZ3sPbC^FPF7R!W{P7vI|~s#ZlPIuCm`j^x6RmVtaJlMb{iVkCPPQ{ zmS8em#p(K~-W{bHUU*NtO}I8!^9vgB*IG(5>x4%<+PL>mc0ik-dLlYP`+sTcKG*`u zEF5*(OzNXjirax^luEN;i*PqErm5Td_iq4&S|hItXLCj&$th@P6D|$2AWfIqi2c`6 z3@ZF;9LyW~5!f_QDBR!-nsQqnU`dP}t)O7*ZQDbML8g!I?+WzF02e%l4k;?@m+GtS z=;Ja8qU~e}bT=5<*p#}X&&_lWEX+-NmaJ}K<$g`#iW>-Vi}?pY)q&j~gl-~5d{YyY z6j=r7?ESI1gmDD#dd)Ye=fN{UfeH5%tSo0iSl*e{BHvb6xDPaYi0ZP@Jx#N`Z1ikw zLB){yv`CB&(qRB@GNk)7zK7yW3*wN=A1z#Xb@9htdsPPd&IadWmANWbfitePom(Op zDzU`Ntxr+DgfD7(fh8iLSNhvWfGU zSE|TPK%4LoiY?T(OS)LHJ;=*!hz%pc6u<_Y#& zxZ`n%_=7ll!sM;#y_qg-M8##DYPC#m5=>#2Qq&e)0}lS(r0wHQYd|2XA?%t$aA+Xb z5>Z>gK-I!5m{|)6lO2*U_D)bY`rI(Be@vyQskS)UFQ1(Shwy-+T5?+HgQ;3Hb>I{@ z!v{|BYeB`ZC6~gItk(~;Y@3|CKPW)lioluJ&CDo}Nb>KRQxY#~sH!llG+*c#Qk&<# z0lR3-F&ZSQ-y|Y;L{HBb8`Vlrh`H^8iaKD4SIR!?P7Sm3SZ2*+(2|i6;VFl50}b@) zEucNw`e?w=q8SQqLNDOE=m9HeoiRH{(G2OxQVFhu{|#qUn6vq@x4^j9#G8mk#nz8} zH^mKWOUh0WeK=>e1)4&#J;dKp;$ngAUE|jKFCPTE$JjjR-46cjtXEINHEdq{#W|!= zvj!Hm@t^P+hSX< zvcu*?d#8u8kU)@znuh!Rae+`-Z}M}M9~CE+zvr}s8kcaU7Z`YBgQpF)A{4-3syg?d zs0@RF05^HsCQursfckK8lncIa%UNSlEVirhCk2~F)~Lg097T^fSlZ(URdd7LH{tY?mKeX@LEtwBcth@8tL0XbGK8z5Z0ehkQ_saJWs? zPjqt#C~b!K1y8jG0Umnb;mk){O5sy&?KE~6a~fjL%&-ip*-KGz@RV$#pk^Ot5-}+Xc4hcjQ6QsUp@$@ zD%IEw+evxc#Bce=zxH+@<{r^I_7V;kv!?GfrBC(g%CU0Wf|e~jiOVW}DeBO7+&^*1 z%AKw9J5m;@R+*1<7X3QDSig&};_Sno0o0ouEjT%kp{45=PFj@VgfDaS723H|Kks-T zkdpPv41#8s?bEl;N3YNeL@-=-(9FjM0(IW;_SM2xB(zK3pErzrLcagdcsWYk%;+OV z7=i1g89)@M0j43jFaz7vYG|<;D)WrdezqX#X=XpaDj#}US)Y4Jqc(zR2p_%b+mc1B zo7DH)?9ly0+2P8^$|(zYi@xEfQt6JeqAAJ2d}5Up$Ug1-50h7$Ll+nh!)F7O(O_2# zU1@B^M$)S9ycUUK+N{nqDaoXMnU)rzEHNHqup^s$w^W#D-_pc;o*w@_@#$Nk`GrMR z>q^cZzVS4Kj7M^wI)1p^^edO1<}el9Rj`hed74t0G97AED9Siqv<+*gHs7|M9w-+|LKaHO*=gDlN;+i)6i$i^zzXbf6vHn`)Kfo-> zw40vhWK^Z+fd{6}nXL*!c{rjZa8H9^RiCRqWB!MsAlz?30ldNwgz2=%=!AY5K{sc3 zh5E%!mAU1ac$zay6K_WzWIn{C!2RJ2nSK8<>VE1Ve)Ib0Zui!#@-yFB`+z0n_m16r zS{L=XhL&?t6PJf*y=M!PpubBe<7r18aZa+jECE;|iR&2@bL6|&kkM_RS-c>Q4@KAD zgXCVSoq#ItA?}J4dVtI9XeCD}!Cbvgn(;lQqjL!$XMc_d^m^(QSj$3mEj%uzz+QMcaxK)b9y7GbjY zt}q%#x=O9AwwOyo`!sjW2^pXO24noRT(1?C8@ypR+8FPd?$C0uZd;<2c@wbbhgrv2i)WoB*@2JUj1Lj)$_8MeuAYP3c87 zptELl?Bzkt^9Jl_*)=QWmA^9}FwJ?TLa64x2h6V~v zfzI4j&dtxvEbqD{gtya&R0ZaflZfH~H)FXaJIdoO#U`qcZF;y&^p;Dg_Hi%|_VnU! zLYOt`)4B`78nRjkx{a^dbI_;Gl9bTRCm%n#jEpRiyI%3g4JH{JeO5prGTJ zRpt(hiSKeL@ffCbUTMiKv*+NWa_*3n!!xBAq@Wn;8dUXFuXo?koTf?5R$46}ZQevO zJ-vZME#6vtqw|rIPu#yRiz=%hA~J!}u(wu&SW4gpyPA z>lg_RaW`N>G(HB*O_U*w;VOV){?Pzo6zsCD1FlU@;5~r$2h}tqJwSaQD6z=+hj%c<~r^7@v6JT=<+8SR3 zt~5%Xju<82*Y$4TH%)H*NM`q5*{Zx;oji-$bM@eRL!6SA-YO*7b z>9z^}Z;M_LNx{gd4-}FE_?NQym#qV#~WDTC_X%L0HIXSiCUUlnEY8FvxCWSp8ao+$|0|wOST6^ll^qFq}}* zm}&)jy*fx~I0WM3krM`esFcQSoSj_VlGL6gZQd%+n^zB8tNm8q^n&MW=@f-|ZN#xF z?x`M^d5ZxH`~CPZe^F9oi({^^1=v(4j;Pq!wZsC7$4O(tLP}}QAf<;PVCIFJz>Xae z59&neJkw{kS5aTBwn@h(PX1-5$4~Qmh?)lgKyMI{fCK|n^yXfo>f4ZS%3zF^-?h^7 zaCKHY9qV+@E*Ehgj<3L#`r|3ees31}6+{tyoet>v5D%-u5$TKmw702z<3ME*(#xml z7t1_K&9xqR7q7avY5e`5OgIBshi`%uDZm&x98@VS*b3||Io$2)c2oM>dQsRf62pL_ z7$LG<%*?tzzZ0ijvNois`G%Kc)YXc2JLV%97(nBq`W7*g5E$rT_;vB7SiQwVx-Lzf zsc+fjF6mwavbxqc_Mu@&hq?>%SCTXg>)X9F*ue#~L81k3)-<$csDgi&Li<1_c%Kvu zIH$jR7mb_vd-t56BQFm-JAjQIZ}gi2*WXcVNex3#?(KkgA%&i-NQq&91H1hTTZO1H z(7k#y(7yw7#z>PfZNU zO|W7iMJbHOGdynBwy{-X@%Vi=EN_d7J*Bbv-LVw_g0({4bGbbb^02_+rl8#UOahkR zhGamd?f8^y3m;QXGZVW+QJLAN1gV#RH5a_T_Xfsm>-C<+bKfV$8b(&UvrQ}%)*EV+#<8r*XV$WI@KZN0D9uM4R?&^Q6*TFnFLYF9%(c}r??6JT zoXF8IcM`t*TQq8#`I=erbCyBOc|9wiMZBM8~}CB8(^%RoPdPj*V_L zn?lXSG@7q?Y5F2{jU2msG!^x$N-FKMbU4-3gey+IHh zivtkOCv#_VEbm9RK;_UMnMnE4k8;08Hh%Icm7rZK(>tDI$sNTsS!w<}j$WDjZHx6u z?l->yW#ZC)QHdi<2?M}|tAZd^@!*A?!D&CYWaP|p|B`L)G>P_{hK{nlck`HQT=0)@ zZESPw@4H5>2Pj#lmHwAaykQZ3S1r3S+NokR~m5}#kmPo>KSVp|@ z$#)*Qr(@f)J!9wi2%(nnxZFZZ207CapOhg5kmKV?-$)Rx?%_<)&OGnEHgjb*Hq-eZ0f=*sq+z0q(RK!Z|a<#$j!4 zM2VWQ6Pw62;xTgcvP=FW*fDSM=+lD##Syr4oql)Y)bN(+tgR)ttHSY{$y8tOz<(DczVCsj8td zWt6rspvpE?7a>$5RrW74=17pOBko zipsZW)8dlG6oAL~A#iukta89t=Tu#?YxrK6d7);9$Fi2M}I3K;_@oUoN zKb2rIgTi!0>&WJ~Kdf%zpW(}6kZZ;6y6x9=^{qoS+JAm3ox)~r_!HF1wnk=Da_S4S zZH+Uu*$QZEByHc_Y`+k#p#D2VuHic1Fl#`itd1jL(=ca{Us6;S-61O@^@$Er%Y!3g zjuuaF@B-{rrscrStc+X@tIF;Of==M|*<^k`_nN*_mai<$oBhqHvBsXvJO8+}ghW!l z<+Q-3RFqv^gUYNo7_=!nHdwO+fK@&6S{Afc$GQt=o!&=h#zpn_yKG_z?)B~@_8J>lnGuyU9JsOINa06qW9VhUV4O*J@H0!(^_B3&*WUU*UEQPKe%V z&M7zA8V0~hQ&&7{i=Z1M9hH;^?HSZMQkG^oA`a{zvx66}ZYrH*wjhY~0+-G%t^RwZ zjIHAsoyKPMHK!`ry2+y;^HxE~xf51_g?fYwWUW_1@PbbD6SKW;c}h{WZMr3&h!%0R z4!;Ti2xeTc@YgnR_i;{6pI@G9>Uqqj0d}=`=4sy3TYrB}xwII=mtjeoy>>S6B;9pT zi$?SSjO(%?!OYAV4P)!n6L+;=Be{tcy{J{b^Zjg!Qq$yWUU?Q{o6OJ`Lg#wR7TQ$6 ztNoH0>iA=!(u3xrj7A1F-xdxbFO6lmmI3?B=%+=CW?AQW{v>)X6)EqU!7MUDz(IH% zENjTL$ySP^yk2KW(<%!ZAtWm%t8ze!uVNrnE9FByG%;LqCV0LJ_5T69YO!Q5(P#C# z+f^{J@-Iqi1r!##?B^fv^=sis2@L_zB^MO3bjBt;FbvAHXJcTFo8CAe7!+Wh#U7anO?x9;n25cqU)f(r&uhL{;6h5 z(gmWaoZI_(S#}>3Bz~fou4{Y2KbP9|=K*Pb>}*5IDbL)@ej-^b0(>s~62{k6VD1=L zDJ|5jcUTCSh_<0Tvc)o(7Z^1?!Sd#bMUA@yZ$PwG6%s;UG#Q@Ab+OOgZT-(w)%@?6 zD)MbAxCh{Yb>pU-WW7fU=<%MT!c8B`(k|fq)g}jBUr*LX_84 z+?}`v`Put9&@x*DG)C_V)E|GnKg8@DEyH=i{zmTc9w~>j9C>y3WYZ(`aUn9RVfIbx z&lBa%8UA8z&-d??=qCtDwykt~mW3*u?>7&?{gQLH$FB{qk0=iiJQ8f-TK$`!gHWrz z02yu=D9YfA#hZjK+V#Yng}}O>&qhd(+Y3o8h_9p|b1(-_Hu`L&LQJy*@8A{gE|J)R z1BndgMi<^P5@?yVfbl=Ogh%CuWi-Bz%?6JHALjvbad~Rvgl9mDCJwZ0oOp$L!yBT1 zfHxuH3s^|Yj=D%K_l=vPncp#$1MD^>80U9Swj2>q%Ji>_IHFG4K-{d?Uv?@pTTtLO z{X89>7^cqI+D9k4M#mDLco@2ZOpMlF@+u9E$Q?lXTE@9&kNDr*&yRy%k0%L9Sc^~| zs3$<%kueOZI#Mm@x8NzjQQClR-hjMo4VfDN`P}oAo>LR*tiW|llvu%FtTb*sysmS> z@jgEIR5Da~0PEz9@|+@Qqvp6{k7{uN9}K+`^#=6ERQJ$NT2wBA z*%23}5LNnpVOxw0d=B*Slg00G<>X4L0iomYN*tPx$jS%2g$k{Cl&p(-oIlPj4^=h9 zw!Jkr^!FP1FDlxszt{K>i(B&8wW8+{X7ijkkm{Pf&Rx`QED11*K5u_UF?2!RkhcN* z{g&S#D7-!u8#NYn|32whzd4?ZgE*~8Q#3eJ(MSB}r<-Catz)I2e#L>ks>c~thQ{zl zmI!X29T@E;RrN>OUL&mAjX)#Vyq!Nu<6^OY(#N|&N)u=DNu!r5j$W4&rJrjZBOT|2 z68>1UJsTj0CXlXUYbvs)=<^0?yO8BHnT>})lLw6r4^sPL8f8R=8%4~SdNo?5Y{Drb zzuf;u<)w^t_14|h1Y3z3Qj#0erkYK`L+$$@yL#t!oibmy4w-aCs}6f`Q@+q zbN{^u^pDxAXEkOAZ|77Fi#fLe8!f?@JDz@x173j--C?aqBgO$|vYjlSgSC{2wqwKM z$z-@EDOK^ZM=)T!*aa=P^?5i?48Oz0>oR2@{GJ=CPEx1IZf{C{z7LvDEtrNKoyF#G z&$o=3au0Wd5mqwOl$0u6ZL+Ps!AVUvD;6GVvbu_{aPw^!BAMG-iZ@+!*fs~fSX>)P z8Npl`_iZT(VrbdZR&xFkh}j_I<0#)+unuv_o?9q@UiNCf@)*tbY2>k92Ms~m@nTFaiui(qsn`7a&rH&8h2v9PNWdn z)h#;yx_cyE;4)%ztXe>m7^Gm#;GAK1s`xu>PD4^d>V=~4f3tS()&IYvy4-#G+d@jg25y;nKyE?`bhDiF8h z8N!Vb9n!zF3#9uisLT{;XA2B8%6qCh%Itk9Exm zfUEF&O9gWg4JMYX{VUn0wGWaF_KIT$SPFAu(6)#cB}8mdU9Pv%q*)(RB>-xc22wN` z7YX55U+OHYX$lI)RGguSK9RdBT(t@k5y`a3YT~fER>wW&GnrU{!jl$Mr2fR-ruuS9 zrzA2#E9VC(zRm<)2Ee>NeRiaHof(8+zJga2SeeZVvu8Pxql@Usz9{m*fzFy7nG zv8BFlA)$Hi20~LJS&Il6=;b9Poo9aXj=#ugg6V2mxXEK(GU)Bjw!9laituEd>PsAb z-eOno&zc>8;D~(I4Ozdl=egnybS>fLmRp0R`j?HA?VmIlPwgHMIpcK#o-J|I3|^j$ zj*0419GicYpjvw0a9ai&Q&y*ck732Rb3lDkafAywDoY#o8~LazQbsN^^NfFHq#@Ze z$e!nyzq>8|T5eq3i^#o{1zI-;5d+iNk3!r^Ra{A4flR(d7sC4 zU?T!P=b9aU&h>LMq}n8^VuoLt+PXz+=}gFT$u(VFcg4H{F(p(S@mgb&f=H;894n^F zEovNq+Rjz*q%^a7LzCaMQopy2z#)B1yWh(3GPCSzQ0IZigUMGd3#-_1aK>fdN~RwJ zkB4Q8)cpd^d5sSD=xn~(^(;5|Hy^J zBC6>si{vpba8>-t){)rWbo$W?#_3*lEoG$NE+jRpvWt)kp~D#(Zpe;dmpc_JoVg*b0lQ8S=$-5VAXW+P&s2Kj<0>kE2Qj;Q5HmW;QN9ju;v+S73BHb$B5u;XOYnW&tsdn>;}2}-MrdxZC+gb+6?>YqB9=9fyH{x z$1^oO@99Tv@hiTF_Li&x&Q9+et$j0Xt4!fpj+mLE9MM+hIXX5gh<~BaI`W1n41f#F z;2-QdQ(6-uP5HF3zV}wP{>n{tP*dJy0kwP6Wdhyf&u;w!O|m1*AjY_*(eFbk+<}-l zHg;BwT(H^XHl7=JW-d5DTXs8Azl;cdaB9~u{8rpB@kv%)RSJk(1jVQB#sZ80SDU^r zoryg3w7C3SMTDwmL!{d@8sj}>mWLIp5A~S?crzTF@F!5eq2fAupQ%TF?O~_unRRU? zg7eq-mbQ$J7`<31C}G)jFruHijf~)w2a!)3p}2Ux#j5G6b+QZXDL*3>);>P{(!BP` z%Utl(-Kp69_tyk>$WT`70`I+;=)Eb-T5HrKK{!k$WakMBJ$X_>7y zur21kc5Z_f`9f6MLxvw3uTa)#SiE>bT2IehU1XaaMS`mJ{kSNHFwK zN08U?!^F4lGZF#*Rm7)e>$Di<0zF$tK3>TzDt{$^z#bt_S@*yTBsDjbru;DZ~xe`DqM{!dz zqcN|wa#Be=`Gff#+LtmlS!_vJ=Q`oLR#U_|dfA+22_FeV{Gy*uRB>CMv^oHmm6j*J zZNp~w(-w#o7T~>C8#e9xM@>8*9;9;)`eDvX$ooK(N&yYTu<-B(g=1rz6}yBXfOgPm z6I>T*;LY6ZZ{AoQt=Zv0vsgF3)y?^Ot2XG1s z^48AuZWL?o4g%=na-L5F>H(qgLWnVK_M)<)Xqb?dvJzdq+QO?&8)t@2LF~=H-}Idt zSstmzaL(@Xaav}Rd^pmU>|x-;1E-tBfg2nSD(BX?0ovVjguHoSkUzEewM&h1RepTD zoE~dQS#P53durY`2Q%mYo@6|yx55cN$|e}7Sponn%lX3m;>6X$Uuyhx zXk*7M-#ouO?|NZ*&4eb&$NIh>ei*O3h$x>zHj--YUq|5rO@5-U@>xE5xsUSxnon0& z&MT^fLd!7JWR95ZAs-jS;hy7^ z0_OsAg~9HtW5@lo{Lb+1>?iTx8-GcJzy`RkoZu93tIe|V(Cqq|&Ls;w>>2S0ev6%N z1I@S=_pCfD?oZhoM-P>1Q!^gRl0RnW2&cZ~hSr>VVNdsBWbtG`ad9y*$TjLi5oJ&L zy9iA^jzmTOXi^i0&the{Uw>^ELt^b@@yBJUB)UM(aB`=+-SE0k8^gm*>A;Buc=U$> z(#x79yK1>XF$^jO*H?q!3zij}PW^g^;oA7n;CX6gJ`rsqjap4?v+%^uO<8BEU&6_K zd<=*^=f(}YqtmIO$8_kP+JID-D%<7Y;qqNAr{`Lwn*pbH0J2uTDPen1r0LKN3|x32 zRSOPkg3D+%yWqc~_vT3OXwg5hcM=#$N!v5T(ZVafa-b^R^=DYjVj>`->gj2fU&T+E zZBT7lId?TkFFN;>K;4aiX8lN>gAH~82`?@%@i3SiH_xp4*uu|*H+PdpCtZ346X-Ih zUw)uU6-3!qA=9ok0>MMaqzZ#HN!T1jTy&29q_EkSR%XBP*!poQV)+ly!0xB$39#gB zlvXvH@?1$F@ra*rL1@o=R3WCtisZHCVPu) zbRzwCw9WXkQLL4S^L*wTZ3klp%e1W8+9@)ta$Z73r~Kwi+~%mP(TJAZMG-X4R@iX* z^ine-VnWw7w^rfEkjK2;fclNPi@DJxioJuK)Xpk(+BT3IOpLH|*qFkbFKJ8RYpLlESl)s)ByC#@T4yTTM) zJqlZFTmgQdy6(;>P9g`dNvTa5bz%&qVw;;U(GNVbXs{>-qw*jB{RfDazg1rgy}>;b zIJuG99}7u1kei#`YRxv7oY4*WL;dN2KHE~(C=cOGLuK5z!2m4&2Vjv+6I1e`Z4WGo zY1iF}85h1@LkjU=CT%!o86Q?ni(KfPojtr`{KEnoeEc@C-sSx$_Nlgznd#W7?ekUS z#i$$=5>J@P?L?GK^LsjLBB1|PxcR}_@(=Th16dp19qi-*`==#KvVUyd&ehLhem*p> zzbDkifASgvvhLO_5zkWZm*jmIpYGyM|7)lNew)pxC?@{SpsYhbgPOj|$4&}`V->&& zcp$lg_VZ`KVOWcb4}?0oh1nC_{^hhcng=)M1|eLSx1 zjC7hDkzWEqgUHeJ@>6Z0@(VZZazCY{ZSB%n2f2baBj4|(h}su#cRCL$pR#{`?0j|4y z{)gGKM>FA`9l86Mc<_eaXlr-rY!LZDk_oMhE}pXe$rLmTg|Sowbsi&AYDvcm2Y7U= z2~d_z9twXy)D0u3SRaEi+?3B@A^_O zKI(TCcU1dIQ!BmR+%<1;lB*Vyx1UDHcDc;RjJe1xSkq1Hz=6U0D1fVQo5oNS3AVO% z0B`T|8xq#LpsPs9I?9l6?E;GkXIy9$Y(@v=$=f6|%i^oHmQv`?(P&sqgWG_lKB}7+Sj$mN&v{sniSdcck@A zg?3F3gsOX6#^m~7c!CMtD`PY~*bU@jEHSkZ2unGq{z8~s3?qhoHb~rgtw4RJUZ0aW zn<=yx!v5n5sg^<>no|z$#4ZE2>QKe57QYG|m{JIox$%lj5*50YNU?@TYH~ zSYG1*phK=Bxu^b-6o=F8KftFhw;9CtmXv*E{pw*!Rpaq;l0H32{|9|FSL~@FRe&9lWCm&y+%K^ z&=IkssIpADobC{xkp}uGzAGrt;pXaHYuwk@A)&p@BxsJ|@wst)ycVSXhDvX9({EX_ z!hq!wHH5N=y+Upa&>7+)=QVsfJ55A@44rNWE?c(MR zH-Xiq?_Hqqcrq(?5N)W61oJ2M+13240n552`!fWDT58KL|HJ?fKOx=*%RGS=_~PXU zw8R_}6(SoI2@K~Tp^Us}q~bbdlZMz##Wrk8Q`*^5G%syQZ(8WsAZIa+A@*v=igXFh zaW$-38v$3iMa0efDI@wH6(HKc`Z&LR?gU?B`gpfySvMJsC>9nK8#02F(YXMXsH%^u z3n!Qbp<9a;I(Ej|!#vcM+VrlNGy}l)3S1w1vtG+pS}RzO#jG7wtkx}=w7fKRcVG81 z%WcD&bzG%eI@Pi&Y8uwyT}%Ix8WcZ$3Y_S$&1~CT;j6U#M*9h>F=S ze;b#pTJ(&dy7`5atn&sHo9*z3c8}T!JM?>(lf8=+K34<TA;$o8@GGo;hy0wKVA(Td70OvqDPHhuM4Is_nRVj^#SU@KsDOi z0pkEM7P=t{z?ymD)HkOE%2{c61A6zEeQjfzZQA$T)(;CmupQmf=XqT&Fkl%TAuau? zqH~PwT8C`)^D&vw1>b^vzib&+G`Ks;0Eel&lMPq%nVu`p2nE?ETvD*<$$He~N1QqEM0U zjJYne!*4F1x+Ez@_&q<|(lftWP5-dal860H*Vv}a9G8e2S;-6@7yMvKYo5(#Rk6T^ z;O_V|Ta=OCY@}zXZHP_iLU_7vvZb;o7^o}^M6Frl`j*r1GD z&f&*J$Kr@q{fqC7FoQ3S^Q4iM&4RS`p;)q2%w6!~oPaV`hsqU)!baW3Eozasvfs)m zW!|u6UETc>{4m(bw5R=ei;_ZotUtU%};s8l}^`%*CdwbFwvA`P& z-iZvtew;02tU_o^*kqw94Hz<0%MvO1E2oix`$kg=wz^gwF<^`5Yi`R1HH}BVJ_bw?ru9xqA4if^ zBg!g&KwV%Wds}gCBcPq98te1U?vmGuvb^Cp6x1icZ}K1Od5kAWv~fJ7BS!Q+a^eL` z%lG3yTz~*F2V7MI?V|waRDotI7NJO8?E(9&6_1>}_NfuA2sZ zODOINDx!Rh!+0I)-s)9q$O!Gg5(ozW z>#ub00h0Y)5e|1rSPE(c?qfT5) zN!_uGikjbfVuc4(B}Xbo8Cv45M6wncMbS5WbvTYk*4q=Dby(b5UwLU$5V3^O>7so? z@v)Hg0%m5nxag#a1X_Cyej%+7l%P#b9~<0f8=bRWuo*urGHXz2p-Uw#BYry_{IzUG zS1Q<3okXkB(NpIesdQn^U6?VOW;|00O^DF-ZQ}j_c?+8PrF#45Mnm{>TOd5Tw=JWp>mGA*8F>L8eovJ4^ zH&L_q8Q!Me-Y>f&NKS>Pza;YmNV!1T%(s5iSAcp&BYVM=1@2;E7=kO)Zuz$-oJGuRd^0_$YnoEZ42s@IIa!VrjMTl@4q3mh4YBpP`Sapp znV95Xc_v+~UFX+lN1SIeQKM^x#G09x8Ee@5;otsnPSgmPfPYbRuy=20;I64@j8-Qe zbGZ(S_rXO%w?y;_8^dH|51szkb^LT7Rfl`{Zx7B%jrnE_X)O~F_DJS_1~8Uw>2M#R z+b2)7LR5gu?zimiiI%;sS2H#w)AU8_l!Xi#%K`tx|84hV+Rw~TPW><`fXX1T_CM`* z)XtZ3r}ljg#Y+Fhe87M2|Ar#tznJG&(y+3PS!Dkg)Pr~b&wxiyAMzaOh+5VEf_0tz z|GT3MnX?XG_K3xV7Rg{t;J7=)9i&Tzg$0YXp?9VIB3boyO^T61$$t1P-h0z6zkziW z09!diG7|?RRHp}spAAe3X5BE$c&SYa?kP+)@A-1>-esfBVnBUp{AMUkB*bDX2RrwZ zOAK3(>%gR4#jj&XAZO~q1l`Hl6P%6M1FqIvxeU-T@@|*lOi50iSaL;PT$>EES;23+ zu7*RxVLk<@3DG@6-3Krp$6nhnF2Gr7w+x9577d*}Ssl(qm+h9l*y$=)8xh6QKXFv? z$^QrVKnK6Br~An#^6;)}aEODI)IG;-$4WOt{pFMScvfTl)Mii0dc6oj>^TpXRkCJO z`ir~dP?AZ-CUT~&=OBEFC5f6*;H05Z)XDrMJXoy{qc}?kU?!}3-;2F;Mnsx3R_`%8 zu+>FHGwu@LiguFG{n6Mc>W5{7s{X6F8cQ>wW3Xg7E3X{VR?cZc-4*_jwLMk(=>92P z)U@CX^Ho)cIFd=`d98A|vSfKBZ0d?oRE^d_@lP!ld!5z%G&HY}4sYbv{G{xy6nz`q z_+LDeZGYQLbvd4vcC~y}eUs*AvzcMb|(1JGBA-00=yP zGM{!HN9^SAQ=@ZFdRdNVj#a1iuD@r@ueP82$9+jgbX}+qI{RaP&vE`_JdpAox%eu< z>}bw$-ntDhMf!?E4I!?u!+D;ZR6}K!;?~?A!p=61sEh|Wo^WAsaTwbt3O+uIF8=`X zmwE<_Z^Fm9dJ9POX-{M662n(&wrQhdqne&p-z#R4TAHF-+`LF-3~S4_YXdypfzC3u zN)q)JN^w_51F&dYwcAWHQ}*jEvdn7aq;*}&x2R(!U}@kZgpx>hzyeMjP5?@`LFy*! z5vAE343#dW?X9Y1TTLOPEaUAxcP^`kek1Z@J1fSb(1xR;yH&7XqhsULcN&L%%Rc>( zfsh@xFn9HpWuHk_R9gI#L2{s)uH(_oHKvn_Q6CjUClc^w#|`3Z9Noy=?~JXENWLH4 zSk4k#{qsdf^(_sfqC4Hu^;RpfH+mSU?iSjX)HR-Ly<~h?4r%wKf(Ax0kfSV?s*24! zTX}@U>T7(k$2)lZ_VuKOJ0Axv#(YTGZ0jxSO7tP9q11Hjw%1i(E$)hnX_zW_8rgx6 z#tuVCI0WhW@P(Z%@>UxGm-1EcZf%x^3 znVKrSL7}a*mar;ot#vgfs+F$-SGHo;HfFS(ylh%=k}xx}=*KryzU<@A1*+fO5!CuR z`91lzXjw}oL+M>t42_%^XM{AKHb0SR0PnXWoMAe3uAYlVU(2Vq+$tfip=@KDUq>{cp@h#gsP)3-L&7E0H)H_gQM!^92?nhxL-yRf6WHowKE zG^OU`XsN5Eis3+GhG*c7rOVllP5|t84J01moyuOHd$LeV*YAR(sBJZtN#mxk>X}sN z#E++I_@swCn;_)Z<9;0EXM7!$t>;QpQRpjfppNxymZqjzgpe|Gv4K)Z(=e{4SElCAgZ*w>e#y1T7_sefN=2<)#DsoJMd?V z9ogAMT6EQA%GT?omG-M$2U=l{qT^H`WYPc$Yc?d12qf|u86jOM?3L8rDmPTiS59mZ zT>Pr*w`gxv_&UzBW1RJe-tc?wBaC;bi={1IuhDj|)crqbp5I$q+NwC-(IjGdM3KwF zNXtm`ONPL+d?>lLipD822De0N3VlNrmRRW=-yo@PQ4KqRJ!9net!Nvbeb~u3 zSdT>23j1eSd9gm*Upa-h7_0M4*S7`Hx%@d~m^lEqe1*{K`noHd^wZgAsJPc?yLB}q zD&-EPsFpW}n7G55-#dixo*)aF2302aHTuhmOd(NV{NIHE+AZEWKx$9-e(_D=Y_cL zS-K*sx<9^CMN|z z86MXW!HzB?xC*hZq>c9N8Y6oj!KSI0?iT`DM6&F0$nG{#m1+C=m5HvEve#bbnUs!# zD5;_|RMgZ;B8CXT#}nLn0(Jv(PbE1%mAOMLv_nyEt*5xoDXFUIDtgEaxd5@wz%6j% z1cEtkv7nePdP`7g%4uR{&aO&Ys%YeqtnDHfKaM83#11SxI5eI3cHLR@#XOpN-DtL5 z-5fR5`ihRNl&^bB;D#pfE= zrC@95F1#)-7;!CjH}5C&sE&^7sVH?+eYUBTan#aOQVOS>Hl6as<~BlmfFxx1Wlbw6 z)h0$?G?jfNwzA<*akE__q9e98-C8DnI46WT;{(mlo5V6Qn$+}hdy(`|Np;h-wU-zp zo`#a5=GIM8*%}KtTaAe)hYl^t*kxF4c6*kPqSRL{LlkrnI?+>Zr-}11#;$3a8o?N8 zJZ)|`%Z9)=o>Dsh07q&Y=B3kBcGzL;QdzB{TDMfj*y#fzX>+C|<}e4HzcI@x)K<&y z*Z4DCJ-&bNa=Kk1ce{B;NoAn3(pzQ}^_6!@j?WZR9DxpSOQbv}&1fe8ld@$WMjE!S zRm-O-VzV}$1zE34{z{Wi6=>Ui{>n#-tbBGq-5 zK|yegnQCcfYZ}SnXnQ!zOAcBx>^vNERoW|+?hBRL&8Vqt7KdB(Ey_At8+?r&oJ#Jq ztCP=mBqX`q1;l{iu;i$sx%=S9Ieq@Lb4_2NE>;T!SLR)8SDRz%dnA=Mn&D8`CgCm- zzhGKRLx?ya@SGi#ev8sKEmI|P>1Uy$qPM~)t*)=A5YyAJyM???!QIXwt!M<3-QK6H z^2Ry>)UY~8#IDpf*ENO1h=B!8NF4FF-`1AsWw-a!Y6z?X%XD+;q7_v$$O*f}2n2 zty5qXP{X8dcl#aEj;`GL^E4Kj=Z(?9E?ivbTP|=~@=HeNWmnRgZu8OhpVn7RUrx(p zRaQESJsc8G8>FqMnattpn%5pSG&H=(Jlp|;k`_JAoscT;s6S20>8QW#hwC;(#)KT0kWv#PN(c5k>w^dYDR|unI%^Ai>$p^atli}XA z8hY)hdQH&!s?y47borpNnXXT(iI7v8c;aNumCkVBdtAp36S>;}J0;&A;5a5?`@60PHi%bn^LY zx$5@m+pe6BI=Vw>qoSR{b~I5<12`lS@i=e|xWkUbJ7bk64P=*HA5m$w3r4QGTJJS8 zRCcz$Nh;!ztZQl^1?_XjSXz0z1RP^2=-%wM-;#x^?Nzoq(@9<;aePglDPWLE6!AD^ zuZ`npG=OpVLUF9LO(mzJt2U>LP}!;~YUG?v1XaQAcx#v%*q9rV=J6gepEqu44wCDx z;;!9nywcieq_@!sp`^EvL=1D>{s-aC!}8)t$;L+{>Z(#YGSN4<>AQ6mj`de1&8%=H zAZ3N^4jjO62L~7^YS->Yd0xzpJs)Z)VVWmZS&h~Tb5k{$w+5Spafa~{V#mG>^NRzE zfaW`v_6;X;xLW9L6Wwf9n64y>23+gKJe6P)(&je@&Egy(&cM%lwclpc^jiAktTgVN z(Q?okr@7JUM+`*hpTv0F_f3H=99mdg#l^P{6?XpsWV>r?UXi)!T4?L3p|Vq3Dx+la zx3NzNczb0IaO&7W4-Y#K?s-yRruZi;+Fq)oqy0rqTLlHO<7?Cu@Kw~@C2S&=KBitK zx#uSZ+#YLlla6W|^$Dn|H7&lwMEiYw_c~YAP)|)%A5T>q8shE;fzQlv!2suCv3RKw z^lPdqU#KI!&fQr?J7|=T|gd8tp$XM z_;bF*?Tq-Wl27OwnM}Rt`;E56QFvv}%W|irm5|npeR!Spj($UW#^7KQ2*@rO7|K=- zk8jh8T6b31>8_QLHfmcLM{1nsuz9S>6!T^(zoBcm=fHtq=A z;0y6u!ayDSbH}Y%^=_TI>TZ?)09F=?if8G|jbt|#-Jev(K}i#M3)?X+%x{l`w}6b2 z1_8=lJbcEszhb9ZLeJKDwE}>7Q0li)mvvuuBeIXVc>DhV+W4s3w?=x70b5Sm>kU=f zh8Is)W~R9|TKF2#m*y}qT)+u)TIVnj^1i&s6t*1^)7?q)m#Cui!K?miBD zx8==3X#FdA(w!|gSzfB?Mw_+N%W{3;wQO`1(KtM?L_@P9<>G620LbDzKwzv7M$h7g4fVA>n*n7;EJFqgp}8!-*N$O5bdEO?lDYjGszUvbolp zI-70AmN}T$(n{*7W@FwQMk8}29)GDJ}$UxioWY2Sz%A3)>!E)u2BiC*1EfcVyvr-=YX;@G3Vg$@j1L* z+`@CFG%d>GYkktPy3b>xZA+;eE!wlQi6(A1*ulc*63mV)j0}vfji?RVQ0kj*tI|44 zN!_jWG}MwsbEp`76p+IkT*`+Tnj$f}K4bt!2+C`x->NTmI=ZoG)7sLOs_|1jO{_49 zD5@StW{u5rUdZGFAI zu4xVga|JI?Pq5ip^?sR#pHki#VR@*x+aZEVfcoZ4X^WcB=!3}}Zv)9@S)NKF2=j#& z%ZT<|{?#WXCPDL5#BmHPx)4?-V`W;ZhamZ?BC>;Hvb#-82s(pmld{NgQ74WuvEs}kDI`tXX9~5=R z#chR>eR?|e8P^{ab;rdP7D@H$Q%cWK<;XiNbQDwX)yY4+amTzrFD>>}j=1=vuG@Xn z;>p{Zmw}@#GED09a8p5WwAa^BQQ9s>;>MV1>RRaKW;c0gaSh+rl(ElQJ1vc})I`QI z=P#7n+1ST889dV9PF&L7SjyymXz(90mb7X*%Vcb2JTwn|MVy&0i*(Fo%JX9mDW85Pd z;>QU%ZZWa>mp--Jr?%W6ucY8?@VkkH&BzDj{3#h~Op?A=aPd9G&cMdxS}85}`}v&$+jJ51e8{J(cU9$PGDyUmn0RvGkAuxi-fCtM-(gOpn&+}(gq^_i)rK1!z!LTz?J)!+}a~1%}Jj+jy zddugRByu=;xOK1k)K-IO|nZ|dUlq!N_b~wMNxZt_B(?y z?UD%raxS;jJ$o#5jo)FvJ-McjwA!bqeZ72F%j9f&)~UGf{{Zv&Iu@v&u01JD74CLR zay74XUv*@U5b*E2Ndcte3ZvJk&bz>)t}BN=ZtSjzX3gA{(I?lVuTh(pmld{NgGmKIlfXP1vg0sjD9hxnYhs5x@$eJ{*TkRRib ze-oD=joEtok7PUP{{VJHbHP`Dj-@nvt@93F-tP3gvWDml38}>?oe%A%KdSuxSd9Aw7TC8Lwki75n3ZZM6%cN{s z$O`KDGQzp;vUYAxY3@JFudCrDUl9eBGo-A>@pBQsEvJvpl#dS&!l749=+=})W)l!N zrgunrV^z4G3AslQNYg#r5>ur}hyqY)*@!yaFduV_b@jD(F zPwyAzT4Rcunl?IjH;WGB(c`l7*7n)yHt$SIyxqRvR4MD}-vf`m;u{~rq$#8?Zb8De zG4z_JNz~KS@UrDk2$~biC!WDn?O+(%2pPiJCFl`vhCgP05?O?-#}-B~oJS9-AjXZ# z!{B50>X=E+e9^jd99yUKQAXE^CBS1c=M&&Lrd#YRpQ#kf9nz*gwg_0jM#bbbxF+y6 zqK>W9)sUFv2P6@lzZ`6Ha7T7Bq%~9&m9~alX~yxq7CZZra7W-& zNj?cTD79;2oOGk5V7_UoZZwqfvgJaqq*CfFv@DVBVhjLi*L+A>*-~C9KA#m-4?A2Aa(YMt^obh z10y)th0>}inBWVT*JE%CM$4G=b_?}I0|zl7C-4Hg?5x{xy*zC4`ju@E&!=YyZv${S z401_2A)YJ@jz_#HSH<9(%D^@X$mSztU<8l=C!PXpBS#*1MtpnJjLid|G|FryprMqE zU_3#L;^&?n)9ZE0(FGf*?)qku?7<i2I38&qAqkv`rAgm!1sS5T z9BSLmMxeUBx~d9z2Uf^or-h_N1WagaBWO81AOX*xGtEPAvAM$@!*w_$p;(~s zIdBf@pLm~lCy9+B2I)5w$T&DVXLTLL-GPq`E$Uy#E03)tuC_#*wrpLuAhpkk2jy5o zaV*=2<86=}dxJ-;1+GwlQWR^q_pSBprLC2`1afbz56q#0%N$zlgbbuzAg*J8;tY4n z6N6mW0mX-7mUqIZ#a3DdN?ca$%|D>}iwu>Z3^xFJfKl}|0q*1p@xqKXMdtx82K$nd zTp4yR8v~ui!rbRM#`#W}8y<*Lzao09Gp=bmt#O7AsC&Q1za(dNV^c1buH@l52wIpJtNpc3+u zk$*JNHbs+8>K!{tYGn=kL(pE`1df&(metEkG2+H!l(T6g$k=(LWPsqCYMbqTs?@c2 z>ziP0O-tH%A!iJ6HLVO|7&pUO*0rO4K|!^-I0{CJE-WUKY)GVslu$Lq6B|i9$!Jsb zH0*H&%xk;18BA^Pc!gk~hnC7k2b7Sv4f7kfExCN23Ra!C#>uriFaW}R7{(F|IEg9- zQcNjUxdO8eU?Y-A&;#6@0#@KB*xv~e?I%_n)@K34oq-F3 z@UE3}6M_3HrSbJOZ%z_8Karlt(nIe1JXS zp{!wWbDU4T1BKh3;HM(c_5F#jZe*%+%LEaC;C%Kp5a8?(c=Mn38~9&I{l8J6?0%Ql zKT^s1^Gp4$kIO&yA-yw7U60h*{I~xAVy)C@+k{r9R}%}E$q13r$k#?0!U%sDI5{VT z4rKmqpP{b|ox&P+&N|)(0V70?9bt?(vpE2`V?36A71I9zX#W6%^p*L3rLHcP=9Bv$ zX#M&B0I@9Il_o#9Odr0_*i{y3&c|@4r@GcdNfgl;TRdb;!qJd1!gtG?k5Z7S(ndI7 ze09cG%Mp>Glbw*FQzc_X=hjJkI6~Bb^pWF2${gcxF0B_W@N77`kAbA!s`{@0I zyE;Ub-?=f5-zV%Udo-=-nBtC=nBwCmsendD2rY5W8sJ{gLEm(o7Q2(`Wu|RDCW@)F zk87R>46Y;w{{Z1Tqwt=S`$9g-=^pxirPuYtkaM+1`APdI{cz;p{pyeMllD~>?QXbR zsasW4$b@b!1h!_lu()wIj02YBZ@+<0?>chfLs>Kw(nna>S~#2}VB>ga8`~J-CHyTQ zoNtZD9qRp;(l6=ykN8hV{l8M#`r%3Usz1t4*+=VzC*HXK04YCZQew5v%bisnbwpI+ ziUU1M<04|lf(Hl3~zLviz zeihOG0B_W{$FHP+D`Z3W!TTx1dd_Ez`8py00DgYTsyj{G;hL&2$2+N#DB^pg;B4jK zor&0B0-oEfcL}XAS1`t1FPz9sjccDD2N-j5a!xa_++hpZT`#Ome#z-Sx9VCV)f2q` z0Kj4&_s8s~EWXq@f5Bn=ar-K{1vGNp*+p)tZEsn^Ba?@KIFZYKN^Y9ZaxgYt&H!^d z#14-s~J9?A;4bp#a)K9~D zZ|xdOsOlsC0GY&p?~mC`sx_4HAK2*6{rUSTdaDK5+CO3i41TtuvWmC`@y`j+$4ET7uw{ImZ6V#|7D zkpBQ<&HS_f0AlBLmJ6LN40V-Ef+%Hk85w;;0daF$;enjv4g{VyHkMPsI*M%@ov^}w}}4N@L?x)(7Kk-Y^k|i zsH3N+rJc~cnuyDZYns;!R3xuB8ohj#0K3+dPNiTGzn9FCVp0a!rXMB zDgDH6M0ck?SdC?7p3UNwD@;NiXU8mK|TLD)j{=YzzZNOJ7Ba{YVt6e%63ai>8; z_S*^vQ`7bI{b&T1>`#DKirABTl^*rhbQx%{(qrJC<13T7rLG|J3!?OOSl8P6gYTko z1ZTx^bt>X@^lfW8wW9`&$Gl*w)~R#be{pdorHn24FsF3wLo#A{!(1@8y4oSQJ+aL5 z6w%}|MvUYh?~!pW)gAGY$CFbU=))uLROA!F1Gu~~gO#-lKqQV_M+!;`YFiDmMn^H8 zvUczX5sWv#ZsfuYFb4Mpk7Yy3YI3wpQ-F6)*u@nEOJiwsj=*H)KeOCvt}*e&kU4^J zxJoTLvFuQ-Zn3!9Dw`Pdx|d@K+c`?3jQXdVy0{S)vd_Ljyx%j~N5I9D;PTrr7ziER>L2+8YoD zo)@0=^xRz_UyN-8n%57^2lFoeY9pqleDb(9IGA4d9_E3PyvJKq`-Q@)xKfWeWv7YKamxvNck^+Kj}_A7rq)B=+-!3Ew30XY zoT~j5=<8ixoqf*fLfMT>pK#)Hh9hp-*p6pEGP6md^x)409MS&(fmJJi^Dja+d3hWKwpwfH$mT?1M*Qtsw)1SM95L3$U+^F1yXH7kf2qH*ys~m6Vr_oU0W%0=%h0ogk!NT}*FxKeayl8T3N6rCx+QITkpusdugalJ;w{3k7b z+|(M}svOAig%?{k0U1lpF5J{L!hMeGC%cX|2ls<#O;?rPCONs;d- zh?E6_jH@I?nB5zp35*18gdoZ?3dr&BTC9W`ZOv}dlUWM}v3R+u3Su@5yxvKTOk{FXkBco#>L4y0mKGo- zZsj0Yd=$jg`|?QkQhSz!hA=`&Vf>F~P!?JMFn=s)h9+r%;!(5eVO`7DRT#BOyEGbr<(`FR23IKA)1m-QuX2P68 z?ZRZuq4Z1`TbMEyuoWjm6K0+$osb^(w2%fsC)Pmu)uXvNIwEDI1aeHSlTO=vX!@vH z#>Dsp&5W6w6Wzq{2{_#Pmt=N@vzob@`Rn72u`$hygt}puy`|-$oInl{u>f!Hv4Ws3 zT31h&*05C6x5?D8)l@msH}1@QS;Gc4JZ@mY&d&7|&OU-ErMoy*pt)5`s%kFmji-(? z2Ujz49Tx`yYkn?)~&S~I@1kAlzpn9vW~IMna*zu zTFDsP7UP~Cch7QOlS$B4YD*QJ)K!$xR2jsr%X;|(T>cZBV<&`TZvONp?0IRTi>Yeq zt}|1LI$q69O-?D|ZZWqJc5#!9+;+)HoBhTLcSBDN96VSuIgpTKA~!G-z5&CI;0&G4 zS672WSScm8O)WipYAfYydnHrY?#Y^CA!MV3aUA0w_Z&kZH??$aV6LyDiM4h0FxAsC zwSpN3SjZ)OamSF>IF|<*OSZrb1n`WNMIS?&QjHwS`>Dl65T~J}Y$jJeN~gV}GQIAN z#NZrrj2!pm>=bMorsYX+tFI8z$t_JwYMs_ZNMx-fwaoyITt{P&x`f>rS_MTlu)6B$ zs?SkRbmELrI;G}D#}Nn41+HU5uun2i2*QG~Xgej_P+zFvr@dUMXe#NcVeC>cNJNtL za!le{M*~PM?%SCh*6!*0k#dYy$2!#7noE=&mKs>8;d^20OF`=;baC(kic1FOo;Hk-Vp+*!T`TG7lO5rxz(JsauTO1c`UpHXmyoDc0&@ERKP zBWDH}+l=wY)rTF=Bal4Y#b0zLn5G8hS5JAGh`ENYrrFfC3v(GAIdGA#{jJy z0p4&Bt8`W~S6&Wt9;B^p-mc`~Pb2FC+ffskOma2Y%W<8CKqChrfS%2*F0)8oD`{TB z$4Awe+*%mughjdH&%FbD=R4%5TK7u9q&00lt|IGzq!F6g4jl}Vlhzp9jfm=uc^S@J zRk}?LVIoRcgiVqY)V^Q=AMU4v6Tr^>TL~Vb6Gt4Rwi(J1b6b{?lgpVSak@gmVx+CPT!ez5t&ZgSa4E}pX_@DdEAly~}PQyjT6WHjc>m`~uW$qhb0Cw94=PK9wrL3r_o^Z%o=_HZyIJYi@ zJO+^6@HPXu{sj$eu+g=QA{&g{6yjDoH#df~mNnRmY>aUp=WGsec2)~+oTYsiT<2EC zMBrl$bGS^r96NcuW1cvP^(vw{DT+GvRZ%n(7^#@(C3Ni#k7qsDB)cT%l8}c|ktmY3 znX`3RbPZ_Pt{hk-xRakdp8o(M*|u6nHSB9=d25V~iKKP1eatv85&;>{BHZoCZC7Hq zfan=K#&XxauPFieeGUmQ6x2#}y4CBse9cxG#1D^;yyfLz; zUM$oR*V^f!sG3$+5iVJR=ECf7;CwH9r!CzZ9!iz^{{UN6O;HP?q-S2oM)$HZAJv!j zomeEFH;aEB?5HY@S8{+cjE0P!21hfU5iY1>80Iyv^S1yvjj(xmE`xQ_7N)~jE9z?5 z!U1C%3(Q%Mj2HQt0G+(<9BU)j517FD;i$Y!;TOhNfR4OCe(j4KQ&%pf}bZz&6g#^(U2@ zE}5*Iw2ioSn8dAy2{=pYI3E}jFahrz9^;Mij%Rd>Q1VNU*pE8W_bhcWKeBMuGP#ms z3~gBEx@>Q;%SR7~tw~(9?e6DjxZ7$e?ZKBPhg8WN4r`r)(l9uN>E>bo>jFyxGvVeSE^VZ+SeZ@Jtj5$S3W01#bf;HNV&(Ux%6o~^Fn zhhjkm#Bz7NJdVq4v`=L0DLO;H(=wRD6}huQA#9Z$n3*aBF}gT}hl>O?uRMcuu{px3 zvu3moKme|E+Dh8@M%g5$(JdTVuBi9J}hhrnG!OnB|F_pbGlAw+XCR`14HC1n9 zTpUejROdQi2?S(-BW~Ms=gAb`>=0_`rn7eiCqOv_zNw?4q_3nF`e~ttS{Nn!q?~+C za{+M&<<5P63rY|+Ta9jXH%Obew{Wa9EaafA!*Hy0Ba-#7t&T~uMgRZ_cAe5u4>c$k zK?W(6qlz+CuRdug0STSrno3f$A2_Dcm5qf7J;;l4lX1yg#mp#8l!_#26r=!PDB3ou zNOnrMGE8vMvPyC0l)EVNXlC}cO#^hywgArF;CBZY_>=DkSuKBSn75)GFsmgiQMD-d=9U5#?gY{oWAvAA2P z6d0HX2}s!IE!y0kN##5s<7Cm1l7kb5l(-C~#kx5GjqDCPomokvr!H#2(_g z)~3)GYkQwPy^gP?8|8!UjUKl5{Go1aYD&?Nn}f3TV!FdK88kCB>^z7n(GACrG3R9W zFFVlJSKB8&M305w?$SSu6=k<;y0}1XML2(pnCyOK=1-@Rc8^9qR3yG5t<*`z^741} zq}wp%l|h4EP`nPf%NNST{-0M`pTBO6zb-ky}5W9WQUWZ zQq+$3C#;wekl?w%*7g|pb<&^k5>j&Xlc(Va6_1dQff*}SIX^;fQ1W!g)Q)5Td{b9T z#P03aDy!*Y+}!qhI;oGWhN|V~q^&`8%`Lhf#vixbviT3ld%psta813@IcCQd$$061 zSV2o^lTXpg9aB&-P+ITnOz&wvC-Vi*v?iac)mN5MLLACS$aPHE*^K)~xO}BZ=?;uF z4fb}`-Z<^ljyz6uyUi!a)4$;>y6MX$w!v(U-)yIBFt>BwUheYa-dA=wXh)f!I+NIQ zOG_0sG*qpt70H4B|||9BC(sQrY)6fpys5Un( zE>~`mbMTarrzsbO86weUu6bEww^})D&S6GH(DIwOsVE(QqiOaDtsn;V3nL5AaHuyD#v3oOBQJAP?s z-MVVdX?7H>2Q4X9xi(=+G@u7ea$Xm1nlPoKb_&B$DNg=MQkmIq>JFXWwJS>gLn_dF zi6Tk6jHIWJE##Dl_br|mN1-ymaHS3o$R9F>mXpuU6|$xva+tc4iQJNQ?d)C|bfOX( z9PPpsy{ZbDI;K@pJ<-g}@V&goK?k3xkfbQ>{vaueS{9Dw(T}ItmQJV8t+LJt1AubJ zC70N;Gr~S)bB2+l8z%yhnA|E$0SDCEC{$MJyKQSLXj~zvj2;O%1B*!*BxD>M9gi{i z6eV4vvN|fNINsq;R9NYm&y28=-28-}opp0W!aeFnYg}&qs++}J2YSu}a?@|$?thtA zq_$MiR>M&QP3vNjvNMV>;l$ICmXJZ;xPlj=>ueE7512k=!rf$!j(U^)!qF10w^Msd^q; zl`&+v;$d@K*KouDl$HPq$;ie%eA9Sp=$k$UTl+trgdx9 ztV)VNPporKNd>rByW4KCTga)**cJPqBl0TkXv_I49mr%AUaI%_T$u|* zN-C;|Xy&7iP8cV1Osx$We-7Xi&l%qt#!^ggEtc3>Xi~A{Y|xcp0IdNDNXGe39tpL$ zt3caewOHWYWqOGU6(nnKHTGkf44YGG2_Z_>JW-azO@~THJrq)+mMNBbYsAGF1 zj6JV};oK*`9FOK*Gf!90-Dp`^Z=I6Fd^xoE5!_ca)LLRqHE^i7Nl5#}wSmzVJ=t^v z*Wx{D3s2lH8cME~b8MQxIzQ6FC$e+uZj8>8JndV$TVxmKFE@?RW$Ed{;BryHtemW`&eHu}})OWs>U zt!e0^1BM5&rQSI>BjzfRri_$Jl?O$dKA3|0eAO-=8&KjtVTEh7SgiJzhTCm)l)kv) z0pCA0I_gr=MmZcTbp&sWCzdmdQ)6&ER?XOel`-SijtqRMbTHtKS%6$51%R^5u0m~&C}BRNitAgY_WP_@zQRfegY%80FEZ6+eOQ6A~5 znx!gPxlE;ENh0uL7qwZREtG)lIknt`sLp8V6Q*?Fi+$x}rb*wUfoyBST^?>XIQtckZ^ge)FwObnwaLJTs6 zg_Hq<&15VS;IotfApxyO0lUixl1u%3$P^`l8mUHj&M$#F-uvftzwmwlKHq{4%8HW^Og$S>YZ5I5GN`3l?fN#_nJv zkVrnAyg=i0?6qoJy4AQ?n-~Xj-x*l}ZH<=6j}|2DiqY5uBVv_s$0X9OP{tLo_?-;S zbJG1QC%1K&1<|`8;d2XgxFb1T8>K4twt?*>a=UcdJk+}7rfBKu*TP)w^6n0M)WmXS zpeoI}U4ol}T(oYb2e40(#OKW_BD3D9H#;MmV^-YqSuslOc*{zHsDzi5YpJK=$--eR z7ZbCE%aInx8!PRn^(}=zsHxt?>RIf2a>|Vz9leMiqkZ#*vmzsI^)UKecO?5hHo{~i zv612zWh%&APbDE0HhYuEsRjnYI*5y6J{XI8l!X|^68)4862r{cV3!wX% zhBfWO{FeU!1wP{n!>8-2t?qlNi#+^iiM&H@ zO0`1%EGs3kfxu;YSQVTZS|lK+6Y+JeYs2zf(%p`Ej4m~;EHt`XQ@OVqdYY?5@wwDN zuRdq@A1FVY3%gOo(S)V{08ZO=9imHR&K|NC?$-^S8@rs-+<%RAyn3Q>xl!g@ZEg2X zO$Ew=T8aZZNn^ijD}7^;{3=T8(k`;Er!Y@blm(&L8+aB$;t>Kbcmo9(3`Kk#s+E^&qY3PT1lyBbG_e`K@vOJS~RE*{esVWub0e zf!4D|x0h4fQE0d8Sk2d?rZ39;KYd6h&)sl{;77 zqH3ANos%F@EA=eqnM%%TVyY}3QjeLO)a1*>5szl;ENg+UBu z2to|7LJ)%i2toi5gdhxpg@k1W*_E(bp#W~(iggS3=9z+WmW9|THZF;}H|{r6bWY{E zuF^Yjrs!O76r^=PoTqnkbkmf=oac1UVAyr$EWtH}VQvnCA)tjr*ypN9PNx6Cor`QZOFnB?|@<3L}sdtPRT!2AVgV^VscP1F@jnMe>+>@tw78B+)5VeY;Ff`!v2{TGO z6rhjPw-F5YD9s&M;zSBhP(h^Il9}qgK_@I=D719e#0=D zxeKLxoHo|={{ZC2{{Sl*{L9ay)YLz0 z;CJO`v=0=>7oO#iB=A2nG_y6K?`iNU-4xtKMK!V?+PmgbHprex=bw>N93G)3HCJVt z*_RNlcDA@Qb5+|s2MzI8D_uUrE7!vcN1c{-Nl`W1e2QL}5slMYcvPJz1LWf?+w5uXUNY%%jU6j$ z5YKztGWps7+%*3H66+r2sG99|B_npyO^=j-xu%vewzeYt zV4M|y=mxcxj*}_r=6GXX=_$!48<0T!`1#PD!?m&M@U(Cp>tJ?RaX~gRs*H0{)eRe| zT7%6;RAFBqBqoT8rt`v$pKPgGvNBX%P8V84MshsiH*}>dFErXgx+u*ilE`pVDcpBX zWE&>3g_IgbbBv}lH=2=`l4UZ>D56DGG;iLcCuqsan5habq;91)S}`N104C>}buQ_% z_FS`eUI-n@Au-u*=WLqKBIbOZ6|l;!+|(s=)SX?l0gt2d#v6nW@kPMj>qp^;4=pZJ>Y2joU zq!MZ{vO5xm9671;IREFxb3NDdy!yWWy}7UZ_r31#{gL#fQusq2Dp6Fy&XVQh`iH8lBW0a%bQhA!vfgkF`wK;;$Nm$|2@lvI(^H0O! zRwgG!SAkh!-WrVpOq&^QXdn@tjpNzGuS%UTX1~jyxQo1xSa-j4a*j(M>`8q#(dcsmz`(&{&LCa>C%71*n~L- z+jBZt(a-My^>k@};mANxE|pMWE*V*?jThKdYlmjWxrx+r<(qn9TjgjFoK3w_!+3;g z_6RfWM*7db2UlstJ4KtgCl^~qXp=HD#;2O2l|B5_vKOS=wp*3I4jn^$KIP#oLpgT* z%YHW{B;r^%;fXwW6@B0`R|)BS#0hh)E5lB6zcREMx624)aKnY{cU89=MoG0=i^eB9 zl(9OXBBzk%VEs2@G6J^&;p2c1D+4tZ?_S78`aD>VhYi(C5qo`%iWfifT+)nr1>2Fk z)O3f3S)t39u`PCn8V3%U@S^+-lL!2ndz(h`|s#pCfCgs1uM@1?{x(FZ~eCSYdxvv^VTD@(k4Ar^QZZ(JNg|}YO zE33$|#3B3VlR6^dbGw;IKZ{XCnaG8PR^LBMm^u+5CV}pGL90l=>ZMy3#x{Q%$mMKH zDnzS1#O3Dx#cT&j1SKDQ4-Gx{PWA<-5c7st2s$DYdX<-oe;pGEF>n>GW98gJm6K0$ zGwU;cOH6z)9mN`H&g-34M0;-J{{mdktLDZti9>uhUUEHr8y`icY#s+d{boK>RZlPD zd3)Gzd9P%>D&|`}Jj25ddS2HKMjb!ZYsuRfoZHI&3#n8)2VW_I@8V&O9o-0bfAhX& z-D24p97Ud99wW&5_TNi>@JG`UzpCVi>XCj(mAAWjrK`$C{Xm3~`V2N{n^qgM3-x8) zhdxS*SpK6{Ss8S|*GUOajbm>Kaa~UOM2D9%B39VtSI5)8^H*(s?* z`1XVPbnh_{xXvDqA4#ztsk>B{pjEVA+ct?V7`Y*~y7N40Q8ww-Oreu$Y%IDBP-e_F8vK(WJ9O1wl-mTcS zh5p&|DaHI?cf;PA!Z?0_ZJX-wX%{;0Fqam`&*0wdvaO~S^kvo1Sjp7fA@@9mN{kNy zqmUB<`rpd@pPll58^yYLf8a5x=9sz4YBoQu!sd3RP7VM#7k@sj!(rvABW#!SWk&p7 zqqA|l(ibo`$CZidWM+>azti|mjqmknP{4KcI~7CsR)xEuXNLO*usRsOcU(hRdl z-GR1d6EvL>)Xf&|jb9MQh~5cL%*r2izr{!3?ADJbvxeo*i< z2>D7!?bC@_PY}rVT!qae|l-f%DK|w))B%#l| z(WCWjvLA4zahpKIA!CK8ajAzk%nLp8!pNH)7twb9T;{}dZDQ`{+WclG<5}5Ir`xQS zahx6i-#IRhw-z;3rg%w>Hh0@Dn>+ysgr<>01IbdX$Fa^oR~Jb%8s_s~}WZ?cELEbr&Q%>wPxOwRfuCN>oJ{Z^l77guD5 zR9>W0_U!Ag`gTw$q^5rN7%|^w+u^-BH+Lxe!iqFZ@m$|7h*0X3x~?GFP$JZy%X>#7 zh49v*r}zOKRDI0ic1fCJaT()#_>86uVC+RQLD_VGD=CrEy}zeE{y2(WRWP@4wSTGz zq1X7#ZcnrX&W1i;H!dj%3V7~S6bb$jx6^x2ED2&HHqq#OyI8s3mr6K_)Yu;|sAN-I z5NI^{saFIaG}#TE7gOA7pqk57Q?{N`v>OpPjA%(1UKM+D$Hz{a)kdmqI_Kv8Ynk04 z{9sG!8aB|2d%Lt{Km98BbO2>Ce4c!jKgp{FE2X2T9c0?;=LtyGvTHvrU$}7anA#-4 z!ddU6@0CpfBn7WU-C^{#gd5HbXDt-PD_`<;00V_vu*6%=ZoH6t4(N68-p9y z?^^vFyI6lN!q=^GAyPSl_#o66XfK+y0c?&~aq4YC)%BfiLcOy9B~{1flvpXZ2tbdK zM!q)4@;vtRnx#15M-Pg6{=C}hM;{NQ9*7Eb%vd{ehx|30kusvZjI}-E@&<|&t?tti z+qR4TZbEUcr?7v!KW^yZ(Qt9}4D0OoLa=}G9RAgXVa!+BB4qYSmhU6w6VL06pA6nK z&QlZgOndY{+>sROjt+ZdI=PpjCZr6tWZqowtK~OmY`FN>zP{!+^|zB^+s- z9}?)>87nR_F#DksvAt!(fGXTCZQfW-Le1ytAvqH4cV0m+7AhGJLKyNvaj1|)^kciA zkwpkbXR-H{D^XWY0xT^Cle_(YhgV;x+}``{i;|}BOIlK|Ww8HR<=LPW&EbcJA9SuE zqJSKL5Y@W&$g!cao`5x_8zb<$7TO|wp4c3-!Bnyifap)&SlS1C?1;JTYPnUyW{Sr_tialec3fi!AL+;`mlZjwl|x-gat@-R$r&T!hZo<eWRL4Of(ZM5_PJPD_&$is@jk?w=T79x6GRc)z;9XAZmZ5G zXrK#2Q*mwyn*k+N2@1GQi-F4?`?CKL%XV*3_+XwRF7TdzcZVotcFxE-syW zr$TA2z+)(wGo9!pUlxI|=A&b2xh2}fMe5Tl{s(7zJ*@M0emQl0nyy4(PMB6@-E_pJ ztIEaZR%R&)ozMsY0hme!9_+SoH|yC?QjwCO-f1Uz2b^d2zOgdUq63_40w5=jMw-K4 z9q6%TI=f769^Z4573>Xw&UYiK0gu zF~Xc-nfq{0qth4$vgrHbrUHL?nGbdPB|u!mLj>3v%kaN=6nB2qneux7*>!g~v0CWi zC}_6Io+K1EKhBbAKkC%k{6W|NHTim2yLx5=-e2+U*r1w|XKI-54kzNSy<)zFuSzL1 z_LJ`JAp+X2&p5VcqqONJJRt}y+c0w`8QU9|)-tY=yU&$0o{5#e8aNVlha(2~B(Rq| zsG1{3dNcYmib`U?lxPr3B7)-tEQ#j0SXs$6+{Y)2F!^!=7HI0~GsfMooS@b>4eGl2 zJ=?vou#%k5l^^FC1yXxgjc=>_NXb__8x~cZoO%S%PE8|1dTDb@IbGK_6QAIvhEPu1 z^0N~qx-rHsQ@(EftzcR9Y?fY4Nm)IovL+`sg!1_q8L(5soQPPSH?hZY>#pY{X7|_` z!4yOE4~KF5E85kEu$vXG)Pm>%p->CDzR-I@tad4=G^k`H_Ya z12xX!I8pWgh%p#XBY!0Y8^n{3vfCSP6ZK}M=A(J&FK;v~AKgmbtsZC~>KE^QQP;Pa z31k3#$)&Q)!D5(S0dd+o3eh3$LTa=M|B1}LprR@P)@lWrSeM!AEU`O@P+mNkf%>7L zaM%lqhsifwKfK<~iZtcHMu zX@R+)fgBYHFsgOF)Bw~e*X;H(H2!y7JQydQ7zzzpB|`jlhk;-nC9uD_^rf^3FIm`& zi)O2qca&g?-1fWQQBS+Mog_v~36bJAN(xcP=gnesV&4F_CMnBW2QG4lNYsiI!XwOJwU!CtG z38@&Oq5gW<${#@VmxM>LiJxjrMOy8%EV5j`X{+4^>o@H=$GSm@k z0NLFXll#71$AQYEuQwf5LX#zanGm%o z)voO^NJTmr#krt`+^y_=a>(X~tq+zdN~9<{sSYPWe4OUrLF1lU&}(eTGgR8prq= i=XVqI_jI4Xe7#PFDFSaRy#;O-vW-90$LW#LYc;3T*vkl?PtA-KB+g1ohN?{j*e z?sM-ueO|x&?z>+vzWS)SYLtvowQ7#~|54BL&uhR7IVo8w0165UFoygA&+907*6!}k z{46YvZp3 zmm;g8vxJ4Ujf}6Wg}SejhMBLO8J{_=h%g$mpf|s_gR_H$y9tH2gT130zqb(8@2&Gg z^1pq}LM1HdYHrD|_FC!>3CNQW)gNQ=^73N#;$U`iwPIo8`tzK>0aH!<^S1i+uI0>o4Ec(IY|C58Az*; zC5MEBB*^mT4*%W)zkdT+agcidzCIx}DgGCH{?*ApWaNLD>tE*jhb-_93IA(#{mWec zkOlrB;eV~J|DT!buRgAYBgC=wf_SjcOMnD`00##T2a5m?2akw=fQXEV0`W1BaWP(? zViMpI5fb1M;1iS4QWBHWkm3_iF;mgdy<%WwAfjO5V4-KHrDvf3tq~{$L_}mHWE>O} z9C{K068eAm^V|hsB0|MLE5Sff0nnIGFqlx!JpefXK*2%0_}?7)KR!^+LREJQj0QVzgk!eLReiNRy5njlcQ;IIcLy+;Iz*M7xSn>?fD zFm(+qno4bdn zm$#2^Xjpi}yU3_$aB@m&T6#uiR$)K>`OB~ zWM`2TuH1944fvw9fvXmG!+h%&&ot9LVoYWzf?L{;jjx9U1%62s1y+XkXu7sTYMGkr@5B~Vs}GvZdXwQkAaYn01pcAoDnhTf!1btq{~%qm@(ffy14h9IcwVZj z^ZF~_#G<{^G=$$rNMF`StbdI1P{z|gB#L{eZ3O@5;HFOs@3C9Xdz9Wb=nLJ*WD>E` zAAXloy_${ML`a+Bf22IXKBLVa`vm;dUk^Z0YJaEHIg5z(W=vGyc;1F2xlig0-Zr=9 z_~H)Sr2SOohwChY*+_gyj`fqCfnhkt`^3XN-aSG~jNam{7VywLKSx?EQMkv?xY!x- z_NAgn)gns{C|grjZ7W{x&gXQ0)Yki>4jDyY1pg<+h)cByE#;HsdeG%4bLDr8hs;BF z?VO*bs5z(k~Ef5f>o5!2f zvB$z3TRXruM`9e`;NFe_sx9ou@17+p?Nx5HyYH(nvso0&E&NnFy?gORl6UzCf%X~r zxP;3|tMSui^BAO%tkwRV6U`-yp!X=xJna%a!$~6P{$8bxc18$8t*|3}?fdm<{2S1u z@%K~4hSR!lml-sash-joAH3CiE=2b*sx`kiJOh|NY5R#h->rAPFdVhnz_CtkM7YfQ z9!y-U<`*s)cweShvV$RiM>Z+xy&LB)e;RSqBuqQ`AW^x(scl2L#nb%qbtW<2=GkLF zrPBsWw1r}z+}Y=*dc08FE6a^bHLz#|?>k9xZ`64Zr!PYJK92S~yYx1rkm~nyf~1>s z-HT@;^_t$(@Ttu3|Qd;P|tOG;p!}%w8F?cm`xeT7PvOwA}H}$!-i+ zp2F|>@`MY%@^X1u0vY*>mDS;$4ml;=C{T_g!4(dZX}*5w&+08-N!(qIhgZ3bdivz} zhr^ZhC-PA&Na9cX`}w|eKW#Q*I&r*}N55;JNsW0mw9&H?&i$-CL40r%C6&BBZpt>{ zI=&i)Yd|yyOYu#~L%ZZV>4}gf(NVPA&OuZLu%>pn>R~@l8+ZQ#D0wn)-E7`F zdJ5x3Q*ybDdK$KYUb!sAH*hHe2^O&DdsFRw#bhB&Az$^S9c05|Pi4q~VB1N~W8g{4 zJI=eW!)=6jbmDO=BG-0y(poxNra%>b$~4PGo1it=CoNaGyS)5%Lc7gv#ek`3FYq8u z4Of<)2Wo=McY01ae~bAUU>P}J6x2(95}N5?Pm7H!T`C@RHhQ-b554)L#*Rn#oVmo} z+^+i`7K`FjXH%B!OaY^=X5`o732m4nZ|I@jjhoJ*rs}FE>|d3iifr*!JYr0+(O5ACj7Y5idxNwJW!WOmuL6G5jX5X6+{Zdj9%;qXT0jK;H0N zI)>2$3A148v?Ip245woIKJOWD*9v@~{lfbU6k2#Z1EHMHzy<@)+VN=bZe)jpo1e9P z4Na$Z+CsihRFr>>_n46N$wQ|GhEx7s-bYEF)35r&**}1e=4PyA*_(xQ{~Ci$P;Aya zna^#3i^Ojl{4%o^I9nDd*|DMnJqF$cUD#a9-!HCDe)+L$I^Jz4b^i<)p67VYrQ^SH zs2U_e;jG%AhWk{3wC0C=de|#S{{DcB>f9^NUR$Ge+Pz_x#%FP~NnRk`7(ei=3`mY| z#VvQSEB9wV{}6LyX!=WS;yUVSkn8hRpHzgzt*-LsJ-MyCCb{Gt%*w;Kc40If@J~)K zqfZ>-H@?D28#*sC8x+O)qDVd2px$kWf6otXQpbQFu6~oVa+vPAIurn94|TOE66aO- zI$6pr6YsTSMK{G04i&X(Sez!N6m(e^4in2`pgzp(kGbpC%ehF-!Rd{F-QYshHqXY& zuWt`TS|m7vf95~9Yx|x1y-w2)KrskaB+C5~}weyM$1NOVy|#P-U}2}X(5 z+Kj!dE3s@@gb18A$lSfMd|`QR^$pvcrg74JI6H!zCP$AwGqatU+l+6sTJL8lEZ*W= zcS|*s+7#~h%>`I%Ofy2G6uLF-;*!)VwY%CSad2RO8SvzOM;WapmB#7%j!su>F+jS6 zjm%_&q1+$g+~h$$z=5;vWuy6D#;|pu?jMwwQZg;9vBm665%4_+!ix0d_ zEobR*^83d&0-sBkq(*Uj6na7s5xxXInpPRuBAxSW;Dz0zs(p!iFE_{Wqr<+EI>$kB zV7K65eDi=qzuWn}BW1h_KZ45q!~SGn5`|2XDuSeH5S<}0`iNj-=^zr+_z)fb&qrl}gPNdWk2s4Oh$*V_4c7n;o!!i{gMtM4JC`|D)b2s59( z>GX`}JS6VN=b%r!xV8Vvdrv-;-j7eKSAX^l#CK2;Ylcd-d4YLTgVUJfH8AtI@4d!t zulA|pt%nq1sK|a_q|!LfeONd;6YiP>FlWUzsU0U6+CNE1eh_wm9y6@!+p`YN({DXr z!Q53nrhh;X)XWcmOa5h|gO)n0=dI#Ri3iQrr)OZC=@IAG+S|st>eLFwostFyTEh)i zj9qmV1isB5D1qNh)($_vA~nmcrD<=LO!6`KMV24u>Wk4EV@Nd0nGnfpuus&O6}hsC zXT1v;^C#uC-20L%E0^swg=|5&pt=T6@Wc1-N_}nJyx)zwdIm@zeH8+tA2OAoLS;xLR6VlR(;t4qxC{L* z!gjr5gmQP@pYRMEy?O@fW#42g#3L43Sr@*xK{u!f(z(yq z-VmJI*V)W@HrEMS%49?()k1y?(-%}FXHpd&oe5bd1x#Db(E)4<4D`pA32bnt0_JWB z;taFfjm^2;qp)i1S5~4jrHE9zvBOwMI>s%kEeQ$}4K|&J@-VZ9_p7_H-W+}0Z*b4^ zVV%pU0)5V6?>~ z4Q^iFeAM_w)2fSqbncM2-S_pKaOrF=4x4B;MI6ZJq%cTC4lk`!d4k-C?MhV=!1*U9 ztNto6rq3No#j(>P#+U#P1GI!y9``ZzBk!@+)WNFS2H&O|`48l^ zd7M}%>*}+1Ebl0zN{snvL)UaK_oj}Ndr?OV8+_ClH`O&0eg?QmB`22jBlSGPEn|m@ zm^~6K9Nm5?2mSb(5b>o-{-0Kzl~Svj5bQ z4BvPs3G#fKuvV+pt7s{y2$^PTi;!A#5HATj25mGy6wPW0+~>Hhb3wPyRf?d#I@B|y zuUGq8u;-D(0u}2L-1;X8>IQyaz1&b^DO#7^4;^^uvK;_crS7@Z!LBTi7h}<~$GWZ^>KV68@ zq-n7l$h)`^;O)JUMCYL+`;H!$62F5VEwjRGVfKaneW=U`BDG12P$kt4;Rt_YTuDcA zFVpAY%Fp#6>e#nyrmX8x)MgVN8^zXpZcv zl(GEA(~+>4Zq01BPi&L-fk8r6-02!6<2@L~W(AosQl%ZPTX=e4943*YnKQyVCQ{E0 zdXz9#O2H&zO*j>&IZvy^$);Y|-BtMUhnLA4w$t{j8vBx!zD6_3=De3NDxTh^4NFAK zbA~(OoovR^6q|XHwsx;Xme#XS%v|cmwjAhmb@Ew|-?j*P?Zl^(>l4{{IWXFvFTdU^ zwPSCgAeR$fvWpyFH0deD%xCp~29))-P8coQ|tTu?jB)W1v*s^Iz8RUD%QbzJ74 zUzfNhiushs93na5ZE)#CiyG>&=DSgtymjc$L3fjFXNa;ra`-%hnbDKn7optR+O=|Z zUGnR-uvhY~^v*Nj=Dad3BpjwqN!oC1tEC!wa%2)meuQN}+Rm!M{%I*hcFSvg+Df9% zFF;){&D`~3xew3Ez^9_=95q2TcST^QVllXOhgO9D%rg)2#-33(Z;8OM%+lG^N~nzaB4%K#><`P9$!p5V6DkoRUD)xzrEW|lS#w#3?I;p zO$Bno)Hvc%h(z5TJRB3NJ_^bcqgJK^C^<0SQdTvhzX!E!75HxcK$`#90q+sRtggYkji$E zj;ft)(lowrvh!imv&+sj4WB4S+QH88Brv&~6WKiUnO2c6JVfhQ^lvitawsQ>-CNS_ z4C601TzPeaUbV;MukOHg#huQ5srUKo5=whNm4L@m8@DkA0Bx1#cc6%|urw85F zIM0^hGmqZ%hndDvkaF(n+AJ*+d74-rlBzZ+AyWd5Z~tq_-2DZQM z&F-2k(dj%wmKj032!c5_Q$9kG?M$=z+cNjhFY3JCE>4TJ*3B|GO4#z$>EoaWVKQ6n zzkE1@67tjZ_>`caUq(K>BoNU%x01R9>pl?tM(@_54cv zxj_^DY}#BK-g}HCX1ES^pF~zmp|d)?K6tn2y~<2|yIhG4!E}7B3#PnuYrOBP?6@U~ z4@af%DMd-#N8MFMXcK%Z%a*mVDAm9AODx4>xQsFf&w&5HM}Nae|Jx~qz1WIuvk^xH z7B4MnLEJ3H4bSxC#C5D^3miCJqAZC6sQxKwsOn3j^;}X2>>7_JFVn$X;WGV40ZoQc zHkOXwtc^7Z`eQIoGV+IZ4{GL8PYU3!auQS|>|ad9*!4;FN^sAgAxYXJ(Ux?sjLu$%P^ z{GdvBDRQ^dc{@;mFsX21_6+3NJp=yHe=QFpm*f~sc=Gx9ctQ8qav%U_{Ev!7|5gfh z^}j{45{#f9*<_S4&rSr2-t z9G{X}j;xS&t`laehGw4=5@{SW#{Nc$Qd?HrG&?tIoxYxgOlMby%-5~wsb^r7Gn*I9 zL!VKL1M|PN?G?r&s?n)XTeDUm09qOqa#gMA-FJ8Qgx_4V+kOVJGb{~MF_CSoB}T;q zgVZ?yLOC^Z>;Y>x*{=tk5a$mYuML;2V%bV<@z@TySsXanBfg@4)(nQlyrLi~5l#&d z=odJ^M2QTg`qXsC{R!BX_ZUFndtfM@Z+%%=`g)tDvr&pv^Mi^s;q?{86scAZn`B4u z77P_vsyunRbJuvOh}^g`nk2UL_SjdmME;Og-WNW+l9s`kaE%I8ZMOJjY+O=cN9NA(sC>th08xYn_N%8Iknhp2nyN1xtjpdh;9EaV+~Tw}A*OqN=5YR<=kM`eRhg)jB> z-WFLKmw_pfs&37M+Zm`Ato-?1)9O8o63Tw4&1a%F?2PJnQx$Ng?}G+~f8K|x{!EZa zH>%@)8&Ib&6I)k&ljkznM~c4Qn4UxCvrD1{;XQ&!SC+={N~sl?&DtVU{i|Xyz+UWa zX>b9^Ik%wb4gUBLAuENna|hEI2eR$jCfr>4oSOBET@m-ttDX0sXA7sV5t&Yocj5)! zv6T#(UtD13?CvbX<6OpS!Kbd>9XDnY`IsdrHMK|h>6j&?n>Wb>ue2l_npPTNZDOiP0HQ@*-aGxc$-7N zAH@7^2%Tdp7Zh1!7p2Ao?# z`9tZ)FM^Xfy|0()F--viXJOMGxUMbZAOVd)lO*cMzO|&pF)8n*;IEuejjMKs-2PX#)_R)vErEHQlZp`vNVWx&*0uVcDHHmfW z!BVUop>w#EoD70eJd8NE()59>VignnT4@(mpFlLGpl?iu7)?+~j9 zMPU;WU_*RB1)RgxdJOta!RwhrRD+Pupnn(+eO$x@DdkLfipj6N~s&fftEFwo-ZdT6=$GV<8lH! zc;<|rcJe4souQvHCGmBh+lhhI`!UhG?BIS*pl7yvD~nU6lztm3-D)WO%bwtFazC(k z-AmI{OS=87A9^h+))k&!=1vx2o0gQHEI_mpq||_UXNp-*@6z%NU?^`ZHclNg-UQ@v zlfB_SNy>JF0$h~|XrqCU0MFUg3p-tyyV?(Hm5nhM@BjkEcF-2;PU4|$`@=AC1LpZF z`qE)X=TfvmK{LW%-Mpg;_d>DYjs$Ex|J~b-mGG~>&Vx4quEjD zr*4<70r#;OVxnkZANY$TFRqJIc5Cca2QcM(3Bb zzhWL1gJ>(#7Y)-&oH+4kCx=P)>l9+~40Z`gt}ETu6-(V;CQs%xKQI_Uj+YY*&%jH_ zp1Dz3($pM1HOt^dU>|fVnZH-qA{?5$w2GoiLBYVrU+oL>m5h|ti%~~L zs;cfLr6-CB$eX#K{@{7zJMj<{Ki)Ho-^Os@lBNSnkz^T3*v<(Ct46QE!zL=hvHq+W zSrKGiT2c5^i!B$)-Sd9PiH{ zrl608V8mgYvQ3jV%{rX~QbL4JmF|iPJm`3094LB{ zLmYNmWZoy~YHwR_8p~M1=5$KJ{&LZ__c-)BmaLjZi8QinP^Jg!VFTi|Ve<%r2M7m1 zpe*}5qABxCbMBF>x#+jTYi$u!`7?+4$US5EV~ZCkHeXP(}gmmUnkkO0(toR%I#hb3DJ*o%(2p z75OUy02&F_tn{+v!fbbYOi4+WZnyM_m$xOk4C<=s*#v7AWvy!Nc>2g ztSB6g>hB3X^ilf(sWY>j9&+3W?8?5&0{`6sm{KQKgN`AHO}LTwFN7 zk5ylmUFlOH{L4~RQMAY1!YB8)my?0~9{)>=popvDfjeowL)m|ln*Uuh5)&OMkonMF zm;PsTn-=vKwzCJGX1utHt~tD+V@?t;jIJ!R)Cy7Avv*}tu}|I&Y4+(9Y|D3BXHSO^I^`Kb1O@EHiyf3SwOr6;fJKcszp zbUH8kKly70Q-#-9O0yQQ_t28^e`iAyuC)AWJ#YTgZsqr_fpz0pMv{VWG>(RrbV9y% zvw`?XWp_!wzdXyUHM6<#L#)|qu=B%fYsR0qSwV@K)ae|Ox%d_25<6Ff&fYKt2Rhh-@E{K&NIj*0$k6&HAdzB&jVzP)s-W?J^M5W&z6J!=4 zh5`(}TUOfOXhjrqWo4M6D=G=v^2aV*-Jj)=(1^c>&*GhxIdR02WQ0OJ(44=_lkIcn zt#MPDx?Yi2YFlt&x^BvK&hnQ<8|(Yr94|ig;tpVg!{;MEn77KhhF2NV45F7p1XW8r zIKbuB=`V_ryy#<1dL67OT>uj-b+TSp+qGmv2AbZA-&p;&e;k``LmK*~NT^Mw{8K&0 zTF^j0kORNb;E!K$;K_sJQq#|pO_pr~O-PFcm!$cy3WJ%GI_!01S67%w=7JVqRQ9u5 z6+DL0E~&d zdi&|k_=`Ajm88zNC|a1Bb%OPs$3VxUJ|hwvSmy4X?;c%YvB}?{U4M&y{p~X>kI}*OQycA5 z7`<)8;iF#Q+-rz08?Gn{hr7dbe^X?$+5W-qaIczjmgzWZwb~Knt$zE~Xq8d7g~Hg1 zZxh#6nf#!c$kaezPw#bGc<#*2Yq>Wv3KaRPHEaWm$`SXNNgmd#FJ(gAkG^UO?=c|bnMHReOhE&x} zBaYDBvYf=2ltQ8}vss7@4CEHeQ7~Jl?H?+&y}Tdh^2`OqW5J%WB&b2`l1S&|TCLO6 ztqoI0w@bPPD+Y|opU7KN-lK${#$HaP&RuT_a7>of=*yfNjumY<9sSDIIi^e_=bm%1 zw3)L7OF%V;%roS~WB86h7>$}IkrxL0ZH6f-& zGz$zd#7qb}_-)9yd)pr!JES^LwzhGMcwvKBmk3~T90c>WkVhvUoLtP-MXpkHcj~9A zPBeE@PIF5v)xkczi+s05)!}ZC5kWr#z5H=wjioI*6w@2CFPj%|yL~Pq3sYVU#yZfr z#onm@h{HhpS*ka;8E-YsW`Dk z1@Jq{Cm$cLpMlw;e=FjT1{}?w4j^c^(W5N~?XC6`ByRCgz3gAI|8Lu&6029oINqDD zR9*TW!bQ6W>UsPgFeKseR4sB?7`P|?q0BL!N-c2rw|w!X`mgTG0%U3NDWwk{*d+_Z z8xq7tj(LtQv8R2$F0;AlaUb-TM_rss^(2M5sBF~Ww33CqUa$ueHSd((zT1_~%3meV z1yp0Y?>SjzQTY{PU1SNOHs#Hc2aqUb`a#q=?t@%LI%g{%nk#H>dG=Aybfd(YvM{OS zJD|qAHwpLb^hcFXF~$z~J>(KOjGEYQ@}FkMa2;;}d_30?W=iV@zW z>!JLxWdG3ZCcL%@`!0?pi_&muK|F1Y16%+d08iilyC!6|f!=T3q2zy|$e`JG%h#>g zJOgCANBbE*$f@JlzWQ z`1VVqUClDXIW6m<;CDcUd3HBqii<+^F7mQVAO_IxNTWnni7!>#4fBbF(!I`JC zhdrnnb^qTpf0-WyRmI;kMZX&>h*Xm2&sOum`Eylh0i$at2t!Q%42W}aN!Yq!V?F~y ze|h@5&@pzF>sL>EHTWA=F*W{7rHwPJqk_(NqP?gQLOT+)jBDm}7r)GCA{4z;1Iv|f zB{e&zsv8kxX;#4n^we>mWP~F3q-)`WSUZq52(OP{nYYB7uQ=fj`TS%o6yG$VK;5(y z>yxY7%~O_e@wxF^k`KuKGIi8mf9qV*NtV*2#kzl%aokNh+PX4d&v#Az3lItdG`#Lz zf83$cX07V`2o7wA)ofGa3bIm!Ady4^6{|GU1&ht#J1oKYVD9=g#t5OU;ENj3L0%XT zZB~c~t{x*eW<;V%9gEszJ852)KA>0WNggvq`Ar7lCw~$9*}ASvrB!z{)OfiQhY{WE z5A5<}^EYMdXT2#z;ML;#Ogtk_=;3C84^B#%ErEjp7Z~zv2+{8Qg|hZL*nRqF7czwD zX1wOaZ~en~L7}0cNzvfBo<)lpt$6A*^2TrVRHG;#z8lM|%6v->4N~Ui9i{qdJL>4L zb4knOMB-A$$SO`9&Cy?6eTUIk_>)%tlESBXY+|YU%YIQ*W~vynm;F#8h9<*=3e`>K z$0ggjbT&Q4JOfN=+Klr$ydUj9bzowd-6nRU^+hoEwJ)U7n)UOvR0*sXyiT+%ECvYG zFh6yNHeAY=?hTg?3U=DJwxwBvsisrb)jgLTR3A5WZ}PBY)*HZ^Ds4QolRZgeA4FE{ zwG1nejYB_wIit<%P@Un&dj{5DPN%EjePmuaB#c+A(nz<|M0E)pG(hVyKjW*I6=tc+ zSByS6eUX`pEP?2=byuj1uBk2vPY41LP{*#xJ_Cr2O_)R%$L~>IfT;$XjF@7|ozjJr zc|n}R%7}~m8z2)uA16i`5LS6?tr0Wlq8BAeWa8DBbSVx~BU$*b&u+@KZQQr&DJhb> zteEud)t!7v6 zYVcUG!nEvP45wuY3yr~NHU|pswd!3*e4nOM(BkJO>oEHYYn8W%!+%VNRi_JxfME!o z%e$f!0f|Ab4izUC8RSlwb5pssL?Da1TqgFsLIESeR7?D-u9t`gmD`gsED&8qQZiyT!^d0rBT=5B@$(xn3mPwpY>K@F3}sTU^`JH za`1!aBYQ(HuIQB&{7mCR4ut%bi#gHgSJ)&iRDY$9gx5D4FQub}KpBKc!P`v!4C#?e zTvjOO;6SDD)a+)D8*PB2E+^m}ghkybtUnuV%xo61Y0W%2t$m2cITH^NI&J4@Rb-^Cvy|~0)+XX#1*35D zr;)XJ`A9Yic1zfQ^enn3@hrZ4F^DQ98!^aDse)4GsX1tH!Pepho$s{%%Ps(KQ$g3l z+L6bRSCSzqw1GbSP3D>h^=%ns^$;}+yAoFx!B#U=!G4%uR5+#gJb8L~AVZu$$_lil zM}le_>a&P#wt12fH?>1FmS({7;@SXNQN9V796!pvd=)N!Jt_w}?Aw}g4g;1pa+S9h zFRCxLw&PJz2PTp{#;e6v4Ohm2W`FE6HcW{f{4@eHG4e!c7`KG7I_qbsY%L#FX@ z@0BflT7HG@LFBQ;t3*n|A$D`JFh>}AKi0JyF2_1fBeaD*Hb!4Jc8b0=swkcyRv27S zeNtDS+iG9q|5KS;8q_i-DZH!FP@l$oQYw>Y)Kc~KcBK3nc+a2k^F;v) zjyiQ7Zyt5hw}$FE*1*WM9E>jPpT84W5UwEQX}>$xoc#iW_i(xqkp11uXZP7`3f{^6 zCQX!PDFl%2UqKu?uAG-E3wQDGP@KTQpMXKi#%Dn58MvN&2ChKr8r+=+Kc3n|p2BQx z{|>D%|BJs@k@OWaPBw}kV;$#|iu`UX9}>xc!l~)>N4{v_-IEV3By<6K6j%S>@)wkl zFbBxy;2#atOKSb~NiZ^S7aaJ5Du{7Xv*V9^!oM2*M{Sz($FkI5r7BLS6+h!g_5F(z z4}~^&54n9;69rjI$XV~(Aak96Jt=ZUsjdP~vzl9efM2J#Vo)%((40&@3`)4$3HYq+ z(re$3C5haN6((s|QNfDii|m1m8KPLHq2|R`cJ-)5j>esU+h98>rAiyWR*)%nL!6r7 zArwXXvfSXOlUhrAgtsbXG+$^j2Ak8X*Ei#_zwX$%5nw2^EhKFM9MvW^s3y4HLEZt! zW~pl4JK#kDFq9L$rYpOz#dP@~3~g4k$@_!Z+ZT_Y?k>uMs(&o%-_jNBCODm2!CL)n zHowB1Rh8l4y`A8)o|BKBr+~b$tZY79Mp;sR&8E(CEh6O`9JkFPMNzA-MJWx7&^IL_ z7%4Rmlj{kMABjsayQ-;(hH*=+J-c~t^HG9vj$;s3pU^_rEk{ZM6guC^)aL{G@MO*#t;ik~ z-_|_rhqdBX7Z7`@v(9A@;>{6#{|$5Hj%?GW75FIa<4*14!s-HO22b+zmSeTemJTNN zT{nMiT|9ZiC}PH)Hl5Y4q*TLELXxc%m>lwqJcgo)V<#rgVnZcWrmfg1g|01lOIqt2 z7$AT_Jo>ktjpDZ`tbgD)|B?K@_&1hXAHsvjQbkN{+^ofYLose|x(D}aV3ZRcYe7zr z8u=&DB`k}K*EY=S4Sp>=+L#$c>!2tTMkGze9_$dQ4Z}9i z`wjn$UX>t{w;)8Xs4%ssN9zF(@3~BK;U4!#T@A0;9Wj;h50*0^SQF0jDz+?|Eum&d zoQFW?7+X2Yt9^mQACo0W`aC$)7h9>B{CKjh$|$7H+*(xY;iX|GR9yK(+{cPbFVW#XS`Dj=~npmUFyZ%o#1> z%KgoTI^3O>UFXFh^kzETgLjhpWjQ^7OD9VEQm+rJN?+RAaadpY3LADk=~igCJ@m3m;%a&A^Lodq6<^ovmQ>c2T^68FIJAdH!}+`8;Xp#LDnf{v>?>t z>uxeMz!N9_kO8_!T5s2fa0z?2LqT}yya}@IXx!-Yyw8Df(NF-yMNcCU9^%pCFmCE;f`S&l% zD~LZ{+d$5w*pM?RE*GHrWv05}mvl>>SfkQJyd(tAB09` z(S>ce(YD8BkqJ3IUq$E~PY`Y+H@S*b$?Oi~cD{VTEsbf|uUk99U#lnJvu}+r@)f z?Phi{2L{fhtwb{mRH#KcFl!eXJBKEtzpRBHsuI=)PwKWt?2?QUD44}Ze{O57Csv%sv$!ZCmNo51#bJZZi|r?^mH9&2gjc_GcMC_OJMm&&!H&VvxESyj zLK?h>TuqNR!nCQT>Z?<*u(Y_4Z1`fj=_sq%p5i||2>5r;RxEfo^_|K#cP53&QaPrW z%uD$T&y`}qE8i?lW1Fuuwxu;svARdCW8UNO%c_50>q`@ z`BFmlq;BNpx+XkNyqk*NFt#d_1b5@WX%fVE;$+01eLn zX_63-syYyIv?{mdolMQlCJADtm;3z$@@MWr<*!>x8Bkcu!qvLfmaH)CV2=Om6OqL? zs=#rBTe8q{u3D@%(HPKO9evQ46c4!pdMajC@oS*qc4UN~*gd`7ai55xm2tt0e9# z7G&X)uD;Td9syDZgpQ!PkojR8HSzoo*Eev<3{yP2nipQeiEip?7O; z;Uw5-&@oiCxX}F6nl24%8kQJ5JM64amRB<`1qDYNi}hYy{&qh z@5fpL?Yv;wx}93+)Pm>i9AJYP*wBTIbjusS@tp|*S5U}+H4H|kiACF3!M#1MzM0 z#Gs=hzAnD6$E)vaXFco=^`$!eRB47J1YaU*E~-JZ7{h3xCF_ zrY*^aoY=`PTqBx#pHRe>QJaqu!1K}ryA+PRUHgUsY!K>O<~M2!_D?6*h`C37$Q@*9 z2wxQk;j8}krG=}uq~6q)J{;TPP%`I>i(0UjsBA#KLq9ANT@r%|mH!O_utIK1s7J8z zI+WV^kyw#e3w|P%fuOS1#mlXI>-p8p)<9vh^B6nFewIP#Y7p`(o{tbPTxw0qmF+MK z(EHX;>a3ocg3XE^yyS;@);rk938EnVd6a{i>s%7G2z>U)W3x$qbubqP3lts zSD45ugvf=%qcVmR-c4Ws%47nU7j#*GR93v&LhIahILh>Q!0&$sa{LF1;7=%qS7YW!;je()eoH8{+41ppVc+*JQ*rAnHtFK=(@Ln{sl@=Ku7%VfJsiu*)jQ6l; zGyRl9o)aY7zgButZq*jOT#y=XM5(D!Ymb@(H7*CFMbp!rn5H%{nA{1F;M&8)u3g67 z?pZ_Yy-HRj?OyrzY@rYg$1Kx77mNI7w<=whnW zQsBa#@k0+MLmVuj-zQt0I@MHVgdjHjPNjBhv*0P944TaXm_a+4<+yvRV|pZBBS!Ix zm#}LLftPS!ecCjQujmJA43&A@fGayX#sQm{a~=JQ1^Z28na!Ci@;HG1k6Sv3f91%& zqkX)GuwgZjOX%;3vi>f%hjpoYYS>|W+&g~K1)kzt*(y0Y59u8})RxP>T6aN}x&&Ji zYVFas=~65Q7(Wl{N318zXS+#J!csXC(u-bBm+VZ~+P3ZyN45~3yH?<)LUBEaX++ha z{B8{O>@J8B0Ypd=G9q@I7Xdj}p!Cp0DT4Ig1nFWRbWrIK6ltNUH0d4b9T6#^ z6M6}q1du8n1msN4nOU>WJMWtH%{TMwoA1xw``LZ%XRYVC@9VyZquUnQhcq&179ML2p(bd{m%@XyJjc5d*hCIaTdL$Y<W+4G zA>5{^=j%&rZK}XxH*q=TL$W;qH)bn4_LVA0D->4pjM#f4Q<3Svde%p39Ws>VJTvC* zOFxE-0L6X`FLuk@&a1sy5SKymrcI)D?3#in;C^Y=vbKGX8pwJ*+S1M|4uEyeWOCv! zHn}q$N?4rTt4{R>0yui-c|&Nrz;-nHUI~`ubHNQ7A3-RH42+`;hh(d35_I1l16%4~TZbVoMa~ok^D_NcY55xL_yVbv z#-BIi;jeTJ+uw?m^4rPDtXv};-QZOX!OD3v9YUfdaaoC>?sXP4(XXv(4X@KbL{?N5 z)7i<1P3ZW%K`JX8mNrSS;>PdBJ&w1epeSSnASI!fcKKN!|7rC6kE1EE{hvqr&&}79 zlQLg(d|kl>*xq;HW1RUDWKy|g(;Yi3O?VU`sxq!kYo)IQU`^QIgRfao1v2^y8DO;S>vO0s5TYw_KMgx%RaNY`^6?rshRbiFlI+ky^K_2*=%N45Tr zcCWdQhOx!6L&Wv)=p}T2X-BExkJR&mZnB~^V1&&j!&lD++kM$#DKoBAHY&Ou%7~QO zI1#=E(vIw{umQQ4%_uC6ha;>pIf2zg-z?ZB&~+v|o$zXjKH$I}o? zH&X=Ay$4eKH1ra&0CN8NZaDQ+Wb(R029=HUL!;`)ly_pWHr9a(&^36vUol&UEMs%Tq(Nhq2(LiGH#<{f(#p%F4}CLLPmXkJEOLYnaK)Z>MeOXV&MPR9B%Vpp1-fv&0cySPUO;v^2HQC?3&Vo`>&B< z`Tq^O1Fah_93B2uDtY&BV6EQYxHy1(zao?M<0$xuGf6Ek7yr*``J>}v;U+bZ^Io-j z@3pA6y`L2$avC{;Uu+lh%dJz&_-nl`XA!5yILRL#7Q~1iakxLz1)oMw(AP6qjrPRJ zzp1uw2SZHI&Zr zNY)f&M^`G?6 z>0g$*K%b%_3tBM>WWfrcTMD8ko9(+SVn&vRaR!fYSjmUx;O??!AZoU=Dg^sd3xqeX zg5`v26pj3XR#S<|%D3CN_JGI8I%)-in7eZtuZXm6fSEu6Lg0&jvgMl^FVgBlt>Ywe z$L)Qclf2R*%Gu+VT8XwvdTyESKgfU&U2YnymtQ>~o8DWAorCcbizS)&hH*<{nx`sT zkDIF+=b&2M*68Hv)`tLSx)kNUe+w%68I7rPLVxAM3V4Cyqt4IPycZc%Zbp=zl8i+o zr-GQ(L1w3>;vPIoJn9YRp;zs-o|!nejGgm2U&8oI4Au0U@4OTCylus+Wt8c8P9nPv zOLq<{(qV%&SZ&!{mhSg@y#YyI{`7)}l~@u#thK%H?9N2Vw^QY9CXR!gWJk_uqm{%d zXIFNuIRG$JOBlddDlZKChj{xIj%daha7NTrolz4}puaN{{wXANJ0lB&%Lt*WdpL$X zy1c93eM%k_F-l;9E>~IXZ?rG^r@33*jaZct#P(Uv_}+s}rh0aIK)zqz0Rr0_RoIU3 zM2^F4lgEe$zu`ParP~5{0Jm1*9qvVvApqHvt924QaN{rQEzobZEj58^{1Zc+U~f(b zf%eCINwa-y0_Bv%-b+Vy`16ffwV>^tOo@Znqt4lx>{=pbW&9*KpKKN6`7?RjG8uO) z<`C$b_JxIg>9$|QTiN( z*XL!GJfWty^u4KmyVttTq%C}zGxr`2bLQ9B=gU&vz0uJ{F#wK1%^E^|eKs2AwnKjK z>xrP4dhjcQ62E!k$RUxRLSLkkngU)^uxSZ=Q z5b%7dp5IGY6fq|K6Pf}!$SF)+dDohRGI!pON8LY6A$)_#dV*)W;VY0^fwTy1tT?Bz zGT8pt$S>`*=_r4fulq-5qnpTe>y$ms_iXL&kY4ih7AXR={?>>C7AARxqq(Dk>Sy$` z8?W}N;-syanwn~-sX0|TxJYKE8$A}$Jy;f9rI@H6rO}_5I`u~ni=Xmq@GnoV4IXr> z_6Tk_L~AyztCA^3PWa!`%-^WO87sJW&vfbV`xVuiMF*$H%Q)O2Jo(LNYr$?clf!C1r-4}# ziEE@iS2R+!(`&Sg6xZ1O2)4~@ZfZB=ck@NDeU8!kdv{(QPCJ^X(1H52;-JY4fY(WG zX?X6S?0FZ%PkWEHdG1oe`6KFT=SKxSPHW*<4T8s^?6~V2YpCJ%jt0c9{T z`L#*J2us*XN_Kj+s9ORc>Xi5uuzjgeQrLT1Gjy=)nD&s=>>B$X%ha%FQ_4px@jGTp zkEsce%OzW2`l||7A|TpnD;IU7GHxYiFyMC1WF|J%>Hr_gsiJZdTayuS#qc%Y>LCu_ zH@i%fBE-x@cvwTVzWb&J6#FdbJFz%3i`G>%me=@>=$_AY@QRIJ()84a!vnp}_7+Sf z<0iQ5jhSL;eh8O#Y4_mw@@9Hmyb&y&Ej{-Vy&*yEz=gfSKmgz>;Kvm)_N<7PaZp%w zTw@kHe}5N={Dx`{Y)pGHmuO$0PLug5i;^-T^OGOR;LRTaynX;$UCQCoHu*tNbZ+A7 zSXlg7%;0C@pft4-?U1BmZWD#lPasfl+<;a=ueBK9LL{F{Xh#y#+oSV{x_bZ$5EAPP z@-AAv9OGq^bcN>8Vl>u3!5Oa+a_9#{Ux9ygYan;7f2aC`MO8Kgng6STXxa8BPFF~< zu^jV%6fnz{2oOqPyC5Qg8!=*XzlbR0I2W4jglt9muciF;)h;44i-;m-55!#l2~DaJ zlz)H!rTy1Zi}c@bSa4uXte*b~SL*l@VKSt@-oLE?EiVHOh=5}ee2VBT@F(J_m;Tpt zS^pn@IuPOe?(GlrwZM)&RYZ%G(YeF%Ua;wVExu+Dpt zn3Py(!TThLf6=spJ1T_l$}^#z9rIR}XxRP{R)fz@=+?}Wopkk$y#&e}p6`x#;7AQ* zcK}5YToV+pgr1p|?xp3wtLs*=@LhWM=FXr3ApqjK6|sBzYJZ}QF(ZiysuC;J+pnVv za?Xt*ljP681Zt}-HLbtBacmoO*Jy-gCB!n5B*l^|5uW;cC)M3fh;dr8X=}nHv=^Nd zbEPF1w!&BAuWdFM-Cb|pk;qzTpEO81E(D{cmF|iV)2+r}mR*He4J9d$ zO%tt6tpOKT7|JKCY1dRs@a38Ad)nKL(I<8H<>K&pEn;& z#h9>$%-UsUEm&-fs0%{WyyS!Q5}%8Nh6Kf*n5LfmkZ!>~Zm9Kpq$ZwRCw);%v&9aB z@{su8s7U&d62M%u+6l|1rd!Ii8DiUU!pug2*I3*y6bp((P8&z)m`i?snz4$OSf<*) zx)7X642aSZle8WB&BLB_waHo={ru^o(eyJFwJl;xBJTAbeBFam&pn4-F8b_@@1i7D zL>@SFZ1u45#x<}9U1D`7^20lhPi{ABO)VrD?zcZ+rkkm!?4XPU2P;283DGpaa!&L1 zb@{l%pT6P!_U7ESJ{KVMk zrPXRV@!AYDklZon!UF=gbA+J-(YKYbH>E!@LCsG{+s?lMF1!{_5NL=9x-boh^e&3? z$-^-_+9i$bGL8vHX&cYl2I1(Uk$P)W_PGH0d6qP~$fwt1L>V7$^+vv@8psFWSAR8n z0ynP5+)#Vqwz}p~#>|aQtNP5Nt-081y5T-iD)$bd{n>*-THh%9itZ}iOrmyb{6Qq8 zySDgy{6f+XQ+5Yv$2Ndp?zzL<+Zh=0H$*F`bcuQt`(LV)%;i)U23E^EL>At zfr@lMVpDIY!hm4U0bNbT=_ehEj(+SEp^e}7NzakFRdsU0Kb4wD@20djM($Pq&LW@7 zVpn4pNsu+=N&)~7eOIyIn5NO|;^Ac-d!@N!t}_C?Ppjh_J8eRYFhU1h|VSzwGj-q$D1N||a{CBFZe_$?qkPQ2IOb-jD7 zU^$QVZXKoa2mU}YrXj&w^b|Me2{y+A%4`t`vx0LD9E!SjRS!pf0_fOji_8S$<76B+ z1iG__J;^x_mXq$Svs>mVkvc!)zd$1K8FJob>N=X_=4k?p^^MWS=`bcQJNB~ai)PC| z0JXq?qfHCMb5lPHC!*mNp4H?L!0Kl_BrkP8B38`r)Z*Goex=4}eh*mMH zwWhIjp9Fcf4hV+v&Az+e`cX?|Rg*6N)n!wgFq=LJFRcY>=bf2KWtp>+QZ`iC z2+nd+#m45bLQ^0Jd)LAcKxg}`X(msi)HKQqx1b@O#rJMm6|PCq5MH5f=mp7q_e4#&|s>bT7mBewfM-NK-kp67rEU=tNy z!17v8@nH*%q~pDW8f-GFs)*Q13{O=Y&^l>LlCe|Ob=hY6G71#2;6P25aH9m&!;HW2 zc^S_h@FZD|2G>KXK4hj0M!$pDT|YqS7&2P-AtcDY}S@?L6>WbZS)wkbW&Gu}O{E|iO>#xN;T^IR8L`mv$&u4AtsF>!oZBXd`Z!(?O zlGQnQlah-lW-IjaSWL`Gr(HMVqPLi~yjin4XM--LWtIROvu7&$+F5~`2ai#XG-B@* zm%N71#1_zU{-{?^K;);!H2dq$&)xyON95P^p131|ql#m{V;4q}WJwW^ zj&Ans!t3e_Sl~>*ie}YO*c?ERjCg5tqk}`*<#_|L=%%bgj^A*-n?4 z5ZIr#d_9T&To!BVLXT~zdM-?7iS2{En>vY6^ueyK1uuvn}z zcv>W@0}wCc2E*bNO^qMz9Y@0e!W4j^wQR!{)09b#;k2$ATLO>-bbUEY$l6P@S2Z?`Ufz_H!mdWK+A zcU!66R1yJzKQgQW8L?nIaG#EAioYM3Ssh{nq!vnoF=B*UQe8W3zI-UCY4`mgQi2e6 zgt;w9%yz9@E`A3B+43|@aGT<2a|MJu%v0}%IF0}u=m@Q36&BIu8=`_e)z#d-o|a!R z_TGtET0hLPE_haIJMv!9)md23sB}flD~{2Z_D|!dO}q0?EjS>BGF^pSdnKVGHG1~3 zbKO|z;9%ZTMb)5zR`#j?)AmTuPQ%O2acDH-MNhW*7w8Q?$eIs(NPIVw8EZCZcng2g zN|;pim|mZhwc(tfF#lxuFk;4yF3_!y6`P#ox0}z#HWqh5f9$c=~+f+dRtTa z3`(vW2TYw+wnCzP4Mf?R6nqx5$;Yk=^sozCR};X8qL3eF`SD2q>H9tRpQtbhlAR3= z2X*7b2rN0Q)0u5@{S+EAcj6q9J(4PL?^Ud8qc!h$t0X|c)V+AJ(kD3c5cSHMs0y?m zZ$p?jKnmbGq*pud9ebsXR{~G562#g7AFD~~ELHLEatf9mpt|;4IZ5vAj!XZ(-%~|S zbY8zvUp}te*sH>UmS8Ud_rQv}MJV#sezqA=h8VY6a0)Ope&E*Bp^|toIdb@mf}x_; znsx3|n8sYgOtb_>Lq_DqI4ue2*q}~j-4j9C$0=TdM%{@1gf-K7uVw|Vc<&Re4!gI- z=o-}=eF2aS&dUm9Pr{7Y+9pph0qv1K-v?b&FBSJ`7q-sz!~2367jd#m(V|z#L8Kxu zbo|U$$%Cwi0?CH- zBe+S!^4?k5uQ6_C+b8StHDPk!2{lvVGh}3hc{I>=Oz;97TH`mX(cI$($}CLvJ?saD z1sN1^j#3^NUBS;UR-fN7A1XW`|Dg%Kd~o{UT-r_m;Rxb4s(@i=<9xV+CQAO9vGiXl zY5bqhNzpusSyvkUjX%>O9abfVg+7-F2)TK=+&_!B|34j5xhfUsUtRrAn!*3ZY(s+m z1JGul&#J?mWYJHD^!xQfZb^h_h5q?<+4+jxY0*KqGt7k%yBo7&kZA7!-~Jc_3hrk> zvZ#OvmrP}!jl;a_2)@@D^tZg_c0U;fV82fO-v4}|&-V9*?;ikMc&Qq*njpOTIkSXB zs{|ALaQ$IF-`9{$Ph;ZGW7=%3{s73HJUi(P*wYL6drN=q55No7YQN(7564k1>}M;A zLpLK!06le$UFXF_ji$lYePvgW`@@-Rv|{$FV38ZXY&gHou?IrG7(9NS9T78ldAfz* zPL1Z|4~oS%Ec8uvgoYo}t+QnQUrKZTqg3~Q+9nI-z(BOq+p2BHw(aT5xIW$?AHO4$ zQM@hNfQR5}J}>zfv4nb0gx%jyn!U!Rt`pE!K28K2jDS#HVb#UFr!bNgT4{)BSR;r9EZtW#%1xjiuFmb?{488<6q`VDG^{yluE9{bhFo z?D|&f0UhhO?zqD3Xt1rvC*3Mkx{i literal 0 HcmV?d00001 diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/PR0.png b/Firmware_1.26b/Documentation/How To Contribute Pictures/PR0.png new file mode 100644 index 0000000000000000000000000000000000000000..e3ae792c2d9a5b2d476411387c099d82c6f23b3d GIT binary patch literal 46931 zcmd43d0bL!_cm^t+0kP*I5aqPo=$05>S@p%sXS(7YUY%pf;kUprs52lnU$%X$~iSP zwN%6jNKvt@sGLPbL8Kya03<~~Mc~Cc=XrX+?{9iPzdzpZAAbD6X5V}7`(F22*LAJ6 z_T5W%){64G<)x&g6wjag^RkqbOplb5blK)jl5b>6oxe%`ZHT;VeMYLTPkmPMVPn8) z+tX4~4Ot3n-m;R%6w(!^W2UQ|Hc|*>UdN=JUUA-Tuoa>E8x^%e6C^eWo8Z zr14A0A6wFoZNWRFxozo2HhoRF6`}m?*Qc9xj2z1D@4awoZ&{xJ14>}qbE}|9)veXo zYAk<#IsqZ~g2ZnMrGNkdnHwa0a~T`m-68c*%rFb;kZ?AY*)aN#5LF@(J8_ z|D-|5+CmUIaU=lZ7=Toqwga2 zmf=)tSRVP<<&Yj3xJT-2<=5pv>$qT-@g0h6fn}3V+DnT$EEWSxn~JglffE%W_`Xpy_Tobi6Ltr8iiCG!mD_M z;XD&^!t@&o+2a8=RsOj_X#26XOdN`5Rr3BKuE$03fB?WMNHQGj`284M`el^scw}o$ zIi=5Zf4xWd{gDtSppbhzDd_D$yrUkwF%4uNfU5Trf4l(XWg878WaNskq;c*t_`qqd zTDCng0LHnu7^LDdhTtCf^`=FNd$rpax+ zd{P|>lHHy0mrKW4)G$cCN0((2bPjexzR}SHmpc*Uy={H@7xyER-PUeQ+^atvE$1&L zO~t$4&k~FURY>OUNMwWz=WSsP>VnZLd>w|D5DyXIZ&wy+q~bC|`t(6zWeYNqGoqa# zvms8FLTAl9R;LW~ZHChLtEI4-dz}(9e4rn$9hl1^m8kdEWk&N{Me(+d=9^1SV!BKS!kEd#8pOdPMp4qpy)N;S?%R2f z!p1RPCi~kLXlOnDAi{dtO`-&9s=-!mm9l($ELIrCW6)3yS+f zDjQYl>7l3b?Ow#ifrzsN0uerWBB55hD27p{Fce)zq`iiQP#;+k1$=U^!bF=fy15I& z_5zx^5`uAOM=%xKcoxZ7P!=a(wTAGoh!I}7{48WsruqEJ9xvgP96g2imC}t6HdrpG zH?iID4W7ITx$ydf_~85$-nYv1axw|;6oM5b&~p+SIe#)@zX3-hR)+7zrFq47lJo)i zOhSAW)yMuU;Y(+t7{jzN3SNByeU|}ha((ocQ9a;O=fB+P!8*p4qkrW|Cm9lmSRa-O zw2Z7NC3Q+h`7mRfdraGKq}dKuUeZQ-werO@G}2&uT7PhI9B&JQxm=s{Wg{Y?ps3yO zS|df-IWr_!`F>QwYS7@(s__pBP^;hSjv9pQL4>v6$NFI}ZHvKs1!z}sZl8ItTo}QC zh2ZA?B~a)!E$wxw*Z_Zru=I|8hY*xa$KsMqI?yq95tODb|7YajL*m_Zp&+!kLhpeK zpl_L*b!M?wp)YG%_%@1S4%|U7&{omD z2@wk70cccj>^_8m>$-BHC!n^Yzxc3cS8b=+hzo4$R6G?a!%J1+uoU$7^Of_eYGHeS zX_wQ&WO9bK!e$~u07(@|pT`#sLuBbRI(NK$!56~#GX(y|iut)4UfVU85Iqw~k6^Q^ zOIAX`ql`$m>-n$o<$?<07AdKx%ZuuHo>xY3BGy3TKIa(l=nQfGR@6J@XQYO?z)>wb zhgu(JeJy`5s5aG&l1W*3{3|&+^7q&H=(RHQ(I(!}aFRL}ngy&oyE8;qzu6D#qa^E( z`aPf+c`nhzVe9PO60FW%b}(j_!%VtNlyZluaFpPG2xVaXO55aJF>h)%dhA3d0j~dM zSXzXEawY~Cf0?Nj)s*2axJ~FFu{o5%?Peh@=^1ayEilpa1yKvzA9m#^)xY1#X7TRmg40p+FmJo?nhSg_ zMx*_t(BtT!t}I=*ZSQ2D8jDFo_`Ou6&y~c9QHSB4Q^;n@GHOqOB!FCUic{<qlp&2-~5-v^4`0gdEx_Y}R8;f#4y?XjqPRDQ`#vs!uS-9ZC9rEz3r z`QFS<-eb>x56!%q)RyM`#`5nAkAKTKdm!uPoty72xv~%FV*QOx(B{Fi!yUou0ajo; zEk5(w`;mp*$$i>S!lyk)yfsqze{KMNMmKbtH6uQrs?=A727NlgM*_lka$V`W>5YQ( zU>CKym&NV)O5}2xIcN2>Y3y^e-(3}YSw%(2Ce9J5W4xGQq?Gs5*B0%(ju_f=0pb z6`5hXOymf9v{zxn4&U?yYN_j4<`Ot?)+gcpCjg^?c{y`Kq$vo3-S*V8mcOB@yl$T6Kcb zQ1PlWkqH`)Bl1alF`)v!)doBe85HF))t{{J6ds*H7Mr7I3sfc-a?`452mWCmOSdvYO<6GkC+)aWDSe*as7)L+p$VD@12*zu-1{_7Z z4-#*|qRopiRm8gXYcuJa6ARXp)fr6;&@A!S}x_U`oWpl08^W;CAd8r@X zly!P+8Ln-A>MS)rF+tRpszYVt10kRur<4Pd==P-pk!9d+zTv!&WdDpM7)kxJKvKvl3u< zt4ybQm&&R@`XY3rztnFV{r6hy+$$?^D8=b_`dWiGZCyu?|L1>H016+=b$Jq4!c3gl zQsMY;wK%#qw$sa=eWIqAX*Ot5e1U!6%_?hZOfTVRyR}O5mX1&m4vQb1XdZN-G`~f! z2{}-MBIhR9!X3!?%ANL{NsT(#%9~t>fCVf|3T-}7hzqrEFT4n!LmH7h?X@x8j5utJ z@TvKde>`6;3rO|Xpotp;hR$<|3?8>=533R<>S%vtcYe+dTa%1`DlbghaKKdh*p030 zu)J4amcA!+YA&5s7eF{4u`Ta~`UutmJTc+JH(Q8Im`<{drFtc-olf|wHrShDKQ<}a z?cMlSXW}=q!xa%wF#jr6n49hbf$+X}(nfkm<;`NjUlJ)^vk75A1dJzL1t*esw{5xwb>C*=6 zRRZQHrH#m@U`E~qKHswA+xW4nfRb3Zz$>TGvWAl?=`-Vwjo zZJvv)ZT92Cx;w7XjG-QF8OZUP54AH-z0mp)ci(^~QCFKMov^xFrq6>#b3UGU!tu+TV_fDNR9`S)HC>!0gfaD=tEAc?5s1RN&`n_FBM~=4FZM zy3v5I7Nr~gpYGb+BX#DTv4NHkzT_B{qzWgg>Yewvc0I7g#hB7p6qBr>^27*gm)CMQ ze!}`42C%#!YnXJgMCR*xj>PwnOYsOFdM~d(V*58~&Z{(L&IqVEVCdF01NmZtDNfBE z=j}y0gzzh49cJ9EWXv0dq4#t+#L2!mv+#IC>Dg~9Pt8ej4Jb;<@7_j8Wmx-=1t5RZ zwSQ0&U1?0s8OuokvGUfVE_=bEPZ##vXOniej8oH^THlv4~ zzS|6p+L!FcowsK(Vq(S%xI$j)v3&}2QxL%F|!5cJoWO@nybLkil;{CxX@-7q`;QRZiL~FzyrlG1EQ68zLXSdVAdH%B$OyGJ7_6E=6jem*>Nq6HfZ-U z*Tf@}_Gat`-|HT7B~3`^B)Dn1*WUd;fp!;|HzHj$Iv~{fRuW?m-dpi3b!Bj=7;CS_ zDtmmBmdmo9ZNDckONW5;ai9X^sX5fDOOVjHT}B)z(^0n=_@JDgI*Y?K9T2yH_VGPvC&~*uk$t1948<}1%e4d z6sbJ{JcC%`SXvW-uCnwEBU|$}+`10}TZHAHP@Z7x+w`Id7uDVN1?^*ftLLHw`;I~8 znfZn&76E@kCH$XqcIKYtk2o z!6lu;RR~gnYB-feMMT;a_QoJ4wJiGet~@vlk0T!z%%n{$T*Nq*ebNdKc$H|%DGyo} z56nVGpG3t+9X?i7^!Os+i&LR{fknUFok|TAmbJk3ie07k7kuO`jX087VIjH`WC71C zdMfnK45z2MULmh&Ym>7um@$8tN7f%LSziKS*>e6A@!Y)?D6z?5c}bdciO5(qS^lI5 z?J}CYBfaR7u=Jocni>i+`Gm3ysQ#A$Zpo@JiDns*er?4pbs-%g{7VM<4cz>hs8#RR zCF_rSi>+b~wpX{vcyW(f_w=F|EqoZwCL{R+%xrK-~7 z?qQ#A8bcFz|4YoIamuBVT9YnuGEY+aGNhRYtpkPj}=bB}weqL%lF?4{7u;dEup-%;d|#n&-CP+$ZwInb+X z+Oe;%DZc{0kP97M`x=2|m7gpCjd!Y#BUdA`m@!{I0gSuc++&l>fT{SpQo*_u z?nnFR@gokgUOCXFzML})+D7J&Lybs$KzQrR;b^Rx0U#iz2s6~NHJtv`JW_nYG;B=O zKb84nkd^z$=b&>&=h{$`VS?rMF(ElklN{`5=m!r@FR15!$z@e?Q+RxR(Z`3U8>wh5 z^QEj0I^*(h3dIqDH);nr(x*GT47c-Z#KYl6LZLm)ZJ$z)CoeVX83Z?{(BmNd!a(~0 zvrtCH1|=<_DJ=E-XOOKyO3?Avm8xgn#zijf?AXFMA(Ro*%?qzLRLjE}jv**vtE$*| z_Z5q)TJ2*l;cP8Zm>3E)*Ij8Or*ewO318shML^9rS^20@^en7Z*h_LXVUt(|=vVYu z@_3s!R`H!+S91|VZxmlRx&Fo34R1Bk_2<__M;$Xi!$>z67&~n&`r!YhzA@nqo$!R+u$*@7iC1K!;ch z{toS`()M_8CeG<38J>AN6T@8oa>HxN_)O_>oOH5rb-;Yb%VAk}?y3)etZ_)nBR!Pp zQ-|Yj5WJq61cTB#{8;!tjDFkWiC!1=d$`3D*wbW_S#=jz>V#KV*9G$>TBssS)wp3Vz(7oFLmTS zI(u+QA-o|>)+zOCmt6xo<2;{kh`*)UU%s&*R|rHM!+vW=P5l&Czck0Wusn`}`PI|WjQ>#QSq^4n?rRo(YBouG z9L{f@wIry9-5hN0u%AKr} zi(L)9K=c;Vq*(27Hx2+2*$?Q-ye}s-8M267R5!Ir=D&$EglD!I)+lf<7Sihe&^%yJ zQ`1}rv7q-4t-L5mj(b%L#?&rG+hHQr^qLgxOe;h4mt$42btG8s?3`y~+9=?iU12VB z-=4gH;+*?=o>&`b95_>}yUiFnuPzIPo80@(2(s5~e~I~EC(X(EcEc_I+b%gm9SRyh ze%)C*a<=0U6FyCPVM*`+7pqX}RPv?|8AxE|RU`JY@2Pr;l8f{FXTe-{ZjtqY$Gf_^ zj+=B{kb8Gw)2zFHWED2#w)m+0qYs@|axtD;WhYjpo6gMqLQtzBr;ipD-I||EUePi2 zuH-e1Rpz9Qe>}BXh4%y>Bb>&m>UmuaDA{V8m1Ujs;D}Au35{PbG7@KgHI0ECP5S)h zEp#5AnOUV}%(~}Wz>gJn*6NWXkHahN_GZ?XSM_4hu`BjK@{?I;bIx6-P4s=tTM9YO z9$Fb!OV=sYez@c7j9^%UZjbH6famFwxS9OccS*hN*P$+E3 zvKB|m+lD{4fo^k(`k-kIhc*_SfHxE+d4M(LQ`YI4WZqwF&!e33l7D)1ESy|tpSu#M z>`q8-dl>T2z5yNWY1w`DH`MVNVtuml(W#?A;)!9|#QFrpkQxauB?HHE)wXxdi3M>DN7a6zxJZ`V90YT z0poWa`x?WzO}b& zc=%!^#1gLl@DVOch=w2pD+j^8>v(&&e9xCO|KASFAg0bVS;Qz?IrKgspza1Y?lX|t z9CXqk{Y;ZW&n>^FT-C!K%JBKWY3;EewDxFO=V3jAH2Q`>#sBc)^?SLmW5Ad$Un=ZA zx>)k?0<7<~Ec=RC>(oUoly(+q&RFhQl=`0uvSg&%kb@)UPRa$A-M{J!h4_qaRvV{E zyRzu2)=8fX*8NJhhpBn}7K0Xt^#^*0J4j&OTsg*i-b2lAEi%CS7YTDe$7vP#6VwtV zydkLR(HTy~=xPJ5xrt7^0>9#{NyXF0r<$t9OZ=;pXenACFu{IHzvUm_QKF7P_}Dez zK?7a0w47aDyYq}Zw&%(1{bzsf@&jA6^wNuWY-!Va0!{5TW4-^>_HZ{t+g&-&dgghg zDp__T{mlA=?TW|^mG#>N$z|T_G>b{$S`#pcVWACkR3t>>60ndx7h6L?So2j3ygUhN zX+M-<+L|;{8wf1WqG&PQLn6yqPdd=LtvE`Z@HzSzWi&d(6f+h_!XIXp<423&FHs1_ zU4Cwq0vpq-+jlQ(-?)7)gb**>^95489^xSPyei22 zQkCu#auT*j|@l&6k`X9%0J`mOLC1<@CQ`Wtug7UMhMo0RepE+-Q%E;DZ zB}FIkB>EE{ICM;cd2jkbUj=a%eN8@eEo+doW6z1tH z={0cdhuaouD^0YrDb>EF9nC^n4l@>!a8CUAM)&$Gw-(AKBkFej8UqC6*D#Om z$Vhr4FccVrQ*6zlMUkfj#uNTwccdHXxp$>wO|*6@eD@+>!!MjP(1N{|g`OsFFVw=+ z>!Dw0Wu9T<%f9WBr8L=zx=Tagj9+`SdoBX~ZH8Q&!iD?#z0}8CBrZOxE#hfWFrgc* zHb`6kCTkcYl7&9Qt=*C4I1K)w-+&IBJnwY_xhqfTGOaU)?{-$t3OQ}@+U^4IVU{uc z^wN{QX5-a=?Iqc*g$KpmKe28s3ram)Ngz02pakhs>PaK3r%p)XEQ|gskhFjfq=B0y z+fVBvu(%%-LK$2%MV16D$#DU}Q0SB0z03$%X;G26;jGXzh_fLvZ#DYuldppi9_28v zXe7sF63YaG`ChK;Y)1QuT1=HoZm4aIseyHtu9qDlCD{!zuTaJ+{%cQ^6PnAs1hyEpE1Yf( z#>SP^4cFE1{(?F+Q@bUz=fmnj?}yI+6689UZ*vG~Zy}jH`>NSLWaW<5sOHr~eaOUK z6|Y1Uj!3-fMc`xmyp~S?UK>g3o(1k%k0Z*a23qI|Lu^Y6zh%W=nrG`*f3gg(6K6D4smvrre( zzv5rZ&UQN63khWx2vtPQ_k4-Y-ekdaayqV;X6Ra$|R4`t;!| zHiBHZ5IXTzkU)jE4!aA#*yxi(#3J@WGuv!6Pq>P}d|{cb=~Elw317}9@F_90DJRnH zoIw~UcA;Vjeehne-MT*iNJFwCHm{d&_~+hyE^%rK`fY(Yv5-xRgRjxFXb)<(B21!Y zE~!6&tI2|8DcU8gUS_u40AWf1P3j4vM97@x5nPqtU{FU=Lm?88n3^fQOk048XaLbZ zud^H{Ii(H_ea4wabm^1?zg+$pa zfH$lBk;}EJ(|DX9JVK%2HS&VE^%7zL@j!^Bwrf#|QJ5#Mn{f6K9LeDS%L8fUInT)p z*Esrb5FPS8!4A+PeK3hfap%ePo2kixDZG?xh6Xi$Kyh_r@`@TR*1W^k!71d>5??lt zxeoC*_ngW+j%`eKIXf*budhcIS=AdQjR? zM{rRfeEHsas;D;{9@1|n@Mr_vE1RqNU)J4!q!7329P~+F?S>c^ZlSK!$ECS?-R+7* zbu#O$U0g#IzjEi2WfbN7A+%|vFkwOnq%>%W=f!s||47a+D{%dP%8|eu;bK_V*M{ZjyQ zdiexsw7ek+S7fceZ}p zX0UgxS}3C9EcQz zS!<4E{8t{>;897ej%@8eCnn887w;{hwB&vemR}_K#OKEwBokRcI`UrLD6QlwWX~#1 zVCwqBPb)9lh7_G}PJG*jnHSain&|DQ*8~)tKz7#^^L{IAa=-{!P1Ep`^8P_P=cr(a zqlJ@vaG?Z2<}*A33GwICE6_2kCpSGmJ9WY!R~o6mHLnY4U6~rk*={<2%VvmwYDqMf zm{An>^(~YEjskFscTZev&~OO;Fpn7tC<&+`aNo&%k4I5wBxZWZ_M0kQ(QvxlCN%Pz z*Poy1_nj?|yz#m=bjrJCx;Q}F&Uk;23Qszl>TVo`yACpSwX>auU}~y-U%UUlg;bbp zEjZa<=Z-Pobtm+uZlXfuH?EFS5836(!&y2Ykl~;7p0pJ2Pj!@7UD=K{gCr3tBB|)$ z_gv)nEg>-lf7FbImMp;p>8(d`4OuwvpflGf5(RpOw^S#$z!618Q@hD@w2DK$gc=f9 zO(X8Aa@g9Wsr}GJ>%PKoGBzp}1~zXQe|Uf=!!dofSg!z#%6QAw>fQ;1E2~6Mcd*K>f2%!yA9db!@^0|ujr8FGMrmi_Jx`Q*k=oot z^ZhK(t)!gFUiYi%l_N7OgR?)I{TDg<`%gS)L(Z_TL0xPoBAfi^+Y?2jN#Q)|80$^! zjk*`m5pH){rK@7kps)@#2(t*)I?3#UF4m%;HGuGI32VTC1@Ps;HCmrtD+`J&@+zo| zzTLWLchO3zXT&ROp3$FPrDX_k3z#OQ6Hb4&@U+V0{4GL*+5LmQ z|JYw18|e$z852t;Q=M&XAAP`@aQU7cw15{s-Syp04=XW!3QGSx3${;QiL(NSO?-N1 z!+aB=$?Oh-3O_5s>$S`{wdPAW+^+TLi8dFnDL`iiN~7-1ammyUAHdomXTebC-bdFT zyL!KLQ&p0iNg2;OpGrTnRXTFtL+Uk)(2oP$J{n@YqP}LJ<{M*Pyf%#-7q4KnneF_^ z^eX3?co~j8$Q+Clae=eu_sR~O`DZlF@0Q>`jK8a)0XCl7nS63)v|94pbp7^F94x)_ zqQj0CKURNxa@@n;45ooiHSS;$%alEqRW`dGjeYdn*BZ^g2X#q&A~GP zhq3dMbE^nHDont7DJu{Q=v_Ps?Lkq6^TJrSdu8wH{_DuWVBYI`_W}@Hm=U|mhKmyt z=F!2sGu;zGn z)KPTwVcZHUoUmVlg3kW!zyS_7q#r2t>d9Uf$K>HSGd>I4_pooycSfV}VnJcno8f|5 z?pmjZWN7zXuAoo8gH%@sge^6&b9hyPjsEv`ljVN|8~FBu&ETtL|0#fwXk7oPYLM*h z?Gm)L?H|=g;(h=8xx_)@=e9`z#CHV@4 z4mw+ACK?DXbsoFKHG-IlhJ!CNK0FJjT^76<)M`{x7pd{??k}v>ufI6PGGx@pK|`)h z#*X{B+M9RR&CB--dhS1B)puF=MjA1jfXL-~TOdlez+#)0wdjY-`{#xt1@AIOi7^4G z^Yfb6)wvqhN8Q}9A;0d>09V(x(7-*9&h`hep6sBHw`x+@%@vLSU$x1`s_QLJpGZ<^ z99I3V5)@^8b|XFKr}C2v(Q zs#=|Pb3uA(^s61&Lwe^M5kgK29X&GH%+h5wztDwLVJ=?HMPR?EoATawv1HPcp4aMf zJ_70E%C>;TC}907lwHi&kfZqZ7SqE8uw~Ggam@tk%dAO=C4@u7x>vy*{X&-y=}7z{fi;#M_VJ?Yz*@a6_P{S)*z!+ne?6*0_xg4J89z#{&FVw< zzk7A8K9fv+_ZAxZB4JsRoY-p&y`|7N*hXj*#vBH8TSV9@lSV4m-s|iQx36S(_;m=U zK66n9ax#(4?HoWH3Wdi%P^UI5n7I3+5jMoP-+p*^oW5k&T<$v36YL2+?N--1cZe}F z<|5y{kuE7hjXtn5hBTs85>|5F^6P`&1Gl7}(~sT4a~D*{8M2-|V(HUd+|;fL{XVi| zJR&QLnktQo^c)84rXgOi>m(EA-J7+o4+NecANgp+fk%0Vcst})y(9*Ut3Md&LPC%k z?e7w<3qB;n@^vPMqI1s%Xf->*&{(EEi+3xooBm)wjxiIQuTTBF-fC+fP=@kx@JUg;$IOwY-08+ z0VcMXt{w)qEmStf6(Y}P9W%MT&+cSZ6y>`0_$hA&Lvz3B&b)o5;cid1{Hv07l0u&> z%VCirr-KSIGs4EZes+tJeJwIipzTdeNJy}i?^$R2T^3HuRjA^;RlgWpm@sS$5p=Lz@K8p_t3k3Q$x&E z3L6#xh^3D&gIwXuU0TdEK>Q?3K#mzY$R+l}MDDdJ+<7dUgfn08WeWLJ`>IUO)Z&^; z8N8F+HpU8(aj9m`yx8AW7epHzCF52Q!kN@umY{!apjbGl0R6_IK8p+{>Q65F)fTU2 ziI}fo*E%>`KKwPcR692wjfa6d8mhgGXmC476lM=^XfCDH6zI@63o=328xdxJC%pX^@5FiNdU>x zHj}pnlRVNB% zVn8I{EI1;I2jRFb@!`yx$r~ml+EPi$KUcn!yb^;;pn4^)sF*rUwOo2H{7?h1VLQ9* zOJ3myw!p=28ME!B)ke*SW)6Kjv|N2=!%G*5@FTSoxE}ZmJWB_%6?^1wh(+n3F#;g= zok+s=L)QhLp}Q?NKT5taEUsGtz^1Y<=dDiZ!-K?&NGdu_#5ZC|q#ctj$4GP>OfVQ* zpmU}Atu3NaN!*S35{KJ-Ynw(2&>Dl%(7PP+QqA0Z9V^}SFxV_ zo!p(xNg7q7a0$d~47XU*UofmrjnPOSm1xAXHF96@bH%#m9p7~$cDTjWbtu=C!HlR@ z88QdNCnALc9G>ByQV*w6ToinHEsNdedMJO!$!6iY{1cJu-AjOhRzBF%;z<58+)J}3 zQIn4bBdhR>A9VqDF{MM1)w3od?c&5kFba1y7(2g0z>O5+8V<=`MGf7)z!{Eqhkcvi zM0|3J6|IEe>H}cQXAT|?kZF>Bk<)#9AcmUIUz{Ma5{w|bK}u@w@P$=<+WhF^=qn5@ zPVZ~0-^4=OY7_B`&vm{~@9PN99=u5k9J&sof}kw}Q)ixD_^iDr&+{DgGq1BBrb->X z4zQPLY*o_rNOjjzd9QrZdA$DlY@I@rbft7283QueqPF{lxB)NDYG0`Vz2!$!zU{C# z_rtB&Za+C0H(j)R1;&vCxhz`@oXY^=In6kUHU<9@7k^QHK#l;WJWq;LqTe3hCm>a~y)34<|B6|{kcK%9vM1ax}L+}}vwNyPZ< z1v2M{?I9thxsFspM>}`)RjjcqsWQRqi~hzke%9;d*c|ty5Y*NHU|uwE1Hl}bvC%)f z)uF~pV6ESw-cFp%s0wP)>iBk9J&zl|wn~(vF>+8!fUoz$LJAHk-*En)XXxOSksWzL zsppK-aOGaOw)~56gK0VI)GMjf?}}S@1-g9E@@b-YR_n35Lk+63dW|+?J^0;no$MT~6h5i<;tCE7!E*1dWw%!+Xit$5pJ$UCu zw1fA@?8<{zUc9}Mt>_f|Hc7Oi_Qk~m&|IzjyGrr!;&MtraXOIz5i+C;w4|E^)y|>_ z-xOaR1Kr^lHqnMxR`F#YEi7E+(_vtj?t1rflm<(8IND<>+`e1qNe#-SKPA%*Uu+H& z!%*b$j~05_rgh9Vcce9M0V^Qc@r<1%EdhUS?pgR0sE@mftJ%KOGI?C7GXrfPm>TW9 z?IMQlOCEPd2^sB6Ls@B?G#vL6U{`TUZT8iFQ?2j*{@!JSDB`DT-PwMSfd5j~4N-nb zR!7#iH&@Lo_Kz)&t%ytXR!7}ajNMmLwPkmv+C-Bxh4Gy)MkK~9zd=th5VG4hMH*&>?+Plyk#JK@3z zOwz!jOXvH-t?@MwT>Pg~iTC5p#ygn+S6I*<(&PX~95&&u72kvM%3{)D_)YyUYVPjL zbC!dN*b#wIM1MxK;{)e!PA6S-qKW=l2Mib_Kh)t6U_7h2N1}d4yPa}b;ioC|M2rcO z;>HkYILom-3ddt3@faGvzuzle3%>8Cn9*G3abxJI!(4UYMnvhOC|MoU@wryek@Bt2 zA4QFrI-GMnH~RFF{E)ld=kwlYFevj>6WKFr1I+-`p^zew^=HfEQ^_9P7tkZ5Y%Qil z)vbWc?i?|97teJZ+M|h5j5&M=j)k@0pWm;HSs?D~Nv>@}}#)X7?mo z!rOmy=Krg2ew5VzCmR31K#m`IlOO!{KWz4IBL5HW`JvMNhrNCmZhnGEe^dB>>iPeB zUi>dQaSyLTMVq9}hUvAliN7U85ne!}rujnxpDRdsuS+p3%RGOw=n2=HaS|QEEJ<0f z1J%{6ClatbI{t6!{;|aWk0f>ARJ55g3|+i} zJ%Sc~237FAFxI?iEBwpB`CpPIZXaX?jIcoHfFS{_UHqnf5V|M!u)|L#uwL#z1$}!D z!J8?KdRUX<5LjeH_0O^f*I~B6x=G<{?y%RMRvOJ|MwC#HqJ@++r=A<89B;%QGq+!x zn2ZDMn8Xk@;RBj0sbM$>wIu_D;?pkZXepNSj2X2)7Xh5pjVq@)n1)_Z?fDmvSSNJd8* zvz2l%-R<$>>mfLCIy&@Ua`ZOTZ5OA-HMk_-a5J9Tk-%3a3u1?cfNn@KF@|S!&;St5 z|Faur)IRM>NnV-7p`78u(0Dxa1#U7h=ETlC%tR6r#ZSbx$qGADMqzwO(WmJzl1AfZ z>2-KVcilZ!EG$5@t)=sVO-7i;SjM8Hdkx?EvDFtRI+u&GHI?)ZK&w%ZcpXoRU!b7) zZ<`9Qhwc__F%KvKMPzEkFz*`reMsVsB)F0qk!{=bA!(A*|B2X$X69Y!L~}N8C7{Wc z?66XLq$8=sJW<>WeRtk{+Fvl292MW3QSPV_;U3$i*`DCn=5hVL(pY+OZ_SqWr5h+v zu{v!qh%afLqCg)mvhf&PS=|@ycUevp^;5ca}yXvJ*fV= zvQk})4fO2AG7f4u4QWhj!2O7P-}W>~KUUp9ympa~kz`f&D^)ET1D4;r6xL0ZL2U1O zVYLZ(4K02OwK221>OlVo3e^U)&3VZ^F~~8#XRr;sbcHr8NauZXJ=)K|RipE!4yn3b zC1=FSwBqS%x^-xG-+IqNRoI|A@`9xH0^%nHqZYS>V=2w-Z32f%T#UM}R_tq0Dcq(F zc|w>q7Bbs*S;yrH6u+ItNe+yk74?-)(d6f;vYcs2iKnI@fz6Gjv*VeQ(;d_+{Ke=0 z$dc>Jl^gPTnEO$U>=`68R*FZHRQT2bQ}%JmE8_{wd$!a=D6@`uoWd*l@b%__3AeS= zg6Ta~XE{RxIjt;9zsAtx;a!Tn)BwWpwq8cwu0X5aP4q`}avlC*bTgGU@yANH6}N|? zMqaWbvbaypcN{VGBhV~2430?pAB0QUmiWI$uO-KQoRhl%I;3NuWrXb4v^84jS#Q4m zYsqGVDHx=KQqKhd}OTMbVEWNOmS*$&2r+s{To->=&twaf7 z5OYD=h`rcgj<}H>{8|9O!0+5#oy0#1BlscSOL`rMzxE*UL|y7qOuzOHs1|5TPz(3=@08dT@XmvikD8E1=~;Xx(&grFJU(09<3gdX*m-De%ka|A_n<< zfJpRJm5R>lqyVj4pivy`cIGP_zyqu&KKdI>Q!5H|dAUE%2?+=*!9}$67UwokVu^@V zpX$V-FGG>7zBB2`_om^mhb65pWLzlVf`m%#H3%29s?~Q}R!TE3>0Zko1&s)BjqFLH z52O5>z%I)5G+J14yI4al)H!1#{WA~HOqpg)lG!Ns+5ELnT`6dxchUxlw~>14{5@%l zTkC{&c3g{7eq6Fz=K0y(?^yE6?eNDatIF(OpzBSF^rS(ri|p#=u!9C^XWY@%x4%5E z?o-%EKUDhdlTnx+s&n;3D40io>)A+iiOl9DH3=hUW`nMRHRBZqtVnoW8_!KH z*3kikz;Q=@>04)_?rH0#2b>zSdX2i{ct$-EukDQyu9L|vk^Xo(9(zz z^u)_F@sg4;;kerpQIo~de;aeOVoI-`7yfd3p>!tJL#IE~F>Bh4Pipg43U7^F?o`(Z z8j7~yxDUs6fZAd@C=X#lN25$4EuNS~pP( zgLQe90x62hL~%Es@i$bKbmI;#z@t&T$ZFO-!s`u!0HZtEXwThwwT)ZM6H1Px%NY=S zTJ()!iZ1Bi$0wPJO5?e0^~N4xs7&BnN@+RXygjNt649v+(bjy)_|vowZ{A<`aH?bJ z>7K-p3JN!m41yM>G4m60waNL!F!5UUdXMMir%>w>SVNK*fg>qpiJ#844rQZ#JC6u0 z7AMnSyJNCl+Iio=i`Wl*t5=Pao$7~Ugx80h<9qvXDE6}>#C?iAYyjU6i1cB^y@BQ1 z)i_TH1~-2eeFA+qkMA$j@L~*J3@q0PPSpJm$ok-;;bb#^9>^M82)gl1=g_5p5-SpO z@|ydQFkOXX)lfH1x>`r>4~utC7Qy<}{>`Yf`R z^-iC3EbaJo0+cvwH0BD*QtKXG$F!0cbmYe&;eHj-X4#W39PFXRSBTf0Q1R4%I#EMM zZ1+HV=?Sb-8Fm#XnCJ*^ADoXjX+P%CE^rjAQq0i@NcieP^jKZmklLDB)>uxFB;bE& zUySFF(MiHwR{nCIfLAWJO5s2zZrM!;c$&ZXHom-4GDB^>GanR3G82Pe^q0Hd}FfD z=q1OQF;HonAi@r7rgiv%4-3K+eKHlWl$a=(l51s7?oO7p!magCAsCi;iKD|i%N3D% z!x&sRZkXksJdRwC!G+>M*jMR!T_w^gF2S(f(Y`$l#GY;JkRUwJ0Xc6uP~t#`$iu9u z?(ekTcP-B=O%uZ-U`Sm-de6#CzFCD}CD8I}e9X&3N-Z1d5j8TB9)tDP)uk}Bq`jRh zM+aGXqwu27YO|iWImMpwsbUdO()21h;Hov#z>|X&Ozv^}$(C)ARjZ*FBxJ+1G=3d8 zRun}H-GweSI3gef8Q#_1bt=-iNmCJmxs2(t2<=`Bup^?=3trnzvdhXbPijdLxnVxZ zphMrv@Meri5Hvb+^w;_j)mR7X$tZmcE%+J4xnGw4d!3o>7vHEvfGJv zW6eHmjK|$W<4PJD+_1V^Z;U)__a{qGPvw#EihC*FQg}shQb`oi3rFpkzll=#uu9bE zwiWWY;a1+`IFRZaOMxr6Uym63)BN?;eSZDQKPasA|O8J)34ZR*BIB7!+$rxt&v#e`~Zco~K!;X$v1d!egqX@v@CGUCZ&;JwA2c z)K0KNY;HcU13mpesQU7FsK4+3!5cL~izR!#E0ipitXZO{RH$sjpk&EpH^#n|v{))N zq%1>rV;{@NT9L*w!c1cf*_Xj&8G|wWUWNDf^ZS#>yk4(+?>YCJ=Xu_9&h?j7D)`P( z!d@<%p+)DKI9WhRJjgxQ-T4ANx2c<-b86-tQxtZQz&fuL|E7rPc3i2z7rl(6zk@}O zDh)US)!IPh84^TKTX*ZD7$1jLvCJK}D)U`=d|bA=$Xco_bbtry!2eQ3%YlVB?EnOZ zN6M~Ju^s12)E3|zO;{f(Nvcq)EkUPO57dv9LHqN?CyloJAn|^wuC*iQHf0|J+>qR4 zM-|Ddz%xKLd{je=$VRMbJd4cZ=2t24_x&lZe~{F{HT(yz zMKOvmw&ufiimU!7NHKqdg&JG2zM>AG__dwwu&N>_G<#13`St%x0g`#miQ+ld0V~?p zD(Ch#bPa?=$Q#v)w^DM9^A9FvhJ?ZCdEJ|~akY;u&?bqq0T1v+s!E1I{=PlxDz)dp zi|)?RgC${uCR$2Ex4_e%fjZUAk3l!>wvd>v)BNpe17ilV@hdgc_iBg5zKpNWxCMO- zdx74f%FOm5610ENwnmtKT{`f()i5YHirK8A_FCO^MMs7=)5tL64MirmK^p+0r~km{iflg83p8huhO2T&K;${x=?F>@lysZHLPc!ZPM14Qpg*ik%)Qd)(UFrjH5rF>@ z=-;8j>UFjn*2STpwUD>xVqEOD#Al?7@}25kaw#=Won=3dQM@FgueXfF3^ zwb?s)5vPYa$|Xcadtob2qGydrLKDTo9q#zh%+~5z_bTK3`o*yK{+Vdfnj>@mecJ~{ z8nX;-L7Yf697zk$S5%6Ys|i)7v`(;A7+qNxgFi;Bv4C))qkk|xL`!S%F13S3uG1nL zHE`CA(|)8?=9mAEgl)__?5~;j`u|Tj^&0oD((T^I0Hby>b7kLbxkMeuLIY~8tiS^w z$mIUhVe1>mpX0!q)9mLi->3#WhH`#+P@~GjAqT|lz@dE|619w$B{E_*FNqtZYx{?t z-o;#^Sua1G0pn2k+2*p`w+~8k<>MS?D9q4r=`xq}p8q@A+}q?LtIWJ>1(nmsv5j7a zhC*d=H+zDJc0vxg5U*j#x?nQgPK&(^$37bI-vOwvo|0&&>cc#h{fCuO2bkp^#s}Mb zBlDOQO7V)qNpP08@pAH%5icbt5iAY<-)~)6yK5zn>*HeQXn9XvFA#DR{xQH*`7_AW zFa|^|Fm{z0@htLxzjF}9R=)vD-rJFMW!biUNPWF!lkX!ec(!TU__dmiZTTguv28jY> zwaZ&rU@>M?Bfi|R4)fH&V&KA<^doP1;I@i=&-zakokP=nLYf@kpV)m$`Mnf!{Eb8oS0V?<{$HSc zDpRT0*_O0-IE=hLG+Q=^i^Qqu|2Lj&vyiltOg&R*8Ix=M5sn?C^a>zpO_Tey3QjBI z4v^!Ya&z*?>xiNb*@0XDtxva7nXh?NvJWJ?52#502i$51moyVf&LW{Z{`-jtF!!{$ zt(;}m-^a-DKoK0sJGOD3a<^HC#oLtA-ycA8&d>Ev;GZdilurTb01@T1<_M~32wAtT z4oa7)J`Dl|0QIuT4}TR!lpUxTZ*XT7dlBclxhDU6M0CJDlW3LULl8AY5%>-lL@m`j8@|O(IQ5e^Uy|%F+0vo7?Am6b}ws2mX}f4 zR@Dvp4x4gd@eZ<|Q{n=2W6nWS$K3B;0HLTn5=S_wu^@rw*`mL!V{{&^-NNaVCS)=V z;SEmwpO*bnWadBDE@kP&S$TFi+Hbbht_;E&fKt1n-i^}~RwZi{4Ita$#^7(8()Fy@ z@L}urV!c%Q+30$-%1Qy>6>DTEF|HUc0BS7%~@n zinFMaCESCn4jPmZp&p*hX)rqL+ULfoA%CK6&&tRH8VQODfAu7qnYNiyC#<+?7&PCO zCd2&Bb)6Qf6;U&C2D%gpWsDtV!at=={Ty12MN?j$4jNV+lDn}*Hx6?!u3zG2PO!Q^ zJ*+-iYv&fE__Kd%p?Z3y$L>U{ZN4wr{r$H@NZN@yogWrfSq#UoOr^s~cI6)RhrrF_ z^6f+|k&v5%{Po*gtv_XYMMzsRWhz?FKwK%~<;H5)NJz?tBV{XvG9=Lf(*szk z>s|e(Lr?V<#5~Aw>+@SD$iHu4c_paKhANNHwJiU@fw{h@e$j}UnU#^3hqRvfV`Z5B zFO5EjAj@d)W|<`mjTi1TY)%)?VV8|k0|7*>*XteJ(s}OtrmaN%-0xKeQXdzOG$7dG z>y-G4Noi9{d1lNn5;9+*rGgWETADA?D%e5F9Dqj2knn{Ojmo-7Shr|oBK{f8MO={6 zoH_lzDPV*fzZKjewjx11J8O3Enq3)HG7LE5i(CwvKC4i;-b5de$z(Ye{CoV;spii- zep_PGe#!fjSoY;hSt#Vft;^(|(t5@Zu|X_Y@iX^?E1B6v+-R5dmjkPMY!EglHZ7ji zA3vfb-0Yc_Wn!`sn2_;{rMiB$&8>hB0GLBJ5Q7iH`WJM* zZyKnB+eHU(P|Xin=EEl8f*nhVW`_~P{n0DqxwRF@KCh@aVNkgFQKiiN1R7Kd0XN^H zg{D@h`8!43Y;Jj>nY{(WZ3%vm3XJ))y9F^BGhb@IxA_4(xQ^9;uux#6H7uk8`@PnW zxOKsP32P_IQy>Vmh0FCUi&##!n2nHC(pih0^5bD&f*DK6S{n#yvzXWI38TdTlBrDe zZ$pO6xdknvbz0=9UcwM|pELWGtiIPf1Fb<`2LeYK`x_>gZF&8;i~sf2`z2Q3j{j`x zV)5b}`s?5Bs|ND}6%1+X-l}h%9gC;!2BkrKf(y=2kE{bR#stK6I{aS;k|;j!^KH9XWOS2biHj4d^Aphv4f@RX#|XZGd@peC^0_lW(G0wREpFT( zkQdGmp&VZcV|0ubn1s6MOlAj9`>Xk>`ug_uPYu`I0IAwdC6AY;Bb_j|1t+k59M9N5 zCj9K@q?H*y*S8$3t6}!%atqR63ur?Zv5t(QIMig*-jvn2LF3s@slZ330S(g-uUkV~ z*&#hr19BQo@nPSynKzg>*U9CgV>9oIn7+!i0ona69Ei&}Tj8kZR7ok({YD&6Erx&k zc@;i>8cEg8h+(#(S+4UeGDzdMr7~+PHZDXtf~2*1-?KEg_xXn74P&lp??-X0)#<7y z*!zhcFCtkzrs;}NDS$q|)p~dHT4`uEV=G;9>X1R^ zh6k%y(ixJ{G!DSy`lwzL|HE>F=i8gsbVDEC+#@>7|1FEH8ghQmVTeapqc*uu)y3Lx z4#P`kD34WkYI%jv*CzmNhO76qC*e1SOh_xFH z|I`vv&tJ;LJ}Nt;u^@jO03EjgCu2|nw}Y%OuG{^SFNScjx_%w}-Sw*Z6mQh90fzST z5H}5QVn@1wFonmA+Kk?>^pVW~*Lun7Q_Z!QNo?=>(nxn@?B7JVG?*e=M5ximSLBB--BYk$bXyn564 znfl)RLWN#bI{6{Fmca#>_(h-=SovKM%Dl=eEd4A-IU4D9=RZJlGHL?vp+fC<0-6~= zD$OY=Bn+8Uy9q*t(X1zN+#OjLe<~k-k0rgRFY)BSOouvmrMpoj?Mqbb{{g0yFqQ1e z>NTr0vs%{dM!^ACxxg9zCsW-3W<~SX^lH887{=Tr6SkbHR)&OZBpq_XX!Y69f&tkm zUp=3tJaR41SJY(Pt*}Lpb!~hgB#n(6J`DIHX*D0>J4cyk+Of+L5a;8-VuA3vfEJb8 z^aQzm#dIVKL4?q%lJYpK#}gBHpIq}XJbf}bdw-!ht8+dgNe?qs$7?LUn8u5xx-mN|X0JKP@S*bNz#KuU1d;1}-tgUe6{ zI_Muuz3aaFv_}}kxXzaO|AX} z@g#AVM6O5lfAG)vU?{Kn`TN!ae&-b{ZXR=SEGqKo zvOn3Lk3m#VeusZ`|41LC#YrS9YVZ;J3l;jYQV_nReZcrr;(msHsea_ZNvX|*Z zR=P(cKTpME!>uj`czTxP*Ks_`n*Vg{vYbzn6p}8=M=UD{pG8^}c)GlMX@Z#DKQ|QR zG#8DJX#-NT_USjE3d3h_{$8%l2uY*zD3D!u==&ziZhQNA?8G_0)B`qL$8tM{BH~t%eh@;@fh?qUFe>$rzq;TAh@M3H!DDyQZ8~P=&4>|ty9e)^(Cw5CkkoD z(EjGGxP0g~rh3%-7~JQ^Iq747g2xoB7oCb4@4?;_ODy`C`KO}t_h){PtR(Qhz6MqC zn5_O!ub%jztXK9oWL2js%~TmgW6hYv5~h4}f2DPC|5LJ+yC#GP?{dHIc_w`iu&zx& zcBs9#Nv;=L&H?L8&>P;*qGLv=N-f^2sQLcdb%RaKF0ebQRf$xsD6t$|?O9;{%azE( zyjuhDgxe+GFNXPL+R3FedkWh4_$KVmp+`Fv_yq(bL}b<2&zZcx$u7v%d+QKZ+xX}u znG#6$pt*?sg&1Go*&^B1^^2DB-${-FA6Sl;P#U#1$7UYfkUzUczqOyRG+ZRY2Y9ePcI;TpQ26Z{ceF;9z)L_-iPN9tZ&D39k#4P2f?uT*%! zB@^r7sB>o!K{%?V$_D$0-~E2WL=j?QW7&}{Gm2coi|GO{AusLpP+rXf}% zb@tP%3UiJCAjAg8HSX(0x?S$R`YAG+y~4c~`N6 zdB;R{*GcnTq2E1OQjw1d=Q4;6EB&;qmAio@ zvJGgvl0{T7(z;mPe;ydrFwr%Hux$PqqS}}gcTQPK79d$nJOReSe}3$|vT=2&$e~w} zFJa>_PIwiNBQY=S`_)gHI(c%f8KuLQ+!t9gMK?QAR2j47*yeA;Uo_fNPnX=+!TlUy zUIfG=L~_xo3EI3FnU21ZqRIR*+(c-VnVx+6k3yk|w!=yEB>GRopnzzq$g$Bi#7RxA ze@rd`Eh>KjdhbT}mGi~jH%#Mfc_HST*SGw>9o)8V!SN{8@BTx(DKEhksvZ>9{y4CD zkh6mir=h@_2zIf3N>!5!csAh~>n&=j( z1g^MTC$KG-$(PNzqw!WW`T)2BqgTfB1H)dkNqF$?p{hG^o$_s{2K~U^y!a75cy~Jj zN>?^>^H(iRJjU1tUN)6IT?u&$kNggAPXh8e1}$&7nD4oLq$ihzauhw&FGTp{9d8#F z)ccycIk->w7Ut8|(k+xDAV2!XI`00XDyA6moBc!gl;Jq3Z|8P~t)ZjD^gWm>RD!=i zJo`^fbm>E=-*Re~ZR>^pB2og~=VRLITh+cOv*j!sbeiXn3ss*sRiaWg0X?hz^o5^7 zavX4!>95z(GNQh4uN8X0Yo8rfj$^+Juqc0Zc>)qI_!9nODlKN_l39P_oW{RV-M{I%ZV5Tl_C;{*?5!!)1>-g zyzS@V$g&BheAnkF(~wuUs61L)lY#T}%{F%&MuT597bW(N3@7=~E;DL>&>x2#iQln> z>4!Jc4vHFy;!grR{fzqSw8Z2>G;Rdq(pM&)tOzk!qAX=eDxk(ihnvgpbFX`A2`yvq z!0J|N90yeTAaikvjWHQO)(a=lFF5?(;Td-8tLR5y3x$f+qj@4&CigwC<=lf8V^{8T zknfM!CYV$`2w@xMcEk*-Xr89}xd83a?VcaZa9GmE40=E;TCdm}bOUDS&%V<=BU@7a z`xv$ue;e&sV%{jp{~5j}k2T>bx788WzC3IOO{G4Vlemd40h}84j`O5r&74aB1wp*? zA}#?K6!40_gWBkU=O}!vHW7q$<|y5Et6-F7JGdL{X+I~Nq&hbs7WQtKy`ZNs{dA~h zXT3!QKV#eoO-;Rwb9#i~`Q{Eq@G3`$T)w<5XwceZk)64}ND;HJ%Y#>3F;>#Y^klG8 znwY9a*tv%5_?3YbeRONlWwOU~Q44f*7D*q9o=>9GZ_va41sYdu59hYr@Rdh7L;Y%! z(o1k${c$C#Ow#)3k^Wi50~H|+K?s%8uzHxp3Wvw}qRTb|rC8*Ht##L`m|A`TfKmJ7 zWk6$T%^fbGljbP1qis>|OVe51H>y4a@fs{ap2*^{N(CX0o6D#g=(W#LaCur>AAH(R zp4cC6-3dMQ%b4RifSdmq5>QKAq=B)(!IWXhLd)ys4ohfHA*gRwsP|t_`Nq)nzMxBt z^B%{$-VJeD7kl`Lg<2Ld;B9{76^@Fn6HmzqmoblY*bt~S_O>RvYN~fVa`L(sFKA;@=K->C?VCC=32{~PpS9j2p!rqY%wEsLhd?o30uvG zW(SJ;5j{5Hegm83^8LE6cFeD?&q?3esT)Nn%`JaFNY;CN+f5|uyAuNE_899@Thep7 zUlLjZ>j{!s9yqBc=Sw)`La*;;wxSCdx2H6`>V)Q5IdjBvH{q$T9?$%UcqYwitF*V= z?MU(N*wqEVWf!f`2-grXcY8VF!8r)?61jV&<=n%mYJvKV)?V4DGm+k`*ONdMIO2qS zIX%?tVBnS+tb^#id6u+xG*Gb`KJ(y=-!R1P&EpAu@8dI6R8C zqxdp9d{bKwmu@)#D*}B;$zg;C={(iT%kC2k7d!L1A!iK{NQTFcsQ$4}Re;i5a(#h^anE}Nd0YJ0zKgJjo>w`KXAT8js(U>7L>;xU6M#ePnCGHbW ztG}POqRr!FH}Z7wQEX^wMq>dIRuwzUwd#G>3O8d(!D1yKlCuBqtc*)cZT+2ymH{~osPi|j*Cq1VGE|XyBMkDlN(~O z<`+)3Sd8(>@gM6Iyl$lM}xR+phs(Ij}l5!7-L#<#--pQu+u# ze$3cIFa-I)G1aEhmp8UjyWc*aQCz>=UHPRUSeGUfa^O&Z^w0}ER7kX{nx)p=ptIg# z=a$8z>pu}f;Kc|#yF>Ga2b53S$D5gho#(4M?5QxyT`FuX!OG}a`y zTYK-Rgy#*p*jzieWC8;AdbYS8QcoB989(?KfTeArJ-dpAK<+_aO!aF zWRGF-tBq}|sh~o1>xpt=b-gopvcI3td54G{h@oB;Lm^KxYWO+~&(zrJ&udw94K2?m z<^*<4ZSlK9L%K(~A4I7WeJ%o^01HbY_!*GP{_QtxUCGFpRclc%I|E6P^v7hiv5= z734oI^8o>@m&{Y?mP&}b*GqgO7^UjZ@=~Qdg8(r^* zw5*GxgW@Q#M;k}}x&#FUqG3B`kC%r&Y%3XRh$OhLLs3n`m(l}$x5QxD!tYWCKBbTYKL3L!5R`+w2Q|E z68H7Bh~b%5OLR_47j0>kzp6bk(w4esZR?TWQHXDC|JEnA);ee3X4Q8?it{`&A(b1` z3iuku?3QGypD$L|t8v$Cgzqv!+n+SHU8gn8!po`*(}?J9pRusg^zK6Xr<&i=fjU$p zVV#XrvP|4+6!{Uzk|2IfdXI3msK>c#)0pZ%~K!0H3;4C^}b}p zrZ;f)!_6d_pyJ1_O+PWe<0iBCE^Cwg0M1S&13JskQ+2cw z-J$Sdg0Y2Tq7MTD4GU0~W@>kOZ_y^yJ7u=#ckj1;$xY8E%(SARTcZTjdzIkFt!@TO!K#7?tk{#xR9;agPS+(sv;2mRyX1Y zJx9f>88w^pPbM7hZQ}_AF2-EN)QTr`qBrBioS*7|Mv~3);E~h(@4f-oLa62Y>7`n% zTfd!iFKoS5oV30?*PUp`Q3@f)N8a`y^%=Ub9@($eg<2ayb`K5U zgRei_-tS*g3F0~+rVh`@ZEE?@V)~&hym!*Ta_X;;Gan)Lsj~9=3f01xsB2vfsW6t2 zr9tY{R?YfD?3N5Qq>#M6h1u*2zJb`Xo4`Ha-917nS7yGDIGtJ4Xi3B^c~=a|Oe8m6 z+j{=oxN))2$JS)+$@%gd>HkRcMcreN3S0dd<`+k|E%S@3GF?T~6qwf!W#Nx>UWA_n z2vgG)zjfjc=7^T$z%%tU5Bm|%Fx7#fy(}FoG(Zv(8c4cYgLd^Oubt_PSE)@`Zpxs^ zm*>j%RwOg`IdV*2stL7Z61}GU^_JLTv{-fcUk^Uhr@S9w1l`0V+rs}Ml$xIdQzZAt zHy5m1LBi}c?(Y7Zn5Ub*Df?mTmsZby$2hGO=Y)n?w6;G}11awsp}gAMA&Kj38WrNw zGQvo@DSLDgJq*v$4+$$(xgDNN13X_Rfy*;Ru=j@~$cT*XrGO zgzstsMYWl%2oZPGi&>ihMjO6 z!I6&?FiMZ=o!8`ca}a;Z9Ca{SZY?ek3VE?vejB7@yZvB9o1xB014~JDEd)4ibZw)C za368{L^sRLRE@AvHeTmGx~$9=KCy!rrDgPbzSU44w`O803%W4U%=J+r+TiB*aTbxp z>J_iM0ZI?pb)sjAFy`o5hlQ_?B7Y;HGq>gtHG>XSIp{XhIQ%;JtGjP7q7IIp9|MKI z+C`%+dDgYf&T`f;%^6TH>A&jl(~0+ZcGeMAvgoI z_Bn6G$0S*3W(IxaQzjxkeiwbYryN5#$0~pRxU*IVZlQs*o%>ZBvy30Mq$;O%&lnWfk{#`qRn@0&zcZ5yESn9Hd@~!S`5NIw8 ziYs*Q$5LjyYuP||xAzQ4Nn?TDY_HMyj_1D6@kUn> z|E~H1lU9$ijMbQnwv3u^)#2`w1#;hu9EGZ`yGZ`0u59UNTv@T!Z|n94Sqr>ApPR_V z0Hb^Mxas)Hmq!L*VDC~)guS+lH~$7-4g>IJg)in*J&G)}*yg~OOmbh5<4RQMwdZLs z*~1Cj#?T;D_Dycz4Wd_m)(y6ckHik_Q$h;76ud&W-Phsqc(4Z(%I8{57;~l07yW>W zf$%ol)BARa(?RF38dwN59%1e!UvrFAW}w5Jr5L=yD6Pz+zKy0{gU;oAtkA;Vmoy`8f5IE)(}WQl&`*1Ocx0`6I}Hj3cQ1NA|5pEo7$`+RtG1!MfxGIeWWN?H}Y~vHI@Y1(#&-`@6vgUtoE*m)3M$4U!mwwCv zdIE&}e-Za64&K+vw@2k5_#4*go%>IalFIHkf=`Z}Qj${xa(qD2|LwG}P}Mmgiz{)sdV_BSq(s_XjV~Dr{hwKv%rZ5Co`n8z zWu*ABxWb)wZCP7WYz8{565L@3n?jVGKZu2_y{Gg^Hm>fzy3N6v7EWKhecRy_)5k8x zo=*U{I`eNt4ML-e=nAqu&HMs~{`=RkUfHG@ah9y{z>#Y=YCf#v8uH^=1y=yLgB#LO z$1OOaw{*rE{Iv*9;vK0hSACalihr+FA{M@|V=H3PI_K|?-D8O*^H(JEc#6J!jvo*Q zf1mN2YhGNLUsU)B#%*3mMI0I0aSjW>@u2^0OLEet!8ufb@AAL{<%hyg`dAvvBtP`} zrguy#@0jrR5S1!@Z=ne?Uh+2pdypBlGWL-e%2W&S(sOa=!w4}i22@X)rorpx71WkU z+>1bqj6bS-*jnSHpUk(TwIcgmZh04nxeQwV)-TtyaS`dAfW*?X^y?l4&P_?!A5l6o zxih5F9M6md2Sg+~44!r|Tw1Y?|G2V8;S^4sNIt48g_&OS8MauyV9wJt6FFyxD{Npx zjf1WSZ*TR+)nQR5wLqx>$tX1b!dP_uzMe@Eey>Jc&IdY$Oi+}$*4du}S#E#rs0mLZIOc;`FOL4N7o}v{?5xUi z)?>&rMOa8zZYM+r<(tyDIWH8IN{BRECb1?kdOj{z%87bqRM9SB0T&?u{jb&6J+JV4 zFZ8Kl%ht4PYHR5z_REVQc}bUTr0fLJl?VGju6wm)*p;1CPZx+`rBS^pzhJQtz8J1u zAJx#A`b=v|7!|PWGW<}hP8Di`1k(8)=`g;+BAj*|;6l!!wP%~>+C2O8~4`4&BKVp4zagE`<`;VuI962%dyI&h#GlnYx3eBDND6}QXLd?Z zA>s{GlJ>L`MGcU-?a~ReC&0$I%mH<7Nq{*{u%4Ok3>klVy-hsj!>QR7ngnUDYdrDP zN01~W`{}Yj88M-#RPeqa4oZA}@S4(rGmXNK9S^5lzDnGepA~Ri{>!FHCBithu}~3g zKt8Kut71@$;ps>~%V~jjMd0t3K9fxSa}`K5vf~yt-`W{5q_Mz%XC0Lj~das;J6-7z}KFPdNP`^}_*v}Cx{i95X$57GR5Cj|brteX<};?a%h`;q?^(H&p(aMcV}3JWnWD2*)V`JOSfKu=^4ebDWf`4i@A_H^Jhx!5>Nc7lCS z@?~_3!s^^JcjwPE0u;DgH$!M**4t_x;>0=mYO~TuvU>8kvSL?Y&(MP+#BWv5H?iFn z8pB$_N{UQC^DA5&Jq@+%Pp}>qqoMC>zHx+4F97UIDxF3V-qJ3Y6hn#V9@sIdF4FJ@ zctmxGvl`IS;yuMXITdQ&3!baY!`pmOsNWtQv~^xm3V5b_S8yu4v*SfpNY^IPR-L1% zEP>t*wj?=HMZ7e-27LA>Tl`b|gG#< zMgb($qDKSqBn9ZI$k2z7Bf zq6FIE*FJcFrRM+X?WRZmIYEwCc*)zD5nib1Kj5MA!kwx$SEa!(Q_*nYR``c~N4*it zRe9y_)4JGA#JBg!TGky(wlu!$cffepkin2iUGXR70!1%;>&||kHqzO&W%~x4hy&(m zVx#}{=IMB>L+yjjuBufWd*h{#iW|#}Yj(>AlG(<#kN3OdG;~Y758j+vPl$jEQ0S)|t)c8k+Wv z_1x!gA2C?7aN+CV4uAG^*S<(asIM&=qpTtV&TdGb55Kny1r`kLCG{-1Udrqk9HmX5 zRqspV|NeUYYF>mQ`8PS^uc1;h%?qk5dO(ovN3DUB26uKS=+Il9_L-uaE?i2xiU^WE z%ThRp5^21&%e5y>{V@QicGUZD7%PZ-O+D-G@(MrF;E+W)pF9W1VHa4p49x+SEreS~ z?)(ResY`Yg@Sa^haI_2a;mHKs|KblIPWZM>768~e?4OBOWRm7#L?2%VN4WVeSoky3 zcbj$kT@t{c{Qr0U>b&gPlQ(rVzfO@rEuy<_KqsocGd1GZg?;h(efFPrz0mVU{*IY^ z2?!S`d3UTP0t(89lGtJdcV-4K-AJ~W9fxEeJS+0k85;7avIgccyV7|dFOw6}n(Dv4 zGS5b>_c;P)vq{_wBq{^fru~6lG4h;_aIp@qu|U~N9;Ea8x!v4kDniC?8*ka4R^|sO zdF^a-2g9R?o=y}f*w8l!F%(W;;r}@paZyZMyv&(qe<8%ME8LAD$oCUG=o-Q|$Fr6} zyj|?&B57clc5c{6`fn$JzhC2p=b7`AM!vc^DENdGZo|*AiDR#1uaNq1{?u=zi)h4= zh5?vJa&$K-DfH@P7cM+_TQ3@adS)_aK5CJZ2likt09iT0CBd$!JBT^_=9$tOqLMOy zW~O5Da@OlqyO2@=V66;*Y=uAS&Dzaz8jAd$)8BE2n3`-gM`nOSf-DGm90)TS-mj4O|;2VJK4xUDEOOe_224Vqyqp3mJj(XCw zl`)Ov1?l2;Bzfo&B$WkAfx^mbi`P(e<@6+}51747@_f-fq*A{bKAr(O$0C} z2HPKXxGaI`cZK@!Z&D$A%a;vZBwL;^gFdFYQ-{QCxj<#x#^8*tuigyA_fkW==%37& zfypDv{0^;APFN?7+#R6X@~F8?jAVsYU$@XfUvg==f7w1&ZB_H1|2}3kb7~giX=6!f z%j4r)}O6CS70f}&b4jRrNH@aQ2R3&U=#F8~@#l)t-E{_MJ zH$5zB8N>eGtq1?VpZ0neD$PbaLiP#FCt3OwxY@bn~;Bc>p`M_b__Fv`byquTy zNh371KY1~Kplgf_yo+!(7kd|ot?0L&n!*;4&~Yu{*9@X$txs1vFQ2px&p925$AQzV z@j=zc6W8WF)-H)$;y-M(Dqad#!Mu0B#P-e|+B%T1E*xR4TWEgmP4-ltg^^SIOb*j@eZ@ zAS>(4J^kJFIMC^E7C1Ssz}}Bu(HR_Y*w?`!4V+p@?;PoaMsHATDB;(@l`{~u{QxN; z#zkUl;1&lPDW_z%5>1%FZ_2Q<`-D!jG_AN^`apk_4>(`na+;j>X;l-HJ-cIjM;{=z z@VeJr?@B&U;_IKRf-n+qPQlrWVW>X3rtkI9qv{6iK9V(QACmW>tm3=tEX10U*#7V7 zi}E+YMe~m#^4~MTI8(LGn?1n2jO2`xPkAtpJZnFKG$+0BOxy{?X;eVc&yD@+B6{V` z#i0mNP8wJ5D6xSQux-Zk&C^Ey|B61n8U*{vEVWlpdT5A zGE))mlv*ZNA%&a`c?C7`v$3BzE_GOf5s>x}+Re7Z5iFvr!t4gnYjLuxd3_bk&SyI7 zh3s=~5A5MObv;RAIqA#Am6@$W_2<^yEZj6hB{Lca#JrALR+V2QrO^Nt1sUuxK;O8d z^o7~W(Ust+^=H!Zqrk-u$0>Sn2{fV454iZF=iV43r8lLYKYw0y?6j&Kn}u&mX=G_! zR(B(Myzl!gO%=zQ?Y&<+DBxg3y9-TK5~+3NNMPGG$uIfAMWH5x)#d9nu=DhND5@NZ z4~#3~C+umA<-0B@>@y5gMgD_;?M?ON020bhwk zWZE9el?3-08zbl?_xpY!d?Ew9vO7%C5hhlXB~e~V zDcm_JUQ2dWhqIN6s`mTJqv+yuisa{V*lbI52KeVp3;GCJfkJtu$(Vhik3rs^;&ZE# z6s1F2RR?J2Vf77)v4wL|1(D_Tpx=hw(n=16`;#MfBdNvDQKzD`bd;To54Z~gp;m)6 z!i>h3x-nSBMV*P)FMluDKj=A-Zes<;7M&R2w2yM_=y4%$J|#o4AwT_a*B}2Li94ap z|Mge&AGamXaU^WpBSdUmX`V7kyccC5Y$JG(vRpcXedIyAS#+Wvt(;FcS@o&Xr}7(8 znxSe%eP3<5B4F}Hc*x%em@VhK&U z<9X-Xvi{wIRdk2K?A0LOec+WMPI=$Xk%Z@sAF^8We;2ZH9n~wYBWowD zhP8naacdb{`z-|FK`&Kz-;*nsqn8Tt(?5!*WyoVINm66^w%`N>aoF#|hX`lGqgG5` zbj>=kqkxh0{&H&pYsyl8sr(6Y5^^g>F{I{;M+C>(4kjNnbVi)rgXH=Qj?y)C>DYYp zqeUX$^)?jg%DzQ^Fx}*gLf6&FNBnK|PIyj;!g}Z*gDHO5%_rAvb;E znc5?B(ZBa=A@P3sA___c=R*wzzLhi0EcvyF4rm<>ZNPSq{feHTbUSNR>Kp>t4TtGw_#0XOqJ2=AWi?NLNJEEvsZRuBXHV;t&bFOZj z^{^wGn-JXKK7ZbRqcubEgx-=;KsCOd-mV+EtB~Cdh$%*(;Htp$zVqZLy@moW@x}}? zxrdrsby?;Y#2~_QSWUSxaW?lyU?DYb6feTvg;F4Z1CH@_f`@0Gr10YAv6Fa>zT9yL zbqWXM?rGTt@-2^t&%@N^bxaLp{NlBg`4e7fX9jUKFM+OK*jcaoYWs27hxv{_r9jt* zRWvOV*~{1~bZ%69fTRf?sXa?R!0AmCm4le$WRKUn_y4%!$p?hjqE)rUqd&@A)%_|$ zw(1*h2q!@iURvDPK?rjXoMvuR0i-vFOa(~7=DmO`{Qe8;j@a3h+^X)d{rrKq7SfWY z2!84Mz$|?^k=GPf$b(t8AmbDgcsn6C*{pl?kKJ`nWIQU%u0`5$LWCn>-5ULAp~;5i zTL>7U{bufa6(Bw8&zIk-Y6Aq1;yJ!oDKo&L6*SyK6oB z>^-C_o?c+O-`o;TRqHR-`|WwrY6;`P8F1tF9&@=ep2}lc4*Z-5_H&DR#Pihhj4lrs z?eK-&J@o=+*6DY($bfhpw&qHdj;?TqxQL;S1T*y`wmcp79&lWy->niM!rD4Glm@Exi+r9I*qsEV7vn8xzkkIl|SC z?QJijn;p9g3!~!~k6xAY7X8rkGJmv#%Q45?zVjBYw7Hy|SXqGd6n>%){U%X$b4p#3 zU-ZKbA{E{NRt1K$qe=)u40v@unsS_d~U^wl^7j!VfKV*urX>aoDB)?ZyK~X z;oaw3`m?cbVEAHu;4O{8QxO`M$T&Z4qMsg4!@UOYv+ug{%-&&zRudN|0XO@Ro%nk3 zE4<5Bz69$|iqbKZub)qLAg+@oC>BZPMrN3_H{X9e3s7;1dsC~Tt_(^n_I2~>kF-_P zlJY{(o?@Md;PK>1Nrx$QF6n=Dl&L(q__LrE$sM1nNNPM?^wtXcin148zIxF|d1lUa zt~od}g2d^D`A7ugGTdNRA@BAF#zj24hO)YA#SsxT!ErcfR|#h4jhj=4#x2q9^H?Z6 z%-rP;(XHWq*#t}iK5mXH-|W~_C`S_4lZ&Z|=WnnP;l+M>#B2OH00HXY-Fnt$s>Ai8 zV=|DP*NfyyTC}j5fnP#Vb?Ob z6h!3+D1 zjVExRsyNwdIe|M&=r{nJr!BEEH@|ttpHt?~{Tl14^Qs=izRTzy3A3pNM_pV9bN$}E z=Lh{CM?=a-Oe*A!{*u^us6xJZ!HS8+^jIkXDCoiK?7Eb1EH@y$vYOVS1%?2ypmgW# zX)K<{0;M!njkK}(cebs?_MPXR+{$Cc?B54ZHp=Vh5^u~*GRsh z8)!Qa2ZY}*Ka4|i3r~c}xq%fCSB8m-GmursXk-^QHf!rf* z)fXFk&%T8kZqN-1QX6et*CeEsm;$MNi=XZWg?%boxjm=h+zqO`@9`_X#DACqhx=X^z}`fQ4fmrDB@<;C znz$mm1@tRRsn|ip%^o?sJZALheyTC0|NMym)EXx!-F9amY*r6lSpm{8J!O@!j!(q) z$rbd{Yvbt3XRDCH@HL^R0ESq{{9%C+mbtC)FTr(+FdGJY$6~Z{avmnOdA_qh9+K4e zV>UY~)fxm6-Jxp6;tdeyzsRCdy|Y~kd1Op;{?N?qL=BVfdR(bCHTSvu6Zk;;Zrrhbaz;c#xGSeKXghI z>pQDF;)%`TQTH0g?+6$O-suaZX4iyU&Os(!HxxQD2rxKHa=w4^bc413)M4L3cROsQ znr4_y@~anda0BX+Ly+*Q_#NjvfrWU3>%dU z)%2W(fWXV-8(VN@yQHB!0vlG>Dy9=kQ}reDbAf5;(thn>}9~g+hDLAy0S?7!aGttC;TbDY>0CrQElQ#Q}(jVV&UCTf; zNxy6E<##2Cz>Y<|qn%M2Q5S?aM_Q*g`+_{z%{P8aaMPX!K^HeAIsVjb z{b3&LgHIl5y?6rbf=ZZo^)oiu4tK$d7 z0JpGje@%8u_EXf&B(VeFPIqM&;e!R7PS8;?aNCR|dVcWz54x`%?m;h1qP!tC@ID7R zvWlDtDT5czO`n;ndV}$pD;Vr9qw==b(t3Sf%^G%HomzYNxVe3>sf*KY$Vrap%Y$^V z#35;JojX)56oVVu6!G8Dtya|kYwz2`q1@iTC&EV2uB3=+@7iiJ*byOzlG<%KRZcU8 zk(|v)%m|Is4z-DP+D3%rw8IRU6Eg-;sm6JjF*6R8j5KDX!C;Jjk81zEzwh z^}fG<-s}DE!DFrU+-t4-zSrlz*XOS7JM%H*((i=E*E2u?Dm(ow51*3VqvK;ZR|{fy zPjM-{u;R};4fGJ#r^c%Bx*QIYj}kUOp2>t%GAX4SqmEXYQ|A1qLh;lCdys(+sQ z`R?p{9T`?5n>vu;JJr8;cfkI)Ae|`iK&fO$GXGoH=((@H9HFdDAlEPfiKLX{YI8NaVPuEAWg2P63XzbGK9bT4biZ*YkxKPO!$H;0ACU+ zn~?oTZ-hQkeNLVTJ-t0q;|9sv)>!{+aFWD3hr+Ts^&7agdlQ4Wzs!Bm>c{zFdE

B$J`1iemHT7Z%(@F13)WgdVCJ<`NTDBF0;KIcqX$${D8;d5o@>a`*c3 zo7O9faf+;gXlNWYKUL}hE24fxWpMocIBYMYEc)VOZXt3CzpfavjF z38_)xg%zQHmLIWf#{KylURx*PC5f>yi1^2;2{rl@D9d*=#T)#DQ*U5Ji$_dUBE!db zHkI+n==rG~c3d=AFsxjqaB6vWT_7Ofv7$`P}8I64Fb23p$u{t%`ewUYT)1-uT{; zt*OdgZBMH_-tRxD*SfjZuxG2~nc|SQJKhj8W2D({>ae=XFh5*LWf-xrDe;wKZ&iZt z5S^AZ`*f*0@YdD)5+i5h#d+VTvY?DHPf$VRU`pI%F#37Q()IJ^T;(bRQI#J7E*vMr z3yZGCn;I2-erzHFsFu-pyJG>HDFbf%y(|5`VCZMuwo7T&X)T}NMXTDDO}dUWX*&~o z{P-|QO|REs`*mhsg0)M)!g*KV-l%IX8%XQ4W_^rKetTsWp)fI!V7WEE7ZhR*#Io&y zm<({dIG5t4H*DE&m?pf@j!vWFHCSoA`^%sCA5*C;-L`Uj|I@Id(t2#gGIGz`?0w3# zmr*};7LKq2UW6|p%p_VrpQV+QX~p|)D`hKev;TDO=cLj7YR~>$lIdO@-H_FqE=N$D z892iDkdAv`kcmZc?=S11qoD5w)Szfo+};-SLeIdeMgOWkp6d&V9a?~qF$s~)FhCCh zZWd_o$x{90xBE5^hrU>}FHjxcD16@Z8oFYBXLBpw{ixcLKl=n5_u2yWX|x(0*#w_RqVzK;d3 z*~fsda!vNGnJfSC0ry(2tbO9Dwq;)F#BYthn_fP~+LC`=T~cCB?TxcJ(W{aCvh+<` zZ9o1jA!@dwnc}^s;5D5TZw*ajIR1U+jufkgZzRRiuYy*Ac z$l0@0clFb_-YB>;TQn{ zQaiYJosSyS7r$A7?`ke+aBIluA9QP=7*eJkc^%^9^@Owa0bq#t?z$;#!Q$A zdb@bU7%F&ld&{2j7DO&CA5-eoTHoz~6q0%bn!{<#D&9ONGXfLa;3K((V4*Rz(MCI1 zOEB-@!YGT^G8p8y6Re4&gh2-y=t)UcxPrnM)e;-o3Fzg3SW8SUxTs|i-x`%j6goz5 z+A|}bu`cljS`$;cVMFdzbyMKJ9WW-MZ=yV5Qw;Z(XAfC*;x*5&z{Uq&OuHDqyFr4& z6Pq+o?USq+@+e6qDE$3!P2BJfqpG%R{i)ixa6h8&X9PNsI5IOSoQs!HV4+OS+Pd#P zNToc)w1X!X0ntbILi6hwc}zENQS)XS zW+IJpPJA3d z4vw7t<3zRS^uGBOGg?Ss@G&EiGu?FBhF&KzqkVeFQs5)>4I9Xfj z$4X!J#1l0T`Vlp@Iw4zt!#)TULU&W*dt+mU^KjNtJ6W>^b$_&%73wkYW8YJN3t5SE zO^D;Uas*nUg-%2bVj2;u8QRSY)92kuX$&%gM6xOMX>m!Cc&MqBb^2d|hcXsWcY?%V z?wV081EM199|5S?<*sNm-T~}%{5#>}T?9%V|7DyBWw=5$H%^7Y>>2kdFt2XA@2Jw{ z`%&=}5Q+!>i#YbTyg1}6x$Rhe=%enSdLvT+Bwin`wVXKL6)T!H!z`W)pQrg3@?;v_RK$)=zNd+)U6@q43NCL-WXuxn!;l#3!&u#7#%HM8I59m3^`;l zJHpY9^yI0}QaTrfQXgYeQ0|{L>MK6iZH)GPX%&76s76P}$XKI1%?v2%J98(ZHNulu zM;$M=IbpJ;f6A^TBdi3w<;%h_J`9+&{xeiaDr()Q7`v?Z`DJ24sz5&Xrj63A>w*38 zrPIJ*Kw;qrjpbheULNpleE6$l3p}>H_;&ULo`3un<^~?K0HWfrse1nhFPr}3?zmi& zQ-jY;i>rG5-;2F(u~eOufIeKIfDfQIEtSkF8E-J%TA;kH`r2L$>f{eKXjn!m0R}T} z6UN#8i%R_Rd(?o=m)~nCKlvsoz&NU{*B=6X$&s}H^16UFAb^&C_idg1W9-)F>VN)n zopMSO4;fL2WL8xfHoxHFeFC8g_6#$ZS?V(S%^$cYaipvmYxw$&LZEFNyS!~A$Q)fI zkt}e@+L{~(O~Zx-+1izf^3P_pD^G5*fb;IV?cWwTUx|NVs=CQ6!9AEmjOxdfkx1X? zyBU02JCGgul32gU=&A7#`kc&{hM4xD8H*aMd3c}kA_J59A&;KcgGDWEtg6w*1fJ*c zYNp{?>eXI9&By@ez%+S&MH{h}#>5GqBLyvw!E2t3PD))QWg#=DQ{Zzn;n8R%;*deO z_M?izfk5U$jE_*Cdq?Kd+85*(SB6sC-?_zz^2rQJ+G~-m8d~vuBj8o7%dRdhCGPLQ zSm^fO>Y8!v#n6=&Lz)fDw=_ny0Gkw`a1BkGuw4pcm_VjRzEPIkRd&m}L^ETT68Z>N zO6su@P!n5VR|69oTFz8IBk+i6{yUxt021AsX>yW$hEf;q4CoVyTqV zc5E=rKuC^Rxx%aFxyuu>^;P)Oi2+h1L7%zMz^ffmGEV$vOi2fgXEWtQ4xu02jbW}B zP(5apJpH`FOwztgHsq#5Fu<2KqrBg?&5%B_Hg&1AXyWP-)KQ?sR-ZE)h#UX#&0w?EdEQ{Qs8)|4&Q9wOfb$@w_Id)}8jMYPR`h5V)!A8n>Q^nQsSRIJ_`j&)>YFD-_tVUR`9DB;6Ha>Tv0dQa(bqqn zIU%AhI0{D`DBg92&cLo%&zAYJ)-Ft(K$hU>Gh3n8I_(bA4UA)XV1^MP+7|U^k?ax2 zETG?sT+ut8eqJ}9X66%42ns36oEh@9x$ z!iHetP4+!20-<71C$)re47@1tGgf$hxj8> zU4ie!m>OPo4?|+KCJCAps+~>2b+ft4CRiTW`V45C9!KiF_jnN5Z)RBr zKNkH6$16$~Cy#39@s=}@nG&}n#-5z)_Sq(cxp&6m&^Cpsd)VP29eZ&AK*&oHr&oI7 zbJO1zFQ8v$rJ)g3i@$8qVGo&2oVOSADLArIsORER{>0STUi%fV(KQhK&VP>f6*P@f z+ibcERJ%Q&!W$wybp4RgYE9uxmQcCeQQ4hR1j0M+Cah&ly+Iz3j{|ur`yi-}I%w$4 zp6Yg7h#4+8po(~2>j*f!apvB^rgR7#PcCXCUA5;YjyNQ=QO$gUu_uqmo#OsHLq)2C zbDQe6G&h%-V&IptFe^RfE|~!PoOf{Bp6C)B>?kkDu<51QOzm0)2(-??@^u*i^Q*KN zL4HQq!QonkZR8&(wN--q1H%;f7&POK1$u~I{>;+K1^fiqWL}iUfn4qWvztJ; zGbF*NfdGUzkuSnEVGu2YaQ?%EsM|V_u|wk?oHozsJT4^dY~qx!W>(w}hU&yPWI>*q6IlHjKlLD>~64_^z1Sb%J zeZn%$|ISA=!&oMW||xW zwA1M8?ASRAo4O5+RBLH7CgO*=@4RaejzfW3rlsT4E3_)L6oBc+L* z*F6%(_^!*To`Wxl#vxRCIE7{T4n)ZCuNE9mn^a;Vwq%1zyG#a$#9IqnkxqM?)rP4K(KFRn>6JoX z%8MZU$gXkS{$K9S$rEC&qPwDlz>i7OSVfos%j;Uo59Vb#2=pnB>Sw5((jAA(}A z=L5^~i;^}X_(rs$M;p4GtrG~cs?b7VYf^Pb9zy8C7rrOv2BEo5;Z`&GA!A9F2{qkk z{IFN)DBjFc41L0gcW+VUeS-zlaz@MC2vUWxr&^b^H;{KZwg>LcXP*=#{XELQV<^x^ zL>G>39~a$%Mt(j`MM7zm?z?0YS%D7v6!CMehvXD9>-FEXSGZ#Wt~yvLe5QH}mOUf5PP) zk@`s<-4r_9WwLv=3r?(HiY>* zA-m)8^{R)%tTe>RzO#|RGW5CVNfU0!-|}tVcb`}N6eySw zVGHy83Vdp6L!-hUvE^{Asa>iCP=5=0U!c;P9 zq~2KNE(fRxlhAR_iZTe{1&4EYaJ6tI0|5t3&ca2RmE908R=Z7jKZ5m_VnMdMJ4D$8 z+*O#@d$YI$&C{u41Lo~i4$3Vd&{0+?L=VRCX3~+?l?V4DKV+S_m@)cbVf(?dE#{qR zG{jhQ2tD`V?U8%B?7VPt<(mr|E)$9#L-x6p5<0SPoCuv1Z&4;1f0l5H$PT<2QN#2U z;_)-+kzUm<$W%iq>clJZHk}TfBbhso3jKAA8ITDR%o^v^am53>(s;S}m+8ZwT>V(> zBXnk^!@f8U+4`jnU(_GK3(KT5EsTgY6a?>=S7s}w%6swm=tKBvXUfDO^)3RUXS3A= z8!btnL??d4U^nthjXcs*LqDbUp#|&&aJ>3LSR8$iE$SwCtWPtN(i-iwJqXJM$0Jiq z9=$VpoFM-2X>tJZv~vq4@vGUDd|2{gN@{g`*X{P{)qXnRi}c+S$GhIC%a?T~xKa_q>zj~XJwe8X07F+bTg!27jhYJLdj<|XlC?3?6Glb?k$@J3@IKDgOt$AX){5$8d>R6JGo;}hbY zIuwFt85yOarSQM|8lQ2^94Pv76(<4?y9k`1+F>$n7<{qLUrjNH!wlADBPb>|6(Yvk zW4%|DvbGWb8aW)X!@8xqH&Zk_O)B(=9iDT$>Y^wKGdA`k9Ko#pTv7rq8Pif&v#v;z zE!^iT^4H#*T)o+yA4?+9Bxj#V&1Ltim2Q~V9X8hY@-(cPURk~0+FTal9sGU{l>fe9 zYrZWZ2r*q~GP*bg976cOk#)J!u+$_dj(zxa%oW>cXRT95z=JyRdD_;V``$Ff_zuX1 zNj}SZ!YEI{Icy)X@XBA8OBeV+5-YwSR_IzY^J`9N)}D}Np6IC5^hN&xdzjno!P!p` zpc+~`?~aK0Cs5U4S84s$5AmyygyAfg^eM ze5*!)wd&AGsO-pwc<7$2xMua?4*gm7AF0c(;g_pf6EzFXclYz~n_5)5pb<}4^G(XA zmxgIeZ2_6tfZs-k1b;pDzJhFD{ zE3OFK!400L^=KJ~_E%IKZw*RURL$HxykoP$Uuwt&Tf-ZvBiW{X<=}coUWi?FSDR;l z6e0`imAkMejZ?W^FlGlIV+JCkVyE9pG6gDKZmzNNi86JCS8aAd9O0&U6t97Cr}M!= z_P|1SfvY&q z!|RQL%Tv5(OSjU;A4*_{UjJO~yMsO}x}h7qn%E53qt!c0))y@D*?kF6`RN0{4>&No zy&+n)hP3-j^4E*3CkB9C0k6pxSdB`GioYdg#Xy-Ovf3FcNDFW;`>v^UO{QQ5&d3KI z4bg17j=A;{?pJZV@)t08mT_z0#*+(|SGa z|9wEQ#>zNWD0+;M+Grk&Q!+-+TMSP9GHYe0bJwk`DNymYe{F{ zl<8NbIO{BcgvQ*#=Yflofh4Gv)gxQ;9M&Vjz@Yxdm9}kKPoD*z|2x6j{{jQA5B7sL zahg3te&k34W&Mazqs1$wmN5T?IP+a_!y4-!`afW__Ig6lbC>tgT3_+RQvm56pR4nSqvp6O@?`OPK{TG0|C10C3lV>9s6Ya3c{OayCikWI@bVpqt zheb8Qbese{sRa*<7I^ISyn3Ogh6)8d%IQ&p5poxc3UL-30)-bAQWY<%Ft{ZlI<`B* zy%D|L>=jZrvq~6}P>>WHf1iqDg*i!bpuJAx#g_^~mId6|+F>kzI$z`N=r1>QI}Y?e zMhcv%)Nl(O$(=&!tLy-m`MS#B9MoZze-mTR2Vh2KAY#~lH(?rz8W(EIn{|-<`xee z=IjVcLn=h2y>&U=d$XO)OV4I21a%jZ!eTjVKh^weXKhMp+7KqZ;8>R$9?~K=8DB>u zpLmcucMH1s^bJ#;mpHs2j|=x_wH8dJ)~Dh`0&-;_rTa*=ir7(M93YKYBJ&9DHyb=5%sISpi=u`;oCI=Zv}4ttmU{8r+EB16Ql#|` zArr;$h>a$Bb;4>*fB;-ScFcHitB$4G{uBS&gB$sZhc5iQsrrb=kCy~gsDd339E{`O zdsJ?zWT;?pYF*s)?3Z9ch*V|8yd0oTwscOSp9178;6?~12;Ywaq)!N!;}AiO284OU zZy#i|b`<+PHPM^#NCVP|lIh5R`k?>T-S>SUZ+zk7)cX)mjSCt!Ktx+nFmTNL<6o>$ z6x<^=Dh)1#vLUod9k$%aE}Wm>DCXA2pngqdZgI9BbD=JKh-9F@sYXCah@d({8KK2_ z%ovH3#m$C17$wUl?0)#BEI)pZoXtjTNl)FYVwT~Ua&EW9Nn-fB?S@O-r&Q*~^X-a8 zkmM|QdS!Ky$3`HQb!nrCsk@N)1E8|^{+M6-D6C5334mVgda}vM-3s>|5TtwYT~J6h zH`D=`7P}yee9F{k*!P!nge2W3sesZy%y`ngXI8wg;0>CsCIR5SYRZb^w^vh&zxA+5 z?`!k^N58e*q5QSsozCm8o-*#Z{H3kbUFq8ZJ$?K8F5~+EjJZC}H~-eeoJH$p#__Z0 TK?MLx0fEjqIG@CyfT#Wk_U%(( literal 0 HcmV?d00001 diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/PR1.png b/Firmware_1.26b/Documentation/How To Contribute Pictures/PR1.png new file mode 100644 index 0000000000000000000000000000000000000000..1ad8c1e07fc4aed3503589dc47ff0ee9a83dd098 GIT binary patch literal 69205 zcmd4&2T)UO-vB2oegAwWoggoF*Z<$2!s`(}4$XJ>Y=8DL1RbFP0czwlJmGOu*#bS-O2`tQw?T)^EOETDUNtkRw^UfuHMi1&FI-JDiU@%(c~mMjl8co~XO z-;=In%q6IL_GsZTw%qZoYLM&ho=E>)t4sa}Wk;qw7Z(pl8oxYXP8bNd4*J zmGNrbe8VgW8il}d=+BPotOI}c)cT2pf6~UV;w&&;J09L=Rr%gMG3No+nGIpt`7^+SCQq_R; zOK1tjlYkwcjvm04H&e!4n{ubLIDQ>Gu+m7UV6NV6qT=8YIN1!gY{?}bM7>?-3G-U7 zM^Z69P*ShLd;^b-$SxMNqgA9F*T;YTK)ED3w3M#)1;CgEbiqvEc7yr)72dOLf?(1@ z?|PSLS%;-(Q)02euQRgg1D`fl8i)p(Ls?8|FJL~xnrmjkf}hcuGnztFqar$INkS;T z_Hf4VN%G2rfB58=tV1wJ_wE-)rF`!)L#azG=jA^3>DIoY>+i8aZt7>=$I-mruc$6f z_EaQtT+Vg4W4OdJq58KttAq?y*KYG=!h$};YfU!{`q?xWKIU6&-Aw;oG8U2j^&Ov^u8N&#(!H*S2_^&wP`bZG;q_qQbrGF^6Rb{D2Q zdKISKLIbU_-vYrYM&?Q&eo;qll?RY~<(;}us?cTMR={P)IHWajYg5=UK3|IpW!v`YJB*R`!&YJUT%VSNJ#neY$v-hj+ArS|Ulr8^xNlGUZ0 z4KNCXu&K^hTx!!aK5>ul$Sunf#y;~ppS(ueO2a+Q-&Qlu1`UPrr^D148=6sESB$e8 zWY^OX{+W!sA{vBFBa@=Z6YX(A$-FWS9ZBMr;rrg1M2G|nhC`0KNOrKtvRPm+uZK3cf$2lb8i%Q=F|XUQp#IZraEsxnKL1Uvhc)H> zDVs=!5T78orA!MBx#WXUXufa~D3=duM&1Gv!I7>(y>cVB!DrL>%Vzyj0qP(3_!-}| z-nh@A;=e2v$8q>zj#|#4M%6<8U%ZSTr`Mx|((3`&C*73&;wlEJP;Bs5{2wWPg|H!y ze@sD8lg!|iI@x35-=U>2|J4E2(n^P39qfp`Ch3d1aBD+=ZIy*U*uS@hefHG+Qt4t;|48-ueNaLV>w@9dlx zB@U>WnYd+-59Yugz^_b&?Lt$OeDmE#5f{#?*M;uP3MpJzLT!)ij;r!W%f`VE0hP-n zK6FPe+`x_WG^q$ed#w|`8OST&1YH`9E=Va`QUO^Swtl^QK13oFpwP?OaBnRBbs4q& z8PTj#@7y{0{oR+3a+Qb{nSN+2f6?N7Uy8S^oim-xHGD^apO7fviGRZmlT~nE zyCm5l8gIH&P4}xuMpT0MT5yj8x1zbbbsTv|6o9H1Tp?eGo9@9{lyj;go`Q;R(j-4} zJ|Lr^La8-(_w+_q^!nDmuW_x7f1%VQLzwAv7SN4P%~0A~zTc);#g=1hasVAA6gqnL zh$+n#;Zm9CKoRc3Jt-j9DAP7DwkBcQRzxwikS#B%03S5Az~wHrJPso0unHq#9+A|c3yvq=j0a94B-wce$pJSXYbx}_bo=6yIDs6)_MeB{?wW5D z59vvzcszNCyw+V3?Yi@xrLs3=o-dy)i&wxxo_T!9%P*oy??+)P-}U+y zn6GvoE;7<0)<4(G@{anbo7k+OD9qStD)M!pW_NIR%BSJsZ=42|Gi9m6G8S!FNl97A zd*9oZ8ovc4AiF$uhnF|7c3*a-Z`s65nKnH^n?#`1*jfi)EqfqfF1sVM8gXnq0>cR3 zwVz*`d`4iUu3ulBo~Yg{8<@-e1#Q;E9wqs+uRYGRnydHCD=*)CW>mRLSn{g&(RITh zdv^l*TO!yZo+S{O3CHEu1M*Tq7FXY_viHv~evAv6k*wGosa{g&R4I25Fnif>>zbI5 z^A=akzy~bDES^{uTkdW(sh|1OhZifzffAs_Ude02 zc>M76(Om|9z3fi&A}idpV}l>A_N3b5x1ggI#EoevLAD^(+Qm4tC10~-G4scQuE&pP z2H&zyF8v)`vaJzu2LgUPW9uQNZY?SXx5N54N(Fk*`g_O@p1)s6ktDMYjY;pCkIb6#tK= zt52fZTOCq;wc+f?6K32HBbUvo45HFL~COBX1PXa|x+Wu-kp0*19{5%VHS$F}AdJ5+G} zAKD1>9cx{G?KyE(@+xTCbh9|%9+1e%6vz$3l#;Er>!xa48v(1|%I5KtFzVf>Mu*2; z$nmT}4+a{Ven+nHg9?gG$k_fMVyY*IeojhJ#7~NslcIUEoPHtm&ce1*p zC7a*(eSk3NS|{@Ban@lT<`-sJzORgG)H)Uf=Gf2Ml9y+sRmI!WB*iVU<%8)6+42X7 z)E-AXW~Uv_*YfdD+G~P;_s}M?r!W>N$d|7?J4r5Radi-sd?SZh87ld~WdaG_!L~a@ zpgVZ9yTZ1(4G=JoEb$L0nspts@UZ{#^0@S)uYxko@D`lhh}FrXM&NVtSoc%O_=Nw2F~0Yap&ebY!NVpwWksioCCm`n4@Q@Q zx95}7vi+8ReqE0O?A%n}-R^hH{08IZVest!1lip}XYI@hr$|$8E7%d-X+D!?=6lDj z1`?Y#dqzm$Ad$oF)s#|`l9RvuOQRu2LCQJw<4qWh7?^*3gD3S6eB8W1Kg~h#$a0jf zi7JT$^yVakxQm%EuYuAiJ+k7YT@sOD%?As`r%m_h5oKsn6GIJZz7X(ZlrgPTkcZJ} zMYKR;5jbmj)7m8<>`4 zZv@IvZXTNGEKZ?J^L#@>uPr*HX=)o6vatPeGz&d@D~?;J$rX%-nJkzWhaMh3iIZ^v z7Mr!infN)L(zMil(j3?03piv^V&4{yGtE)&!ci5fo?o4<@rN&P}Fx@6Jq@!2*CY9=jEt# zEVr6LNURXRBlMvT(FMAcm)sMFBtN%6s)O#dnuMGDzV7MN2Pre?<|L%IjDnAweZK$7 z?Pb~aC_&+%#@fY^bug8gxa^2iO=_^x*~M=kRDTCO7M5(DYe#|P_WVpJ#azi}?yiL1 ztuJPK#D1II>x}+ghqzm8$@I->!`57*_s?H)5&#!AYX6AgY0FIsGc;D#-_P%T_ToT} zX3Kf@B;nPSW$(y;#O zpG_LOcUsZ^oD@D(`Rg|D8l%5$%+brTgGcPGBh16mHc7Up|6Fp2j};!s4h%N`t0R`P zPREKD_6}eN<{Sy54raZD{MlVHJ6isvt=>=AY!d0-AQlu@u9qQi+y+o;VfH@h1{~rt z$CmvOL0hYj#t@GpZpbzXSK$Z2QTa8WCmSGXUiehk(s)lO-trC<;J<7p)7z&Iw6WOZ z(|g(M#r0#w`+psyVYvETSCSY1J<*oDI&-Napi??UafvrY%KMe-4TkgfVC~u+XxS|K zt8P+ipr-wXW5em-@q>5f4ojY$J{#DTwDFS3``{yg%;8g~euI;OU}6Dgq*9zjquK(E|F4A{L7I?>yf^*gSB_BF=*2o46`ZnjvkPHOD4093s=P!_0_*6GzcSn2r}DiOhuje1I-4A19>e%UYs{5F#?(|5G2cmv){))6awOIBpH0ZNkAa3d2`ke8}*UARO z$JP7b%=+_rmrI^?@5U|vYi5LQBlP%5@IcuXM#V(Vmb3Q*E^51U<+*YT4kZ|fWPd15 zWwb)**3u6Xxp?PUq1Qx-*N@)bbQ(xaLEZUe*2cmP1zB+NJu zY1|Jx>!>|S;Mj<>0_p4@ciSD8B(-h3pJX%kPN*efvb@et=KEnAziR~*K&$(4H$X$4 z?owky5hla{Sz1SlV~A?L`};J(_;c7G8__ZwkPt>~hx-~+HctiTnrSNuOgLn?kccS#8h%)tgTjICG^Ws7sCLCwezUQ~N49cICZGqW1EktlNJtg{_y>U1K-IHPA zyn43&X`JM8`)j<1#&^wq&+2?j?yV+1?;z#6Q)({oKmPjYL0<2W?N!cPHe&>zI%7Q1 zBg3@*F7Y7zTTt$-x}R11v&C8up-Q!r#S5KP=I4+08;%fQUK3Zbu~US75^8=^tV{+M z_t}Ke!GUD7>1#s(y{fZ(Sq4a^GohvLOUj7m!E2%p^iF>NOHbPgA?TE4 zjYouAh`Vv>tbT@k>qIYX2F7gA>g~ynt_R`tYY(fD6$Z>kw0h~`%E+#@W)6%mwWb5s zf(vURHguYHkQg;INrMHKTWF1bc2&6m-;vX75cK}G0jl&&rgdENIQSu#MU(Pnd-36Q zcXOMUP7CFO7rSqDoDEZfyVs1hRS*`x*~-;j8rwP$C_Q$1n|`)``fPHK<)bXSE}i_P zuU;#;R+4_crk{hJEnA03@Ldz44n#dhNgJGbO?wq0qOX(jV=%)|jx=g(f~_1(&z9x+ zf-5xIKG@A>Ci}gwK-r!R?|5&x@-F_Q;jT{O{l1_|a?IN2^2@4bJV$Q6rBDu>kV&6d zo1Z2pW;l!_a39{0eid;XuwWPA+xlWV(cySJ=34*~wTJnUrQMs_$JmTfxNGbu`X`hF?G@VtOPVuUJanbsSvubK z8e8@W+*w*fpxj^6&w55T^jAV*4m2eQno4TGckDd5HfBIF{ODw{hTKcyRk6%!E2ZH9 z{V1LXwe{khihoZbk-k(PBf+0*fS~rs3=XQ?cSi)xbsQh7CxcUz-ShP_lr{Yc`Aj0K9k1|d=rvf&L!B=L8$d;G@Ie~-c;h%Iy2gG>AzNGcD zzIdhr)Fc}*Ev!Dq7|Bl9(U5(~c_N|ZWASo5eaXN&cgc`qgn*5%eiKOk9?=48c%9Fc zN4o(c=F`3q`9)QZgrmbb9_{9iJ&!lYb_zFAcvscpC~fA|4zrA8S4T-pq@K8c&5V3Y zA7#Lm?fIga>!MRp!01 zud&@5CMpso#uHo~0ZB?+($GnXG@3>*%>g_(;ZCI17Iku0^` zW}sUFvK+>zCfk>+U#w+kOiu#FNSY6mbJbIZWH2i>&>jRv@OTO`w$Rei+Vg%!W5uR+ z`#(@3D>PvIxi5^j}Bixs^x8!p_cDY7R6@}WJl=q@Vfg}Yyis2TtuOxe#eSYt<*N1Gq z45nSM1aWX0y4S)W@H1;e#)f%0FbU(^8Mfq3Vd0Pc2Gw!<5BJuDZ0n@R2BxNrz?h(p zdm@D&PvuLs(GE9hZ#h;x&N5(jD)TfeT>n7Z^%j_E7B1(5X;ip-H2#6rw9n4`bq|P+ zDk>OTn8Ox<)|+f3FBkC@ClO9&*yOG7Sj&Ws0oXI?L=E$#0sr?1^r50U@?6A_Thl2{wpRx}_8e@MQ9lbbn~;*@kuaZldj6bK zEq-9r0#~@<-9v?Vsb8t1P`#_PjNS8=3@Lu-=>w z3zN=&mI0g(gj;h0voZ$`10lqzOWjE&Z%&IU_t2VxH#=pF3(|zDzXt|iGOOMOiArk- z9{e%7e4nM1s%cs?>2FE!YcP#KztxaDSx>e{xP)54Z+T%ya%9cW(oJ5KCm8-oo)D+T z7Vb-I76=^iWTo0T@fBu>TmA7wwD*;BwiGCWk1a2>sp4jlZsK`)lwg=Zovn%Hsol?* zrn8V+XEr|r&Rx8GA@|!DTYgMH$dls==S2>mn+W0b!~Tp=Y|vD zPc|`I+%@O z0Ptg2d!|Ahrji%>lJ6xHq+-h{Z68>u%dsZafEVzR(rEY53Zb%!acl`NWu%&^3!|;1 zH|&#*Ud*E6bn+mLR&<)fpQ#XwhaegCQ>9d%_cykq z7k8}FbSQWV^ms9lU8juM>3BV@`ITd$?9U z&39`c&Hg0#U7tZuuSA1q-RkON3k^JI^SG2rWDn!v{uYxY4a_Md^aVZ5QhqGbPQ>(% zll6)`bx;N)R2XNO%u+|WUvG)Eo&HB^mfsyO^kE@Dtk}gC_3$&?wPH6qE-HloQ2&+V zl+o|kQv8n+G>tu)K}i(C%Um%3emr}>&?3(nPw0hIAAZ(Yo&f^48-VUHuZ$oq#hI(gfFs!-f~Sy-wd<~7hfRZXxq^6b zFL-R6_79p@{sf6~6bs73XSp(*ODJiZ0elarfYNOjDgi8`6pRF4b1x_k7NO8;=C%5Cf`Yf@$ zaAwtZ`QzQl2RqT;0*pXP?lkA|9gUWw7@rUJ{0S3M7x<6aCEZxu&{#c2nD$F&msnZ* z933DqR&g;muzf7?VC$gi+%bI4Vt9+_W9wN5x@W!zHJF%Y~Ym@ zM93<-YZYfS@MK`#m;WqL29jdYZ`QkfGGnEWSRGx2!WfKEsh9-ou);|az2sS+(BU$d z;ksf28uqns*N6`vzWbnu17?z3YnLonOX6wjufC_6ZXIWdL_uB_(GAaFITG#Av77GxG)3qz1yNfoo`DESUH1jx3 z2Xm%=pElpj%7Q`iakDIL`FTX}1bD}|qXsh3X*>&NGHCv|_% z>$dOwZofd!P3GyIyJkG7VoBJkcPs2+I3 zg&o?KjGEfCJ{j<0$eH}|K);)k!9X&{HGWe2Gt2W|bVZKfV(zCbn9`b9HaneC`~-!! z2G2_w0}qvP)hT1~kHfVZ1o>lAsi$A0AH*zqB;ZOE8U)dzsJL+SPH2o2X;HC2O^5Oi zihw+)V20kT6m0uKK}T6kf|mY@h(1<Czug7oz3$Etfc4dsX~uXRN&>~iNSBiBI|sfEMce1(oVY_< zSEleQzj`};HQT5?ZD z)yeN+Qj2QKrVNv&9HX#eooWRhm_5M4zUX8zEZWBAaWkbXr$~7|Wrrk~6&-bxteJx3eNsd)%S+5>wNvP5NQx`St54k$s_u3&}ZyKe5`$U<9v9Jtic%B+k z)g>BC)_8)Xfjz;rWfPjyQ|bQ#KP=9bs>ibyQWL|_hhWqQ6XxS(%t@uJvb41q`6K0) zEiji>^b{9xk38IyeX7{PS$u`9@X9mhMS>Z-6o}DNj zZlh6mvbjz69a0YY%Dcz3?Z7~yEgIIZk9LF^WXQ`f3zX&&Zw!(%-4RA*(p$m$7Y39X zSTsP4m;Ub$&ztq?BF4K<`~j+1K50bQ%1JWuIu+;dmjkgGkhc$&BrE)1B1f?j7WKC%=K=;?Uy-PLnr5Pi-7@R6b zaeyz+oJ2%QM1K=aspD5bNx*F;MS{5nxgt47gDFwA+L{>z45S0uVHC!GPsqh1>Hw1ud-0p{%%%q2?pUixmhs z#?5n1k>TI#{|k!!nJsA%8YOU%ixD*esO9!H9WNB?uup0K~%v=AgC+m_dKf=Up2PHiZ)SoMaljgCgyI=5tAN#=ICm^;=-x*?dQI z_6T$*&WOV!axMT(F;YXwKlXay+b?R}f+55S-lH7l_2ZE_$UioF?&UAiA7f~3v1T?-8Kxs|Uijl%U;KX?3C4yQWi|i062b15{UV!K;geB+Z3xr( zhv)w@!qKHPic0(Z>Wsly*pD~MlMoHc@}$s1CPd8~I5>Ho=h>2mD< zB-me{Q+;B!D)!$3VSyjx&)WW^-?BQ4T+=M;*>W-EhOfUnkGKt=SedmzA&sY@ltLN^ z*fZW`-v5?U2^Wwo0Vne-*zZ5Xgwe<6xr!sAxY#t`D7*0HRM0+WG*I5#>TV`X-6)uq zeR$>YB0ru|#u!SjA9p-t4C3!#-dO@W$RJks_r{OK=Q!`V%jzFWYo-svyR|#ng)^5G zb%2)>>Oa527$!wuT{esiiUb~l^R+E$b*A%RJ5#IidbR~jJiK5~hZsJguJ2L%BXsGo zK3*8uG+6wKKJOvRX(G1)l(VYNfr0yUNp_^9k%(@--q42I%}W8TUvQ9ym2|~h&D&}7 zovS{)!7YbVn$-Z)wg@;Kj@r1wFIYz}z#*C)CNB(@^-|!THY)o53k&elCD%!@4=P+6 zboiOc#9}Oj-mdq}PasQNbP84H`$8#eu795Z>fQo5-?3k4+x}HP899C^XU!UUB}|eW z68uk$^@-Fo6-|Bp;~)Ycgk1TG0B4S;fCbf(nk9z;hSf+Y)mZ4x?c0B%&SMOw%a(lC zu^@dDfVxyxYMB-DPrEgg?nN3u%6ZfGCT{({v`^rAGsn@7w&+N2zTC)sxN>ikQ|DNJ zgh>+%#|uIJ%wUbuEgEUg7bJMykwHHk=(L6m7?15;U#~Rm>@{T=Dv@Hh>*j|TUOZ)o z1npa3;K8JlmU$9QyxFXbuM`PFj90sh;6TAPDPjOxDW!}ww=633Hqi0_={6;*`6K;H zvjvelA@X{1IDZTMX%0*wZ`BT+Jj!ohUdVNdZv?C>mvDM%@m$}`!-C7A)2FW#+ z{Ui)JYe7aMlQ>@FI#{jj#1lD&D{QL)=0hGZ1JN|WDno{iyh;scI;n;^u_Cme+OO5X zUA&@5(~oUjo37VG#ZbC8Ufl#URKIhD?J_eHE$)w(Bd?pGe{6Jv)J7)ksZ0Ht@iC|C zsP+6k%sa#9npezBk2_dxlfIP$YZCEpXF8In)a6BNi_4ZrC3$_Z zmJ&+W>W+L%m zdD5tSS7s~_9)7`h7{U&c6%bZy@O+EgDGY1=m-<>L69Nn?6~R56aH6} zyc=HLOOXQGKQ8gVH{k{*%wN4q12p-ThfLd30;_ub3bJJ3mL7qgD%JgU_QVaUgGGC8 z^YYnc(ETuFQa7Z#=VP3EmVZOYimS)2%cv0bE#VRpHN-nSQvA#oO>pJwxxV%sQJr6*SAdi3D zryC2D?Lq;STkfbYYFSt8!Lt)1rsEAvvyP^|KFVonLJxVo`A^?T3we3<72TR^zFg&W zc`rfp;~ps6Y3}MU7psCQE19wp!z0PeJm@C*Cmy?NAzX+$WKEN3{!(Tcz3$i1k$=JQ z1Z-+5{;2l*H&ttkPbaL)?!9CVAx!N!)E7m^mTYIsuWj5Z{< zayjmhnw>&OwrDFO#hh2cEpM&;wI4dDpZ!*Lfchwkh-)vs$3$A%6WQQjK{uAIqbZ5i ze)W)No|4PU>RmQxVPnvQf26!SSw};Jo_N8@zyzm^!<_^{MH| zpXzu%90?kL_Bh?;zR9^<~-(`-mF zya(!8sjLmztnDxEe@A?Gn(RwE4cfIDoF}!97tFowVOU9WTPr`5*dC-Vhs4vDtd8@Q z`P*CM6RLW98EEJ?#mEW*zhc{`UhjBY#tJtZxv#-{dXwh)-GHH_tZe#~ zn6?>s@<*QgSs_EljdvL~yAvZk_5BYy)fVowk1gf(n^(KPQzBlb5{g>;n8Qn|Z#@Ah zZd2#5nx=#$B-aZ%3p4Ag{VFoQB5N92Tq=#w4+KkrOw`iwO|%cdZhmTsuNjYqp3-2H zv()Qt5-pf2wD6mGB&oBrMhR~d%AyYlfsWZpDtEOhG~8X2TwUG>fY!TJa;(}){j8m@ zyRlA|1YNG__0Eb{Gz&Lr3UFOS`l?TKtVHj;ctZJH@yJ#vhzABs;@ONCQ17QCtk)-Q zrc7x0I%I~_9>Z0Z<}eaDfW9}aS{Vb$ZbIesygp`*dyVNOn5IAzF`F~=jIs6=>Cg__ zg0#R^dvm(4esaIiGh35>o&y)mz?(TLrDIj;ed^wr>a{6AW<{(2ZY1Rqy2st2%@trVH9(ppMJpF$c!aj^;>E|oe+orUcsSaa(OtkaWD0L_ywz=LpROFy{=12kJ8U~N41bsBlLA=_H7nhldW-#2yK znBCz>`0~Rv@T93>y;d`$T6b>2Ijzb0z$Ozh&KvZliMuWx4D$&3@%e^aL%K^+FJbVm zu}!U5P1d`SlEAEclKC=t_L7=HNrj{2GUdHTrplaIXy$y{Aa5?AoDvil`M471H(hFQa@0Lxk5h|0-KN9n8%7qUg4BZ#bH<5h3g1 zlxm^eWQQv1mDozNQOtKpmceP+XM?^RS}<%g;Q*4M)#@i}o@Lay@xP+^6o%#XKP*{| zLI1bqF^6p0^|C*l=^;{%LwF}0pUtWwLngO<^;<2l+%!G3(v;T^UO3aCAAzjl2Hj~@ z)#@r^?lp6b(rSL$))PX*TOSS`Q^j_nPkFGPB1h8pN# zpL@zI!WG-xJizq4#T4R-FHl$L;E$yhw#lhn-B!m*#4Z1VSVJ*%jj>X8AKvwudJKQEU zxdGp5^R9Mw$OT|?8oCIP_{7J-A3*=1r_nk=4HljmU=HULvK6W^(xu|Yb4%ykQbdA5|AI8-Wy(m9kNLWd;J8Ef9W zx&1X~>A*^}EZAGZ0X`%?>gYF4H&B}lqG60C9IYehx)I2-4B=!|qy^H`Qk>g5Ff#<& z^LB?BBXcCj)F0Dy?`N$QL}5jbM4mX%?%cRL(Y#2G>ye&0-Hsg3M}JwhX~Ed6M6lH&gZF|0Yg{0)F;fgHMAT}x z04;i;n#*L)RT&`o$enli>)R7)>JwN}zZto&KZP+>?F#}qhc)UGDjQTjMLEE1r75z%+HcI%p0CS11klH1-j=^^FbAjh z4IVui>+;E^m$ig3vfTncSKc^sF-LvR#8_-dlKGaFS#g>oN-!!QIEmVvoA{1nC}G-)|FV zi4rH-PJIg)1awo~h6k))TP^@DC+|!K-bX1LGG_9ZDwL1ald%oF^uSw#t)$b-o~~C1 zoZlm%j~%urq{pYzp|ibN;@wN8&RNmz_O!dNNm2FSe?Um2OAZ4~plvXlr^SI_=uCzQbEZla+zcEM zLVJDVR>$!j6`|dQibbr*n6wVo53;3(BF3kSF(|4r==&_D*@7t&U`AQPLTkYk-40OR@pRIGgV7xY=i7vb){jx81d2UVMNmqq~xIkJ)8L zwEuNx-eNAG#pz-gUn%azOZ77v2Y>>@94DCFtlzi>w@FEhO8@ootQB=*a_;v-1v#r9 z#x|ZUXdFHQV>YtG$+FK8Wx%k^HzrtorvA!Pf)*Q&A#U8y9aOsLdDAPb96}9D34U+y zLE9M%hin+;LrWCHqQ)lVMfh=(y*}SF% zj-UAhO`YG<2{q@k!k@uU7M8Q8p8pE~{vI!6VfmDO@mB=;1H`f%I{mBl{QH4a;o*M) zz`w(#Pj71dlH}hlN3Y-d7q|O+kgd`2f03lWL#r$iuYOtV-)qi3{C|yfcFC=Cwo5|1(Ryqxw?*l;@VtCx82T)-MQanJq))!o!t;Ja4qeO-kb7Ek)30X(Ch55 zp~1P6Ac5=2v1f&ify6hnLYGOJS>@1mDWxmp3I$eMh+?(Om~%aU3H9R*H+fpRezTxB z!z((Sc8~vKQtRq7?;$`GkEF`nDt zjS|P1?pw36fg8iF^Ar8)XZn3rT3kS_0&u~>5Qgsi zESc_JokSY<@m;+n?AOuE{Wfs_a+;TUMf3fNi@Xp!k`-@oua-}n@T`x)*>wdU%6v`7 z2M&s`?>n!MsN(mlh%ts=pmB1v-RPoo1=5b>3*NRxi8VsZEc&jQstMD2(r1DcMkQw@ z4TjyroW!oXer2tJ{`5bm1kN~j%~>cp0HBDmAGd#}XU^mK@Pk1Ky8;-Xs{HtUIy8wi z>yo7^JjLVNL>D>&gh=+Sv^$OIK#i2D%ok$#ue9#LJZImEWmS#6o;{PiQ6%UT+^|ze zIr}oMK-aT|-f52gdh)yai7)4}xE*V{tCmD~QH{5DrzS7VYJ)_vrengttWnDLyxGCR zj&Zg=y<73aQx0`7~;_ZMiQ! zcc>0W_kB$fx<(Rr6>7CioBt-Hbkm}5aBhNaxHF$wIb{e)Gy6rd7Ij}PPq9aq6;cRr zCD}lN5%rnE&XY*lH*0>sfsN+nieYTEdHWQd9KfFQX^t^(s-`Ghbj$fcf3 zuI83^PIkzV_{HRgCDTN&=Kw4cSubSKN{aQ{{F7(9iO$boX-0M-*a|ww6_n>YE`U*P z7E(9wC_gfPls(64cS##`Rand3TA@@ESuh`yfbY{8_WkMXGdm$5jla$rZIIxr-Jhu6 zFbnnosp+ryeIE7|!lW0UkLEXu%{o^ic^$h97fiYahbV&MhL>0$X!U=rw$JdH5no>% zimj5+_V-Lu+EmUNQfTj_*zxkzNIVf#)HYDWW2HmEK9Kn}0cl4oo)xnuaJnkBcafaH z)A_y#e`LITu5X^(zas#v-S-M})n(U{OMd}>2T?y;*Td*7m0W)fmUjHCChhj6>a#6) zdF%fANd0nuTj%Fq+TeVCEzP#0S{iRuQQZCtL#QXluSt%|4@xV~ean&yXC!#ooLgiQ zccTfMoXgF9avf*P(N0%YUx-YX#Ac@Tn4a=jc|UyENrwDSjq48KHB!m>%fy7gTxRET zwd))O?b~ZzjAgw19XxHbnc>#xAFjH=NV$^w*5!bxn5up^HT;Weyd$7K{uXNv>=k%mOD*M^~ z_#61QYg{x3fY@w8+1IGijnVDSb;rnL2!6fur;24_R}0L-4>E5V%}>+E2p{wF6mrB{ z4a?K)`+Bjm!y{;06U^vvaEDPHY5oXktj3P2?`>TZS3~gk8FKtA0RCDVZ1?C9J+3?b zI8w+;w9?1K%>+YyscD{33Q>ZyWtZl_j zBkFzUE9_L{)qtTq_Ls7cP8TK549M0E^|@wcnMX}B)nT_CeHE*zRwEGx^$gSmas%ma z#B@JEBfCB@^qYikL$9zS4C`@9N^fJhen#T0j{@T)5iOZh|5()vuh+KV;_^?AkhiSr zzV(f`h4CCO=^iHaSt&T($Ee`X%2%q|stfkgMjWO(K9#>gx^`OE-*_#x`SIIIq!Ko! zbR+l|7mJ(BNd7Pv-2yv#Iq{$cS37p&H1l2sY8fM4FCg^vL;$+9w{c7y;CG_{>x|lFjP*SyFyV^mBROHfBWw46>XqsB%Qn}y#=4YdnI@KIj{ zCUv#oN}?0I559Z;9E{1o5yr&C?<|J+w~)Mai^e@Kex7;6G8yMtobZBUp=*on16`3B z&IJhV8zUQ+bR*CbHBH8M@)}$+wtX>Gnr)yrdhppd!P0b{-T32C%kf#NAdexeAP=48 z_v`FO7575d%mlC54JpyD>`|~VXv17zuk3l(6MfapUYuQrIXS<(mvlBO^j3jPBF7sg z=1IyoEi21Bl3C%-Eas~r7Fiw#;r5S$Ps1o_FPYQwSY=+o&z*J9Cqpq#V8aCE_3Uh! zkQ3GI^~(xdbe(2X(spPy)MfpN`I2fur?7;;72{>@;$L;tr>8HN<-o<)jw+czK^0f?dBM$8hB5>M|F;}E5BgR0{aau>w4d}G6l!p$ez@Jc7-A5~#Ixt`v(z`QKWuNIJ$J>QgRY2JVSb3yR)j&BVI{s{#}(hJOZ6> zf3_>!1p7^>S5V(5iaWNux!2de=S9}5ZeTxbUDfQjN5t)UL>v2K16AWY%@Y~eeN6A~ z*YASSXH8~6nsEhWe}u)Aqkc#^(sDOfolISK`Nqgj#;VtORyge{2Fyw^=E6obF`wku z@3Z|H`Yz{m3y$IJY-y!jJx9^S3Y}!Wcc2VFn9OT`kL^$7Pw=_*$eX$t_bSe>u$!`$ zoYxO3VJIH^O^YFumZ3+Jp7Tff+ZL^p_!|UY%7$_>c8=^zKdJg6l-|@Ij!u}LxC%)1 z+nK-boSg*aa;h%#5K2)NvmVhn474XHDygIZ`Ob<`PgCutN)N*OtWk;7cx};e^mmo} z{IWRS)G|5u=>V(t6ln*rbOj5iygPKg1%@FS;8T7Kvirl;>VMI~Lgi-$Jh?IT9PffL z=7ZBqBl>2-+NmLln;kfIpGl#{Pm2S-(mm?Q4^X$P-IYxX7I zfOCWw(0%9c(2k-fOf&f*#b>76Qv&_5%-3BeeR3H$*5|_;6sIkOpY*ASrx+3}5UB)h zK(e`(A?sGQ@fm~6G|pp8bc_jwo;ldr{(<~)_sz@YB3pEZ|7Y_Lc8_ij3W4aBN+V0A z%-6`LUQtUk9PbXPdtRQ^T;ztRZKa#uiHd2Gb0OyXw(`%;P1w<`sWUfzOWBv{k1n%^ zGXBX@)s_&5-!bbC|57wN*LS>i?kFun?%5}ilZu?Y*INbCuewen0M9Ey^5XB$U&_GV z$UL5SJVpwB$WDL%;Jd3Nx&2+;bGf>5=XTzuhm{#`PNvzuEcfR_x9tOpW)Jdc`+Ooorr)Vg;q+x_*k%R#*^Ba%erI*nkGjsaF)E!Ia`$Vrh zC?8Pq(Ya*tiAI3+^mq|>H=^tgt&{s0oay^N9gFL4t~>jzEY?*xLn=y`Vd~nZ&E`d1kY-S7)rGCemb_0!c#i-t#r81jQbu|{ z5O9>W4g$QO^TQ>H1jEJVzQp*6cz2xCh)QXDC%7KqM>XH1Iu zt^QkXavvIwGd1^tXi-Cb-q&$d+%K@SGf>!%)S)kacUC)Ad?x^MhL-6~d#vT)$Y-NcgnQpFxcw@q) zGlv`yE{hXlzWXu$v$bEBOuyiVP}kbY9%ck>tldhLD($oDd|#o^LUYm-%+_SdO4!&V zE;gcn^o<%0^)0Af;x5J9Ijy>x5a*UD`lPI`(7U}Bsp+Sx?t(XV%t$Vep)7v}%PM@iAwLhc(d!zMJW~Jz&iLmHvF8W}nM-}UrYFCJL-T5(S zj!LXn^{hO&oP4cj7kDN~U6NAk7PMTkky7Bex;JyYw-zrlLyQrBINHaJmcEhFZ8!J4 zu7dK~K*{Isq-0u>VM6&x`t+7}(aHY!`0nlNL9PhET`*G{-|tH^UVtkmtNsu2-aD+R z?Q0j^>Q;0kU`IfRovjEcRa&AO6_uuy$ceREC%)6KB%)s31EU`VOkM)ba)g2*dpZol)_ zqWDJPZ`))Bxv}rbLHPE18>2y4^;VWCKx%oK4h=%ZK`ZPMmN*+E_Qk>Y7=;D>zxg=?zq@Zd*>> zsxs%9aLyCcp>A{h32^_aKmq2>(Ua#nkdG#^rZOjT+dpo%j$A(K_Ht{9@BUJlH;P+xoS*)R4d&fhU1i-`A<7XCWa9`0BphT0)|1`{f;gHQ&&G z#D$NYck1j=-)?OLe4+;Mr)oqFa>CuE9*1q2)Lo?>d`}0oGUGzUi1DscX=!eodVN%3 zF%a_r{10isfBkYBKl?#8P9FomeIYb`Jx_o2;HKD9$IvWwjO?zh17=I!h5H@d(j@C! zS7z=}W%{}dSu5k0O+AcWxy!a;ePHQkwyCd;^wRx0Rw!+ayUb^xGk!71+<8@hl4r|K zoJgp%k`jdL^v2!zwX$`XJ{(>tD7|$al%?yCK$VS64JxX_B!!b}X&&4foD+8R21t`# z|JvVl8;0tEDX$k5x1_^&`)-s1T*a@h;9-DrVbRGk!ocN2mMI^{ zdc%Jc6&6_vINe;1m(kp^Vc|W+O3{%~&wE{U`M$x76kp0?xGVo1Rc5q~*hw3)`9O@P zkSr8^(eh#L!?f-T?GZ;OEAvFY*k-Ivv(5=OuE|#$pG>W?%)~k4VR&^bbBl*UL!H)~ z&9*|OChhXf$dLi-9R-L`YBC1e*~^W2Yq^c#MfqefuE{2O3CuQbRf_nz?FdlyYac5Q z>ZJ&VOd^A^dmImTSoF!fGp`ADHexo2BjnwW3*N07E==NH8DMazM#9DTkd*46O|eRS z7_^F4w9@I&R-SRm&-AoiU%DE!;arkyidc1DxhQ@pLH#d9xCL3!HgGO#J$w~`+0{-*w z5EKsWTu-C4N?Ioc`bK8(1}ZB<01mL%HlV_0b=uMP(opQPU~tffyO0KD(EONWO4rtW zr*VRd*K6F#p#EA1(izk7NLt$6jY+L9_1l-DnL2M7{jvKTtUV%Mhh!6rG8G~a=<3^0a8LtS3 z;{gp5VwY95zff{=_AvwjN}VDd!S!ZousIb!rvx!lDdcf2oOJ)H5Bvp#p6|Pe4H-ef z%@nh^&*sl|mL7A4-i6FsgH~`S(z8h|>gq~ZHl2&1CMYd~A7cBV$jYdE@FpQ5iBhng zpz0)~4IpIaO>YjnHZ-O9`G3VaQyr2d>kY39ZXKX_Rxw=#_QOr>EM-dhu*kU&j1RA( ze{fOYF;@5vJZ>`DwW`yT0y+A=1WmX#rXd)A?_Dr{)9xmrVv(#xDO7Xb=peUWUNh#7 z_S@Pxu60#9i`blwRPy0dy$<74n>!S6y%Pe`gXuIOqu=0yK2weN-8_?(R_=@hw z*p|90L+O9S>IhAZFDiW7-<2cjr_d6s^lSEkm`CoMIkax`w zu<(Ui$60U6#m>Or2F6sluTj0ZG&)YxD&~c+D^`72efZ^|FWo494e)IH0T1N$V&krn z+1%D^YQh_%fh~-OosRjk@JEs|iaCu#Un^gzon*^q)HOIQW}NHSYMeS_hbpJ0prMw3 zz?RWRv{VPAd3Eb<6s@y_`h-t)KaY^gOuVRGb{>t(mEGzdTLci>oJ3z8&UQ1&*8@Z9 zxrltmcIa8_F>-Fmwl(B$q4qq)V7Ml8-|;BJ&suX5N@FZzZNUpDeKJ(CH|M>7d+59M zkY5Hrlp4kIoi3GI3fxHh#}~g)Km|VHD0mk0^qB6jxNNao@edY4eWd3kJg?f~x(6>& zwCj~hNpR*TcRZ6^>c?t0r*AYIQsdPZ^=ck#?#4e|7mhigW!3;FS!TM4W%bsAi-QLVqP)u(AzV+?7o+#(p z^jlis7+lYHa0f|`tTPv^+DXx|$|it-2U2Vd6saC*?^io+s($qsHF_VTk7bfZgqvR&whgQFe}Sa=R~CRm}YS+eM7PemRV z_wzi9?u_fP$4{s6ix8=Rp)>CrsAB6CcbuMOh4!#>Fh9*DwC&A$5PK{0)KjvL&+{fy?sm~d#m=*UYg3>_f4zeD_Pi-q@*3Z-hGQEUq ze(e5&v3vI{?0SV!pl_crOwAFKTdMBfPA2MQUtcrV7;7NASHhhcwqa)5C{{S_an@J; zQ|YwE`%3uA>$vyfk*Q==1n4xx3Z|)6uLM&xU*>yOSmM`-nP}ZwP-RFvx#asn&7ZlK z%Uq4ls@mB+R1i&lJLa(V81eOO+_s)jhQ|H+{nar8SaU&8G!S*Q)#R2%y5Jv+y!*NB zuaimr>Ya0BZN5dc%hjTNf5fN1R0rulu$@yIFtp{QoTD+E%1Et3{8Hb~$*hLw&CHvV zzJc`kCxZ_g@2w2194VNrv9Z_1jOH!NHG~{kIHtR<_KP*Z7@epN@&f_tA6k!q_}~|F z@T$r?+2dPfFY%kfO)jTu!}>XVS+Ct5PS@b_?zfLTyy(g}P}bRaAwI{5TvV0N>GX%2 z+KAzAzA5)(qMU>wZj|cwFSZllU#iO-P?f$*ef+1~m_*7(GvCXp!FPKeCF7f2=P6rH z&dQ$CEXIv71;I&bcKrS8E|C4-xl?Dh5})KYfZQ0jFfv;i`2#AP`p1(XPoQM|ryA^jN_SyXEr~ME5+l;8xDFvlNQgF{kpdoCr7m z)glXUyuQagJ=ryY-cD8-Rd(IXq?hO4r;ryk_0?`5W1(w8?4{SFQ?X89))Y4DqmGKb zE7VI+-y7er943^_AStjkKr{6=lx)u5npG7ONdf`$zj|l?(T!T;CjWU35TzxzyRcky$8>X7t#Fv%%UOYOwjJhWGjo=qn8*5 zoTBiuFK(vmXJIh)J`LvhSV$}YBY3z>Ut{dCT%)Tu{vJpW@!R6nH%YnWtGfl z9l;}q2`Gi>LK?$$=2YF;1nd_oH|)HcvK2Dst45F)e*apH%}mDXB#9~maEJ$-@;I^_ zSJde8E@oA$rgbd;5dkwb(E)E;js3Wi%)cIZWYG_m!sKj99o0GMn_fs{7)-={NEKa}cXZG`^;w zEa>yk4>oe9v;yChsbVs$s^OO@Zz)zI)Z%YtZ=efk;qN%8yr8{0-%8mEW!9+JAWo;Y z{#4K{6z#!X_89Kt>UE|?Y~{O|xj^0K?Z>&|It?u&)O3HH2gx1VT~==c8o08RVdF#P zlH}Gl!5qJ5P2ui)I8;t|#F9$r_ch0dZH9T9=`TJpm)ESmrraO)v+IvUqCJM7CqGeo z&IJ5Kj}GKyf5?!M$do7%*X7OWyj|U5>My!HaW}wgc9N{Ea6Y4QY$*^Yh#Oqc;dh>9 zg#yvj7YECRsQz_BakUWqf>LmknumS9_SA;zHQWjgoY5o(_Ui%i7;iQKago%*1w;<$Gbnj*ZvVYQKh~!@JJI(np`(eT+YNzqD{RZ{Vfl zuftF+U5}B%?~|uhk(YvBO=IsT$DTtIp*aN5(Jn6DcUDzau6L1Hl^7b*=~ddPg7e|M z?PfNlV>t!9yBD$kmpn%FOy9xL-sFX+NG!o<7qid@ZVd0bMMA+V83Ah9o&1Y1!Ao3} zuygPZ|GJrnAdgeWJaDu=zI)C1SulDoR0l$S`{NnOkgqt2|k4~stt-mDv@jM0}BD|#XT;jD*hfo=Xdx0=jZb;hEyYQNox z4M~uRGrAG}fb^;a_Bb8aKQrOGdTK)_|++l9d-HI zV*@FpLC4zRv=pgx>8Uj~0UPSOe&q2# zy?ItCiSR;h8xoUmlo~!%*#3HJ-r!4 zU$pA;_wxbdIB-7ZPyg3!_5-8&^Z4I_D>xmv)NL`04Z<{haFzL+8+V|H+!G-s)yD!X zcKgD{;RQ&TZ301%-LNK>_?xz5`^MRTp{+G>y4nCR*Z#f@?C#>fe{F4r$>rF~zd-}# zuA<)&$wyXWHvf$`X_>Flx?u3bZ*TgCmh?GdPw8*<|7ZU7=+U9lCUI-19k1hoUDL|` zOQpF=x)H)Z5>%31OBQ{xs0e%hPxsbnjs~?%2K)R`Zo|(de;LK)&9)N$MNW;m!&~-{ z!wM^MF*AVA_gm>W+p<$u1{9y5V1&SKQ(Hfe=O69S%((WH$UbRZTSK{N&I)wIvt+ZQ!fKL66#+7E?X4^!&uT&d3eJglCP%{{8)I zb8$cKr%vFuY(Q%DL;lz^EsdI^sm%{=q7QncO+>V0c}uLFZ9aWZaQ&abN9fza#qYK@ zFOS`UylrB$B4=7uFbyjsHRQf8N<{082xhEgApa*!1C|>yw~~Cw^U1n)^#*_>2V~7c z0gl+4&0|v5vZ{7RbjJf@ZUU;uTDL_rTT|UyYpzFLTuE5llyWy(t{i;m7baj`@zS55|ejzV?0TZo}|2f8Xjh>n(y#GE#ZL^x@;^@LqfFfd_lYY*iD$0iT z_zxTB`VINNhUV=By2H^Wh>RabY0hl{&OQQc=rxM~Cg4!hKa>6uYg{qwGE)Y>>8r(;*f)3cF` z>mZl336iwBT?+j69^&wKdFMkz8_$N6{_`TmjSAXY-2m3Kk~d#0dz|}(;jriiY2&xZ zY%B-h1-fhPnP?N0Zt9B(Rg8b?ZbHKy#8N&e^9Fuc$a-iqU(bAQI{n99%apz4X-6X) z=KPNjG>JZ!f1*joP{VFDDXK;en57y{2L}`x>{FtW1mchhMSy%8QA*(qt4`bEu+3eX+c>eW7VzZf4>_nf+bOOsmt6y4KKMnKNX2k(rbjg4J=WFh zLz>D4B!b~164s^mPWQ!iE%ss#L}B-WD{&mGmXw{YCW~0q2pZq13e_s5rAL^+YdeI? zOB%eVdNENKS{Mw&jl;|++n6U*t_J5M z_HIm{vxEPdj#&8pOvLxZb)n!nAyuKkC!R#32k09f@SeD@U4p_W{ivYvp}rH@J{Z7=&k0WHC?AMW#lr9?^j7`|_9 zQ06_qx#mSgGdy)$vPr_WLfptP6KbLWA$ViBQb_C;^clK`zH2&ZC|t3bW-E(tWCOxh zl+!ZOqBubETS=mXrI8$EByE8F@ax$!6~F8=)L1nxM9dVp&D1$ndQNHJ1(C~NU=8I~ zw6{kJJN8>iYo&Z>exT8?{2tUnv=qLM@?Mp!SKGLxeQ$6tss_ zBBo|Wt35)?#sez&yje%VTz`qifOI$hngxHcA5YS=89XO#-N?4Jfx|0>lRdo3o4qgv z=u3qjLp!k1$@0bQQ#PH~JjK^%7Qm+?XT+!ZnE}~`wKr4c)Ts&)HNtyC_;@z+RjXc5 zFRN^2x}qq{AvGO&_O5ApD^rFRX_IvZigfdK<<}9XO>-LU%WI1O zeV0?}iV131^`*yy_MM*5sE(}Ng&o(Z3hD~^vCLq8Gp8~FkQ3Trtxh;ux3u9CJb^r$ z4tNfenNG`?EO}p3SA`m(F@se2=<^3RBdnscuJ6EhgF5F8u7Y3a2WsgVh;3OFOKi|! zsuY`$y4TN%l($l+>&SWBFpDQO<+{TetB=SHzgKqX49byK#(>?-az=yLlkl=pAX6|^ zoC4ifnxYPpD52I(#;nX8(QVH<7RtYw&Z|nIy|`=R*`v*)#m4wn@ar_Y(azpOMuaOF zmHFaQxS+qtAIU&*g?MKrVZ5fMW73KzCNpHa!T zaSX31b!;S=L9v0!j)H-lPTk%OtYgHNWDU>p-}Lw-gGz7eCcGe9Koc%Ho}nWJ_vUQb z#py^UKVD;U#-UrtuM1!^(mCljIN6citNvmUuKV%^t5G6PvM4!lutqm+*~Up=r5Uwa zHg!^~_Do&vhA1DY!63&*m0`A(#7KjZ->E=f7C-47JFYxSHp!RdyZSGtwzuTXwRm*+ zslo))MR6tWD_q&>LVMEaV^NK^9r+Wwps5gLw;u%!bBOv-&LDHL!ZI6NNK>l*F);I# z#W{3+{p180WU0n&DqVy!^m{CqE zWY_8QeqlZhT9pfNa%K;)RAVXWywE?c#uW$UG}@629xb7f8FhJSr-ea1 ztaWgyhG;E)t~WzmM(p_PS#XX10XF?H)5L9I5u{BV4c}lN#Rsh(9Ik;84#jt*X~J@a zv&G)s=QL&>eOQ@!<=X!t$SgbS>~I%y;!A3JpfpS=i5HvFW_}Fmp3vUKedE_P{=XhskQ+Td$Qrd}rBAtJSVnSno5@zz7^8#;Ap)_ivpSZIrXCQ{*_kldP5=o4$}lC=IhRkisz%v3&uxc zWRzI1`(2e@Lcq(f?T~kKOh08vW~ZHkA-T7Cb6K;8-VDG@=vlxkD%m>+d6Wodhei>z z1Z_#~5>tHtw7{e&5hfq3kR0-rmSmnbpN$HJV|p7c)hgIR&WXS^$FYPL^vvp}S0=bL za2c$0gim4PEszs4UX6UqKiq0(quwJ;E#%Kpvlge8U)7DZr z;>N2acG9bMeCS;*mP@ds3@m~1{3bORryeorI%pK?#5o95XXFv#_t$!A^hvIP0^0IF$^lQ2iwRrmAVSB-~_YVSAtTvc0wBIjfJpDsAf{AR0eW?B27 zU_pPrI!B?@4}C^g2oxwNh z>HPVpfE(W(cj0B%+qb6Tmr$fam}~khk@hTZhi0}y#<`Q$Cui#ie7BqfTX8!3= zh1|*W&iXTwfuDMv&oUfD0jHUVRW<-rTa&Jux?0ZGH8(UVl{O#0@VS`q0;=GFeJQZaI}JOe{6p8^S7nceXUMpA%ksu%Vb!OULfJWaX+wS1wW?7px}N4q zsJ(pPGOhNAjfbcQJTm468U|xJ>*0utU+Gg=93|D!i&}R^4tzK%34Sjc4d1iYJv$U} zT$-TCiFNi@A2PW^v57Gj6kTQi`nzczAZ4cycX8cQ`ruiUuD(fk7&kl!F>u3!fmNKz z!i#IVJwTS3oUGAMI;LAMkl15Xx%TnM03;iEPJeAYEJ=>U9z!7l(WPGXHjE}2xVGXW@K%Vrgfoy!*pSu}jTr$9Ij1VH5!vr*hh>kT z5EYj&b?h3P8E^=#OU#%$uYV;!Fl7!agB&mQ=NPwRGYQ_ySVpK~e1d3DA?ahJNnp9t zo zcyx%3O{Vd)?2hPe2lvtSLKN1*WJD4ztFvj}T&G#oQFU2p z;N?|2H+(}AypY$hH>V!efnFQ+7Vj>F1$yfdViP=7=`Ob|`sv42p<8Ynm2=LAqF{=o zWx|UDh*3E*b6bhOC$@K0aHOBgw=tl7Z}kF6=?xne-)k+m7&fBY%t54s#bXNOPDacW z?ZD`6&eKKn1U~r|UfX_V<&;2^8KNccFW!+D#nP+uj&>A3_cCf1J8fM3W)lNGsW5IK zPUj9&rk}zmxH3$n5soq^7Utd+Im|2~FZsy)ue9dp5(1A2(ikWUQCrA-54y#9;=NzH z=v(Zz$o|rczdOe<7z_%m{fP|Zqz!aKGe{yPfvV_a=Dp5i#;QM8>msI09%#JUccX1o zk>*8*kqa69ock5UE%FEON0{Q-JR0dHEOSohb>HtDY8cKSfA;dXE;{gLV+UTusYm-K zZS{wBu#Z_JTcQwO{s4o{$ztPO2D=FGrZ`1$%WU52!gRTk6RUP1Bh*++c#21ATds7m z8nx!;*{GACNDX_U=VH>kc74f|CPYP;h=8<}{u;gz69hPRl7AyvJmY6_a)q?@*h@GqB zsE+Ps*#`pm)H>a9ouEfKj_dV{-GR^VT05kYcUEy|OioWg|lpR0Wn> zm_+>ruIO0**3~S$Pm@0_Xkb?{zR0wu@eWu!O*TsfdYx6N*?E~>6xpkH2OQXAIX#}v z=!R5QFLd#)Zb2Hwyk$74yC&6ZtDyaZ)AJqNzH0aDt!7c&T0u7`~`%_(km@9Y}3jO`3I1-p0%x9Zup_y5()nl7vBI-T^WSXDrgf%c2&Q0kr*~n z9G>l@mGgkkNQg}-Ujo;*!nXerJta9W_$oOsm5I$Tu(oNe>xn}9&3Ady+CIQEWcQ%` z6?GpKkK_4`orqu6y8%U8EiJX{FUYdcx1V99^A+2+^0m)PWdsiaUOKz67CQbx-^rN~ z*%GhYsSOd~4Y{9_+5^8ZtTbg?B9?i>(DpLmeOWZ`!#ERVrI)w1M&Q@FW*f()-paP$ z-?b|h_Hf`<_-X>EV@?@yy*%T9YNm5slL9m?N_5lCo%EhfY@Rn^^+_g9TNF<8c0NAm znaQ&;dJEfYr0$w8Ir;%JFLZEQ=vz<7eUi&;cU-^HA~DmsT~xk)PF zN|#Xv)EOE=i2ON-PRt$61-u(DMNN)|AoT?ybTVxNz z!ygV*`sCoCQr$n7EJJp5RXF6hRAgZMLqW7cU|AC{t=-g=0qLCv%9uAA4J9mx^Wv(=fr5$=bfFj0IEw;53HMYtDwx4pgFS5QVt zBy7>K^&P!mGNrYh#961&V|;C^R3bndnsX}#tVGOkU;o?_`4QxF6|Ozbsm^h<(5EeE zb#{}THv1-ieo@N>e%79300N{=vkWFVC!6P!teul_{C>@fRVGp@2v(D3BjzNTAR;wSm38{MwysIg$}( zMO8?FWB^DJKJR;CEE#S%E3g4r5iZ|!p0!RWe0WrP5 zwk!Z42!2=G@Z8wVaz8*1`^MatCO{{@KFS6ty2>L$uYhcsis;KN$S|KQ;S!PDwqir- zU~P$+&W+jdQrm}ZXlijhJUjM2;%+VsP|ku&zg0tiU)s%HI45PoQF)u{81OFq=ii-I z{i%4H?40_;II!rKZ0EOKVce~n4Pm_NJTa}s4M>-R&W?y>>8fTqnRU&MqtN?m)}#FS zl@e09uB=eg6XH+$u=X)CkO5Q@?0N}l6z9l`2GAG-gX!|#E3&_|J3-L?%xCJ>t<1O? zl)8@Ah53b1^#OnJZ-GY^UX$gzk@pX!h3d=ZFAJ<_kBOx8-yhI#!S{U})>xq(3xJcr zr=jwJ*-=ae;Veu#M6J)jL;aN`I1+N0Pp6A*-j(K_dBWLPOa|FjeN z@s&tc)=JWP&%QAoD}qHjG6r#H)e#SDA5{905yN$%*>R#Vb|t55-ERzI)Sx#2b|Av3 zcFsg1t=Cd*77IAPN!F*?Ml{P0C$0SG`F$v5d`@U$wzO1}OHVfln&N_O)M}R`XBf}* z38ywPr_3m8muZW4PCH-U{{AD z`F94cS$Sq)P!FgiN#-4l-%GhF=u7Ch&gr^!$YF1iuhtaDdy=(cYE!B~m~T3we_%D? zSCKppahbE!k29aGnB(YnIh93xXaax^nv6AynpDl?M41Q3Xtz@s5P9cxUFA27r4}^w zpjV#Fu}$+PEYizi_ZZ^&Z*wg0^XP7H`XO}?CjdyIhUFV!ou*jK{+2QPVRb(Df+kRE zlgh-U!As!HAVi33a8H9F&~Y=OXJLR@pBFS^$~OPiwWm?iSqIRcA61CgMO}Z+|05ft z{X2Zx(lTvj)w@^BPt`kuO4+y?oJ|4)9wB=+ir04x`5HsJH5m0%d>Mh zAltf8?wG)g_Y~fye~GN{M*CcdBg9DvQ3H8!%{>4sI^M4NaX)!c)L&rX zfz?cGRM3JxePnep6-cbeN@UBlUDg{)8B-&}N)8*=JJs#KHU^a;#C`Pij3D1&$5J~& zf0hb}XZ4j1rTT3)7e%od0)#gok0?J&v{=H<9@kD-!zE6^A03)EJV}7h-enJMHnJFF1_>IYvrvw+O3FG1 zQ8T)tX-By#jR<5|V_f`9=jt&uWP~VdlB0e_jWiK5ld}z4r>?IP!jBLYmLd>#>JoW` z7PNtZ+d@*mXBI9mBm+<&64g1rwIWyp8yk?L*qHx_4T=Fb)fhB5@BEE1W~F00_;Sz* ztI{faeDO2Lo}tRPQ%vm$#8d1CF7tb+XJv9N)w;l7;;ClA57ywqs}S*Qm~deDNNhR-?% zN%U^gY-n*j?|9ZPCLKAJ1bMZgf4uIEFgSQZWP9vv)<)(uBLs*VEC{O??J6Ossgeg_ zO~N;hS;DKIO~4|!+__^-6$y-_pX(qQY6c+6TD{ICfKeYr+Z!mN;u&=|Gu}UC zIlE9+g2n5B@dfwsVt$CC2fk==cByGgjCsXd+Wg9zn44QfUC?A_vWugy_lMt! z8H-?{T163EqAQKZDk^##Y1>NrEA)tSioA9JE6#!*g{6Z!c(0>;SHtA;AH5O>c~gS% zhP)Si6EGaWZ-!T$q8fqbmg;s8uJ#6iK>WRO^;*TSN)gcLYMJ^ZOz}N8Y7lRC@&sgP z^_3;`sB86TuwXOYR1`D(ochYd*)%#tSl-@_*O9YG(IsXD?Hu8au}c)*rq8j$p+IXx zZ6!Y-5?ktN52Z{^gi+A0OEuR5@!*K&EN^0Dvty-_1HqTQg;=BM)al*-WBVZ@!BO1t zAPCqLVHdo@bt=?{n!v%*Rtj)&b2W9I{)oH7BA67>k=OTJr{eiwdmscNHa9gSniwyc`qFN zwfEpSeV+s18TOVQ#bW+-40oD~OF+fN@>d_cDV~pn+5d=RBKpfg_ER>EODtnkZF&M;rbRb#xV6?0ni$J#rCaz-sqV`4a zWS(3(Ed5K!V21{J<5!(7p`h^H zpSX<}I-v_6dRFGYx?`8`5+&RxKj01aYufup0(>|aavym9{$JbuoH158O0q$Lj1qudeavM+5pcD`SPKAfKxxuP9lN*q zUmzjC?o{RcV0`7;_lfTkc9+grtFNxE_fI`@EkWA<4Oa1<{sC6$`~g<^H=q0gRw+i@ z7_9$kRmJ+5t&@>ohuSJ|y>XAft``dZ^Lk+5dcCIqY-Vl?{71xhNcJBb!T%MYo&RqS z;?YG=X=u}N-2?+Cup#T0@TeGFU*aX6pBA%T66QuUP(#1#Oh|e6=>E{>6KkEi>b1vb zhfe7C{;k+M=1@)^1r&N~Lgrj+%F59v4FGwg*PtVJ3pqG^ zCntND325tHS_uEQ?p7~RA{kn?JprfW6c8J={=Q^d!V;}UO~Yv$G{!s`eB#YY1sR4n znyqXZyXbX(-w|7LKr4Eapbp9D;_t9-8Tf(Ya!~y@g`xwEgUB9jF+{W)`3(QgLw@Aq zV(K+3i`3qx3VTwo5fm)^=2|(99&c%$FMn$D$Kq?nKlYUBymG0LIBx5!48U{%1xehA ze{ercpgY@*JB<+&zRls|6kT(~S=J%BDsTirjNp~R{R=5BA>wUz`t)CTi}vGF)K?0! zelPRe4e>4^i$~=&-HWn3W)x3D(yH{)WNqi3fXPe4?*_(44<~szoq$FeDj`RbY}(WA z2!c8tnEV{*+M6ht(5_!lH4O?z`BndA%nnpqhRd-7JY}9yduuXlNUb*528~@20N?`MtxT(C2v(V z+*7tzQ^v5N^Q3Oy2SW|!gOhN2=2$8VI~<`s6Y`srzd=x^-arRVyF9brER<43N%u2t z=Eu%2^xC*1KeqtE8e?Hmwn{ObW5*^sHE^r?VP;^#xZOu{3f%}EHW*@f|EhJG> z8FbauvU;7iw{phjwdVsl6pw7P3jR!>9B+DV<-;{pd$E&=8>7-;I(DijQ6+WT) zWu0U|{l6{7S~{I@CHW+mDdy7@`gNjwT1^A`hTkUWEQuydF9-HjcS=;wKdqILh4@Pn=d_{kM}D->%VJ&*-<`vzcXnqAU*!DWlYr(H)Dl` z^8@Di_=)p3I@PGl3K$CuBcGpA%c*AmXBH)#43sTmQ_X*St5tgaG2TaStM5b;YE-V~ zDLkj2qT`!6*Uqo2GPhH~zIULyP_M?3lE+fxBc@YLH#c<&ha*}klRn->W}ZXaO6L&E zBUf;~rLt#rHWMFn3PZSb6iJpN;hS0@IHuZS7t=$p_VyA?ELL zq-^h3ea3wA7cJY67Sc4a9IRvD+#_WTQ~iqJLQf=dPq3SimkJpOuyt@Uj6vP zMyD#u%N(j*%=@an2k_hGnWX$`RpGAUk5O`$Nkav}j=bvDI^%&5csB!+vZz4tAt0YJ zW>S(=G|AXUU`Cn~7~<~{;gS=hN&&I7`~}xLWpMEnNXFouLRr>8U)`7(q<VGW2+N;8E^SKY+^5&6-{?^JvJHf6Y__%Mp#0w-TYvx$C-WaCKfZzP! z&<%dCzQ`->U7rLBv5ydZ>3>pqV$vTC7Z zj12l-Cnj5ZSHEWk!Hjqu_iq2l<)&paa}9F=X@$o2CckGU4y*Gtf+2X0_nDj=vML0M zBz6dn)l0)NNF@)EvOX~e$nx@Z{_%`C9$aZur^@_VS_ap~l0GEE$#qQsf!j6u^&iiD z5Wsa7Pdq5Qp{>zmz=;Td>-wt85^h%hO=Dp!_uAFrT7l+Q!&Gf?vx;KqleY5*8=X)3 zLXJwT8O)P~%$0-?mTkylX-N0hT=U0+9wA-8+x%)rq9y|e>$g5r^Am#X`<$So`Z8M%g0K; zJj&j6Oy9_n(7>w%_(pyR0&@R1%A97i$Z1b0-#5c)97@nNs_2cc;l|(+g6$NcedIV^ z9S?rS#s=r4F+&+V!|=~cxyyL%O)kxCDxP}50L1^E4MqI32!6aEWqn82tZZ*_!Cm(m z2J?fd=bX%i6VRuYzjdID#BjW;ov>?wYTiEwBpKKd9{R9G`bMl(&dYZg@7mfsDQbsK zpc+PgrD{tb?|r2J9Y0)Rt(xj&k5SHF`RZ9(oI>g_UvFEa!zA3{+sT5_uBKkxWkVDtVOX3bfOsKk zh#=qoDfQ9`+9+JU*n1eIsd0D&!PhKPxuyR)XNOay}~!` z&K#R5a(2$FrH!5q2rqY@TR8zgtxIr7{pzBvF_3*MkMEwkM$S=z>^L)^(N(Q4$p3!u zm+EkmFpvfeXCmNEAE*JF-gGIoH)bS0{1+}-z6KiO0J75gvqcBD^q=&{{yixSZ8vkoN6Fn1FXi<;K7B{rLzc<@Se_sK^ZhqK`mkUJYc#yxdd5zT0aJWc z#wcu8+?z-|;mwE&NdvZAw{G0{VZk5w zZ`~M8^1lCj=nuWZ%@Wjw*CGj-z2$#>cvR;m2F;PT$GqD#@qz=fSf`%Jw^d8>!?yxi3Ohs;}oy$_b%k7vK2NU#ER` zw;LdhDEyyci2Tndn~wldZA$|8byUdAmz58NO>sls4{`>YWapFqGKUe+!s;&*&-zvH zS6d6GU6XoJj!25Fqf6JLv*g=VFpbL**T2!L7w?01a?JlU{O9b%e`23tU0Wm1)-NZ& z%U22&UKxkeYHXmEb`Q(vp5!(?|ML<{f zxPo|g3i=E8zn|T}7A`am>_`N@nV7p=vdtN&-o&Yqcov~cPlXL14dWDu2L zU}|9}#J!?-5TOZBIgeW17>GVAw)wvg#!sRI$Zf*`Qr}R;G;rG)P|>Tun+iq# zC*OmEQ4#>(oFE_Dz)~;}BvZF}87R?k`8FuD+(PExmOSyVB@q=71yNDWWbbfV9mQ?< zRZZo@kTs8$k&_-EUwm5J@T~jzU!9IVkEi@=NZ?ji&3L`+rjr}t2)9-K@^p<)*zkn* z3d9)<6%+H==C%B)__gCT&xd(E&b+}C36)gh(sw2B-0r{0PYXaFtG{vnfO5T5jhH=p zd?7YUuP-& zmw2PP!y0O6B4)=z%Qz1Lh%!(}U2p`Ka~<#A>!G(Kj%?4`jRc>>_^4zce<%3apFsDY z3~k~?Y8o!9j(ulpe3)PH6-Imo^=$utof#sL+{y>po>!=DJrfJWgvv}!N5wnu0sq7u z#Ka36k{rr!t`s27Qvx;Bs zvwkieCQLg7(W&pGp;vFjyMzeN<9QOYZM1CHRChXK-APLfQwL~6Wd-I}u99ndoS`b zm@CvOsB}{J>^a_*=9Mxfizi(Nl5HZx05F~szfq3G2JR^g>q9aR z_YVESW4D09m)Olsa$5V2j#PwHIDcESt{737*<$f{(D^JmCgbOlAta9$adB z(bo1rZ_m!UsrdUV%}VL@%k}Xb{GmuvDZML1y?th_TKEhZWuuQWOX}>H4_Y{Zr+-w^ z6QewK%o*|%M-xktkL@_2=`Yn%e@=){E|m6;k+<1ue!M$Shz57n zg}T%J;8E#GmpGT2t$RxMlwwgo`T?E4G5GQJqQ&4YZ7rw4`}(NpvfR0l|D63fMh4RO zE{4r%DTjGW+@q-~faB1qe6gTGB@;Gw#B+Xqt4#Ync*Mt?wYDHke4+!kOfz?Ux#!yQ zsv^UUnAzK54q* zP}|lP>kDha8|&o@kd;Isw`N&`dG*kRj5k^tnBBKVm>=#gEQAe3zkA9yV3=;{bgc{< zs0fRi<05U8Sl{|Ii>aAawCs>6nw~=C1BKZYgCv&_PgnST#f%il^_d6D8$|H+_y`!4i{@9hB&m~B62*d1j}xBeCer}tG!e%6xa~X zuezOYk6H1zLBHA74<&hQ6gv?VJ7R}h&k;zQa3fG@6F{Y}Jb&fUMUSuXk*OgH%)Ba$ zVFz0rm9d6{BrMVAwneS9wqEk~^{*gh(=64+RYr^M)8GLu}g6FhPKyrr8#CK1(TZVXSkf%6@IoS5IZc;5Xn z2bEeShRa&&PdR?XHNh>-tGm{)cEUTOgJgsqR!|l&h!T)4dfPe@@V3yduC-88!?d}~ z?!3ic?^7XJ0r~`0Y!81OAQF`y5FgFHX|n;`6FRcx>|EQ$^;h$Ju6jzfL3y(-@2G?C+@FX1753$3ojgBm1S5SuFB|Ez z%&Z~}k~O~B3_W@$riiXu{#478EL>7m)1|%Hi>&La%=H^18rF%F`HP9NFL>EHW;K-e zDqF_r+Me+C|EL~at0-?(*Q2uKl?ih31@+3{!gpe3{5wu~`P9>mTHKd;vYfHNoO~Ny zTnlo7$)m>{%WZZ$bN;eX zpevZKlLVLlhiR6P14pMb&r#=MWz8e)CmXJ6Q^!=NxvS83-UG54`ohn-8wEAIQ)Dkr z0l2P}ONS56@rS)NK*-#%okSp}cW#mO)PlCpc8%v{5a&5RZ=D#%D)IA)VT(lWDr8Pn zH1G z-Y}yVwd6cSKAJ=+w0D?G|DVxn!QtY^Lk<1LJkSzVdYpASipAq};;Jm&SgTr7R_Z+8 zO2$x!d)3t_Q9RJMW>0kU`P!JqF!lAyuJH@N9Ki&IEbBnWGIa+1LfPhDZIr+XknMS(e5YiAr z_bR*5p__I00O^+DaLS7QNZ`>GQjbC*J-<&+0}7n=tN%oa9!?usPNx-A7~dRmRp|UXtk(S76s_j4cV(Gmvbm$yCGLuvS}YPI{f=cuGrtD8VuA))0Y9;n*C3wI_kQx zO%91}8p+o?2%+NneJPIv^j*$juVQ7NVbWaQc*93Bmf;=_4W>e0S`1WHLdxZL!ZMu3 zMhTFO+Fr5L>fBtJooe1(qK*iz*7PMz>>F`42soHeQq~RsJ6pS4U%h9Wv1Hnv5(MdZ zSiFX;XY_EL^S-mq!XN1v;bLn$^gs~Z$l5HXkf?LsUqiKM zNr~pQYZJCea*da;@uZS|_QaoGvc=kkTTutwN>sH^ITt&(R=x;PJ|>meM~abyOr2#^ zDg(z7RVK`Qc&|P) z^jXfT&Zub`IAc~%#!}!n7|oIJ;unA=mWi_!lv z1d6nlNiXdlRGxKVcGPw1$9+KFk4ssUlQD{(=qkY#nzVwBE;?kyivwI{|1cpm@*^X+ zCi=TU##-3mTWh19ThAe?UE61EV|UevrkZI^3*W8`q(ypxrnkakoR(R$v?Vz$aMZIp z=+Jo2$l*v~tuyIpFqZtedZlwIj1N5orO)k8^N7MajVLc7FAwI!qkv#lS9@d$Wm#% z_Sq!h|JZ7^6w89cdTB-)81md&q&x`^#*9$jatQWSSL|9sI?1b1@FC-s7gU)LpGMj2 z#iQQFF(LuDXDJ_eJ;`~YxzWhg#{A!cw(<=E6JKo+j3AvzA8ZE2THe-^{fC#p%Ka`Ma_0 zxm!?OY;aS?lQXN0d6fy2zD3}yvGIgyWTY}5ML+cc6;dB=1_+oRS~VX;iHuK#(h z$i&e7@Ykr0P_OSOol4Dj{*(f4N64r=j%(bj%tpV)X~Kw~8qix;F*IBXs?8ByCn*}> z6vio(h2u-6(6GvgPC?7omJuc~3HO9?x7$C(Abxzn4>zSTQdm}2=c+L_Z_qG8v0PtD zrN|?)bS%+tRN^~SHDXSm`TkCcxmrT-M{l5l3Zj>dh#d%)^j-XHmuvz`%|O3`i{M%rO}Vfv-D@lSH1w`;y_$|C=6w_2lWC6;9iF(y2&1%iVffd|tAh zWAl4CrR~Nf;4-F8;~7Vka@|c0cTcGR%es5!D|+~j{jTqTcYxmfqmyiNyrks!B{>R6 zFJzltZ2EiBaBDCF+q4Iw$Xl#f;Ae{#U}huw`{u#~hsRMnO}`f;2&!iizQ94f=0x8< z7|pwk|F&~~6U0Un`-u&k{`-b{qabpEJnZ)!?vfw*A*5ffy+xj$^G5sB!hZ#v0O&4f znO+^f^{gNJY)YqJ5*4wwExfXIzuf01s!U1zz3hTH$y_?j5Vh53{radPaTEZmg|+Ya z{9rJWM%rl(xo35%)zxbLQ@p<{7-4I4Za{r<^iN_T`X1Fj%UibLfuAGhfe!25 zbL6i!d_VL3(Xn^wwUC|Rm7nBP%wOc-gHaxCKZ%9j?Gi@rejbG0lji)%+_VM$d5Pr) zS6RVNY?lT4tLzJHHA+9R`>(J)25w!g|4D^==Quqe%+*hw;*Y#Q2wFCo`KKJ`qkk{# zgVcY{cSEn&ANk}S8PbvZRY$SA`J4?a3#%;K(bfw=Ar7@0}Jfer~Oo zU1pcM8w(K5(&Q!KZj!`YcD+udeV3!*+%tu+qh4HIJf{TaTGoMOu7ly4j#3aWQ;ExZuo4STl-Y$bZ_K9 zc%;zj-@4%wOs)0GjAn3Yrq;BR|7!4i77mMuLuRjKFR;6h>DFAdTS~0q*6X6?7{zxb zuq&;bK2f?x7O^7Q$H8?$16i^3H30*bUJ8#!JAOZ%2!@v$!Qeasbw65d| z=?_FEJ1b9be9N(`SY*UkBegr7(v_bk^0zS;)l|3nLq1P4x}NSk0#Nq+aSVLL%+k<$ zF1=uTaw$8?u_o*HBDj2JG1pm~k7?!iZf$qfVX-)3$tif^5gs!fAJ-Qn??0Om(DHz!mB-Fy9rUBAC;Y(_kpeaGb-#xWYcM%~i}!!Tb;4KhfoB zknnE@ZR$}jD~@E@;AY5?mHWo`V0E2ah$w?JtWstLZtNunm7-BPQh9t?eM#-KnW=QU zOa_;M!fdW9)%uSMQP01Fi&K9n&>-CfpDTjqm1e(qFjXs8RZRl6YlEbSwEL9$r!*vC z7z@k0zD|Q)!N2#{9cB&@&>sVK0xh#aU7lAI&?1vEae?QzJ-^oS&OUE@o_!!(8iISD z$QZA!Uf6nG-4R2LF#xOCI@8lmZ`-;K6*06Of|hTxEc+4%#W!H78~%E2>bQ_hx7?*q z=zewSQuf66{~5NI`qw(^i+W>PimM#1VV;Hn8k#oB>Gnz(VaynpzK58G@R%QuUmTYq ziGJHM8ni@Q~la1tZObc12SX$=;=nVq0F%?@VbbPU|fKTwMw~(|L5cpp}M|h z$~nSvCL4YIP_@p-j$88IAVXcL{ZuFye5&HB&om#SDVbuv1XKLp>bae}zF9Kj`zrbb z#me;~y>Gjh-shX#4r<+=4BbgZY}7STfQtbawPsoZSNmm;do-^@0)y+2)&IX9n-RJp7(S1%Dx+eT@bnl(!>@Pse6=qUlkr^cXE#dy*9q8aroyp|$Nr#v}0PvDA|nnF^%y%`7jjrFcckJ5Mwb zox8b))BM}MzM=cr0Yjv#A_(vAC(4@#J-Z^{SDC4#{zFw^Qx*H?^6*IcnaQA<$wus7 zLc@n^X1M-1Co=-Ef8Sx{Oz>ZNjlI1?u-AstweKH&TEqsh`=XYnbGYtjUJ$R}c|9IN zTM8NgG3pk|1NEJrkakF$)a`0^ziWFsoR-T<$>j+HA@d>es{H1U-b7Gk-GHv z{S|pkqW<0>70%_*z!eAtrI^Put=*U>g&(Wsta=6gA%6+rqTgMG`_s+KVCU>r99-l! z%CQ==iJH0UG1$kHf-NhFLf5ntbva_<9K7cwwXf+dW}oJ{3OyUsyJ)0$G4XK{Q~pk; z0E{|yImMUeS2gu^h<+|Wd78KH9396zpmUl-TXpt10pLH9)TKSI-JY9bZ;EbFcNhj&OjN#%s0TX8#ST znGQrklNp%}vB+gTUq8eMPKpffc1Roy#gx$6Wc+Uy2MhQ32?HCZ{Zy%>`h6s(GKL7sfV!#rrNX&1il|w$STN3;{+<)s|XW#6#`rB<4J4OZ36pT ze~XAN`}obh3QZ{0Y^7^w>9AJL?mu_mNUgnX9j>Ug6{J?)mrmH%`}+hkyE}o1x~G;b z&=zt_2BfUazjNtRNI@ent}#yIQ-`)*p4@UAZf|qnZtF*P?w>oj@g8v`u=P6?U`vvi zSS1M-X^((Mlc!R6zX?IRuBO}18cKHf%vioX|nlT`Mszm)zfKGZsgCD;19c}2gOMlR*earnUxax=K0)}%0kha_o@W22J9S?Y&8BuuQWm~ab!qgdUQmnN zsZaiYTS_xktk!`R(P;gyok`<(jTKvm^dG#wb*dWu$!DXVT^*KnvX``DPZ>_*P5I*a zKiUb)JI711jZ(~ysXDz8Pc)fV&+3|Q)GwI4J;JgS2aO4{-xtdLdt~TXeuMnz1$&iP zYLip5#wQku%fOTN1=e#mTZfK65PI|<=W>AMl+@f+%M&Gis;>9Y-mapzpOjqz9%fnE z|9dbiXZ3cQe0e!|H^6-0{M#`7|0pp1neG4OsQDc~!2iJpW%?@sJkS4pAiszA7w^rL zFY0WGeUtckQI>}X(j8ACtz=RQ3^ZvOMbssb!!q`#I1O(aFc#1~$2R}65l z|FvFWVcpda9{<|1sUsKkCi*>2VxbZU<@Y`uQown$#!f=VBzts${Y~sIIp+rt0byNT z9#_a)_j7i?w2e<)1dd$|{*7)FKB8wU0{eBD<-ie}x4jCJIe#V15C)F9@y*Fn zWA@)9caxwZlg(cft~0l`GafYH?siSCn`^qyNcjKm_H6*Q zU15v5f#64~uv=vq4+s2GCeq#cM-5OvzJ;6PQYmnfw#RvW{+9+E%j=z81<+T{IyS&N zhrN$*&N#`Pr}#2n1x;(8#a)%5w4sjQmMNS3$y#5lEx)HGb$$5reuIoRtoGxNt|oZy zAJ9qj;;1`yJ&k?VGL}V)8)Ko;jm&oxB(Ir;%3ejRfQFQ)oON`O`=e%5u3K0q1jDWu zWap}FX>X}$bZ?%m7+9cOxq8V)7`$Msrnz{jk?&=oTSL;?jR9Hu1OJt2w#*2g{!L(& zQXczOXgOT$P{63NhJcJJr)kU5YWqF3=Uzsxy1R9{!Lq=2#3H4&(xf$_D@iY6rH|Cd zQ~8(wF!4a87_Yz~j#kH-Ud*1@x`my<#srD}k@K%WAf+XK<#xN@a(tp@e`HKlt= zvhLem3m<-xQx;j?7(x)Du98&?rpPVvRqLbF=Tdp@hj=FOd?-*rO2xyB!=pVL7c>1+ z4nOe(Vts=LMN@F9Vp}nHxAM?&{>e)t^%-W;+fpl_gq2B>pQ zf8U4xPoBWhhl{80AE;Rze(&|bHO6Zzjn&Pe^CXvQVbQ*PPI==8vt!cp2ZNj=#eeif z2R1=^D<84+BZphq6(^XUT3L6@U)TWtJ||qT1=J1==#GWUNsl{FH65Q_22LH zEyY~i%6u`f(F<^x|9sT`DbH*NB0Y|)ch-hEWp4fm|3lOJ#vEIg@9P=1ijSAvWUi5i z=X(K>M*VvOE%bi{~QU4rp(Se>wb0kXzeW%+%+2G`n~{Lox*xJsn#i$GLYWVnU&kFQJN)ka-F*zxNWv8 z&HNl!@RF#VCx<8O0>bB7`baXQ64Kl20@;lujx3`sWQa!bdo~8`- zvOkSTxPePQe3E_t`}aTO<6$c79C&r-A{~sb*oE+X37^Ydh|xx=+@B?ml211TtY)V@}ZgroU*+m<(#MY2Z$q zPm(TX6|Vov@!dP%)bg(%|BdGS+@%Rkzrj7hJ|LLbO_S?Ca`vCHfg)@GqN2Z&SOTQ! z|7ScffNNXG*`d44FD@pw$8hmahOd_ks3)Fk8UEIzbj9P|2GpoyRgBPv5G|u31O2$X= z{wjLOzbUZhExaiRn@-3afdNF;4vxSH$kMd}Z?>B6iBJw`we! zTmM+g9$WjB$_-9n`V-0rwxymJQaV4jJ0!{G)Lm~Sw0c4L050VJ0ZA5q(M% zR_rP)W~4{6Y=wUPd$$a74?@=O(aF#jGvMeyr>RdpB#%B9{x{P{0U^bPwBz3{dh8QCe!?3F_+ij_8$IX9%MuxQo0}qGBeDuJ6tF zTRU}|WgtKE*{q!xblymW>T~CcKV>`~S*KNS_n+Z78r2bfu`OK$Y~6ONT)N|wXH>6o zr`3Ct@+X`+AO2vst@l;GcIi~?L9p(hf4;@f4b2T)zGdiMd=B`jbZTf_qhGtOC1}aa zyr`+9c!EJilI`thD>ox4#KB_5l6?`&>l3FCEVxt37UYh%8)+rmWT<^yNnuGOc_&VF zLL!m@DnJEHR!sSHeWl1#i&mCZ+{!YWjD_YkT;t6vA!$A75e~)d%*$nsr65WcHs16> z1@no41ABpw5<&h+Y$;UtWcZ9MpqtZw)o)c9;RFgq%1qe`y=(y4iS@UnEgh08zm2sP zJ23KV-Zz5ES?nv6cSkOucKYqh+cnL|(Y8SuE=9{DK?9m+PUp9D$w&P0&bV$R8J&S{ z*9@vzS$$O-i$A#2XrO|e6zwnF&bCYU>~HXg$GQ{^67v)+Omza_J!uiI>;P{3HM?5? zE7Wjz)MRk*`@-2T3r`egA3doQLv^HGvW{fnD_zOYJlQb6;@en90r-j|OoVuvp)gx5%{|k=bOD z@oUAjS{K5;+OoHr+S|gaSWD(qa4lZUc+LOw7mLmzPmi_7>lrr$L!V5Uc3HNrCT{s; z*{(F%EH7EL2Q=>LV7-PfhA!|_hF>j7;)g-Pk_6X+YoXNVP~b&UvjhX*yHn^SVy2a> zWDdih@qlkc6A>Prd$!j1|t4Ri8+mI=4+6sxJf(j7k zJY#aAIW*eR%qojWgo>KV4ykE+r{$teK2B2!bzKu25MB?OvA_39Ds;i9@d^eqX@+%b zBc`OTZ`|CsZozQ^VeJpDSSeoVI>D1)2)=_n%Gn*oK7b`lS| zMtz}aJgD_rGCFZGThTu#66&@bTIlS6i89rc@>hlxL{+Xcu?Z2D-3cjcU+mYcatO@w z9@_NPE|Q^B*${E;CHE{Y2DdI4^#$s5xfb2&-!Eb9wAOr0hKaG^rJn9R;COwc@p9{$ zFabhVO+V#w3em#8+x_o)^x}Gt;0EM%HLj(t$Ws}pND&x1dD%2>tO$}4QrfXN+&a&G zOdJ?Jf_j!kC9gs~7oBRw8%jk{0Xae>(T0l9#jT8)h7!P%xvV27qf2W#t>wnrj387u zbSGRQqLj8_<&AXbGjGDU7b75_OD?I|pNbN9>K$O4ZurLSx82*mHkM_{w=So8*9^R> z*>Hcp@QkthH3zYj$knh)KkOY|eh0}qhwRMFVu-@)i3PTp0-v_43Z%8^t?fI!8W+z? zqD!d`7jy&$xkr^P`r&Hq+lJg`oCC6jtUsv0@B?@xqm<*wXBxiKJRp;8cdWq+2_L9w zS1UE2`8zQb8m_PR2t|E8g%FO#&gYsdsH$mizRJy)?&}P`<()lC1%>Id9u-P{NaNv) zs#Pl7R~TQqIWC2OvBh3gUc7(KLk4)w1U#s2k)F^2v}`xSYnDfM>Ovo9{!PW|FT!#s zBhrZ}dbM+(thFyo z^b$f}ZSz1^z61r?RaD&NZx5y*%iDh>Ia_)_rEE<7vT~N&cD+`?vE1{6ZmtzcB+H^dG zHa*is>D+Os$DJxEX#h=Jn6z#dSF5#b-RY+}K_)N3oqK(bVr#R&VyNrQE=cd-@B6Cu z-#5YMv1mpqDxdU8D3TVISG7p7jl^uN2k{${- zjaPUR;a#%Id{-($XTyjVxl1=v69Uu4FeMCiRaso^;IIXO8XPin3SRrg2VZPJQ1jK0 zPh4_b^FovYf#GXJFsRKmDLvQyZX=BwGE?MnZ(Gtt+OvHq(VVZe)xajv^3D$xX|~e} zfcsW|;FEfEDMU--)&M8iJmOhaYIL|~;tZln%Gw+m9tN61vlujhRQ8R66w zw?6$GQI@!lSE}y$IB0c0M}E}tnuLYgcHRxn4nf5lhW@_#5G$Zr1DObqR+SGnki;Ps zi=}O@?u2Q9So2grfhe59@hrySp;`}?Q9^pF-BN0|!n(woN4$%t^OpSWv=?#J@EnMf zduC+T==q}7iuBU`**c$| zgLCX;?X?Oba8 z4N9~{bxGR7GV~8Djs)FW-u|pj?b#U>vlMIens)$~2{cCV9E1B^k$= z4-ax2SF$1~SYYW0LRnHp<7EqvmQi;XpysIx?)-=oI(H!!1vVYXa73JWL}5u5XsUZq zqUywHi(R9LrLLBE29z)z&6!s$8c{eM2O>XWI0AevdwcviKw#XX>0>U;cCVn!%6Owx zBM`eX4C6B+r_IK9zxO$cSF!Mkpu}bh2`29Ynr(hz06RV8ax`OV-rs;AZy}qoj@|;V zdk(#l=ECl0JS^@GL5$k~+;|2L5fAt>IaUZea2U8-J#_x2+_t)+gbiC@)50gEdYJd?&wn z#6keKUM9n-r_Ar~-O1(M#Y#lKw||izWZ`>MR1(O{XAaj-=G`jN5-#b}Q&D1X)<<`XhXn#2o1! zqH9W@Rn@Q3KbDUv@yT!0L$suya4dXKapcp%L0vq)*uAi1BcRCG{G+M`Ii~m|FfYGo zT~D`z;$G61QUde)tr!GLqR)(13ba{XEpXifbDJ?X>4Wk@o^1RoJ6%H9hDPhxH#V;K0?;y0; zZ-uOH`P}=ujg^m9fx8-P1@mN;r=H`}TOacDpwuv(*!8M`MC!ScI~z~d{CltWpTb+M zuXC#vIv+IQ)q_L^YRnzEQD>)N?42CyWwR(-K{(Uj?sCshZ+`r$U>d;ybu zr>|=au8}jgoR-MRa<@oHkJu4IPrA-}6j1S@BM_7$Ih$;gIJ;y@WSl;!`xuCOjKD|0 zWcK2U5(a3-WRIw#mkmtVTJyi=23%4lTs1mJRQ%P zN-ppT7RNXBh^yQ+4eC5V5m;FE9&cf(;}A;G7t(OD$TIocy`)w1o}EdSdKU2)F2Yj! z&gx()CVcB#4CWXfUkHCSvl^pA7s39!5VLs*^!e2Zbw=&+e^Lg%J{$xlH6FmD>|J=u z9c%tT=26A3ME{9S?Ee5t_49Mu1Q>^nhkix3EV`My!QSy$^S%2IF7A4#Ge8CRKE6O& zpRNLb+WY+-NbB_r;7@zMKOFvly8sCpdGO;vCI^2j)Sn91Nk@Q!?EkIchj|MEo>Tw| zXTMeMaqK|jdjL#e`K$%zA0e~T30PWS`n7Bw@bs11c37`k|u04gnylGuu_{eYVA?lPkbmITJ;_VfeMK15q&-(wmz@qqkuLi%a{Qv(Evu?u-&?^vg zVR-F_tWehRQ9wn(Ew2>iopR-DOjY*&rz!tKlgL5d7B_A`o9x7-)OCK1w_jU`&poeP zACclYUW+@0SlRh@AY_H1(-}50=`f+a+1FIL^X`(`{X_mIzKi|r^}VJw;%&S|F0ica zj?dMq^w`wq9o3LREsYB&MN>Giefi#mpd}TIySHQOW~+xQWr5NV)Bz!VtwnaQeBU#l zp7ScrboVF~uEm#CvlCr?KNEi7{YEd3uLL0Oefcfw?Amtj+0Sl(zD?x{`3lBK8M8ox zzVrp#i9si^Ov)BT@<5a|Y~P1HBTZe6%?dVCxl{IYq#7M|S6T+d3Q#bCq*r+z#2*#% zYJQ7<-&WUD7h~gsbx#a)sbflBL7XUSDj10mCO<9xX|`q1^3k%}=0t?KyyZ_HP{^vx zw<&m0G$vjsC9lJ@d+rOrpHv$BMX%jTu!V1>5)>(`7*8md< z9n>v-uX6iWQjIXaxa~tM_V~1nk`B|>6LEh2=A*Wn4 zMT?}D4SQpD{8F5rvVcEW*~!EtsJH=$Jb)|}%P_`?h0R8c^!axu9!NndyBO7^UJ!68+HUE05rlkBn+P}j4)EW+CxSkpTvLLH;quQiC9 zxM+lC;nuJ#%LzK}w}yi@g%bF^jr!!tp@tNl221Ult(S}2HvnnDk6lci#+_8PIt`BQ z1Sh09tTY|G5~WzV{tTk90_RDS*PMm>6Nki)y0B^J2F6uC4;rFJ@*37+>NHRLqw9^b z!xXjn?mCf;{XPPr?Ihbsyj!=`&ilgQ<*n?<2J(7JDn(;w?dsZB%Ie}Z{#XjOS#-Ra z$vqP9oDX(aSUFpm4)9zproTEdFxLFs+RwBp7EWykL z83?O`0I}j)!;|7?UwS-|qUvDs8;@yV%HTH;`kn2XR@E{PH#TY$I-n8 z@CaQ+_($EdV_i1B+f46JxY6#icr~35k>>%KI5^u?5LA{F!4~60eDuO;=%8vB&X~g` zMurbj1hfo$g1p(r&A%gdjo1upq-23dhP%+U);H}ab;EV4J{Mg0S>*R-gEt*2*U2@g zOnOa=?BlY(N>!xq%2~j=v_O+*H#K!6u(rtWyOpd-@>S=I!>=m(jXFSr0g$5BtFz`3 z5GOpeVg0u8Cat0ofD?d%1a(D^z16J0UN#VTo@3_Z{m)j)zWom8BWfm(?T$`6cV5I5 zm}rjKEcUrb*v<<-!!@;;WS6CgJDfVSmt&iRZ=SUJ<{wkkwVZxa?E~Y?H?f}9(wkc9 z=g&H%&$y!&Usj~^C(ljroqwIg^G!FjHZka($UDi@LtX)z^yyjE0KFP^0V? zXwWSOzwmF~4KAm5?v&R-rerDIMJQ9;dWwV@ZvN*#wACawrG&b>g%V^Lca0``kJcn#EagE^Rg>M!^$m$X&P;=m(F2xSC6!I8QeK zNsT!o<6AZ!NY!g@xIWaKNC!=b38QbFM4tLnOT)|1&>F40VUW-&AkNeEad_-pL|8Ww zDNURHYSTbYuhv#KDGPPFsIhBb^6~+g1>cahFkyi5cE-oas!nx65}G|7FzFZ?{$s~M z66*J{-w6&cOcHZOmROHun{=mN1;!mT`0rYQix)cdKq<44TTeX?WqZu)=Ez(4Or|z# zGv16vuAcL2$BFk=fcc>kJNHIRZD+r^;UrHXj;a2Pf(!i?k}RKE_fol<9$zfIGu|>?IobjP@Nc5eszr`_14K@T zN1$}hkTnq3vydaE&U%rHjUo-iG*zdaA9otA8e>o`*+MDcO1eH9WGc66ZD^Id^748Y z2ljow(ZIxy56?sq({}#hC`~sz6qggJJJ%`fTG4RrsP(|-I~xvln3B;E&gWfQrLER z3!PIbxGRXBBcly4j;{Iqo>i{vW_^RQFzVV$S2wv`A@E*#aAq49o7q|5-Dd!bYhqOT zZfyXFmjCX|E*(|yeQt5Zz4W$^!??T4n#HSp410{t>$GLiGqKF-O zj4>5Vpb>2)FE8yL62WB^+f^*gjeP8KdG)bU=04KPc*07{qs4nH@~XG#8v5IOon*YF zr!A%gN`HrH%^ak$J*gPAhmp5$wHDM?%%mfqi2T`U$r(FlR{@%>k9K%^60=Y?Ox&+5nZt$r&=Y4)LafqggFQXH zX0V5ht_u6gFSj)nFYv&wRp?_WZ%=1W)3pXbr_x-A zUBaRrE2j+N>r5t}dSprf07}~6z1k_A2&*#Fc<8sTckVX?g+nIiNd*QuJPc15n~&$n zRQIR5i{`%G7sKLbFI&5nN_jr<)1^0CQj)8%BXMx7yG6~Ami(8Ixi0CNBJy}0P z=iOk7hbc`1CMzD6b2v-bJ<5~lYvWwIpW@+xO{#Z^6o0W%A5#6m)?pN85k~Y%EPd@Y zm-pCWN_WCel08A8tkWV}WrZ7SrF9c!3Ur%e=x1v%fP2y-)_A{%!8*H1IwH`_#U1z# zSuy0!2lYVOi?rgBoU6Bb8PsxQlU4|06V@ryyS`Pf*&r2W^p2YIvOy>EW;CpbxU{|0 zqOgg!OUw6V zWzGa!Fbn*^J2Jd#k#?*!v^dlu(Y~}Cz%7$~c=Vh2nE)rgT* z&Y+BbgJC8V)jc<|>9mn_!f$Djov6{DukhXz@d14T;S4k8kDgum~`QKNx?e~n2uchEDzr((ypso zRQ2&xPA!ziWSdfy*MRL2?5wSYpOrhcCHe&mP@9;eh#)mWO zx&0sDrPnjTu)6R7wu?vVVmZ@+60lb@Uim{`t}-j`@GY_e67Cw;Do5h z(Xd%(5X}dIQ~~<2PG2KJA@ZU!!zCgzDb|Sw^!;g}#=FRw8Mj)-tj_3IFmk{u;^y+F zq>}B14+&-N;{cwgK!R^}vs(>|ix+dZnjU4m?0eLlVZO|WwLcBNM=o_~6EimImX zL~LH49@U5a<-Fk4#bz@b;OF3uoRB6hH4{D=0)c_rufSkb`8q+%$FbP!i0IpjTc-|| z_LL6(?JDQy3D)b+L4UH&DiI@T%1)}!n7BW+@^x`GPHKP;ytiWfcs!QZZ;Tf%C<(^6 z1E4WkMEP70cFo>py7W75i5DM2L8hPicfW9gZT7Wpt^1cFsc;c$D)X4R5NYmdxX4KB zboQcJSpIVV0p9!+-}QV}uQITvBKq3>Qx zx_I6g*~f>NBCRB-RiP4XEqxL=NzzM)OGk|?jc58>1xD6%w`1{|D~kZJu2itD3WsoV z1WEX%kA0-IpC-)3PGzhZ!3$s8j&Yj)`f_7j%~Jbwk5#WlL*)0`no1v<81J>{N^ti` zKaX<16{BDBy0 zq0O7fhRzw(-~|`y#|#LoDq`G6XDBo=z=Vu^06!5X1aGL4y&u;j&D90XVOTf#yzq{R z!{2Ypu4w#P@k$DIt0__&VF!btO*p%`;$w$*lbUu zFItmUy~$yY%~!gJaev>SI-Rn)Y_d>cs2#`-v5t zL`BCcsr3q`q*J4k^z06GgX}f}t-g1y_5O})fQB>py^v}lI#b(A!1iiRdZeezVvdhn_O|D7^hDHD~~He?XsKIy4F!A zvGDdTc}DlnLQFz`au*=^1~=_xdNlZwfq5jgKt@ze&?O1rPq<|PW<+YsN{SVfs zO=W2%^tsI#+!V%&q2os|^-eY=t-e6L@%&!P8V{Fv@K!A*LKBlSRQT9L`C;(Cz~nn1Jd>z$-%c;-w$0eY z&Tdf4wv}mrr-TPtMN&sc7SHb{%Ce!LIAW!>#G6)AdjPYLzvfX9S8=3*`zN^m&lAA* zMQoZYu)Ykr9%s0|nf1(z2ea@8Zg|WAR&nIje|gdqStt?L<1m4-dh%rtkKaqi46_T~ zl!ud+f@0m$m`jW$a)v`!D934&Jv{#BbMF%G@FViTK7Yh@&C8TpezD5ZhW-Zx+}m_` zm$-@rF>GpAMy1c{!}t%}vJAo$j#&w6U%VS@t}IyuH^~mQbqIxc41rmE_rRflYm=ga zKI4%Ss^>sx0#1Qzi0H#|l=PgW2DV*Wb`SW_jtZm)VoK6WG=f&(--fwXi(Da`MJmQWUkHX>aVO9fRXU;)We05`1Oz5rvDjxBB62?$MXJYJOH%)i-iltn(x(YA@-<%z^mPT1!-GQ*2w`Y<(V7yH~jA)FE9R=(&Tm- za&~LcqKO*>7h=oijw5A$aVeD8%swCeD}2#tW6DX&BdnCKOH~xl2y|xAjPG z_5EQl_rG1kdPn=fg8su_}+K!THp7r zZ>^g@lbn6_+56eQ=l9ejI5rgnKrwT7K70mO-L+ZPj8ls6};c=+KC?9OR1r)DSFdIR?NQE6K&i6 zOMbrze3PL83s}iq*lg_so81Ew!P-NTx*8oJ>&pHE8o|r_wVcQFnYz}g7v6<-C8>p+Z>vV9+F~w9R&)v)Y=c62|w00755~ z&pwSZvZ7}2$^HWOrKM#U@^J&)@{BYd!CbC~{+mEAJ{e3ic~>qhY()npE3gmwFIHBC zOdodaUcwO}x$P8nB<;aTyNj9=9>Oa*1@&ch%j*=7EvtHQgtl+1>f?yxlO6k8I1~Z4 zN)1UEPxC;D-ukgs?YsNKijOXo3V@=uda}kFOrR4s!B@-7l2r&f8D=w8*Gz?nIIT{k zL?YdLc0n)-+z|wxF26mURPK@CbPzEGI z948@+^W_2A8g*`4UMJ>LFE)YpB_VKI7m9SMI?c_!qSrTYj4p7qB1*^DA>2Tt;}7E}!$swkD+JPN(glb$ zpr(XVe{A<)z7~l!sD@n++LmEyclY1t16_Hsg#ProTUFnaxi#nL#hWw z8BPOMD~+cI4Q-c~1gWcUM^llsbc~dY_e0G_)**lQ^_qs&dR1;rLGuN#bH^t1a)9nl z1x_2R7Qs|V~ zn|a)x1Gu(jm9WJg?j0z~KtVIDSaVXXiJgX7CAhid!e34cIh*(C*2<99Ub+nSO| z5zab}Skk;%+~B1+I>|ELz!CO$#hfI-%GFt~tV8b80t`}u*L#{JD@tv}>s#YE6}UKl z?e>krq4ozFf$>4C$Mw;DEP~vFwi17&SC-BOlS$Yg1&)Uo%q@l$qjv(SG1(mJibiYQ zEXE>wc#^a5D*pQMg94JgM&zsR&=N(9_!M!M*LX;Y<%Yqyxy>a^rR}5glwxiW!sNtM z^dBe;jrm=e;lehTx24&*nOjz^PGoJf_L3XTFLO6!xZbSaMiQ~gw@d4tII5y~E3Ds5 z*(CZlnKso%^mh%WtkfE6aC+UMolM0}K)@twJi2x#*bd5?-WnoywReec|A0a8%j&|b zxQS_dsz~kLZ(-0l^e@S0I!qryC9XxEA`@V}Su(KHs${fj2`lzTX(-&ZwCM_6e_D?& z#_Pc6{Pd-prV?rLjI2&1=g}83{J=LDFGy8vQu}Z!VS(7YNJS9@IBVLN**84}u|J5# za04NBTPC)LX1M;7nUTvBM-EM52G6^4DwH{PYxv@Z&BepZFmQ0KFsck~CSQ(i;;(m{WnF!m?=F0Y8f8;gD-@00Rd?mO?*(%JUsvnd{+=IggKkeP0QKj zI*JRW4H;F-2hvq-{#i?MDR<(4Lp_SHh*1rjAy}PIl`sa^8N@#A2j2PzeW=&fZVWR4 zsQ5C|msZwBY?~M2!&q5!JCEDnyai?E@s)^oEWC~`v$XpMreN9Z8ri^LsuC)J+fAx) zyj>6vq>7sb^LNC32MqxWVrm_fkz035hEDF-mcJ=cN&{EKe};HwC_-m_`ag#&ftIpW zvSI)5G;Te={Vy%#E_8*LwL0a>SnrX1KI+JEyl-aqTM2oRgWB$#Ej-W+%LO6SUgB{58kW|+<5l}(wOs4;}3LvHHtEunH@J9-Alv%;Z7O03Z`)5 zs^KouKaV3}3a%{{R2h=^X~OYO0{)(xRrNQsYrI<$OeIIAlZtDT1q0IE`W~E6^$#-n zpZ>pSwvB6CrqDL=N1a1Fa>m&BGr_G%=ti2$L+(tnJ=}cAuv*Hhu&m(Kp^lW&`?(8Q z-Za|u_PJOO)st6;9EAOTS+-<8UOFVK&0WIYsPC}HR>l+zoq&*Gn({`FFAJt zpZ-!vjZYk4!waYLntl;fG-U)NwXt0Xd;~Byq!!khQwt+$OX_u>nw*+f3}#Ybc9ZI_ z(Hi<`sO|9q>E(!ZSGMK)T{+mc$nzr+U%k11_#Vy%1hkujiydGg6PkIHreJSr>aF}< z5Z-9gaU5vW`Q(k#p0&`xd5t2FhN8)9uLxvEL>mj-<%!lyo^^ zvyw%+dEtBnIQ{gOGjpiJGpsl2(ntHluQ>y*F!Nd>-v9+*Nr;@8;Mk zLRQkyO}9-(Lu`Y1sl&a9=xH-Lf?o21FViN5v=Sacx!rMyQM+8-Z4lr3s!FHG2211k zRUM+><2O#UHnL7qR|YSd*^1VKCYbUoe5T6FzMt`-=yZg_aBv1;8G~jHarlRgESrTt zQhK{_4nRjXU%ZSc8$~CsD+G?$Om~+$4^ZB^t<#cH?KW)3CBv?R;U>v;-Xv<|+;nzb zG@9r-7P93FiRTXvDdM(gE+zOlWgzO4lc=m@zi|rWQ@_k-29{VKY?IHp4dIpquu8C- zD*05(vK;JABGG4m_NlY~c2~aTSKUDUMmTWuR+sOXCjl>nu$)wF!s8+AH#`=c+I(JmU z-PM&P=w5V;$uR4j^beiHwgI=M4YvncP=h_#U@xW>jZ8x8iQ}l7^5JMm?=TpioKfiX zg?e`kE0&w1zPV~oxa*%GgnE#n?r-*#MtQxYftg%kq6Q8Xc=k6*vm1knbeE;b1`wK^ zQ@6eOWl1K!c-C)!9#1B2gP*L$z%;&d({lVnIzSF$X|#JH`1k?EJcwMqao$o0{LfVqV?9* zXOw>oMKnA z4UinbF9+sf@11gO>3I=&YQ+6sN68Jw&HY_!J9Xj$KLi|Y#HMWh zj-Pr1Bj3<7R9B;yvTq|u>#pf?+TdY&Pn&V9=$TG>c+?h&=NCknje|fq4$--YaLE+%!8}6 zpVCxLRmGRW4#FlTn((-b)sw*@(XL=bz;@a_J9&y`bLTa6Ex7ZFoA-GAeKJh4!sR5+ zT{HGx#z#a2zwUhO8wBLHfm&EeYHCy2b_7Iak}MDyKdWRdWh!~OG@qadT4zIw+O)ZB z^8h#+N6;wm@THi{eQY)LpeWnAzh_6E3lAx%mV65bl=jx!G}K&HXn{xf5mh#1 zj*}H8&upq`t?(vjQSU4dc)eq!CiMr@_~Ja?SqmCi7A{$1Az&-TwcLyFNB{?%eCVwF z`JH5-kQ<=AGz)-zHphwipm=pOAI@XW4YWJchJm(QnQFynn5e_dxzJ#)ulbzPQGUJ% z_Z%lsQf1l)M{GC@1h545(sWS87=i_G^O!<%uL*|n1QUql_Nzhp;I?L;=yzaKdaZn= z;m5Ax&^C-sDBpEaP=$bQG7ow}Dr0H&13sQqy|Iy9gSk88O|5&@je$LjDTb*j;B7{$ zgH^xyKOs-(+xfk)13rc_fd0#-fxhDF|TJ$e*K}8{FH-7chXrMgXo=MuU zQZFu+2t4)?cpI1;jruUhx9t;mEX^@2&q*E=Dd&1$G_U}>)Nb2^yK97&U9E=ImojeH z=gg9(JVN*|X3ZuDRY#Q8b^{v05N*T%=!%Bib84k_EQ=y-qIe5EvB=f?>Qd7Sxq z_zd9%)0xWv-9v(&QusZTtb#SrM48dw#;DHKA;=BnVj{eCOlA26Q0NJ(HAeNNw=IgI zIjDHkHaNbY9^p66N);&g67{ih8TX&GwKG`{9o~nSkZ5(p1oOI`Lw>|pYl>XD`MopDP# zoy=2QJq46Z$txC@J1b73FJ{Dh9#2}zbDhwMPYzPl8OSPSJjK^5eWU~6-Ftc{k>!^g zba3irbk^IpjPVV=nFQCA_eaK7*6q$s?H7yjN13TcUy40@+`B-w`GORuFLkrQl-hd- zY-2zgPIgoCw+Now_nhYayAn8NG2CCb+w|aN@|DZDZeLq}P@ogP|Kb*r zqUAKK?D-6hI1tr--QOY}(yx5NZ#joA&{nir>X;M5r2*ejE;xN)_+27j{jjZ*t!<{6 z^}cBMl86Ky15*tI`cduQ&z*5wse4VhA2;kFI)pA?S_^NeGsE8*7{P$6rN)`eRu8)3 zB^sSryx1%YGHMz)1YSAZ^|jV9swcdwO}Mq-@?&Z;srs(FV$mW}8>~#gkOw{YscK?T zsF2cv6_llE;IOoon8$Z|zzG7*pMy!IqS3t|MQ#=9C#Y=y@{?S$EGk?iL;7R!1?@^+^ zk85%ceFjASVN!|N?p&ZZ z=IISuN*3R|G)J^nce+*%6BcK
  • j&{@?KB|JoGu__I?5!~P2IUrzLAsec5QuBj*K zY5x^O_z3+YY-ManwCpg5zfpu+Kz_~n>RBYc2j$NZEr)X_@_Fx0gstsJ|3QcGnN(U|S)^x1Yp4BKHF>#5Rff9-2_z2jSap4(pM__7rJ zV}+gOr1o3|i^>kt@QqYQssrFPld@;N;kheGbT!F5J$D-3Z?6X08$~iNYEWb}{si&; zY5zpekA9r&X*o|NBz!8e6A|e)Av`t9ky8qYgv76xtf@t3&mv25SJZdy`dV-P*FI+G zPaZTf?pFYiT27xvO8GM~qCBh;8#Kt%Q@M_qlY|rwOD$I8IC5PoxGBJkU5;zN_=G&-y^V2<9Q& zo_;?e(F%{#X9WT6lh>=!`rTV4o3G@XG`gxknx8PvD2+xK0;Bv>t|1>o-bCUSS{nY9 z5~6K){Jsma!z<$Ik2h~n1S*knl(Oci3H{vrPnc%wPmje&MHe=!4MFWpa%4*m?-Lu#xq{u9jUp*Sd84pbx(bRKI{Q zD-N+NIH1kIte<&#KY0MPs*wDA4`321Tg>jtD+gLBi&u+gLA|UJzy+%S+W=epIBMdZ z7F4g#xvM&-r+X2@YLZWIVyvQ4N6W^iWwz5E4?Y{-Xb0xqb%x=4GSe$;lmSN zHkisO^_E`ouye_{k*ZXTicG&{iI9%n>z%{fPntXMrbG zKf=2Shmv~2%55grf@>8Kb|#t5V`T!*Ovm~1(VnSmnRrNzzLRh#!}LL?z!KuMU3DZG zfG8o|XH(&`eII2O3aTl?=fYATMm;kA{H_Wi4@%@a3L8w-xNDs2D@L~Na8nO6y3~P- zjG4Z$*KBOg$=x#H6lJ5zo@L!(Fx`)&R{A@)6T2aY@U`l}f@NgYmFm~+>30~m_V?ID zOPQ6z+Ut_lvFa%a|Jrrr0;zHtJ#`WlX$Dp2)D+%ZNU!79ulH!@mO0$92y}uhSL|uQpA2?D@0?#;~!T) zRBLP3558X}=TSQvR8#?UZ$jMq85^Xs{o=~pl;oN1F-aF$MWNM2lc*{v@}-eQu#F($ zfr#-bt2?H_9`+>$_$dYC^cRma(S6MYDTF-VRkDV7y^HY#f>l;#;J!&4P#jR~?B7Fp zn!y)i(6MN^{o^j+?wz#D2mT&SpEk_D(p%WW<{UKbh-PBv)&sgvASXF56u3d+eb*}$n!jqqWVgvZ3Qh0B^)Jwsi zkhwbP745bvM}a*RqMKcS!sW6#zMe}&wMt<9E3eu_bX#mZ(}u6Bz?47G$^C}K zM(v}r$?)LJhD_H<)Yhaigi!EWPU_--O zb?rbEh#q&!d`#8jEt(mrDse9|kofj^(%B@PKt1i&0^*a0 zVmyMb6HD8JoiMnMrO7FaUDRG_f@mwS{uwuqRG~Bf@37H5xm};tY2aU~4yG>vn*z{q z?QHADr>@edduA-(s%_E-U79CbP||c4!aM&wmshSG`?ssVk=~+x|2Cs1Xtb?M>9S4)SNGgSiA zHNH(eN#i@JO6>YDXuCnhpTDa{Ts<%QrPEf~sk1{w=1Sn77kqa84xy%@_NLF4HRIv4 zYccmnDXZVCi))^tI}eH^aCPpv{r36ul#Icg&}gn`1gQAR37iprHKkE;Wgsgm#(Cc>CGIp#Ui1^t=v z#U9}OduuW}%fONR`w+d9e-puL(Zsh|K?XOgsqx0|DZa8-SsA0Ow$JTfjJ)AP?j)|I z#vFneCIGL(h1@L?-Y2>&*yD}MAa-KN+|lLIEZ@!!+H}%>Z~-)t+@DRCIVgFVTqG1m z<<>Y~SdmpUp5#_Tci`P1(b!U<&RmYHr)(KM9N!*ydGw|{aMrhPuZjnNBhq^i>lwW+ z&sHx_g^WtHwh0adAj60mBT1E0-i`QPH*v$JxTaed*qp7hfeVW)2Dd5h*X|X6gOks< zqhWy6J)_RNBZO%bo^p(eypkdUm0c2a-FPw*OwAm&=;sM`7X8#{Ut%irMxfx=tMY`d zO{e7cxRzR1=9UM_HyocE*l>OjDB;=pH0|21DS;dIB{ zwiO;`)2lTOJ}SGFz{j-R%h@GxWjw^0IXeLQ( zQbq!+?;*5axFIFe%I(+|Qb#LJdZH?kJ+9-ee5Z#ff8TEvx=?>t%ykkRmc&;LZc1^{ zV`CLzX)SDMDA^;~GFd63%t4H)u%Id7LEfKicu+ap{8&``%lX;X-kj(lU@Bu>RQIla zztrg6=-n9oOZD({fgfjUrX}CCOBv+C7lmxIk&0VYacBo?r6td>#6r@tztAj(zO?xm zc~mxtEd59b*HzBDHz8rT=8X15OQ=X{JX8zP--0Ws&uEqmzlg1l;pyrLzs0V-VZ&=1 zN?@MveeYDMoRCL)!UtNN@x^Skm$==tZOQp(v7vM5H z`n-EV5I~Je@#PqB>VBw}N7O_4#^f|NOSc?2ps$_M^l7}i-`>RJZk0AverC0XN{Sld ze6a64TFs03#7jM#srpDj_FbMy!laxu&~9|@W`4K`K>(4fV?#P(iFR^n)GizIb+O3| zD+i^Q$eXJ73zQ?@k9cG>zY(lZTpsCVRm#LfmJ7)Yn~B8Q#1flsf09~Eh@ZHyeY(19 z+-;=A@Krw5Sj6qHQZt@>Ra6M2htH!H`-*>Ju(FH1jT=PSAD%;&qfwsj~gd^uleIRa!+)wG5lV5x>Vp1bY>3 zx%4B6x}ud^waW+@|1Kv$*{t%@mmib)0!lsa z<;}y!Ivv}1pD(RERCsiS29KBn6NX}5W^I^eBqsCSu%RQ`rsYLPq1Plf@$g3^5xu!W zyL3{ydqrLpwoK$>4UF(&Ag1qbwVu#ix`78QMF!fBuDx4T3m*33w}SmDuU6QXbGAEd zM6eY{$dTCUTy(|YBvuL6b#ot`SmujuD1GELLCK1$ualyASBkWc^m)gzsw3WX^ z2oUYM0+*m@q-FdqQj+@txEp1&GU^x1CSh~!^mgO>rH)0+>XTAoZr=UEk2@7zDb~CS zs7nV9WXOQ|0#urQbyT{V&3kI^5I(uZ>ZZ2CwO8}UQSMVEx25?e9ch^cZ@U~vdU}A* zx%SZbIiz3C6pt2a?Nw!G|Lxz#9JC6aPT{d_-3DXt1$uSTx+8QYaE1pz)+`cU9R1uA zwn;_sq)kQSc>IeSW66`^T0L5O-L%tq%i=fk=MSZTD|T}_@;vp73K5GRqr+dRZMn;x z9T(+KqI4;Qqk$!hO>K8?FP7yMnYnhGeVm&gdKY~bzHYja?AGjZtJww?qtoo6qoLoR zvz;>BK82r@+gvqtXWt*2l_yx^^}1MtS!H%A9Fh1ehNnOW$=@WpJ;6nJiveR=aEJJ{ v%V64tTjvrqCWPW@i^iY+Sfs)M+V<{|q4JS|#~s68)rigw{p+P#_K*JylG{By literal 0 HcmV?d00001 diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/PR2.png b/Firmware_1.26b/Documentation/How To Contribute Pictures/PR2.png new file mode 100644 index 0000000000000000000000000000000000000000..8da9e576fa795312dec596e84fd18d374df52d63 GIT binary patch literal 64618 zcmd?RXH-+&w=ayMC>&+<-_X0k!crE^x%=oK^E3OC zyQZEjEIe&{Kl?hM`L--9REGAg8xMW0R%m{uqS&;Ba1{z^IRNa{SSt!|SdA2$ifo4O zWM3J4So>j;;GtD(DV?Y{_ToZAhOJSpE!XJ&Gv+6_M!(!?zhiwTqE5DR_oB}# zul6Bd25k#6Rt}N1Y3KT6mQULW;nle7e~n4{zvFsB)B*JJNJ-)X5@Dt2I(}9wTI}|U zqmtXi`3n2~1fMBC$))dqCbO81^MDxJ9e^%QnZ}c7;}V|GhcBD*$@YYi@s@pmW(6`Q z)wqnEuCVKkWj(}mfc4@htB2GIvNK`&&lDC7*F)%%#*NpP!OdzX^iPq?$4jaZtbZ|8f71Braf|F*c{rqKGP9b^_%=5UT)pBMq;1*E!tpokZrRb3U9A!wQ$Np^n}J{ zCa*#jZa`(JCMtZuk@fysP<;NQIE~LWuDEK8!*i$`OL+j=lJy&*2MgycKD!xF>&QN| z6=DZ~e*d_XnQgiR_lwLlZ!8K}?nj)rCH&?lX=c4c+@Q?}C@x>VXz!EU$C;LAdU!0d z6~&gvSYyl~xI@vsxm7wXW;YR1G^{bW_n=`jm@z)0YwbU554cp)L{7Hw>{Zy<+h792 zV?L=J!C0fG?aoR9uC_E56Birnb@K~T*L2@jWQ!K48i`ULTc@8Qe=ZY`t&nWyPaPJY zPV)7xEV7yV{Gl>iCQ2%O_-2v47OsEj^J+>3r5sK?4%|z$3rLen)^+=zSIjTimn`Nh9K^&mAL#wa8R9K zUQ2Ovz}Bjln5c%w?8}`(;^>a~i|Wj$tDj%-&xzXCM&Z4YaPrtQzD?1j6OjPwN+vI; zs*pF0uo|B4#t)W9y3zphielAv!C2S+&R)h(URl^}8_J+hLRXi1-;>)V%@lk-55MOO zELES_5jI3Grdd&2!kam)JEBDAVf!*qdYv44nkWGKr6$)!2TQ2b)&gqw*P>j_0C`Tm z26YqQ#7S7jzuRb}k#QS8!ew%wImE060INd6=H1iO1H4sQq=l0u$+rb@{gQG4mi)R= zqL=LLgS+p-{e4z$C0!e8MGd!=q+}N`J_+a@c0oP{PFlm(H4$gx5*2b`H@OX4HsVXZ zO!`cxMPd3?q>t8y{w6fKxgXLQdv3lHYsfe5NUCBLDo$7Pll{wi^`Br?YwT7*{hB2V zKA&VCo0Dnj&!pHTLuDWn^`PL~6oLUyQgBWvG_R39p-~q!dq(`~sihWb4P&@bKvq5) z%?45_k1mP_gZCQ64eBeZ+yI{$4bMv|SyBa?8?=2sdou89GC-;KK!f&J zOk@eAe*cPKNe6c-iGBEvs4yX36uSI|9mHu> z_6C`EU#lolKYZDEw~FRfUma2b7HY-s_gjRD#X|aIi_H@?q|rW~kXvp6I^N>fPKJ@! z`g;YwvK3H9Xd=lqcL`hL4AQkHgCqM~ChM_kRVd=~j|2MX60uRHFMIIY$e;T2aex#I z;ftAJ5t&b_%tL@FMU~|#4j^&WA{>4NQ`L&1Z`5g+`fvaIZvAr>wPt{Qv)NBy=?}(e z;v4HDm{KgR=2+9s#~&zBX%SUKVtj%m_7$X!a8qNST(yiAIIHN@)>Eri<2GhpWo;?p z(i{5r_S(JP193}=cOWU{6ZN(2CG1ylsiwt`%nT~h+#Jx5_BOYMl>Ylk>(vTf{m)DG zP0D&r$8UnFFB{Xm}t2iwuh;{^x zMH?RqVQ$x;2oEp`{MmX)oBOwy@fY7h(}l7^r;w+Pk4 zfxL}P^Z*66V7NF-6{pi$luj)nCgc{*gdF!)Vcf1p_E9-uH$VOM=!4QD%8Obs?0w+u2SFXsJIKn z_}}T?#(dqtC~A*iOH(p~eg*Bgb|$CMvm&VA_D=NRLb*Xy^#v{ra1|U@vd7=Kc>{kv z44q^C7+38&-x0tga*dBGHLzcesLLOVYN1Z91ruvENJBcb64Ana&)3EtqCk{b`&h7;OX~aegV{KzYN9N#y5!i1BqD(Si$a8~a8dl1`1%kNu zSL~Zom34PfbIDaUs7&U&D%i&sAQcSUy0otU4n3C#v7PTelofd$g9M2Lw`bZ{i#X@f z?Iu^N6}!A@l*QJE0<2;Wo3?(K4H~>x!soTxhOd1p(T1xEi6xcu(w4 z43}}+^~DZ;=IsRRw)Ji}ZNwvBTVF?P=h6pMLBd4&3Vwjq9IE4)7_SDUDiCf41heyT z+)yoQj=gTcL8(;wCEV+lPeL#$ZuQ#peQB43mE7c;e}3e&OV!8t-E6(IDNeoR6f^mH zxXAPg3d5E~&$&0z6i}nKHQ_n$+>x1aVRmnEnjWsybDWv0p{J*VGhZOAKsg`4&!9+-Co_0iDiqDh(()T*Eqv$fGJ zqjX~_>mcW>Qp--{E(y$l&5IUMJia4HC3K*~!zMfmEeqj#<@QBolxMEKtkPd?(fzyU z#;i7x6qqKq7sBCAz~uwKO-yNXpG0r8{9PbPZtdXjJ`--LdLz>o>O6vcB2zqiHmv^9gd#9H`}B=P3=2c|8=w6!nH$M1?uSYuCqi5dYb z)@0&&JED3o%f08ZD|KqNS__0}5Q849*pX@nX4gdNB*ue6vx~9?y6>>eQ)wPrU`O|-hKJbc)ChRC4ukAuThpBbpGf+r%wMF zkIN3AU;Z7(&Y9f4^=A~GZ@u_u+Udu)*+F3+Al(U_7z2P*G=P5X&!xvBD8b=WWl!7b zW_W9=^EI7Pl`q96WgorT&uB#*{7CL<+{U2-ZGEg+H*J@E-_J0!K3Fcfp=ct2N+aOpcVhUP0P0R435&{G~6pi4n;hC*hxKg!`S;sKTRsFmrd*R&r`tF+Y zd!_!^9`G0YAoV-dB6vBxz37Pe@m-41hD=Gn|8lwS_^N%&ImSkmy{(Vhi424E+U%<> z;R#gUe)2g@DHCt4aFTp>El=7Rt1w3-SjHes$F;^S1=nonS2MZx=AfOfve_YY$eCQKJL9Pctc`7GWU*%>`j?cU8H z{b8t)R~P(r1l^Y=-Qn_E;f@0C)Z9Z1*x z!0;eCMzuMWD;`oefjz0r6Kyp&c%@3myV(cK{6I&6x zZF~pNxmHs_C6z6d8&|mG_6^T2de@7;%YZe?dkj6|D|EW@sBJ%SXZ2(0Wp3edj=OBq zCfsb-?<3y1XpIs$H=`}U_x6vwFvcZ4C8)0ahm73gYLUwZ*CL895K@gPo!=@;$foM^ z;glk7iH55tq$sV5=n4P!4x91Nx}_tX?!^mL^H^cLO~6yejXevrW~pPA{&UIB#aHnQ z7ay{NYFww&n{|L~n52sIL>iU%OKZp>j30Sr>58_Rh1Ya1RwW7byuY#egag#p z0k(8pZv1M%CSwvg%rCl?IitdJOR@&u!=qc8EQzsuc0~tuHhODVbj|A>gGJstLANHTfryWKHcYmbFD5L^X76WO;(F>*-cQ3S$Vx16tMt}(3zJiGmwRx z!))4J^D!z`s;^Uh)O3UFrm+y6$O~W8ECav0Oq4|2(0D76qyKZMFE828r4&URbJRCX z=6no$n734sfR*Q+jG9%#)t1$u11m+IUObl`tvDqYEt&Y zki^JkyYY`lk48u1atGb$HDnIuI092qfD8(MvhnU6`L2zn{!^@EB$Z@H&=m9=lz>RXws zP}M7Vd>RR0&)B6YO1Sp;r%lxwwa;!f04bc+7@4;QGSNSw;s?3b;g{2#*6OAs`_|n4 z)|0Un55L`|_0ksCNZJW#ctd{$9QBy0Y=ET@8Gw!-h2l(baAUP$O^8$huuL3;Xfn-&iHX#0YCjY%6jS!Nr3jrmjj`{EUBcLR6Fo zWanTtC=A7Cf;d1h!8{lK@ttQ5e8OiXLbOfCU{p+6{VfdgM20o6?0dGVG=wDt=p(Er zn!MT(*kr!S-vYgCZpBx4eBv-wsaGPxYyWNj=k=NIxi#WigC#+evbsNaUUUw=efgjj zCE!GXd0c_0K69L&?OYGE6I6N=xqK`v?_PPjZqo#bLhP6g4y&YX&QEba5F(^mN(ik5 z9vjiEAgqODIS-#jRzNyhuiy8@6YPtSY=D+ zk*1U`gE1!5R_eQ})_ymgzxHJl*5FcYNgx-#qTDw-2W^-k_d_+$9OiJ11N4C<%z9I6 z-Fml5c-pD*81kxyKJsG3A;Rt|y)#`rtNtjd^L_f5_ZHqJbdvn?OC{_UR%O{g96uZ1 zB%`9gVqaq*)Z^a-Pm)gA6v(se8XQf`wOZY9+_6fzHB&*rI<&Z?kvgAldseUb3i{w) zbOIa~O6NA26ioYfj3>0P&3jbIUY+VKUU?O2c!W(ILZQ>0}UEM8TFXKcIb+Nd# zfBM%nl$}m|uvRcqf~q%kv!Q#*uk>Y%e7L1OlseY+3Ifg)+{h7^2t}UPW8)0Q_OxZL zs^tU&8SL2WN%t}?>o}IKv{(9Y#Xxu*UP6*3Rvo@`xzGDkNTjP5Kxy($q8BZpR!qXSB6r!jYI4WjEKheQ ziQ??1SolgqYlgH`>FX_ZX^4DJF{9HJ-M}kF_oj3pM~b;WQqNWBBgQOR*1HZDU3zG* zV`rA3@oZy4BX4^lz6(ZnUw#icHl*&!b!WS6-G9Zuf?B1fZ^?;6`Hi_XdB7Djmo$`W zmk0W*#ReA~rV`+|N*nLMpVxSb8+Pbj1Ozjlc~C29GtnQe%Ex#_FO@qO=lnYh~Nhyc0b=d3+UgmfljsKi+DJnRDhr}>eYk~0E@PA`8< z`!*=e=zsY!wH>DU{Om1x73zn#N1~yZf3O`m_$_RU;MDzX$QinX#)4Fo^CW4h?UH8N{j!fa{E1|+%=wnaZehPeLO=tS_#uB zhv|(hi74}DxE2a{v^^P=0xz+0LqAXbM`sQ3IL)~M! z6I-??hRinRW8(b0R9Rj3?-|Iu32&UM1knR|7u&C*pBK+enD8we*7H3J7~_45C5-+c z`nj=6$BLw_s*!~*3??^atBj`|%@Vru3Rso$5vxD)S<$6Jyrg`5t0*C91ZEh5HQY{k z!#>&gL`wY2u|$k_shJAXX86vd?G^ z{t07Qf4oY+bXZ>YyOt~?Ie*1Ab@=8G_VeT4OJ->GCG5@ho4ypC-F@vuZhdBtEUC zOBIAZfY!bn!mx<@w^Pky;ni1t+qa1N)t5L!xxMQ?c>9yC5GB^ShL+;@C--=V&38w47qyijGDL@Uhacso ze$yb01B_y7#WFKGGP)NOuT0sm%EnKXC67s}Or}jc3m744(#lDs8p#H_VZ#E|oHY%= zX9XwQ1kR#9enBa?Gw8OTjS^$8sS zVAi?vCxefPetX6AxEux}X-?R!cggQ@s|2^ARNj8aUoXaS>yacr!lgcB-45@$rrKn> zZDu=WO=_76C}VHDiLZ3}^o)sKN-lQ4cpJGh^FfO5$GM{iVeR?4L^RFnDfL#Ru1Ylj zt|Q;O3ztHS!z|K>u&b?EmeJf=dbHO!`+^BxHQJ=%6w7FQJm6NVQxM?JJ3p^fjF=wz zRSTh7M2VT7*9m`{h;(5kK1c1G%KIXto3JC5eqL`uiCD=2I-|QdmbKg2r&gDtB>t{` zE+=k+bjuEDU38)lujg~^_D{EVh3khWdh)v4GoP|qO1w)|t2^TLj;}2#;rIhSzH7vJ zR4%FOpnB$qGhmQiT~_I-0_S2isPIs&+m83E3p@_xIMHMofPT$6qr7kQ&SBN5pqio| zeqUW*l4Ef6F`8rN>PWk{^RZ-CWJQFW5r&q6laP`GGrW>)gQ(66^!iU>w?{1-C3w~s6dNE4UTf$|&ITr2WQvv1`(oaiA(V{jSEE|AJNEb7)dc=7 zb{|k9VKm`ntIt7)&?xaIq4R==4_$m%)l8=>C-u#tF%*6j3KD|-9>(?p`>~_Xh_A4^ z`{@C+=xIJf^)Dv$ zl#P;+F>gxo!cR2?#FahP!1b7*yXLHvb8 z+4>TyMs#b8Nfkc8h?It676|vIb5KawM73)Z zQ6C8Y1$pgF+Z+Co-oe=VdrUCypTfN;x;L(u+$c>>WCCmd3jmF}i81J2LolfCb^c6e z@lw)?5{b!6_rLfK#%<3II%G=AsZyHqJ+qYX>w(PQlilCj!XQ(PezNv`sn){^spm{Y z_b1AL-O??X@ZE3J@yL+|U~lQ(!2p#^;GDN;GYtm*ff;Xodi_t~A29LsY0z8iV}I`| z%ldEVByGSGgXI5vqi;b>?D{V=!{ReD zhDfQNee6*_|AF&JirTkVFb`B&<&-va%=_GsEx(=_r;TUc~gGwl$he~MNf(BGV~hfw>$k_=5>HfPdrgHh2d z;5}x1dM5YZI6*ex)|mKN`TF17z;n4;v~~U3&jbQ^ayW6mCq+iizR7TGhx7QsZZx{7 z9#O_{0`Nv^{rjA&|M46z6%%Y;;c)Tv8+Mb;iYRn9zsVsUF`m$qz#-Y25Z)K6J_N<+031dH(vOH!aD0(=P}XnJWR62 z!8&-Th0=zGsaW#xxdiyv!idQY`Q%WPkUv_ec-#<6>2mh8oynDIg+$u5M8+P88c_$* z9Y@j(BIAy@LswO*e;{3u@z#)0dhT&cgo43 z9)+1mNl3L6E5vh~oZmFr`azSWi1#P9P;kWALWGDUuk`3~16EqG>cwEEppsw3$H??$=HL}GkV5E z-bt1VQ)0>d)Dbgp6NX(RE2q-t)l+SJY}v!|vz)q@%AYXEMQ=OYPDt4=?aXu=cTal8 z5yR}2R=^64B|iul$J+*@p$VKXvg|BYcVpH#hwWOOluU=*Q2Ne_>Wgo78RgizBA>o# z#k*Jp-vGj*lKKH3RWUvLMVQedjgiTwZCG?>s361&+87Mx;aWq-ADd-XF$&jcxE9qB zH3;RE0bD}x(ngbWi5&BMsp1K2ZK!+ptxj&&lx?li<~=5iJ>>8CBMe2({Un;lOix<H6X1D?&l=pvmZ$iZ8Y5*jGhfloYQ()yP*eL$bl))5k$uBM1zw~}@pdmo zK`6_D9GcWFxU1%1vpk!d^knH7@jzSFij7vM@(H6(x&hL{rFl)3s%AE?oQJGLnY;Nx zRjc~zAZwcxJF||g=9LpG;QI)bW$4;lQ*Cja#?0{@v`jq>{YYu^98SvxQ6O80s9*~Q z)|5D&Ph2sm(W{_#FY|WFMoL=Ez}^$7`_kCyLKsQu&3OZ=6QExl?m0IvlP(GHyDB(E z4&MCD65D#n($d!y3a3nHMhYJ%kGxkERNr38+!tuNZ zG(+r4Z^<_Dd$vHMMJ3%WBZ+ecA+D5*=o> z&(NzPpEy5VBal>ge-pZ$C47fi=McDTjh!&OmiaoME!NUo>!F>-iNO+9%A>HgF0EpH zq)B9l0xu}MiGbhe7mhjKijWzn_0xA+_x8}EIU>86ZDEF zM{@9>0sGxIZVMmJb=o6@UsDU6^ASaX@_2*kpa-CF_e|YIFRP4*U~SJM!vnDM5_ad zHEya2k`~8T0%Invo-Z zxd+mV8$iN0bDU(Du~_EP@<2=x9-s6b-Ls&k%=Hd?8On@s@QR*R#d?w3gI!@YRdp+* zG!D98#yJMo6@?NcFXZu8uU5K_MaO#^Wt7^n{3yjhB0)%3AIJ1VEae^fiqR3OwKVFWri zA!K)5-Rrm;;yq43^LvIB!_{9}ju_g99t&FCa#k>R`?i~^%tQ5A6?P%9199z6i)cC> zy?+y^Oji@E5^eN+*sNZqE<}h!rbDOi5s+g7uiO9^Rt_;U1Ja*dZqHo-7&78e!NPH$ zQoO9`$4rON;5;4SM~>H0U3Cr8eItk0aDCA>7nsg}vLv!$28al(vj#>&yF8xVYu%n# zxy{>dr-BB^;N5KOTAup>Y1eDq`A;cI&kh4cF%i9kJ2ANm@%+-Z7rgX zFEeB9=t174W}-YMh151smy2A8<}fJq#?+mbw<3&GZtiAMajMmoQZRpJ9~f0a{m_AN z^*z_IN?u;L*mk3d=tlHRN&~EBN7{6yNd`7Ty17LJl4eQ~3(c+7fL4_BOn;ox)bRGi zHgv4n?&`=coC%n=w>qx# zqt~x(y~28H4)LWO28CN4G_Y~%w1$81JLjIA0LqSrDplR-6>U0jDqeGR?+ zkmB(m??zRF-LbWiF(UBWM8Yo>V`P9y8vwhVPnni7rmVq<(;<-;;hzX=Zww#G% zB_d@(EKO{eQGw%SW);hhzbeh)Dg6WJ*R=JE01KEVFfH!{{Kw|zu2F%GTknCq-l;NF zt78t6&X>$t^Bribl(+zV+tl0InIR8=)iKLWRVC}ll<=(eofHmF{)OqMR3*{&#n26b zzU`jK$C{HGfR)iE`^*XY9C5Zwa=0ru68E4c58!}RGm+Y@`hKI@0c@J0zvcGR(_hKk z4scD$YgL15>RN7SaPYiRST1iZ_3O~*x+E#18f)aBQN%Dr&Xrj##Ok747rMCDc9ALo9n^_qOZ1SFbs5->Ac|Ly8p z+DP2o?o8973DbcRM*4xFAs}{8w#Jx)=2oo-AdDJF7e!C)C}XDg{K7>-v~hv3lB*-L z36jFSw4KZ3Sylh1o}Dvp{aK8bZEqEmDr)!ih@&XS|4{D&Yb-nrFR4LFvUQnp1f}H? zD?dKZ7AiH9yMboF=s)=jmp084QXXwJq2@bBy>`Ax@2p>J`aV+9xnoc?F3j(f+Luja z(+uv3%xXGyck|<$-R<4VSDZwpQ|_bqcN3+y9Rkyb=h9W=z;o&b^out1v{#wdRp#l} zRiFGUWp4n|EMWDB5b>|B)63~*v2~fwelzdPo}6)j(v4D9hz{!XUYCmcxdel*E0`WV zPn*UDT@k}uGkOe{Vf%{Ebf*dVts8=*IbwDYtT~Vrx?l@A>9stcCrIQj2)5T9T4i>7sRl7zsw2vXF#XvVBJh%I5ei)z!w%n=DSLAv+QkrG8HRObT~muq0wl>afX!=K z)Ds?O`w6Jf-j|9qF`!}0f282Yxb;Z|4;in3+{WF{QBC(GgMq;5GL+Iu^putPwrzYU zO2r_)1PjX+l4c&X0Ymo9@fDOn2H?3)zGg80lBGlFNjoeZs|VMPhEhlH{ru%CfrMmU zB-^yrR0}GdcY-$!~Ch4}okDmb9pcfU6u0ZYT_ssk45vT(uQ+}xi~e8UtB z0R9GdhwnCtl^JB??F0JCM=p%#DLjQGE=kQuI{C>mL7_18pEQmggv*O-MWK{VQ|J%3 z3MBrt!U1cvLU?IaZcRHJ2hX6GD5lqxn+t2xt0DON(BL%?CZN~KZ~vvCmii_cl9C#J z&1251Icnk@nA14Go$;7a#Q?07WXh_#%{$LJ!8NgODA6rW4rb6%3iiMrJN^^oz$`Iw zs<0Beu~Rpy`$d=Lzi7%z^nXwo_7})nw*BoBnLU2wQ-AsuKdJnNld2M}tKf(K;7n!u ze~SBaCa&Ut@v_3W|0|Eihsj^LQCJZcEu!<|#-hx4XlC`FcFUF9dr%PI?X1LKWR<0D zzi?DDdE7bvzu;Pyr;pfMFaDi!{q|wd-wsKZi#PwP36jO|NHFm4yr-}E{(`_PEDxXm z?Pz6ovz9wI=PcLyV4DPt1Sb4dq(`M9Bb`gPH$dj za+a0@eWtrj>4^J=eqo;~Iif##UNZLfKCZt^SLbZKcpWfGr4)Ho6TR>k5bjYHDyyfG zHa7PA*;uW}#X;k*o+)o#wr^%+xhyOJOZf_i)6WQl6SZfgyFJn^UYrQVCRbRrOLow18?paZA3PhA zieo&@=WV`90{dgup<;RxmES@{W#=9U7Y99T@3~kfG9=8rQS-No8QL>7@1Ez)geecu zKVI;M(#iE_1i`U0CEX;&w=^`k%gKtJYbL^Q@`pgleP9J?tmP))(6A@DZ za0Fxcp#20)N|TZgQn&7G0q&d;1S+ej8*c6TAq2Zii7rgKID$l0LWipP6H*3EDU($N^)6SSA037WZ_Rh_d6h<5uF&BR-*6l+&j7_;2xcd_P9;hfC+ma z!wsu6@_DW;*L00JUQgJnY-uo05Hm>V9cXC9Pc7}x<%6_k(K$sL{1}w0!A|(qjh?83 zAtwr}H4^ldXVmJN7SlRat=>ADS88XA{!yM#P9~i>Pd>(aN_L0Zx*$ya!?}$&_7w@g z*GuwFO7+HT&8=J#kF^J_zBzL!`p#+`H&Md=X8Olc_l}4=d=vqJ&gVb3>4@M$QXa!f zyJjoj1^mMeD!lyUW{);zHKG3&lCisdUo{WMU*tT;mGtdEW1giD2Va1^Nz+22?0iIY zSDla48-g~!n5nX9y1QI&H8tYPD~FUyS69KAJn1*w@ahPKjUIJv!86itJPCoULWSvX za(vPf)f9w94FIW^p)M1Nn0FsljD(yT8CcwX>Y^Y6=YT6TQ)C6WiPP5)o;q*svu!=Hr|8afjO{lF@~?%% zzXfCOSOPo|t6*{2_c(DvxP9v5WYLl$$1=vRXql0>=U!g$8&(Mx7B@2rKW5|}`SCpc zB*}fh-WutEU?Eqpq5wp-=+2=zo+?Y z=p{nnY6QSo_2-#!kIFu}Oj!d%o+nmR?Fj1qP_mm||Kr4>(hQ2i?TpnqFOnYtl7M?RF>b%}WV z%L5|ks$`Gaj%yJM^Mxm1c>5zEm4M<|wbBdb0(|T&5>R{4`s*A^NW-10_n=mVi zN(?NeJvyjLxG<>l6My_?09WpFRsxG^Zr4G(w1cjr3aw6(lpc?|N%Go1fT!n#CA-J8 zCz&XB*tl=6%pBq@rmHDE^tDO06jhAu} z@aMwH!a%f!f)%Gb({Cn6aFu>PLVfO0a|oTbC?`1^i98G6jc~U0j(cOVV9AUnU1wNZ zowUYB2})-qxly1eL}niT)s&Cbn?m81@bRWgI@?Iq*S4FD6u zU8MW?T%}H47dd$5F||;<(>``5;+b`ok?RUu39=4y17ibQYixkT8pk(b5EtTxkE#>! z&pTTsorMWt`~|CD>bQ7;nOjj>$ptpE{jS#k_>D`-yt%5Rmta3H^+qY8r2Fk5x3@Zg z1$ykZ*4zYjM4sE2$$W@M4EvUbw7`U%CJ3q*^e_*a-5BFnGovgUq+R>zjLdHS{SG<$ z18I-$R};-1p}ImoNrAfE9L*gbPnhqNYDLTIHq+)J%SQ@k4iKGJ5<9n3r0)$6x|RA{ z4OI&b1wHJef4B8(+r5@h3=Jzxr|Z;xlZmaD=WGRxo{zgTx}%@iA2@xXV@wNKHwUUy zOv+mh!M-F@brlZ)2y4YLucqj!zH@%_;u3vuTaPndTnEu8doOs+5=vTtVQI zeRqmDvpjDv(|%V$liYjR^i_i_m1lZ#2Gm)I?DyW`8}}scsy17=K|yrEg-!xg5dnR# zAvk*YQTT3tD!hN=`Zv|PtxmV*FMLZ~__FPw3QPB`owQa!%|wZA^!Q8+;I?Kw9OERz zxmE4HO|qiGzXix zZJ{KG{ggmKLB`_hB7pUVv%#iet{{KZMWNGbX_* z-@pBvB&J)axRt9_c!Z^%-*M}(ctdX0FjXOe7CMckwoVHYKP;DLu0YpCCeN3sJ&CmV zHoO+m^0uO1^vsAs`YAML$UrNTz%$NvU$(pZ!;zsw<@6sSb>Hw|vytx`nE|aON?atK zTLy5}rVm=#jYLR~+t=vE=Rj&&t6l9F5i#o+!tyD9854!ghJN|c23sd@1b!oN`l3<7 zsQ=r;pm=ZGXzTEjoW2Q~x*LpMOSnK(3d@)q@m(9y5YehR2)cm63&Gjy0CdhzsO&>_BHtaQkq zulVD~L-<59rq_*7Yrq_g?NdgzQSU_&1a4hNL^&jb4p$RwE z!1D~qRyWGl@M=c_9pQS7M7*wgU2-wqhLi1Gv+KrIVxttJL}$1&8{S!aPb5YQv0c6E z*LxG(e+wXQS*{Fs2ib3hkQkD07g*;+HKO;ro5K+9X zPD1B-Mul70mO%NJ;aV0U0>#`g}VO zs+Q`gC@-hv|7`t;o#;}f-Hno(DGB1Zu+!un)s~i`R?@uN-5G-8fmFTy2EzX&e^9wF z!p+U9)G#K@UVZF{(^BQ%{Wf;z?Xv!{A@ny#`GOkClzT2NB zTT$e#-lt~QFtfhCyV_fsHl4OQf-y(pcw=4D(<-B-1y&A)Puk>mHb-=s#p8@M#_Go@ zqom@CD*BD&9s<#>+kZI%H{#myq@}EO&Td>Lq{cEx)o&rKHmH-HlAx>8P42$<|55jz zVNGUV`>2j>7zM^*6s2V>$RJHYIwUG8DosUt2}&;^^qQimpo4&d(jfv0N()jFdPEe2 zPz?|ugou;?A+!)62}#bw%+Gnx`+hvvdH>fr&*wbZ``Kmfwf4I2d)bgZD8EYlxuGJA zi07FUh|7m652BHN`VGWd%5UR>g|LV7w{AOk6?d)3k+Gp5?;+F(Y&~uN_w4pcb|7Bi zn68)xzjH0zA#R3$f!I6Lfs0m8&oh;dVz3hFGkj%=^-43FelycACA?G{f;qWcKscD> z`+~8dgzxqfdbv;(j~c%1uv^)9y%8$U$o z-W{7T{e8z-r&E>?P-i=4BRDgkXBl&y=NsTA?pM-d$v#^+DM|dCD8wj zDW|6!Cb&X8R{zAiG5-VB_;7T}^bnDn_?9rM>JHtKV9T^d8NJsTnA2@=p4YM?CDm=9+Wrw5-RNn(lS5 z=W8qZD?3AY(#(U{-X)0kAK%b;G;Gx0Vt^1b zK7%|-ko5=ksZ-bOYii%~A4Tw5Rn(GjDHO<9C~j8#;0RZdvno~X(;5+VQ|L8h9)>Q0 z$=IePmFruE!wFLi%S*W2zZ|q#x|T_PPAr}R)Ojx)G%HB#UFi>c#Mjo9Ys9H8NZ!o& zOg_2@US~+j@^Gps4ywt}beO(78A-x_zK|s%Mctt$#*n(>`J3wKvYO}~*bSRA1nH@a z(ApN)m1>;>e%2s0)3qm^zNYbvWU*+*S6Cz8Ijt;_S|r7QQ&?*lA^J76KIKM@pvPH9+Kd9eF3TD%Rj_ExbRXkO(=z`=k zSJt0=eZ9onWcSyP-r+k&*1h_jTX6B-2It zRPNiPZE>sIiu9R>#|r(BHK-B6pdV(fK$HaTYs`t^7j%GcZq?KA^2djlesY`ftwC48 z#v9R_=dxy=j|e`X6dPa%A0bb^vnZ!tU&}dw`ZDwCeu=c4l=_5=&W^4S|Kf8l@^}c-dV_s(ym`c!n498`QIFzFkkMcf8Fb*sh_~it{Qq0MfjWDHR z5P&I8y8r~TF;;n5ib-P$N#oDbi}DPbq?N+$U1bHLiDI7g1eJPSGk+X4QbXHaG?P|Q zV+)TWy&=wuCJPdZ=D7Re3o+Wh_2pBilmc1@=L^fcoH$HhoY_RBx_kB8ERM`+NEO1M z$H}5OSFUVS`69(&(I|octR2>%JfT+$ONN7-P6hk9&D)LTCb)l(9K&5N+Jn<|X#aq7 zZJMi~uF`CudcO%&4N;qc^_ZzWfOfoR)e?NMHs|h7q!>24=lLFFV?d*E zp|U*Sk@jj#@X3C>kL?!=x?$p+ZGiM0V&3}67zljw3Q1?~$csO3*=#E8QKF8qg zMe8p#%5xv^bWe>fo|PXxLlz5b$iiC&NH>KocMLVXf>i%maKDOLZ#wF~hdEIVV+kfm zrN|ROFfWFjZMlokz8b0S{w8#d_!lE9qv#T?hM#g?~nC9IRLL4l05i-k)C}0jQL<9~Eq;BCXLmcg|l+@4R+=px)`WqFD z|FdU4_gKDPdb68XM{(x3Px6`7Hib`@>!o1XnDO+(2j5x*Lats-dqVWDS3|~7KoX0_ z*QmkB;||zD;=Epy;P*5-E;10^{mf3)q|oWam>!2DHML>!R;XkjOTh5KYiKr%x^8~s4nDd zS3obqQorFZ;}SpfY|}JYFK6|Ss$cL<{U%YOhn|oq;fq-3oL9F=TiB{wK4Y0?J@w#w z+xm2o=FbDVM?!p#3UG?`h*y49WqF)K@SHuoFEB>F%OLo@)Bym2%m$qQ*`KyA(ht(! zKK$udUgG_zu(Hjo<)k*}U})j8_96hHK4>^6(n* z_$!fwQ}Y*>uTHQUe?OmEM$!oVGWNKgdJogE2VO-l+$6@ht%K{-=+ z2rF^0E6CholYNdd{MLr#Zp0Y))&d>(-AByz-iT(>YvNjH@D9}b&{aSqqjt%*dtDxG z_gNWJ9lSOIO@bAC+uTvo_~FXgN&8&SRoF-=b75-{=SJ@(lW1ukI!xF5Om(EHzF|Wn zE71yX)>Qcy{zPVPq-WuXWCvo@V?sR-HQ0cP_z#9rj55-IzJ}^zmba4;EOR7Pxo$O|J+C|d zw08{>-u!`65D>k^e^Kpjk8`jFI$LyfJ?+UdPQygzLtUO@O?atCYs*keF`?Y6UR06) z;j07sW`wPbRQ+aX_uj-pKkdeaVA}gk>J_xzXIkPF>EU~p^pUADni}~#z^5pvg-Nkh ze6nigoRRzIB|*f?^j`thk`^E>^6IB`kHWn0g30kejwDNm8%Li=R$&Nc+fMxY^KA8) z=sQ<`q{z(7rygz9)B3mZ>4+x2bm3t}H}&Vw6vvQB->d#Z3)m)l=j}1rF0Y>k0(oShR8YCz!A6vDWrU@iu4F?F)FT9Q5pe*&2YX?WxABW(TNa6*0>Cg`w491ON zN!Zbm^}aB_Q9R6H_vq-tuA(tN0@2@Qt2zuNm*y9V6LfRoE`(X!VOb-yUPXU9XW^F@ z`$+X31U_PYpMJ z`0M3k@__k1FZcI*K=>3}9{pDV@#1dQLo56~qYep2!{4S_moEr!#-K*zW`y#FYr^IU zAh8I%^kO>$w-*#MD3Be{1UeH8B~z)0D8q=Vkg~C;p*-+`S*QRJzf( zBXoO{?&d-sBKL_ApFpx-q%5KD0my~zXU}|7)wq#F`9BH_NkS32)MT1j_x*>d(v zZ+6Zf0M1&GwUPsQ!khmPl#buEZA#nwRs#rWqP;&Nyn zNQ9mj`4`4e0w@gq)1800BZDVxAJuQ?5PtfBYWU>yTj@Xj+4+M?a#vHtI&X11pa$~S z|4?84W|xI;pE-TR7Qp&b+(#Ug+&e1qzrK%&8k=2_&?~>4SeAz$1WS3%?Rv~4)`dmr z56}ZI$wd74uU9q?teS2hJzG!dau)+RtsNWPI(%N-lv?Wn4MzinvY!9i=7>z~#N_aN z;vE>8DsB{LX%2EppXfONGF&hB8?M#WBl~MiI_dVzLrQr7#cH8@)QdVcHJ{2K*S<7(jM0p=Xcs_E({5N4ilZ?nmXaC-M$h$IpK{(|W*0dd5+| zF%IA~F_eBx;(?F~?pI${%p}E1?G{=XmooGHC1GnCE)>N2uLI38mTrtaBkkKH(s~3= z)ow@IN6rYOM}?1V#s3{#KuA>Z@l6mv0S`#+>YEu29z0>}-WGa2+GsU;>8I2?u}4)Q zGQTi^KlA;+eM7BX#b^in%veq&VZ>W_9#mbarZP0!eIATHB2h_1Hy(#SaJWhOzQH4EpL z76@s&*38aX%DhoGxV0F7o^N2T+}tJw5fuwC&#B{UWgXR6!{(9z&c}%|i!bDScX&E9 zNTA*tZS&;>WXqTX_q@b5WSer}w21SmatUqloV!DzotG`$vh;;pn9D4_>3BdVg*7A* zM704c76Gc3h+EBCfp28GO5yPa0pl4#)RLt_3N7G;K_&aOjHAAZ93m=5rqo_2B^r0J z;dJ}ZSG;u_5)u5hU8yu{BB(VFIbdo?b2MBpg5|(V)^<8!*6+VjvQEt;%vYoe`Jlx8 z>+i#9`o}CFyleztIxU0c;l;_nqtZK|Ki}#;lN2XOOzPI1stTgtf^%0s2R+a&;+xJ$ zszMF6+RXYZB@K@`nDo#>HX|^NK^ypKEToXlsoi2*C4K39(6JW2LEPdQf2Pxt_yvv| zT{96|E3TC=ra|P?shqO3d9#kZ4aOmUm(LxogW@&ia@4lR-;r zpl5L)WEVoLo75#3AU}*l^Y(BUmIM`xwK|d(aTgtVOF%&<0m3#JxBQ>9_JDfDO&Lkj zMIGAtS^Ojf(>bHYBW=N%V7s_=1;LWVGE8-uPc_`vG?M7*N?ymF4@bZYi(NB9YgyLO0k$bqsv8)+V|kEgU+=0 z4D72`dsv7sNkub<16#njRc4L)OtG&!lbcZIUA6#insi}f3xb&ni}uem!j@l3PgM)$ za(r`wtqx7P4C*Jb$tt9&c6{$kc2u*2u+lMnXm0h1NFXvC!ZOrlmSQ@TknL_83`o2H z6WDA};hdInoTjrBy*hc8uGND#mZEo2ky+DE&fe73R?!k3d08GG3{#{SlJ8m-2%@Gr z>f8>LcyPR0y&Pijdc78U*%`G_4Qi z(0rB~!ui^oB~2n59LER;Hr&=OC%Dv@M$QF^+)ISM|7eX4J1&TISK4n*}U zB8iv2e5s$`d#xghGuWRXEXtP_?&=89wl!3@K?SsB^yALqZW1B29x$n^jajAbxYolY zt%QmKAsb5zD9PemyK`E6UWSG*EvrVJ)N?kk^A3#b^o7?hh(`8Dmm!UaT9#rjTU4j&}2U0=|DmZ;=_x>+%b;ON-$J7?iUg`V0A&boJtKq+<*1E(uV z9OoIw6linAFd+S#?Y+2my>*eJ`Spb?+mlI2$#3Srq>ZxZ_L1LA`i0Wj%kP#Eb%KMO zWYIg!TCWCZSWnH0Fpi7ohl2b!9Ekyg6Pvb7a%k_40|dKOgT%*83O{Vv8o+4>Om(v) zv~iw%VUjR05hoXEiVEX7tqx0AWMH2rHh+(<^qcn4K(16C3hEX|ojjqsndzv<{Uy@9 zM>=R>bIF}N&JUtfH#+u6Ivw=2bt?r5w*O0)~-r=rLZ|5~V(o`>f5MgR<$$yiI%E zU(19a;$JGdPnuy{Q<$KpPJU9^JVl_{X-TSl`KqiJZ6Mk`Lv86 zF%Z&brU&|`_ETYo?kNq1_+o+CI9ShTrgwwW9jMErt#T1#8&b^3Dv>9vypwk0Yu#94 z5}Xv8*g1e51N)3O>p8B+Hl_eO3%uM@*j*@Yz+W(}o2h4LAkPZIU!}BT&N0*$g0Ib7#fR=~)uyU@G_$p=fn3>}>&nWoR@ zCWRm!oC!8pMk597f7Y==sfo$-tm@|H?OGY&GKcHS`4pq9<~Tj3U2lOYSWm`w8F5k_h>n*C~vJ7L@%nq*F?jm)w` z_lG8@Vp|DZc55NR@CvJ)cUTv(P`fqX66d}uVM$`eP@8LMkmFUT651tQC$PG@o_W|M zA>kbPsAngg03ohP=b)*UG+!C*{nK^CeRI ziv*))Y!f7HUdNq@$eEl(->72yHVF$Nb2#y_G{@?bc;UhKa{nGJ@O>pKk4na$Hb_=|O?S|_8w`;$f2@`)tFV;f__dop@l zfBW&7GVb_5mU}l>)MMs=?qkx?n-EwiPP&RVS|$;)#IkK)ZDvE4cFi*IUf z>T1~{XZzbtAG0acCqZQv zm^Srkc?y3nYo@cjl{Yn=)%hl-5qYA?_-_g^MMelttL z{Kmp-hqM-HN1>w6NsB!Svr1H9QlhHLwCAJzRFJ+eIdS^|0zuZCS^wGKbM-sPXvbP` zeaFxTzsXcs(4Zzc16^7%J!e)QyDQ}syTKDA`fGcAtH%qWBm$cUDG|#YyYpm>FesQ^L}NXGX)dGLZ(Z>+wM>CPbV5MOHtY zn9JX1CXARHoE?kii+b4hhSTci?d=Y;<)fR2Ry9Ac$=H@eaCb4?PxO*zZ9l3il43q0 zJ$Tv3t^q7+T_YoUJ2X=IX9oA&jV9lZNDr_Ip`w?MdjFKfmzAY4@>x#}7kRndFhtK; z3o^we5L4<@C!q5S=^_MF8 z_E2~8F{wnJ<2zPD*-`^<`pt?bQPJ}`WI;Ise@yD;4iB9AT&D zbdUVVI$3M8!arPHMu`40w*+`Cx=WetxwW<+dayR-k?`fmjYpiYrIcE`Qx=?@ zt=ZU>{x#Xkjc<22>{fyq)?{t75A716s&|Tgq>d%I(IH=O#h85D#ErO~GZUo%4hN-B zmYUnQj4Hq#Wz$=y^>S;nciq&zOulB{y!UOCBO`D@Zb`3n5`9<}9pxxg7qzAl{V;PI zo|lAJH1Dm9Er?m5VXloWPOoFUU29scS_6rN2%6cx?!<|Rx=8$GNrMC1b<*TWYu1A8VdU-JUml(BwVz$9Z@gdnuLK zFm*pp?)ef@7&jv#CQFl~n)+^XYD}(N)}Be}7L6Z2>Gh{uZemb1pg2lm&vF5U&^w~> zW6#2%A*3KuS$O80){DM-ovK*&Aa~Ympi~m7#lVsNdJ2z)r$#QxzD#S&QN+|TR3x~F z;jv+@7%L6odYyXU0=^*YYgI~7R7jmfrEgnk|8o1Z(qz$>M$tfrku2vXJKE}{>O>&= ziBArdiyzVq_N(67yxdO*xcjSavi(tjtL0JM)7vRaG*4fiXNi};bdAoJ&N_Lcn%y&7 zY7!@DrsDuM@F-kRpRl^s?pdy$myYUD!OBIOENE z%V|sNd1;XadU36Do$Q+Wq^O~gWJvvH4vCxb_L%j+cD{EP_Mhjy7i&NYuZHa6cQRO0 zMcTAeG^yY>y3Qeu!Np(c%mmyVx!x}Y zd3Wfj(Dg#2-}wDuktQb9kkqgN3XPH_OC(T%v_E5o+bh37LnwQORAgK zV+P^GoAk6%t5!};i?XbfHLB8F;k}{gEfsuLAKI8U9#VH#@^edZE`7)>SuK|f%cwNr znaFsx@sBM!M4=qdvc>8UQ+2DHDMkG%$B@K&dbY-NE8S6kqs!h`aLk0*lbv*KnH+qz ze!NEgY@~hF0Ov}YF78@xvz}gDZg5rCm_P9eV=33d`Ky9844UM(MRU6f|Ue_hA<+pb)OjMtnlh!X)llNX^5$JpFNv5%EHB#;$$|4PwQFpSBcIi z>O6Qxh{eI8^2s?skIrTKT-{vf{%IB+aSL3^`>2dpo2P@cEwqxN{hpWB@M(tD1$Tn^ z$qR(o(cUH&^8N#)objje=Ra<)^bVGy7!8m!+RIT!*j8?2jAVJ{#>i#XyRhc4Y=YOj z@Chl%v0tSU;cu7B;BU#WVZU5krhro0$YJV-oP)4QX^rV1K!|)HcSR#Zml3-;SL~I0XajjH z6XK&EOrnn|>oI+YT>aNIpZO0!a1plf)m81N=~QvrLK+0OCGFcZLSWJ*OlfG?c$T_W zWK^H1V`!wPCC#?Nwp`c|AyGL`vQ4=6%8?ojqqC>mz^gn&7*uY!LWe?U+8AlH_-rNZ z_82a+IAhyQ)^12zC1r^+1j`#YmBc~1r^vJj2k90c4!BPzPBX?ze@w?y&YW(uaiujO zcqw{j%d@vBN)X(ewvK@DZ2cMqZMwYkQl&nGN|L7A*E3$NGq4WfKEI05h_BY|-oKVI zR*1dglnM`9yAYyx z2i9?@6JfnIQOa|n51b*xfq=gn!bKPmD0FshP;W1{{=f!EaxMJ^lVb;^-yseu)L~_L zuEDamLvp6lgj+sFu63i)cEuqhqu@dcIZ35r3a zH~m6SNLY>mEKxVQR1Z*00mWLCB}tcRVd3irxtMXkbeBW#oBwsM0VNer&*o=f+39&e z#$)%(@dZG)sGhiC+;nwtndKD%uo-5Rr3Bq4Ql=@iCi~RJ8hh?K=*2z|x2*2waJ73} z-G#m)OLp5ujQQXlp4?R@lyKt24AoUCao*;taYFOQ#-Gl^x%j2A6KYLhH9VOAOYZpV zE`-2cqtT^9oij7->gF863jSkMU_)$1zkoMYhe2r7 z9SrN#m+D4)%cRSN`d^vs_3Zp&Jd}RVhkhJ+=);IQ@LhpOYm4Mw;4%!cVgk{!5R=U* zvgk@oevYYcAL~kAcMOO_j5cb+lDnK5EW-SqmDCK+^&8xLS?=pxU>FV#w%T(0%RlQK z?Pf-F7RqYPv2Hc*a-|0uJkl7IXu36MQpt(fs$P@?ji!5Jx>E>q%Gk-tRr)FIkSxId z1#hrtt8y0o@nQ=1pLjzl<8xcarpwEpSv}eoGi^*{`O__~XE#|Q6lEzG)Nn7tQTA&S z6}rN%5Iu$@G9LDV1Z}@ZGH#qh_+gY0%X15Yer|}D4x$Pw82%c*G-qRm$psS;$lE;J zxED4eI;RUU;m(=s#$VAE^4teA*&dB3voR-B|JOq^HdONE_89QNH_*u;>{~hTdaj79 zmfwg^uFqf=JEuP|!;U};^L`6llW6f~S7zHNOjfkJ2XG8FpPQDYDvD=;31_6hr+ep8 zhU*E5^C97wORXLl)A+O`ZtdO@ad;xQ0f<4!PbR|rzr;5i_H~{{x=`E9JZL`9C$;_NTiAdagbFd*p;e^Z-QeL0qjgnN6>4JOLIaWAh=I&uGX$s{YKAno#7YQbWBR;2QTzA&CK=ZG$duNJFxmV zL7jHmL=*j_&K?{8#Lff(ZuWjUyq%f?mkPG zc@T!$*cu(~apTUkPfptQ#_9PbzH8%}A-{4aT{Wod8~Ky#jD8&ScNnkQivr`!3k+WQI4MVG> z?#_%tvRKh*Z*HBlO}eW>eNW%&8VKi4P}19*KY3yMSZviBZ@y9hr|k@;2Gc&#(iz$L zjFSWe((Kk`1SD5xi8b}DKYTh(9PH-o@T&b?1Ja*Be#V->HncwxZ7blIL3C|SDaV6B z&Poym9CiLxdeZued_Vj1<{rJqwylB|`cguoSx&RH@TN5uI@Bqc6}B3OtEN4%xJ1@z zF9^+avFhd5JHECgn2W}(Lyiv_{YW0oUaBbesrA7)*3@gWxoabh-yIu!o=iLAJU&uA_^_atu$Ji<(cwNbcLSM*X}XiXHD%e~ z2-Sv0H=L-S=#%!#K?6CsRcc8AbE_Sj;Xcy^O?QBvupK^JB*qjmkBJpc2yJqKy7(xK(ueWQ`e}x$G+|{!d9+*k-Vbx4I28+e z61@65EIy4K;5Xr_{Y4UT5Z$!?A}L2D&D8d!emGc`dK>8=N1Ib!+PkM?m8+fU??1cd z0g+0CK;&qz=hoIv863p{oGNN;SQtw5p2f9X)Ym&CK@mzrY%GK$N}38PTRMt)LBvED zG}{d@*G9<$aEeUbr1Ul3EG_}9D2kwR!|&E^dJx!^dZiN?0@v0D;*is{+BM2dA$OWg z|14at@WpPedEzr%zceydahNREyRE6PxwEg^ALc+?&+-rco&!y~*7T0-x)KWH%arxQ z+w*SLqXCC%(>>Min&(I5qXK~ zu@K%*bQAu*DoeE&akOi(pDL)^i;>Vc(tj=hmV3Oz zD3cQrlpNRPoTBLLZ%7&JDkh#K=t8Y%bURr0|i)@+@#t=B4i1Q5ifnejs#l%(u%tihHN zMJ<1_tLboUcw`Wj#hYye3I9lKj<+JxN+CacCcUd_R+)6}V_za0MO)L<}EAofyQCYEN~*F?AHx5rWz>)UsixzBjkas#~nXB^Mtu}P;# zrGGu8x(vFsKplZte;`T3GVlitQ6!1TW0YCyU zA1R?ZL|QT0C{Gqh)bmA|f1@Z7P-Dne0mXhly{Gl#d@S(TL{3gFFRf>Ytiw!zdD{a{9Jaa)(fW^ou>SYY3pItMvE&?We$aWznJ6s#8gJtJeRVl zqV2W#j9&ge^yuB1vhs{$`bMOvPE{Y0Y6wRyUm%Q^Z}E1gat3sYp5}pL_x3LQjqLib zDZR1b5;|V~re$Tw)dc%#y3;Rj9M<>QyQ0-_a^lX_^pwSd8AS`dr08z=E z$&mbl0dpRgh8BqjRMayP`X?0JPT3tTHxvnMSrI#hGQymAZ-dDl5v?cY~G$nV!PD(*u4BTJlwCcbjd;)@Wf z+$~*BaXG8+I%kkX|AO&8YBBz2FDy9K_f~stqr>$3%VeT%e~83s44?`MHN`=E3gV#| z#|TlUxqghX{4RAZQESPbXN<4p-D3(wYNR?=;>+HvgTrLd#1IsrsH#k+Y`Hod%_^fgMMWj-i8Yir%->){ObtUc8fDlTk(XhuuZ zk6P%n(#+~!Gzq8pHA%7b^2+f!b<^42-FVINtOnCCN);u;-=u{bKflmx%utux(i1u781C z17~ej4i#VV&kfGontQ=>`z#{stSC{4um`ihceWW^tKhydK_en(VYKp+Ty8l--@-py-x&jM6!doJR(X6GRY~CTyHjjB zA6jL(vsN3XK>4uEstoMs3!d?MqaQZl9=&P13Z1~u4ym<=R=}3O?x&r*4?A(7yn?!C zW|zFCi1XJ!PKnqrAWqo^#vGBwu`<7P=HO0pWYR`{UJcQazNl5*lBhv_K{=ARt7c)9 zh@Keico!%7?JGNLE@7Jg%9n1b@!dV;S4Gj1WEWKj^9v5Om=obwV0R#%YdAB?Or0B& z>1R2V44WU)9@hS?Ak=-sy+DpLoqSJC1C7gF!Rb(>PLqz}cKX&s8*%-xtl2$J6F$6m z;d|%sIR)&?{0o#f(}JtSfT28=E>p@L-5SwQ)t=&C;$-3F@Ykr;2)!<}fu+FuJryKg z#M(DHGJt)H*@jk%0rdm^bLtUWd}jIY+>HiPmf)#zMJRiLU)bao#OHYWB_dTmKKcAv zQEO_2Cg*(#B>I?hkEnHcHyOJQRkT<#n?VX68*KQU<9pLP%-hFGc8oWh2>e#*Q(SlR z$5F?{5WhL!T0P%?9{hbLesW-1?}? z(2*Ky$~5t5yQVfM=H2~o?ILlj7T>%#le;kcMI?eJZZ$6Y=~}CGT?-*gm*aiIq*qz` zj5DEOACHsIH&LU`!S+KQo<0M;^864^QI?Fbcctdd)i)2ZZL*f634R3hBgRZ>ijoEy zcOT41cLGD;9#JlsI2aBx<~_cysR9|(@)vqp+2lCaS{O0Hc<5Q%KKEqyBd$+a!!{Ch zpYxC7W_Hj;b4@U?n&aipav>`l%3~$>r?>BQT6>in;7};fukSTUl?D9{?tfantx|0A_na$d(v#zM+ znQfP(0rxrcOi^s~uhxdEo=xvB=cUb;7TEP2N}q{)p256k$|xsh1v*C;#^N<=2$UCz zzTmR{!unn+dy1TO;#ElBhztOTo$_~lMxll|u8@JaAop#guh^@9mkk4uKb!D* zb3;=drN`#2F0XRbwb=*jE)pv&;!YiNpPcKx%5oms+=mSr7Ck=cvc_9oTR#!xf+;|C z(^Qvir=M7Dbl8&}e;qw;3)>zHg_*2BbgNLj-(el<#3R6fTu74$(iD$%tjTtBc4`jU z{7o!C>b}RTaeo~*Wii~{oY1M%&=4FYF_>|)UZqQ~QOhiZNF46bdNY}6;aloZ6vs%@ zhFX)5DOt27=pJ?$*E9gFEn>~r>Q-IC(z4`+>223}tq#WZrHN{@zHJEV7C5z}gra(s z#q>#K78BMKRwYMhEjNJIwQ=QOCsj0NU8d#UWSjI7AH{uq-lzs?0wFl zIVvbwD?fL#$13Enehn`zf6?BhZ`n%}yiIi-1QcmygQuH>xm`K$D2QC(;JQBIHy?6g zUACmV^Bf7RAlcg+`$zN0nJ<~*;p%r%q(5z5AxT|GlwR=4xWBCI)#!L?$Ldf<3Elys z?|3BYoj*01txM8avSr5`HaX-**P1fes>(>=I4+irmmkMp zhTZM#Uf>}dKCx<<=}fgc7)+{^%lx)Pi(z{fdhWUeuw1V5P7uUM@N&f{{v*xC>;?;? zP#CUPgJk+a8c+vfPEO?O&8%DAa<&J-Y1@Etv4{VzB4SIiJ^Pv!d$>}XWf5y{GjCad zNrgAnVGrKw$x*X_NDDs-FlI+{I4@C<#|G;?mO=c12xny32bw`}N#hHS51~L1B(#*W z2e@3^g{L~N4Jyp#vLf%S?%%?s2*KTZ1AJ{K6TrKr@Ib|y8XsHCtZEg<0mP&y_RW+*-yuKzBBhDS!~?So8Q$IiGD`? zTbz4}{r*Xy!pmF><{{i8kqoKH)(M-t0pnr#4$X|A*Jf6%wL5x->SXP^RTP;)qOSx# zds}F-#HJpR0)ClAD>DHCOLbE2WIoqDZG((af`}-S)Vr!r^9sHl`K3B?Xe+22=jjGo`(hL>SXN38a*0B8JG(FIqM_q z#9h1;WKU*vRLGYE#^4rvTXyg%C?5KLd~?x9LpL)uDOz_Nseqh;^pSYpMbyo}!8g zuRnEQZ=8U_Gd@XsQ}fPLeKFc;#CqiCX;&jLQS2PxPpNYl7k+!-wq0;-$9Z@G85fmc zQVWz7%8A*gq>T0(9V=YQGm3K;3XCe@&<|c)Ef3;ii0^<>9E#3bjoH|t8mBcVOT=nh z73G!xtY*100~qWOKuG+Hep1FFVY=Z$0qgRKs3 z<5>+4h{gNU7N74!H^|p6eDWI6^xf!a@siDRM^Y{mPXEmfx?x;9v}eaX^S=qeHzMXr zEMBNO&vbjn!>(JgO&MF zRY$+=b#UHk!X7AvuD55K_i}OK&C>k`E0#r)PwnL~!cK=(?GsX{MIyWd$VI-1%+#zd z<$kJWu1?3Zh$yh#Iy({>^lisK(t&_BZrT1HBbB!d#3Lmp>t7(K;Flt|dbx42QqNG{ zQ`b4{0>CmIl%%KCrMav&H@$00aznq2yvX4qgTaj(7y5m@xJ&c7@}yL!u# z6rLVh%eW2PBiagkz`79?E9ZP00^W;kw-Wm3zdows{k` z;&%%EvWj+}o=3hbIc|d;QJ~;JSBb0C=E-}FOV2InS4?xroC~Lg#)SZIrpQ$D*H9x;*g&P0-(P^<(=BSKk8BSZ{b)=pFSuoX zv59v={G?G?f6;ESOOiFlNwR6-Nd$#<8qaXss(rs#Le7m6Ehgtjnb{xSUOE3Pn7)c2 zo!uo?Mpl>AOp}_T9mjcm(9|c8c_+xcIceK4=zN>6DRO==U*q+%;&0WIf40E6($eUP zQOpgi{{5uzB;mN@a4td!2>b)*(FIHF1-AX)zl{Z~`n})0Z088BRu68AYL#Jx*BRlZ z>&8gy}L)*F?#J{Y* zjCSu5AL^{@*Bc8(DHgXv9IJ0Fa;HztF+3|q&EFRP!)yC~1E8?&*kJ^y*Pa*g0}$ii zj%94j_-CwbT64Om%2pZ1RpT3s?jRx+P^_pXO>+AHNC6rE(%8z5mBxaVtdcI9HEMVst|0Y| zMSHUr)5wx|el@U!pr2gF@sbj`1O5R-g1y4;*1y6`Nd30x=;qV_;m>U3OMc@0aPiVXM zj{X0{u)qGIh6KuvT16b%vAwX?E2)P{$JI)b@7N*GVMkt_nkBvUe>Q5$yRGz(Na}?@ z8`qehU99Hbfw1-w@!3K1DwSu>se~q(HgAU1Ek7~5?|o=&<+WqP{2TR1W0z5v5z){i zekROGF+CZ|5x|?e5=NIOk#^^b8+Yu%_ohsCtQoNsI)>q&up+g~`;t0}y_)MF2{U!U zdD*5jBP*Ms>fbwQ9f?jF?tbTJ58_iq+O<0uDA?5fYnr{@E@}H+9s!*32p6xo0>R3RfO0H}HOucq@m|zMxtg5TmSeaCw+!0p&G^hBE&!-{p{%VFB*ZMh|(0uXA7`S(LmA+h){gtFTJrVoK zzCmSZ#bQc_o@%3haojul^~mLqH-l2jL9av>^{q5-v-<TM<3@i!|}k-i}Sf6;E`e2D9v1(8QyD zJ>jrI6}IWJGim}=_pJ!q8CYd1GkmyQUt;{UvD;#If%~V=lT!k3Vt&1R!A_Yq5i9Bc zi@o=biz@lzL>m#5&=^pVtfGJ*L2{6!f|5a?$_?}beB*HU_5AemL{bry) z?ycHFJ%JOdQ{@t+=<8N{{~qVco4m@dVy4NPk_~ey$+I`xr>YDa0C5iWfE)5y#~yyl z11^&Eed{vv-xT}S#H`mXdboYe1@Afxt_8Fd*+q=e0cFt+x3&Shq=0eUvABU>4G+JH zR3O?*?mGYu!}vDCGo=^UsvX|*Zt@q92nl@UA1Xzrc?9cU?8)oOD<=9#gor5Kv)G&E z1?Y`1TmGyy$3i*W8&k_&XGB#edc!xm!eO!+D)2dq)vWJx0`JlRhv|n__fCDVCjmVm zZNB}%BI58nOwoW^Bh%nDZoU7l6_H668Di968msTNP3vjWY^T#`+-N&CrWzVwU!mpa zg%5$|!>#k-Ds@Hvtc|PDbKYNSO-2(>CF_afFnhw+CiA5gF}6^O3Th;~W((Sn2tk{A z`&l*#tGyv@vPzn@_?*THXK4wKk8QX645dO)vo#9o^U8dAM%ifWu0vQ0w(anBLVy58 zINzKA$y%wadJIhQVWX|*e*c)BQ9?L5b6)f-9znbSWMm5T*wzK#i7j|a{jtGdvmv~7+P=Hgf97FvzUB&$tQ z75zm#h2RpdUP~!X_zNko_$a;FiqBVl3LP>Hm5}lJ_B+zw#k@2%ru5T}+P6uL;+TOb zyYLW!{(9XuL+{{;tp}w=nXaLMnqeuZyEMcO4n{=j>l)jR(`B6q5L6hrKdyQP%yGf0 zq-Ooq1pbrx{%6U;SAG5>$B7Nw_I*Y-sG~gfAV`eO8Es#I0L?U($-23K2|;5M9t};v zdIsvBGaQ$$+m3N(6&sk0%oM4MF9cq7!i&?HX#wBNSq`?UfTF!K`KfJN6F>EUn+F4W zN$R2<*C>kxOPqtM^siaIN41I02K0glZL8vn<88jaKxZo_T<0O#O_WH$^7Fg3dAnA+ z_EbohIaFxW#*#sjDhrJ&EvKhfhdIi7Wr*Y! z;QM7cg1UU0)ztb3rlbP$wheAj+r8+ty*~h7*JZfpl-xaa^@74c4WMMmC%idqiq&a< z$PuJ6c7|=I9WmS;rG@*{j)3l+YT0Lmfb_-BdYpQ-v_4LUeq=FYe}0NEL5M6X7vfP=$xDf}i&u@=jp;<1@)IhaDl5)2%s zS7B^il4!&-G$J!+-bTHu z0if~9+4(c_;L!&JS}ebZ1(o_JmfN&p+Jsk+wX}bL&_0y^h(|HFwHA+BL2G6S?@^gPEptqZ?-&zBqisk7{?{$Vs zirIv_p4;6feEm`lG>+6bz)*q^!c)Dfzob;L#B0DElH`tD_Er

    ^~;tySzJLdaw!fTws>9?U-!r!>v&^6tuRn}G=m+gyId z(yYs6c{e}EMgl;*+Aq(lKZL2@)CQw7s&8XCX?js%m9_{JP(b=#c~6Gp>x3N+U3+t% z{NraEy}afO&s_f+oRD!P50D@h(~-%&?UaO=JM&iT4| zizN3tynxF#Dh@z?w4IMajd-`da|orDR>kzVvmSO(%QHOOd%RtyEoH*=&V=u!bj%xM zMfRmQDW-La5X~2P3M@>H+#0CNg5SUI7v|Om7pbgF^L~J#?K*_>CO<>PXyfB1GhtaZ zNBpA{%HF{!?gG8s?)L{Zu=U`E*N(nrb9n5R(HllwryHy6)biqabIQik6;C6Rj-&6{ zC*>(@Bk&N0hAp@NU=V7V#W{+vuW*PJm?O4Avt2tH}@;!gUhcy5W08)coK2_*}Sf+D& zftsstoAXRg4VhZtj~`u0mFSW;TVJU88uwM}IH^AV^i%K1PAfzNWB_#?($Ahnv|dE+ zq*uGAU51}(686BZ{GoXBHZKPy&8mmEF*@xlajyJ6Zk&Y4^Pj?rHG z)p@Id8v^ha>c>T|#MZF4eE(FMy8*@f$LDAv@N*RO(F;c7cO)DAV?5={>4sHZ+cw3_ z)~6o+`9AU=?_&mf)DfW+T~ofH-9s4%XuRD3ShJ!C_uvmdc>VS7rpRqUdN5I5VR;u2 zri$}iuiqWag9tRO%EFGyi*Qfpescz}6{oE+$M3*Yn8A0u=-Ja#yGWy0uIqapjPF>< zEn02s&`JXH$^zGwNBMA#>amG;Hc__YD1|BU;O%BDbHCj}0%Y`zIY-S(7}Un=$)gH@Ba8Qe z1Muq4RH)0HQbY)oVg^>`qLe#pDpp{n64Kz+L>gS)s>B(PS~Kno_k> zN)#bV*8mWN1X4>5JY3}Yxiew}OBJ1GBT`-#-wY=%W|n24BJz>j6T)^Uy)o;o=xUoS zw=Gjvpru_#fM{LMb0&?9_5*6B>lx#eX~iL@Ri`803Mu{gaa}Dv*?b9Nci#G1}ERJDlt zwIdt|RfMz!GT@ZY=L6LgF0bV@r%==y8`Kop2EgZ9rL*}OEOp%L_USoShIP8E-i%T> zYA432S8+NDW3-Ljsy{h2x6yGEE>fv!ET2NrTTFALSP6j^ zuL6hj`nf-Vqv2Q};lN~x%0rYaXi*}iVC-T)^A!o}{DnltKH_lH-MoqSW=Ep3UD;+V z#=n)?GWRRKZymH|sDs@_s+b&638mkqfIM`4xl+7on)Z8yB^6TEb(3&FmZ1*k5aOD; zdcd5LeigI~ug%uaDU8I_A+GG&oTSUE<=yv{tCiv^GG^c;8+DH9 zw45tMQI1jx&kJKWQ19|3o;8*El+aqXTuEU>PsfQ%0cok|LF7!Qvv`aS>tU$f`PeBy z*X`u0Ua3%d;gp)o&wv7x$x_h#nKZxFDdIqubeH*iDxz^DG_F-VW8s9@b2#-}V%D>^ zD5P>ydKZgpKlC2lp6%AEzsDj`bnx~7?xQ4w&1eD);i1c1;%0Q?V&;a6T@lQ{$#rOZ z%-CLR!gz8w!3xBa{C#_CatR8!OrV@A>rR@_b-eY;z~*2dpCXqa)eFQN+7UsbLU+R- zHf^nZ?l~jjpGdM!+f^f-Ny5Ol>3st_Qwm_Am+mGy;hbb#VK11T$X-FSS`~Zv0D918 zC)y##?)%Nl%3=JjJ*bMt9?_zAbwOH{tD>ZV=-(Cf%;E^YTjL-RxW4T&Wr{0Ule5OR zCgqd}{djU9bcZ4DM5W^lh@A0s<7aiY&O21|%$=bJo~JW97>v>Z$6kv2H2aardB~;% z0mb)0R~4;*0rI9(f1lo2gl829K(9dg=k!Mjew^w5k^kmP7WXD_?<)JS(JU*u&=H5B zZAKDyY7RSBOh0^7YeV?&se7*N$ItC;>_%62I&Y7q<<4Cxn5!fkb^Q}`1oo{pBUcjv z=%uIKjsnY9?Q&C3-dueDt30+vD?xBgXsDl9>sHyb2ZVBTQ&!Niura_fw&gJ(^*sZO z$Z@6Zq+Q$kWaV`7xweSL$+PKhK03B|J#Ko}-~py-u7Axh;Mt>~^K{oNJ@{3tnxAX7 zM6sr&PC-iYZ@i4lAy5#?ypbTGw);VSDCQnGQ7P!y_P5r-!+xg-94w z9u`7)V46?NC_y`HIcAmCO`9+EA>^{%dHBk*hV}rg3Y&{t2}u@JO1n=EjE*Z$WzI_E zpu#c?yatzemnR)P^0@ISE(@p^eEnVVnf{Bl1`mu==-@k-Ghpwmubp5fdSUT9 z(&9$dzPf#^l~b;1BB}h3Tz8{Jlv>cGmMIm<{gT6r!rtAefA5lX2L9&`Efhk+6~zSo z{U3>MWsDLmYN022^}GBcCVSUIsoZ@0`%7JPz`?a(uxN!{#;5Y}a`v%2KLJ~(T|``g z*-AOPbUGI$Y3yCmLU~o9)~aWw#UXH77YxiYcSpK1ZFkovbAe^|FnfU;hsXF~fC6AO zM?k(^BjRkVfJWPH*Hx{3a60Ziojk}gC8%!hMopsli;JP7jjl@=qI zlY*|~;FgALb#-)u;c@U8c<)MOPRNHH0YcH9!pb!vhPB*L!nYE*!=@ODm7P$R1)E@0 z&M|YauV@WWql2GA3zoO~?EM8sSd$e#RctC}dH>Nu*}_XzOL#MauH3p2`R#c{VHkYQ zQV($|g!>Cmd12%;Fk}|A^+qq5t_i5{99GwazW;i;cQnut43UZJ2x4B3*X+0m8YZL5 z#W+ZxESH2h?i9$=UAaRWvM9V;z|91f>U@4(LbnK>kq(5IbJOnZu@Tw5mr1krLULz9{1_$T+jfoDwg$fJ~@`GIGf%%l}2w|sE z*hlkps;$M$F5I%)Tg>$BI5r8~(K^vCbdqrFq98)l_)qv>>o+M>Y^)qRs4O)AST`tL z{g2sDK+HM{$BVzNeC6z_zmE1U70@w%8B&_ZG7G3Ll*Okx^;1~+8*T!ne%2E2n7~SE z_WU-tmTi4s3e-40Ss2<_0=Eh$)GIs=d7x{d{}eJSrww+X6S{4ZcROOH&tlnRG-J_e zjR&OB+(6t!OnsmgDll9=qyGdfDi*KeUv}>Kf0xQ%h1?h>1MN&ZqMe zOo9YMW~|Yw=uCnHF!Cy1%Q21E#c`p4gVqwmdhJFySnJ`~vF>naXF9%V$Mpy?XVqWq zJJ|sFKz!o0Hne|qy^^NJhvuiv_!YoN+~E>d)`3rbodm%8^}7fb0;~C}XRJzSW4wPu z-<_?KZ%S$;B?JoK3|@47U+Qt4M3v9DfM((T!1CFQd2zU#PAgcB@0k@nT(Hx%Wzg2a zx-)!UDM$;f%SXToOj62_ z!(AyCK=2IX6vhQwQOk7Wisk~^1JX+0z+o_t=re;nra`L|7oYKBLcP_YO3ipWa@%yA zHMVTL9R3z0aHr4LX;gwCe+Yj69revEFHl(I5NOn2T#8{p5bc(KU@E}he>~VL`P|Y0 ze!@14R9O){z(+k;yEoqL1}MEhq#H4_wo>Cxnx}llrI6*ViJ`pMK+ThF5SUM;J}!F* zxWo5CBVHdwd;T{{I_dl)q)MuwXQ_Z{2wiGhS{83NFX}Gq2cm$^vApU-)(^Iexgig3 z;)mmj%~L)U4M~V2FnQ((KQpa&&uq)`?u3%Uv})@ibP^aTVg5o%%UUbFJr(4#pPi6K zg=Jbv@i_;yV^69oJ!v_&Rby$@$*WH*y;{UzBHX>94kv@eSOiMlO{jkjm{FDQiovcc z(!TaNM$EMK53A|BniK>S1~)oP`%IMY_(@a%@28oQrh?pIeFVM-+$P+y8oXW;9+J6J z+{)RNHgA&V6EWW<(YhR50a7Kw-^yabER}%IKTvTSXEi|gtG_&Ija#x#1FiOX*@6Tv z5-8MKrr6@KxN`m^Vw_1J`ia62XgHymoR)N1@;qD0-O-%y{K1_N$5>obclBuyt29d1Kw*EX{d z49G=9@GZ%JEv*aFK{;H46BALKdM$D>X3#wCmUOv22fEP${6Cf*2kIjhn0Vt?;Mh{gVSWlR~^nPBlirEFk!| z9{K-`|Jn*;A^{mEU^18J-c4ko6H1tYlRb5-PN^5W0;Ca@{-eC8R8K#d@+mO`MBjf8 z3wZfQb=iQ#=GN~uI)|?o0q>`)KMx#)132R_IhWw~aEqcp;ty_Kc>@8`Fs7UT0~iSC z<@FyRWo~k~_3J~k>&31ry$RQuWg}0$X3_UFMQ$P(Pg3q;ifTAdZw0;indN0O`EcorO34LA~z0WUar;@kbv1*gG;jR)h zE)*_krtg3=xhx>ly%E8S-$BflayRI%rB3E|W$ee8BJViA(ccSdH;wf(!AJS>?(VF7 zc~3UGA#}e|GL`0ffG@jdn(pLy<>>RmmZv{ho7C64FQ6GHy(h*a-5KQ8fkzyW%wpV&pEvDSrAj@C@CiZwhQ%C)7x@GQO@Bii*2L9TkJmDrSal{D9xP&`yd+&{kuZ~l~73z{n zoR6#yB*rwOIu^+ucP!E|##GaJG;%y2VAX(G!b2LC*BjZT;tBq-RTh6!Z`7SLEHOMD zmJ`9DPVSuSDg~ZWRoHY{pujMxW)v<{OmyvcsB2%jBk$*fgwolsmqhF)xVfkA%gajE z+)JJL#m6@hw6Pc?7T2+AG{rVeFQRMbzyE|qTfi*xol3pzp<~8Gnj!}&q^E=gQv6B| z5iLitpPB#6#zZPvY0fVM=UT#$yO9{}^NtNdUAY&BypX%IBoD8l@A`tydd zrw1GW5WJKQI`FqCi>SmaF#Ax~B*jKxiBm@6$=m7uXQmh^cFY>zA*MCy)1!wrEMBg#`91O+LeHOd8Z3UJ#w1bSq^-D{2 z^EJhPP4kqo^Su2_&YbGNfEN6{^fQ#_7xv$OT1yes1iefuj{tCeRlZZ@0zkN^zbl)~ ze+iz`w}7ZS?(a}}klc@fpPsoTP9W87ykcy9hXdb^a=oH*wV5aHm2`W!zRU8dHH&;X zGM8C^kG^s3T3pwjI(N(+-wr6}IIB9Bh(Q~-9Pzop+m&$=c0l*1z&MCF{>StOHlUh8 z{R(!m8}V<*FhCmf1VQZ3D~>FRW@`lO`&ujte%FQmo>U42M1T!_z03@nC{-f*@gkDy zdwTMIn_p%rN{6)Gd-Ggfh9EWMab9Yw2SO3>h|@ZZFXeUZ75IrbHpRxx1edbpR}66_ zu&XB$A>>|F@Efoc)apIf^Rx8su2Q{b@le=ZuWp|g_o^@poYcc{wR_8>ehsyceKWqM zTFWsdN(Wo0uqq3*@^c%fDR>@tE4;zf!i{aW-!scW=|;fmoQ) z`mI}C&&`#^JaE6Q7>}9}j<|?D0Gu$?qa5#TW6JFGv?M=ub+4z0zJ>kL8?(gZ);Nc~J!v;ov?f|tv%HlJJ~}?# zG@ie%5jo_jsq4btw`XsKqA2g?RNXM->JRHT>;5(l>bb0I@v>2Zo2@H0AwjaP;cZj7 z>ZE#Uh9TEA^!EH2F){yqM$vkxfuDHbwlxZNsoLyJMm84WC-!(zka$<2L}L8gCVn`9 zQP*%Ztvrw9?j%Zy#P(r`LlXb;<w`%t|YpvSt zV`10i2n4q_Gs-+ld`}76!_7Rrqg-w7{lJx+D7pE-w5xBlCt<2Q>cir<;gt^zC}_YmunJ<0vV5MoLyfG;JSkY;;6QTs$ht; zhc~RxyZh^PAJEP%;9r*=>+4-L!HA>?m4Im;9CZ~cc+}M5_PrigZ7X5!`YqV|r2)f| z`W~P7H=~iw3q(ULvxN!t4!>kFEsFqG{wL1oeJ+8&Q@pQ##nPIASGs^?>E(j^3RTuj zBAq4CdtS=t22|wCbXV?L#BYq+ERUbxh7%$Dq{hxvGKOSFOl~I}@Q*j>({KVA#l$a) z62Dk*-Ax!TRzeAh)$1_5$esLL;hh^fC20Bt(*d(6PH{TIPTSc_E-Wt(vl^Y22HYdp zIfY+Cav~!%x=o3^ zql>C765i`14wP$}9}#&Btya92@aFZ%=7?gx1t$MN3EUJVHokLn&~wPM?%>V&tx~fu zD={|MZa>Yi1BK^8>wCBT_QwzA^Hv;8yzZ;qzYSyn#3|y$n768 zB1>HbNx^g`;|}@V1XWs~>2>obX@FC&`+mU^aRCqjcPd2mfAA9^a6zD(@m|_`H+k$RgR(@QAS`F@dF2f~H@CDzRL^Qwn+xcg;ol+*9i45Yve41-tks{BAmdb= zKd1Qy6?hLmGYQpv_(_e#VZp$3Uht@Na?Vw^3@TvVQeOA~`-ywKJEq9!&X^zQn#A7& z_)~_~+|YJy`6ycgpFPZ@Eqj)c^G-2HQI&?AyiCPFmro@qj<+C+M2c>f?nc4xEn7?d zN4nGcU*Cd#hW0NX8Y`Ii2rh1qCXpB<5h0HG{psp(LM&atnGaC-Ay5C(FvJ4U=NTFV zk30RCFVZhU(Y{_~;OH8x>z;Am2sc=d^3c&OLGirRqEU%8N*z0TteNTMc1v67qwT|( zCjK%drFp`DnZGR4zk0O+dIgiT8;XI7&#;{*Kl+AOKpAdO7FU<>U11ZQ9Sj&Qto;pD z$kc3oS+Os2IZj!~tk$@6lRcn&!8A$tEP}WeTwQwV`1%hcP6|W|Cp!l{0H515;=EuS zC?%Fg_jNx5YCgsx`IX;RWMcH(1os6@$K}^F>lv)(T=!kq&xQvJQt|I`J~A|^xdy3d}RAP#Sr7%g#o$$&sjs{ey(&<_ItZ>PWg zFF0@-IMj8tf%$js>ryHIQdYly0G99nc1`%?1UHFyr=Lq%*kGDh8K1mZRE=937x#8! zah5w%9j*A$V;9-$6?^ew%e}CUW?^X>A7S&DcP+xgv={H)e54o{Gxq33#LZ-a83hpb zh3#Ei=S$(R@zSPuoOEIj#(XLpT$jAy2TKr12ts#z3-8*yTfSTX&*L(%*7DVdy8%M5 z>9ptz2*kz=sC`neZKVrrE+NmPo~q;^DH`Bc&`VP?d4n+M)vrL+7~sXu)7sXmxAat( zfkPT#@m+^kl?D0;xH%s9bo8b+(f#kbP5>|PE9goG)tefsX7*1sr&=ZG%_X3Z^e3qF z;R>K(->D7)N)JEnL#C7{r%0xR)C0Jf1-xkX2sn&v(VT3q{}YEOwUIi#{Zv~@?BCz& zZX8m#n5!qFexIh2e4i6*c#TBCAL5_rSNVVQuA!_MM0wRnG+k-a8OHua>G}A5MIbo*3KsCQJ6ubLBb2WY>k5S&lb+u6 zbIjT)^yIll>_=J6TT;^JA1_vQ@N!r1A_^9m@Db~QuiAzBn#jAXAm#Z6qz<)`SUuJ4}Pbe-6FUgves zns{FC+nlCu0(UX(LKmXn?-$Zn2x{YAk2T-)R+t!oEU!A8T*;n+yDq#)k4oZ9`s|J$jn{qu_T|Yz{35N+AdRB` zEU!-O?ftUl&2RHkQ4@|P!&(bMkdEB1I`DZuNa&o{#$II7n&3Rq{OD3aS?s6bI%iFV zw7i;=SRwYl-{#bS5UyVqMfWQ54DJzd7r;(qGXbz);YQXu1b6#?-Gu-zBke%44LI;Fo z&-ck)qzy@MtnE~Zm&g(zeVVnuWx>afz9;~;qg3OeJ6ABz-{y74S=4}O4T#LEe)seC zFTV)bb>vDxny{{OnO2}guxyWUN?TPeKXRG7gLM6k(%Su=(7OHoSw}!*@wopoB`Vnx z+WwijAYRNHsDNbJq@~K0DwbmQ>EaiFRGRPodB6jKBoIPceK&6VLp9J2RKV-5RG|Yu zvv%m(GwCJ1v;_EyCi7ds{Si?8%MmSq6^LF8Lw0}VC6(jwkG4OXUJ;}j>rF4!!=3ap zw<|QqIKZach=wVoX#0Q=)cr3y1)_;EHrk0npv0D+N2Dfp4l$EbuwQFV0NU*Q<(W4z zVk7I!UW^}zE%|4;n&sAD0?73H|NoKvzovHNYc?;xtIT7230M1lWPWuTb?z{=(7#*|NF5HLT;g{yzBY0wt?T7m8Z;{a_k8EqA)`kbLi#!wV>) zJdM%UHP=;rtxjxWRR!*pDG_Qn{mKvk!KO@sd?gcB`&sv<(Ddf>VeP}axuz~h#5A5_ zjAyB?)zhKLpRQ;+X>okw`{n!;f+60f_@z4{LY}IEezgjs5Q?q>51*D?clq@Q1E&){ zb;qD2XXYcP^}-`w+6#o6H~zbnJ!@DACW$z)Z`VAO>}ds~R7^sj23l1>1slC_-{LB+ z>E~lV@PHih*t^DbAf+D2x_fy^TY@b{8VhK7Ir!Yg0Rjf0!dJ%&D$mP008UPUIdFR% zaPa#xy7&%EMvEH0m6Eq~O`>|gExq3Pg^T_DWN&)u;r8l!m5=q6TrV(o ztMT*pBA6Fb8Hvwxby1SreUj`_3j{vqzv@@K z+^C(R;MCM@KrjKCF7Ltksuse2S9+;2N1>tYHdv80ifD7$hDAFi8aHilGt5r^Mm-@j zuLy(S8Ry?5NTt#W5-lVwVjmOyOCbl=h}Pc|UA@>l{9Hi0-v6>>Oc#rMvt| zW!wiN!wQWx+&IlPpR;yq^@-imDmiAByO=bE?sWq;(+@AZBj;Zi?l9H9LleaW;_CVD z*C+**t|5zlUo#}4VgoD2)T;GZ6tPId{R(1R@0zsR9k+Vt_rGWAgLn{omK>{eOV@ zXT=dAYQ4<{K40Z^xyu--1aQoT$qfMH68nYrx->{PZlfDvaThvGC$g!WN<=Y3GK*v& z=U*^}{2U-tK)6P5EFc&@3H^GSDIjxW=`KKR%z-KqCZzS-YD-7`w#hOUQ@2P3c<+eTwL9 z_@!9 zsMiqz$oyA2nKds5_V1Yhh2eXQe;!eON)Y;M@9?2P87RQh?3ZWaLFhd-fO(rzm@)&|3FUkl4|n8%r@qZlh}9zGKlAC(77^W?Y23cW`8u02-6 z8fM|hqGVv+kvXu@c9_3#BFcBET@AaoQI6|6Qo|N8TVcUbk73-5%Gl#IqfFGo1z=3G ztZLZxV@?=8O)>(5YD_>K6<5KM21Yg>4ew0QSz%8MnJUD^;!sCvX)>_Bx>S_w@qKGN z&c+Hm>UXI^oZ&F>Hq2=HVgFfO@+8w`Q+tFnCL6i}CUIX%@<#Mh@Gsos^H;kj#d;17wpt_QmYr^0H7&IA!eG_~i=m8V;D=1~wn}I>icG ze?nVv)NiRrQz?G<8^&##PYwH!I~z9bDQNBeb-x@}+oGn|w?2r{?2`eqhXN0qOy6U}P zX*J}V?UHsI7IhY{wbY=5aY^Iwy$~(vYyYM}OD?G)RDOCWTWQ)RXWe%&xBdB`$t|lP zlgCT%-jpxh%UvUnY{|x1I3_VB$t5wC$w$p(D@DO_+PwyI8wut8S)&Dy4Ac&4W6GD- z-waN_%U1H=eRIsk0y_|cZ@CLv(UJQ##va?T0)H28@m;qX>LbocyDFFD7s7U=D2Lf9 zlU=e<8O%+Slb6f_x>|jDpc7ZVWRX1BSC_3MNfzrT2y~TDu*Js@G==1(RRB$iIgS*S zfu_1k7VbdPC3(r&7@(=vfxYx#?ujhhkr1$r=qi^QIpva$ld`s^)3cRMU{4S1HG#(= zcaDTOt%m$p-W+4&%a=w)`GIJ~Ww$+d`P0oU#TvF;LoA^0- z%+|z{rRt|ZQ&suC0-)*WQ?IpHplQOOb2-p-@=a>jZJ=r1Rx&rxR61uN1Zc{~E*=Vu zYU1fqwK>o^txJ?N2_e$lMG!Ea|Ruf0oJi^7MyFaY^Jf=TJJ^-_rT%6&W?) z#|#M}LbOk%X0pL$2_*hjjAH+2%5L(j8T+H%T|lb+(|eHf$EP~Af3fW3Prq_SCidMg zZ1k@W{K|H}59^9%+pp~M`%Kv2;egBFCqKa-^U$CH92Wmzqdp{%-NST+H9w~b(O!t? zQD&?3(Wl*kzGei9$=69{ZlM~&hwmKj4V}-MuG#k1pi-HkT3=HKMuR-awKDyggUkjT})Wb4jxQ!0bcUG!U#h&*^-uD5U zug<27z9O6(`5xx;WM`~RAcHrpivsUFCDBJ$5a%zn|yUjtCUi>({&*xGXbE z&pn?Kh!&+@>#6fdtt4~2z+K8A?N0B8%}pqD@vpq4ZScDQkm32wmOJ&OYzTKK6rIoF zBPa+t@SMy%q5tU5NKJzjz0%As!`b~4{Sx*`AuX>~&Ryu3j8lb5pG647jdq7Ec-CIr z#oZL!JdWy8cQ?>&qGWVFi%`3SJWvZJMr=}>k8lQ}$HSnpnbv?u=O1pIZk3Y6=O+8F z6hkA#D1*WljO(=v$@BcJQ>%mSQQv(|T~+OEmZxe2>7L;+097T^uNzY9$(5}Zqws&Z;F(iSX zkIIL%g-k@`jFx!K$J?^sr@J&B>S&uoX^&p`4g0AcwD&AUELrz54X?ec5~s1)q0!jA zA#xd&bM$y-;nB61n1lP@5J9o~Sxe!rh&M11R72TjqVLK0L(144%Z7(mX*0qmG;QVE zHmKQK{`xrrSVxU@_o3v+Q6`)2`MfwEdYfuj_+9MGE~`#)9{URYkzY0zdf4zb7Jr|@ z-#-S%-;N&V+T29Id5<1rU)MdJ@o@IeeS;k;!t*pfS{d%)fX)W_nN}X@U_~0d!N(4MvL5nu`J> zDxp2w9Y}k-`oX14*G?mi1&&pYDxM-mYQw7bmABLLiPXLOX06l{8|4GMr5UXQtW5Hu z71Q0VHTPgu5^dhE_3~_|$30ip)@zQ&IF`Aw7UkWx!mlAmumVH#9pOQ^*R)N&)<${4 zarY6eauV4ib}SQ^^(dt4-qb?=v@Z6ohTyOwhkIonO|E$$dg72ayX}Vg6?ksO;%g&@ zm;Sxea=Hx2#Ag=5$!FuuPo!m}^I=C7tL{iajQf>bS@%lW%>=Bz_RRlfjykl(P zcx0AtW77U?=F{rwoPDtomnj$hZMTtW?w#qziIQptb2HQ(8j2ACon5%ErJYtv-*21l z{P|hUjaLtx&HbFm_vhwOBICK3b(kF;-?~AG|H_VDeen?N<@7@5;T4&LpSjHDB_zbi z!Ge39Z?@vwjC9e~d%i?NZs8uX{_^C5VOQR^gw0&)$v84M9A86Kp>Arzp<1Hb*vA(kU?JKOC!6gIK= z+mwE23HxTwEMJ#Er`ruXL)AQd&W@W7cYcH*mN)abdpq(#Fg`^CV@^iUjatR)di(c{ zs1)5@kJ%~2zFA9KhBtD?9sLGo89Xu+@STX;(yFL;)T{DKkYcG#Dgh3pi-t<21JUc~v5*1REk=4A%jb6rA z^TZA^j~3kAy>T)wY~QZyrjK^(E;agtKw!lrKdMFEo+D~4bPf8ryTdlA`Yu+~TCeT| zu_HGD@%B$zVd%3*Iy))ymlqe}(=yorKlVQ)q?H$NW&_$)8=(%G{+gU{`g^{loc zj()3#tIP(DCHD&UCJPz3rSR~mi>8Q!kTp<>&boez(TDA$wU)g&I?l4`WwS54YF^Do zHolp#N?7Q)7HS%U_eS}Zn(5`48hpdTfb;k+ymGaD`~l@=Jse}Wx!3QfLBfqUTQfM{q zCP;i+;X9><0UTu#ck~p!YujQjzyot*8d+pj2m5g)b(I!o*}2~@#CjuQ{bau^C{5?J z?Nq?VugJ*!e2RL&5F3MTb8b<@1NcO+shiKR1ut@zcZjx6yJzckqg+pK6LvP-JR^8m z4PlbiMm6hEX#G$BF@Cx#oPlRVV?RcEx#Y;FL=M==0ds*Xzcg_%G(%`MFN!6;U zzMJIjA(k!@{Jjy5>Gf4J;@1NP$Pwu9c}P|o?wP5Jkj;Gq;fXyy2yVt=!s5_*I1kSU zp~GR3xn~goD@vGU*K>`^>UNB#vxq~nw#V(4jnpyNV6;Swyu?=4AM`M~UdzP3{WjJJfgYc6zMy;@NlYbqjqBR`?{b)G}%Ss`+d5 zLT*8`bxPPmcdLUBL6YGcS?WaETp8+^jbKx4j`yDi>RyrK<=aMU#)i$_QdgVL0bFUG z+ljA>lwG&c#ka@xqt>w2H&~zU_{D5qrNV7RcxhvKpl>eq>IN@@yK@%RStEXBRbf_~ zq$R*ZzeImCX{(|e*W;Je*uc7U(1&WY*)_T2oKha`$Bx@Eflr~vb`*B1I*U$h*EP%Q zlOpybTuGA4e7;C5}$LjaMs&tX$#JX{w{Lz{k0x-{+Ci;z;;kJxX6P&>cKc7XZD z#d#vt&}Jb>Kq1ZrLLK&F&lY%vE-T=T5YORq2{0h6{~zA{idgjLrh9d>Wjo(mYKs#u zUOxQ-a^x&xAjMs-(R*3qa%SDtDP!FgosvQ}aR2<0hkg}srBOTUu1tx%TF$9vA4Ax@ zP(P*V*GDCCweohfBY=C)eC=LoDRs0|d|!c`qzl)(@v!~9T2o-2dsd>fb-nzWHPJs{ zd}|waa=M@x;8J2(@5A6`>GFyE<->&1k=s*~BS^oO$jm_W7vJLHGZ&J%b9keu`gxhS zKY4OyLn{~}D{=vyQ6{!jmlioyqhV+0lXl;k*N&V4fUC7{rU>OUFYmS0=FFnN-*PFs zZ)^KHhxshfA*8AJR&o^8BpIy`#tQ7HY zSK`P%*{3x2E=}GhJaTG}Xx{5Jb2^FRUo5Q9Z_0MhXUQmt!>Jr?Mv?Y=g3|uR>;AHn z07WQLdHqdAN|)*Eiu7!&@1TFzWa(1>Ba`N3%f<;Go8oZGd{0Mt*%7YTNC7c3b0^gr zYVO$M0h$!%STZwySf|{#=QL-1Jg;J+et?S=%7T@RZVgVE2bD)RS$i=mmUsSK^Tk1Db@9hay;|E7 zX!9um$-D$IXm)UUY?;-(+#SidbpGUxQOg+A!za|%i^cu%r!|QseV;V)rS5}P?XdWc zgCn&!qLf?c1pg~i7CeO^1+IbUkT|jr-~5-2id}U7b}0^vj!$@-)&L`zwBY`z<*!`z z=Y%U7wvsjal(y*wM2yhRT1lQ4AcV7$I_4ANm`{9=xw<-$eoEi!;m<%=RvY_xcAsVn zecbv77=zFxr%eoZO3k$`@4n~~@j4CxZOq=QjoVt4#nBPovkukDCA!Yl0j>WnmkTg3 zA2DHLC1s6@$ZcCRlSeRjSwr{OiRxG@{(Yygrf`{5I4=>V?bvb_xX zjp<-+Va`OX;Vu)tWxB(k{H2y5oiBP;Hi{|UA@)Bs>D+FtmXUyGEU%w%cof^#A62uHRlW z_$#P6vx`U4w*H5C%)yUWzO-N)ZZSD4auD0^KlU2{QUPd~*72U`{?`%VyV!%) z(+(#?wuP;SeTWc~U0NSAfuJB7p@Mx1h`RH6h`^OKnioK_C9WUj{T?qXQ~mAnXlH0D zKGR2-&Cs)cSPK}wfc>c}>$&@@MCnt|ZLjCYw)-!ooo856N!!QS7Zs7FqAOC@f}luw zKm=*QvY;TKtAw85BB)3Wy(CdkuuxP$Kp?0npaepPP!cf;LV%z#^kR%5gn-lpLPGMM zh(5d5K0fc4cfQ@Z&NXw+nUk5hfA{?F0sH~6GwFKHDmaLR8UL+qq{ji_%(BuvC&nN+ z@cP}EccX;lZfIp+AM}Ai%RbZ*_GROyx!i!+Ed%`%d{w+ox~F4`j7{B^pm9K;1=*pU zq7@Nw^(JRal9J50T@m@yArxujQSxs_JJ1QNEe`o^`5p5$Y92Ekq09nl-_oM)F>}4$ z$B89vw@*KtKDu3AQ{3|EU-QothXz! zQ%WrMN7yWh*gifv1IjYJ?%M%m>laEH_jf=g2bcJNK+J?GDUx|ya)3+o9@GrIi2f?n#9l`^ zvlIh2_dqf8w5hN%)8*Wxt~U|gIAK|C_TWJzG!Q--W#5Z3)*;U%hP=zJBDKTk=8Y2W zTI^QRS}<23ErcH8+bE(3i;N&?o5OwUlsER7qsm4(Gm$3`=Nq=FFW~B&z^vs0>(`u$ z0w(ML>)ydSdtu-7&_Rg@@aONkd&TcMFCgW+?vMDBwG};SL^lP z=;3yG8bToZhD(Qpz5_2u@M_78tQy9}Dfgb4lmIMzZ04eS9i!t*{y3bbo5XdTm z6PkB}({t}w9K~{3t*w=tE1N@}IO2pr^|;4V^o;YS`A@?)y9JsrFm5x;%bXeo)<>>| z|5)>NK3`XI8!4cAQOj}r=E-{rJ~{i5uOIsA-I!N*o@SPg%8t~cT0B9U(K-i#K{Mz@ zS>&=jjNQYCTZvtcw&S}Z`!_0IwO4a6Xm)$3PD@qp{q;!D#MKO@niRQ>Q2E4HKq4j> z9~wU66-k%$H{S1NO%o)7iC{bMB~C|2z1q+U|G1fua-8K&x(OUXFB}g~AV{QnvhN4g zM@M@_%~iw3+b=s0u>z1y=nzu7lh*26R#D4K*;MO=)Z`-K-8f35kTMM#HJVY&)W($E zQwrtRV%o!~p~+48>_lBTV1C%X9c}eXQPkHRH&Zi0sIH8X5E*brnL}mnN#WC{vYLAt3 z;W21(4$lxz@){3Xtg1+EjdoIzA76jUlF_AW`}=~76`W&s6)AU+wNrnHaLmpAWpNCUH1+*fm~pIS@5Av1WGM~rJ*(5^*B2aHO=BhzD0b2wsEzs1)q87o`$ zbu2T{`(V`8SG<{b*9j%`!E&`BT(FjCD%2H)4YYsEG6tERlzkvOeRm{o??!{;MN`6_ zoTC>G!Ike&B*6N%EeazZoo|n-@ZP~N(~!ieAZ>A zlizUK1BF#BoDxW8I&R<43I`9e0%Q6UD+E*v>BO$E9(LvQ-C|4!Kb!93$Z-ikIuZlC zp6Vkzm1XN%`k^Mdeo#)9UY#zAoPcgUeL;XfjJ&qu@pWf8qc)J*?pnx};jI*K^im02!HaaH!GdtMq~BX6pb2esJv4 zM3!Hq`eik4p`ZORLZravmVz86)=kO2qjwc65X{W&uK>_1~ww4#otDYj zT806}*JY_=x#-qtSHskhmcargUGgc6ni19aZ0ALwL&#$9l~rGCI&S~yO;1csZSQ}xhq-9rHJ_I0)GnUb_S#clT873g_;ij3)y+xuOE2Nf zNET%a$k+9fnnOsb-h|tNoC4#TAho%-zs@RyR=R>3Of?)52$#C0 ziQ+BGrHs!*rX&j$w!E&cG&l_2J^3zlRi9{ZtiQEZm=kXHzfo`@In`(Ttp(v2{0{^0Cvt%Uai zGYwWae~Gu7YygZUS|$k1O{{L&=VS@?3plBxzp;I+Kq8L0)HK)S8C!%lK_T3Pivue2 z?l9}iWQjx`CGaxOPpJu;f01+|Z(gi(Xko$ba`p@a^*oFq*1YRj^R68&b!{FvlJ z;nk?4b^bo7=uHgFsI^-%{5)RhSh=68f6y?*9iqTXj2!ulpq=FjwLQizj$Bge{f~c( zh>O=|$~En7MBv*@lJ`qaZdFWreiW*6W7CY7a_49mQxTo8`iSbbZO~i1{DfXW6lRhA zhA5S}ees-@ng6kJMV;eIPS5lGUS;|_@Q6zu%yWG&wg&Z%g-;XQg)ixpksZuvt9jt% zBi>Cn`ZDMAh7fwZ_tcBL*W4tpwyC1gS{7-5wkN{Rhf}dDRyUawWCFMn)6?Shfc7{E4j|YtW0~k2GIR@p^}(~|3DeC84R~gv!27@5T+w`=e4e3gOVA&hdg_VR z_pli5sP;ZyeJ`Y3@#Je_xo>QgW2f}^%lP)#lUaVY+fd$Zj&d6FEEC_+`#F-DUGV3- zE)7C)GpF+}Jl>ItX`Ft~`JEQ0FFtimr+|ag>pMqJJeLuc+^6M|IeDdum8KK(aJ9#4 zF~=0u5FeZ|P4a_I`;+h>o1spD79m)jm39S?P>EUU@LHhl8RC8G*~|$xknJ>rU{yZY zvnX|8Iq^#QV7g#D&^fihN)&hc%Z<-W>!OSy_2gBt>D{IgHG~Fi@jAF>bM(w}?cV?) zqLwrm8Rc;%KLui_w*c!02GK`|UD8S|zUNkQ@Kj>&x9wp+cG{iJwm(d06egK&&e<(w z3~CwzZ`iqCC+3qb{f-7kX3_-vC#?qdT;y-lM2@j2y8ahspc@Y)2^US5ikO);gu2B5 zSHYnn4PeYIFZbZA;?uPbyDKGJY?_aLAzB2B;{X3Z8Fyd0RFGz!NNfzz@ zm$x4KDF(SqE%q~T<%$C^=-z_v^y&8(z4o7Qmfx|Q_p;cjHsl^PK2t+;@_|jN+JAA~ zy;p7V59QFS_3oSkd~JfyHb=~2{d=1Af2sJxnbR}Ie7O=~?$cbGRHe)_jz4Ms|BHDj zvAHbOn3y|Hixt=ZL({nY6Z9e$`x7Q1hWiN}`6ra(s6={GuZK%pUM}YO!Ws*80xT*39bdYb09~Mc&XKKM^ONDt%xewM>$#iQWOyU>!K}zEG!;$8erf*s|chYh>x*6U+MK)^i6ML2Ww+F5+{WFfT ze*jl$Ytr{MJ!A*1&=qLp@#eohwSP&LXV|fXhY_ciUY#&=7iC@F_Ihoa72V8Zf5UBP zlv3IgUgjz5p4y34@5=CrppOB7lz{Y2KARKA{8jgUqw0_b?tmN^qn(u5@?sFXe$Qvzhf%ryOtWLehHoH8=-dw&K{Ov<8n$pjl0J06 zcuSLS#Clx+{#-y}F~ixCGR@(SAR2V{h!RbY-E%Ee7w2|ZWfP)olSq3y7Z3CGv9eFL z*s|f-)rih@dqN`6KoD4_a47U7?_&Z2%k72ie6Pp;oSuaCIG}Phyrc6Or{esIHH~?! z#UvJxwcyNu3q(l`I;f^6o1n=?ThZg0N{jgLo5dbm{^N$%G&7kW1u`(FtpN$Uo^QB2u&K>)eMw0iqT0zj;f0+v zm}Y84xFB;dgta{dA9<#CtXEy7uJi$$;03b*j*0JA>?-l8Wv^S97-^7MSJDbIwDhQk zIls>Fpj6!U9JXMRO&vp61w*lu*@hpUM9gxeJ0|LPa{kAX1$;Jjj~)o+qE|HI6?YhY Q%g}!6cl#4%$2{Zy7wt4!WB>pF literal 0 HcmV?d00001 diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/PR3.png b/Firmware_1.26b/Documentation/How To Contribute Pictures/PR3.png new file mode 100644 index 0000000000000000000000000000000000000000..d639bd7e689b4ccc07b96f6f5c54c6a0ab2895da GIT binary patch literal 73289 zcmd42cT`hb*Egz10i}oy5TvLms5Gf6RYbu;Q6M3d0MdI8RfvFs6;z~36=_KbAU%{A zP+F)$2oNA5O$Z^hPyz{e>p7n1`QCfS9e3RE{qe0a#KC6mHRqahu33I_?PvE4^>{di zIQQ(?!*l!A4dXp~*uZ=C{55od9e9#_wnz#1Z?C_x-t|4`Zs9rLm;KJ#2HJb}l*M!H zJYWNUKj?GI+<(uWL(RYb?QQigbl9_JH}CchZPQ@u1?ItbB7}^B7oo5XN`yCv3=5+- zz-Smk^E~lu1N1n-lynVdk9Dh4Kb~JIFZ%g}v;hBKmPgwTa3Ap4t8gmv9M?Go#RI2Uf?tUcf@kpi|6mz`72Vnm9cy!+JAUJ4o^a2;Z z^lOc<^;>uEa@kc^<>YA3^km7^1yVUJuKbyM?Oh-TGFi?h=?RxWN0lcj{WPClkSVFW z%H5OvXU-nq5fRiPsoH3!>%F9;VY&~y>C>_Mo;@Sz%J6-ECVg=YDrMj}#M)Y3oy?dx zZWjb5RaSZb`Rk)AR8BCjn5MM*0`(D7rrc_ei0ez-uq{g#|R%v7K$+)L_;au zd56QIMj9(K{vmK}*8gYkY4a+NRQ(K9LSYF^^xC=J8C&}1@}#k)rIdkzLHD(bXw3sI zz1iA+)JkFpoDsj<2h7Wq^)HSdBDif22BN7Aheyg`L^L$xgBRD|RI>~GCz{xfebiiO z6E}pVChh%sXG9oOF!>f0);EaNs1OQXhi2Uc zn+S0eidkFw_oaBoBpWC-hcPJe^*RG(x1o;>n}>w2ygrcQp?sb>LTsGjHio*HH-S(} zl^O0~M4~Ssp|kFTDEWrl&<8HHV;C56VXW@*km}zAul3k>yt`1lWJ-wBJJ+%J?R|1pnjf3&*zC zr&nxtDey#W?YhMzcDr0F!8tReMLh(HcQJ>yg3P`_6((kS+PaPfUQHTql+@8uG#$s+ zqe|-}M$_%;sAZnp1VUh2h^vJRfk2rqbT^koP@$x7VIFX`$FN=KTTE21A9DB6FB8_> zno6+c{l^4C52;2VMA8wyKk!DG>Vndd>mPDl<(m}}pGsY$w%r4@Ka{Yrv~*k?t^MTO zBkH_|520;3bd1j0rd?iLo152*6K+rJn^Sb|P9a)INM}h@cn<dx@$l-P|+$42M|k z?>gpS_Ar8ze3Bt3$gsXLW)MXfS_Zq7GJfX9cRW6L?C2_BFfV$7iU4*Ss^BL@IKO|# zMLX5(F*`hR#O*Ww+SuQm_8#jaF(+|F%zJaj_?+9t0-Xg7yulE!OC?ycA4$ zUjP`aln?B0^1D}5Gw~Q0MZX7RcG$uTHnf+=OwPLg#KJ!(=337wP3~)jaRqMib#7|F z$+GoyksAZ}Xu9^BkN(unwSFVV@%oUJK0UFk&61>^i1l)bv&`~c%C5rX^F$)SCR_s7$C5_`DAZ)N<9df3ULT74)N|u6V;3%hqI7Jy|#J8S7GbUHJW)<%=Ywbio+}-ZM$8tn(1(uG~>wvpb#oupawUs1)yL5|y zU3WJdzV22>TrZ*Rdyh|+!?T#%YL!I9Aq}5}p|by24m%nUB;oRSaPv=2Gbv?Am-DHw z#b=*WjcQQe)~_0VWk)im{Hf-lj5Sy1B?shWf!i$x5zZubPs>)K(76;$((J$^S%LhP z(4e#>S<#Q|{dq~|dyB=6#%O=kNJ5H1RKuKFLVeOcD}kNW_a8D?hg1#{!nr6iHCYoF zx3X|qepE~HlUWr_t=>L+(7ygstEpi7S!*J55i2AiHc!dRoyIb&$?XUq^U3QWbD3_# z`6d3ic~Nt%X`SJ4_4EDg&DSbrau5irH3{3u`{QQC|64oewR;L}#0B$Q^x&h_h7=wf?XzqOl>f!YYNI6W8>3 zqme*+LoR+QOR@@&?;M|LP{FxXc4k~M3slm>J5)B{fL+>wsXG=Tp$@NB&YTJ?yb)td``>h*|+F8rnk)Z`F1thC+qVv$8XUn2K$bT)?> zrr!!Wxn4=McE4^6W30_}D^w{ub+#p9XVTo$9Unp`vYZdgw&<9tjY?HXLm~6;(H^aA z$Zk&(|JbZC4iUEd5LO$6ZpNrdK}4X`%7%lVBH$JJ{LS}3yCWq~#}`F^SdE3uT|ptu zN>rLHYMOfE?p5cJe&rOv_<7-R^WK+YTI1@(vvJ*AVJJ8A^I~7G_uJtyX?A$$DL4bWOIwj+eZ{`kVv<>x&DU7l-G1{NFZkON;mZQGwy^J? zBfI@thKiROg}$>*WQUXL3)n;7keDxI{9~RAski9#bf4h-JTBml`5rOCPj(&yd+oxq z{Htl(l&kSF1$;ixE11 z)m#VMvCh$-u~F;m|88jrH|O7@A&F0tQ4D&9;1ZBkS`A1|@?|UO4Lp-^LIivfFTiC2S?CgAbA_kd>SK5gz8|CR=$v9vEUH*_1< zktmhd*f=g2lVmy89Vem|rSZ3x_xu!ev7HZn4JwosH+_PZ0F`1MZmoQH;Cz~f-HkZ* z4sBj}hqV-|)kfZBlJ#0#2)HM^UD&P5Z|>12V#VSHBB#sloqFYILgr;OKJ{PzannDn zQ8tJzXIf>U60yDiZz8?@y@&ME#9Ut^=G|LNpWMlDC`G)gtg0I1<`m{l{uVq*#LAlO zY-PRAguQz8>W!ntEPQigS5p8n?z>HWGYye2;04ujNLQJ8)&W%DDefg8kyubzabSxM z%9O`%V`2E%pYX9~PXPP5Xpo4Uao9|4Q(lGU(&v3EaF*C^>_Ld~0nS-ULRa%W`m-Dz zafY{L-e- zWU8X`KZdwxPxjkBZuhN~X^9>`M`(k26v416KVKKfzoz5iJGoYk56yv8^l^#_>2Vd$ zKN5L#N4uFIsOWU196c_LbCX0u3;C{tq(A=GgzJhjW`lo|Y_=uv6`qdy>z|iRkM2j_ zJ_uGbj{@n7|MTqHIqlN4cea%Y=OAB|8ky^){ER=sf0y7t+bvlBEz_3%Ia0UCvi6P> zu{)uNW_prd+1>AmhGC+qhrsXC(x!mqM;Vh8^jIu>?alJqTz~iU^ita!af#7ylbFdk zwU><0rpE`J%pr?;$=1(NW_Nzk$6fq~PQd;b0&*%&c`~^9xqfE{!hEH|1afQxx=SyGefPH4sk$y(FpclgRKh1yeE^O|bN^&i`<bEcw-Pndk7wWYG_>@20WjN(_~KCe7`)?BkXyxc}4coeD~xnUEy zvzp`%4%N({TX-r*WK4Q0d{Pe?f1e!JUSgSK|F@t8(mbDpBsF$lAGEFXnszJ7P}CCm zXjp=NjscaX1Lx_1Nr^xCbbRo|p?ie8FUduJDbM;fFp6y>wVv+x_E18Yg&_bSr2SZHqy- zq-n09A7Z(p2;$|730fiH_Lrv1=V9JhXP6b@CwH@cw!-a^b z8u_-6B(B_xN)Y;n9Jrb&D)B_IY0|$U{)Q!IRISUlTT))akJ*+(Z1#H}@V1KRRzG=% zLnvcI=FU=7w)q;Ne~U-cXdQM%;R(>u*V%{~}dVe?}*UTYjD*4eWzgNoA(R zn6MPESkLCSvw84p$ch8HvoBZAkv^|1;XtremM)=;z!FKa)G~{MfH-QK2}@u2PhPH6 z1kxa*R;AVFsTVf6&q8FBGKiXsZ)dZK`;kKVXZI=a5J!a9*P3iWI(aVHdAMAu&9!}f zw-Z`Sol1qc@ag+;qsDr#`FRf7YeVIgD)3JpHC%weu)8C=7+d9UVEZ9r&;Es*Xzw+P zurJYOzj=32++L?9P)XG%3yiY7{7^nGLE#zz4l?Q|WBF1VH^0Is)iqQUQ8Hkz;EX0m zmetmp&r`JCX4D1F`qd9t`WtwIdCY!QLulmNuHz`MaiNe!w+|@(c6?VOlRU_WK%hT8 z(Lae|#V6AadYv{3WlC+R5^txd^p^i+#B-49xs_wrVM{1$xOMBKm)>p+>6S=E%lhd; zq#=cu;I81^By8$>$&K%Pyy~lwR%fLB-*7Fw#ko2# z|H5T*jcx1%zF1gj<^17@mXT+0{l2$bA#vf) zyv2SiRl$E@NWNc6Ir9N?-VFQpm(Qoe9@hS<*xHVwy3>>;iN}<=!9D3$#ltoh6NW2S z9o83W{Wg6P(p6!1+?)nyqCikRB8*`E%!w1+{9XQq&=<`79s3h0PWOScoY>-%1;uwb zj@S|o?T2CpZ@aMNcTeY(`8^3mVb*m3GniKek4dz>;`m@Ff^)MYEl&?N2IC6?@0AJ} z>aDj{?TaR8h0L>=^L5JaE#!NiKVK%qjsRaZF}fncUc!1OJX~6Kt<>VwfoB{F5-%(M zx_RvJNRGpahwKS#p{Nm9%J)^vg!*%$MNtGup&(h3%cPnwMa3X(Dp`>-6p6yxLO;4vBifEX>W_b13b|vKOvm4BZnm}d%Gy~y%xmJm&F4y)!1S#Oi5fK!}5zETM{rLupjuj}h$y4CCsnJYlTMT((|ME$+toDkow={9@h?&QrKTRvt z+e3FTNzP@>(V$;&lF&gg7sWy{M;yYl?^>=%aQ*@CUG|r*QH0>$_o@K_`;l?>s~dSs zEdFXL4pCymve633(${e4qJ6eiRycmGUw^BSuOj~t*j~d_oSyPs*~VF0>B_U%3!*~m z!xK;06PGXbjpZt(NFPS&s>Y5u8nYpnMGcf(O0{$s5|yk8PGeI>@>eX8LLlfKgN z!gm*j?1}9*)<1*QJ2hLo3kKiR9ZGO;UA%IaD)rm+D+EODf>zPKlPzriE06KtURI9` z+QLF%nh;Mn)idrybTXZCIgO|nFPdOpKARG2;X2%X0NlJ&A}nY-le4GE2Nd>Uy((vq z2VL8&M{D=tOhBDUG~rC7b=l`~lW5SYPq7~d(!yDKRNt}6mY_^7+;$Q(3E~3Zj1?$t z8YneGDi2%}R`bB;Mm`fcP`j@a%?oB`D>d5mWe-Rg9DYA)`0(U2Tje8hAw!W#e5HIm zBI0|K#O$V%*dvp>drIs$EYYv=&ExT-?mXCv#fNSA+kAuWG<)rZP`+~b7RHa#is$=0 z-e^?zs9O_kRy$RHLoI$G88rUhyJOBT;|R8D5Vq8nwfc>y*o%Zc`GG?yK7IMbMB;?v8Mo*mvDT}fUo52xxYGxSh2(p z5yp@buV#|u_RhI=#ZZqol%jXs^3d59D^UAt-hYCL!_Ye?InuOu?Q#V=4{?vF#-tole{Hqm*F|(>6)ExgA271_XwXf7!#nJ#KY($ zHB(TffE&3nyvw&Mi>6iFnJ3$?FhAZ9fyo@~<^gLM6ee?XsGWrt*>N{ zk228Tm7P7rp0guy@?Sz>y$6=`+t&alOE$3 z*BOfAG_I6HilN*}j~-k-Q}p!1gWKvu2b*rFp_C>Z1*1Xbjg_P3SdHSF_2JK7J`wUF zlfe}pN%G)wAhl4s8uc;wN?yN_u8xe_(-*ORPO2!P^ za}!p+Y)>y)w?dY;WZ|QaefN@#RgZ6a8S|23w7erML}8&kUeWNGPmjD@*{e;KTDK1K zY(~|*uXX>>R{X+KtQcFgK2*#15li`Q#goy%Nf`UIJ$`H(0Y#bc;#JYGg|ci@-%tCI96~1@=hX-;LHP|*isKm< z+y~JK%I<^h^UCgB6ig!WqtncSRnK5)J(_|jKk8{xiU@S9899>URw$A-&+8Bdc?8T( z37J^2n{Yqf&yL)koDS1JFlU@xJ9q&l7OYDti)y@aD^-pb`_eTUWOVEzJ85ZN$%q=y zR%6lt^K(S)G24d^-jjaWvJ}CXaH}akCHyKj^9Yx4LAbt~M_nJau#8c69zu`4*YJdV z(YXUsP3O=6llwTpY>wg&JiJcqA(x7(ZT1qMaeurer`E4SP;YAog4;**jrea?Atw2z zrSlK2_Z+1ged;(HHSS>RMohMJ@NQKciB`5Ro#$>+X@`x^fhr*9u0 z_GtBU^;+;BBnZPS9FNuUb2T+lF;Nx4&^Pp>tpbM^+&?r9$rrL3&-J`8l0Nm)R;(In z<(DaX*C8vND2XAnmPxZ6atUheG@)}*)Tx8U1&ifm1s+?A@l(2OS7Lip0t^t;~X zQxLmWFS&kVJ5L(3&08vhYPU^;Xnivj{zq%n$JIN?AaZzh2qY0v(!BLm)PnErIS7aX zMypga-CYpf>B^FJU7aIVg$TFb9g?d&Gzbxko;LUJFGaL8gUnLnN^`Fhde7ZWnhHf@ z1{^&Pf(R8jH=2n~m&b(tmW=SJYW$&tVEkkE^N*xcd?fgXf?e8va1L9!d{3zrc+ zMBcst5sJjJ7yaEBlc6ATN8M&Vm}jwIGCg*6(V$KV+{OH|y8X!1XJeXViVo<}p`6@M z)Nj<_ns>eo&aE)+J;EN*jm}6uc^70uso%$e=}AHO{@dbHX=~t zJE`06530K-{s-6rBhntoSXSw$y?>u^)y(_x zD&hangYh2#$TK2?`_D`37opm&;Dg{lkkXMdvpLQ?<#$S-{|gv3+%dbC28sgxyUYRz z6ZH*s6!jmF5)4(+7+ zkNJgB>2RstRjJEu0$2tNwP*LoynDv#k+59G@W-tC=pNbM+xxPZEp@)@BJSdPsPfs~ z&ujX3?;g%g(#6lKW^KQhyF&3O5rTY)=3cM>B$jX#{aXTdL4?0|A66;HTujuDbQ6Yd zRAa-2&4a=|7Pw8{E`6S2s)e-5dhoYM6Vd;WxKmkB6pn<4^yjNYn`CUmZr0QcIVvF-4IZP->ZmHS^W>R1DchA%eM)>|a8_vRatku){~n=l|Ao!yPK< zS1frt2#w1`qL==v0|UCQM)zC-B=V(-AprM}ez-jSA~TDB2kB@|c z>lR=buiX-InNEIB;hX5#Lmd9!aw$JCz}Y@Hv-wlSiq!Mre==0eqHBOwF3VMQz~Rfs zc4^+x*ugcMjj;Y&*)w+hfLs*|c@fW7+a`7V@$^cOQa4*S(l@`sP9k-pzW@I<+epF}?}cqU;*zhXEU3H-+zxQ2aKR9$XD) zQ~(vGg<&T5nl+`OyGN!xDHb09Ep7%~w)=H<rNBET?J~^a-L?e6kn$PIu z|I$k_t3ZsU&1yDrp4K{~X0}9wW6C!kKNfl#gDV;--KgnI3%Vy^CiZ&X{MDxriu~1x zop-*Jb$bQ-z+7{%;%xSU*A-FoWFJ0xz*z0>G?O+bhpN}ALBxA|p08WL5{+`D>Tgk` zxK!GoyEbRw8#j?|=4HNl`piUo^P8&LGoGVoS0iW^gSFt$QpP}kvtyfFmXEB?!Y%0E zX6i}TvRU0&DZpNt95!AmN%Acw9pec@#0(Z+J;M}3CwuQsI&JkmDmK=ryPp=9{!U!a zDD5*Hy3D@?klSX>^i0CI<6q5cse)=J9z)+gc-(@sG1k> zMBpkMdr!q?O`;(oO6)Riu^%Xks3 z;fwuF>^MZhx-s*?ZZYssCuP#U{abLR{ii~lC%CeSbEW1~J zF)0f@eG%u@nj!%q_?Yk%D4U9GmUDeeyr`%1GbbJ>YW(DV(Gbdy|H2{cSoSD4&!UG}mn(wDlz~ZUD+|d9_~@!!JW}s# zQeIVg4>YI-%!~iRyR+(cvQdxZxWJ5is?l09>XT5<(oIy~ppd6#n8_6E>D_g;V^cQc z@O!N3aE>m@?pkdewMZz!sWu6gSYWtaz3XlS;sGhEGpCm_RzAxGw#j9VUEtDEmu`*A zcx&HPFcqC=pr8a<-&9m{)TL^d8)nQdYP5ExAkm(u)_=tWlR~4lp!;#-h$`6t68h6` zNpNu>k2$zOhY|=FI+>g8`-TS(K1RcO>;Y>0IjvZ$i+1j0Qi$6~$7twDe*LyYIgBU4 zL(7VvoDV0#0~&0%$0=_1i_~QHJ_)dKt$HQH+MTC z*s~sZ4+if+Hdr=0J`hobZ?5J#{46aHU!{g-3NE{EEpE`1=*%C_9ynRd203|~FN|R{ zn-v5f+pLmB#dB>=h}(~+iQlE`bwv?BW+5Mrik?Ji%1+M6B;^q@j%3q!Y(eo<#?VUa zxWyaGab=vFCEE8gCpdYa?Fvn!nC4EOi*2Nxe}6v;^hLBN2Ju3(7mj82IPjS5;%&kQ z&8u>GHgJ_FyHg?^Va1X}%pz|rP`TlS{HAVPJ@R^NLgf5NF?>(;SJsc(` znk1P?ava>6(;+$Pdgi8I3F)Zi`7-|N_;ON$77o~TtE+N9LVAP+u+@+#L09le-}tO+ zq>rOU_U5J@YBrL(r4;#*?>UC2$*|4}MJ#OKUH05==6{THd{{p)A@PV_KqXdf*(#f5 zjoB+3V+$0obQ`tCn-`2l`h8Qv0rGtEmjRSNCR^2W<5GBVo17oTrFK>~E=i4sQ4^>c z(YQ~qgvO&!vLn~4U?YdTkEq=tIzuF)m+*(GM8hoim25bSj)7~huMgQ)D(SG34xVnhYKPA@+7X%uT+q05QN#q~y-OS~6hh1w?*doNIy9Iz1fnXft zFJ3<6=d<`u)#|ljX>Wru@1)wQ$RSH0>g(sci00tEimz(Du3-;#ygSD!XEl=JgbN8g z;mQ%e{Q8@#^iTj>wuRAQu*8O>&A8wcKh#WyABAa#6icQj7n;OteQFH%_-dfm;&vit zq`Lp`b4;8z^APelMPB%KgvOW@Uu z27uq4+90}~(JS?W{?sVKsds7g{Fg|=lFIpwXlDmIPnO=;hY_MfZ*miC@tq{=l3vo_ z7CtEyFVTImK3uts_vSp7)!Ku9x3Q`rncOWTsl_?ZJzF%hi4BNX*KqXpvH{D!7q|cR zxaZufC$J|~CN2?0?jM~rI3_}=@}nhWti);qcD0q9U>Vq8uA-;AD_cd|h)cS#y0TsC z*Dfr$aqrU0Yr(|@^%5qX#fza2`}~8LIuWUP<7*oM8P{8(--TvJx=Ys5_v7osQ#J=O zaE+~KP#F`nJF!;~>Ip4BmoR;>d;$M$_lb~sg>(wmqf9?UWmGpz<|t~MV)G)gyrr$n zY5baC^=EQPYyIlcs`q_5)(Pf!*D7bX$Jag&DYrF{>o;a;#gn}`HxRA2c9)oxdZ%%i z&=p-ovq}L)KV%$h{d8z~08_5?&TDmQ2J#vM2_h z{5O0RZ#=?7#}!2WvTZBTe5g$R6i!0##{XL~RL!nPupuraY;a z(n1m~p#d{qxpF5;G0}vb;*Cfgk2w{yu4*gJO+(3@x=`-j?x@7HQh$aavzZ zVQ9L#%1_^r#o~>f98OLTn^y}ueGJ;NPM#`!I9^nAlIas_!X7@iy%Js5u$oQkd%e6E zHWjw(Q@L|~DA`<2Yq2ZLO4qFCf={~ntC(K~;1BrCW1W5;B~IScW+p^oEA9rLRF z&dO<`D4}ndKR)C^j^z5rf;_l5b$B}hU&XmY1CFx5=u;gUt)WEHW?X7UoGl32SH8pOQioA=f1psN?gIjZro z_%uI?tB8eJJu7Y;{^icE^!mvYuRfyWR$WK+SJsBc;Q=8>#!DgREn`d*SMoF`I5#rS zQys$d*SEhkG+?A>@&@9hs_1(`mk=}YIgnDJ0dFy*h0SyvV$i(0H{}ZNP5oo2`R3e( zQzp%ZAe+`!U7lC51wt+S^JNIP@Ia0A6F_1(#P>VB*l)>dM(X12qoaIes_IcVgm~K> z1ielNWk>2E&e3$18O@e&qeEaX96O$7OBTD6Y*xG}hbX@;I+vdlOo$u(qY60CjXE{+^208q22jWK z3F=*J*jMw$cYxb<42uG3z2o+tl{>B=5e*{n-doiTd&+J!5kxro7`aSudaazEMf)m5 zj%c*1@hY42;XvY8YGFV5RjAF#1xsf0J!R7Z>a>ORtotdU?*872d+{JMjR}BON!nLz!I+=;n=OxowSoT#upMwilfh+Eyqwr%fWl<7-9KO4#eskItVsrZ5_D zcu_ihyWJ||P55~WIAoTvLI}%BzIaSFhS%J0!TqNe_qzh}pl9&xbhTsfx6m9Fe1%7 z^(3-l%2%?djvTl)xLL|V=8g7RT)o*gr5ps2xWB~ z{V8teCKlpRxRriqveY?7jdH$vV%-XV$2B%#n)@8={G(!0d^;+HBhRT@JA{(4Z)L|j z2;ZL@h?k3{y@LzabnQpDWwA(80zHdsNz}Kq)}t~Yla2QmEtMLxu@*%PX;&M zp~zOb=4Qw=hq3}=f@7+TyghlEpR-PZ14&+;nG1el&9slvJf(#pky`Nm9~q8V&0{UD zOp}&2dtR*zxdrtCYuwyb@M*<-$*B%UTKgAgvDdK?A}nM0$_kr+N*Xk;A#RZTtnK?Fm@wV2*{K{GqogehJ+CXA?qPZB8+WZq z12D>4dsNJ1dN*&2GqbNb*YO9cUHiRPiFT>bNlx3fr?JyBQq8{inHzeGu%*w%rI+Wv zS$J!4%xxi-<1cUU4~N547BN{9DNQGCOs#R;%;PMa6-? z&IIP06oB4uJQQ*!bi)Skdo@#Qlk)EGYxj$Nt13JHa`=@WF`U$?Qz$C3{zlq-{H$7_ z3On?fts3xSU&rjLXy%w?=JXL%(83I~lBxk_&>A>xMqoL|)> zgys#zVJveD-%bBksA0^NL-L?pL8F&Gs13!a0|FU!K%LL+FyuAk1=^Mv6X1QpL=c%M+Pdb-$? z1D-P^BRFrI8brnM3t>e({CQYS2Ii{*g}3M3-0hjZRbv;mC)I$D45^|DSM=W?akhM` z2)m-&;o$DxSf;|KdBQcdx|{b-g-omRArkFfvLt?I$qK7wkje5LN*EZoe!j|@oXvBy zX6?v^?{=NaZZOH*Y!;@3qF>*n#a-wxUIJ9*p*YLo-61E&dA+MTYc0Cx(hgy~*rsCx zBC=7Jw&P1^l;C~R%=V=Om%R8)B$h1euj6o~By}S*eBL0{kvjQp!`-1`RdL@DwT{M( zwVno!{*fcid%y5hPXix_WU7Z)jAuq%^J?@juN{N;+N(KGV{)Bb9%ai@xSm9 zuVrBszvP3Ucu|dWCohX7;IN~oFGrARU5uG`OyFMTmvI32wz~sE^&jTZsT6Q$#);sB z-vD(^JH^|yT}12RShHzZj;6*=NV%c>h++&A@SG3Bd1;ght&&!B{ZPK zE3cnUmu|wj*B*v=pI#TGepY&c#&ozkdrH1owxt(nl_ZDIMBehekAD_djcDFG`auJ% zAr{6EH?Oa6e~jSLx+1+#tVj}aQ~Jy=hUl&Ew$vp4Rnyy41GiY@Y2fBqEM|#$Q@iMg zuzJ8yZG^=njxDg^U-C_23+E4l0m^p75s@fR_$9)lSc>Bk07Wo$=BGI}Jm{?uCQf22 z0xRQ3&K>_`vv?_Iej}p(i7j8*Q(zUr3U3n8N12=LNArFcZ!nR8VE^RmV&n}X9Fi$j zI19NMKw)rG=8m##^=_ATgmIN!uKU@%(|fLbw$ndp?$t~bL5u;EzIo;Yutore{rL{a z9dZMCK_a5pW?g$gJWzsCq|1fp^k4%(g8vI{Dvum_c5@#HWK-9%rc3u~yG`Keyn+yV zoi<)1H~?G2fdMyp*WP}65p`q16+o_?lvt;bRXfp8ZXOVc@%f^qS#Ts&3U~2?CDHlB zFPJ!~m5g1-ph&@{p^m}0mb%~ zPyL=C=6@HUyNA&6 z29Qxngvt@bKj1cyZ<5b0H*xgL-_LYzu^8eP5|rwb|C)WZ?*oXbz!FqxTSxG;{QKVz}Iqe z5uvva|GQ4u3&8IF9sl!A?f+)#|L2k_YpwBy=XwlP+#K{AdJJ92@3O=U$XHglN47+F z2O8^-+;fG_)|F2)_=&J?)&44Lu`i2&&-!gM>j#uC4OfQ6SEQ@SWm)YEboOJj_QO*b z>*p#dm+zRZ&J|?cv7f~0PaN_rTnjj7W%-0+85~NDF~FJ6tB&}EAFlgzuX#w^3hVl! zB3(l=%j#tekA4s<;M^1M5&v$2wbi$nJ4R+5m7to&MPS`JO$g}IFDB0ahlwRu<etrA7cc>#+ z_d(ACc8O@oyQMlOFEXp&qKlj81}rLiw=8l<8pVyn&R=cfHo#eP7UcO zyb`d&19n-K%dL|TZ-07Ue}>i=@THGmdUU4h*s&;rUuOKBbP34K1@&K0 ztqTV-FRCB-cJ4Nzm%7peEM`;!lc}cf>xD;nM@z$Gy^&BsR7~q}e=Czx^{-o3Yit@# zJhnz+9GG7_)J8Y!Sbp2DEv`;M_`S%Lua>T)2`sJ@z+u;fCMiIZ(k`|rvgZkyM^JX9 z`o%8Vngop|tXJoJ#m_smuV4nI>qz7~n5sK^Q1Y<9KpR!79uHCT)^6WQT&u2QwX)j< z{qnp|0!uAADsb~!Vi>H;&%rDHdWVPTFKuCSS9WWT?JZzWjI*u$?km6z=HloJmF?$1 zQXHC~OvffSqJohWgt;S5U*RJm#Pjv>4EC)KqiVdFwfEbkO$H$Mp$Aox$JIt2UY9UJ zCW)s)a|`FRGSE%E2M<= zS2wyh_2+iAPQxR%Vn$bdSZ{12Mi{F8nExSMQ`~$F^K0}qf3>h^)4W4x%ZJ*5qEj?q zc6D!&Sc__tvtIaIG|5=>-Ble1Ud~xKK$;5(4L5F}Aj_71%E1KITI_w(erei(K= zE(cp*spYs8Xz0uXj+YUZt!9nEX4K(}>k|sQwxyqQeKV^UR>!v*X7Jx=(;&YE- z%%iK<)1$)}H%^6&Tjyg@W}mNBYij&3VEZVd&@*uusNe`=B~Wm=S8+&%X}+2+pnOkutPYh&>kVgEkdxy^{Crk&3y5*bSg8PN3ZANGZK6 z8o<6SBsO^JKnx7qCI9Zk`YCVL5Z7SF0Wj0g@!<25?$gOZJPB9FtJ!A#lnqLS;#Sk@ zWN~Fbw@7dc{+FcFa8XemNLEm~TD)-58zawTt=0V91y+W_r^Slu#hb%h6JE8G5m0#D z&X#yxo?Gix?6}WZ7WIwt;ChfD`m&?eMoZaf{R>GU$Lyr=#`|eqYw{t^O|o0v(Gd;v zvsue=b8TODRNsWFoi)<>FpZjAU*E`^4Qc~v(TUjk*>O!dT770OaHxEhm->887njd; z_OKlk$`-vEsD58}c6b7TJ|>q7T&;BXLI(Fb z@sI=MP)VMW4Fa<#9p)cVrk-bEC7lDbnMl9p#C?uUNlsVGcQr!hk!JWu!!nq&%7FEw zJYAN*@ku<|?RtStD999j<1U#4pboBr)ULEbd$Oq(gP2hE=)O-Phe6yCx{_ksYKNWm{Qf!9J>aLw9FK#XD0BC5jZ4uGUn&!%m*hs6NCE zF1IExspe;tr1eCJHJqcQ#o>=knmgBis9I&F(V0YyLyeU$@hnYa=#29~5*V(H4^!Ce zpiC9r91lY~Cca!6hgTbZViCpJ0BETHcN;ENPT%O&_&dOUI*)T zyxP3_t;Lo;=NoE3he<=i9STO5SE+uj-Y2JUr>ua=2^rX)#WQ-E*KkNCC=B0)(ORtv zH>7wbnHdbZX6;U{%-d^Um3rr8{zL1YlzMW$X9)d}FzJ-Iq*B|Y_&n27vqo?5;n4xU zMbf-O4%5Ts22sc#w=AYJIXz5dOhr1QkWkT6m- zg(6?=x%0~JYw5Y8U(`Qs7n7!*@2#vI4{&vHUjomcAZNa%QPaUtN#iU&)C?sEh-mAQ zmqn~72*~;5Q0CEoa~-wlxg&!6k$Y!UIdBN0a{UIPno-7aRQ^@#2C7X7Nhe-2(^Awr zh*~KmR|4;Hj@)P@JIjXJY+K7WIKfXdcRR^@iy8i$JwH<7R437qX6Y4j81psS5{}6Ln#u4( zsL5v>May$4mOpYpIS+<@UaID0izZN4oVCa@ioDgT^T^~@N>pZHR%QYlmS>(hXIL~M zwswX&_4MUVs@CotoyB-S8;InxJVPH_OX((`Q#9I~9<0ylSDPXVVYnu$N-iN%VZDoJRd^&n^YuL+t^u!;d7oV7r3G?#wvPh2`kL4nRynG?^%^@KV>b1|ECOmh`kjdVahcd5 z(CU@suSaZqv9Ix5mh$!z+ty-l?Mh#5vvFRIn-@7kMk-)ivYuwBLwmRD`|2`{p*CI1 z8z(Rv5do*u3I$pq^qV5|A1ODsuJ=n3QCxP3FDu;Q339ixZu2;O+kX{Y>h@Q*dkf@& zmFuVdYUU%a4V@2~kuw!!%*l;KerAWGW+=Q-1U^*}t4Zhl4z=iAL-fiFd>u`6pdQ5T z=qY9;(IVz7Om;yV#5T=iZPV2u#COfsB=eK*YOD2Clf_uG>hMZ+^(OCQtn~`(9-m!d zfQ*##&@7<&N%A*vX2!p2DPnf|7O5U@1sZH>Xy6Nw&G}afb|Ej? zLa1e-8QhsfUyYU{zjNOU710D^r-R^xoNSRh{9NEwZD_aEcfs{DGRNCmqCn-mPojn( z=EqLVPzc$eWWGaz3EHl{P{1561au#rEq#>~>H=~p)zFyDf`7DbwA=dDlCA&7mcF=E zHlF?;)3v^Tj`gX&bTTd^Lqfj^R zpO>olb8n4+qE9dy)0a9tQ-hHYC+n)&wUIGsVp`@4XCvAh8MPh;T@3XmD;TCxZBY$x z;~m#U9b7LkcVoAaf^Q{UG!I)srEeDAiBO*QDP~#I0Ps{Lg=Lq%jyb3v1Y>L{#f-9tc9` zixgCmxEx2jYOrx3j;*x6um4PHA*X4SYl}vh5Ym~gWYyvBlI68yhsrgLU28HAKbYPg zK5L?0bwzFg1nW9*0t#;Aytz!0yRPQ9ICfb2JNuG)@K(=^_4&ERSXW_ccNzgVxe z_R*~8Z6*KP(hLzlYL;2TPzDvP5MCAHeStGm#ko0s7xRlKVGQ|8`nOjB%6+QI4-Cpw9~n4K zG?>Ut0Zi}53t9qGwQtuI2$PgKw+ zLoLGB#x05Nqtk-~UapBA3kDNW?G2W6MrgV{?b;fJ6n+?q zf+Xmnd}n7g8NbslXI>L7-OEoOxk9iRh!wP!F$>$i$G2?-rpsWp+fOb!x@y(X7_Tii znCU(P4YEHK<-06JR@s$Utbt;yg!Z70^sn$*2x1vLbaA}vGFqlU+kTZDVw znI)dlhY+6V<}DGqDXLYYePyNo7l!nl$whZ=Wvo55PIR2vqVSR!=r8?yt z?N%~{^2Hl@rM57Eg>=G(@V;iAKUzWmU1pR!uHnhsF`qbkaEtQpgEz>hOLyuQ(joQ2 zGp?f0A33r>ICS()Y{C6Xb_B!jI^S`L=ePr6F6ArooO6GsT)akKI0A%n_g$E+FJaKv zBDO{Sr0>~b=UTSs5F@bhMvwOK1!5EqIfZIf;6WYb()v-uj#ynkK7=2#gR~A_(;N?B zCE`TRe$;-fv5ar5^a?C9y!!cTPuSWS)OJ!>g^Hk&Vr@daonp9GD}#S_c1Y*;?Zsg7 z5Hf*{GhD9Z)0-J7wscP*0H%{%Wo^9Um$L|l8WMr9*7bN z@2cWSYmm0lD5|%?TTB(!hK8hsiU)E<2_t~VLMe<^=aFM}5xg78jx6oSsGQhJa^Jq! z7XW`=Q>i2}su~5MuZ|3it3f>pR7fk?+$HFS5ZApZVm;ldx#@^$Y0$N^NOo+u;-VCt zXD8L_$@F@KRjYZWjc-WFyze2z^-MIKpoiDq6>qg_izi=;{|9Ku6H1LiKRCwrB|Qpf zHxU@~^VY*&e+*nC{Oqx_2ItZUkJY8)j4V}aoM{~d(-bpjbsttw7fbVNhFq@N?D_39 zJS_ZH>-1O>P-674H;D7HKD7_t_ZrxkcnbM93FB)j?gHULjWd|Zq3za#FT`BxA_9yC zSL`1Kj7LAm86^;Z2BRHjkGMCJCJxH`#VW=DyTmKE4}HGP5DVF-IlIG$I136VGt^~x zKe#-DW9H+>L!8=5K(lAP)gH2nE)N{V*UmaIK20p_HYz@d*i7_*@1%rwXNHH~f723L zFA{*RSC$k>_exUHDotG;3n&V8_`~hJmDm(SNBNqylww(m-GxkfE*s%&saOjOV&69s z+LI9p#Rf%;O9^K?1WVUsO^ToLY6MgY$_mT1<3&a<_?Ze_DG#%j8)xXMS=XxSl?{kW zJyveNMqv-sm@5w+5U8-^tya==NRG(#o&GdcNFUSJ`EBtQ3F0UCcF|CO>=Q^nTZP_X zrR`hY^2G4cu{a~_druDHijMnCbgq?@*_i1?>f`zvHgCpDMNP)0zwzX2-kBC#hDrM9 z9C~7wqtZcn6T9w7a!~Q8%|@Fr?O^rvhTl6Eiz=-N&yFsXTP$o^4Y(_L&`RbfGs*DM zHz~@b#>s~x0_ID$%9OB%;*m^^rVdWFmFh`k()5IHWzV>Y{yF!~OaS(O0HAYC^C<(= z1vJ^rW%tj3c@%COn|3#!KJsf+kdy8Bi(==q8kfyn6L9Ry-6O%qvpkLc3kEsd0N-&Q z0B#F?d|{p!jAaT_VYn$v(Hr`Qo;1I*!<`U~(X^Chu63#l9XV%ms2D>NUl$~F_Doysi<;Yc0}6eA8J2)$@0C3oL{Q^Gpj%l zn@iY(s{$&*UDnD)6y_#HJtP&;F0UqbcIow^(j^l+rB1pyGh0?wDCx~k)Qg?9H-Vkg z$${;wK0&hW{zfA3pyA9R%V^fT!71;!)JbZ|SSiothS}wroxsA`V4;P81i1*!<~$yF z!z`P5AwjL;&QI>Tk%+rJ)WFV{+T9mxmsN9U`p(BDxjP59y_0&=*I8`!Q#)o(+J0qU z7$81oAU){-!}h7kmSKN7 zkLeqcTz88oKR@dPrOe*fkBF?qK^{|aEQP#i{ig9wlN@yxtfkSzh6rh0n`JRfmVp5) zm!{e)+sN1olv~8B)sQlJg5v^OaBac6Xfd*1Z;@MyXL3wCDi`mB@1Pz;(jV&rY4{?5 zj{D(0ml48Q?rMZJ_Kl_Fjltj7_!=%ghv1I#wjS?#;b~g7z!4FYKlMc%DpQuDCVDJh zOt>bR%zIQDf7e6~wFH`2-%v%sd2oLgcK_4+O0P!p(MnYl>R&O;)15ps^ zi~YBBKYsa8L8hkxD6DM$!#sM6rMBD|ZNIgZGTGvFAmsu1x=^-FIhjyfNA6d1{YZ2Fx<&4nOSfz8+Zy+50MOfC{dlw81?NZ`TXfE@&w8L<>hi+8QuL(I zA)sKuA3$NRH>|W0XP1YB8c$-&8q=rpAOMU4U5&}>NQbt6^(Pqx((S4RNgsha>=!_2 zv5Ft;xgH6pS)tNFa_d{!AoOz}*)jk?a^EKq^Qerqe~)+j?PsCI-a9~&-Gk9z&l3?t z?B%-nZ6 z)uy_eG#~-cnTjH0QGQ(X{8E*28tEH09)PEd{Dq1CW@18Ks0q+IW+`gKxmN={W&727 zbq@z947z%#OLC}N|L3^TC;x}z-tuR;lqztYEpx|NK5KkHxr|RWj#YYSfoCjv)HnZt zWmoo8p@6Wz5deArj(qRe|0gq3|Mzo4#h}$$QI#9NjS9+_cR8-5jM`L<*NvX~pM2hl z6DC2yy=R?$Vm{pQ1eXLv|Fy)hHGpH?{{B!&NOgv@>-fMIN*k`^pTt<>9yR{uhfWqp z!r_~i{j_N}vww^?{8ME786U=ip1O)3?>vpX|-@IRRyg}uDrwUk4M zKHe}3N*O4!{LI+ArxLtaC#W*I_z(aY zWf0`L1-FDl2vEYF*c<~OG%NYtG0eJ=Zc+qmmX+fL3cL_xzx;f#_+PVxWbWPg86>;t z>OMtOLkXg%X7oO0VPhdM%B(NFs;1`7x4~O(^}fdOK#pTgHC@fy{xR7U^<)TdVz6C* zf2sHIqH1+^xX`4q-0c@zT z=~L`6ZYmecEpiPgl`6tky>+*Ca6mCDvPsB%Pa`8-9dRLLXaW%Nz+IP-xx-}!(6u(+ z*s>a!Q{A=Ce{pBP3vwYg6ti(bY3c6rg-G8Y?QxjFJA6-wH`7N?>(kC}(8A50T6EI5 zj~VyaL3U#bvxi#l^K@p3(MVrNKrZUNWSZvsh`j!+f@&)4xhHGv%jX8$CC_R$=OQEscL zHl5|TG)*u-=-lci%={GLPJV^p-o$b%wRf@&%%pSd-uGg5S9}k4%cy~L(%1oE6aeVa zvW>{U0u_%rVye@zW%r9mXCM{8)kfstV=-; z-OAhmCTK7I=wZG!vD}b)?5$h@oeb{wPpb)?-IMhO&0A>AweO8;S;Wp&zWdzc_)f5f zwdt2wlpn}Ul7FYoaglkJ8CZ6=%;MfzRd2YgRLz)c8dJ?&6-tqvH2WqB+10w)vL1~W z9n2}(k3?|eLM60E;q-b%@p0!UvfpR5ut|WAuqX>Sh5?_pTCXm8=7XewfDOK&Zf&~Q z=BY!Ko|Cn$qK?faynp(If9FOy33%AZ>bYlxkqsf)lteh`XJ?ZEhoe#J*<#@dqvoxs z)rvvO8X_fcE#J0T65O(_#BhrQc23Z*Q30eEP}-Nv%Iw9Gc4m*wRzKol`?$VQO|yc% zJ8TLXimUkc>kkkte;0XJFl5AcW%tHL?V1m`l$6`+oJkOdOk-vgYI>gIr-~+q%fcv7!*6~ z_Z&ir|jV~>IpKlcmv~BW&^vr@fD5p?drnA)l4p4ck<=UWI}9W~ z)Ou}=;nH1;?+82lT_a)I-gWW%9Wc+v`bD#eft|6A?!ZG~OTApXetDCY_HsBG`JE-g z=iT@0h_~J<8seRKWd6~0U70uhEk9LJ_)7uV=cimfvY}-Qwj3>SRTuXyOOChY+M0UQ z4-B^?PnC~SuC6VcMMlV-BDII_J|)2%9D{tUO$o5*?c*VG#1h;22$M$LZMDfIK;>Z= zzCeGsl5u*chveQ9*snCJu`@%u8@W#M*bc}Z+P+YZUa|Nwde18;TmzUoqdk&KGG|D^ zPc59WniZ~MmDnM&C>tf$^Gf7exg467u=ZQWaH;JsGIT>P5DzD{DIU7HdGMl!El?S{ z%IFt)TQ1T+5j5dq!<(_ZYximgAU9@is?y82CDCHVJK8%yY19}91rjhKVuNrg}*1A(J{d-^%bo*^?%bc@b9g3;=x`wey zdqi~boc%;sNeS7*1fl>BWbu$5P~!We6*tHGxM)?b`pz~-0!y`&rLDGFKtP&2YRq=b z6A_(CNZw?w#2SQ#Z>Td!7lONf%r^EUg?U<$plREL>);2v%;R!rkXyCuG+@Mse?k>$ zsdhM9;S8P=CNXJz0IhN9XQbe}D~9LWS)^|y>WJx68G>mrK%|dGMe$@;Y zbo{bP65XsKUSYQ|pk~WjPQ49IHr?Gc-mmI^ze)cgNO?=eDUADjPaK?dT^(FPORr;3 zQvI{cX4EKjqlVYq%f{>{9dMey_w4b&PH{#-SbxT7cDU7Ofd_lXXRq3tRCG6xAr4IW*bTN$PdTHyv=W6bi;$1SoVkHAQeKS(7x@J|bE|MXVTq2^h)3ov?U?$c%+T2C* z*{wo>qoQy|)BEgQm_}pkP={*v2W7Gw9uNm=R08 z1D$|^onKE@B_EaEGWXVKd6#<)c#iG#akY90fUS5+D@yY~rGxTmJM|@TY+o?dzpnX< z<1Y`%KL6bT7@XC3e{FKca8M(ByXkX!0RMKNd=N5v5=?7JV^BX$Dq1-a_>nPZx0I`; zssO2`II34drA4UZvkx>_zn{rxR{f~+AEpzR=`_g^r;=Jg?<07O`7!V@+F?R)A-|EXONjQF5bfEf)gOvr~{aX%fK^FTjS2 zL2eDPWb6Qu|} zx$3Y|h!R!go88I+M_~A}Qjh+10+KLpW1GH#_1`dw-jRuytTJbjDP zy8ctU^CAs9z^d<;CQqKbV9V-^2t=4e+=V&xl#k1rMb=iTb3M-(klF8BohSve%w;gnqEn!lwOKEXgnr*_bJi>b& zk0r#O2G(lIRG>z+eQz_f6%nx1(=E4?Ef)})Gb=b7f4|pks<&)L(cQL;ACLs_Z3$h< z2!{PgJ2R@hw`MQwtywtOs&yYOydi8j6OvZIctYj~N=*_uImJ6}OxDr2a|~P73uL~j z0qSh7n23QNZj8-Qd{=D{Q#_|basUmsxyZRCzvI@kU`^#MhpSKGo{K2= zGdkQ)Wz2=ucxG(u&U&ulUMA?`YRdGd?5eFm{r@^+wm>cCoiL%I!L@f7cr0s!8IBVW z-|xEp9Kut{3T5>Z*76BMlwqy?l0Rq$uaF{x_U&8;f4i5SVy_C9BrgY+ctn1rtr4+3 zzpEaW!O7LJ!Y7b${@c)Hii;$#Z5xlq;#v~r$3mwZw$yp{j5IH9#J$=z_8}N_*K0%L zx)&3ZFaJ0lq*Uo$uwe>0W^Gc9!hX9c8H`fz4vMp#hBo%e4*^QKd?i?G48+V;q@}q> zo}#d}{Fw};tUuhG#BK&BMI1!?7GClJcr_qiwcV*|&Qik?dikT4ECp zkXD>Ro}0H>8x$vU-m-RC@@cceL!5lNS1ICVb=>!ZiO9181Ih>rmubrrEXudA;K!FK z*Q^KFMuAnk>US=lp0Jpr=)pBg!SyIyoh!DQ@bqv$+hf+4B+2=<3g_q;*zFXCmY#JM@y3vO zE{t2jhMhhT!QKNw^yasW?sXB&J)4jj6A9(QaL`?r@JZSo9Dd5#bdzISGIhk0?&w6^ zvBUH2s12K1!&1lFJ!jl{xggdH5nJ#Qr}5UAK8Y7_0KE8%KKugWuD-_0I%WJV1xlzN zBFCftK|+)OBmIjobe{NE=fw2g-$VXi04)A5U?~8Nnc8*|m|hQ~Tor-aj{8RbSC9q= zRPSKCCH^CAv+tSB{{L#+?%Q|s&f$MW*Z004f9t;rwEOlYo_PLO!RPOh&)y#YM|tP( zC&w3dXa4@N_e)g#5aPcd_VJ1RSAluozV^fazqr)++kJ?=I*#8^i`5% z+b{9vM?Su2kn5@pLw-VQYhHLw4cyVo=J+@w?QchfUR9 z4pami#_3y*3+i)(R^5gd%B2ZmE&wOGX=LBs5Vy8^iPzwzc}D~cygyhTSP2xOBZ~8? z=Bs5$FY;adD?myjMClL$ec(Bc`%!IIrmEiAC2om>+$C9;AnUcA(RQks0#lVbhiqw! zGUJIH8*zw9*kp-~WVO^n!TclR5=q{I4updZMLI|g+Tyk)oxZxGIufp+&Bkkljjz^o zyhBB{(@3aMnKoHAr@dwP=mln>tz5M7S0MmG?#)u4VLXI~^ZC0zG5MB@P^c+D=JqXy z@Z%xaIi2nHVOemYq%(i&U0hkDe4WHlrtATXTdjoWwm6h>jvJNiYQozwdiVM06?YQ8 zy(&fL`TULU2g-;$@QL(`*UutTah7DKs3!<%mQS93f8u&}^n<`TU*ieP2&$xtV!z*VxJ-(hd=F%Wv0YaUDGf zi~@=@uho>Ta!U*<|FpXheqh59cuq%uXcjk&^PDINwkzAX9@&ADw+qm@0Kl`_uJE4h z-4d`wCKE88|9=&lZO0=p`YQwh?y@?&%Q!@T3Rqfk=o`f_l zwRc4N((|A_V~YV3o&vm2ZicvgxS*Vwc)QIM)f3AA+nUDX#Sp_$t$ai z{<}xLbBko(<1R(hSLmkSkXe!^_(yWKm9rCX2T{&2xjPqa@ zz?eSRy}7Y-nH9DCF^@$=vEtXZi#iivBO2KnVp8ylcRV~7$yj-VvZEjXd3sjkTWs?) z9Jd=guP2A!UPt;6^`@hOoTBWiB>^})K^^age#@?r((!(QVCV^fs1_kk`2pyA4ZeCd3h;1Ttp zp8El|8c>U}dHO%KJ`QHRv?gg}kMxY6pk2!jB#52ajKm@tPqsK3; zygLpHXGpb(DvyC~OGvvVUT-i0UQ;OdZ~3fGuyIxBorm7~^zRFL-4)HjZ#kQ{&oZpa zx)D1|N_fkkIWi4L{1`i(mGC#GSZn z?Uv+OsblVW3n0_fdnb**nONyT!$Nagw7r@m-s@YNNzZi0RK~f4SPFaOyM$m@MA*&0 ztry10!#>l6>*kMPYEWbgx5JKp6A~RJbhXhRdbkQ1yzFS-jupnOuC#nzIXD2l8*ZSb zLa12k)zkXii(=4`tY&Zhi8J0w=b@nG?Apw4!QQJqM*T+}HhDfD&CSUjF&DUCl0!MF zof5o!-L%b6Mv3!gym*CwVJ$_QF@xu{POMNy@qv}7HNZ4|thM7nkdUGSifDku)zTCF zi4DtvaZ6!GloP{mkn#83LTCz@D;xfM5BqHd@~OmOO@*6WvsauS^Kc)CBJ0M2_qV0K zeV6HH|FX50CpDeJEQR}{tRj}9cRcmjW9#sxNDEi1^z%@I`)Nz~!SkRJi$KG7`*Q=4 zyusa`^1;?xKpF#8(YV#|hcvdy#&@+CBbA*3ytPTnopau?nwGy1&7eC&yy3%jX5%OM z?mLE2{dgYgIi#+D4PPtywoWgnxOfw}P0{XZu4QKqs}2U#R@`g|UI7ImzXxHx8(9Dg zm>%9iw(6-_wC+74N0$m;dbrGtgFcY_Aa??pQ<_#D7(=3;<-0$pdU~e9%0)%yk|7aP z7m)O@8+w_53c6&7!!`x_dpr!uA=Mu+f?s(C{^`1?6n+uVTwmls)Eg@wjvdf=e`Qg~ zaw$`E&!U!vxVT%B#LO7Tyfn2tsJo8vVRG zU3Q?D1ZUxGLe6CpY9EiFLmyn&Xw2*LImO|=9vSeNyO%YpCNGj>t>|&DLusMVKSUs; zb~5I5ZLKe$5LAse^a_9U4(Z~;-BTO5Q$_b$Vp5af!DF3Ho+(#mCYCe}N`UWcAdmyZt4ID5nt?Wr%6$OFl} za<1pGmUl`-$ZC$=m9H<7-Z*-y{oKDf^HIdb&=Ph*rMWnMa^YO~SA%@%ocrRC>v%Sd z+wrRA+{c3Z6Y>SR!Y>4O0}7EhOMe2I#rxJh_IMp_QTv9rwl+2d zX;P0+T6GKFx5ExXUJpTQcn2d>M{_{`d08tZE~hL6-%Y_~Qah*CG|LC!0B85`PgnGx z!uu7Uj7cb#>D^-01Cm@WEvKbh>}TN5YmX}%3Z0v`pF8>`9(Ty8gijKpc1-Xl_GHkN z;i9o~l`2S|ABcRr(xFtykPId#`|3}(8Ff(Q=M@<$N#OGp-UHPndq>9atJHG{w>+B9 zgqpK`<`LnHvjygl*|)=R&+b(;-UMV*-&kpxf4&4heW#o@bft0f3T~p47g^)A5!LxA zZ@hp#-6y0B&EZDWziR1fEkBkULG+ZjcfL9hO@ z;_|XQ8Bpriv6?M3GTCB2zvvJ%gkcIMS{fXYW1XX-yyw@uuyII>&$El$LuXYBNN z(kU|U;}*)~^shFVUsa_xsm-NE%v|y7W)vg!?#bhvCqDAzUb#2zmi{NDn**ULfh0#l zqb0BQ?8#eixGfAJukU}%&$6Ssriav-b0c&tyO_ilfa`ir-HbcdiSG7cfdjEaMmT+- zN6Xo^tyic^XFmAPZuOX37jmxa^x*@PKG&~{-)b9XTRC->>(4Q+;;)~$X>R|MlI$3m z_w0vV+(B~s;YbTJw#Z_&u5#C`(;K&&9>2Z4BjP*$<@aW3a#8AOy;M+5Q^v7aRSjr$ z$+*GgpI@sN^kdpwT>;H!^~EvPkf&xn;Uq-@Pb=X&zy2m3kq+iHLq9ywt$6UHc_To3ud*d0@^5X-`mlra)V-LKH`IOtf zc4C5FnYWC6Ww*7sR9v68PnQD`UF&Rg3VF*Y*6xg`)b=H!SBKoW44Y9&@o&O~Y^}GX zp1q`I`90zSCm#NY?E4H&6!3jKalA#i_x9oU$F%h}Y9PL1_Z41RfaT|e(iZmH{P>p7 z`T0nVe9k2~1AtXcam1+0nJ? zT3-wrJl{`?r^#M5DVifMus{6SH zD@O^87w^p)_n{6LUCeaUTbaVWhUB}MeIgTY?+q9soBuY zs@lc0wWWTbpz=R)M`DuawD*QqloSWH>pbW{Em|;D%13}vz-;}p_4%m4>qEx%u?MNi z4$#R^x};*xeE0V+%b=Y)#cUv!l?cUO5 z4cteCkz%=7W8!bzVdFs+8+}AOulJQ9X4toZP4dfKN$Gk@mQ#x-(+klL-BYpgmFF!L zpw^rB`wjw0HQ-?%O%OqbFUF>CDIZp_9tbbv57jxQ5b285OuzoekbzWYrP(gXIUp{5 z$lIp?^*j=VBWi-$@a-?Xt;whm)LSSY3fv3|Y4C!T%eCzr7Xh4T>EYVh$5&UMN&Ptb zNO#AO-*Ww4iNWN;WFa^ zs6b|okWedx5SsMYTf&6e2A6C^F?E3`(vV=Z39hz1+lx%%LvUNJ8)D0;BD%P@DHY=x zML9Bkt5uR|@tZsuaC4dH81rWTtumx_#oa=P`(g4ntxLPYhZ3&h`R?JaJ%qvG!2r3P z;u*Vgdu0W_d7}cbUSDJX*R?JcE_pEbPL1ize>}sAGT8`(kA!vYcY<_4{%ceF3}d+>ldeeF9myoSvp~Sg%hJv%od2tXi5(@Q5^+GDhvw z9<^jd;l$+EKa$TKgZ}R8^(am`aj;o1ti{$ZQ(dX?X690bT{X*7g`U%bu=qurmmXtB z1~9++kTuOFluT$ygYJTa&jAa9=7M_ablF@7Dz_(?S1CerOBAsg@W6pKz# zgpalDei!X(;tdRI?hFv3r$hG;2&sP&h(vy}>n@%%2~I>fY9ArB99JLfPz=aZG;~`1 zD)W_JRrCaM=!KY0XW7pNPgUUq#8}n#O(|c8 zmxKVfbu5)0I%QK*9uV56CO1{T&9qB5?{W8Y$<`l;)v-QY$W`P-&Eik5QT^fUW)VLZ z;O1y!nQL1cQr`rE)JUOAtL#Ls2E~$k6?cuQ|BxwO*)K`62~uXFS)hFiwXjFb_U?&Gr!3 zNR-%)bj$nQEX#HElBwx&k4-3d%Wm!BVRrar`oHhtG_`cx>5WnyWtO2%zb{8?$2Sh1 znt#KLeKy#V5%M6cAx}~MSB37K7ic+aPcgr;VCz-inDdmm=i_Yv#Xsnnq} zd_@FOg~+#A;n2NN|31ZzXlCr8FloSk!?U;FT-*y{zQqD{l*EG83%O_088?qhUIfvdT=iLCUg5KkJC%7j&~T{pncWD)^?)r$T=MIU z!MOe#ii_H$k$wz(Jb#@A_(l(x)e$|Gl^Pc{bew^BDj?(hhR3OZa}yJ^#~k5%?hIR? zIW~HkR|iDfY;!H~6lmx89xrwr5G1-hVGFcckjxY;tpf}}1n~(<>#gT_Q{yo_<<_~; zO94poi)ob2lL1Nd`!S0lZGX%kR7<9Q%vimPB{U9*9JR}l2A%9`|JKnh@8A|U=oOz` zlq}H2e8=;-!B|f9?br8bVx#x~o9xrzhvuk;U|xLKnM{!K4Q9ZrF~SEo^nqaSfj!%2 z{M&a_zFV20eZ)EQnv0XzCHQ{aFX+dKpFu{mT1Rjvnmj{PIBiOk!=snDn*EJu!Qpz% z!bX98XV{_I3lC(g+iMn-9mAWXQqJ_8J$By$J>8 zM3)d5?8W@Yvtmnw+k7-Wec*#vdAIrdkoR9`PGD45CZO6bBrVD}JI7Rbd}l z>#-GELG-vPg>i~#f(k8twA-`x9BKyWjM|6nYT1BB=Wqi!2S3tst7XIY=eFh>+S0(Y zDEKh4@DL4|Np&O6gscsd)?wD*-;nfrqTNm;c&||X^VF~9gZq+$X=Mm`|)742~>#>Tp~*^yFOQ=L|gvbw~&6O1o_ zg3=b8o{tpT&id8zq``>{dUAwkTl;SUt7xZml3bw`hBY;NOAf8wxLowl)T zh}wHC`$xIa6wtMMrZYX`nj=cv5CkiTfRNqD6#$%!G=K_!HI&L68_#!yhb?UgHYr^I z4|!l>@1OB*OX`iLy+F)H8h2RkRI1mxMTDURnVY^>iNF8Y7iX$rmr=oA?y7L487`;& zs8)OcL4Wq~3H}~28i7N?Ds~@Tm1}cSL3_SxLZL0NDmH&H!E*~k9xKg=>}yj_1*3zZ zzZU-i1x48ymd^&_HC-Gg*Cut~e?W(Y&|9BuE-ANsMlU0C5~82iMlE+Z)R$qW6l*)? zQe={B{Cb}0_BS9C;fX*E7sPzI%gw@xu&Kc~{$q+H+$Zd9dVB!rJlv(#WJS;u%&+Y} zBX?#}d78wbhwGuefNP)x+HQvka@>h!m$WT|yDWcY9!xtrUyVvr4mN|wIeK~5-h)K; zWTD7EPmkLUhz~R#>WAUE*#8^r~qPd5Cf;A*xho|J|9(SWYu0u%Qc z$|#T1YD4fynWBHCw9VDt7a5T2XFC>dBR7`V2#D8)V4~89- z7i7M=Hr)DQu6%{}!fAfQ`f!6A-;-U>aJgGD+YHN@*=?PUt}#@{<>wIMgGywn@Wq48 zEaI3FIB>vI-p&!_aSWk*3V9{Xf|(N=Xt@m|!hBh^=&cxocj=b8^v|mKXfF}UCFK|B z*%C&@SSbB?dLkKR-fRa^sTm_osUQ2HoLK%``A_k=bRd$9PG(CJ@9!!Nk$*qGp~gb=996-~DYY2PQ6cm?TlF z(B##J*sZ7n@ws;txo}zk8*w8gbVMy$8ejC*(|ocL(%MA!G11sSFDyUzt6ln7brvOM zpcYT961sXXAW*w5xER8{1if^O)RTM}7vAm`>YS=yY<*rYP%!D(k9g{!mwA(&z5n=p zrQ_%raiXDn?Vd66^k`%C5-WO*woxYRy=@}|y7c5 z;DdWvyS_XZBSY|Qf%EGW>AzbPfT#)l&1?z1qz>*{Ub^RTSATEo+H2%-Y%iJTFE~{9 z#g;#J6|?8c?fskqFywvv9G#~H)}XMk)pE5=z^$2TMeV)sjo8=!ZI=qGaU_7$%%X|wx zsgC=n-P6909Do1onO|)4*pOfLpclG(Av?I*iW*qk(M<;RCb zgSr3n)vtT55nIW}a^?T@{@kYlSn9G*^jq}(eb02KzG){7h`h=ACJQNzw0WZ&Q}bXX zAXaIw#fb4?ARanhckAbbftYT8qZdMB0;mj>C(?$pHNC~wnH7zKaZs&Q_V>(Rmn z-dPZR*h+<8Kkd9bgZAgBV;LDXaA93!9Sm;#!}>jHgtXe5;s$|#M_I!Uw`rN-_=k-? z)7Pd$tj}%%&7p!o(XuSzrjKk@vjB zq6z<8UNb$*SR*prjym`)Ny1o2!M8zrJ>E%c{8swf#)eXCj*c@=nnqYGDPel!Y;o|y z{UEOZ4UaEfcCaXYk74}p{#FXH*%_7+AXs4w1 z`c^($V&7X2R$}?6nBpJLafzfr1D}#zGnk3fbWwPE>UyT5{lFu0->sJ-6*d~@tEus@ zhQBxby&B^`Y&rj`-uKFfkLPSVwtL`WI zA%u?Ow`U}xZRp6la;6|QBoS8H9>Is6KqKQC<`(FY?qKZf>yB_s#@dbavflEhqQ(}} zaP>0NfX3A7`~SN;rO-`x^?SmDZ7eiE&NgKA5XpVnMJ~ON5OiOfVZizK9sB_ff~%umf~1d7}T9XL;TpNj{&S zU4>?$SG4(NP(|SORy!DtCL>Se-SK3Eu_vT3)Z`Ai2W5FDYCFVYjh6eVXd;~}4c;(~ z`6fD6?G1^K&X`gv?8=qas){cca3qm=g4c!Lzk*FQ>l~rOMhZLRH!f`jCvx^XsECaB zI%&!a9Cx^xi$!+ri z(d&D9>1A|nnUgaO2htM?<14@Q8LWLz%T2pvdI4MT;9z9{8^ZLaKundy3oM6ELrbkb z=ucWNn}7DXU$CcT3(Z5W6H!S4Q&Xjt7`Hb&A${Qqr-MuDX#?IO{qC!B?9%TOP7;58 z!8e5AJuu#Do);${QmrA&hIxg;=i>r=r{}!i;zRB;u#(Weszj?xyD~8KOr52ilI)>+yh`7PG5dhHu zo!1NCXg#vH7B!lhTwSr!6jLu8p?--VkRRzKW^#f@XDRq$PKfiHtWLHlg9;aq6lp@3 zRZp&lDAs0hMP6j+1vo20HK00+XJ|D-9V`hBThvZR)1C>Aqm6%#kx~SHv+BI4N3Ce# z@4-_BlO&l^_r&~d<@QBVl(Byl_s!!>m)cuWfn}q%Tk7}4Ia;qBQxFa7;(4~Mu4Hr8 zGl3mB)y&ObX-r!Jme(w_iNzf8N&iD3VTjX2F>B>>?3l?r$In?ciIQrK(!?g##JrbR zdVa9g&k1=$opXyMutO{kN3uYx!OcvbLeEe8?VfVhKhsROrv7-D`rT^fcW#1J{qGFz zq4mOi%`Za!n`8pEw&9x+Po+`Pvo0RO;_>hA%S#Pjh-OvBxAH(+eXa*cYcg(a3)i#9 zY;H{{zC<}tY}Y=Fxqt%D_XG(gtF_b1MMA%S#!CfsGuI}X-ujaNv0)T+UStIn=BL;d^Eb4-ztoHFUTR{hBum1VDmKzy=Kck z)G3gUZm|v1PJN0EFbew>f*N21Jr?3JZe>UuQj_+c+p4c{tK$kW4{y|KqHt!yxBtj( zuMW0ic5cH?v}D96YOCV@{OqP1Z$7x;_J%2_`#`^TEe4YQ~!wsw9BVLTolT7H&V*+t-v3P!k7!Go>ul=iry+J*Xq0cW;*;Pe)(1SrWtZz7DT{Fv#CGi zo9*F)HFIk|tdQqxx$PJS$Xa`k#mJXe6GV1K6g!{{47YdFGD%Ty^hOB|uB;_Y__ozd z7k*=Y?M^6fun$j}-#$f}U-#2^tmS97XJ+_0qVF~4loy-YDrL6j#I92~@Upd< z)!AsC{85lKdyo@5+Oy8seYcZ9+uR~?v3VOW^y>e zLITE>9@~CX70>&SFqCPl%x{=_6zy@Ia9@z1JLGK=Oel!|p~3Ttbqy~n+&)a$s7>Q> zJ7c}X{lw!FsV{QfO0vW=^+wOrtNf+;*~C*M8N<&_4!aH{m2j^=12NA@m-v2uk*NFi zOh2l-_!tOiogwSYRv3QsjHNI?P@z0v@7*SP?m8wzC})06^mjFNq0VWc&}!r=^L4D< z2|#53NEvhAMwnX#Y?L7BepDDG(-J&Ru>;U{$u;&5eWeeGk>NKWmz;@qSeSkfAp&Y*M zOZXMAP-_JC;39ki6objoy(V@3%6q`h@1uOvF?FfMVy~PCc-=~6uu0ighegnNv&V3c zrkU=>x_dcXX}PErfp0_(W@717B3+f!6h-XcdXsr{JxZA$o|OR}J9>eAld%Aw~g$3g)M#{P7R7`kqSO4@XxrUSMe+X)!)M8uGcm76^ zHo(^9IKS$e>+nqH28&rWm7!B%Trb}TTJ?UyxJ8neImbe+BK2hl2W|5Bq0#$IKRd&n&pmd9 zE*Pk3b>B_Q;IwBYN*|u4$!zQx(rQrlct>+%$rs1ymo^31;o1i$Uf3JMBO#lBQ4J0Y zY_M-|M#;B0+slUYs@L>QxYql~f_$^E?d^X_*a-}fEI_wN12UVqNwT5FxxS%24A z9vf6KBQPinao4>)uM#<6&F2Aeig5#ZPOTK$(HO$t9f zY5&`BQh-jA6C=Lz*SBu(=e$5J`2%9fj(*0 z;_aVtSIh2-9Pw)&S5@zf>5tEML8y3(E1&NvBMhZsMJ%sf`O8`+l)bOchanmh`CnkD z?frjb11B96gI;Bz3CX*laa+-EG%9^XEuV7k7~sG>i_IekBBd_+3EG zB91ZcssRJ|iH*H|7+w12eZyYYF>lcnC} zyZV`qULS88=GgskaKaIS_L^$%Glp^Sg2XX<+;p>y?cdaEJ$KG^$KIbuo;e-$^3fHk z8x^ko!UWj5@(|jy{OJbGjR^C<{&ImdKE%-P2Mv#>!RS0>8g%5QS99Dkm(r6OIJYO> z1~ZP8l`Dq)Xu4Y6p_r=r<1v?#JN3;P7cV=e(IE4H>;0t~rHcFFtuCco`YNS0;5|ZdDEB>E@~`QF#Psrw3zI zg&Rbkm&TED#A|6(MqF3FxiI?R<*!~U-#wUIFiEXik zxBw|Qx9vPXW3r5Lu|^SN65&as!|s~KZNMLZT%3#HHVlKLaaEP6Ji1i!JrE?$0hz7w zs`jJ&m@&oo?3BTtKI`nfQkZR4gV(&?fs?p+#&OT{SEEA)`>ENDQk7oIMu+Dq6LYWC z{^~7~H-?HuhSAgi1S-&hZI{3NC*-Z-E`U0`bsRExf^gAI-PKOhSgY19DY7pXu$SiD zF}+zma;r}=7#e5+YI!Jc#NWM`%y+iiUWCtWxmCE1*bp;A68kLAL)VhsUW!+5E2V&2 z$?p8tp9=^fjSgM)fs^Sy?obygk-WWcyJ_!ZhB$S?Uw_!SHo}fN7d_mdh2BsmdR`D-NYIY7Oyd@6GS6v2gyyqrkQ+a#%NNJuSbS-1tOL$N!F z#@ZCH)MZ-F@+w^wg>|*C&oJ~F+N~@d-NE3yx_2=ew^);Gl}jx~?d({QJcAK_(?ntV z9BujPRj@|93@~UIIg*dlGe4t@n$92XvB1zG?|w0t&RHzHW`kc->-+qkm;^gcMEZ{ZS3W{w^Eche$%$j?A3f zM560s-$m2K`v*HO5OHgcMEdH7Ai7uBvyS;WI{{ZuMHsZ@KS`*0E>HTry-wQ@>}U%B z6Qe25PoKUVd>H=!mzWB>?PlwSroTo1ve?|}`pHHI>-X5MOP@%W){`}Ru3fGNvGg=dfhhn59Aho?gA!K%MZgT=wT7PLi)`N(qTQ%(qd31s)+xkv(2N zrpAv7Dh7x%H-IetXVjvD8{n%2d*9j*!J!ELS3uv06M6++RvYB$%%H?tQA&hf$Z5=+~XF|kx>89^v zpHmN0p^vU*AbnmV5sE09;4==aBskq^! z_vb%vTd2R8~`M-CujdKcn>w40##oA;A_&?ill;ySm0tn!?zx$@O9CtXD2qaTU zz$!i=9HVcq-wV5YW}45`35hNjK6>M4he+%zw_poG6%kzhs~xGi)9FHBK^C*nf>QyPsH*<<&y|O$#kboF*13&PFp+Tx8fMOS6qjTNf; zx&Bd!f?@C8VIc`b@Y(=%bjsWCgjpKNb3)!K9F!39F4~;qxpVmZQ=Pa+_&ZY$>L-yc zi4hq7OJgE+j38jHeecAngl&$Ww%VWPL+$!VK1yIHSm0{8G}qA z=k#fsUxAu07u*anckJfUD(5x?^`1huRS<{#w8#YqN(l4k%Kjspu#&6wBc)NpOu!d1 ze9BWx4RDDSOO@jn3|qn!j%_FUZ3H?setpX3Pn0d08e?`V+qfhxv+Zx>zHxeJsVan6 z$T(`+Uj~(M!W;Fw#T}a#JX9~A zKG?AkAF7a>LlWE4!Xo2?4nti2P`LnnQy^Kz$wD(Y&)_&2#In!&CF6{5Y$z zk*)ecd^ov_uA-p}A=`BRc)_w2X_9A>oTmFBrE$F?B%*bpAvdlLobZGEnv4B1s(zOu zsr7=~^?s<4?e<|+A%FNu^(O26af{yjsNhU2dd03&#KoteBS65A4B+~F+Ql<3n%tq& zW)sl*0;}28O2^rvZ1~r`l3CFp?)W<0EV82RuFur&G7KWWXaUM+SbsjjkVG<`N|S{d z+MP;S`Ee&8MQ(wkV5%kvm+|a0vyq}5)4qg+Ax_Fi(9_#5<(a=n-JsV3e02an>x5Te zM2|f$auiOgs#vamH{l?eK6NKssR(g+JeKw2dY{d%R`$IH4%O<<(BVO=a{C}u!!Q4# z1mwY|`Q33_=w6w%?P-ID4oMa7`A?J!+A_Zw13FzP(eMF-ftAEgbB=D+DNdwYJIl~Y zHZAvPof@~Tbxt|g&W_};qmJ{U@8i1SDHQ64^3hkY7H@RE5_uC>ygBq#w%)vY#)48j zQ&wkgmj3-6(+*}qSfI1pS68KCHJFPCjGz3;qwkydy$2Gy;&!I262b0&b2+f{`K`-3 zlqW`4g5Gf3dB{{cpZB_l3)3c%ZvYkfs@6$Q>YSJZu%7Z^qrl|9LPtA|t>M)89H4p= zl`JWbASP zUE1Qi9*n+P!kE|IQIjY;iV=KFy~coS>ED>y-ReNB@d9WMb7$uh%2;$dx@RJ52o=Y>;9GIKYck^e7G9sf7I5U~_FgC^Y4bJ(X z)bMZE4R4yuzM3~h-@oMM$PC*`tO~#P%HK(|U{B0&t{ML+%3PB91e3{B_qD?k#px9> zY-?TgdZYfMrTo%*7gL8Q>T*JSL+U=Ok*RfA{$JhjfdCQEw;neore3SdpVW`krQ0c_ z>sQe}Bq6qYzms&faDqn1DY+4O+4ANqkgQTU1pfqOq{w`ng6C!M+ks{rv#m`nYjp4k zh}~7-sZ67XYfiAxaA`(hA8^oE45OW{(0tN}gtk)KNo*JKa#&tY5wZdXOnCM@6ro$0 zONdUVq9uEGHFTxTy{-1j+}K_lIp$ciz+6UWxX@F^>6p|8KU*|_IhEzT3JiN?=_z}J z^Jg5}lq&GL^x!bo`C)de-)iHvz(>z$Q^`^_7W~@zgJ)V;@#2{+oD=C*0Rf#1-V^m=D;Lb4h^pe55AFV}uoMira^tMsma?3kb#2m=Oel3&jd)e0S1zPc^0 zzG+gX$dSyM7F}7g9-8ote1Aawd8Hy|r1HhpIo|EnHxZ-NX)6-OuU|P~N)7*|7f&G3 z-!TR}d&)NK3jBgRe|4ALc(SKTKA3I5B>LL6_N=9~_Oxwc5*yOEg01LV9-H3Ha~c*c zINx8945jipdw5o8r+eClKn}>xx>vuwFeyT{VzMu8D)^e&U5rCQ0)%;MdY*ZKH<6xK z{sA@e?oVk;>oR}A==n3qs#o1|)lMyy$Yah33-Q4Uc1HED6J%;+n*Wad)j_G^?X=04 z=#v=!vt-N%dCpe;zbKeKaY{5%&U3G#7qA=|#}H&4tOy8;%TfVxUQ(4lo)uEf#m8bf zlpe>wJ39h&gD#OGb(=qf;DE7q1$w+5z<>zTmgiqmKRs*B_Z*tTTcOknQYv14GWAF> zuXH5P4*2-XmJF9Bgcq>VLsWiYIy~Af$}RA#0*ol|W6GhcE!pX*s7ZTindy#0t+}|< zPrtf;0tFQC_Qg_IWKdw^?v;X1{Sr>h2B#fNxi(Xj`%=OGuF}5wlfs4{`+pe1PZa(U~balY4vdG7~%ooKrE>FW{+iYKeo88 zy4Hk!mcVZ32`*v@vhr`ej25p`(wI8*_d@0z1TLaxWny1(xM(bH395X>k!$6E-pkGO z%)p3Nhw+LFJSG0mI)C9saMC#Pd`)oMx8fNe6w5q$zLPLp-sHD!ND0}^QT7=6R{o|N zl>BczMMd@Cx1UIjgq{JV&zF@YYoB0iJ}kY@2*g5E9UYNtEa?7{*w;aDdkvF<%1?Kn z4v$|QR*9OX}o7Du=$M*fGN!K@gyG^OtpqHg2wr z?K7RhnZraH;OLs?kR7>B%&|{@%wtLZ&MBAKC(|Hrh4`MX4Px{;TM_PJZ|)2DReT%d zdG%lgN9Df94%HA%=fSr>2DchhULc)3ga5dwS^wv}_5Yvah#rYQO$qy`kLt1xDRp%H zUsiWc_5Z1wJ~HYolhDVL0Xyq6@ANmdH;YZ@k| z2}y9;kQF+NIb(oX5ic0*RA6sDy6UFL2)0C|MNQcRkL^bD=t|@CJQL!0YYTkqs%i=s z?j1;`Jv^H5=9{>~ZqP6XXr-7y5jIcioGe=04Z}Aa5&U1?BhzOWgC*0G2n15Ko&p(^l$F>DUfO|)q2js#4z_=SPMKSDwyg(?Hl(Pj@}N9BzOWs z)qYrxOk+9@HC=dA;RJs$08~}j-d)X zu`mY~V4&f3+@4y|ViZx^?H2%V9CqBa^t}$a8ZX>_11ry&aVL;-;qCMRHP{n*lKzT? zCqEPF97AjOy?}9yWZ$T{p!9jm-<>qSd1)S6a3atX7RU}-78UxlAo2hCXD_=v-2>by zkbR^Be#GwqIR9|Y;#5kKHW$lIn5+aQA08S}ER&zzBlnZ9eo?Z{vw@V4er^;!q~?dN z5w6koGFt$OqydupCYsPE$KJq)CoM^j-W@dVIf77HwoHR09onLQsPAs(*d%1Gu z=b54UCVsShLn^`(n=gHpo^Et}WXf#QDcZGgDK`5W56}(~4#F) z`F&>pU}8G{2`iLCB%;w~T5|E0{C5WvIsdOLR#<#co%U$3%f^sEgFWdA@~F$oVDt^c z&Z&2vc&*5t{SxsKPlL>PX^)YkW&2)W%bnG8@uL;!o@$gJK;oGA8u6qssyd+S$P0$o zb?QlgMjn>KokbX-oCX;9waSuWe>^&G?C~;W0Foa%uJ+JtXV{=iFo3)Y+7^6DK zUFiex)V7%mXFb6sw03=#!`{KFXqY>FwtdBoVz#$NX1^Y&-Wi+E!w%IO7J+{>z=`Ay zksxEPkeHxm&}#puyS+S8srB^Q@%ddPSx&}AH|Xh^g*hdvjE*UIPR;K-6eKX-s4pQ0r1bX`ymHQerc2-jAJN2=|0f93e{y?^ey);!m%2G zK{yg5_X>i2AGz|L_U09LXXa(KxI@{QbO8$_qmyJ2O zYM%R0Crz3^4N_wb;Z*cCjw=|k=*P9U za9?=gd$vBVO!F~4aKHjKPaZmf*CTwaHCHeluvRu-043cpTqsIK+%4MaXGKD{d$A?U z3rs}F-YaRJayD43?h^xQWSF~pqS8h^DF>sxWEdxGcFW~l(%96G((%#p-khc7T~{{z z)k690T)8!8y#m@shoAM;tIuV-Rf>TgQL`I9em?s<0Evi3Qps}H&Ze#GkJc^SOQ=|V zA;vDt#hM)vPuT%?+4=$n8^d~lzd2#6=qXf*6=f-yl_?++ANwMM8WD)T0ym@iDhp4P zfGk|?cUq9&4@ZM&s7sODrFZtPq z!|O(e+q%yWzMvp5egCb#{3%AbuRuRJ*VBG!uo;sy`7K1R%c(_MC3tL~^8|7N9JH4B z+2-wLCUn}={(Zc*JwS<@lWcNkUQ%(f_bzd$1=L#=kqN012G&u4ll4R*kbO5e}0pK(=&3^;mEa zulpmf4t8PPQOVYrzVzc90q{^U>bc;?UuD(8Q$Fv3BC9fOlgZAOJ^bnhBQi06fN49L zPSmyoXhh0krdSp0V!t)PbsDx{(qNTtQxzuZ$b)GzZuv-8^5kpaSnVn3NbfU3W)P+3 z*@CtA$cVC(2FHMvH1lZpn@0Ky4J9^CQSOgvNcTAp@0(SE#Y-YC4Z^CG?6<)N3jJeT z6R2%t7lqvQ?l!302qGipxQJ85{^(}{y00<&)e#3d_xxEd zTrgv#;eqMPv+OyaAI?o{pl^3%6>1O8tPQ|41!#uDZ*@OUYZ`|oeun}3((QLkyAk&8 z_EHDk{=&I>`V$-CPAUAErziy9b>GHhGp4%j#)fOxzGEC~P+uAhQZAz$y7kx<#gosq zJcb7h4M(lDk2+${JzjWL&Q=G)hMxsDaUkhLDQA|9BOpSgKw{1;!rE@DZjmV(iZpN@ zDupC48DN?}bu{ue#NY!I%+7J7@~hOjUBaC_+a=k$+Y_=kM<={C{_u*@sH{ynz(8A#eSvOE=MTVjK|60mcN7XoUaXWn@QpTI_D`nW z$ld_gXVLW*IR%;yv)NATDd&B7bmjjzdeorH>Uv0vOh&msz$diw4#w{C3n zm+}(EKd|F=3y@X!X?!)iGEJ5-BEGT4S%g;kx}m)9-9!oP_~1Gsy}`m^W}WonQDz+v z4+dd&${IV@)X6mCC&J#B?85K27LNR$tf~0AR7I|IZ$$cZVB@n<5s}VQuWiiT6xWBr z3Jvf88K&bW7p}8hH3rVXEfaS#NO$M>HH%ny=Tg*{FqT`!5km?su1#K-N4s|`c8O%y z;qg35GBM&lW_a%E)eMaCxb-?g5Wj2d+Bfo{8f_3R%)-A(=P!2Jc<%>xm-YN^lKav$ zvG>_jhFC{``s*M~?MwrMzTnjk`6g)M89m|l@U}71zKU_$0dpY%8pj#xqUd5vjg&d@ zg55NzF}p6@F||Ois~EiSP`u343K`^OS~P3c{UzN+vK1Ie^fe!}+DG}0Ik}ezWOO~f zvi9kWez!0uKYS-#{2)A(EpkY4Nm#dgvwjemo9;r zn<6UdwHp<45J^VGhDzZe=h4%M!djIe2! z6!Hh_@9ekQ_jvX|P}Vg7)d?@IsjX;Vr&_qvPb2OW$a(FF6!BE(HE836 z@Y`{@J=aV;bLDUnM84;BL?+W*MBJy2H-f9fRD}hPFvRCu6Is?ph&sJj#B`>v*6>Zl zD~`N9;`o`BvGOLU&Xx#bXT~kfV5%MwWU)8l|C9A8kPvbCXET}GJO?z@;l{iW>w2&p zO6^inEb;?)?tJvzO@9lu*;d0bHWPvMKH?MamVJA8wfhD0237b6&%Zjiy;3E+TgiGS zkkrSua9&Q)6pJ+V&5crA56+8~U2;^Gp6q{FMnP4z!{}DB7%aOgh)+}=%o%%sV{9(_ z&8q&g%QwXBvCY@jViq$Fy8(YafQMH~ z8iobORIIp>MX0vN@*LlFoelo$bPhg~Umvt_3|z44R6YUBn%y|aU_%Yu-e_q@d_p70 z9NJ|sTc+B32C$;pF6Un)esZr8kYTPrH^sSO-U9T_lmOi))Q?FBOSbK{sI_OjnaJuc z`Qb@*)Q;=O zc%U7N5Ha$m;@tXT0-{#2#8>?A-hB_|wGNSLm*v2HC+*ZH&#k}K7`}zRx@oX{`Dx2R z51^L!EpBti?8z8%?4B-BL0YrN0lPOKS*E4nr#M~8RK!-Rn@Nr7}H{jk=g5$59 zrxn9LKOk2;DQ~|O!zEu0xA&m6q5Sc@YWMF4 zBOG;hfwf*~o6>&icW=^>6@rZlZ4lU7A zflwWW#@7#VokP2gb_Yl=Zc2Cjmh5tIAm~87BT&@GCQyt`_F4<-0@CTUFd!Kh;Q{?K1B|}9=9hNKi%eR zuO7heg}#3MK}IwVXQla+&|4hfGhe;aQ5}+kzq)a6pnNJ;(2!1?5-U76T##Qq1&pRV zj?=A7G2t1kj2-g|^xpR-SeR+5stVYQKkKEioeREb?EQuIQQ53hz$wK4szv?IwBQq6TMnL!z#D%OK`(E>)39(+%zfL$2Aw3DU3M25@>9*n^TLNI&yd0`Gy zp;9Jlt4xQ&zGK4e(>$oiI~RR+R8FjWXQ-X?p$IW`w{}&MPU5R?A=NhHgZ=k4f%Nh~ z$^4g#nWF2(r-;>W8Y^g=@Rw0RuQ9btgH*2b=~NzCSShj;l9rmP?$}Xe@sijUonyVR zllfR4`DiRJL}p`D&3g|xBSL;aUp%+QCgYd0yS4AswXDC;7l7RTHIyPc4-CCY^YM?b zB@ZZ+hHZJ}_);EM?!0AFOrAGv8(DeB*=Y zGkpAa&fPgVm$akOK3vd1C!6aKC7r3(?${SkQDG42YCMDuR2dpCR}|P(n(#&eW7~xE^Lo$nZr!iM^wJp%88_!<-7*Ty zzro0RoZ9$--thX_tYi3~pt3Cccg+`b3%hH_?zngPj*;YfY~7|lx5-9OJbfW;erb2y zd)d=E5=zDN5aJ+IVgySCW(3Nb)!>4BDn0MJxA6|^kun6owfY_#6xw^HD=opfMb9+x zAU(0mB|HnxHe1*YV_P4T0HbQ=bi%zw;XlV?2PjufzS@w7E|r=mz*{+568Cf}oH%Vu z!=?ki7<`{`3=NuN#JxVR%$H}PQ}1mmL5SZZ#^2vr4}FP%Iucz~$qg9KAbLd*{BvYM zK=abZf%CV6O$!7Ak{oZ4#kpO`(qZeX~TPI7uRUkL~Z5{eg6wx3mZJnx3|itJ%vG@++OADkh7N_*1840P+L|c z=jEpgKA5Lp?Zz#{33ts!2+1I}e~It8jduDH69fw}`+v0%zbJ{zjBNgTRBg3=%q0)e z^BA=BeDuI=p+tE8N*pWG(w#%dWZTWR!K1(j6cnV>+N$B+jNr>M)qaP4FeMcE1|y+y z5Mo`k7q)G_5NWPJ{X)g^j5y&R?UEC(>%~UR^F$EE3qdE&gBxd;Dp-QYSMls-yCWPHyNNYbT26ZILfZZ zKiAyxFS}m-a50jg^~n(XZ4OHmBkx2*`>fwpJ#CCH;L*D%0YW(>FR14UC_;)8X_JV2 zg>_v!8P?${Ws8C`BM*yNZU|axXH2;0;t2eGC3uvOE$5~~hXR%t%)d67Z*Em#PDyQL z^Ho00UCmpXoII~JP*0!o9K(>f)3ZO}Qg5}W?1||TlhG#K=ltsvW@kVe(seHnVSlff zrh{QoeQ)j_iCUS&{~$ET@^WKeiJNLD*6P}7AhxibbO6oqn+jcNS?}{BYsx~$zRH)B z9^~>`Z1hmsuRHe|94rUz`jTE$>SL!<5XOjEi4mx|!ZTAwfnmprCoX#K-gq4&|D_jf zym^M8zU=_N^SyQsXLW%WO%JjxFP=`x8Ex<$iOH5hHIst0yTLTNduA;&Vkzn*rzvNU zneEOUZ6q*HxtUMIl}DX`V#pzgSd=^=O~>o`v7V8v=u#iBt7hg;y6ZZqr%KZ>FapZOzW zF$U!6)VNp%Bp}_Vx%=+uE`}Er>!fYyB(?Xz2jH99j-Kn)dB&;3-Nsmg=ZI=ro(xF2 zn1$v*KRxSd7^zLNb_$SVS(CE}~sz5}w}z+9yF*{*YQ+AEnmhUO*7kRotxMRo)Ql z6O$RKT+1CP-c_<;mL=?u`Fs0QieN)d@Fur~FyC9?Gu*)1H?IiZ+E~=B>qPWABQpKpX*Yet-#+j3-FybX(=Rp0EJUfy+Cj0JQ+w}2H1Q8*t(PTIvdf4?pF=M`WdsM>%1VP412hT5Szbx8fpZWZn5@HN3`o2!^vsdpfNbif<1&^Pl@ zeG>SyN4099*tT=ce1~^Vb2tAR(IPBk4}W|eDf0j3XJI{5fj_7~;~h3H5>u~L4D2?r zrbcEu0BgrI8^kaI9Q?|b38}cdf^;K}n5|X|FNwiIQ~OjY%iGejL`DCtceIaC7mwaj z)cN0tZEuw4JrQOrn>qc(w=7KVL(#7DA{_~n~`pK zZ+Sh;dC{0%npZs{>?2xbBXd*lhF2bfGA!_i5*Gn312(kyY;VY+%=^yeSMtH~9bQUb zj$TY#bS(X|tVZrXzrf~%puh%Q8skSj!5SB64C37%8odU%j7rI9{*?#tZ0h4{)(5Wc zjrV_(z^=#948Wp){@$O{?;+0)4_mo^88cBmWcd|XHU#@Q1n9 zplLa1_XR4krr$(Ae+76oDyr8AC=BIAz8_%go2`*$m|_WheN4xH`jgmZ1n=S$DrVoh z%mn4IBIBzQRr^Yq_rRyKwymbarw=;eTH{>Wsh=g*uYOE_v$66iG$4$7#?1QiSDA){ z?792#Nz<9szu+@ixHfJa&)GBvsqOfc%6+F<5LMc=vfqL+n&_Nhj#}|C6~%WJ6kdg; zPJT3=>kwFS=4Ynk^83w|FTWfzG!>V=pdk2~*SI|sGF!j=-H${|vDg^j*k3xq3nc|5 z`A=UW=0Za?9R0>h$j{e&%TVRrHL0^Zi5KFtVmBu12E)P?pQi@aW1J z7)2r_jyKZNZ01?5V(eNLC8eN6W)qP-anhpZw+{Ue%6b+%#KVnCKxdUGi(0X9FV2~7 z=Vqm*So>61XyKswk}x9}XC{hm1e2v8<6>^qxyVP(I;L-snV-70qCw z??5nVsyo5IwH}uUAP-bjr?HSY5l3d5*-GuGh3!(CNXqMkTG*_Blh(rVfqwhQCPsbXa5*`lJgy3)GvGN*J1zHFLXB+M-r_Z zkwcQBIx_RM=X?#j;WjKU62ARAFFBOF!&c>%V!l?LK>3;0LK;arcZg=5MraMOEGrxT zoD&^p0|qwW(0iq09@VvQ_IMKwwN)~YG-PFKKHi{tE>FiK1;`XiWo({zBpad&jaoqQ zl~R$)u8XXot&dr({#F9i$D5iD+nFmL-cc&1v5@)K zE{AF#%EUXz(V3T)m%n)YEu6GWNrxo6jH~&VCi%xALjO{nFTXr1J_DpuK6K4L`!6%Y zC1U#Yh;L1SgUi45@#+7DCAAWmlJK%!@tdZ7g6h%ZKH*;GJWDf!A85U4Juz64VDv(p z#iJTw1DHGasIly1*IGeza8Ohu7khMYfwcLeA2;*UH%xKjyD%VW`rSX(+xd^ZLK5Yt z>ueH6ytS?Fu{O_McU*nWB0hII-H?4r{7@`KQXc)o+ML!hVoEZOarhwZ{3P*{VG7_l zOCPG$)6D;{GB3ZxxEJRU^&aaGFF!ZtNP+oBL02DY7bB<*WcK{3OYvs9rq4hF<1r=K zx!O5qeS-8@esJ_vM_*`yHDLj+g=CXPbiyh+FDcd1TD)q@eD+Ct{NmutI5+|T#e4^&L7rMU|oqf+AjhdH4>uGik2&8Q!1c}p;( zL#ZR?0r*i2qj9VouTUKV^Z5q2MoZ3A5Ltp3$%-?3cjE@wIfSHD7-KoJZ~d-s7-u!r z9pl9dYlw~#&`UIGX_OY4@&Al}aCV@5Zn@JXUpAoO>Xf(n?2WR_`zo~JKvVZt$SSUz(TTLrCq-3 z0z7PN?bm49{ElOHp7>~Gt+S$ZYIadsgwq?6xb;@VeNXetLOY)(%sCbUxWr#J4v0s_Q2l1xwHXEi}Vo^;(#1Xg`P3_1kX3co? zYd0;vFtcV!yd~YngzU(^R3$sImn(g;xTdAkEO=?qWKO)Wr81)aRUcY$Xal#HBwn}Z zdp#S2o~SM4zIL$3x}@2)8jG7SS8x~Lr#N$(0H@R^kLc8ni5Er0yY^Yh#aIIT1|kApuV>?n-N4mHpcZg!NWUp5gQ<<$AX)+i zGsbk_K`F;A!oH0WCO zjE(GnrR{b_r7bz9YYu7DBGrsYSmb4|`{ljhZqwzMf=fz)EXiNgo_iMVYr~m>i~PXG zLy?kg$(!0+sCOpG;pUO$isgqX8l86cihU*rZ*gDeQEL4c31=<)7@WMb^ear?oxLXb z^;cB;ND3+L?Tm+6&UW_pa0#L${Fc`frue7#Gd89e>-qFhyk?bk`Bhu(jIZuD+AO)# zb-N{qiW;dy72}}~T9}-cwQqVQExZ&N{-w^2Vx1eLGW=NOFfP(NK)tOVb~W2HU#GiPGQ}!x z(XmqoaK4_5{3B#I)a4TGdWjk3qFG|VP1pad)5C7VuKO(6sXAVVmT`71&a zK)T9#zW=oT9~1U}#gZ@GnC#REuQrD$KLPVMrudY1KHlqQlnBt9Il|3)>w+l{g zAZO3B`bE1Py4H<998Hea9Jmsjvt$>KcUg)Y3YBPmCR!1B#{^2Or7qbG>9IZ`QvUfK zVl2JJy&DtzSUgN#=d2-@#~(MAYKA&zALqB1%kVqA>XY|z!q+?&cUwJE?WmLURJzy* z+))i0VAuNo*RdY-qlK&GkY2R$%gF7c5ay_yq{Hr7ohFpL+9}Go*B}V1#DqE0-_TRl zY1jf#Zv`yW)VAXnB+ zIHseBvGyvx=vyoe8R|YR<`zJ~`}EzRfMEf~d|xG>cmi9Y?^tI^MrDogwQjFA%hE2d z1j@pxEOW(TxR*vM#2?v_!Wz-ACzFL?F|9tbMDftelT;Fr1%0s5xs9Ecer>9hK ztwrrnfL>VKc#~Uwtvo6zi}FH;EjFj2LCL1u~M;wu2j6G z%lUJd-QOqJ!8p;uk8=aYdHEBDiu+F_$Hny9^_LteRka~h+&!rq-fkZ~vAVU1hcb>z}s^fr*0No=)n!ZyxVZ>$Cc@pshgccs?_N z&Ojl4euS^dM!BpjRj1lD)w$AaYOJ4oZl}fC+Dg4dSVkue?_hJXwpX~Y*BU^7BZUjU zc1-*Z%anwUBIi#hc+w)#WrpQTUeq@eD31<&dc0r$_#>l{p+}MU$G2uBi}m@U&waEe z*SWoS7Fn&yyRp4#e%qIy2_>_^OCKi>!wMYMy%D|;pR82@FbDOEgfG7%rWdA1aoQJE zwx}_@bFRPY0iK^Y6KK^Y_H*QaiLM=+%s4DfpnCD_-*K`(;*WOy!<9fJ^x@xF1Tche|5&e9069IBaVq7>Kh!D!Ga+reQ)BgVblTdY zd9>BkblO8M-OnI+O5N#9bk^+)=os@RrC8@5{TtOr^^F--09oQPK!$?Q`dHdpA5;Im z=}&TlaE+P(xS?HwY~dM)(bOF*@6%?Y-W*#Uk1|e`N@#!V?-G+j}XFf8RT&!=y@GLUGfl zbM^O|g#C#Mxp3A@$nK|bvjU?kbp=XR%BrsULcF;`6a(_nx)4^lauZ{FV4u@rR%DXu z)Qos9}m@V4%QFa zx^!*7tcNS>E6w+P_dXd-4c$5gk#|6TJXeeC1%%@v%r z3883y1g?LMuKv+>38JZI37z38tlG!n`|GVAsUW^n6gO6-4y^jbd*Yi$3HbN>?fls> zDcdqbtZ-(pEn>FiV8dBo5VVnb;8J`0@isXiY`)Kl?b4Ymh%rz?KZAIZWMYBGaRP@e| z!gG3u(hMvR^oJcEPAnAPmR=v8>up$i5du86JsXy>IIrkXzh~Z%JIh1Q5d%FC=Ys8# zj#b~`k;%W7NP1}pF`F7U=ahgIIovlP2vw6x4cd4XM`LMy*Yn#`6xQcVppAvW(dj3# zM&@ygc)l6UphS{6;Wea5|MqUKK-J76<_9PB;G2*en=xKL+ZBKYK3ep?9D4~K1@HPc z=I7b~x->la4lD36^bZhV9{p_9tzbIZRovMN8VV}igV)8bq&P}y-cLG3_2q9~Q8}wG zsAoP>XHH%WXjTotxkBTSJKFm#5fL9<_Homrh_!}lgZkw{bjQRozwKbVVR6a%4?L+H z2!WirAD&ojltG>z zsqAiDqkUm{S?TQbXrA%sdjIw3qBm<|!u)ZrGWlBe#XCF8XVy$Xg5Zr%)c%t$q3w}) zSi9~1%)RaPd8r+Ac%QvJ0G`>g@Pa9ebs(Q0`FqKXUOqgIEa=l%%l<^L;EmucQugdt z5RQ~i(M!OUzK=_fT}id<0lC0ki+6HA%EIzj)NC491)0j23iE|;w+NxTW<|Y<6Fd68+&)ERVcdsS=3LM{S+cG(;4otp z3j?N{*Oxwyyg857%_nw<&X7G*?+bZ{Iq^eRGH!_a_5@ASd~(QUL~>&okjA;N)wKSX z34bt7D!s(v9<;vMp6>+Oa6wFylln&kDR+0L=k5%kS9aH#f+r~l-b&8qUP{hpHRk)o zn$hfs*s}7aI2S^(Vj{U@#B=l5jL$S6upj6GOWZdfl@|D+CsWI~FeCR6_l%8y-kZ12 zwnH(#_mci7XuIIqZ)9%fm2TTZOnFt3u+e-k)5SbxJ7r<2XW}96jRoi|aPGKd@6F7q zxi>1~C1jhztJe$uZc>=nRg9U3*>ECS8c~($R&-Qf#E5<;6m?9496}Pc7J-13_%j-vX!iadGs(K{N|-xf!9r zw9$ZLj{`KJgt@ZkT2%aGTc=8i%fao#!wSDmiZF&W?3E}BI837@PJ>#$JJmR7&jN*r z!I3cyra0k-X=V}zDN3CKx@z-X9X0;+m>vDxDi+N?VF-nE?aaEr>wJx-_a<8As}0y* zPN)HZbO#IB=1}aU&_i1j`}hgI>ip%Y3E3s=;7lyUuRYspg-t|Pe0g^u8lKs z1v7HuZ%~!*JI^ISqtN=DqsUZQ@Eurrg|cxG`w&+s2^Hg^>0FFxM*2S;`Bse$G~&ywm0k1&sSF|Fl{#W^*^bIYMa?Zl$_sI_p zS0>>6NJibx_htAJa*2mXqUVgl)R*=7jRZ7iz)SL72IW{R4qi@_tSg>ty?jusClpcg zc>=13I7c7R8lIvK9nYssMg_cIve|1J4)hGgmKBv+wO7g9%QfkMVk(DwdviC?SRT@z9j(uaw6NpKLVSYVW&=5{RO~^NAqn&-dQ^19WVc}1RhTD)p zbgj59l)^{a`0Jze-yVU8IV5%@1z~O&>;EA(oS%Y0j#zFCCz0DTBkFF#Wg`+v`Lh#L zLO5A)ra;Z!jqSZDZaswah=*zcrLvBW5m|o2DodlUBwtjUghm*PI1GJ^bF`_S9ZfKv zf<8d&*KJ_4)_iExeK|cIo^81~5HHBO@ancL#S_bWe_`S$o9t+?8YHmtif315J0M(g zp5bQX-DVOmBzT`g*oAx;*NI$W-~&g?YQfiR6&BM*h7!AS@EVw&$qOf3i)R`0hBC1A zN#$9h)F$QcQH)5Lt~%sxlPlQ>j6U?;1D7Ws>*hqYr<{KTMa@U>Dj_G3H}c$hP%fsQ zOB%$RttyuDJK~=O>tR=hGH|2L*&g`@sG7bJ+|OG7XlrJ`la%;l*d6R%B49ZV35Xs7 zMhFyZf|_O0>pYl(7;OQmCFLgMb|%tBOSj?Puh7*9gQciBm+@rfP z(Z=pr{QEm^k{CZ3=Ry}p`hSTeFm~eOd3Sz^7PwVroBZ^~8Km*9_HGzq^l?mCNn?pH6J>Urw6ERJPnmB*n zJKtFnQtzb*xPcEEEz2J#f)!TH;a-SpbpLx_L;nL*9mFxAJP8^BKZRUF;o8Z`E3V1H z-}pjJie{EGwysgI%0<{_1boxxQWRXbay%}jCLp#%d^}t;zAYy5`?q(XHJOdAY(-F6 zS{4H`q{A^+@1qSwFJ+smgZ7VSntUhLas%U9jJRk2VOliJ>E|OVyEjkIw5hj@}PxUo`M*anv4~;b+KqjeXTW27^NIC*EN{e_RYB=ZlV_ z@Iuk~>c_18bs>EK=JlaIDACgZh&le&m(RNFifghdk>245#?MoW{l|Nt>!JBI92ti4 zOeL^THT&g7Q^23$Z8j)MaO?UX<-K=QQ)&AyjQTpxjD=AV1{D|!AR;hQL_olfbftt2 zO7BPwArN$Clo5nT4LwQ~2w>dKm-g(OQeKI2#F9Nge2tbSmxEYeCPY)ob~(G z`uvaO-aETI&;8u@bzj%@DF0Z07{&K)hAV6x;?RF1C~a4J)xV(&es!i37X94FE-xdm zL@a!G@sI@2XzcY{fv^7D;1_V!q?g|Aa6{F6i*mnEP&$Z#Z z+=19XoZp^4rO)p;5;`(}xuBTF8jqvQb`N|?qI;;ZybH%v@5zan>S+D+l zUB4f1V8-jR-fRCe-|q2b9L;+zl|Kq!+xFaQ>PyQ0xd;~NRbO-4UeF{%2|B-#yxC^( z50U51U-J4-RS-}g9{r|5`=2N={-cl`Vb+i{O7 z@ox|K>EiU?mAx?Q1@POepVy85fBgCDwr^p&k5B#UHlPBwBth6tEbbDpWR_7kOjf|F zrD{PoupM8Tcps1a<+e|9Iru4Kf)!G1W$FeW+A98i-scJwINX0nu34RwsiD-yP5!Sd011nzf$%=}w+5k=b5&#ZL9KLy= z;?fxE6d(rGe@Y0BMz$}9oGi8bh;DpObQiBEWe25I>11^MR;}`=L2D66 z*uRq;{y_u2^-tp=0J0s7b%~bnmGji9u+?ofABJI^#@b0o{E$CC+Ph(GvX6U1WW&T7 z!Oyk+3OxCZs;E*LlKl~kxO3gq9v!v(gPk7xJ3EdQ?@uK)^E}t^NvvH5P0HL#dgpb@ zIk#|sE9aQ$TXxb)BWtTWJOrbW>aTt05jH-mF3uWV2%B4TUnoAD9(-A@=O;AEs!|c8 zLzz!43>lkMl05VVzCb?Z$A0)ASL^sfomih(#bV7mmFqs+o4HGWKw+f6`NA+mLUMdU zAz*-6p^3Xk|Ac^%B;Siwlm%3HFmj6r{Xo0wGQNeAfDc5W03YZR9#=kmpkfiU68NUE zNU)jHcT8kVJi?G^KB)r=N>A5saS-oKoI`?ZQExM0s0}4ZeW_(&u0*vT!&IuK|C})q z)=AqRVxx*#tZ1~yZ>fRWgCF7{rOh4yPxLiKL|F? z8wJJX;^nj@H$v74DR#0v_PtZd0UzfhTV@$Wc2#x5&a<&chYvrt^)$^Uw_ zEBcJ;5>}xIXb=A)sC_fRU1-ty{m!r2*L%;oK;{!*7l`eeE~oMSQllOPD}luM4;1T9 zQ&;L=j?I!#y6$BEY-29KTJASt+ebug%fB3Ar=qtrLV2}+JYFok%7}&n2Ue&5MHp-V^&kVm^syvfKWCun{H9h?drUEul$e`XhaydOvJvu z$!;5!)%PrrLk!jTm>hu5!B@F!;YSCA!fBEH7rtth0biU!#78=Fho12k)`B1i{;Zmf zaNwx1=4ZAEN0VB=W{~s2(^(xfO|S}!;iWbZE(C?He9a_y!8!n4ogQP)DRu|h**}YD zUk=Tx zjPyso?C^DqJtS7K-vD^|`-KtjZ+;`e<~=b%QA)r^FlE>|i!s}2tYfXcla-A1HZfv+ zh_#ECnu`_DJM7Sm)X+mqouY;O12q$~;>{MudFGDtjnF0Dr5Yj2qe584|nYxuavYvaXi4^oa; zg(bl8yHobyE8YPxVP6A&wYo~M`@Wl#71RP-YXB!>?+SykD-R3=n3}-KE}_d$faH-( z-O*_D*akavTbuC8X9Unx*YI+Hobs#2x5FeIvO2xoSGXOppy!n;SWJ37Gn*?E@%PB6 zNDXfEJvcf1m-=;-9@r$mncXrALBz`2RF5eV&0R*6V^^AYxKANA%{=GVy*CvFZV3o%*Rb^TqVI3`Zr2SSzZ&i*nP7@BCQx{vT1VKnhR3n?29A zXdXndgD5?+@a`#aD&(lwcgQqukXgR0Z$s;K?ZO$S;HdM`^S0iLBNrj>Z>shY-<=^2 z^bKpp&o!_6;b)V3g7M%mR*b43p4N<^L(M^ifUsSQF?p*?XY87M6AoAUx88NjYP)aJ z+Z;jm((*`WpDST`y2azbh3vI*huI#ui+kt1o(ehoq_fTadS?2F+AmHvw5H-31>G>O z{Iv0c)o6bT$@`a9!njWPxY>S08j-Vy&deD16jWwKyr35k>O56k{h-%>Oiw(KKY6tm zZA6A{NH?iyt8}X)d$@kr_f#8`T?WV#JbH*JwluDQeRV^#QUE*kAjz1qn==ggVUhfk zi1+EQcosl{pjz$h*ba#vsL|lta)*{ICd!6Z+c8kYQ%MSO=;$Y70@wvL6ZfB4IH!2i9dT|THoh1&rir|12Tikr6 zUd!3^`=si$BGp+cZ5NHJ65OW>eO{#dUm6)lU%6VDa+|Ab)BO@!5TiD3f5awxpO4S- zy{q#ZDu@Ix7p1&~hOT23;@SL){{52nDy;fl&A&R0q%L2_g%A2fA?Vs+GMI(iva)Y* z${3@nHU({QI2fPj5|3|H9I+a&DV*F{9MGM;ZmZjVRXl5ET+XS)TU!>Rc?Iv7dHB#| zb?cZrgp~K^+8J!^)iV@-*6lFo`nS#R6!Ei9aE)Ch439xiXF>S#b?4+#f-Z(#?%rHH zctFZHv?}8`K~z^N@7N?*_kP8&0k_4OfmO&COeaYhz92s5oIU-M(jkmj*hD&hdZxyO zyo155vj#P?>RV+q$CK8`*b)h8hfPVi(y!eZ+tWmMDws<_kAT7xJp!EBEE7bRqr?l8L< zz62R|W9N_h@m!+AJ+C(y;MUD7>B?!`)w2Q8zsiCy#Wr?xvco&T#fnj)RwO8*sw>tr zV0p8}KO)D`bF+PQ-C0T^1woQ;O~v9%NJGC*hJ>$ZM!&FO7;p0b6qI-YW@lyr&jt5I z&L`9t*-kcC0JXr!3gEBXgnf1xC17Ksf8aiKxq!rQnbtwckylwO+`2L&h${6>wy+*T zd8(XQ9p3=<=~9m}s0MNkH`07WSWZXtJ!@sA|$c7RkdKak+mJ2?;5)Q&#>XqANrR zQWgE!!d?=BQyZN_$(nWQ9z!z8t)F zBs|(Cs^0+lF(?s84!O?Fc8Bc}UzBU(&Z=&_ zSMr?P98^*|u?X+R)!@no+~&t6z`3neOZ|m{+(f-*_2$qI%-NnCnMbDEB3{vq8gBJy zV^|i?^3o^#AIx-OgU?7rzqc2{Wk`pV8` zIbOb*(TF=ta}%o}IQ{*nH<>Ys9vii>1X-ZAo`3syxpkBPq@Ly&mO<@9l27>!?S5FG zZ^g$UpA*yW3uuJY&{Wi%#GV-m^`2T@Yw7Is8PTqnvv$c4u+|*nXyA?HTKJ`fKHPn; z7=_Ji+_k%IHQZ7g2kykRC&?(NSsmQ7-0!#IYsa>aWk~`1sqvzoObGX}(Kt~E$AQ_S z_&mvpTY8|w`n9Tpq+XDCMf%7gftF6mMRc|aK^Gq0Kl)(HXc56qgV5P_LL1ghxO9!7 z`p}u`6O-W^E#cv)t&(oKA#$Ay!=-h zHRH7|UY=tg)3C}@AWGMFcIUi`SL6#PU9IuGqoFCb;6_?>0(7GYd}Fchz04wQ{Y1To zHxd;ged+PI-9#!+#)6gk8$F7(woT;v!@rA=SxyS<4>Fr#xzT0?C4oxp`kejqvGXBJ zSo4yue)!Si@~e$@j%HIoNn#)0=wCMDp!w2Nx0jMWQ;+zWm9W{dXgUw-u*~Eotgopk zx5uX)UCN8o;9fud!lEd7YoD5V3#sQUH&QxOpG5a|&ncBoz1MxagiaFN;bcPRW@Z{N z-Gy7}xLvjp)ei}*Ji@3Yp{pcl9&M~2LVAy0$qV{4yxjV=YT++hb=;dXf;VogxTh&@ z+Co=g&dnyC#jGss1Mi80x>qCi(jZcn1-5-UE;HBGbh*-h_Al+@=OiSx>RqZYV~0iU zDICcq2j~pC{q*kRixiUW?Ni3ErB|LRsHHCTd;;>~pq23(-{741gwYkj zZF`n2x0ucei*0f{Ad>x=DC<*;Fkrt_e1&of9#rfR zP>34@w@(J=hZA+-J_-k=m@1Wz45YE<(xZDTXAUiK&EVD2u}-kz#*lcw^ymcvYG)za zpAvNQd`mClT4Ez1d1YrcKoUr#WmF|DL8@Xfi9iq1mv&B~JDrU}m@1CsxDC7}2ZWS* zuG(r*hvbz&Dm;f~6YQhDjo)gFM#pBM8@)*fmb7@@t8M3MJj)z0s=C8fD>0uxPo*+w zQMJwFOhQP(%p!w^)fv8gZiIDSGQhXkQzv@w>u)qw=dJO8U8T|g$8qsQJB ziqy!`+)UHUv&%l5xHBNZNadtc#WpJ)dG#L4U7KyK(?B9z!k-LrSbl$JrziQSlMY?( zjF${qS1w0;Y#P4bWgQ%{T8;_%rIwH=anNh68li)Yfbe!xTgWbUCoyv^Fd#HslBG&& zJ)0A6ew%haR?$WoVzQ@{P@#_B-E&M+zFOs==E6)s&26H%7H#5yXw)#=9q zTQ&X+0bh?o)O8F2sk;-`yn8KuXX;G#%t{t=f%1Ib9ag=<_>0c+oY6U7;o^FLCBvPp zNP#~$!0{V^u@_dJSDoytp}L;A3f><}$Dpy}T`%M--HNFTzIIKW+Q_OE{wlD3%#mn* zO)WEq3k>QUd8kllxa*}#F~JjaO)uoiie8i|vrqCFVq7S%z4&VVHyD-6YU0DOo~qBdS?^q9iD|Q&K`)evIo+o4`Luf$iOq(Pyv{a zj>^t&)(b^=9lkuZxhxm0UZr;ED>0ugLz&$-raeP>Rhq6c#LJOg3c!D{v> zQ@CA8Q5-Uzw-1UDxwG^|P8EH{*}2Y8wTy-oV9h-N^(3fPA_p!NGu-L|83?H# z)rkrh$|s&j+FPK^en`|mBeehe)HDDJ!LFPhACRO(PU1PQdXx#BBg8#3A6!%d_2rc@ zoN7hxWPD;D2?35a0C`IfMneea5n!_Y-br!b*w=r4h$qh8*b-eNBO>=16$Y?}Ia7*y z#lr;Cm@2yaM1A@AHKd==6#1e28y$dCkxKYG9b731$+jNu@MI?^lK6^hExUoE9^d%3 zjK4<$(6^qpw{L+E>bU=tUbQsL z9;Ix5G(jTZ(UiNDb+nCihc7Wr3520C9Sd#ygm^{f(XSr;$A8GJCzvXMbTlJ({;ITB zg6;o^X!gX4^A?gOr0>2hI!t@Oykm;Pf!j)0YaR`S3x?E$*pd19mb`sogCl2c|f8~s~?vfMoKX56vUd{mXOi@{oqQ>zpp^t=2OGV{x?YK69o z6`R0N-0bc-5UjMG)~uWqev$%k=uGqvuYgdU!V zdCzG1{cF}>j{>56JY3!O@+f`;g)O;UvAk&PL9UER@^GmRc)75&n3Gh| z%hX{kwaf%>hI%uNF;ioFGqTJKk{K0-S>tr&j<-}-udTk(b)MNhPG?*6MXyC1ipiTt z$GZ=ERpYbeEp!30NZof|L6vu(_vX41mFwsQUCL1_U`)=y13Qv(Tw1k%Ptwrf38mL` z@@}PkKq;Z7G<~Raxl=LElL^*FN-~vp`Vss60xaRh^_%MLuKvLN9k@G;?os5NT&U7A zujg6>z2!OA2DP*=5gPGMh#0*=a$@!f6(A~5%Pp?8;QZQdvEP>BUgW8S9%hkMmel=X z=A*M#JqU*NCY6nV(52^Vm=qWaWww=KTJ6Ca*wz}#^?)rUHLSND<^0ws9Y9DPyMipw z(x1w)X`WeJu8PRwjbt^d%!PX~H z=q;0WZn_dD@As!Z429cZZs{`87cbLU@01avfuw~n+`{deq~48OPFQwe<8$s0B6l7L z$)jIXxj$uQ0V~4xT#_9^sjB>5N)|&2>Wi1P%(uIeF4-_Q5MI1J8@Ne|MGH#dN$#}5 zm_g7Bgh>TGRvksK?W@vPrVid}oDFrU?Tgtxx9;(yYNO*y&WEVph0rxq9PzN1Uw*Hu z7PUKyA0F4&QiCt;jSlZ`tR!)M#TC@#M`r8z%N%mDF+GyKrxjPx|BTzx7o}D`Zr`t! z#L&z10@l&DRDeIKE5C8jriW$*c64JZ0jjmf-#!2cmHiT@TxK%wCShbapdoK+zxhTy zqDRaO*ae~SuZ6lgliFC#3I4CeRy9@L(Xr;Fywtsx_Qm7%>}qW@Ym za#$OKiw-mNMbD&WXd7*h7kRuwr#AM`{23rL=q6>wT+6`c#(Br=o!76JA!&A8(8KqJq%B)ewcv-jL%Z2iN)3VQTkWFLLYnK~OiC-yJGt;{XOD!Ob) zv3G>)dS%nFZis){PbvF=wOc zQIX73|0-+&RmUCwNGku2U6K;D#>ta=Zt@w@0Oa2O(ubq-J}K$n0eok5>i-)t z%8F|!JrDfRGvNCll*KBZ|5f~7btb@9{wSM&bbTn^HN45|L2v$0zWZHA==kq7f-qI| zqZ{)s+-ECN#^2plxccwiaiM(nBZ=V$jla8`QIW{7*ixr4M&!k-Df7E^YOO*2eh3O2 zE_W=^FB{J| zdBZ-Kh-@v8qZXGNo`P{ByBO|PABVaN_X~rCvXtrS zPWT>gE^Xg@)LN6BNs|Agj)5lP`1A!W-Cr>Hpo}vye?4!@@wmc#63H8#83YR~nj@Um zVT`SI6ER(o!x!3;hE()UG`e7ak=Cp>Uc(u0+g|{FT2frr$-WWGzOkic*H5aSlGd+o z#|MIrntOyAGT1VKvFx9uW; z8ss|uQ^qRP?SC{w*yn3+g90(d101XX#~4eL9JoAtid!(Hlm7@XY2JN}{qmz`LkSc& zLtb3<1qF@EJF&(oRf)uxVe8lGP@BDC6@|+yY>6&9#Ms@#9Jvd5`qt{Nc`Cifcy9#xG8J{n~)GD^*l&)k(Oa&a#1j)o9_adEzv^%i<@1dH1xq#d5-Rgu!95D$Q&@G)2H9GhgugBEGJomis@eH|MFJj zUF+3LY@POzF+ZBzu+J<37mg7eO%ts67K%zY?|xy3eD#(}{LxVnCf~)P0pbfYh3}Ob z{9OGp`04VZAhYZ<^YZRzj$bNSy7=^+VI@rZx>522^T zS9;+SprF_(XU;W(_3{%J7)WpBwis-=_B|mq4bG#TWNofus)gZ6m4E4*e78@$qA{q| zMvwRYz_KR6MOGqEV8F>a!JG9;M#^k-cpb`bq$4H#F-Cg49DE=5EqhZA@CoT!0Zd4~ zQrD|Hpf>ds(V>01@M zX9AHm0=ugGy4AYS@dGbCWah?Sk>O! z$x~$?q&MDWn?wKe-IXK|k+Jrh8>1>++X*puk-Xg31mPLa2_K{1qo2Ngqo#mq3b&58 zswVh}vXeJU{R0MjS4!Q~UAc>No{ov#58Rh~)VE^qY-Lbv)C1n?TpvlXWn)7u6cJHEcRaX*&p>eTFJ;- zSTuutsYSG%ttni5O2FU#$h@nyFtE1ij^uq{Rm-s zXvK@|6LTf5czjn-noZb;mCpMJ(bZA~(4pK$Yke>Nx+{~LBV2cfbiS!$hWydm3kDMS zIBBe-Ufq0%mSBmHg`C+VQzl+ve+o91)jmCIt9m2B8u*E@CJR*dRHEwR-|bOmw__|l z)-y)Fn|(97cXWCAuMFgC=+oILy9%5Ns1YWJ&f+FaWe0=(`}#GdLS`jce$MzXf~Ee% zvBn^l>7kVI>QQ;8-`joa2UepullL;~HYAg)I-s*ERb_HcgeilyZWrF|t}OlThAo6T zZ={4w+N-SK{9V#%1Wi>Jv0BmLcK(&SZWf1hOSUbifyds!+XZA6f05*KTrdF=bjI^d z6A=#teWn*zg8UC+M+|d;Xgv<-pD3P1(hMDD!%;*K#ChHlw#)e?Y_ zsiJ(w@;Y^9E9?x7sp52Q32For~Fb8BG&Q z;dId4FDJ->xdUfivS=AkQf*P5J&Kk;o33PPShOe4XZb_~Vq*3CE(^99LW)mk9rXFu zGy#T;aT$o zEvb}~_hyWjZa3P|pM~Yj8=^OGiKNA1e0Iz*Uyaq5T6~FddR;%ALc@}XHIzK>cX<*X zb}e}bRLq(2%ErxmHPcPusDf4I`YVraznZrTK_94GCh|Ej)R0W9fC)q*O@Jsh)SO#n ztE73aLDxFo+Vn1^_KEFoO)-FTI92@7=!cjF_+^Rw^qF*i{w5F->czN=9>EtpV6Z^m zRGn?iBFL^99NdmEZTBmYe^ok+mraLEQ>qj06W$l4E_lpWDMRRW;!ovgyC=1E6+n~# z$+OGMkOzTYtXRCW()Wb?M^e8#)vOS`+|MU;bd_n=@p9$yq}QMi0g{IqDGqCu2q}A` ze5pq}@*~!4V&!Cu#N&U*jo{-EBY5#z(WQm1v^39Ve9EePhp)PDOs%*h>wh(!YiyK| zs7OXjcyxp=t@NIL-q1ia1{G@@O@{r%$Fa1+HX zPK>kFmm1_|>TkyoAcm+`+ew4%Z=hj!FiA}-hch%-s8xFzr=*cW?sc8MBu-bTHoP7S z2$ZsLqgOqmF*>33Z$HGeol{uMuL1UZR`8%xPEwpLXtqObSCYJPg69kI@-vDa2~J`j z`c+JaMki@X^^h5CZ+eM^uN?S+X9H8|enEH%?k^?%#i^wv^noBWE$!My)X=IGwca_F z!W*mB%96%>2j%o=tzzbSLPkTKT4Q}WIS%U`DjtFAdR&>ED@?a`lpz^D-!?!-a%IGM zvC!d~bSyV)lOCnG)LxoraM_kR785&GU29p4-BB>|n5m^}w$?HkK&%=H=ybZ8v#}%43kOu9fM2^$>KnO zjDzvv-I3bGyDtbmvL(-;4iRmK6PdB3i5D&Gcf^5nhG^}lc>eVU?|H}^gcI1(?zA*n zRhlID^`MzikN1Ys{K~7P<=-zgcD~Yv-3)R(+>S19=`CAbE(_a`nO?sA?pZBXJI2KV zHO2~pUi~h7A_rS(GLoV?>0E3(DIuz#D^?+zGw*{wsFYKsvXK?2;(SJ1JoZ|Hi`IAJ z1#XXev5I=mb3Z@iMpe3M~crq`DP$(7;G|zd7?9=Z)pk=2-O*v>hjz{~CH? zV_wlF+_4Zp{)&2q`wkjABB$)gSclbTo-Tf9y^>j=DruIG85Q@^=IC!{O)(>B4-|Hx_I0Ltci*;nYTcs>%~tk0U_u;JQLq~H(ROj(JB7Nm zGnLloY1s_k+|P2XaYO1-B{^TbZ$Y=yOqF~6 zfw&>)NV-Dq^wK6}(CwhajpmN@Q5kM#GgUS!FP)Vf8l7rERJy1Z8>`iU<>xn&7uMG4 zWcO8OuXObl+C&c-DG2I}rO(W`$>{6q&EKBmQ*wyR=8x>mZ4E$w0X!NX2kSO~M24wVZvp|k&}tuo48@`NlzzFmljTV;>&(QpSbT@@|d z$-b8BgCzVa>FIS2;mNjLX##=$9 z{jh1eNQNjF=)Z*iJ;WMpb%Q8m{0Z;E;}9`DIaamu(zhV_Iz(!BmJk=2(4( z!uFwgdkeYorkO~KwZ+6Z(>41muFI|FZKm>THR(&k5xPT)_uOhkgV9mfq$3bO;F?j^ zA)Wr2y{gwzZjXv8g@Yd=y5QtUr~c#ct!G)otPq0QQj{;d-c}CSC@+MGCx%$ZvipXv zg~>!SgMwBV^+xD|D-RuNtP&9ZK9)L%qXiuyC~Z zNGRK=F4I<47Nrkfv{X>0UwoM*j?lD!YQ=w!ncGgNt+pis`YdHAVK2g(+fjbT^4&^P^@3w zL&@re6`sL&f_4Y$>BR8<8fuT0G+^M`%Fym`X~~7|@k2gQ0^(M6hlgXYwBh04GQ&lLdzOyJkdFCe%7~L*)>WWB>HAU+mT+8G_b=ZiM_<)z zno>&?oXbrsiJO^%nzaS!xyI5aoBmQ`0Sl@VV@J&u{q)UJs>f)8)N;^`Kr@)~#B#cK zi#0GJIB)!_7c#vedD21D>6I${Ohv&|WR_YXwhv_<+Yt0=wVTaKt|u<(%;;!))H&!i zl}1DvSVZVG%1c*?Rd_~)Bh|(YVIX`@7*BMzdG_b9vs`ZC`=1{QqEad3Nkzq>#iEXK zU0pAJI-kpLESgyz>C1cOWybsKA=ssquYHgMA&JU=kgkD|xXXkhHKRfn7uK#awu8(a z&*??jrr$tq7~{v_GB${SXbk9!m$Oi}ACaOlv%1QSKh17BTYb!|jxc{N{KuRqTvJQcS(01T_!+#8M~Zw4iSCp- zu#ww(dWds!96ro6t7gOr+TPIJEc{DicgQ7*SIl8hvD@YekXCkLGSpF?;kuxIOorFzRe(gu>Ek4U@6r7s!SF&Efi;oU8NE)xS;4Packtw5AvQ|on8qKjFOJ?Ag9#> zPU?fKU9Q8(bm_)Tt0a|+B@IML!z|-OyI*R@Qk$6(&v>GDvrcb_ zYe}^vuX17vqPu!uent8uWIaYd(;IzILT3#(TOSFiKxyhqzC77St$R!{9*0hXOzrHI zE-eOFCCEavd?EHs4UdB2`%dNFS&#PQkn?^!nm4CxV+b=$%~LUYbaPEuSRO&eHi5It*A zYPhF!O>e8O#5Tgc*1|!B6feHPmi5h&lLI=|*y`?fSNE zeH_Sd_&9l~{&wV`TlOvoW&*vr!i8r|coGwx7e4-~MQVZXJ$!?uJ#EDvaVDQ#=(j^i zanHKL4Hut12=`aT8U#}b`f~MDIkU~BN{H?nIY$>6^tPyl5ln6@dShY)jH&66rGieG z?eA1TGq|m@>4lO5dZ!qpzf>%GmC#@mv05O@etqr>UI=8_Og?$}Za5;l*9exR6MaI# zRJ3?Vd)5%MeHorJtJutnwt=N_KpTyeH#s>)uS^yy#VVHCg2#45blqIuZnnI3#Eu;& zwIr2|gWW74jIC_5i>1NS0iQdcD0(8JN6&pN7FGVeK0mT-O0IA)`xP8 z1KN`9f;x%uBVrvv=a3E=*;_~K+f^sis#b@0i2MxyMBVx2R{-|O6F7MCH-?t)y11OI zl{SQ#4NR>)**~Wtdf4B8v-h?=N*aqrb4p*{##*D!s0y?W!pHz_gK19v!F$#Vzp^b62S>1jqwdOg89)Tui!ITDZiBeY3FBGf%N0)Z1l=u~i*OEB zsnm@5NG5nk&3*DXsPPs{7eFNdCNiz7ib{~M&mfa4+9Hd~U6>?TLyzNE7HxdWt2 zvEghS@cRD~S~%1}i;Xtv=XP|Yw~;sU0HjSa|3~H%Z2a1b{|+7A$NHdfyKA_wmw7}9~&ER&GYFWcZT|M`gk{1Xi0GM8=Gu-uSzle5%1 zTmHQKZ1v`X+guDC`k%o`C6I=_(Y#cw{iD6Ac?C=dBVnK8_{6u!DqtY`Nm*-o`Wy7_ z6OQ@Q#fyN}@Z)d3x%fXDUjHX9T?Z(`|Gn?}xr_2j>Yp;9?OXpZ z-aJbm+`r`f$7lcS$wI)vRwV7k=T=f?>vuNY%&QHNDwjXC6tk)Z{2VcW$KV$!^WFbs zR%cuWXpB-n1tg#?Ec~Yy|3C5P9m)5jRB*P4+7~-2;jP?}eD}ZaqzVrd5xHxeV1>C9 zPR&Os7W*EA=88W%|Ne7G68^U*3NYGMg_^bYwg(hGJU(MFUk6Z-JR|AP_YY3${8Acz zbG*lUY~Q@DtK1gLd{UyXMA>QziTL9mU%X|2YuxNqrOdBtcGZVw^vuYoBzGRM0}pM@ z;u3w)+HYej>S6#>ChHy93Luxs6X3}=7Zef<5v25TaAo_Mus3Oy*}uodoh&Zz-}a>w zCzRQVsDYwwXco=Kqft%WQ@?kw^V#HIG^-|0VnFDR3^RbRbxZ1Y z&p@(QtNW5o;e6bL3lC?;T7uph>fP#n~;doY3xk~~BLEMF!7D?7KA z%juRqNvo9^euW%Rke;%eo0}@{vX?q)+?<-YHuX_``*ejIThW`}YQGWwqHU3;{v7DH zzX4cA!}%g5nWf2V$;kP-3eA7x9MQpV7GpI0@sN70FeABDp7i z#kjQp>H;R n$cY7f!2h32R8JKy3%1?bN~&C;|BwV6E@F7a>~ht`o4@@p%iLSF literal 0 HcmV?d00001 diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/Push Origin.png b/Firmware_1.26b/Documentation/How To Contribute Pictures/Push Origin.png new file mode 100644 index 0000000000000000000000000000000000000000..42d71da738f500bdb52fc9e1830294310fd54251 GIT binary patch literal 43035 zcmeFYc{rPG_bwb1Eky^aszjd-v>LRO8iTg9)zZ-rf>zB_O;JKZRkc;s5vArDiWn0^ zB4Q}2hL}T4RV9c}LV`%LBwbnY%weEF2zhQ1FCUQsw z004+xxqR^!03gr-0Ptt+6yn_x$h`ZT_rVu%%hVW9+;w=4cd^6O=(-UAP!=z`bx)9Y zz3bs+n*abnylMNNuhlpI0RWI!dgY?gok#XGwrI7TbLtWc3ri2`BC{4M26a5sE0_>s zUFvvDxYvTuo?Xrv$_XT9@! zy@LOhV@ICXB(a=l5KdjAC(1~4@RU}|qr&k+bX4-)bA>K<<2E_r23-Yyg*U6z5NmZ) zazLG#p{d=xSpop>|4*q!VL9 z73wJM;D>_3oAQ%^TxF)UT$`4P^~{yv(g6+#`+5g)#y&d^G1Cy zF2&TqL)zXyI-F4yV3v#gwf=4)tG)QSJoh%ECZNv4p=P%H?FP-TBonS*Qo}ib`{8Lt zPEUV$_2IC~!7t4Go8{?EW&{pMcX@>f#yfdYNQZlt{+~TH+mu zdC8JP+VX}`pX{W%D?3P1v*cM*MG9|F{DpWu5y%PwP8uZ?EB+&N;PM;OmsV2|4ri z3sshP`|fW|D)m=SV|?5`PJRn;v{c)TxvJG@YO(nl>OZYDMes>(oS<}VTy68GwMcYi zvW}uYF5Nu(0PFzNrB(PXJ(l3QFUP!fQP|e5zyx#gj-QYH)f>z2$R$D7KXh-s4juer zSyTUorE-i_b#Cb;G2PP&%1o^`TiQspb8nR=tt&uJ?xc<`Dibzn>&pcHo*X|dHxLC_ zul%frbggf+PU{6EVW4sAi~76Lyu~3TeC}NIA{Mdprdcu8)q#ylq0JKrZ3avdMGV4G z1;Z^z@7nYQIkXoxL#kxkB))}CsJt8pV-lzcH}E-V3GGs%yrI-f5wm z4#Uo*Fl7X4tuAaPfFfC0LNu+#e{=5%I6SX^stN=`wnvW;+^2%oMt-5rMm%kl&9*1XOG_q zUA%q1$6o|)g`l@QN<#ulLOOl${Z6>W8j&h##PzYVcM(5gUI!2f$Hezx*>9#SUNyxt znC;RW=%n5(fipj0a&KNocW!^)NIGKm*ZSyv_CT#kFLlzsPdVF>K1VoJXE4pUy?O}e zh$7ju3I>Cii0X$WY%3+bX;rW+IDx-rr0z~={3&m(;%63OI|p^)=j9a$`Uby+8aqX%i`pM}$Jx^j0DBrV7aLaF}Ek z_zRdx{l6)&)LVShHW&SKjukTJG?f&5zlkWudPxKCqbAaIZAJPU5<0!NT)U4&i0=;pC9ywRwgqh;(eDeK4U@J_S?Px_PvWhC5vG%G*B zA5=ogd!3VTjazo;Qap8B6>~71sg>A*n*PA(LvqJpU4&mR&i`_rkmz9()8R&=^Myp5 zaldKrZ-+Vk0yGE&Bn%>#mmBpk5vRU-5?06DS{&_$iJ9ZFG{SgAw?X)308&oy2SN2E zY$?r_Q8Bwn6&7Vb{F$q}c{=|RnV`x!8@G>KnO5R?ZxH^PZRf^iGkXcN%1ky1PFdvH z<}aH(p_vBz^e4Bp1iyAIr~YaGhJJ}F9B&%(TsB<7s)pU`#L7Ii zNDkZhp)#DDD0VU~H{(m|dIyF0+?Yk8Wh+X9Z>T(ZfU{?j)Hr#^BhXvW8Dott z9*@fiwwe#j#rAdSl|kif2hY5Z4R8<8C{= zb`h26urczPisftyl%BiF2$-E9F21vmk5wgTBE&GCxT9Mm9QFcbxb5lC0^3By+m=Y= zIU}CsY*my*zqjT2ScQ0=kF^qMi4*Uxy1CcV<1B`}mdR7on zCQ8!R*sp(04AxZ6p9=kXGS0V?{$WHl`dCok-C*b#n7*KTci}Cnbf#p&O{7w1=?~V}qw&kNhdMZ7OX*1?6wfXjSP{_VIe8bm6SB_jSiN%$aA|@xo^$oyPqlkG7 z{->?+8)q2(d=G+?asWC|O2|elz zjtN~v22Te?A83obbkYWRM;dSu+|uj^tzkFLCA< zjww(#s6pQm;yl<~xq7eqP-c*=bH3q%ae$jWszAIWE9$nOqg)^r7PeR@eQWDYS*lB5 zYl45n9p;5d8;T-ga+E$5nT~c4xphc;$f0WQsE*LEsu)XKDMq4Rx= zAcG24a6>ra*k4kDFY*V}Y%9nVMIPVkQ1{z&8NMhnw9S3`C6g`*C$B79q~3G`tWi{kEY{(vP)m&#PQflY%HI&>SC4poKxn2fOW@nb zL3Ku`F3u_vXxH?&$H)t?~K{?3+gEWAhY1+jwXfZ3yzEMB|qG9?#)5^ z)e^CbTwBg;_hew{3BegN2Q;Y1rKJV+NFdx6r^nsg*Ey2*Xg*p0X*QG7o7o*zm@!jX&4`uD+~N z=QPrYAefQl&Y!eV-A)y**C7$k&-*x-v5r1Dv5XXU@*}55lvdEV+6IGZ(E4ZnR@X(^ z+g2}cg_)PWQ%&}I*PBoSyq4nVO7&A`1&@IB-1H|lJj&UR;1a__W~+zav1WZh`heMp zrH!D(mzZ74!3#H2ey7IL&UdyO%$)3DPGDYxyPYU46HTgQOkeIWhBPXRlmI^ZVUNo% zWvdQPM=xze!8Q~tSXzB1sYu8@aCbQQ4>dx7YbbaZzL|w_vlLZVTlrIZ2a+u67LTL^ zvZbTwr{pgaUy5G^e|*~ORwKNa>gbwtWW_@D;{mx}_Fjq}P+qB$`ZHRC?v3fgW4%gMbDl~vRftMCV0qT^7OL(`LNiDK?Sq`rEzw7@fFTv zi|b1xs;bX86J9jpyC4f7m^g^Nn@v+CIprK-e+){ltUn>?Q-ZD{iMd^=h_p`ue@ROS z2t2xNB?*Eqf=yWQ&r=6-fBNf_@<3H@Dq3?vhJtOO(Q8xFbq`46i{fc9vjrQ&s~kn& z>$cH)7=Przf|raDQ49J z?#~GOnRCV@&uKnG(=eha^)st*$!_LMyf%Xl8_$QMD3PY`5@=;sCVi4g@P*OFvprK^ zS*c;%*uMSKOo_4laDKWVV@!Im61ERNSZ@m|uvGQ4&_Vde? zZW`S59@$~>yHbbA5txEVn^Q45Kn34tzc|1?KA63+Jav(ZXNK#VG8H!>hoe_QG$(sS z7k*x$|6C+H3k0BNek!(-o3-?v+drhZvrRs1t0xbMC)Nk!7+sH}&y2}?Y`(4=b&|No zfsr4l?3F7zfRjvjq})CKnjz6L@K}AmeNN9}F480LwJkLgEguZYuyt2b18WR-^-lOl z+AzVJ$90*yJq=9!JK92gf<#Aj6f;mZia%gd`#8#Hf3bF-dEJaXt1Hnqs91@76C?~s zvSM}p(;RQ=K8E3%k)Q_6({W-AtlX=52qAV*FH3<&KY=eD4%Oj@V zt|;8>Kv$K z4P95cpUk=Ox1e+)3?`k@U(Q8@=FeSV-RezU)=eb0Ejt=2jy$JWlzIj!gmpbg(J_Li z3q^$=y&SnLNKlNxl70u{cBx0JQW>da*bJijkQ--w4g zie1}D0~xfujvU6tGlEtW!A^-tdamQa;t!SCv}pOfecR?%AP`U^;EoJk8blqZ?mj7Z zP+6vy(o-#{=>B~3zT}B_d;y5=0M9^2o3Ti=@$7K6{M9OH6ddlaX3sHP>z_5Wj;Ftd z-reUSEZi%BT(p!;5#L;^zo1UjNu?ZIiWgE0)fgiMs;Qyq(upmU3n$va546IxWqwe8 zdCFhQ4Iz>wI_Asujp$P<>54<{q-zyvk2cb+iBD`7G(h`h4kuZZR``Yoc5n0;@^p_Q z;mBdypgK2;J(D4s?4YOpGZS>#;`C35))xZL#6mlWCKK(Cx=R9o6u*en#?p{nyb+<1 zCrgb_0`#R5>+_RQL+kN0O9e_&ozL6UbdA!W?+c}6NBgl|E!*h z3-PkXjzW8G-F7?x)+pTBZWvG#MGqDK?pz&dbI(Tj*C|>o;dD33WCi|FY<Rj^IoE zoL0Xz*m!A9kznl$+F5ncla<*j#^dfgzibBq;&yuzB4=<+4sbB&hRT}IOd>bLK2-Tj zXcXUTtD_tEz;Y>w(Co2k?1R?tJ6u}tx}{x6^a3>9wQ@XQl^Fsco8lvfKVa{9svT`S z+kJkAi^5GDs9x@aMC{rS^9;;VK7jV3#?t z@pUp)>9z50;u-U3$R~T-!nMr zL>!<}v-*8q_)HJ2`|LTt2@1*K8bMc}a{7a=_hS~vBtRORY|wR`NM5P?8SNw#I#If7 zlauC`*SQ2jm<8iG?Y}0XjW10Eppa`*44ChvsE4h+g{m%{zShGw7%4Z8A9nS%c#&Jf z7Jz(~6QIjXd~^pVeHolgA9_Nqdw&f)?IC-P*7JxgpkGC9yEzo+YX*~znn^w2O>YQH zQKt=>833(k&g(9=@AvAxFo!NnG#R<&nC3#V4=A}lfR2$z7aG8gR}Lcm%Alloi$uIW ztUK5&%CU_3-BcacOlMM~snSd!&UTK^eO}B@R-I5$LXz0SR zkKh=$=djRgV|hVcWkT}>=R;u;38YX6A;D+JU>p0e!t6tJ4HUK3BifQlDALUM`%is` zg>B?kyQ+It(vnYm3Q)Zllay&K(vojG6TpX1@IKi}WgRzry`$Lhx!PIBa0P7Qj@k3q z@{X+IZo86$RR=0nOVeA9gha-z$-9<`Hans5vwl-7X=@_9=cvT#vb6OY0Ie`b7%;~S zaU6^7VS2sqgeLAF*D+nl&54MK1D?68Bh+49@6CSSuSb}x%c5CJwku2ZL&2+1TX(QN zaROEu9pbf>Z9SoT<+6e6{M%W->?Ll$oBiRWwIsVLDO$FiKtK&x4q(y?*l?*CV)eKu~ISoN2Kge`=e3Hh*5O( z#{_5eJJ{}y*6>M79L6>GdYr8_u)NSfCVE`ebW&XeOG@K5|EwY06`I)&Qz``Al?$pk zZ6tlkA;H8>HS#GoS?nT?u9w0Zc{PZt921In4+jxzAM9IMZ67bD>7l|1qov@B%d zdtj>9fm~yp&x*A!D;b`>)>}O7c5>Td?SyBXTuz_C+!fosN^Vb-m#)&Vb#OqlHP&0= z&+U_R*RKGjY>(q&kC3f>|-L70u{fXeC72M_z*h(EaNA%H~;%E7U zhF-dd9}(@DaAbKz!<$;ekqz;VRs)~*Y*ur?F-mh{Q7^+h zo`O6|wkK}{IO6g6KLUQ+KRUco8y9{ryw=xGY;~9{eU>GT&NScEk!RXo&>G`G(iQ!= zR4^#Z!pbU~E~w*0<0oZ^KVG=mwpD2jkIzjxpfSy=`D-ZnnGMc9o<>0AlgzN1%Ae9) zD5uVwF!Rjonv1X7UL@9?ldJZaxh4z0uCr&zv;=)qB3~Ch@giBtJC2P`)t}F7G`tV4 zW{=EmbZ|ERV*Bz{*A5?R7o3@8oU|f~`KX~j-c-W>>Ub3D_oMWqCMQ|xU<`kNWEan{ zMs&C#w`$`)YR+%Y!fL|>mmYxStAmrFi$aH3{U}YNz7`iDT&93Od+K4KvP z`tIQ;ukq**n!0zx?B`#HJ~^jWM^R)X}#lGrf%8v4=nICY zw*ri!3fTM~8Cq&yf-~k1ZlNFdy4tZAw+*nt)zdUfsN3am4$or5E=fD1_dHSTVe z_{En0&K~!PPqcFbXSj-s1q+WqLmqGw`(Eu*84>UI-zsTg7dCP@@klm7a*^s=qe6l# zaTzpjWoa6{#FXtYMJZ`$Fs5d*e*gCrh?m1u2iWUeHi=uoj-hiESp)~R@6^NDC;Xq4 z9#wiqtO{>zE|qLCmo?&^(sJiuFgXhM{G!E_rCU{z1@U7K`p6bcXSFFk9Xj&@0FCePDGQ|PK#Xx`eM>B#0RN^Km;liw_c0RzN z*!ofDOOA_myh4c$W_P3MPlY*SM+|4}2~tkDgtoL)Zo!^ieH+583qt-bgEUA~ix4?_ zf|s>Q#vUV%rmC^OHqs^W6GT*!tla?skKfOzDDwv}rFfZoRZKo-z{&N)j*}a~w>jaX z{sn-I_5rTl56JN`e=dv3Wj0o75GB$*%EIA&jg4ED%eIN&u!$JqP7>Xp&ZfLmjIC0s z;Lg1I?Tq$;JKH^!0~k8(Nx~KF>=?7+sdc)fi_{+W@6Rj`8OvBdH#yTtNPFRjv$_^z zh%p8^6IVX5f?Dj)be8-)b~eN-Xbt)8HTNL}sZ?X(CKNGqL@n56ZxXI#XNMt2NfO(w z>>*a1qgxI{SJ1cUk8?htIy`KGSefCcm=_`*qiu_CcU>ut=0-)pUx~DF(0ak9!V#8# z{HKpPrPHiP%X?QF&Z51v5rrtB#_wI+K~XKq8PDN`tvCMdW)q-=7{*ETOQp-KlIK|W zm;~yb;j|rDz_aC-Hnd=+V=9JvjO8+W9QTlsJV^O;4oU6K)qE)-H#AreQV6l z%-OkBy?oLY>~lb071_V!fwl3JBOJG+u%9MSkA?bfktV;pmYmwyUA?%%385rgn5hFa z#3O6kU(}C=Uvd;$Y4DYjH@CKoEgyNs@8TxYy0j0J>73jER;)=-ne>QeFty;j3e2a1 zYhb7uL~MC+4T>1~z|@QcPfWCg0o;!B2P8^G*05gi+((q?8xL=k*6CQFiE^s+LO$je zD#4?9cc-rq7u${z*U4=t8O4gc$#mAaG#hkdC&MN5xCz}s|hPdvS zsr$g_ST|dkY6ZHs9_Gs6e)b$6%$vidVU&vzgRo}Nn*(dc!=JtcU;n?#4QRi-jGJ}8~X?)@sYDor}C0MR`eyisB*-KkP* z@H4o6UqxcR9d_M$nQ9dPP+D26*>uCD#Dw zyo%i%0RVQRItAzvczw=0O~%@>Qxd2613Cv%BSWh61J<+_WO(o3-tYL*y`^_!Xf@qc z5!T5t-KENGikuL%1@B&mt__HwUN6k(+Lg!vJo;uLL!PgNEp)9wy{GE8-gk00@~d$S zQ;z@pPTF+}3jV!rGf{E)OlyL9d=n|#cgVtb^JVz2p?3>YT6j0xw>CEo9NfWmkiPhe z{VL(3GY0d*m@!S{Ei!1!DRF4Xs#nY-l>jE0KO5AZams$1u%uaRC*;D7d1tf~)94>) z%RCNsCF!cuUaZpn8YjYtX*P)*rTxBCKe)@hU=PLdE!%C2;=TFeK|;aOhntK6#j%(o z^*=X8xNY*2=-6Wa_jzFxvBy%7V(13w+o3W&^h-z=o2jmQwt9wIen)3%43w=x=9~pY zd?)LwErpi(iGcHT zH;<+Kwy%AU59?FRc1(DhStmFcFn%REqcW`JgC-+LnvAyZz5j&<9W~-BxGfNH!om3TBoasXBi{7SfI39I8fDbILqdIT zoE){=^eT%U5;Z@h!E066y?Oo)vW}GeI2<%xn#{lJJ$s*R;5NDPYbqY7grp``Yl;6hx(Tu5U7F?^1;W zkD}H2h;;mPNWPM79(=Vh6eN)Dtjf&+iWu{t!hv@HeMK2;l-sA05PKvFPf2L2kJFwejM-Yx*MulAl zGMG;J^2`T=H;!p1?3qIhUy_S0R_Xl1e zv1@}fOUVlOKp&l!2bf$<5uVBK4`(=Oku9ti%yAIr@Jc#ZUj8`lAu{JWcuJPhSMBP9 z-g-At8oygAX`pk{SF*e>1UFu~>o~L=?3$K(o~ay}R=Islr{o;kPJTncZBAG~OymHh zICULbUO2Zaa0pxT6Xau@E}h@@UgE_XO1|WEwt~@lbKNl{*7xlC3&M zRyWky@#g-(Hen!i*qbyxkn?erPTHu=bS6g|7mrx&0^K%e=yYT;?TIzAp^^Z@?4XN| zK6ml@C-p6~O$VMw)~w~!kJcpS@Myx=bx=Gfq}`)tq2(sn)zG{ptLj9T-wQJeaI4cYY{QnP0toOdhg+ z`H0#V=b98-8Maz7-p5b(+pBq$%3#y5X;2d>e+aR}KZiE+;xkm z;pG6^vlnW5LqXftlvTfFN-9zdl=zD+&DwJmti~jF7Ut~DAERcgPa-YlN}h1J+ZBzw9$ z>~NewIaeoWL>oU$HQ1lbm(d>+s3xW`VeEhaY*2)Pdvo3!)89PeQLwj>r5e@{x0>4C z_#KNiq9k{rh%AZd6a3#KcuPv{_n+tQ_56PdE%Y zv9#J0*#!?SiF#jCU zJcYWwd1H3%O^RIn<=|w6>dbWBlM6gJ>X}D>g!2ZdnG$v3!zaa_4aPwS_ySe`89JOA zEh};)Cg6r=cE)V*6-&=>w;G@2*{tE?s6{NwJ=2*_!S~;O(_=@xNm4#L*x!B#Ukth_ z4kCg23yKDvnaR%(?{|Sj0U@`791R|=KSNEF_9T>8yAy2d{zf2JG7O4OBm;5Yi z9Gh|?=cm$}+B2-$FnBic!}dCB3w6|#clwT^+cqT*7r8aH#PyWRJ{|#Vmjdua*);w= z)$?(C##!#!+w)mtD9Tya4N9vh$y4aHE3Y~%ryb!M&K7>G=|lDknAy_f6tc_`SK?z}3 zO{n_Hi&&7aQ*p2ni}Xj0@`&}lDQmM%l{vwlwO($rP$yDHt+`dZbk!g5IB z81<+fUDj}%SCNZkE&efrcU@8lKyU)!vzanwBqZBJ?|S>w${rA`_EBv3^7245i$xjp z0nUX~J@~ky15&f7bUN`QO*XOy`sY9iH>4d8Cb>Ty5*&w2OVG3ZfhY- zUbh9es$e}{c{38OcvWmj*!#Msg?*9>Sh#W=`jJw5X1J?w^_^-Z>p=D3+<+#vkvL@f zDlQkum0=B5$o9?6>Cla-hcV|=$J4HXIbpcDX6@rfu!_N(q-7`YJxUyWc<^(dDD->w zoOI_WPj%z%_dl$CW|bR^CsSTq{GF;|9V{z@dlQ?Didoa<<+qEIontrO&Mnt9$M3(6 zEX9GfI(exEY&_UlbL?3Rk)To`gckwz(N>#Y!s9NYmOtrAC`fpSbcnQB7;IFWR{$HZ z6r)Rv+>=cm%_T256$HP69@yF8DNh*cI?OEW2o&tJ7#grRe(#Z~_*3mwMH-vX6eU#PSl(hssjq(kBfGs~W|^1Q6>VwGt{Q@)V! zv*E3>w`sAhR;0$myE}RqKASW9E0xA$9&o!}l6uZojcf%%HH0H&W(_#g$ep03JhQ7C zq$8Gz%x?cN6*%4{mDF*(6A*|^woMwqE<7&Znl%Mi4tNe8XgnKPW9OKbva3aw_Pk{5 zJ~8h|xzeuW<~?(Q#7KPQ>~I@wEwQUgwFOnK@^!QQ{kQ|YUy6Z}X6E)C7a`BpPRFOG zSBk^46be;-Are;}I8Y@z$m1EU&jr}_a1JiLjDDh{tcqj>f2HNY^I6zf{&LaNB3+rz zH*^VtA1r59cx4`SeG zgW>E~oUPe2i=Y~N8IMZ0P2g(b|T_(WJ6=gvK_J~h3RUbiQDLqmb8N0|(2du1XoP(Im4#Fb^Wo6$JwH zf{BvK4}}Qe?r#R5Z08FjvnQe>E6wYMT54y7DBsC$#CY6!k}{v*cKz_S@S2)5o-@;22Qq6>Kyv;i~jNj zd)1pI!Y189-B)<2W45qFv(ft4rC8-#j)S~YBN<}v<;rA3{?rECXGzMiW(@W|3tCa* zMd}Vkga=Qq?PKR(a1-i2$!q*A(g5R@?o7!U!}iGW^6TB!^Ye?shS)lZPJ(82m{-fm zKzHHpy*oQX@_a^@*W%y#OeE^BA3(M9IKgf}T<~@lVpqg&eoYOr%ap1vDx`CMMjmni zKo;DttmMU$8m)pBQ0tw@ZOjf-FK!G_o=JG(lDfYO)5wQb{|gWSZsLLukbBfHIxz_s zPKuc@mvXmQjnv$c-8Y0YpgeHhCIN=@E&nxe;toRh*@M^khPh=%C8?0~3+?>dH14k_ z0>YOt&;4fmj=wXe@69b9n*Y9NT!HlfW8Gj6Z2)dke~)H}>%BaDXsbQirRN!$hqW0} ze_<^jfOd`Ym`d(IxLFp4yV(E^x&wO~G$O)8!#DTt5ni!uO#QW++B^op`+ft+ zuYPH|mM3mrVQl#SH25DW{f}z=KW7gaGUD>u9x05&&$&-$+AG-tm3iE#A9?_Q4qxQQ zEPs1m>Z7yt9_gNKDJKFn=C5`z*~%9zNpz^4tIr7Go$(U+#|I=E9SON2nQ$RB#bgnc5NPn^-pB;`M1 zyGJ3RY$UF1RlkRznCTp8sqnX5WqjP~UI4D{OX%?#b?w8PF8pA_T+>49nLLGTtr^U& z#s%q04Et&wTk3mdz!5Wo|J!bOyQrwB_(SG&gyqdd2kGzSeXGN3iOt{q!FJUNh-jBF ztN4h8azo`kNheQHc!1OGh0yXkskP@|_tiyu&64B3j{e7ASZKAX1kny1WJoaAa4Y-i zVxO5H?eX8(T;-TkFW$wqv`(XYHnZC-8+ z3Lh$0Etl>bBp%>q09gOW;kpS$i%0+Tr^uYrD8xKFpvOCWdG!AcS7g##7X=*ZVhVc& zb0g&R_Sy4}V`SX^dlygf9B60Aq4+kQ3mu30&C*IBzwj`E`zc~O9l z%-`DoQc^CWurL==ps~|>BJ;OD0ODynQJ(>33!I+|8CDg*$mS3 zBu9k-vl{;>6hNfiM}zeyYy3p$Xg4RLOk-zC=z4w%epXmi>qg3=@2I|`XR!ReQq2tU zf0|_A=2oAXq!!vKM+X`QOnn)_i8g1F!e0lm+a|=?!clo^!F3kA`WB^s8^AGH&e}Zt zJQylA@Zzuz*RD_U@z}wASvNpfykq#jBx&Cj15x*9_L8VV+KN2iz5i;cb6Qu#Ka<_m zE&1TW(PZkm0f0|tP}m{7UAyXY15uyk!GI&7lbgTPvuISmtsuVb1v7bu7_s;seLCT3 zk>$_w+nC#;WfNINmcP1{et8@j+`18ASvsf(n#w&MslBU*oHl{6jh7DHongE8Z!3;i z%&wo}zk$0UdLl8U@D=0(wEKgZcf(aBLhJ>R^4kCyr02KJm(mT*x(pM{cre*ha7D~$K3o;Y2J}(Z2Lpo z#EH1Z{>{`FFJJDPeV)OGUr?e4zX+l_rfItCMn^gdFv0nx??KI$rNxY(HJnq-Oe~`b zqgfbRxfqimfc@9q&Z;!ILoIK}um6ZD7nj?pAH3M0jrPH~Ig8Vq%Ey~BAuy@eV=Ep~ z;-LNe=3mKWwFYO}#9weTsrus|s~@|NX~LH$&vWYHPk+6heCmSTNLXp|$AFcpfhNYF z=FsqgOS-z<$+EcT)(W&xJ%cScSL zppEg_PRvE!Tl=02WPO5~Gz>eKNETGI4`d||_Uq9nR0Z$hFNv!bU-QU{N5epJFT#n_B}NnqAWP!bx<5s z#dUNic?r_G{Rie5zzjPpFTq=a5av=G#BTsgRkgit{mM3?{mFgOTc|g+yc#K6ff`%$ z5}keUw`E1H1S;eUfNy%fp!y``6vr?AC>xPj>8Z1O{e|~h;9OE77J@4ts`D~KWBpwd zzg*IkgzYEYDntgr)})$BIjL_FY<{tsx~ znGrwHE_d)M?6+)2>Tbo;5|;#!8%8$$=iuiP-}__Fso|KOlY2^{feCBA#2dUF&w$0> zq{fGTNFdeqe1GX<^v@1=MBkH3dO8!Us~`q#6m-jRdFqTg&*Jq|KKiWm^w^;!WYxJ1 z=EZ_tjniE=2S{RsThxkNt)u-|z7`Mn8X=v%e>-SLx5XdlG%U^|WoVa;zNL|7HlI#Njm!-$_2FbC$d7~Ae%+^~pIllh;rFX?-U6CI{0yoY7V#*eqnp9&f3QFD zyNGbO?04X*`yM$^wm^S(Sca5c@R-XkjG9?CBnfv$jjBzpkzlThlhjQh8%wufyLT$Y z|AX}(?)IU&LGR?k54cHb&EBe*OXg*nHVY#gp6Z^hR9&rI=?cm$)^IUC_j6oO_7E@u zOM?weUlMk=d-#n zIXlR=S`I3o_dx-v1^Vf>k(IYDzlsW6UAmKFSd65iuT{!cd9sW9M^1R&4NY6aohuRu zJoHcBAv)GU!oPJVfX^iC*a5~twy5tqhSPd3Xwh)J+p@E=H~K%Pce9&8(QHa(&Zm#06(xdc<0Zj+l)e$}hUq`r9n4=R(NLwrKmBa)%C zEd{&9)qUVV*F?X(R5uo9^)yNqOM`r#u$cgIJ5@w~3I4t98D~kMMG-|&CS1om!Uf5> z0uao6pl9Jha*RQgh~iQA5zf&lUKs5v4zi8QG`6w#Mml6_>`E-JW!|`}Z@KFGHlZXi z5JjF-A?m^?Be!avljk zfRq+QvQa0t1X7><6Q}=*LY~Zg^SS-9vp@ybofHuAg_rw3Kr${&;JpLsIh(v>ue$bd z7syIfI^no(cOtbcgPCJT#SlSLm0t!ust7w=eo6hq)4#>smmX^9*U5i4Z5#`Hd+46k z#G51`4y3k*bF-o%5|vWTJl5|G87pRI6eavHiE$ni@9cAm?uuo&Pi);l5mN>S4E80x z3I2x}C;%m`?bi2>S$gUA;A>MO7QSz@3;YVf@A3(>oo(_td&(aD=SS|wcxhVWA{GXND2Dr!-tY=%{^I5t^cs3%;hX`LZYyA$ zGZ@~b98FyCoHC*K{)*p4P8&hwuMJ_`SfH`#>VQvUktpa`;sjp!1kC7TuZY$rz zH}v^>dqw*g_zp`8&jhj02=$dd9X7$8yX8^!5-0IX z>>okThKXo3)pVhZ3yt53Y8^F-H`N-uwWxov3oesoNNp^VKPs63CAoJ3PZfEFkfcU} z=3pRF=;5kQx_9f-h5pmeL2Z#kIF_);Q;%lZD zP=61~WY1?=05gX9_X0gwA#n^zKSZiERMG0<^T9LOQ(l=16x=7DV za3k$o%ylNhVe#qSJwhu_{@Fy01mo6ReN&-0|I;EeB70v^AKR8+L#G)#XXB;^jiG4h zkh`RJyvoprxe9t0wxJ~TafPw#Io=v%!x5v{&6m+#`$_OggKRS5+z2evek;K(SRBv& zIKUV!AMlc$z4Pz>o{pZk{XR+3S-MuF{eH!7l992G^ z?Qb+9Q8(0`bS_6rK|zxcotMn8OPk| zE70nd{Ekk)PsxN+b@g>5jYa2V_jlNbL8R#K-ztF~ZmJxvj>s-9-=EMd zxZz=28fk9wZwJ{4&eD+YLArOJ-R%C2YaiV2C0PkAJbL69cgxa+pj!u79;3MBN7idt z7}E)e-5=WkZq-AN-WYXizj4nd{>uU9aA4qwKI5SQ)ll)@6eT7gQ$g~Cq}x_~ z*8gJfP2-{5!~gM-gCeHWv6OA?1o#DxsCKFNI!y_uQZLTHe?Dx-RK2=6Ms0oA=vy z(Rb4e;yjOYb;Q0$pPu={i2+s?ZSreGQTO>JsL5nvD>=jH3Tn~Re|8%P8%)nS@xYV5 zqSB|kafMsgwL44f$nb5Yu&SSnk~8;O2}U{)L%BOrLCY)UWg<5fyOP}vrfsNy-JZhg zJz^)5raI-re%szT8-wIuWbV|_e+LZI=T|kyQ#8*0dg+JS>^+FkU^pLl!)~ul9$1ePgfF4!uA;&}U*(`m8u^7! z8}=b&LFKPSZ_OZr3AK5zif_S+yaIgD%fn=pEvvt7~%>kO0fIL6N1%0r07! z&V^`OB}^d2PF}t;yM~rF*1A6`&CJM+(Sj!vAP0wDju&KbwvL$2M3@b;UhyZrO`trj zcXo)YBzJFe0a}`a`s4V}%&A=`XdP@_m^FJxvWHCfStI<Zd__7mz=m`O?g!@DV6ShuN_11{AS zJg#N@vfw!&^1U}A?Q&9@g&T?!0*(%ciL)2@vvZ1h&%EC(ZaHB8G z1g{mMy=YuxYFC_$`ZG6cE(Px!MO$NyMj4GE=Evp2B(^6x1?>n+DB-Pw>v-VPB0A;C zhL*Y`433}}Lb-K>S& zl8WOahoR;N$9mi)10rmXYDe%|MX*6e$R~1v#sxk-WUxok3OsO2NG=|WKJaZrgpv&J zXNGKi7nbKf?-y{_igz0WUyf6L*kDYLdnW4}=g~LGo4l+X47)|6pOV`_cy5@)4p0^U z#763Sv}U*++DJ*xV}svS=O7MB$L24Wq(b7Pp76a~M}CX#`Kre;- zV#XFMj;BT_9QPHH7MeIG2bMM`qn1`@v0;qYV%*!bmnP0*QLF5`t@?hC`SL!E8>mIu zh<`7@=M<0RoTBv-M*Yw`##xaIVS~3bYFuBtdMM5r-#FY5+l7mxC-O{8H_Tr>b?$pJ zTpd9e1ixGjyy;dEK{`^M)%2TlgP~~OuUb9d%iedLn}|kNGZ*-fmZA?jK?R|Ff?Re6 zXG>t}K*p*Ei>YSe&+Sq}a8#NNqmZDa^jl^s1xO|odo(5Sm)_HL^e4AWi@v9Br-n!4 z7s}D&!SCW)RrZ6rHv*Hb2ebTjJ(Y{6B*%Y_Yo*5(qN+pTEe&2v6W@q27_IH|Qj{bw zB+rF-Z`2+z#2ONk5dDdN!ga#5VvqiGl>~ATm;?cOe zt`8J_SMv#M&BVQMi0FG3!8y%=>tMp%(uwrP68SK)9{KAF-zqU&+?U=e!NSvAvnLye zt~4H?iL%;q*;+)yvG|C|_+!QKW=j*E*b@~;oa5^f@xw+fMX2o)*%cT(5Wu&9)-O`L zeuHar6+Q_MpmgG$GOGE+^;^?|`yyAlrb%Vu!zEqfq|Ex@o!fxQbWCW858+qc_kjw6 zt~H>t7 z+cTD>Nmx9y_t5v4_{dhOwt*F>FnHTQq1`23F^b3!QidX;xs4>xK75=DekFm)gfuk) z^jgcFe(EnE*?(hvLm#jtKV$U6pI=N&ZcJ&0zvAFsEyig#)R9)bs@1W7Dxpdy35#gu z@M8c;`@g3y(j>)by10QQ$v^*qAAK z7KR8oqzvqg?YBkpcR&SVD(>{0eCxS*@jH5z|w+7o2j(7T+B+M3~On> zJF$}oD_2N%6Z$&;!wfKSV2U8(zJJZrIMG+4rG5gvy@MdP)(OL(AvS(YahSwKQ&_pw z&1LOTfu^$nf61kQrkkc+FAK8ShLJ(#1*Vl^uT%?3Q94Q%DxJuci?DL#yskJ^49g1wZRfY4{maE3^CE&4 zZ-2+=6HofB4Et1%Ll9v)O8n20@#$ErylVX`j&mVdj|Mn1x5Yt+Qn!2%-86)iouiYC zq-?)}bb0bkv|%(*u@O?N?!pSOF~jb3ggUBx!uPy<0rL2^rLWA(f)n3D_S|i||8P1= zZzlH(F{U8Ocz3u?dB`VpMb!ur7P}5ht-o1cx|jz_c({#C<=s*pg&(WRGMiZ}BSINd zg}G5A`vgvwlu*D;;FQX2ozk$qLc5YdSBYwv?3=YWUok|{L9cyByG&M^f3KwmeL}l1 zmBx_nwMz=SRKOtk?kybv1m=^S$WqX^n6arsOs-hZXlVYK)&cx_?bJKo!z%WUT2eS~ z8jlnN$!2VOUqjXc!$L4yL}>XrCjpX5$>M!R^OGxg@V zNrg#WPVxIVe863GM7K)H$&_)WBXE}E@)E{n74<$B-b~xr3JBkqPevp=<)yGyk4!UfU-~jo;1b^4Wq@>IX%xBb&gFjtfBD%P9Z4m zUq^&kpJGB2?^a|+f_m+>u)P9i~CsPRgO<(T!^6>LNdq zw-*Q0Q&hFAszmtQ)RZM1_aBS^BFd{CW>n+7H&BA;ZsYN77#3=Qw$^<>I$&M2VqDkQ zSJ>_fH=HZ8nFqLi2aqltiFe#HqERIxC_$p^ww54`)-Zx%7JvxZ<|Cjofmb_w(uxWz zk!01A)l_GSkjvH4f=-4+nC8|IGG+kjl76BH%K?POZ`mmp)p_O}sH;x2YBL}k4@QRRr>P z{(JC;O3BJZueD&HiRj3(-bN$~fTvg;tZb@XFAx=w|CL8ez>-S+lFEkr)))|AR= z;^uX(x$OUWT+21cLCGNt5n))@viKb{6WwR*Zfv-{HJ~f)uXZelCPg*69j=noY`$oI zJMM{1Y76h}4!H34?Mw(6;+Y6!g!(h=;I`v83WItO$)D^NZVB3^_s5AVoOsk7N@!zWedaCsKSI!(gBj3t0cJcT=UKS&S_E|X%DzRH+ zThGCp(+JdPqMGUALVx>c%&I@W@FWAJDC)*am4;@)Qfr|(K#ZN_B~zSe z{;w~NCLag5U%$+S4L86E!x9>2fL@=dea1lsj(a1DvC$s}Z)k1)r^$&;wf1<#K zyzz38po|N4Fn%;>P;U3qnWem!Z&B@|owx+eFhDSY0#zEoun=x@rvS!&^U; zOr%-SYW18oHBvGK68?=D0S{z)eog{!#t}{74wj)WS)*}IZiGpjra1Qaq3^Ng^-OtH zfJ0yi`nDaT0HuA!dn%t)URqV@nd z9*&|_@GUO`s9HFgwB+xE(qtOS_c3mVJ|7ls4c4Od2^0=)A8eu$l33;c(;o2#5$k~X z!5*OYuI43m)VlOxPty%9;mN;iR1cooxi3L~8=fz;9rByMIgw~4nAFaG9q?Y-%T_ED z)p#;Obup-lIksyIu{WFik+XEH;O?-!#JVsj@4qDuq1A>POxb|OM;+yNUpjb$x_*tz z3~_it_U>H-c|^r+KDjEPfSo91YXK{*xP4oR=VeE_gucGd0SgNTrC zj%d$Q^D)*H7ItS3Ba9~@9j&-0Ti`#KG_5qTc}%D4PgQLm*+m+w&4}?92LM)F_OJDN z&!fdn7k_xTM8y$iQ1JbrnX_AGN3Wpw*D(zJ4m$Pb?e*7Uo^TzH7ruMclf7h~gt;VY zM~~M6+7n4mZ?D5g01?H#u^)aT@a`2w`eM+u*cF{J=RV77Yq*=+&!XpvZJ_P2!*p-y zgLw(#ya{s?vxB;T{USR0`J`@VB z%)71t`KDZJbazpw0LbIT){e7WW!KIZnV5`P*+uxv99{EDL=|UV!Rl61BOAWC()~`3 zhpD$54b4|OB?Ow0-(Ha{vF=e88DLb*%04F*NMMwO;8;U8pfcre*GX2LF~X?o0u_WO zCzL^X_x`z1p>*hTz~!aAp=oUVP+6}95!08F3f7wkz_GWyLEBM`Q2LLKH+U=_q_X?9 zV3>3s8SQqcC^E7P@duE%5q4rrFy&bZ#shR*nJ4c9gN2Fv$GBP=)pEc-|Mw5pc# zQrO*V)}P)Y0DUHa0obBjLH($zDUD5w{eKun02Qfl8+j2_+pOeT9*H^^Lc`+Wf6B~#%3wz@G!$ZN+8;aGAtQ_U&Y z*vL!5u_4ldy8Eo%>lbU7F&pP4cWA5q21-DgZRxUo&Z3_XIIzTD!!~!^8ks@z7;GMq z)BhaB1-~<01c8{_=DvD}WJp$kj?>OI%MvP;3whJbx0okB1p9wZDi%x;{yLk3g5d0_ z#R<(WEZ(sTZmqqvHbv0)dMefT#GMjM)*xa5?0?8&FVc&jyZrWbiectMeGwlt`Ndo&PW1WJLaskptAaHlq;;-2$9~R6O(+#7p{pV&FFU}6wsP6H4 z6}^n(Kkf73bo^)+7hy&;r}zWH>h1E_XOFNR*2$>8rSatHqF~AFVU?WF=K>nr`|RP# zG*~c^_Xc88MnAAS-k1iJ4?C-TLN=bnI`Q5*!!T!HKyffb%3!8}#mq%8NMSpqNz|1c zhJG0ZzZ30U-$_vgDeoiL)`T~^q3PiDmn%@~M7xP#0X-%!al__ZR zDb^hqJZ_YryR8u^8F*LT7f1A8MN_pyqReW*Xf-}Afk=tfny~sBw+iN8*!{E|A^jz=z zzr=EI^8p!|XSplj9zhUhdx`d4SchY3%Zz+K-Zcx2+I0l*EfxyH6V3bS#O0s`qZITv z&XNBqXRaT9HRW`5B+%Bu>3hd%m2S9jZ0S&T(+#`tbw}|KXxxkUyxJ9yAVsL9QPs?o zU)NzffJz?!+zRyPf{yta!$X6`{Y%dWjwG!?yw-?gs!4jYAs&0PQ%E5j4!>q^7CZhM zM>DTb`s=3(KqS?;hp=*J3ocM|9*-uXmKEMG*~iL+F_w(elpI5A%YnYVMLL%Zl9xIp zH_}Vwwmo^}SJ5~L(_wKyRF`L(-iM|-B9)nq2M{<2h6|P$X%m6Ga~1m|OTrYpv=UMv zXS(RYn)rd*e-^y&!q$E2zo_~xXyI;DgKd@B!AN@zE0vEa8HW#!I=BAeoJsN;`UL4O z@NoJh~R1(P+8F{nb+8p_y%<+{3t z>H>vSSw>~@*5?9I`7IIm?GgbyP*4X@kHm|5tHPr6Llw!5;~w&1OXVuGTpYBTp(amc zfZXV&6^saY0rcQ_=XtmyC5Q0siqekRQ5l42lJO6Ozu9P`!t(2?-pmKOhe=>uri~>t z$@5A$zfSTHEGsv3KV{9p;E}Y5MXAeLOhbPH?@_{_MB)ly5`=|G z%gBeP$H3#Peqlbr$YVr-ytMK;-Gkh1)z-OMGLcH93oy7FWdiC1%++}rjR0uEouWr_8*UG~M{ zk`E%56?RET<6<{{b(uH+E4^|Ay8BbQShxH)!H&rmHjN~u@F07~Vm_ZwBE&kzfX0<5 z`8c^KeV;&$cm{{|b~zDQ%uZ|p7qKtsK-Dx900~Tu*D$1`eAx%7fO*Y~i7#YY6xeq$ z+m|oEWBbIahogLALyjxK_Fkkq?=#o{%>B_HN^2)hRxCRu0&L%4Voh^D)8B@qVWgx7 z(AV37HXA_1A2`igZC?%(8-AIOslrX-baJH+k>_5phT?3(=?8oo zS410%7w=2mmx`*`HO8*AoWW%}D%Wi^IJ0W)XsDLs=9zKY1GBqmBldDL!uBHG*k61) zYW-(v2+O$oE@_of-_%SN#=asVtJ}Q}nW2(iidc{CLXCc~ioQ7AS(1VuMRI>5v6%#ik3i3si+OpxT>7u$ugd`){ zi2t}tiSOUku_>v zFzR}G;yBPRU{>@>n+^mZOEm-s)RlojXPj=$kro}EI4T#xeGOr~$Ys6dwiw5VR z(-oaCEZQ|xmc@`5d)V z4e4&W_y7##ZfOCvB0;*=R*BAnsM%bv@D2x?%>5b2n!9%75iaZASn~(P*kX-6MvK-t zVvEPlE<)D&SKIM@{46(@`Z((*7+}%Z1C=Wd6lh#T$-f>@eJ@(A+Hm49e)iD&a1r-b zWu2@WMRLQsFJn>lW(@E-T02a;YUuqKtn^bssY6o{w3k*pN^X>*__`DIMSFD7i2`j2 zYd~8kM1opgU8RGU?LIf0Yf>aLZ5c^(+548)eI*Kh!=0rANR1B=KiYYfS zoLAWp@Ys*75r9C$K;s1j1|k0Wr7Ed7^Lp}Cqr+Jx3;N8r;mP5xOV}fv3N65vu}1(& zbTKDn45cLa(hfAmx!j4Unc(o=FwMiMrM@jfUqOTvg+cM%q$yG*-m#v3eYp}I^R7x?)N65RLm9>Gqkr>JTdMtp_ za7xo}NJ%cV^D%BdNH^*4WSIj6Lr?7vTB{I>_RK`|OXpGN!6Ei4$rohO&)jgp5$Z}F zRCb1;8&?_A_JqE)V*cT$pTQVmuKDhwT#e>RMUW~C2&b_*fLBABBx zxRLl3I@)Zt%$@Tg>v;$xJ*SB>9vfK3tf0$Juaiq^^t+_FkTkX;Z57|#c&g=sZ6jc= zJ+PKT9ZB-=Rj;(!DVa=~fB9sb8b&0s^d(a!PGY-Hc-}K|%B)jY_{&n-g6a&!0aZqG zPqOVIg5nL*a-07U{m7EVJmoY3$lS~omcI@pmGeoHu;NFE&(ttFD)A#IfHmY9ws6c;21I9dHyZk3 zA9ihiZ`4#VBpYyP;O=>H&oZiNM<+jwg56;V{_J7LF7LEj=dJ-g+ZFC4RV-`tam4*M zw%4QldtW!>z9;kiyUT4g=h7jR9KFX=s20j~1GSSlN48xSTW>z4|9*3-!n;;G{0 ze3u-Ie@*~~e)I^f-6Bo)I=49+*_Jt4X{xb=+A^pZ?U8HHcp^{Aej|rF`ht!t zPF!v&FfJn&@s+hZ24_czh=d*Zot#Lz)^-7E?HrP#HUwVS`0}vkq)8RM3FZDs4ilp z!JYwJ|GeVq&}ZaI>Td-pW1(!yGo;aaofT)$N0VxuKkomyrM2|%;fx#%UOk>;moq=U z|9yCwVFM{sbwVnzzN#&k)Zd&Mz09tEbj>w!0y@kqB)X zbYnjERFh=2_!$^fo7>s*ahzpmO=h~@BNE-#AhR-a6o;-o)@k6M`ZOOKrxav&<>{s{ zIxhDNw&w~NVU(ac?h4=~Lf+`sV^DL!nBz8?h*zY>e&yzbDrv?SiEmTFGN~fUi%I@x z=@(N-$9>A%=35PAFSwXE*AMp?EI~6gn5n(Lf_u!kK}F9OpC|U(hI+U)h53vXuaRZc z?)pCQPo9AhxYYDKozGrDosV$I~=XZT`;9mCIVA3R=d1#3d1D&(a{duYpD3+ug5p{ZYZMsMzfocVe+-` z9#oMHER7$UE|p7WU+Rr^BOKb*E&5Khvq+%D)9yKGGB4KRk&T>4-!&NoR-Y`FE7cA- zJ93${$iAZRPqu(&?#~b@T8V02lARIxg%*)jxmBCNh1I zeAQuL7(No`;m}pvUOTO|q}yHLRx_GfZ+_4|qIl1$X+~Pk_4 zt0EI4nU5zckFf?6lIhsKQOqT=ItWl<7L!6Bd2C>v9ijWjxnWm8U$wf{gh*-*pPmPU zN`qWZJCX5%9D>pTWn&)WUZx$RZigoTf+q>@wL1`jepBp)y>D8}C{@A!LbtJTQ*u+T z;aGOPo*L=r@OkT+Fb|SDjofxkcLJL6>)bdx6RuM2z#}sB2gVj9Hl5n)t0L3!xwRCB z^|%Q6+u?arJ{y+4Vv8l#{(_)+%rn*gvG4Ex40;8l}m*47U4IZ_RL-o z{)(SW38aWw`CrB51yaE5^W3YwjQ&Z7o!#FXyGr)Wr^=!Lb+i`p_Tm@KXo*nGdB6Sf zE#-(>C{*e--^*-BmSKt}4RUI`Jd^4&9otAt#PcJgQvi2*wra{Tk(B)TA|_qYI%~Qg zH}sSW{!m?xDS z*&*7k;4IqhwoqEGyJ-TEA7PZS!u@|P*vTM-JgmBez591kvdg5WL+HnRmLaQ!L3~eJ zki8Z%kKvkrv!+)Z#nASn+3!?5p@e8rbW!QZF5Oe<;3?zJcv%P$W&PqECYncHqt57+ z1NCWEfV8!d#7J$tiaNwivy0_XqxM>0^P*Xj#T{xsp)ROe&<`V4Lg+_RPEwrW&kvt@ zHbDzh5*_W=+>!P8PaC(IgQG2wCwcy4zk>Wah95H}&|*-sm!Ij&?J&(mBqOsz&(YRz zPZtpy8P&gKCvwhuC_el%i?yi$oN>=Em(COd8Ym7Rx$h`$FX+9_5dnqH?dq;t4*yvC zZEe~QzVe_!YE+1>p;R%fCHEu`=&)d^(ka@VN+{_@NjWHJx~q5_c9 z%|#G-GKshwQ;;oKXZ~@WT9NhsYD9x-L&&Sn>Zs{SrsLY>zAyBo-`)`jT*`p3(lFq!qVU1UcGJ7m~n&~9G?$-ZmdwuoE`H* z)8TqWUJCWDGiQV;X;G#PgQq03_n(u4Lx9>e<4l5ot2urgM~>r@I1OGm8YDBd0!M!f zbfkifSV+C7C9vCr-qImtsd;rg?jTx+uDqn(C?Qt-bT-)I z8{ns%`(m&1Ru>c~8Bp!&gp!oNAtw}EAu~r;6^Hg_o?|4J3c{`RRv*>SBXk^;>w3jV zVd3!(@S(<@_448D>hLgMrSPYuiTQA#E+mP(#??HssCkylXHoX*Iz}lC|Kh!I+Q}?= zyb=m61t8}H^H;~!1!weuVj6Wbr_Wy)QD#yq87B~U=yQIT#qlu~Q*GSw87HasCZ;`{ z^T;lBu+8-@9#xTA-|D9GbVuEeC|u4B)bpaSC=U|&AT#8yGSE`N;gIn(3*fnGIHd4Q2|Tczp@br)YChM_%kazMB4oIu21Rs3kU6HN7DiC4o~w*bchDW*vu@Oz=h2fw?-T3+8~;2 z(up0zdxf_k;f*1(3P9~TOjX5FHZzHkqb!fWx7S8r{@NZoa4$|>qT{J)BRmpKy`1RW zmt^vnjT+FlA$2nX*JH9()hd5NTH=03BC$Wg-OoNfX=?iILCoH8EGcSER3Y2F!VhRG zyRr$RTB!70IIk++myRe>?PQ82`5&~F%#LX4YwT`2zl8?rWK zQiGI$6_Qd=X;Q*dJqX1;umR}JSv3^_D1W;f4qb~tw%2!jRBi}eCslZlOEFzR#TpRJ zy8$GBvs?%{Znfw*tt?_-q?kI{v!a{ae#_ zp_5XT%aaMwZd4BV7k76M=rtfW|1R65s5Q4-Z1wT{$Xt|y=-uX7owtU0^zuyCyb}GP zon&Mlu?gD9I7uM6hf8rgnmArJ5_OuYMJJJjmgIg$;jf)$)oOs}1lS3iP@HZ?6(mt7KM76msh=MJQjctFxeD5{ zt);Ok8y+I*XRE`%*-S69y;BCrXUUvlANBR<^VN=rS9vYSvUsjVbx8?%s2TTkJ}ont z^8&@y>Q(GVm9$3fW)6cmNBPJQ42proDn> zS5Y$&1w&q8UL3=(YY4ID|Dxf)J#M{pW=_1jh>TO(H5dh1E#aCKom$Ed7fsd{(v^vU z{Ty7RLiph(wpRy|$qS5|ezRx74jM?dOnz3d9YGn9ZjI}Kn41Al1%M$~7%G2%N3BHR zFlE2)jH*vp3-~LMe$)HqXICo^l1}Srm+E_x!X1}N?EM{8!pzs<3pLlys|Z8me+f+f zzU-^D=w}+}5V|AO*j=`esx(qAq%GmgWCqqI` zUoMzjOgw?Ho{GPMrgnfeFj)J@W5*_v}t2G`L z{m4K`jHGi@sbe*Seg1VCKd|jp&{E}akt~}+doiHrlf_qu;CKSwur}WP>bMY)jRh*W zS(CXeq8o|{jM}}ivaVU{+h_cdp(Q_e5fW99(t(v$mLD{b9saX#M>vl}Pa(lQJb|#t zYeB&9!_;f5bCbb0QY;h6LY_YTA70ppPmu-|lVSUYb^40}bVMgb2PsI@0rgIy8JmhA zC3R&u@1O&9e1G#%O1w}w4Kie)U(B~R=G0gBx1Z@tlU0qn#P|4IUBUFFM&%M0E3@#! zDdY4grNe`1vT4N-*P&JU)k=ZC35kDi#pQ*RpB|cF52!nfKF^m|ECVT@QpG?W5uovv zi{vf-!n}yLRVc0au^0FQRn*}2PXP-0kZ7yuJ4!y}nN(>VIhM4DUfQ?(XFXheKsqiS zVWEZ4NR9HjWf%&&y-70s=ZwufvcPW0&r+GfU6f zf_ybtL?4N^g);}#*%-%Y^U-qKSEnW`>0jvn!{cG7$9`Xl8s~d(^k=b zRGjM6Q`bXUk+6x3b&i5x20|6_?mD+)7Yu8w!XMe2k!^Ke*!j(^Hf!az+p68as^G&7>xUOV&zOO5v8Y!h#GQ;n-m7z=oE?J1fEs zB|7>;$&4b0YcM0{t2bV#3Jt?WGGZRI^j&z69)0kZo8Y%>#!8__rDfXttS5d+kjMn& zFs994&%Nftpd0pu568_#8}TUZF2R4|D!BEzY7F3bJ=avtiz{e;j+z`N{JfB(iM%xM zKAOV#u9?{*>s9A=W4JVJzn4LO5;F#SY`x-MU~A3D_}UkR@4DAn&%DI2kJ@W-53{i+ zVYr&Q=z#B!4L(k0$X<`oUwa*(pWA&mE2oZ_Pf#1pIEDGsE&#|H1WlDs{h4ShGNMZ~ zEM$G?H>rpIA%zpsdC|6Cp-?%-oI80y5rVNO(hw~z5?p<7_}x*u-!T)EdcdH8x%|$7 z*gG9ae1WW|rO}>uZyj|t)-htiYp3Ggd z;Ijp>Rdu^DWk-dluXV8~N>2>skBpRL$AwiiKTxf<(Vb03XG1H|eWNde!4`>HZg?Bf z?(4;%mNR*|;@u^zX91}t@%M{GYJh@~b*I2;mlf3p+vlt6IUj>Hk)&&>j&*S^JlEjn zubL%#-wlr?<`h$kfUsY}o@CWz1mCF`a^W4;iBOZdbn(2YrU^k)wBM%!Hd&p4>yoJ+i2^f8X3ZI%3cHzQXYf)!wJa2dm^Ugzg2 zrPtwr83fWW8+cu?W-s&oa14R8ad_w4UUPoRqkMtb@9yLu=+JkM+sYS4{NBd`klJ|P z`GFjhN3juoU3_BUDItk-eFl-@kI09XpaL@zR-)Y&B?)?};w_@3+@}!G{LEz+&fLiy z4e#t`#Q-yO3pne=$cwLS^VkK4-QA)slld4d9%kv`K)g%_AZ#W8O#pSy3Rh$mpJgbH z`=$C=-y>KPZZy7r!3Zr+|6sC`5~%2K4HrD={gPIZ3V>CL!+&&=J`^=gka}m|1Y3Uy zcK!oRPuH>4M@6JElJTAs532y4JEifT`e};*#t==FppmTq9>Y! zNXy~eob8@!4jiY8H!ORm5w2zNpe2>V`eWCW2rulOlXK+zK*x zkDZCOpN-1qPIt_Dc=ksgFEVO{@_A# zeYGYy1(UOQ70Gkrt=m%OusXyr24H!HyG*fsY$eYCu}h#AIjBc#zOBiNfoqr=5xPbr zX*h;`EG_@AS=k7<>n#9Cx)H+_Os<)~l)Y-Kn+2F$J=??Rkmw$*IjKd{Je6l@du6jV z!QXj zQi0I@&K}9(_5rT-L`QQ!_tcWXW{XB(49l-{fi8^$^#FndN!ZK}Tp!+okbn=%D@)sU z7cTDkd*fEO3UqHi1U$RxECWBznf>F113v<}ZU1mIBAoreWBR=xjOx*0tC?i~wL_Mc zW#Sj8*#TlV7w77~zl`=@vwY64@OXP@az63gmq1x^H0Ginuq3u$c?FVj%xs@|Y{$RO!X&forCH@`Ccp79ki{*H>wpu-}_)o8~- z$384|V5(ZqfR;b;=%mYW^%UH1BGZwn%*5~6icI$W%UQ4h&wqXC?t8lJGZx8tpA)^D z30qBFiX1~u#&ZzS{yz+oW2th?#V1SO1D~ylxjbo6m818a(9e?duD(+yV61gui}nL+ zdO(;uCl^m0#GPz`?e6aKw#MWrI{WKMz*k~%{=Ixu$I^R}OH!~^wkEByz#)%G-9u=?F0HLKW8efjR%ntIP(mwo@j5q z)th4uGW1Rfe_YuynKH23G4c0=iQ3~O?D{gTnNt!LyyaVIEsffNbFk0=XUbE9ar)0Q zgNz4;jvJ>03dOdzen#~rx?Pz*mbV)O!1oO1-S4(a%N-Mm$(*E|f|_%zIFn!(W%{Kz zkfvFY(GJb{RqdQN8lr7|v;ezl_TuzQR5i}sFr+n2(ddY;Q2ttW!2MEy3_XSWtzKH~ zudxgQ9D*AcYOOhLYonNl6D3qp-+P_rO5OCSR=s4TU(=JH{{U#%qUH0Rs`M*+5!mky zCW?Bfdi18sRJT8*&X3n0 zzSR^fA`|ajM7GauZp* z@(*?ddQz{wASeiG1B8gei7i2NQ)0f(%ZSifC6>NN0<;Ox7yUDSP$4|oK-xXW8CIzb zOOgd00B{ns2}L<__)ybbB)AKbd(MESVLf~=A z0JbMUm1nxZ-TG1q{?zpn&iq#n5QY3GlD=knzssu5ZF>4kKaM&P+F2co-Uq>e>1~3$#@w_@e%T>w=Sj!`CzIM z5fblcW7u3y^mH{>ier`$t4>KT_2FXW{@Jj?w3FEZWGi>4kRIyO(9)6cjFZcmRG&rG zbGQ-I*0uDgi(B3I$L@7$MUjG*%)}fY>dnth-rpgi$$a<{pVP(cXWrwDD#V3Ph~_jL z&zXGwxPP7+@U;o{Hgd{8W;TE6hx4mPY-jQ8b!TS%IpAm^&#Nt; znR*$J=mo-vCN>Hi#dG-$FG)hA%6PZ90}^f4O?5^R_o^$;vy3?2dsiiYr?-%0A}q%7 z8%a0D=j*xD$716d9n*cqt)ksf}%b79t-f>6A~k zT|?z)!8)IYgPzN-at4H6(9nqr%@OAef0Z#c$TK~w0s}5zNk34u2cZBoO;6idU+4wiVt!8lc*3R&5(?gkW70M(RxMvHA7cE+S>IY3VS62#R_07!60v5MA! zsw(4_BuyTFTu`$=f_A+x@Io2-1_k*EV@iJEvZD^lU<91^BS+_uRV=38sa|1k?AZzapKp%nVj$;l{VjM3o6E&e zUk=2*^_Mg7iPaDIv=;jvlLlzH-`p?a^I0%{Hs527c_Ct;pF5Hv{Q~x9oyfvEzq=`I z(Pwm~e{N3aeQ9s}sXcCB>e}pYObg4@K~#4Evc6|jexeEix%d-kVxKokzdH$e6FHk9 z+#J}8qkfHTp_yC9BNjBJGGSWO99o7rVP2~)l?Ju2j_+|W-(V^`tD)ZE_}*yP4Voyg z1mQ3OnP~c;=rUZ;O~v&0DiHePmOuIF8Dw)U$mrU;v%J04TJh+-r&SRou2xy|4jknj zf;3`>bi?$*#0Hovl9|{Zr@g8`x38|5pI@iLax(m}vB?2dSoin!+>y`;cdz(IRng?% z19OfC&@;<4M_=|&7U)F;Y6KKChq>b~V~ohHwa1)M<#b0@_-K6(i*WrVKe(xv&1`It z!%;1gr#$nVR+HLV?B$rNOOgCCcpf2cQt?=1vtka92ai@}LP{&|=MO#%8@HuOGpWu- zqp$|{$s3-z278RS-~L$Yn)zdIe3gau8;FW%)A&OVkMUMwT#(Ds{`=`#OQY@!f6;)b z!183@WGW|TC1YgfXPx1D#T$RDIkRC4n6wO|f^7?McCxdJ-=1G^=16u{OfR=8A7O{I zY%$V0yD0s#;N#B~eVJHR2~(0AoYOz<# z16gAkEfe|UK>(#GkRY+d#vRi-!_z@J6CfM%&~AqTik* z6cM3>zPLy-pJR!(V;er%_q#efqcp9x^+j^*+EOwpM>zXT-&5Zs-57PX9D`F);xg3q z8_j?*dU?sUOigj@&sP7u*tHK>&VZ^xnbKiZ>Yn6xXE={Yc7^v%$KFlMTW7)uZ?x5* z>@jxW8}ZpVbc~<9>}4sCgTG0*ZAIEO0cGiS7a&yV-0?+HS;n(4QORCnEO><^7SA$N^$Q{a1b z96MUo!s2p9C`ljrXduLh`{Z32&S)eni<0^o%bm$&&sKx*PC!e*W>NZp1&GS|IWYaR znYL*wORkL_No@Staq-l%qeeT?^@g#e;y$9AN_F34kDdRAo3Y?=R=M&4XQ&W6ltevQ4;Vr0k8Msy9ZhQGIz7C0Le$g!e&NblIs<#FfgSQpx(V<5%^ z;GCEUdNv|Ih=%yV>}~9S#zb6S0>d?|7RTBgp=G0q&b0SZH?c;#WQq#Asb0rdV7%ej zEXfsV6pQ`EJG_|$2CC_C+y|E(d2`TAsoUXvzr2mgW%rHPfnn$(CbyKpa6#zF`d^~< zvPAY4v3+*}0Tr!&fsOxD+nI(XnYMkr(bP#Ro7@`L*-TqVDswlg$)#};n!#4S*9%Us6XH5Ei4GrP5T&ivFpZtBlXJq2e)$!4WUbKg3mHUKRb3QwaMw@uaG7W zXCS`T`*X!@-XP#lYL4q_atd0yX8d>S?okIe!b3%^Z9tvoNwZF>lCcw1x#y}4J&4WL z)7HnbRle?`tQFE~H6hMpHVlTX_R0KhR^k4t!*QMBUnrHGK7WCz4G~n}Jy(z%R12Yv zt0FXeZ7QN*UNcR(OTr-8sCvz6U*wf&OUA0RCe*Ba z+ru(C$kxYZSjUW5qZ#miO#gz56=;4{dVVSW_&Y&!hUtoBfvzSiSjGKtz|ZWQ(>ar& zmJ5Od(+Q-7oyT%KwxIyY8Tx!H3aiSfQd(M@dT+6-@LcC2Q@CXH%Gf9&O^I+RY$Smi z=&L*@m9S8+YE!kxT=qEybZ1ie3QD^*)~~xVB~E!~klA2{ZneW#f9)$(wRaOOJ-n;f z#Y$9e^~*&*@2eh|b5&>Rsv4?kCP%t{nsE`=EoY9)`D|!&kjPY73BP`ImN$?wgrl=X zXQ$Ds=`M^Ayz^*oHiAB4BU0v-Bf8;Nec@br(Tk&C$g6`mseI$fLopQx71tD$Vx-HN zZStJ;DND0fTWEB%dQETFv)&-F^(Ey!L9F*pB}nTC^YbGjZXx}pLu%N=UWHRsAkY6L zB|3M0;y8+T-BdWX}td2vb{5y zD1ikQCQvmbUGWxyE|xiPvanYzg8D5a*F3C)ut23>HfTEX?TPK2%T7J%kdH>I>kNh_L~JVDca`KB@-~IO5$8V9LqgIC+yLS2<(rBuSmnt zBQ)NG+KFS}S&8XF4eF-GG{c8zU(25r?89a2!TyZeK$ol#;=>`;E2qug>0_gi=5(ol zMnuShWI{_jT|}>w1VLS2)K6}!0%|p;oc?#6kvOTcHvKRVvN#1i5ZW!EmSGuuuuK5{)LXcOA(*1};g5+5Z z7q#^KXLIsvVimc!xYkJpQrak`Q&$qbs9nWs4~woWbcu?dM5OH^UAtB4g_%bBwsLF6 z(>jiA_+bWaHyDk6atQi$xZghvF+MidH=7@lmXA`9mjnaZa6)NcUN3B^=FoOG!aHnU zFLS`KuPvt?K@(IKwdCZ!j*V1E*sl@$ z@8S2%Lb0m=Uq9P|ujsl3kL)A&Lh*Dh;}SI)4~=brNcu8NpJ`$>y2<^7kQY={e2u;k zblJZs?OUFI3t(P728tLOR(%<<3jA%htZpbuIr_6fc5ra2Zh~hKPs?&&F9d4h?JfuJ z;%*sv-bsP zw&ws5=`#&yi~X|6pZiCte%>|)9Ig*gU^X#wn@NHHx2d*y;og6v_kfQn{muXVTSDXU zkvSl&UnH6k-ZXHeJuAC<;{;=hLjP)0Iml+Y z=ro|R`kBfK@Y5*|P&ckb4<*gMAFLsWUXd-I7_%*YDv0>@Lr8_7Dk zkr&e4R|gJj=}@fLf%!#^DR=2V*`JgS02W&JM8Hx>!7x>9lkt4gmL1gFPHg>#Fp^X6 zbG(f@4TRAb%v_Yn!}N@kJ-6*tf5|V)BnKkG1=hkfl1~xk$0KKh5Z9C+H3CGcH`XDj z$#pMjykHQgjZ3sPk!*&YD+9dH#ynh1i_+w#fK5CcAN1++QdK+@MmOkzsadx#E&Lek zIyS-G^ad-0T(lO%_tkQN0HdKw33>AoLHmKvotX-A)Z@-KZQ4JBDAt_UD%)zWHA3{% zE$0z0bPDje3uPJm zfpor~<=uF|&zscO zT*Bq(ikdi6tABk}?G>||@svA9$?%z7zE6gX`@sssT&z$k24h)w=dX!B8m{?L5(|H$ z?Ia94ztrEZvNZ$%$ew9KD3sn*cWsz&a<$kL)fwk^$j|SOcP6@*->1R?l&e$UB{gXg z#&;O0-=1mXy4@lk1L{q>_ZJfD<@zTK=b=#@{waqdyYg~n1>;kzjt{cg{^aj=Pfk~; z$y5TU^wpiCdiA=~A+GcG1LB6@p2OJaet#2h;mpdyL?dDH=-w^2T=b&BK{#N*tCeV| z*V;+ct&Ww7o7|=o%A-(z&dD_QY(M;5Q8KfM94K%kkxYFjV9ks?>W< zr2N?fv`ZdJDn-59lRn7zj{%CD0LRisQfq;W+I2&i2YR~k_t(42c7c!!}RO?m0V zGvjayqs9Cs(R40Bo6u&{SXPw(%&OW!_}DnpOVj^3s0r zy;`qCH0W=@`7IXxN-3U}+EnV67mIo;R&)9J#b2Jn_h36AiNY;n>nOihQ${XVs` zO!!0i`mg-l%+HS&NY|PdoUSgVMm{{B1*snTmbsN>*#vVsoo3>%oL*@+qWu^n+F{9| zL22yuh#DRHG{*dZjxZ%r$G1I-r-=0uqgtDyZp2G@dPe0c2}5-bJU#bO9tv1uzNB}Z zUf+-r97Uvi2JwcLx`itvLFF1@*okCeN;6IQ_t2Zlp>>8pn>i3;D zIvjqZ#(Hu2Gjo!Yg(g~8@SHrP0A%-b170a`m_`grLOsogsN5Bz{wujNTM?e^mtlQ# z$P0_@TUs=Mgc0Kr;0SR-c z=`Po!>@B_~Y^w_kfW2YiR@i#Dln>)|DWu79+ikxCr)9Wb=!kw5ggg=%xSf-_wHPs9 zwl$Uf5lO8d6P3nqH1C9c?1l+G@X@S}cKT5RgvW8+wR@gmKFsHM>2Ick$-Fprmd8Y+ z^UmT7?s>;y^Y!CGV!I1tJwp5y%vj)RX#;m|TvA4}?;MhsyDIngYADh5+?$UaQy-dl zQI_g?%MQny>#3lbLvTBfnzEitAps$p={XS#db~JH$zWi)dFfDH(5r4SdfI$SVAi5~Y0ZhHb^8Ve63RO>UgkBby{jf$h!6Z{IaXEdo;Z?N7A8 z=moT;fNI1@;Q3P}Agv9;EGof0R*_^^2brbNJNqXR0T9MkKo&{@wo@;*8znTuH7ioP z%8n0yR|6n0`4!DIum3y)#*OUHvKpEdy7A>}O59@Q#Gx2e6m!qfA=7))t9bJ>zpVs97oT!E)*+5-Y z6ytG@ps#==-p<(~9Ib-F<>CV^B|I?g%v=mZW<%yOlTz8~x9O(bHtwKUHq3hC@kkQvnAz}{ z;Wmw*XP){F;+u`ZLj)*oF+$vCc%w+x4TnnYen8ez?3z)>g;mYjVUqSB_JtnCWD4?{ zvNC0}`bDKoQ9&{MK3gQV%O*-gi=k2Oz3`~@cp1k{_@x@AHr8d#@C+6M3s9} z$7U~RFFA0JsywBB^?7E04n@UAfB*i}UPs^3-CeS-iC?6MTN+9jg`pQe1dX230+P)@ o>;LbRJ@AG9NVZ_KUu{6XVG%!}@oMqFkGGw(aXedk26_8`0JOXCKmY&$ literal 0 HcmV?d00001 diff --git a/Firmware_1.26b/Documentation/Open Firmware.jpg b/Firmware_1.26b/Documentation/Open Firmware.jpg new file mode 100644 index 0000000000000000000000000000000000000000..bc58a474d7460d4162537839a6a069c8c41a96a6 GIT binary patch literal 91291 zcmeFZ1z1&Gw?Dd&1_4o8NU1;^WA&yx&QMVx6gW9d+jmj9OE})jydO8AP13?z=be~bU<^URaj{^R1CqCiqe~<#W@L`z}zyxp4 zgWtu$3!q&7_RHD*pU)oz{vhxNfjD;a~4j zdHDe#BI4KmuWSM<=nStv*~I@stNA1H9|Zm&@CSiE2>e0dHw3sjxdencd4#$6Xt_9r zdANi*`G9})3;=Ed`hY#y5;=uSV&>>*E6l-R?ZB>YWMg2=ZfIl0;i_-T!NtzW0f<6e zZS@T;jU8zXj7`n0#h5m#VNA5j2pwDB(#>Hi%&!%t0!^LLA!($}C$0f*Z!ev1BeRw0opQGD4 z*+2R^wvi!+@grj^V{1nT5DhL4I*xBl|5uF(LiBUce+WM)BS<5B%idVu(fBraiJz&H zjgyCsi%;c;irIPjc|MkmT~2F7oU{?~H;pF&Gq)W}fS@QimG`)|YFH@5qKr|n1P z;^0=>H{rnhZ#Q7CpvhrlV~cY9KHz^u;Oi66;=p!4?GtQC``_^SGswRM@*lYV!1Zq- z@NW_Sv93RG{aXn9Tf~2?>wg$rzj9n-YcR2O0W(VuB0j3CV~l$jOMwNH0?}UAaufNJUCU$4hKi1k1|CbIc!9qIXoTn&uW(6VTvF1i7 zMSruXo>;kilYz&;-VYmxgp`b&g7GTTHD(rGK7Ii~A>muMC8eZgWbfQpQB_laprL7K zWNcz;W^Uo&=;Z9;>gN9V$NoiSmMP=28 zhQ_Amme#h9J-vNj`UeJwhNq@yX6NP?7MGT{ws&^-_74t^j?d&m0Z_k*^;5FH$wdgt zbq);;6%F%DE|haF;Dt(vhJJ+$@PE;j&Z>^j{+OcSwC_z z9FndS#kpAbTsb1pKDu=Wa;Qd4iv*H_1rSI;76~*e(>$Z5g>3J=k7A73NG;wgOh@gu^5JR6s78c}@0IUbPMZBV-#+2+P z0B1o07oc68aYz7~h6JXWp;HfBA0xbZCr(b8kN}}>ktE;-fwR(pM9n{lt|5V^`qKnQ zhrO_k-6XiAdlMgntOQq81zHx1gP$Osk7%YR*FX!r#{ApZuMotEFeCt>aQOyWf!f=a z>-KLK6LjpQRA!AR36DNwM$tUeL;`U5_a>o-YQn#LtyQIB4A$jWmm*iYA10m2D}CKT zikej8!mhCp=2kKRD8y640wmDYobW>q$kc-sB(SrU0sV^Vo;iceE64oIO4RGN+zOa0 z3QVY1eMFNG#GxQ4Gv7fWf_^AEgUlTE6|!1Qp^IkyG6_0l#u^F|)XfPus1=a_PD3Nj z&ejiYfy4X-t~`dK#^jI7K4Hm4&9Z{$A~aI{u133&2=*B#3mv4iF z9;zbF>>)wqyFIAqFch_8MGFzn=vN4rNl;g2CL%id0@A8{No@8c(*Rk-MuBc0%3Q;g z|L?5BHgiQK&M^LNm<10~zRDN!75E?4dWO^QimN3;nMDGdxt?E}epgTGcT^O9mdjSmF--mZ}7C7!Sfw;5S_y_W7_zuF;PK(Jp*0fE22N`e=qhLY8w*x zhO6UuGyKO?u)h*X|1jnsM!?!{mP`Oz@mHCTdZAy9mF9=Ee*@|t8p1dGtu+V)wxNG_ zT&2I;!d~ESod0kjIgqOTH%Ru}uc3Z~Olf?zn(w%r(RAsZ1%+Qm0HUc1KJNYb7y^2u zG@Mob8+LHeIV9clh*0MAHuLz9z*k=c1Jf30!zBYqU}5Hm_LfWTVMhJ!AxKpEkBI*A zkO;P!=k#08#LF+ioz6TauOH;L2D_4eRpmsg05B>#HxOC1mrvM_?JPQk%;YX zoP6Uuf$02p*P+@lD8#|{7{UZ+)%ndVbh9K;oZa+(KK$D5%AxsRoSgNGS+ev?=!bV- zo%WlqK*QAi8ee}w*?oihOjo~a;cp7iE%+7XI)7NtS(H0-mZP6h?ssPq{%$@$oaJX+ zJ#!W?q+j_hq)TkV8tD6daA?@5XvIoZi>rzS*h!7jQV(W)A!o2=0&3zz_`* z(SSUCCmI8Zk~VW{ekV$Xvu&XufmaDXrWo}+5CUlsg5pNV&QC{EJXB4*au#`hlI4SB zk|0?DXs>%eA{+I!qSVvy(kMNN({4M*9bwWvPI9N()qs2^haEG z4^+cVye&@R>H}^6HS&)%1o;WWS$O`9^PJfNIUg>Eiq<)U;Nn%^sck{ zM&~zOT{+a6J||fDLn+0hl2nbhJcxbm)qB_sC~f=H3w`)|Y$OuSZUo<9`#CIYK#0{c zo)@zormCY0!0=$%+Cys)w(QmKaNhb1Pd&1mYt(s!ChDUv9MhXkUG z?eNy$lq*Nl49%~o1kRg*!6JXeC(dB}wQ83X+E)C4+!Sy?%}`k>OMN>;=-x&pDSmkI zn*eIbR+G!df}>5UeMUWFo>w==I+hZ|2dvX(8_uWdFN|JRZgSy>TUTjxkZ?nprzrqamaCK$x2+nfn$knBX%&Tzx^c@Lc23q zgl_+ScgDA?L-kEfEh*QX19>`G4>nkM(aooqw>o)}Ub?_V`uB)GdOXv8;j&-R-tIL& zO8lt|MtdS+8ukA2GhuthJ96zGVn1kgdF_*VmYQ|7itb;R&@L1coOIYxd)o9)N9v+l z)D59e$|a^d%6Qi=7aiC`)ZS4m?s9V7=PBE= zs?c7S2)N}{-&++Q??TKUltZ0FNB2~N#Hnl6WxtKtt`MW zHaaKo{XC!Cs~w}V#MAO7yL0K)bn~jC{%-HPw6{4ixB^RJYo0A%R;$!2xx7RlaUJgi zCuP30zE90T-Y~Nx>MNaFO0i8DTKz#y8H{b`cts}WJMD$3YB3-<#r)}Z`$t4NN6NY3 zx%?g~N3Hd;)>1QHD$!8N6Zc?};>o6#N>ckpGFv&KE*Dk}Dp_OH1;w)KitH#OwF-t2 z9aOcQOs~uurP~?Z9!lGF(I;sRrG$}}krFPGu%gcorE>+4>xxqeT*wPDOsH%!X&059 z5|PoJ#u}F66wMMee`WUZ&8lK|wVe(l5irzPqrDjawXNcr!-&b53*L?{8dE5b%q#Be(c{*VnTy6oI#xr-UV`TjAYdnl6NrQ)O>oY$0dYoP;j zoatNN+R~9UgOHw%t_0j{emd_&hUNow-3`rL z(QytHeS+-FutvlKTN#mt{K3{?;Ibm4f-LH}jO4X!z5adSW7eSP z^`lZtSH~l^+z-oKP4rj~Vu~%RIs7kIht_)utuE)@(U){kC)pfy4b#)n8X3zQ``Cil zDV=0-!ZjDFBFN;&RWVB#siDd7+ls9jiuk%`I(qvEPiS4CdI%WfATVp^U~#ZDk?Fh`_x1O5NB%d_0(K(W6rt>BfF|3~kVXYMXO>la6wlxtql zqngYd*zx*rv{H<&nQa6sdRxwjNK@WZXa~_vo$5P?yNS_P$-#G1mEt8{Ll#f&@41o=2l^KV>tndzSi@dhuQ ziwe-XV^5EnsZ{Lal`|VS(hFzJ)Vt02FnX(;wpBsq7#d8YwnMN6UH67;5@cSDl&O%C z-5p|7f4ExkR^}Eb8QPq%4}dwG2es4!^E{C*_&G4u3n+*#5T(l0lF}s!nZ(bI!8@XO zPn&b$y&pc7Smts0Yp5j>aM(fuK3-1q=BW1s8WbYeo;)0dn#j%*26?T;EHz!;^{R#z z>)Axj8lG_9b%TzcB)N>Fdq$aC@~!n~4Zl6o6H%u%MHNFtr6K{W{9+^^4m~17K6 z`R~IHAT)=VeS}y2&oveMb2MqGgaHC#b&RV7;ElALjbGXX0e`wgRq zF6UZInM7v~3SL2{i2I=nT}Xf~uQSL6SG|^5@mO~5 z?}#@M#LdmPe8S*~cM|^{r!ViI2JP4F+tZ8NF2&G0_slYq#YbbBq9r=4s6$Hgz-%#L z0f7Q$;f(_yA-{8r1fHmCfa?heJTPfS`b$m2iQY+4C>(V;t?zoO8?}gKl(~YDap6l+ z!Dhv_E`Z=e&fQq5PqyjJ5yo@Y2`YYbAADhlEU~m zo6Ff?<9)Gm;+B6sEdopJUjIgV>&G>ERuZARrmTta^QG!4rII*>W7)nw=s|<1h{J-A z#nk0fb{cT4ISPkP(ik9tznEs~iRJ{tZ5%pDGy#|QbdvmSs3PcJ#O*%Kvq1u)8<0&L z8^qN*;gsKWKL{J{2X~t~caQ)8E}W*#5dG!g0@x+#5M2NXT+*Xb`VEj(y){ed(SjRj z@b{rxynl0*kj&KOasBTeyU(#-3WM*|Ac6PHu*2BD;oqX7v}ePK7(gt{fa9K!{w@m5 zUm3ET$-ed%b9(U?X+nSJh;Qo)k(bsdNGTGiJOoD;Z~Ch=(tqLUa5+#sZ~hOyfAIYl z>i^j9pZM^5%=(`eA0pOx@$T$@VP~@{Z#)_vHwc=Xsoc+k{gwxG{}yzQtN&Hdon5No z%aK6sV9W0dmgCwXnnZ~lf4BHA;&7cs`9q?e@rvWcEAeywwT5a*jHP1dsX10e$Jg=< z?>8^-b3zC77A?A-IPRA9kjxfrSaZwn-m}HrgIg2?!)BTZj#p0c^fuF{bNGAV$ z#K1mprD3`Z!ZOR|HO>0*Hnh`y_lC3$2FBn_u($7x{KxHr!30ujTem+e2(*~UIlvzX z>TSVU%VL*ttzc$}g5{1ol2R^-+3y1bgDY8Ht#w!ab%$Lwd)x+5*AXnZaHa8AK=d^TbHjkIC znZ)5a(AKxyrcOF_Z`-P!7A@O;M822_*A5RXuM`XErl(a=pNOp*U#zp43fF z#Fazp89&rf>$uGE{B*YH)bmZ}^UDtKs6S5{`Pc%BJmC+h`H?_aA7pPGc6>=);<8&+ zR8a`|jY~W{mz{5547o?VINciE_DV*CD4jjnLJ*=VorbRoE0!5#-t;`oodK z*wfO55H02)!TRzCZ4q3jt4>XXE$~++n!Mr<}Juu}x8j1PTHmyY#BeBt%M*!2d~?%Q0S$hATg73<~ST)<$r* zM8r;>^!P(^#nra9&`y5+=V8(-N!u)?v2sj4Q*s_k4)ivv_u)b&mtpkBecem3jnPY% z0z-7v_X5@XVkh`|Vd%47qQ71b8O;IPm zVF4V?`({nQZ*rcQ-n^%KY+KIf_8rJcbH$bz0hH+k%F(yv2`-MPzk0o8bno8f1nyaR zvlFdU)K>jPNtfY*amD6H+0T1y&My9UN-g~*DhqEurJfCAeI%^gxt3^cF63ns!Bzc^ zn{Ml)8x;1=3JI)2Fn4nE^coK|(@cnzY*3c7?X{LIKZ8eZI<6TAU+57RDH0$CkD3aI zkicgSByg1u%xH70&7jy6v;?gMaE*zb&Ff_=OF);Hy6gb{VuC2+-;egN4P z&HivKFMKSLd9EaU0i{`*HgrWxZ!^w9Z>M>xoeb?X zL3Yn0fwt$c!)&29@K*1i-3cll%9nB+&44=a1QU5;4b8V%;suVyqq!CzeSx40ToE3T zE4pv~)(2!t_YBFT?@01OVsL*-i()fZpeEl=51N5x8DFL#bvVLzYoi)hR#D`5jO5$KdT6&~hL=6WSv z-+#cJG|M`~iepX`5x7h6LvW>^bVBO3`#p&JU5f=bes)dsuo6TMdbpVi3ihq(hJ5a{ z5_!-%J?(wOFHu<5IsR48b|)ZL3%lycUVaM*aD6uOA@nB$AFKV#UTr5rCI5lA-{tvl zXvzFeQ;~wibu%@qmDfIh`V0x*lUQ50 zuY&}Bn3ebM>iL&l&-`Z;|DUxPre8=kor#Mg=~6V@#S-yc29q)j3=n@YDW?7ZACUa2 z-EVe200*b+7XQN@Bw#uQ?c#vDLW6%8U7vdLZ%=844)k`~L2c8_fPVB9&OPEq$gig| z{iH1ELE88gwB0{V+GT4<`;KpqXx5@Vy2y$63c?LK(*QR=bNDkuP||&Tngo^th{Cp} z5WLWz9Q^R|W!BHo;&s@?n3bmQ6C3P zsvbPjU38Q_9g2h;QA+pjnx=P4+LFfFS&=q{LydLCi^Se0=h+vQ4RyDZU7(KO|KJ1Q zkL3z>640rOEp@cKndp^mvJ;N>-@hDeG9lMHD~J8CcQ*POJ%a*zW0Dy_P&3bXZ=%t@ za+x)?yMLICg1E3G_T!-Sc5=d;S{qx&UWx9Bp4*7cQM>yWsFos+=Py0Cu~^}w-1 zyX;UaRih1ecuc49VT3F_HdTeHsj-RRc2Rta;YsxkvU4T-7HyT9h_~MT*78yUMKIHB zt%<>UH*<~{^hV3;ihcsD=N~_Aojk~r{}_@B5pFNp)OIG})YP=pjJMTlF1npmA)+b; zw7p>RRUMg{i_9P5lb7uM6d@lvOUy=lrSrV&ERVNoe~1hc;D$q6^W8?K;IL19Mg7y5@10d+~l0V$W#k@G6`5L~C(B-?fzS?MLU%V>q)?*54;x=^SoHpC<)>cQ% zuPFD8o6E3|Oq0I{Z0TEWuy7ozQV5))@j*_GXpq3={EEJ}5!w?;N7U%rbv4U(WUWWw zio7A)%sTx7?NYW4RCpp?m;GjE{oL)25PXZ!&5RO&%&YkRkw2t1G*K3@kahJXoc6Qa zrTsBQ22KV!YVSv;hhqM7s%z#*KwtqO1s$pgnFv@&w5g@GsdcA>VDVn|e9pmlt-kqY z8yQXX$6K2&Hw>=`#3mXm=X(w!9)dfdh-|Su$UIn3(+VlJqk>)P@|ioY{}DdOYloA;quHc&_Xx9n zFz<{5lMPx#N24=bQFNzyvQmgPG2R;*%mJ$CnfC=V#()#+j0m!ejG+*I9yoQwb_&fC z3cR}8q_Hm_&Rj7HB4{_J?oZnBhR)J_gHhH#g4yVi&m9EqBqAkY{$$_{Q~d-%TAhKe zg~YbP2EXXez@e~154gkoHz9u^YPkhxCrOT8UOP^_@&0rc z3YRVgi+_SIBm5|mPT}CM!QDR*jX6U!{#Cc+)fP{FZd>g4d*Y8*?r_lYxZS*=_t4YB zvBUiioUxlY;pu+HD3>t|e0kMt+9I0T(8CbLO?R+R z!;8q2^f;`o?R3@?%;AN9$;U+%$`gBhja;>z~!Pzx&gB0**riS0+SOMcwkoKTis zhs{^Fxvzr}`Tl5frnr$8J_!AXSnycJky*6kU^r&yk|APWTw2tt%R#y{0}eU|=Dsz3 z(So;4EyF8TA}jhbVhIy*AN4m$kLzg6gWm2a@8DvL&9}t+hOT=kL+W7!vhz08eQ}@2 zJlknHK!fzwP00M4HHcmElR*PhReBmkm7c(OEiQuSz<;0UL^rkQIiqLmrY%7EXcsk5 z>QHEEL5092i}S|KXA#^0c&4TQ8&9Av4&pZCEniAWn$$a#dUawWZVbGE)prrJmDJ9^ zZBn<0yl#}aFCr*@YQ7Dp`<#JuwYD#wxfMg^c!p+l_v%j_j7r-y?!W}bQ!8GblITKx zkO0f>Ys5vfu;z;*Yw{|N)Q>!&GcV^sPk9$*d3x866Y2&=55n)PptiG?f~>TFj@IEu ziSzd61lRBzl_DncMe%2~JP2Z`U?d=cr-(p+?$x}M2g2`sbKp4UnhVDU{p4imy8ES{ zG8ucf#7R09GaHR!*zLTze?+LbhFS^5rX$6UU)f!-1l3>F|rlT~mVjC*2Jr}-&6%I73m4kNfKX!IhJ@>o4-KWoxl8(-Gq#_wh@j9)nU z4-kVv-mPwLG2D~xbFy;b__9pef?0$pL4zqVSQ7YqDD3&okqbt)L_4ve&TeP>XP<+G z|<b{su zBC2UYzDZU|f1hwWjq3ub#tpaM$fC$XxZY2CbmQ&bFJ|EytyO)QMdM4n*f2Ta|9Im> zHywr}06Ni{5asGVO_a<8)-HdTP+i{vI&1iK!^c5L0JHEn-UfFH1jfTgQ@C0Aam&7I z{uvCjM*O)d`yQiCeIY~8`Nv`23z_LQkB@O9bPtq;ycW1y+D6Jx65|d28mp#+-Eznw zBFqoPp7Fq&?&29QJ6jp%={^{W!5NOraZL!N$3Hh4!qc*(&|6IYGW-eS4V7}PpxN2U z2#=t|c(pu@!5xNpotVsPxdHds-X`lZT_Srsb_MNR%^LYev-oRXg+R7Bt|q#hU08!E zS#0y3Ei1i=yMzw9fq4dT7j>Q+K5u*dIe(NL(|UA1_cOPM&EejQ(|UN8Neu1tHs&i5 zs81PYx3d}2T?ndovLsgR;F-9wylSfHPxP<% z%R!^^LSxC@%iDs-;blChEV!BTR>HJaG4muj{$@ji{K5q5Ne;);zS{i}>tyf9Uxy)d ziE*h$Tnqts2Zd+TB2TZ-+xXp0n9B6N>@8D89D=6yhEs z>DJNMb}9D}oi=w^XLe&bl{@7Cs$3-gnC2`Os zKV7=yBS;xxncQz;#@lS^xAd)$5XPucw{1$EOGw~4V}4Fk zgqto6M?8v?WrPPbOMj8=1VuyD<`R{l|;{`8F5m}>61}6-W(zaw%tSZ z)p;jMGoJIdv0GD3SHi*?&ig*5d*LR*WQ%4LG($!{6WGj^nKqi3fES;&olabE|84)? zVaa`~i$h};q~+FXpN4$18MspH|3EI2Y5JkxtQhdYI>-5*qkS{3be zONBzKEt@_4ZHK;-({(G`aH;5auF=aljSRj;!H0+|W$~&9h*H9(UG+q`+U9!Bw55oL z803yX5f&5kb!H3WXOlkkBKatT@nxD^^XEv>R4pe^b+wl%^79=VBh`fS6YLBfd#;4j z2V3qwvrX9%h6i98$98c?M4$7u0m){n-UR=y6`IJtpRn+xW*WTHRz^fVb&x@}kme-LeSv+(1K=J`e?WsbQWXj_|zkT<(ijXX|P;P$AX3Cqc#7K z6QylIkn)^s0Ym8~b&jZ>sUlu5`&2WkAzfUkc|{kq5=rEG-^BW6vqoqQ+lL zv)QjNFTo*p8PCdl-pH(5KQuK&pNhV}E%P48ppQ?wyQLCg#j)ZnU*-9LjK*R@C4>Q!HxV5B7sOCq~kO=19OGZZx}&e&o4s)elEgw8Tc zFgCs*Lk~=eragC~6Eic1^W)X0jM`6~&hreQsmHnce;5uPubg)2DIwt76XTwzhk8(z z?T06;ga|Tfh&J7nW~K8DlhOa&-3Pyvr#O{XSke2ox+3&mh?m0r=lT$D6 zS$AAyzbIuTwX#}71U!YZ&9)nbaFH)1+UeREPKxA+oCK64P#D8dfqs5$&5d|{xQSl zI(BQbMP9+)_(WLsF?6jQzAHu-I3p@%m3OFj^OZvJ=i8eN>~Gj|1Zt>Qg}lx>s`gu*YOwMsOrJPeOF^2tlrsG6-RamJj1CeB$jP~VijY@^dGo`uuM=hrg6=?P-gSFZr zoT%Iz>ZGZzcV_BISD5@=CWe*;Q1;B;I$h-bWIJHyO0&_-$;s_QSbA~?0M`Z@k6eo% zfajIq?XIB`VSd1x)!YCde+1T8@M*IgEz_x`S`Z1zYnsJE=tPljP&VV$&;&QnY>$sx z@rj=oRo@%y`(d@x#edA@e9ze`NMA9lZXHbm-C4psJt5jC)BsO&(r6A=mG|3=XoegR zMz*`^cKf)Hqus}d(?IchQ}8q^4D49COy}_lJM>cs{s=-0tX#8&vP4w-W@uakG)8;` zf!j6SFTMP_5MH$4>}QZvrt{=oR{9pbe@b=e&mq8rlkeT?4ms28gXc&wlw!oAznc9< zy7uZJqCIKnpLHPiZuLLKEOp@eZz2p{2TKNf2u}8|?Y9>~jk}J*8@hG&-X<6gd}h@c z2{XDU5#YA4q;+vA_V$IE;=v(lN(+s#sTSYu_r--LzG2vmk+Xk|xigKQmjiCF9lP+|&8$S|l);*f7aBGCc%c z`KWk`FT5lwOB=W<;`qS#c-s=S9+jFk5>Yb?t}SNr{To>*5Mu9X#vZpG@I{GrF0DRn zv!Wj=u{dFHh_)%v+gVc@lg6nhtl=t&dr1-&;;kQBEBVOC$>|t>OL)qrLSAtLU=1I#?PrU3e;SXoTW&d7{YyNK#8E+kMlksz;=x^!IBGp-9u zVTFFUGF5O)T2cT%2ksyR?;$WAiut}4N|ey9zRfEP>{_(Sl&3Wpsfu%aVD4gp(-?mG0RQK1_(J7h1Dg9X1U zp{EpI@-QWIoWuo|?RyVN-#9V%^<}91%PJ2=V!`FbmbA@Aqn-0++KyJKkOaVFN!%397;7?* zj{d1$qRnPc*`>ps%2v};sb#u@$$$lcPbb_TK3QB}w9dLM2He zK-J^Liig&V2TYMhuk6X*=%j5tOmCgZ_?Wh{q{bS%W!y4Yig)g4ZR4un@X@fLxj9<{ zE&p~VBfZ)qW1miu&zN$m8ytDNhss)&q9tz1#3Hio)#yqsS+weyeB*C250iB?*lS*K zxS>ACX>dSKE`ERUDD%D4WpSH}cwjBQ&1Sz)$rk!p4faF6#~yWGO0Rw~sE9_Z)~X0u z41bQnDca*1amh?Oya`tgRw9Be1$<2Ykl72M#T|i1ndujmQTa*|cs@m% z1gAY!HwFf?7G)4ojESLX9d5H7DNDD>+RsJHaQR`v^6n^ZFoG#(4|LHay4kC$&%FFf zDr@|17vzL#MUPL8`2I+fkeJ2?aRJkC|F&(P& zO-~3QE?znXt3|L$hrC;1Llc9#P`IbH6~gq@_QI*!1mr-^1Ja}c85+M@);rb5JG2+W z_u@tE&8u?N0TjHUq!^TqEgzLC4TeWNeB&wAdmJkpte^!e2<$QN%!Ka^^fM{=()W9C zmktLqMe!N7h?@bOq=P;+JmgueUWXRLrWm(HD-Mu=wcFv2+gR}$O-(0P0<3zeJmHI6 zQ=JW*f$8KH;v&a8uW*pKum(JPIUF5kQp)+6X!>)J3OzMkIp)#BAxY`xy_#dUi*L~u zE7g)2Q4+Vdimiy$(~PKx=~__J$yIwKMRc&eHMn#kIFCC+aa_p$a@CVO0@RTX^G&cs zsl4i$4ATn*Uxq+QmevoPShU+%yBSspz2Js7mcOeLjD}eKPr(K{B1iz`5}Z{b@P-NW zUueO+`v!T^X0VywE_yF)lMwPD^iZmV8DNE^2Yppmnu$hc)w3QkIb)kAG zn^Y;*U;}qfMHe69t4*`KV6ng2jTa$xBZB+=j2ITZAAtcRQPRywINw*G;Z(ebRcq|S zjf3ze+pOymh8xi=E*#p1WH~gL#&s0~dmmJrldx2RD%(aMgr)5=5GZbVe8$XeW4T4{ zrlW+ZX6OTRGCaTn!2Mf}@KX3K8| z6`$T8efbcgIU}lvM(WL2R45hH!IxX-5_v)5qDb@kAdk&=4-+Q=Zp-H88H@W_t5fND zS&4MSVu1+)d5BXh!?K<|IeAOD$M<@Tck(i{QzwHaCpX>DE=bDrHQI9fk8Ai|QRa8> z?VChhh6uBHb`@WVig`Ud_Z|~%6CWT)4a{=ytV(~|eC@4}K;be57{)~jnyc-I7vu=m z3`%>U{II;vK->9OtOk0P!zOXoCN>}6u>TZeIlVF}UdO3!mWD=8Q zSK_Y6O{$HuWv@71IlN65=1fVL5Zm8Af$4?6n1+z(nH{G*Skk4c?Pu6lGuNCD4C3Lu zXPehHIG!M~-zE;(B3l8y8eBZIoSh_FEz=kydI!A6i}_&tULji;U`<~^5?L3OoeE!Z z%DA3ucF%l+(h;I2 z)H^zxsM)QQb1g5@REJsU{tJ&GiV`JBBeTD+$=!@(Hm31pgOXUryPhr}+{^1AcLv_Y zs)rK>8cXbOW;{;h>M)fgf{su;Nz~jpv1;ikPuj~HFMTw%9rLpZg~l_9|=!F@dNm*vT%nXh%TSkibed5)jVO_|$_|2HQF! zICa!p(7gmqo?4FOL1(sUju&B_HBw{V_xEyRaupx`o@;$x`I&2hD^))qYL-ZvodqU@ zKb0c|_{Tz^8K?F%pT69udlMx|q&80{a3@`)q6$m8RVDn{N^fQhEKkQe>dy2y|Eo_T z2l%hUec;7`K>Ax**24yQ{O82h48Su6B#;TUao@$6%r#KmdKNu%CDxp$t^Twzp-SBo zL+7#D-4H7_5~w91X{F*}GP zbPx%kb9H`KlRp{MN+3lgX-*gzWtH&qf_iu?(BPJk=1ifRU;VlWWz7~_XdSUD!7AbW zie^Z-x@!0Qe#N4+Ip#sIwO7=s`cCRre-Iz*VEO*WFB@!qHw*``^Q^8fo z2#C@!8@m$jWD!2)P+6UdJ zh9X2B_)BjteSws8H4K88V#2~{?$D51orwd?8@}Ep)ajrD8PfX#6&C-9$T{lnpPIdo z7)wIA%3K{tc+Fs`CM>4z0VultN4zaZ(OepO!%X^0n0ApR476Qm?Ak`T0() zYa$dnU*2hr^1hShY4Q=xB0bawUwN_UKVdyCSdji|7{IgG#dpnZbpBFg#`=?}jC zCKJ8Bn2R&@Ov(&33_OH&OTFS$>Jj%qdk0M+UAk~IEps1DZU0r;kXae7>D%{(H!}n& zqnWZ8wq^JD(to*#BZ|~|2Zy0#c*0Hb&3lszXijkNQX);sC+t*K;b}D6J&Fl1{!yjuvgdCV<@H>BTa7LwJuOe-}>ydn*;l*@UL8I-rF?y3|(*N>#I)G-OZbt)m2T0#5=dypycbhZxf%xNio1 zLY3*X|D+LM!Vn?L6gi&TH}Q)njk4MG12%@Ja6DpxU!K=Pjz`R*Rh?4E`iz`B{VVe~ zE_C1j-P>+S%6}a~-v z?{FB${>STli>2^;A5#KZ9SAR{D@8jC;E_hmvWweF3BfIP9JAFqF<-fc5BP>0q(mFXe|hF)~CIDj9^>7rlHnBp>gzrIdQDDbJ`!?@JYRs3eg(^WfRU&vpEzQShna z30)RUv*Ix)7&%Rkm7`WyF-g-sWkT<7-gaN=y-Nx)D|@Cz5`T#-@wSTXi5t4nc|r1e z$_tihdKb-XoIEUI`x6I9u#9S+>s;|LrqYy%Po`>XvU7k7_km@R#G7;JQDgDK&l01< zEYQ}uMjOs&v7vNy4wW3>G7eYU#xVhuo`>RZW#o%PzxNCnpnZ?O0QsW_rq7 z%c3K(Hzq!fWt~#`a%BAWybx8H&jcqb4bKHPoLmnzb$?OTX)MQDRQUl&u~ptK5e7+d z!aBvg(q*aKkr_ocscGln#&~-`340@>I8Lb|u!VpSx(_Sbgw{r8#-zKmr^m?+-Y@>8?&70cj3h(8cYHaeY?S1L%S2QNGWD^%m@v1k9 z?w?8@KGY@jRc&pfgx5Swt0NgmtDqPx@4?79&3x7TepGhfo@BH>RHS_jh6yGw9EI9Y zV#o>ts|u-FLoQ>_yg-@@I)IJ7(bir2; zBo~J2LN{@om&Onl6Hhx6YE-B8de-*n^UeP+>fSOau5H~KZW2O5uq3#JB)Ge4Ab4=6 zk>EiZck6@%NN@@6u8l+E?i#Fdx8Uy3dDlMo-o5uZ_uO0cRlW6AeLtvzMR%{&-E+-3 zo-xKVW{XjMbU(cA*3?&hB#NhK3)AsQ>(&>=BSa;@THyq6?VI%8iq65tptQdCNdXSY znD_RKQPoFbl}6k#=V3`X!Cwj4=D`NLguLm+iw0)61H_IU{h$oxC!+3JO3U{zp*UBp zGGnYHw5i==d{iHu$|_2*=RY}IspO;$oc{)WzSoO352DNdBLxYS!Ia=td*R6wq@?RC zdJia>49A-y$BBeC=-g}RnZfofA|ZQwbY`BpNd9Hg*`QtBbCAm0P zm*IeCsOZ}BIu^k8wbt-qh5z8Y@?jwB4Sxe^jCNyQ~yzma< zkmG}$dD%HjkVq{MR-LE&L{>-Wwo2hEq?cdFWKijL-$znpx08fBq(;R67}h6-5lmy? z9}Xzd`QKBPzRk_=vbdOC;SK<r{ z)ATKH!vFDNL9e;@!?!-l4=IHxRLf33HT})4Ds|C#E|YYq!m&tmH_Z4^pNBl(m%-K& zJI+qbEsm`ZND%(&wllWvC{uU3rZRjewG7XFa>0zyplvFP%(5ib$%6Fia>yk=kL-Dj z8lJ&z%dh&equVhrqYLEGXn2A*A-a39_8TNsZTB~wA zY9ADXhvuSg+A;{*yemeeR31>f^NXJG?LrL!=x_$01&Qm#_M?wIL23V~>cJNNWc1}s z)j9GrgXTM>wl!Exr+ct%%PRTbR`&1MefHxjgV8j3q;mRh3qi64A zfyKI*i3LZ10wY$WzOXkagwKjp;5R(cr4kaOLgy>#9snxr91rS2|Yrm`j7C%XUi zXxALya?(Mw!WX*f(jB5_>x`#?5o)|RXHYq2DvNm;p&(?F4#9XX)|$K}+NkF+eO5x} zEfcMrq~cyRBsV1;E~cQtnhAE|GWwdG0;7Cj|5+VRl+ETY8}|Ten0Cz>BiXV$+>@!I zN9D^@7p&hLQs0RKVJ0qJakOv!6s5ewqPLNLK=t1f`Z1JT+FaKB$(@Bxt;J@ABR&4 zf>A@l0#PTbgvq}v?yN}SsS^E9(BR)4S9?wRA>?JhXpBf=+RoH3I+O`5`s`gd1iO2o z;j_h@)ootrYrnaH2cngdG+oNtse0#3vZ7*?iCdkTgp0V~1-UnHI5XB6hD}DwP~+GK z5&P$IbRasrIO;GNmZ>|@XP&;IpQlFkHdA~GXv3foWTo_~|*UmzGD7N;Ae^{g-fA_@|@2xGl<7W5fdLK`U1y(V22?oxY`_p;?e$Wdv!~pLgXa#$A z?q+t&P11g-c$ZR3Ab95y~}5gXU)i(-&gbK1fe$)+g*ZWIZ&I5DeAV+6=1++VB>dopYx- zIj$y6Q9W2!;7OihZx7#CzJ9eQGsOh573;pk{j7YYq*wpEB&iT;yRZWV`q_M!9@XrM z8=az<*rFQq0MoEZU76Acmyg)(LCa_Na!6V3TYe$wLV5gRw%*E`M86vXmQ^K|d5PE% zf8`Jpo2Y5#Fd79fRl~2kH6`4SQjueb^Na=zV(3DGP)(%REES5Du zB0;A$S7~M|`|L}dPQ(Z16NfAC5P7@D2Om-*yvG_XTc_EhdW5mjNkrI=$#1~!mO=uo zB+Rzw&r9|Y54N9w&nA7>^O1?LKP7cgZ^%uwD6Rpu`DvfcL3tvQHg7qsyccZ^k&!VKH%39|ABw)FKa zN9DPa#1BlO6hRg9AA9n!-BBwTYQ!dcPB*NNrod`O;`seEN|5h~$ zFGBm5#R*jU5I{p(2G<7YrvI@X<+?L%bt(O4>4`wL0MhpMZ;)Q#Dffu`tF128|5TFy z#%}7W{>5RA)Ha1`DzsIESK1L%oppWWmFusojtnWS5ZSPE>U5@}ACtkLAP_a@~uxUs>q>6F}VV`ea`ijKf>})g&7tbxscG=~mam-7<`A*Zw-p~8t zL=6dUI?es@OA+U9ZFG_^V-AM8<E53{*!t}7+EN7|$*>ti z#=JdX`a0HbY*r2ny2S+W=lx@n4m4?G(H#9_PgX)Dq>1KD1TSJXzU5xR&+mOvB^P;x zJ%dgGa`w3dD#<&`we&>psZ_ILiUjky9Px%%OB>gW5qc+eA_knvlR9@QFlc*Uv=VY* zY_E7F3J+e>+!#jF{5=!3zdRm8PM!diou8ij^vDrV*l+G0|2*qw?Cl9y7?uWKdx0-UL{c8}TX5UDLbL28ua$jCMkm?dqB8EQ-8^_u4W&c3hoF?P>{T3Lzk z%_IO4CTVXo3q*ArC~mTWr>YVs<%8#ikE4i4-mw>M=tw`qD6#X@9kwzoTE#!gj`?Me72jTts3mqQ0JIZ=9gZoxv5_sRaC&GL! zd6F4TDHUZyn#lJlD*3;jB%gcq$zEO4-dJJc3Zv``&>=}CgmneMPiNoieamqP|$zg%8TxRerwoJs9?JS|ZbALOz)x z@L##oyxCG1&m*LO)J8p{^nd$c0(Eu}XW;V3UEKigXMKb4f{{XS!-6H@topa<=LYe? zY?QA*e_wEzBOW0OODLfD9_8Z;;TeD5QX4d@@@VMJSd<3+>Er3v+K8ip{tT5`(qz$T2fO=qNzqF zEyFEu{{0x^_9e~ctFNFz6ZfNe=gz=f{w}RiZ%NA%a*4g43t~(xA|tf3%WSbCy0Q_l zQr~(*q7!;>@gV2<>1CYsY6SJ@$jZ0JPQadx~!JJcewgWC^jf{`s6{ zQivNnizkDvHj18`RNH2Y2(wvEupDIn)`+ph(V?w}tWx`^!^$%!=ROynzs;%Je)OtB z-c_|&J(c?Vk+0;sNl>}TDu%vUqA+Wl=ZR!5AYQV+?^!>smCF>MbdUGi%+X-$fqd!-hQ*&%=MNl77uNhuwAZz5z zoI2MpL+z+S;aEHzug7;gr=<6=TQL>@K&{u{bXp6SdjQEMlp$)zhhS9|VBg(=Fm1os z;E)Hr59(enhbvo?bhOKwu+>6LH0tU-1}||3IOyv{R6;c-pKDo_Jb9WGfkVsh8?zdJ z&J1MTs3$2jkFS+QX>WvW^_!bKyY7!)m{|5}@+=@PJP0mSD6(AL@u9htpZAq1C3&+~ zi^_YDZU30B?bY#E*x}6tn5qSa+3QWoWN4YvC|fL_KluH{4mR`Mbe1O5b9HgbHl`V- zugT}j#_d;{Bgp6S`)KmP1;!JU3AQEral?^0!p%KFtJ4Mtb_O z{~%t=_0;rUd^|=Ck&PSqUd>p`vPn-X<&TimKz&xIFaLbLAvHH&&s(OfZ1nKZMW0r^ zEUN88lsvyGLCjjhh4h=f$cO@)@TSPB<8gt+-=N^L794HMDK~SSwTY69>KcMyM3r*B zn(HBSWYKrSkA&?`@0}bva(dC|DJ*9( zj4q;3y6rzU#WPMvDLv3Fj#SFCs*g?b!0(#ab+Z{I?CMN4jf{!n5l^a#jOm@_-%YU| zdO>f-#Z$i*&oBCIUT5*9ablxLirqoYx(RW zfv#_~`H2vL=66g8{iC1~u|5zc65mM3UaH9<*TCILv*MQN!RG3Y2eVMT5q0a2nBUX^DCN}bp zSjBhL3JMhSnE=N;=zsc2{U=08`j^_V>sgtQ{h*Pg)Ayihv+-rG??HKFv69S@(p~7E zAo4FeqV~(De-}330D%U;Vx^mP(S)LGNePA^I@sVl+Zc^?ttGf9{j4MVkgjb^w8O*d z&OylVroF0u$3`pJdGGesW%?sPeu=CExR^g|ZV8M{isxINdgh{p+g3(TQBRGoei=tB zYh}{@ld@4bZy8Idg_weCYL4sc+TIGCyemFBAcBNQX;GF4OcpZYe#rdijCPc8L`e^_ zKy(3L_D?MGiL(uegbLWhxjz2_*f0|_5gbgJ0JSqKSno$UF3Y{2F0Z6Kzxio-_EBs9!v++(9L%^M&BG{ZslKfv^OMPmjV$-WKeLkWZYY za4O!)G>;vuoi?5;ME$@Zf!H>{dHF$*EtnZBHm7+0EwtduRt9pmFJNspUP}FWqsij| z8jZ0@aC8x&p%}hOBCM_52dGoIf=u5Qj=Id-DPTRb)OJ~@*2cEPq_*QkAjnyCHNtNdMKQZfO!9^1hMJ}hJ0MP{eyBl0gQk8yU7ip;VJP5RM@GtNA{!5H z$dmwLhc~clw>C*(;%uB#Y6xp*nt>3*Z!}np@F&3sq7@&;n#>@`!u;3bVnAGa{l9T| z{}j>9BYJLqhPPt_{ezu&7*RiV{tEe~M#fZfikmNrKZ}13rN*DyyP*FWWyAxAQ^+~- zB*M9GYr>lkq5SYsK)P8RDhe6YJdw@b^KLlnAp%a9TZL@EYPd(-4jZb%Cz%>0U{R_iczT49)YY2w%D&mpI6UCeGuEfwQu3l9b)C#v0t=j-dR*z z^B8Od>A>?ScVbZTMU^Vr!QnkH?@|VkNR_h`BWUH_i_IrjCw*tfrE9p9LpSg-!Gou` zWDk-Q-7JC-HC2;b+umRgh~?&pi__M0&nDez|LnU@rfG33U!B4dwuhXZRmS6PwvjUO z($HOi^;ct=QV4&4R5;CDWLT`3L-lFjyiU;fgIh#)Iql&ybfLrzA>oznVi)R$z;+Xb z3f_J0oNskOqI-8>JWHY4VA?}c#%kGzu4`Ws4}WD9`E+DTKQc2bl%}b41E>RJ9eK*U zN=A9K+PB3%nk}Z|VOnZsG$J*QwawY0J554~$?PkI;%#P|0S^~z_t@A9Azx#rq`N9N z!-$qaULHkRs!Fo*{g0Wm+Lp6&(&+i_Z#G4-dyVTFC(o_F1LP@>b&tP}QNRjW=2vyG zLZR;MDB1O6bygw#;-+H6;(I6XHe9pp*RLp$WLbTXCD9fLqORRK>_8yB*yX8#cL=*X zyoScDc2;Qu0&fJSfe{gM-{UfX%f}Uh(|%)+mobn_^XY}odVMOv?Yr-|Z;B1nS_WdN zD)(DKAV=35ygvpH{e%k?G55ezdzni<9>^WnTi7Y5cyi?^gW%ie_7TTn(u<|KCN(t+ z<@s`ACgt&jP1d(@WRhJ1ae$xnywk-IiqAl$ZVd2l} zs+dm3i^s}s@h^%63c982?WM%{AC{Hab&8%m`^O}kZl?v^HEoe#`1h0qs>j{G5as{3 zm~-&tm%rKP?KGXZK52cOffkm!mOcUKR}Jl61Z~z8;1KQ7qP_R%1C+!beYAgKC1{aS zb)vh&e{{wCa{2emhN@-O^w1{DB%ev`2MW2G1xA7$jv>y^G(xR%*O1faKf|X^@IJYw zajCjD$Z4-j8F3{%ZH>H5VEl>OmAw77`7`#Yj za12%acI@O0(WB<;kJAKhjiV~AmK!uH=;ff{onyQ&!}il@0oS~=%Qt|7CT8J>WuEnWu>w=7Z~74B5* z0F6((iKaVIJ)F{ZD2w6(&77Obj_DSUVIVVaspiTAu0xz9jIBVG$eemGscZ?=vu@6m zvLZG#sc#lUyE-+^A`?ln0A%~|igQP&EN#g4Eo~%s%848bBolyryR|J z7av8YE=u2sR@t1~?SJtd+_F8W9pNhsPycw*=Xhet!*Us1vynK1p6t?*?A`Gh@$J_+ zvLzeGaQ9}%!QMSiz4|jvb@lk!5H&Y=+Kwf290(bLOXAW+F*1q{>gsWP=>utAl&)gb zox?<>j}{iw$fm6A_dT45YeO+H3y)Ey#SK||=Xt)`e9={NHxa9=h1b^pJex7EiOKWR zstQe{Cx&wtP%?Bi8%tB2DmEQ$1{P>1F-uF0AMC&HUTzaE6!6H7GPER`muIIfrA34V z-vEf8{oH2#u+gw|c2~C|%aYkF+ls(7O58Ylqz<>3e^z4Ui6!VzF?^TtiT3c6}w7+Dg5l>Z7m1=<0{@g(B(QQv( z5{In$4f=BP5YCc@2tS7x`~>Roum5V_{9pfW6>r6ez+;i6B_hfjS4aDbM*PVB?V+^T zjt3%j)LmZl7}HfiAveW^Ij2E)dYa7|FdWA6WgFuw#qX)}sC~-X^d_@#PwE)^MZ=F4 zG5bZDJX_a1mnK9wr6=jOBjCeIwmIq#tj1&!P^oyuQO%cJD$AT-7nKw8^K+d0!j($wLTKuAuT@ux0ZoDux-6Ob+s%Fhn>@>$spuPz?rEZLhiMK#v&pnZjsdR^p;cQpLPVl`AtYm^Hj zs3_C2s*f`b%L=xasMi!!chvLW65VMUa)H@BT%aD1AXOsapvsZj(0o<)I3Kle-L3U3 z6T_X^gdT!vpCu@x$^8_AooT4YQI_hGDzWCg{`3wEjV`CxWe`c5TKAaxmZ89?d0c!E zHH0glF+0H3?Pe}!R)?uxPA#UljEOR>u}{o=MnPn_Er4@jke209P7HDL@G|8&7%pR2 zMr&{16UN|GOWY5I)uqY~J|{K{k)%pO+Y*y~s$|d0OR-O(n`gbUK+ru*D$o3~eQ_4e zJctOQ@`9r^fFb?E3!*P!>1n#DX>U?1TFxt^QGD2DK z^E&2x^WSz92Q^0QWub(7VJn=$aZsxFL{AM6!AXrO7GEiVEJlESJrlfrEKooJYC7W^!8b* zr*Bk}k3M~H8d0orwuFLxb?=el3jpI^x_fqN5h+>3^b+@2F^S7FNTKi-p+HCrq^!2a zu-e0hR)h1+0nx`JLLvIRt5}b%E9-(Q`kd&Y@jcqwRIyI>iZE6VZ0M{BnZ?vV+*p(A zsba+h9!rLWopXkcSSqzQnrbmW`O_$ze7>AGrHWMkC~H0{*_9J&t?x2XBEC{30*VtX;3hAT2lj-@)_9Vk{z#b(M1~@-sCcmHpc(Ye z!w3@J4YugVaSB>(#LfAoHH((A%2>;6>#|LF&!`gr&@oP!Dj2$`4Eu4?*80$vUBB@U zT*N5k?(~ji1|b!i7pi>TOi-|u%JUmk+cUQ-^Q9NrFd}-I>FMYy#*{IL-J%J(!>^a1Q3|ET=Emxu(t%t9NnXz3O832| zG|F9Da~K>f%e_sGuBM;6Tsjmh^f_<&ZT7puW7h9~yld8q3$d9Af%Fh{GqmSRK22x% z{0X%D6wYjTzI4~a>U9IaNXp)-IsCGpcV?xc{z8Hd>qAAgEoql=xcjk&3w;znI0A`8 zo7S;YQ*!f>Cc4d&`iLFZ{8qBmN6w-%HKHb|<9h&(Hm_wd5A4^Eilb`Y=*C`Ebef{& z4lFIqIg|Uu@J$SaiPD!}vnba_>jvdPp0fOV>}4#3WW9cBMR9)X@Eeq+Tb=%kk>+0y zl;m~aE9ycYoU#1F=mu41iBnf5~ zujQg6T|z>Qz4H99y>(`SQ+9`{^wW;wEK>~-hE)oFwbxJ=T8iGO z?0?dOeDGAXlODNC)p5BdZe~s?mVIZn)fei3+n>&xTIBaq?qGQ}nai)ho_eHOp6Lt7 zni>xue)Nw|m8A+(@Z`fZZdd3lnm;*Z!su>iS40RAv+nC(a!-g}9%=d~UtHo!W8!u( zRj|DaB_lAW1%U*jtY-rK8$|>@>RKRCdXRW4E1{^)qg+dOsNr{v)3M&EKZRuM_cG5D zx~`rQDB)fwDR!4fTbq1|^$!$1s7T9txY+cjVAhhvHjO^EL#etZqGar-HDBhemz)pZ zu@TdNau?qxCp@dosJTc|tqJ)4O4Q0s{&XOy`c}J&p35SCr9WkGDAk8fRZ-mFRZD1B zQdreYyzo$cR|^lf+MjJ5BuoxDb0vF@$g8U*NIW}a(xRrS`N}8>p-PV!TQ^f*JH#0- zGBnItx9_lfw98))w@d6c1EEKLr%DHb(AR&WE;39WR>3%^M?VCtsWrq)SmRw!5BcpW z^0!KwT&v-B>+()B+uE{_P*m&W%*z;ykl74*!w}BE%^#41(-?B&>V!j(wM2b4hhX?4E#ryO>acuwYIDG-K zzyYW;TQR^ZU~BwV8;i%}AAgZ6g2j)yCqj#xOQAVS+Lq-^c`D;sA6KME@20^Vd`zEF zsGeVTtGoH_b_(nl&%TQFq0(C-3P}|GvAI3Djxs|!xcn{z<3$KI;+P2c00UXr|2wI=*~qF94`uYN+Q36)10Jy?6)NtzVnGY1u0MDq>lqXrMA>uvnqWWK3;C&pQ?;P__ zLE7MJ>iLI1CPuvu?(GrU6Ja`jnPovHV0WR@6u{W<-ImHv0&7fyH`b5)g_+Q>;_5IS zc6fxf?p6nh|H#+u@zse}HO=+4w+ibO;#1G%gR9_$TQp>2h49c5oayu@H_lV(FE$e@7&}P zot|cm&vYeofz9sVH7Avv19jfXwuV3GUOFtlP<+fdmXfh>6?&)QWm06g?N;L&`^!LH zSVZ1cCwZMl*Msvbu@Fvk>bWl~j-*}DwwCLdhy8Xe$BZ=E{DxlFmjhkUzSQ8^uiCdsMEr_&lqqK}{!?g0Mo zK#=5&kxnHi)tN?FgvhO@0qPY~{3h@HNq zWSF>;oq)EIC#G63_As4jBJ&M(J#Ngp6JFIfq@H^hC_kE|{;@aP`jR~|@_@;T0w=vW zS~JpaJ!D6~WQKvLgNj4Qm^T@7y<9!Sgz~HCB9|!ZE_BFlQyt<0-L<s3Bl7@*htq~BW~@IRn%+_aA;wuo#gvUabZ0SYi72LGk7{yvVw5t z=icq93ey*6`B707l_`Vjb?Jv6zkJriUn;2*uMVx$8*}Hi_~g8VdEX*xbjy096n%O3 zT~(=}A#{#?Voms$AwkpB-HX^RC6cR>HL)q@U_3;X0`}q!>36C|#2c2REcQo|_h%Bc zgC-Ma+o~h01sRijHtCHOO`KNcGkPAbBNS1vkK;%35uFjmPnH=?qBz04y1cXADtXo~ zeV5AS^xm%T4gUslbvq>=hqLBlJI&$8i28j+zVcBht@Y91#wCotpOdhw6l~aXb=VI( ziw(XxL`quPMc)nyQ+D2HHaIW|n4a{S=&z*CYDcLL^L8I(nCblny&xb9^B~Rw_L6== z`;VqNR#bO1)<+FFwWEvA38Tp_Zp7yn>c2#8y)Su}2QuB$OSL-u)6JtWmm#bZ1D>_J z`?7imO(-T=90xLV3D@q1Uj4tsUF)?JThIce%XyA>AZmP+BJ>;3ci1geF5-9P?e7f+ zwk-gtFTfyLI0aBa_oBNINb|biphwb`U8)o}PX7`5fc0M%QL6%6^*@?H(pv$G=;om& zX^#1V)RN^id5!ETMe@2yK80R5;uG3J(7-ucOyS&*ey~thH*T8oMUEq$59cjQQlalK#xESGqN&jk98fP zlfEbp(I=+Zv`LO|UkjoH3|jzZIC{)zH3dxJxDr~&+0QNExF6ePbKp(z8n@J8Gk^Ge zF>8f5zFr7?!NiY0-TgO6A*qYRHPQlWW6-USlX+HWWaA6zo1;YoghcJ#N=*p1uaP=y zGr33s0nE-Pf3C+Ye*ia0o>BI7FgjmM!jHk$-em|&26`XWOLkuzbVKlxC1G78Zry*)D>w8NibjnG*Q$*-!?|4BbZtMvRwq9>(fKZn; z3P0?_<@n4H#vg9K?io~}z4lG>mh?4IQj&d)3EjRYXNG*K!mYDtarS_G%jmjRy#lUvnW)(U^_H zxwM7*g?Z!PSzcs~(&5x0T1#omUAW|g3!?(f$iD8^W_1x$2isZjrrVP&5bgjQMW}8m z6F5b_lj8B2*F$WW@LBAv#`uzluaVCbopvDq{LZrm(`P8CN7f}rF*%zl(9&te%afV6 z-nrfK+t~>r5LBBs(}-9zY{R;?-u<8wFi)C1lHfOp-C5udujhlmRippw@Bgp~(@*?i z^(y_T^7E;HVpGoUfa9$2p4)e8-bkiM(|n)8X{^y&qu$>A2@)7Zurs~w*{$|D(d?Qk z^M#CG&9-;|b$N(?CnSJREeySP7;p6gVTbqj!GN7p(M~ydreBK~%kn{0L1e%*fz$!V zSIyMQJT9$8+<^9(p{CfZQ;&}_LF|?S4}8$%0HYuF*_8D5wG|Ki%-dX(&i=fRWS5-cUD;7n zyOolqo7I}~1k+jH!OV$td{&>-^a-I;Z5W7;nDPk;pm^)YU8m3=D~54TjEPKi@AqnS zau5aoSi~KgtMna7GT)!`=w{%%Gs@J{)?d_~AIN`e!3R$$W;UyT-Ctz%&Z;Yb$T9u% zZd-}b2Vgy}ig(_f@Tl%}p*z4TDt|ZrJ zD|bM(#3iW3umH7Vde4|K_Sj2Om?I50kPy!dW;458*OtB;PI-l6p12~*I8XoLICMMn zgE+LEVQbfr!T_7>AXuwNj7T_4*Sd!0pv@LRK8?21Z*6Xi(yOB(OC&7T)1+20wmg1E zgwPG@1LT!ZuMJAVgn5D={^6TUgM;>sr(I44WG_1MU&EDfe}hb!kC7wtkv#jE(}$;x zr<>Q{(=rheZijwox6H?&R+ zPgq5(N?auB&c0##?uC08{k#V~aO)lRlQ+1R!#dY3EOS% zUMO2pl{6ET<6O|PXA!H^YG`}3h7{L z<6R{6rGZv7Z!A!%B=&zlS)*j?=O?pB)&$xs3n&hLgXB)U4AFPXy%~SLOKh%ViWEs6 z`*>(=OTY$yPN0hVKpF3Whj(aW6sLkUqsZ>@qw-&gBj3-4&^8fs%DfQa*#-&xoUfOP z{Yh@*<&@9R&ezvqaaPvik?jw6AlnB-AI34>L)++-mVWMS)R!Aluj$gYI9JMOuJu|T^GIn0fS|9-gSd|ae(VI14bf<0 zD;<~~>fgAP3Xc!qkZc#~Ra}R(KI6L|Y*{h*nzHk^WU>DcTwK3KE z9sC+o0;0WMjH+ZG%S?x++@3OuwmNDrS(DtK?c*hOSiLAJ zS{n+&7gQ13Aq+Y=1i*N=Xg*S^JUhia$aND|+?>9U(K`a3SDbWA(kMN|%zbyeywc6UGE$on-a{w_<<_M;$1uiEkYW5p z#h|#%hU3`+qpq7wwZ3Ka>O07d)L;=AZC0+}vc`O={o2r~V8AWLy+^0Sn;Xbe%(7&c zMmOS8$sQAGv5M4}<$a>Hj{cH=Ieej6E{gM)kE);Usn6lvNKD)_bC#Ud0>_fnVZxKC zIOuNm&1=@qC*NlZe@#6UJwZ%Pg5bD~zA>_`~CF3O`irHs*m=y#k#G{7w+hPqZ$_BElnI@(KMo%#9TrFgD(Ar6|6 z_=j|lsomEtA~(L=lMFrU{1`So22rJ^D(YBgs_8JTRZezaHApdr5>Yst*rkhv8S_gM5>rgn82iN5sH05$xtQuBO9eneTJ9pqt>nm||;++h6R zPL>*(X6^JSHUna9ji>dMjpLgbF*~-XS8bGRALGx5;Fm=8O|^)|cZpw&RvP@@F>=b1 z@mKpNC`X9sccy;fA4an*rlz-pHeEyGfvzlv=LmK`ASnRIKjrFvyCQf6QJwMDDV9W) zBcR()X&ZRTA+JaB^8|0;ib+=ZWF9ddH zc~dsZW#l5<)twPuy`zZlJHjR||HJX2?TT3Yk$@wake8E(8Tn#(7W1IPcBGY?u~!Ry zR+vKP8&C-OZ;iuf~y`Y`iv~7=ENjEj%8r}(vSIc(JhQU`c67XFE zqOQ>&j^7(L>AWPFaCW3<*S+6QCx_Uj?X&SNOKFK@))UcygWWg71*yb#)5JNI^3EC1 z?|6KRMd9oxK_PkW7naJnG#1f=x>C^$y1`MXxC-Uj`=rYN;08 z4o3RtPnvp2;(z)dN>p59}z0gP|aQ3$U zmnYB7Ex4_|A2GT!ytm3yPy!rvSu^5uf4o2Wzb@;qYc1s+uYQ}yLxPnqF<)Ij5}SZ!p5TS;1)aW}SEE8KCKO)-hv8Fk-!h3ewxhWCcL*G^IV zX+MHKV5+Jw-{5TtyBuCI0>Z)PC8!m2oZ`+4=(Uo*$h&6;)PNQsW@1)}CT&gMdC5xa z#jJGR-28s6L&ZE{?Lrj@MD(_=kB^uZKcV2QgUgEhM%1plzMb+5B@=5q4=Qth3etzD zuWUkWuo~#6Ud3*B@wsAqEKVU|PGitNzplT1^rxDMM^;0H!uO-Kfx5v;w*tfMxajJt zm^yRG<{M3+Cft%fCC{>K$ipAI{gDQ}YSEr36~_#0yy(e~N=QjbS=6`Ym0T z74F3Vvuzb^X}<*PbPG0vxbEB6$IL|ObD-E#Y`HRTZhRJHEJL}u%SPL76V|9AtV)_m z{eEBY8}uG}e2A>3m`ytavd3NmxffcImWk^~wuWO&0h%T|2jK-+@dcvX3jCN;^AJ=fSPCP-SB{mtcR@%h*dfHFtb(UHD%jHrH5+f}D%25s;klM|#4)`$4_< zD@PY`{^8F?eDEZYq>F#jRs6xWZHuNkuQb{?xu`{W$aKiq=lKdy8RE-Br?UUZ!mS3V z&Hqf*F}{*OO2z$G55BeGUp@GAdkhVK#N;|Buky-eIauTNHGQ!VtaU{5aY$@jU}#+U z^-!c8Pl?FV5o<2d5@jG7*e=6#|Bo(vzyIb!=l-jg@jtX{Q=iZ`6FCk3DYPGy>myU@ zhD8OYiXpn!&U1pnaPd{n%eURKd=$ftjqSK;R7S_VW)NPUJUVfX9~W}JK@P8i3DI2L zJaCTL?-=ZWxeZ9w2K)g>z;`?$2ngyx{0!H|aeo}?-V?o(cQdbico6Kpr*yOfN+YX= zn@+z$5VI4{i93pG@|4O-83}eu@*&;A*p^+T+iKhTlZyq6%FLQ*zyRAYs0i-7c{EY) zpIf&w;m_?Q)q##ZS@-S!*L3(G?#~J9wFZYug=5L0j{@Ib73%S^zpuURV_gv4g1IOm za_YwS&Kaq{s8k2+yg)NaWZND8iSVunsapnmUC$`L=cz_zeGli*rAf(-vmNr_{x#ZV zZ9qIxjY7Q?=pvYe&VuI=j9V7u%SN<+7=n4)il30-j-y{4xL03OVDEf1!=pL8$2HB zc-Py1dp1lMk%#JicmFuOB)mjjZkWQQW%;FZ1=Azl)G_?2?7Fz+A91U8R?WoK2u+-t zIlZE}D5F?lo6PlaO4P@pF`p>&hp`{0=k~3DiB&gD%VWAGj`bAcBI2T$lSujZH}a;) zwrDC@xs|@@x|SQ|7G3!wH*dX)t;vcuI^!28$wDwISe;_YT=HEEUtU#q#35?xM*?kV zydnle?Yzq6irz%YKdiEiK~s7U7{BwihkOYyp^-E9(X>YzK!X81>NjYt*iv>yv!=ej z<>%K}UH>+w_b{QFx$mU$bKmhXo{1c_jqnR?gs*^MnzOH0-3YamWppu8IQaKSxG5jG zF%8~bUYEJAg-p_1r4)7eaEJDMVRPSD_+IKomCH;5}gBG+IZs4 z+5P9LVOp*Wt(o4_eGgG1W!=(u$`%wHR{EH2%p0PI8m$}XZM_js^0QGGAnp0&r`MYp zh9p;|YK=|R0O#|a`bRL{=9=2ujmkH*sE@WbT!e71kKYUY28HBRhpij9i+3-6e7Qmu zdmzjEE}bA!=CxdC2lG!;U)m|$S=NJ(1S+bc_%f`wzN{xUV>L%t3Ub1_JJYg7K0mP84z`B6upL`HyIA2Q(o&+6=+A9E!U|?O^X}2w zeg|IAZ@Moe&9(J~{i~c{bq}fd&95E4OpR4U>qM>TjdOKgl|Nd)32_u|n3ecQ=@UX| zD?yR){nZDuJv%ulIOPm*e&HAZd??iXr*7kW=m|hX*MN@&lI$>abPcE{o4$Sr+3Kt2t|l?UD!>9CxNd2Ly&rkvUuWfrqg1N?Pq8X|PH(*D~(+KEa0GVS83 zttlj}yfsT^A!LkP3SVb>?OU=x2TuHlPXb{Khj(vML0@#jdbB5uCR{uy24t#*)do|5 zwuY}v9QOSVVP8E*&x0E1d__0xZ&I;Ih8v(O!M{Os$ug59Z>wv^?iA3iOt@g zvZqbR+TzQaW38Z6zPz%!BjgWROCnihG{=P=%8A!yNrQwEdPlzA%$5DeU9XR>^Btzf zr$)kTE51hKO}ygA0ZGLR3dWZ_HM1dZylk-Vb(#rd#JZwvv{+xtQsc=v98|Yd^SaOW z>hFGo`n#lZNijjv`)xC`i-XWIWU&3F!f_7T$?}dz=>B=i3EiUEqaB%hr#y z%f76=Q|Ji2=wUSYhsyrahyQ>5E7vDh_SN)Jou=ONsuOnb830z)Ti!~;U8fDY44r~% zjx<8E3#izZIExDyg}VmfSTuuss$;Q`!l7EaSGHSI0&W6w3q#i2UBzJ+Q3)A*M*oMn zw+w5mUDriJp`}QnP@uS5ad$1ni#x%!NC@r_pv4^uv}kd6_ZD||cX#*h(QmFf_ndRD zwa>b)v(9yX@FQ;+$w)Gi_kNz|mhvk$^N3dZvhAttF#%BzySzOvzN0i~?w~QM3sv#a zV22s^a#;C?x%PhRFbuz!G@Q>|OAZ!Xy{Ja1LKrRIw>Zcr84#<+&{7<~rN{003GcGR zv!RyS3)3GX$f%z1yKcAD@3o_>IcG>v>O?*I{sd1u#*TpXgbNJsYCF%!I-l$`&3W;(*B%<-sG$#wD)8LQ+=a`g!tl z!3w_Z5beN_OCAn_VzYLM+Pd;8izUfa;DRy_U_$wUQKJ=7gB8UB$H4B>Ts`LeR6|le zHBGAUaz?T+C#QxzDeKqs?6|LWx~YcmoxgKEv=|bUciE}*uI^hHOc;9bB3rs~8@wep zGsZ|2z4cZDBKC&0T^^|4q*xg1vcOEe${C0+OIXQ=dT`O{ZIDglxS>Pq*S74+TCSlQ zlZKNq?P4JWi$bRm|LVt+Fure@u?_+jq$3sijt93} zRC|ed>XK1IqM>PmBd>Tfz|AOxfIpL`4kIP2kWVtK%zzEFLbx*JNzB&LJjO^_F&br= zkTA_;y({o#yQI^gS?uOqUFH>d&uW4I;eIZpI^F+lb`fN&F8oMyN)WyA;ag2)Y?eldF8sn<``L%6qATduezFKh3y? zSBE3$>|CA5=DS%A=MFnku#_8RN%i6S;1Qa<8yfeqV!Q4R&%GgD2iJ{VFU=2f)|UsY zu*68E#9j5Mnt~*(;}DTuhp{}&or^eS&Fv?*g0UY%W*6tADPNv84^!9m(S?eVY@zHi+^*Vz4AlJvv@GUZl`E9Y`7c9Mg#l*S%<*N}riI z->BDiMR!#{EEv0>&B50GPWp8w2v7dyuMK;lj6&`}i1tw5^Z^4|nTeH&ZhIdsOC3dO zvd8B^CuBS1v@5Gb1w7~pTGAS{%oyP61LBhNmhCh;$?KZ)T5osM^=jhTS}SKjqRS}? zb`a7>uu##Q(IygFB_EINuQ|(2}y7} zAH$78wp`oA0K4pEt5+)y;j>)|#WwqMSGk6z77g;jIokR<`eFi|CC7=g6q;cMXXR4T zLIwwXN_J}&443ru?+ywybq5FpSG|P7j z87)|4;9rg$w*ss7wW77ccax#Lufo=k>>^U`&Og?d1(3|9Z$9-`10mY5{9L@N{Y3r zVb3*Np@$sMx%bqMJm>uUzlk5==zJd%?)8;fn=J9~R?hK&TqKvC;!vp=sy0-UjTn1{ ziR+@CfAwW4Dfqi9Xf+h`eUg#xj~Khut!%*BJF6_?U*)2pf4cq5cqwp2 zI^o=q;(x1T>;bjcrb_Yru69mfLLWxbU~B76h#x4=mX8D|A0MR?w{q!V1Bv$+yik-+ zZetryqvINb=Mh4qFJFZhKCUJ^6&+*kB*3di-t)`F_MJ(155v)?3_gyAU6g*vqNJrv zhU=xNhRSE=hPWm*yX%XE!=M-90%h*S{}gmVjo9U)BeL1j251FTd}I*6uYOX z(QnzSh`@9Ay-j<6vdQ^e!5&{%k^}1Nc}uQXnd$g>;|M1+;a0Jqh-1|>si&9k7!OVT zC?l|9*JG4H3QV>s+|#L1NVo5ipUl%ycVBVi8F>bmesQ%=QPe>C0WQ?v)Aj5bAU zaXHG=tcGH2Os7Hfl>U1!(6y%~A0#teJwG@d8Y_$=%$~K(J4W4p>vBG#;OW`j*QVX4 zv^*_yG(fIM_7fCGxx0-x=D(ewvTahI(5LSXdq$@F_r2qXT|zOv#AHmxy`YVrjgpREGV&Zmq6ZNk*>RY5-J zn>}yZrg7_>y4FPcP=fD=TnqDEjO%i_?ucQV;LXESTYGw-i2VZJ5&LOmS0#mx--8JG zTDm5V$;3H%pu9k8&lv6n#m2LlVT9>yaVMz2xH#%*FI6MLcZ^@G<#0ZRGb^7z&wN%M zee}k82vN3JSapIv(_K<;=1Ma}Wr=z(P*W+8P6+o@{Kp0pUcl~iCUw#p%JA!* z#KFPTBvjzynAZh&dr=g0zY7bLWCV>2g~n(|Zc`x%j;^q?*fZ@};`Zmw8OnO0*h(o^iELiQXn0sG(y)WgkFa`;r1 z+*n`TYOHv`8ej&T)A$<{tDpCu8MFQSn#zmg%BN$3tB1x0bF90+$)N#mF&YWd-q3Y) zf9~#_Zff3WyOVK_PF0!p!Z61G9tGS6f`oIrfS>02<{oD_9YjoVWV`m$D98P}9j%cl zok6?+Gm!)NWjAQ*%UkDZHU*;U4i&+sRGof;09GM*hyfoV3y)yXWnNdVK^LfYs$-#N zR5Uo@x}<)gaCksss)sN{_agzrjN{R=2f@-lU zA!bg}?u|}c$l3c6l#CkZm}U`vFk%aOwo3CUad1vWNoLXRRoJ;3GEKt=Mkcr!Ht#E3 zLZ=P)u>(LBrsxHJYAwWtZ`bZf{1str)S%iB=3W$5(fF}~uJq{r0jTtwZ&TaPb^6L? z3&|`?^|X`NVN=Gs`iY$LqR>i+1kPwjjO9DpnXtTj|drVtiKU1A+Z~Am4%ffU{S`+In$T#x~EoA;=v++~GpD-nMIZ`d4QUrCi}17hTHER|mMI@??js zNz0FuO3?k3$~~&3lN3wbsao`qoU%4)9^(WP+-rU-ik$=O$iJXQX-R{8L?0|1i=i^p z5bbTTiGxd8j4O^B7bLbq1EQ>a3Let+rKCoiHEoG*dXfN7@$4OkISZ0mMhCX`EuFxa zIj!KhjXD+b%sBnzpdN&hEdfIO;zCzMrKty@odnoP0qCpgt2ckk#Ae7~v3 z(Chj>N#QI{r`=YDm7Or9TL>ixPCjra;AnsQp5yhar5B*GpaSBNXCmD{7>2y)8!|#% z3<0Mc*GarD=zr0EF?ZuzkjIM2Myq%(_qnTLbj2A}**WYpdp;y_$EazVTn_V;ibp@L3|A~!HL_6|?qW}4<}Z(Mcg!@0?ThS~+ywr*@}@eKh;=KRvA7FJ zGltqnLOot4ut^!s^%Z5=V$`pkUlw5AFkLpuOpnS!h-$9}T>3%=@QlE3pjEHxUNuJX z8Mn9=?~~xTx~K%~LAdqDj@Bv_*ftN3jiU|pyv<1;GC%iTaGFa`bELR09&rdN_bdAo z826gn#?sZW`>95uy6j;v)Y=7*Js(oVmADrKcCI;AA9`x=4 zXfy*cZ*mfS1WEpGo&#UH`+m9zO(;1B6%@tmRbM7O-IJ`UK_Q3MSDvv#K=4Js z2y5icE64LpGc*^D*ZWRB$Wp%P^T*ByY7{LS4AX>1Op=B#8yA9zmTQQ?#{xao zR;`%f?8cbtzl-?zD+C?<| z9cMu&X@e$Bxbf|P%uBis996lW8*smflf+4;S0CBjDY_-Yn`Bu|j#El38jKb!)UVCF zB=-0}w0!>-{ASCyedYNrMy6pa?}l;NNkk)4`WnQnZC~qYJaKWhX09K~SlobzOJ|BD z6$4`FCj+b}w~6Agj!Tzsfbv6DBRApl9B8mdq5fUlRiN-6mNHmyspt=?Z;hW)41h$> z&Ae)dr@*(5Uh}Y>o85*Gk%mmZWqt6_$PdTrT1>z6Gz;NIYr^<~y!h#aXs}$-9>YHQ zN7B?qax}GCW@;)yl^=rPAcLE8)u*1*?SLb+#;hH;$`<{qz1{|jbMV6txAKQ>LeIrW zY<;Ea%g)JaFNtAYXqm-aOB&==vhDj(1+0B&t3wo)6sr0I**` zF7?}Do!pzAl5AF@m-jD^g$7rB%1+9+`(n+Od9P_Ddmy>qpaR*o`I#y&c?f-HCU|@; zU^IK`<7?p=d}-&w0jWG^$@4=487EJ_=k9UX^a}fc=u4OddUqd*1;f=S;m%43<(Nt!yWtzBKWS0$_9OTRstk?E`9r6Er&X*ItF)wOkrc6!==f z>rcaDt@deitQ?|E%S-QEZbM5b=p&gE*Q-j2tTc$RVxE>eQ3{q}ZTwCiZqL9XFOt|K za;V!%RLf~LJp+ExfpAOBC`dy(BHL<|TnTT~OzZBE%DIFLP0u|m{MnO@ozZgy3*3bP z6nU$eSM3C21{@JTDj-R|MXfa{Z#z9JOTW;XO(0t&_EB3oIH#8t0 z16WbtVQv)ADy7yvOH)1cLe2EB1a$V~e*Yap?Z1&}(J*^TzNE6$j1;d{$IGeHd(dWt z(NR`t&-*xsp+4)3EaQZ#k8(URYn~`pSNogRwA|AvY(}#8f%zj7Ty)Hn-OqJBqr~aE z&N?DSxo&2^Vut&%0hc)51$CMnKX~(o9`9&Uz%Vl#lBTtQMj*uxv48Yq6gwaQTpIgpp~%Y7NeutQsvlaVH~Rtef`S= z!Qd#m_=8fUfXms#kJ01%`o3-InhTn;llhyePd`G&y1H&Y8vC(?gw!aq8=xUN=*D3= z)+XG-qT*s(FB@U`L$el9^RC2OjApBlmRW?#J#PNCFBYN}1P&&kdQx*AEN5)r)nX5? z4fV2{+LDfOgtqT&&Mi?8oxLjoH1*DHe_*>{Cmu z>6I++lF6sBT_G3e4^)xgB%YmM**kRVzh*qj&z{$^41Pz9Gr^GVmi-YWDWD^ePgONM|@D~HFHmRPIu6c}PuHmn#-Pj#BB-$g47X;|& z3ya$ArCqFUxgUS(a*o_)eNDejVoW$^^+P*YYXsCR0E1g4pVOn{53%(OEilyLPCno1 zB=Fu`F=S|JX}IkzS53y8bG&R^4C#DUAMHmsV`P-G?o{66hj&?f!TGvYi394+mAbR@ z^HkMe57`bP?J)T(s5NiD7(?MCX#|{9)#@z)!TN8|7O&N#J1lyO4>Hu6?Ml;ypPiFw zN>p6jRm#}(zB6pJuTn+~57i&n#GF`veSayls;1_Qx1U31z)QLqKi}!83f8CuX=Zq} zxIEa}`VjOfBg9Bx>fZ&|Y=~bhwS8iE@mdz`Vk+Q%gBZaxQyrLK1Me;9{hjbl;%+|G zFtbW(vVLV`y5YNti}>j$SD@_#3k1Fq^5+oP_Lt@B8`vpl8Xt39w36~|P3w6Z^!@=j zQea;Hc9r|_iR3{}$dRxpB&5|8YUS3t@tte^NgEz0jelBBU#XQAEnfq?cx2uY`%3(O z+VCa+|GSIppRC{%-t4-k49_|-KHKh_sCwMu(Rn)BBp}FymW+N*ZAoUCij=PnQH>T@ z?D-X-X-sia$eEmI+Ns%dvJ~x*Wl`};=CTx8lFj{=ouskJhovRtnU7EkXvK9Z4SHW8 zRq9!aT0v4@;@(IwF38=MNlg0>MATn;nfW-kA;3x+*>M0CKHVib=s}*Z_u-+ zxZ*EQ=dfkrM|Z!yK9uGb;~uVU0+Hg6L)MdSg_(SUIl@zex5&j@(Ewr+G<)y|IdGAj zaqa3~&M7>;p>o+>s{0KpYlp0Pk*&GmCIymk32%R?o}qCcgQ0o}tDB>T04dmi9QVz9 z{~|ls(sXK9mt?!5MlXmHP4txad}}KT10guBxV)&gesD1)LxEw{6puS|r$0zioIYzv zMQaF2V;n!Q>m~|xu-yWZG}0$V)ee~tnb$D2bUOKn!wCWkvHP6=IGz1xSVM&5CT$V@ z&IuUezK_q}=dxu7FTGxKtgli05C%u=eyM2deY(d#aV>0FJC&14k91@dzeM>8MS`Vo z3=?fj{}{Q{^?EuVl|E~+^C=d-vghPbO-n79Cn`0>9U0Vh+EVFayyk`0#t2p)hcFc% zWqsY{vu%o-MI~cv`IyB#G)pFFo!Dr%-pEg+2jSBdR{hR!^rNC-0zoOrD8^I_51P!1 z(DUO^rRox7kTka)0IT7YC6ZXynBXXEq}>eRwf@3bZ$hid63*+49ZDgVVf)B>K^;-9pwhHF9AJ zM=eY`;1`57h%Df}K^za~vzxOyesKH*hnI#zgFm_JL2d+f{EEyy#q4HJKQMh~!t+Ip z|GAYzj8X+)=D14zWv4r}DTOw*qN~8FU}b739FD*RpQbHb$*eoZ$WZ zDN5PfRI0><5BKY{6`Z1hw-u`K!XCCi^YviUup7|f_}$!c@xw!y+D!sZl+%1Grlg$} zAzw0=bG*hYC~9;iSdvVPf+w`(YQd!2KwhMH@NKsGiL>onm?8y7 zaDc%!jpN5w>J|H!lqNy2RekMS2Pvl%%{@$gs+)I4Uqtp zDP?WZrdy@DrLO$5a!qx}7OhHO)f+Lik&URq21#K@UY)Q*+>)jG+Xn(eJK`TP!;Y{j zX2w!#$bQrb@Y$SQ2+3^o3ZzQn?$D0)1DT58AVBgi0_-)Q|JENc;{3}2xcjNt+b_b$ zeonsD%lK_b_UWrVJ*HTfGhD`|GKzZ+WoxzP!JEU%9kCbBcuPFR4ZT)5n8}fPhq-o z6dWnUy3+F}8Xu8LyW$?Z@>qaZGi2w}zmeJa8W8~pvtgTtkkGE5GZK|6w?JEe z&dNO^ma~ZY846{sDP5=Znr0f}hMojZHh>v?1dm#a-#)x~Rh?pD3B;F(6lZBSX@hqQ zvCO#CRaK}D8?SF8)0%5PbuFB0aAX!+ns=z<2edLaO}U3iVlVnvDc#y7xth%3h({SS z%`(=VPuM=6IPogjx5^WIya?T99G_#)jivf2;%D^i#bOouSC)@H&fAGqPsBB@oOM$k zK|@uYxsC?-Y=)Zl$#!Qy1h$hOY43%AK^60)aO^FTr}iNrZ+(it&17yLEUxu~G7~7( zPcj{S7`GU7Af$cLLytl02)F=>hORJCx)G~i8QbBWRj%ER z8p>~x$DD3-M0s}D!TYI4?PV8NFQebgn#puE)s1)|Al%YAK4gSy6O@%FJkG}UTVTD) z5W#j~dO<*%xABVSf68>2S+g4Wc&8c@aK6TR=mR!l6h5(??&Gd58bD7S+6k}yfzN*4 z@{p*pNM(>m+JKr8qXsMgzA*ttlWlpE&~+EP(}3E55-OV%n&ifb?K(MtLGUF&D#9Kf zkFdlGwp!T`F@|g!0)9RQ+Cji?y!o6)8HnoUExM}ydGtB+93lFW=OEgll}2n3@_~nJ`y6@ zsVv<4tXc1YmAHAKHTITSz>4M=^*sZ&8R&C_>o)f84m)P#l@*33g+a^fij$SZ?E`0h z^Rs39+rZvvU3=&Cn9l-e>|=>H)km!>elwk?U4Pqvy8f{NecQ#iZTb#uK=yxaKnwmv z^}FK3!DgZQ73Gx^%!EwUL@C>ItHGjTM&l42TGBV=5w>DBgiOz!-r|clcQu<9Huf+v ztR}vkz$h!qM!{rFemb-pc9^Q%Jn>Frs+f!Iw>5=`Iz3BDfPSk1g6!Z49BK`R*psij zvHnBSe#4gbrG?^?H~Rz=BZoP|NcUDDUOJ3RaAvWF7caK9pFGoH{Bwlg{^KWrBwyLY zznXRjj-$`3zO^xb+%6?zt#?15xlVclqy_t{oCKT1qS0a3a$k;U>PfRp zc%VE4e$S&!7DLmFSTfrcrv)BhOP63ev(49NUn~ znJfEmD3LG8%e*-UnHZr7b}A+sJxH(!%DLO*IEL%>6mO;B{OErw!BcX1vsW|&Ph|hf zb}qu#9Es7;jr!Yy(bByG8QzB925YxKK&Kbl8}={c>B{_{Jcqbx^ObEJHyfJ+Zr&lg zZjD?pBg{9Syr7?=AMzy2*b82hg}m1^wBlKh6B1`&>x;BLzZ@W?ut9?W$=5w}V^DFJ+1NmH|m2xN&APo~I~`zS@`;w>$=Rs;8?aKn zYxEpf_;*p-nZ7hJKMC(I(~N7vs6x%_jF?-7&NW=|304d>31`|3jo+MKjq=qaP}udX zr%w78xXN6?aF*mA18k1WnyM2NrW0Lz$5+CQ(Q&kzM(ksV^0M^@Z-e>`beSKm9%0{> zrUl7E&N*+~&F|kekET0t2bYvWdrbyvau0>{&H*`(dn=8wmoH&8Q``!FIQhPGa~Y5% za5b*oIPh!Q-r|4;L$Z+<$h#@Wy$4)bUPL7R27zH|E12r;Fz|0s!dj&0|3xG2a2FT} zaa@#D4)CH-wPK|E5OJ>@PX5VYA>@{h@?6H>srRMG#s$K3s@Tb~TEjS}`Gf#d(e;bA z%>$E&Ulj3c^Z{-UUqewo6R;J^%+GM)73O*|gE3vxWXet!rl#h$<7=iB7#rs2Bp~F$ zpXqw^>8pLzl#xI-prdE=!%qZHFDFaQ+*x?>2t$y5Qa6p=|C$c$n5J?RuGSHp%-o$j zjVE>7q0nsajA>Kbq~uqUsZBb^i0>%-lz5;$=^s3rbI+I?R8q}7fqHT)hgHa{TiEKo zVx~r#wxmk^oIy>rSGKOERn4LT{0_!0{0nW}%861F5{>cirIgXx zASi96{fW~Gh?exHtWM$YhgIs-VipgMieCjs%y9-QtvP>n+iUzBLr$eB{4suzU%&r} z(0KgJmZX|l2*eW&F&X!!1t>6MoL z-E8YvchRVx(n;=zXvl+L0r(RnM{S!psa~n-^e4RM?f!VN6zD4^RRC#Kxly$bokk({fGD-PrJ_7C2-bk%<>3(@LWNoVc-VvBNRJmMP zV6__9AtrIyv(xcKzY{@{Sp660X_G40v-v%RTPMn)6YhYl_7+fPTWWUy~G*2yu_X1qpeZGS-8-MrDdIb|vkVOP3) zByD#}-qtSJ+C1r)qTD9?+)tWeQ%YMS!hDu6v_j&2c7@QD#CZ3|J*y|?u?IoJT;0X* z=8?(`0aG*JA4Y@kZox4uKkOCGd9XkKPa31^CU7?W2E7t4ZSpUI0tLniy38Ns&M6GE zb=8R?LlRV))yl@4-d$`Ng%%WaG0sHrJn!(gXThZ&pCEJqgAwBI(Iq|-deO(9luuni zgu2@k8W0AF!i;8}q;dlf#y*7ldo_0W2Eo&Bu5h_^4@xfs*33_hi0=uQgA=``;+WDM zvi9O%!_0aMz>n#M)JHFWG8xZOylSUEYZ*UB_q6^bL>&pPud7awZyq~lT#qoTX+Epv zP)MnG7rrP(rRmf|XOD>8wY!X7jRFmLBkCczc~s{q%#;SPu%jen#9P1349m#d^m{cl z;H`A-G;Fv!{OT1}uZt7RE#LAjh9p+P+W^77AhekYiJ){*GeI_4!q_gxY?nV4GCsU+ zFfi;F+4uvPDPM4J=Egxi9!1*x^CADC8g&dcZJ*CzW4tn)snVXf)zJKRY2~a^(o5|2 zQs1N4He&i`^y3A4k}5b?+saXG`|Lf&!qfh zx;vg|{(B9|H3*_WQ0|3t%9dcQ$?>daII`887&G zUhT>JI{dE%rN2OGu975!2Vza(!|*Y|KcQCnj0nvubcn`n+7kC)4=ni?3{DXzEI%Ng zD?Jx(g8sD-$@u5F`9gS&X9WMkw99`j5NrQIwoX{~-DMt@tpiV|Eq^TtR6VUdsqWEk zMjBjA!oEMQd;YcH_UA0~CzSe$fBo}$7kalpO5Ler+su$GL}t5bg-A;*!O}02d3mKL zw_N5gIh!1P4QqZru|E_JL2Zf;IUA*!aw8D9&Ou{5it;;ky`|!({l@|GkLM4C;l&k? zwmawNv$X5;UI`lpltE-MADllcq+XOq>vSP_YcRa*f{Sum=N)$Uq^H`rvXiy5CI3_+ z^^X3X6DFwyC1A9K=JmL5A9A!QU=FT$D!xtbsI84OH>Z%ruZp)5fKs(fHYlUn7UT{* zkt8fHRddSvLa4r0$Zo!;Ay;Sg2X);ncyUAam$9=fxijOk>lQV8i}_FeBDsCE$t zoF&2My#hWR%*5@!yZYiZ?kACf;9M}NfXLry0>B@sm=Bweqqm4J(`+#@^{482%C#&f>N7F|(s{J7HH()#{ zBvmck^E>6x&mD&|xL(}eT$e|;ke;2q5_H;K-2r46jV~ zxK5TVA#W_W-bP~4cFAVI!F?}7>{(tEPBAOA;KJW*u09IRo*URiWfQCZ#%lByl#!a5 zw;O$94RqK4OACF_R7TT%cZ2>_Ys3RL^wB?S|664Xv|{hf`itk(ZxD-+Y8uP%wMVKY zxD;z2$KC&?B2uomQRBX_>kJ{P1b9>M5v+29@vN`@f`eE2A z!>PcNbPeD8$6Ea~=~_&1pJ(3My@ZJoKXE%sa_BPsThezdzd?m`Qi#Wi0>FSRZL78Lvm8H67uNf@6!>FQPdM*pyc56W zyW6Yc4jek_ahsx2p)Mnf;_ZeRp%3+D$RaB7v@-F^p~=D3UIenSPj42%s(v$8Tn_IU zop=n-wj=D!5#!0dbsfk+q{b=pZoR$5Ko7pSb-+S*mbhBnR)d&nI-{i}4pyl=Ez?w0 zQC}HD!@eNUkHHXw2*>;FxpH`;;f8rAt7{jqF=oc_t9i7(*4?#f)WpDgZ(sD{xH%}6 zCYQ!H+IOe5l==JvVC-25OP^EHduLc=S@u92D%a>GWJQ0BtlRqxOmSQ0ru4kO-iVOs zVO7K8=WWBZR_;w{hf69Og#P20x-N~pE924TJn?D^wgdG!Uxjaz;RohMi`xKi?V4hk zZXlH@Ouub;%jFUar{=1>Li-mX?a>%pm#-K*VI`ppWsHKo)!>6@@gA2q!_?(6szS~% z)M~ZSW6JHbOf5!M0%JKc3%u>{aLfzDzS;G$^sjPI!XE~F0idg%LAfem#QOCb-HKL{64KYV>KKYPN5kiTam-z!^`&?EW>m|@T|1aa3{@nMj9QZu-f8?sD{Go>t zft;{^?Z(gqWS)K>kKT-Pk{X+({=Q*h7BjU#YHl=OfAB)yR?uHI&((WcYSQyH1zS_i z^&ygT+*LhSEyIxtze}Y_e3!iYxXjh9H{H7B^z9QORNSu2D^e8Tt_PQHSbPwZs%}V0 z)%bc!HOjLf{{j)2hsfV-uZ6gJ!jl*6yH_@N2}odwu*zl!t#wJWws>{Non4dX>n9&7 zvi70?EzH-JL(5asj|v|$nnsI@6FSiIU&mOL-9!-J9uYjcL~l~>R8E_J)qCH}9^Yjp zCIe97y2B2gLV2K$J)BgjsuPHFqMga8T470{7`?r_lCxW9tsB2V)Kt#5u;RIg(Zx}n zgaA)^sNo8K5&;3&i%wSyII6~9jnpj=M0bd2bg0Lg(roXb)q+9OejRh;JSU8%)oJcd zQ6JN{eBif30A;a`^zgngbTN%kG>`C|8!X));MM>Prkaj-N_obs`02fjJMaO^)431& zmQ}Thg6~X84C|jsJNHsp4}a_MoDDh&?O$0z!P0;BAZ>+eMrH-cZyPzSz(lQ&5Wp0u zzAqg2$3ym3V%(XP){_x(790dIhHi-?sX`|c*l@37N80UVy3B-b7B+cyKXqQa`2+(j zotA-jyXO+{*U2&lnkat_RnRZtAD4Ia_$?gPC{Cd5(F)nS7CCN-25;ZxON~SBKk_Sl zH9(2&l6Vr7<18xPYJDv$o7yk#b{*;1dI%%Bv01)Hk)CEX_gpre+?aiNTl{3;nJ;9R zc62Q;DccXURKB!~O>*4xiyE&<8FyxZKc=11JKshU1T9t(qQ|KkhsavB?t{^mW6g8a zWdG`NZVHjOW_EbL3%nOoAB&lmZLEDWCliW0ANy2FFAz?Hc#IYLTwWs?t>ka*(0G+21UVM=)aPX7^g(si%F^IhbsXk_!{tpV&Tpa1LM z!g%+Qv}To((cqPJUzxP$3cbB1sV92- zK+^);`6J;;Bog>0W(o11lI`aKcG@q2l$^xvyv#X;M)dsE*6juF4G-a;`WTjp-JPLQ zP6VZVoVDNEZY}HhSyMrmoR^j^rN9H23*R!}EMM*lKYi9WpmBF1uw=Y?)N(XL_8j%A zXjS+CfQzE=f!5cb0KsU3RK@v2ijo2I8izr}DNmZmQoG{*t7V#d z4Jmvxf#M}~)LfWS+GR7(eY4woW=16Qe%VCgJdn%c9_e$$WH|9WHQj=+ww86MQb&uw zxm?yMkd^IYSmfCTkAO*-OR=0wn|dl)^%$d*7|~`;ntf$2_67<|Lx=n~1J@yaXInQS zK|W;KrqV(%!Rt0xc;z-Y(IJ@r>qx zK@HW0kiC7%rYI3Z1%o`TAlysi1@Sns#hzg^Z;l~OF(=E91JNT-*5=@!0pB;u=9**XOyRGVk|Fm}}-l}{MEz$?? z;Uua@OqDI^bTYOt>U9mjs$xA{=v4b!PBj5n?;e}VVmaqJu24M!VXBtX8&->1&Bho^ z2g};W(s47DcW<#Ea|Q5{Nq4znF|AJHFH zarrIk?53Zj1u`BoK@3JX>WYuLn8;*l+di_VrHHgU40Dv(s$K2r|=yse(V2jI63vbaLUbPcNwGcDGYol&R#CI!|+=8!yXhIsbJ z^843ykzdL1+ZxPzlZN;s<;@3_+W8~7J=2GE! zQ(ha5VWLjgNA#8cwd%G7&&mY_X@It?M*9?seGMPZck5a^H*RtQo{^8=y1IYfCJ-8& zD%1htLoNm2Jq>NHG{MKRXDIoMO4&hZA{rF*VaW!QFHWZeW4iY4WP3Bqs~x48iHA&m zLwUlmzUK74SbL!w#h1#PQybaD7flG$W^>vp!t*kDx?_CqCQXGM|b(lE? zz$2c%T;SwX`7oAQ>-y$nrKaA3c9YTKvnmRnurT}24xY`tLe);HfMtt*)*P7w3!cT7)#DUO{o;zr_gvI8lEw&Hl2-r`>sO!BL3E zgyUQjCPnl1`B%s?shn>TiL3ulydf6B7c}upNE^Xh0ldVB=j7&!A0d8?2_vgPJqJ?9 zIxYTdR=`h!7a-G@Z7CZ!(gIXv5~FQl+_z;lCbnA7o=H(0hvglAcUWh1pC3qc8fTnV z2$))Xn)=|t5NbyTr&R0XuWC%m;*4PU9Q3Elvjvy}s)g@5I6w%h{8%Y`1MCQ(;*|EP ztTYzuvE9^#mP@!JPPY`Xx}zM6a%<0xt@@?5Xwel>;6qA<(hKx0=lml8BZT)uw4=H8 z!PzMM4>NQ{^(e$>Y)I#Cqa)mAJhj#YC5Ct$mk%mEP&HgI7o-sa2(kj8j0l#LeQwDq zoyoLBB&1^vKtQOJGi-Xr8Dl3=RXfI#)gs=)i;#SgNqrF^^!1K!c~r|Ho%#4dR>U4J zBdKH4@SIu(flkThmY?NYWcMlBlp;)3dRhtJ0{o2W87uQMOS1X)YOHZ>#+!V^_SP9|o1iQxYF zUB&K|N>M0hGA2U>Lj_{6{Iw3mxSJB9L!9~PqJ)cta1YZJ+@bw7zUEZH)aWigIg3>b z62cptY|cx~o{aH}h)&Ra?fGS3+tf58BjYj{`P3^$Zb^IiwK0>eLluKfd#VWGdE$%M zQHqv~jDPi}mn-DQOquNZD|owvqaQA}+lZmqKN&302z%#QH6yCS#KIy%G2*KdfCMsI zq1$*;8~UUj8RXOhar$xRR1@v&r&*-EBvE(v&6IGkiPngvQ=l@kvF>qCZfu7m2#BT|HFo zm9-x;vnU6(f;uPQa2+H2C%B%?;!BeGh9w_uu&lTMUzb9lVBpTZ+~F9Fion*#I*jt3cTW$){nk zWX#^n6=x-SU%UDMELOO;yelDxdJ3GzQ7i^MFAZ4GTliI%4LJeTMR5QyQu%o^zUC5q z>BYU45CkbIdB{_~yej<~h_`VjnO|byy5C`(llgb>C%d-&5Vwp8o8E_!=|G_BS(DOQ zm*zwQoJgX)qTDt;JFTmNr!i1 z?ml`H*5RmGCI1z1mN&u>-azrJ3bLo5&J zYr{(c?uYxxh5rshkF*dv5c)6P=<9isOMQROU-}A~HRKQU2^jCB=_@NyBvPm!la*Ud zjnS{ZM74gocmO7Kf2$INrdvF{?3b|1hJiKoN1V%T%p0hv!gH={o7&n06br&)JFC2T zK5=>$)R=kW!EmgU#$M8tx>bL95*g{l>8b1px{xDI^gtEad~i-UO)POHCC2VlZT6g1 z%xTw=+7xM6p2;t0Lhi>?`Gi%yY~#{h9Q@`Bb@jWVa4d}&twmC_y1s)LO3#OOL;`v5 zYeXVM!EqjKdS?>U?5S)HoW!H=oY_spUR@aoy9o3tbz~Wsn3{QTiW_CuT}8ww;~V3g z=-eInMhX_3HS?#AhgOsh^sCNA5(+HXM0I#QxYWKWZw~fi{_-GZU*9VB8iJ0OFJc@hSr|e7fcQN;0n%UlD|1GD$>=O_Yb?%xbUo%Nl z-eB&(YLGqatrGWY!f`cFJFiQ5jBevE-`H^85{laQV>K_>$7#-rW}0MkdJBb8w%ByY z5!*}P5by3irUmnF;#VP?b$+x--c#Ydi)AL;5rGJ3srAP?FA5752lHONm+q}sMTazo{ktr5D4MS@?mSuOZ$^?Q{ocOO8C!U#f?fH-i6%zjJyRMOLv=GI5q`0 zQwnhaj*z}?JbZec+pzw5c@IQ2%|V}Ze=n#a)gt>!zSksz*R1w@&2?kGnF#(J1#Q;r zK2fC!6Jn$LRU^Im8EL_;1P?C==fc=;kj3t^y(tw3nr}B>dXQiLgz)#mlWud)?%gd0 z1X{-Ku{8t}N@Cfzoy*c=q~zm28?r_Ei3oZ#f*<>F;;=egkeT6Q&Rd2ba`0_?Y9UcQ zD{N7sxTK2wl~JLqzx3Y%SLKq$_CZBfd4YwmX&3{sMl4~DSOsBB8w(HRnS=VF5Xmo` zw2YZ0J+GWs+|p?uqdkjT-1{h=x17#LGUp1qpXz#1(X|RFX;r8I+3s+lw(7e ztU;~gdn011yhI1xKr`m0TE@gdbINBIKxj`#Dj^#ca7_SaM>{iz|MV!nR7 z@IN-E^m@#^paD1P zp1+sc3`h|l{O-Whr|N7Ef|)I$IUH}_>RZ((x-r?%U>s<~NH92;$WP+^#Nz>(#12{l z3Euyb(hcy~|I^zn&!%qF=Q?c(@P2h`dvWpv17u*|i4BF%m-NLFvWvz_6%C2|J$@T= z+MET|O+dcLoZkC`0q5j00_mUoNqUqg?yd=1<#kO@gIqOrG~UU?$7HqGvVh51qeNQ( z91?{<*lBi_Yoy%&YVWK}3>B&PkAr2u;q=1O-82BOp0v z0m(V%oI!HVIXBR>Z?X42`{_RS+&_Pj<$aopF-M+NMjTPQl`)6*G%dFswXs6$%1q#Jp)&vaRjb~9#BQE(N#8LtTc zf&&4C+@0e&pO%LlaC}_^U4uFK>hoN^e^&9fP6r9 zA?4KSV6Q4%jcCxPF}S z?GAqU*LUHmc>?SoOy=a4q&pYLvC!eNX#+0VQ`7SuoKps9wHn?K2E4{w&zjz)VWrU+ zhIi)J2RpXt`e@pp$DQN3*h$)eX=}r|Z@)kbNQH{hH1k z8lRr=Tke%*bslyR^b&DTX}3M9lEhi-t9CkeBDnDHmXoIr(v!!~O}e`kYhPXP^wczb z51j1Pew+8Md+FTEMUdh#9(oteD1gJ)a?Ty?#P+(=uuR2t*5XNN;Eo!1z{@pNM`C4S z{SNQg3Zekc9CrcX$_ggVE9Vuc`9mVLkCF+CY1GcfQ=&>7;Xw*#PSXIrXwUD^JIvoC zQns$`dlG#oUX!I(s4qP}=?P{Rb#M~ex=>2SD3y6US>`2ZNKHMXF)BOq%JHQz-t zYTr?;!saJs!f=ooAs@gz5Qm2bIfz&1bBoYr~0+1|aa=+kBB@;yb5t&z|0_`c8V zfZ&8^su{nYzx|+{cjOykB7^vtj8vX60xBi-k!ZFD+Q`2uzce85L%?wJv zC2meCTP>H<7=Y$#;~jFe^+tv*oHJY&-Qv70(PPIo;9Zy|&rnxME>w;O?}_peXE~nk z@f0Ayz}AhL2Z2igOFON@*ljo>bQ?d07oO^wnSyI-5^Am`Y^KVzC`vl;1u9%@KJ>H2 zt6uhvThWvjS62C;RzZnLUwjZgd4KD92o8Ogm=sw(0ur(`q%)VW9L%9HYQHT+BW*`J zW64yh;}MBZahm9FjS=d;9yvR#K)v__^eO2`-5qcj>*d2g*pyAW>-+#gYnJ3MufZ#f z!9Pa^0~w}Y`)>V5X{Pl_MT)C-daUXrXY}WKA8ePnC1tTD``q31flX@1ADh&biieDv zoRj(a_79%4TYR!FPuv?b(WDWd9((1-s*xJ?2ubiV_EbJ3KM6wvup%7*8^4FOEeZ#F z!GI=uFxNn3!P*Edi~fEmAjV5rtD8c=>rH&}YjorVlW#zH6kWri41Z{=u9yuEy zqriUh-lPs?Od|Rq!@c0)dqeQ5sm7zefnE!)T3K@bI=_tc4K1rkq0i0w%t3p_VWLRy ziyO!x*!)TF=(3W<$zyp3*Q-Y%WpC#3q~B6SKw=Ny-7UDdi11Cc8&nGpZJAYDR+SZA zLE`Eq!ZI0GYH^H^#Uo;k4w22Z=35Dm>|R)_76guSJbWiox%E$v_8RPx&2cr#iprzq zrB-oYWt^|h_a1Bdf<))Ty-?BcWtPUE{cfU**Hi*7nLhF?G%>f(iwSILx{x_mzeEXy z_Oe!ffKz;x%$78z(#(^&lgKx%P(irowGb{0K+i7t@LJV6WPCeV>H_KzYSo?-5}ggo z(AcD7JQ0v2lM>@T{P4)x7!zA`vyZ4eP3Zo@>&&Tvj?B^Y3co3tN-J9Dh1qW$nDJHy zE__066XWJ{^&;2tfWzRMHUOIY19XYy0U+A~D36z(U;8QW>ma|`{QGXzjuP+~AGOlfi(XaU6Bp5u1v*iZjqYnfXQ%79c zuAXtXm%m5tK=zBK7WoKolgw>niVFX@>_oLS`%#tNn;j1Vx&vo?+EU%uUt=&aVxDhk zL2WY87s382A-+IZ!MTH8D(pjSPzjq_sQxh1J6&YW+Rv^Kwe8FHx&I4mW4 zYsyBaTa`cAEs46E#mVm&_-*f`ju?5GCMC`84J6d`U$4KiE3Xh_2Xihuac2>hIM`%w z^C-~A4ogKHe2w6gEeoLzH3PAd?}>J{GXh!F+LxP%=bPZ|!i$)BoD)lRF<}BtGPR=u zdrgTHtm#ez9~IUMnQ!nSR+M%SiWgrOfJCK^C9dp*sNH*D<-`eGOFif#Xi9}6imYKEmFVuvy#R>8n0}%7pT19J$^@* z@r1UXYQQl!cK$Wt88^=&;aoqXfSa}&bn2=*?3+x$t#G`QCNz5&`qS0B=Q;6KouWh-KR7g>w3ol3dFxP%lI-MK>xl6pnpq5M$BIh&rf{Wzjoih zcEKJw$?KuG=dATO%>^aO-^NmKD?K@aJNedJmLcx8@1~X(KAvp$R(1X;yEs={Q$^6r zI1SM|Pb&9Rio%=rD2DSD)mEl!j^Vmp(hS)JezezZnH1SigA^rwWgRkU zVN`|7eq`66;G!z}G$WLsb^bLLAwq~uF_8Jz_&C}3hkau);~G6*ErPnK(X|rzJH-RZ%!NuYt6@9sEu!mDv~VRx3O2pG2LqpB0LyCUIBXB>g*}q!y)#n<^@y z9N<9FJjzza>+eq(z|@lixIAn%sXX}7hvvp-nBG`XF{Ps;Co>=)U629A4CJa4*G(qe>Y&pf@*SQaMkC}5s#fqhaO z&8T-48Qx_n-R@kL_OSSLFhNkrHWk1<S z2$t{Q(w@qNYQH6^6hBS}gJPF`%Ga8#0uQ=H`P!8ITRt+Cm5$O?myFqeJ|^wU7nQj6 zBFLBSK-JqbPKweYWfNc=9m0an=G5{>2bqP!q1RdD_bwhP%Vkg4Fb$AGNyhQ!3>l{8 zS(Sv9H_X?YE(ZtoG`J70LwMC(*qrV}Qk&c@7y=*Pf=b-cA@?2j&s-?`-kKUXdl2de zR8SmS9Z}lf8M%&?wmg2g3Kb_o@35Z2k)2r%Vc4{0%`V72Zd8vNcNK|tumW?DnN~+( z1f-VB7$IAtYLc@o5tEY}Qrf99*Wwn=_PJql+gwC(h@&(MjY_GeTYr>TBl}!}$=ZE{ zZPSOL>$8SJP$|gh@*uN_xu=;zx-p8^Dt}d=A~zAaCNOy3<95)3O&8$;%npc-V0j=h z*F7g=o^rpvCtEv;!4|D&%?deEA3q41jszf?0SUj0a zGwWt~gxp|=2f%NaH)KvgSKs0?3F}`s`a3i;zRBuIvg_0^e z(lZM8pfDspe57E&0Gu@INpS30l%{7!8u$He5tBMY_Ntm{7=bZnIy*G|o@l4g_Qv-8 ztK8Mrx8WnAZ~JAIT?RhvG;E(hHgI&P;i4kn)z8Wg-m>a$spWv3)q!L_@y}j?Mn}l{ z`%k{mRFPK@^A@Zxn-BOg{r=2rT6KQ}K|rgy+PW_NCr%5eA-Z8sZ5aK~cVr%Z=qqT) znqbh^yj$eZ6{Ck}1}-@#4I~?}OyS~&$*=1IKl#!S@u!w_AGNKlyEa!Ue1P5Nd$%5> zP9P2*Zhv6qIOP;-$?1ZJ#V9xWZpX0PIn9}iOQzK+TsOfAnOEn%YNP1UiYZjaO3*xQ z&bj+auXc!w$SwPo4Bl2=>$#HL%y#T=I}OWQHF0 z+}n)yk%b`%tC)QU_sdD3Z-b+k;>grw6Wi=Ezt5F#_b|HowR14N?06U-SVV4)Z$U1V z9mtxS2Exg35f1pO3)7QnNECW)Dc?B(rmQWFeDjn{nxEJc<1s{|diIQt&DMMzJJSq`gg~zB8ros7m2@+%pm_LT~Wmwu|Lg zE0)(|D^JPq^BVioK<_Q{uBXsXSWx0Q`&wD5`-)VO;qGl!ynJN3G`nyZird#2HHvz5~7Fc1}<+rO9~^Z22$j zxHtA)b`|qS_R^$u#*|WCR?1uK=$+@t${Wd;`4}zZuOC)KGQqoy6UAuGIm$0g45WK_ zJR5pXX%e&;l5cDjI3e|vZ>QuE4#nCPwzMpFXQHFAFof!ko)hp;A7IM&D;L=Kj?}rt zSu#1^A`-l1`|NVU@X!wNaz8+1`?MjffV(sgE-k{rFVY;yV|@6k81{Nv>Way2QNLIx zA}W@^VDmoCv;Ot@6>>|0h9&urj<4y4hueREv+YC)-9gH=p| z8Ds$~jssksiZ46)XLb!>{=5gJu7VLTABvLcx>BkhZPsUuMZRt(~f|QYj3A=lBUC)B6uc5a@kAvw?uk^NtmWbJ z?w+<-|BpK-0;Qv1_s@7;IRTh91w&8ZL+k$+E*~!?s9jyD+ zu#{g7pUyuJ^8dJNxu5@L1kX)IyA+4Sj>gCQ77xm2bcr2fu>*>yH=}D= zmT2s98ejrJUuWs1Dn^-BtE!_;Gc58x(1J6c-Rj)}-CY2IZhLE~ez;C^GfbJB-UM4< z&86hcOmzrNafY{DP0m0AyEVc|6nLI8@$JYqP69y{wk=oZKxi==uwpK4{N;W-tojff zuz;9gn>D*n=WkL$^c0!B=PU|`y%=W>=W)@!PTDgz>a}(Y)0Y!v9%4$`IV`0gIlI7_ zMKX_7hgUe=+F!(V*W4!oKh4&!@CsZ?oN{bLPGm zBw1vXm8!c250-~4?QugHJSA*jGCnqVPH@}yNK#P$FzFx+mN~6ACN;)sQ7->YGgS;f z|CTiEXjsW|--R}4PfqHQy3I6{S@#C)*_AP208Sl6G2ie5)D+zD14JbG>#ZgNq#51( z#%d)*v+Z;td?_fk#3NTHEFFsKX0$vyX7Lp8$O^N8v8yLP#hI^0ZAOwI1kZdi7-m~I z_zUDD3?pu5VwYn_b3+!%zag%FfDo8gBCu+aU+&ru65?G=QkGzrQ%)~N$Gj^mp{89W zUf1Uav#@pV#zuk-xq^3G3gFv=R~^bwo5EITS_y0HLq?pYH>>nufp@s%_{m_v88aUfqA;jDO-3wLs9{ zZT`0;ZH45gYj2*}=uGvv7Uz#u`%H}RKFSoQ^s_~$4DZY%4av(f=NSf%tc)^Su`+vh zChR{*Yf*rhmonRfnS&CaJtE>^a11)K<{cnux8?{0)%;On z5AC)wPrzx-uI_HF^cjPt14+K&ryX4B56T_%Xek|w>LSH(z^E%0icnhm0U`yz7a527 zBU++Gu9)o|Hq;BBIFK8p8DD=tI}yCZr&fyn91mo1)v+M5gs!8P<}b-1N6|#Ep`WhD zucB~^M56#BQ6YCld2#tcy?^1PI1Zd9T3vy;ZLlLr@Izx&K)-F1iu4iQa~DIO>1 z1QRIQhw7C)j62z&P|cdtgW)&y&LMgZ!PnR#7c!sVWO;e$?6Ky~(tK2FsUc-5AxwAZ5zurYb zB(hQfi$FAJU))``D27!5j$x%ICg zq2*QeMSXo>88~c$h1$sB&ABP_p`R||LD|FTPe7iDkn^c)L!0?+nCCRb@ma&=?TOE7 zpY6Q~PP3bVVj4le?aWpF*`EZc?#Tg!3`)hdt31%l#P>UMrAaLm@?$YAOVNcJ{zL!P z=sLDFFEax&EW&6=$74*h+sMFDd%NSRYVGW|Z~OYVB8Hy4dPc$C>ws=yO=3w^iJ#m^m>MBR;=U(YW1Knt% zo7$fhP~X*)57CdZJk1NAz&c=kmTeTp&i&b>T~i9Ae;8Osm}HE}T_k3XY%}S_ z98RS`iS#nqm*Q!+)N)aqMyeM(*qw24S2~qH#5Ys-iwviU8}IxZlbKc{o2Zq`#J5Ak zoa4darB_Np&_~L*7V;AM`Rxt69t_YGC_cki79UO>TNyJLVH#14KK*#ZPIq_W{Ce^3pyjy+ft4Ic?+3DM_T#hPL_)RNRj_#IjT5_2$u|1G`K!6xdBc>2|VHbpXJG^lr zu;e-&vfjOX9Qp$kn06%vL@Y*jtOJ=&1kc_XwV?zR^?{eLw6zZjg1X9f9Axph-^cq9 zf814oqVGwa^|LwB9>lXZ(eUH7pB*x>7Mt1L#(h7ZI>=@TP0QVYEuI12|tRT)G3 zMG#Lycd3D}PIZcS2wW9ps#klzJL~26={4THJKUF^A#o(12u+2J^AcJUt!?H>y7;+c z6C>aDaL}Hd`{Da(PjcqG7S}+(GGqr48W~6%fj~%tu@OHDq2$>YOz&O#XZ<;qJB>76 z{5(0y7^8oHZMuxdU(WE5qL$gLZJ2> zaf}R+&%L*;Ym99>wdDKe7JMb`#@Vsnjr zg)X2#zKWa!0VId`9@YB@k2gSFg7qJukJ)FRMb_t+dd?hvfY#R+LU5!!C|(RF$rl}P ze=Cx`7r2t}=(aAXvbVDRNR)3NC(luJNmXB_XKd^2E1+A_|00jkOV;p6F|j4y7u*A5|P= zeWVKHx*MLEP^N+n0zE_#LEr(0pcKPaJ=jyg44s$$3pFICfnCx1IK>qL0t*z%r?@zW zeLGWaxEVY6FAs_>p60hjd)r^Rb<$MC2=)zif6%mJ#0_)Vuu$Fws=I9C0Otb{xVUCX zC68LO+Oy!Q&)M&mF(q|yUMlCK$&S3YbWA*-0`RbT6=Sn=<wFIm zAMu}!Z)l@xI0%^ri~vc183G94DX0@$G9T~<;tRKTAtz{sPxH;;bPf(*fW1db7_iqs z+Da-(f=6KhNX|(>Vr=2J`*rS+E509~E`0z)u@Erio{(N4VRQUy#!v4&O`{$!;Uo-v z6{^K9WQJt+`!`-!E@Xtj;i3Ue`b?przt>^?a(WG!n84`r8(-!Tqd{#Z_DT#%MZF+p*-0}95|DH+(y$^)nX~EV3}9zh4Y}VW%~K-jD6HEMxPp#ORJHshH#fdRnV+OYO(PN^fhvGo;)*nx&C~l-Lb-x0ntQAl;;?p zCI_+avFdwxP(aXw6vDInxMmeop5Vc}cYeWgZ3TaQ9$}IrEnV|tMT6iKWC7n2m(`f^ z5_T)T>BiO}m@view2;!i>L}Q#ghzMNzO7a=k&#Hgv=<*Fq(!@^?UJEn!PHi08^~0VqZ#2lnExjcGb{;vN(CaOYRaI z3#V+o`GI$|A#ZMd(@a-zd~d8!367>oRChWwe7oOF7#-U(SGT(*#*|~j708ZG8w0xY zsCysT^7U;L0SVD{_JPGXms)0vlr|>^Fu@luQ5zDmC&ZeXWNS+4tEje>+ikeVd-Zz_ z6W}jGJ3-rpANf7La<5;BC`P%gLGN3To3BZ1vbXs4c(LzQHu0eeJt@dIlo20hR@mY` zC#>*up@cRsEsc{H7~Sn)Iz}Jp-jJA}@dx~w-0Mv|75RCyB&o%9qYh-6W4miCj{?!2 z6I;D<@i#Z%-t9-~L{7kgJ%6MSF}+P1Px=Ka8KEL}CsB7%jPW)}D6%945-K;QVf?4X ziOcDOx#i)t@tEAEyeUx^gF@PbwpzOuyU1xu_jsg)Nzg4@(1qWfb)vUr8A;#Aa9ONq z10G35(s{t9lfG1uO@>HF8xGp@^~G9E3`VXI^v~--Ow20IQ=Cdsom3E4;CD}#tVKvS z@}fsioKJgjO>GS=;gLvN~l%(a$PgQ`oYDbXA1 zf=t)xb2e3{7u(W>DYa+m%s96R*s8y4Poap18wX7Kq2IRtAi*|4pBOpZlj)L3Sw1E> z<3cz*eWC4nb|%qpH*NaLDOatyA>ju|zExYNx#TeY`QD)eQE*Cy)EHL${g+4GMlr-s zP?#X2>qv6KRvK7i$%4iyG5J(PwpKM$_peEH9+@(vidEp^Eo9@A?jbu6__`eQV>EEB zRh3mm4BT&du=+6;G-tFU)~*94uB6UxQkdLT5<57}FDRX~Ec}`;o``WBAtU2NQOiyc zkY>yfoRC4$i;NT>Uqo04+u+&xG@TuPUk<60V7RMUF zaO!y9;9P8e-=Ks(?U$d_OQq6dEnKL=WUyK>k;5uCdcs7vB+w~+fC9XNbC?{0PFPFK zhPxXy%C1_dwjucJ$ZW);?w`(aj=Ec;4e6>ZUhbO=vl}GW zC_XSrFigkd=PP)PD^zZR-{v4S$G!n}2vju(W@w{5onxutzc|#mZt4zN-+=2u?AeB1)MadQakZrQ zgULR)q~#PcIgnri3}yr8wZ-euLmb32R)9@@|H4K~Y>_>w6-czwL;~zyXt|#KkRuJ| zhV5a%!QH7~bqxOVZMuTF|U>!8(GJV+jp@{T(niQ;pBY`ZF3%x)SY=}fq zta*5dyZZtteI$ps5uQ7c16(tp9AFU48`vf~ionoIZGRhu=)luei2p^Bo}wP*4^WGQ z`!isZRzm?t))HAv6Q+a=%!VRvF_VWQi~(Ox*xy55p!zG7Rk350;t$Nr)S&97sC6-!v{2k3kg(j59fy%R&O#5gd93|B^V>Z!1l$Z+z9w5xaM zsk1MXx<3}>u?&TH*$)VwofJkwev&VWpV#paz|zeQhjj9-!V7`CC60t&Z7o`)XBAFM zLazJjqvamCyYQ}87G*Mq5h1gT!jTg3)4Cn9T*yiK0In{^zl%C{gGzShoU{hcDI_j@ z6I>6NtenSHv2p~s-?)qN4W4BLE$ItV=C?h@@-w z1HK|qUhiL5sQ`RnD^lCM8Im?>!@^*cR8oZ_i-`tmj0!@UjznSkdD zX&}X8y%Xlkj9*MfRP|LAN(#jgJ?ca%AKw7Txq!b5AM`)*PhFew2Pi`Zae;8?QrFnR z>YW5G?PH|M0OTlLMp?}Vw`ij8=AvEY>&QAK@m05F*SX9V5q%d|K z5nVku0$ex7+c7D(Z?K~b{zIYqkKq3PZ~cESOZ|A|k@FlR!MbcNq21j2`^CUWbLvFCuvwP7KS0%|jf3TAl>oQjoO%9p<+T2r zwIle>^oeG8-O(v&UB|-}ZL(XQ1^=GL4-o$=v;IRhf8mHUYI%osaDqhd^?YPrSV2h} zk+N+1S38dK$F<>h=#ZeL^~{5XvrvY4&R$^ha}K(x;Zt~nE1C7fmwzg z6Ui!NAJ>{MUPv4DahAg`m(;thfJ`Z@~|$TJEV!Zr#c$$ zy9yWi@|ARclpwKPT%4(c7-U-cRqr1uR4P_cuZQnILl`kQEA|Wq6=OslSLb=a>RfN5Au71%j4R`EV%2Abs@rm+q5p`*T};lMYyF63q7a-I-M58K|Cb)=;mi z`k(P3-_>bPY@0gg4A8m#B{MSvB#Xo9K%=_4a=FJz(a+d}EU&pGu<+Qkz2Q z2&Z=8-R4*0VRPLCua0yr!|8a)9Ep4MB_3UzFBg*4DE2;VJFzHSuq{bW9lfKzqc?yG%DV&^)}sKi25-(7y7E7E>tc%OXou z!lrN}nuy9LBDcM2@$8($?A1Uvcf7LLn926|3)f_PhjK^-D;$JtXx0Dx0mDUTv@Cks=WzVTTW@T8G`1 zBL-6b#8LejAGHV1#_hN`5RB9%dI?ix40B&=hV}*AV;6~)7|v99dEqQ5;UeOeO{O*A zR~n})^D2;+>Fbi)Rb|Y2m2Ghw-U|hp=!e?S-n*-;eZCdsP+Rlbul8 zzeMG*%(E4eWXpLxh3c6Won8fkwq)HJ@&`bblucpc0ffAIWr zsr=pP$CE-Ly_pTI(x_O^6hjC8T-lW+F)&N3u^J_Nr>7#+MTtK!i;7y7GtMnuoM3EI zHce;KXIWdyYJZQm0cu{rG9&$EL7J+c*!IXuCrrl3yPwTXZlso$J1x6xQWR%$*TfHf zk7(ui(L8&aU^WkRSTdpED1iYs5tmuVizOdR3fX>`%%hFo3;<7Jr|^Z2m>HQ8WA)HYlKBh$#h8bW=(p!j>w zy+-X)a`EPeuGf1j41nDnNtcHE=&D0^&$%x(F0Po5R1~I3s2dEwH2hE%ewEElyEaB(Q)b zV}uiS8vK%3Qdx74WG!Tu#pVv~4$5fw`TO@Q&S+&;ooBWb_co%5)Xv7wc^n77lcb~P z-4(YUY!JdvVzh&dJeSvUpSqVlC#!c^HXx8%N2t8mr>;Hnrl!(IMn;Hsp+cD|+fkONc(wbU}J#T+Tg%w)H(Gn+gphn?L}sduuMs891Y#H1K5N5ILIEt8&yT ze_rEWFEbV5yJ2Z(3EC^^cj+M)C`ja9+(E}W?Jpxd+&t-V#KAq+ z!4}KfcU13fis#cO;@eRr8wIb13PzMh>yRh1y5v(kS;w}=Paz7;-Pk*{Jy>>-W;mnaN;dlJGm+K!2b##w8J!BKi}4KpPSobM{7cb1;ht?= z4X1`)snrnTIrE9~sr#D~g|@}`EiKu3ecQMw_ z#X&k=S%!rk=be7C%TJZ3It*LCn4n`!*Dye6C&6je zAjj>?B723f3EDLZaCe4SmCILZB}KJYC%Fq7W6_*r^SzrtK#Na+_~gX<2r)PiEb~5h z1mP@yfpb`3YL=Ycre2;i({m+)1#kESIP)@unMx^+njxK#U>*eCw%plqXd@)pj?zx1 zNM2DAXev^2Fy8}fIOYe#WGn$RiTNzpFr-=A0&tNYdnPUG^hl&7XL@0YSSnXSOcxuX z4&+M^M8J$e`CaVJ1--Kt}tBkE(fw+StO{&=P^P?etfreOpE@9OpV zh-YLkwyYq-N!ql^9>pXKyb9O5NZ^N+_n!LLz;F(;04PL7GgmPi001NOut0|)8D7V5 zHYVVI=1Fz|AwrnSxvQFqtbXWN`K`wq`HMxHi>I&&w#vlP8qw`vUMKQU)%$8_1}F6~ z5Uii8ddMB+dYuiKrUg!&NexLVtQEN3_;z6Xz@S>q|W#I|nAsx!1gnxGn_Z zTXX`0JD}!Ja&DA|Q(4xCffmS9AeFFp2eL>r@@&%q_M!o<3y{`Q#OaPhs2(!}mb+re z#Y)ecv775e@sEM42+Cwa?$uIAsRJp$$*^eIf$j>^ZM@Ly#45whSJd%}Kx3R8_|qfA zQ+R)=bF|E!RmXLa9)cwn!7w}u_c`>heJOJ0x)K;-(=i;g>fQIpd_aDi4%^QPVj z5W(;Hd;eK4DV%mq5tBeHKaq~hGjUFdsvD9&{l_mf!m{LcD(DfQ2DmCKte}H}Ngeqr zHFR6Y_d!;mszC>)-7mCkS-P3!q?=i`g%vkm!wS?l0wHH_SBk`crHRPmCn!L>s@I$HrdtCTY@jY?XDg(uMx% z4dnr1^87~3LIj=%qsY<4AGFDoUit)rI6N4E)RBf>f0=mFeLp$-Rgl}z&(AcuD`q9t zJs1=@?E|LM2~KlqrW08+ko6fLmraatW;*uGp#J1al{qFLdq5`DV_6X>=c@!D5gmCt z@BL1qH7VlFSKpI=<@h&;a!GKunLpkd(yRysBnTFW?0>jn&ZwgaD;o(m`JYAP@uBXQ zO-vxL4VVGNr5cul8OS^%f~)s4vdX*4%~+u_xuriDb6Ya7bbm=E%1+q57D8UL6t#U#Q>UqtGSvatQqw3PmY#P-(--kfMFr-2Uw zQk8=!U0$krIHW@X0~~h2wh~+?$pv%oZ^%gW52n`~ z+jkV-e9)hbAsZT2X@@6c6022MCIRLr1qZ$!d1nxZ7vPY66WoS(QLHdbftW-LIPgMpnJ{g;Kn z`vhFzM_svaOzFdhJUPCg|L@QkoDgN16SqOBWhx4dNM0Ttq@Ry_VyCn znf#oOHcvof%_*{&mC!17WB?8tv%vv1Mugd+sU;xlphRQsS^#X+37tg;&}1E%i} zjPnJbHICb-$*0=P1`@^@VB;q_H?sjC;)iqhQ5HPDE+FB z0U_OKSP%YfdZpYoO#%6(hx^0E+hY!{Ue+F(dfRtdJw<*0JFG$6+n}qq1Pn1`@?5j8rYWrCo-d2A?f$IwIYK|>i>&`9770;XM3v!Z z^&|l#mlLIs=BR^B*fD^=AV19|vNQk9BdhP&@VLUVpQFS|WPxkBdM^n(W{Fv%`Boo6 h{^++9TMPnqO4A3hoX@KwALl|IMq*rXStR|K{9h#W3-15` literal 0 HcmV?d00001 diff --git a/Firmware_1.26b/Documentation/Select Board.jpg b/Firmware_1.26b/Documentation/Select Board.jpg new file mode 100644 index 0000000000000000000000000000000000000000..8de7256a88ca7759f9e30a62152460a64a31fc3f GIT binary patch literal 90579 zcmeFZ1yo$iwl3T_K|&xva1uPYLvWH{AwVFw26qn*X(T{!3lKcGySoOL;7Q}|?$F)* zEBll&Ze{cDo3=_d-%e5`=(&0D1%bfo_-X zjY+tgn}9%aav(+!2!swoMi2xc0wv_9`VOE#a}Y96MgShXNKX0jAD{r;>)0j(p#eoK z;JXNLfylQ1_T)$T=jSH^KN0wez)u8zBJdM|{|6C3iA4Ivg1`qXg-?;lzm|)lqkbtP z@pFPe(b2z^f3qggLx14))0+5yP-=d%{1btn2>e9gCjvha_#FbA>>PXo>|6pIJP$e8 z1-PCFaB+hE**y^GDM%mW0K9p-gh^=j_N|=&8=H+ItGpgz8xC}D?1xV zNYvF%-_X+d?Lz}&Q*#?(`h&(+`iJI5!t`o9a_n+;&y3B?rQIEjU%SgI8@gK>J~5&f z6~V?3ausm3wzD>VtN+l|+RDaJz*U&)m)Zq@@{ikWR3btSMkWGE&n5p(0elmt`g>no zTwGXPxL9o+OxZY|JbA*#&dJ8f$pTQYIJ()q)pupFaisox1<#Eg4IRww-kRImJp56i zzJaaNTVX0ECvzhK6MYjN10y3I76W}QBNh%0BYhTqBQ6dWBQ7o@J{}H!P7@9Ts=qgH zWcX|Ac1{jfzqD;+$YyM1Y;A1w))7F1gN=&qZ=L?{Y7>Cy*GB&-`~Z&tjleSpWBs?r z&w)$i$8fT+bFpynDF0)KS@}75gxLN>C&cyxjNf(izqjXq2`v#JBSQhhAAPrV_*?U@ zjqU&UM%&6<1PHbLjX9wFw*pWrAaZx^+!12?eS`lIfnV+b5(m8Zt9$})KKvi}{A}dk z0{JIgKjHef5cs!jGG?w=pdUmH~(=KugQyHdb z#Kx6mEmfPF>mntrtr7;qCQgwTvC_s{EYoYUGVvSU>V#|XOWw_zsc2PO=q-l%7vF-u z8VuZmP!4WEJ$dkssawz{hw&}Q_u>|`GP#j1nYX z7vd5p8x()>h54F>+NSF8?J?Jl+Sq43%<{xK3Qy4&gG1ydtew1A zXB5Y?Pl|0a@jB_o8b5~m`65t;iJG&q)q^8F_^)6G(82$Tf#QLk9XZZ^+2*IqOqON= zx*FPyrTk=R4k#)*9&)zWVB3(0%Q&z2y;Qfb!2Ozoxmwbe1O9HWd=D8nuK}pvclw0` z@Vdz@=#M;#mQ}Z2V`+dFn{PpvXEr+XGvBsO^mO{EYJ9nvqxmFWaVo4ygzdFt=eBzo zG9=C~^F%)eQ9DFM+PP6ald6i32S!16Sa@On7BtxTFYx@{G*QeR)EL?pO{ieA9 zLuGC~)V&2k-6MWK;5v9^##mgwT)pkke6#cD#z7 zy>hI?)=>6lS)#eD&!waCzRy>E(ioqp(2ZaoYloia;dHHTAuqoe1VA9NK}J3FR`!J) zNcBia%@k9*dJeashv%}^?=IjbrhgQ>%o|LtThQk(@o>zATTp~*TxIFjJIXOVrKwWt z$|~{bW2BgNe$0!6GMs({p|^PlO|m)W4YAd+yOlk(qvB*~#4pP?bmjcqQATl5{;Ll37t z*owH?+tZ=N|Hs_v83E>w!*nX)#2Mxj7F!-!V*N<{k6Q;LaLJ+pwm_G2wJ2@Md$9EM zTaZ#M;TY$a8J`U`HwlWdzl(50Goz(#Smb(&C)H%~~QGt^~=;FY^TDf|vv|jW82;!_XCK{*vzCKZ-1R z6J>sfRgEQYqg5tHS5AAmFQ^Z8pp7#z`3GUvA;*Um{Sfu1=ZgOf>px9HH7NFiZl=)3 zg$EU|B=~*71?t`#(U^1l%7Jd)y@iM#;sYI?`1fa)q?jJkXN{)PRO+#*?IHIvLCLby z!8>MunriVB#8b${^yfo48c)+sQTNiWtq(Lbr#p+KG@HvCOf93S@dDRJcwQww~wExJTL1>WQ`1q{RUABN$$s$^?v7>X6a+nu2oE3X=Em824lzMC}lE9t0s2|+o5~jGLPlmD0AG)sH(9d zX?5C8UOs^h(Dds+s#&gE5c)pQckv`q=mWsWq{xKh&Y8mfc)^!!ws2t`p8uNLaEMKAw{OX7z5uiKSx1jef8i4&Vlm^F~ z`C)%#x71s@l+K#-hAbgVc}(i5M!4l}kjUP+BrHNCzCQN05I(Y+7Y_cbNv#=za=l*P0p7z%-T z^=j+u*PT&PI6>9M0X$*vhOF!gKsVzm3LjK|cmujGcF69K#T`rce|bIV+PhE|fIhDm zH{;e7Yuj1c+65_xsKH2P{2~tIbeJ-FL&MW!12Cc@rLvW?2e_f}tD&Ycs+o*l2Un>) zmL+Ci%_Fz)bTp*P=Za^fg5ce~{5K-&gP%qYo+ve5J`CP_N2wK2HsFRI!iEIC^L#jjl@S5dyW3Nj4?Q-?{$!wCt#0S-=0ZP2|fQR4@C2FIT1jf2OnPOXC{ zT3-CvBUA9j2+3Qe~)Rzu>w((YX6XaUx8?;(B(&lgLU-#!(+uUsuKjw#F={gJtsHNZDR*9Ghkv%VO%duES@#&~z#E zRmO%w=6cK?a)4&$5$}lrUQPl!_3BJGQ}!hENrtQUbDlj)g^8{w$1O7!F>Y?%&iiP@ zZChJv*2SMIs)HfJM0N9<0G_zobl(f>zO2s++2LCEPMBa$n|UWs%t7M z>iLdjStex9KeAh^vP!-dJkJwEpGB2i(h2nCzRJAR&osXnoz;|srI0D5&*7Joe-iOm ze`nBO(N}kv7HD(kQ>e2^qJ16RP}dYU%=?LR#e80JHx!HP$VaX*Cr$5CbX{=9kiJ82 zhA&1|q>gpTS_C&2C9rLYyLYe$wNH)a$ieeOXJyP)$QndZO?b7iuirsNTi%i~~JUpb>r^Vmikb4jrWf z*>Ub6!ge-_{dL~7k=P7>{fLWD3JIy1x`G_u( zzlK=M;3G2)>#kc+1Da+2U{VnBV=T$>x`_tO?Y-qo=t?Q}D~npxgCVY4kSQ#1er~I)BJ?S)Ijt@4#wBhsQ)FtSt(W<6g?V7Ba0mG;nP$oM|*K zAKogyaD6qqau(#oqOerbnyaHe$D4omxw>%8uP{s$1qv4@ASMpoLcbM$PJg;mKb4(Z7x(iBO1=+lNo2Bh~# z^g%36dm{avFUzJWmd>mN6y`V8$}$RcJN5?;?x`TC1kr@Y&W%cd01!X~1FjuoJ6#q+ zT;>*Ae@0!itZWa`*@Xt|DVQoxz@5E*1ym4ct?Z#79id z{w;<~&S@-hBMW`@&=)Ck_^(jag2Af_Q{bHrFpO}rzc@B$6ds17aJ9}(?gR$Bn{foz`#Xd& z=Y?W>_GmMi3+M_hIxfb}7bEg#vYlziTowywd)Bw0bUE#sB*)S%U5ulEeDl2TQkItX zg#)(t$_=?4iYg+zpFNT!Chm#9ypDax77dM3Hgvu2UkJGcQIEZ8s;Q4wuBi()eeWM@ zXxGiD%#KFRnML7o&%)verl&Vq6;wSF#=B2SS-qngrL+A2ujsK=KnLBdky*C-@sgS& zHBJ&49{On-hR&>>t7^yc`Sr-Fl$ERfBGda4tanKL3i1qn`Y^qDm|wh8BR@Y; zqn(6GWw?4iciJ;l7)SmNDB8D?SDyeyOU>WAwWCJcTwPnOm9VcLjLJx;7KuXp0RutE zK^kcyN}E2yNntmF!qsANr$Ih2NpS5(z9=a}l&7^HEs1i_zGvv$k$MZ)5km8X&2H`y z-gASA(^1nb8pS9lBsnD5XR-(Sb!D@~WmfITCocqMhTt`i3n>b%U93GwWlZe}I+&`g zM)}_m%M;6xwsObimbsgQBg1V%iMJ^Wb}@iVCA02kaOr3zWt}_>1<5vSFn+%0VE2R|tBCyBBdjc= zdk*NOkEVHK1+nS7S|~@)NLfsVWwDjkmLpJiUVJR943ZXgO8G9iSacUvFPaj(g6%xr zQP$g#CE&Chf26hW%%0{|P6STeI;SyvpU)#@*iKN{3R`-Q7Va{X8;BGf+extAig>=Mv>(^f(&OwY4#jeo<3egg?K`!=K z5`lTxp}|R=0{;8yi-6^|Cm7@6XzA!-WAUqKtb_2p-Kz?n}mz2vnT z&GuP%C`Illb31%ltEdx3fA}W&>o_Z2ocWabOCOaNs|ca{BVxiRt{3l}>a8Di2zVy8 zJgOVFo?;OgQ^(4#DL0Md)8iUwBQl!_B?~p0E;Xk-Io|_aqpzXy>@kXT@54h0H|(L>4{1xK zVMdjc+;vq4RhB5lYvV@I1}#>N-XG-)?rfl$QUsKAE_*q`37OrM6T1^~H9Dq_I&e0|t;|Kaarxp7T` z@<(#}@k=S3{i63vLL*&ur?&fN#WAbrMmc?m=Cf+{f_Yhqj;g{P_i9F%;d#MPa4bvyxU#Z%qG<^ne*7{GZpNLbiWj^I~r05m;_Jt zqE=J}X(b(UGAm8T!GEeF6HZ9za|;rkO1tC$Dqg8x99T4KYE8Vlxc<;B$~;9;x^z=a zjYCK4oqR_b%mK;W-lqzPW^2JVGV z58ysO=`VlkKQ~Muwwk!j48^7HCOKb~?75`YUOCF#-l+pyDqJZ7LA!s|tCRKg#rnk$ zeTIAxj=r#X%XbvjgOMs9-iV_iQ%rd2xZv!W-+~xL@&TRZ{~0`TmJ7$S7QNh~{8PQ9 zpQ?&kt#!9P*O*PlV#YjrX!y_>ZK}F;>COarqq!7zx&W1EaGrXDe`uo9X8Q5)=rIoj4d*7ON@Xa0-kB>D3D}P{=+ww zS_!GzsOep*KN6|fDl|0KM4P6`)?IaY<4H%nyskSdyajzx>~pfk?&3Wj!IKm5{Pexe zoSoA-JQpb@I6>uOY=UAoQDX#rDhBT3l6Enn2i2j3jDf$hp1`jG>mVdoQG+C5v_NY4 z@mcJ6HBOa+C3)dvS7&5NXJqWFVWTG-V}K-D%G`p)8b@xn+2E{6_V(D>Rq+p$da!UG zxzR@X7BCRg#I%823KCTtvna z`H3|ub;@jA**Pqc4~yXA(#Ms$hrWWiVmSY)q!sO{bwTd>bK6_G&!^<{QSCo(Y7D1Z z$q_T)WZX;HE6Fq^pHFkdo~$Ztc=9tcx&`Usf(7ylt3tO&qLXtP=!PTyq+6@Nf7F*P zDj5weC5@?+f77Qbe|r2M)MTus z{%?w^;9n`xShHVM_nF!sb)wmy-t{b$_*I`4wEoxXbWM}tx?!IZG7eYvQUSt8m}0k} zv>gQ~5d?e$5&h%4dW@q|lhbzaskGzF?b1K3JAgv`^&o!I-_RBcXI700d8T4Nyd6a;!9 za}AQi1k9@z3&2!~=mqa&+=2wIRRAMQc`7Fz{krw*e!D>`m6EmQ6ik8P_hwYF*;M(~ zH8VPUYvbL$eMy;u1!Be5T~qq_3^#0I98k%$blqnKoA!l!4*6>@1HT!j<(1SynMU79 z`GmoRnq~PQ+0Ai@w#1#?Qv2u02lSuuBYWsFGttlZRrwOwH=8TRH{Dg8asyNsUgHT3 z(I(S--s7M*q-c%5x|o_^GaTPFuK%?7a1rc!P9XJY(3P`Yb$@?Z470;C`&?)h9@|)G z$qO;!q#i7EFkr(Ypts*37yjbda(5z5@MAJ_mwm5fD6*hoqHDNEk=6GA@B-Lx7TojKG*IcmTLbv4j%!VH=@nSlv_FhvDxBT z5cD_1h6BA)td=21x}W1A?dn=@?bzbbH|5=KK{y@WT5&=^l=@MA>&{&3DQ)r9gQ1E2 z=P@rp2`b9koFLvWU(xgqQhQ=f(U96jk4ci?&4BmzRC9}*HDiL6n8hTD;??$O#bQ|b zEofWT2ecX86Q62r7l4vwnh7lHVUCY_BqcnLeJshcli~;%`5=c=vFk zT8B?;f(Q5Wr|7A5G;hi9_cC@OZUnqD$!>e<7Ogq3ie{_?Y&Utq=NRrrL=c<3?P%sMF`0j)T(db(Qy-|*^hwKh z+>ninDQ#{~fyWnn46#+TA63GAjX-aD4X*b=PgZnCvh}rJV{5}i3$|;3M`3AAUPX&E zn`c>?g}+LNtUtoLHwgXSxp^R5*@A77^^m1G`Wr3X%8HtXhH$1ZrLkTy=JewP9}&lX z@5%zYbE2!G&`8V1jCd$co9H53bk%J?w%AfLwfHk6%to>@!8V&uai$9!`fA`_(6F*M zvHDshsBO(YmMYv2yd0*=b~k$@xa8iByK-%GldAJ#+tHPlXHz;QU&4tEcCu$9m(Mo7 z;@HBp-ie-__Ayfg<@Ry=QqZG`Xvn^Y7IDd9v~(0}*VuboR%%SaNF+kY(fj^Xx01A_ zj1Me4jT$^bw)>AJ_urSjG{8YMb-1G}LG5}~zj9MY2ISiWx8dN#`;hrGU&}MV0gFVz zR}}k8mmLJPJj0w%AT_phZboxQO*3?ahVLbEZNV5NZ6t1j+Q7F=Gya*{Jf7K6saIQu zeQyOrZur$+lpP88*4H1&O;&&7nBgvabR+9mJ8&htr#65nj5^PxCf|5OkQ-nV5nxqZ zGJEN}XKY?V!mGm9MaI~*=$lrz-b&sA@ekh9{IC@&m%$97cNz^k5kfD)cbJ znRUaQ6>%g_DSLt*|NT(;BD?qAZj}6F@P`p?(`jlMm$`6>q|!??ctG`rGJcS?=*ltW z^=9jEORQdlNbHG9F7(~ATaeC!tLd>qK%3Vei6XxPr|++kj;vj$>KujNF*%aRjk(_! zqU)T`e+8-2qMPL2i4YijykZl0VT$aI8+>{|(H(Ueg>055GT6k>b0jRWw1BdmN>>}V z+|`cHQPXi!kB~&%)+Um9QsQrnJhK@=O}MQqoZa7Bn&sj5V0@7W5(i{NpX? zQ$(Sm=*GCvD~)+3#F}y6C&-en#W$k3JIJrw#Gw-P3(1pvptx!2r9lA^phl>ZV29I0#_&!S7 zaeVVo1GWYJkxeDO4r|xPR2vEgXyQyKK-fU>cl}FPZ*VRz9VpP05|mrx?k)WUx{}2@ zscA_rMe%!CA8>P@A?$OKWg&&QYCGkpQuh)oxsnJ=x{oPO=Cpoj^T>0?uMz0Z&2VeMjgT8HE-qEF z7BKQr)PYbXWd?mG71RjSzIUhni*Re{qeAlj!S$mh-mxN!;0^~h!)SSBto`0L`iFNV z?`+^rCz!)=r^mYIm)9q5L1y1J<1lSTI5{i}-DnMotx^lxW#2v;5w@VjbEQ_A*gMTX zV74j6GpVba*xmI{>aE4wWtg$?33_jl!`>EvL@IwL=hPYAT6#&|0R(AhuAv?jKE;+% zn|)TTM)fTXjq!c8)z#lyR58>S8yQ0x%lq`l$)XW#(n>qQ1-!}Dti?9b!%X$mDauxN zhtuVWpl#jXyQN;<*SMbZPU<8i9N$cgD>1}f(r*Z6>LsJcyMy%sDO}vh?ww(%uVoC7 zUsvlo+2IukZ#LtxbgkMkJFwD}4r+9YGeDpzsFWlp@_TO>eOD~AxCzL9>>NG#-WtE% z`fRN9p!jr1U>$y~zzCV5OEiVZPbfy)JrTM)$!t^6UGb>D3=1cZXH^Z1!*)-V9AHdULu%fXON>vVWu zf|0?o6{poz?c+IOlPdv78B5#vZ5%nECkiKEdx*I}6Uk83I3(*s+3b)-hZq72zCTgu z{ch!znXyu}RP%X^`id!L9;0zpVKGzD4p~^Zf~eW>yCoLlZvyv|P3fBNhJUb? z;chKfSCqgJANGt-!Js-k)}J1UH2;{935krx?pUPDcBc=s#)?)X zWs0f4)XML8A=K%FD8pZS|Hd_?K9EjJ(`Y^T4(RV2M({z;RoY?ZKMENGbsjI$`t5$B z%KTN^0{c;o6=0V@2oH`A{2XHT7-*Br5(9o})kNC9|!n(A_ z2!7o58(qY&7)*mwzW{~vE79+Ox&>9_!lB>RwZz;QSd|aW zMferZ--Z!bWX_cV2QA`6bm?Whd?Ld@bSS>j;%L7gWCH%$@1LS{^|t=Ict6%T&C#{e z?-2OEmT#$F5s-+t`yu9Qk0zVMkssqr8cRXiPu=R>v(2<_ zKQaf=!lCoZtKP_B8}y~b%gxq5?y)}B#Jz$Cel?1AI1ejX$ZrQ^5H1OfV<~Vl;A?8* z!uwm$F~g6z6ktt!&bAW~23(^k(Vg$$Q~HvNB`(trt_ay_%FAUHRXE}mvHmS+)mk)R zR)wR;Jm7IQNmzRLydu`fMhUfp7)Fl}uQZX+YH+=_T#KJ49KUv~gxf6IQseDr_NP8# zz98%l?r?jk;4^kC7ra5<>#Hp~FS0e-ihU;}t+DV=PPqBslkVBs_;*~1Z4fOaJFOJ! zsH(l{ea3|4dsm#GPsi-yaGTHN>o>0)o~gJqmZ-0!AK+bO(R}w1@bKOlh^%`ty>yKb zAIk{tQJgqUVO=MR((Rp>Y?10me|4816l%xcgTMFfh3%f1nL@$VR4oq5B&>)_>Q2f^ zw6UsskJ`gjeD~9$>Z6hXI5|m|T6rI-2G90PQJ#qr#-Nzaf~%ViM`~WD5J`lB@3Upu zkh)#{=E{}?HkPwTj08ae0%PQUf*5MhyMTmx{IExGa)WIzm0pa6&)XAWi8$ zw@fYnH|Pc+!OVxz{QAlF#LTH^pDakso|0tR7n|4A7;Ia96N(ENl2pT9rxQaFTdU9z z>vmATyId%@yl_`bTLz`)19x3cP_PVHe0d=?k}o>FFOEh2(j4KA!o=BwCW(8J>!f7t zqV=p}8|3wobfR04B4@n&W*aVMNhBuegoRn(w|U#U`0Qwo0*T&~qz8B%T1*;W>JEDe zc900iuD;XxQXP7)KLO3M$O650@mNqb8^5G7Pb7RfT^R&$udye+! zZXzRu?Qz&53(UB4E=KN3C%B~&Z^T!;5Isl>TdRk#oIgY`YD46ZleCvGx;M!?DIS;! zMj+7#5061D8gj}V(d&XC5Mepy&l*KJ8YV+|A2U%Ob}#NfG46gq)Hg)_EPJ>kc%y28 z!qrg~Ysx+7cxtj#==YqgxH|FVXkJ4G zkP4nW(!yg*CeNjqJ*D#gHl0zYcJyTd%IwBX6W7&_H5g&N+L~ynjvU62SL*PEY<29oA_{>|04*oioA}pNWw05tMKb9Y-b#|@6$Nhlt$XG* z7a<%$UD>N~>gV`3GZn#z)^l}Hp+^eWP*&EoX%BK0f*{I}s)VXO+jPFM9^{snUwd+9 zxsOD+0=%Wx*^tR%yU~TQO)evr@5W}kT6pYttn0E5F-Q4>j&z z^+o9A4v3u#uL%x^JmbmYtU(fBB756MK+9XS`@%)-hp*oe%8N6=4Z<`LkNyYl13Vt40kb6iO|NmqjeQoNVD8YNi{ z3q{8{jaL%sTRrtDk1!H-4G`N@Z=I#=4+;9xB%-ehPEclCp@|0V?3?}iD8U0$!HW8o zywOv;Z~S-fY;0m9>Y=aIA>OC$Aa!~@k~na+iubtNHDIvcZ}29K{i-FkS!(0e5W;i6 zKDEeabj#VtgX~hOBDq4TljO}+LH0-uZy5U(sMnac#h?|U7)VOs8ps~Y`6s*2c%JRu z?ypmqiGqV@!!TiA2T>2Qm8+`E{3Bi4aJBH?C3DQcu~l-an*=Px$@Dm?)n{yG_mR@+ zYjcFJUolneSa7(7k%{L-86O8rsy%^d)l&o>p=Jkf(csx)-*( zh82R;o3SX(TX8H@oYH#$-O|0Yagt-!R57ov-iI6+s=h(y82#A)yS+)!qy~+o8ov_J zy`Gur^c>;Y$5e#^-tFPblA~4Ll3orL<-v9X{Qf~VQb}tzq~6CsJn+dzF(*GObu_W= z%)14lihW|zS=@-uQ)vF(-R6zY2`lsznrJ4%?2dqsp7_>*CXa$%?e*x#Rg#e#{AEs` za8)9Ffv9N3ApViFmBezB=;xtE8nQBv=sg}&hv(XWwq}IQFe~is?_fR8_qQ%`xr>v2 zk#+Nu;#JIW#DGmi(;K*`Ptiuu%GlInmI+So$I(&;b}OgX*NJcQsrsL*`s zPE;WM`j$ej^Xq;3sw4AnC`AW>@jZa-0nWxUTXXF}cuSh5qXNbtmH8{_xqD@OP{x#@ zO#UX^ZVuYKa1p=ttGe^;s+l|+qXtrH*g^{FnzOeUQ?%o-tFYiZWt8uX+lnugwWwza z+2BQ`q|#{l6qyv=IpO>CKG`P6zT_n|g3grBRH(yUSqb1nG(Im^R*m8GSU5D!L;T{R z*XI$;rYA2ShOU^jag7UOBQ~-I;nwUq2?ngSZwpJUiwYRbJwI`?Xp0Wsc3^MYAUeCr zDahh#JM1lsfA|6e70KotOW>TS2S1MYM4Vev+Lf@pON*MZ(^+afcS~%)+d^QMM7u-q z6RU`Rtdk1kg1ki+iLYEP&p`~geL*}z8&(_ED%Qj_;nz7yymi{BXQ&8)_HxZ(+2i|E zAB?PZ%m=@Du_9VZnH zNAP;umkv+lpNhX7CTKdvQ$tM?FGbKz4m-%K$ zp<|vXBC+4E=68RnjZgr;(1wySg|-jjwgSRx|B6%1^$velga+ z+)up3VDYj*$8RlN?Zh*HYvHDq?bH(y2aB)Sh8l6J*K>@2;D+e*kBhDg&Pt*!K9*WHn3Y* ztWoL_o1YWYjz^G_oC7frXCzDUm*$9gGLe_57IC4yU;4n!Cm<;#TP4j)x?KxD#R;bm z`!-t2I+6;EBmGZRC)&#;&mTHA(!|W9R!@(LwU&Ne&OXHFa0M$=HcZgEzMUgkk#`RG z79S~H?z{cDy!ZH0o7eH`%i{Y! zh%g^3$Bwwqw0vc)*28Si(VL$MT1mX4X=(YI%(Oqj2qdXfv-(i4$$lDA3+&CFxh}KW zw|C#@>^*Z`4YIKo8LnM`dI86!?Z%dQckPCy z=v8q*+G;yiq_)uJGRwvqa~u8$zbN|%c`-fUBj!Q|gh8 zjj9)Sb8>(ArztKQ<36MSl#~|x)HZaQOGgh1-?znFy5SJwQ~$A&@4HCxDt8IS@22A% z5Z!Y@GJ>t=WC;Am8*IN(f+gHh@I7oF!u#RCMyOj5^2s&RSBA_PH?(uLi{IX$nCTU*Xl=a& zw+q38PcazI=fz>Muv<_k9Ej$qeO8pJImX#7J%CdlDv0LogIA{XE^v-ZpJ$}i9HV`l z^928+kMX~w%VhFvH)M6wOmueKx$cRbCfS8j_9GmiM22{Kr4PG8TgT; zASm#VmY6Ao-Q6X;zg_Xst<>XPPL3b2El(2IS*2UEa7}imrRUJ_u^`Q>zu?9*Gp(~& zZmHY(h_%S*RW9(80H`BJa(gmG;9gDJOB}c_Bkd7z8YjFCD#~|NN#()8{Fp>g@_xFK zBNS%;yd6*afgx_=Iuo&eSe65rq*8*Np>@EXCS(JVRt&Mwni@obhSn@g=B?WcO2R^$ zS7S;}UIBukCc&Ug6B<5=keAB&Gy)Zi8?%dP*&6lj)sgpln4rWXTSKxEOy+MMlV{33 zLg}{e!Lyl*7@^D-ar4t+C43$CI^uC5G>= z>T8@{o$#+7>Yz(H-^p9LT{v6XOF3=eq(-+B5u1LkrAbR&ib+)QnB=|p{tKY{9o+~RgZ4v~ zGnbU&)&7eC^Q&5dS-uks!(Sy;#i@2bv~(d%kTD?D$}?IXpl?FnkIUIxGY;`|%r=$H z$zoplau7bFMiddR@)o1cbM=buP9xFkQWxUk{+Y?rHIXusJugodp_Ftz8;|tJ(#`Zde#u6xR>)G>qNd{ zMpq8mXU$;D;5lHlB*zZVqmg0B&l8SnVt#nn7DDhPcxy~Dv^QtY#ef}wRBV1Wl*0Xx zq0XZgJgs;9L|EaAK!Iy2rruphx8hmeUWwe?&9bp28$Zfx(ksJhnI`IUFOfWHi|1TpI-MJu=iWOrIfpQF(6)cteRxlOPn&GRCzaiC7{$=g>>19)rmRXm*R9(#^638f8VMW!vQBUkIr>q?WXk%Q%WmEJNCwP$S0^qK1 zYHOOJiHfHlYY@D&c-kvJ*E5Kn^6jRMU|N+MjyJk7xuC>8LeLdj%3j-)NVH+RX%t3A z6G%k-#sNf*LT-a&NmdiHLWxJ0+-f_{T(ZA^Hj^Uojpa(^RT#%rL^OK=6$UzT+3Mn< zaoJJiSE#7HeSS{57xj*d>eiZ;f_=HjH$x-`YHJ8OB$v1wA+S2dHpQO6)qOf=V!R?X-x3yV>$@1#%yE6G;W@nZkTI^k92@JZCByFntn z73Y#VHgyh&@IyxjFN;gq^vfpSyEir9+eu%jp5K=2%!J|9JDAG+b=gDebN~1m2#{(uYyx z|E4JsfvQ%;o;1&CCDX|1j5}f}jC{HN!*_=8ZC4vw3FlY3EU6kG3efSmk53PEG4ALN z%o46QZDco6xP6@)Qq`!#_^mkkwS~>7T(JUiq8U9p=Dkp7;|gk;60%UwkQ8jnp7=P? zyQey8T~jgIx(m#rJYh}K7~8wSI)ipgr0eu1PpC2EEeop;*JDjR$mgm{`c^Ch)J}*N zhnLnClRXDN-#C8}l>5p(M=z@*Fg(}N9ZvozRV~5rp)cYAy%{nhsEue5Lsmk+k%USVD`r;=eW&fyJ3-)q-rvszzhIO+|(qpjyTlF4>;GpkiA z4%cIHejI1>?R!XKg=1@$*M*+x)fm9#mlD#~w=z2(9(M)jgSQ-Rnop@V!%IfsEu!a1 zQ^m%X3){Q5pdBFRY~GCNpxbSYuc-Cue`iO+k3A3%xLdE#d*D0ZO}c~vSNTq@skj@p zIVXJQZuDaHC=x>Yw<+(AkU_59vuE9;W-o@n$fE~8Mc+Fn3E5MlJegOx*`0blJ0^(f z2rT~wP{G!5|H1gjw#Ih(G`Z{F0~m8R(e*k%Zz=v*-2+upO}|#ty6JrUt`Mo7c4acj z2{={&6ame8o3v1=P2d17uqQDp6WEmH#FtZ-Eehmzf>+KG{%9as>2ABBQ;vjn9bP)X~* zO+gj%%`FSnWs3W-BDY^@%;?R^+FIp_^hVbvQHyQzk$>wlihF~KCRNdTHV*Bv*4%Yx zulFf|OqztwQr#iBx8j~pgGya;M~Q3Ki!rwJ!>R0^k~Qam`uINE;@mpq+1m(a4|!4t zq$t1k-sO5q#BDy!)(@EzJg907^@nrsV>nB`4jQG=6A^8E^FmQOY>Ca^P7F+AcD6Hz z=r-qTO9{vi*>e%o$@%kwLQbOP*M~>jMv$9lptm5jHy&OK!S$PQ)9kuhQjX@_j_r&A z;p)kpz_B1|U&a?l&0Jk-i7xL?J#6=Yl%Ygm=b^UwD7pc7PY^hlUbZc}Vg>w+m)=E+ z8&RN6us(gryP0L#LMERA^XVAP^>1$W;7k*}L{8^Nz1Yd`c5Oz6;-;HzcRav)A0U;r zXD|y76@qok~FN@U6P@mvB)XlVyyj~jY)l_?L!`!;mR zS;E}GpH_==)2;wjFteRFADiA5W2u>vnt~rzPSaSY9-Bnm#w;n1uw3-T$=05xyj{ql z35!rg3b|Vv_zAJEi+&>p*!H??6ZfTgN#@S;v$q6R31g@QhyM{$%be?j&%mZejZD zt-Ih(;!DdrUP^t>FHonbZ0@5#=Me2*S%;5Zo zLmNT+r!bnDH1`VbTJPs2nhR?hWOVz1Wg?R^QdDwyvY16t4FPJeBil|NUf{oNJ*x{; zWeZ9&PN{TD)p$V0%QXU=WP=w#ii$m8I%zOZ@E%`I?fq{Xshi#3;;bXqAEDb{$aBr) z>Y5+*Rct@E3^bj0?y~Rg_Tofq*3PKmVEC@U9Bm+z;aTzm4do+@H}u_;LPyRbW?cma z7te4}k;kX65xqZ(q+m+fmpvBSBi0o#{r}i|>!`T8HE*zRCkX+9ySuxF-~ocW1b25x z3JC;v*I>cjB}j00E8K%yaH!15oxXkF_ey^=-7~$uS<`>iVo~eVsZ;yNex9FgAtUuB zVuR-@5@h>rQ5^-ck|5>w7Ec;NQ#Di=@)V5aYdk8baqNk^p5TWvTkRL_#7$j?r@uf4 zr9V~R_(ljW;HVA^N6C8qFC3-krw=vIu;TR!spz$Cj|8FM0rfNx>K8f?j31IUDA%4H zeaQi?E z=l$H)VMZ2^d=+`lUgt`7D#Y(tNR@D+Q)Rj`7uDwGkdo)caHk%}8hG|9n2u6>d|xH8 zzNedvab{^{feFM!!sx#K#cTcBZ~aeR@YfxO>Ck4`-|ca!Mmcz%_sKaPfF!v!YO;1? z7s`vl1FrzNKqdVz&`(wM0>I&{?#6ltdti9ABMJ?(uIq69K;QA(@{9t0anCw4GXdVV zoCP1wE&T#XWaZ6?ZZq>fA^{CN4$YriY!X06Om5Y&E_#n#n%sY37)K%cY!qsnCyA{J zDtgxe+14`uoewE<~5BFUZHHiJwn*B14&g_UFv$P(|^W z=zTn?m-xVuBKk06A*NTP}zm6wI}<*f{*;`nGc;^MumiyItw!Fa&I`&f?e zy+vFFpbU{MXfy9cMME>=+8xp|c%BBTJ~!vWEKI($UEgq8}=`NO_KBC(l8)8_>%6CAYDx7^`c$PQpa0e7{ae(dzBr7Ss)A)D| z9t3}nX71Rlg~~&*VW@FPlh!U5e}SlhQ55>09shR@MPlTph2_z4CVOJG(9P4*T;<=+ z#PB)1_4S+;9Tt7lo+pxMtGA7laD=Lp$ ziTMnYtPJ&d2N*LGbhBhaS>@QMgb!)YI7co_)-p~OIJ3)bjd_k@E!g1$p2vvy%Y}?O z;xvb*8^z$Lh!OW2e2Dh08>lGIm!LmD9^mSNrQqmH?914F<<(Rj~W29!|?8ykiU(d{8*5UVwk@6$}%dBARgu1F!~S%dM+t-_K{mcJkreNnz;VfNLqZWWzWV((crZr-7sNjS+*pz8f_tkRzCTKS#@%fB7t$c{>Hn5E^EokLqyN zJhEsbH%W(Ba^w~qMd~qC?>_AXFN^i-#V~+3D|ydJ(pd^N0lXAVikNby|GMf!2OT|1 zcm?u6q7nEPNS$%<@Chup1(X|^(PHtcRl(2bdO*!%GE$tk(i-uQ~`?u=rP$-roZpuurOz|Xw_<)=uZ#+u>e$0}k|DJ8Or_fMjQi$mH{2edrTEg@AQ``-1Drx`^3*ER|9o+@xJ>N3`=e%ER5 zeZ{dF{Xq?`Q6^r-lwQwUN>$zJ@nBHNd{tfm6uO-94p=E0UZ&a;w#o^pt-;RS4op_{ z4u|(gEXjs*YrD~sxox{^y^w8sPi{j#LPqT?+1@tUT{MpfJQGlaJ^B=SR=YI+VA%>` z&no#WSwjs8MU)aC77{Pg7J8+dVk;P{h&fuT zibmuaf#xo=MU$B%{yf#W7=>uv0t`VQ}I{k<%Tt?zA>`(2!nuHPhw zG@^zmB^@HgkS3xoMU>^UlVO6&H-)9f6-k7r99T@kmFFl)7w00Js8=74$(ZDZX3POWY2U*GFGdfsqM>pml*&cULd%X zuY76k{*k6*I=)99XEyOF^IK9xRgVHh$T3x%%E5@2(@bV@&{zr-yrmCJ-+ej)t2X8~ zt>EX1ah9d1a8?8oj+FL@k2QXa#uD~-Vz61s(6)||#E-h|YkAmD^kM{p^U{PtfH5Uw4iI0(RO9fVwCDpOuvV^gV5z zoBLMLdw{uuIOxFdwAO&`2*=Y!*ru1Gvao)ecN_S3`H$xE`_76o z0t80_B9#*pkoEnRssRWgr1o}xxX~u|M%D?C6CrC1B=k!BVI#(VEOa$nPx8lH) z9AT6d`kEa`{ad?7DNpO00>tr@qz~l)u93D_R@j{H&M5?d928%HcMMd)KM-r?PofK~ zJ>#L03cAoX0Q#T6FslUG5QkfvS!lpt;(fUP^@CaV3((L{0>KOO<&DtK!qR_}1MK{k z1B66(UxL%=0Bp6BA=l91Vt)7z@;aimNzY?UB+A$fw)1Dmsoc!|jI4FO!AR zxf6>gB6CPH+Q55SWygG(Y-a|pzDuz~`CYH^SuJ)PH#Mr6@t#OwmVyYOroZ8^Wnwzs z5-zsMk}#Nn8)kFo<2X@`Z)@jwKdrq9lX89*4s>GEWrRmG-qBw|JF!!aZFW9ZE zHo}A`V%ng8RDF$hG>Pf;78M}#c`nMp4Ljn@RQ>twvB;O`J!P(oWCt41L7^4(nd~(V zlkCo$B20Hb&O_xCQ>>TRIm%Ho^zo;G+52yiD_M+fbVIs{S9POX92KA8@28~$f{mCS zAR-7LS=4P>J#bawC{hxM1CI7`PP4&swZIt|Fb4nDPB0dtJSrvM5jAye0LAD?jwH5b zk(aSY33G)NeF+A8y*zaXE$qZHZJHwI4QE!y&wb6-`SgQVex9wGwY&{+4zp$31X}R= zZ{Ik^{OD>@@7uZ{!D)X#V?nPY>%sMjzjE7K0jEdX=BDQGAi5;gzI{cA^T&6(ON5rw zB^ubfK=OAd<_sR|n3AT8x3!vWbu$F>>Y7qEG>!4Ds)P2_O$!4{#**l-Ksn250AC_k zl36~}VZsR5TaUcoPIudpraCdaNe?)Q4Ty*X;R_FvJ#&#~s_sG?<}7o{P4aN@`{G7* zjkA|UIb+7_Vl|((<<)R=&E9KtE=8~_%7M$7L1!$Fi?2tv6k*=VEF@WKsnYA>@sx)? z%B3Q^lhVj?t&)OAN$Medo^_?1&C@ePRLrCAv!r#LwJV>Z0&iT&C<9xJWCi~dN$7*M z_qMMrk)c)1#4%TC=4%uZ-KAC^k7z+>r+CVuUFmVd4Iy=XTFqHjdsji+rmQg;qh{S7 zsD0y9FffE;r45oYPA=(n8yo{Rz~7tR%?P07T|hBpYH z#FV1SZ*HDL`ly=I_}*2CO|iYx%7BSqjssP)D_CD&91t!k7_A+I=dQ^aX}u%l{{?dO z{gUI^g$KE_=cnZ^ciBQ=si+{7oF#8+jA9nt`)pF=WiKbg891ni?taZBmFsQ@$P4Hv zZSF7SuLOq}LuzN;{EKw-<%@;RmaT8xNln=Lie3n9eqz&K`kaL55&*#1pWmEIPHLT4 z%qr&Z4(@eSzv#n==&V=>p1_wi9&C86bv)+D#ZY?xvndmw^>DOu;^@RpL1YYK6W)4g zN#@@m&s57$X4j7{+bIJerqvu}?~qPR4)GQ!Fx2)bx6o@*V2Z9Nu1yImRvC-R3$m!PjQZ$OJFQ@!j`NE9q@1P#J?tC9EvI`} z^wGmnoW3Ox;iAohV#mKZXE8UVZT0F1B^lMPlo!nQpgvnQ^~7AeeLnOH)LBZhd9i;r zdoCPVE9>EwzxpkKL(0QT`OZKk@o*+M?(wUsMmpz%ddff}T6G z$4FjQ*sEX@h9zIkKSnj_FQs=|(uN;Xh;nteIiO_NFU{j`aZ#_dC9CMrUaqOLBihstjDO&7&tP-UE;!*aRqkdfc+bq`;R}VMgp^XHmZTNVq>WG8n;PwNm z)a=ih*;fi5Ue7u#+v}=wgld`aqhw^k2n%Y^MsVBl;QazspE}sun$Fm5OE#s-vVY}1a_e0Aos~q8x+&c8IQsjbW8y=N!_{||M5zh2-zva01 zKM@oG^17pvGatG%)uyzVfV&^`7q+$RRs9=P)czSXC(v&phmYaWlg{bk2;C zY(TGgT&N~WF!s>EaH2R1L#7H<2Z-Q|wL_@jwu5$8#Z0N({I8e1s{!1*tba2^PC@i26eXbdMFu&pJ zR%x~Ot}1zCuI^4M0y}&uu6ilvyy_#4+=*zb5T);MhQAF}NBP7(kM}Xoo(?$l3Z?B` zwMc{6H|SJTV>57>P}m)-ejKcNHHwc$=wQyUY7W|Q3VOd4=??8z_Yt-;jU3Cmu5k$1 z)K%u5PdaZOP{#TG9F=%S={)V#Hyby^GJvfpxAi{m9l?#cYjlx@_eta(*pS*KS2Mk# z@)MTDVfNw;chiP0I^`dbP=Q6Jm8XpZ72@y$S0#5l`!=flLs_)!6^eMa>}`t9qFPyU zHto#6A8JFV(^eK6Aj1yKG!Q_R+cjbLdx%wpN*>Um)oZ zN)Pm=%$pb*_hY=0%giSlyJFNLtIEbcAGa~T)_k4&dgc(In7XmFQ80*bQgpqmof}1u zi@$)}?rCa8wEg~-6&ddcUyiM6WV-yf4$%wYhOkSYQ6Ixs_g`~Js?L|J?!RW+C!smK zh?3dU1+#JDumbRwRxvu8_X!?s_9HF9uxFu;KFhiNM)26(=Jbx|P8!M=GxZg0Cq^<_ zC)6oHftZh~Qfu>Z;G(1koAQpAvvieI*?npGxZaZ!zKU67jSW?`iL6-GqOsCt&zm33T}K zr}sAi#VF2gUt$dyUg6sTAjnJf=Swj>S7k|8yuZ^BHP{f!1NCGC_@ogUU}OFlR&wMY zRlUWVN_RNi4)+)7zsbv_|5s?qyp}LUUWE4a3KH=mUZ3z$@U1$Oaq`acx%6_E$H#=_nCU~#0PJA1oKFBQnz*HXYI z52Kb~+fl_w{Q^B%gIsGvwBhKe}a;2f*{#9%HK zPrmiOX_)S}tR{E|p+@;wGi*44zQ!y+~GCoqTf8(OQn1yc^iY$Uq$gZn}? z%;Rv?qEVd}U4BRt`OK*3v@Uby(#bohlT`#OLHYSPFZ^1+FksL;ltt}ASJUVy#%=a=*rv4r_dtscn4IZ zV+#oH`QTn?N~%)0l9Byi*^%xmf~WF^Z@6*iBNoZSkS?joZ)WeuT&56@mwh&p+No>5 z&ABnN%<*rxOwVv)d|~P*`b4!J8k2oBf*V)b=-a1&i(0ekY6pm~~e^ zqa|4)w*ji>;_!j;hqKH+zz-Mww=WC*S6`+x-DXp0EpXKkQ>DMOyrLC;`}RkU4#x<# zV^1)-yiru9qccM3Gi)tu1NvDmG_#ZyE2o~zfp^H`DJZCg{8T1cY@Ao!_s6=B0Yl)z z0h|*lyikJKO6JE_uM;LxM-jW`PYuGNo@MN}=II5VQhUma?I!n`f;y-7cSQgCD*P{=iSGL=#o_zA@B^-gj>B!Ue{n-- z^oMWS@#u?L>3m+~l}d7seg5DhXeW+!mmVxjH1OPLk8iNpbqxn%&HG$zuF>7)t(ihH z!@3RqkY%J1_883=1ykg2VWj%`% zTCI6}zW1cC2ZaHsk)Fw?9MZ@0HlS7G2ck7BlzQPe(B*eHH?k!>R1*t0@-0#N0jb}IU(15!=R z)lR~Vg|9$kz$Hw<%ztJZJ(ewo^B*6zl)VuKLu%d%G6vnMh?tb~2R=YP^yiPfO*=OW zkeM+2K9Y}uHS~JGX~qnB;0E4D?ZQA;5^I>bN0yM@%-st5?a%wfZ&$nOEzQNe34r!3(Jnf0Iybkajd$oYr>Q0(2r8 z>bVMDCjz3jURbC3-b7jBvSEsbl082Q`FuIDs-?lv1U0^`Sfktt~;R$|j)WquV zNjm&20N0FF)%Y!4>-Y%=fPm6d_5TC`=6&Qo0BTXz-|KZG`_lV36xl!udNZ<2rB>lr z>Y_AcXM>*!J(m;(n6H1+jjKO{)zY_WCp$;yRd`7$pn#MlOTnAu(QS(UT>CRVUa#RF zL~jn8cdUaiNQ3S>MiVS^!;EmAw|wfWz}rZ-yi;`9kE&<3C}=H~6-wpxN@Yyk%KGMW zey0LE(C(j5#Tr>qWAZ-sa5~Kq_{eyZ-!~6>q@}=7)nIy)+BkAMmOY8Mv3v`>tu*g$ zjtli|QAXHam;ST!{-!Tzuot*|2(?WtJUrqec|hu*uKNlBeQP zrVyhR)jwbEuHLm=Fc4s+BZR2U%Yyhiv7gqX>KM{G^ncQPU#fvzw*?_$;nVP|(qoN- zW3K&rG@l|S<=hMVw~jqHYdajiHMA?sFbf>WKpYMZGn%yHzR4)fncBJ4I2Q!o+dtW` zskNgT)uuoa9+s^!I2B(ogtvt7o!ScFYBV+>QDUG;J&yA&a&1sf45Ey|P?m>g9{1 zz9jz*hoezRRu)&h)eAfG>y1>MnOW0%%YNXj)_Q#h+JVj|5}F`8?Re$cGKx zKRmbURkAnE8k%PIrd)MBO+RbaHcjbJgkO7#`;G6oJXFafJ4e{>1;!dAO7cB4G%8K4 zZS$OzjnjvB2~63fU5zIevlP3tN;VV{CE3{TlR41qh#^csP%ALi<$z!}9Oj>?rZc`0 z?{hpAg}I11zT^L_z1EgNw0ax#u2!PMT-zh#Wk7d^W~BnU=5tw$9xEmldg;g+j+)p2 zWMT1=7K8ADAMT?Lx%&;?u9y!HMj2dc^G}&9d})!G?;p1 zxB9Yt>!a2(m8DzQ6foyQ9n&}cl88xYVDeol@pty9FgDK2a>F+tbbB>4aYYF11a^6! zxs;18&a@e*(toDgmEQ4#bg~Y~2(kF+(0QLwf9+4SGC-gCIZ$pk-Nx5|W#zPl782)K zTdF|hR~IJX?2ZJPIyN>19m8=?1BKWD??<$AD(6l+*7_V5D)*y}G~#pQNv&c^cO2O+ zGAuD#{EC(^LOW4GC=ZY%`l80FBI!|dV_Ya(p?#hk@th^lK5BA5Db8wVTODzeo^}n* zLq$UZpUSD}2C>+>9dRBbsTe1PL*A`W2W2}-W@hCrOF`N$d)sqfBr*p=%=KsZmG5%X z5eheMbssx$y>xE1_96CJ^CAT8?Nj9#)55_y)Dcp1QVSZ6F*Vz-U^5TOddzq%w9&+CpR#w5}%LQ>8u_pn5s@h`Dwy&y~$|KRkF!g?h2{E2} z*L7-(+~$IN5L*7N~OcrrkXxBPWBTOoB0*8beJgkwD4QptIFyg;KRyC4jP~ktsJZZ zWP|Ack$+Pm8U3dN}(Rc>N&k2j4%w}VAmF9#BP1b-(ezu(OSN|EsdK! zVWFKlIkj^=OwT@=3P-Q5d#|2wn&8~k49^Ps$vp>9Qq08mNUTmJD^;^B8y%+gVOk~; zAu(mjEqywQseI^4v~W!nCEC{6rftp5`m*MAc8XkC=id=5p<`_FAZ*_yDJhsoo7&vS zj!Ll~PE(!%cSk#Et3NpI1OofIumg9hUSwtZKl!+Gmmjszw&hN^wn#SE4K*RtFwvGIw8wAby3w_tX0LhAYnH|R_faO-& zyB>y6&MZz@6o; zWiDfXsUC*-mdzsb=7RC-P%273KB~;FRR3+j)Bbku3L6fvCtmPn3hcR85>aff?&Qv# z=;^#+=b}nQyx|vR z^(Bd!L>l>)h;>z3Wxf!kH9Wl$zfM7S-sMDbhV!y6jGcFA>VJdwhb?Hb3c7zz`u9MBi7;LQRFla)j8Bvsd&@d5;-~o%;VLp^vfD@s=iN+_f2}HdjYRA?x&gv z)HHl^?(A;Rhmpxjn$Xvj46QXT6?V6n!gyi7yxGRtio!(tn8(#w`$sX-hP{|++g%0X zi?9Gfhn2lb(!H>g(!ZJQHclTk%NK7yzhi*-Sh))ne9f{`Xno2xo-97T;riR?d}|T1sk$c)!lfc^ zI@378uJ?}Bkp=7lCS9s+JGDW5&vfF(yXJX-Bv5Pr0{W3?GS?S>7M#s5a?=f4CRJLHC(Xn<5gx7h5!pJdM3AO9dvZyS-%kTn##c

    mE?I*?vRGt#fuSX(q|RanZ+rN_z!_L1DvfVup3#a8 z9g{mYO^@TXlu86if)YV|RIYquQr^#>DeKgMfEZR#cCWVg=a90x6&Izc3ZZG?JG+SR zglJ;ktfgqUnYqGqO_+*Xi(c>ElV%?akHUphcIpUCTsy8$V!i{*GPMj}_vJ~{)=fkb zS`MpRg<*>p4$iCzf(tBAWooRZnK+U`h~|-|gkJlfiJiu5K7TvQyt=rJS51B+^=*cQ znb?R^iYjZxByha(Sq7+&R|N%i0iSQTRNK==b^3&Qrc8*Fx}Z(qNOQvK-6$xg`&yJL z=xIGt#+=rEoedLZi>q<|{q)sHR?{dCn@{#$9?_`UO|~1+DwyH-Cm1YQ;55Uiy}VKKFcd1SRh2L;sg&gf zVni8ykzHVpmp3T}n|}zAr=R&^6Vmw(UFM5v6YWkno1U`=sj(y}q7`dFZ&91K(lv47 zXs3@Irz^M#21n~SGWDekta~wK^L7l!QrA2yQshPyIsUAPC)Z7Em%8+47Z4JI&^|S- z(B*!Zl2YqEw9TLKhdWPWwsqPD?yBV+icmFG80?VKpn;Bya-C#q1VnrM={`dM&oqy7!rb7v?z+aNjNpqj%MX;vdPq(RVKC7(@ z0_dS&4SwX2X;aoOR2BzHQ-yzMGyel`75LSkt;}HzVfhqyd8+t}54{m4GaYQ zy8o!a5}R-7vP#7i^KH0nLqjt}U?&bK@|}ai$QbecCjnfe3r6G{S|uwt%Pw+I-}wel{%Yl_`X zk_wUE!>2|eei?70hG-9Y(CfJ_6#*)f_t~4~oIBLA+WG31wyhiTYiR+Km;n@U<`fP!NkOvv}%f zx#e$ZzzozgSbYQBZPf!uc1gw+WgKN9A9FlGZU@Zna3#6TcaQo768wqvd~s8Fl_ah_ zHLpa?&9t@H*5RoFc;Xfbm59nn_|BesGmnQ1T6#^3F1;G2`g-+Z2`Op<$()f@{DOgN zU}~$D_eUANknVfl&!=w0+*#Vp>4Oi#JxUH_nN?Ukve+C+Oeq7~Y?S4u2L@ELCN^uV z>JxS0ADH?b+`LNOK-GJPDcWbA4!mrF4P>3=UqmPGiURtFgHP@W8WNs)veB9f>=ncn zS|v$QtI|RE$(OKX0O_&m#ney-q-qUQ9|B^ozd{N;EIvj zi;+8vuV41UG*2mOwPc4f*~tdEA(!uo+cDzXAVV;qf^uf@l@D7o^eu2Skm45ej*p9SzUbq7{6P?I z->)g@lGjf_q@c*|bP^o&EilMO*vjgZEwL5fah|4eQJsJU3elJ^Xs+sJ4&?SS%Uy(IoG%~AuDBLy znj`gPLo*P_g2j;;Abquy$SNq^G-*nLb*-J<-q76?91{g?vlo z+j$21L2uW_UZ8X9{s9$mfRASJhOYah62UtKglUJW_k-v`?!8v#4kxrv*Wm9Ff8DL} zHlbij)h(lV@b`lW$f$sRNq&vK{-{ua+72jjxg|)bVu~kA>KPX)f~B2t(pR($>aOOO zPc7g&eAFW*^R->x;fss@oz5Si^0I&5Wok!L_6=aiMFox2pM4Frus;(w3V2ncFPvv? zuF7pm5t#)Ntu!fvk(>0P z0gS)+=?|g6a+W~${Rl7J(yfnteOuT8nqB;BdsN<(engLFtngdAM$Z~;QNyOcr%^{> zAbbn(Vm3{}Ac`0(w{NY+M^}^{Tk+!Gt-IvCc?o?G-H_e0G+Cj$gHJpQ`3zn+@ko{j&%>@@JtQ=S^P3F|fUi8AOxD78ELB-^^`9#kETBkV5urdsb>B|q#kTGugdljXlXwjPjpSA<6i@+8>@q#F z`?lnJq?P~VjT0V+oTTCDz+1@lIOg_gSA8)HwV-uGDuflb>AFcCFYPa|p48T{iA|Ux z%NiMxWe*wd>6$jd1`#jysVgG!ANIvAI6-fOEpp1+7)!#`MFnVz*r4{_t4gl zU$Pln_yX63r7mQ5XRnsL_L3Os5|$S55;Y($Z0kckNnYp$}^)kwHocq%=O`s z@1T2xk86TAV4n!DHJ|p?Kq1$ks`i_Uy7!Q^*x_5B@4Pxfb7)>A{a!ZtOWYONSUPu# zA?^`FOG_h0MR{ao2TlV$-u;1<+=SnhZLd6!xsI)r-3Z-l*C^k=W{(m(tf~POI=8dO zh8@xsv^Ej-t_9-maGT1nF}tBX$ali?Uwk4_8oX&9kDrgQ|KT*u)JE!JRV+oQCd-w= zx-&yohuf4OPwq}$uof&f#SbDAb;af5KPbw(f9x1UlK-v6`iIy5$0tM_(#4HSp>Z1F zyRqXu{`;APckotr@V0LqrSc=Nijc4a=9bCD;or*+>IWhgs7eDSp_HbLf4C zgRrnoRfXIQRQ!hYYOo{Gtv+Lv3;;~bfoR3wRqHOV$E!xt=WdpD`&Z4}j30C+?WTB} zdDxfk*y_HEL%;Zbl?c4tj&KRXt*LUg{dvzAVMutuX=djtL!f=7T{nyq_gIv;$#Lq1 z9C2sUKp_Per^tpxqt#|ov{GMRko1}Gz;+(?0EN|E8rgrAsLUV5S-xUI-TB#wCSHM4 zy@kaSSVQ1|F>DG-rc}c85`zOWH}m7%x{-6m@JI{ivGZlfn4<~4Js;IIXukF~@`H~J zR{zE(aP9PEka_I{aZKQUN=?IdY{KJ@7M5A*n>g5uFWR`1k1PFrcus*-W!i3 zG@qPa8ygQFo{XvTo0RkA9x5iDJ0rZoP(RziX$FRd%&lV=^>78AcDzPyZX24mT5Y$t zu*Hp@F(FZF?X8Z4{C5q`^kBoHqp^#yb<$1$GzDhYZ-^(C$L?%~dhk&mmMSV@>K8d~ zOgtTHmh=9>hmqf2^>}}+_M#cZ;;M>*`tUTp`qC1TCdq+K$Hx=~g3nIb3mS9>&&M=C zTQjL~lAQ`x_myk|5$bVb3z%iZlY$r5Y`^<$cXR|cZ;U)$RGhwj4Qq&R*jAjx(Sw5tON~g4EVRJ4!{HewHu>C`c6gD?Kk&dZlG(3rSBGWK!$N%}ZH&{{f(omB>ZDpO(=kzBCM}W>p}V~|h@RBlHdTvzDNm;{rgS5QM-19b)(uXo_V?Nn9QJuK#^Vav3s-6in4%Y1tgoO= zdGpS0F-U3kaWqbh2yqPYW8|it+*%JLsG-s()c&feOarHtqu*BKdrjP@qM^7?TWG^r zUWZepC_l;z4YcZ0Em?hQ`8Z{?BP@#|2;Fy#DBrS??TC+g6}{?&z-lYlCe5SLHt81A zyqdo2Q-7DMB>3@cNen)CFJq6USX=aP=ohHy9<1Ln($jVhk)WC{R7lLPZJgD9XHb(D zE{h|>fH-9sfC67gW3EWO! zZ#+C{LMc0WFdh-n8QqVLiuL0=sP$SD@uukdOAmM()C1RK;18JRsf+Ly4 ztO=H&m(jW@3#WfpKyo11|%@R@frpldoqT$K-r!`RO&sJ4fD^ zyKY;B9XRFfi(ZnOKUw5)} zrHm(Zimb12Ul8!8J$OOCb)UM|oM zMMrk{F}k#rFSRNu5jSz#ZNEi_%ms9iz7e-5cI9n=jQBv5Seekw;YIt# z;1xf3eh-ka$*q9P!2@Bec%ff$_f17+=EG5YrcKyV9@j)qeqLPmiJUEET_FVuIq-&? zy9+RnCgy#oZD@+)?~FxRXZKX*H3|%Yh|lk?zij8S6SB!(f?bpZR$YS*@7aqU+}JNg zY*qT2m;Qj_PjjJ|+R?KZNyDSLcyV^&(elZp4v~%DsF@VX;Z#0>4ZvOkO90p%k#2~u zzkI-6J*Dg#db%^c(fZ0OWfw}oOBm}aj!yR1_=_Ky-2jKo#1u3ATEQ5ja?Gtf4ca%k z>%P6$t*yue}73n-K*h6Nbv{NKTE1ma+JMid`di{2_;X|qf+w+X(K5GimfSdyp7 zscW0W7cp1HU&4RUC{!h6M~Uv9b7me2&nZs)t$%SRk%ni~hf{)(DnN1(|3kIkIuRLM z1ADJdba#u|N2y`G4*=(I`wQf`#&p`@a@fU)XdT#~b$9 zSSrSy`yi?U9hyz3dv)5ds%u=dB!)`LB(6z@0~cXB_x*Np{ahn6C!M=Fc*~U4*3NCsfNFStbvrV%I34y=}cJtIw-Y3Z&@gEeIqrHXO(#ri3_d|O3CH5z&F4=d_4Eutc-V-z?QtW)s?DTDW0w-C* zdNZJ$%wa4>Nh5Rgg6_aN)+=nOQ!-01e(0d@+vsrPdRa4|hd%&WuUs6bbXIcwXBhaF z<+e_qT=Wb6mYA-7Tz9A|*gBkU*`VMY$y4r;U)5S;1P_#wN(0{JsavLuZtwSJ` zHkQ?rN`{8pBF;`_`tek-#bvsHSS)z!dz$cA)|`q?OOJil8J8xOG{xHy?Mx~S%uh)U zEzdfwp#|dhO@GcJa(4`a=+_6=x54u~w zjk(C4NhKEEekA7E#c2^;jI~O}!WyCpg>!1;GtiGFx}5jd09wP`1tAB7x=|{R*GKZg z%eDL|QYM(%3rTk<2C}3v<$_PIhvjPGE>&9t#^#v3;+N$p-wbvRV}Z8)6{hRuF^oqY zxY7@84$Y~Uu4|b>WY!~xWJ+4?s%-%;o^g$*i(JHOta%d2?c_=5dAs)Z+PC|gOVX%} zGd^tXTMxM^==cM5W%5(H{oGtfo5@b!k_Rho#*u-d5~kC;* z1hsb@vb27nQyK3DV^VlaGHoy18=i6#P(#o$YoUMJ7hqB&diBl=CiLKgg5Kxu7Co#k zDvkexy|)aDYirYlA!u+24#6P=ceg-r3+|Et!GgP10)gNz!9BRU76fdZdx zH9dV!Pxsq1-`Df6|4{6zZENkl)_UZ=@2Ayx_0V7-`e*-_n$s(?O2O4-3S>`&uqkb< zoP=O?E>sa*MO8I>E>HE%RXGd9{4lkzp9&F8F9j*pG{-^<$(YGhYmov~Jy&N5LN3EF z*iZ%6odRd@uxuv&Lw#C(llf)J`Be)_469vHBe9+ww=$setKDa0-(THv*p!U@#5ad7 zif$Y243`INY^)v%q4*!aS2XM9=nO$iJ~6Hhkyhn$Wi2-iHE2PwuI># zS+=LXf1mtp8mTuBP8%J=POiOeRV`DU{ksSaB^&>c@e+Yc9P2>sfsEDZ)@PA@>(2$f z<9U2O{UN$v#oLjoEfZ_vGX{MXX6p&!uFjG0kA$1`qz~_4cmln4lM;WDHI7Dx1G~MA z+Ac<7gcV=^UJj+plr>}gF@T}SN%!FEl71s{rJtZC5%AAar~l?RH18%9>GpvG2L|!8 zc%6R>c=?~mrxHQ7@{Ok8RlQC5!tr=A0ZayDmC2cPXD4+Kfmd`G5Y_Ik4F?}hrBcDhIwpj_cZdlAsf3?0KXETe={+buam~x~4K?9=4=M9cL?_-KlLgN5C22f%AGB zV8N1yO@im!-sM&l+p*QsFA%yDeZDlX`c|!1=(*>n^#P6MtrOUt^NNrpzh3?h27b4+ zHedLVnJDc7;3s!yKFvr1=xj(5jv->*%x(YE%|b!&{_nh#Pcl1jPJsiwQxkvj3C-hW z2}KqOxTjssEE=Iuz);s5TPjx|_K4*$7|F=nd6B!w%GcuTDv&IyBe97{DHZA3%(js)NZ+ z{euNL{=c&z3pQVxrTx}#l{}&eR}7+8k)YPay+OqB>;3$1q)mvrNX=6{!hJtn{v3zU z1?;$cQ*z399s!tGCh)&%nJA;cWFmE7?RMa6!6Sv!sa1nQFKUc_68fK((Pml<3CX$8 zSPq@=8&H~H3$q?pEd6zoT79iiUuz~(dJ4YNpwS{i>_b?k|Ht|abz$8Q=B$*g8GszG zm_aZ!#EaV4y{*VF62G%;2h)4DSzFS8`B6gw{hqMAKkJE$#lRf?fa_Ho3rtL)t978B zrLz=9qjH8bd`7k&MksqFhr^cqA}3L47tdRhlj$GQC<7OT|yF zaM0c&^20b)*B}*}LHbp%!IJ`LJYO83jb3Q_6^QRmQH}y^#1g@YW|AxyTb95t&g4QT zF-Ztw_Yi2cI&a11-dK#iBh+p^x_iN2%jK`PdYb@LB$fm519X|9J*n-_ZYNEI^IR|K z;QB^BP`rdhm%F$h75eR^`nvA5n44h7=aE-z&Y~Xe_^kAxBUgaAaBX!pAY$$47LG}y zto^FEF@(+T)DBLS*G_V5(*6Tic2G$0dX`4KmaD-ZaCnEenS^1guU4cOs(&pTFOR-1 zXxOp9vC~B6fgwrc%@eJ*?oP7i;v z`+yqwv(AfZUg5Oi;CXi5c5PjDb|_i<7bBWbOKN+5B*_lT;qKU0CKHqh_!E3}7#NwC zSr`CN6+Ti}i-)=qyDhS67(UVOwB5!mSov$pK1mYE4G#u%m^n{j4*WyOVzC^MHR!8Z zeLI(|*k;i5v9`mr?!j2_bAT0zmWMRC!obUA$-1bqe9DCR5;dv$3&2@Q42_IaoIV$^ zQN>-+U$K2G`~iKR3JopLWxtIt`}k42DM7BMpG1kKmd~AU*|)3e-Re24zWmU;A?Wk! zo4VEjH7}OwgZM7@H@G}VY6UpCflqxXHta*PpwxDXFzdx&Ai0tVEUW+L;(GrgWG8o8 zohMwSr54w-4u7O*_#;BC-p@zs93ppQ>3uowUF2vi&`JIBnnj{0y_wdf5dED_N%l%o zdB-5b+Irm;ecC2l;BKAJ$JW_hRH+ev2y4X%|Eg%zoF=XBhy9^WbIUXGTizuAkn^v^a6_Un zAO&yP3Y2F6?V}qlkYkD{%c8~kn8@1qWAO`=2mdNiNGEK#r+NAVj<^3y;`}S9)C?9j zg;9*^b5hL0Vx0WNZTom0C5)!or`$!k1{^hZctYD0PxfICtdtpeQF?P&mW;wM74Lo} zQrNSYpza<9zM}z4<-j_XfED%%Ag!;h!TK^=-XxI?UyL<3MWM%Z`XgDL>D{HS6hxI< z7Ao(0&8I93HEZ@O_cy2_%*+$retzxoG`4mVNbv_8KvjZ|eju7xXpzAX@hUO*?#%a> zwjw00Y1p~{=GL_(QsSPPz~7iWH_7~?I`LCX6)|0IQ@<$3)^z&hbBdHLxIO&Y zw67xupxaTyq$_Lh!`)?j*tk1|=v?`sbQ@7?q)Um%Dsf1>1y0VfsC4EQbR%dd>YQDB zf`Z4W>)TP>^y0@uq5zZc8wYHy*DXjKN`!q$dPl*G;qIBG$h?pt+LiyL8V=t7JOw_7 zKS=ga(_K_{bCe6iXWPa|htEt*cG(nXGQ+HhFEUXix25lKKcWCYv_W=b*$v`B9+V@W z0kWK5vEL5M9o`>sJ1gSQ7Yv$TNxpu1c@7{>%aVs_V)Nik&tri_~|zH@LWT2*5K6nxtT}N^p zB4ctH;{x=#3Z7Gf+v}hDVO5{WirM4jCdKg1Aw{ojg+> zLvck#{@IpWX8!nQk$tL1F&sUqJ~rPF#T1_2YujZ$Y$nITQ@he(82ar3>vKkXo(UgV z4JE*z@+E(UxQiuS-E;$puULEo>m217fd&dZFVcUA)}60_*)QoY2tVJIvqRBLcEw>h zXKaQEN zXpo*zu@tr(whSM;FRkxc86(o-M(ZV+geg=|Mu^U^efiFM);=|cR`5hhs9dy788C)! z2h&k;H_$Q3(gx8-d7_}add~P>e{#=$$^7KQ)81YNK7R{JneN>HzmODDW*WJO&Lni$ z#e7%fDchCY;=6|dI2b{Obu1ll7-P!jo{w4D16)Obcu^v)cComO@(e7OR47l`V`pp4D6n|=APL~b3)L5OQ!m8XYzCa?kjDcqV0$p zl4&q#CUTaTj-|!<{yW1koCi?_W0S>HI5l)uu4im))tDxV4E3|v%BZ5+8+T2u*zwf^?Ip_YqZ6SXjsWzR0cT&T z>51c1i|MjdJbNVoJq~7#e;Ys2692Ps03JBxnds2QO8kVivi#=iZ5HD-eD6U{CmHJ>Ny^0 zmf`>)s2i5`C-C*{KdSO!cX{)|zVYQ)6zP=(%PZw+>%rRsyk%cP7Gm=!zf)*KCNRTO zh6Cz4{a3tZFgyor(8Qane)PD#AESuQSrX$6IC?Ogvy^MoQ7JxNF?z1 z`~Kp8Jy$lGrq(a{@x-4?qhfG)d}|V z6TV;6Jj@Re^ZgOY=c0&d>e5%}%o4f|IpA1moFfLt|lC{sHZ+{iD?m>JjxhdZywi163 z+FNQT@2D5zH7pTk2F32};@fEF=P4VlLC0Uui4fS89+`cJ+m-9KyZVHlaZkLy7X^1y zk=lxVF9ANJ2LR;aPfU9^;dab&9Zx_}Frvp`?ptOuZkE791XF*8cCDyRHG3QFjz{jX zV1txTONFR{dR|uGin5tAL;K3?`*4kx*@_eUFXf8Fb5nxl5plTKV-e&EFLs70G%q3^ zb>yl&YxaZd&c_o;p2|HuLl*AT;@%$R-tVe&+U9o00)k#|VjG?vnTIolu~{qc01>bz z^MxW`^?;jnlkLSJqkHGmecQ%MYlV58WWrM#E-J5V%^#yb0Nn}3p?6e#$ez2UOIG?p z3FCg&*@Jc%`YlG?g}p4o(8`*J_w3`dxZ~U2J ztBeHiQ|AIpKr@qAtF&;@@F}oP(Ml)G)o18~?q8kQhiuTFuhzT#TDDZ>9OkX4$mQn3 zD;EiyWRo(B!4^gF)hZo-xeNpltfcd;_meyb=j>S9oSD!I<#k7XWa@4GPO>KxcvJ2! z^&7@-80(YM+z%i3L0rN5{13RON%@Z(57?%0O5#8Bs}or3I?hb4$c9SWOQu1$ckWr5 zQD(}Mdpb|#-UinCZnNvnPdJbU;w`PMJM-M+7=(IxM0-*B-?sXn%SmnBm;5r80g7<+ z-qMPmQ5mKkdqVM3cRQICBiYVMY>X^|D6O976!uLfWqk|qehs%@R)Ee*KF;P>!yP^H zl^4oFHNrpg$lsWMfhB^By7fovFF`xomd}yV?FU7}Q%(-2>fm+f{%)PM^NfZ9AEcYk zD;itdQWqO_I@}<07phl`%fvB15c!qjwOB=PJ?wIpAWIAVwk}RNhI(rQubr>B`e?D< zJyieb+Czv!W}akq6GvZV*!R`=gpyxID;|$yD(K`o z<)CM8@ePtc;0nReA3#K-@T5q89@eqpLkb-;1kbN}-WIMuZ8*5uS=%umY^epS*7i(r zFH1BGQ@$`YqZ2^ELU!MF3DoqJ&8?3Pw$E>!tgtWNn!+HgSs8_k>+15|rnNKbios?i z4?>e50NkDPh(F+_*I>Yuc{Iyh31^+$ShZ^0ZSCZSEKl85l$QxTFH%rLqO!a+Oz76HCJ;bG+!ouGXjYksn(GSS~`$ zwENwVVz!;qv2FUJyGgUJ2nD9-z^%<;P$Ck(QQ?6y&P?}OHlb*K(Nb`8TKAlJc-AZH z{qB;K4~;vmyvgjLzKqc|tUf1P?oq2_@-LxHMM>PKb z{2Y*i-o&0;YcJn3TN^tguovHcKDq#BRx)iZ=CTL=iicv{(uR54R6(lO*)id~dZy<{ zY_{jO?;DNwL#;U3IfGwzTgOkxN-G}_??L*_*Iwn?hz>cQVTsapnBK~|hl=aMbYQj1 z)nPZ3G(ffjUR2;{s`hc0#2`ueWU{?OR&t2*?rw|ttZlu~V{uTtvu~0|S%H#5xnxC` z%p%qv&zhF-0KeJoGGy_oUs#83z*DdjZZ6Z|R79%-&}3})@$o{fO{5DPkkCNZrucl> z&jR-N>Pa52pQm)umgS)^{Sj~kl9DZ|Z#s*Kx;up8$+9HA$-%Biy03fD$t2&>j}|6B zgl^vlLlV}(C%}xzoUYX$Y%Sb8}~jwx)m<)v>J#)VB=`gt@AeD zvZm?)i2v5S8t^*31toq;1Civ$`Lg2|iXhIIQI2IrlXO{n?sea~@86D9Oq-xAagL)2 zifGOCPo|UVw8DT3(J*c|6=|xd5SmQDDg z5B74(a!P~~Zw<$RE#tJpX+q?O6Xn-VD05~QnbGH6L8$HK3EL_0f{=BC&fC`=8xz%U zT%yg4en9C~fdE%_?++NVER1(sT0vvaW+nPlUGYTsvvGPtnn%1&LmIu0huwi)V|AWk zRwR$@v%j6#uxhRDh;yh)*%aK|PuMyJadqeIQ~QGv_+GwE6!5FUv7s2z|8V-#y4S9W z|MaZ>bm|&JeqYN?{tmh1DJy}G?Og7kS%;55hAW)&_}hK(fPO1)oIPUbg4WGJTN0T6 zd!B?nL_|7gd?Q1Jk=NiYecYJVdxJXqP)RsAH(tCyOLT*4R3Y1>ghsvu z=FMW@xwSjbetIO%ZBNOK#4TuQ_ChN{f}ChzWNCaw_Jb=Mj#OBhbHV6va{M+Bg%Xb@ z4;Pocl>;rE4UUO?Vjs9S>|@MQKpJb_Oa&=0y5Jc2C92YhPbR@p2Nz0N? z4qfK*=`$>By~aW?yZk6;o}i{S&f|W2smg5^#mjaQu?`<+g;Ws|7iQD+*_7Y65QRzB z)br+ODdQh9`2SgVxS=o1L2d} zHe^6sV+>aM9XYTTQC1_HsAg`Edh>ON**LcHio3D|rrzm0Vc=#(?50_x2{j@K3;nE>`(V+*CP+xYI^XBv21L%}p zx`IVZA4KP` zYueDYp#jy+3J3iQ-oCU=17Sw0Fh$FwFGV-6F*+vpm!ov zYQ}dp;_2CZtN(ZlIZCtbX(C)>(U6RVQ?P$XsMDjR4W<=61VgDwW8-}G=2_RYTDrg@f1(UX!UL=Q9z)_$KBEt%zO$o9whfSm2l@rx(4@EMZ`ZKw-Rh^Y(yVWb*+>`p zbO);2aum5(zDaU^D5RoHh#;q6BDmMV;IdZFZ&5y;N-JNwwYIb!RPKm41Crbig>UWF z0EIu=T;eimdK)*oxGO*KNc+bP_8*Tcv$Giu(KLnzNYVZ8=KI#q#r@7b8E@I3AECZI zdT~iTC_0VV!Hg~vylXZS6_5i8o*Vx%)lls3rr~pY;da{$WRv4P#Xn#9w!yvFdW~W@ z=l?r$zNO>rC};AyG+MskPiF-PX6+GS1$rU!llG)0bjwHU#;eAyu6k`|GWK=_nO|W< zRJ`kAu6BOewS~O)<9hfE$0nIi-z3znNxatKl)63sq-?UERN;X9qpF^s#3z>^@~zz$ zt>~)ACbBFI^DRBx)|kceMd7+%Mx1Nw`m|&d2D)N6QQ+}2^4^dj8;N&WD$FE*sG1Qe zZD`9h2)^WM#8G6H->x~`E_O(~igD>9E>_D?R2DB6|I^eXV3{U9d+NJ6sz|-NY`k&j z6(IqUZuowzz=h3(fKn%57~ojPRgQVUTlxH+a?rLkH`)yQpaxV|&EGx`L!i7AWWSd{ z{O(uUO98OIccqH#w4pD;Tum@VSSl#CRDGIJE|!<&siEO!*A*3EqCw(2D5++47Fw0c z;>;x4tArD*a8G=ph5b>Ri`)-eyao825@}SSv?iyyU&R&t2y!E|2eyj!3sj?&A6tX) z)illjMaP5SpHQx|v9tDb!|qf^Ui?pZ4>I_%;gR%K8Yp>X%m z0Z9v~LoUn`U$DkF)Xl=yV)HYh_5>s}2XBBTg5i#3(JU%|-DR$+*d8gf9;m%+$R%%w zqk)f2MaPpu^1;#TwV!RWmkN`mG~K>H4c^{(%HVy{hNw|DUriPWD#>%=tk=7fNp zd!04wV8#+s#DLnW@?Z@208+3wf*KHISG0A$`@qwvb`XoYhL|Pb_5DPAbxg=*yxrAR zZ6L}bByRq3b@z2|d$(=cm|zO&8v|{3-A<$Kk>wWwQsxw1XR$i$ud`?E>@m~_iGy{= z6N0KnK74hW7FK-|Hj!JJ5N+#Y^rg%>)Luy*-9W*9Ua?VEHAyv*{ftBPPEK@OiBf+u z6PbIt?p!3P@4;B}a@Z?$oAD{zx7%OHn^Iu`HCJ*&Qy322EDqU``#x(dLp|G?Maupb z1_V%PvocYH{OX(+y@vGF1LRWQktRLhXP?zYsc;4kjOw%i3=JIgQoX&zx*j=+$dovv zaOqBZgw{ekpy z_)9bvvQSl?d$QyH;{LS`{eK}@NaeHUBo?RkoREP!kXpeMq87ptY~ve zS{?0MUGjRsySD=*gT-t8$qnINgax^D{Kc>HlVYTOc3FP!YT$o_m|hMzU72zq#OMc= zAg97wUl$NW=h_l^hnp-Nx^pg?=nmj%25gN-22xpAIG3oRq!&>I&X}fSGWX(Hfl*vD z>>uoT$&%_CKfLsavo>c6k3--b<`{&JHhkgv28!K-*9@67G%Ad|v3vKW{7ah$+N4O1FgE!?XisRF}tB>0G? zV?fbE5nXo~7R(r$u_PJj2!BV&}%&?ux&l;zN!C5ZG^@gBVS0(9*fG?B z5}VPA&TDrVKw1aX*(CmDUi<6k|BE^9H`p3e=C-?+RCU3DjkR$Ja8wzzl^6WE1IIOt zc>x>*7Lc@g2ZTqUFF_ZTM$f;%+g6j{qgkN3w$KIXb}>WdGtqXmKmG^Dm!G{O?JHH0Vn$P{by&DvdT%!k9R|2nQstlt<3E7a z>V*l^RwzucU|BSheaFNJh>HB}YI!ic*S4^LI{-&gDT z+iHvQQjNM7reIokq~d?Sp7>uI$eSTeK6Og*-~IXD{rSJf*nhvD|K50?_B1h?-M#RS zCT}S?>bpB$hk%51)e1th-4c%G0w>zj6q{_Zk5O2o*~`?Wr4+Jmajdw)@5q-_9*1Vxf zP4xGQJV!^?7*|OUo)_dUcnOYT0Rn ziLAz-vTG+mVg&IdchWZay~O;^33~zeQ&Y8(klbVnKBVGU29DN>3=$hSZj5B>mirZK zhT|#x-pGPix<1B;EJoyqeDx(b%@JaJpoIUW@6EIsh6 z_YHi9`_NMLSsiYunrhvgT)TaAr9EBJU~scBq9xnQkddVai3F&g2fv(}6glz5rN$Gx zJI-Lq;Q8AWnW9_0+-6H6!G>|H9Kny&41b+vK@n${$v<^tbF+hQ=Qa;Fm(YJ&G&L~2 z38h2YWZ`Q4y5lTJa>&>U5PDLNNX-n>+-B@BHbJ#NzaKRzHhLsS?76R{IT*U={QFem ze@d3}1>*Yue4W#BQEX2Bf3|j>5CNlZ{`!7rmfe`YIZ}^wW586`95++iFZEA=&88@T z*H-3-b!-C3)n30Q;5(*m$gj#3SipB$(&$73>Bmf@CuPvUWFBa~^bfdww@u!YwYqs| zBq{&1HyHNAFsayXBWa4ZWx}vokH;%XgtcwtW~gLvE&IiPN0jg&+60!t{2p^~m$ zoKDDo5+pvF=_l>YS9rcO#!ft%*O2RalyOI-YD?2wGdJl`XF2NiV{C{B?a9+r?}xYI zdO0$r2XArpKENPc^?0z-EKOC>Yg<A#ZZGgmO+e!(XEZvzXGWY<~ms+kE8WlE!lQIME&I{eeG}p zVm5B5OA>S}W`$nmC*%>>qYCiEH)~fV=y>>Sgp2ZbCS6G*r+E~s zerk#AO5Ft2b)yduC|NayFm6!~3ofg`y(qSQwXZ|*x^9O0e755!8!wUW)YPGSZ26X2 zvtEIRQBTX)E?Fkee*8zs~9v9W#K-%>5V*Nw7kR?jEvezZ?&V0KLoCmW=r{~Rgz9;2i;FtOVyoxGAE zsHnn4Q^(*$P;Z)%OhrAI_7ciGyy38FDpq-oSli-@!T2wKg$UE}Ivx1Ug%eAty736UF{MXwch zR56I{LSCD{S-|=nc0zNWYGd;1#*SNMdM~wKHPb6~Y}Qzhlo;}?@AgS`DElg6`8^cb9A%`}9#$X1?8P|L<2a2Q@%1QQUe zq$y929t)W5D2;Bu;&&{9EiNymRs%$f3}TCS#8lrh1rJT}bu`>Im<3qa@L2WbdBYWX z+L~(l(mtVf$!jJ1>&+U;Bf&i_n0-q#W)A%QX!3(+SebBf7Z5znZHl|xUEGQ(HII*V z9^B`9@Dp4~rO2AEeBjVO0i-IdwiwH^(5)I$VKs9)kD=3_2(MIcqiILccXDD*$-W`j zG}68i*vjNR_9e?d6iN(xSE-WfpM!XUG_&MSAxJ}Fp2SJL)I_pe@EFA%gMIY)^mS{$ zqCi9tXdK%vOcmEKgN8qfcrRLMd5p80Q29Qea~$vb-=v$cEEhC55hBCI&Dr` z60n%&Zk|DwR2Xn9kXv?Ci2q7iZjihI}%82=X|i^9(`=%WaK*b&sMlaSdtB5I0GMDQepRV2JI2aA64pkDqIOg$U$P zD%dEAlPuJ;yrl-rr3=R&Q*PUPf+Vv6e~ZAxUQb4q4$J1#Oas}pb0oo<{JQdseq%z9 zrJLiqDQmpLm%Ih}TsR-ZhZM#ptDYAHWvQ}~nVe-_X9ndeW9|Y>!&S%u$LQ-eZcIUA zuZ)C7POnx?xWYGHCtsa`q<&@J+E1XK8xUp6$ZaJSAt{h(0pIS0(ANlQ4ZYvR6d%`% z?OGV{C?4!ns4~QQc(67-M>F)4+0rr6(sm6t2r+dFCEO%lE_PjE{JD)x^k+4dr?rF~)f^CFDl~M*XFMVcs>_ux4B{eYCTg%Q)3bGI6+vlM=kBKRMGNGu`QB9RN@sRW(* zler%-Tn}7yeuFNBtg>!#0{?)MVfA}5!O^#N*UrMf7WN^TWYsIHFpHB*rGezh!!a2v zaleWpj_i-XLV;YnHi1k$|5P3YC{|{h8IrKG9@3=JU;CuNxje7%^p`u&Q70!t*-*x5 znwRsbmkM)^rrL$?i>+;aDzbh)>RzP*^#gTO@0Ed`{U1|M%Up)w4{Q+G79&VMEEP?S2@sV+@ zwEE-$FiDz(n5Z6A?`U{#=_V_*v{ug~ZapzH^Wd>CzIzfWq561vNuauw>7sphbB1G8 zT4JDBHt3F&5wzHrv_$nq+j>=SMN9KVNSGlY&+XeAY&%tyS9r6Fxpo1ahw_hH9Vx4C z8BABydGdlzhJ_(J^^G&PvQH2Y3xGW0`KVUKpKSqW@l}v&R@nzoI`E)i^(ve$ce4)Q zOCu~MyzXe!B_h0F+g^DZ=de?kV~@ky$dc#inJzmaB~epg36j~-2#^r{wj@q{pjzhOAcBr>eMA-59W2O(O3E|UW~-@&~FQeGcq%M)j;wT zE?&3~>{Z-2BC9P^E;2e?C2wtyqP0Z}v8T};BL1EIM)(1<>D4qs*o_V2!LvK)e1q&w zW%9aL##(eidrPwewk_YCd$qxVTQ?b&XOd)q1K9ICO&@bJ%oS zOG@lj3Gq|yVqr!O&koPjYc4~+V(h-`mCM$*)5u9@J!cc(Be3+Ypgs`c@IY6)|iJ0HUv8I1lsgugtdCDS>DSYRW1Jhd?UwxkqD60P9Z%O~Z zspq==JE(hC?c%xD?X{(O#PruY>AZ z>-0oUgpVc4Q|B)dUx{5g0yXdSuT7$p z9V+klRBD1>;l~Wq$0dFFAsiEYODQIfVCY}JF-kKmpLy9WbHUwZ>CU>QmcYKqre$Co zvnjs9NeeF@U->42NbQJdyZnw7gwN!|yZZ+mKTK()>0&;F?eqiy(`9>|U}PHp8p7<6 z({15gyvkVxT4v$@iE~t2?CnfnHANxOf@xC}LkPN`&?;jFF-}*mChB@H)u~2ouMzls zhDhvfShp0btu1c?f6&d#?&l0rq{QKt+-){h>A`h4`CjAdbCy?-Lu5Pc(Je)IKkE`% zVb+S?6tftiI^&PDPQSmBQJL~>=&=Ka%&762$IX2T&?#q-3by>F#*7NuDE{EhzL%zG zfvALpQluy3m?a!9`!&?DDek`;8jQ_rUn)De&sWQ{e#aW-#vmM~2BZ&AzSTP-&-R`$ zZ&Z|)9bPWzt{5m067Pj=65BIGd2Vm$`8K5_nB#bqtOsDB_FC#$6Iv?Iug}<>=FPe` zwavITsWRg7IMr}{p^qL@SzmXWm}-%zcZbz4bf;=(Zpx=qSrb>Ie#6Ie`CSBuZ3;)w zB;ruX7W^o?l+EWX(QwJECt)l%pMbH${~G*Te(1K>R7crq{a2$wvv{LxGj&5%6jUkP zsm8*6sp$J}G2a*tM|gqpp#>kRm6$^@!TB5cywu%O;+?2{W3QwJM@X#-cPL4oG+Xx@ zq}rLsY0w7G9C85?R7yEu6Dd}+D}Sk{j847cwKhiuS{z5`jaa>l(LJd6-g{WJeWrps zYV1*sXo(a(WR6DSOU%VvrvMc*ECI2_Xq|J@iF$!@UTmEGGNoUFBd-(yc;gmT6K+x$ z<%%|wr)gmrpF2`Ruvlf;>QS=VcoC0uZiF=HI|p*yzOV81>bzPAbeSmX%F213(drW- z8^4B8<-<~Fni|43`Iwx`Yoslfxf~Y;2D`TB(#6o5XWHC~JbhH$B2O$5UTE89C6bYQ zeMojFitvtMI)hRvI+&G9m97~a=sb!-IYyn_xVa(mrLtX3Fl4b zz`NMBTr6$YmAZb}UEUS*uj+?IZZDJ$xcv@rGvp)3NzAFv1=ls5J)<<%e~R#9&m(v>YiGNOE~-xUt;E_fbTbt_pM&e6nt|__{u`b>2Dwud z(@s`5HqPq(2iu9>r=$j-{P5#D#5Vc##-FsD2tl9lo6NrT(=r{7UQa(l#o>;CaK1?> zkc)lER^-Zl9LU2kZJC5_@ZRDj*uRTyjf3ITJ-E+Dlkagi$JXW7IO4i|L5v+YX;s7z z_H^7};ZTvis(mDT&wk+RZv3@ph3e<8RMWJ-TAtH|B$lU*NawmII>P{?wOtkr_SOvA;!XzIuHk zG-PDblK6mj%^RQVnWc4p9%HT1OY9*J^0C8*&?%j`trnU^_5`c0lT$=(jOyV;kHCo2vb0`ITDw`ZV=+sYt2A%hsur(WlhG*y86RK0;U(Ma>GJ)S|@FMB=BT7o{|W(?IQ zni|`xrt{bJiJ5tr`SfA@+yHX@L4Q{^2k(R+|*jEplKA-VlpVRo6)nyAA9Cy0QE zrJlC(3*CIOb^Q-GobC+}E?Y5g-5rB~MHFv z?Z;pTu=9^6hB44$>uObnamhK0hJ{UEecOkp11zBzL3!4$)6i}=|3Bc0?Vtu_V%1o` zJ~tYKQ1e~n>iw=Nd(ZK9`#bK5Fof0~Yb!Ou6Jp38zpTt#(3N4P9k!?1m`Z>fP=xnJ zGPDj4d4l8R>mv>AbI~%s+vtMBxwzBGHTBq$aT>$p*xBy_AshmRCyrf`<7C!!E@DOpw zu&3ORlJAn~Az~h3zK-xMK0}woKGI}XTUVV9x zBc9EW3FlMa=A@heoo_Q88|E8ZFKd7ZL z8iSS7%#23F-kW7)XQpqxcEnc7LcLk6=dWvMscpr{OWCbc44os?)?(D6VKZO@yUCGn zN05uN1LgK`t((Igw#xmNV2T43tiFq+3}}yjt+KCVI7yT}VWeH((G@J3rS2@=X(UWFJRwitcCjVt@iTr2WrBZnJ> zBs^##%HJ;Ej_Ru;CiOY oO=s3XzlQgvJJVM-3^$WEKWnd$&}%(ng1ZvSE^;d8JTa z>8cw$DbK8NRk%7n-SrJYsr7oXz3ZzI#d2%Dj}~z&N+_+kG4peTWPU+G{;k?Y}B*Pw# z;{3{tTv+2HcSdU`LsHm)0+edv2wm_I)JA|k@N}-GZK8w}TI-#%bR`WOoYX2eC>dlu zeC8xx66Fj)c@cfDOF?D#$xmCJ=fT0A7FV99MXNL}N5K?<1c6B*-HaA)??r{wIqXXB z;#Xt76~)Jfsht>}ntqn!BD#fUU9-=hoW%~kGvRoiRD)7))xX~n z!7)k5r6l0UvXw^tKnWuRgj-KQ>_^au-ix`Gq|Z}tSw4Mz$fEPMsDa<*sx`yC7@{UV zsCSA$%M=e;Wr!Y!c-X>XcSE@g4PFnw9SI%rrNxtfce%YsvKu$uIj>`4CRKcJKJHWm z;D)jH2w4253=Ol0wUx+|!}1?B*aK{ywQo}3Ziq6{fDE-~&kBfi;lqNoIIR%6CV z#ivY8G7**6?_`*FkO>Z5u59#<8~q1)4VVBSIM$!^y@mDdzq1BsJFD9 zM)F9;skTsfMs>QJt@Y{0@|RZQU0MG}dv6^U<-Ych4h<60g0z&hbeBqrNJ*!Fz%bO% zJ%pfi2`H&FN=ObJ(%s!4-QDAPTzjwgUCXuB-upV|-S7FG>+C<~n(K*q=6=5Yz3S#o5?W$L_P$l(qYy47wk`V4Q3DYXyCx;k-rQl4)#AZAfuMJ+mDp0XYDyeeWs zygtPa=`f9em`SKj_Um(t-P2a@CL>fgrZK&KD$Bt}o^E%_9Ld>7bqzB7XLX`r`|3)- zc^1TcplSGViH$>0fB5)wBwxRep6R_6`gWzYisi-={=93AMo2yRfnl*{q2c80#;ItJ zf+%jS$`I1^)}UQsZRnTwReL)=IMNmVNZ1G#>r|#dY_?# zKIieGUEeWranFm{+Y4~Htqc+rIb(;)Y2yqAGsCqPj&_>YK-}RY{tqkAp9y~&GrT); zd=>1>b{nS?Y=>7va(wqWuN1?Bo5)T&m>azsdGK^44vN29FUJX@0-ykE^Z-CoW9?ad zeQ@Ykjw~}Lb8wTv8`%e$L^aIJWT^HIa^ycK+OXV$j-FI=WR>yi>q0{4Aa6P~tKxJ? z7zB8v#MV$Kqc!)gaa}E|Gw+fnP-<#vy5NeJseQtpq)(Yzq)0XRTSBDiNI*KGCO|PK zZ8c%JYUA+&k#;Ki0m}h@h+%7n6)9=#=+%(xnd~PvnoXS<9w$ZWk_M zsUIjTIsx-t6=6-!7y%1FVH--#)1dpt!`VDDs8KAjSnx5P?b^T&VbSV@KxZA!y_dDa zk`>l^n((UBj!v5Er}y;u-&_|qJ!3?wr~+;GXB(ZIPl!x+A1j}TQ->V&ay7x}pAY2J z4$&!!GB(6hD5OwX>#PJXM1rE@Zb9L!uZ*dQDZ8!FOi1c7L{n&<>4Q_!K%U73Q74{mo~q-m$Q2N0-~nvc;yC@QZYa!JLWn83&JRLS@{j=h{>SV{He5FrTyg zCGAx_ibsukW_4c-OsOSOcH{<;tMb;F=wGcHK++lQ;+$+l|AyPAteOnfZzZ;+ux7*W zlUMnW97x`Hx>{~_!1R&%b%B$~U?@bVc4C6L&zSoqAT91xdw>BkWYYeSVZad|k zT0wiwQ?g9;ch2y#*SuS5gJzyiHX}QrgZjHG@;2-5zt%cH-h>-c4FwSPidTzwL@Y#) zHh5Q>R*V^WjiC`Ejr1?aSB`P*rAZC>TS4E}m1|ZJ=o8V#LM2@GUGFby*jZ<2LSx{;`TGCz}QtP^UG;BvrmPp~5r|TS#%J2on>{CHmF}*|a zwgZUdwG7B^#;vG#U}dwck@LfUimLB;X8RdQ}b|@C%u_^7(&YTMmXA+d{bX8QYvTcOYR5cYV626 z-OwCGj8lVGuCddM`IjN&wHKxa8K~qqrgX%F_=LRu%wjjh71epFNmvqJ7Z$FPI3Jj=_nME-+HdAcgO@WsSA?>YV4W;8vp=2-`=KT@ws zy055#WSfWg_!~aG6x}Xy>TbEPc1m6G(jN2h%DN7&;bE!zF*-_!-bH*^U976aukFKNO>oP;bShZ zr#CtQL5m>RZMn?W#aYftljy97RdUYSk!b%QXthZd9kFqtI4B!JeIGFae{Uo+v{P7U zMyNm6MD#xAMT~Oac3zBwSGoR;P(CY*HZI3)T@k9$mMv3=``WaEwc5ANK%F}fg5r@i z)CdL2;|;xWNdnsIjd;ZaoW!{CF!vF zrpA{D)tV;QNs1Pf}NgzT8#G*t{p4rGtFh}E9WQ^7~9H^=Y1T~ zYGU4}E8Zh7YADmm9858dTXMiB;6srnXLozU6u?-u(WVL{IKT^D}yy|rFaui zcRIR1=)XT+JF-N)APvoKW{7_$fu2e)0d8)xA54Ar(*`oV$XnNA9-sP@RTyGJ2KSx6ZpO)X0fZ!k< zD>TmHR`UUBWLy1Zk#8+C5MIj;{tkM9DS2!%K3|3dBw>J*m$HE5*VU6EB7JZ@V`+&$ zW@f1o`zB$9>tiMuCskdQy<_Uvh&&9%6b_PL=Ve^HzCD$S%9?1i;fG22dQUWYnw}Ic zRI*QxTlwn*H=+hS=ToN8-Av57CX$Q;;4r3UcjvUfxd?P~YiW{e(nzY*f<#V8Ymi1& z^{)|}Lm!j7rjixFI9ib+6gt>xr9AohWcJ8}(i95T;W-hSw<+CxmikUtxC~56p1aph zgH25e<-?@&m!%B3|}?Kor*8vhWwB9v`dP+**`u7nZ=;EzrpHkn%z)XPr~gR(UXGP zIDL`jq(ZfMAYJ#C@L}vYs95MsqMQTjK@&*}!<*VnrEe&!-~m^_weXv5IPZazKiEuK z=e_Xdj%#9AIQWba%C{qv-2D|Veic^AM-;2j#7?cM! z(A6?dpL;Vi8FT|>?*^lnr_wC13XmJ+cxe{HZ;#65VMM0K73Ndfx(s?LRYknu-d_zm zqA076QKwwYs?;!MFkzyZGc9}Jpm2)^!mN4VG*uDfbir4H?e-l6Enhrx<%$X7Z`;7U zdW8~wO}p=)EGZ+H%R$vEd3%dqYK(3~HU$i0$0@pH@cv=OXLPNb>5mKq12MuIT7cnT zJ7;I+>wAd|#WP|K>^$C?Z^#85BADiQYZypr7od%W9wDxq=&f)7 zZ*v=GhHQms)Q!MD_><2g|73ApqZ?yrcg$}B zP%?^Q)w}~A7Z?w==cw1t4!j3?JA1@pSt2WkBkMT|JAcSe&v4dXs8?UWltrCE*{&?{ z)bf%R0ej!~S#mpnhISo4VN=7v9y#npEyE zr)A;2#3NQ#tKmbVm|MTVDg=PB!rb!L0pow;8*=`;MhaQr!UEWZHqv1e4{zU)m7nc^ zeptbLpp|^y&~~b;9QIssiA|4q@D+!6=xjRwc=Ck3N^(WV{(|Y}TgP@wpA^zJHtb-a z3UqOq+1S2k?CZS% z+a6Y*vsLRD(1L(H@39?`l_r8|grnS3U(vOo)#OXTWW4B$QdJqTRuPD~#+PRlMiJ&0 zJwH4hw7WM__BiN-zAR=4v&gIUoqm@|n5Z?i4xWTHI>-TA^OGA*^Wda+v^CbNR!1yc zC>^6MCa+n1C%cqzpPV&7_=RJ6`FaX>_FWW^zi&f#L`K6Y!2XW*`iJ1tgT{q5KRKBj zR}8!UBh710-p6B{C!`JKBip7W^~F&Pd1&ov6zEc2T`SL1ZwsqPW8^kTKr=QISJU>} z`n88S_@#4a#6uKa^R0IHwC*Xy>7=V2S@&&IrsLDlGeQmjd5X+u7?LGv_48_LRU--( z5`1ZX^UG@f)=r(^}g~*NvZ9# z3ntCBG}eC{=wnZH=vZ1Pt3WG`VCr7mx{c@O$QY4AHK~|Vnj5{-Y>U%I!=e%L09C#{ z`#GiG2n`OH1Fc2bdKb?7NUU`&I#J;sCcQ~(Y4l2t546w0(NGy}-9g!#&VNN+MF(xP z)^#|O@FKLl^OcZN3$-?8B0vwp%}+zMCE_u&yT4K!)cw>zZR>6{ z1sw$m6{U!5~*$?DivBJf>_*ZfNlJF#a|v_A8f_TQ}avL36k13 zGXx4zREwtJZD_$DS2Bg)K@~dKKsRw~_Cj$X3TU6Vl@mMJP=$SE%M3TOik5Rk8zXXu z*CjF}7=OKp{`@M+uT7g8M1_XelbSaE@^U6`fl66p%nLhf^X~fV9aqxzmBm=scbFJZ z3St(q6)9Se#P!XH$P67z5s!%tFoR21OQxM@7tu}J+_O=tx5jv1i_~M4W)2uhNL`x^!?t$0Zg8}wLjiA9J^dd}mBE?~i~c?fOL*L5 zvKMT7DQ0oxd!iOA@rJjoOg$}L8yOE9hyUc9A`vtUJ(N~n^eH-eAw#Tb4s2+DkCyv4 z9-}wB0%*;h1|_%YFc4w7SEu#J`)St^iOe^zXupF7Lydd}egOB7VI*>lqqTzg)7@e~ zXywq<0x7exb4nx`?-{G|QW5vTvyU*>C0s>~VJF;2s&}!1Ic$yHP%YOVC!nlF>+h=J z@2C%)Y&^LHLKE^F*{^d({xbWmNTTk5Gka@E>DjoR8z5j5DsOymP9S0m%hc~%C9|!9 zhU<&iGP8J8JYK#uf^aVN5q{JIR99WS^B~M3ew|l}lu;BUpi*Ca+$HX+hyKuras^1y z3H%~5>pQ5R&?CcOI%~$INK6sR%G-`*Pc;gy4BV9J=-i1`8;?_34mUAi-P~kf9YM_Kys zx;|eB7T166EthVF#?#(bgFY9d$?MIX-jsF*;IWv@Sm3;!$g{0tMclzaxv7@$F3>VY z6eMB)WVIpVnr?7Uvdp^YX|d^3vAhPe8Lq@CYzjN``*Y@?73jKC{HKLu7homui|ox` ze*a#sOYgVoX#*H*<-gJAy>m=+LC!aSc@+xG@+7BA0FMmyzXf+sbYL4E8d6E72zoy83>v+uBS&(`}>nbjFQ3JE8(Ff!{JccVctj>TXb$ z#Vz>~@Gv`10tnqa+>F9~<24nu&l35Bgy`v(E9Jc@O*vWfWRi(jrnjU;OB|rSau^KI z_rTiN-yW+_`N_eyZta7*`hd@}XD;FHro`DZ{NJpe3w&jwlb_4M(<&p1 zy2XDnL1x71{6pL#k0Bo!n4n9>eGGsQK{e6NU-}Cc&#UCT&MME#Z5Tla_D3$zC68hhC?k?iz3O~pGX%F+O z4EnzqdUXAneUk7`b{3 zIBslAyR!Ea-q`VdPM^|y#NV1-nNC_676*B+@loxODFaHMJ$EOGEx>s&?h^V*`Xd! zDebzmfaBoA2B`mkT=oA@8T@GKH#;2c%iGssiFP;MtpKTB$Q2Y&6Vz()_`^BP$aBaj zA_#IGIp~w)_tV_%>AJ%YxS3?bfyHqV@R;#8gX&8cT%Bl=uL1n`|G66#O^MjgGe%pw zH_4v~vy+@DAC%;E;-Web&Kx?dWec^BRRBBiEgKZg;se=?TwSYplV-IPrqnS#46w9z zj2L^m3c3qQ7j;?r`0#a*+E6Wos;|_}2I^|ZpVgNJ7Q16Vtw5Hjld3_(!cnXo|A3;Z zP2paw-hn^{ptVxgfHSu-K*PFIXwgs>^IYq7*M%%YWaQl8q%n8IhcTP+fP`iQr4!Mt z70~fs>Vf0CA?B^u=LU1aZZkw{FNLjHcRHq3bLLVA%GV2=xpVaTN*}pem$D!A zbo6ueHj2hYDlhHKr6djapTJL6gSN9)0OEUq28v1V%R#}bYR*v4ymm+P%Y6KfhV_zK z?y`4Cx*BSs@y6&&ywO`K^XGGeUNYHW5q*Dm<`JcoZt>bAfO^mziwT+c^F4ngYX?k> zOlrn`f`i*{3Qm}7%e5B|Z^=PTm|{?f>&;&{EXXtj+P#edt%Z0QV%JA%l}2r;RwS9` zb>}vLPsJ3fWnvxpYWAggipf-@7IwE}!{_@?jP?~KC6$M-yA3%G82bWFRbSXqH81Yk z#vL8%wnp+N(6k=ir_rr(UP__vR=+~)om6OrPt9CBQxo#Bn-lZ3k-4CVr~k6ctEjfG zky>7)Z>3u>dz2r)VS_^oFP(ZbK&VZ_Dl=c1>NqL&$;AhRzj3DNs+%0!E)hu`MJ7`| zNRTyk!SHP-3Qta>-wSKw#vK?KuH}GLQxVs>q;CZbpPlpMsv|6%GzqQXbAGI@5^=rt zk(kvjk)SF2ccRcEqGYGBssr4Z&1juRFk*+S^|D0f3RlimqWdz&QtEKr%3U&4XR#N( z3kJ$6g5!7V>rl_&0%KoV8ARMegc9e>N+iCBq;=RT zG`I8HX@FpK!r=C0*QipKoANBMk*Ty zf@Fqg-NQV=Iajp#Wu`vZcCfWPlkiOwG{z-*<#??KE^^8A8fKBJm<#cED|i-;tVgdm zMd3EY&u}xet4P?+EVN*Z=KzLn^&>D&KFm$Q^k7Xq^R4i$MZJQjGInc^3aG@jAU51L zWzw;It~SDb(A0^gyv}7@18Xlu&(m;DVZJw<$zUF-rBxa(*Eo9k`=gA&nFk>cX1Lo0 z=bK!W-S(+;CAWq73G(<80PQ^QRSd$NBlxn#J3&)(Putv+G&Cz}y400&1M`WTNzMZ6 zp1bY}^hAa8bKFrEzBu+Dk!Y!#iHf+=uF)=MvbuW<$FI2%kL$4yIOZC}mlR=Ho2LWq zMA;v+WYxI1;kK^=7~a1`QlP6A>Y%#pT05q}n*&c}UZxi1N_%>8lxg}-0WUvxzndVA z^IL^M)ohq4$T8KwP_sTrwXPheyfO6Z5F-5g0ESf27_bpcF>HOkNMKM*k9AW3zQh)}Jz3^0Jcm_eXjc+! z{vIbViLv8Ckh`g|Q|!49(>Rg(0s1>mU|YU8Y$z^GXFv$a;OLee_|%~}k3kXUYumMq znhI4~M*uyaV^8mLYAt(EpE8wqL;!PA?Mv^$S1^$}xD$5-(lLZ&dB*zOMB z9pkFjJM|2sKz@s*kwvLMqWV_MRQ`sW>x?_}Sw1!G2UO1YG`tp;3@ojpke72`H(+dt zJEC1|e&?Y}@0@D36p6=ooRUJ_Xw;_pr=)Ce;nTlfrDt7pk-OseS#JLXCscfC0@u|S z5wSWn2n{bZg))sko<8C}Y}ZunTni&E*8=#p$aacORuGn3>qTM`tYc2|#8yOGx*p9H z-Opr7g08#qc?}fE?OX4xA_e&vx*)|ofEezz-k)QPRQ6sXJwDn5}u76S6Xw%&vKex@lRHUFPq3>6F(#)`DPp;i?xQ=|6?h| zEiQ;?_?%RxDntAK(#9+8I|yuf-9WhB%nlpOl;i~z%f@Qe>S}(DA6VuccqM%EPisDc z{UFyX<@-x}|Jg?J|HgIx>z~4S<@=!hr z<%y5So2so@koNj`iztT=-$Y4ZvcM({dSPl)6C^_D!o}cn#-F7sZq$7JtUN%a zsy>8Wf0mVfh?Lp>=?)n)2)EsD(<%@i$fqcu9fFN^xK@5e8C_HQ`BBxhIazcVKyB^U zE(My%-(hRfWvV>P4$jxM;=mIdEvr^|>b_9}7FzeXRE4aIYi2u9qwJs5)s3)$MMEpq zuu>tDE78$pC7|sUKQ#qZd^s|)TZ!FG)l>obQMz4290RpS=GF09;8*4x+kGv?6VOh{ z6kAoPus7E%>2eUTH9NtF(z2K?GC->mzfxsgn%SQ2PN6dOYFdVyqtbxaaE_e7#lz2? zP-l*oKrK-%udp6svqkB~&c<(JSr$fak&lP@$*lP~OqI)OE8Amjpia@9OwZ6qnVFd* zLk-%$@||?jN3O8|fL423sJL z#~o2vK=yq$nwr+_Es;k_h{plu>qk^A2anHguY4_Bd>ZcWk}LiUNr=iX@0W1Z?*d}K z^^W{O>DD3=4c2z}_hB@5gCr@VkgPtqgO#@`9T+K-I(=Xu}l`{W2@ z*yW*(eh0zXX_FbVb1Ed~3tQO*Wl3ltgo5``!l?6n-K;#FQINi>B85om#wQQnHyXj-$ADgceE6!Kjwm7Z(Ew0_nF~@ zCTJ-2U|!V8^N$WbLew8{NbC(?TBL#R_Lb*t-9`H_mI)CKJkH(}b@OWoAvYlq?utTT zqbvcDQ5N!K0%<#f>SNcA1>n2Z0^o7i&?|uv_2L!r=z-yy70>`w>xx17C~{k}xNc&+oz5v?c1%j!b4m3iRrrWM z5HbYhm!A<1t54JHjhn<%WZa4@52kpF)OMS8Tv1+LM>t^4yVS*D*#CCQ4IF`Lry|x9Zvi9l#Ay~6v+zNr@)xL z7txi`<{C;v@nU(6ZQd--`u1!OHL3@@7)f8qhUOe<>c|( zo{OSeD+f$DoNvNCbM2KzlVy_Q!H^W)$@}5rvd341wNNYl5-$LN9 z1xSs|DD6O5y9PgKG#aS-pD=?G zSDn6ts5e9sUZo$P)oMMQTnjC}Fv>nkvIBQ{vNU{9TExTxpyw zJMo>8)^E*pwD_(0c-#KKRubdP377rw5#o7N%YT5cJde=cNtWFYxR7lkPqB zmvIr*8Mkd$KTQ6XQfwYVTyAM zrUaQACq&fFXVF`1ulM_3+2+?OLSO}Ya!|(Xa2p%k?hZ!oo+5$$ta|G}X9|FI|1w&G z-wu1;z^(dpVLi>Ny0We!v048J5QpCXpmgx6)!IypHg zI<2iz7$Cc5|00mJI9#BMee*=sVy*S6BGG$)=EVdTcBL8BR)b&in1~y;4%TA-jvnq4 zw{54-ZlvNOig!HOUYQt_+DquKNVvTd?Ch6G7uj36oN*XB-GKF+va%)Z+X4CS#U`W7 zRV5MF-Lp?NE#BI2vCFzz9yW{FSo=*w7YHGlnanlPf9BZ#w>$KWe#7NwNN*&6ZM%;V zTq#Ht2oIW;DOLbicyR5x!TlCaRb1p_K^x>U$0l?>+=50~gxH0lhBO-}+G9 zdr8)d_KB7rL*9#t-;H>0^JE0JqZ^4J)@o6{L~8yH3J_IBi0UL#10;aAukRPVNjpXX z3JBdL?b;>sT-As`avkF~0%u3^ddbr?S%gsK^#@c7b*>s z{{E#MR`Q;Lyq5T=R=1;%0i7sJlij~4gU4e#RaVv11+G5E>&XqhTSCfgO6VG1NlCen z)F5L#cV47C@K|7uwg&mA^T(&ojUu3q+_Fj;5f8bM6sr$$l7;=@k@w6ai#hD z(KOr9!zOl3o+rLf(%v5FLfsl<(zHa(1l1_gxIbzN481YbAh#S-tJf21>I!18u@w@c z4p}&!nNBYeWB#mMc>YLn)OLt3^>CCa+647JJC8jUGfg;T*s8A)02lq<_4iM379{KQ z`yV720ZeaY!#OvQC$#+b4>P9U5R%Gf(eK zo6ya)BR_lw5<^P7bO%DIzYUva^>P7-4rN50O~bM9r$o1yBh`blM5Z`O0%?<)y_Yp= z3_i(^-(yhT97XrRYAPeOhMkIt0rZEJ6={W`O+K~Jl!f-$;%c8DL9&^TQ-VjDf047I z!INd3q41TQ%lE^o&yB^gG$~#i;>j_O4CkgG6b~OigeqiTHuNTmG+etE-8j*7jPWbx zxn(qulWrD6F4Z5{Lr>RVn<7TdVYcfH$CN`2`w}z=*3uR4(9@{h&=C!qo!L8xfJ7|> z2C&3vRlTW62MXTt3E&(*hXH;>Bjf+v_MZazPYe0~V_&$FcCZNj4$@D$(0ZXy(pQ?P z2xf;u?pnu)@O)z2e%d3y0HR>H((;r^WKmEw2Zs53ul^;yJz(oY!aaIOm>7C@1+~j*2-$9F*BVn=g5>>W9df;1+Fh?q}3-0Ph zT9y?ohv$XcUKiw)$&QnQ8USYXJBWcJE`s=4DBeIso6|X(VOVbys=zvBgH}W-Y+Q4W z74d#;L^J5~LfQ^n-tHZh2VG+o(GR^+z6x_>gH=0bkC0oCYwd4~eRF=U3I#mRMzD3W z^+fT$R6AQ|wuwEiz0BKuUm9P8p{acO6!^{;wA&J+Y>gC1)7%j&T|U%MMsAAevSGa# z!Y^q$j*yZr{)`_sV+*gs5m636LNVGJ^ zO^Ej9(=pNO7PU1eBca3Tvj_>h2i`LQ0SU?ruVUuagV^RdxQYrmN8EJ|11n#lUd;=5 zrPi9dK8o=8bYEArXiM)k@bc{}HVd5#wSH;p;X4K8@13Tg*b{bi%mnmV}TXPy_K`wON3s#j8n07S*0(nuti_ia~*gSGC zNhA<zTTeP6Tu6#5AQ&_wHXuF6qZu@brFsZ7|lQ0I&cc3okVy>`+Y zamFmS0~r}jvj>y3rLey#`KSqM^9Z=Ur2Y`ys{ycxzD+y}@sflt);*!{c2$bk;b43m z&P8u-eqRcN(#c%T`a^@2Au+qoX#J^Kmg*$HD!O7s4uGXCO94=f(M|GridOoy1po$3 z??=?ZPF;#biXKYd0#xA+C;HEVF9D$1)0KZ)q%_XP!c(hCn*riBLEnYHtts5d{DB!G z(o_|oktwjWw}+L$h-S!g)_Y|1+}bVYfgtr77KO*>=O16``-5rxvy|^E~P=_WC9_u|Zq?WHk3Vw69?Nybxh85e1IjcuhOjTQ~BsvG$xcSTK3&&^Uc zG3^l0gW(tE7=@JGn&;*qYQxw+37_gjZR0C{8AY~a$|}F;1LIMtaTk?F+!anUK2>dK ziO>e?`UP#OzHnZdte8$X)Wa8mz81Q8=C=At3z~5r`2^8lmY|*TK0hPHqFBNqsUmtZ z?9Bm>Zwmp1ozSfeq-vbC`T^LYQC7aoeu|!Ct@)DF99VSZO@v%RVAET?99vn1o-33b z3IoNDJ?bqy&UehmnDE{clptX~p4(*o+DMm+z5+%`IhI}bM;wAVL&63?_ZVGd9(l>YK3ti;YV|0nN!Jaz)RIm%>tt z4WDADXRqLusA_~F_M5=K@1R7+@ZIQJc5KvR3wfwEboB>ocR7{~WQFlkm_lv&OMNO- zrwc9wcHTXm?wK=O5MYC@tkL2aua>Dd&e0eMEH&*gr&7ccyqz)ZWq&0*ouNu!W&f#} zP8wu(&+^6x8YzZBp|M=BIxtuc(L-?buuNtZPxkiOw^-$Mp_0X{hCLRLP?HcGMX%%e(Zo zYuo|oS&V^YS^_(ChXcLrT_rmkH6Cr5m)vV1>r4CDkx0Xd*zWhd`BMsJIbUjaM;Upd z_awbRgYV9`3-j~uy*{pcqBve(rqg@#p|lF8H<%9XjlKm+!jCkj1+}TUM?<}?0GZRF z5E~b%6=^E-I6pXb>2U0Ds$;{$Q?Z2q$dVxJ!;Ts`=$il}uV%kK+=Ka!0P9yz%N>2Tk|m*uvKRKU zL-{R1`uNa(6#Pi^b^lfluh1~Yjv6A0$(~i?8rS#mi&r}r?xu$a!y#5(b4F_bdMRLR zui--PhB~6fxtqWDMy=@w?MHHfj`FdO^`yw`>`>8Nwb6vCGt! zJ79IAq3+tc3peC|$Eu&bx69c$0N|B_ZQ)Q8L4h&U{F&C}$V!=QiQ6#eGXwR@MWjpLg4+B(SIlnm{@{ z+4rKxU!D;}M47AMON(#sEse2m#X5apoAKfkL{)#o1jezo2h)BRq3C z1{)6(g|NUX%seJmA!Z8J{!Q{^5SHT2`a`B^^|SK%^=m{m*HKYcoR8{pKDQ*Q5A5U4 zON#!L%QW8e_N6JeW{seOW76`&^uw|=M`j37LhTqkEnpxs8?1D1#jfcM)h?VMQhJmh}PNn#xkfk!-s zS-gNH9KcrT4ql-kUI1P7m*=rG?7x>1*>H%w@}RkvAy)nS-O@KHfe544@1S?Ub-mO? zvxZ-uCb`J{J6j_2NB7RT4sUO7a~&eM06U1teq+Z|8$fM}oa+~>LhfJo8h!`)e+SVb z`o01Q6HDJgJ&%^}V_bh-0X#gwz|`_%z515s7&`$Fntc5oL?A=#ZC(Uxf<^smxscme zl<%MiRdP3VzB8+@@8}gUMPj{|5ieOY70gfN91+$OTdMKbrACv;_O+Hr!#;pY16061z{Om_CMNI#umRP0{c4fzZwh74lrAS2etqN zl9%oy=HYv$_knlz`%$|xG&-N>_l>^MOimcBTpL}4-qhJmb*X;`*|Y=yssPj`8r+iw zws-zZEB`~wBE+^GQ%k#Y`%&D}`>_634d?j3vElW9+0ZaO@E!E)W!1tafF2AeIiTVE zvE+~nr(;{+{_R1MaJuiHG;+y(THq~J<;JYeuJ2r6oVwh(fZaiuggfA!s{Q@7L{=)l zgA!PjZ{UC4W15#RCD*>%U1I{5QCdjX3c`MGYQU8!_H_f`DdvX33nCSTfB8!i^Ko_m z6{`Af)*YLMt)_m^caZDce>c3}bee>n`0t>jJ+2!B&9xGZH5{t+v2HD&cp~{2)*rgMX-w({9J1Iiss<$@4^TJ)FuW>pQ5S`8z215ABU;=M=!b zME?Cx!SmK|agG(q(+SuC-_Pat;ZP{f?EE)3V*gqe53UU0*ZZ*m z6#6!TDYAST){iCm=P%V=%|BZM8N2nR1FI?w`6UL;17J~8Uzr}#=gg=&C#S?NE`s&R zYWxRoRsfKl{44w^z+uH9L()Uk%cs&y86(xi_}KobwUjZLixBP61Q4G>D%=^`71c^* ztc)XHepQLLSvm9Ygx1XLv?I?lJ;IkHS?p1IMVXWH=r&%i$VBMdqjrjh(KXj+9!}{Y zq$OX(3oU_3_gCQIUw&&S86l(+=1=yR5&o9xz7os;0HbXl;aBqOaR2w?m|u_6tN-5n z7yf$~H9G%gq^0=VNE?eFqOiL}?*<$Me>z;;0j|R?(G~xGJyU`kPIL6vqbR$NfIo{y yTLP1YA9*#Giv-_6UBJ+5l^zljXQ9f-8FXxaoNF}s*=XeZOJ4N=X~FN?sNao-OFb_%r(}SW4!NgyyML=MT{Y4f$MTovQhvN5)$wf{0AWB zt`A7MnVSNDq9Sk)002w?6-gLC2JcWG7&-uf<^U>qj|Bc8m-PPoU$6&o{p&gffC1j( zg5Sl!3!qs4+b`em|N8uez+VXbg}`43{Dr_@2>dTZ04);bHxGgk^c3DkqW*E88y)rA zJqiyO07OUsdH<(3ff@Q8ufM#B|AkWX7t4Pk@D~DqA@COhe1rRpd~#lQ4O1F5}@~qUNEbZscKUBxuYC z5yQh4aT9X0wzD>IGNf^{wz6>)aucQfZFC{<{(Cb!t(b^|v8j;iL#f|;fZs%Ef2YOO z)s@Yao6Xk2jGa?ZP>`L2i=B&$73{(4=x*a==*DW}NcZ~y4^1469L(*U%x!IGz7J^l z%+}dSl-AkV+*rue(3JO?u`w^}Ged4;R!&Z1Lsmm$ZcbKXZf;|KUQPinQ_g3!zfW&$ z^vCRW&JI?;&24PNZenF(ZDQl(2%^EsPRsr`qW`Pr1R?rk(tij)$RpTCNW#Iy(8=T> zc!_;qPF4bX;iHR5+2^oE--PYl6)2o@- z|G%xamAM$0YWo{=;Qiljz)?Yw!@|N6VgGT$|A@eEEuh4K&;22v;FC1}4WGXz`L{s+ z3$DN5`nM4Hw>tkNU4Oy#Zz1q+b^c4b{(lD7pFXaM4d~dqf*vel0+0YO(9qD)P%+Ta z&@nMEFtG`6Kpz8}2>&`R0V&ZfGEyQ^5^^fW+vJoClq96IY_tqacbQq3Z_%)Gv)|)l zyvKa+`yfadn3&jD*n~JZg!d>&DenE-A4CH{fQg)mf{lVi3m_99p%5S;ngMFC&WHw9 zCchUafBzsMqoAUpV_;%oiXRE+O@AtAeh7YYF?+HFqs8{#S$hW0mUxqLARA4Gj9Y{a7DR^26f z=FpE#OwTjNu=ky{-#Gi%81wtT;_MH`{^Sb=;G!Ubi-$r0K!D>AX5sgy2Wn=+1+3B2 zs}dA;EV}pi(`@G-IL3>vkMC9|S8ZpW=^}u=?2yKNmaLpA0cZY84y%5q8Vu8VHHcE1wWt|^4?bVa+syQ=yPj{cJWkKNt zW(Xh^99A3ww0uSYFSQZCs&E$k5p*wme?qr_Qrm!cC^0?iW2~6<*1mV5UXvZRUK!v0 zwuy;>TF0iulB$;QV!g&=&$gr{XZ*{9SdZ{b|3<3j$LgwnbrFm8Z7W}&t<4)RbTZZR zA%LzN1b|tL0Qy|jE>jV}f;#jo3j#Q#96|t0kket?el1T~ckj;22?NaE+B;@oDpTD)=pv4;$1uvVa_jnF9B(N?F1{ z0JqY9TCePtAl?lFyw!aR{w$utw0l8$gI?jyvuI>wqVN|ZFS(`dZ7KQ$+|nPdHl-nR z;jx>uvsXeRJq6Cbj|=%fkDK#gL9@JkG`A#B7Vq04w=y}vhZdA-m9zq>d160yn8VL4 zi+X#$EN&?zdo$=W%?%{mgcl7Mj7hV0So0CTPr~%uB)0!#5}#nv^qRUQxcKJ6%1QkJ z2V{;IdVXyk`iA<_BI3vAa-^Gy>vv=C_%7;QWo%8)%JmTiS`eaQ2uwoV>Ro9Zqwxt1 zEK^K|KMYzsZFE1Fi#2|?IjyDpd^|YNk?wPggkAN!B@vY^hEK3F_I-RaYDg^tNYMNV z$zLSDG~dl{^uDfyE81keMMd}&UJcqX*`hky#P;XT@bsHKNFr*CdpBUG;WKiTgX|yW zGdXoo(^S|MHgzUlG? zS&jc`v3`YI(6b&z+^e5=q##T9!9<$vBy#3DZRV64EBkGN-h7KOTv9?e72hM=LO;gvM73EC{ZBW0}F<$|t_fSDp)blR=n})~*&B zAf~THagCgJL`AwJK7O*kO*F|1egZe+w4HTh^-7`B8j5cVX^*%Phb7r}={N0vhR*40 zFWa8JTdy|7rR4usyew$N9`75|-awXL7VI3*$j7W9WrTfUmH#jtep=N|L@Pqh6{WSU}J()J<%@hRo~?+dK*^RtiZe_8LhKPp`5 zpB~k?BK(^f@&C`Q$RVf~{v!GB_V}NpEHh2W8U|bbWal98kGJ5-C9S~`#qY-a@lXwt zWzO3E*t$?%CT~f_^t%sFX8i;S{D-jDf7N$A?`9(c64Fg;hC5~9U*3I)UlF;i*%uy_ z1%)8~N}BgKi?4_G^RhaI%XYY5s0}9@;g5Hw zuTib;D-D*SOUZ8N)&4wy-To!>VCJj26oWmAD47gBYE=d;DomPiNpqdkJIu@i*4Cx( z6>t0ThVxuC!cw1Jdv-`P_{-K3{gFUW3jbu^iRTx|YOgR4CfX~Z+I&1Rqw8XzT z2KfP%SB_7Ht&XmQW%>>~g*QSvbwfT`b}pC6j1a$)L3rw;lnj!2*9N#iLHNqmQOE3sD+9&6l$2=nsa)9MPin^DR!bCL zSSHSxbI6)D8;t}-&b1MZ*z5j5jjOF6K$pt5TX{hWYtCIe2+4-^HDmeCLN3D)YgxqM zTMww0T1?H&18C~UJieOvb?Z~joejtl9CG-O_x0Yj&d$4^JBr>pd@how%zhF?CeoeT z55Y~Br=gGXyFN1W$_Ea*)CLO(;Gu*b65xl~CMu~G&oa1g5Y3S#srhkssucQ8L<*m1 zErK%d4V9Br_nlxY*w?!+r+vJ7Cl^uAf?$M^=<0r01uDA%$;Y>DCD6v92x@AXUhI8r ziAuG>=q}@>ccCA?@FtNfsp99WGD+f2TGrYc)>Gf|^3a!lU*vY8d z=~V7nNt|-i-BjC7;WvIh^w8NiL75H75-mNuyyK1TdO;Mv)O1RC9OE zTZo)|X;6f;JArOshmDo>EpoFh7R4(&84>@Z<;u<-^!6(d3R{E!H1@@z}$6xlsyVqY^c4PzfNJ?O{?g;SV4&b3;0P- zqjmF>#IPcuu7h$Gdt`bd>>ukwO*PgdDiJWJ>sU_i2u4Zn0&Jg|RJ_Fkj$IoK(L4wl(yTfK0li6oozg6iHQUo(t$Z=x2Us+l|aKDqF)@%N$mnP7Qy>a7tzP z4V>|9c9ah>n+{iLPZu`Y z7L#JR%&A*@@MY?Spp^$JVO+{+8~yeKyu32R-O!maoTv7IK)KGum|hdzHi~6+gSt@x zE#GBbY>QCjQ0xVHeeP;?$>ePngARd3St7DafmF-lk(p-%g7jk?|@c4X52~zs-U^8)QdHOc${6`GfhD2Q*Ujv0pG#D)N8#l~(D? zmS`F@~fh{=_(YvtJT0bnApmCO|fpClG)fU2f?` z+L}%>7XpYfRX#r}LjVIo8>~L7=Nb{Gmc#G>%hQN{pHC65l*qMvFA)F&*upf2X@>E5 z+l)OiPg9LUzMh^bTlFwf7!6H34JlBN-WaL9VY#@Da;7XNRd1$^P_(PRqmlbXw>1`x z*>vRU4BCr7*VjABzL!cLvfO+;vhr=*|We{#{9vy zHEmWSM{RRv4>;}z@A*7-rO}%*Nz?5fd+Bw0WhwS{1Z2TE+)|;Ru{4%~RxP%+GtD#Q z%_$e_bf*;;?;~^DdWW9QQh0rCO_7^F^5;$YR!}DEm_H6{{{(9xR~mpVlLu&jx+6#- zey0KD+N*2if`=V^uvepDJmppX%{SJG&oB3%loWPZrIqhzUN15`xo>Suru>e6XK`S) zK0o!aKKhFNEIHOZOGiIei=jCWyXR@Ffv9 z%#I6DhIEMy*FxwG#TUHMm#5`}w#~E%=2dv&)LNp?!s(>K5`ZXquCVslMT%K}-J?bR zJ&OZ3hXa}2jIu1p4BgU@vDO^(g9jtgd6Q-xs%-`Iav>FEq@NAy9A8vT`q0EH573f$ zT)h#_N6+IQx6L;ud8=5h0h5_&M*!L-Eed)_PZn_Gp$4Oe)vxLcHqK`XHwg4}dwKdL zL>y#o8t*)`Q?R=Kl+;ClX7-q7NOfH!(jpG#RJ2uH6)tNSVJ;kt9Vpm>&R?K5v!QQ@ z{w`}R`ZV8?dJCLsv82NCMLb<^8D|6AEd~b_)A>iAA#N4e0DwIZ|DbH-Xa^sUw?_I} zJmve-IQQk+fLYGxd^z%bcOJ>mdpuLCU1tLLXIK4yn2{V z-z(#p*q&K;yyUv0uz6kcm0=OST?zV-Ygx;3Z7+jHHxKYyDbZ!fMBDOV=AXx15dd9u ze(`Ae*}KAyftDhcQ5p_Z^r)eOb*#4YTfygWQGVr$y4vbwX3OV^+6LW@rG&;wC}1Y= z39H|FYjbDChJ^a9u*S**g&D&O>fWWT-ff?q*sv5a$CUZp*s>9}8g3|dYe6UU&TFT{ z63rZ8Nrrv}rk9WorLEI_AH9m+-C;*_r}`YI>{-k$%fxO3pb5|Q$d(z9%8$Pp`xH~m zaUUWyIG`7LbH~-YXqMzzGhVjm==BKCONMREuM1Ut>6PuId`wKG zT|+dcNYrYg@}=h_=-3!sMOiRct65`*o%J=&E8Z=^v9{8KHdk$Q?3?b-EFWmAh&?ej zNsy)sJqWJ+Y%pQ&VcmUonEW^|SCMDHnzfYBBph9K)}?^CbT_%0s7g`^~kj zJK@J=b4ED!1ST~18IbNX#3rMzbQv}ffJww!&!t!u&YEi*sCW4D(;dLLPi z-qLDoJnVD6lKNsyvMjUyH1t({*P*JW=62MkeOpmWk(5I|%H1RM_xdt}>)dVy>ZPR> zdngvfuvfua-%yl~1=QMoKi#mV(ju3?Q3P#3pLg7F;vMSN@0gP$R3%lBBn18kT}ZDM z*w2WK5kSE^+bgEn?LG*F1IRxYBz3_EhM69l(2TZ)a* z5wFgT#;f-b%rk8`(J@09&gi~oB|Od$6lX~DzBo@_K>#>0P0#}bV1@ubfHR^o**;R(;nj9!LI@ zOpm(pH%9s^{KI?&ziasD;2@AvOBaKPvlJQV*Tvl#(5#Mw3AD3_0XCq~MAx^tnu!qgY%2;frDZRe#3<5j`}CELzcoo&2bJ!5R>N_gc-foJZg zDaKA>4>!3K9sev9OHXs?MpoFdwGrGM45(*D5y1TO3%)`GAhHSF*#M(V-eO7VvJ`0B z#xcj%+1nYj5lE#G0)QGIfY&*3>{&3W^^uWi67O*mmWo;YZECs7%f|{E#3)a0304|x zp$ZxeB>#LqY#Y%)S?#3!=hxv8Dn3YVyE6iZjO7(fwZAC z=*+~c%jswluhOEG&z8qf?gJT%dR({@45Vzq;xEs15WuW1bgxQmDht{hTL4EZM*!rY zZ;1*2u_5iJzR_uAm45p$;dioW$yn+<4$X71jjQ4m1otr}O4-l$OA$Z==+G@Vc~`4~ zV$W=FiDL`rS5>)BaP?z@^iQ3g83>W6e`@*b@qZaQV~P3qcNQKCdDjfe(>M|&3d`zD z3akg%)oDGI;@j?V+xP~U{}b$;;!Ymv!CD>7c^n&Q1H-kFxT=z05;PJ~z5fhbhnduU z$n0FvnQWmCR?Kj{ONN1p47mlw|0EGVNl&h|L5q;mD=201M_vM+t{d!ha#in*pW#?* zhVyAyA=_PZ<1MG~(~6eFB^u(u%}^Fg-N!FXMgJ!R{@cQ#EwmG6wA*FZp3jh%s}`Nb z_@2(MiNf$1a9eNMw} zeW~T~zotqJ`1_@YXQ^SO7vJ@F`Y+1=KdQ=it7+@I_**(x@e6RX0qWgK5wHRQIfkBb zBY?KUUp4n=_aUf>F^=v4yHzu2{3raL&5Zph9hez7$Xzf5*k7c5o)z=sRQeIU!;w|_M%zZy}m8A)o*7f_4Q&3ftsvB+PI z#;=yG&h}$OP6KGe{sR8L7x)@i_;uy;AkbI9hj&DribK}v5I`j4;+|Lm0n}3C`|62? z{3oKZ+ilxqFg7A(tIh`J25Y{Fo)}$vD!W4C2f^Nf;NWK-gi$1*Q@u|Azu4>8zX6((L^-GE8_$>+ZdaA;B zY%)#wV$Mtn+rYV#T*x(1)aNoihV9wTqTLd9(oJpKZvj(shjGM-Vb9|Tc8Z{ci3vczfbv*aOXNdqh9EF2CP zCqn0%pkm-IxN3$RXSf{mjS}c7^L~BkC;2Fcd>hXAOu3_e=1MT14sK>}5d__mL!wGc zOMuML4!WS-J$^GSyNG*yX|G?dFaI$P^eID>0lYd7G=pJWXP{1+kdBaFnB~ z>nf5&T^{pLBKPztx72mT`Gx+CBi7p^9Q`|J<=Sdfupp!<#N@+vM z;@+5|Suw=wBs=)z08*ZxxNaOiM|VMk(F3O@ z6#pb{&EvWU!JiNuW%^)kyHS2gttT}#g#hyFS57Fz$_?`j zyzUj1R9~nJ>*(HOZV5iPO+s*^8Bj0sjcL@!T2tJk%vg#YiAB%*>=vRjfa;1qzo4v5 zJliAZF8(T!&I)JwklZnBDyQmW;Ach?qb|n6J(03oFGpi6X^$tqu3L|gr9T=qR>CKU zEMOw%LU)HrOY&5G^39c?Dl1D23|iz^&GLNy_1FRQ{7$M1{SUl{u6id|wsFCnyb>4@ z&%mL6IACeR^~{ImKzJeF0&;yzvvW9)HPmlKcf;fK-v+ z6Rc4?YM-n-J4LlEtc*FfHJWF=xtWi5soLp$<0=D}{Ba1uo1U#yua`C`bapxCY%vR{ zyAdyG2MSnA7R&r@JKMS&(#gDhFuT*-zvQ59)gs>5OIjfDG5Z8w3+-ZaOlBypN>SOZ zmcH4&Xz@{YnyF{Vpty^ls#;2hB6(I*T9WY9l@D~8P(>2>ei1DhfPv2=zvfQjz8;4D>wz$N5X z?^Bq1RJR%HyuTAGYJ=`@K zL(^<(6qzEvv7_M6-J+UXMIkAHbo}a~P4g6M=Lr5jCn$fTWo92O5MDV=^bF zPPdP?=BGaxp>CtR_a7SNw=~KbS6qhWJcQ@a9vrPC?$j89A*we5xB&BYA4keXcz365 zuRkwb=UQjBh`G6x8rVgTET!DV*~U9EX@prR7P2pLFRDP7MD;z>)D+w->AhNWi)h7t zXbrMyk=dZLd_tn`OLKag+=080p4whG;m(ybbYB^i-?Sg@bFWI-mQz$(!JxnX8#G}K zMS2LS%^&0H2+SFbme=nwlo%o%5IP-T7gC2i>NkSwz!jcWf5r%g#$Yu4!Ya*_7USz+Aew))CdeQd+{&5p)IvDKTQ84DQOd`+thzj(xk(kAHSr1x8&d@Q&Kze`%C?PZ4p@tt2rx1y^YNF?6$5x#ysa z|6R2U0^qTkN?H-z&|mwJk0DoT%scY#w?ztt@Iu5 zo82{>h==y05vn|CEn?i$Alnl$YLR$w!EMF4u;tm(FE#~N67~9`E11_i5AI`}yc%05 zSR*D}P!)OL#{ zS-oIy=fPcyg-B@&Fp>CjMN-jm({Y`cKu6Xb?OW-=G)?$y$3D};UR3xF9qNjxK<><` z#1XTe*j*NQ6YExfwS9IgY7v)&K-A*bYE%X-mKXk|Upj=s&7C7K*KchmPEAb;d1>mz zz2F%ek{iIx=t{p_LK=@(vX3dxM1D1MK5^MmRBbSFd6Nvk`oi^R#V{aWJq~lSy+q$yY7DORwR%3Q^5Wyt z?arATizTS$a9j+yu|4gOk3lE6IJh2vR4B^k2z&zVtdjHV z{M@)qL|ZU_f?cLnMj9hU04lQ7JB>?qV%WZ(>GtC!NfC!v993Kmq*B~p%JA<2}OJrZXSJFr*W0&BHC)OI0a#CtaH=fk*QmYyN%bK+P;F39o!9So+l-RU6`(&^Rh;wlX{#R>GCqzMlahYB&!ZT7CMBivnh}GZ!a2Vu zTca*zN>y=J08?qh3V*iIwrX$(?(%^QlOkqK5tSE%R5}0D#yFs z!#!@PV{l7guRE7#Yit*?38tgY=D=EZ!D;_h7`U@UAba06+zzA&vQ`fl1eJN(1s(hy zn9WJK@;G9>Iq$xHEbwnW#(I4vXKWS$6c&J5Fc2 zX$Kt}MF0m)2!PsPFYV$M0)V?g7dGI$(|?XH{pX}QxBmw+HRNa>b^|#Yqa6j+DC-+> zP||vSApSo=5OfiLTjPlT4U5%kwTE$esRx|}9Sakw-s{lbZ=-NjFtU0KCZPWip2k0b z39onZX6|s>xFf$I`~Jm*D=7@aU>Zq3_j_{;k#U+Wr0-lIPBm6g&{d?Vg?gVK+zd4- z=d6~aV${&KKyXijPQ^KAPTQs7j~-a9?c9RRE^(rFI`tVr_8#PGMCZOB7&)GiX&`{| z`onZ5)lQ1*HG@K}6c*Z3;mE%2cZ#5Mto?Q0h(=+?`^yy<(VtaTjF@WzU{{QpubRqbB#nP z-9Mbnh$g~Lh6lFE)Ljtqpe}ELl3Ss0*d#2yGDXpM*^TZs+`9r59b3Hd9%<;y9$mtX z2;#9+lM?OBMBxxEld!pHcIIBUH#RI4xWp#bnK6C>jo)OwAldRCEfbldyRCLU*6cGd zgudD)OIarUnjLT0GA|`$gtn7vK|*}8Y-CL_nwS?0Z;nb(c}6@jDlE>(AttcGoMb!) zqZfP(uY>Mh^IM*07M9JoAm2BUAEhFJA{wIaD}ZB4-4g2j>-N`}5z zZTGscybPrXUW*0@v_CQlX|D1fYPVr6Rp@BMc$cn6d(g_#{{o{@fO3Ov=4*VU8;Mqb z;{089_S8hoCHgI#C3lW(fnLn4YX6??+5!12)i)^(&TmvCWeewhz!F#Fr+Dz})ie0B zT9=xTCg?sP7-?+e8gyyqk18=PhI(^ui#g5dKHRx6$>T#?J5)Mz z-AFm+(N*)UC(ot@KDc5VCFC6!zfyTIK#`o5hf)mnj*$KMC09hv(laOQj<9EM84W9K zTM(aQ2~k3jm6g|vip9t#6ie%t;Zo1~Q|;I3?+rAIONccNq_3r9vaHcZumn$Ap4}iF z#ZF_0bQauEf@MtVkqcWezb)CDiXADSj6Zfs!{yRfeimPp{){-8^&%#awJj{jx>{Lb zg+@@s)(R$4RXA`&Gzgx^WM#wt22VD&iwb%pTVcasUqiDBmXBECfi46AI`f zvy|)UNdEo@HjMuFwZRx1vM-7pycE+~rmr|xImj!lofnNoR~AQqz@}k(mmrim>VTt# zG|ONfM@NS`=;H_s4k^?dQ_Sr8GAZHqnM|vtpi%0n6otbzQSK368_Rxu1H*+d4N498 z`L<=&W=%*!9!)alTzL($-WTua`_*Hy)O`Dnwc6sUcuqc$;q8(fJ@UprboK=eBlwWEg6dG^pc?XI}5 z{OYI3=>5<|#YLqnJ}=Y<%QB$cHj;eSd|gSFw2^GT!pergW-qkgAYJb#U5LwDov|$F8N2XFZ+1Pp8Q;W;%x6(qpH@8G1+&6L;GU5G zSoDX=_jCJkOvBTfV<=*MVyYgq=jy{~!`V|j$db}w^phP6G-0_y-ZH6H8kN^uKCPm< z^mbAioSPk{dydi3b6<^Jeti&)e9$A^Hz1Fa8zpN|xXknXD<>?K!sFV6G!fF^q^=@1 z*ZboT~b|`pAtYlL_I|RSXts; zH(K)fAg@_IxpjGC>j2xNJELp#_REl^*8~l0QUFcV3l5K)F`yrt%8NQgH5X-_idq;W zX31q_gmg7H3JH`;U?*ueO;E6jD2zmIb>VIi+7W9x-sTBTSk0%>UI1BBFv%NTwA?u{prD{A_2Wt zb^`0(<{_3MiiA<5;|(!(&+e0t@l!bZ-D4PB(eldc-||#1_feAKHx36^?@ImJX8Ca` z9^dZ$;QRhSq3s)fz;Wg;m@@keP^)9_{ z=q`rU(9OIF?}T6}W9`>pV@mKs1qF_F!sp*DK9O+5c=Nft=-Ia-LSkou9jaif?SI1DKS)@FV5NnZ@$&J|{n4h~|+d*K=%V_CLRc-dZ~#QD`Qt7a;RUi+v#+ zqw*Ww^hC=5hJ#2E%KJ#nP%sLv8$o+Yk87 zeD{;Crc1eIBp2x;DqU~zZP9~gD^U8vOZBH=`$KHazHPp=f^Wjr%OS3HlA_jkUOwC- zjDCz??S2o-1y`ADTj&w1Jf1UlZm2=f!VOLo0kvePge*}0}c(d-8KXwDbzvyShFZAeYR*XPDQglphdtaD^TGS7N}Bd#M#j}@hw>tcz< z(@>XAcF==s^|;W8(UZjsR(8A|7Q$qV|Gx66&_bC-qvW%UH#ahAqWXqhIeGf;WdW}V zDi3k7;Oe+e+^s@!K{5V**pcFgGzZF`KfF$hn|m87Ph%LNm<`F0zfS-|0D0x0Qf@{7 z{a>5on`y zCt9mRH8h&dA-5c0%?xd$x*OhNFwMD0C8<1TP!C25qhNiq|N4mc1zKIDsQ|JR{kenr zOo`sOp7OKmBtJN1SxuDGkYA!~)c-tyT8x^JbH6v^Y=9pAjgS_3> z3DtLMkGg8w*%K<2J5Qh+Mvx)kVeT_P){ zpBUa3B3#E&dVbYM?jm&*6@NPE(&Di%JIX-!!2*}VBB ziLnC-Wu&TuX=j;z<51xE)Y+0DqclBnyJ)2BTG3kHSs~K1wG%ST2*)i7q`UUvsYiJm zc{i8`GkB-E_B%f*vC&0tp=%P9xPvbiNyNNDNphJl`JCy3!OiZ++T5?4xekkaZ;x6m za$}-I;hAiZ`E49}t4~}Vq{vvPcK7Gs+t0p}T}+&{;NLTlb*7x3Zs~WAl8X#-WnxlW zzAug@a~2LPP%;pfQTE6k%q_i|%C*N+Q}a{4Gfy58v>4G?}T8hf>>s>}_R_CLTJg^|}pch^#e>sqUZ9t)=mRIAQ|GN9=7&~NT0D5u! z`~q#|@*E71eY#xaBncDUT<0*%yiuQ1!~fC zme6$dM{8QeV1W+o5z96f(|zPSD-jv4Z&bEY3`Mf>ycFi(jqc#-E711O6ifeoO3R9m z5mp!Y|K>CiU-Y59>0rHVbJSjvYWx^~vjWO30R5x2{}`wD>@Wp>mAK86HX+t{6_3Ac zhW|&S*q?;xeIxWV8-oy8KfCz^C*qF26j{6XfMsvS>9n|t{q6za=3WF3th zu~`?5OCpPW69NS3rmK&@^95?BIq>^XRGRM)0*NwVU zzW(@BUZk9gd}yg6TAN-dceW&7FB};>0UwGKA@2K4Im`b}8jBW#js}~33(^{B#=`V= zC1dMSY;z{GTbI68y}s>w)32|&HD+5;vlb-&BI0~~rYGjKPJUndp%3-D%W)}BfqZ)D zNaIW;G-i?u3xb=3*y3KHjuBqRS)V_lk!y!& zr3!wMEGdQkPPeio$2~<-zP+H$p2z<8Uih0{^Y*+@TXx5JpfN24n+V6=Yb4zmO-%7P zd&iG=+B10&p+hu0#KmDEiYZ8lB$=l*ouF;P=w{+Pz8@~ozOtWlsHUOrVj`_!a?wB$ zb(D%dvaY%Wls#9;|6q7xf70i|JFdwxv%w1H2?mKQ{#$*6h#E*k&YOBwM^lTg!lm+eh;tbM5PQ9SE5i zDeVA?V?gcc;O3SpT3Lx7QF-V$%y62I^a36E7${2=_~L7_>4W;R-VN`{6PBsS_o#9* zPwA9P2dEXx1EqJD>OMdw(p>qmCBlLmM>~Os4vP>LF@3@Ds=e@fst?}wggRaxCIKHz zEE#Gd+id7{Uj;(McC*#HuLhG-*tk5}YxqA*;@r0XxV9e#p*EVa2s^eiqSBXc?{jJu z*Dz4{65n&ck~h;E#Srf#=hdoUZMqQ6myfk*O%oVt!>dFnk_^J4$`fR*_@E3Yz%8mY0XXn@8;o@caE#ejR zlJWpXjZ)6kr_nc7x~K(I8}4AP^-^}OdMHHS-#2$rIzA|EW*J#kP%Z3~$)w<9WC*;I z7TA=?P^@2C7na!!dqKO~Y7ugrv?6AT(VLW9xo+Xp4Za$3S<~v=?dg0aTM}OzBj=~6 zBtu^rbl~4WELn8({_f8aQl9Wsr&2?vJ+vtWOQ9r7Pl`A@uF7pyPfK>8S(^_AUK!h2WWX6x zJGp(b<2P3g52~0<4r_>fQK<=AL!(WQxR>ygc6KJ-(bwm_^wmX;cSsJI$?IMrVOH8i#BcM(xnFHc^Qi zbTa0;H8lp=Z!i+GXIN0t4q06muy!?;_tJP@lr1o6nhv%KS6^G-5bxh{mf>Zdy4Nxf zpG3kNDr?*S<{wqs*49YB>p9e<@I~*PRbFd6_mexc25}laD-?FEj>bpA5qZk;9`F~( z@TxoYZF{cqkB6+-ORF^pa;XLz`zObx(fs|5Y830+44L-FHtFmr`EV)g`BSG(BcAjd z_T{Db=Q}6ZjM1NHSmMg8bh^MoSR0-=Qgq@vS_T!1!h4lU!QFd1Xx5J-$X~EQrQy?z?S>}YkkJ*oVO%fKdsO{t z0De!bZnLk^BpsHwUP#Sa6Qe|$WWUcL#VCNJld-FnxG>LFoISa7!=lP0Z=j_azD>un zabuypEn5b@XR*Ebr8rSGJ#hew%B?0rI}Np+8bU|4alnreuAC=mZ9TA-uZlV1B2F%M z9i0j5w(Q0WFcFtXoD#8cwFslPqExKLjX@Q;O4rIfAs5uwiU|m zf=8_?!NV)Kjq1hMfyHQ#M@W){zh8HbW{T~mLbrMaGA41ZW45hx5Byo%yo-}vl*55m zx5}7@1T^ ziQc*>Rbu@$Rh&TKcD;OfUnt^c9?fQ*K@V`SE$ILPs^=&S~E*{6p!v zv-O)|i*JNTN^7|Ba)ecpfyTV^)h=I>C1n1U z6mj3P<`Z&#le}9-Z}IxJmMrRFub1c04KJF3*U^IEc!-{&nP~UzFW`Eky}o=LZ#J*U{b<-^ zaEl>PHjU+za#6=^Q?-D{ZwunOu8Ctehf+&~DbE)OR>Wu(R}Wj&;1GZQsO#CT4?Av8 z3mDlzO>1NcM%jr>dBa^GNPd4wze#Q-ZAfGEt~0ra{JmE$4;Wsj399)w0Wu5zec|G? zHRaM@hPStzI@Pi_4ko&@rEG>^>%^)O)Z@#OxG^2u>R%LM?NS#=8F@)wQ#W^~c3LA_ zsyw+WR*jopC*5K2%54_EuBFF8CUbA#CMix>Ca)rxV%IlVIY7%c7=`YS7Orc+Vl$?O zmr84@mkJ}L?W$$Qz7aLFQ(Wd|h92cwvQxV`J}R!LDzABOSYBc|V!oLf=!G-#@S1;@ z%6h`OsHF6qr)R}c%8hP!)WWNe>ljjQ9j_t%w^1Vu-V(IhN!lM%-5k-KGprbX((P_L zSGl?Av}&b)mzGP4pV@EI*s&03&_@95BCO?`^^E7?cjcyCL^b%ejkK>XX`y2b-STx7 zMjtObo;-`;t$OzOEaS;`sADHyUeu7aSnSHE$~t%;bC3>dd*>q?D|-AfR74xcI_j*> zbY^lz%w>mr<)RuIP&mKarIBKMkXIuM_n-HCZNsPNbNUKQ*swi>DeXE^>2diORqT(u zXqF#Ufti$=h(gz^=QFFGL_~{@t@9~mr-`zqlzP1Qcdo4SZV&D#*u2wfFnTLv-H2jH zu3|vrC(9_7k~V%7C{yO&RT1lFGQDgT_n5~?j%H@gX#@C*4OPe$622wuiA?d`$Y?&JGrF6^FCakea-D1JS7^v96nF_JR z*FIHN8FbdQ-0*}JcJ%9X74ngwKdw~yf=?iZ8H!dVxT{gzp-=3Dn8Qv)TS`r%k&_YIl?f&dJg>KY zZ%>|v+ciY^47aehDQg&?4SNQ1O=OGr0LN_TfRND3?(K{}Q04(VnA(%mSvq@}xIJ!ks7dvA5` zXUEy+{hjlD=j=a>>BKSS9Al1q+;Lsk;F26a)8$jHfdp<3%#u8X$h<}AUqeyjLM=7A zX<)<%3^Zp%+%=?w_f2~^zK%-`1V(HzOe5D#&l=t!Z)Y7d^o2tB1(gz>k%S>-)RGNA|d@_h^$N7M&(nl?~~Ns8-cxpGDQOw+?(b~!n| zFm3!|P4fukjP)2lAy(Z2?oEh&9w&#zaw4~yBQt3tql$A6n`1_ves*1Ds9N7MmJh_e z_~?Y?Lb%i!?%;9#JF{KlHoe_VqSr;=^6&F>4v@u%)|C+LJ<4@>^T>0$aKuQtHYqY< z%G+{E;r;_H)izZA_N?~KoM?5TjD6ULEH28d=mlI$e8W!(@JPh&J&wcr*$KX*p11nRN3s1yRZ+s3(0>05tW5bD@oST2P6Fnf&{IpNfcDXZC z)}CcVs3nR{F*E|!vy!Is6J6G>(Xo#))?^=8}gaIW)n@*T8RYYx1bbAjX+(#k;X@p<)uAn+D3S+C+OVqD5r)1I0`XV?_-s)A@Byqc>6HX{M4tsWAkcp~`fEa3k=+mAoV})W~(6jr`aQ}(?!hk^u+;MZba2JRxHVw-VnV$`YLrFktp80NP?Uc`+UY_|p+6S!-WSk0K4@ zbnak^Je47s;s#=iE{sRnMSv(l1mNtZ?t+ETjf2 zH8(wSCz>9hy;l~VwE{nC`JR?3)vI8V%;ow-NvD6^!^Y%z(v>LH7+=8oAS^iyG@>0x z_7-LF12itEzhkvdb0iVh z$(#@uGTNtNr1j2UXm=Zwb%E( zq%5-%sJbT)kOpM5$J`dRNnbX3FbotM7S*q>4rJsaU>qI{z@~F?1nKdm%+5Jhp9V5RtKbNd|1|r* zVGsZl#@Hsi7eH_im7AxRtj3sh_ONX9PZKsHSHtRUhGdbq?Y&w++|3kDTTa78$x&&} z$R9_x2*oFKz8*&?zBs~isA_)k1)o5aS zopvPdgK@bzmx>d8fTcn@01YhSA)_AvjDRTLmOx z*8XAa_U|Gh|IV-EUsk#rP@?%^1;Xo}M|SJV!$h3Gv({jMI9`+VPu+C#OHD)051HGp z^{gIBjf2I+;p4K4&+vA?tOktPbSVrx^|UVqal z*+YIF#+h4j&oSsAk&h!32Q4@*oJ>xsoFB0F_>86C zlklQOWzt+t+@)irijfX+X2d%Q(2aK!G1Spc!|`;M)81=6?psn%i0z80kyIc-FPI3y z>N@I%FH%F;(5WQ4-b`;OS_`Ig+~|p_&tFHvjGFr)rmF#2HtL>(n{Y(vErhNalRIg=L?@_`mD zzK2_g!ljpj*jfg__So0xD%R>+(Uvl!KH>2elQmVYThXMHIw$WNL<)OJF(I-eeZ5nE zc1QNjb@DPvrY`baDnI_EQC00wi7f@C=yTL7gN8m-?h$$Jkw<8JU5QV!DdxHhi~GqU zUR~=B@$WHZq_YOK-z>8GrA9OOO`Y!9w$KqN&glnFaWHAE?0>SO$``F-bVLGkW;> z^Skaj>}!|3v%1VA+!=Oc>R1Fzxac5qWeY(=zA4a$er}>8SwYsZmkDW;+jLL#M$auU zB^RkI-QEs(nAjt*g8UJeF3Z6R)h%J0+ATLYLzQ9`b9y$BxMqpi{tJ9h{gUQ`xfP^n zg%OTk)VU@3JZWi)9N2n!@s`PM*>Bl2#!&k$oS7(FBSv+!Fd2z3Pd4uyO#jCI3erFl zp?wX#Ov2xnKj({jBw_e`v09=yl(MNNf;jU#rNwJ|01yH(kQm+x z>p7w-c&l`NJTY>j+3;>R*@|gMQ_bwg_`!P*t75{z9)M2MFp8ZBaesd0Qz!5+>_k@n z<&4s%X7a#A7s|P;bPt*U=C-*$c`U*QU&^Zh#8=gJ9ZH|j8a|kYbn#-(MV(7;&wkY0 zHsX^kr%rUHRMsXN*`#cu+@=woC4xdI;gD6y0>VKEm>sS*b}h_J zu36{(En?>#tTo{3E5uzL0{&eOFIoz_z4?Z2KC7g&CjCP(S#Pkor>a_#Vr_^@{bX*E z?evh74E7uOp+Xhbk!P%}p4YP}-?(@qHbc3zbatwjB+8(aJ+AM+P-VAdGD{wZqGH3r zK9at`FLs4jd8be_r7U+ue4b;Qqwn3y(sC-^EU5Seiv-V6ZGP>x0p9*;?5zF{P$6&k zG1XpLht&hbG_e`#M*qcSsf|eLwA+S+1$YXBw32iHaq*~qs&-YaNiD~bIPm(DyZ`Y> zuf8Tl%+o2u7(;6%6yzm|)WRfqMme_6bGc#F{62Iy_My2ciqn${$M!RG6U2h2JzKTm zh&+M83y(Q5YH^N{DPx_$`u@LxSgGE4%pcj`M(Jc1S)79nCzvu%n5hgtxHW!QkFH!> ze;+rM&ilw01S+YStFEM5)By~R*uM;i|HX;_HC2`BhF!;|W+_uboUYv{oJsttg6Edk zC~`t)vMCne%jAct+3LufdqF6rW;E75gQB?()V~e0A@i zIIaKaK8l(`ZRdh`AfiRX=*^BCtgiuf3;qCXJ8?gXSPW{Fi5r!l*UttY*uHl2AV6lH zkBZN@x{NGkStOOt=+-|5+5fJWHGVXO@~?Zh|Ki?uUt|-5V=a|Znp?18^it)F!0%No z>$-_TX~WKeFi!Vcge^mVH`$LL#XIczw0+r{^JM#kxdm2iwYUo(-x>BW|G_0TLDX)I@n z!AGCo0(_vzds?L>#&F=m)5p(46d4jQyOf%El$-w&+Ss%qP6i|Ben#|jooV)Os!n`= zsyfNYnxc1%ewBo&K>y@QjUmLV`25ME&H0Px3rB@R`WH|6FP<+*>ZQaFSDF7$F10YG zqT{r>r`eZ=1zKCt{W#%zN-`XA4GVI5;>??Ii=o_GYF7X8(f{WHl~P@Mm?$pz zY(Re_q3p+G_0I&el(z3-x5~G?UTw&$ln$dU8xs9rSnJ>I02&%8OppqQS@mz8m1zx( z11y>q{p)prY4~uu)U>hGm9<3`h*lAScoYypA|)37o?iyzfcxMezsuxF^eTK`^aZ!i zfjCQ4{fIRCPL}i!eN^?^Kh8v3z*u5$V=yj#>`zR-Gg2vHDU2Er;KReGxhs;z!*Sr( zsO60#1Fm3C%Xtq(8yRB4Bd6gt8J?C%k*g{-T>039J9m>|@?GZoONl#@E)gJ|A(58R z%ni-N%Ge*rk3!-6+DGw)W>T4up|BXv&EDYz1mnptW$X8PLcH>+>nZE~t0eC;k)(u@ zYLJ)24bzGu(_3O*;Z>$BU<4tU_%%lc&{QC%+V-P_u06_(_{uDKx)o;pS@f&jVyErS zLFyg2CqnpRMB8&4oCWrPDU}CQU4fFQqE8o*dEjS-CUK0ia4)?=O}@l>wM0M$h02~i zNqVZe7n1nxiF;TgJSu-TKxmrP*YVfBa-PScXwY1FNQkev!IBAcnf&QCD-iP>O4uNtZ4DgT3K5WOUCs|BdyUvJj@Yz3JvQo5kuB)_t zL)H0`X$EoHw|?N!-X$lHeT910B1V{2EQ;8gI=Yp&zS}AJ;IB8wQ^y&uVP^TnRGvM& z`fmUIO0w4c^%C?@Wa|?4aI;`>o3jo}>!lk@;zgXtW3=1@@6yY!j>kDf>D&d2OCrX| ziCecdmY8G?@hFhby&YH51j;jyuuR+k!J-u=%F+(k`E>9_^-N(kEBjjidIzQ- zMqCSPfs7uSdo@LrY)@>JFx#yJ(YT+dV|+-EbBvVc0)X|Dvvdg2IirNf$ow196spw0eZeIxR*2lVK2zcRTp_R%qhcYU-QEvxe}dFyF&-8j{(aorSo z@C5G6E0~oot3B)LjWA14xE=Qu8-(RZVe$)DyJGT4%nCpy>IzlF@$N+7eVdu7t4H+M z)Nbur;?w3Sh*eb%b|kVGQgA#mwr3cn;7xRMfPU_9v+Dku{ydhGUL}EoBEVlTBzg6W zR{PTudBc0L!cT@Sc^#(KZuy$E3yBq2lCD=)v5%2m$l@7}qdn%+?RMQeS58FZw5DA6 z&@U6U`%LO4?aJYrmR@DQsExsq<8PxRHmsgB=eYSnewv2M$1r7=)adHAwehaU^-AN*&G47STa~?vvvn9a zfM)juV4mK>*TCi{ABU7?xU^O0v?!18YSUR)dNTKobfQUUoo^{AoNKg$C4fY{a-%EL zZGp(Zz|&Eh*)2_QZ|*0)PmTbD%2-~1yr3DXu7cEkpuR$tA&W_N@+EK>>EVwi^u2E; z;=RJRN7KnRUsti2mli(k6zay^0wp^Ui+6muClYI_&PcirPmrGgUA%GjXt#~t3^#j0&jBHdVo0z}ZNHa{HP>6JDad$@ zwQ+5}X=pjh5UIN;#u`dJMNBHmfF%>SLjU+yVJYl4(9Ah+imbg{+YHNTvv%}Flh0_) zr&_-#&wV|~j=s|oI*wsC*%@=lyH`!xA(Q)PWn-#j611R%ethn}EkNg#h4FbASGOk& zl4Dsd|Jq(@k%C^;?rH2C4(fw;aw=8I^Luho|f zfFG^P8HXQw83!XrAOXaGkF5 z3jrVlJ*R703z1`tDg{K@uIg2|Z~k7F0T`|KujzfZ{)NlV~jEKgygr9S}}}c zm}o5W9nQF{yJgR$P-_2?p2|Qw>cIkP3CcThupWm*%~d=@XqAQ z(SzXumy`DhSaQN}V#b44#2+a7^B&9bc}|*4Wk%WEh8G$=02K;$Z5|KvYuO4HIkNes zf8FFiiIF*1X!a^HdG`=+y`ztqH$X;#ka5zx$S4R9C~X9VgQ247_2eIr5?9}_t*!dA zAM8mRP_GVSNpkm$;o;v_%ifTk1o~?t&M@LpfYMuAzrl?)S4&snP!WQPSHt1Ay{)u@ zxu4Luo#Z+#M0Yr5w7*dE(51TQ%mU9O9p_DK+X-d zYQLv(d$__NYar;^iS2KooYlhba0>t}a0TMJ^O^^LyWGAHz%f+-wS-pvZ_+S|Q~jcx zpP2#EC{O@e*#J1#Ww(HL{Iedv3JZ7@whC*iKPe;a1_b$^3ZW0fZ2SR-94_>s1Dj(z zb%}&GN+(gQplp{d%}yjwZ>^?H0yj7J*BDi$;VuU3YQ&eKC4n7l#x%*oQdCoprGW>6 z8uxw0pjT5deU!Qb_~_^HMYj>cOs0bNDQxxc{d`n?3l8F*HxqDL9^LKX!ns7zUL%qS&f#yaCvk7sJxs(OoueXrAcLF5FG{9Eo9H7J zEsm)-=U;8}Zl!0nre1D(K~MZXA|(2a%LRuODCrT>9!RSmI@2`YO$HzMmECGlP}kjUd*S}~y4%d8O7G4Xfc%{@71B{^>P-v{tN zWUJ*oC0tGWart*iHxepUH8;lh>rVDD_>UbsO>TQ*CV?X8H3L5&;P519*l&9G<$A8T z^*d*$bQ4+-Rhn~x4o3fKi~>5IyKPyS9bVTHP5)ytoSN)&f$9cs`Vem8Sj77v>v0t< z-3h80$_e9X#tfxUHz|{PWHS+8CuKh04&vr8#^-yas&Ru8XWE3b9elR?N@9LBaX~aU zJHLUv(G|tN>StFiPuu0r=6&>Lv)CJJz%%C~w0iOB(y>1#ME}an`$$aU=+)d^dG_l? z!RL*22DUkk4YWzDtmIS+h25%k^@r){r*PxrI{87XDDRqOQbsZ7x3s8ox!AQzA#=g9 z$1jFR54!Q;k%t~hwNv^H+ss|YiM6$aP4sF`?%SEY8x6y^i&>KV4b)crNctv{7A=CF zfs+N}Tiji9-^}YPq3Y`M#Ux3e!SKzYjw`{foyd@h96^S|?X9xHI!N9-98>W|u9z#4 z_ogB?tCWw0_t8MsiW*OP-`br*tCqAh=9etl`H?SVJVFF*!orM&1G%r_k9Rs&pNr4- zD#{dEmvB$2O^Rb)WfQ-Uayuq6&HQ{1KEPi;oqIC?hW?e9*`-FE)N)n3OhT^Sn{!sO zt)->Of@!5@hX0!iJ)SXR3C8DkR9jUa>63t%!Zw<~OK$67+ou^UDZ1^DlxFjU^uU8F z=N)0fcy+Fv%bIOLrm0&Y50kni&Ig1HrAtObuPl!54^%9$WnT30zbWqaeseZm0GD-?N#c1v0^Gc_p0K8prZS|8zrpmrL7uyuy@A>}+&T68H;S$|b8u>znZWVc zj$ zSwP;0yYtDq^9fF@SWaWtOXiwZ+AxVCZNRIh#5Al&J7Ng*0k;$g@T%2ImlWs@zOgx$ zw>mGamco}9kuFI<>mzyw7c$$b^^Z?OsC0o`Ap?c;SvqjC%5`~F6aUPp2MP*-_F&>J z*C2fCJ$vH#Sn++|RRJfmpV5NfaTM5v*RkMli--#qaNtZT>el7zEe3ppSBh4t&$jVB9WKb=y9Dcmj~;i5ewBPltm>B%7m( zY<%`J3dv7wI8G)4l0e;6D1wao#(w|H5a!p%LLsTCo|A1;oaTdZK6`C?h`VQJy>gyY zh;!ho_e!+JI{x?i7M+04QdTA)4<%F~lB$ zFW;}-Q$RKjN3RfEJ;|3rsE%iU2_J-(KpFjDYyPZoZeo4x-av{Ga~b|FK` zJ=o?)XJs;Jp4)^)MjFfXkppZ6mDiIIbgHgz^VB#J)?Q<)KL=Evh@rP9A+Rff~7ya0))2c`d;8Nj|?jUr*2SiB}!F_JZ7z=#p9I z1jF0Uo2;h{ea3wUf^o~b+Ml@2*)6RN3&|$4J~rZE2|!{gTy4i~CHnYA`y4OuHUOl= zVay`HC*%en#KAbgof2+977Fl8+vG1Nuk*B_KrX|Ege^{u=TeY#aUN>*&e_nuSX*b% zje||LLQf0^ailePIG%Mia24hpl|oRWe;DOn(_0{C#}r(E8X4i~f@oG>Z;5@S?K6VA zx~^A_;nzdRV+Aa_z{mrb2cRh9m2s2?6>o6>-VcCLQ| z`G((+KCt>|r7%Cjagsl`UH>Fk-I{{%!xLrl;{ois2DWG&o`G`C@FQ?%8*$4R#~tQ~ z`|BBPVvc!Peydk)W(v#remB*@G~ARydH<+iNCg9YkCGeYtPGHR)Yh$UYZMY=9&za#30Y-x-OPT)-qR{hwojfP^ZRBI1=3ZdVv#8} zXo9&fD*x_BK^0J(24n|z6x;`7wXb0{w7p*kvy+_`2&L2}fpD%Qm@Cllrn?a_s(z0xD1--~2ifuFdCjN%lTTe@)2ROA$YzRJUBOD^HB#Bqg z@XOi*d`kXA(WMhDOzAqU@R`HKp1OWQ4>!g9V}yW21uksEcIsyIOUZpeE-6*$q91_W z2rW|p*`{=WYXzmbwY-xnuZPvjpW@BZ;a|%Kw@BsYzq6!Dk1PDL|M*+})(ZNTpQZS+{CxR2<;TjJ$dQeiFUub`W9_*t5MR>zsoY1%WQtob zrat(2rTsDl{8Z{CuyRtJ-0<2%=-c2@{ug9`pM|M{Vn{rdVeTF%OUibo9bkF_D?JQ@ z?5WN}(HFJ61htW)<_>I4BhLb5YGmoN(0??SCHC7h^=m@qliLn@&uW0@a(mfUslUs;Uu%p1 zIf8RlId)|S{DDrM!qdKCY2so&n4rHrt%a(5!F^C3ASRImX#RET5UxpdW>!06)^`qV zYJ0oG8<-jak%$c1Kdr;4UuF~+vv^9LK&k|+O?8bnZS#C53P;QZCo%<`KVMAfzVGsY z%)+D}N|X4pso5Z+(J-9Im~vYFvAe$Nk?vlnm6V~eC2`ttS@kFOQOYH|G1M@{dxZ}l z2y4?c^vFVg>FC!_$6Kxt)+l|!Hv7rv>64E~j{~HlRHPJ`0^O9n(^fDzyaw0p(2_>4 zt2^ldS$?$|Cft?5F5Jfh#62GjxzjfXOd>7!O*Qew{@cu#?x+~2X&LdB{8 z`=qRtrEKEc>zaRH&{>M6NoVPZnQ(@GF_yr7|5M9T+adq={>+ovYyKw*>$$TLlreLa zF-)N(+EP8Uh70A7*xPBi`w&!qcBxdTrZ*tRwsubgyD5(l3FRq<^mv}P-o*fNO=E(y zuv?Z(HTD8}rJ9JMsR)fFYGRzmpYJLDe4(_-5dA5;4xmlFUI4hd|MkC>0DUS;$SFE7 zvk(**wsQ!1$V)r$&;Rtx#s8N3Vx~Zy>;`vI3!tH0qO&6i#A&4cW2 zBKppVoCFitnb#O5DF}+0lbEo`q(B%rbn$b&`1l70BXn?v7369i%{!5~K!Q};-Da3G_%U`h#IIxPEq zO^3h4M&|0RSVSWQ1YEHxg;pZr);gm!|NemRS^H+u%@mx=4|J(j-ozk64h5^Y?)Y2^D zN6#EoMfe?K<>=6-O6*r|7z$O(GSe+dOoNOVKES?iLF z8kxrpi2x&xc0lnh*}cIA2M0tAza6!e@w&T|J>Hk4qb_6if`8Pue$1 zMwj1MCipMvia|ym8Ji3;mNm{Ma1)$%T;#Lp?>P0Ocu^q0~x-OgbtOs3Xowdul>Mqn~4(w(z2009nR6%th$~E%_g1zLi+R2sb*bT`KgF0;0h!p;h0VgrL z@)V4Ae|&FcI^82xi_jS%ve^(7@i0%^qgP3ePXT4921Xf1=%KgWbNqk;<73b?N>j6~ z5@#jx8*_?@lHL_diZ}(X>(_@8wj7R`Ot?}G4N6`^=1i$;sBXhrB&0zrE=|o%jWOZi z*7*Fdl^;zNYlV9x_)V@)yQ(af%UP&`&o|&bYWfN*tJXk`gwbc9M@|BT2ztTdiP&zT z%Vq?ujrWs2e~r1qk}p2TRkWP*;!M0^?QB-5V*@jy_ra;r!p8#QP0`+vJ16~hWfe~S zWAu6;Cn|GWY_(`(1S~Vw-@)qtMDFUzlb@5b2|p3)a7unh+8ew74J{r9cnHz(;Mw7N zSX5-Dev@E={P&al0)IcMDOnKb=6duF9Ce3*rT};We9iM^BIqL6sjn233Q%qZpjx*B6E=_#5ws>EChmhQ%yVp z8zYQoQOwP!(P{UPdFJY3lV_7)?PxB)#U&wis7Qt$ZJCe!_*$2%2|2nys(U zvrsc>h(JzFi1Fh#Y6jGO$Ih=6?k6Nr#ljPo_&Go3lXLLuE>9>e(|z~6hOuic4u7Lj z(iF|TK@)MOP?Cv|mcr@LO7oLY&h(&e>RPfJw1V4fAY$|BCN%^+&kPOl!RMlHMVm=Z zjTE0N&Ix6qM?2_uH`tILcOhXd9mApi_K&x#ppnzdU-;WSjiOvMw4bLj3i` zB78@K-BLaIAm^mtI`hPUQ-_aj1)-RmQ0M#Qsh9aV&Xng2PixF*&8at768zX6KXUN7 zaE_dcUz>2-yNvqMb6yVySYEE+zdU))E@#Hc_qV~>&ZR&vMp}e zT31fQ1vT=-s|p^UejD$pAR!V`1%8)bf40MrWUDt>)fDvNa0**Jub-qhWt166 zuGuw@-g?Ud1Ryk0J0RhZQ3N?yF237|A1~!-Rg#&%Gb4PHCO31fVo3vP%~TiE5cLSR znfru4;^y+4nYFc4DZcDYTE=`ikhs{kzqz!yae?06{ob5M_jG<5SBT4^)txbHzOEq+ zbIbRnEKTDrCVRhvNYq2Yb6AMufLLLj-^#F?dduRuM?vJ$GG3}AQ?|v?8QFS%|Q^h(F4Kc;9rM9d4sGn}-M^;r`o)PS22t)bk`@ zWj_Aptnak4X@&`be6|+&gZbVp_~eZ1?v~?6o0-`qu>x-aI}HBII884;-CxmF!;W21 zS8k>skrbjUZGvQj`;5>p@nHVeyp>VaiD?9RbTV@idWAA9S4i_fwwwy4`uykErGnh% z4M2`p22LmWr>8Og_ZLvrmx)`uD+0^OTg8a_-Gar#v-B6beMJC5`0RY1&W~-n;-{m~ zMK54N`$B+s&pV-y*Y6|w_Ew1Ns_MV+*!&MiYnxA~T+%hZJhbaDaJ?adiz?uN%X+C0 z=AJm*-BMYoiA*I)j$N;#U~Yt?bh6GCgoy@u)+_h^w(#B^PR4obII~>>2<@gLpe4Xp zfY;e?rd*r-dFiWN%@1&tQCa}mEQ_gYkRzIbQ^uDxDw-tKct=Ts18g57I95883762v z!|!-!31|8v8UdJZ%rhdJp9pnYs=V|0bBx!!a>|iNBU}?wFF1lbUSg}@(j2KiI7NH1 zqyA2{al*!I$`JI@gQ|*S+%MIzuW#Fvbb~YVexdS=lP*Tp34QfO8D z&yRSoVZ5e0Xjzwc?8W)YbhL1@7DlSLIFCrfZ7Yvp&Bny(Meqh*Wt~NN53@pNo*AL& za*v>WJlv?kec4b*TgF8Pkf~(-Q=`Hdme;nCF(!$gstK(T#h7X+7Kt1>sj2k7NYBl3 z{@^_T65`)JkTgC2pC@7bFI{}+AYy^Ng$@E>97gsB1$T$w-x-MiFE>gy1%Qjkg?3iZ z@1E3-EPc@xxckIZGnB7J_I8wiR>sk0R^ffVDXpXsttnYRv=bpkGy{@e=pJ=V*xbfG zJ6i*loe97Hd;Yj>Fz>f4%?VGY5zkXq)soLS=Y)`}vlKwtOz;y>#}KRrL#q{gpASlZ zBy3&?MYa^2xLr*(-U_Rx95PDjZ)#$}L%Mq^hrT)N;_c)e(|;!EW}t*gWe!ckcVl&b`XUEC=F{}hGdC2+K-wo82O&-y6SES0IxubJO>-4|x3d-vVm_ zw?f#O`pIvEpr$=D{7&N29eaLT${o({L@4WLUvb4R*irUx!jqBaQ4Lj5mOjdHel$Hm z*9cBM+4i`8C|FN*uHdaEG}K2Z#$5mKT5r7x(1}26djVyJrbMOqA_)Z3gFos!Hf ztVT z6wSi4%uhw&S^vG*5n?^$WVM%54-hT2)Hd*=7`x(TXCu?-%l;C*+OJ%(^ka~QYybzy zivU~wpQRGvVqa916MZDzZPZ_vSHKZ1Y=;N(I=`P2^{+Cw0loBrTe=*9-Y`PN$y0Ju zrn<($){QE!gc}__lVY+fjXo%=*hwM$;MddsZJ}!LPQ?{T$xDy@gp~@c?Q>oPYr!Z> zk5Ww;@TQa{LpQbs1&M|}2d!WXu+w}@t`FwZx0BtXS?%W|v(Lz@~yt|dO zJ7H1QNYAOJkgyhgW0I1FZ$YPfOwXO}w{-E_ZkVB;1#FOL-W`a=+*AUgQ!BVXa`gHN zoGgGFww!h3_SS`za6x0sQ@TG-Qx;oY2`9<{9kUr!Ub zE7LN)&*9q?6xww2yovW!hBH3uUZc1+Qx6K+#Zz@WnKWCR0B_?03#@Gt+Qvi!!!XNr z1piF@6(kVqsh{JhlD9awE<%LdyvpHjfP(*y&Sdgs{~JSr2AKueiQxx4SCkjx3#*1j zkh42ausU&+Ms~|P-BuEo!}6Tc6n8rnsr;=iTb?d6`I;9eIYgXrZYp+<_}fDAv?pv< zDjO%WGz=$zViS+oBHMIGLP5sIAy$HRLJc@tKJ`2EMWp9y(Ca;zLBcdpkOBDppfh@g zo?36-QL)464L`SRO&w_cXX?cLK62RScY87ATLH!wrOs*VehZR58jo%|v|i20Cgy^x z#iPs}UCpW|jze~fDpkV8rI|O?yo)6XTb*TOcwPe&79E)$c9KTgEyy~(GA``>Xi3&u zF7}-IhH-@H7Q#XvlFYS#f+X6^b8{z)#@Ain6cTiFvtuhwBVx3HFm-e2=^iV9%f9G=?I5&PJ6p?ces=1n%iqN!)Eg4sHPFQ1&HA z>>R*=wQ}77QP@$=Zp?2WPx~7fu)8ZO3O~M!6*~AHPeE@j(c)pqy2r@Ee3bK8l%Dj&F#2_gNJ1v!1la={D5y$*pAn2AL;r!y9rB+_; zZ3V~Jwmg2K_`--kcPBf^TKR1$IN-TxA)Nh10+lkTPS ziz$xJuW#;13&t0p(WKM!mMJB z!wSJWKV0?jT^pD3@-W^7H#*tuEjQdG+*w}R+%a9-n-@;PrPa0|w6Ecu_X;=1JeB6Y zU7NlQ)YzIy?7VOKuHR325LLvWf#{y_2=7;we?ntF9hRHam|Sh0TxSy@C&LvNN5CvC zErnAK+MgE$O~;UwW1#=fe=S|(z7EV(4K zqKNf+_4(Bqh=McQJ??$6GswPOpw3D*LdPQ(NO2VkLbUTzZqKD#G}BLN)#TjPa8Y;z&y;-Fk;;|4y)?k zcOwQ4_B)*V05 z=k8uBpQOIKISRL1JTWi#*pZ$y4OqIXEG?VcA-me3f<_aFEQTKv`<@%|B?A&~re7|N zg(u6_1LVg}=QYe+Vl}?jMBpsSslJ7eMJG!St_4mWV-U;N(7wyqJy$#OPGrX>e5!h^ zuu9)R3hX3)z3>y6w(t^fjBVy*-wBUXB2w6-yt0r2(9boPlEiS&vtEMK-^o?^t0toG zxv$ByTjxqYyb32c6oyfQGL+Z=(Yl|c0sn=+YcxS`0~rB-F&;9^VD&QwQ8{uYv74SY zyPoyGQW5{=iD|(5a&UkzFOy)6;N8wzYla_0Z2GxvS6QYtuvLU!FR3N!yjP~W1C78( z=k!!kvEOSV3V)3*EO7VVV1Pc9aIv{rPS@6?u)%12H6HEY@y)X2uZY@8vwnN&BlBv( z+KmUqF85wt5W3YFzCEc`aZE*pYsb<1OU|WrnHv4>WBX$?;2aK--$07!Wfn5n;^x%& zp$ks0teme^W#{y%uAUlHe3uO#R@Cy;E6d%{x8T(bUT0c6UW>6kOlgJ3`Q(FeMv|S` z+F)T%Od%;6Zs0+;b(%M#PA-?FEve3}B!Xa2Ne2Jz!RlcN*f#0rd)7PKt*Jqr3EXN#G+7fh1Ff;XhO2gX-ts5K2VhHS(=2G$e z3%D8m?o$3RCk=^QTt?smh59S@GozMc37>{LdJ${P1Pbs#cgO)@(auttcb)$J_qqwz zE$xpMMgpP>nO0=pQ>yZ{jpM1&5X3n9%^#N6HHID#UWgk%6sLJx?P1Yy?k}>20;IAhA+)fU_3x$-Iobh)- z-DAP%b6-SA-`@XDd0YNN%3JvkFK#)WDz17ud3Q$0#2Xgo^RHJ)%>~BLP5UPP>Vyu( zdN{{#LUY&lcL+@2gJZydApQA*4`4KbuVC#w@Ruc5ttEdD*4BDI@YFoQbE7Yy7ejO#?29bzg;x zRODnBQJ_c;k?Vn)+9- zfs*k1_gdM18Oon8^3&1)$M)dP1L^Dvtk3Dt1U_##60MGKsa2gS2PhI|xM-#)S0Zjc zt9)LiHg_Al`!M?MNvb3E&pXN(<-PX&YO(!xAD153p0Imob8ESoyJ4i-y`|;8k4>ar z{L8ETa*>!ZdzLxh3^{|GwxZLePijUEs(L@Ru4{7XsYj6!=&oHzVzObvaJ#QA6Rb$4 z;Ly>I!~+-f8irFjWqL%_Qh#w>yO>uVhaN{czA)EInXfrr-%Wwbh-GlMY>B`UaLP2UDpY$4y+#HqMbLG?r~LIwSUdY4 zya$|JSkW(S|Ju{o{U-W?^R^V=pkEaIo7?ZlH~w@XjQg!P*son(Bn!|%UuyRB` zz6~N>xh@8vv&jJ?Ci6SgZA4L*Gy(ng5GZi6Tq^z_xTyv{uZw*?y6gHZ?<#6YLl0_q zcBZ6`2F(&c&*~T<3i#oz6k4|-O+MdKV)!x?&C|J9%2cD<^GsAw;9-S;1M3&*Q>(Wh zzC0o4$1Fqy(`yYkS4~v0^2=a5xLdru$LQEAP@GNHS%}pGFk)~p0cu3it?J)MQ9!>- z9V7p()NzLTNjb9hZM(w>3r9ps!x`4hMGj~^!;!bE}1Cn#hY*xG&r^;<$NlOtL@mT8Pe zox*#IIO9m~606sfjP7b#HuT-+=)lXohatBYQ9#xMu!}1e0Kj*rlk{Xs=oUT+po``t z>ITd!!AvhgU$WfN=sgBd)JC8vAL+xWBQ;&oZDp>KmZ-2Hf7J%K(`6a`>VOmmH~1T)er*E?&SnFJHe0}#NG!jBup}6p zk?Qhp2M;jA^#7_6p}!i6^(2GyDaZ%!6-Al9Zsf0qf~abjWG?B1rA7Kbo&@Wq~(9d1`Wn+4+qR#gl2nD?pID;HW`NmFyj{v6H&t3e* z;(sf7Kg-YMu|kTW(f@|>v85~8M(-Lc9-CC}(N`Nip}@`XvkuMw?iXRa{A;|anqB>> z0Fv5d;y~xlP($Jd)aVMc+>s4y5cM_U?;5Z=aVpa{kTHdLQ_hux>^u2qMT=mmr_rH{~Bk9#-exJN1|h8 zWj(CO?%;%FT*13;iji{R1;SVSs;?d&PJzQD6Fa{O+daj?@*{9;<{n|4%|c8Y?;m9D zno^N*hS%Xh;V?5Lu=s@5?in+auo)(Bv;OjU_RYHQT+6XH5>ke-aA`knVcY*;@2!L4 zYWj82A!vdG2=2iX+})Dk?(Xhx0Wt&vgux*=!QFjucXxMpcYDvuSGCXfy8G^1bqn;TZz3p0LqXDY-pVy2359)W2!PHHO$?ONB%Pb7A;+nG z^m_0Y9lJN3s}cRov0T$gzN91iPQu~)(g*w8uak`S$H$sVnz%z|q8NdM;X7~81XwK^ z;PC~b%pk=J0mY7|sU8`GDQ{Ut@fQ{)4-X@9J=-_ZfZwT87U)t$fGfR)B}0j36CHCJ ztl$8g4I?ulwEuKj`G4!@s~Ny9@qGyC!+i)~1CD)o2o%h5s=bl&eWsN#zEazWPikXP69zFEU&;tqPq-r zPI(ojRo$hO=cbR04w}4vLfc6XGXic@9)Cu}=tj<9a8b@RI5CJi(GfLm-sm$|qA_uL zBs!c-W8h^>ig(+2%*E8ChSag!AUXrp6=p$Szvx9J7`3GLZl(sSUNHh1d;07Gw1Z@& zXGcI*ro`b~oW0Udiv@4F5oBO5`H)*V<%aUs=Ds-?~PB~Z1nI$i8M`vAzr)*Z1b~#Y~oH zHdWVoC1Nu?O-G-+?rQwyX_W&*l(M@`b1w9`LX;@~+lrP&YY{jq#?tVk{%6W@)Zm+@ zXpx?Kf2N)KmzwymVdmKk#d{I_4_4a6Vxmi>=~wvu{S+s=v7}lD`5B!ez37vT`qL*I z8gT}S@s@2gq+GC3PxV)MilUlB|CL+0|I^QCO$u$X7z1@R7Vw@?vk%}nuO4Zcc7X>d zQ_B)suUPb201rR9ApGiY;Ee0~w`X|=-ZhWHDBfymq?d=d7aTjP`(RQN&2JxdSg&x# z%QjfwUX-zyN~Qgw*4-BT;ntOBLg?6p{|C&)|7eYXExyzJ3qx7r|;1bW8uf09CF;DjXIQ9i%N{gK3TQzN? zv@9d?6p-+holebJZ#ID+1iI5s!3 zPm^^GPUbI#TuFH2uP1P5KQbuYcz`R4v*K>RHO!D5af>z<>{>U8p1(j%ik+qo!hD6< zy!!rz_L#g>C-vs$_HZ*X3oC?9$=P9=a(9A8$We9aaBmx46FM{QqKdk4rjm>w8A^JK z=N>MeT;owx`N*LF>5Jc$RqyV+$K`BfBwoeB|ERPL0cvZhV$S(xRmu_ zQ>lMM>Gz`QD&cD=hlc4JLFZMc%jfNvxnZN~{OBkxNYG-s(zOmQN3*D+Qa2wuvGwVMQ9*>Gf4mowH zuy$Ybs7_dWL`$E!jThShC<7KJo5I?3F1XliCAyqEAsjvQ7f|q)`CnO7Eb$L@c&nA>w^qC(*VO?Oz~1 zMETee9LVZ<*lo2QDd51fRUf)cOy+~kPb-IDII}U!?l0>?1(_61vF#l z+DI6ZUtD&qDcD5;v0tGt{4Cekt-P%qimn0kJ=$V#)&8=a$On55!-Gc5=aU!n>;y+( zdYXMyo%r%Isrc^UXA~h zTPvJ@FLh-khqT~=s~nQqn1+6*-;pHdr^MjUQd>JF7j+sN=S-f3{rbjKg-|DQ#oF9r z&2F7vemxC!KlL3~lIZYNLqPKu;5|Kb#Gh-ioWO4nXT~{zQKKcy?6k}(z{pY3G(rNQ z8yiyl%G4uGOfA4B-%uNwZvc4t5v6X@qIH-RMds3hNi7U7rlQ;7s;xK?Bv5_ zOByi*UN0DJK3{4m^zOkc^}$SWVKnr#n0TggtBvO-`;6(aM7)?(7)69p*_cpazTNsM1*m;3cv&dq?uk-Eb`D zsa-EY$x&=BdBcYkUF-=DX{iYgIv*<^D^w}NJWZcc_VOr|TFNgU7o*Ar9o)f4N)F3( zYKxsMc)0P=`ix~aLPz=6d@hiU_w>T$2s8tRmGWquYlgKc$GKPP;6I#^ms4S_My5mi zOL1UHaU-A!I1%i*V6343+We@c`7xv(%N@ zjCLq|78mQYA(34^%|YlzD6Ji$`A$J2;kAq=&xM@Gr3ZcbW?>+|LdDrg)H|)tGR;Hg zWh<@FI0X@+pAn`|0}`WZ&p)J@R@#d@{L$g|BJ7E&jlI$q2AYnU7HqDhvYVonlA{^z zqut;Pqe46>STb%x-}$uU((QdMTtWB=@c|8k31_fbBU>z>(I>ZfnfW2y0PZW3@3Th7BfaPDY{e`$QlnCayZwY^i8 zo8%x?QY@3^=R_Bt7^K&3Q;sZZp7|j4!3@@|XX|^96K{!p#|p+o#>`0)s?*J?TwLGh zEnTt9FLgg!cAQ@?z!0%0$Zf-`>=drfj&$%JK(3nk)<;4Zrl)`3WUxESJJR!7<4d^B zWA?d!DsPcGRandpb#U+;<&XLylM0kZ zkv+$uC2QsAe=Io09bW}~2XX2fwWKX*GzJF-d7@MyKOR{NQA;K4IjX81xEy?#RU0)tnUBqTPPy5vSPp_^A4E zI#QP!OKvPEEV;i&KH*V2)Mkr|LsCzts5!uk?p|j-zwFbw`wxDOTub$dy|jfQM=Q;s zg%gS>DTYbyO=NP2f*BvUScs)=tQzs7*nF4Y?<5*N=;trW62w5HC<>H zJMH6jxO_Mr4 zkJ=x#QuQOwB>2wt$spBcx+7={e2`Q)tZ}|T&GLAv&zsjuC+zT*P#N#8wy@ccNXtFq z3M=vO1?`Hu4M=%+?)eK#mdpz)^V;nWiIYEMx2yBv{sLK0_8q+#kZ3L>%WZEN)mt1b z%D0rqYgg1u^9;z>L}sKCF9EzaxK}V(6OH9%IRotKMS9eM4e>$OIpMvUp)1QlK@#I` zbPGL&g9*AACLiLceo_$O*ftqA=WO>v=*wIrT$UyD_K*3U^et{~9JRzs&#NaovO8ER zTFjP^$TrES#OTL>h;a?tYxuxzSZqm7>LZ6=>dyA- zvM5@}gAujEmU+o_HJTYsVd9A-{4pfPe5!-A_{-4}eZ9;FUpa$0qq3=^vaB3dbS(E> zojqnVH4OCyHa&^qc#zw+m|@8bQljGk7aA|%=*wjbm>Ut9Vy}9{cYMPxZ;6l@ceM@) zlM@iN*{Km>pOC2kIFxUj`KImr1%mg<+Ift04++WHb68-kGzm1J-Sc^qDw1#M`(IEo z{gZYbX2zQlC^ThcfM-Wv2CR=vfm6CZ(bK>CPD^OLO#K1>A1dNBrYHA?)WJ>IrTI~+ z<}S{&Ca11#O+0frj6T8Z_9c(1E_L@az2(D)>|3{kLDa7JX!a-sJcD96VG957n*B7K zt2qvEM5M-YJi0WBpuy)rQ&4oF7bXH?eJP)sGnjUutFt5U(%Ab&TqFEC%gQi!R#Tp8Wloq6x94jLNV^n{VFM=eXX#npH-q zS?pe+^e_r|5-F@!xc{a_IR7TM^H;ysfh2`*9VWj8ajbLy8wt40 zS}`9{H!eZAD#(Tg+0Wtk~?dzX*v z1PCh+Pb?W0Z*$`X|8&u2E5$E%wL~G`K}t`O$VS11H~Kvm3S49l%B-b?gIF{@ygG|E zefXqxon$}Z+rc-5Jtwt$AFqFky;MjD|8{0-_jZ7LXxZ`-Fn8d}IUU=!J7si5?q@tb zp=zj)g-WuI=q^3P@yDpqa|~-sLF=Fs*V2o$cJVgni%b00%rOPj@`mG^mU zrE?1)D$c1S#Wi{sS~lpVIVjpz*J%-YjG-g!G7fn@cBRUfmwYH@SUU?ZKppvQPm+^! zps-l8A{W2T8$a*y2$C?eUd8TJz!IjXfBPMHV(!;*` z{3R=}o!?ZK`Y5a2G2=psR$yaK-wE!MO?KVY2fMHa>UGJu>V_*tAS zwr9ymG%SMO!7(7i($O0CVqw_nX4}?0l~dwJauWA~Y~BtY+y{Ih?b&i=IM^x*r=a*C zX?tMFS}S%ZiaL)TsOXLpvhR$v;w(>4QRDw#Ik2v)cQ zOVVuBS!$wt!G08Ho$ayx)urdIPA3+9DW%7dvG+hwLO*=APWb%VQCTM;)l?1M3BM$f zo0^jdrVev$SdOL9C9kx@PnEYD>fUGS6iIGX(Cg+_7G1W4$tFd{-+5M%$jI6uzm;ep zUiaB)qe$J7ur}Z2htjtSXd<1^K8BS-3+FAN1U{*Gp7y4$FD(mnK^oheq^$mdn=@Hc zM}f&jx|+y883US1@KRTV&j(=IOby!+ORPoF5`{Vs3u5Hv^A}cyOTJE4Fjms%8OUJ^ z13|Yuqugtv)1_+A3W>XTU0Xa$M6D^b1Q6gYC=`w0ZfxfEM~En^+?BLbkL75sHIk9v zi!o&B?sD-%Fr9_Fc;Si^{Yfxca-3hlZb5gts*!7isJwuH$JWpWTtC;MoPmWM0`Gk`3zq(_`%W022>uZN)dcjzZV z3nr>?+D@FgjGwTS(H_^7Qw20YrkGA14)mq92t5t`P+aR}j<@-K8u6*sCkMDgX#~>I z-F;SguQn3xOAlt;-PP5Sa*l9uzsK!ZloIPX^wJZ5A2hjeo~gYeru))zrkCegA~(Ze z>SI^rY7Z;V9zrgi@WV`0#uU~hQW&+r58I9j^yyaGhC|aN)|K{{#=@qPQb8hMGmU{f zRpnjv_fVp!9?K#=u-4*Jf2;oC=Y$y5R9Q4sI;7gMkz0UQ`+M%=cDQGoFk-HJiBf4H zP}n}}h6XTP<8g$kNf+$aL#TLNjClB)lbyVe(%-k!pw8lLGT3X~f$g(ATu=4&tGw&nv|QyiD6-A~wOy4N3b z5j6)1Q9VbfD#Ht}FVeRXBl;P(Jvdy&J;L=abj{_e{f6Yg31fqTCf8c9eKgr`f+7bw>&swKNNt5L=rU zgM1;|R=G?~*pr}#o<{_iFrL_zc#9T&c61Y|OXAyC-61o;HJG6FXj08lgELb7D(f={qGmsMPSbaW>tZsh@-Ve$87U&uue0|Krs4hQqO()uDbo&aq9$lulz?(GTa%v_p zdGoit)LG7mzfGa-367|_b#lZn?oJr=_<{YX7<~Tg5ta!L>rMhv2*1FFW(j@t>x?)_ zTS`mH*yHu3M)CM})#;#KM#CtHO(%?`t&v1qCSP^6;5WM32l}Rol@hU(p$(3yZxUA1 zcO9;B#vhoveAJ7c-rVZZ%$`=)OftC+OKr5j3aCyx5fA?KJcgd)xETI%^od50;d%8* zm0P1&I>wT1k~tph(sUtt^W^D^=6E=b8ZR2i zJ5sWWQ#^%)#yFDKI!Sg=zm6 zTwfzbkX%?HeYea$T2LErgBI6l@{9I9c+*n$hxD%1rN={-!$L#_YQY#Q%j@zxw6 z3l(Q%O=mhulU73J4LBFN;+C`lUn(dJVuw~N_vXmS>vimiqQEM5p4khQ$~tp*;Tt<9 z-*Y6WCckLcwi6v8zt+Z+R54G1;`I*8Y3Tt@0oVBqS`}fX9;d3aF4_XDo41Zyyu5Yw zb+PkNQUybmbvmy+gtJmpP)rY6$Y*NS(PueAo+Un~(H+Oja}I5CFUhfepPZ;E^X9X4 z_go*8MF7qO3*{iHI^T}Pr`^za5)=QhW_5g!cm0TkH75aTNww0R)^<$>Cv6zBm-J0bL)qkyag&Y*)2VZRGXl?MZ~yU{wYU~7#-;32|d}2D^l@E2>VUH z%LY$~&&B{6p}^%#!=il9SN1qeS@(^2P4Xm<)uUQE$9Kg_;&>*JGF*0-Srp%&G%4`e zv(FexnpWp$c?TJ*KFU(nRBG7;%y2ruN;hGfT`Ynq(9|hS);UWYOEgEJ!5lr~;EF}f zDYV2;pP$P@F`*|tL&t}say4qZ3QbLcD};mfyO3%AI!sMzdb*Tj1^EHCIdu`o^8k{)tfQ5erT4it*Yqesn|P@gy9kPrEdu!*iH{)fl|u^+TNE6)Nn)e4zoALO z#367gN4_Q6oFaf*klG~dA)$72dLf@q=<7R?y$W)E5C8hU{-bbjF2Y9%e%p;A^~B>Q z+2T*Ln4VSa?iU47X9zo;P7a{{E9{*02>3wC7)Yy1aWH0aE@cJL(j?YV5^Upem@gUX4G1UM3c4yb`3Ia9;+*`+^&6CxAPjor@ zTBCIAv&x@cj;$-k3cKd?S1KEPpS<&(Q+7iMEvQOcXCT|wX;^oDH#`(gv#xwUVl_=P z?I{fox^Up$^-+lkX1|rnG0fN7SFc#HjCY=27XKZyI56H|VzB-l&OzeIx?)O@R3kUv z#>Lk2WGnE2k1wyj;sS@^yy^Qa+O{u7ix^DbCeN^mbpt|F-rd(u)d`M}qU)Aa4YdzP za0o1Ty4^pc?)hdxCI%NG8)2q>KW))v)S;4t?w6H!z>&f%_clw2wI|paQ z2H~@{LTyvMBT-!3*`oGOr%bHiPx*RIyyj&}vN}`ilcengvfJUmZ?wy50)T5H1(77i|GDIsF6@Vb82pO7ec@C3viyOGsR zm*gc@0YhRsU5_BGmg)CXr>y2DPV^d3BfIw_%;678qT;v1_N-G$Nx-5aQi zOgkb(@z!2su~Wux^m!=0_jsu-m-(}MJua$Lo}&OK9k&@)>E{&eACHouq6zKRqv2pz-g#KyN2Tl<95gLOq@?jTeKuzn(e3)-I5 z!~rXUu#=Lnw@EqM-N#c2s{%tM6txHln!z-_@H&;}>OWl;-<#)IH~h}YS5t(;jV1^6 z(sTNUzMGway1a$AOgeI(&C<2jWnJ-DgJ}P%4b;^9RY65nFAB01AP(LPuS@Q1eOt^? zqIA=7*fmowY42v6X>E+s;W&DV#ojlPM}*WB>Vt?+0_Z4~n0#cAn#2swe)j|*B$^W} z^VwAeKaj781bF`|W<H_@51!1TrX9Z$qVtC+0StHR{sSk0dBPJ>XNjpGo4+uWlCfH zHN7WwMoB9oRmuy~Bm)P7AnK=ulN~;HhVL=~axZ?q;kj&WCVF=&wXRRr- z$s>b0Z5Pg&%nk79yaC7pT0*zHr~Dg%S+8I!q(KQ zSX`ybAlP-2> z{G{>X2mFW^bLq|BAgF|5Vqt@mk)y-b_-LC@t7gv97$eMNHN9-{}yhf;IfDWiR2ak;FmIZsmnxucf}Cc^DdK=-CADjh(LlbUw^pOzR=Vs)bxE1p6H0xuTHkTyR3g+TQfh|N+Ej1 zWv~xEd>Fg@N>?_)|32Fa$L*F&Yk9lcp7>ChswWzP_K^TBtD*q=n@y zr!|m~Tv|Z32F}vVPu$v`#wIEf52n6S&~TJ!H`E~R$`a8zDHF=ils9Lk4g}~)beLA9 zO1p6Gd~uWb{bGihp<~;}ZJ1&zv9|9)(;i1cj|TmE_0?s?0mA+1%gH?ca>cfo;T+P8 z7!6d$muubqDHav^r3HMWtZ)1$xbyCC-4}KvE)eU4)M{*e$1F_079g~TzDdiY^Ch$i)KG?`eg$H>%rtQrM~RAha`7QR*InAtr~e*b0&Q!K{Xzl3F~SfT6)oPis@9J0 zOp?oT9mQZy&{?V#4}G&C-eH|5TtpP2<;E-K{h$d_i+`fjs(of@S$xkc(H$rJJUZMs znd;-*2Alq>$|4t0k|v^NpL%l3e6oE~H+B4-WR1!Xs1mw3v`m1T|9YpWdlOX)75r$0 zkwyG9Hy zgtLA#1zpY*Gj-WxlCv^&$4xrT8W1y19sdrODSB*;eJ~6}YU`nk&y0;EbX#GZE^)DR zse5Ugslqh5tRA#9al3CZrV!I9Uzy|S8^y~%;a4nJ-j~i>dJfl!W)Cy<5rpMd?HS)a zx?~1{yq6Jp9W}9(VePfgzg2DEX)!2So2e%sV|wB!2%E;h**g<_aK7YXNX?t6s$P~l zl$bJVncTwA`6M?(Tgn56uKFDXi4t7|j)Utl>Alq!V zPxQxTmK(2a3Hpc|V#pMBp=tuSW5$9I&{E@hV1xNBf!yD-pRznmh0Wxe|8d3#3#KaDqe|@$+@T5_ z3l2Jy_p__xpzF|wW^FI;P?(@O@V=5HN@~r$Yi6+Jn721*X#ma_lz!4RO<%%P`zRAa z#cBMw4KFHSiLK)^gYpRp>><}-G_qc(g8SqFp+8ulVc8)=3T4}U19}1jAU=sVbv%k zH9oA}e4h4Q?BCRl-yWKhlB&^lCBg^^tu-#d)zJnSN}rtqf)VM9xgHr$F2L`0=Z+IEN_6 zUf*L>vo&yrN2}+(*}=`Ib?%~e6D5mb&1RSeYFCOmK2PC8Yw)$K(=u6W^s=EON+z8) zw{28PD6VO+3Y&p34RxhOI;!rwu74>r4O(>_R2cf zSat~Arw~^LaWQ|X1{~^%x`Af64;P$8O_QOe6CXxUx#plbQJ4ZRH$!_iev z)E9U4B0kCH+jsRwGGO;s7#}pxfe)+N-^(`2&_@B^sFg!5#bQ~fdyQXPUwq-ekcxu7 zVe5;|oO%o8m)s=YI65TET`q`ne?ofyOQIO|6#^bggjR+qRpuB;V{(*7uUg>Ajtc?! zL2Z;5Vd6Lmf$n$7R>D(xC(X{Aw?m#=Qw`?fHOC}kKD^f42}75qE{oQ_*RLYhs=mz9RG0cTLh{V#H`Oa3-#ZL_`>Ug})SM)+c(Ndm$&T zUWaDq=$6NZQ9I20{iq>Lp*%kQ81NUk^aEYrLvQmAUYHx2&zo0&UTtwk>tN#G-{`=9 zN=C7H1Mj-n^XBR>wPs{om~gY_;dGIvF3!txxT7ZmwfhHV2b?hy4(_MmYD|P_Jh<;u z6Z0OcI+Gb5#aoqOTI(kkGnRmzCEDx$@NLmq2}bj ziIPM2Lo&sr1GRk*gr%4%?FF_QbVZ5dE|WKzfg0M9H5QTzpUQvsmNTQQGAnrUU;G(Y zD^=&Ejiwx36-(`OOFGH9*2%Qyi!6uao@fnO8pixv13Cd_M zJnGm@C(X!#J)Ht0IkwQtnfikdnp$nPvKzxnKJe_8xblyfZ)4S^Yt<1!IG1o9L?PFND@RV2La&$?+7&_wDEwoGuo4$_TFAx~(`mwK8 zoR0nR6P=hU44fYp$a%!dhpYGNO%$DE-k|9_d_7Y@mtuD@UDb^ow>e0Ngz!yAi{2Jl=KDXlK! zyoquEd{aBgbJxdhsL5uuH4X%{n%vW{+&x_~6|ITfsQsfpe4l;MB{4@ia+EBTE#<=f zT@3I;Q~b(>2g>tFpqQcHA@{; zZV^|Sr^}9H&RkJ_gf}hd+pE0VbNJ^{h)aIUfX%|Xos^_0N~nomkk@+~w;o47F=jbu z+6;^0?*}I%g+jr4G?2R$s_FOzLbAPbLGWP=EZDWzR z`H6q>Jdi9-`k)C@kZ~8GaCQ{kpYt5bKUk5p(Sz&<1BcE(Wt$#Iwuz6JGQB87bQp)h z?-s4mRpM~_A&hk{!PFoliQITd{7tK~9Wx7nG;N21xZr+;vDQPNCU44d!wM+K%fi3? zyYEU!|47JDX3zf|cH&wsNbf&R0+$`d`hByB>bWmtLKmueKqX3}HL8p?Gw)AW>l^T& zuvQ@SZ)ohFlK=jveg54y|9R5m-+l9U-~4yx^WWpa_yRTi%FxK=S~rxzV?PRo!C53!5;Bi0Ie9Ku>J$5TQMubwH>82uLt`0H>yZ(?ZbS4g9+Y{~m*X zPm;fvng5v!HIQXLm0jT&-X1;&$Deca56dy1;)&Bz>FW?t8@h8^Z(7!-? zOn=Y-VEzFpl>QbcvpMet-?;~Th5HAJ0IMVbW5)j-`dPqs=a*Rm;GuJ#_6+|7{9Ewu zAJ77KGJ1@@_`Q$}`B0FA(Z(CGdz(A_ZU|A#iBA^$rPz!@0r z3I3eR?@2n(`XM(fYuMV{ndI&`H#VDZj;zh1?Vz(&>NWsS!~M%GK@5Q9f*cVKFQgCT z9|y)bhQ+nd1G7+^8Aw1fyfz@1-fi_A-`NX>qq z#Hq?tiw`6igSJ(|3oS`E#5?bqvYMk`5E{eWvX6~FM2Yhw%t!JFB^DLD<}7Yt>c{J7 zrp-->cK1#b zXL~%PFR=0e>hA&8ih$b{_=+gvFAz)~@ZwyY={>q2K~&xjO&Pa^Qn@0N*Tjz~2#o(@mNKZ`oAo~7N%zxYQ1hK}sOV6%(3lYgQC zUUna_%OL>2aEVhsBL3a-zx({}(ef`R^xre|@3rOcRq_AWsyM5t2Z(oo3HdK!@zDGQ zr_~R@Nj8A=R|P)D`e#rK!0rVAbM{RC83BBuX8%GSai{fy3_$Sci_|b6AXEI`fa`{( z4s3pq_1nQ$z;3Hwv-J)lv~GRJ^x`jcPY1})G5#43=M;6oPYhsq0O!pCLoYMHITqW_GvhN8fE{jBCsPK-#}Q!L%}Zw z^5$*v*o*6JmU~y}gog!R&p4aBm5iO(wxG8+5hklZ@ITD0iy726-Uf0Ea$g-YDPNxC z*82}e99;nRku2N4(0peOfZNN$Xse`F_Xl{M9%nno2d1gBRfy1q&yH>wut1iqP`^eWJkI8Epgyy6?@403fRjWIPtgN3l%9#2Z82w2ra~8qe@cPj zX)XV~4$JeB^$xax(=wtK<0EDU>U|@)ou@P1%2=ErqlSDetQ}gqQQz~NxLn0=*Ryn< zGUMtR)JF&= zU2WO-Dlq3lU?42N%0>s#F<2d=9g~MssW=;1eTi`TKq;k8h(pX0 z?YqQiyv`e5+Ivz~J13Hi>}eIcI+;a$5>P!SE=oH>CH5^p(CPPNrMrpAM=h^Km4>jS zN419F+I-VTl{ZmfT!l`WF_&RnpMazFr(RsO;_Ag_QO2Z^ceK^MOY(uRCI-IRsZHhk z!>)0H>=i-k_04tC<+HENF4-*_OSNcghl$dd@2Q+LQYG6cF+IA^dg{>v1die{_y-+d zeXbDhgmJ_QEgAh3RsJMC6VlSLi0Ut>zkHHC{0m;#A0~?Pol;`kh1F!Ofhny zD_U|oM$~b%P1_xYg-;Sl8hj#DEB{23@$g3xTnqb}#l*FV3e6p#^vg8>BC(j%cwO!8G zL?UljqwW)WPvLs%@)G55YA%=owl_6PHSHcM!jg>SVk3fyY1_Ijm=$ZaaD5$6KcBmK zY*J35rf+aMI^@`6t?4cK`aCYEaPTImW>T$NiU{WwTqw6bwZ0G%2LohoYBD9qPQImk$}hyg9))*H{-# z)VF~UQh99uT00XNW;CBGGk&`>ar1;mDm#AaYR^2M?Pb*Fp5zh$!_&63g_1&qvb8qV z+nE%tIqJ+RVi(CD)v%=7jTI1c8X#scBrXTD8(w{kAd7>a6R+)+z6S$EU!?4B ze)@XLjn55tg;3nSe)t%MeXS9eHc#<*G&@FDa9`ete6r-miNHFyMle3^t!SOGKc-C` zk9x>H%rL3L4)Ih#=Wo%eZ7*>eyNx@@dND(2?!+X?iNIE9|Xf@!+MwS?{nO zg1DZKbfu@|Jm7Ari_$>XPO4Z%uWeibjaH^CS+^jwpgJCWxZ{kSlji|enl@ma zYb$LWvTiW>OyP?*g(BkCPQ)lrG1F*|ahL>1HTfqF*mOUmZcq2&C>3#3@_r##S!fGT z`y4<;XtBj8YPxi|Lfkyd=<3gzWB#=R12!j9hJp^0uK!X7?PC2WWi4+?MW4=aNfZ>O7&wk2<(BPIev`p-F~1bu z5>yIkvz@S8$i`6+Aq(rAQfp2N&8mP_ItyGMF8U;!hIQooAp~sN?hSm6!q=}uBic^5 z&=m^4S}gLkv1h#I%QuHc)3hYPvGt%t_C*zXCeY@R2pYarl*8jj)_>3j)E$ovDP0Y! zN4({edavw}3+bgk+cAV1grhkzixW*n?|luWGtyh7%V%RKqJ(rPl`5?Hfqxob?`w@6 z;wazsGh(L_ezu@DPBMTc!&x<#)Oh6}(wXuOQuQ|2hM}6z8aaVF`c$sQ<2YNkIG87T z?F5dCuGYjRVk6XT=lA?atmPBn`UOqzX2eJEWnw_}cu_-qNg@50%!mPbe zn9Du=lQ@=IX<4D(($bfSFWOGhx2hcj>Db%f$%S99q2>1E64wxYWw) zXee)hy#2V87&~u*8<|k<&y)yzqy&Qx=f^4_s&lSZpXcGPIl24U?L7nrb!dXo)LUxT zVVMHcjWt|5zZdkTy5T0)&?#y!DYwGhg4|;|t2&IzH%@Fdjs4VY-cKYnl#!dzayj@D zu4NSoDT-D6yFt_@w@ZE-+*|j^%Dygh8yiAQPNaKfnuVknqNz#w@av6W!$=BeXOeAo zZZ*^8dX+8jA<%A#OWX^0typKj50RqI>jmy{i7D||Oy1E;6hsy~A#l7M8cgwFn7LfT z27L1TxO#A-P=w=m|x=X2x4;``9<~)w}3^_w_w=C7pU$%(} z3nLvw#dX;Z)#6gQaoblk$iCaQj3dE^l+*={%52g&Tp~#95VMXvc=O*PZkgdO5s)i}VR5Z@iB6iA7X@I#yj1plp)EsNkq=(s3 z|KX+a7wMNNmsmZu zL~A+-&7dX?tW0rf7D=LCSpHXA*BaEs6@|BhHngRqP5B!tZhjJ&7zi~#4!yh z1}RM`%}^_asi06ASVi6z8I=S($YcbWnAWH`0}Noz5KFMo0#X_WT0ve$WT*s;Y{;_d z-RuT7%DM(KI)8zekf1@PIpc_NTHbl5h}hdS(~#R}$Swz)*}SodCpG-CEZ+)e;$6u9jls)G z&l$Ul)-)8>6&-gsultDa1r_#$2~INDa9yI@ZD2)xkf=d3~2)Xglh=yD2fDqW3PhN*~)84h&PNj9Wh8B zO(ak=!q`IP;M7i|A3S{q%$D|zQ)hY*O~Uu!o92{Qfw8#K0xe?`VC&UW7axL~sU_uO zpkK%e$2N12nUPlk3nk)31P3igfqzD7;8ktaj9XKH@9Y>h-_>b5rY~5aGYW927LyKy zMw7PM2`y-CsI~zdG350dZ{5PKfGe*jRi)PsJVV#d$=D_+LpusyR8=CkD#rH+05@di z?r=LF4=DDUYXvVq%wa0y!3JLu%DWEhwOv-R)%Yq?TdXfR%scB#1=7Oky=j5&v8QBl z>}GM|f^!cJ{@@!(M`Kgtq=Y}Dq(AmZVvnga+ez%IVs34e`qAm9LS)oo*j&=+79=Nl z3@4o3b=3EL)JhzU1_rh{eWNOmGy(WF-Lr z1w#ZKVJ>zST>KpAl9nzIm7t(UBqH zpk=*GC}NF{XDIImqSv9~RBKt` zH55OwvNgZN3EMu9)elu{b5gHe1^-I-tn<7YulxcVv_QqxlNRXt1miL2jvsWf!$ZDi znv4ZA2<~&i{4vsX4F;F>h692{wNB^ZnTPM1)E3BfU+`Hbmf2!Gw)46}q`pE3gVw^Z z5^Or(;ZF*sM+|Fnp#Eld3P|lw1KY4U63-5Uog&cnvoXY~EqFeG+YN3CysGcpp&qhs zoB$HM_^V&X1g#JBXIdJD5)T!~NoB6mk7>!}82Dj$L;coGs>Tgvsp{s}=AUIM=G7c* z?l8d#-S`|tvwPup`Z3)>`D$+qRL&Dwb+5q(%JD3J#9)DNANy40qkA?1-9pHLAmej$ zM5Y<=WyQ9aZQyPw$0d^_#;M`eh`#fI1p+;t;j1(&LQ(p30G_xAPItXaMt+pe2B1V5 z9`Ep9Qa!=-KL>g!Im-RbpbuoTiH_!M&IU@?Q%b`Ppi0Rp)2XDemSEQaiQv1pE=P9$ zk<&Oz6oy`SN=7R!cGP=fn`T8bW3iEK5z z2jqYJaiaE?_>&n%L7e73}d2E#MK$QVF3OxhyRv$tk-Nh(>G` zxHYKP)l$y!^Ls_m>1mbVtLMzW)K7sR``> literal 0 HcmV?d00001 diff --git a/Firmware_1.26b/Documentation/Upload.jpg b/Firmware_1.26b/Documentation/Upload.jpg new file mode 100644 index 0000000000000000000000000000000000000000..7c78e5189d74fc99d41d2076ae7215df2c87a168 GIT binary patch literal 64058 zcmeFZ2UJwcwl2KL2neF&EJ2chB*`?2WF<;Yl0kA#LMsX?0!>B{$p}c29F-_J=bUrS zvFZMoy0>n<=e={!d-uQN-0^lh*08!))vP(c8EUSYwLlIdr-4iI(sI%O3JMDF0Q?6a zXD;<06K~YfC{$IZyPxQ&#eG-u#E!VkdJ%!^?$GjaH(#U3cv!J zc;I(&@B*k-zu)=V{`>Pc0)Hd$Hv)en@HYZ~Bk=zq0vMra-!cdyFjIIPivFXW9Uk_r zjV34v0O8?3+ds1j?4YlB{hdwxKWH_7i~KhNeEhxb%*AEr%xPq5Z*0bCVsFdkVdTKY&3S_h z5QTU+7@1g`xzHJ#Syh5?Gt*g_iZN^Q-@9?oLDJ09O4iHCOwCL2zKNH$iI6EX zMEoL-sE4qJt%I$ZixHiNt&N?tu!k7^H|oM*`|HnK^x~pUrsl$`cclO50e%ys|AQBI zcXv*AUQT-_3odRUAtA0CJX}0H9AFO)XHPp9BM%NcXNErr+%a=Dak6r7v9hSXh6Zc`I3GaEBoGdmY&5DjiFdamzG|5wckLiA(Oe+WM)BiKh+(#g!o#q17v ziGNim#|>T%ZvOj!s+dzykXMxJw|=5rU%~hbqyM#>|EJIr7d15zHu=iCz0>#U)yy3K z@3d`WB@S-2eHRXFe{Xhmv^a3w5Bmg1()~Al{+{Gt0{L&a z{)X#cLf~KO{I_-e4cEVfz`xY_Z|nLW2G`FV*USz~Y~8^O7C8n;0$3Orm>B3-m>8JY zSXkINgt%aifkRAi36GGBn1Y;)n2eN?hWRQbH4`-{89gUG6ALT*b#@9mE?zD+9%eRn zwy#7`u&}XlF5nR1;u5h@kx{Yz%O7M7K!}Z+fkugjLJy!4qM#9?AR7Q$u+E49Rwlm| zC;#}MprWB;U}9lkz`+GO6kh^RQP9v((a|t4(801KiVt`nKqthwe3kna<`oqqEP6*G zo+n{R*bKMxYl&5Rwi$Vio%}A~kdTs*Q!rg)W?^OHHMa3nh zW#tuh^$lMdo0?l%d;9ta28V`6MrUT{<`)*1mRDAHcK7xV4v&scPQS{90-${t>xX2& z$wdgtg^G@jhK}`BE)-OE@IoU*$GFOkdHI$KmXYHXdY&iPM7P6|@@p?J@TzVT8$0#j zkTCMiFztL5?VDu(Il=t?k0kpc*iX4e0X#GmPl1o z+%4r`G;#>#6;!ubazGrd=o)Tkm?440Vyb$t;%Nq$8ZXki=xg2{^kLWe2 z5XyTLUy3iPE^~(vtJYp}b;42!#}qu>(ZAUCMw->8g0qQn0mo%RK6vx=^LdCNf*7xQ zpO*F*0||_=AOU|#u5+v=1Pb)9wXqLwHMf_oKwcEPlPDD1KJw%v%@hls;7Y{F&<9K5 z2CvQFi~Ej6*GIICpr5Wh4N&V#I{c84uH^001`m0}$r->}Ok)b)tX6yW3t7mFavKu3 zwSxp68=e<@;t6aTRcPBZoOeGHJUQQjck%wx+wl0lDiY}Sfo|g>ffCKMes|JKqq+)? zuGbxI;gE)Fld&Z~36~QEu)M@lcF$r?unG;JAR@e-kQo&PaGHbfP|3jAgrLjf)!)Qq z@6Id6)fZ7H>$hjRU}cM|bUl#-Cs2T-rbQHgK-8|FvEXX!N4)fY3bE8mu5xIo_jkqw zK*r<*&asA&08o8qM!TJP4b;Uc5|}1M0yep8Izuj9_*PC2DJJIK-148s_@++Bu~6mL zhyrq7l)N)WR}QnBJ-K3VTd3s6O4R*>XdM3x# z+N!Tcc)OP>A8<&FGu`z1MDx7=O->WVyD6^Ve zoDL4t9c>d~=@hsTtZTd!+~I%pr|jQU)=3J=KJ^34@3PN*SD(9A?x(cn;D;4y>uy_~ zJhk?erbW5!L>MY93o*=zor)OJlMH=ohWZq8%pp6SSA4Rwh=NOf2O{&LJ4%@?jU5Q6 zK=Y{jynwj1K9n$t1lnhiz%P~!JHF5J7t4LGB2yF-GhW>+7WW8ogs^yn1nQDNRs6vY z?Ju5f@J5QJ*TB#T3D6xn?ww7Y#9JT%oB+d90@!!Efc|x?ml=__oG0jYPe+=%wxEli z32-)Y(Apv2d`9J$kx?s=DjQ4-M_juE7POF0NZ`#P^p~kYPx(1k^WU25zZx0X{;LUk z>Hh{vI-HI5M*v`j&Zyq|85|6ven;C1#4H3vJMUW{1Y;1WiJvj(H%-QZnoRxaRG{7? z2u@(%hwgu1ISl_EmtfzlWDg`(2>p{57~1O6-XflY0r6WfycYPUP0f7^24e`~>r?wQ ze*}Z-?aZaW`jzZ&ekA~6pal8uhA<>Rm4YA^MFQW<9|Cv!ME`^Mko(t2Gxh!USL)zx z*s=N*P)JYcHZ~I2Y26QGIfQ);%QPMC-vVj}Xx?gFe}Kk-1e(4s7AoLuF`z$voh=V! z#}fYCA->U{LlEBqr~i#UZ_ye z*?)uZPfnFUyng_ynf8yA^AllEInMv<&i~ja|BUc?cYnkCYaIJE?EN)X|Ff_Mdi+1_ z{wwvb_WsAxZxHjl$^IE2zS|wR$jbe)$o^?p-(%Gt?Xg-fwEGeC+tQVSAlgs(GY4Sr z%lHx8ziYl7GNV}iXHo#RA?J9sCrn_vz}~m~54wUTfdqEJwYNkSTK5)uN`M6BK^w8j zQ~nJ;E)YIY%{QRmZi7sWf%XSQ0*v6|>gE5N|3cxc=|~{y>G#{raMt&Kd_w|Y@8I8h zyTe(dfAkiH%-k*ggXfWOIIDgVp+O*v#0@F=$BcSLQ$=>Rx~2?hkV1 zKcyBvVEYkUzB|V5)UoOkB7guMfdtlmNxsl{h{JRT{q%Yk$ESJ6 zm&R9EaGhx|4R{k?vx;ar+-j62m-}HO-`p1oAc+1t9agO$WbsdOXbM9duCFSGvq`kC z7KYv#(v^u|jC+2^W+9L;K(L0HobiS}+pk``Q%wlxv&Z-FUAm7LI#UWOJTf#NsdV;V ztD4)gNOOEJuUYyCR6)3VCTLk)=M+&hY)F75O-+k=?G&HlUY=6_sb3&V#`PKB%SfO( z??={~;Y+Veub1}GX3M}p9bn1-V?Bh zEGbXXTN#YCiP6xcH40HTt0F}mRih70!)`;YiI6(9sLHZA$Rr`Fy3 zhB@?RykywJZdrhTg757)%UMlB@N^7tD}Aof3W!7&7G?-_-p;4Fno^S}lqupJ88fIP>Re|jhET;2x5-5Ui%iJ|hVwBi$8jCa1Flog4Osf^vhxxv z`ioAIOM2(=4d^}=_!A-l&$#?)Q@?n>Vz?#tc5#L%?FNSk5>U9B8=YlnbvPPTQ0q;0ophFqA2>$}Y7Lj7N zIyI!U3)fyer11S@pQZiK*SDB)&%^KVLQ=eEEJh&`kmX*acYD?xlr<;%82<(<0#pC~ zYRN?h*B!U(^N0zGHwo*DOYAV__7m}=H!z0zv7uw@9?R6C3nC>*AZH8A3Ti%;zWYqK ze8i3yjP7N-Dw=db-8_6agE^6r{egS!ey)g)?%9TG@mmE$!cl{VBsUXARHO^(rP!Jm z1{ajql?5{C4P!7$<`+NR4kU@*MFLL|#$H)e)h`wjw70v@ZYFrZNb(;Buo_(*G5!Q| zd5i~tty)`M*+s0W7VBM2yYlj3MO1B3*)?77cVdIR6Qb#u9!sMiI^F$i-Ork^v9F7; zvFJbz66OUySh6Gsq7$h|0soyBF?G9=Sa!aYXml4nv34?!0gp5q=d>n6Ml(Y{MR*{v z2qs*l14v-mdk5?MxDN@OkW}DW#^Y)wM|*M_@Zt2y6Nx^5PCX5qRi`W};eXZTFz zz3c1m%wn{H$dFf;zYPVA+bhW5Skib1~^PoXCD#wV`TGZnz z4QIXoqUZtvm0$K)zlsD^UPIRjvrc;N*JwZ8?5kq1w&)DLg#@J2Jb2D~G`VK- zG*1a>XCYFj@jIT09tDV93wx4RxF%P36N~b1-?j*6QOnwqRM$r-grQk$`-Ascopqyp;@|be z@m_aHao2ILJX5ON6G%FSrt(xC>+1FImqkkl_bF9#keM;^gt|ZQ!)C~DP7Nm@@sN6U zc%5fSKXh_0Cehz64@$*?VJ^`RHDZfPn!m8?tCC06{Nt7I+ z6mxnOa;g<)>(0b-rj<3hx;a#`HffN#a!f%2z4VCLlQQ<$6}cCw%BE)sYS0mle&Dt8t~X zKl!Bnf-yAFgjgkGAoBEJ-<;pUWif7hW4YJSJ1Z;4D>tTK=zV(1F|T%i)jg)eV%`@; zFZJrv$DY-i-M$qWj&kxz7*A8vKy3T-_^?O15~*;1h8-M&9({P%2v=~=f=P3Ja*T&; zrT}->@v)fGrmS&6yh8LCj&uiubKR4cxzP^^JgIS|H=1@uO=sl1Ge>kwq7Qt|3VHgz z#1iix_2@n<$sWAINQ&N!no>TR6;aFd*#Po_aIl1Zaf4F-V=o-{W|-;q+)bwV$=$J* z2NrlSRtOj;%1NL!l?fFUF%`*hf0f*vw#MW=$uC~|!Nn)#0Y;8aC5~FHmC&9^L#Du% z02_9v+ZK+ZaWjUoY^~sipWzUkd(7~9uy8?D|APdMh02FR1#%^MyDQ%By)pAZ21wqil zXN~-R=&U_*lCj{iwic*68F%9cgpSY^w1PyikAMYD(CN7?J*&C>z zmM*&*Q1-wj-|NetZoPmO8;3JBm`|AO&UdxnqW;jCK1YkUT>8FCYlkKxeS!t=LB;1l zW?)}L`$_7yU8Zx+F@tpfR^Z#WSuAO<6Kgo{n?4z1E>_uj4i69oA5D#_&x^})qQqsI zD^KJ2v*fGZ$)&!lV2plM(7lozb?qgS|Df!IBtug31FuWofwo^7ZbtWx>nl)Qy6rz7 zEsc|rXd12rpiEY6Deg$8JI)qAJ#+5t$4_^(b)1=EU zxU!!x71~7U1VrBXNWFb_Gq7Imqwpj5y3^s2w!*fuJV@qOTpZF z#~LK3r=FW7-0z*byT@0@5pgffeC+VG8;q}0lOgC`+$oNE&a98KDy&h%D?0zZB$b<2 zB<*mQ$18`hRQrXB+W8AY$~k4Nt&*34Y4-5qA!`H}?Rljri&tYNy>EYX#e2pR7J93h zKDsK|kmRBAama2X?d9v5B&8)cv@Dac74(}JmC0{4PuAF*w}uslHw2-q?(>jl@D z&^mA%9QEJm!dIKMhey0qTOmaR%Ws=OSn@oN--6GfOZQKukU)xR)kURNwgouZ?NeYaM{ z&Zn&w%3`-t+noEF(K*XG=0k~-W4aFoXl&D}{rPy2fEb5s8V^CDb`(@TM8SGZ4Cm-> z{tn4=S6e8(oJ;tsa!N}n7D{`^3M|cYz~8?!-J3csh=Z?}iY;&Nka%+B5sTZin@O3^ zLPJ!^j!=%nc~3OMVDZ}EmO)kjg8kN6_&I^eg@%((w#mjwJ>$XC9DbdaDJ8XTTg1&{ zH=tx_P(Y(MakR~@N9pohK}9LUGTUb6TnAP|Jn`qk!hYjo>oJR$2D6LUt#;^6IduGU z6-c1|oupiecb1UUJ~qz`80!wkI%Rsxww)Y2i9gd6U)LwqB~Ves^@Sm52N)> zDf;y(a&k3&Ee%ff#cX{>BT6lXhWXmwPH^2kHd>W0ZcOzTb9vVt5(F2|XnKYRR-a zogE~~1$<2WSVVAw0PUbQ7~ChJ&Wnf4T0*E!G-&>YCN3HVc! z^%Cs(wkz$)mNgRa5dhOD8TeIU82qRh348_};$_xp#ildVTIob(AM)!+P(XkGL}=GR zIs(rYa=h`VBg-;ISRmps<|TY$>`{RtcSt$fVD<`v zwX*LtpZ^n@U_}XAF$J{84d@oQJ2d-{9fmbErqd=Gp-cP{_oIeQD5eh!$Rh1%AL70b zITFCdl|TXsYf5mkQRvPnkd&2uQ^8)aiv>f0CR($IgfHa zEz7LwlfDpTHOZ;v#Wo2!R884nq{=|ISlbQKoO{!&Ae?#7Ho7_)tGi&=G`7IW#hJeD zZM`G><9Fz(3L<{E?R2MD` zZE2ir9mi2gs;DI?D$S|hdsKRU(GbmN4J@dEwZua8a!EOiKHN7N`hB+7Rw7w1azYjo zfs0R%9c$NGbUtGuftamS=o!D&b@#9f$~xnhOhdC6a}6p?ijNCO<-jgoZFG$JX62e zPw8;&<$FKbs2=r4jp%Wr&kF@4>Z`j^zBoemz{4ivl1Sj8#!_U+np*5GICj- zv&XobPS#j;u_5VBrdLw*#$tpb%i3*+l7#3htf(?^=-n^&=L*i_FHJ$79Cj$+YVjT4 z)o|mf3#olgiWN~h09NdUeF_?!5#YXm48a+gwiOIk`|pZ!TNjzmZ1WB+J#5~Yf|o(Z zl+L4zt8RRG#9>pb5K85*XA0kF;(Oj*S2eh3Nc@F;Ofg<|x8w7s*4{Bqa)po7q!PhI zRoIEmV5j_*ch#)335+WIz2n8Ns&@Rql%LbFOVQ`~`M%ipgvu*R_l8WvarqmL%bs(4 z?-|-bFOu>nQjx&;H@avdvJDlm!mKUmnK~Mtpb3a;37zC0Q>kNAmG_OyS3IdMC8afg z!w9nmH)0CB!Q8hrXXR)#>Pxo9F5?a9NfU*jf{!atj(h7<$2&Z!8*|(^A4R-Qxigwn zUFCC+2Zx3yR;WlYmYn3)q5p!em~zf64o zF?IZi_aQ>vWi41&A+$JE4Vdzz;8Cx}S>=Sxtr{LZ-zDx{HY7NJU9!r8K0NHMnSaJx ziFz!^2&4!3u@4=YV3&)(+7+iS%u*v(C7N@0KZ!Hi(a1Ha=>wo!p7yZTkM@uvu3Vbg zU2=u^oP|&To;3{a<*Tk$?;WK>r$9rWWdR=t6u|0K*CZ$flokoR$YwiZ3oGTX^yDo? zyKZ;6R5+zQK3vI4YBS+v^Ihx!4cEh%?t9c7v5Fzjo#ZIu3G#_YM;_f7ntsN#_?q)I z!9l$4RfwMB35qU7UOmBO%L|8DvJCwXoX^_4uUWW2CUGR14~fHVHxkME53u(~u(UQe z?9`u^5)v91uoJ}08Al7V7EdXauOzKs$F#lu=tR#<*l9plqbiNqn}2f9JBK_X_qeb@ zc%8%UaLd+a%8SLssCre2d8M~Jrl>5~T@L-l=j>-VTRM{+FBPbD#*|}#1Qd(dexAnfq3 zCTwTAPMw_fRd3CK--)1gX+zMZEkz_y4MPGAnm!OSMI1I=8fo6O;i@}ptx@IgHpbc( z@)w|Ez6=QX)G>ZF{GNqPzwg*#^)-7)`=0xW%$9{vBlqB^7z8nACAiVz<$ex_BIuLL zj@9#O?HRK;BEJwNa0*d6d*fx0!>tv)pzTiQhGbFaZ$<0R>>Hp{pfRF=8-g!We)*Og z%^_@Mf{(*u6c(X`XiYfVL0G`q6*!k@ixPI@^!HCcr!SlrUyEt$oEo1aZ}cKCQqx%# z-iRvD9X)BeZ1L~}m}3@e`s6w_qJ{)~A?=_k(f(|b=r?V!L0Q{=L5HuU*#43d?ibcK z;Zkh%>(i!$PvQJvX~|6K96V3Liy(sjXlc6>SV0y92|iAM)|owZwBB<_S$%Tw7I7X6 zmh=kJ5pXDYN(Kk=qjkOVc~K@j9py(i@p^Y8AYKTaD%78^aOsiOi+qs6j2Ty3!MboMqwG#zQD;&3V8U!p9s`kU8wfY(voVD9F(qyz5xyN5gDfEKTXZiX|j)cpnK& z!S*0CGCx{UF%E}OkjUwutji4BA%Ueq`?EvqN|;i-jO&S}Q7vPC!cU;7GQ@IZ4i(YX z1)zIt0_SIZK0m|(jb%L(l#6x|S_k{ldc`^ORWmg|`~6#sUHzwNvixWiY|`|m@5W*M zz{c|I;uQQ8JQ?QO0qXoGHow?o{pfv!+T))+X^lX9611zgM!*1g#s=MLIss3)&i5?^ z_xNf|I$-lTB_0-&jtDCKFpB>h6a3fp{ogBi%AW`%x0QLzC$u{JgeT=s)8e1{>8ix! zeM?uaLs_r$;CrM*VHIb5ZmIi!z@m8cg)LJ!c` z%%7J0S3f8Ew$yliTi!|Zzs1n!#l>ZTKD)QrSTx#rE@8Dk+=a9X<+Pp2Y08zq`S{_( zE%dz=z25Rsb{I+a*WCAg3*&;KZEpH7c&f#bW@ZmOjJtEdbvD(lSq>LR0$~LAkbo@sL3y+q*o8iwr&LE%AJ(6OmgRbf>L^oYm8 z5%(dbF0hYjONTizBl>~Yk$~mBpqk4PHq)WRA!4vJijByMgy*j8loo^?u2$E%%LPZ< zpP`+^E*|J}X%BF?w79&x)+by3RP{`fqekxb6PulvR99<-u1cWCU)u4*ir?21k7jLs zNGgA>zi~`4Iu*1ph9w_@*gO?7c_*oxR(OGCPV6S&dAfh}-UIUGaFVC*+UJ78@{&N- zN7PpJ13sB-D{ z(c_JcVp`lak_#WK(v17FHO`&AUhOug;W|vuhw#Sj#Az~QYQ`V-*nKS>ozO~AUBg;! z<-B+QZIS8ztCCX@ev*AvAA6VVjTMUYm!M#6%4HRwpCXugJWC0$e=xlTi?r>+2m!Fj z8F9LH2!e}p7^I?SdpB{{O4W6(t+h2|qQ+V80$!JvNA~H0<}I-9cD<~k&6P>jmUQ6a z*lM775+xv_*uF+0zB|nmFcD;}kVOK&QM3t$0Id_}<)w8^)# z8rw~;f@8Ig)9;oJ7=^wPN~#EyW@_vszc+QmX3iekTd>bnylQZ1N9p;NU-e7XK?M^# zU)5DQ!aJ?He%YQ~cgvTtb3LTfgq(!D3=Mb1Y@{AtTw#T}8DEFGY_JFH6|YVbLIgCm+`Ey3&d(b6XgL8)qJ)i1CIj3C#s9CMUR`vin4s z_@szyu}8cZOSrqUHmpp_S=@mAp^NWfHc#qDAVla~W=U1UFosd!W=-v4Nz2#+hK2D} z$1W-h;v`#2NoyiScOE)bA6X()BWEN)Q-B1@piy!v<6uEAyLyv$K~-ypJISQ2d!d*fADncX*LcYcIfR?vQcH4e_M2J+%@aOV zw~nNcF<#rlm9299D=h6NL_!cJuz%QbuR z=9UGy`~t&eY{hU@5{LG5GC732VLR#BvyfRiyte_^4~}cr;980NoHCAh z4KLmYHv{jo@iDmba-x!GoCM+)E(M@pf$fT?s`KZ^tcTtqlCEo+H3{1-$3Jx5@C!y&}&e=W<@O8je}{_=_9nXohESU<)f7A#&_q;XX56> z#G~Rln05JIwKAm^$;#nDTxzHyx~gsVGgFJ*tOE#xKD8^RGeqgXfutytn&pdfaKAK@ zq(6|TXV`wvKh8Z)X6hUi?R0IDpt>^{Gka=CvZ;~Pr8ax+zig{qB4bc&_++tdep+9Xo{XD zuV}14*a=dG@c6I=Y4mRTPnbehFs1j%<BVV6iwCC-A4?6OdkQjRiVRZJ;cnB(E=;kK~G z0ZEu463|ZW6!0W^QIhS>D-^-7c=Fn0sCt=X9{0O9OEhI4ct@-9Cv0CVDo6#RedMTInvOdQaaLngjOo3C z?dp!t#P}$IPS0xz*5A!u;1VlD9xX%|NOeO4%YN{6Olb3FCjG}?N!|bq2RUl!^tH^i z)D7T8W>8w8WL4N+ep5$N_rXC@&eEGD$1A#Hy9NsJ5U+EwuMGmpUQR#_TtWnTl~x%Ut2 z@AMiucG>Iaf?`AN+?A0<595uURI#Om4_h11gMo`VKpZ%Vsuqk-c zCYsphd=X_2{spy?^E`J7;Y)uu=6k%ha*)oqon3b=3O%?77cZeMb9|KdRV|gtWt|su z%i{KLVRl*fDgqW2k_sRbCq17vEzwcSnMIeL_LVM3=!fT~5v55Lh}9Y+fz{TXqQ_og ztK91kEjMR9C^YO@u8z)1mKyEzs|qgp%^0rt$`W;oOB>EQ)a=UG^gX)*?%P`KHbVL8 zusd(spo#HzgPL6qqqG}RE3?z1N$K}B*~|Dce$6)CIOsz`i8Q5~Bh0YkVS%J50p6<% zPUwk=4{mNfsLwMBa#Ut|S69FA+S6NbdaBHf%&u#iN7!4L)EqWyOyhQl{jp@wf)4*N z5>Qda#7m0wOEtaZ!7puX)gE49Z@B-2Znt&QXu*HZo!ZBTb`)0AUj(1HKx0R^6k!{+4os ze79CFPI~;*0%lP6W})R`$HyC`)e<@^wXQeY*bp;-8OLjvQZA0!(vg_qxczLvzGX2*9Mz1 z;cVke3mJ7`z9)4cBQar1=C0v%+gs`KO0z7znIxbiJFhE4+uBmAIcHGT4;+iHkQQmK>-x1O6m0(A(a8IsRF7*YKsI4CXSmZlA@wZU0 zcBak_V>EDr|}DIJ4O6s9@h|20dFLL z1};%+e)#f%TdoNwBwNsF=qa@WTTYQCC%Yw>he$5(8qT!M`$S0*X%cSG^8Mwp3s#?Z za>-@u3_MzuVo-=6fi_qAfMY@L?xd&nz?yMi@2e36sS zVFvbjX6_^6TXi%PvCW^$^GZkg&kin%1__p`HTz>d5IK!q&3YlDsoz}tJVPk)hOq=) zl%Sv(+lt4M zfKgqnlOf3&!;4xT_Hwe>vnHbTK3^JYJo~tpIKAVQ$ZN87q#p!ozfebGjOcwY=+US* z)w}63*#2QKIa8r^>m*6N-G^eZ zbd}eIcUC?zO6$!zJdpNby_->hZlS!pp4_`4t*#}TrZuBD zH(s{kLuKNf~YXtdD;=fDL7<0-jnpSrFx3?6g!i>S_3~RGC-9F zTg=Mp%$`nL=_lR0p0mMqq8ZuJx1)jBpCSpev3Iki{KkXS&uKxCx8m;yWrPhVP;t%$ z#k&4_OUENz0>;K3AE=IzIV$0>B=25?hBWih2PI4v?lxoCCJw| zakY}#p3_ssbqd;9$rjDpn^r;ug!f`2vo`ogXq)$j;rN7iR8a%@Y{gj(EDdv z`OOdysGCmn5vS1Q+n+86`i?czsJZ?hS@1tc^gr?*0G9q}FN4RLxz1m!SAJ4#ZJZs% zZOfR6-c;g5cdHG{k0V$(pmSy5*&*>JDR`9!`>HAr-@LBpT##>}d$pP+FWHv~e1}$e z06MO8PFB1(nlZ}GHXt;ckhkn5NX0c!p5(o8nqa6RMcnC5rCGOiLJHQ&*3PT<@4Lhn zqWOsG!FR>i-IP5+KWdDbfx;hi{c+ose+v#BhYo2VTq}=1E9^=W9{bwwS>PMf@DK5< zuvrdL%F3CTlJXqPQ#quZ3@MLc%+dvI4Bu+7uyev*BHPfg%wFkR7+4({32ZpC)2el< zV{5TrJ=HJGf^vkj)JMM21LqXYB_p;?bPf^5AMZm!zz3qnB@MFwkx|jH}H9@ypp`d)URH7>XZ`m$C*2cN0;r+1)%ai^WHOh&#&ss z4J$gvd)?nx#vsLI__8~m%vKG#sic^mXZP+QGjDZt2V*{B!|_GjOyxW(L`BC%71-!7 zmmyc9dL0Vm3ys%xkefdj_BAhBevj!|*`9L^2?#zVxAC;E_d;!o*sn<+C3)51Nnvr9 zlLxjHhZdokk%~cVGg62BM%{rCCx|k=Pp~UZ;QT6%=xrHvp2ufpz`Uu~90PNFRFV`R zWs@DQSG^lqdGlK?Wg}`h^5Dj zGF_;N%KI?w-jpR($D+N+E~WV-lt3{KQS1~bp;~gsUPvO2gn4TVjTQzSOi|Wo_mp$| zd?ULidOjr46g()yE**Fs(;N3GWzpM#H+3Zw^8l7IN*8mlU;AJQ!l)dNEPy2!Uu@@C z!=DHxL0Fy<#XL%xZun8D^YQe#FlEc_f{hzi8dLajR)3 zNAfTWcCy8MerQc@XH6YwAY2kYG^0LI)K}adI#y5Fer|fTn?#5?Vkk2YM+>21&@(5L z7Ew!)5iVo2z>L>`1lsQB(WswD2|+J>mfa!_-IWe^Y zn6uIz(H;y`zmwT+Hj(Uye2ZMJO#dh}nSynM8>nckSV?63Zx%+d?eUDMGU#lZ&@2(v zIaWQgc!y=-g7bIEz`x0Kb5>%MK&@t_FMmzr`n)H-@op0*B}!PmuPF-r!xy5O6mY+U zwrxT7C0Dd_LHc@><7$6Ied;9&w%&9m_oj@Fc_iz!_jXF_A&^ z%p{&b`Qe@D3D*mEY)KAPqEva>FPuM|AVP^}4x1BKA3WlYHdC&yWGGb>6Uxl7@P7H` zvzf$G9LJ~e&)<8ge_(xLuw}6chkJ^Aww(}mOt423OMWIB(6}%-Niy#4cSDH^b=){l zMHX+VJQQ_t{;HPbdfl$`Rwuzh=G`QFIqP(sT6wzKi*fsNkSM+6$E;1P-Yvv-10@24 zkIF@z#GqYXvdnn(K6S0x&sx*TU~n;^uRdZ;e%0~~on^D8eH8Yzo#2Xs_rmMQd-T${ zj*EDihxFMhckzzrwPu3vwAhl5yC;#E#E%s|nIak)6$<`X@lK6BJl&2UsUA(|zAEb5 z8-e>-_?W;%-UAlEGoq=z4m-XcS zI-}!Q(2g9{E}xpHrZw-ijZA-0H&M_VvoW2yY^*p?tRPcx{FgTY=`n^Kf6;JtAY_xWWB;4OH zIh2U;Qdl$CR6c2J#eFobsmnp!uQS7@5x+Cf-` zJp>VtXywC2UVjOS*KhESdNCE&sO#sz-IdFBKvdJI&E$Q1%SA%_@!q9ON{_7|!mc!N zYk$Jqsz;XQZ2Eri`l0ky!P9|NRun}mRaOr8SSqvV<|xk%UwiwyMr7L4xP$>-(h z>KVhL@~sM}f{YJhU5QX`>z0HZbH#pmTNi0gE=27Zgb+&N)RHF{z4JEJ6x;0(i&|tK zzIqNCqYLlV&%v<^j3!s?rZ0ZN7leC=M{%1gxFxvNv!iOk%06MOXpBg*;-O$=Fys)` zBpxx@zKh;)$VHWRgHI+NLIT*vsTv60E}``tFYV5zCO>A;yF0rR##urTXhtOO zl5DBXv3(KCqugO>aRH4$JhMhm~#EqvA144*>#W^f%&DzylJGLmzVA48>xx|W9j zs{CYLk~c}SU7!u7yE^4$9?AOrAq`KuXwd25xz7g{yCp$hPpzg0G9vD-%xOAjd?>H5 z8OBFihIyO^Bi28f(A@FZA7()n(M}JSBbiZ`e=LE96?c{(A8z5wl5dN*5%jT{$|8M6 zDTHhWU5X-6>~;ou(wv;8O-AnLARg8y8XB>dDv}=r-sA^9?dn4()JV|}`w$U_FUPpF z*TJ8Y=&EjMVrE!@gGZ1i3#g+=0C<3iGKL9b@<#nViiRXbaxv#AzGl>{IeDNgeu?6T}m|!T*Jfou3k&v_!YiQuhH@>M~`xuR8%42Ci z(@u`?F{v4MyKD)qYgt60C z)v^E7{UCWlLq>8@A^+Ly_MG7$_x&utLE!&m?>*z1dfRl-(0eb^L5g%G0qMPlA~hgV z1nD3hrAq<`A_fQ@G199v=^!egNbexM8j1*rbVG@I`G05T_5IDBnKNhh@9Yof{jk0y zD{DP@*0b*CF4uM4jHG;chN?5N$_-V7hA+7IoreR{30#X?*=~(zjcSgQvGHG*2b(1SoS=>g_P*}?;?jawYyeG@$^GMc z=!1@us>v;~5KW(~XJx9|05?+k*lGTQ6NJTaDYR)UcQ~dwl2n+|17=T~XK#v6l(F5L zUZkaMzEBCXKeq?t9#q}zS8pX9mt$8KR;ttCj|gEBYHT)lrqyJ6gNP>1+!+mtuuJ6{ z-1P25UJBt8T+JR9PF(jIIJJyCMJUmzR9TlLRJ9425o+nE8r#F-U&S+l%sD{Bpb{cE z^SS*l2UFi7x@$}!O4^U!34aN4N#IP~3{nU2pk0$kI7Q&sZpaKBObp_1z(|v;@?6A5 zyDg6eh;Q+T&gqMO0;Q*Cz%cF#u_OV@N1f&NR40M32#wc72Q%2D_i(GwdDRz98f@QL zJcU@f(xRpo&C~7UL?5lt+E3u$%rL5(-RCj;Gvf*)pF)x(b*pwlCSf%sl*=P53|ci!nuoS;HAzwW zA*@yWddug^?L8U;H2=piWL^#$sXwID(>+z?6TIu^V$ z9Js?WGLD*?PbasJdvye8C`<6ZZOP%l;z7+9W?6ftQK}bP1Vfx%k0DtXpNOpa4@fj} z@g@L^ee0@_!EWY3Jf@;txCO17-6lL$_sm@us^Arvg|hZ!7r$;i{i5hFd`5UT?| zK4BU$@6ndis8W zK5)fxeb>}fWJk5|^(S$Ozf^L5E9Lw*k84kGO5fYJQ9$)zs=_=Aj#=8qwbEQtc{DnT z4>{H*U}&)P4}H$oa?fsx_AVzM!#h$_!g!d?wK!n&OpJkki#_TiG9A9_M9y=wlx;&Nl{DTEsPKw6G+ho%cp_C)-SJ4~t#{c8sbLZpvX0R| zDT9uS0?U1}`Er0tFM% zsmTVU#W_CpeT_^4>Uh`#;;`tXEw!+$$GVS`(Wp<$EEpyAUm!iyoTelA<+*O(CB`YY zI>7LL@Z3%9C3ST4yE+w)4HTVj$XZ+Ft5@n#?O-`s<%I{^&>Pkx(7Ed^lxl+Re5D2v zjaM5G2uer1K)kO)VU|UyVZ@851vvucmSG{hf-iP*lOLq7u1BAAhdN%Ik6YU|eq7CW zA_^k@7|}{_G^CfYUsT1rx3Cz%M+>L?61R(aTFh_r&eckU6jXv%hk;-*=;=Q0O zz0;Gms3bpDMmORoq|#=?+goPm+qdS5e6YD~s6TY7&69f_dYiSA??=ztExDc5fDD>R z?qj4J=h^XTF>@{1V}$gIF1K9A$X&^J5Fj#_PNB=;SjKLHM)_?)Q(KzE2HxCS$N#>E ze%OKeQTog>x}Jy!1&`a$Y1vHrknF_^b7ue1BM1R+%8lHm0)eZYS?mN1UVKR2@ayfB z`*e#k)-sxD&R>mnm{hjpnI(c7zV6lWoL%lzZX??h!+Vn`ia*DNf+6)-`C^pt7`7zQ z3a%9EXA!n%Kion_-1I1v-hUoGk|pgQ*b2H-m6hty43dHHfk4K$snEwKn9_IZ|L$cn z5HGy*cB~!9(v~D74agQr`=)f2V!x7Q*qhlwn zRJEzS3h4+DU7I8ml;reWv2-oxEM*Xg+P3Y%9^lAY&M6_CMA3($u7^Wxk^G)J&(rZ` z@;sA<^RrjKBu@{R;(HtAX2^BR1Ae;5OBinqYsWEv?%=qh+fMPc0QK#e3H;aZ;3@+W zV7#bW;~o+mwp;F)iFZWOMk)e2R~6NH&V>dR+{DmZ7dy!fD)h^0RTX1uDheMqz47ap zL(>p2$&X=S4?+`LU4f6<_Omhk^w6)5dJcv}48P3OU*D2RqiB2YH%*ZA;U#C02|ld^ zHW1m{LolDCLe4xcpl#Al=^wzy6@Wfo86{xbFo`*U^}QA5a^*lqqhX`H&T(MdQhqx0 zN_4ziV;tTo&SHTqxjr`_$9+umb;;x~#7NBOu!Qh-0_57y=ZL%cun1SB_vp{@iPml< zUgN@oEV2#|C2D!xO#zT<^K}~r7CK2Li^buHtgW6Z$ijlIVuC0rGLF2G6tKhrXOkb6 zZl(rPp;Hq!L1!4*0@2`A2eSwx+i^*_Bou!`Cw_5BqOxByR+fpe&PFIM#(4cCjRvJn zW2$BOkUGZ3+0s5f&Pu(Ami=n8Q=3x`8h!Y40$=dGGi;vB)pL!ii<09ZdDyvm*79J2 zoxANv*?UnUDs}3NLQ4|5gwWZ|8o438ibhq|4wkhI#8sk<@3#(RGG0+nASpNJmCF10 zE=#ohV$2Ee)%PebEgdDfGxQG6_j$L!wWnD{n?7@!@{#gcf^QW%9t;cPanBXevEHTB zYIuG1;87&YFA$sCyR@#|lYmxehd`RNp?o@%$eeo7MNt&#M=%e;R~mvJg*(Y1&Sa?a z?f_A)+ypknL;&xHoqGd?yCOx&+d0HxXD~Y-xHu^y(_Ysu3q!)0mODs}p3|J=SJwCG zO@4#ndh4g>s7B^p>BTUAxStKN=n1d~M zkHlYS^);~995lBMk~?!OC&)gGr?ihY{p5{G zaa=AT$Q@tzk)BMp)X1H-7VH0a+juvvo%OpZ7oGBLC8_ z%QXRNL;@V}j}Z?Z>EPN&aPjdO{}vPbeDuK*c&HrX;72gn_A}SE}znzg#sGNYrJ)YEe1ECb_RI*wWYI`O?uw-pV5{Tksbjs!huq7zA@oS3o z1p0ntVJUk*M@~%Jue~^gP&U~cIT#XOFulbB{cI%1-%9vMR;gZJ;B}yYQ*ftkB?AlJ zK6gKgWG>dIca4P9h;u)Bx|BCE;Q8QPgI2Ss85XW5Rnq!eLA@E8tW=HAZXJz@xf~SZ z^P)(rtU^eS;xCZcIE81o zM(_GelpQikKCov?!zv?AFjuIvPmVAZeahXRMIqk%G#=}Hu5DSyEd)^3(sJ)}`59d| zz$eB@A5Oe?zdH}VXhPAqS+hs@)NozaLZ=WJU3Ee(79I25@_}cjc>BFp?vD15EI!Uo zpxVzC#`((fh(M|rBPvxV4OzoW?4SYsEqQ2HZJo^Gy=VjS?K15jigCz!QX*Kn;w80+ znm;M))6V7B(Mf6NhX&_d8XI3s?O0WAc)u*mSiC6L)CtoIIPdN-ODrUqF~xT)K7^qv z^T2ogh86a2r7vE4=5C9ehl-A;k3GJcLlO~ilukq%K>SXUZO{5C zD1e96?N)A&5m$|;QWuRCr4?xU4uZV=_(L&5ww$Ns3IVS$ts_rMx0`-of?nl;S2rVP z`;D!Otx=6No%+Ebf|4D8jA}rXVkeGbbfKR22S*-nRJ<=_wD-|A)$MRGLHp$xiVW61 zbrhNfopS2D16OsDt+#0!dl7*rCQ$Ak1Z?{{nRUYa^w-ygNK~r$mUTF`=`6%%y1~mc zXk6M!vr97f2#S$q<%UWzmDhXQA+Z-h#IwoGd_P8ftn5Yl4G#E(jq~VGa@)fJySoPG z_H&k>c-Zx?t71EjHnCsO;=Slz7u1@4IR!HG!APjjEb(}WJL#NxK=V4uMABxq72>BW zgX>ywFKBgt^hgobNN>I4;v=omihr00UXGluQkFWvz!pXt90NE~k4p&33gSUPGVA}- zV-yhO!F;hh13(M)AdD4oF^dAT!Jqr%Fe{f*UB&q$y#No~sxPAw#QE-wt!|~k zlMw;!;CE$$%`|<+*R)HE70D9wLmr=*PLgG8TuVSR+|#At)8CbAZs6AP&wWD|*RG@fO{z`pOcg z9vQ&kJ*P{a|CHQ_WMcY935yHXQlABdUxalfd?b14AuP3eZF!0AagQOcz5L?qB!%1R zm~E&;FNTSHMD(>V2+Z8Qdx4n-c0NO5Vj|Vo(5ePK#Y#Z-OT}RG%nVO!jUPB-rz(*I*vSDuc1CX5>rnQ>dlTP;pZf4L z20JBN(jm;jNt5Hc9*5n`AsU>ss}kT*r0Y92#Nk8wD1e2X9*@@UA&lUzqPP9XAQUKf zFa1MmZV8e4S;SWpnF=o|T&)as7)HrM%|`;vl%cX%z2vBfdq3$xfctzUi@}c{1!2Sp zmMV!@y_(Y4y=Ht>Aq%|Byuq!J-Dp6HdFe#Y6-iC4##z5W&fAjc;*4y9;cHyI+iqe~ z$q;?rCFwM}!Im1lkgI2X-={uPr43u#<^I}lH+2Z4%U@0(wRYeOB24{B9&>|0HO1>3 zc&Ygx_SpFSoUH2}HZQcVE{z&U#yY`xr|ywt2pYY&No74AIeq7bf2Z0Z`qG^bi58aS zD&-Wq0(AvD-1^9Yb>%q!QjjzDo%H%X$90H9AIWFK;LA{05@oEzem|`QUhG1S5{>u! zGz8JYHAiO5TMk+nG9nlEM*Gd>;JCkg z?909AxVRn`+-Wfg+U)zf*Kv~OP1uo=eArR`_b*yvnonq6N3!;+7?@EtB$f`Q>#q=9 zl^~`LVcpEjv(~RYH7I`mF}fZ^mpHri2?U)6zbaS2-9r(28m%Maola{%(%A>SY(ubi zD>xzieoi>oLw4NRT(hp3Iiq%d0Q901$eF^uM z5)rCoE1T`jN(yF^w0Yn@f)rvAI>ryHMTd@^Ec5F*Xbk#%0&jFtORmenh;tvek@j66GCQ6mX)1bJ4#Qa+pG25 zLuUKEiQ{dujAg|$PQ~IS-#Tz{(GE#Ve>6k4;>gmmxx7?xAHP#S%eK>}om!i0!~l@U zvWoPxgv6SmwADDj;RUw41v{}@N)Uih{<3}DMEYzy3Af25zz0a04%iJJQORTxs&P?d zzHGPb_Kq-sCvMc*U|jHrC~tN0m67BtPfos#(&}$#4{|C8C3zkfohwu;`;JvG!zf|} zb0l*^W7%~D8lm3}@$-$_v~^g9)p*7yDf|plHeGgVjQe3Y?G*PZBFfb`ewuWBxQKIO zb8_4IV^>^=R{i1HWU97v68XF(ZAWsB+K>cq*rx={LRIY~DzIrM>BKKPxtjM@s~{zW z)Kpt(M9tvf+ETTPg-E4b()9jTM;W)Ft0pnD4@S{iFbrM@_{1Z2S*$#Iuj@su+`+Ki z=_h^T1_*0&Q9c2P#j{WLXfyHs@l6R{{TS!u*E7hKgit57C@m7b4^s~`}p{4%ZyEi$rgKM1xu95 zAQG)~>FjrOsoHYD^IW)wK8KfsPWmiD0fSC!D@l6~Hqr~8S2L@L-Ge#0BU6VZhaZ*U zyYLHl^!0$UYp8Z0-RyzOseZk(r=5FA9dNEg(SI+NiS4I$4Meo$DB?1cw&U2*{|gcpV1g++ZIHVl}qvEu5G6y`Fc zjnvH$$M!@NWaR0JPYCpX)zpU(K6G7M0U9qZnbSw7@d}szk*`iYU_u5 z4h&c6c&@hq^VUi1;x)*^gOd`%wEw26xtkln65YRX=@0PvV?3rT{(bN>bfE^2N3R&4 zefrC*_$>f6{hkNt$?yz*{Oq@IcL+TV%Jgr31@~WmMG6p`G5T{;2ai9z0aOE3&O}6R z{Hs?{xH@tX_3uBf!c7BB7&^TU;V*c8M|KP`f`ls%IKT0~iNq`ksKroryzbwe9xwLX zRS1#ATr2Bwy@5)G@){@C#i|?nE2rVPf4`Stn*+mBK2;JP>rbiv`qDPk*-*>kz?+{T zBK)dU{c+V-;8xN78;2^JHXTiA$^!9ade?B^-jj{!Kw`Cc)sC|H zgSE~5R~u6s&>58s_5pGhIYs1o5OJlHDSJy187s_`f_XFdF}PKLm41xYoFlzYUwZU|H7Cm4Dv;i3 zd~#8&9C>YLx3a1HX0GFelCX1|WzhqnwE`auN0PS(gS*@;*SaN!l0Y+&M!Cy?0)^?gIx8Q#2LQzDDuJUhxOYWL74f5D`e z+Omlb>}jsz?f!CHEX*~YA4H687lYrO#Dlz%l&~;`ts<0!Lg*Dk5-U<8TQGv-g^`x5 zY|t?Zx$dz(&ZkO4SHKOgnUDx9k?t{Z7Gb7DH}`|5Y2Rc(I(cj30|Ar*n&Sn`TP>KI zB(o*@Atrjg2hJJ_$uZp|vN!qocWNapFSy!x-$7!AIrS?@4}a42@z5?{X!X^cN9m@+0sv zPVrtU9dzwG<#(M!2*_Bh2C;sjK)VKSZ|P0b7Cv?_v`}Jv-B-q6@3WYO?JuW#&MKLj z;;*#DHD!t{=dfqdyq_t^ohT2F0ojygd?N{juIoJPondh)W}TCv~9RzHlWVE__ zHaRug;JNda@il>RfHE8~A7XVy;7k;Pq?|x`VO*&T{Q8c7rUQgPf;eT}DJ&2gmC{i& zIMb~&I!WKDI9OcxET)sa561&<+f`+_e6^gk+%pV5Obi%*x$$L1({j^Ei5V|Oo|z=^6j)<4wvT3j1XGKJ8<_0{C#GK1^hry(XRCy!aZ zRnHvHCYa|Qw$X=I5`g>CTStsCSs3x|dD}a?+$pp#6w@Gxgf<86u_n7B%eoC$yB~Q7 z@uX8)XGkzhTZnWW7(P;Jx59@u6R4RvoUl z$!5_g*`C^01+16@&HL=6(pg_LIzefteg`Li{g6r%ZLCNRYSLFo#XP&~pg?lo$y?=ASfY?%vko#6B+Pc(74 zm$-DVSI*Tm0G;y-G@MgA#NaJ7p6)-}I}iolMke(~(m(69X1|jdFvi||ce3C+{TTA~ zA+ec|s!F1WaE9(2WE2Xb`p}EV^}LgbLhHePnPq&4ABX_tzwiLt@>Ph{t9sRTRy@tV z5}zR|H1N`$`QQqQH=|E6Vi$3-zvIyw@6PW^TgRNNOL;pT`-sLt#CM#c+`8Al4MZZ^ z$9j62M-|y6RhhBZG0#=kBUwhgCFgS%zv6#lnkCebE@b6Jq|$vkBrS9Wn%WUJ%dyX7)o7|ptW1d`>dJlWN&1x+kf)LVMJ%io5rKh)05m~2+e{D*BZFWekt#Z!v#NleLDq`p@3 zJ&(`#>Trrxe;dJDp`AkY$!pDgCP?!Dzw!}@Am^oswbR2OEI;&zM4d7w*W0L3LLkE_ zMnkuaaK+1X0msBWf0Y8=Y~yt>A7pUU9X1w>{1F2S!ggL|AwUF7^S-EEImi~uR;}Hc zZ}H~JnM8!VMM$te?WICJMsi`h!DbdAP3T%12`)<#LNCV@y)z8jrKVg!O$3&FYUE)L zzRs6ok)XTuPR&#$*D6fHTr2)_ma zfG_Yi2Gw!{fv3{uiJ4|uGxq*MSGXSEcN&;4cL4&-O-zn-|2QP>$GNh}az00dTwYJW z2S#{?*9Yi_L{hm9{!=MD=bEd=MfIE?6UuttD^SZ7%lLtwY+mgdh@06wD%0!F7~oDB z9^m0G=ay!dTRSaxh4?&ky1r`d$5X>WmuU13B$nyhwQd{7S56M)HXAj*aaFeG`61Zk zyyTk-xvF!#j``yjmjw<9kn42&mH`X}Ept>b)qaF!ksIL*$Z^AWYSHC$y|sS3+9dL# zc1UK|H%oD4&`cp%1APh3MktM|TPWNn%#;&**T?ts-8V_9e)WCQ*=WM6D3KMUYXz4t z$-3$lOuDmeuc2fVDNj-_SdOZft4n>5FZb{E3ri{6$L%< z?p-G8U_?Lt+rj`g2Q;&r7+9-oMy{cwP!=XwzwGqa`yWp_ODap;@ zHsX;x;w0H5-C8anva{6u+LO@kTn94ROaZ*RS>IG;w~xzmKCdN8{OGFmZ_8}UyZ=~C(>cjf_F3*ZxZFeg9hbHUun2eZ zMc)~={9x|TVX2qACcQ4(jkh;a%yYf*^BXXYqKA&L4W-$*<+>POvP})ieOD%^Xw**~ zp-A$JQUMKDmScj(JIxB&cO*J(>tuvU@;GV6v*>lje9IucWn>*?@8E6?jwVFA#b4p!F32slQgt7L*@^mor|RU@?7-{Cv~w!C zUuB?p+b8yXVb)IkBzahFc-e5$hT1owU#?4 zb&uo&0czV=#{H+yi8@?-9f2)j#Z{?YSv zMKWE*@NzHnTva_+FpY)dw3qYj;TObplRN7!=Pp*d3>)k^89StyD7E?RNwb1}!>Sk2 zZ!8EU{P8h~Zy)wZRTF&^l?E%YTFJb)22p+B+&PjjE4USDAr_5~OLac&`rSBxjMIm6`7H1hj5+3CP<$cb}S~Cqa@y`QEnSKKPs?ocIz`~2DwID1cw(i4)>(!&brdyfs+wBaujdi!-Qk94Iv zUPD1Cz9gpZOwnb|SJRMDG*&eaakW9uqr7AfqFsaDt6Z8Jh~aFkb1V@Fs$GV@IyNzU z$Bc;21?6>*-(Me)WTt4o=jn>xMALLXXV<$)+5Eimd8BQkDrc)=ggWAekKKz6?i)*+ zrBjcS`Blg2-sHpp>6Yen^9`0<@1W~P0o}xY0B%4y%3w~9(V#R$j!xRwy2ca7F@e9! zWICI}e#iD=*0-x{ZkCTA&l@h^L=EGhOCBBlKjC-(SJ(J&`sIQefL{)e)A2zZ6CWKU z;k5J)EOQ@tJSzXoHIII>&s}h7R0LE5HDvexp_cY12v3a@0Dy!9%y)C9;N^?4(3jxa93a1GiO~gVx z|1PCf)Be=)eUbuMU32@D)t%-AgTsfM;=-Fl760{zmU6D<*N- z%HFo1tVdDkdQ8P9^mjZ`l@AbKVJ}X$GyBv^td>G7Bt-co{OkxXFup3J;a$rip|{hA zW>yZa=dZ?>WM)T;KWyH3P9a1U9XWHjjGx{yUQjMom#(dA`E-q4NequnjgcXoz<}a`MM(C;w+C~<-BTd3L_EJ9+4;URHVujUy_Bhd;#D*= zNnaQRw z%sO`x*JqoNgS`8rWkC_=9+d}HZ5iVFUbTM!TCz2?fKiLJF7@3 zkB+t&%CKV+l}JWl9WYX-XH#Io8MVqxEkA4>W-W00DdfWPU?=n_i?Jqa2j3{y?IU8>rEIGsvP7k6g8^>!klq2vq zT5-d_WHOY~UxHQyvhewFF{bwLO(z{@Cr<4RrcZ@9ItjNCMb7W|5-X#}e5Hh5O+nPh zAgW`i>SYnSjs?H*RFi{GZ?FXr#ZMim6@c(UZf{jk7JCjU!CJ5^S|T1ZnRQF2$nD{n z$QQ~}gWp)r=4tce9X2a+|KJ#JVM{ZY6r*@V7x?s=)75V6fNmnO0PP#=YVrz9EH>3@ zeV9b|NbmS^FPZ1O8{1(_0tMvC8bAHPdq(XCxQ{npHnSVbgr4M4Fq#X07au}bP>vN8 ztT2hd(A=2-Gyo)<`VHLAM~h zT91S%?NS;UAy=?+_kRkI`Y(Mr@qK>G>e8!6%qjp+9uqjN^0jZo<3#0Y`@yYa_$eR) zq%9uIe+8r(9pqv57l}yYFA~wzq=^=9;*HfO@>DpL&ELfNhvNT6Kjr>N*Q`ECa;fs0 zTU7Lik=#D8O95Ml|BXWAKrSRmkX`QO$3G6yYq7Z1uR7<4O}!|?Ut}`pENr|=y>X}~ z>~E;-NqJi2UX4c=&AiWJI!{f?rzAPOpGWb)+^E5zA3y6e!r@aSKtkf!zZ3}zau+WQ z>fSK!aqHMX@E4TphVVl7!{597pxs#^K)UAEtefS-8=;jQ35aSuOzIwv5$`6G&R}}w z`eCX1Cp$M)^A|DnGm(OokVHx(4_}xAE5jOydT+kF$3kK{|hs6Y#ZXVk&Meb*Jgu zV;>Y=>w#Z4oDFyd%GrCKK0!0q43;_^^BiwaaK1~p(;Sqt$YtPtFE`CGaS~5}36__> z?tU!=QWM#D62onX-h3xA1a|gGb!=5_QFwAUASd)e9)*-S)TQMim!nQ5vM$~1U?uVG z;nd>{pV|y}2lw#TE1qA$3$7Q!Ho!dlKsG&y52Aa6dFUA(l@yLniUQrmKgwMlS8dhi z;m)GY9i71UBPT-^1|CR6I3^7gbE${me1_Ut0O0S1Wc(wum)0W?ABV`a@D$YTQua`; z_PcJt-@W6K_NI1ry)BI#Z$bVr_hX4Lss|iW>>gkLSOt!mwycW zp&pcV)hMF9irX_owOim@r-`0FH6-8=?<^kJ++IB@2oYZie*1cyvy#Pif8`v0yv3ih z>wJKDYMZX+i5ENk$kMU&9mu92HFS^El9=zR?nVZH_~#Q*8&Q73WO~!7F{^vGEdXTu z3`2O94Qkd>b7#;2Ev?VK_Sfg$xW(}HgWEVWl9=%2HzT7i<0Je~k^GkD6X6k7F-T}< zq}+(?$<}nXiCDY4*LZg_sPw)dpBzRG*v89>sEhk!i89MZc%OJB*ZXyh2;w7{@Qo6#-m@f9~DOSc87Z78W3$-5aQ%~VyBtQ9_+P(oZE*P zOuXWY{NA{Z&`Y?Ly=B2Gk_?5X5*d!uVK0+iw~T zm^QqK_@c}dsi!mp8+%t1M>0WZOil~#p~Iceyve8vmNVp$GA<2IoJqH|)gnDe-AbYb zOCzU*{ZhnWz-iLYu;J;zh`eZJ*^CE9twFh3)s^zb|5Fe(-dbd$d%eC;(81f+e6~Yx zxnI<*Pt-`^ImA~wwcJmr#om*C@=e@{CvK0%)YYd38^f`D>XO zq>t~rg7O!H-?2(AcMLz?`{Dki-aycMYi{uA$hIoOn0dw> z!mwwk0XEXL)D8Z;-jy?EuJ;XqgH+0Y3W$16imA=A&<89yaZdq})A)+mJ<70j%Vf0c zey`%0F<=UcWUkN;4cfg~(Ds$>dH+2$)P$&O&#%ci3R0XFIh{Nj%x@%w zDmhFOL@_?VEZ1N(uPCfS^c$JrNh+dYNj`@|5`qN?e~8?Fp2z-w;0u>_VUl9s0GP)T zcc28!{60MTUZn0(O&;!A^8s)7kqAR->iw7E+iu3}Rn^4*d_a_uaZ=0H^GOgFeLO+O9dQeBe?zYF>lo!&3 z-Hn$JcFQBq8g2UWEJv=VRL`vmp}RrqNQ3@PDw$iQ3tZD{Rp4o?V*3(SXXyC2*wR6J zA-SLljLPE(HT#-J_~5o_b$;40p%a_y>?-CId{O9z)gc%M_`tmPtpm+1q99kkM@7eH z#0%kry+Fod8CqPV8yN{n@LE6a^{g`8;xB$V&JSyf)2!8DSiq;;-Na0540w%mi z)@K_{cqyU>5IuxGyo#G7Ixlqlf(C&=5+teswTNZ3>wt_+%JnW1<`f|nLW_+x5|+uS zYH-3yoeAOJY>r{Qb2UK^iO)!Ba^i*$!Gd=kGuVl#fd8a(5*%K0qc3S-IB=KcqU^pK zr@0l&>}_D61Y5vFk-jR+HzqRa0NIn@YkoYi!BPl$xD2q`%7yZXNqOm?6GHiwEQR_m z-1(YguZc5)^Z5v0MFPL0w7hEWY>5JBdW-?b`T0*LE4q zjH8KxNn+

    1uP((i-+HWK5#;mw;#^Re6|=gG0Vfp8rvgd&f9q~TZVtqLB9#% zJtgnqPizm>$PnC$4-;}0>7dmn1vuTtg!g^O`FOS13LmYLgQWhNbjm*_osM3Lg6);i zS4Ml|uXVzA7$G_Nv1-6DMBe8l4hErEo9Wg|?LN6jd^%s297!GQmf11Dg?S7y;u+5n zw4WXj@O-3=qli#&H|^49(UHvadDqCt3go{$J~QH3?`RU@e=(+ASA~Hh*xhdxvJ$)~ zZx-U=5aj;3YgvF0ZOnJfXhESJ157in3n%SR9_9&P&8?9C_8WZ`sX*k(HsRLe? zPvfw8R&;Gw=&6>&$kCS(R<&9nGd8DtcQg|kYtv`BsFj+=Un=RnhBR@kKgr}Ce1x-V z))K{oSt8mrN17FC>l9t5zmJ~qT2P4%uZJ>2hgJ6H8UeYV7eo+jtPAki*L!kDyaZ2z z55vb4qYO5EVT8YX%zDRL;J>cty&+~ZP|q@FPQ!gVB;j8Bs;=@e@bLMP0CqZOMVc9Y z-o&W3BmHZ2f0zyz&1zG0X@xeQyJf+V8AmX8>|C=J2qy2(RR_lSoVA>VKAI!WDNy}l zK`k$n$)$s7sv1*eis(>WmKlZvq&>co&8FlBYv%T;@+2%?anF)}idzHH1_-N7{5yAH zILs@1oW2>PqWrdTe`pkhN}RC+)X}l>U$6lF>xATueU8W2#D;Fl>I6kQRL z!0Y2qkR6_1<+3hAt$Zg)q~Uz@?km0rprhO66Umq;L%5LVDA+9c3siM0cI$Z)G~wk= ze#eJeR!ns$`S0!1N5PQH?JhWVfL5)u$I%^T4D9zlQ}HO`OJzjQML%h)46L}NPK;&*&WHGZ8IRDW0v^M%%5IcodSTH zTMSI7bQ#hZrt{yf9UM+B7mHTV5FS|zzVL%mFv28kC?b;?XxsDYHNO`mwELXjVxl1qo5odT=M5(ql8B=6*ou! zF;b40o?&uKZjaQA_nlm)xY?zC4oYD@W$afW{7+0)b6-cK${a;s|Ip>Yy*p)z}x+8h~3M#RKO6g^GKHGlC;vfwK7l+ z{KKrOGnn|jWWzU_DH#LoG%xfrQ%S-{ne3)Pp(Ej*vtcI@z@hOQqtD6^5$A3d_T@%s&J3(b@8CdG<n7!Hk}YL?epn9y>Yn&|VMcY$t-jpb;w5U>0QJ!2~m;6W=6L0co!Sp zbo>wRs@C5hHBbBa&~9DM;zLxsA^6Nxsrsu0SS%i|kI&n3Q%*7TKf38l5r{X2*5^L{PEcS@n!{{kv)4wy?X}- z0qCP+#*&HeyDjPJwf3O9WFyV*Y|r)JBSk7N0C*zok3}Fi>JO=y-^+wQ=lwxI#N*ww zjWx5FcGuX12DU~79vH2Dhs(GA`NaOXOhDe6({&0yBCkpv64p+}6d=i8{3o;C zTlOE$Rb_m9=0AVg|IZoX`2W#Lm}zKkYH8HvnkA49i1o3nx^=>CggyP;#J(FaAC;X2 z&F?<~F{1MJ?}qU|fj(aUSHAuHKwdL*{Eqh2P!QYqU}k?OlOBN}Cu*Gyp-r{^-UslX zKQnQy@SP8JH-CYM`d)dA1eJaZn9+%-U@qtI%2mF};dSJVe`cTSyQpdLqoeC1t-3ZD zVU7xeDNJ`UBR#n%T)Q!TWL3NPzQ>EJu}iWTo76^)G6KPzsP{fF1+7Qmec_-Bh0nLo z2Uz}!i}Bz1&dC;dPyQxe{S6@90uZmX{oyp-QoBaKnW0bP8;-+teRi(zdR4F0Wtcnb z#~~J3kAWa!n_HcR@5PVUcO_eaXK6C0Q%wgqzyC-zEQ1~tvUV!T-fUSC`f&~xw0ym` ziBsVNQZlU%j_gu+IUm_=47L+&O@}JSKA7LVt{^PF#y1?Rx&@@eZ^?fri9~e-b}N4y zDu?%~+kM26xBUW<$vkQQ3cd$)CrSPVO1PbR=SRc%l~mYkvC!OR!Jm`N#sxtCHjiL4 zTvQ*}BH(Qh;J4|ao1-sd9v3(%mn!aS2Z z?yVf)4GRbNY0%J($V>7&l{<;d>RLH7@`Z(q?pxef?yW z;PXLi$HaBcL;+J@5<$fMA>;6d@*Ed21Wi;sH8Z6bK>p1}8%8M_& z-B|swt>!cnkVOKcL3FX6eUn-KHEQ-b-6q zhwjjDy$drdj}s~=OmX`XoIFn@>Zz7kN>qy#E>h|PL=jT?lXwfA3%nAQsPTH%v_Q)7 z$Xo0-ig@k8@zn!~h!i{^`DO(4xnc+UXd3|eW8?n{5AuKfd$S(LASnl^mrF8@wq+m5 zewpZ-rk0$ERjRJ3dR@W_o_T&x^H^t-POi^GPpfu>Tjx#`B+~fqj6C0BX+GtEp8y2z z3#<)%x#V~2-TE6qYubJc?o#F_%eY+zTAd2lM1s1i+D(@7qX~Tg%*a&xX^%uyy zW=(SABRuSf0B#UCDOWV<{Ad~IeEa7GpW*1m@8hDc05LVNMPqC?KZz$X;`q^fNmT={;r8RWz+k(7n7Kb6 z#qBpHI#cU2DzDw)3W_)W9QExK;j5?~h?KW{1ts0j+wX5D1h?a~7d3Ei;A++;)!+1n zxB~BGXprf`kT2SrHym=7_h>e);&R(KEL`_*oPWel)jjI8d7djtSe{y53&@lnvmUI~^;~wwjrD6L zr;uM}rN(e-@6Hm`NZHISuoIidYP?|oq($ye0LhxzZYJRRJX$9TxV8>YM4;!TgiaBJ zN!>5?Q8krHQZrrIg9{#-w+Ix)%l72V8fs?!a!bA|Nq*86@3QzIzSxj-pJAa4c~!ya z`FVX}hmfoiv5wwynQKGy8}k3v-j|0{*}eO3$yB^TCF4$r$Pg+~c9J$BNf9y>Lgpbe zPm#=XD076&$sF2|d7kIlM&^0md;6_T_4Z!p{I2gg*Y*8=&w0<)A1)sI+3Q*BUZ4BE z*K?1&>7%dD)NXk&kn{;{T~95c>48cGSzQ|!jdOU}COXf0bXi(y3{<_J7vPFh9gxvA zWqJqc>J~YDOe6R9XRichLzZ1RPOMFqSVeKhzq(nZ+?L*GF+XT<@P@D~H=3*bWk;fI zLY)a$-!sKpOqHvAc%x8pF`rJu;lZ=PTvz2I=-dfow@`LLNMZCwhKtt&59q!g!byum zrssI)wVEX4y4ja(Zh!t~lnCK1duqFl^rlNTb6+Q|n+nV$^)k-+*i1!>EZtGK8{#vm z(4evlQ=>pq-^eI>rbXJHAU{fZDoXNbJ-*7qKV3roBdMs~kz2e0k(#jNzLXv}AnqQ! zQ*X`{4O`DRo|A@=NSRtsHPy9WEPoe}LgMVi9d=BzD{=T!RJX|Lx56EnUIjyWfiMi~ zr!FkP0_b^iY!_DMzlnUBxlK3(n%4lui%ogQh{B-ub>y8Zt=HpJ-R&<@DZ5M{U zcLRGc0pq@@@R!k@l$@F&lMz&?CdjiD?9tDp--W#>(g2F}6$(@VJcRgV{FJ6olym(T zm+R&=CmeW=jcNW#9po?Luc>T^V~bwmRGjKCO}cT#hB)du2b{|toCF3GxA}E&u~e~d zh5(0J10?J73|qPzd@EN%iw!GwVape$;cIQ%zs~RDd`4o) zCkO8&0U4IMb4(6O?fSKm8BG@j>feukdoM0JxZRh%atg=33$ukpxjU7*Zf8Q26`tfsNo=@M63YIqkG)=-JnFk6G zn^FKYhw-410cSev7{-@kY@ZR6oroEYr%LEKCVRe`6DfE5g3Z-FM;o<(b-Swqq5>S? z4x%=}HQ65kKH_-zkU>jn(`PJY3b4L>+TDt~w?U8i>+=vJEI{S+K|tm6 z;m$`%GPce$SB5QT7X0JYb54N1_d=);r%M07KFrz7hmEZLIP0v61;Ws{i%Aeo-{#$UKEKmbz<MWj*=oRx`zFuX6k1GS-`cvR! z9edz!`16PR7tQ6%215%7ocEKBa?=3i=bMx`q^~Fzq{X!uYb>LzlY6b#x`FXOybIF+VNY+*o8=6)02>4K5Bi+= z2LV|>GDZKl{U&JMq`@JL5kNu!QVaz6x)ig1iCGo}PEF-K)|vpa=OxFme<~0?LyRS$ z`Z|l`QKbozvLRZ#rH>#2ECu=|_khO+etZ{(wvyjolgE;!x+kvt$6*3Om-l%qpzLob zbMSKV57#fKWs&<%I(wuT^aa=f)^(_QQX4ewLIBRnjd%QkozDz=*h$m}*!i+4KiVWF z@SPeS8Fizsv`cqo9eVk2FV-qMuEYb@VlOVyoB)JL{@X&QWY~X;F%6na0z!G+>fr}v zA6pI_@-W}K7yzZNj?W7BN5$|md5B`E4m8tg2YE0?T8?x}7jZXip_vY7^8ozm{=z!?Dv5ajYV1rEg!5fCv0daK}#Su)qYwy>AG#*wbd zn+Gwl|DSMFE%#YuDO`D*egt>Pp09no)r&J-*5Bnb+sdfaIbd)024bef;(Vv$^-D`c zK)EMLf|}ifg(8Kkcz^d5;O_?Dd4KkwB`5#gk z;`*>P(5j+xd@3d`@nbP75KIy`;d_F|P4ehHx)?%7@yQ2yAoE)s#O5;>s!m_FFU^g( zlf*jf8VJe}GZ)$y&Vxu(kC#pR7;*t*`dc1)C^AU_hMG)49f5Hmf8;ctr7wG}ERaFf zbtG6z5GN*i#m37SIGJ{G0g=R8tt0W$85mG+v#v~5ATJ&#!9^j~(?Zifm82<<0Vj= z20%dre|Qc{zj}*nd@tVfnieq8;oFC7;M<2dJ8q^DJCI)(S-+KpTF^=3`i3!}E=^Xc zbR{shg|BzsoaDY4ktw;wD&hb_mOsRKaSL9J``5PA{8zQ>BvkwgEz@gmk05ZK_I*la z{-Ifpz!=O@QKfkb!cwmlTpkiv-HY+2*)Qa72MW2rL4u>TuL}H5w*K=&#=;a`Se=kY zW#riXdex9{+CL;S2bm}r*fK0~l0N}?B$$-Fuj;dfz*+jg-5=(E!*|Z_(WD*Jm!{dn z&6hRzk*p~5tH4ve|BpbEp`rBs&|wKsmV;`WuYIQzSacgGpItTv59ShW5+1x)b6yT~ zc4uKfQzQoZcC6q}-x8zkmh2&^%!z_Sh|2bR5iQg?*M^9%L~3a{O{8>8XTAicZe-;s zNCsElaszR2U;b5Zv|LKLQ9O6XV*`!Rk37#vWWClt$^62{?@EQFy3=~@+kSm&eY5nk z^kOo!dQPF|__cZ||2p!b`XKVqE6P`dLwk9t4iT)Rq( zfNdQX&hk<%!ecn!cRXB)jL|&#u{8$_CKBYJY1S5I% zy1TlowgM{@M_#IV1~J$Us_1CF_egl-`3=S-XC;?xKsmzpfxj1#OwuCONzmYi|_rvo>WtFbD8eRtb6;Iv|z=R^M$F>rOVZmgfQ|^ z@Tg2(<{%`MJb!K8l<197+Q*Us$-VWl)CBWab*n+6khTa=i0TD4X*Sg6qKJGLTVU^z zzz6A_!`D(4WjRwrnAD=vp0t0;bZ6~IitgpU;i37YwJcrl)w$wBJU3cVHnzfw8}4Dk_UMx*1w87-d#v&UL_txEdM^Ewn}laYrUj?3K?zVg#nl}(5Hg*L|P{4bf@aw-mrCVs$(5-eXkBl2g;S7mOR1eJf|5v zHRE+DMr+;tQ*jZFn4wReDMy)F;#BE5T|cF3$7;vSNZwZ7a1!9+n%{-xISL2qTT|Eb zu3|5YqNyKgow$6&E#T#iE!o;Rm$a*l$=^&jH7GdlE#1R(=2^paWa@4}0&p?JNt2Zi zP8+fw1FtKofg0M4^$Z5(WQk@e(QbjX9j8_o^t zhOLuV$U)yZBvG;H+13wIW4MV;aMB^8gz8eXh#1`_|?V1XRL zfA!q!Lk(fW<3@ohSRLKs#GA2*w;3hx_}P>c>P+$^w1W@Xp(%O1_>Iu8^g72ce#(eI zjZ#P;cMb|^JX9t3xqVzer;ppa=9rCuT6yb{D^i3BGQ{qw>MC+}#tDNBhQuR6OMOLb z4mZ>+37$W%X}VcB(*7}^@jTDNv!|{F@f61yhw+kC%0B5njPLY7EFjfY*u|5vy7N3) zbE+$5X;p(QOE+8vt#^h?O3|%f!JpHt=w_rvpH1`YvOg}GE?>%yn~qftP8=k#tH|FL zb>4+x8^uh^-WF#SwPmOd-Odf~d^#Q%E#QM7Y_Q1}JJUMPmt^T+%BY-Ozv#gejmSz1 zkb^ILaIM!hxb1Rrm|M$dw9r>?HlJTr+~9p*KcqV~!u+sA@+)2UoR7duHZtUG;Tx+* z&xplG3A5W4yzQh_Vv2OTH!^xKIEq>j`RwghCHB1)#)D^!=GeWSdOluOtPi8A z$X{@|;C9=*=PHrqfW9vi5uK|1c2*7a=n1L^>ILDuF~BetgUZei*~r6Uv@@CPmu`u{ zJ0)kW^`t)2-bvgX-Vt1Qx^~zna6z3X#zUyjcD2vQz1h;qMShSBL-SeiH`I4d3b*1zjJH6#t1}w zm91ONp~gXpoXER*`9}uM=QK+*mF0b7nD zU7&?zs^ot6a=UY~>O-BWS;p}WqyPhxYww+ZaX_61{%h`Iv6{)_4%Mq@58`?W6#mj1&=;yHkGjL2y@rZNy*gWkj~wQ|cQD8dwxHbib-Q+` z;!&^U@&G7spMRlgLYVLpAo4Rq&GImNS=`As_U4Syygq8r`B;z2tXg(x5SEp6z1#UN z$+V?%mqK27UG(8QR)S}3ecgp_0wXb1kpJ}-W*eFgsx;thaf$`J% zM*k&xg67>2neox{Wej=)q^u_ks%pV3FgNR~r(CsWcYTf+a3>cQwv8>V z$T&9_8yt~Nuv*dHk;?CF<%cb3icVZ+^jWl2o?Y{&C{2A}_o2Ja)ZFP&u%L>r<8y}e zw#o|={P$g8UoH5BM^?njQ>2S5pJr96_CC;jkWli9x?i59Op==R@iswCa%}5UhSZI$ zytetoBH4v}zvBk9Oct>^kJ9yRjxYIM>zvlfqs{w#?SWL9(&-hdWowsimP3n_gXx4% zwJn*G5q8ZBe(fBTc4+(**DS8or|fzAYel>HCJvWr=3HweKM5c_#Ye{>? zqqP~g@uw)1?qSV{?ZS!%^1Lo;adU9?evipR-*h<8oTS5Y#^w5*PLb9$Wyc|fK4OH>=&{rlXhI=aq4gA-wBP~6R4lOcSkd;% zPOCgNi!U_C9aXrumI8uFiE!7U$0JbK5;SprJ2B|vL-KjlpkfR*G&Vx*gHH@^@6=L% z0AgL0Gk)g01MV=!4IANx)2!Hqy-~zbO9|K*ET{NQpn*Bc@3y1N6Jj~HFU%{HxKm!7 z+Z`ZQ)CIKJ!!?5Z2EI`coG-sAJx9tQG!y4AaU1x({5ligI2k8@sSl80^lrWI+H!L) z&Pyy;88wWmMr40L)or3yPWK;qY$(mj)D%sLtGh$V(kvv^cqIvrkvn?lKY4)BOW{|v zxdoFgrNB=1M8@*r#le+$F*gvhEGgePV}qgHqR=hS9LH#Gg;GT2FG?|VH^$=bzgH#I zo{&m7Jk18;2Xw&{^40KDfO-n#@wdL<))hR~XZ6lL6JDEytG6-jzuG8*t|!6ONrDuP ze5e!xVb0n7G5F~+3K{x-IUf&m*ct=g&g2^}C*3@~?aADCVKkCQKj*7`0@2hIy07=f z4Vh?@`*3>t+#$a?3lv7~u5z|D%RzUha#su|$kOPX|2&Snx?In(jN`*p&E*JpTgazP zBN9~d+s0lGzw`cfJ=T9*@@O>g-UOh>4-xn+RFgZz(Rg{*uh@U_J-X%E8O|Uv5zH_& zo1-8<^Rx(TpX-hw83qL$j)KhN(Z|a#@CmQU1Y+{;8uFB)rvwS6d4a2~hchm9<{o~t zJ#h^`_Rg%(gHc+~0)=eC)yW!mE6F+qIWoVfC7H_eI`f?hKX9b4DrsQpTc+RiRtri{ zGd_K;Sqix`w!f-{O}=Hy*?vC!s;b%B1}JOvMEw;`g8CCrBIBf%iQiaBtpyXV^hqAY zjyG>9 zLl-H5ZR2dhxhhDN9&*bL$+uZ~25#1mi|I_+09ZJ@BYJp`7U!7Cuf92pzQ9NJm6XRmVfnri_frCMH^uBsVuFvn@(dF1Wr-oOXy%=W;` zEhkvkrzszx-HC>ljvdyhjW=u6(_Nzl5nmp0UNXm&@o=Erx%hn+-pOb}Y#3lA2;hZE z1{>D{3hdmgyyCdD3oBQURNkL84K`|@0bg&R?tc-uFH4d$ybGHR(U7wkKuo}`pt)E; zP5rpA{o5&jF0wBDYIkFl6~V#;CGK>RNK|ycw}by%vwhy)+iv$Cy#2Z*MI57aQQS$w zbr<%reQBWYra)f4xRXj2xNMPxtL_mS{(WnLS^Si+13BY}VjZwD-FM-JCoJeb48D8{ z-{JX_O<8`x}$a!jH|$&-0ESWlc6=; zv4vwKk1Bkh?X^Fd1bTIxzg11jy}2GN=OG#9!t9VV_#WVWrze?sLGgnIf;J7Vx)-rH zuqxIDYNr_kBsLE()P9WlCk4I@o^hVb8QNHcmV~A*Aa`NBtL+wa)~#u` zAX=PG^j)1La+FUjkRuIQ)K@({;j8^%Iv`1G5AHwj)6jWXo15dkFzJsw9rcN3JBtZrXtF<~=FFk2wn0m5VE=6QX2OrhNV)t^ZCNeehO;ke-XC9ryR{Oxig zX(xw!@H>OQ`Z@TI6$(waxK{Wi?LYb!{X1m3&sSU@p!ZKA|F{$0n>U72X9wAfV?d}S z&?gi!s^aJ5zK6%N_x^)+X1L?_HjpUoSq;N!*)L;etcgSRHS~@rc5)O{+EYbhsM?T} Nw_Kit=Qi#3{69{2?!f>6 literal 0 HcmV?d00001 diff --git a/Firmware_1.26b/Documentation/posErrorAlarm/alarm.PNG b/Firmware_1.26b/Documentation/posErrorAlarm/alarm.PNG new file mode 100644 index 0000000000000000000000000000000000000000..27187a124d1b7623824ff1922fa3db694d37357c GIT binary patch literal 10698 zcmeHtXH-+|)-8yFN(l&31OmcqK};}=`K+~`x%OUjhCS3(r@eaPDj69W zt)_;mJ{cJ~5_mCPrUcH6$T!*mf5_eR)$fs&4st93Z!X#>>nM|vRUoO4tu6uYuQ+Qw zaU&z6>pXvvqn+}flabxF&{S16L_AwdKPbDUc5v3_9|S856a3QoT~tC`qEB=%i#v4n zLMIQdoSLSHo195a`T1D=rCxPjG1R5I7ZWdr;hAsUf2hn$|38Q$x^{?mtq zn^uSa(|KL_wbB1{-gJ5^;lG2>R)y|PdvBziqm`KL-+pdYIUt3r4vy$~{^}63+2o+; zc`ec$n$p2=eIa67e|kG(FEmtxTnC0_`qaSmu_9dEKr(+7?7jM^>S(LsF%Z=N$XY1OPRbJoD4IVO$nc)|FR@LO65-z|yw?vpvrx04mSMS`Q45>sgvC5Z2ym=sZIY2xkN?v?AR z9Q1Uj7~LYVD+$6uyD02algj79NwT7g0uhAp>8@Wlo>X2Reo63of$o;q&B)-Le)^>P z)gytfwen87nlkgMmpVe+`?Cnj%CQJ_=!z0?BEYoijlcWmr=YT~&1Jau1aP=SrM>?MRE#ZBJBHA!PV=c_Vvs;w!S5 z2oQ<|J^na#2uuaP4suMaceqD>9mEjRdkx>7O}?(UuQoK%m?Dj57?MY9l_5eywKEK% zZ>Bv7*gbr}Tm!n95u|7ve1{{Vm zW&e*3BYWCTNoC8C5`(XzOf}NH*Bizd^`MUwPWR_Zh&?1BRyf+? z>=3gI^55@#>CwF2xUyU?S$vVQQJum%g>7Y^oNS5p8?8r$EEYZ$ zr@iRQnI#BG+3oKVMK&3pU++5B&i66Ll(2Wh$z*gnB+-+eX1=5`3A_Q(q{YjFbh6>! zMi;4t zHX7_*EVt3Tedw9PO@Fyt#Q&gwS-R~&=WHR8Df@iCv!fXd&u$Md((oM1(F>4Wtl2L!iSKW? zR}WXp%GR5=2bY6bp5?E%>`i;6is6@50K%LN_^&f_9&$F4O#2U~uM%Ar&qD3{<7-R^+s?$6fjZ~5W^CT8tb>{E))zEYs4 zcLsT*&?tWZeNFmgJg4_+MNKx^uXLcMx4g1xA{xPM62jrCpj0uY>nN@7%Zw?7G@VwC3n2pd4$Qqw}V)#GzcWSP1gx=UGEGkWrAd+F<36-`TFNpXOW%g$Sii|CMYo0c^ zzBp?%X{j3PJh1NyXo{o)BeJ-t(4240Jn&(BPNXnUm z!MCr~$C&qEXWKB6ifQzSJje*QH{i-F47&C_A0*CS*+@mXxe=oVsowbXDg{39yInN@ zoMIy39-M>JKQMOCF&aiyB*4TqUTTiZ6lA!6e2)n^^#)hsm|0ujV7<|@S2`%SQaoO7 zsTF}9|DhZEMt2!Cg{PBW{m}-&tOww2CHhdp zTiv>S*6cTjzpjnuPS10m(0f31Qf$iSqUFb3BFirGigfT7Mfl#{@x%e4ZNF+zCNll5*9-?6OPw^*9Zr-1UGiv3dW@2v|<+kKMWD z=FyskpkV;j*3ilQ$y)xQ0xHp!Tgq7mI)?w*jrFIYHboJeKxsCD9~Q)FS<#Dc*6+>+ zfJ&p~*XzB?)qD(~!3!WN4ritFJ!y1K@(xgZC~q*GM&DwJ%+RmcYir7f%4_Yaa?API zg`FT+^B~er7UZ2|80P}C{;}Gs!|>|cH^HMZSKe;*^6d?U4b>c#BMy_jEN9+RflWBy zOjvoGj@};5JCDQBTAjrdXukVyoK{Nh;qT2*_@o-EZir~#vbDw4-*KFTYL+DfWm$mf z?bu~?SH{P=%u&9vW*LErk#||gLjaop;#;4vivt?#T3l1Lh2!z&cSh4><1UF{O(cxX zu+3#??BE0b=Sr6{UfE`ZKTU#c5a{}T(|l>p_Y@vFUoIBpKU=LD0?Tkm!%p{?li<+> z#>(H6x_;jGxdU!Eu1JJ0>p^F^gK2x*KdB66#F=?J)7n-fUkPfd7Gey(q6Vd)^=?=o z$Uy93=|K>&r6r3}K4FZoIX24cA?B5|QNSoKN(rmm;3Z~wNjEXGX-OhY>y38lBGIYx$!13$ zY_QNes# zLolc9Gv#7@efP`UjzHbL1OsBvf}U?Oy?ubHm(gh_<#Pk5>u%0GHlP-jvH1Fv8|0}> zjEr8H?FR(6OfhSP*c#fbX&&F%kaIGydx0+Lu{^;6FP1+&ALgc8$L}oOHFO^u{44Q8 zXO05fp4r>QWSj9KA0vF%@BKlUxkx{DDYQ}*%#{>X9%q*EP<*`cyU=o{`6b<>0Ip+8 z|08~kUqkZ~8fWcvUIjQylV-nXm0tr?J-KN6Qg^o41UKZ7+&5VW4HZ3_#?px6b^zqk z3(;d?SArTCaCzFQcu%$?{4Q;m@ruHQdd%)0~P?-ad) zJa3fFuuC-aNp&Mn6NZP)NfEgn%-CN%bV_?rrT7R{-$kK+lu}-D@8p&D#l&4}!59%9 zZFW?Rc{lu_FRx&31ma<4DO{+pe?W+X2_t62BY2LwNrv9obX0WH4_0^*#01YC8A&YtwPCIIpj4qe%+&3WM+dFS z3&jTR3*+0nvK3`ib}M;-5^C6&BHS}uAA~<_@!ZtHR&xbUd6s+e(V@Xs6_t6#!n=2^ z1k+smZlA=9ScOs^od&|;W;pkqfzzHb=?;BY&xGh2VYdjk+CnMENt5(9SX*Cjx3$E6 zcJ|b_;CCmF&R(8C!~oc%dPEIM_IU_{XBF2_A@WLliP%|1$otsEOJ+mUfeq|vBTX35tBd09dL#RxipphbtBnMgD++<^|&SlFE(VxS5&o_G`LiM^Sf)|Dq z1u^2UT(I+}8jXKidcJdF!uV8n8iLO;k!Dc}r| zuo}HCrdj8nB}OSwhDOfKG6f_&&lMX zT8?qFncw0Qs>5q*<4ruQxdbxnAwhHt<8p)lSe~WzBhc!CCmEvx{$2Zh*@?+W>QLTH z8T8GM7IEoziB`nlW)pqwihb6rIV4?NfmVwqy9bZnRyNK0WgeZYaJtklGfB?#>QBs9 z?E+RRZqo9aZ?hS?(MTR;+rjeYxBe=AUff=;_?KSCu>74xa(COdPehf&uO$wo{sqm$ zPYrSwNw0|?mw3{s&v1D4_e69~JHza&Cnc5Q;1|a_9j&$Pz#A+$Z2IDLD|c+_*as4A3})oEJ%;GmD9l`*6euEo~^VKs7`#D4;( z&ZRtZ@?7%S${yi`VPnTcam-fgRlcnI)zT!#BJVrkIA!^&t8+S&^}#~dut7W36rT5i zX8_OJ=D1fT@}OlA{tEWsc$IX1Dq>dJBKz+jFSTSiuvR9VTJ{d%>T*&|wYHco*8}2x zIpV0qFugjftvXxXO>i}_+!Izz7uTCQ|J!ZYU3OE;0e=_Qx{8&KwOsDvrDQO@7~tm+ z8LiQl7q+qfJB>2j$2nO0^)tG;l*O`a29}uvm5{oV3s1ag=li1G-mC?>+@feW9DUj(I2zc|OmMZ?9<5d2c(_uqs6}s zJB8jF+81x?;oDnzwKSg{QxRW66%7}a>gF|eq+y~|Oz)PZyM&_}d&??zr8o02`@v6U z8GlOaKr#9Qor|lKeUW3JH=i<`+M;|^pe74eFkjV{uuk1&jf`rAr6u`RPsy~`4-&WZ z8>=6crsEEaMjdGizTQlyCdY;|HA1-!(# zc59?~*or>Y@LboD-qvMYqmsD>Oapq~0cUntUF_0{NP9rkkY~v2swFFWKKyfY$^4@8 z;Kk@G;HyJIJOUJyOi?Tt>7bj#XwU5w;RTe^?{QiD+#YvI-ORTshS*ExRcu_bqUOZP zrx3vsY91w444jH0i2UBswwiNsU{bw{0$O|ZksqySDK(IhPj=a*C%Dxz{U)uxc7_~` zq%HPS5xk(}hZ+?1_?d89DgKeTBW_Uv2mkJUtezw}@&nadbMhD;`EdMoHqvf(2W$>h%qLy?=qvD!+@*IVoJNA*(jQ5*mVAGe z>Fxw}`75#)_0Fn@tf>GNz-BXO8NK4Nntgi1(u~FZw#Y5aeeE@q z5Ft-DXgH#Jz#C<7jtT?Z5(y+Kc0kA%^l}j&6O^xNTh_8#KkhJBZ8RS6-z|Ki#;7;l zV4-doP9=3sFC^Guz|M6c+B?fqz*Y-#(;;vUm29ww;GbjyE%%F^X#sirubo6QaC)bP zy)kY?4VqFrzbq480!$Bvw;JcwQ!PQhgBLz@UnZV!pZicxIlkhb z+&sje=g;zWcK}X_@|vlxJDn+S1!&-|J9BKBUhih68|8!f029&n37m~(Rs1Kv3)#16 zavV-CJlRe$YnTJ`XKUXZwq(ha`@BA(ITeOhcJ;jjc2Q`nW|kV(>+~BC%GCmx3!ATX zR!cGtoBENPCXD}CovX#E<&YkQaDJx$Eb%x=>$}!r+T0EcOKP9~Fq0NAHg?gWY$VGy(GO{JOPFb5D^cEsa28d&fmRs!QlVE4@IEOQ{;{Z_SiAFT=Z8tcr^-M@TIg$zh}A zelB)Z-QmgD9914(9OYYmS-JHNdCHsCn~44Km+`X)7^yyzlc|3^mbSq)pZXxzN++e( zy#Of0i6lqHT)5lhf=4eXL=`-md?o|IYs&Z4M4O4^#R zkB02%z$9?BYoGk|e}EK4Sr}q?m_UGt@Dku)M~l=tBrrlqFJJ^tB`f^vctV|eKH1Mc z1{wa9E2#hHasKPu4qR=iwDT(I_%!6{PhBF>c>3Kx9;W73=!pBx^Ig;i z&0@%;uDd#^DCLppI2WI*r2~taquEgnck*PV2p=?&L&El9Uj5EYNahrZc$TZZ@+~h} zbMftcu)Qg@D)PJm%=0c;ry?HaW@nU^zB|+j>xiu`XiKrjO46mg$%#~fV(l|j6|hM~ zuC;-T={x(YAMh0NY>21YCT>R(Kln=%zs-Df*dOA}r^g41-U zQ$$3at@?vdDht`42?=#CdfDZ9X%84sQV&uGvd4LAU)1}V98qN_jND(E2(+4e2VcDJ z!*~H6ey9fZB<{L?&%O-8E=#QwugJ=$l7vfGwm*t;m`!MNIDO8Wu~afU9B-g`d8eC# zsyi@rqv7{au=CfLud)vtq)zAx%?{~79LhM6rCiZX0zMJ1uMwhC%@!LX`E5Rr&Os`M z4jtoX%;?Y|OA)e9Plm6LRgUBjk(*x)ubv+u5vNpQm~o+b{=BqSN(dL%|B#eSOyRx;;p^?+kv)lgZ5eaf$Zm%UnYey!f$Aor0U zdrZO`^&cAjg?EP+yRy$Q$Jm|m!&qz5Ah~b}X}WTXCis{h^hMrKdOn{nnB8{opW*%0 zJy<=RJu1)@up)zgiGsLYcL@`z@!YfP;5%?ceCGGqsTRl@=QW?eMf> zx1BJu>b|a9XltOY2r&*MkBxEOa$qD2wXoIhOi{(YY(j~&L}@`AM|m-)wvCo?uEWm! zoT&{i-{xON1Xo0CLpb5r_`nA-igmL|!0xiPdAjjvd2F0ZY;l6nz4u-RyN0Jw;&6K9Row$R|qPrE#NHruD9jeJ7I=l2kV}#N+c~pl_gAmI{ znr*gaJg8h#LIjdW2RY+$UA*hym)?Z-@C3v~UOc=;%iCqTx4cFG8eoccCVo3~DLon1Mb>^E8co!-&QeO7lbWOyBJ4TXJow zzPVpCo09=T@A6dubV>F(+1kqk{(}ut_zDL3S1|jIu<~wt-1C6Y>Ns`Z{Tc240G*EV z#JL^JLa0-fXPj3g4;VlOuoQO-CHLsxkfGV3ibF$U1}NVFJaiPc|1Zku^^=u@?GFMOWnMyv3Bq*`L_p>c;i z@KQhrc4z52ygF?(p&Qn3+qah&@L5irE|hi%cV1RIdI(t>sZWaZSybHm>NH%-b`kRs zW<*za`>S+iEA{Vi5xHc zbq0SZwP@|LxN1M%RQ+u9efelGtJ@OmoNz$-CYQPYZRZ=Gb@Ftf&&2}~^Jy`m-~E|D zZ0zA7Jv&*5o{3P0cfvSB9`UySEv^5H%KrZk|KT?HAI9O=7rgRKm&(^;g{Q<%x3mt? ztZZnUeU;7`0#J2I&fv3vq&>reT&uuk==iy|4!w+=yDng~ zgJcnUItoL*MY}Ao5I0;nFy4flJmPvTxCj4^DER@=q|MLQV<|V$$oQG(3sQleFYuA4 z-_-E}#AF?qTs*$QWe&BBj}R$s`12(KSXIzw?Ed$!T^_&mcuQSBl zoCU7h9~@28%|&n^X5W`Y{l&wR8ZcxC1#Yx}yDcObxUbS+3s(mLBZ?fF?(7i2t)U-` z|EU5j=e7#*&u2gZkNb?+c?h^Q`W`~P&V}`BXJ2lZIy*)d_cvR~M)<;|p--@(EdT5-2xTqdSL^&GHAW|KsgmC%Q4~FdLWq1`vBVnby z$E8i{h3D$Fu4j1*YDSI4+%U5dicnk=4JXd9`5A9%$@uJ$AEv~ z#_LenxlnSh&rkEnAO6WMI@e6-oEVYHp6(1tQ^$r}W~q#9OFo=+4s5H3_sCWi`;Yhp zIioU<=lM+M44l8!O?$0Gimq#eJ?8;Ym;dF?R?%DEN+~uv<%U){-iPEmB+p^rxVr} zq7OQk+@>ExDHmcGk@dA}NcpcCyu*K&=SN`Jz24s5sVhfKKB{;1%F#k z*RwG9T!@z_Z8%&mvO|BD8Xf-&40sw`d^0{o#oW)K{YL_L{4M=)0vUDl zJ0ElfxOFW91yOn~RUXPxW}@)O>aMfR5Lhwn1*u`kxAfeeadMVylTk2Z69!fLM;i1y zp4g;6j-YZ%oI`8?O5pMw*V+C{jPH_`Md5}Lebl+5f|T9Z$pOPz%%5!ai(quq%K@pq zf4QBCtN0nGNg)8A*I3G3yF#@H=CSxWa%5;| zWG2uXN>AIYyTe~E^u?1pIJuh7y<>`=)1g$98vy%^0XzSxaiBa1yxZ030$>8|KMsTg z;x}nK8nA<50EbjFkkIcS;)M4`%gPWp+!-pVPHtTC^zn=?Q8WaZ+>Y;#ctO6^h-oRk zYo>|QSf+vF>w!bqK1fI6} zj`@dVHcR$Re1sHPW>OuW46p-UFnqi0kz+ph5G2ucbK?ODCj7LKI#mpASphhIl> zUytFw!$-}iC_cdqc;|RY6>hg~w5xUj7D8sJe+~tDOlE^}YyX4e5P_=^GE-%S{Oj-_ zB=XWU!hxD4CMfKm&cuJQCWtfdr@#MC-*lepbDLqz-s3Z_SFXgEGWdfBfd7(AQ%zU3 J^q%F1{{_YY5bpp0 literal 0 HcmV?d00001 diff --git a/Firmware_1.26b/Documentation/posErrorAlarm/alarmSetting.PNG b/Firmware_1.26b/Documentation/posErrorAlarm/alarmSetting.PNG new file mode 100644 index 0000000000000000000000000000000000000000..d774fdb37f62df1fb78bd6f00bc909909874dca0 GIT binary patch literal 70324 zcmd43XIN8fw*?weP=kmlh=Pc2RGNTFQ9wXJKzdC;YAkdDDosj)f`|>UP(um5gc6hv zLd1qjFCjocRHP*!3WSo7V78>T5&FI`&P2A2zw2H8~4`Jd5L9yT}cG z-g@=?1wRO6`)kgh4K2QfS0E5}p24}Z);FAHMz$u$zrDr&c@_KDNyFMX+2N#{X%F^2 zzAMGE>8!cnS;0*fJ2nYCVraInnmIUDbniLY(Cxj`aQPg-{lQFq4;0R-WQZ!{3)_jWF3yspwGM5tk$3OA79VM3k_8aj3hSI#v zGXMG3=U2AD*()ttn9bs0T|Hj^xXQ0=>One+_=JLJ!rS7Td zwK4JV#j-0F_6Mugk@rNR>gOrNk!L;M&kNb4EPo1}%Q3V1^-$JL^A(e5*YAv3RNm5O zaq%_xt$!|TNR%-+c;z@xG1SzHSR}g5=IPLNIS>7>W%%$Bp8Vbpj1OD=;@7>dloYr8 zs3MD?;owPqtf`dQtfGYG=_$1z{dZ9lMRAyqgter)Zd8C5r{?;l zBx{x3uW8cnc0$d0_u_E5V)s=26v{77r#m;aI{3|sDAL+ICWHwqx|eE0K9vkkMDlB{ zxNp66Nr$+Y`GX)|_hyZxk8dTMi)fA09yMCyqnGq`!al2`5Z%J~{Z(T4J|Q{2i_u+)Mt*RwH-y`zhLfzt_sg zdyX=p<+!h0MD1vtOp(OT*W#>Wa<9&g-H} z9@dwntXreskwucW2&ePT)gM!)C{w)5!sL|IR4DC1qigPFIG^rS1CiC@v6>ap2kpBQ zPXFwde6FB|&KeWRqu%~K?N3IZe7ti)D*s8PMp@}VwW^)WX=hPhIw7bj#mnH+`DwBRI$F)WyEZKq@T-n?@$)(arqjZgWglW z+}v2SBQ{!PoFD~BXZiL{=IkNwc|hTFR3?&v1!i2xZKz`bLiy;YxDXW zA9gNGr21mWtl7YY*}1TmJ2;oF zXY@9<+#X+yxOyjfGC|ur&af!aXnhlX$W}FP70H%K>veN*H?*}o{WfY$Bn#&! zc=8EMB91s&t?#R-KvwhAcx%-5J ziTYnP;p3yd+PxlbCN*qWEzY6@o$A+0U{Uq4+mi}rN|(`hlcjGiMs!p{PV9^rvY&gJ zI99_Pon+N%I5{`$^R1H+FAKt=u$3Aq{d-CImY8wQG8{iA>*Hk1oo$e_8%4=!f|9ma z6#H0Q#Vzcs=gA(X{b(;}3f69et&bs?-w%zo0!7#ESGkj)L|9b`U1Ibmu6%Ep!?@Tu z2y8Rg+3g&d5vOY3* zdmbX-T_KB)b0+G-PcL`>E9n@@=bf`=^cX3m95zzm=P7D35_WcFE!7ZEi_*WMK%O+z zO6Z|UlgssEn;y*Ti=QYsa@bC=EXlRQQA5foC;QK`6f_((y1K1IFY8kX8R`12PSI!+ z&aLxQ%Nl{be0X7r>>J*fy1v~EJ?>8!64wf{UK;h~zog}h51(7nmGI1u^^w&0u(B)5zhRQ#b!n zwtc9|s~w~41%aH&aCo)^?M3KBS|3mj9{GmQ${cWLobdGP4{%FyA}ya#KG|=~3s0{X zrD6_JqmvJNC2dOD0D;JeyXbtp8!sfS_}57;mf7dYvCFQkwN=;V2yWMuQqF>_f;Z@ z7R;5Xu}CaHZV8bm{&LZkw>`|csc+z>Cer*mwgzs3KwK12-~Fu^^r52iqR}37Gy05+ z%4~#3V6LaTpjRtVZmaDENa34!p*lpu@RswF%&;FDxgcknR&!R9xgfA~*1@dF=NTUC z^z2&pR@W4K@8PHZiJYFmB96L3w#4a z>gI9b7=s2m%(1PKe+ifC6>RC6Lh9kUAm*xn-txY}y%1-gsl&XvD@xBxU;H{O$k9>p zTJsx3I0RyTdJFv4jZMX17#?#SVlPb|@xlyPgl09pyru-R+OiE{OY6IlV+XJ@TUj<6IAde(N_Qdf<*Ou;mAG;rs*NsEJ9C8U3M&E%zq;~%6 zN>SPvd*#0E2aFHmURi57AcJ5H2xsu5O@BXWb0u$n9@jyWtve_i4-9^O8`=AcsF}39 zb!j66G9LZsDfdqWx(f45Z=KB2gq(QL(eQC&DY#|Zzds1E_Ub42A!EwzJ@fSODnI~) z9{hbS82nYmv9-NL(aj%{AH3Vd0JHiE%;>KN*^Dm#xUcxkcOD0o12o0AktP2&7N5^; zg}ZfTAUV-51-tf5vU#bn%8MkDP+V3oGvL&A0?9~I^=p%>8NS3?EYL~``V`!Pbu$YSwRfEdy5hz?lseKJ* zc{F_V1whynPmJWZF8zd!BWR+dD|dott4M9nF1NHPlN>ICt$LZYHmQ{=i4E)F>B{On z#{>bG-6o5F@#L9lcv$$P`lvy%x_~|!G=?T^n~lo!kRbopGHi_X>i}n(rm(sl*pVy zF=?cB0+US0BjW9AI?%4K@9=rhu07|2n^}u6XCq+DG2KG2R;7+c5ZCJFniy@)ta)L@ zpzp(#bPlgMz0jsuwEXvHWk1HrZ^CE>g_N7QR3n@WP`$Jnenwojy9)KkLRxWepvBLX`veC;wLI@bwr`|MQ{NzMW)Cmu3&u;Rwg zOXTV+A9gmRjkUz37GTk8Rbg5$`$|{o!t5lckPk0bCsHS#wd_|cw!xcL$!=?8E|F*D z79xs|$ua8VVh!QV>zr{*}UAz&D%vJU= zJb^C37;h*}tyIpa2qw2wPIf46QrKXv9r zHtI>gYB(!w0S|VKN+$7H*Q8E>ovD;127;`$SpZEYyVV9&w{>&ZSeUcy|dMst=4xk%5}h zUP>{q1y6NlSvMpWA^Re+eJlX(^4lHr0;U!1O!JXJ0T%Svi{1L-Ran?m*z!manQ3jG zA3#A>TWz=2wGAX3ybgE3br`5Kbr>(K^)~vr$O6WdEtFFYolzH#&spj$VDu=fQl? z4D!5{mKhRWwRH)AkSP6fj5y}2p>8Cv_N=CsEldiReG7sXXG%1%;DHjRPgzZ^6LXgF zeCx63TW7_P--S*D_T%~Rfww~KbvR9^r1On0QI(y#uMJ}M6VpsFcvvr2t=5XtN2^=7 zi2hau!f;wRYcne?fWz?x8d=0j{u-lkw&DP#j zOdmT%Uv)2+5q9){EcT^Xde@?Utv&kLlwUBmuk(psWHcSJo@LtknW*AP$kbeid+PUi z`VgsUciLr`gpu;p%Msf6%wRs59ww61XORtEvKee_HN%=mR(|m@p4NJ?;)oBPc8Opr<+(wy?x4B z5#-$2Qu_4nVCGp|umv+v_@QgXtR~X}_tiJLhB1e0-wN{h?W61u6U zF&sMA=)uTat+O6}{p$WLcATIH-+l^6#n3o}a=8C;zh9?@n@+!b<* zE*SIiB#UOhkgK`+?P;|se{7F9N(OyuS}%gK-lU!r|Yf~ zPqZ}Cs7ddQC)4hZI1lyU1*jhgMywsMm8s5a3GLO4iS|^truhW?Kyb<8UX48G@RxK6 zUByx>38c`wCXm3E;>fl2J)4R{@LGvg+mK1IMb%ci5;nxL$94Q#Yvt*&XBQ!5=2x98 zlAQsF{Cc(=<4h-8Hse@4R$WDeK^5OmY5kHSCHHxh+z;Gj<@b$ZTVlnGygEU|$tM_D zsBqA%;QPV{`gwXIsv(6$0Pu?YB1_G~1nKlSA-m!!m1Be^+v5a)ZQe%yL2MgL8W0$< zYm?E%**9Ug1UAUdo79AQyeZxPF!OOS#_~*#2zvf0b`wKbV!{UC@*989wbbVNs=5!D zBOYIHwKoIattv)fH-6OSC-qow!I++@2}J>z^Q>3pHhs4!^YU%Rs{5bdiT(pe<0VY^ zyRHYcR$hfI-rPUJGJbh~SGtzgwN4j}NDg9KJ@^|onr~2wNRZ~b=}(X5W^Sv+M&IK- z!ovZU^I!x2q6=IetoP{6kwR$DC|13%U>7&Z znhIW)7kOI$-OIbMSqBWjb;*SRxevd~Y{~FRI!u!;E_MR*8F~e6mpfU#E_@oeICBF$!G?5c4NI zZ)nuamN2i#qQY7a3~UAuVw`bWRnGdbE%y@+gE4<=j8z}uao#8|iqMgbF_$x%O5hi{ zHx*sMa=#!c(gi(hznZG%>q%LOtG#lLvgYnz*^%DiGPN)1PJWSl1un+1tbfVxW8>bEShINIO}FTRcn2?n+dx* z8~Z@ik;37}H(s=UG&%X@l~vIG#c%AcYA&$Rb_nC3zo{GK&Gj5-l>DOrK_B`>N8Om% zc1htKyG3JGwjq6k51s-WfMNiJMS;mr+FjC-d|YB+E8yh9EaXJ2c*p&Q@!_O7fdnao zmI18^mP5S{h9|-b0>R}QXW_PqsvH$6c_O-DdQtH)6fS9;jOfr<9!BVcC3-3Ik%CCi z{qWWXg%CyqUglvLu@}V0Bdlv(uk(kWS$2u3RYM@3-#j)c#C78uLzhjti@)gs#@HEw zK4RJI$)wXvqPL3~FMl5~Dzz#wb?K?|o6PRdGfK)P0Rm;1Wnbf?tKbg^bl0`>`n^kw z)j~%qO+Zn`g;?gO-di6)eP~zdev#5w^b`vB`w(*zr>DhBPdU#G*3$ZM({d}E>-X!g z+_JnlB)NKGsynB-8h5Uy*`^pSH;`CNAr_|sG*3QA&sxH{e|>Y$72J>O+xtSzOV6by zypB)PrN33dh^t!al3zOoz}0Tv@2>Q)V!TY%iQb;lA|5^*M(@R%dij2OQMU>Rly62j zD|msUj5UCQifP`|kQWi>vNSj9>vZD__d>tDZ_4KVH(oBzjcQQ?A>0BbZ6BT-HuAO= zxc+XhoAn?f01Qh}!GyB+K-bJrRjZOmPwqKFm{k6m_oH(Thvf8IEJzPo1=%Qm+J{6! z#-+yHIV7`#csXV#iM>}NY^A*J%N^0SfoGSkP%6lwD|!$2JPskab?zrGgWtJ=$m{xj zxGw)}Bu~-Oym>!07OY4Rv~+9PEJnMPnT8ACaBkL%JN6MA&rX3Fg*#z#ah6P4YYAVA z4xV||VhqG0B%{C7zWsqhlRF>>u5=pJ?R)Lm_Jv`;&b*0`w!ZC|2O<)J{oV@MBo|o~ zzR=T(zbo4y85F4 zh>vs1aka1Z_Sh}&;I85`?4C4E7qq(&x0M6mzyx&RV6qHn?!0aUj6We{Ji(@?X>96j zs|vy1iON6FW3k5Y`KEGlS+lsaEAXzhO1MSxG+dXuY5-#qJ5 zutb^WY&q#YfY_)&l;qY93Bmd#k?Je8UPtqrRV4(dD_Q!_4pl8BawGNePK}m~sks{Z zJEY&R+SkOfZF^4~Dn<1bT2yP2{cRmcX^bs)fY!}CZ8#3EwDOG7bm5@hqX9@Ee;}+T^2(5 z+~`H?JKM!PH&+%;$s-7HdM_yrM)`q+?Pr|0WfzXf+rpBw>U66agHDCUf{ZSk?r zMupkBpQ}{q#j51Wbh`KOwU|2vt4-Cz)kaFT#Jj|fbanE9-cm)Ya+&%GfFpY<)uj8B zr^TQ4thKdp7aL5f_bPKrzmUO?M{J49dA?y|q7(XB^vBGy>^Tb=ksIHZL#MK$XO@h#TyYE3{G1}wGN$%KCZHfLuV~% zZW+P(7n;I??VORMZy%oSN_x6jH>Gw+e$CL%wC7pZ@vAk^yL!DIDU#{_mfqz<&o1kW zO0Bl|{`lM+80<2#y%7#6bf#mB?FoHC4$?QRQVF951gKm`-Q2Ed1Nt z**9dQ(Et2!7)uo92%%ERr9CYYCw1 z(K4Tv9iv(B8ofFLUDW??w)xM+Yn1$o0A7hd3MM9xvfZ;#2>l zi*^?ieFR7f+CfJ}lsyGSOFZKp{TtF8s&y_F`9$_h=|%a}3pLXo@MK@(JYe_u%K!L) z*%EM_=Ud^*J&H<~s?15b;l_pwisHg0N7CnvNrIf&ydo=YOFWYbg5to<#ZfkMw7sHJ z(`)X9pM)iI?rXL{QN6@5s|M%I2k;YU%=7STFF)pELPo`nn$EdJ%LBWNPu2G&#)rMi#OxS z^l4k$zu?9v7??gUc5?iLo2I<2iP~sN84!FRkoR!Qa!PN!yDx!RE%q>H5?)x_Af65u z*Sn4^%s*zx0)v2^jn-55TukLUG$PUn1Tluut2z8Jql59U_H$cfj4WEa2;a`>>}U@t zDmP-$s6y&L&jB(Ko<33?@=GA;LV)-enA^V}}|=G??m7s?X776AiZ zfbd2X1>2uTPE{7MY?Y-3PN|@2y$*6iCz(dc^o+3i57pT9WhyPTkTkaZ*uC6t$Zu?c zWHse=+(Z3ote28)`*PJdX?$l1Wlwqtr6@2LN1qB`V@>AnAmutST5^Afu7Kgy4u2EC z_#tPi7sd46^22G3KdMMhMvSKX$wVnz;z&>kds2(7DtCw&lo&LMB55Z5mHI2sruOg@ zhm^i_pYF*EjBwFdai=d%AJ%&;-8R$^gikr?o593qD3#d<6L&+;3fk2b;JtEFL+K&w z^K2LWN))-Uwz^=n>GHMK4`A)`nv<(8w`^C3nxTjjo3&YPpvV(2TqQT8$Bim0Eg@%h z$J4n>>)TULl2HN7HD*7f7THl5J9Rw_WGzEKpD-3DiW?3G8iD}jq{UL1qz+yG2y`h$ zXnc+DsE_ZnI8DJ;o4Z~;T1WC$Q{s5x#N9znTY)?S#D633qz4itGj6;J;}DjEUUQ!s z+d1xn1rmX!tX!+#+tRo;-#Rf<(OEre!O>$y^C{|=RMxZLg+)Qv+2K0H0l3Jj-F8z4 z2OZ9Gy6FuPZ+E;$%_zEo&r0agC&1&EQiRGJBQGf>>+@HIfFf)gN4cdh&tU`9Z$@l^ z@79Qb3G$X5dxSvJ9z`UqzX1PvquKEH%QG(!hkw63;8ecz z_sbm$wg8f@A9saI+8RJQPL_A9-$c$nVw&b22&6W6iLHQlryh+$Z2vjdVnXdNjhr3N z@*z`(UNM{aHhAi;!yW?CW( z(yrgXQ01ARAr1n`37tFJKH&I%eexL$!sU|-CxlG`_z;22v*-q}NBY>hURoaVB}zD- zBC70pg#!d@a^R(Q6T7f0w^jY89;pH@k8G&^3Fb;AfZDH&qAwng<`-81E2ndS<5L31 z0h96*ZX0>F9ZNmwTYYf4m0KFIy7pgLs-$;Fc z$`rZ$V&rspPIM`$5H6>K7mEo5AQ&lQOH^aJ$UD>?D4qR4yoRXNc`BGPjU88bE!aS-gWN{tS21GAmyX z@i$Dkgde}MtHf3D5*WSGKvCsae&60d4onG2_ppDeSE3gQYs@%)`3|4FkeZjesFFLP z0NV9T2so!333CPrw;hmQWI1kjdbqBFFMz2@FR7L- zYR3arhjSpfW&N_dlQG4;cq>~_X#qSS@Vi+Qx(o>xXVIAxA|*Ji-o^T5k+Zl*^SMt= zKYEqpEUM~f9WQ#eCd!$_h$x@%@$!g(A(N<*`my_t1F`tz<#!LCEo9M=KDUdUg(U&v zI)J0e<_7rXd8XJ^j{#` zkZh!O^!IUN?qr&zsw}PO$CYZTgLU{ug#g$q=eQ{Zc*@GpvG$J%vb_|CU#R4BovLMt?yYCUX=B$YYJtOO{13;wS8Fq>Jo4O{2%mJk# zHD#O*evahjE`|!zF0iZ7-SJ#Q@DX{uiiVWo!NQDetcQJ0>*A;z*udCIbbA!;avr1) z3shKB=4L}(uq=={i6laJxac{ra3zHjE}JTb-@AHAwpRwp7)U1TM-RBse1z}9M7zqN zbdAtzv8W;h3<(uYl6UmnsHJh&uqL&^A}gy1qEz(~)Ee4j#nfkB7Yka-#9OCEoR`z7 z`RSEm9pl5tT`XdNqqSqTw2*_@J1orBY#tRNm-MraAiexkSPXBlpy9_#q_2 z+{`~@|8s9Cbp1?-VB`ND*g^Sy{dmLsPh$Riq9H&3kuMI*0^0TG?JMR|I!yEbAzA!+ z)Bk?W|4%vSAD5k&xwU!!v6|uQMs|)MW3(-FYGH9$wE)~+Ep(Wjc!6s>=7=4K-TMJg z5(cCgZY?Xg0r|_7-ruA8a;t=GN`-s*Q29ljg#|2oIBYI-R1s(#)d4jlfvI(%Y-oiF zlecvQypj{Fl|B2U{1~$}sUXC@UYzcgT&a70*QaHEycG#a<5XTb$IGp9wke8Qwxv#u z^>x&;hPJ0>njRPxq+Pb}U0%3C)5_OMI)K&590#B)V`TfHX z1eHi7g~r7vbz`yW#vl_~&awheGiE9R8_Q~G(bdWxjdo3pH64D9E1$v^Od3W+0;meV zgXft%LGa1E@X1cB?}ca_Z1j<;fz7eErm4qTccsp1)b75L+FB z#}j@L`HWB>ik~x+V$&`Wclr_!2zxw$o1+(V#4nVMjK+e*l}aqON#&Gr1L<5y{mQs2 zc6eSmn^ShL=um6j1_IzP0EH7L39BZad)J2%)J{tgE**j;no9$h0}oAtg7>9~wiK&u zGnHn~N~s^#$v^=r9Bv5m9dcU+$s0{8cFy~x_4CcH2}SIxF{LrWoVyZ}eP%9)EP#O? z7?SJ_aV*D~6RXTJP7n5bY$`4O{p9A-AaCR&U^OGuEGv;JI;9wo0T3sb_Th+a06(7c zsjdI7h(%$TZQB?$z`oN@3s;(b?A{lIY!U1k~d7!`cJn9NkFbZaKRF z@=8F%i{e&g+XQDeo#YCFxJQ6pORt$0(%H*@I!h;d=B^E?EZ7`osyZ&n(5x53C@A+@ zLsI_ZYOwAtW-*ItDo6|p8;1x0CWNJfmPw9*Dbs@$1sCf5i-N%}n0=ksR~Bqd`-avy zcW;1`=2T!qKLR2~Jpi|4O{ZfV!_oVY6P@QGr;N2UOMU=tYy z3YjN?1%tO*Nc%Xq_Uh1b?)cQcsjxsw--qv^g=W=jG(oR&k;bJpq=T(k`SQk;9S5UUE5!yfvELUW*W z7(n3xj1>SSX63%^I%0gj>ZH%`z)}0^wtb*B&7;jxw;3;{oZSWMr-UCQ0s^Pm@B$$1 zyu?ZRDQNNuIcGN1e=O$Y&{fZlG}Wbm&I}Etd0x0&&j}?#=Pa`tpOH48XU|Bz0<2`< zrBUm7=xvU+?VF?pWJVAb9_-Z&yMZ&IcF*_aJ7+l7`#+;yV@zrmJkAE-T^a2C=j3i+ zIvGI4ktcfg>$tstbkJiqM=$0%c-v03SR8+;q&VqbwNA^0Ny|xVj-(mizkkSdtC$V3 z0ZClatr@JEt~a(r=lfBBHNXw*5LXZcmpH=FC+Z&R3TJo0CR-l;4gqdm3;+dM?NWX>+q!XcJ5UpNwV%WAl$6oTd*E?RwnGvi_ z13svHpOJc%DQnwo`x2(h$_9APd>=_%BdIcMq^b0!#X%V00&UX;SRda4_?Fxsdep9_ zFwjI$L$!ICGyXUH=PDc5-*`|TSs!D6D>)JWI0IS$OpR{g9x^Yj3iD>wW-EJV=BrFn zmdvuAXe<mC%o^#QNpzVxr83CVKY0mWrxk-6iIt?(NqPSN)3Tj1#EhWW_#+t?MZ5 zxCR#Gt{N+BjCxu352cWYj`s4CefM~ZMV<}S`MHT+sSj|4!gWc*c}Y$fxMWoQ5$5Hc z8j}XCF}(1n9YOhC>(Nt26m`<78*zld%8K6qd^BoJ4I(51)aXG|?yKM43-mUjLVL4x zHmlz+1q-mK8sxB~Ei|BY4bLwQ@drOi)N*ax<2MpO%A>eUcBB^}X!)r=hD7QD*yDzc zBzHArr-5WT(9Z&A2D*6+S@j@!d)EL@RHssFl7bl(fB9ta{I`dU0?1Y1#>@|1m{7TC zc{LAWiexoOBKUt6$&OJK3$1kOe`tttdKP9FC268$DgwsD z*HdtRw9_e7GdmxLa*ThI;%{MjaO%6I5K3!-8V=I);M`Rpl|liD5am8HxT#n~x6mH1 z?3*ioNEQ9)5U_sNoNipw$;ch|(w=(zK)67zg&!_dxr&5V_&=yc7uAg`0Ys!?OO$Gu zI3{Z@Gz5KVxa@(@*W{R_|v7s{`*j@kojxrz%c^~76Tdo z{z(6+8fH(P_Ncqo?Ai0T%;YkrS3)11)0Kb+BxN~o&eR5ycs`&udR@|cdbXS;Xy8h~ z+vfwQgo)5aDsUi`TGc3kI>N{uXQ*VA1}Hda?h+F#6hMmz6p`lxO4e8*_->Q|qkx

    ASxr;4HX#>8)8h~C^AsB}p5PJ6Wa=To5~tAFs=zm%|BEzut~0pj`nrN^ zvYxIpaorWitcS%CIutukzXsODYXA?#a6JW8e5jRDwxz_3pyl)um790>fU^vm4Srqk zVk;piwEwW2^M)MlBkjz>)g$_G`_olgaN?h&jQa>Xr5C#=E5nd+KKSL02T9J>;T->q z19U!Q8VZ(OI4*&uWyA1JT%py zS*u&ZP)fo$wyN|S<+CMM2Sf>&d^j&&Uf*vI)q6k>fPP7SY4TADSIkmF?=>CSCB26(d*9uY)qg`7&Hh1{CFL3^&;#&to_UF-0et%ZdfFxztjte#+SE? zYkFf&`tG0M{dLlTIiO#O9z)z5d=Xs1XW-V3aoH}W77vAsp7iksHeJ`({V}2^F@W@w zLt^T!_fQ^+D1Yn^qV~6!0K4m*Xi*jKV;UigtK%MXRoh7gK)(zO<{%m%z zFrp`fMj3o*b}&cVv|SbVXz|5DM@5dDkj(c{!ssV8e5cGgntq8)rgdS_<4nM3Rjl%j zpVbU_se%|k_|O(8ki{eKfIge@SVDiug%XgDG!c0w!Uv~?ynDD;WgBd&WY!xX>~xtk zEuL@g3M|>Cqv_KsN04D0l#h#0zG1zvMc6Y-x?O3 z{>qTMSWM0T7)W|b!1-xh1qiX4(0Q<}XrS^A1A@>ancUOUxliXsN<6Jgee!IQhn~9_ zSpjtPkZcEvBjj=V2XKGJfFrjjAHUoNEX+y$)qay5*5xAEDzu+ePAJ%j_#=h=8lA^a zd3PT@U+mXRd3kFi^79^LkDfzhU@N_^=SSI%8o|xcPlA-?+l-5_A8Eo{WY+VA1G8tf zCQ!h30+AS39X?d);rjFITMr~ie_}0D$9wJ)r+W(uh`(uqR5HTF^j(~|FTBhl1rEes zAQugpn@i|01A&`LCce+DA!yFWx6>vQ_tKJ0ylciC&zc03kfIVgVuvRU9T^G1+y4~0 z>pIjQ2I4y{9H83u&yuquPnij1j%fh2Q2F<&2Lt*Pl=FwW^MI^Vy>Q3V6B6|h3KzQJ zxme_5Z?jTJ{;phK1suyu6+mK~qkWd-&V^bjzp`rWiHFc%aD8k-F@{J_CC#dlfN<6P zpjNPu%xr1y%2EtJ92sIBuiXXo3DvP`y`*VECrIU*9!yaDu4(ZE%Abc{3FYDimJV)T z_;;JAX1k0DuNaQIpL3Y+0Az(WH#+M5>BZokTu#={IVMzsGr2g{lV>y=nYnmCX5`g( zy{J3+TwQ%!K!;RT51c9I$6KB+GPguR|Ek(H@(v$tsa&rtSmJr8sQ+X*Ypv4dL4<+E zPvw`LQDO#*z$k6 z=Kodd^IPK3PZmb+>~Vx0(|^YKzz(zIKh{3K~3SGsk3s$FCqSeSM&S;q(&>UuzKq zcc4b`ChhCIW44ko5^cgCz<~y*YqMx~kcm(gAvDhgAj-Tob<3Q+ zyY$$Y8qiF^vKA%%`Y*Vp06hr9aq6xC+08)iZygXgpHd=-E&D^;Vu!eJ{CbAK zBYH2e7;~v0+~rg5Y}EN#PR>>^mgi1#dJ8P)us6PLT}bH+ zJ3@0hTgYW+av^iMyGuz)Xk7@ZN5HahURWUgm-cS4v-zWrS#E((7;}mfHs^5`#rP&V z4wQtAa40bNODdskMJ8jp=ImuqUEl9SYzz(R1^qXbnjnE!qXdWOG^pZe=$r;9WQj4* zfKE+->UYhC;#XbAFTcyBDFDAkI}iXVqjWq;2Bf9)4A8U2Ic{cyx@L-23l6lTr%y;~ zt==ngY^X+sgC-ozDD!(zQ6SI(`P!dRrmC5sH~eK7#R_X!j0Ke|W{J;uP=E-AscIq84Mb4vlCFFrMNrvc1hMC*Q$Bjdsc9|x7;s=+ER8@u%W)x};j zGD*ZSWUA|+`d4C=*M92+D^u0CO>sQM|0&h|x-zW$u4&8+N2=p9#D-9$7qr+5T1)US zjhB=!(c;x-FUvPmfLDE1Cs)2<=0tCWn^}ebwB>s1O|(&w<3b_j12g1mAMjNpu?pd< ztrK;V84uDg)7BO`YZjU*8|;1Px7@MDRA9dRHDI`SAj@huDNRS9fw6JTwf z^nLO3PP&3hpZ=47D3a3upCIf18a26z)ku3k5Y!O%^4s^FLe%?D@ANk60TW;aXgk9G z!ne?1SofQIyV}8$Zoe-i8!_u*QAm{$e^R!!Ea`bMQ1w;OYqcH#Lk&^QK}Q@g`@%s@ z_#~FSHrWnJ5WY?!(}(>)V@RrLx*9hF6qZL{fNeHWfn|D^i=C+hzN9N)C#!tkqB{0a z@xF{La-cj5EPy27C^RV75dAIkRp1w%y}18v&Pe`AV$S6p&|_mDwT<_exsVT@Lppa5 zp9BzG9`l8mX4t?mXuois8F*Ht$ti$K=si5&I9lNrHyaATWCdVJpeM_rH}hx2?Mgg=zoQP1sAHW}1c5t#Y)>p@LEWru4m4xuk5f3YBM zXce>oVZsDBdC1M{evGZyV;8k?jlfUm3IsV7DcH+ifWRs{)&JDxo4Y_=z70e>;B6f~ zA$R~eQct|24?eZtW(f83=ZPR_2fyrxzB^o=g>!RK$ciEExF_Je)ZVB*=UU{f=v)&$T=MN1H< z${&u!>)i(lwST|DtPwB}MliCQvY4iJ`oq`L4(i;=t%~Cij+R-Y#jrYovMk!SvHG6C zsZ*VR6gb(0XaGP{`R{f@7VSypn(?~Q)se0Hpsg)Mah6((AU2YY_y62`(#HYUk<{sR z!hgTc?P1sDns7+%Ci)N?qt`jxsK$ulhnCp`gXC#K-4^lse=`u@hT!AO?!dvL3S^YE*2ufkGscWU zjxxB2zaVm<5Mq{2Lr@}&5r18m=|95kJmlutCsDl=dw|4XX*W461WJ7+Vx^6un%YG#b+1<;!oz!zq8 zeTpdrEsbZoIjiu$`U?#gCIv1uh6LPuWSTPq%p?i$f^uCTL!A)B4g2?+6oqIFSb|P- z{fnI(;Uy`{T(8xG!-W(@wia}z`S%zsp&ZP2*Szpv2K}G0OABZMz$4@_e}EA3^$2Qe z{Q$_Do^A>$g_ui(DXUha4P zC=uBu^0u(6oltc^)C5_Zd}19!*<&wQO(t@g!FxH8E41M`rLxhknpJha zIUzz9btDy`TnQ%Bf*KRMy>E+F%-ufZs#-NVypc53lsi@|P*Jb!5MUSnFAE~!j|CA( zzhT_PgZmfE%R>Mh84@U7*WdsjY7H@E)&u$ol_E+iMHeTg&Usnl|D|vnEvR$y66AhN zzIiC8QukSGBqqrkRQ=*VpMbRYtLG#RDPJbdHY2ssG&~(U#UQtRardcmxkpYiKA23%2y?K3!m9{s&UAc62%h}WG4!`9 zaTiNPpZqbzH2pbGG5sOeIB+VF?PqfM-_8qt<@koD(puzB0<)6+@amCu*k*35R5*T5 zGUM3jYDbXwdtj{eU3d$=T4;@i50^W>=lw+)NT&NH*;~7wfE=*+TakpGwJI3_EKS82 zwK|^E4%$mDW3LHNWPfdYF3CfGcW4k zrdC*hnCiE-a*fkmf(Q+s8mcNT0^zm%kI64@H}EC`i!LaWCWF3g3_xCkSC#rCMZ4Gg zHe3hFFCM0k|5b0yMuGZiJIKg0tlFh8pd0>&nb2?%m=5!i4PWoe8dmJU|bAd5Hg?njOWNe7T%;8@>YWzYCh(o`GBxhX)3Nd-)rQ#Bn3 ziSZ=P-D0xrBynB{K#v}SU_Q7q zu9{PlGe!cVRgp!G-aDim2${3jnZU*sp!AkAM0CU%&ise1QuO|M&s}9yIy97FY8xEbXi;1>sI44>yYi z9Ph%58`tdYtAQ_Yk+`@CqCj+;^+G=NX(Vki=gv;4Rt6SC zAEq_3$emsUMi^Lq&Zu~%~`xfT& zn3oqIU|%xyu%4eRqvGmkoh~8(DV%Z3X~uo>Qp)GDj4BfOQsm-c2the*$eY+nq<(lR zNv;N8kMP+7OY@})n@DFOiKUC4y^-015tOYAa7X_Sd2b#M_1gcBw;ZRMj-zu9DU#Fa zlr5A{C?reBmL=JSO4dkLU;mu*C^7Hlx~|vj`FbvB5yK6b(q~Zj*3i6*EFRG*IXX9CwyfX@ZZ z&VKWyuI^_LK|xH-?`6bcsdNj;9A&<%Hs`&1;rEGji(ssju30b=VS}d?>kuuNk3++g zXeUAi-P^uks2+Te63%L}cb|N{2joz>v=!Z*g>O3M^9J|Xe8mB5QvbYxB4w7O9#_(4 zucDzqSzB;U2>1fEUYmTcCQUA~EDl{81(Ru*J@hxfw^>)IFTZcElyAD+3>hhxeyw9+}XM=8%Da zKqo^tlF96bY0PZX$&l+-!dZ&!SD8klLB@JfB0`=q=0DUgvWFzEz^-9eME2@dZ71pp z7;fqsE${Jq{aY_T)CDPT2Bc}wE25S^#mb+KD~|`2yh?sS%eAu@{!dQZR6FO{f1-?Cre)o8mqd(&~ml>saZ zFM6d0jX-m;9FhvN!`yrnM(x22+a3ea3oO7uo_`x3%BJ@`U+;3;iP6>234^m&)4;4K z-yB(*0tNKNZh2gUt*);I8l&jlcV~wJu`eDOo5&%lRSuy;bwB%7)7|I&ySL!ZeFpU{ z(4*3-bBC#6(*j+QnmKHtI8Ey3PeL$b)nM8sPsd8|h!Mp&e8pQV!1>n=3xs@FzB6#r zHAr+0As%W!TKPnsxOcgQ3{cETt3n4Hz{It;fQm&UnAWBI;!D=F;ecb;GDWUhY(lsJpXo&Ix!P zAUR8Kv#Kr|M>H!qobK`5OZGd8$>XNMEX2J$2P&De?jDoyB22V6!gv85MlkUNQJm8- z7AKy^oox>Ne(acXy+XV9vl4z}_<+7F?(kk+5m^jPaHcXuy4988%k?s*z)qS7O3YhG+0-dBNg1@PM)%2ctcLByCPQu0535D_Ckf+&vP1;% z0p@MQN8^ULcjR7-&Si}2K41YJqdrW?JQfcvR9W5U37gQbFhms2BS#z_iuH=hyF6tc zujFAhT)j;5CcKAg`6&;}5&JT_z_-qQa;de*-b!~0DK9p4TAEAVV!rNHQ?b3{U{6~C z59ci!S2{Wwtv0qD-rU>#zgtcQP&Lef2Wpi%81Itomi5hU;K${k1Uaa^13H=_t)fIM zIdH&_s%kxHq707@0Lnb#>QL?1*vbWQMS67xDSlQwToGk_Z;X{oSY?E7IUY} z&!nEMGa(F{yK$gAaAFUaeF7!crq`6i*d(al95PCv=4pH(xQ-OFjDp;XU}8a!FmoGg z0k%h4fYYv%uRWLdxwU6z3?m3#G?sK3YM#zYnC+Dk)cyC&aXPZ!4SGwCJ1Vs+&oCFB zwk97OZs~b-q&XI~RvBh32D$C|Qy5VuE!+d@6r)mqL_kU&EBkb?am~#^vJ%$)&^pQZ z*d(d#dk_uF19#5@OZIikIY$A>$jb=-p|zpio#VsPXmGu}WqC^1?RyD5Q=I9ZU6+LA zjhR0+O%FS;**Q7i`tIT2HYmDY=^jJ=EASF3DB#Y0X4Xm{fI0+<7c?6bh-k}h1O*PQ z#q4crzkp@cYAfdPxuwg$y@iV26-PMW(q+UK9v{0&x)q-SmM+R+9gnVcb?`wa*IvAn z?>vCB#i;`W>eDJ!qpaJ>{e^4Hh=(Z}iH?-0Yv>;*Srx80mlF(BQIlMaQ*Xjxksp43 zKVae@(EOi+Ky1{N3NEsYjV3qn_P3c6!bKh=0Su8M=u#W1LFyR}X`W`-GV@g05fn;wHGO!h40VLNUH9R`(fAQ}NX zcr-XmBt8hB>J@BZtsS0=d&iZZ;U})NYOIg^Ve^P0ANeM>eMMLBL{laRS?X%S4}JYp zKaVd##{chXjjw664wLBtdjr%vtgK*vP=uXcS;i`FWtni5)`p+509Nb=NlPa5KXp^j zNI<RYqaQK_ukN1;l3m7Fh#|#fHR8I#PYR=CDeZY(-oiYn- zuF3*Tko}PV&FEZg;jwC{73fy4&Qb>PxfA%QS1yUrd;>d+^)jpm`l2$~cHYgua|(5f z^SNp-z=7paa)FR5sofs=7#K7OFw&!6 zxdT}H38ac!2YvcE{{6#n?4A?WzaD5@u45~cin3$?Ow;0bA+*3I{<~I$(i*oIvz)w#l=*QAL=!F9I zDWn+sR&lE3tli-_Y)ED0WSe38FrsvZ?sC)4>LilWdu+XdYtmN(-FQ$?3=Ll7n%>Hm`5eP)pbsn`;3=x+Oo0{Qv*`Psj0y%S=y@JB7l9j(p!o1j2{PK) z!4;tFUk*G0k(Z|omOh3NrHh`a)JpSHcWf_moF%PW6iPq zYiI#dRXPQa z=0NGTBonbvCWQer-_Wk>o#UbEf!$=rlX0TQ;rc(SO~?ytVPl=NX$NS(ua8zQTvevx2Q~nS&EJ-c5!x2k z)Q3rbb-3&jxNPF~%|PlU_6q*$>UDtdG3K<>Rifj*GrwcA%>2kVt%!|X0|lk1I7H&^R(;iYv0kT zuFD{@?Gs=LoG?aJ5O-!@ERqrg~@Kjmd>D$eT zPNn=von7B78;ZoNM-sMbhHASJXxtX>=KkqS?Ls=DSmfE1K9dWA_R)dLh&RdXq5GtZX z^MFzoUZ>8xTp;-Z-SHl33V={Szv7E%JT0mFLCgIGD!0^p3BwCpjpGe#M9-`8lr&H| z>;$ROP9)C%f6ds{+iY0+H&8ih<-P8I)D6m0WLXpjO^vus@8bw5SJgx(9(@Cfw=e9N zXMe@TtDWr;N0;v`M!$K{mPhpe2uT;!56Zrse#)*b4~&KG98)^_cx6zYu?EN22PhvP z+f+gN1%@9Z@|VxV9ccs$i$tMrxkNSmCdNw5chK>BKn>BebGL;N3pk;Dn>$Pe{&+`F z)X$a&0^0N?`jo6G*)(YO>Dx;IdPF$d`tnl6I#O99^E%WEx1fPd1di1$kh;p{<9Iq4 zrJuean_7snd^P@mL&~+C#EWv_vEvAtxTY;2F0sVT!$AM}yC;|0X`iP|JlfVjDc^6C z|Gn~k9LxgAY;Xc23F8(IEYg~mfqzH$ z!@_1(IrCDcU`v_1x^?N$J~PZdh;Vp+nJ!|VIj;_MKXy73jW9Om0<@k5)6WQJHwUZv zdw*iY=uUQm)cqdF7(}nVNZw12erQodQVx%TiCL+@*|u}pFm*~65fVwjXqvA^zFj~F zdZd2eU{i*ceyLPshk~zYZNENcuoLk0tLZj9&=t4G%ED+tf-5u9q0AF{sN84ua!6?~6yljaIB>KuN+g^57{J7AH%Bwg2s=_jeuW|M&Fj zsbKG4_zgSG3Qhb!P4<{p{fSn4;$be;1(q)TVA`BJ3*M$)(;nb`S66eh2}XURJ4QgS zccBbnMrDn1Re9RB2h^kS9q@-u&@rFGWmv+brb;6u0BHHotEXRk0B9LIJbiM0>LgCFb~~6}>;&M|gn2=Fs(0b$huue0k~1BE)!_ms2d`#Ai(JReu-sVZ z4m)fUa`&F#jED9FgNdgi=(?1kb5laNhr=UEUt?V2KuW0kOREE5rBUqk7I0Yev{8^# zDj$?%{RQkoA&I=}SvH zYdQPuaLrNVJ9;CV$_2Te{g&b08+uD_#W*s7(QBMrXhu9g3)CLRGVu55i9j9i92)1I zX8>|#oI7oq`T6!J04TK0yod(xtwjqHVc$Q5AV5V-XOQI!vXNj81G@_W^#L$3AC;^_ zeLxv-e!;e|AM{U^ocmh2aN1|6i}PprvdeV0sUvm1!C9aY*B3l0Wy3l+!M5}7#&4mO zL?MP+W4pytX`UHfjF?(yr<*v_f%p@C8?c^rcwUBTV-=eznYfRa#OGwKiyrLZ&h+*J zaI64(OFChkCZg==$}R-{*;qM?hYcbjKzU1Ut?p6vxet#{JP2Ew)2st%WlC}5$CI{T z1WwFXL#$$ae6+pfl7qC69Kf`BZr>|g5Q^1b)x#+e6B?$Ke(%p89(~=bw-#*Q4{>x- z2f@-W-b%u|jx;HEH76}2ozG2O^vopv>p%wGkg?0)d9S431SPe2Woq)&l_<^+^-{VOzP z&TuY^I*IVJkrUB!^(OkO+{5x}{-n;s$j?SR3wAHRSs*-T8J5fzuc{J^m6`)x@E!gT zBz`>No{O!m0lHRc(rHbnoMoC6tZ%E1@)f({;}^O+!Ed1Lwbq!Hig2EEMMudu2@;dG zJ*-%MNhN{o=%)x8+X3qJkP{j|rS;}r83lrg5oKttU-)UR_fy}Iw0hO{sYck!M`zL4 z7Rlykk$bjYI+^~ScV2U-}*7+9HkO;{lSemWNCxf4e(W=y| z1+9S+iMl&6=Zx5$oR9!-sPCt78h74!V#J%sZR?m{W}+0q%Pt2wISmsPi> zet4;J`uzbKjuAL|@}zRT91Ig^A+qNCavz#e3w#P%iE{5Jf#R}J0(Y(;0<{p+B0uD= zxJ=2n-9@Pfg=dLmw&e_ig)E!WOSDE@tL59hn|z}T-Of@xUzlflAgfRKIq4BO++ckNn>WUCFskn0n>L5!CXS7rI7v#Dm5x$It&D za@r#KIF-f@4X4@tOb5NO;gg;}JfrOuA6w}|D_LZDAz1?p1fiPA4Ea|Pmxf9U${}gs zlG`Y9e|(fnhRGHnGe^>}Wp%>@wQ zH>OVQz&bO6O>uPpdAa)^9$p3!Q#qhwFR7sHaf<64Z70t;M|NiYaKY<{x{+-WRBL$y z);EC@^RhLb+-+ZHb;vRM!;wvi{X@QZ1@M=svcsKJKWB;b2cAFYb2zZGpB%V_$GzI1 zHgD~6k3-WH;=3Ipj#UQcq>H<@7eb707b9l^o2uTkmZ8#NR{-@#?(!vc;rti_)dJP; z(M4>rh6g5Le`(=KH6XKx%5QVClKc_~`75{;e%+tM_^mh*mQuG5-4TXjWx`E5%od0Z zq*~Wx!})5H3G?AIrkML_Okk77jCvT^-g&no5Q;S&cDCjO6ozg~)4ZAww`N;cQ|E}S z4@?=|Jo>y>2336sUvrKErARzl^nU7AP2$7l&ORe^$7JKnu;tkv(qS;NN@toi3>I8) zEfP^R#*{PfYzmLWbhYt7x&$Y5%qL|h_>SEb*w3Q(a8E3k4R?{#ws6f@p@gJ!Q*SLrgw{=e zAT0+w(})$&-8B0SwLN*Bq5(x%bEq<;ffzGCN_}WkWp?;Qee1i~QpjQUZEWWRGDK8< zZ+RsrK+Ccu2E&~UliGXB@XYOvZIgZSp|7GXd?#!WO5+y~Agf__azTr+Kxmt67qG&1 zHKpYA-kAzsksEmWz6^QqURv_dOPv^e=4c#m$g_(8Ct?XTTuVdjr2luIY9HMF6j>kn z$yDI+W-zuHQ|Vt+VMcy!GSFdnOKw zelrvs9KMe?^1xKuMP|P-HraRBb^602fvoV0t)>QNa{K?VXi4V=28Lv+Sd_}~@dO{} z+~g^SMBlRril089L$f;HW}brUk(L{ArxqktLR!e^Ij}rD31j4`RUgJCM5=SPo0J#J ztn^_5cBO!f4!W(HF62b)tSp18PwUOPquLRRuD$eET&-(?<=!U_0#^>L%=H-&kAs)M z|MujPokC6Y;o&sE!0lUSDIY6gf^8_I4Ze@*9(JRx@FLhW`X(!U^-BMkt;p+NHP6#{ zuf>71DoZ717Z40a-`qS3fXdWtd&5#mkvfArgF{v5(3TGC~6nXp$!Xl1e7{M>p^5VRLx}!cLg0DU>T~%38|JnSoO2@D#5)? z{v_LXCu?T=Uq&qOTdrseFl9SUDXmj(Y9}k+eye7Gdl26hG_A@~@7UGO`!DVAQrzIo zGE2Kfzot9S)Zj2U>vZC7s~^HMbPP9n{PpiQTQ{Y&eB>ilEEeRNHzCeJBei$6h4&(f zBupBG3ux5~XTLjpQzr}I_&kE#U#w9k@}Y`ca07fSGd}U_Uq(K0IzW?ef`jrLu5S~z z{wia45O+smBx5%g6Yydu$4>BQcWTOb@Z9q%T)y-`^)?JM=qr|B@a;yegZjVr|tB7S>$M|BQ-9cs;YEZp zAgwaUWOJs+{2!v=9{AJeU6npYfZHDeGsHX%VeXFRY5aZAeROzVRt4F|*%YZuT61I1 zrUug1Fuvym5A?dc?&;LJJ^g8>+pZITJV@Q=DoB=Me56_@Vw-zY3OxXXv)BV+GONU} zcP^sCZ<9e!4dEQl+3etEE17ejWTh(jV;mqmqpyc4YK z^ckX-k-gS5#uFfvto_HCk*2LM#)_%7j}0;ko73>)$-QnE z;QuBdm3VqV$zfP%IWUc!u?!kAWv?&1V9qb>B7e-M#+Aaj`jzdR;4eeUwaCwqCUmC& zq}b76$S;xK!>(FOH0o2kiy{jerPMN6R$t~KGBmaN_Sr-rQD()Cy9!>Waa0KxeD__Y zDV_cR2Zo;-jAEP_h|WQ!fEeU5yR8tb;e&i%j_q)Hv4KqnNqLT67Lw6g)uUk(vYAF> z6IQV&k*==y_9n}{TD8EY9;Q%-u%1wvpDgzPS0q0*$U1UEqdPcdkM}eJOmT?eUr^bf zPy!5n2E@R4Ve6Cj&+l=jm8bix^Y;p-t(f1L`t+3A}XZqgfIZs+LQ+pw9rfm4W z%!a7sY0rXMcp+c<`Fm=^iJuPXGF_+Bs6k!o`dy`cQ-jrUDmNLFkq&L)1rjQ zdq3LiK}m5eRHE|Om6#s;3{K?-YX0=Ax$g|SW><28>p9QWR1475zq)qj-KEiNw`qs^ z*R@t9`T7IhtC9vF{@f`>?%ewVTt`PU70>1^=dBp`ezi+Lm&IC?~86$Z|o2L za=qN1YrY%01KPpml6f4c!k(LfKIOo#HL zA7_!MA+1MT&I~uIyAl1=Ei35++g(&B&%H|UkcarB^PzF3q3t-lFP_u@2yn_Q+vnR@ zt}&iebHg2b{e@E*R%>U{qjb*HP(mwy@U;YbJ7~(`^5P&uXpi08dezQ*U@x6v(hvS@ z0LH}yhSu>3-?}76Zm2P~i4NUxeM)MG_Nnk#eshmTk}aXqpPnH<$Cc%#_2xHMd6*+WX+CaJwv5&=GkF0T+F#%<@Cl&0?H#x7e;^2QB4Xp|F z*Duo$Ze_?Oro2s`NSzvN_P0wSdg$R)T~s4j)$etq7}c@)cotp6|23yiw|QTiQYx3b zqmf$4)R5<@Du~rrG;hh5Z&z1UJx`7myfJLkrb1N^I(@=MchYVvr*_NGZr$d@+L)SW zALbPSa^GzUT7#aSF}lq1g4}iwiqw8@yqqU~oS=`3|2OPX z){p5_RvHm&hw)-&9Kae2ZPa;mp@Pub5XS>Djp*Y15~_Y9uC4! zdsoDVteC0ah8^fE{3%o{KAI>`pNJnFSK-VbnNOKwl+THC(gA(hnG1#Szb8oRn6?QNCJay2%z~{Hp*@3uJre<~XjY zWlHfkxm=ZoNwo(WXrqPEAEN>6lU^k^dxka-%{TL)^>(hbbyLaZmdeZQP{TIw%gMV! z#fcX=^KMWWog#r)@@ghVhsY#N=%q^UVY<=6JZTD_D~WA_X>ePWN{24#gTW5&6j5G| z^(l4!JZPq7BBQM-4V&}nd=}n{!@3M6qbu&`s6(x|CQ|!p#OMPbspN&IOVuD#)Au@`Z8PCf=BAo#MvIr6o~ujX>VCLgz0;t$*`nxiRRf1pLf zM4uh&`~A+*a(UL1Jwv;XW9o|eHxyTMH-x*gmdSJPXX-b8j5*e(zQx`aWLDLk%v_01 znd7IJ#(<2EMzFL8F5F1RHJ3Dd59k(hIG1_OL-l*;J-gxya@OR7^T$?Bp7vLFeTMO3 z%4PRZ@F4yOTwq}5__n53xjp&`@7^OLfJTa6wn;&qduGqlg>8)S7^|1rJJ>iCe1aY1 zH8=BdOTUXB{Jpbwb4HoOpRfL9>8XWRU&Tx}kISg#dXS9Ag-Xcd!~%75+pP;l^RwGS zhQHUW(`8(*$s4+Kqu;C}PLSYc){-tSOJ*A50`q_HWt}FjU9}`Mr~_7u$!>2 zQx-3>gSg`D48tN(y%5*o5%r>7p@cwwVv-tNb6o0Wt1O*%qI=_D=#Vi@7*`vc8ZfF@ ze*2*m;mF1FKhYcrcd7CR2z70;=R`{1J&c5cCN{U_NWBRTtS_+NDPh3AEzW>oRlgO; zZWB#Idpv4Xgu}L=qGijdZJWyTlAfAD;feI#HT*l$=6d6OU*Cg=)8vzFt6eI_6&_k# z6CLtHv^IqW?cz)yj?O$<0ZR!$9qSaH=I|E4v8HR#Ff-(;q+@I3 zX2Ownmo)6{$#Cm=Rbs^c!PRY`F*vtbM{r%XePg@46k)bwD#wVZJNe!Lm*_?9j5DJ! z46kiaIGn&!MEWNr7;euM%Q>YXE{iW5>4h~T2(p&S_Qum;p749Q$cG$0T!71 zCAH|*iM4x`&7REtStN+<$LQc0^N0`HXtey!cv68l1Uc=hGkAYS;}>0lw3c%kVB~YX zbA_Z8D<#cqwLodAd#}GR^ywC74vt8tQ7poUyY=D$!*dhTYw}N;t$aE8*OvSS;|F0)f!ERLDb&p`a-e$ z`+OC}!=S&2l()bH8j!u5@#eTUj~|W8!SB3%0AemB7HZc8KYi0aNRT!85BhC!z%(!$ zc|G3(+0r85rmVGPm{iD}A&0oBY6rcZDryEn1I9IP{?e->?{dd0M?6cC02;ctG;^@@ zGK>(o{;-F|zGl=Gyr}la7u3G@Ig)y8_3b6VH1dD*U}-y?*N(OwV1F=b{`ByFVC`@E zaqH*osar?30fzCSWomgga^`GQw#K!kUr-60%pQU$D1N>DgyJ9gt*C|AlQ5OCO2f*f zfwMPc@9^@J#$r60vpy3sHc}CU2gG0$_zPcQzd=U8E@UPJ!XIN?DMe^w9z)!jlt+OYLJx=iKz$rycm||so<=Bshn}yrwX9;x!n@79&A z1*4XnvX-)8?1j1i$q(#-_`{wry{OXXUerM75;A!E}IaKgbPRs115XQJ9JYOhgpU{m?P=I_Jg85o|Cx**0^#+>%RA&IeY7@uUKmT86 z1I85G)16$XX?Z4toBKlwMv~JEWgZ1LMJ{zHEHxrC9m?OytZ6FA2j^qh$N*SqqbY#3 zTxMBo$}gJrVBB%njkEZ;!OTiQ0+vK6(Gc-X2ly!+OW=v;Nq^`VH194e_+VDv?cwWz zn0q{F9iz?!b3iE5{r9Zc45_7)0em+ARw*r%FiG~L!(`R#E!BlXXX%(@Ty2%a^JtTI zB*X7OzVzuoa8YvYp(zltKxktDoyIGM0_IQc{nnI6#d8rBD%`F@%(>D%O;nN5&z?P? zTvPd?kJd+d+j>qwlSq8{2b%4y*f+G#f*jr*h2b~iyOYBQ^CJ(iH**qq$hdMSHJv7? z?Y^EIg`G%u_w@iX!~=)&Pl7#?TjN^3>w)iTAL`@oX<(GTL;wtzo^>+XcZbknm%}QA z>hBTE!ErAcp;pMwS}i7j${zu7EqC^9VJ+S`Fl+nDPk-S+Soo`dFx0oL{g;ONeq2Bf zXms}fore0@G<8vkLsyiBO-Q=66C82r5G)>d({*(KYbXmPumA-4MR_N>aC5_?VSoBN zUwvanViXXF;t>Y{nXYW1p~P=M^v7=j%^!ZK6i}`|OX-*)z}{8Xo?)r zZ>#!`-F6>`1EQJ`id1lr(GxBf#e(TXB53zAS=zjrc*@7D<%56D#4)F-`L-@7wtE67 z9JkQW9)|w1l#QU$7mLy0Rs?{Zfaj9D>5w4g@@=%M`#3LI{>$Ke2=G{vJ>wKRm&xh_ z>VY!omOM=~~FF1ZIKH02-PA1H}Zh+?@W?w`r#MWBa0}$T?@$im_uGC5O zhYKqiS~AJv+4d8VSb%=A76gCOLwlrWp6d^Rc-$3y5`W6(gCSr4fK$>T%rD4yiCb z#Uahwm2?_(5m~XDT$1pyVrC?>0&o|&M<|hpq3PoIH+~_48xd-1W}e7rmM)5HcsFQb zz*?wj3#m0@OnDwuVovGFpT?;=d%+>vPc;nb9pIBsqsd8*GO!TBaIn3JbjKE|hk*If zl#+qfL^;{H0TeMKrzhjVLY_{A^2mhI+X(r1k~T&w?p&=zj#|iOs*Sctj(~nF= z4}Yopb(JF}bjgj4+8I~Oi8}W74ZuJc3C`01a>H||4%%sm1^1{Cxj$1pLae4$RfQg) zM0up1=?H4|Bc(VnltYa8)+D`n1019ikcT*hhd{qQ`JjOkpg@etWQ%ku1x#M@7vF5n z46v9xqG&A?g|R$ETA^9#$VAMF_2ARGUg3Bo;R*$f_Da?$YMadX>j)%XEE5MW_ZJLR zkW;I1!ZLqp5nK)f)3Q-8cRS}u(g+k^%R zh#&`U+P9a19q^lwp%V8g6aP1osdsu5u|8+6Q&69U{3OED)ik2 ziIGPcbAC;wIvXhS7J*rc*=nxxbuo?cPgiR4C zz!n?I!TU@!?V4zjUf5CYeEPTPE?;ZIzt(HrgcMAQ#b1J1|33C0Ev?{5a8j+7!!gUK z(B~$PQ+P}6=B16n9N6IKD?-`MPS6+z0$A%w zwaSZMlv?*`T1^V~*UwxvQ$DgANDp}DcOu;d@B&7*?Wr%uJ)Ipo` z^-Kjg5Y#a3h`!+!`xpVVflfbRdhsTHQ1pdPIPuX%lb2C3bl=we~!0pO3x@OQj&=RkLCkBq^fv6C8(28c!22`FT`P zo-IV!v*XZ)K#v5xIIxBLY-(m(#WOVYX*BuZ0*BSD`S}b0`dT|ANh#hdnI?CSh5$XJj!EDKbc#e88QsN(?dp z3`U8yJ;S2qP2P-1+vuIg8?Ka0fltOOmS=NR^v&V@jHmUbzkwVZ%zOVx2jq7OS*tNB zn)RBoT{Q=~W_{U2LgW|~_Ff!pI%CBT_Y6Wxt9@{WWRz8Ns}* ze+fzD9-`#;sOq*lHkc)P4Onf@Gh zDQYlKgh0SEUs<%HYNig#X@`>lKi@w8Nq+ul?W62Lw$XxDJLq{tK&30Pg+y;sDkrWE z3=Vm@IaPBKing-a-vrM~uJmOFK8W^WPO}jcyA!44`n2LB#b;(x4?{9#bhv{|M_a>w zK8rDH$)CXxQHdr;wl|ierxsbv+hn$0#`GX7zF}d0?cOq#MdK$*Te4^hvVFRA8VzNx z-Ullq$_tXNNPz}S0dmBN}l$3Rl z%CoSzk%c0yky|YUF$$raWpH^>dS>)CN>_(9Y6jPXXp2$S%tvdwqYFkqu)&nOoOday z51t4F&$Y<7sp!{hL4-#oR9?#8nD5SUMoPAWzBlgZvfR?$j+E~w%HuCp4Es8uX+W0A zO1?k{y+v`Fi=nsjbH zV}J&qs?NP%V%%01$F%A2_?t_TFtVM3GJOSo2`_&}vO^L~c^>R1iYZ}?>#lk^cNY2Y z{RVu@G%emHYl-uPCYYNwp7QZzIYssxTE5IOiyh82)jbmvn*^b$&Ed<0yVdiq7GSP@ zzE-ES{&b5OqT`{)P6d2WwfJ|lDV7kaz_T^mP$k#hpJ$e7;{exP{xLV@;r`LY{%020 z?x}(hZU{tnWIlL~jqcI=5{CCSVfZ_2)Yq3^lwW2%3y@*@g2gdELBa zPqr*PSf3*mp+&|^B|bWQ;~U~A#2ZJ5MP=2vPn_E{e=qHaGpb{>wK(F#qg1QT(H2R| zy|VUr){}yN6`}gcTUHg*>nk>k_fCmPuB{+kt(aI}{fAb)NxO~qzy>@oP?c35Im&Y` z>)xNCh4GeUv5zFAFk#!qc@JE06hcc>r}Z3Z@&gHMIohYx?q>eR2G@*{=@HXV^g2Ue zY9zEFi-D=8m*pzo|L6lxq$h)n4ckc`nn4rA;W%&K3{D{FJvX5a8ZD-CGN< zCW<(buI8sM>W{$Z3q_?a`-qG^)KZ3k4R~&p_p_EX9Qki!?*0*1{i*3c!Bv+m`EMgr z0eJMA4~CA!>Mx+DJ$NSR27vxt0#dAm#PZhCfW!P8$#TOOD241L!p7lC^EJ%al^q`} zS=5;%C^dqunWRu2NVa&vO6T*TmQe&9cNr51kNTo#RKQT*wg>pT_rNH}XXb;`Jupp0 zeU)vYS-#DA2Q`sV8q^q|Rl&0w?J7<=*@U*9hL|9aa=AHAGxCD`_DjOwtdE5z2k-$tYr{VH|2ftqBbh>?}10;2( z|BwqMe4z_Ce4zOC{a?YPB4&G`ZC`F1L0sYoRoj&H&~G4*YajC| zS!_mm##GwG9WXjTZlT~&3#m~^6k`N;!5jy!=f-^3;Focr4ZImx_(M8I%0zW2{XQgN zSkmtY_=skfdA@3cu4{8|Su8Yuew85*-N(x=0#)-uJW(l%6&A|-V?A)+_r3sih64Dy zDFYZ${`OS%*T}f`=AFpo0%8p;L9(`ih*(W*7@oJf8h57^+A{4!`7X{v`asw46aoH# z{sBI#I|D#t80_lixU<1V^Tb+thufX85NVfj^*$(*_{$c%mxd~kRH5Jm@x1p`aKD55 zqr98aU|QP^sWX@@%vUJSoIW9xEnUzAsBU*-PCc4SRSq$28kp5zsZ;4+&ONYuK@(p#9cK$#f%pFyTdJ-NEc!)4sT ze~KXWqLn<|0OrVmpImGuEj$p-kN>OQlUK09zx)?T)Q5{t1IoMjsKW%p6*>g|z5mF+ z`I*9b|D7+H^NWqYy;^~B+*Ta6Cb*J6it|}iOUeTk0f2bOSEZn8jHe9(pFXz>HQvam>Q>6!dx z$X%-HzANFj);GCkpEZ6DRzYn6S*G0(WQ#Oq2YC?+pm*K7C3E!$9!6R|$8KNh3;sf# zNdSoEsPdJg?h_>!8U&Gf|Q;L@`f}ylM}AyBb@x`B3-da&8$6FnjVGs%hYJA9~k(V@KYR z_UB1z)ccS|nF+W|nF#_jTSAWQyrx;+X#?aF}go@ zQk^{7nzN*Yzp#2L0VQ-23V*m83T{Y7Adfcxye(STz#WsaCV=rZnq!V+L+?$XfD~a% zKE$dHBURHVGeK9=0{Z6b?$iS>D^3I0{|W()Ef#%{gl;UmpH~~DSrF|a_(e~!UFjV4 z8c;z54;f+=5L`LRs2Z=K2Y@LCXoQ5yorp%j8_z$ zXcCzKq2p@=FH!p8;3-0BEkyb!3WUw!>0E>q51hm|URl5M#LK<~gU3R!3`*{-hu~C_ zSxLh8ci?C8syv=HMQ!2r2s4mb7(%4!tX5l*<5lU8hxjODkB=0EP0b-wJMV$TP)Qk* zTzxo=B7c|(DU|AHW4;dz>^yA*+I6NwiT!XE6-HF%OSQA)cZ2aia%Uxob^A57qr4gPVjgeszSI(lOX9Jva}LGK`x6SyE>db7rSu;_OA&9G-E^y=Xh7t%L$15MS)MQ=4&OL;(WG7`K z|DQ3e9ArSoJ|$Ia?~_0Fx|$wcY`HQBobKXb8jwLF(hJNAMB+)dT%i#%3mF~)eW;AA zy0|uPLR3z`Y2c`)XRcfPBU5J}SP+4c8UHtG2wvRpmec8fhg%M>`gf_+{|dJh0mIV& zIIh*Lk1;32U>>y_Db@P7^*Si1j;#w{G9hCwJu~T~n zL+@~#n*e8P;@{Qf_(!x@;_y8bX>{~)WCt6`b!x!Fb*Gx&$aa)90*bu@rEw9(4ks5j z>MLHb=l+*bt;aL9s(DeZIU}2`2pM|?AgXo8zm94(_?xKKz|B01fiPcq74HLNWHd~; zccSUJ+W7rr$P669tfVc#HUzw-yVU^|^$S`(`}?Y&4viuWA`&65_Wkm0&Yd4*EJ$@D3pYE&NzH4xs--IzxuRY zkx2O-CR48!0wl|EGN&x8Eejp?q8^z}CkcHk^|)2Fghw$SWeH8XRzm%v}OC0Eu)CujmURJ4Czumwo zU*o8f8#b-J6&pPRcqTs0c7VgfGv~G<_yV+E|>x#^bc8+LQau{+pNf|-~MHIYxZBmTMZY(Tg{1UyAK%X z)q4TzxqjNDZWz=g2jRfSt;twoxbHS?ZZW(z+ZCLO8PCMhQ2Dq5ovf)2jqrb4XS5 z^OqcMI%u0dFx4T43A*jm+;Ss(=_bXxpLKp%iTUN{YW>3xW*+ak5EF3d;AO^B`OIyG zT1WMFT+lyw)aa=8xmB^**3GTP@jfqZt3P@^Fm^8{ z6APl$XWO4rD+f=y%vjeq?XpMeIE5rbv=^El85%xxGb9U?@=(aIZC{9gdq+#>`{(QV zB=n(i5u|Jx9oA?QxUoUQ^coZdi76Y|P9|M*_<*Uie5()j_d*EQc8)iuwBwVhxVx7+ zrlE~5*BvLE96=Q2&tWVLeF@^3k)nh2tRjoJ{kclShvgt4`KCR5d8;quc9Z&dt5@WD z(|;@#CvZ=n_D*g9HxQiRYXo1rRe1x3g*-x~e6@?R9Coxn_E7 z9CxM&no#cvYR3HVbgOtQ?2Zcf^*(6(Sebe15CdGYhLzr0opm3|ip?Z%!?K^HI5bn9 z$$POoScl>wJ#LldK;A_e`)szRyjRk_R}oHc9hJOnPYdO3-D{#9XDr!pA41JWG8iIj z(M33`$_+)k!0b2%Um$B&(eiDLSH<;90CcCi&4sunRp8}EE3@mle&=KGUBT^qx!&~) zK-q&FgXzbnIs2kD=0N;RjIq2^q|JLY$ZFEEBkhpvsG#xC=^=RZF9n1`SrCX}ubS7H zjk)@+zc9?q={hUSqV_uG{+zlMXN{gy8rLBGgI;0#T&X(w{%e8rU6W~Vp~fop|KJlx z%)Ob@35Qdr@?-~=sA&B5MyC!#xST+~jBS_N(=jzvXp>+SSM8x1O7HDdNhA!KZ023E zLbwy}$wjiRQ&>3~N6NY0h0`(EuCm8sCi8P0pB}PJIM>~4(vA&wQlt!vNKB-Y^E9+H zB0A3&UjO>aGYLae0W;p@UTvOT%NrOhHOgoGp3T}j2~GhogB)hsA?5n&a-XeGcf|&q7`iJs2mk``DNCLL}bRe5{JM6Om zjozN`Q^sx){@!X!ciC~wqq)BK@Ah~L{xS3$>rq>^dhlEu?ozs1GTajPdFcHMwNr@3 zD0M_D#Dd%?x$l(f0B_q)fdb_RSp&SnqP zu*dE><%XQpH4?a^rTu+g@!Z;Y^3oe#&)WetyWtjQhjfg%>7UGc(W}11GEt-}+o=Qk z(k8H3N1{t3ICM8>@tHdPvcgKAeB35ZEElV1Ps-~|LJ0FJ+cU*&v+1#k?oQ9JA`3O8 zbbiAb%UG5)WlJX<+uOmm^G>PsX)o|7Dbr|&LP;-rq3GAlSfjFr_gf(m!r{H<;{R#} zUR}OeoGuyC`Tlduoi6&ufSJkL;JDANjxGi4Xd%O1!6c_;gy@L0GUmx5k+`&g^-8Z?Y z=0Rg`Ck9wbHNjf-h{&a6JT!FyJ)_@m&|U-T=i&KV1@asRS(%z$zKxQ=UcU|+^4{N9 zL~>?L+*b4VdN!Fhi<-~^Vt)^`hK_a};V~{;t=5!)TmQ!0o6b_?O7n4mhuRv>or2|S3h=`(El-StJ__&bK}~o z=u!x>Kw|lcj^2X|5$aK;4SB;KAr!)M9jWCAW} zA~{z%H$X*s?9q|XmnhV3j^niWls;`e?HHe}l*yW(jF8H+D53#V%?Ak0pbTqr>;jnk zoTkEtJa;m*AAHS}vlg5BK%p1g?r53sj+d%_*a7}T3CKs$jtX02eq5q4QmXnO*HgGD ziHTlhDd(;iNowaDl`j6_CKCD*#KE{FBLbf-b9Y@`-l#1rG4MS8y25k5Ttv4#bL=Jf ze2)6Qb+qhAFpnE#93t%E3}vMx--8M+U#{n{jH&&34FKBJ_Oz2@w^&=sSmw_|UHlv! zmwz||r%e12`+%$!Dg_k2TewW#bGQyO_IPmH$@&hW9iSWZl+2Dz<^CqI0j1A+RQV1a zm0wJsB|SmW4oql!$eZ z>SxPaq_xQjapZ4W7(%9iYqqOz1YbBYVWGU?A494;YxA%j8DX84oI3a0UV<5GO5keN zQNMhOu09uxG?rc5iE})xX(0%^_{Ko-hy1fBW^SRA6*hl`k$Z0G@4u zcuLtF9tAYm;$3IkqOyHgRe1=BP=vzBYhS|l{t8A~)d4pVfGU#p^P!0r=ec1C%Y0iR zR0zLPJ|P04!b!93Ici*)+a0RxeAC{}&mSvB=)2t2%Wy=N0R?n#rThpwcPgB>ffT^f z(RwR-6`FVex9vxev+}+g5*yA)>V?SIbSoO}DszW6<{9W4d0!ZV_nJ3;vhOb(`?ez` zSB`O*(FNx~++gwI-)ru>up#nvI@cbrG7oL_NFS%|39up zb(BgbARsdL69-D*z_mIVR&r-||MmU8NGd@^s#?5t>?x0O&zoo9^Epol^%bhF%ID z!hcbh%u+q$9X@-ZBSV13ymnt?O=-Zgap6JWV~B`CMFs_3!3w^;C}(ZYOAIG^18_Ym z$tKHUR8VKu&Vv?H3MATMN62s_tVBf!V^!u0FW-zHB-dr3vy=I4pAqL@S5s4|dsl`% zWUBp!@o9~As*w|>gCDVM9{hh4F&%{OM8Y&yzAim(wx0Oijizu5wzDS7a8s9ylIkai zV0HhXCQ)?R3`AaIsJa){ruAKkz6_MekD2e}>iPEmi40qV6Tu517$D@UMk+{DXd3~5 z+D8C2kM78_${%FhWPx}yc4lFU<{;qF_uRt6eY!KCIm83T5h` zxwz7eJrw2XyMKRC@d43@X#Tr|g<97vccd@@3C501dW~!xS_AcIziuj=XfU=rPEyuF zl@3D%y#ixUF1nunhaUswAFm^UJ}QT94yjkUwyQ81O3r-`IkAVpRRY%RE2#0eWiJDd z`LaG8nLuEmK86Ce2A5T+fK&D)hA2xR6)OFhLwl%-fhy4_AG^R|3N4H@TP$R+pQkZJepBc*l%$udD8C%(2$vGZQz;-ffjXdles2X1Z!ABnNs8IAQ}E^ythN;$4P@Y@I`! z&`}U{G&X_(&?-;gwb=l#Cq}7bXrv#@1ev*T*UD)OE;yHg3i%X6USIZ>u3$0*)I69$ z;aw8ljhq>=ZeQ=6DIpDw3}29q;t1)0v*%zVzUM=P%RUBANtFccI-E8yRRs7kVCeZA zWtf)E*7ocIE1nc*&{kim@d~7!V|g@IwF!i%xUf*5CMxBKgcC*cXs5*ltYA5-vg|9n zQy!t2V!~zBO2xpf%EVK?*rhz17#7~T_|&I3kc%&MLnF1SU3^+4xb;sNQE)-Kh(qh( z!+>@G_9T?3_Mto6T;KuM`gAG6f*0So%`7p_r@7svQZTF7zyWmLEl6s5noH?2a6UZf z`)s;NVQJKF<|UbY?RgI7g+cv!49=D1QCsetl95Ud0OGGs@~-?Dn+UHj<0cq`M4?f~ z&9f|XAd9Aa6a0}&zx;zNDA8$Aet8`}El6F|nzI}q$d;P)Uu+C%r~DXzDn)=iS0z|9 z5LDfTL6sNasEqEwy%nKnGkaY{b{)O)pa9m7YS7>a$`v2`fj6_#g{V@f3)>2E=%{z2 zs*dgZdxytN1_|i332~vrC3-|5K1UXm; zw(dK-mVUh{y99dHkGmBkiSQtTfKhx5LioUW4)_J)o0*|1lyLJvep1VH*?M9k8;-v6@+D?o@-9Y6mF*ZXXoG5b> zz^{8ZDP?MQWALe+-VfVQVe<4yXURN+>H;<6la4=UFSS2`75e<~0zsqBmcN?LS#^w- z)Y1ebl4rp@I*+aIh8|^KM_ABb4J0|vYP+;#vS4E~Dnq~tzus0=RD<@Rm6 zooe?fN2i59?}77}Bbq9oj?M-~-66Jwjg0EvP3hFBdjHlP8+mE_=E-GPz}_>5vvY8E zz8B-L_?X%AoOVjwyjamqywidKm6F9Mmuj%fxrF4IIrz~f=r=j39X(au1v~Kb2?#5g zol|_h_@sDhLY@;XzqfuQoD~ycHH-&fz)~MGV*L*d0<6>2y zMDaD)5BMH9pzbyTltHX5WBV5N^hNW_XOb@(uN-c646qXYf5Mfs?uJ++!H6C}(#&b7Q13=7`1_!iadjGZFq2J}CS}7hhwqot(FTDEd3U6A_#p*e zOjbXn(u$56^PaHhfzp}=BK3?Z>*VaJM_udBBy7I{77Ep!J-&>5cOes<>^`$!H|Kzy z=(@2ZN(mPho8ms7#)wz$Yn?aA?+!Sv+7s@~$7rrGH;l7ChU79&EoUtl+4-#W3Jx{A zTn_H2h!>xv#R*B%<6AWH+9JZX#)e4zmQik}Htps=gC4yDp9PL$ngUzG^1F8OX51II zGmKBo{58S1_C_E>=szRJQBzC0il?%TzcUv3#cf`Y(pR%AEdgSYmM9w6y~ji`Mq?0@ zT4VM(HFIG+N{t@lSiV!3zUp0!FQ)-RO7nIIPItDeto|3L{5W{J%B%N*WT9u8;{}K_ zAl<31)EJgCfoA?CNipk=HWnw8S*<7mFv!n4;M9Q1jLW?0}l- z-b_ne@z9Rc!qRi>9*$_W8SyGDg>tRjZz4t-)Y=0rmwMKFMg*%-yCNW8=hDOxD%7v@ zO;bBH#eK1M0V$(%$@s4gMLE3*0&{=e`B%o;mlu%~Ps7yu8|8uvp!-mne9_-`zY^J7 zyt?>0vT3(lZ&VL=g3U0C4lNRR05#>Dd3YXGfRvKp(b40XH zXUu(qFG2Er=Y4dm!+~|;0LkL4_dV(s)syiHdy~GLeV$;yKdG^=&Ml}hxqMd&^T`JZ zri_g|{sdWJ4YleMqf&oPwI%DL9-+JLxW8VrV5A}3>sIrTnw`%Z&Jo1u5Zl<`ypa3G z&K0D%aUqx>7&7wh-gDpi>*Efh`+V}bzx0VKI{@bF-FvP0D>Z&36jZn#Oo<4aG?KLm zMydEe0M2#GAHDt`Q2!!#V7z`fj7xd?PqT;tt=>M_em^edYyN~R=6(IpU2!vIaXz!w zK8tMb`q>Z>DQbcPH^X55#mW|(opiUm!8!rR!cr#U*iVs|q$4seqkDM!xdbOV! zq`^iT+UHa+49?%i)VDvtB{_ItawtVt=Z7O&3-K9r#08NYnZdsS( z_qT83uql&$xB8(%_x6m{?}8u$vKh5GF5|iJH?_-lNL$E*>O#)_M-oaBushyUj`{I! zU+$y30&x&rnyX@?&#YODJZsp;Y9z42Ij_QCMrc{UF(fOixlRlLWD)v@_!Gk_4T>b5 zP_m3SpLh#h4I=lTVz_xhoe_7V-VGKo`1Mrq{~Lf2>X}U?Ec)dA`2fbzOT)fCAQ(Rv ztd)QSS1=jFDOKiCSJmmiPPQvkNvapeN<;!oyiBl}a-K^}QQiAnMmv;kUHS6o?E@*I zfg_5n-W5O8%a*S4UR_}NtMBuOe)oY2D?d39o9!d&$=jB50n3$CfW3+lZh$m%-f13G8&;zfNGt)d^b2 z>rJT2%n2}n=1v=Y8gv~)#Vvn3Bv`emiC@?p34WblndXnqS7m}g2V^@aAwBCxiSY|};E|L8oXt)kp1kZeJmcE7I z@Pc$p_j$_3H7L$g;zgquOxvos45)y7n|TRgGY|Ki{;oK2oK7vL7$Fc<5yor2J0i{v z9;n;Fg(u!y8d+wtoYRU=>9MCrhTsxyKHKlS3DSzD8x4XGR(oB6Krnh1mOSCw_G>FB zBu)lm#T+1q(|v%t^0^%6`6g|IwN;;JV{+*krLpHabhJ-0VMX~nHZH&T!cN^p!U7nE`8 zQRicuEA!$=W;FH#_U&hhlYnX5qY_jUx@IerR`!zCnKnhgtKL)$^7EF}&bCu>Lh zIhz;q)^$lwErWeKA$1@Uu$#4I^%t;hn^OHVP8pH|!}x|=R<6XK1au{;D*jjSb6*Y0 z{)q~J>ZP^Fi5)7pCZ_-l(@ptxFaWyEn&VqKHuG;ZogLOnw-zt_{_-z8ZDC*5Qd6nj zKpik=D(vahKg_cxBnEi#!tr=4A$u2bdlbh>{5cjdE3w2yMQbE6_<`^B8T<=V zzg77!Ox=lc`q(`k`FX70b1S6b#t|V@S1zNgxp%Aheh4!w8 z&H#(#@?05RZP%1q$QU?#fx0zR+|rdSoJd`*-MHGuv;ZlV$3*;}avYG>Jekz9HP|th}P%hIcw>JSa1(tVlV6WJ<*a{tUCco4|aZ~ zHK|o&@YveTy(1AqSk1d8^32ZAhx`Js`1itDPXdUY~xx z#z7@L>I$>m0FG!H5$l%kgA;G}8HsJ7UN#py&-jlZJo@_X{zm=qvGiI!({?S}pRLN0 z|C=cIeNKb9iGdZUj7{k4RbtN1ww8b3;{OGz^54MifBUh}cMfh*>r(vuwBu66!zKhP zIsuv+iBzPh_N8P1A)TJy0fa zM9E`Z5)oDTrzGnk=EotQwqWI(P64ohLXfZ)soTKTbIHGt11!Zv~egKSO zdQj^G()mKaMM!ieDeb|W6%6@3p@wGnely(p?I!D&m0s{4Sth;=IQ}GWG90Lbm(zawQtY0BRPAp*0XN#bGYB?w<^`7?=oZo%zo(Sq{;EY_t3{jrv zW+yRY{5@K%s8L&bx&PfiW~@Rg8Ms#(_px8SXlvM2rd>Pe`a%m6Oq#nNi`MJ z#bg-$lgZ&`QdzVGs{5DQ>ycjD&t3Spc8YDdsW~1$@>as<(|q4Kj1=1Sy5RA4=vBD( zG5(7*O7|%Pn~rTs@WhnrbMm<4?RReRYoH$_`)Gb_$&C`Kz#SN%jO zV2s@AqFk8y?3sqV;!r8|xSZZ}1qR8Su2b76WM3Y+e7htd_9gq!5Q$ zoT){YoF3$-9IJPv+rpvY$&coIE8Do4?l=c4)2sJd@-$m-O7YX22eR(t^3+>?l1C2- z-2xea@YJ^ggyWK5dW_Q;B9}Nr#`D46-vgsa?(?rpJ=BM-r=c^&?k)}}^f{A~ek9|B z7S9h5Vxgw+K}RS}d^PYQ5Xu8rHS=P@&Ey#3>ZRD-P7(h^8%o-rT4nX*TdNP_b>c0i zVm*gmco$I{GmKu8-mx0%t(Ar2j}$QZM+AMQEe&AUk}{DbS~vhIe+Buvh48HEN+c?r zh8W{#(C`|8B1>{_T?Zg8;>e{tGZ0vz4!-s8IY9p94G`Iyi`rH5%rmL|B7EPN$FH%_ zFgOODdE$rDaQ&dCPJ~Xy(C)Lw5#R^H&GsoZ% zZ4>@{O#J=88J@hFZFvsT%Jh{B$&qFJ*zPCw_KpTLL|HPMYRSW>nu#>hpALYX^?)Sd zRT6e@?S73yMnyn?UC&Rt>7A1c9)~-3scBe~K&(!>5&PW*$?B`TBvs_5hvm!grBj5W);p|Og@ zm*t&h@Q5QzTB2>!b*OoDiN+l-9xdmSIfJLqB}@jMI^o~6AZa&-Vl=)KRCc&piW?OH z3g&0Yp^F8GmGh49{`w=%&+Q*uoin`<7l^OPahOm>5+SO`_i z?zcB%B&+eZ?3GrG!F?A#^BN?EcHwNOl!iYO_!vXuoNJcGIV5bHXOJ(}wTl$T`hK;< zw*JBdaQC?(aO^ZCS>VC-RWgQ}i!F7M#W!#-So5fixWo4?&;mc z3v*3DTy!562)M5cipDPhC8PiQu0yZQxy4B^Jb}2*_Y}nozbaMawV;={QOq%GT}gFW zNxd0a38&|YVNuSXJ1wLP2coSz4qntu=_2+rp?IO~vHd^alPmkf;Ms?*pfy=4o;lEH zpMOf%KTw2X?_9={(GGO#~Y7^+z){9@>V11>Ifj*J%^1LFL@r$aC7&cy=Y^~ z%qx8gJ=Dyw=L9U%SI+;j2z#Tw*E3w1jS>TUd-e$4yYcKV!@TSr93hyAG_7QHSvaf~ znvfG?({J);95i(~{_F!o{%UicYS&&UhM$~aq z=PjvgP4~olW>(^}NxiCJv8kU;FC7TG95w!I$$ARrBO27v z;mJeJvfhOJ*%$f+RZaXDBc3*k^T~W>1(pRH3{+&_*Tu|Ut%g_%g#P-CRAqTAN1K$`K2=yLrXb`bs^HsWweMB~D60WjVvHWu z435nK-a)>{We;Dd_lbZko+9hVIIe+pn*CYWJ-M?bczWuOtr-U|PQq4ZUB-O0@7%hU z=sNiKUGDUVBeWA{@7ovuE)Ftc%(>k;XZbtP!k7mYtTZ-)|KK%(NO(mzhu#k6lfc}#4 zQlIR|sJ?xQnUtjmC+H{NTk^a2%lYX1kJTPdCh1b_G@oqT24x7PNimUHIXT2TL#SfX zLth566d)*>&oiyXH}xmWx*y644*7FukOVdHCvQ~nyS{1vNmHGW`Y%Ka`p-*jfO`A@ zi#crR29N@D1l&WSt{t_{5oPrxXYHh`&zr%qQ#${krO-K3`@F~0ke%}Mmo-knajYvt zizMoViGT`(XNZ9E0=`uStRo!dP`X$39VG8dasWm5x^^MsF~_cndDwwB$Id}n)9F`W z(|PB}b`yq&ezdQRZ0$}66t7gxCUNZ~6fc!(b%z-vI{y1KVEXxQ*1t!I`#=_LQN%2@ zyhni~EDjW5Ej499QxLB5Ub6+ZzHMERAePG`BED+;mymPJq>VEij)Z~MU7(fwmS35q z=*OrVI=T#vgsOl(ZOMX^_`{De>@!u^1IwZe>KcIf6cCAfE8BLtHb3i4jyQ1uLz@y*E?5-O#G;@Dj+z@2wmkpeGhu17UF1Pj< zgWLD9TY&ZMZAY5SByfX$Dshv(XO6fgcR0Q})Bw2kv{CK25gsM7i__+B&KW*OL2+D% zIcc!#A@cuvQ!_}}6x8W(>`-tcmr@}_DXP|c$f-n<36Q;M2#5_pNrMbLg#tCuQ=kDu zyPXB<6xiJw)N-);5-7`EW`O2=)tQ~ECYT!8ZXP=s)zafURzD4kcQdOHW}0ntd8oHw z+brsq>E68Sn9z>!%NF-MuX(rxZLD76WbYSfu+87Q?hbyNMd0mxd- zea`uz1R5+HdGZ{TJql_1!K#!-7r-Le|#3@_>ACvCxYJ}woK^@7;BT=(MAJ^o7e z`EqIqD|2r#yTE^pbNIgWkEAu!r*pRy9u zB4c=bgl}n5hmXRj`!0v({2-@Rnk)cXV}iGy>t=ZwoJ5gX%NCv={!@7i^iN0hnus&~ z7%?$D^3$@4(zp-^H?$q}96ZD#Ciimem@w&mk~{F=Xw6;IJ3ZZb#fJxH&r`jLW10gg zmdzM>2MP`1YIYTxJH4pws)@+A3sT^cHYddSPpP$fEzddJ@+|uqlorRQ$t)1e=$8$@ zKr3k-x4D&2Y`|zzqZR0j7v2y+yq2eC$dh&Hvz(29{@vP@m^Q8;HZRZi9_t1jVs8aq zVD*oJ39hC16XTSIm}XmksHkCB{^cgHEtq9B1lZX1rF=5KQa`IdRu@nUD}%jX6;dPt zz21Vq205&fMWymA6>Esxo22YY(bmYq<|mG-`XP_~y4tQ>YY3;6$;X$eScXsPnB3Ya zTbs{nd4765pV3T~-m~cHVy$f%BGL85SRvv=^%B?Cd7fKYMlbg65XYT;Y=Ny1@rv-P zDFh#7=<)5!?CCheDU;rSngjl!_RngBHF)zjDNUX(t;-BaYH^hxp10dRs4(&N*Sx=9 zw~6DwWz5bUurFR-K{#T3Xo^tLcQP&&lsz102~&j~pBvI`w0}Td;Ky~bm6A`@QpXFc zG$cZlCZDnFddvh3J3I6eyt=?xDK_dUaAJ}Jlr+y$|I}n9&fZSzTAu=>8gGw^4jZwm z5HCj=Fvg0tA5$09@4Tf}f<>0h<1lWpo!irh_V8eWPq)31kfKZ2PkxjqFH2bX|M|27%AY`lf-{DbJ5O zfmlI?7ac516uVgF35=+8Stkgf{|+js+7sLSo1tQMazWpX*e-4z`W;UPG)%v8>$8@yGYEAgh?yd6-YuEg4d(fMbeekg}^u7X| zQjdsH(9i2|$i4%Bwb@IzaT(=cI3ni1q~*W~ONRNPK}%zvCqr1ssU_K( z5*ryOFmRd?6c}|ig_Uk`k-$#>F&=)568zyxM+LbN^^TlAKEa;2Ta#c-ryhfB4wnV$ zyjd3AM_W*ms%|=_z70Zmzu~!THE6 zuWr$vdxv5-#L{4DJ9$@RRt%Xm)_Nyi`87kNFsy{e9ZitZ@uxlx=w$9Cgk_Jl=+^7Q+)?FsK`s z9cgwljC$ase7+;ICj#iOq|Vn z?YUXFcY4(wxascN{G>}Uc;qmQMh@;!5}%a^Do9s z0`ee%F~j=p41$qSHMb?CQ#tR$uI8Ez74Hg;(jojdRpy$=nd14Ywo$ zzBrW@dkG7~GyBA)59%dGc2$H#fla)5Hoi=lA@i+Rz<)gMHLf}zY(crTHDm9C zm5C-^a!bZ`Nnh+AKSwg|b^jZT7lPiL{(t1WPNOp?vP-~uk#Cb;d^#TCX9b;i_|(y} z;|QCF3>Z((PhM$pJ_x}H3s-$| zFakhE_7WQ)!It15bb#)HaUu%2CfE$RD8a~u-}N_}hm%6^$^~V+8xG21tvKZ?a7dHM zh=LRvIUsAcEQjSlpuionjh*{4-KCVarS_k6*J@O4^}j}Uo!CR9%I#3{aL!&jal_fN z`G3+~T4QZ5tpX#CJN~{ULu3a-QZ|UX_v09ZD%56H!9m8(sJ~poIQIie16QtrbS}5) z7GW@cX+*53NRNj?A2{|Faf|**YozqKLENIbQU4?H;rM;g%xv;O9ud;pWbv3rTb=}v z;_zsT)a$E#M7#g?XVkw;Afzuk14iK5fyBTq3R+4vIhl@P2EcR(Xhlf9T^Gs`Lx}|l zDch9&nmH%vV29EHUH&`*G3z~v2FbWw<2#8^bt$}|s4pSV*Mb6wjBp7lH4A6gfvh2? zO$n{Y8sfoplz~@p+}6y;a5*@i?awsvEZ8V6kp#5}&q^k*3cf{m&tZy-0Q$dUf-_GcN?B<__avYIMGd~j?bvOyxnAV?)9yIr$KA*~b2-N|x znS8j(&3h5RqI!Ra70a7a6Pe|EjXe$*=8LV?8=LHfoKSVX-v(Yx7BYEVnC|qWO#`KPNU+m!=?n1qhEn-uhrZ$dGD~?)#0Fl~@Pz!1h zKAg^;B3>p4@u~c=)}~e4z^O!PAfS?5IA#fVfwZYP1!PC-#jdiziqfy&CV7p(Jl^*L z_ughPV2X^(03oZAX7le@Q?AsFY?S^9;)?iR6Av#11|}=$F^fgE7Nj>?6^pww+ZA&o zo20FqHCUG%$oYdiRiuwjvl&ghRY&lKm?`mBjR$^sWZ>(Pr>NYhVjW+tl1)-uL=i_z zoL#p5Sa8DNBoS-4#-@bCO2&W6oiW|mcbs|F&?9=k5q2@Re{(0CchCRyAEj~t;fgTd z+_3L3IV~GeqUo!7=F=w9#4(1`sZ~Qf+_~32l@`l@m#DygKFLC>Galz=W7fazM3&)+ zG)e9MNSHAWjO`-wsR*wH-Ih-IU-XlV^$dtFU(WTHZj?}GUc$;&>E<(OGKX7#$Bysv z|I{Ba0ggkiJ9FOUB4-*rguEEYLeqeKKFrQ*@=$8UAfSx}s*$JdjB0qiXa?j?L~?$+ z&wH(`9HzC;VIhbtQ*kAqS|-atJ9z}${n@fvy64lhb-N%KT>uP~tRxcN7W_70Nw{_Z zm~?x@ICkJG2>uUnS7|&pt<*ccObl!w{Vz(@@h9W$^y7%Lh9#ujli~BC-zUuZwr@5t z{gP2N!DBNgX1~Oqon!bkgKmHcNU~3p7%54Yk2zMw(BHV z0EK@VT2kHCrn8?CJH=?bHS5Iap0SB31lDAm>Gowljcw`cXIO>(FTL6>UkGQ?aVWnH zehI1n7g)m$DW*Ygyf*AW^kgA}x@w3G#IpQG1KMFyX?;JHBTUYi&68Brl;b?G_W- zM$ru3c#&tDEni~TzFk=}*3H)&e?4)wds{|Ll&pl68=zhv%ok@3U%?{$w6j28rzG~& z2Z)YQxM`vSEpmPxbtQ$p9~FF#6FNjRk%hs&UT(J@^m^j$x_A$7)JEq+zJk0~Ws zXJEM1=#Br&{+bgf$!5Llb2u(xboSfGv0X?8fjw&5`v8~Ow-?lfM+l(b{D9oAptV0V z*BVz0EVN9v7jmrt`zPT9-j7I7+OO*pbo+99_eU>C%K3iNw4i&A4xKrS`L=<-c(DnC zbYp@*F`OH1fMo+@Aohrs;^>)X%g5HVB+nQLc)Ete5$)xkiPC}q-p#9Gp|lss%)crz z)hM4zc@f4SYQ?>CPik3Q`b@tCohoxzng8>M`pLvo`V?+E)BQHe{ugdLEbfgs)u3+j z>^oiAQS9nl{}0Ui!`mpqCwTORmXribsUZQPsr2k6M~xdw90trsw$aoz2HBaat-?*W zzaE10_Y}@qgss78>Z$_dF&yE{o1-s zJ1oE(v}eh-GqwSFVY5CXz4*E?=A8qdC3Lbjih?#o(iN<_xe~2{^Iz64mC!Fa72sAz z082H1a5k}CKi>cC-A3b5`*m5VTXe_Nhw5oQ+BmNR=Yk7`|!~-==1*eWiqPPl|))Vv| zu&Mp!qObMS*vWi7dUtnXQHGA6wf@p%Igs$L7w-XqtLwXXl1NDFx=Am84oI~KRKeM+ zI*D2OY~+%w+RC0M_$v9Q^;aG1mnKS4O0j{uu72V=i!V9Mk5YQ75Age?POQ;90{1vI z$`B6)&p99}vWkQcyv2Hn>@l(I2@v$zvDOvB`K6(LJ(tsnM`p92vZB>2G->az!b6ie zlO~W3yMEjc`Ez@&)K{n1-=}LN)=f@lZRAp;n(KGE`-ehdIpT@TWOwRK05`s)XY~~_ zG4|IbsEw^MRNRm&z&+>b1L8;Q-1`m(4l`*JQ{m~hRd+i~PdrWaxz6L99@3K9y@vP< z)`_m!CVdEQuMmvVf;=zbG9siXo2SRua@s<94`M1&Q|tA2{p;PqMyeWSj4A~~gh=WT zq{~WJp%V3l`}Z-p#t!myW=_3N9ay`VVvw-Ccsz>ZGPx9Dkg6Yn%>%gM@Yfi?QYK%N z79yZ@dzSrcaTP;~eOt3K*Lu(XkYnOTq3TuScNSPFa@?6B@r=E`j8xW=6eoCL-^TjOcx={3kA~(NJ4Z&edOm)t%a?WaOjQ_)TgMk$^ zn4s0*MalD79hCJ|IgOO;UIWG*QYen!9fh}r_>AwPgObg{>v$6?Iao5?p}-u_ukpwQ zy%EcU*`Hds@bMT47MRP;5=^sRwLHzmDZ=8_iod^>NZiF)S&K;AejEAAhgye8rC40% z>U(hTSU$tO`^EIfa4Dwk*ga*e(>by}i%*AHuCGI1b^hcMh{49jVVrNy$W=*5In9)o zNKlw9^i~gNJ8^bp(~G|$efX<6Njc$sy|a)4trkngu}S?Tkp0!dlMAy$)au97SWTo5 zY#z;;!tv&>uci^U^8QF;kZ@UNH3C{k=Uyf=M79L3OitXfHwNCfqkq<3`1Rx*4$ge= zsz8^y^supCyS9~gNK8oJ&X3MvPYQQK5IG@b4Jn`F7lR6rSpI9^bcNaCDmWv#s8xBldUvXu8qn5;n4wb`{(cNMX>Q$ z>9_aVrgVo+T^&!$Oqe7Z+fx@kH7Qd%+q!4mjTqRsW1<&SVw`|Fc`-Z(tLC}j+R)Tt zPaYQkmQ>wRGPZ^HUgQvW9i(z1z9$l#Ht%20^hEUl;BgGLxu9qRD37)R$=g-5|7*r7 zLeH9#4RA#Ka&~DSM88fhe%&j75UvCES@A|5g5dqw_zW4yBUr~J@S9>I?;h5dL6C{E zj(pP+T?sRY_clrG)cKiYklR;4tLb!{F*rZ>Y72xE{1&1)aS}^_f$diX2Tk!2(>Th z-j0H(-Z397?BH$gb-q~h_T_7tHaWv)_k-Rs?Q`-0V>>f!cETs6Q+6T!@Em`tl=Do% z#tG7&oay5Q&@w;&Msf7buU8=AAO&nYJqjH&!7~+@1xt|qY@b=`T87?|YV~K5C6K^W z)e2-$5AdJ`b6)!4Y-)k|U6N^V`<>uP89w#4BOu|BP&!N>+YdULpJ7St3_YModM9z# zKL4C|4qa;?fQwU~~os_iBH zg#D1 zPvcV2(l+qP_5k~7i^R#`1&*#1I`2LLGB*1OR#3k!36Ne!A=zq{^@_iVrJJ{+n_brx zjl?7%8i|5r*%paY9#ey{!xyW;Q58{(=2JY`58U1?Op*?BL%X%UGj|$$>we` zZO5m0lby#JZBZ_C9vtxP4&+vc+Y9i#z#M4v`DHObD9Sue+4}=%mcJi?4UiNQP8;q9 zZ?q(gxm>a4P#bdvxustCe7qKyN(pK>iPCQ=en6G8<(3TWg%{Lwme5rhGJC(q5XHO&c9>?@*)SKQM|LJg&u2 znP*z!?Nsvw6LQ-K-bVGF+GSl~gS7+*1Qf0<>-9&ORsS*rz*N-BL7crwcI1%vepSq&#F|IWbINU_j1lKJRmZNRjJSZ}8`=FI zpv-58czpr$#JS>_jdFnpm)z&q;zPf=c0Cce1a=(5+_)E?Gpc$AYz1qp0H73gv0Waqf+1jS9pve!&#&*m_B@&FpbDHOvt>Yl}si?=JU9n(^#XgGi#HcEf%#yfERs0wiSNx7& z*{f;OPN_F{&fs{xL$Cq?o6FRSOEWw~J-=RNux#3-{Kr!?9|3lvJ6 z847?kYau^>rot}D*!6u*aCZ^96-NoJ<<(l?qdZ}*jaNS=Q6xTpz&QNiEXz>%8e^2M z+#p3UMR8>Sf9CCp4@(o=6dAtIB?mq?z2I{xcItVi_A{DpaRK2wT|bPU*6vO8@nY`i z!<UtL_d%CiB{HtV%FtP>9x)u(+rR5U!Q75+%Cvr zfszOc4-;Cx_Bh!L8yEnP6oqW&IHoS=8HjrRoM{^YAt$0?J6G*+KP<07ph&aidv{Fs`Dcty;< zh2pyk#g1{R$t)8_?x7jQaqA-KAcfr7&J-v8lK9+xQH!--gRScq-+IJ^>4Z%^q=~^z zN0*Bo-!XU7(Z_0TXOy#2*QBdkL}z19f3(_c`(01dR+l~sE;nV#%du!)f2l~Exlnt| zwBGgm2;6bkOzMV}+4fGivFUeK)iSdCfbOC!=J{7Jom7%*tq5Qh$Jk>6;TB7YZy6rW zbzEBh&i}RiS;4~lwox!kf{e-gt{!PsWbvzw1rWQ(GlwNT`N&38Sr=A+w%M>YI14C_`` zaD>kW8#()F#9}sTVdC2)DSv))9x8Y;a4EuCe$dd4=#!B@CN{+4mZhO=hD*#4dWg1b z@mxz-pcC;WZ5SV%HW7+ZZy^sh&Yc?j=)s)-bcr>f6;oMHsOxFgS>#`FNvR zO^jZD!GNInv4Ci&ttO|@DA=iuN*zSJGdzi7hjqS{*MN2f%*o6v8n{|Zh&t4y0 zwgQe-2!{R2k)J+&WK}|6q4wz1^S)myMH)*;3%Z#S@A@~Yo2QnxhO9Z%zdlf0tiIcl z`dT|YbEa$jdG{S=RkV1mj@o8#Im7e~oLalG-&AAlTjnhz8eY7fA||y+EQGY=&!kDy zp->RL@zz~s&(D| z&|f{}y}aR2lQ;TE{rqUl#f(GB#sTQ>bTlm|F8%Yod4IkIgTEykww6GJl+Ky+ z;_au03NDXP)qCCQE`6_hI}1r(TOR$-jh?LJtUwUy8LQmIvCt*tM`g+Me#1B`Qth zdEq;pYJE%OUk~@JZn}iZkUMl+$1NV%H*_v?fg@w4Pht|7-BiKDvh8k(cGk}YZD#`u zFq*X!;dsh}daKL3Qmp!dy{K>0F<&3AJM1_X(jr4JYE>N1e?4`zb$K^%0EqU$>>uh= zZ%x9b`_#tpjiy&6L>ZD`U>pVJ8hkWZu@9Bz0$IT54T5^r_2 znQI}JnCPD5$@TY7d9`lLtA%_paN|t-oXp7|a|H3iQ!v8}7S|oAJGOB1)h`BZb3)95 zXy$LDQ!1^aL38RNgS|E~i{bJxemk~syQ-Isefn{8bot4B8`Jf9<;hjP^y(t0CE(!j z@1JkQ?CA&8;F|-{&Wl$g#rqXp+~C6IEU41v*f!`q>|d?e_DI<#Qt#P<(KtknMmT`6 zbJA0@{#ZhXEop>@4T4@whUNgs&Z*?*oxRAudRAP2-dhMx3U%Sl5SHaFj1}GB{mUob z$Ih6#@l}a5i*&7htUv3zwP!`C$|m#733hXHMat$`UD86#F)r^t^zPqhOH*hg*P@{; zd*j2N4EPdfl-9k+?g`)k&nWepldR4u}j9@r}<#@ zX-q7m_o>exeRv)74-8^hu9mlrwfn9VJA*I8?!JwbT&=7|D~nEe;79Ko6Y~dej@>K; zXZ(l!O9o*U(v1~T_VTO~A43jNG(S1ng@o;#^0^-sS1!EcQ=9OFys12KyX=tH)Zd@? zl$kUYl8?HLr*zERk(BLkaCff7uo^G?zuyi6$@qHZ#!JxQ?v*1JG3iGe?3Y(z@y^mO zw0cU~f9{+Kh?|=`YOh4W12Mg~8KpLg$Cq%LW-|=4ymM zP8DZ}hu{IF@T33S^M4#$bdC$4-qy^=$PBL6=nA$o`u8Qiz)7V4x7wZ^g)Rujm&M_;nWpfc`+-M*b-ypb;`-_dh(vpxfKk~P2-$P&` zmYsCi^vclc*CGuxlFuRt9Q_O)*Dl*)&oFvFqR4JS#SFdskJ*d(3Kg;Yi7Bf{yS;fu z7L>V_PF`fHk$n#5_v)DIddtQ`EJVKP=#IV{J7t{HmpIoUmD|FJ+IRzUVVNH;n_ms$I({M+p_kO2kTt^ zAV~fZa;{ZAxg|4uL^)*k(c__Kp_A*AzI7R;L}_9k;td_9;tGnV2YNO|w8MD92+^Qu ze>y(6hPA^r3$_Qk*W;DdLw)W%rhI&#`aqW8%Y|dqZ^v4%#ylBx53~19tQpL|)K#@K zjMVfvNilzvR){cRP>}DjF%N8aZ6?b1P`{a;{3G`O-DiVCp}-tn-f_6ZxvJqfVWG2k zVc|ngtbCmF%*)00dQV1NyUv&RsDb?6=0%@CSwcbQqGz=FaAH#L%~rW>?Xt{Zht{jQ z7nKd^-U2ppeJSQRL0Q4~GDe~KPBLvrf+Dpt+fQreW(6u#ypk)|T;Ba*4N2;Fl3->W z=~NRJ_ebweSAm(w_5nas%2Td49>J46o)pu%mJR^YhwTMm4N3B>U5z#18LZNa;|J+W zh&#-+gS|=AH8)VIIT58+6j_6oenC*#@#`NEitZ4BOLJ~6hB&ls&s5Kx)Q9@h>rMU2 zf=)x_d*#J#Ut6BwA+8Miso%%hF z3JfkL@D25qtIj_EqUA)oKc`Om5NC*;dA6GE$NBKZLJJDVM3x6Ya?NUUiT%)$nnPCv z3-M&g@geEi#IyxAzFfE8vinT?7yVBQSka(6urufo(xn5>Xsp-Y^AoE3ibY=x{jAb@ zBte1g)(X(3pG{RUu{gI#@~;}+Y;kr}GM?jS2pLbh_g3B}4KaZ`rHNIG49;5$2K@rN zZRF$c|HR>VY_+%YHgKZvNa8arxWu5j?a)^FH@~xw_y3LdL%Taj=xeFGy$QByzTs`Z z)6zQ=YO{991u!FxBdJpdv_%vjj7%)_N)<8ePr;_XBD;?y|ofJe51 z)GG@ahxY40uxytz1&!;HDSDyfFH`gqX%*i(L*8Auo$GWbPUj831fFY)G^aK@(qsL3 z0}zl$T`zS$mDngFVjqdGH$n6ubRo4wgSDz>vc*9brW2QY))Y-pfXF~9j5M;OA*D5x z*16wXjv^FteR4lPUQ=vuV#>)*ZA|`<8%11To&L%H!U(PLKa9{E|EtQ7e>XxSYhIfn z#G&PdKs(2kypwd%>n`;B4VD0#3ztC_jPc%j#!D_iR@c`a++1r&@em%wG0yEPB1AUKiUl!%l+EpaC;dH49zzpLV;vEFeMqQ~&uSDo zGhv(|60e_{_EDRR!kPZ>&CoahgBe2jM^ zzXx=Y32jR}iiR6?{htzJTyUBoPb4u8{NT`oi(!ol2OUk}s75ifmv;;wf-BY9x-^}+ z47KiDn;s!_-M~B@?q{(hnqwbd&s!e7T9b3~1!gJ4^A<6To|hyiNN_uuW|fL*{{<8*2PT?P7)jM~GtU@ znXc}e;1EIqRDvOVvNgeh90vGbXl4WE4HEsjCk99h7Sfus_jNar6o#+j8d0W#svp+w zNm!P`ysfz@%9ioY=s$~Hs3x8{*^f0ewL+r)#!rHW7HsF0f9Kg{ThLi-v~)M6Zg~}$ zZ$WV%mE_KS3oEUyk>aM*-$9*n0gM&Z@anIhmj{@$h2xdmZJF!!ri1vh18sLNgr^i5 zgadV*YJ2-J^NI-1FPTehuz?G^ZZjw;7tgO-$=IAy#K{R-% zLysTXlCgSix<8VFNU@M5p=#2ayc7?2yqiuT!rw`JPXAg@?a9%|nf7ll97;)X>U zHl`Kb#R>Kw!{W6;=^|Xd*uQqNE$nIH(Ou=((2XS`Csybyk@GEkm;bQp!QP>!rM36S z&mHmiY1zzOI*OY@%f7?cq|v(kudkWl-uOG21_nI8X{7yzUtzXfh398oyvQBF8fl58 zHy`AA32m8wH)=oRr5HABUQHdl6T>UV$)QzP)xusuW->JP5m#wqeOxXCuI$!F!nO-< z?&~AI+BRyu3xe!PAiZ4rEVPeoFc1}7ymLwPe!wa$_li9@72=^o)vEV$=(QagFb6^} z{{9AE>}eftm7o7%gBcSRjk}XPXQ%0JPp6$ClQExn{g%}p;K|FCEOg%@G(qV8%73Xh z$)BgHH~UfxV_&Dc31RO}l-}c2Z_~j0bxjmqEjCoVlOW`a{rTPS*D5L8Db#q)J)+or z>7gOVk{6NVv?uoibh(rF8o|&0`IAW|YUJIfMvXoWb6=n9KW7-m&Dz|EuD6+JGOoB^ zq5bdQ-Kut*v~iI8i;h3`P`i>PZrFzZw?w6oAz^{jI!{Ia`2vcHS>t(rA2nCC7Ye>M zR=fjC#0X)dZ&w*-x{wHUgMsj0FXBGw;jYo-ttZ`FyF%;_3tYfDE6wJe^XuBHCE)qe zZIgQvH@vy78TS>Fp(<`xgxV@ltutv`xUQkbkIaNZ?!^Teo(nI2-p%UG7kDCjRYOT`=i) zrPHpPb5}Bdu(FgV7*gw>>vZPHX#Tv<@kF7^ z5U|8yp~m;}P8nm;vnA?Kh|)#Huu3bYQ30#f&G=GFhnR}a`+wejZ;}ntIOJJhj@I}t z8f%lb6FCf7RrCp?s+60CJ~UE-WOPF6HMKd~JT}dLuvLs}Ck%U2_B!UqY zTY(mhU{FNR8W188(y}l1(I0GH|A2STIro0&`_A0C=R6uNdnne>;C3ddN7h_NMpkZsRd+jC$hV(jD&N+9}Kl1V$I>Luld zViJrKZ4-rxidsCslUEK&!eGDZe?&iab2zC*4rvG zn-Aa%TW%ojrK)^MJuC6f8F5sW#*W(KgNveR zcS8o2&+Od4ff?dv&IWrvA**y_8xv@3wC7MVICD{=ti?4EKIS`-Vu>?61mE9lq!olF zo6`NDF^JK8=m~lp(40=nQr_puGkuAc|M?cJ5Z<4Ux<@@X2%9Jl$5%#uu^QDFt!OSZ|@E^J|1vbxk#%ajK6WYK6Dxf&1 zmp9$rOru~0tq9-}Hp-kx)wFxB%B0Z~xOtT?nE7eNQvu<_rFr@(hE?K%R(7fc8&zIr((D)LriVDml(Q|E&Xi~k5#Ft{CB7b6rze)T++y$ZOjh+y8 zRxhkBjf{`>20E$!4QnMelt8^HTai%SLVjNUJmMIsBfv#T1*Tw9b=by>vh-LKWb@MI z`6Xt-W5uwu8wLk}zfNdrt){&KxV@P-pUuaAku-gWy1LGlRep`tq<(q>Q}gFEbj*0O zakyO=CXlpf5g4e2V-7q??OWNoY70CX-{2R*OeOR4<}>!1o%CLuMb#r~>_6^8)sBOn zm^9p3xzwqvJaou3e>}F6y>t__1>qt1n0i6g`rx`g)yRk-%sxrQVy3yWLkWxPh0s5&bIlw7Wt^>e-C~eD1?yX(C@xDjJaMx`yqSUp-4ID`2QZ)EG6?Uka(j>F z3^uMS^sF@3KLP?7gko2P%$pAx@Rz$oL*%e`XA$0QBlP?o%k_k1sV{@5X<2|^uzZ!BLHWNo(IKMV<^c%qq|34{#|QDO52Ae Xic=g;>uN&jLbVn}j1AZ9-dFGsTUfs{ literal 0 HcmV?d00001 diff --git a/Firmware_1.26b/INSTRUCTIONS.md b/Firmware_1.26b/INSTRUCTIONS.md new file mode 100644 index 00000000..9921ba72 --- /dev/null +++ b/Firmware_1.26b/INSTRUCTIONS.md @@ -0,0 +1,41 @@ + + +# Maslow Firmware Setup + +Installing new firmware on your machine is important. We come out with a new firmware version every other week so be prepared to do this regularly. This process will also install the proper drivers to connect to your Arduino on some older computers so if you have trouble connecting it can be helpful to do this process on the same computer you will control the machine with. + +### Step 1: Connect Your Arduino +Connect your Arduino to your computer using the provided USB cable. + +### Step 2: Download The Arduino IDE +Download and install the last Arduino IDE from [https://www.arduino.cc/en/Main/Software](https://www.arduino.cc/en/Main/Software). Older versions of Arduino IDE have problems with libraries when compiling the firmware, so make sure you have the latest version. + +Note - For Windows there are three options: "Windows Installer", "Windows Zip", and "Windows App". + Some users have reported problems with the "Windows App" version. +![Download IDE](https://raw.githubusercontent.com/MaslowCNC/Firmware/master/Documentation/Download%20IDE.jpg) + +### Step 3: Download The Latest Maslow Firmware +You can do this at http://github.com/MaslowCNC/Firmware/releases/ Click the zip file for the most recent release to download it. Extract the files from the zip folder. +![Download Firmware](https://raw.githubusercontent.com/MaslowCNC/Firmware/master/Documentation/Download%20Firmware.jpg) + +### Step 4: Open Firmware +Click **File -> Open** and then open the firmware by selecting cnc_ctrl_v1.ino +![Open Firmware](https://raw.githubusercontent.com/MaslowCNC/Firmware/master/Documentation/Open%20Firmware.jpg) + +### Step 5: Select The Board Type +Select the board type by clicking **Tools -> Board -> Arduino/Genuino Mega or Mega 2560** +![Select Board Type](https://raw.githubusercontent.com/MaslowCNC/Firmware/master/Documentation/Select%20Board.jpg) + +### Step 6: Select The Serial Port +Select the correct port to connect to by clicking **Tools -> Port -> Your Port**. On Windows this will be something like COM3, on Mac and Linux computers it will be something like dev/tty/. You can find the right one by plugging and unplugging your Arduino compatible board and checking which option disappears. +![Select Serial Port](https://raw.githubusercontent.com/MaslowCNC/Firmware/master/Documentation/Select%20COM%20Port.jpg) + +### Step 7: Upload The Firmware +Upload the newest firmware to your machine by clicking the upload button in the top left corner. The arrow looks disabled until you hover over it! _Linux users_: if you are getting timeout or permissions errors, you may need to add your username to the `dialout` group and then logout and back in. [Instructions here.](https://askubuntu.com/questions/112568/how-do-i-allow-a-non-default-user-to-use-serial-device-ttyusb0) +![Upload Firmware](https://raw.githubusercontent.com/MaslowCNC/Firmware/master/Documentation/Upload.jpg) + +### Step 8: Finish +You are now running the latest firmware. *Great Job!* Make sure you close the Arduino IDE before proceeding. + +### Step 9: Proceed +You have finished setting up the Maslow firmware. Proceed to the [next step](http://maslowcommunitygarden.org/GroundControl.html?instructions=true) to install Ground Control on your OS. diff --git a/Firmware_1.26b/LICENSE b/Firmware_1.26b/LICENSE new file mode 100644 index 00000000..2f4b8c0b --- /dev/null +++ b/Firmware_1.26b/LICENSE @@ -0,0 +1,189 @@ +GNU GENERAL PUBLIC LICENSE + +Version 3, 29 June 2007 + +Copyright © 2007 Free Software Foundation, Inc. + +Everyone is permitted to copy and distribute verbatim copies of this license document, but changing it is not allowed. +Preamble + +The GNU General Public License is a free, copyleft license for software and other kinds of works. + +The licenses for most software and other practical works are designed to take away your freedom to share and change the works. By contrast, the GNU General Public License is intended to guarantee your freedom to share and change all versions of a program--to make sure it remains free software for all its users. We, the Free Software Foundation, use the GNU General Public License for most of our software; it applies also to any other work released this way by its authors. You can apply it to your programs, too. + +When we speak of free software, we are referring to freedom, not price. Our General Public Licenses are designed to make sure that you have the freedom to distribute copies of free software (and charge for them if you wish), that you receive source code or can get it if you want it, that you can change the software or use pieces of it in new free programs, and that you know you can do these things. + +To protect your rights, we need to prevent others from denying you these rights or asking you to surrender the rights. Therefore, you have certain responsibilities if you distribute copies of the software, or if you modify it: responsibilities to respect the freedom of others. + +For example, if you distribute copies of such a program, whether gratis or for a fee, you must pass on to the recipients the same freedoms that you received. You must make sure that they, too, receive or can get the source code. And you must show them these terms so they know their rights. + +Developers that use the GNU GPL protect your rights with two steps: (1) assert copyright on the software, and (2) offer you this License giving you legal permission to copy, distribute and/or modify it. + +For the developers' and authors' protection, the GPL clearly explains that there is no warranty for this free software. For both users' and authors' sake, the GPL requires that modified versions be marked as changed, so that their problems will not be attributed erroneously to authors of previous versions. + +Some devices are designed to deny users access to install or run modified versions of the software inside them, although the manufacturer can do so. This is fundamentally incompatible with the aim of protecting users' freedom to change the software. The systematic pattern of such abuse occurs in the area of products for individuals to use, which is precisely where it is most unacceptable. Therefore, we have designed this version of the GPL to prohibit the practice for those products. If such problems arise substantially in other domains, we stand ready to extend this provision to those domains in future versions of the GPL, as needed to protect the freedom of users. + +Finally, every program is threatened constantly by software patents. States should not allow patents to restrict development and use of software on general-purpose computers, but in those that do, we wish to avoid the special danger that patents applied to a free program could make it effectively proprietary. To prevent this, the GPL assures that patents cannot be used to render the program non-free. + +The precise terms and conditions for copying, distribution and modification follow. +TERMS AND CONDITIONS +0. Definitions. + +“This License” refers to version 3 of the GNU General Public License. + +“Copyright” also means copyright-like laws that apply to other kinds of works, such as semiconductor masks. + +“The Program” refers to any copyrightable work licensed under this License. Each licensee is addressed as “you”. “Licensees” and “recipients” may be individuals or organizations. + +To “modify” a work means to copy from or adapt all or part of the work in a fashion requiring copyright permission, other than the making of an exact copy. The resulting work is called a “modified version” of the earlier work or a work “based on” the earlier work. + +A “covered work” means either the unmodified Program or a work based on the Program. + +To “propagate” a work means to do anything with it that, without permission, would make you directly or secondarily liable for infringement under applicable copyright law, except executing it on a computer or modifying a private copy. Propagation includes copying, distribution (with or without modification), making available to the public, and in some countries other activities as well. + +To “convey” a work means any kind of propagation that enables other parties to make or receive copies. Mere interaction with a user through a computer network, with no transfer of a copy, is not conveying. + +An interactive user interface displays “Appropriate Legal Notices” to the extent that it includes a convenient and prominently visible feature that (1) displays an appropriate copyright notice, and (2) tells the user that there is no warranty for the work (except to the extent that warranties are provided), that licensees may convey the work under this License, and how to view a copy of this License. If the interface presents a list of user commands or options, such as a menu, a prominent item in the list meets this criterion. +1. Source Code. + +The “source code” for a work means the preferred form of the work for making modifications to it. “Object code” means any non-source form of a work. + +A “Standard Interface” means an interface that either is an official standard defined by a recognized standards body, or, in the case of interfaces specified for a particular programming language, one that is widely used among developers working in that language. + +The “System Libraries” of an executable work include anything, other than the work as a whole, that (a) is included in the normal form of packaging a Major Component, but which is not part of that Major Component, and (b) serves only to enable use of the work with that Major Component, or to implement a Standard Interface for which an implementation is available to the public in source code form. A “Major Component”, in this context, means a major essential component (kernel, window system, and so on) of the specific operating system (if any) on which the executable work runs, or a compiler used to produce the work, or an object code interpreter used to run it. + +The “Corresponding Source” for a work in object code form means all the source code needed to generate, install, and (for an executable work) run the object code and to modify the work, including scripts to control those activities. However, it does not include the work's System Libraries, or general-purpose tools or generally available free programs which are used unmodified in performing those activities but which are not part of the work. For example, Corresponding Source includes interface definition files associated with source files for the work, and the source code for shared libraries and dynamically linked subprograms that the work is specifically designed to require, such as by intimate data communication or control flow between those subprograms and other parts of the work. + +The Corresponding Source need not include anything that users can regenerate automatically from other parts of the Corresponding Source. + +The Corresponding Source for a work in source code form is that same work. +2. Basic Permissions. + +All rights granted under this License are granted for the term of copyright on the Program, and are irrevocable provided the stated conditions are met. This License explicitly affirms your unlimited permission to run the unmodified Program. The output from running a covered work is covered by this License only if the output, given its content, constitutes a covered work. This License acknowledges your rights of fair use or other equivalent, as provided by copyright law. + +You may make, run and propagate covered works that you do not convey, without conditions so long as your license otherwise remains in force. You may convey covered works to others for the sole purpose of having them make modifications exclusively for you, or provide you with facilities for running those works, provided that you comply with the terms of this License in conveying all material for which you do not control copyright. Those thus making or running the covered works for you must do so exclusively on your behalf, under your direction and control, on terms that prohibit them from making any copies of your copyrighted material outside their relationship with you. + +Conveying under any other circumstances is permitted solely under the conditions stated below. Sublicensing is not allowed; section 10 makes it unnecessary. +3. Protecting Users' Legal Rights From Anti-Circumvention Law. + +No covered work shall be deemed part of an effective technological measure under any applicable law fulfilling obligations under article 11 of the WIPO copyright treaty adopted on 20 December 1996, or similar laws prohibiting or restricting circumvention of such measures. + +When you convey a covered work, you waive any legal power to forbid circumvention of technological measures to the extent such circumvention is effected by exercising rights under this License with respect to the covered work, and you disclaim any intention to limit operation or modification of the work as a means of enforcing, against the work's users, your or third parties' legal rights to forbid circumvention of technological measures. +4. Conveying Verbatim Copies. + +You may convey verbatim copies of the Program's source code as you receive it, in any medium, provided that you conspicuously and appropriately publish on each copy an appropriate copyright notice; keep intact all notices stating that this License and any non-permissive terms added in accord with section 7 apply to the code; keep intact all notices of the absence of any warranty; and give all recipients a copy of this License along with the Program. + +You may charge any price or no price for each copy that you convey, and you may offer support or warranty protection for a fee. +5. Conveying Modified Source Versions. + +You may convey a work based on the Program, or the modifications to produce it from the Program, in the form of source code under the terms of section 4, provided that you also meet all of these conditions: + + a) The work must carry prominent notices stating that you modified it, and giving a relevant date. + b) The work must carry prominent notices stating that it is released under this License and any conditions added under section 7. This requirement modifies the requirement in section 4 to “keep intact all notices”. + c) You must license the entire work, as a whole, under this License to anyone who comes into possession of a copy. This License will therefore apply, along with any applicable section 7 additional terms, to the whole of the work, and all its parts, regardless of how they are packaged. This License gives no permission to license the work in any other way, but it does not invalidate such permission if you have separately received it. + d) If the work has interactive user interfaces, each must display Appropriate Legal Notices; however, if the Program has interactive interfaces that do not display Appropriate Legal Notices, your work need not make them do so. + +A compilation of a covered work with other separate and independent works, which are not by their nature extensions of the covered work, and which are not combined with it such as to form a larger program, in or on a volume of a storage or distribution medium, is called an “aggregate” if the compilation and its resulting copyright are not used to limit the access or legal rights of the compilation's users beyond what the individual works permit. Inclusion of a covered work in an aggregate does not cause this License to apply to the other parts of the aggregate. +6. Conveying Non-Source Forms. + +You may convey a covered work in object code form under the terms of sections 4 and 5, provided that you also convey the machine-readable Corresponding Source under the terms of this License, in one of these ways: + + a) Convey the object code in, or embodied in, a physical product (including a physical distribution medium), accompanied by the Corresponding Source fixed on a durable physical medium customarily used for software interchange. + b) Convey the object code in, or embodied in, a physical product (including a physical distribution medium), accompanied by a written offer, valid for at least three years and valid for as long as you offer spare parts or customer support for that product model, to give anyone who possesses the object code either (1) a copy of the Corresponding Source for all the software in the product that is covered by this License, on a durable physical medium customarily used for software interchange, for a price no more than your reasonable cost of physically performing this conveying of source, or (2) access to copy the Corresponding Source from a network server at no charge. + c) Convey individual copies of the object code with a copy of the written offer to provide the Corresponding Source. This alternative is allowed only occasionally and noncommercially, and only if you received the object code with such an offer, in accord with subsection 6b. + d) Convey the object code by offering access from a designated place (gratis or for a charge), and offer equivalent access to the Corresponding Source in the same way through the same place at no further charge. You need not require recipients to copy the Corresponding Source along with the object code. If the place to copy the object code is a network server, the Corresponding Source may be on a different server (operated by you or a third party) that supports equivalent copying facilities, provided you maintain clear directions next to the object code saying where to find the Corresponding Source. Regardless of what server hosts the Corresponding Source, you remain obligated to ensure that it is available for as long as needed to satisfy these requirements. + e) Convey the object code using peer-to-peer transmission, provided you inform other peers where the object code and Corresponding Source of the work are being offered to the general public at no charge under subsection 6d. + +A separable portion of the object code, whose source code is excluded from the Corresponding Source as a System Library, need not be included in conveying the object code work. + +A “User Product” is either (1) a “consumer product”, which means any tangible personal property which is normally used for personal, family, or household purposes, or (2) anything designed or sold for incorporation into a dwelling. In determining whether a product is a consumer product, doubtful cases shall be resolved in favor of coverage. For a particular product received by a particular user, “normally used” refers to a typical or common use of that class of product, regardless of the status of the particular user or of the way in which the particular user actually uses, or expects or is expected to use, the product. A product is a consumer product regardless of whether the product has substantial commercial, industrial or non-consumer uses, unless such uses represent the only significant mode of use of the product. + +“Installation Information” for a User Product means any methods, procedures, authorization keys, or other information required to install and execute modified versions of a covered work in that User Product from a modified version of its Corresponding Source. The information must suffice to ensure that the continued functioning of the modified object code is in no case prevented or interfered with solely because modification has been made. + +If you convey an object code work under this section in, or with, or specifically for use in, a User Product, and the conveying occurs as part of a transaction in which the right of possession and use of the User Product is transferred to the recipient in perpetuity or for a fixed term (regardless of how the transaction is characterized), the Corresponding Source conveyed under this section must be accompanied by the Installation Information. But this requirement does not apply if neither you nor any third party retains the ability to install modified object code on the User Product (for example, the work has been installed in ROM). + +The requirement to provide Installation Information does not include a requirement to continue to provide support service, warranty, or updates for a work that has been modified or installed by the recipient, or for the User Product in which it has been modified or installed. Access to a network may be denied when the modification itself materially and adversely affects the operation of the network or violates the rules and protocols for communication across the network. + +Corresponding Source conveyed, and Installation Information provided, in accord with this section must be in a format that is publicly documented (and with an implementation available to the public in source code form), and must require no special password or key for unpacking, reading or copying. +7. Additional Terms. + +“Additional permissions” are terms that supplement the terms of this License by making exceptions from one or more of its conditions. Additional permissions that are applicable to the entire Program shall be treated as though they were included in this License, to the extent that they are valid under applicable law. If additional permissions apply only to part of the Program, that part may be used separately under those permissions, but the entire Program remains governed by this License without regard to the additional permissions. + +When you convey a copy of a covered work, you may at your option remove any additional permissions from that copy, or from any part of it. (Additional permissions may be written to require their own removal in certain cases when you modify the work.) You may place additional permissions on material, added by you to a covered work, for which you have or can give appropriate copyright permission. + +Notwithstanding any other provision of this License, for material you add to a covered work, you may (if authorized by the copyright holders of that material) supplement the terms of this License with terms: + + a) Disclaiming warranty or limiting liability differently from the terms of sections 15 and 16 of this License; or + b) Requiring preservation of specified reasonable legal notices or author attributions in that material or in the Appropriate Legal Notices displayed by works containing it; or + c) Prohibiting misrepresentation of the origin of that material, or requiring that modified versions of such material be marked in reasonable ways as different from the original version; or + d) Limiting the use for publicity purposes of names of licensors or authors of the material; or + e) Declining to grant rights under trademark law for use of some trade names, trademarks, or service marks; or + f) Requiring indemnification of licensors and authors of that material by anyone who conveys the material (or modified versions of it) with contractual assumptions of liability to the recipient, for any liability that these contractual assumptions directly impose on those licensors and authors. + +All other non-permissive additional terms are considered “further restrictions” within the meaning of section 10. If the Program as you received it, or any part of it, contains a notice stating that it is governed by this License along with a term that is a further restriction, you may remove that term. If a license document contains a further restriction but permits relicensing or conveying under this License, you may add to a covered work material governed by the terms of that license document, provided that the further restriction does not survive such relicensing or conveying. + +If you add terms to a covered work in accord with this section, you must place, in the relevant source files, a statement of the additional terms that apply to those files, or a notice indicating where to find the applicable terms. + +Additional terms, permissive or non-permissive, may be stated in the form of a separately written license, or stated as exceptions; the above requirements apply either way. +8. Termination. + +You may not propagate or modify a covered work except as expressly provided under this License. Any attempt otherwise to propagate or modify it is void, and will automatically terminate your rights under this License (including any patent licenses granted under the third paragraph of section 11). + +However, if you cease all violation of this License, then your license from a particular copyright holder is reinstated (a) provisionally, unless and until the copyright holder explicitly and finally terminates your license, and (b) permanently, if the copyright holder fails to notify you of the violation by some reasonable means prior to 60 days after the cessation. + +Moreover, your license from a particular copyright holder is reinstated permanently if the copyright holder notifies you of the violation by some reasonable means, this is the first time you have received notice of violation of this License (for any work) from that copyright holder, and you cure the violation prior to 30 days after your receipt of the notice. + +Termination of your rights under this section does not terminate the licenses of parties who have received copies or rights from you under this License. If your rights have been terminated and not permanently reinstated, you do not qualify to receive new licenses for the same material under section 10. +9. Acceptance Not Required for Having Copies. + +You are not required to accept this License in order to receive or run a copy of the Program. Ancillary propagation of a covered work occurring solely as a consequence of using peer-to-peer transmission to receive a copy likewise does not require acceptance. However, nothing other than this License grants you permission to propagate or modify any covered work. These actions infringe copyright if you do not accept this License. Therefore, by modifying or propagating a covered work, you indicate your acceptance of this License to do so. +10. Automatic Licensing of Downstream Recipients. + +Each time you convey a covered work, the recipient automatically receives a license from the original licensors, to run, modify and propagate that work, subject to this License. You are not responsible for enforcing compliance by third parties with this License. + +An “entity transaction” is a transaction transferring control of an organization, or substantially all assets of one, or subdividing an organization, or merging organizations. If propagation of a covered work results from an entity transaction, each party to that transaction who receives a copy of the work also receives whatever licenses to the work the party's predecessor in interest had or could give under the previous paragraph, plus a right to possession of the Corresponding Source of the work from the predecessor in interest, if the predecessor has it or can get it with reasonable efforts. + +You may not impose any further restrictions on the exercise of the rights granted or affirmed under this License. For example, you may not impose a license fee, royalty, or other charge for exercise of rights granted under this License, and you may not initiate litigation (including a cross-claim or counterclaim in a lawsuit) alleging that any patent claim is infringed by making, using, selling, offering for sale, or importing the Program or any portion of it. +11. Patents. + +A “contributor” is a copyright holder who authorizes use under this License of the Program or a work on which the Program is based. The work thus licensed is called the contributor's “contributor version”. + +A contributor's “essential patent claims” are all patent claims owned or controlled by the contributor, whether already acquired or hereafter acquired, that would be infringed by some manner, permitted by this License, of making, using, or selling its contributor version, but do not include claims that would be infringed only as a consequence of further modification of the contributor version. For purposes of this definition, “control” includes the right to grant patent sublicenses in a manner consistent with the requirements of this License. + +Each contributor grants you a non-exclusive, worldwide, royalty-free patent license under the contributor's essential patent claims, to make, use, sell, offer for sale, import and otherwise run, modify and propagate the contents of its contributor version. + +In the following three paragraphs, a “patent license” is any express agreement or commitment, however denominated, not to enforce a patent (such as an express permission to practice a patent or covenant not to sue for patent infringement). To “grant” such a patent license to a party means to make such an agreement or commitment not to enforce a patent against the party. + +If you convey a covered work, knowingly relying on a patent license, and the Corresponding Source of the work is not available for anyone to copy, free of charge and under the terms of this License, through a publicly available network server or other readily accessible means, then you must either (1) cause the Corresponding Source to be so available, or (2) arrange to deprive yourself of the benefit of the patent license for this particular work, or (3) arrange, in a manner consistent with the requirements of this License, to extend the patent license to downstream recipients. “Knowingly relying” means you have actual knowledge that, but for the patent license, your conveying the covered work in a country, or your recipient's use of the covered work in a country, would infringe one or more identifiable patents in that country that you have reason to believe are valid. + +If, pursuant to or in connection with a single transaction or arrangement, you convey, or propagate by procuring conveyance of, a covered work, and grant a patent license to some of the parties receiving the covered work authorizing them to use, propagate, modify or convey a specific copy of the covered work, then the patent license you grant is automatically extended to all recipients of the covered work and works based on it. + +A patent license is “discriminatory” if it does not include within the scope of its coverage, prohibits the exercise of, or is conditioned on the non-exercise of one or more of the rights that are specifically granted under this License. You may not convey a covered work if you are a party to an arrangement with a third party that is in the business of distributing software, under which you make payment to the third party based on the extent of your activity of conveying the work, and under which the third party grants, to any of the parties who would receive the covered work from you, a discriminatory patent license (a) in connection with copies of the covered work conveyed by you (or copies made from those copies), or (b) primarily for and in connection with specific products or compilations that contain the covered work, unless you entered into that arrangement, or that patent license was granted, prior to 28 March 2007. + +Nothing in this License shall be construed as excluding or limiting any implied license or other defenses to infringement that may otherwise be available to you under applicable patent law. +12. No Surrender of Others' Freedom. + +If conditions are imposed on you (whether by court order, agreement or otherwise) that contradict the conditions of this License, they do not excuse you from the conditions of this License. If you cannot convey a covered work so as to satisfy simultaneously your obligations under this License and any other pertinent obligations, then as a consequence you may not convey it at all. For example, if you agree to terms that obligate you to collect a royalty for further conveying from those to whom you convey the Program, the only way you could satisfy both those terms and this License would be to refrain entirely from conveying the Program. +13. Use with the GNU Affero General Public License. + +Notwithstanding any other provision of this License, you have permission to link or combine any covered work with a work licensed under version 3 of the GNU Affero General Public License into a single combined work, and to convey the resulting work. The terms of this License will continue to apply to the part which is the covered work, but the special requirements of the GNU Affero General Public License, section 13, concerning interaction through a network will apply to the combination as such. +14. Revised Versions of this License. + +The Free Software Foundation may publish revised and/or new versions of the GNU General Public License from time to time. Such new versions will be similar in spirit to the present version, but may differ in detail to address new problems or concerns. + +Each version is given a distinguishing version number. If the Program specifies that a certain numbered version of the GNU General Public License “or any later version” applies to it, you have the option of following the terms and conditions either of that numbered version or of any later version published by the Free Software Foundation. If the Program does not specify a version number of the GNU General Public License, you may choose any version ever published by the Free Software Foundation. + +If the Program specifies that a proxy can decide which future versions of the GNU General Public License can be used, that proxy's public statement of acceptance of a version permanently authorizes you to choose that version for the Program. + +Later license versions may give you additional or different permissions. However, no additional obligations are imposed on any author or copyright holder as a result of your choosing to follow a later version. +15. Disclaimer of Warranty. + +THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM “AS IS” WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION. +16. Limitation of Liability. + +IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGES. +17. Interpretation of Sections 15 and 16. + +If the disclaimer of warranty and limitation of liability provided above cannot be given local legal effect according to their terms, reviewing courts shall apply local law that most closely approximates an absolute waiver of all civil liability in connection with the Program, unless a warranty or assumption of liability accompanies a copy of the Program in return for a fee. + +END OF TERMS AND CONDITIONS \ No newline at end of file diff --git a/Firmware_1.26b/README.md b/Firmware_1.26b/README.md new file mode 100644 index 00000000..56b5ec48 --- /dev/null +++ b/Firmware_1.26b/README.md @@ -0,0 +1,77 @@ +# Maslow Firmware + +This is the firmware which controls the Maslow CNC machine + +[![Build Status](https://travis-ci.org/MaslowCNC/Firmware.svg?branch=master)](https://travis-ci.org/MaslowCNC/Firmware) + +This is the firmware for the Maslow CNC Router + + +## Steps to setup the Firmware development environment + +First clone the Firmware repository, then install and setup the IDE of your choice. + +### Using Arduino IDE +1. Download [Arduino IDE](https://www.arduino.cc/en/main/software) 1.8.1 or higher +2. Install Arduino IDE and run Arduino IDE +3. Navigate menus: File, Open +4. In the file chooser navigate to the cloned repository and choose the "cnc_ctrl_v1.ino" file to open +5. Navigate menu: Tools, Board, change to "Arduino/Genuino Mega or Mega 2560" +6. Navigate menu: Sketch -> Upload + +This should compile the project without errors, and possibly some warnings. + +### Using PlatformIO +1. Download package for [Atom](https://atom.io/) +2. Follow directions for [installing PlatformIO within Atom](http://docs.platformio.org/en/latest/ide/atom.html#ide-installation) +3. Within Atom navigate menus: PlatformIO, Open Project +4. Select "Firmware" directory +5. Click "Open Firmware" + +### Using Eclipse Neon C/C++ with Sloeber plugin + +1. Download [Eclipse C/C++](https://eclipse.org/downloads/) Neon or higher +2. Install Eclipse C/C++ and run Eclipse +3. Install Sloeber Arduino plugin + * Navigate menus: Help, Install New Software... + * Copy this URL in the "Work With" field: http://eclipse.baeyens.it/update/V4/stable + * Select "Add" button + * Select "Sloeber Arduino IDE" check box + * Select "Finish" button + * Accept defaults and accept licenses, the plugin will restart Eclipse, and configure the plugin +4. Change to Arduino perspective, navigate menus: Window, Perspective, Open Perspective, Other... + * Choose the "Arduino" perspective and select "Ok" button +5. Create an Arduino project + * Navigate menus: File, New, New Arduino Sketch + * Project Name: cnc_ctrl_v1 + * Select "Next" button + * Select appropriate item from "Platform folder" drop down listing + * Select Board: Arduino/Genuino Mega or Mega 2560 + * Select Upload Protocol: Default + * Select Processor: ATmega2560 (Mega 2560) + * Select "Finish" button +6. Import project source code + * Select project folder, navigate menus: File, Import... + * Expand "General" and select "File system" + * Select "Next" button + * Select the "Browse" button to select the source location (location of the cloned repository cnc_ctrl_v1 directory) + * Select whole source directory in the left pane + * Open Advanced Settings by klicking on "Advanced>>" button + * Select 'Create Links in Workspace' and 'Create virtual folders' leave other settings untouched + * Select 'Finish' button + * Eclipse asks if overwriting the original cnc_ctrl_v1.ino file is ok. Confirm with 'yes'. +7. Update eclipse project include paths + * Select the project folder in the project explorer and click Project->Properties in the menu. + * In the Project properties left Pane select C/C++ Build->Settings + * In the right Pane select the 'Tool Settings' Tab and add the path to the source location to the include paths of all compilers/linkers of the toolchain. + * The last two steps may differ between toolchains. + + +### Using NotePad++ in Conjunction with the Arduino IDE +1. Download NotePad++ (Windows only) [link](https://notepad-plus-plus.org/) +2. Download the Arduino IDE [link](https://www.arduino.cc/en/main/software) +3. Set that you would like use an external editor from within the Arduino IDE by clicking File -> Preferences -> Use External Editor + *The Arduino editor will no longer allow you to edit the files, but instead will only work to compile and upload your code. + *The code can be edited from within NotePad++ + *This method can be used on other platforms with editing programs other than NP++ + diff --git a/Firmware_1.26b/cnc_ctrl_v1/Axis.cpp b/Firmware_1.26b/cnc_ctrl_v1/Axis.cpp new file mode 100644 index 00000000..c6ce84b9 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Axis.cpp @@ -0,0 +1,301 @@ +/*This file is part of the Maslow Control Software. + + The Maslow Control Software is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Maslow Control Software is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with the Maslow Control Software. If not, see . + + Copyright 2014-2017 Bar Smith*/ + + +#include "Maslow.h" + +void Axis::setup(const int& pwmPin, const int& directionPin1, const int& directionPin2, const int& encoderPin1, const int& encoderPin2, const char& axisName, const unsigned long& loopInterval) +{ + // I don't really like this, but I don't know how else to initialize a pointer to a value + float zero = 0.0; + float one = 1.0; + _Kp = _Ki = _Kd = &zero; + + motorGearboxEncoder.setup(pwmPin, directionPin1, directionPin2, encoderPin1, encoderPin2, loopInterval); + _pidController.setup(&_pidInput, &_pidOutput, &_pidSetpoint, _Kp, _Ki, _Kd, &one, REVERSE); + + //initialize variables + _axisName = axisName; + + initializePID(loopInterval); + + motorGearboxEncoder.setName(&_axisName); +} + +void Axis::initializePID(const unsigned long& loopInterval){ + _pidController.SetMode(AUTOMATIC); + _pidController.SetOutputLimits(-20, 20); + _pidController.SetSampleTime( loopInterval / 1000); +} + +void Axis::write(const float& targetPosition){ + _timeLastMoved = millis(); + _pidSetpoint = targetPosition/ *_mmPerRotation; + return; +} + +float Axis::read(){ + //returns the true axis position + + return (motorGearboxEncoder.encoder.read()/ *_encoderSteps) * *_mmPerRotation; + +} + +float Axis::setpoint(){ + return _pidSetpoint * *_mmPerRotation; +} + +void Axis::set(const float& newAxisPosition){ + + //reset everything to the new value + _pidSetpoint = newAxisPosition/ *_mmPerRotation; + motorGearboxEncoder.encoder.write((newAxisPosition * *_encoderSteps)/ *_mmPerRotation); + +} + +long Axis::steps(){ + /* + Returns the number of steps reported by the encoder + */ + return motorGearboxEncoder.encoder.read(); +} + +void Axis::setSteps(const long& steps){ + + //reset everything to the new value + _pidSetpoint = steps/ *_encoderSteps; + motorGearboxEncoder.encoder.write(steps); + +} + +void Axis::computePID(){ + + #ifdef FAKE_SERVO + if (motorGearboxEncoder.motor.attached()){ + // Adds up to 10% error just to simulate servo noise + double rpm = (-1 * _pidOutput) * random(90, 110) / 100; + unsigned long steps = motorGearboxEncoder.encoder.read() + round( rpm * *_encoderSteps * LOOPINTERVAL)/(60 * 1000000); + motorGearboxEncoder.encoder.write(steps); + } + #endif + + if (_disableAxisForTesting || !motorGearboxEncoder.motor.attached()){ + return; + } + + _pidInput = motorGearboxEncoder.encoder.read()/ *_encoderSteps; + + if (_pidController.Compute()){ + // Only write output if the PID calculation was performed + motorGearboxEncoder.write(_pidOutput); + } + + motorGearboxEncoder.computePID(); + +} + +void Axis::disablePositionPID(){ + + _pidController.SetMode(MANUAL); + +} + +void Axis::enablePositionPID(){ + + _pidController.SetMode(AUTOMATIC); + +} + +void Axis::setPIDValues(float* KpPos, float* KiPos, float* KdPos, float* propWeight, float* KpV, float* KiV, float* KdV, float* propWeightV){ + /* + + Sets the positional PID values for the axis + + */ + _Kp = KpPos; + _Ki = KiPos; + _Kd = KdPos; + + _pidController.SetTunings(_Kp, _Ki, _Kd, propWeight); + + motorGearboxEncoder.setPIDValues(KpV, KiV, KdV, propWeightV); +} + +String Axis::getPIDString(){ + /* + + Get PID tuning values + + */ + String PIDString = "Kp="; + return PIDString + *_Kp + ",Ki=" + *_Ki + ",Kd=" + *_Kd; +} + +void Axis::setPIDAggressiveness(float aggressiveness){ + /* + + The setPIDAggressiveness() function sets the aggressiveness of the PID controller to + compensate for a change in the load on the motor. + + */ + + motorGearboxEncoder.setPIDAggressiveness(aggressiveness); +} + +float Axis::error(){ + + float encoderErr = (motorGearboxEncoder.encoder.read()/ *_encoderSteps) - _pidSetpoint; + + return encoderErr * *_mmPerRotation; +} + +void Axis::changePitch(float *newPitch){ + /* + Reassign the distance moved per-rotation for the axis. + */ + _mmPerRotation = newPitch; +} + +float Axis::getPitch(){ + /* + Returns the distance moved per-rotation for the axis. + */ + return *_mmPerRotation; +} + +void Axis::changeEncoderResolution(float *newResolution){ + /* + Reassign the encoder resolution for the axis. + */ + _encoderSteps = newResolution; + + //push to the gearbox for calculating RPM + motorGearboxEncoder.setEncoderResolution(*newResolution); + +} + +int Axis::detach(){ + + motorGearboxEncoder.motor.detach(); + + return 1; +} + +int Axis::attach(){ + motorGearboxEncoder.motor.attach(); + return 1; +} + +bool Axis::attached(){ + /* + + Returns true if the axis is attached, false if it is not. + + */ + + return motorGearboxEncoder.motor.attached(); +} + +void Axis::detachIfIdle(){ + /* + Detaches the axis, turning off the motor and PID control, if it has been + stationary for more than axisDetachTime + */ + if (millis() - _timeLastMoved > sysSettings.axisDetachTime){ + detach(); + } + +} + +void Axis::endMove(const float& finalTarget){ + + _timeLastMoved = millis(); + _pidSetpoint = finalTarget/ *_mmPerRotation; + +} + +void Axis::stop(){ + /* + + Immediately stop the axis where it is, not where it should be + + */ + + _timeLastMoved = millis(); + _pidSetpoint = read()/ *_mmPerRotation; + +} + +void Axis::test(){ + /* + Test the axis by directly commanding the motor and observing if the encoder moves + */ + + Serial.print(F("Testing ")); + Serial.print(_axisName); + Serial.println(F(" motor:")); + + //print something to prevent the connection from timing out + Serial.print(F("")); + + int i = 0; + double encoderPos = motorGearboxEncoder.encoder.read(); //record the position now + + //move the motor + while (i < 1000){ + motorGearboxEncoder.motor.directWrite(255); + i++; + maslowDelay(1); + if (sys.stop){return;} + } + + //check to see if it moved + if(encoderPos - motorGearboxEncoder.encoder.read() > 500){ + Serial.println(F("Direction 1 - Pass")); + } + else{ + Serial.println(F("Direction 1 - Fail")); + } + + //record the position again + encoderPos = motorGearboxEncoder.encoder.read(); + Serial.print(F("")); + + //move the motor in the other direction + i = 0; + while (i < 1000){ + motorGearboxEncoder.motor.directWrite(-255); + i++; + maslowDelay(1); + if (sys.stop){return;} + } + + //check to see if it moved + if(encoderPos - motorGearboxEncoder.encoder.read() < -500){ + Serial.println(F("Direction 2 - Pass")); + } + else{ + Serial.println(F("Direction 2 - Fail")); + } + + //stop the motor + motorGearboxEncoder.motor.directWrite(0); + Serial.print(F("")); +} + +double Axis::pidInput(){ return _pidInput * *_mmPerRotation;} +double Axis::pidOutput(){ return _pidOutput;} diff --git a/Firmware_1.26b/cnc_ctrl_v1/Axis.h b/Firmware_1.26b/cnc_ctrl_v1/Axis.h new file mode 100644 index 00000000..2f193dbc --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Axis.h @@ -0,0 +1,70 @@ + /*This file is part of the Maslow Control Software. + + The Maslow Control Software is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Maslow Control Software is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with the Maslow Control Software. If not, see . + + Copyright 2014-2017 Bar Smith*/ + + #ifndef Axis_h + #define Axis_h + + class Axis{ + public: + void setup(const int& pwmPin, const int& directionPin1, const int& directionPin2, const int& encoderPin1, const int& encoderPin2, const char& axisName, const unsigned long& loopInterval); + void write(const float& targetPosition); + float read(); + void set(const float& newAxisPosition); + void setSteps(const long& steps); + int updatePositionFromEncoder(); + void initializePID(const unsigned long& loopInterval); + int detach(); + int attach(); + void detachIfIdle(); + void endMove(const float& finalTarget); + void stop(); + float target(); + float error(); + float setpoint(); + void computePID(); + void disablePositionPID(); + void enablePositionPID(); + void setPIDAggressiveness(float aggressiveness); + void test(); + void changePitch(float* newPitch); + float getPitch(); + void changeEncoderResolution(float* newResolution); + bool attached(); + MotorGearboxEncoder motorGearboxEncoder; + void setPIDValues(float* Kp, float* Ki, float* Kd, float* propWeight, float* KpV, float* KiV, float* KdV, float* propWeightV); + String getPIDString(); + double pidInput(); + double pidOutput(); + long steps(); + + private: + int _PWMread(int pin); + void _writeFloat(const unsigned int& addr, const float& x); + float _readFloat(const unsigned int& addr); + unsigned long _timeLastMoved; + volatile double _pidSetpoint; + volatile double _pidInput; + volatile double _pidOutput; + float *_Kp, *_Ki, *_Kd; + PID _pidController; + float *_mmPerRotation; + float *_encoderSteps; + bool _disableAxisForTesting = false; + char _axisName; + }; + + #endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/Config.h b/Firmware_1.26b/cnc_ctrl_v1/Config.h new file mode 100644 index 00000000..b31d2dac --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Config.h @@ -0,0 +1,64 @@ +/*This file is part of the Maslow Control Software. + The Maslow Control Software is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + Maslow Control Software is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + You should have received a copy of the GNU General Public License + along with the Maslow Control Software. If not, see . + + Copyright 2014-2017 Bar Smith*/ + +// This file contains precompile configuration settings that apply to the +// whole system + +#ifndef config_h +#define config_h + +// Debugging Options +#define verboseDebug 0 // set to 0 for no debug messages, 1 for single-line messages, 2 to also output ring buffer contents +#define misloopDebug 0 // set to 1 for a warning every time the movement loop fails + // to complete before being interrupted, helpful for loop + // LOOPINTERVAL tuning +#define KINEMATICSDBG 0 // set to 1 for additional kinematics debug messaging + +// #define FAKE_SERVO // Uncomment this line to cause the Firmware to mimic + // a servo updating the encoder steps even if no servo + // is connected. Useful for testing on an arduino only + +// #define SIMAVR // Uncomment this if you plan to run the Firmware in the simavr + // simulator. Normally, you would not define this directly, but + // use PlatformIO to build the simavr environment. + +#define LOOPINTERVAL 10000 // What is the frequency of the PID loop in microseconds + +// Define version detect pins +#define VERS1 22 +#define VERS2 23 +#define VERS3 24 +#define VERS4 25 +#define VERS5 26 +#define VERS6 27 + +// Serial variables +#define INCBUFFERLENGTH 128 // The number of bytes(characters) allocated to the + // incoming buffer. +#define EXPGCODELINE 60 // Maximum expected Gcode line length in characters + // including line ending character(s). Assumes + // client will not send more than this. Ground + // Control is currently set to 60. NIST spec allows + // 256. This value must be <= INCBUFFERLENGTH +#define MAXBUFFERLINES 4 // The maximum number of lines allowed in the buffer +#define POSITIONTIMEOUT 200 // The minimum number of milliseconds between + // position reports sent to Ground Control. This + // cannot be larger than the connection timout in + // Ground Control which is 2000, a smaller number + // takes more processing time for sending data + // a larger number make position updates in GC less + // smooth. This is only a minimum, and the actual + // timeout could be significantly larger. + +#endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/Encoder.cpp b/Firmware_1.26b/cnc_ctrl_v1/Encoder.cpp new file mode 100644 index 00000000..b4492dfe --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Encoder.cpp @@ -0,0 +1,10 @@ + +#include "Maslow.h" + +// Yes, all the code is in the header file, to provide the user +// configure options with #define (before they include it), and +// to facilitate some crafty optimizations! + +Encoder_internal_state_t * Encoder::interruptArgs[]; + + diff --git a/Firmware_1.26b/cnc_ctrl_v1/Encoder.h b/Firmware_1.26b/cnc_ctrl_v1/Encoder.h new file mode 100644 index 00000000..4b428997 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Encoder.h @@ -0,0 +1,976 @@ +/* Encoder Library, for measuring quadrature encoded signals + * http://www.pjrc.com/teensy/td_libs_Encoder.html + * Copyright (c) 2011,2013 PJRC.COM, LLC - Paul Stoffregen + * + * Version 1.2 - fix -2 bug in C-only code + * Version 1.1 - expand to support boards with up to 60 interrupts + * Version 1.0 - initial release + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + + +#ifndef Encoder_h_ +#define Encoder_h_ + +#if defined(ARDUINO) && ARDUINO >= 100 +#include "Arduino.h" +#elif defined(WIRING) +#include "Wiring.h" +#else +#include "WProgram.h" +#include "pins_arduino.h" +#endif + +#if defined(ENCODER_USE_INTERRUPTS) || !defined(ENCODER_DO_NOT_USE_INTERRUPTS) +#define ENCODER_USE_INTERRUPTS +#define ENCODER_ARGLIST_SIZE CORE_NUM_INTERRUPT +#include "utility/interrupt_pins.h" +#ifdef ENCODER_OPTIMIZE_INTERRUPTS +#include "utility/interrupt_config.h" +#endif +#else +#define ENCODER_ARGLIST_SIZE 0 +#endif + + + +// All the data needed by interrupts is consolidated into this ugly struct +// to facilitate assembly language optimizing of the speed critical update. +// The assembly code uses auto-incrementing addressing modes, so the struct +// must remain in exactly this order. +typedef struct { + volatile IO_REG_TYPE * pin1_register; + volatile IO_REG_TYPE * pin2_register; + IO_REG_TYPE pin1_bitmask; + IO_REG_TYPE pin2_bitmask; + uint8_t state; + int32_t position; + int32_t elapsedTime; + int32_t lastTime; +} Encoder_internal_state_t; + +class Encoder +{ +public: + void setup(uint8_t pin1, uint8_t pin2) { + #ifdef INPUT_PULLUP + pinMode(pin1, INPUT_PULLUP); + pinMode(pin2, INPUT_PULLUP); + #else + pinMode(pin1, INPUT); + digitalWrite(pin1, HIGH); + pinMode(pin2, INPUT); + digitalWrite(pin2, HIGH); + #endif + encoder.pin1_register = PIN_TO_BASEREG(pin1); + encoder.pin1_bitmask = PIN_TO_BITMASK(pin1); + encoder.pin2_register = PIN_TO_BASEREG(pin2); + encoder.pin2_bitmask = PIN_TO_BITMASK(pin2); + encoder.position = 0; + // allow time for a passive R-C filter to charge + // through the pullup resistors, before reading + // the initial state + delayMicroseconds(2000); + uint8_t s = 0; + if (DIRECT_PIN_READ(encoder.pin1_register, encoder.pin1_bitmask)) s |= 1; + if (DIRECT_PIN_READ(encoder.pin2_register, encoder.pin2_bitmask)) s |= 2; + encoder.state = s; +#ifdef ENCODER_USE_INTERRUPTS + interrupts_in_use = attach_interrupt(pin1, &encoder); + interrupts_in_use += attach_interrupt(pin2, &encoder); +#endif + //update_finishup(); // to force linker to include the code (does not work) + } + + +#ifdef ENCODER_USE_INTERRUPTS + inline int32_t read() { + if (interrupts_in_use < 2) { + noInterrupts(); + update(&encoder); + } else { + noInterrupts(); + } + int32_t ret = encoder.position; + interrupts(); + return ret; + } + inline int32_t elapsedTime() { + if (interrupts_in_use < 2) { + noInterrupts(); + update(&encoder); + } else { + noInterrupts(); + } + int32_t ret = encoder.elapsedTime; + interrupts(); + return ret; + } + inline int32_t lastStepTime() { + if (interrupts_in_use < 2) { + noInterrupts(); + update(&encoder); + } else { + noInterrupts(); + } + int32_t ret = encoder.lastTime; + interrupts(); + return ret; + } + inline void write(int32_t p) { + noInterrupts(); + encoder.position = p; + interrupts(); + } +#else + inline int32_t read() { + update(&encoder); + return encoder.position; + } + inline void write(int32_t p) { + encoder.position = p; + } +#endif +private: + Encoder_internal_state_t encoder; +#ifdef ENCODER_USE_INTERRUPTS + uint8_t interrupts_in_use; +#endif +public: + static Encoder_internal_state_t * interruptArgs[ENCODER_ARGLIST_SIZE]; + +// _______ _______ +// Pin1 ______| |_______| |______ Pin1 +// negative <--- _______ _______ __ --> positive +// Pin2 __| |_______| |_______| Pin2 + + // new new old old + // pin2 pin1 pin2 pin1 Result + // ---- ---- ---- ---- ------ + // 0 0 0 0 no movement + // 0 0 0 1 +1 + // 0 0 1 0 -1 + // 0 0 1 1 +2 (assume pin1 edges only) + // 0 1 0 0 -1 + // 0 1 0 1 no movement + // 0 1 1 0 -2 (assume pin1 edges only) + // 0 1 1 1 +1 + // 1 0 0 0 +1 + // 1 0 0 1 -2 (assume pin1 edges only) + // 1 0 1 0 no movement + // 1 0 1 1 -1 + // 1 1 0 0 +2 (assume pin1 edges only) + // 1 1 0 1 -1 + // 1 1 1 0 +1 + // 1 1 1 1 no movement +/* + // Simple, easy-to-read "documentation" version :-) + // + void update(void) { + uint8_t s = state & 3; + if (digitalRead(pin1)) s |= 4; + if (digitalRead(pin2)) s |= 8; + switch (s) { + case 0: case 5: case 10: case 15: + break; + case 1: case 7: case 8: case 14: + position++; break; + case 2: case 4: case 11: case 13: + position--; break; + case 3: case 12: + position += 2; break; + default: + position -= 2; break; + } + state = (s >> 2); + } +*/ + +private: + static void update(Encoder_internal_state_t *arg) { +#if defined(__AVR_DISABLED__) + // Changed from __AVR__ to force C code below, until someone has + // the chance to write the elapsedTime feature into assembly + // code. The time difference between the two options is + // minimal at best. + // The compiler believes this is just 1 line of code, so + // it will inline this function into each interrupt + // handler. That's a tiny bit faster, but grows the code. + // Especially when used with ENCODER_OPTIMIZE_INTERRUPTS, + // the inline nature allows the ISR prologue and epilogue + // to only save/restore necessary registers, for very nice + // speed increase. + asm volatile ( + "ld r30, X+" "\n\t" + "ld r31, X+" "\n\t" + "ld r24, Z" "\n\t" // r24 = pin1 input + "ld r30, X+" "\n\t" + "ld r31, X+" "\n\t" + "ld r25, Z" "\n\t" // r25 = pin2 input + "ld r30, X+" "\n\t" // r30 = pin1 mask + "ld r31, X+" "\n\t" // r31 = pin2 mask + "ld r22, X" "\n\t" // r22 = state + "andi r22, 3" "\n\t" + "and r24, r30" "\n\t" + "breq L%=1" "\n\t" // if (pin1) + "ori r22, 4" "\n\t" // state |= 4 + "L%=1:" "and r25, r31" "\n\t" + "breq L%=2" "\n\t" // if (pin2) + "ori r22, 8" "\n\t" // state |= 8 + "L%=2:" "ldi r30, lo8(pm(L%=table))" "\n\t" + "ldi r31, hi8(pm(L%=table))" "\n\t" + "add r30, r22" "\n\t" + "adc r31, __zero_reg__" "\n\t" + "asr r22" "\n\t" + "asr r22" "\n\t" + "st X+, r22" "\n\t" // store new state + "ld r22, X+" "\n\t" + "ld r23, X+" "\n\t" + "ld r24, X+" "\n\t" + "ld r25, X+" "\n\t" + "ijmp" "\n\t" // jumps to update_finishup() + // TODO move this table to another static function, + // so it doesn't get needlessly duplicated. Easier + // said than done, due to linker issues and inlining + "L%=table:" "\n\t" + "rjmp L%=end" "\n\t" // 0 + "rjmp L%=plus1" "\n\t" // 1 + "rjmp L%=minus1" "\n\t" // 2 + "rjmp L%=plus2" "\n\t" // 3 + "rjmp L%=minus1" "\n\t" // 4 + "rjmp L%=end" "\n\t" // 5 + "rjmp L%=minus2" "\n\t" // 6 + "rjmp L%=plus1" "\n\t" // 7 + "rjmp L%=plus1" "\n\t" // 8 + "rjmp L%=minus2" "\n\t" // 9 + "rjmp L%=end" "\n\t" // 10 + "rjmp L%=minus1" "\n\t" // 11 + "rjmp L%=plus2" "\n\t" // 12 + "rjmp L%=minus1" "\n\t" // 13 + "rjmp L%=plus1" "\n\t" // 14 + "rjmp L%=end" "\n\t" // 15 + "L%=minus2:" "\n\t" + "subi r22, 2" "\n\t" + "sbci r23, 0" "\n\t" + "sbci r24, 0" "\n\t" + "sbci r25, 0" "\n\t" + "rjmp L%=store" "\n\t" + "L%=minus1:" "\n\t" + "subi r22, 1" "\n\t" + "sbci r23, 0" "\n\t" + "sbci r24, 0" "\n\t" + "sbci r25, 0" "\n\t" + "rjmp L%=store" "\n\t" + "L%=plus2:" "\n\t" + "subi r22, 254" "\n\t" + "rjmp L%=z" "\n\t" + "L%=plus1:" "\n\t" + "subi r22, 255" "\n\t" + "L%=z:" "sbci r23, 255" "\n\t" + "sbci r24, 255" "\n\t" + "sbci r25, 255" "\n\t" + "L%=store:" "\n\t" + "st -X, r25" "\n\t" + "st -X, r24" "\n\t" + "st -X, r23" "\n\t" + "st -X, r22" "\n\t" + "L%=end:" "\n" + : : "x" (arg) : "r22", "r23", "r24", "r25", "r30", "r31"); +#else + uint8_t p1val = DIRECT_PIN_READ(arg->pin1_register, arg->pin1_bitmask); + uint8_t p2val = DIRECT_PIN_READ(arg->pin2_register, arg->pin2_bitmask); + uint8_t state = arg->state & 3; + if (p1val) state |= 4; + if (p2val) state |= 8; + arg->state = (state >> 2); + switch (state) { + case 1: case 7: case 8: case 14: + arg->position++; + arg->elapsedTime = (micros() - arg->lastTime); + arg->lastTime = micros(); + return; + case 2: case 4: case 11: case 13: + arg->position--; + arg->elapsedTime = (arg->lastTime - micros()); + arg->lastTime = micros(); + return; + case 3: case 12: + arg->position += 2; + arg->elapsedTime = (micros() - arg->lastTime) >> 1; + arg->lastTime = micros(); + return; + case 6: case 9: + arg->position -= 2; + arg->elapsedTime = (arg->lastTime - micros()) >> 1; + arg->lastTime = micros(); + return; + } +#endif + } +/* +#if defined(__AVR__) + // TODO: this must be a no inline function + // even noinline does not seem to solve difficult + // problems with this. Oh well, it was only meant + // to shrink code size - there's no performance + // improvement in this, only code size reduction. + __attribute__((noinline)) void update_finishup(void) { + asm volatile ( + "ldi r30, lo8(pm(Ltable))" "\n\t" + "ldi r31, hi8(pm(Ltable))" "\n\t" + "Ltable:" "\n\t" + "rjmp L%=end" "\n\t" // 0 + "rjmp L%=plus1" "\n\t" // 1 + "rjmp L%=minus1" "\n\t" // 2 + "rjmp L%=plus2" "\n\t" // 3 + "rjmp L%=minus1" "\n\t" // 4 + "rjmp L%=end" "\n\t" // 5 + "rjmp L%=minus2" "\n\t" // 6 + "rjmp L%=plus1" "\n\t" // 7 + "rjmp L%=plus1" "\n\t" // 8 + "rjmp L%=minus2" "\n\t" // 9 + "rjmp L%=end" "\n\t" // 10 + "rjmp L%=minus1" "\n\t" // 11 + "rjmp L%=plus2" "\n\t" // 12 + "rjmp L%=minus1" "\n\t" // 13 + "rjmp L%=plus1" "\n\t" // 14 + "rjmp L%=end" "\n\t" // 15 + "L%=minus2:" "\n\t" + "subi r22, 2" "\n\t" + "sbci r23, 0" "\n\t" + "sbci r24, 0" "\n\t" + "sbci r25, 0" "\n\t" + "rjmp L%=store" "\n\t" + "L%=minus1:" "\n\t" + "subi r22, 1" "\n\t" + "sbci r23, 0" "\n\t" + "sbci r24, 0" "\n\t" + "sbci r25, 0" "\n\t" + "rjmp L%=store" "\n\t" + "L%=plus2:" "\n\t" + "subi r22, 254" "\n\t" + "rjmp L%=z" "\n\t" + "L%=plus1:" "\n\t" + "subi r22, 255" "\n\t" + "L%=z:" "sbci r23, 255" "\n\t" + "sbci r24, 255" "\n\t" + "sbci r25, 255" "\n\t" + "L%=store:" "\n\t" + "st -X, r25" "\n\t" + "st -X, r24" "\n\t" + "st -X, r23" "\n\t" + "st -X, r22" "\n\t" + "L%=end:" "\n" + : : : "r22", "r23", "r24", "r25", "r30", "r31"); + } +#endif +*/ + + +#ifdef ENCODER_USE_INTERRUPTS + // this giant function is an unfortunate consequence of Arduino's + // attachInterrupt function not supporting any way to pass a pointer + // or other context to the attached function. + static uint8_t attach_interrupt(uint8_t pin, Encoder_internal_state_t *state) { + switch (pin) { + #ifdef CORE_INT0_PIN + case CORE_INT0_PIN: + interruptArgs[0] = state; + attachInterrupt(0, isr0, CHANGE); + break; + #endif + #ifdef CORE_INT1_PIN + case CORE_INT1_PIN: + interruptArgs[1] = state; + attachInterrupt(1, isr1, CHANGE); + break; + #endif + #ifdef CORE_INT2_PIN + case CORE_INT2_PIN: + interruptArgs[2] = state; + attachInterrupt(2, isr2, CHANGE); + break; + #endif + #ifdef CORE_INT3_PIN + case CORE_INT3_PIN: + interruptArgs[3] = state; + attachInterrupt(3, isr3, CHANGE); + break; + #endif + #ifdef CORE_INT4_PIN + case CORE_INT4_PIN: + interruptArgs[4] = state; + attachInterrupt(4, isr4, CHANGE); + break; + #endif + #ifdef CORE_INT5_PIN + case CORE_INT5_PIN: + interruptArgs[5] = state; + attachInterrupt(5, isr5, CHANGE); + break; + #endif + #ifdef CORE_INT6_PIN + case CORE_INT6_PIN: + interruptArgs[6] = state; + attachInterrupt(6, isr6, CHANGE); + break; + #endif + #ifdef CORE_INT7_PIN + case CORE_INT7_PIN: + interruptArgs[7] = state; + attachInterrupt(7, isr7, CHANGE); + break; + #endif + #ifdef CORE_INT8_PIN + case CORE_INT8_PIN: + interruptArgs[8] = state; + attachInterrupt(8, isr8, CHANGE); + break; + #endif + #ifdef CORE_INT9_PIN + case CORE_INT9_PIN: + interruptArgs[9] = state; + attachInterrupt(9, isr9, CHANGE); + break; + #endif + #ifdef CORE_INT10_PIN + case CORE_INT10_PIN: + interruptArgs[10] = state; + attachInterrupt(10, isr10, CHANGE); + break; + #endif + #ifdef CORE_INT11_PIN + case CORE_INT11_PIN: + interruptArgs[11] = state; + attachInterrupt(11, isr11, CHANGE); + break; + #endif + #ifdef CORE_INT12_PIN + case CORE_INT12_PIN: + interruptArgs[12] = state; + attachInterrupt(12, isr12, CHANGE); + break; + #endif + #ifdef CORE_INT13_PIN + case CORE_INT13_PIN: + interruptArgs[13] = state; + attachInterrupt(13, isr13, CHANGE); + break; + #endif + #ifdef CORE_INT14_PIN + case CORE_INT14_PIN: + interruptArgs[14] = state; + attachInterrupt(14, isr14, CHANGE); + break; + #endif + #ifdef CORE_INT15_PIN + case CORE_INT15_PIN: + interruptArgs[15] = state; + attachInterrupt(15, isr15, CHANGE); + break; + #endif + #ifdef CORE_INT16_PIN + case CORE_INT16_PIN: + interruptArgs[16] = state; + attachInterrupt(16, isr16, CHANGE); + break; + #endif + #ifdef CORE_INT17_PIN + case CORE_INT17_PIN: + interruptArgs[17] = state; + attachInterrupt(17, isr17, CHANGE); + break; + #endif + #ifdef CORE_INT18_PIN + case CORE_INT18_PIN: + interruptArgs[18] = state; + attachInterrupt(18, isr18, CHANGE); + break; + #endif + #ifdef CORE_INT19_PIN + case CORE_INT19_PIN: + interruptArgs[19] = state; + attachInterrupt(19, isr19, CHANGE); + break; + #endif + #ifdef CORE_INT20_PIN + case CORE_INT20_PIN: + interruptArgs[20] = state; + attachInterrupt(20, isr20, CHANGE); + break; + #endif + #ifdef CORE_INT21_PIN + case CORE_INT21_PIN: + interruptArgs[21] = state; + attachInterrupt(21, isr21, CHANGE); + break; + #endif + #ifdef CORE_INT22_PIN + case CORE_INT22_PIN: + interruptArgs[22] = state; + attachInterrupt(22, isr22, CHANGE); + break; + #endif + #ifdef CORE_INT23_PIN + case CORE_INT23_PIN: + interruptArgs[23] = state; + attachInterrupt(23, isr23, CHANGE); + break; + #endif + #ifdef CORE_INT24_PIN + case CORE_INT24_PIN: + interruptArgs[24] = state; + attachInterrupt(24, isr24, CHANGE); + break; + #endif + #ifdef CORE_INT25_PIN + case CORE_INT25_PIN: + interruptArgs[25] = state; + attachInterrupt(25, isr25, CHANGE); + break; + #endif + #ifdef CORE_INT26_PIN + case CORE_INT26_PIN: + interruptArgs[26] = state; + attachInterrupt(26, isr26, CHANGE); + break; + #endif + #ifdef CORE_INT27_PIN + case CORE_INT27_PIN: + interruptArgs[27] = state; + attachInterrupt(27, isr27, CHANGE); + break; + #endif + #ifdef CORE_INT28_PIN + case CORE_INT28_PIN: + interruptArgs[28] = state; + attachInterrupt(28, isr28, CHANGE); + break; + #endif + #ifdef CORE_INT29_PIN + case CORE_INT29_PIN: + interruptArgs[29] = state; + attachInterrupt(29, isr29, CHANGE); + break; + #endif + + #ifdef CORE_INT30_PIN + case CORE_INT30_PIN: + interruptArgs[30] = state; + attachInterrupt(30, isr30, CHANGE); + break; + #endif + #ifdef CORE_INT31_PIN + case CORE_INT31_PIN: + interruptArgs[31] = state; + attachInterrupt(31, isr31, CHANGE); + break; + #endif + #ifdef CORE_INT32_PIN + case CORE_INT32_PIN: + interruptArgs[32] = state; + attachInterrupt(32, isr32, CHANGE); + break; + #endif + #ifdef CORE_INT33_PIN + case CORE_INT33_PIN: + interruptArgs[33] = state; + attachInterrupt(33, isr33, CHANGE); + break; + #endif + #ifdef CORE_INT34_PIN + case CORE_INT34_PIN: + interruptArgs[34] = state; + attachInterrupt(34, isr34, CHANGE); + break; + #endif + #ifdef CORE_INT35_PIN + case CORE_INT35_PIN: + interruptArgs[35] = state; + attachInterrupt(35, isr35, CHANGE); + break; + #endif + #ifdef CORE_INT36_PIN + case CORE_INT36_PIN: + interruptArgs[36] = state; + attachInterrupt(36, isr36, CHANGE); + break; + #endif + #ifdef CORE_INT37_PIN + case CORE_INT37_PIN: + interruptArgs[37] = state; + attachInterrupt(37, isr37, CHANGE); + break; + #endif + #ifdef CORE_INT38_PIN + case CORE_INT38_PIN: + interruptArgs[38] = state; + attachInterrupt(38, isr38, CHANGE); + break; + #endif + #ifdef CORE_INT39_PIN + case CORE_INT39_PIN: + interruptArgs[39] = state; + attachInterrupt(39, isr39, CHANGE); + break; + #endif + #ifdef CORE_INT40_PIN + case CORE_INT40_PIN: + interruptArgs[40] = state; + attachInterrupt(40, isr40, CHANGE); + break; + #endif + #ifdef CORE_INT41_PIN + case CORE_INT41_PIN: + interruptArgs[41] = state; + attachInterrupt(41, isr41, CHANGE); + break; + #endif + #ifdef CORE_INT42_PIN + case CORE_INT42_PIN: + interruptArgs[42] = state; + attachInterrupt(42, isr42, CHANGE); + break; + #endif + #ifdef CORE_INT43_PIN + case CORE_INT43_PIN: + interruptArgs[43] = state; + attachInterrupt(43, isr43, CHANGE); + break; + #endif + #ifdef CORE_INT44_PIN + case CORE_INT44_PIN: + interruptArgs[44] = state; + attachInterrupt(44, isr44, CHANGE); + break; + #endif + #ifdef CORE_INT45_PIN + case CORE_INT45_PIN: + interruptArgs[45] = state; + attachInterrupt(45, isr45, CHANGE); + break; + #endif + #ifdef CORE_INT46_PIN + case CORE_INT46_PIN: + interruptArgs[46] = state; + attachInterrupt(46, isr46, CHANGE); + break; + #endif + #ifdef CORE_INT47_PIN + case CORE_INT47_PIN: + interruptArgs[47] = state; + attachInterrupt(47, isr47, CHANGE); + break; + #endif + #ifdef CORE_INT48_PIN + case CORE_INT48_PIN: + interruptArgs[48] = state; + attachInterrupt(48, isr48, CHANGE); + break; + #endif + #ifdef CORE_INT49_PIN + case CORE_INT49_PIN: + interruptArgs[49] = state; + attachInterrupt(49, isr49, CHANGE); + break; + #endif + #ifdef CORE_INT50_PIN + case CORE_INT50_PIN: + interruptArgs[50] = state; + attachInterrupt(50, isr50, CHANGE); + break; + #endif + #ifdef CORE_INT51_PIN + case CORE_INT51_PIN: + interruptArgs[51] = state; + attachInterrupt(51, isr51, CHANGE); + break; + #endif + #ifdef CORE_INT52_PIN + case CORE_INT52_PIN: + interruptArgs[52] = state; + attachInterrupt(52, isr52, CHANGE); + break; + #endif + #ifdef CORE_INT53_PIN + case CORE_INT53_PIN: + interruptArgs[53] = state; + attachInterrupt(53, isr53, CHANGE); + break; + #endif + #ifdef CORE_INT54_PIN + case CORE_INT54_PIN: + interruptArgs[54] = state; + attachInterrupt(54, isr54, CHANGE); + break; + #endif + #ifdef CORE_INT55_PIN + case CORE_INT55_PIN: + interruptArgs[55] = state; + attachInterrupt(55, isr55, CHANGE); + break; + #endif + #ifdef CORE_INT56_PIN + case CORE_INT56_PIN: + interruptArgs[56] = state; + attachInterrupt(56, isr56, CHANGE); + break; + #endif + #ifdef CORE_INT57_PIN + case CORE_INT57_PIN: + interruptArgs[57] = state; + attachInterrupt(57, isr57, CHANGE); + break; + #endif + #ifdef CORE_INT58_PIN + case CORE_INT58_PIN: + interruptArgs[58] = state; + attachInterrupt(58, isr58, CHANGE); + break; + #endif + #ifdef CORE_INT59_PIN + case CORE_INT59_PIN: + interruptArgs[59] = state; + attachInterrupt(59, isr59, CHANGE); + break; + #endif + default: + return 0; + } + return 1; + } +#endif // ENCODER_USE_INTERRUPTS + + +#if defined(ENCODER_USE_INTERRUPTS) && !defined(ENCODER_OPTIMIZE_INTERRUPTS) + #ifdef CORE_INT0_PIN + static void isr0(void) { update(interruptArgs[0]); } + #endif + #ifdef CORE_INT1_PIN + static void isr1(void) { update(interruptArgs[1]); } + #endif + #ifdef CORE_INT2_PIN + static void isr2(void) { update(interruptArgs[2]); } + #endif + #ifdef CORE_INT3_PIN + static void isr3(void) { update(interruptArgs[3]); } + #endif + #ifdef CORE_INT4_PIN + static void isr4(void) { update(interruptArgs[4]); } + #endif + #ifdef CORE_INT5_PIN + static void isr5(void) { update(interruptArgs[5]); } + #endif + #ifdef CORE_INT6_PIN + static void isr6(void) { update(interruptArgs[6]); } + #endif + #ifdef CORE_INT7_PIN + static void isr7(void) { update(interruptArgs[7]); } + #endif + #ifdef CORE_INT8_PIN + static void isr8(void) { update(interruptArgs[8]); } + #endif + #ifdef CORE_INT9_PIN + static void isr9(void) { update(interruptArgs[9]); } + #endif + #ifdef CORE_INT10_PIN + static void isr10(void) { update(interruptArgs[10]); } + #endif + #ifdef CORE_INT11_PIN + static void isr11(void) { update(interruptArgs[11]); } + #endif + #ifdef CORE_INT12_PIN + static void isr12(void) { update(interruptArgs[12]); } + #endif + #ifdef CORE_INT13_PIN + static void isr13(void) { update(interruptArgs[13]); } + #endif + #ifdef CORE_INT14_PIN + static void isr14(void) { update(interruptArgs[14]); } + #endif + #ifdef CORE_INT15_PIN + static void isr15(void) { update(interruptArgs[15]); } + #endif + #ifdef CORE_INT16_PIN + static void isr16(void) { update(interruptArgs[16]); } + #endif + #ifdef CORE_INT17_PIN + static void isr17(void) { update(interruptArgs[17]); } + #endif + #ifdef CORE_INT18_PIN + static void isr18(void) { update(interruptArgs[18]); } + #endif + #ifdef CORE_INT19_PIN + static void isr19(void) { update(interruptArgs[19]); } + #endif + #ifdef CORE_INT20_PIN + static void isr20(void) { update(interruptArgs[20]); } + #endif + #ifdef CORE_INT21_PIN + static void isr21(void) { update(interruptArgs[21]); } + #endif + #ifdef CORE_INT22_PIN + static void isr22(void) { update(interruptArgs[22]); } + #endif + #ifdef CORE_INT23_PIN + static void isr23(void) { update(interruptArgs[23]); } + #endif + #ifdef CORE_INT24_PIN + static void isr24(void) { update(interruptArgs[24]); } + #endif + #ifdef CORE_INT25_PIN + static void isr25(void) { update(interruptArgs[25]); } + #endif + #ifdef CORE_INT26_PIN + static void isr26(void) { update(interruptArgs[26]); } + #endif + #ifdef CORE_INT27_PIN + static void isr27(void) { update(interruptArgs[27]); } + #endif + #ifdef CORE_INT28_PIN + static void isr28(void) { update(interruptArgs[28]); } + #endif + #ifdef CORE_INT29_PIN + static void isr29(void) { update(interruptArgs[29]); } + #endif + #ifdef CORE_INT30_PIN + static void isr30(void) { update(interruptArgs[30]); } + #endif + #ifdef CORE_INT31_PIN + static void isr31(void) { update(interruptArgs[31]); } + #endif + #ifdef CORE_INT32_PIN + static void isr32(void) { update(interruptArgs[32]); } + #endif + #ifdef CORE_INT33_PIN + static void isr33(void) { update(interruptArgs[33]); } + #endif + #ifdef CORE_INT34_PIN + static void isr34(void) { update(interruptArgs[34]); } + #endif + #ifdef CORE_INT35_PIN + static void isr35(void) { update(interruptArgs[35]); } + #endif + #ifdef CORE_INT36_PIN + static void isr36(void) { update(interruptArgs[36]); } + #endif + #ifdef CORE_INT37_PIN + static void isr37(void) { update(interruptArgs[37]); } + #endif + #ifdef CORE_INT38_PIN + static void isr38(void) { update(interruptArgs[38]); } + #endif + #ifdef CORE_INT39_PIN + static void isr39(void) { update(interruptArgs[39]); } + #endif + #ifdef CORE_INT40_PIN + static void isr40(void) { update(interruptArgs[40]); } + #endif + #ifdef CORE_INT41_PIN + static void isr41(void) { update(interruptArgs[41]); } + #endif + #ifdef CORE_INT42_PIN + static void isr42(void) { update(interruptArgs[42]); } + #endif + #ifdef CORE_INT43_PIN + static void isr43(void) { update(interruptArgs[43]); } + #endif + #ifdef CORE_INT44_PIN + static void isr44(void) { update(interruptArgs[44]); } + #endif + #ifdef CORE_INT45_PIN + static void isr45(void) { update(interruptArgs[45]); } + #endif + #ifdef CORE_INT46_PIN + static void isr46(void) { update(interruptArgs[46]); } + #endif + #ifdef CORE_INT47_PIN + static void isr47(void) { update(interruptArgs[47]); } + #endif + #ifdef CORE_INT48_PIN + static void isr48(void) { update(interruptArgs[48]); } + #endif + #ifdef CORE_INT49_PIN + static void isr49(void) { update(interruptArgs[49]); } + #endif + #ifdef CORE_INT50_PIN + static void isr50(void) { update(interruptArgs[50]); } + #endif + #ifdef CORE_INT51_PIN + static void isr51(void) { update(interruptArgs[51]); } + #endif + #ifdef CORE_INT52_PIN + static void isr52(void) { update(interruptArgs[52]); } + #endif + #ifdef CORE_INT53_PIN + static void isr53(void) { update(interruptArgs[53]); } + #endif + #ifdef CORE_INT54_PIN + static void isr54(void) { update(interruptArgs[54]); } + #endif + #ifdef CORE_INT55_PIN + static void isr55(void) { update(interruptArgs[55]); } + #endif + #ifdef CORE_INT56_PIN + static void isr56(void) { update(interruptArgs[56]); } + #endif + #ifdef CORE_INT57_PIN + static void isr57(void) { update(interruptArgs[57]); } + #endif + #ifdef CORE_INT58_PIN + static void isr58(void) { update(interruptArgs[58]); } + #endif + #ifdef CORE_INT59_PIN + static void isr59(void) { update(interruptArgs[59]); } + #endif +#endif +}; + +#if defined(ENCODER_USE_INTERRUPTS) && defined(ENCODER_OPTIMIZE_INTERRUPTS) +#if defined(__AVR__) +#if defined(INT0_vect) && CORE_NUM_INTERRUPT > 0 +ISR(INT0_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(0)]); } +#endif +#if defined(INT1_vect) && CORE_NUM_INTERRUPT > 1 +ISR(INT1_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(1)]); } +#endif +#if defined(INT2_vect) && CORE_NUM_INTERRUPT > 2 +ISR(INT2_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(2)]); } +#endif +#if defined(INT3_vect) && CORE_NUM_INTERRUPT > 3 +ISR(INT3_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(3)]); } +#endif +#if defined(INT4_vect) && CORE_NUM_INTERRUPT > 4 +ISR(INT4_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(4)]); } +#endif +#if defined(INT5_vect) && CORE_NUM_INTERRUPT > 5 +ISR(INT5_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(5)]); } +#endif +#if defined(INT6_vect) && CORE_NUM_INTERRUPT > 6 +ISR(INT6_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(6)]); } +#endif +#if defined(INT7_vect) && CORE_NUM_INTERRUPT > 7 +ISR(INT7_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(7)]); } +#endif +#endif // AVR +#endif // ENCODER_OPTIMIZE_INTERRUPTS + + +#endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/GCode.cpp b/Firmware_1.26b/cnc_ctrl_v1/GCode.cpp new file mode 100644 index 00000000..8a0cc684 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/GCode.cpp @@ -0,0 +1,889 @@ +/*This file is part of the Maslow Control Software. + +The Maslow Control Software is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +Maslow Control Software is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with the Maslow Control Software. If not, see . + +Copyright 2014-2017 Bar Smith*/ + +// This file contains all the functions used to receive and parse the gcode +// commands + +#include "Maslow.h" + +RingBuffer incSerialBuffer; +String readyCommandString = ""; //KRK why is this a global? +String gcodeLine = ""; //Our use of this is a bit sloppy, at times, + //we pass references to this global and then + //name them the same thing. + +void initGCode(){ + // Called on startup or after a stop command + readyCommandString = ""; + incSerialBuffer.empty(); +} + +void readSerialCommands(){ + /* + Check to see if a new character is available from the serial connection, + if this is a necessary character write to the incSerialBuffer otherwise discard + it. + */ + + static bool quickCommandFlag = false; + + if (Serial.available() > 0) { + while (Serial.available() > 0) { + char c = Serial.read(); + if (c == '!'){ + sys.stop = true; + quickCommandFlag = true; + bit_false(sys.pause, PAUSE_FLAG_USER_PAUSE); + reportStatusMessage(STATUS_OK); + } + else if (c == '~'){ + quickCommandFlag = true; + bit_false(sys.pause, PAUSE_FLAG_USER_PAUSE); + reportStatusMessage(STATUS_OK); + } + else if (quickCommandFlag and c == '\n'){ + // Catch line ending and ignore after quick commands + quickCommandFlag = false; + } + else{ + quickCommandFlag = false; + int bufferOverflow = incSerialBuffer.write(c); //gets one byte from serial buffer, writes it to the internal ring buffer + if (bufferOverflow != 0) { + sys.stop = true; + } + } + if (sys.stop){return;} + } + #if defined (verboseDebug) && verboseDebug > 1 + // print ring buffer contents + Serial.println(F("rSC added to ring buffer")); + incSerialBuffer.print(); + #endif + } +} + +int findEndOfNumber(const String& textString, const int& index){ + //Return the index of the last digit of the number beginning at the index passed in + unsigned int i = index; + + while (i < textString.length()){ + + if(isDigit(textString[i]) or isPunct(textString[i])){ //If we're still looking at a number, keep goin + i++; + } + else{ + return i; //If we've reached the end of the number, return the last index + } + } + return i; //If we've reached the end of the string, return the last number +} + +float extractGcodeValue(const String& readString, char target, const float& defaultReturn){ + + /*Reads a string and returns the value of number following the target character. + If no number is found, defaultReturn is returned*/ + + int begin; + int end; + String numberAsString; + float numberAsFloat; + + begin = readString.indexOf(target); + end = findEndOfNumber(readString,begin+1); + numberAsString = readString.substring(begin+1,end); + + numberAsFloat = numberAsString.toFloat(); + + if (begin == -1){ //if the character was not found, return error + return defaultReturn; + } + + return numberAsFloat; +} + +byte executeBcodeLine(const String& gcodeLine){ + /* + + Executes a single line of gcode beginning with the character 'B'. + + */ + + //Handle B-codes + + if(gcodeLine.substring(0, 3) == "B05"){ + Serial.print(F("Firmware Version ")); + Serial.println(VERSIONNUMBER); + return STATUS_OK; + } + + if(sys.state == STATE_OLD_SETTINGS){ + return STATUS_OLD_SETTINGS; + } + + if(gcodeLine.substring(0, 3) == "B01"){ + + Serial.println(F("Motor Calibration Not Needed")); + + return STATUS_OK; + } + + if(gcodeLine.substring(0, 3) == "B02"){ + calibrateChainLengths(gcodeLine); + return STATUS_OK; + } + + if(gcodeLine.substring(0, 3) == "B04"){ + //set flag to ignore position error limit during the tests + sys.state = (sys.state | STATE_POS_ERR_IGNORE); + //Test each of the axis + maslowDelay(500); + if(sys.stop){return STATUS_OK;} + leftAxis.test(); + maslowDelay(500); + if(sys.stop){return STATUS_OK;} + rightAxis.test(); + maslowDelay(500); + if(sys.stop){return STATUS_OK;} + zAxis.test(); + Serial.println(F("Tests complete.")); + + // update our position + leftAxis.set(leftAxis.read()); + rightAxis.set(rightAxis.read()); + + //clear the flag, re-enable position error limit + sys.state = (sys.state & (!STATE_POS_ERR_IGNORE)); + return STATUS_OK; + } + + if(gcodeLine.substring(0, 3) == "B06"){ + Serial.println(F("Setting Chain Lengths To: ")); + float newL = extractGcodeValue(gcodeLine, 'L', 0); + float newR = extractGcodeValue(gcodeLine, 'R', 0); + + leftAxis.set(newL); + rightAxis.set(newR); + + Serial.print(F("Left: ")); + Serial.print(leftAxis.read()); + Serial.println(F("mm")); + Serial.print(F("Right: ")); + Serial.print(rightAxis.read()); + Serial.println(F("mm")); + + return STATUS_OK; + } + + if(gcodeLine.substring(0, 3) == "B08"){ + //Manually recalibrate chain lengths + leftAxis.set(sysSettings.originalChainLength); + rightAxis.set(sysSettings.originalChainLength); + + Serial.print(F("Left: ")); + Serial.print(leftAxis.read()); + Serial.println(F("mm")); + Serial.print(F("Right: ")); + Serial.print(rightAxis.read()); + Serial.println(F("mm")); + + kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition, 0, 0); + + Serial.println(F("Message: The machine chains have been manually re-calibrated.")); + + return STATUS_OK; + } + + if(gcodeLine.substring(0, 3) == "B09"){ + //Directly command each axis to move to a given distance + float lDist = extractGcodeValue(gcodeLine, 'L', 0); + float rDist = extractGcodeValue(gcodeLine, 'R', 0); + float speed = extractGcodeValue(gcodeLine, 'F', 800); + + if(sys.useRelativeUnits){ + if(abs(lDist) > 0){ + singleAxisMove(&leftAxis, leftAxis.read() + lDist, speed); + } + if(abs(rDist) > 0){ + singleAxisMove(&rightAxis, rightAxis.read() + rDist, speed); + } + } + else{ + singleAxisMove(&leftAxis, lDist, speed); + singleAxisMove(&rightAxis, rDist, speed); + } + + return STATUS_OK; + } + + if(gcodeLine.substring(0, 3) == "B10"){ + //measure the left axis chain length + Serial.print(F("[Measure: ")); + if (gcodeLine.indexOf('L') != -1){ + Serial.print(leftAxis.read()); + } + else{ + Serial.print(rightAxis.read()); + } + Serial.println(F("]")); + return STATUS_OK; + } + + if(gcodeLine.substring(0, 3) == "B11"){ + //run right motor in the given direction at the given speed for the given time + float speed = extractGcodeValue(gcodeLine, 'S', 100); + float time = extractGcodeValue(gcodeLine, 'T', 1); + + double ms = 1000*time; + double begin = millis(); + + int i = 0; + sys.state = (sys.state | STATE_POS_ERR_IGNORE); + while (millis() - begin < ms){ + if (gcodeLine.indexOf('L') != -1){ + leftAxis.motorGearboxEncoder.motor.directWrite(speed); + } + else{ + rightAxis.motorGearboxEncoder.motor.directWrite(speed); + } + + i++; + execSystemRealtime(); + if (sys.stop){return STATUS_OK;} + } + sys.state = (sys.state | (!STATE_POS_ERR_IGNORE)); + return STATUS_OK; + } + + if(gcodeLine.substring(0, 3) == "B13"){ + //PID Testing of Velocity + float left = extractGcodeValue(gcodeLine, 'L', 0); + float useZ = extractGcodeValue(gcodeLine, 'Z', 0); + float start = extractGcodeValue(gcodeLine, 'S', 1); + float stop = extractGcodeValue(gcodeLine, 'F', 1); + float steps = extractGcodeValue(gcodeLine, 'I', 1); + float version = extractGcodeValue(gcodeLine, 'V', 1); + + Axis* axis = &rightAxis; + if (left > 0) axis = &leftAxis; + if (useZ > 0) axis = &zAxis; + PIDTestVelocity(axis, start, stop, steps, version); + return STATUS_OK; + } + + if(gcodeLine.substring(0, 3) == "B14"){ + //PID Testing of Position + float left = extractGcodeValue(gcodeLine, 'L', 0); + float useZ = extractGcodeValue(gcodeLine, 'Z', 0); + float start = extractGcodeValue(gcodeLine, 'S', 1); + float stop = extractGcodeValue(gcodeLine, 'F', 1); + float steps = extractGcodeValue(gcodeLine, 'I', 1); + float stepTime = extractGcodeValue(gcodeLine, 'T', 2000); + float version = extractGcodeValue(gcodeLine, 'V', 1); + + Axis* axis = &rightAxis; + if (left > 0) axis = &leftAxis; + if (useZ > 0) axis = &zAxis; + PIDTestPosition(axis, start, stop, steps, stepTime, version); + return STATUS_OK; + } + + if(gcodeLine.substring(0, 3) == "B16"){ + //Incrementally tests voltages to see what RPMs they produce + float left = extractGcodeValue(gcodeLine, 'L', 0); + float useZ = extractGcodeValue(gcodeLine, 'Z', 0); + float start = extractGcodeValue(gcodeLine, 'S', 1); + float stop = extractGcodeValue(gcodeLine, 'F', 1); + + Axis* axis = &rightAxis; + if (left > 0) axis = &leftAxis; + if (useZ > 0) axis = &zAxis; + voltageTest(axis, start, stop); + return STATUS_OK; + } + + if(gcodeLine.substring(0, 3) == "B15"){ + //The B15 command moves the chains to the length which will put the sled in the center of the sheet + + //Compute chain length for position 0,0 + float chainLengthAtMiddle; + kinematics.inverse(0,0,&chainLengthAtMiddle,&chainLengthAtMiddle); + + //Adjust left chain length + singleAxisMove(&leftAxis, chainLengthAtMiddle, 800); + + //Adjust right chain length + singleAxisMove(&rightAxis, chainLengthAtMiddle, 800); + + //Reload the position + kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition, 0, 0); + + return STATUS_OK; + } + return STATUS_INVALID_STATEMENT; +} + +void executeGcodeLine(const String& gcodeLine){ + /* + + Executes a single line of gcode beginning with the character 'G'. If the G code is + not included on the front of the line, the code from the previous line will be added. + + */ + + //Handle G-Codes + + int gNumber = extractGcodeValue(gcodeLine,'G', -1); + + if (gNumber == -1){ // If the line does not have a G command + gNumber = sys.lastGCommand; // apply the last one + } + + switch(gNumber){ + case 0: // Rapid positioning + case 1: // Linear interpolation + G1(gcodeLine, gNumber); + sys.lastGCommand = gNumber; // remember G number for next time + break; + case 2: // Circular interpolation, clockwise + case 3: // Circular interpolation, counterclockwise + G2(gcodeLine, gNumber); + sys.lastGCommand = gNumber; // remember G number for next time + break; + case 4: + G4(gcodeLine); + break; + case 10: + G10(gcodeLine); + break; + case 20: + setInchesToMillimetersConversion(INCHES); + break; + case 21: + setInchesToMillimetersConversion(MILLIMETERS); + break; + case 40: + break; //the G40 command turns off cutter compensation which is already off so it is safe to ignore + case 38: + G38(gcodeLine); + break; + case 90: + sys.useRelativeUnits = false; + break; + case 91: + sys.useRelativeUnits = true; + break; + default: + Serial.print(F("Command G")); + Serial.print(gNumber); + Serial.println(F(" unsupported and ignored.")); + } + +} + +void executeMcodeLine(const String& gcodeLine){ + /* + + Executes a single line of gcode beginning with the character 'M'. + + */ + + //Handle M-Codes + + int mNumber = extractGcodeValue(gcodeLine,'M', -1); + + switch(mNumber){ + case 0: // Program Pause / Unconditional Halt / Stop + case 1: // Optional Pause / Halt / Sleep + pause(); + break; + case 2: // Program End + case 30: // Program End with return to program top + case 5: // Spindle Off + setSpindlePower(false); // turn off spindle + break; + case 3: // Spindle On - clockwise + case 4: // Spindle On - counterclockwise + // Maslow spindle runs only one direction, but turn spindle on for either code + setSpindlePower(true); // turn on spindle + break; + case 6: // Tool Change + if (sys.nextTool != sys.lastTool) { + setSpindlePower(false); // first, turn off spindle + Serial.print(F("Tool Change: Please insert tool ")); // prompt user to change tool + Serial.println(sys.nextTool); + sys.lastTool = sys.nextTool; + pause(); + } + break; + case 106: + //Turn laser on + laserOn(true); // EBS + break; + case 107: + //Turn laser off + laserOn(false); + break; + default: + Serial.print(F("Command M")); + Serial.print(mNumber); + Serial.println(F(" unsupported and ignored.")); + } + +} + +void executeOtherCodeLine(const String& gcodeLine){ + /* + + Executes a single line of gcode beginning with a character other than 'G', 'B', or 'M'. + + */ + + if (gcodeLine.length() > 1) { + if (gcodeLine[0] == 'T') { + int tNumber = extractGcodeValue(gcodeLine,'T', 0); // get tool number + Serial.print(F("Tool change to tool ")); + Serial.println(tNumber); + sys.nextTool = tNumber; // remember tool number to prompt user when G06 is received + } + else { // try it as a 'G' command without the leading 'G' code + executeGcodeLine(gcodeLine); + } + } + else { + Serial.print(F("Command ")); + Serial.print(gcodeLine); + Serial.println(F(" too short - ignored.")); + } + +} + +int findNextGM(const String& readString, const int& startingPoint){ + int nextGIndex = readString.indexOf('G', startingPoint); + int nextMIndex = readString.indexOf('M', startingPoint); + if (nextMIndex != -1) { // if 'M' was found + if ((nextGIndex == -1) || (nextMIndex < nextGIndex)) { // and 'G' was not found, or if 'M' is before 'G' + nextGIndex = nextMIndex; // then use 'M' + } + } + if (nextGIndex == -1) { // if 'G' was not found (and therefore 'M' was not found) + nextGIndex = readString.length(); // then use the whole string + } + + return nextGIndex; +} + +void sanitizeCommandString(String& cmdString){ + /* + Primarily removes comments and some other non supported characters or functions. + This is taken heavily from the GRBL project at https://github.com/gnea/grbl + */ + + byte line_flags = 0; + size_t pos = 0; + + while (cmdString.length() > pos){ + if (line_flags) { + // Throw away all (except EOL) comment characters and overflow characters. + if (cmdString[pos] == ')') { + // End of '()' comment. Resume line allowed. + cmdString.remove(pos, 1); + if (line_flags & LINE_FLAG_COMMENT_PARENTHESES) { line_flags &= ~(LINE_FLAG_COMMENT_PARENTHESES); } + } + } + else { + if (cmdString[pos] < ' ') { + // Throw away control characters + cmdString.remove(pos, 1); + } + else if (cmdString[pos] == '/') { + // Block delete NOT SUPPORTED. Ignore character. + // NOTE: If supported, would simply need to check the system if block delete is enabled. + cmdString.remove(pos, 1); + } else if (cmdString[pos] == '(') { + // Enable comments flag and ignore all characters until ')' or EOL. + // NOTE: This doesn't follow the NIST definition exactly, but is good enough for now. + // In the future, we could simply remove the items within the comments, but retain the + // comment control characters, so that the g-code parser can error-check it. + cmdString.remove(pos, 1); + line_flags |= LINE_FLAG_COMMENT_PARENTHESES; + } else if (cmdString[pos] == ';') { + // NOTE: ';' comment to EOL is a LinuxCNC definition. Not NIST. + cmdString.remove(pos, 1); + line_flags |= LINE_FLAG_COMMENT_SEMICOLON; + } else if (cmdString[pos] == '%') { + // Program start-end percent sign NOT SUPPORTED. + cmdString.remove(pos, 1); + } else { + pos++; + } + } + } + #if defined (verboseDebug) && verboseDebug > 1 + // print results + Serial.println(F("sCS execution complete")); + Serial.println(cmdString); + #endif +} + +byte interpretCommandString(String& cmdString){ + /* + + Splits a string into lines of gcode which begin with 'G' or 'M', executing each in order + Also executes full lines for 'B' codes, and handles 'T' at beginning of line + + Assumptions: + Leading and trailing white space has already been removed from cmdString + cmdString has been converted to upper case + + */ + + size_t firstG; + size_t secondG; + + if (cmdString.length() > 0) { + if (cmdString[0] == '$') { + // Maslow '$' system command + return(systemExecuteCmdstring(cmdString)); + } + else if (cmdString[0] == 'B'){ //If the command is a B command + #if defined (verboseDebug) && verboseDebug > 0 + Serial.print(F("iCS executing B code line: ")); + #endif + Serial.println(cmdString); + return executeBcodeLine(cmdString); + } + else if (sys.state == STATE_OLD_SETTINGS){ + return STATUS_OLD_SETTINGS; + } + else { + while(cmdString.length() > 0){ //Extract each line of gcode from the string + firstG = findNextGM(cmdString, 0); + secondG = findNextGM(cmdString, firstG + 1); + + if(firstG == cmdString.length()){ //If the line contains no G or M letters + firstG = 0; //send the whole line + } + + if (firstG > 0) { //If there is something before the first 'G' or 'M' + gcodeLine = cmdString.substring(0, firstG); + #if defined (verboseDebug) && verboseDebug > 0 + Serial.print(F("iCS executing other code: ")); + #endif + Serial.println(gcodeLine); + executeOtherCodeLine(gcodeLine); // execute it first + } + + gcodeLine = cmdString.substring(firstG, secondG); + + if (gcodeLine.length() > 0){ + if (gcodeLine[0] == 'M') { + #if defined (verboseDebug) && verboseDebug > 0 + Serial.print(F("iCS executing M code: ")); + #endif + Serial.println(gcodeLine); + executeMcodeLine(gcodeLine); + } + else { + #if defined (verboseDebug) && verboseDebug > 0 + Serial.print(F("iCS executing G code: ")); + #endif + Serial.println(gcodeLine); + executeGcodeLine(gcodeLine); + } + } + + cmdString = cmdString.substring(secondG, cmdString.length()); + + } + return STATUS_OK; + } + return STATUS_INVALID_STATEMENT; + } + return STATUS_OK; +} + +void gcodeExecuteLoop(){ + byte status; + if (incSerialBuffer.numberOfLines() > 0){ + incSerialBuffer.prettyReadLine(readyCommandString); + sanitizeCommandString(readyCommandString); + status = interpretCommandString(readyCommandString); + readyCommandString = ""; + + // Get next line of GCode + if (!sys.stop){reportStatusMessage(status);} + } +} + +void G1(const String& readString, int G0orG1){ + + /*G1() is the function which is called to process the string if it begins with + 'G01' or 'G00'*/ + + float xgoto; + float ygoto; + float zgoto; + + float currentXPos = sys.xPosition; + float currentYPos = sys.yPosition; + + float currentZPos = zAxis.read(); + + xgoto = sys.inchesToMMConversion*extractGcodeValue(readString, 'X', currentXPos/sys.inchesToMMConversion); + ygoto = sys.inchesToMMConversion*extractGcodeValue(readString, 'Y', currentYPos/sys.inchesToMMConversion); + zgoto = sys.inchesToMMConversion*extractGcodeValue(readString, 'Z', currentZPos/sys.inchesToMMConversion); + sys.feedrate = sys.inchesToMMConversion*extractGcodeValue(readString, 'F', sys.feedrate/sys.inchesToMMConversion); + + if (sys.useRelativeUnits){ //if we are using a relative coordinate system + + if(readString.indexOf('X') >= 0){ //if there is an X command + xgoto = currentXPos + xgoto; + } + if(readString.indexOf('Y') >= 0){ //if y has moved + ygoto = currentYPos + ygoto; + } + if(readString.indexOf('Z') >= 0){ //if y has moved + zgoto = currentZPos + zgoto; + } + } + + sys.feedrate = constrain(sys.feedrate, 1, sysSettings.maxFeed); //constrain the maximum feedrate, 35ipm = 900 mmpm + + //if the zaxis is attached + if(!sysSettings.zAxisAttached){ + float threshold = .1; //units of mm + if (abs(currentZPos - zgoto) > threshold){ + Serial.print(F("Message: Please adjust Z-Axis to a depth of ")); + if (zgoto > 0){ + Serial.print(F("+")); + } + Serial.print(zgoto/sys.inchesToMMConversion); + if (sys.inchesToMMConversion == INCHES){ + Serial.println(F(" in")); + } + else{ + Serial.println(F(" mm")); + } + + pause(); //Wait until the z-axis is adjusted + + zAxis.set(zgoto); + + maslowDelay(1000); + } + } + + + if (G0orG1 == 1){ + //if this is a regular move + coordinatedMove(xgoto, ygoto, zgoto, sys.feedrate); //The XY move is performed + } + else{ + //if this is a rapid move + coordinatedMove(xgoto, ygoto, zgoto, sysSettings.maxFeed); //move the same as a regular move, but go fast + } +} + +void G2(const String& readString, int G2orG3){ + /* + + The G2 function handles the processing of the gcode line for both the command G2 and the + command G3 which cut arcs. + + */ + + + float X1 = sys.xPosition; //does this work if units are inches? (It seems to) + float Y1 = sys.yPosition; + float Z1 = zAxis.read(); // I don't know why we treat the zaxis differently + + float X2 = sys.inchesToMMConversion*extractGcodeValue(readString, 'X', X1/sys.inchesToMMConversion); + float Y2 = sys.inchesToMMConversion*extractGcodeValue(readString, 'Y', Y1/sys.inchesToMMConversion); + float Z2 = sys.inchesToMMConversion*extractGcodeValue(readString, 'Z', Z1/sys.inchesToMMConversion); + float I = sys.inchesToMMConversion*extractGcodeValue(readString, 'I', 0.0); + float J = sys.inchesToMMConversion*extractGcodeValue(readString, 'J', 0.0); + sys.feedrate = sys.inchesToMMConversion*extractGcodeValue(readString, 'F', sys.feedrate/sys.inchesToMMConversion); + + float centerX = X1 + I; + float centerY = Y1 + J; + + sys.feedrate = constrain(sys.feedrate, 1, sysSettings.maxFeed); //constrain the maximum feedrate, 35ipm = 900 mmpm + + if (G2orG3 == 2){ + arc(X1, Y1, Z1, X2, Y2, Z2, centerX, centerY, sys.feedrate, CLOCKWISE); + } + else { + arc(X1, Y1, Z1, X2, Y2, Z2, centerX, centerY, sys.feedrate, COUNTERCLOCKWISE); + } +} + +void G4(const String& readString){ + /* + The G4() dwell function handles the G4 gcode which pauses for P milliseconds or S seconds. + Only one of the two is accepted, the other ignored. + Use maslowDelay() to remain responsive to GC during the dwell time. + Because maslowDelay() operates in milliseconds, round to the nearest millisecond. + Negative values are treated as positive (not a time machine). + */ + float dwellMS = abs(extractGcodeValue(readString, 'P', 0)); + float dwellS = abs(extractGcodeValue(readString, 'S', 0)); + + if (dwellMS == 0) { + /* + ignore S parameter unless P is zero + */ + dwellMS = dwellS * 1000; + } + dwellMS = long(dwellMS + .5); + Serial.print(F("dwell time ")); + if (dwellS > 0) { + Serial.print(dwellS); + Serial.println(F(" seconds")); + } else { + Serial.print(dwellMS, 0); + Serial.println(F(" ms.")); + } + maslowDelay(dwellMS); +} + +void G10(const String& readString){ + /*The G10() function handles the G10 gcode which re-zeros one or all of the machine's axes.*/ + float currentZPos = zAxis.read(); + float zgoto = sys.inchesToMMConversion*extractGcodeValue(readString, 'Z', currentZPos/sys.inchesToMMConversion); + + zAxis.set(zgoto); + zAxis.endMove(zgoto); + zAxis.attach(); +} + +void G38(const String& readString) { + //if the zaxis is attached + if (sysSettings.zAxisAttached) { + /* + The G38() function handles the G38 gcode which zeros the machine's z axis. + Currently ignores X and Y options + */ + if (readString.substring(3, 5) == ".2") { + Serial.println(F("probing for z axis zero")); + float zgoto; + + + float currentZPos = zAxis.read(); + int zDirection = sysSettings.zEncoderSteps<0 ? -1 : 1; + + zgoto = zDirection * sys.inchesToMMConversion * extractGcodeValue(readString, 'Z', currentZPos / sys.inchesToMMConversion); + sys.feedrate = sys.inchesToMMConversion * extractGcodeValue(readString, 'F', sys.feedrate / sys.inchesToMMConversion); + sys.feedrate = constrain(sys.feedrate, 1, sysSettings.maxZRPM * abs(zAxis.getPitch())); + + if (sys.useRelativeUnits) { //if we are using a relative coordinate system + if (readString.indexOf('Z') >= 0) { //if z has moved + zgoto = currentZPos + zgoto; + } + } + + Serial.print(F("max depth ")); + Serial.print(zgoto); + Serial.println(F(" mm.")); + Serial.print(F("feedrate ")); + Serial.print(sys.feedrate); + Serial.println(F(" mm per min.")); + + + //set Probe to input with pullup + pinMode(ProbePin, INPUT_PULLUP); + digitalWrite(ProbePin, HIGH); + + if (zgoto != currentZPos / sys.inchesToMMConversion) { + // now move z to the Z destination; + // Currently ignores X and Y options + // we need a version of singleAxisMove that quits if the AUXn input changes (goes LOW) + // which will act the same as the stop found in singleAxisMove (need both?) + // singleAxisMove(&zAxis, zgoto, feedrate); + + /* + Takes a pointer to an axis object and mo ves that axis to endPos at speed MMPerMin + */ + + Axis* axis = &zAxis; + float startingPos = axis->read(); + float endPos = zgoto; + float moveDist = endPos - currentZPos; //total distance to move + + float direction = moveDist / abs(moveDist); //determine the direction of the move + + float stepSizeMM = 0.01; //step size in mm + + //the argument to abs should only be a variable -- splitting calc into 2 lines + long finalNumberOfSteps = moveDist / stepSizeMM; //number of steps taken in move + finalNumberOfSteps = abs(finalNumberOfSteps); + + long numberOfStepsTaken = 0; + float whereAxisShouldBeAtThisStep = startingPos; + + axis->attach(); + // zAxis->attach(); + + while (numberOfStepsTaken < finalNumberOfSteps) { + if (!movementUpdated){ + //find the target point for this step + whereAxisShouldBeAtThisStep += stepSizeMM * direction; + + //write to each axis + axis->write(whereAxisShouldBeAtThisStep); + movementUpdate(); + + // Run realtime commands + execSystemRealtime(); + if (sys.stop){return;} + + //increment the number of steps taken + numberOfStepsTaken++; + } + + //check for Probe touchdown + if (checkForProbeTouch(ProbePin)) { + zAxis.set(0); + zAxis.endMove(0); + zAxis.attach(); + Serial.println(F("z axis zeroed")); + return; + } + } + + /* + If we get here, the probe failed to touch down + - print error + - STOP execution + */ + axis->endMove(endPos); + Serial.println(F("error: probe did not connect\nprogram stopped\nz axis not set\n")); + sys.stop = true; + } // end if zgoto != currentZPos / sys.inchesToMMConversion + + } else { + Serial.print(F("G38")); + Serial.print(readString.substring(3, 5)); + Serial.println(F(" is invalid. Only G38.2 recognized.")); + } + } else { + Serial.println(F("G38.2 gcode only valid with z-axis attached")); + } +} + +void setInchesToMillimetersConversion(float newConversionFactor){ + sys.inchesToMMConversion = newConversionFactor; +} diff --git a/Firmware_1.26b/cnc_ctrl_v1/GCode.h b/Firmware_1.26b/cnc_ctrl_v1/GCode.h new file mode 100644 index 00000000..d2cf12f4 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/GCode.h @@ -0,0 +1,50 @@ +/*This file is part of the Maslow Control Software. + +The Maslow Control Software is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +Maslow Control Software is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with the Maslow Control Software. If not, see . + +Copyright 2014-2017 Bar Smith*/ + +#ifndef gcode_h +#define gcode_h + +// Define line flags. Includes comment type tracking and line overflow detection. +#define LINE_FLAG_COMMENT_PARENTHESES bit(0) +#define LINE_FLAG_COMMENT_SEMICOLON bit(1) + +extern String readyCommandString; //next command queued up and ready to send +extern String gcodeLine; //The next individual line of gcode (for example G91 G01 X19 would be run as two lines) + +void initGCode(); +void gcodeExecuteLoop(); +void readSerialCommands(); +String gcodeBufferReadline(); +int findEndOfNumber(const String&, const int&); +float extractGcodeValue(const String&, char, const float&); +byte executeBcodeLine(const String&); +void executeGcodeLine(const String&); +void executeMcodeLine(const String&); +void executeOtherCodeLine(const String&); +int findNextGM(const String&, const int&); +void sanitizeCommandString(String&); +byte interpretCommandString(String&); +void G1(const String&, int); +void G2(const String&, int); +void G4(const String&); +void G10(const String&); +void G38(const String&); +void setInchesToMillimetersConversion(float); +extern int SpindlePowerControlPin; +extern int ProbePin; + +#endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/Kinematics.cpp b/Firmware_1.26b/cnc_ctrl_v1/Kinematics.cpp new file mode 100644 index 00000000..f5415ea3 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Kinematics.cpp @@ -0,0 +1,425 @@ +/*This file is part of the Maslow Control Software. + + The Maslow Control Software is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Maslow Control Software is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with the Maslow Control Software. If not, see . + + Copyright 2014-2017 Bar Smith*/ + +/* +The Kinematics module relates the lengths of the chains to the position of the cutting head +in X-Y space. +*/ + +#include "Maslow.h" + + +Kinematics::Kinematics(){ + recomputeGeometry(); +} + +void Kinematics::init(){ + recomputeGeometry(); + if (sys.state != STATE_OLD_SETTINGS){ + forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition, sys.xPosition, sys.yPosition); + } +} + +void Kinematics::_verifyValidTarget(float* xTarget,float* yTarget){ + //If the target point is beyond one of the edges of the board, the machine stops at the edge + + *xTarget = (*xTarget < -halfWidth) ? -halfWidth : (*xTarget > halfWidth) ? halfWidth : *xTarget; + *yTarget = (*yTarget < -halfHeight) ? -halfHeight : (*yTarget > halfHeight) ? halfHeight : *yTarget; + +} + +void Kinematics::recomputeGeometry(){ + /* + Some variables are computed on class creation for the geometry of the machine to reduce overhead, + calling this function regenerates those values. These are all floats so they take up + ~32bytes of RAM to keep them in memory. + */ + Phi = -0.2; + h = sqrt((sysSettings.sledWidth/2)*(sysSettings.sledWidth/2) + sysSettings.sledHeight * sysSettings.sledHeight); + Theta = atan(2*sysSettings.sledHeight/sysSettings.sledWidth); + Psi1 = Theta - Phi; + Psi2 = Theta + Phi; + + halfWidth = sysSettings.machineWidth / 2.0; + halfHeight = sysSettings.machineHeight / 2.0; + _xCordOfMotor = sysSettings.distBetweenMotors/2; + _yCordOfMotor = halfHeight + sysSettings.motorOffsetY; + +} + +void Kinematics::inverse(float xTarget,float yTarget, float* aChainLength, float* bChainLength){ + /* + + This function works as a switch to call either the quadrilateralInverse kinematic function + or the triangularInverse kinematic function + + */ + + if(sysSettings.kinematicsType == 1){ + quadrilateralInverse(xTarget, yTarget, aChainLength, bChainLength); + } + else{ + triangularInverse(xTarget, yTarget, aChainLength, bChainLength); + } + +} + +void Kinematics::quadrilateralInverse(float xTarget,float yTarget, float* aChainLength, float* bChainLength){ + + //Confirm that the coordinates are on the wood + _verifyValidTarget(&xTarget, &yTarget); + + //coordinate shift to put (0,0) in the center of the plywood from the left sprocket + y = (halfHeight) + sysSettings.motorOffsetY - yTarget; + x = (sysSettings.distBetweenMotors/2.0) + xTarget; + + //Coordinates definition: + // x -->, y | + // v + // (0,0) at center of left sprocket + // upper left corner of plywood (270, 270) + + byte Tries = 0; //initialize + if(x > sysSettings.distBetweenMotors/2.0){ //the right half of the board mirrors the left half so all computations are done using left half coordinates. + x = sysSettings.distBetweenMotors-x; //Chain lengths are swapped at exit if the x,y is on the right half + Mirror = true; + } + else{ + Mirror = false; + } + + TanGamma = y/x; + TanLambda = y/(sysSettings.distBetweenMotors-x); + Y1Plus = R * sqrt(1 + TanGamma * TanGamma); + Y2Plus = R * sqrt(1 + TanLambda * TanLambda); + + + while (Tries <= KINEMATICSMAXINVERSE) { + + _MyTrig(); + //These criteria will be zero when the correct values are reached + //They are negated here as a numerical efficiency expedient + + Crit[0]= - _moment(Y1Plus, Y2Plus, MySinPhi, SinPsi1, CosPsi1, SinPsi2, CosPsi2); + Crit[1] = - _YOffsetEqn(Y1Plus, x - h * CosPsi1, SinPsi1); + Crit[2] = - _YOffsetEqn(Y2Plus, sysSettings.distBetweenMotors - (x + h * CosPsi2), SinPsi2); + + if (abs(Crit[0]) < KINEMATICSMAXERROR) { + if (abs(Crit[1]) < KINEMATICSMAXERROR) { + if (abs(Crit[2]) < KINEMATICSMAXERROR){ + break; + } + } + } + + //estimate the tilt angle that results in zero net _moment about the pen + //and refine the estimate until the error is acceptable or time runs out + + //Estimate the Jacobian components + + Jac[0] = (_moment( Y1Plus, Y2Plus, MySinPhiDelta, SinPsi1D, CosPsi1D, SinPsi2D, CosPsi2D) + Crit[0])/DELTAPHI; + Jac[1] = (_moment( Y1Plus + DELTAY, Y2Plus, MySinPhi, SinPsi1, CosPsi1, SinPsi2, CosPsi2) + Crit[0])/DELTAY; + Jac[2] = (_moment(Y1Plus, Y2Plus + DELTAY, MySinPhi, SinPsi1, CosPsi1, SinPsi2, CosPsi2) + Crit[0])/DELTAY; + Jac[3] = (_YOffsetEqn(Y1Plus, x - h * CosPsi1D, SinPsi1D) + Crit[1])/DELTAPHI; + Jac[4] = (_YOffsetEqn(Y1Plus + DELTAY, x - h * CosPsi1,SinPsi1) + Crit[1])/DELTAY; + Jac[5] = 0.0; + Jac[6] = (_YOffsetEqn(Y2Plus, sysSettings.distBetweenMotors - (x + h * CosPsi2D), SinPsi2D) + Crit[2])/DELTAPHI; + Jac[7] = 0.0; + Jac[8] = (_YOffsetEqn(Y2Plus + DELTAY, sysSettings.distBetweenMotors - (x + h * CosPsi2D), SinPsi2) + Crit[2])/DELTAY; + + + //solve for the next guess + _MatSolv(); // solves the matrix equation Jx=-Criterion + + // update the variables with the new estimate + + Phi = Phi + Solution[0]; + Y1Plus = Y1Plus + Solution[1]; //don't allow the anchor points to be inside a sprocket + Y1Plus = (Y1Plus < R) ? R : Y1Plus; + + Y2Plus = Y2Plus + Solution[2]; //don't allow the anchor points to be inside a sprocke + Y2Plus = (Y2Plus < R) ? R : Y2Plus; + + Psi1 = Theta - Phi; + Psi2 = Theta + Phi; + + Tries++; // increment itteration count + + } + + //Variables are within accuracy limits + // perform output computation + + Offsetx1 = h * CosPsi1; + Offsetx2 = h * CosPsi2; + Offsety1 = h * SinPsi1; + Offsety2 = h * SinPsi2; + TanGamma = (y - Offsety1 + Y1Plus)/(x - Offsetx1); + TanLambda = (y - Offsety2 + Y2Plus)/(sysSettings.distBetweenMotors -(x + Offsetx2)); + Gamma = atan(TanGamma); + Lambda =atan(TanLambda); + + //compute the chain lengths + + if(Mirror){ + Chain2 = sqrt((x - Offsetx1)*(x - Offsetx1) + (y + Y1Plus - Offsety1)*(y + Y1Plus - Offsety1)) - R * TanGamma + R * Gamma; //right chain length + Chain1 = sqrt((sysSettings.distBetweenMotors - (x + Offsetx2))*(sysSettings.distBetweenMotors - (x + Offsetx2))+(y + Y2Plus - Offsety2)*(y + Y2Plus - Offsety2)) - R * TanLambda + R * Lambda; //left chain length + } + else{ + Chain1 = sqrt((x - Offsetx1)*(x - Offsetx1) + (y + Y1Plus - Offsety1)*(y + Y1Plus - Offsety1)) - R * TanGamma + R * Gamma; //left chain length + Chain2 = sqrt((sysSettings.distBetweenMotors - (x + Offsetx2))*(sysSettings.distBetweenMotors - (x + Offsetx2))+(y + Y2Plus - Offsety2)*(y + Y2Plus - Offsety2)) - R * TanLambda + R * Lambda; //right chain length + } + + *aChainLength = Chain1; + *bChainLength = Chain2; + +} + +void Kinematics::triangularInverse(float xTarget,float yTarget, float* aChainLength, float* bChainLength){ + /* + + The inverse kinematics (relating an xy coordinate pair to the required chain lengths to hit that point) + function for a triangular set up where the chains meet at a point, or are arranged so that they simulate + meeting at a point. + + */ + + //Confirm that the coordinates are on the wood + _verifyValidTarget(&xTarget, &yTarget); + + //Set up variables + float Chain1Angle = 0; + float Chain2Angle = 0; + float Chain1AroundSprocket = 0; + float Chain2AroundSprocket = 0; + + //Calculate motor axes length to the bit + float Motor1Distance = sqrt(pow((-1*_xCordOfMotor - xTarget),2)+pow((_yCordOfMotor - yTarget),2)); + float Motor2Distance = sqrt(pow((_xCordOfMotor - xTarget),2)+pow((_yCordOfMotor - yTarget),2)); + + //Calculate the chain angles from horizontal, based on if the chain connects to the sled from the top or bottom of the sprocket + if(sysSettings.chainOverSprocket == 1){ + Chain1Angle = asin((_yCordOfMotor - yTarget)/Motor1Distance) + asin(R/Motor1Distance); + Chain2Angle = asin((_yCordOfMotor - yTarget)/Motor2Distance) + asin(R/Motor2Distance); + + Chain1AroundSprocket = R * Chain1Angle; + Chain2AroundSprocket = R * Chain2Angle; + } + else{ + Chain1Angle = asin((_yCordOfMotor - yTarget)/Motor1Distance) - asin(R/Motor1Distance); + Chain2Angle = asin((_yCordOfMotor - yTarget)/Motor2Distance) - asin(R/Motor2Distance); + + Chain1AroundSprocket = R * (3.14159 - Chain1Angle); + Chain2AroundSprocket = R * (3.14159 - Chain2Angle); + } + + //Calculate the straight chain length from the sprocket to the bit + float Chain1Straight = sqrt(pow(Motor1Distance,2)-pow(R,2)); + float Chain2Straight = sqrt(pow(Motor2Distance,2)-pow(R,2)); + + //Correct the straight chain lengths to account for chain sag + Chain1Straight *= (1 + ((sysSettings.chainSagCorrection / 1000000000000) * pow(cos(Chain1Angle),2) * pow(Chain1Straight,2) * pow((tan(Chain2Angle) * cos(Chain1Angle)) + sin(Chain1Angle),2))); + Chain2Straight *= (1 + ((sysSettings.chainSagCorrection / 1000000000000) * pow(cos(Chain2Angle),2) * pow(Chain2Straight,2) * pow((tan(Chain1Angle) * cos(Chain2Angle)) + sin(Chain2Angle),2))); + + //Calculate total chain lengths accounting for sprocket geometry and chain sag + float Chain1 = Chain1AroundSprocket + Chain1Straight / (1.0f + sysSettings.leftChainTolerance / 100.0f); + float Chain2 = Chain2AroundSprocket + Chain2Straight / (1.0f + sysSettings.rightChainTolerance / 100.0f); + + //Subtract of the virtual length which is added to the chain by the rotation mechanism + Chain1 = Chain1 - sysSettings.rotationDiskRadius; + Chain2 = Chain2 - sysSettings.rotationDiskRadius; + + *aChainLength = Chain1; + *bChainLength = Chain2; +} + +void Kinematics::forward(const float& chainALength, const float& chainBLength, float* xPos, float* yPos, float xGuess, float yGuess){ + + Serial.println(F("[Forward Calculating Position]")); + + + float guessLengthA; + float guessLengthB; + + int guessCount = 0; + + while(1){ + + + //check our guess + inverse(xGuess, yGuess, &guessLengthA, &guessLengthB); + + float aChainError = chainALength - guessLengthA; + float bChainError = chainBLength - guessLengthB; + + + //adjust the guess based on the result + xGuess = xGuess + .1*aChainError - .1*bChainError; + yGuess = yGuess - .1*aChainError - .1*bChainError; + + guessCount++; + + #if defined (KINEMATICSDBG) && KINEMATICSDBG > 0 + Serial.print(F("[PEk:")); + Serial.print(aChainError); + Serial.print(','); + Serial.print(bChainError); + Serial.print(','); + Serial.print('0'); + Serial.println(F("]")); + #endif + + execSystemRealtime(); + // No need for sys.stop check here + + //if we've converged on the point...or it's time to give up, exit the loop + if((abs(aChainError) < .1 && abs(bChainError) < .1) or guessCount > KINEMATICSMAXGUESS or guessLengthA > sysSettings.chainLength or guessLengthB > sysSettings.chainLength){ + if((guessCount > KINEMATICSMAXGUESS) or guessLengthA > sysSettings.chainLength or guessLengthB > sysSettings.chainLength){ + Serial.print(F("Message: Unable to find valid machine position for chain lengths ")); + Serial.print(chainALength); + Serial.print(", "); + Serial.print(chainBLength); + Serial.println(F(" . Please set the chains to a known length (Actions -> Set Chain Lengths)")); + *xPos = 0; + *yPos = 0; + } + else{ + Serial.println("position loaded at:"); + Serial.println(xGuess); + Serial.println(yGuess); + *xPos = xGuess; + *yPos = yGuess; + } + break; + } + } +} + +void Kinematics::_MatSolv(){ + float Sum; + int NN; + int i; + int ii; + int J; + int JJ; + int K; + int KK; + int L; + int M; + int N; + + float fact; + + // gaus elimination, no pivot + + N = 3; + NN = N-1; + for (i=1;i<=NN;i++){ + J = (N+1-i); + JJ = (J-1) * N-1; + L = J-1; + KK = -1; + for (K=0;K. + + Copyright 2014-2017 Bar Smith*/ + + #ifndef Kinematics_h + #define Kinematics_h + + + //Calculation tolerances + #define DELTAPHI 0.001 + #define DELTAY 0.01 + #define KINEMATICSMAXERROR 0.001 + #define KINEMATICSMAXINVERSE 10 + #define KINEMATICSMAXGUESS 200 + + class Kinematics{ + public: + Kinematics(); + void init (); + void inverse (float xTarget,float yTarget, float* aChainLength, float* bChainLength); + void quadrilateralInverse (float xTarget,float yTarget, float* aChainLength, float* bChainLength); + void triangularInverse (float xTarget,float yTarget, float* aChainLength, float* bChainLength); + void recomputeGeometry(); + void forward(const float& chainALength, const float& chainBLength, float* xPos, float* yPos, float xGuess, float yGuess); + //geometry + float h; //distance between sled attach point and bit + float R = 10.1; //sprocket radius + + float halfWidth; //Half the machine width + float halfHeight; //Half the machine height + private: + float _moment(const float& Y1Plus, const float& Y2Plus, const float& MSinPhi, const float& MSinPsi1, const float& MCosPsi1, const float& MSinPsi2, const float& MCosPsi2); + float _YOffsetEqn(const float& YPlus, const float& Denominator, const float& Psi); + void _MatSolv(); + void _MyTrig(); + void _verifyValidTarget(float* xTarget,float* yTarget); + //target router bit coordinates. + float x = 0; + float y = 0; + float _xCordOfMotor; + float _yCordOfMotor; + + //utility variables + boolean Mirror; + + //Criterion Computation Variables + float Phi = -0.2; + float TanGamma; + float TanLambda; + float Y1Plus ; + float Y2Plus; + float Theta; + float Psi1 = Theta - Phi; + float Psi2 = Theta + Phi; + float Jac[9]; + float Solution[3]; + float Crit[3]; + float Offsetx1; + float Offsetx2; + float Offsety1; + float Offsety2; + float SinPsi1; + float CosPsi1; + float SinPsi2; + float CosPsi2; + float SinPsi1D; + float CosPsi1D; + float SinPsi2D; + float CosPsi2D; + float MySinPhi; + float MySinPhiDelta; + + //intermediate output + float Lambda; + float Gamma; + + // Motor axes length to the bit for triangular kinematics + float Motor1Distance; //left motor axis distance to sled + float Motor2Distance; //right motor axis distance to sled + + // output = chain lengths measured from 12 o'clock + float Chain1; //left chain length + float Chain2; //right chain length + }; + + #endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/Maslow.h b/Firmware_1.26b/cnc_ctrl_v1/Maslow.h new file mode 100644 index 00000000..8380a13e --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Maslow.h @@ -0,0 +1,52 @@ +/*This file is part of the Maslow Control Software. + The Maslow Control Software is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + Maslow Control Software is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + You should have received a copy of the GNU General Public License + along with the Maslow Control Software. If not, see . + + Copyright 2014-2017 Bar Smith*/ + +// This is the main maslow include file + +#ifndef maslow_h +#define maslow_h + +// Maslow Firmware Version tracking +#define VERSIONNUMBER 1.26 + +// Define standard libraries used by maslow. +#include +#include +#include +#include + +// Define the maslow system include files. This ensures that dependencies are +// loaded in the proper order. Be careful moving these around. +#include "Config.h" +#include "TimerOne.h" +#include "Motor.h" +#include "PID_v1.h" +#include "utility/direct_pin_read.h" +#include "Encoder.h" +#include "MotorGearboxEncoder.h" +#include "Axis.h" +#include "Kinematics.h" +#include "RingBuffer.h" +#include "GCode.h" +#include "Testing.h" +#include "Motion.h" +#include "Report.h" +#include "Spindle.h" +#include "Probe.h" +#include "Settings.h" +#include "NutsAndBolts.h" +#include "System.h" +#include "SimavrSerial.h" + +#endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/Motion.cpp b/Firmware_1.26b/cnc_ctrl_v1/Motion.cpp new file mode 100644 index 00000000..358dc222 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Motion.cpp @@ -0,0 +1,376 @@ +/*This file is part of the Maslow Control Software. + The Maslow Control Software is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + Maslow Control Software is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + You should have received a copy of the GNU General Public License + along with the Maslow Control Software. If not, see . + + Copyright 2014-2017 Bar Smith*/ + +// This contains all of the Motion commands + +#include "Maslow.h" + +// Flag for when to send movement commands +volatile bool movementUpdated = false; +// Global variables for misloop tracking +#if misloopDebug > 0 + volatile bool inMovementLoop = false; + volatile bool movementFail = false; +#endif + +void initMotion(){ + // Called on startup or after a stop command + leftAxis.stop(); + rightAxis.stop(); + if(sysSettings.zAxisAttached){ + zAxis.stop(); + } +} + + +float calculateFeedrate(const float& stepSizeMM, const float& usPerStep){ + /* + Calculate the time delay between each step for a given feedrate + */ + + #define MINUTEINUS 60000000.0 + + // derivation: ms / step = 1 min in ms / dist in one min + + float tempFeedrate = (stepSizeMM*MINUTEINUS)/usPerStep; + + return tempFeedrate; +} + +float computeStepSize(const float& MMPerMin){ + /* + + Determines the minimum step size which can be taken for the given feed-rate + based on the loop interval frequency. Converts to MM per microsecond first, + then mutiplies by the number of microseconds in each loop interval + + */ + return LOOPINTERVAL*(MMPerMin/(60 * 1000000)); +} + +void movementUpdate(){ + #if misloopDebug > 0 + if (movementFail){ + Serial.println("Movement loop failed to complete before interrupt."); + movementFail = false; + } + #endif + movementUpdated = true; +} + + +// why does this return anything +int coordinatedMove(const float& xEnd, const float& yEnd, const float& zEnd, float MMPerMin){ + + /*The move() function moves the tool in a straight line to the position (xEnd, yEnd) at + the speed moveSpeed. Movements are correlated so that regardless of the distances moved in each + direction, the tool moves to the target in a straight line. This function is used by the G00 + and G01 commands. The units at this point should all be in mm or mm per minute*/ + + float xStartingLocation = sys.xPosition; + float yStartingLocation = sys.yPosition; + float zStartingLocation = zAxis.read(); // I don't know why we treat the zaxis differently + float zMaxFeed = sysSettings.maxZRPM * abs(zAxis.getPitch()); + + //find the total distances to move + float distanceToMoveInMM = sqrt( sq(xEnd - xStartingLocation) + sq(yEnd - yStartingLocation) + sq(zEnd - zStartingLocation)); + float xDistanceToMoveInMM = xEnd - xStartingLocation; + float yDistanceToMoveInMM = yEnd - yStartingLocation; + float zDistanceToMoveInMM = zEnd - zStartingLocation; + + //compute feed details + MMPerMin = constrain(MMPerMin, 1, sysSettings.maxFeed); //constrain the maximum feedrate, 35ipm = 900 mmpm + float stepSizeMM = computeStepSize(MMPerMin); + float finalNumberOfSteps = abs(distanceToMoveInMM/stepSizeMM); + float delayTime = LOOPINTERVAL; + float zFeedrate = calculateFeedrate(fabs(zDistanceToMoveInMM/finalNumberOfSteps), delayTime); + + //throttle back federate if it exceeds zaxis max + if (zFeedrate > zMaxFeed){ + float zStepSizeMM = computeStepSize(zMaxFeed); + finalNumberOfSteps = abs(zDistanceToMoveInMM/zStepSizeMM); + stepSizeMM = (distanceToMoveInMM/finalNumberOfSteps); + MMPerMin = calculateFeedrate(stepSizeMM, delayTime); + } + + // (fraction of distance in x direction)* size of step toward target + float xStepSize = (xDistanceToMoveInMM/finalNumberOfSteps); + float yStepSize = (yDistanceToMoveInMM/finalNumberOfSteps); + float zStepSize = (zDistanceToMoveInMM/finalNumberOfSteps); + + //attach the axes + leftAxis.attach(); + rightAxis.attach(); + if(sysSettings.zAxisAttached){ + zAxis.attach(); + } + + float aChainLength; + float bChainLength; + float zPosition = zStartingLocation; + long numberOfStepsTaken = 0; + + while(numberOfStepsTaken < finalNumberOfSteps){ + + #if misloopDebug > 0 + inMovementLoop = true; + #endif + //if last movment was performed start the next + if (!movementUpdated) { + //find the target point for this step + // This section ~20us + sys.xPosition += xStepSize; + sys.yPosition += yStepSize; + zPosition += zStepSize; + + //find the chain lengths for this step + // This section ~180us + kinematics.inverse(sys.xPosition,sys.yPosition,&aChainLength,&bChainLength); + + //write to each axis + // This section ~180us + leftAxis.write(aChainLength); + rightAxis.write(bChainLength); + if(sysSettings.zAxisAttached){ + zAxis.write(zPosition); + } + + movementUpdate(); + + //increment the number of steps taken + numberOfStepsTaken++; + + // Run realtime commands + execSystemRealtime(); + if (sys.stop){return 1;} + } + } + #if misloopDebug > 0 + inMovementLoop = false; + #endif + + kinematics.inverse(xEnd,yEnd,&aChainLength,&bChainLength); + leftAxis.endMove(aChainLength); + rightAxis.endMove(bChainLength); + if(sysSettings.zAxisAttached){ + zAxis.endMove(zPosition); + } + + sys.xPosition = xEnd; + sys.yPosition = yEnd; + + return 1; + +} + +void singleAxisMove(Axis* axis, const float& endPos, const float& MMPerMin){ + /* + Takes a pointer to an axis object and moves that axis to endPos at speed MMPerMin + */ + + float startingPos = axis->read(); + float moveDist = endPos - startingPos; //total distance to move + + float direction = moveDist/abs(moveDist); //determine the direction of the move + + float stepSizeMM = computeStepSize(MMPerMin); //step size in mm + + //the argument to abs should only be a variable -- splitting calc into 2 lines + long finalNumberOfSteps = abs(moveDist/stepSizeMM); //number of steps taken in move + finalNumberOfSteps = abs(finalNumberOfSteps); + stepSizeMM = stepSizeMM*direction; + + long numberOfStepsTaken = 0; + + //attach the axis we want to move + axis->attach(); + + float whereAxisShouldBeAtThisStep = startingPos; + #if misloopDebug > 0 + inMovementLoop = true; + #endif + while(numberOfStepsTaken < finalNumberOfSteps){ + if (!movementUpdated) { + //find the target point for this step + whereAxisShouldBeAtThisStep += stepSizeMM; + + //write to axis + axis->write(whereAxisShouldBeAtThisStep); + movementUpdate(); + + // Run realtime commands + execSystemRealtime(); + if (sys.stop){return;} + + //increment the number of steps taken + numberOfStepsTaken++; + } + } + #if misloopDebug > 0 + inMovementLoop = false; + #endif + + axis->endMove(endPos); + +} + +// return the sign of the parameter +int sign(double x) { return x<0 ? -1 : 1; } + +// why does this return anything +int arc(const float& X1, const float& Y1, const float& Z1, const float& X2, const float& Y2, const float& Z2, const float& centerX, const float& centerY, const float& MMPerMin, const float& direction){ + /* + + Move the machine through an arc from point (X1, Y1) to point (X2, Y2) along the + arc defined by center (centerX, centerY) at speed MMPerMin + + */ + + //compute geometry + float pi = 3.1415; + float radius = sqrt( sq(centerX - X1) + sq(centerY - Y1) ); + float circumference = 2.0*pi*radius; + + float startingAngle = atan2(Y1 - centerY, X1 - centerX); + float endingAngle = atan2(Y2 - centerY, X2 - centerX); + + // compute chord height of arc + float chordSquared = sqrt(sq(X2 - X1) + sq(Y2 - Y1)); + float tau = sqrt( sq(radius) - (chordSquared/4.0)); + float chordHeight = radius - tau; + + //compute angle between lines + float theta = endingAngle - startingAngle; + if (direction == COUNTERCLOCKWISE){ + if (theta <= 0){ + theta += 2*pi; + } + } + else { + //CLOCKWISE + if (theta >= 0){ + theta -= 2*pi; + } + } + if ((sign(theta) != sign(direction)) || ((abs(chordHeight) < .01) && (abs(theta) < 0.5)) || (radius > 25400)) { + // There is a parameter error in this line of gcode, either in the size of the angle calculated + // or the chord height of the arc between the starting and ending points + // In either case, the gcode cut was essentially a straight line, so + // Replace it with a G1 cut to the endpoint + String gcodeSubstitution = "G1 X"; + gcodeSubstitution = gcodeSubstitution + String(X2 / sys.inchesToMMConversion, 3) + " Y" + String(Y2 / sys.inchesToMMConversion, 3) + " Z" + String(Z2 / sys.inchesToMMConversion, 3) + " "; + Serial.println("Large-radius arc replaced by straight line to improve accuracy: " + gcodeSubstitution); + G1(gcodeSubstitution, 1); + return 1; + } + + float arcLengthMM = fabs(circumference * (theta / (2*pi) )); + float zDistanceToMoveInMM = Z2 - Z1; + + //set up variables for movement + long numberOfStepsTaken = 0; + + float feedMMPerMin = constrain(MMPerMin, 1, sysSettings.maxFeed); + float stepSizeMM = computeStepSize(feedMMPerMin); + + long finalNumberOfSteps = arcLengthMM/stepSizeMM; + float delayTime = LOOPINTERVAL; + + float zFeedRate = calculateFeedrate(fabs(zDistanceToMoveInMM/finalNumberOfSteps), delayTime); + float zMaxFeed = sysSettings.maxZRPM * abs(zAxis.getPitch()); + // float zStepSizeMM = computeStepSize(zMaxFeed); + float zStepSizeMM = zDistanceToMoveInMM/finalNumberOfSteps; + + if (zFeedRate > zMaxFeed){ + zStepSizeMM = computeStepSize(zMaxFeed); + finalNumberOfSteps = fabs(zDistanceToMoveInMM/zStepSizeMM); + stepSizeMM = arcLengthMM/finalNumberOfSteps; + feedMMPerMin = calculateFeedrate(stepSizeMM, delayTime); + } + + zStepSizeMM = zDistanceToMoveInMM/finalNumberOfSteps; + + //Compute the starting position + float angleNow = startingAngle; + float degreeComplete = 0.0; + + float aChainLength; + float bChainLength; + float zPosition = Z1 + zStepSizeMM; + + //attach the axes + leftAxis.attach(); + rightAxis.attach(); + if (sysSettings.zAxisAttached) { + zAxis.attach(); + } + + while(numberOfStepsTaken < abs(finalNumberOfSteps)){ + #if misloopDebug > 0 + inMovementLoop = true; + #endif + + //if last movement was performed start the next one + if (!movementUpdated){ + + degreeComplete = float(numberOfStepsTaken)/float(finalNumberOfSteps); + + angleNow = startingAngle + theta*degreeComplete; + + sys.xPosition = radius * cos(angleNow) + centerX; + sys.yPosition = radius * sin(angleNow) + centerY; + + kinematics.inverse(sys.xPosition,sys.yPosition,&aChainLength,&bChainLength); + + leftAxis.write(aChainLength); + rightAxis.write(bChainLength); + if(sysSettings.zAxisAttached){ + zAxis.write(zPosition); + } + movementUpdate(); + + // Run realtime commands + execSystemRealtime(); + if (sys.stop){return 1;} + + numberOfStepsTaken++; + zPosition += zStepSizeMM; + } + } + #if misloopDebug > 0 + inMovementLoop = false; + #endif + + kinematics.inverse(X2,Y2,&aChainLength,&bChainLength); + leftAxis.endMove(aChainLength); + rightAxis.endMove(bChainLength); + + sys.xPosition = X2; + sys.yPosition = Y2; + + return 1; +} + +void motionDetachIfIdle(){ + /* + + This function is called every time the main loop runs. When the machine is executing a move it is not called, but when the machine is + not executing a line it is called regularly and causes the motors to hold their positions. + + */ + + leftAxis.detachIfIdle(); + rightAxis.detachIfIdle(); + zAxis.detachIfIdle(); +} diff --git a/Firmware_1.26b/cnc_ctrl_v1/Motion.h b/Firmware_1.26b/cnc_ctrl_v1/Motion.h new file mode 100644 index 00000000..b2aa62a1 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Motion.h @@ -0,0 +1,36 @@ +/*This file is part of the Maslow Control Software. + The Maslow Control Software is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + Maslow Control Software is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + You should have received a copy of the GNU General Public License + along with the Maslow Control Software. If not, see . + + Copyright 2014-2017 Bar Smith*/ + +// This contains all of the Motion commands + +#ifndef motion_h +#define motion_h + +// These are used for movement tracking and need to be available to the ISR +extern volatile bool movementUpdated; +#if misloopDebug > 0 + extern volatile bool inMovementLoop; + extern volatile bool movementFail; +#endif + +void initMotion(); +int coordinatedMove(const float&, const float&, const float&, float); +void singleAxisMove(Axis*, const float&, const float&); +int arc(const float&, const float&, const float&, const float&, const float&, const float&, const float&, const float&, const float&, const float&); +float calculateFeedrate(const float&, const float&); +float computeStepSize(const float&); +void movementUpdate(); +void motionDetachIfIdle(); + +#endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/Motor.cpp b/Firmware_1.26b/cnc_ctrl_v1/Motor.cpp new file mode 100644 index 00000000..0833a66f --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Motor.cpp @@ -0,0 +1,227 @@ +/*This file is part of the Maslow Control Software. + + The Maslow Control Software is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Maslow Control Software is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with the Maslow Control Software. If not, see . + + Copyright 2014-2017 Bar Smith*/ + +/* +The Motor module imitates the behavior of the Arduino servo module. It allows a gear motor (or any electric motor) +to be a drop in replacement for a continuous rotation servo. + +*/ + +#include "Maslow.h" + +Motor::Motor(){ + + _attachedState = 0; + + +} + +int Motor::setupMotor(const int& pwmPin, const int& pin1, const int& pin2){ + + //store pin numbers as private variables + _pwmPin = pwmPin; + _pin1 = pin1; + _pin2 = pin2; + _attachedState = 0; + + if (TLE5206 == true ) { + // EBS v1.4 + pinMode(_pwmPin, INPUT); + pinMode(_pin1, OUTPUT); + pinMode(_pin2, OUTPUT); + + //stop the motor + digitalWrite(_pin1, LOW); + digitalWrite(_pin2, LOW) ; + } + else if (TB6643 == true ) { + // EBS V1.5 + pinMode(_pwmPin, INPUT); + pinMode(_pin1, OUTPUT); + pinMode(_pin2, OUTPUT); + + //stop the motor + digitalWrite(_pin1, LOW); + digitalWrite(_pin2, LOW); + } + else { + // V1.2 + //set pinmodes + pinMode(_pwmPin, OUTPUT); + pinMode(_pin1, OUTPUT); + pinMode(_pin2, OUTPUT); + + //stop the motor + digitalWrite(_pin1, HIGH); + digitalWrite(_pin2, LOW) ; + digitalWrite(_pwmPin, LOW); + } + return 1; +} + +void Motor::attach(){ + _attachedState = 1; +} + +void Motor::detach(){ + _attachedState = 0; + + if (TLE5206 == true) { + //stop the motor + digitalWrite(_pin1, LOW); + digitalWrite(_pin2, LOW) ; + } + else if (TB6643 == true){ + //stop the motor + digitalWrite(_pin1, LOW); + digitalWrite(_pin2, LOW) ; + } + else { + //stop the motor + digitalWrite(_pin1, HIGH); + digitalWrite(_pin2, LOW) ; + digitalWrite(_pwmPin, LOW); + } +} + + +int Motor::lastSpeed(){ + /* + Returns the last speed(voltage) value sent to the pwm + */ + return _lastSpeed; +} + +void Motor::additiveWrite(int speed){ + /* + Increases/decreases the motor speed by the passed speed amount + */ + write(_lastSpeed + speed); +} + +void Motor::write(int speed, bool force){ + /* + Sets motor speed from input. Speed = 0 is stopped, -255 is full reverse, 255 is full ahead. If force is true the motor attached state will be ignored + */ + if (_attachedState == 1 or force){ + speed = constrain(speed, -255, 255); + _lastSpeed = speed; //saves speed for use in additive write + bool forward = (speed > 0); + speed = abs(speed); //remove sign from input because direction is set by control pins on H-bridge + + bool usePin1 = ((_pin1 != 4) && (_pin1 != 13) && (_pin1 != 11) && (_pin1 != 12)); // avoid PWM using timer0 or timer1 + bool usePin2 = ((_pin2 != 4) && (_pin2 != 13) && (_pin2 != 11) && (_pin2 != 12)); // avoid PWM using timer0 or timer1 + bool usepwmPin = ((TLE5206 == false) && (_pwmPin != 4) && (_pwmPin != 13) && (_pwmPin != 11) && (_pwmPin != 12)); // avoid PWM using timer0 or timer1 + if (TLE5206) { + if (forward) { + if (speed > 0) { + if (usePin2) { + digitalWrite(_pin1 , HIGH ); + analogWrite(_pin2 , 255 - speed); // invert drive signals - don't alter speed + } + else { + analogWrite(_pin1 , speed); + digitalWrite(_pin2 , LOW ); + } + } + else { // speed = 0 so put on the brakes + digitalWrite(_pin1 , HIGH ); + digitalWrite(_pin2 , HIGH ); + } + } + else { // reverse + if (usePin1) { + analogWrite(_pin1 , 255 - speed); // invert drive signals - don't alter speed + digitalWrite(_pin2 , HIGH ); + } else { + analogWrite(_pin2 , speed); + digitalWrite(_pin1 , LOW ); + } + } + } + else if (TB6643) { //EBS 1.5 + if (forward) { + if (speed > 0) { + analogWrite(_pin1 , speed); + digitalWrite(_pin2 , LOW); + } else { // speed = 0 so put on the brakes + digitalWrite(_pin1 , HIGH); + digitalWrite(_pin2 , HIGH); + } + } else { // reverse + digitalWrite(_pin1 , LOW); + analogWrite(_pin2 , speed); + } + } + else { // V1.2 + if (forward){ + if (usepwmPin){ + digitalWrite(_pin1 , HIGH ); + digitalWrite(_pin2 , LOW ); + analogWrite(_pwmPin, speed); + } + else if (usePin2) { + digitalWrite(_pin1 , HIGH ); + analogWrite(_pin2 , 255 - speed); // invert drive signals - don't alter speed + digitalWrite(_pwmPin, HIGH); + } + else{ + analogWrite(_pin1 , speed); + digitalWrite(_pin2 , LOW ); + digitalWrite(_pwmPin, HIGH); + } + } + else { // reverse or zero speed + if (usepwmPin){ + digitalWrite(_pin2 , HIGH); + digitalWrite(_pin1 , LOW ); + analogWrite(_pwmPin, speed); + } + else if (usePin1) { + analogWrite(_pin1 , 255 - speed); // invert drive signals - don't alter speed + digitalWrite(_pin2 , HIGH ); + digitalWrite(_pwmPin, HIGH); + } + else { + analogWrite(_pin2 , speed); + digitalWrite(_pin1 , LOW ); + digitalWrite(_pwmPin, HIGH); + } + } + } + + } +} + + + + + + + + +void Motor::directWrite(int voltage){ + /* + Write directly to the motor, ignoring if the axis is attached or any applied calibration. + */ + write(voltage, true); +} + +int Motor::attached(){ + + return _attachedState; +} diff --git a/Firmware_1.26b/cnc_ctrl_v1/Motor.h b/Firmware_1.26b/cnc_ctrl_v1/Motor.h new file mode 100644 index 00000000..c393ec89 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Motor.h @@ -0,0 +1,54 @@ + /*This file is part of the Makesmith Control Software. + + The Makesmith Control Software is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Makesmith Control Software is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with the Makesmith Control Software. If not, see . + + Copyright 2014-2017 Bar Smith*/ + + #ifndef Motor_h + #define Motor_h + + struct LinSegment{ + float slope = 1; + float intercept = 0; + //The bounds are strict, so if the bounds are 0,1 .9 would work + //but 1 and 0 will not + int positiveBound = 0; + int negativeBound = 0; + }; + + + + class Motor{ + public: + Motor(); + void attach(); + int setupMotor(const int& pwmPin, const int& pin1, const int& pin2); + void detach(); + void write(int speed, bool force = false); + int lastSpeed(); + void additiveWrite(int speed); + int attached(); + void directWrite(int voltage); + private: + int _pwmPin; + int _pin1; + int _pin2; + bool _attachedState = false; + LinSegment _linSegments[4]; + int _lastSpeed = 0; + + }; + extern bool TLE5206; + extern bool TB6643; + #endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/MotorGearboxEncoder.cpp b/Firmware_1.26b/cnc_ctrl_v1/MotorGearboxEncoder.cpp new file mode 100644 index 00000000..d5befc9d --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/MotorGearboxEncoder.cpp @@ -0,0 +1,205 @@ +/*This file is part of the Maslow Control Software. + + The Maslow Control Software is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Maslow Control Software is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with the Maslow Control Software. If not, see . + + Copyright 2014-2017 Bar Smith*/ + +/* +The Motor module imitates the behavior of the Arduino servo module. It allows a gear motor (or any electric motor) +to be a drop in replacement for a continuous rotation servo. + +*/ + +#include "Maslow.h" + +void MotorGearboxEncoder::setup(const int& pwmPin, const int& directionPin1, const int& directionPin2, const int& encoderPin1, const int& encoderPin2, const unsigned long& loopInterval) +{ + //initialize encoder + encoder.setup(encoderPin1,encoderPin2); + // I don't like this, but I don't know how else to initialize a pointer to a value + float zero = 0.0; + float one = 1.0; + _Kp = _Ki = _Kd = &zero; + + //initialize motor + motor.setupMotor(pwmPin, directionPin1, directionPin2); + motor.write(0); + + //initialize the PID + _PIDController.setup(&_currentSpeed, &_pidOutput, &_targetSpeed, _Kp, _Ki, _Kd, &one, DIRECT); + initializePID(loopInterval); + + +} + +void MotorGearboxEncoder::write(const float& speed){ + /* + Command the motor to turn at the given speed. Should be RPM is PWM right now. + */ + + _targetSpeed = speed; + +} + +void MotorGearboxEncoder::initializePID(const unsigned long& loopInterval){ + //setup positive PID controller + _PIDController.SetMode(AUTOMATIC); + _PIDController.SetOutputLimits(-255, 255); + _PIDController.SetSampleTime(loopInterval / 1000); +} + +void MotorGearboxEncoder::computePID(){ + /* + Recompute the speed control PID loop and command the motor to move. + */ + _currentSpeed = computeSpeed(); + + _PIDController.Compute(); + + motor.additiveWrite(_pidOutput); +} + +void MotorGearboxEncoder::setPIDValues(float* KpV, float* KiV, float* KdV, float* propWeightV){ + /* + + Set PID tuning values + + */ + + _Kp = KpV; + _Ki = KiV; + _Kd = KdV; + + _PIDController.SetTunings(_Kp, _Ki, _Kd, propWeightV); +} + +String MotorGearboxEncoder::getPIDString(){ + /* + + Get PID tuning values + + */ + String PIDString = "Kp="; + return PIDString + *_Kp + ",Ki=" + *_Ki + ",Kd=" + *_Kd; +} + +String MotorGearboxEncoder::pidState(){ + /* + + Get current value of PID variables, setpoint, input, output + + */ + return _PIDController.pidState(); +} + +void MotorGearboxEncoder::setPIDAggressiveness(float aggressiveness){ + /* + + The setPIDAggressiveness() function sets the aggressiveness of the PID controller to + compensate for a change in the load on the motor. + + */ + + float adjustedKp = aggressiveness * *_Kp; + float one = 1.0; + + _PIDController.SetTunings(&adjustedKp, _Ki, _Kd, &one); + +} + +void MotorGearboxEncoder::setEncoderResolution(float resolution){ + /* + + Change the encoder resolution + + */ + + _encoderStepsToRPMScaleFactor = 60000000.0/resolution; //6*10^7 us per minute divided by 8113.73 steps per revolution + +} + +float MotorGearboxEncoder::computeSpeed(){ + /* + + Returns the motors speed in RPM since the last time this function was called + should only be called by the PID process otherwise we are calculating the + distance moved over a varying amount of time. + + */ + + float currentPosition = encoder.read(); + float currentMicros = micros(); + + float distMoved = currentPosition - _lastPosition; + if (distMoved > 3 || distMoved < -3){ + + // This dampens some of the effects of quantization without having + // a big effect on other changes + float saveDistMoved = distMoved; + if (distMoved - _lastDistMoved <= -1){ distMoved += .5;} + else if (distMoved - _lastDistMoved >= 1){distMoved -= .5;} + _lastDistMoved = saveDistMoved; + + unsigned long timeElapsed = currentMicros - _lastTimeStamp; + //Compute the speed in RPM + _RPM = (_encoderStepsToRPMScaleFactor*distMoved)/float(timeElapsed); + + } + else { + float elapsedTime = encoder.elapsedTime(); + float lastTime = micros() - encoder.lastStepTime(); // no direction associated with this + if (lastTime > abs(elapsedTime)) { + // This allows the RPM to approach 0 + if (elapsedTime < 0){ + elapsedTime = -lastTime; + } + else { + elapsedTime = lastTime; + } + }; + + _RPM = 0 ; + if (elapsedTime != 0){ + _RPM = _encoderStepsToRPMScaleFactor / elapsedTime; + } + } + _RPM = _RPM * -1.0; + + //Store values for next time + _lastTimeStamp = currentMicros; + _lastPosition = currentPosition; + + return _RPM; +} + +float MotorGearboxEncoder::cachedSpeed(){ + /* + Returns the last result of computeSpeed + */ + return _RPM; +} + +void MotorGearboxEncoder::setName(char *newName){ + /* + Set the name for the object + */ + _motorName = newName; +} + +char MotorGearboxEncoder::name(){ + /* + Get the name for the object + */ + return *_motorName; +} diff --git a/Firmware_1.26b/cnc_ctrl_v1/MotorGearboxEncoder.h b/Firmware_1.26b/cnc_ctrl_v1/MotorGearboxEncoder.h new file mode 100644 index 00000000..6a680351 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/MotorGearboxEncoder.h @@ -0,0 +1,56 @@ + /*This file is part of the Makesmith Control Software. + + The Makesmith Control Software is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Makesmith Control Software is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with the Makesmith Control Software. If not, see . + + Copyright 2014-2017 Bar Smith*/ + + #ifndef MotorGearboxEncoder_h + #define MotorGearboxEncoder_h + + class MotorGearboxEncoder{ + public: + void setup(const int& pwmPin, const int& directionPin1, const int& directionPin2, const int& encoderPin1, const int& encoderPin2, const unsigned long& loopInterval); + Encoder encoder; + Motor motor; + float cachedSpeed(); + void write(const float& speed); + void computePID(); + void setName(char *newName); + char name(); + void initializePID(const unsigned long& loopInterval); + void setPIDAggressiveness(float aggressiveness); + void setPIDValues(float* KpV, float* KiV, float* KdV, float* propWeight); + void setEncoderResolution(float resolution); + float computeSpeed(); + String getPIDString(); + String pidState(); + private: + double _targetSpeed; + double _currentSpeed; + volatile double _lastPosition; + volatile double _lastTimeStamp; + float _lastDistMoved; + float _RPM; + char *_motorName; + double _pidOutput; + PID _PIDController; + float *_Kp, *_Ki, *_Kd; + // This could be converted to a pointer to save 4 bytes, but the + // calculation would have to be done at a much higher level and + // passed through each axis for it to have a single pointer to + // both main motors + float _encoderStepsToRPMScaleFactor = 7394.87; //6*10^7 us per minute divided by 8113.73 steps per revolution + }; + + #endif \ No newline at end of file diff --git a/Firmware_1.26b/cnc_ctrl_v1/NutsAndBolts.cpp b/Firmware_1.26b/cnc_ctrl_v1/NutsAndBolts.cpp new file mode 100644 index 00000000..f3711689 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/NutsAndBolts.cpp @@ -0,0 +1,67 @@ +/*This file is part of the Maslow Control Software. + +The Maslow Control Software is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +Maslow Control Software is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with the Maslow Control Software. If not, see . + +Copyright 2014-2017 Bar Smith*/ + +// This file contains helper functions that are used throughout + +#include "Maslow.h" + +float readFloat(const String& str, byte& index, float& retVal){ + /* + Takes a string and a starting character index and returns a float if it can + be parsed from the string, it will skip leading spaces. Does not support + scientific notation as this is officially not supported by GCode. + Code was adopted from arduino Stream::parseFloat and some from Grbl's + read_float. It is a custom function because all arduino and c++ functions + appear to handle scientific notation or hexadecimal notation, or some other + type of numerical representation that we don't want supported. + */ + bool isNegative = false; + bool isFraction = false; + long value = 0; + float fraction = 1.0; + byte ndigit = 0; + while (str[index] == ' ' && index < str.length()){ + index++; + } + do{ + if (index < str.length()){ + if(str[index] == '-') + isNegative = true; + else if (str[index] == '.') + isFraction = true; + else if(str[index] >= '0' && str[index] <= '9') {// is a digit? + ndigit++; + value = value * 10 + str[index] - '0'; + if(isFraction) + fraction *= 0.1; + } + index++; + } + } + while(((str[index] >= '0' && str[index] <= '9') || (str[index] == '.' && !isFraction)) && index < str.length()); + + if (!ndigit) { return false; }; + + if(isNegative) + value = -value; + if(isFraction) + retVal = value * fraction; + else + retVal = value; + + return true; +} \ No newline at end of file diff --git a/Firmware_1.26b/cnc_ctrl_v1/NutsAndBolts.h b/Firmware_1.26b/cnc_ctrl_v1/NutsAndBolts.h new file mode 100644 index 00000000..4f1936f6 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/NutsAndBolts.h @@ -0,0 +1,31 @@ +/*This file is part of the Maslow Control Software. + +The Maslow Control Software is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +Maslow Control Software is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with the Maslow Control Software. If not, see . + +Copyright 2014-2017 Bar Smith*/ + +// This file contains helper functions that are used throughout + +#ifndef nutsandbolts_h +#define nutsandbolts_h + +// These are nifty functions from Grbl +#define bit_true(x,mask) (x) |= (mask) +#define bit_false(x,mask) (x) &= ~(mask) +#define bit_istrue(x,mask) ((x & mask) != 0) +#define bit_isfalse(x,mask) ((x & mask) == 0) + +float readFloat(const String&, byte&, float&); + +#endif \ No newline at end of file diff --git a/Firmware_1.26b/cnc_ctrl_v1/PID_v1.cpp b/Firmware_1.26b/cnc_ctrl_v1/PID_v1.cpp new file mode 100644 index 00000000..8401109c --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/PID_v1.cpp @@ -0,0 +1,236 @@ +/********************************************************************************************** + * Arduino PID Library - Version 1.2.1 + * by Brett Beauregard brettbeauregard.com + * + * This Library is licensed under the MIT License + **********************************************************************************************/ + +#if ARDUINO >= 100 + #include "Arduino.h" +#else + #include "WProgram.h" +#endif + +#include "Maslow.h" + +/*Constructor (...)********************************************************* + * The parameters specified here are those for for which we can't set up + * reliable defaults, so we need to have the user set them. + ***************************************************************************/ +PID::PID() +{ + inAuto = false; +} + +void PID::setup(volatile double* Input, volatile double* Output, volatile double* Setpoint, + float* Kp, float* Ki, float* Kd, float* POn, const int& ControllerDirection) +{ + + myOutput = Output; + myInput = Input; + mySetpoint = Setpoint; + inAuto = false; + + PID::SetOutputLimits(0, 255); //default output limit corresponds to + //the arduino pwm limits + + SampleTime = 100; //default Controller Sample Time is 0.1 seconds + + PID::SetControllerDirection(ControllerDirection); + PID::SetTunings(Kp, Ki, Kd, POn); + + lastTime = millis()-SampleTime; +} + +/* Compute() ********************************************************************** + * This, as they say, is where the magic happens. this function should be called + * every time "void loop()" executes. the function will decide for itself whether a new + * pid Output needs to be computed. returns true when the output is computed, + * false when nothing has been done. + **********************************************************************************/ +bool PID::Compute() +{ + if(!inAuto) return false; + //unsigned long now = millis(); + //unsigned long timeChange = (now - lastTime); + //if(timeChange>=SampleTime) + //{ <--- This if statement has been removed to reduce timing jitter on the interrupt. + //because we are calling the function from within an interrupt timer it will be called + //with a consistent sample period + + /*Compute all the working error variables*/ + double input = *myInput; + double error = *mySetpoint - input; + double dInput = (input - lastInput); + outputSum+= (ki * error); + + /*Add Proportional on Measurement, if P_ON_M is specified*/ + if(pOnM) outputSum-= pOnMKp * dInput; + + if(outputSum > outMax) outputSum= outMax; + else if(outputSum < outMin) outputSum= outMin; + + /*Add Proportional on Error, if P_ON_E is specified*/ + double output; + if(pOnE) output = pOnEKp * error; + else output = 0; + + /*Compute Rest of PID Output*/ + output += outputSum - kd * dInput; + + if(output > outMax) output = outMax; + else if(output < outMin) output = outMin; + *myOutput = output; + + /*Remember some variables for next time*/ + lastInput = input; + //lastTime = now; + return true; + //} + //else return false; +} + + +/* SetTunings(...)************************************************************* + * This function allows the controller's dynamic performance to be adjusted. + * it's called automatically from the constructor, but tunings can also + * be adjusted on the fly during normal operation + ******************************************************************************/ +void PID::SetTunings(float* Kp, float* Ki, float* Kd, float* pOn) +{ + if (*Kp<0 || *Ki<0 || *Kd<0 || *pOn<0 || *pOn>1) return; + + pOnE = *pOn>0; //some p on error is desired; + pOnM = *pOn<1; //some p on measurement is desired; + + dispKp = Kp; dispKi = Ki; dispKd = Kd; + + double SampleTimeInSec = ((double)SampleTime)/1000; + kp = *Kp; + ki = *Ki * SampleTimeInSec; + kd = *Kd / SampleTimeInSec; + + if(controllerDirection ==REVERSE) + { + kp = (0 - kp); + ki = (0 - ki); + kd = (0 - kd); + } + pOnEKp = *pOn * kp; + pOnMKp = (1 - *pOn) * kp; +} + +/* SetSampleTime(...) ********************************************************* + * sets the period, in Milliseconds, at which the calculation is performed + ******************************************************************************/ +void PID::SetSampleTime(const int& NewSampleTime) +{ + if (NewSampleTime > 0) + { + double ratio = (double)NewSampleTime + / (double)SampleTime; + ki *= ratio; + kd /= ratio; + SampleTime = (unsigned long)NewSampleTime; + } +} + +/* SetOutputLimits(...)**************************************************** + * This function will be used far more often than SetInputLimits. while + * the input to the controller will generally be in the 0-1023 range (which is + * the default already,) the output will be a little different. maybe they'll + * be doing a time window and will need 0-8000 or something. or maybe they'll + * want to clamp it from 0-125. who knows. at any rate, that can all be done + * here. + **************************************************************************/ +void PID::SetOutputLimits(const double& Min, const double& Max) +{ + if(Min >= Max) return; + outMin = Min; + outMax = Max; + + if(inAuto) + { + + //clamp myOutput and ITerm + *myOutput = + (*myOutput > outMax) ? outMax : (*myOutput < outMin) ? outMin : *myOutput; + + if(outputSum > outMax) outputSum= outMax; + else if(outputSum < outMin) outputSum= outMin; + + } +} + +/* SetMode(...)**************************************************************** + * Allows the controller Mode to be set to manual (0) or Automatic (non-zero) + * when the transition from manual to auto occurs, the controller is + * automatically initialized + ******************************************************************************/ +void PID::SetMode(const int& Mode) +{ + bool newAuto = (Mode == AUTOMATIC); + if(newAuto && !inAuto) + { /*we just went from manual to auto*/ + PID::Initialize(); + } + inAuto = newAuto; +} + +/* Initialize()**************************************************************** + * does all the things that need to happen to ensure a bumpless transfer + * from manual to automatic mode. + ******************************************************************************/ +void PID::Initialize() +{ + outputSum = *myOutput; + lastInput = *myInput; + if(outputSum > outMax) outputSum = outMax; + else if(outputSum < outMin) outputSum = outMin; +} + +/* SetControllerDirection(...)************************************************* + * The PID will either be connected to a DIRECT acting process (+Output leads + * to +Input) or a REVERSE acting process(+Output leads to -Input.) we need to + * know which one, because otherwise we may increase the output when we should + * be decreasing. This is called from the constructor. + ******************************************************************************/ +void PID::SetControllerDirection(const int& Direction) +{ + if(inAuto && Direction !=controllerDirection) + { + kp = (0 - kp); + ki = (0 - ki); + kd = (0 - kd); + } + controllerDirection = Direction; +} + +/* Status Funcions************************************************************* + * Just because you set the Kp=-1 doesn't mean it actually happened. these + * functions query the internal state of the PID. they're here for display + * purposes. this are the functions the PID Front-end uses for example + ******************************************************************************/ +double PID::GetKp(){ return *dispKp;} +double PID::GetKi(){ return *dispKi;} +double PID::GetKd(){ return *dispKd;} +int PID::GetMode(){ return inAuto ? AUTOMATIC : MANUAL;} +int PID::GetDirection(){ return controllerDirection;} +double PID::GetIterm(){ return outputSum; } +String PID::pidState() { + /* + Returns a comma seperated string of the PID setpoint, input, & output + useful for debugging + */ + double input = *myInput; + double setpoint = *mySetpoint; + double output = *myOutput; + String ret = ""; + ret.concat((double)setpoint); + ret.concat(","); + ret.concat((double)input); + ret.concat(","); + ret.concat((double)output); + return ret; +} + diff --git a/Firmware_1.26b/cnc_ctrl_v1/PID_v1.h b/Firmware_1.26b/cnc_ctrl_v1/PID_v1.h new file mode 100644 index 00000000..803076db --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/PID_v1.h @@ -0,0 +1,98 @@ +#ifndef PID_v1_h +#define PID_v1_h +#define LIBRARY_VERSION 1.2.1 + +class PID +{ + + + public: + + //Constants used in some of the functions below + #define AUTOMATIC 1 + #define MANUAL 0 + #define DIRECT 0 + #define REVERSE 1 + #define P_ON_M 0.0 + #define P_ON_E 1.0 + bool pOnE = true, pOnM = false; + double pOnEKp, pOnMKp; + + //commonly used functions ************************************************************************** + + PID(); + + void setup(volatile double*, volatile double*, volatile double*, // * constructor. links the PID to the Input, Output, and + float*, float*, float*, float*, const int&);// Setpoint. Initial tuning parameters are also set here. + // (overload for specifying proportional mode) + + PID(double*, double*, double*, // * constructor. links the PID to the Input, Output, and + double, double, double, int); // Setpoint. Initial tuning parameters are also set here + + void SetMode(const int& Mode); // * sets PID to either Manual (0) or Auto (non-0) + + bool Compute(); // * performs the PID calculation. it should be + // called every time loop() cycles. ON/OFF and + // calculation frequency can be set using SetMode + // SetSampleTime respectively + + void SetOutputLimits(const double&, const double&); //clamps the output to a specific range. 0-255 by default, but + //it's likely the user will want to change this depending on + //the application + + + + //available but not commonly used functions ******************************************************** + void SetTunings(float*, float*, // * While most users will set the tunings once in the + float*); // constructor, this function gives the user the option + // of changing tunings during runtime for Adaptive control + void SetTunings(float*, float*, // * overload for specifying proportional mode + float*, float*); + + void SetControllerDirection(const int&); // * Sets the Direction, or "Action" of the controller. DIRECT + // means the output will increase when error is positive. REVERSE + // means the opposite. it's very unlikely that this will be needed + // once it is set in the constructor. + void SetSampleTime(const int&); // * sets the frequency, in Milliseconds, with which + // the PID calculation is performed. default is 100 + + + //Display functions **************************************************************** + double GetKp(); // These functions query the pid for interal values. + double GetKi(); // they were created mainly for the pid front-end, + double GetKd(); // where it's important to know what is actually + int GetMode(); // inside the PID. + int GetDirection(); // + double GetIterm(); + String pidState(); + + private: + void Initialize(); + + float *dispKp; // * we'll hold on to the tuning parameters in user-entered + float *dispKi; // format for display purposes + float *dispKd; // + +// While shared by both main motors, these are not pointers because they are +// calculated using sample time in this file. + double kp; // * (P)roportional Tuning Parameter + double ki; // * (I)ntegral Tuning Parameter + double kd; // * (D)erivative Tuning Parameter + + int controllerDirection; + int pOn; + + volatile double *myInput; // * Pointers to the Input, Output, and Setpoint variables + volatile double *myOutput; // This creates a hard link between the variables and the + volatile double *mySetpoint; // PID, freeing the user from having to constantly tell us + // what these values are. with pointers we'll just know. + + unsigned long lastTime; + double outputSum, lastInput; + + unsigned long SampleTime; + double outMin, outMax; + bool inAuto; +}; +#endif + diff --git a/Firmware_1.26b/cnc_ctrl_v1/Probe.cpp b/Firmware_1.26b/cnc_ctrl_v1/Probe.cpp new file mode 100644 index 00000000..619fc09a --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Probe.cpp @@ -0,0 +1,33 @@ +/*This file is part of the Maslow Control Software. + +The Maslow Control Software is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +Maslow Control Software is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with the Maslow Control Software. If not, see . + +Copyright 2014-2017 Bar Smith*/ + +// This file contains functions related to the probe + +#include "Maslow.h" + +// the variable probePin is assigned in configAuxLow() in System.cpp + +bool checkForProbeTouch(const int& probePin) { + /* + Check to see if ProbePin has gone LOW + */ + if (digitalRead(probePin) == LOW) { + readyCommandString = ""; + return 1; + } + return 0; +} diff --git a/Firmware_1.26b/cnc_ctrl_v1/Probe.h b/Firmware_1.26b/cnc_ctrl_v1/Probe.h new file mode 100644 index 00000000..c4340366 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Probe.h @@ -0,0 +1,25 @@ +/*This file is part of the Maslow Control Software. + +The Maslow Control Software is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +Maslow Control Software is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with the Maslow Control Software. If not, see . + +Copyright 2014-2017 Bar Smith*/ + +// This file contains functions related to the probe + +#ifndef probe_h +#define probe_h + +bool checkForProbeTouch(const int&); + +#endif \ No newline at end of file diff --git a/Firmware_1.26b/cnc_ctrl_v1/Report.cpp b/Firmware_1.26b/cnc_ctrl_v1/Report.cpp new file mode 100644 index 00000000..0c8b9e4f --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Report.cpp @@ -0,0 +1,316 @@ +/*This file is part of the Maslow Control Software. + +The Maslow Control Software is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +Maslow Control Software is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with the Maslow Control Software. If not, see . + +Copyright 2014-2017 Bar Smith*/ + +// This file contains the functions for outgoing Serial responses + +#include "Maslow.h" + +void reportStatusMessage(byte status_code){ + /* + + Sends confirmation protocol response for commands. For every incoming line, + this method responds with an 'ok' for a successful command or an 'error:' + to indicate some error event with the line or some critical system error during + operation. + + Taken from Grbl http://github.com/grbl/grbl + */ + if (status_code == 0) { // STATUS_OK + Serial.println(F("ok")); + } else { + Serial.print(F("error: ")); + #ifdef REPORT_GUI_MODE + Serial.println(status_code); + #else + switch(status_code) { + // case STATUS_EXPECTED_COMMAND_LETTER=")); Serial.println( // Serial.println(F("Expected command letter")); break; + case STATUS_BAD_NUMBER_FORMAT: + Serial.println(F("Bad number format")); break; + case STATUS_INVALID_STATEMENT: + Serial.println(F("Invalid statement")); break; + case STATUS_OLD_SETTINGS: + Serial.println(F("Please set $12, $13, $19, and $20 to load old position data.")); break; + // case STATUS_NEGATIVE_VALUE: + // Serial.println(F("Value < 0")); break; + // case STATUS_SETTING_DISABLED: + // Serial.println(F("Setting disabled")); break; + // case STATUS_SETTING_STEP_PULSE_MIN: + // Serial.println(F("Value < 3 usec")); break; + case STATUS_SETTING_READ_FAIL: + Serial.println(F("EEPROM read fail. Using default settings.")); break; + // case STATUS_IDLE_ERROR: + // Serial.println(F("Not idle")); break; + // case STATUS_ALARM_LOCK: + // Serial.println(F("Alarm lock")); break; + // case STATUS_SOFT_LIMIT_ERROR: + // Serial.println(F("Homing not enabled")); break; + // case STATUS_OVERFLOW: + // Serial.println(F("Line overflow")); break; + // #ifdef MAX_STEP_RATE_HZ + // case STATUS_MAX_STEP_RATE_EXCEEDED: + // Serial.println(F("Step rate > 30kHz")); break; + // #endif + // Common g-code parser errors. + // case STATUS_GCODE_MODAL_GROUP_VIOLATION: + // Serial.println(F("Modal group violation")); break; + // case STATUS_GCODE_UNSUPPORTED_COMMAND: + // Serial.println(F("Unsupported command")); break; + // case STATUS_GCODE_UNDEFINED_FEED_RATE: + // Serial.println(F("Undefined feed rate")); break; + default: + // Remaining g-code parser errors with error codes + Serial.print(F("Invalid gcode ID:")); + Serial.println(status_code); // Print error code for user reference + } + #endif + } +} + +void reportFeedbackMessage(byte message_code){ + Serial.print(F("Message: ")); + switch(message_code) { + // case MESSAGE_CRITICAL_EVENT: + // Serial.print(F("Reset to continue")); break; + // case MESSAGE_ALARM_LOCK: + // Serial.print(F("'$H'|'$X' to unlock")); break; + // case MESSAGE_ALARM_UNLOCK: + // Serial.print(F("Caution: Unlocked")); break; + // case MESSAGE_ENABLED: + // Serial.print(F("Enabled")); break; + // case MESSAGE_DISABLED: + // Serial.print(F("Disabled")); break; + // case MESSAGE_SAFETY_DOOR_AJAR: + // Serial.print(F("Check Door")); break; + // case MESSAGE_CHECK_LIMITS: + // Serial.print(F("Check Limits")); break; + // case MESSAGE_PROGRAM_END: + // Serial.print(F("Pgm End")); break; + case MESSAGE_RESTORE_DEFAULTS: + Serial.print(F("Restoring defaults")); break; + // case MESSAGE_SPINDLE_RESTORE: + // Serial.print(F("Restoring spindle")); break; + // case MESSAGE_SLEEP_MODE: + // Serial.print(F("Sleeping")); break; + } + Serial.println(F(" ")); +} + +// Prints alarm messages. +void reportAlarmMessage(byte alarm_code) { + Serial.print(F("ALARM: ")); + #ifdef REPORT_GUI_MODE + Serial.println(alarm_code); + #else + switch (alarm_code) { + case ALARM_POSITION_LOST: { + Serial.println(F("Position Lost")); break; + } + case ALARM_GCODE_PARAM_ERROR: { + Serial.println(F("There is a parameter error in this line of Gcode - make a note of the line number. Cutting will be put on hold until you choose whether to 'Resume Cut' (skipping this line) or 'Stop'. ")); + pause(); //This pause() waits for user acknowledgement of message + pause(); //Now wait for user decision about 'Stop' or 'Resume' + break; + } + case ALARM_POSITION_LIMIT_ERROR: { + Serial.println(F("The sled is not keeping up with its expected position and has halted. Click the 'Stop' button to clear the alarm. More information at: https://github.com/MaslowCNC/Firmware/wiki/Keeping-Up ")); + sys.stop = true; + break; + } + } + #endif +} + +// Maslow global settings print out. +// NOTE: The numbering scheme here must correlate to storing in settings.c +void reportMaslowSettings() { + // Print Maslow settings. + // Taken from Grbl. http://github.com/grbl/grbl + #ifdef REPORT_GUI_MODE + Serial.print(F("$0=")); Serial.println(sysSettings.machineWidth, 8); + Serial.print(F("$1=")); Serial.println(sysSettings.machineHeight, 8); + Serial.print(F("$2=")); Serial.println(sysSettings.distBetweenMotors, 8); + Serial.print(F("$3=")); Serial.println(sysSettings.motorOffsetY, 8); + Serial.print(F("$4=")); Serial.println(sysSettings.sledWidth, 8); + Serial.print(F("$5=")); Serial.println(sysSettings.sledHeight, 8); + Serial.print(F("$6=")); Serial.println(sysSettings.sledCG, 8); + Serial.print(F("$7=")); Serial.println(sysSettings.kinematicsType); + Serial.print(F("$8=")); Serial.println(sysSettings.rotationDiskRadius, 8); + Serial.print(F("$9=")); Serial.println(sysSettings.axisDetachTime); + Serial.print(F("$10=")); Serial.println(sysSettings.chainLength); + Serial.print(F("$11=")); Serial.println(sysSettings.originalChainLength); + Serial.print(F("$12=")); Serial.println(sysSettings.encoderSteps, 8); + Serial.print(F("$13=")); Serial.println(sysSettings.distPerRot, 8); + Serial.print(F("$15=")); Serial.println(sysSettings.maxFeed); + Serial.print(F("$16=")); Serial.println(sysSettings.zAxisAttached); + Serial.print(F("$17=")); Serial.println(sysSettings.spindleAutomate); + Serial.print(F("$18=")); Serial.println(sysSettings.maxZRPM, 8); + Serial.print(F("$19=")); Serial.println(sysSettings.zDistPerRot, 8); + Serial.print(F("$20=")); Serial.println(sysSettings.zEncoderSteps, 8); + Serial.print(F("$21=")); Serial.println(sysSettings.KpPos, 8); + Serial.print(F("$22=")); Serial.println(sysSettings.KiPos, 8); + Serial.print(F("$23=")); Serial.println(sysSettings.KdPos, 8); + Serial.print(F("$24=")); Serial.println(sysSettings.propWeightPos, 8); + Serial.print(F("$25=")); Serial.println(sysSettings.KpV, 8); + Serial.print(F("$26=")); Serial.println(sysSettings.KiV, 8); + Serial.print(F("$27=")); Serial.println(sysSettings.KdV, 8); + Serial.print(F("$28=")); Serial.println(sysSettings.propWeightV, 8); + Serial.print(F("$29=")); Serial.println(sysSettings.zKpPos, 8); + Serial.print(F("$30=")); Serial.println(sysSettings.zKiPos, 8); + Serial.print(F("$31=")); Serial.println(sysSettings.zKdPos, 8); + Serial.print(F("$32=")); Serial.println(sysSettings.zPropWeightPos, 8); + Serial.print(F("$33=")); Serial.println(sysSettings.zKpV, 8); + Serial.print(F("$34=")); Serial.println(sysSettings.zKiV, 8); + Serial.print(F("$35=")); Serial.println(sysSettings.zKdV, 8); + Serial.print(F("$36=")); Serial.println(sysSettings.zPropWeightV, 8); + Serial.print(F("$37=")); Serial.println(sysSettings.chainSagCorrection, 8); + Serial.print(F("$38=")); Serial.println(sysSettings.chainOverSprocket); + Serial.print(F("$39=")); Serial.println(sysSettings.fPWM); + Serial.print(F("$40=")); Serial.println(sysSettings.leftChainTolerance, 8); + Serial.print(F("$41=")); Serial.println(sysSettings.rightChainTolerance, 8); + Serial.print(F("$42=")); Serial.println(sysSettings.positionErrorLimit, 8); + + #else + Serial.print(F("$0=")); Serial.print(sysSettings.machineWidth); + Serial.print(F(" (machine width, mm)\r\n$1=")); Serial.print(sysSettings.machineHeight, 8); + Serial.print(F(" (machine height, mm)\r\n$2=")); Serial.print(sysSettings.distBetweenMotors, 8); + Serial.print(F(" (motor distance, mm)\r\n$3=")); Serial.print(sysSettings.motorOffsetY, 8); + Serial.print(F(" (motor height, mm)\r\n$4=")); Serial.print(sysSettings.sledWidth, 8); + Serial.print(F(" (sled width, mm)\r\n$5=")); Serial.print(sysSettings.sledHeight, 8); + Serial.print(F(" (sled height, mm)\r\n$6=")); Serial.print(sysSettings.sledCG, 8); + Serial.print(F(" (sled cg, mm)\r\n$7=")); Serial.print(sysSettings.kinematicsType); + Serial.print(F(" (Kinematics Type 1=Quadrilateral, 2=Triangular)\r\n$8=")); Serial.print(sysSettings.rotationDiskRadius, 8); + Serial.print(F(" (rotation radius, mm)\r\n$9=")); Serial.print(sysSettings.axisDetachTime); + Serial.print(F(" (axis idle before detach, ms)\r\n$10=")); Serial.print(sysSettings.chainLength); + Serial.print(F(" (full length of chain, mm)\r\n$11=")); Serial.print(sysSettings.originalChainLength); + Serial.print(F(" (calibration chain length, mm)\r\n$12=")); Serial.print(sysSettings.encoderSteps, 8); + Serial.print(F(" (main steps per revolution)\r\n$13=")); Serial.print(sysSettings.distPerRot, 8); + Serial.print(F(" (distance / rotation, mm)\r\n$15=")); Serial.print(sysSettings.maxFeed); + Serial.print(F(" (max feed, mm/min)\r\n$16=")); Serial.print(sysSettings.zAxisAttached); + Serial.print(F(" (Auto Z Axis, 1 = Yes)\r\n$17=")); Serial.print(sysSettings.spindleAutomateType); + Serial.print(F(" (auto spindle enable 1=servo, 2=relay_h, 3=relay_l)\r\n$18=")); Serial.print(sysSettings.maxZRPM, 8); + Serial.print(F(" (max z axis RPM)\r\n$19=")); Serial.print(sysSettings.zDistPerRot, 8); + Serial.print(F(" (z axis distance / rotation)\r\n$20=")); Serial.print(sysSettings.zEncoderSteps, 8); + Serial.print(F(" (z axis steps per revolution)\r\n$21=")); Serial.print(sysSettings.KpPos, 8); + Serial.print(F(" (main Kp Pos)\r\n$22=")); Serial.print(sysSettings.KiPos, 8); + Serial.print(F(" (main Ki Pos)\r\n$23=")); Serial.print(sysSettings.KdPos, 8); + Serial.print(F(" (main Kd Pos)\r\n$24=")); Serial.print(sysSettings.propWeightPos, 8); + Serial.print(F(" (main Pos proportional weight)\r\n$25=")); Serial.print(sysSettings.KpV, 8); + Serial.print(F(" (main Kp Velocity)\r\n$26=")); Serial.print(sysSettings.KiV, 8); + Serial.print(F(" (main Ki Velocity)\r\n$27=")); Serial.print(sysSettings.KdV, 8); + Serial.print(F(" (main Kd Velocity)\r\n$28=")); Serial.print(sysSettings.propWeightV, 8); + Serial.print(F(" (main Velocity proportional weight)\r\n$29=")); Serial.print(sysSettings.zKpPos, 8); + Serial.print(F(" (z axis Kp Pos)\r\n$30=")); Serial.print(sysSettings.zKiPos, 8); + Serial.print(F(" (z axis Ki Pos)\r\n$31=")); Serial.print(sysSettings.zKdPos, 8); + Serial.print(F(" (z axis Kd Pos)\r\n$32=")); Serial.print(sysSettings.zPropWeightPos, 8); + Serial.print(F(" (z axis Pos proportional weight)\r\n$33=")); Serial.print(sysSettings.zKpV, 8); + Serial.print(F(" (z axis Kp Velocity)\r\n$34=")); Serial.print(sysSettings.zKiV, 8); + Serial.print(F(" (z axis Ki Velocity)\r\n$35=")); Serial.print(sysSettings.zKdV, 8); + Serial.print(F(" (z axis Kd Velocity)\r\n$36=")); Serial.print(sysSettings.zPropWeightV, 8); + Serial.print(F(" (z axis Velocity proportional weight)\r\n$37=")); Serial.print(sysSettings.chainSagCorrection, 8); + Serial.print(F(" (chain sag correction value)\r\n$38=")); Serial.print(sysSettings.chainOverSprocket); + Serial.print(F(" (chain over sprocket)\r\n$39=")); Serial.print(sysSettings.fPWM); + Serial.print(F(" (PWM frequency value 1=39,000Hz, 2=4,100Hz, 3=490Hz)\r\n$40=")); Serial.print(sysSettings.leftChainTolerance, 8); + Serial.print(F(" (chain tolerance, left chain, mm)\r\n$41=")); Serial.print(sysSettings.rightChainTolerance, 8); + Serial.print(F(" (chain tolerance, right chain, mm)\r\n$42=")); Serial.print(sysSettings.positionErrorLimit, 8); + Serial.print(F(" (position error alarm limit, mm)")); + Serial.println(); + #endif +} + +void returnError(){ + /* + Prints the machine's positional error and the amount of space available in the + gcode buffer + */ + Serial.print(F("[PE:")); + Serial.print(leftAxis.error()); + Serial.print(','); + Serial.print(rightAxis.error()); + Serial.print(','); + Serial.print(incSerialBuffer.spaceAvailable()); + Serial.println(F("]")); + if (!sys.stop) { + if (!(sys.state & STATE_POS_ERR_IGNORE)) { + if ((abs(leftAxis.error()) >= sysSettings.positionErrorLimit) || (abs(rightAxis.error()) >= sysSettings.positionErrorLimit)) { + reportAlarmMessage(ALARM_POSITION_LIMIT_ERROR); + } + } + } +} + +void returnPoz(){ + /* + Causes the machine's position (x,y) to be sent over the serial connection updated on the UI + in Ground Control. Also causes the error report to be sent. Only executes + if hasn't been called in at least POSITIONTIMEOUT ms. + */ + + static unsigned long lastRan = millis(); + + if (millis() - lastRan > POSITIONTIMEOUT){ + + + Serial.print(F("<")); + if (sys.stop){ + Serial.print(F("Stop,MPos:")); + } + else if (sys.pause){ + Serial.print(F("Pause,MPos:")); + } + else{ + Serial.print(F("Idle,MPos:")); + } + Serial.print(sys.xPosition/sys.inchesToMMConversion); + Serial.print(F(",")); + Serial.print(sys.yPosition/sys.inchesToMMConversion); + Serial.print(F(",")); + Serial.print(zAxis.read()/sys.inchesToMMConversion); + Serial.println(F(",WPos:0.000,0.000,0.000>")); + + + returnError(); + + lastRan = millis(); + } + +} + +void reportMaslowHelp(){ + /* + This function outputs a brief summary of the $ system commands available. + The list is somewhat aspirational based on what Grbl offers. Maslow + does not currently support all of these features. + + This is taken heavily from grbl. https://github.com/grbl/grbl + */ + #ifndef REPORT_GUI_MODE + Serial.println(F("$$ (view Maslow settings)")); + // Serial.println(F("$# (view # parameters)")); + // Serial.println(F("$G (view parser state)")); + // Serial.println(F("$I (view build info)")); + // Serial.println(F("$N (view startup blocks)")); + Serial.println(F("$x=value (save Maslow setting)")); + // Serial.println(F("$Nx=line (save startup block)")); + // Serial.println(F("$C (check gcode mode)")); + // Serial.println(F("$X (kill alarm lock)")); + // Serial.println(F("$H (run homing cycle)")); + Serial.println(F("~ (cycle start)")); // Maslow treats this as resume or un-pause currently + Serial.println(F("! (feed hold)")); // Maslow treats this as a cycle stop. + // Serial.println(F("? (current status)")); + // Serial.println(F("ctrl-x (reset Maslow)")); + #endif +} diff --git a/Firmware_1.26b/cnc_ctrl_v1/Report.h b/Firmware_1.26b/cnc_ctrl_v1/Report.h new file mode 100644 index 00000000..d62b2289 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Report.h @@ -0,0 +1,85 @@ +/*This file is part of the Maslow Control Software. + +The Maslow Control Software is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +Maslow Control Software is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with the Maslow Control Software. If not, see . + +Copyright 2014-2017 Bar Smith*/ + +// This file contains the functions for outgoing Serial responses + +#ifndef report_h +#define report_h + +// Define Maslow status codes. +// Taken from Grbl http://github.com/grbl/grbl +#define STATUS_OK 0 +#define STATUS_EXPECTED_COMMAND_LETTER 1 +#define STATUS_BAD_NUMBER_FORMAT 2 +#define STATUS_INVALID_STATEMENT 3 +#define STATUS_NEGATIVE_VALUE 4 +#define STATUS_SETTING_DISABLED 5 +#define STATUS_SETTING_STEP_PULSE_MIN 6 +#define STATUS_SETTING_READ_FAIL 7 +#define STATUS_IDLE_ERROR 8 +#define STATUS_ALARM_LOCK 9 +#define STATUS_SOFT_LIMIT_ERROR 10 +#define STATUS_OVERFLOW 11 +#define STATUS_MAX_STEP_RATE_EXCEEDED 12 +#define STATUS_OLD_SETTINGS 13 + +#define STATUS_GCODE_UNSUPPORTED_COMMAND 20 +#define STATUS_GCODE_MODAL_GROUP_VIOLATION 21 +#define STATUS_GCODE_UNDEFINED_FEED_RATE 22 +#define STATUS_GCODE_COMMAND_VALUE_NOT_INTEGER 23 +#define STATUS_GCODE_AXIS_COMMAND_CONFLICT 24 +#define STATUS_GCODE_WORD_REPEATED 25 +#define STATUS_GCODE_NO_AXIS_WORDS 26 +#define STATUS_GCODE_INVALID_LINE_NUMBER 27 +#define STATUS_GCODE_VALUE_WORD_MISSING 28 +#define STATUS_GCODE_UNSUPPORTED_COORD_SYS 29 +#define STATUS_GCODE_G53_INVALID_MOTION_MODE 30 +#define STATUS_GCODE_AXIS_WORDS_EXIST 31 +#define STATUS_GCODE_NO_AXIS_WORDS_IN_PLANE 32 +#define STATUS_GCODE_INVALID_TARGET 33 +#define STATUS_GCODE_ARC_RADIUS_ERROR 34 +#define STATUS_GCODE_NO_OFFSETS_IN_PLANE 35 +#define STATUS_GCODE_UNUSED_WORDS 36 +#define STATUS_GCODE_G43_DYNAMIC_AXIS_ERROR 37 + +// Define Maslow alarm codes. +#define ALARM_POSITION_LOST bit(0) +#define ALARM_GCODE_PARAM_ERROR bit(1) +#define ALARM_POSITION_LIMIT_ERROR bit(2) + +// Define Maslow feedback message codes. Valid values (0-255). +#define MESSAGE_CRITICAL_EVENT 1 +#define MESSAGE_ALARM_LOCK 2 +#define MESSAGE_ALARM_UNLOCK 3 +#define MESSAGE_ENABLED 4 +#define MESSAGE_DISABLED 5 +#define MESSAGE_SAFETY_DOOR_AJAR 6 +#define MESSAGE_CHECK_LIMITS 7 +#define MESSAGE_PROGRAM_END 8 +#define MESSAGE_RESTORE_DEFAULTS 9 +#define MESSAGE_SPINDLE_RESTORE 10 +#define MESSAGE_SLEEP_MODE 11 + +void reportStatusMessage(byte); +void reportFeedbackMessage(byte); +void reportMaslowSettings(); +void reportAlarmMessage(byte); +void returnError(); +void returnPoz(); +void reportMaslowHelp(); + +#endif \ No newline at end of file diff --git a/Firmware_1.26b/cnc_ctrl_v1/RingBuffer.cpp b/Firmware_1.26b/cnc_ctrl_v1/RingBuffer.cpp new file mode 100644 index 00000000..c391edc8 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/RingBuffer.cpp @@ -0,0 +1,208 @@ +/*This file is part of the Maslow Control Software. + + The Maslow Control Software is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Maslow Control Software is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with the Maslow Control Software. If not, see . + + Copyright 2014-2017 Bar Smith*/ + +/* +The RingBuffer module creates a circular character buffer used for storing incoming +serial data. +*/ + +#include "Maslow.h" + +RingBuffer::RingBuffer(){ + +} +int RingBuffer::write(char letter){ + /* + + Write one character into the ring buffer. + Return 0 on success + Return 1 on buffer overflow + + */ + if (letter != '?'){ //ignore question marks because grbl sends them all the time + _buffer[_endOfString] = letter; + int bufferOverflow = _incrementEnd(); + return bufferOverflow; + } + return 0; +} + +char RingBuffer::read(){ + /* + + Read one character from the ring buffer. + + */ + + char letter; + if (_beginningOfString == _endOfString){ + letter = '\0'; //if the buffer is empty return null + } + else{ + letter = _buffer[_beginningOfString]; //else return first character + _buffer[_beginningOfString] = '\0'; //set the read character to null so it cannot be read again + _incrementBeginning(); //and increment the pointer + } + + return letter; +} + +int RingBuffer::numberOfLines() { + /* + + Return the number of full lines (as determined by \n terminations) in the buffer + + */ + + int lineCount = 0; + + int i = _beginningOfString; + while (i != _endOfString) { // if we haven't gotten to the end of the buffer yet + if(_buffer[i] == '\n'){ // check to see if the buffer contains a complete line terminated with \n + lineCount++; // yes, so increment lineCount + } + _incrementVariable(&i); // go to the next character in the buffer + } + + return lineCount; +} + +void RingBuffer::readLine(String &lineToReturn){ + /* + + Return one line (terminated with \n) from the buffer + if there are no full lines in the buffer, passed string will be empty + + */ + lineToReturn = ""; // begin with an empty string + + if (numberOfLines() > 0) { // there is at least one full line in the buffer + char lastReadValue = '\0'; + while(lastReadValue != '\n'){ //read until the end of the line is found, building the string + lastReadValue = read(); + lineToReturn += lastReadValue; + } + } +} + +void RingBuffer::prettyReadLine(String &lineToReturn){ + /* + + Return one line (terminated with \n) from the buffer, but in all uppercase + with no leading or trailing whitespaces + + */ + readLine(lineToReturn); + lineToReturn.trim(); // remove leading and trailing white space + lineToReturn.toUpperCase(); +} + +void RingBuffer::print(){ + Serial.print(F("Buffer Used: ")); + Serial.println(length()); + Serial.print(F("Buffer Number of Lines: ")); + Serial.println(numberOfLines()); + Serial.print(F("Buffer Begin: ")); + Serial.println(_beginningOfString); + Serial.print(F("Buffer End: ")); + Serial.println(_endOfString); + + Serial.print(F("Buffer Contents: ")); + int i = _beginningOfString; + while(i != _endOfString){ + if (_buffer[i] == '\n') { + Serial.print(F("\\n")); + } + else if (_buffer[i] == '\r') { + Serial.print(F("\\r")); + } + else if (_buffer[i] == '\t') { + Serial.print(F("\\t")); + } + else { + Serial.print(_buffer[i]); + } + _incrementVariable(&i); + } + + Serial.println(F("(End of Buffer)")); + +} + +void RingBuffer::_incrementBeginning(){ + /* + + Increment the pointer to the beginning of the ring buffer by one. + + */ + + if (_beginningOfString == _endOfString) + return; //don't allow the beginning to pass the end + else + _beginningOfString = (_beginningOfString + 1) % INCBUFFERLENGTH; //move the beginning up one and wrap to zero based upon INCBUFFERLENGTH +} + +int RingBuffer::_incrementEnd(){ + /* + + Increment the pointer to the end of the ring buffer by one. + + */ + if ( spaceAvailable() == 0 ) { + Serial.println(F("Buffer overflow!")); + print(); // print buffer info and contents + return 1; + } + else + _endOfString = (_endOfString+1) % INCBUFFERLENGTH; + return 0; + } + +void RingBuffer::_incrementVariable(int* variable){ + /* + Increment the target variable. + */ + *variable = (*variable + 1 ) % INCBUFFERLENGTH; + } + +int RingBuffer::spaceAvailable(){ + /* + Returns the number of characters available in the buffer + */ + return INCBUFFERLENGTH - length() - 1; +} + +int RingBuffer::length(void) + /* + Returns the number of characters held in the buffer + */ +{ + if ( _endOfString >= _beginningOfString ) // Linear + return _endOfString - _beginningOfString ; + else // must have rolled + return ( INCBUFFERLENGTH - _beginningOfString + _endOfString); +} + + +void RingBuffer::empty(){ + /* + Empty the contents of the ring buffer + */ + + _beginningOfString = 0; + _endOfString = 0; +} diff --git a/Firmware_1.26b/cnc_ctrl_v1/RingBuffer.h b/Firmware_1.26b/cnc_ctrl_v1/RingBuffer.h new file mode 100644 index 00000000..f6369f62 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/RingBuffer.h @@ -0,0 +1,42 @@ + /*This file is part of the Maslow Control Software. + + The Maslow Control Software is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Maslow Control Software is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with the Maslow Control Software. If not, see . + + Copyright 2014-2017 Bar Smith*/ + + #ifndef RingBuffer_h + #define RingBuffer_h + + class RingBuffer{ + public: + RingBuffer(); + int write(char letter); + void print(); + char read(); + int length(); + int numberOfLines(); + int spaceAvailable(); + void empty(); + void readLine(String&); + void prettyReadLine(String&); + private: + void _incrementBeginning(); + int _incrementEnd(); + void _incrementVariable(int* variable); + int _beginningOfString = 0; //points to the first valid character which can be read + int _endOfString = 0; //points to the first open space which can be written + char _buffer[INCBUFFERLENGTH]; + }; + + #endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/Settings.cpp b/Firmware_1.26b/cnc_ctrl_v1/Settings.cpp new file mode 100644 index 00000000..a622e04e --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Settings.cpp @@ -0,0 +1,414 @@ +/*This file is part of the Maslow Control Software. + +The Maslow Control Software is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +Maslow Control Software is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with the Maslow Control Software. If not, see . + +Copyright 2014-2017 Bar Smith*/ + +// This file contains the machine settings that are saved to eeprom + +// EEPROM addresses 300 and up can be used by Maslow. Under 300 was used +// previously by pre v1.00 Firmware. + +#include "Maslow.h" +#include + +void settingsLoadFromEEprom(){ + /* + Loads data from EEPROM if EEPROM data is valid, only called on startup + + Settings are stored starting at address 340 all the way up. + */ + settingsVersion_t settingsVersionStruct; + settings_t tempSettings; + + settingsReset(); // Load default values first + EEPROM.get(300, settingsVersionStruct); + EEPROM.get(340, tempSettings); + if (settingsVersionStruct.settingsVersion == SETTINGSVERSION && + settingsVersionStruct.eepromValidData == EEPROMVALIDDATA && + tempSettings.eepromValidData == EEPROMVALIDDATA){ + sysSettings = tempSettings; + } + else { + reportStatusMessage(STATUS_SETTING_READ_FAIL); + } + + // Apply settings + setPWMPrescalers(int(sysSettings.fPWM)); + kinematics.recomputeGeometry(); + leftAxis.changeEncoderResolution(&sysSettings.encoderSteps); + rightAxis.changeEncoderResolution(&sysSettings.encoderSteps); + leftAxis.changePitch(&sysSettings.distPerRot); + rightAxis.changePitch(&sysSettings.distPerRot); + zAxis.changePitch(&sysSettings.zDistPerRot); + zAxis.changeEncoderResolution(&sysSettings.zEncoderSteps); +} + +void settingsReset() { + /* + Loads default data into settings, many of these values are approximations + from the an ideal stock frame. Other values are just the recommended + value. Ideally we want these defaults to match the defaults in GroundControl + so that if a value is not changed by a user or is not used, it doesn't + need to be updated here. + */ + sysSettings.machineWidth = 2438.4; // float machineWidth; + sysSettings.machineHeight = 1219.2; // float machineHeight; + sysSettings.distBetweenMotors = 2978.4; // float distBetweenMotors; + sysSettings.motorOffsetY = 463.0; // float motorOffsetY; + sysSettings.sledWidth = 310.0; // float sledWidth; + sysSettings.sledHeight = 139.0; // float sledHeight; + sysSettings.sledCG = 79.0; // float sledCG; + sysSettings.kinematicsType = 1; // byte kinematicsType; + sysSettings.rotationDiskRadius = 250.0; // float rotationDiskRadius; + sysSettings.axisDetachTime = 2000; // int axisDetachTime; + sysSettings.chainLength = 3360; // int maximum length of chain; + sysSettings.originalChainLength = 1650; // int originalChainLength; + sysSettings.encoderSteps = 8113.73; // float encoderSteps; + sysSettings.distPerRot = 63.5; // float distPerRot; + sysSettings.maxFeed = 700; // int maxFeed; + sysSettings.zAxisAttached = true; // zAxisAttached; + sysSettings.spindleAutomateType = NONE; // bool spindleAutomate; + sysSettings.maxZRPM = 12.60; // float maxZRPM; + sysSettings.zDistPerRot = 3.17; // float zDistPerRot; + sysSettings.zEncoderSteps = 7560.0; // float zEncoderSteps; + sysSettings.KpPos = 1300.0; // float KpPos; + sysSettings.KiPos = 0.0; // float KiPos; + sysSettings.KdPos = 34.0; // float KdPos; + sysSettings.propWeightPos = 1.0; // float propWeightPos; + sysSettings.KpV = 5.0; // float KpV; + sysSettings.KiV = 0.0; // float KiV; + sysSettings.KdV = 0.28; // float KdV; + sysSettings.propWeightV = 1.0; // float propWeightV; + sysSettings.zKdPos = 1300.0; // float zKpPos; + sysSettings.zKiPos = 0.0; // float zKiPos; + sysSettings.zKdPos = 34.0; // float zKdPos; + sysSettings.zPropWeightPos = 1.0; // float zPropWeightPos; + sysSettings.zKpV = 5.0; // float zKpV; + sysSettings.zKiV = 0.0; // float zKiV; + sysSettings.zKdV = 0.28; // float zKdV; + sysSettings.zPropWeightV = 1.0; // float zPropWeightV; + sysSettings.chainSagCorrection = 0.0; // float chainSagCorrection; + sysSettings.chainOverSprocket = 1; // byte chainOverSprocket; + sysSettings.fPWM = 3; // byte fPWM; + sysSettings.leftChainTolerance = 0.0; // float leftChainTolerance; + sysSettings.rightChainTolerance = 0.0; // float rightChainTolerance; + sysSettings.positionErrorLimit = 2.0; // float positionErrorLimit; + sysSettings.eepromValidData = EEPROMVALIDDATA; // byte eepromValidData; +} + +void settingsWipe(byte resetType){ + /* + Wipes certain bytes in the EEPROM, you probably want to reset after calling + this + */ + if (bit_istrue(resetType, SETTINGS_RESTORE_SETTINGS)){ + for (size_t i = 340 ; i < sizeof(sysSettings) + 340 ; i++) { + EEPROM.write(i, 0); + } + } + else if (bit_istrue(resetType, SETTINGS_RESTORE_MASLOW)){ + for (size_t i = 300 ; i < sizeof(sysSettings) + 340; i++) { + EEPROM.write(i, 0); + } + } + else if (bit_istrue(resetType, SETTINGS_RESTORE_ALL)){ + for (size_t i = 0 ; i < EEPROM.length() ; i++) { + EEPROM.write(i, 0); + } + } +} + +void settingsSaveToEEprom(){ + /* + Saves settings to EEPROM, only called when settings change + + Settings are stored starting at address 340 all the way up. + */ + settingsVersion_t settingsVersionStruct = {SETTINGSVERSION, EEPROMVALIDDATA}; + EEPROM.put(300, settingsVersionStruct); + EEPROM.put(340, sysSettings); +} + +void settingsSaveStepstoEEprom(){ + /* + Saves position to EEPROM, is called frequently by execSystemRealtime + + Steps are saved in address 310 -> 339. Room for expansion for additional + axes in the future. + */ + // don't run if old position data has not been incorporated yet + if (!sys.oldSettingsFlag){ + settingsStepsV1_t sysSteps = { + leftAxis.steps(), + rightAxis.steps(), + zAxis.steps(), + EEPROMVALIDDATA + }; + EEPROM.put(310, sysSteps); + } +} + +void settingsLoadStepsFromEEprom(){ + /* + Loads position to EEPROM, is called on startup. + + Steps are saved in address 310 -> 339. Room for expansion for additional + axes in the future. + */ + settingsStepsV1_t tempStepsV1; + + EEPROM.get(310, tempStepsV1); + if (tempStepsV1.eepromValidData == EEPROMVALIDDATA){ + leftAxis.setSteps(tempStepsV1.lSteps); + rightAxis.setSteps(tempStepsV1.rSteps); + zAxis.setSteps(tempStepsV1.zSteps); + } + else if (EEPROM.read(5) == EEPROMVALIDDATA && + EEPROM.read(105) == EEPROMVALIDDATA && + EEPROM.read(205) == EEPROMVALIDDATA){ + bit_true(sys.oldSettingsFlag, NEED_ENCODER_STEPS); + bit_true(sys.oldSettingsFlag, NEED_DIST_PER_ROT); + bit_true(sys.oldSettingsFlag, NEED_Z_ENCODER_STEPS); + bit_true(sys.oldSettingsFlag, NEED_Z_DIST_PER_ROT); + sys.state = STATE_OLD_SETTINGS; + Serial.println(F("Old position data detected.")); + Serial.println(F("Please set $12, $13, $19, and $20 to load position.")); + } + else { + systemRtExecAlarm |= ALARM_POSITION_LOST; // if this same global is touched by ISR then need to make atomic somehow + // also need to consider if need difference between flag with bits and + // error message as a byte. + } +} + +void settingsLoadOldSteps(){ + /* + Loads the old version of step settings, only called once encoder steps + and distance per rotation have been loaded. Wipes the old data once + incorporated to prevent oddities in the future + */ + if (sys.state == STATE_OLD_SETTINGS){ + float l, r , z; + EEPROM.get(9, l); + EEPROM.get(109, r); + EEPROM.get(209, z); + leftAxis.set(l); + rightAxis.set(r); + zAxis.set(z); + for (int i = 0; i <= 200; i = i +100){ + for (int j = 5; j <= 13; j++){ + EEPROM.write(i + j, 0); + } + } + sys.state = STATE_IDLE; + } + } + +byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ + /* + Alters individual settings which are then stored to EEPROM. Returns a + status message byte value + */ + + // We can add whatever sanity checks we want here and error out if we like + switch(parameter) { + case 0: case 1: case 2: case 3: case 4: case 5: case 6: case 7: case 8: + switch(parameter) { + case 0: + sysSettings.machineWidth = value; + break; + case 1: + sysSettings.machineHeight = value; + break; + case 2: + sysSettings.distBetweenMotors = value; + break; + case 3: + sysSettings.motorOffsetY = value; + break; + case 4: + sysSettings.sledWidth = value; + break; + case 5: + sysSettings.sledHeight = value; + break; + case 6: + sysSettings.sledCG = value; + break; + case 7: + sysSettings.kinematicsType = value; + break; + case 8: + sysSettings.rotationDiskRadius = value; + break; + } + kinematics.init(); + break; + case 9: + sysSettings.axisDetachTime = value; + break; + case 10: + sysSettings.chainLength = value; + break; + case 11: + sysSettings.originalChainLength = value; + break; + case 12: + sysSettings.encoderSteps = value; + leftAxis.changeEncoderResolution(&sysSettings.encoderSteps); + rightAxis.changeEncoderResolution(&sysSettings.encoderSteps); + if (sys.oldSettingsFlag){ + bit_false(sys.oldSettingsFlag, NEED_ENCODER_STEPS); + if (!sys.oldSettingsFlag){ + settingsLoadOldSteps(); + } + } + kinematics.init(); + break; + case 13: + sysSettings.distPerRot = value; + kinematics.R = (sysSettings.distPerRot)/(2.0 * 3.14159); + if (sys.oldSettingsFlag){ + bit_false(sys.oldSettingsFlag, NEED_DIST_PER_ROT); + if (!sys.oldSettingsFlag){ + settingsLoadOldSteps(); + } + } + kinematics.init(); + break; + case 15: + sysSettings.maxFeed = value; + break; + case 16: + sysSettings.zAxisAttached = value; + break; + case 17: + sysSettings.spindleAutomateType = static_cast(value); + break; + case 18: + sysSettings.maxZRPM = value; + break; + case 19: + sysSettings.zDistPerRot = value; + zAxis.changePitch(&sysSettings.zDistPerRot); + if (sys.oldSettingsFlag){ + bit_false(sys.oldSettingsFlag, NEED_Z_DIST_PER_ROT); + if (!sys.oldSettingsFlag){ + settingsLoadOldSteps(); + } + } + break; + case 20: + sysSettings.zEncoderSteps = value; + zAxis.changeEncoderResolution(&sysSettings.zEncoderSteps); + if (sys.oldSettingsFlag){ + bit_false(sys.oldSettingsFlag, NEED_Z_ENCODER_STEPS); + if (!sys.oldSettingsFlag){ + settingsLoadOldSteps(); + } + } + break; + case 21: case 22: case 23: case 24: case 25: case 26: case 27: case 28: + switch(parameter) { + case 21: + sysSettings.KpPos = value; + break; + case 22: + sysSettings.KiPos = value; + break; + case 23: + sysSettings.KdPos = value; + break; + case 24: + sysSettings.propWeightPos = value; + break; + case 25: + sysSettings.KpV = value; + break; + case 26: + sysSettings.KiV = value; + break; + case 27: + sysSettings.KdV = value; + break; + case 28: + sysSettings.propWeightV = value; + break; + } + leftAxis.setPIDValues(&sysSettings.KpPos, &sysSettings.KiPos, &sysSettings.KdPos, &sysSettings.propWeightPos, &sysSettings.KpV, &sysSettings.KiV, &sysSettings.KdV, &sysSettings.propWeightV); + rightAxis.setPIDValues(&sysSettings.KpPos, &sysSettings.KiPos, &sysSettings.KdPos, &sysSettings.propWeightPos, &sysSettings.KpV, &sysSettings.KiV, &sysSettings.KdV, &sysSettings.propWeightV); + break; + case 29: case 30: case 31: case 32: case 33: case 34: case 35: case 36: + switch(parameter) { + case 29: + sysSettings.zKpPos = value; + break; + case 30: + sysSettings.zKiPos = value; + break; + case 31: + sysSettings.zKdPos = value; + break; + case 32: + sysSettings.zPropWeightPos = value; + break; + case 33: + sysSettings.zKpV = value; + break; + case 34: + sysSettings.zKiV = value; + break; + case 35: + sysSettings.zKdV = value; + break; + case 36: + sysSettings.zPropWeightV = value; + break; + } + zAxis.setPIDValues(&sysSettings.zKpPos, &sysSettings.zKiPos, &sysSettings.zKdPos, &sysSettings.zPropWeightPos, &sysSettings.zKpV, &sysSettings.zKiV, &sysSettings.zKdV, &sysSettings.zPropWeightV); + break; + case 37: + sysSettings.chainSagCorrection = value; + break; + case 38: + settingsSaveStepstoEEprom(); + sysSettings.chainOverSprocket = value; + setupAxes(); + settingsLoadStepsFromEEprom(); + // Set initial desired position of the machine to its current position + leftAxis.write(leftAxis.read()); + rightAxis.write(rightAxis.read()); + zAxis.write(zAxis.read()); + kinematics.init(); + break; + case 39: + sysSettings.fPWM = value; + setPWMPrescalers(value); + break; + case 40: + sysSettings.leftChainTolerance = value; + break; + case 41: + sysSettings.rightChainTolerance = value; + break; + case 42: + sysSettings.positionErrorLimit = value; + break; + default: + return(STATUS_INVALID_STATEMENT); + } + settingsSaveToEEprom(); + return(STATUS_OK); +} diff --git a/Firmware_1.26b/cnc_ctrl_v1/Settings.h b/Firmware_1.26b/cnc_ctrl_v1/Settings.h new file mode 100644 index 00000000..cd18150b --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Settings.h @@ -0,0 +1,109 @@ +/*This file is part of the Maslow Control Software. + +The Maslow Control Software is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +Maslow Control Software is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with the Maslow Control Software. If not, see . + +Copyright 2014-2017 Bar Smith*/ + +// This file contains the machine settings that are saved to eeprom + +#ifndef settings_h +#define settings_h + +#define SETTINGSVERSION 5 // The current version of settings, if this doesn't + // match what is in EEPROM then settings on + // machine are reset to defaults +#define EEPROMVALIDDATA 56 // This is just a random byte value that is used + // to determine if the data in the EEPROM was + // saved by maslow, or something else. + +// Reset Types +#define SETTINGS_RESTORE_SETTINGS bit(0) +#define SETTINGS_RESTORE_MASLOW bit(1) +#define SETTINGS_RESTORE_ALL bit(2) + +enum SpindleAutomationType { + NONE, + SERVO, + RELAY_ACTIVE_HIGH, + RELAY_ACTIVE_LOW }; + +typedef struct { // I think this is about ~128 bytes in size if I counted correctly + float machineWidth; + float machineHeight; + float distBetweenMotors; + float motorOffsetY; + float sledWidth; + float sledHeight; + float sledCG; + byte kinematicsType; + float rotationDiskRadius; + unsigned int axisDetachTime; + unsigned int chainLength; + unsigned int originalChainLength; + float encoderSteps; + float distPerRot; + unsigned int maxFeed; + bool zAxisAttached; + SpindleAutomationType spindleAutomateType; + float maxZRPM; + float zDistPerRot; + float zEncoderSteps; + float KpPos; + float KiPos; + float KdPos; + float propWeightPos; + float KpV; + float KiV; + float KdV; + float propWeightV; + float zKpPos; + float zKiPos; + float zKdPos; + float zPropWeightPos; + float zKpV; + float zKiV; + float zKdV; + float zPropWeightV; + float chainSagCorrection; + byte chainOverSprocket; + byte fPWM; + float leftChainTolerance; + float rightChainTolerance; + float positionErrorLimit; + byte eepromValidData; // This should always be last, that way if an error + // happens in writing, it will not be written and we +} settings_t; // will know to reset the settings +extern settings_t sysSettings; + +typedef struct { + byte settingsVersion; + byte eepromValidData; +} settingsVersion_t; + +typedef struct { + long lSteps; + long rSteps; + long zSteps; + byte eepromValidData; +} settingsStepsV1_t; + +void settingsLoadFromEEprom(); +void settingsReset(); +void settingsWipe(byte); +void settingsSaveToEEprom(); +void settingsSaveStepstoEEprom(); +void settingsLoadStepsFromEEprom(); +byte settingsStoreGlobalSetting(const byte&,const float&); + +#endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/SimavrSerial.cpp b/Firmware_1.26b/cnc_ctrl_v1/SimavrSerial.cpp new file mode 100644 index 00000000..5ddebd96 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/SimavrSerial.cpp @@ -0,0 +1,27 @@ +#include "SimavrSerial.h" + +#ifdef Serial +#undef Serial +#endif + +SimavrSerial_ SimavrSerial; + +size_t SimavrSerial_::write(uint8_t c) +{ + size_t n = Serial.write(c); + Serial.flush(); + + return n; +} + +void SimavrSerial_::begin(unsigned long baud) { + Serial.begin(baud); +} + +int SimavrSerial_::available() { + return Serial.available(); +} + +int SimavrSerial_::read() { + return Serial.read(); +} diff --git a/Firmware_1.26b/cnc_ctrl_v1/SimavrSerial.h b/Firmware_1.26b/cnc_ctrl_v1/SimavrSerial.h new file mode 100644 index 00000000..879dd362 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/SimavrSerial.h @@ -0,0 +1,32 @@ +#include "Maslow.h" + +#ifndef SimavrSerial_h_ +#define SimavrSerial_h_ + +#ifdef SIMAVR +#define Serial SimavrSerial +#endif + +// This class is a wrapper around Serial, to be used when running in the simavr simulator +// (https://github.com/buserror/simavr) +// +// Simavr's UART seems to lock up and crash when you write more than a few characters to it. +// SimavrSerial works around this issue by flushing after every single character. On a real +// controller, this might cause a performance issue, so this class is only used if SIMAVR is defined. +// If SIMAVR is defined, though, any reference to Serial is replaces to a reference to SimavrSerial. +// This means that every Serial method that is used in our code also needs a wrapper in SimavrSerial, +// of the simavr environment will not compile. +// +// Not the cleanest thing ever, but it's the best I could come up with that +// will have zero impact on the actual production code. +class SimavrSerial_ : public Print +{ + public: + virtual size_t write(uint8_t); + virtual int available(); + virtual int read(); + void begin(unsigned long baud); +}; + +extern SimavrSerial_ SimavrSerial; +#endif \ No newline at end of file diff --git a/Firmware_1.26b/cnc_ctrl_v1/Spindle.cpp b/Firmware_1.26b/cnc_ctrl_v1/Spindle.cpp new file mode 100644 index 00000000..647acf9c --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Spindle.cpp @@ -0,0 +1,117 @@ +/*This file is part of the Maslow Control Software. + The Maslow Control Software is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + Maslow Control Software is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + You should have received a copy of the GNU General Public License + along with the Maslow Control Software. If not, see . + + Copyright 2014-2017 Bar Smith*/ + +// This contains all of the Spindle commands + +#include "Maslow.h" +#include "Settings.h" + +// the variables SpindlePowerControlPin and LaserPowerPin are assigned in configAuxLow() in System.cpp + +// Globals for Spindle control, both poorly named +Servo myservo; // create servo object to control a servo + +void setSpindlePower(bool powerState) { + /* + * Turn spindle on/off depending on powerState + */ + SpindleAutomationType spindleAutomateType = sysSettings.spindleAutomateType; + + int delayAfterChange = 1000; // milliseconds + int servoIdle = 90; // degrees + int servoOn = 180; // degrees + int servoOff = 0; // degrees + int servoDelay = 2000; // milliseconds + + // Now for the main code + #if defined (verboseDebug) && verboseDebug > 1 + Serial.print(F("Spindle control uses pin ")); + Serial.print(SpindlePowerControlPin); + Serial.print(F("Spindle automation type ")); + Serial.print(spindleAutomateType); + #endif + if (spindleAutomateType == SERVO) { // use a servo to control a standard wall switch + #if defined (verboseDebug) && verboseDebug > 1 + Serial.print(F(" with servo (idle=")); + Serial.print(servoIdle); + Serial.print(F(", on=")); + Serial.print(servoOn); + Serial.print(F(", off=")); + Serial.print(servoOff); + Serial.println(F(")")); + #endif + myservo.attach(SpindlePowerControlPin); // start servo control + myservo.write(servoIdle); // move servo to idle position + maslowDelay(servoDelay); // wait for move to complete + if(sys.stop){return;} + if (powerState) { // turn on spindle + Serial.println(F("Turning Spindle On")); + myservo.write(servoOn); // move servo to turn on switch + } + else { // turn off spindle + Serial.println(F("Turning Spindle Off")); + myservo.write(servoOff); // move servo to turn off switch + } + maslowDelay(servoDelay); // wait for move to complete + if(sys.stop){return;} + myservo.write(servoIdle); // return servo to idle position + maslowDelay(servoDelay); // wait for move to complete + if(sys.stop){return;} + myservo.detach(); // stop servo control + } + else if (spindleAutomateType == RELAY_ACTIVE_HIGH) { + #if defined (verboseDebug) && verboseDebug > 1 + Serial.print(F(" as digital output, active high")); + #endif + pinMode(SpindlePowerControlPin, OUTPUT); + if (powerState) { // turn on spindle + Serial.println(F("Turning Spindle On")); + digitalWrite(SpindlePowerControlPin, HIGH); + } + else { // turn off spindle + Serial.println(F("Turning Spindle Off")); + digitalWrite(SpindlePowerControlPin, LOW); + } + } + else if (spindleAutomateType == RELAY_ACTIVE_LOW) { // use a digital I/O pin to control a relay + #if defined (verboseDebug) && verboseDebug > 1 + Serial.print(F(" as digital output, active low")); + #endif + pinMode(SpindlePowerControlPin, OUTPUT); + if (powerState) { // turn on spindle + Serial.println(F("Turning Spindle On")); + digitalWrite(SpindlePowerControlPin, LOW); + } + else { // turn off spindle + Serial.println(F("Turning Spindle Off")); + digitalWrite(SpindlePowerControlPin, HIGH); + } + } + if (spindleAutomateType != NONE) { + maslowDelay(delayAfterChange); + } +} + +void laserOn(bool OnOff) { + pinMode(LaserPowerPin, OUTPUT); + if (OnOff) { // turn on Laser - EBS BETTER go LOW on system stop + Serial.println(F("Turning Laser ON")); + digitalWrite(LaserPowerPin, HIGH); + } + else { // turn off Laser + // Serial.println(F("Turning Laser OFF")); + digitalWrite(LaserPowerPin, LOW); + } +} + diff --git a/Firmware_1.26b/cnc_ctrl_v1/Spindle.h b/Firmware_1.26b/cnc_ctrl_v1/Spindle.h new file mode 100644 index 00000000..f42fc442 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Spindle.h @@ -0,0 +1,24 @@ +/*This file is part of the Maslow Control Software. + The Maslow Control Software is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + Maslow Control Software is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + You should have received a copy of the GNU General Public License + along with the Maslow Control Software. If not, see . + + Copyright 2014-2017 Bar Smith*/ + +// This contains all of the Spindle commands + +#ifndef spindle_h +#define spindle_h + +void setSpindlePower(bool powerState); +void laserOn(bool OnOff); + + +#endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/System.cpp b/Firmware_1.26b/cnc_ctrl_v1/System.cpp new file mode 100644 index 00000000..e082222d --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/System.cpp @@ -0,0 +1,658 @@ +/*This file is part of the Maslow Control Software. + +The Maslow Control Software is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +Maslow Control Software is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with the Maslow Control Software. If not, see . + +Copyright 2014-2017 Bar Smith*/ + +// This file contains system level functions and states + +#include "Maslow.h" + +bool TLE5206; +bool TB6643; + +// extern values using AUX pins defined in configAuxLow() and configAuxHigh() +int SpindlePowerControlPin; // output for controlling spindle power +int ProbePin; // use this input for zeroing zAxis with G38.2 gcode +int LaserPowerPin; // Use this output to turn on and off a laser diode + + +void calibrateChainLengths(String gcodeLine){ + /* + The calibrateChainLengths function lets the machine know that the chains are set to a given length where each chain is ORIGINCHAINLEN + in length + */ + + if (extractGcodeValue(gcodeLine, 'L', 0)){ + //measure out the left chain + Serial.println(F("Measuring out left chain")); + singleAxisMove(&leftAxis, sysSettings.originalChainLength, (sysSettings.maxFeed * .9)); + + Serial.print(leftAxis.read()); + Serial.println(F("mm")); + + leftAxis.detach(); + } + else if(extractGcodeValue(gcodeLine, 'R', 0)){ + //measure out the right chain + Serial.println(F("Measuring out right chain")); + singleAxisMove(&rightAxis, sysSettings.originalChainLength, (sysSettings.maxFeed * .9)); + + Serial.print(rightAxis.read()); + Serial.println(F("mm")); + + rightAxis.detach(); + } + +} + +void setupAxes(){ + /* + + Detect the version of the Arduino shield connected, and use the appropriate pins + + This function runs before the serial port is open so the version is not printed here + + */ + + + int encoder1A; + int encoder1B; + int encoder2A; + int encoder2B; + int encoder3A; + int encoder3B; + + int in1; + int in2; + int in3; + int in4; + int in5; + int in6; + + int enA; + int enB; + int enC; + + int aux1; + int aux2; + int aux3; + int aux4; + int aux5; + int aux6; + int aux7; + int aux8; + int aux9; + + //read the pins which indicate the PCB version + int pcbVersion = getPCBVersion(); + + if(pcbVersion == 0){ + //Beta PCB v1.0 Detected + //MP1 - Right Motor + encoder1A = 18; // INPUT + encoder1B = 19; // INPUT + in1 = 9; // OUTPUT + in2 = 8; // OUTPUT + enA = 6; // PWM + + //MP2 - Z-axis + encoder2A = 2; // INPUT + encoder2B = 3; // INPUT + in3 = 11; // OUTPUT + in4 = 10; // OUTPUT + enB = 7; // PWM + + //MP3 - Left Motor + encoder3A = 21; // INPUT + encoder3B = 20; // INPUT + in5 = 12; // OUTPUT + in6 = 13; // OUTPUT + enC = 5; // PWM + + //AUX pins + aux1 = 17; + aux2 = 16; + aux3 = 15; + aux4 = 14; + aux5 = 0; // warning! this is the serial TX line on the Mega2560 + aux6 = 1; // warning! this is the serial RX line on the Mega2560 + } + else if(pcbVersion == 1){ + //PCB v1.1 Detected + //MP1 - Right Motor + encoder1A = 20; // INPUT + encoder1B = 21; // INPUT + in1 = 6; // OUTPUT + in2 = 4; // OUTPUT + enA = 5; // PWM + + //MP2 - Z-axis + encoder2A = 19; // INPUT + encoder2B = 18; // INPUT + in3 = 9; // OUTPUT + in4 = 7; // OUTPUT + enB = 8; // PWM + + //MP3 - Left Motor + encoder3A = 2; // INPUT + encoder3B = 3; // INPUT + in5 = 10; // OUTPUT + in6 = 11; // OUTPUT + enC = 12; // PWM + + //AUX pins + aux1 = 17; + aux2 = 16; + aux3 = 15; + aux4 = 14; + aux5 = A7; + aux6 = A6; + } + else if(pcbVersion == 2){ + //PCB v1.2 Detected + + //MP1 - Right Motor + encoder1A = 20; // INPUT + encoder1B = 21; // INPUT + in1 = 4; // OUTPUT + in2 = 6; // OUTPUT + enA = 5; // PWM + + //MP2 - Z-axis + encoder2A = 19; // INPUT + encoder2B = 18; // INPUT + in3 = 7; // OUTPUT + in4 = 9; // OUTPUT + enB = 8; // PWM + + //MP3 - Left Motor + encoder3A = 2; // INPUT + encoder3B = 3; // INPUT + in5 = 11; // OUTPUT + in6 = 12; // OUTPUT + enC = 10; // PWM + + //AUX pins + aux1 = 17; + aux2 = 16; + aux3 = 15; + aux4 = 14; + aux5 = A7; + aux6 = A6; + } + else if(pcbVersion == 4){ // TLE5206 + //TLE5206 PCB v1.4 Detected + //MP1 - Right Motor + encoder1A = 20; // INPUT + encoder1B = 21; // INPUT + in1 = 6; // OUTPUT + in2 = 4; // OUTPUT + enA = 5; // errorFlag + + //MP2 - Z-axis + encoder2A = 19; // INPUT + encoder2B = 18; // INPUT + in3 = 7; // OUTPUT + in4 = 9; // OUTPUT + enB = 8; // errorFlag + + //MP3 - Left Motor + encoder3A = 2; // INPUT + encoder3B = 3; // INPUT + in5 = 10; // OUTPUT + in6 = 11; // OUTPUT + enC = 12; // errorFlag + + //AUX pins + aux1 = 40; + aux2 = 41; + aux3 = 42; + aux4 = 43; + aux5 = 68; + aux6 = 69; + aux7 = 45; + aux8 = 46; + aux9 = 47; + } +else if(pcbVersion == 5){ // EBS PCB v1.5 Detected + + //MP1 - Right Motor + encoder1A = 2; // INPUT + encoder1B = 3; // INPUT + in1 = 9; // OUTPUT + in2 = 10; // OUTPUT + //enA = 12; // errorFlag + + //MP2 - Z-axis + encoder2A = 18; // INPUT + encoder2B = 19; // INPUT + in3 = 7; // OUTPUT + in4 = 8; // OUTPUT + //enB = 8; // errorFlag + + //MP3 - Left Motor + encoder3A = 21; // INPUT + encoder3B = 20; // INPUT + in5 = 6; // OUTPUT + in6 = 5; // OUTPUT + //enC = 5; // errorFlag + + //AUX pins + aux1 = 48; + aux2 = 49; + aux3 = 51; + aux4 = 50; + aux5 = 43; + aux6 = 44; + } + + if(sysSettings.chainOverSprocket == 1){ + leftAxis.setup (enC, in6, in5, encoder3B, encoder3A, 'L', LOOPINTERVAL); + rightAxis.setup(enA, in1, in2, encoder1A, encoder1B, 'R', LOOPINTERVAL); + } + else{ + leftAxis.setup (enC, in5, in6, encoder3A, encoder3B, 'L', LOOPINTERVAL); + rightAxis.setup(enA, in2, in1, encoder1B, encoder1A, 'R', LOOPINTERVAL); + } + + zAxis.setup (enB, in3, in4, encoder2B, encoder2A, 'Z', LOOPINTERVAL); + leftAxis.setPIDValues(&sysSettings.KpPos, &sysSettings.KiPos, &sysSettings.KdPos, &sysSettings.propWeightPos, &sysSettings.KpV, &sysSettings.KiV, &sysSettings.KdV, &sysSettings.propWeightV); + rightAxis.setPIDValues(&sysSettings.KpPos, &sysSettings.KiPos, &sysSettings.KdPos, &sysSettings.propWeightPos, &sysSettings.KpV, &sysSettings.KiV, &sysSettings.KdV, &sysSettings.propWeightV); + zAxis.setPIDValues(&sysSettings.zKpPos, &sysSettings.zKiPos, &sysSettings.zKdPos, &sysSettings.zPropWeightPos, &sysSettings.zKpV, &sysSettings.zKiV, &sysSettings.zKdV, &sysSettings.zPropWeightV); + + // implement the AUXx values that are 'used'. This accomplishes setting their values at runtime. + // Using a separate function is a compiler work-around to avoid + // "warning: variable ‘xxxxx’ set but not used [-Wunused-but-set-variable]" + // for AUX pins defined but not connected + configAuxLow(aux1, aux2, aux3, aux4, aux5, aux6); + if(pcbVersion == 4){ // TLE5206 + configAuxHigh(aux7, aux8, aux9); + } +} + +// Assign AUX pins to extern variables used by functions like Spindle and Probe +void configAuxLow(int aux1, int aux2, int aux3, int aux4, int aux5, int aux6) { + SpindlePowerControlPin = aux1; // output for controlling spindle power + LaserPowerPin = aux2; // output for controlling a laser diode + ProbePin = aux4; // use this input for zeroing zAxis with G38.2 gcode + pinMode(LaserPowerPin, OUTPUT); + digitalWrite(LaserPowerPin, LOW); +} + +void configAuxHigh(int aux7, int aux8, int aux9) { +} + +int getPCBVersion(){ + pinMode(VERS1,INPUT_PULLUP); //22 + pinMode(VERS2,INPUT_PULLUP); //23 + pinMode(VERS3,INPUT_PULLUP); //24 + pinMode(VERS4,INPUT_PULLUP); //25 + pinMode(VERS5,INPUT_PULLUP); //26 + pinMode(VERS6,INPUT_PULLUP); //27 + int pinCheck = (32*digitalRead(VERS6) + 16*digitalRead(VERS5) + 8*digitalRead(VERS4) + 4*digitalRead(VERS3) + 2*digitalRead(VERS2) + 1*digitalRead(VERS1)); + switch (pinCheck) { + // boards v1.0, v1.1, v1.2 don't strap VERS3-6 low + case B111101: case B111110: case B111111: // v 1.0, v1.1, v1.2 + pinCheck &= B000011; // strip off the unstrapped bits + TLE5206 = false; + break; + case B110100: case B000100: // some versions of board v1.3, v1.4 don't strap VERS5-6 low + pinCheck = 5; // V1.3 ~ V1.4 - SAME SHIELD + TLE5206 = true; + break; + case B000110: // new v1.5 + pinCheck &= B000110; // + TB6643 = true; + TLE5206 = false; + break; + +} + return pinCheck - 1; +} + + +// +// PWM frequency change +// presently just sets the default value +// different values seem to need specific PWM tunings... +// +void setPWMPrescalers(int prescalerChoice) { + #if defined (verboseDebug) && verboseDebug > 0 + Serial.print(F("fPWM set to ")); + switch (prescalerChoice) { + case 1: + Serial.println(F("31,000Hz")); + break; + case 2: + Serial.println(F("4,100Hz")); + break; + case 3: + Serial.println(F("490Hz")); + } + #endif + + // tailor the PWM frequency to the chip + //if (TLE5206) { + // The upper limit to PWM frequency for TLE5206 is 1,000Hz + // so only '3' is valid + // prescalerChoice = 3; + //} else if (TLE9201) { + // The upper limit to PWM frequency for TLE9201 is 20,000Hz + // prescalerChoice = 3; + // } + //} else if (TB6643) { + // The upper limit to PWM frequency for TB6643 is 100kz + // prescalerChoice = 3; + // } + + + +// first must erase the bits in each TTCRxB register that control the timers prescaler + int prescalerEraser = 7; // this is 111 in binary and is used as an eraser + TCCR2B &= ~prescalerEraser; // this operation sets the three bits in TCCR2B to 0 + TCCR3B &= ~prescalerEraser; // this operation sets the three bits in TCCR3B to 0 + TCCR4B &= ~prescalerEraser; // this operation sets the three bits in TCCR4B to 0 + // now set those same three bits + + +//----------------------------------------------- +//timer 0 ----- pin 4, 13 +//timer 1 ----- pin 11, 12 +//timer 2 ----- pin 9, 10 +//timer 3 ----- pin 2, 3, 5 +//timer 4 ----- pin 6, 7, 8 +//timer 5 ----- pin 44, 45, 46 +// ————————————————————————————– +// TIMER 2  +// Value Divisor Frequency +// 0x01 1 31.374 KHz +// 0x02 8 3.921 KHz +// 0x03 32 980.3 Hz // don;t use this... +// 0x04 64 490.1 Hz // default +// 0x05 128 245 hz +// 0x06 256 122.5 hz +// 0x07 1024 30.63 hz +// Code: TCCR2B = (TCCR2B & 0xF8) | value ; +// —————————————————————————————- +// Timers 3 & 4 +// +// Value Divisor Frequency +// 0x01 1 31.374 KHz +// 0x02 8 3.921 Khz +// 0x03 64 490.1 Hz        // default +// 0x04 256 122.5 Hz +// 0x05 1024 30.63 Hz +// Code: TCCR3B = (TCCR3B & 0xF8) | value ; +// —————————————————————————————- + // and apply it + if (prescalerChoice >= 3) { + TCCR2B |= (prescalerChoice + 1); // pins 9, 10 - change to match timers3&4 + } else { + TCCR2B |= prescalerChoice; // pins 9, 10 + } + TCCR3B |= prescalerChoice; // pins 2, 3, 5 + TCCR4B |= prescalerChoice; // pins 6, 7, 8 +} + + +// This should likely go away and be handled by setting the pause flag and then +// pausing in the execSystemRealtime function +// Need to check if all returns from this subsequently look to sys.stop +void pause(){ + /* + + The pause command pauses the machine in place without flushing the lines stored in the machine's + buffer. + + When paused the machine enters a while() loop and doesn't exit until the '~' cycle resume command + is issued from Ground Control. + + */ + + bit_true(sys.pause, PAUSE_FLAG_USER_PAUSE); + Serial.println(F("Maslow Paused")); + + while(bit_istrue(sys.pause, PAUSE_FLAG_USER_PAUSE)) { + + // Run realtime commands + execSystemRealtime(); + if (sys.stop){return;} + } +} + + +// This is an important concept. I think maybe this should be expanded and Used +// whenever we have a delay. This should be all of the 'realtime' operations +// and should probably include check for stop command. Although, the holdPosition +// would have to be moved out of here, but I think that is probably correct + +// need to check if all returns from here check for sys.stop +void maslowDelay(unsigned long waitTimeMs) { + /* + * Provides a time delay while holding the machine position, reading serial commands, + * and periodically sending the machine position to Ground Control. This prevents + * Ground Control from thinking that the connection is lost. + * + * This is similar to the pause() command above, but provides a time delay rather than + * waiting for the user (through Ground Control) to tell the machine to continue. + */ + + unsigned long startTime = millis(); + + while ((millis() - startTime) < waitTimeMs){ + execSystemRealtime(); + if (sys.stop){return;} + } +} + +// This executes all of the actions that we want to happen in 'realtime'. This +// should be called whenever there is a delay in the code or when it may have +// been a long time since this command was called. Everything that is executed +// by this command should be relatively fast. Should always check for sys.stop +// after returning from this function +void execSystemRealtime(){ + readSerialCommands(); + returnPoz(); + systemSaveAxesPosition(); + motionDetachIfIdle(); + // check systemRtExecAlarm flag and do stuff +} + +void systemSaveAxesPosition(){ + /* + Save steps of axes to EEPROM if they are all detached + */ + if (!leftAxis.attached() && !rightAxis.attached() && !zAxis.attached()){ + settingsSaveStepstoEEprom(); + } +} + +void systemReset(){ + /* + Stops everything and resets the arduino + */ + leftAxis.detach(); + rightAxis.detach(); + zAxis.detach(); + setSpindlePower(false); + laserOn(false); // EBS + // Reruns the initial setup function and calls stop to re-init state + sys.stop = true; + setup(); +} + +byte systemExecuteCmdstring(String& cmdString){ + /* + This function processes the $ system commands + + This is taken heavily from grbl. https://github.com/grbl/grbl + */ + byte char_counter = 1; +// byte helper_var = 0; // Helper variable + float parameter, value; + if (cmdString.length() == 1){ + reportMaslowHelp(); + } + else { + switch( cmdString[char_counter] ) { + case '$': // case 'G': case 'C': case 'X': + if ( cmdString.length() > 2 ) { return(STATUS_INVALID_STATEMENT); } + switch( cmdString[char_counter] ) { + case '$' : // Prints Maslow settings + // if ( sys.state & (STATE_CYCLE | STATE_HOLD) ) { return(STATUS_IDLE_ERROR); } // Block during cycle. Takes too long to print. + // else { + reportMaslowSettings(); + // } + break; + // case 'G' : // Prints gcode parser state + // report_gcode_modes(); + // break; + // case 'C' : // Set check g-code mode [IDLE/CHECK] + // // Perform reset when toggling off. Check g-code mode should only work if Grbl + // // is idle and ready, regardless of alarm locks. This is mainly to keep things + // // simple and consistent. + // if ( sys.state == STATE_CHECK_MODE ) { + // mc_reset(); + // report_feedback_message(MESSAGE_DISABLED); + // } else { + // if (sys.state) { return(STATUS_IDLE_ERROR); } // Requires no alarm mode. + // sys.state = STATE_CHECK_MODE; + // report_feedback_message(MESSAGE_ENABLED); + // } + // break; + // case 'X' : // Disable alarm lock [ALARM] + // if (sys.state == STATE_ALARM) { + // report_feedback_message(MESSAGE_ALARM_UNLOCK); + // sys.state = STATE_IDLE; + // // Don't run startup script. Prevents stored moves in startup from causing accidents. + // if (system_check_safety_door_ajar()) { // Check safety door switch before returning. + // bit_true(sys_rt_exec_state, EXEC_SAFETY_DOOR); + // protocol_execute_realtime(); // Enter safety door mode. + // } + // } // Otherwise, no effect. + // break; + } + break; + //case 'J' : break; // Jogging methods + // TODO: Here jogging can be placed for execution as a seperate subprogram. It does not need to be + // susceptible to other realtime commands except for e-stop. The jogging function is intended to + // be a basic toggle on/off with controlled acceleration and deceleration to prevent skipped + // steps. The user would supply the desired feedrate, axis to move, and direction. Toggle on would + // start motion and toggle off would initiate a deceleration to stop. One could 'feather' the + // motion by repeatedly toggling to slow the motion to the desired location. Location data would + // need to be updated real-time and supplied to the user through status queries. + // More controlled exact motions can be taken care of by inputting G0 or G1 commands, which are + // handled by the planner. It would be possible for the jog subprogram to insert blocks into the + // block buffer without having the planner plan them. It would need to manage de/ac-celerations + // on its own carefully. This approach could be effective and possibly size/memory efficient. + // break; + // } + //break; + default : + // Block any system command that requires the state as IDLE/ALARM. (i.e. EEPROM, homing) + // if ( !(sys.state == STATE_IDLE || sys.state == STATE_ALARM) ) { return(STATUS_IDLE_ERROR); } + switch( cmdString[char_counter] ) { + // case '#' : // Print Grbl NGC parameters + // if ( line[++char_counter] != 0 ) { return(STATUS_INVALID_STATEMENT); } + // else { report_ngc_parameters(); } + // break; + // case 'H' : // Perform homing cycle [IDLE/ALARM] + // if (bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)) { + // sys.state = STATE_HOMING; // Set system state variable + // // Only perform homing if Grbl is idle or lost. + // + // // TODO: Likely not required. + // if (system_check_safety_door_ajar()) { // Check safety door switch before homing. + // bit_true(sys_rt_exec_state, EXEC_SAFETY_DOOR); + // protocol_execute_realtime(); // Enter safety door mode. + // } + // + // + // mc_homing_cycle(); + // if (!sys.abort) { // Execute startup scripts after successful homing. + // sys.state = STATE_IDLE; // Set to IDLE when complete. + // st_go_idle(); // Set steppers to the settings idle state before returning. + // system_execute_startup(line); + // } + // } else { return(STATUS_SETTING_DISABLED); } + // break; + // case 'I' : // Print or store build info. [IDLE/ALARM] + // if ( line[++char_counter] == 0 ) { + // settings_read_build_info(line); + // report_build_info(line); + // } else { // Store startup line [IDLE/ALARM] + // if(line[char_counter++] != '=') { return(STATUS_INVALID_STATEMENT); } + // helper_var = char_counter; // Set helper variable as counter to start of user info line. + // do { + // line[char_counter-helper_var] = line[char_counter]; + // } while (line[char_counter++] != 0); + // settings_store_build_info(line); + // } + // break; + case 'R' : // Restore defaults [IDLE/ALARM] + if (cmdString[++char_counter] != 'S') { return(STATUS_INVALID_STATEMENT); } + if (cmdString[++char_counter] != 'T') { return(STATUS_INVALID_STATEMENT); } + if (cmdString[++char_counter] != '=') { return(STATUS_INVALID_STATEMENT); } + if (cmdString.length() != 6) { return(STATUS_INVALID_STATEMENT); } + switch (cmdString[++char_counter]) { + case '$': settingsWipe(SETTINGS_RESTORE_SETTINGS); break; + case '#': settingsWipe(SETTINGS_RESTORE_MASLOW); break; + case '*': settingsWipe(SETTINGS_RESTORE_ALL); break; + default: return(STATUS_INVALID_STATEMENT); + } + reportFeedbackMessage(MESSAGE_RESTORE_DEFAULTS); + systemReset(); // Force reset to ensure settings are initialized correctly. + break; + // case 'N' : // Startup lines. [IDLE/ALARM] + // if ( line[++char_counter] == 0 ) { // Print startup lines + // for (helper_var=0; helper_var < N_STARTUP_LINE; helper_var++) { + // if (!(settings_read_startup_line(helper_var, line))) { + // report_status_message(STATUS_SETTING_READ_FAIL); + // } else { + // report_startup_line(helper_var,line); + // } + // } + // break; + // } else { // Store startup line [IDLE Only] Prevents motion during ALARM. + // if (sys.state != STATE_IDLE) { return(STATUS_IDLE_ERROR); } // Store only when idle. + // helper_var = true; // Set helper_var to flag storing method. + // // No break. Continues into default: to read remaining command characters. + // } + default : // Storing setting methods [IDLE/ALARM] + if(!readFloat(cmdString, char_counter, parameter)) { return(STATUS_BAD_NUMBER_FORMAT); } + if(cmdString[char_counter++] != '=') { return(STATUS_INVALID_STATEMENT); } + // if (helper_var) { // Store startup line + // // Prepare sending gcode block to gcode parser by shifting all characters + // helper_var = char_counter; // Set helper variable as counter to start of gcode block + // do { + // line[char_counter-helper_var] = line[char_counter]; + // } while (line[char_counter++] != 0); + // // Execute gcode block to ensure block is valid. + // helper_var = gc_execute_line(line); // Set helper_var to returned status code. + // if (helper_var) { return(helper_var); } + // else { + // helper_var = trunc(parameter); // Set helper_var to int value of parameter + // settings_store_startup_line(helper_var,line); + // } + // } else { // Store global setting. + if(!readFloat(cmdString, char_counter, value)) { return(STATUS_BAD_NUMBER_FORMAT); } + if((cmdString[char_counter] != 0) || (parameter > 255)) { return(STATUS_INVALID_STATEMENT); } + return(settingsStoreGlobalSetting((byte)parameter, value)); + // } + } + } + } + return(STATUS_OK); +} diff --git a/Firmware_1.26b/cnc_ctrl_v1/System.h b/Firmware_1.26b/cnc_ctrl_v1/System.h new file mode 100644 index 00000000..9e297e47 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/System.h @@ -0,0 +1,94 @@ +/*This file is part of the Maslow Control Software. + +The Maslow Control Software is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +Maslow Control Software is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with the Maslow Control Software. If not, see . + +Copyright 2014-2017 Bar Smith*/ + +#ifndef system_h +#define system_h + +// Convenience Defines - Maybe move into a nuts and bolts file? +#define FORWARD 1 +#define BACKWARD -1 +#define CLOCKWISE -1 +#define COUNTERCLOCKWISE 1 +#define MILLIMETERS 1 +#define INCHES 25.4 + +// Define various pause bits +#define PAUSE_FLAG_USER_PAUSE bit(0) // a pause triggered within the code that must be cleared by user using the ~ command + +// Define system state bit map. The state variable primarily tracks the individual functions +// of Maslow to manage each without overlapping. It is also used as a messaging flag for +// critical events. +#define STATE_IDLE 0 // Must be zero. No flags. +#define STATE_ALARM bit(0) // In alarm state. Locks out all g-code processes. Allows settings access. +#define STATE_CHECK_MODE bit(1) // G-code check mode. Locks out planner and motion only. +#define STATE_OLD_SETTINGS bit(2) // Locks out all g-code processes, allows settings access until old settings are loaded +#define STATE_CYCLE bit(3) // Cycle is running or motions are being executed. +#define STATE_HOLD bit(4) // Active feed hold +#define STATE_SAFETY_DOOR bit(5) // Safety door is ajar. Feed holds and de-energizes system. +#define STATE_MOTION_CANCEL bit(6) // Motion cancel by feed hold and return to idle. +#define STATE_POS_ERR_IGNORE bit(7) // Motion not checked for position error + +// Define old settings flag details +#define NEED_ENCODER_STEPS bit(0) +#define NEED_DIST_PER_ROT bit(1) +#define NEED_Z_ENCODER_STEPS bit(2) +#define NEED_Z_DIST_PER_ROT bit(3) + +// Storage for global system states +// Some of this could be more appropriately moved to the gcode parser +typedef struct { + bool stop; // Stop flag. + byte state; // State tracking flag + byte pause; // Pause flag. + float xPosition; // Cartessian position of XY axes + float yPosition; // Cached because calculating position is intensive + float steps[3]; // Encoder position of axes + bool useRelativeUnits; // + unsigned long lastSerialRcvd; // The millis of the last rcvd serial command, used by watchdo + int lastGCommand; //Stores the value of the last command run eg: G01 -> 1 + int lastTool; //Stores the value of the last tool number eg: T4 -> 4 + int nextTool; //Stores the value of the next tool number eg: T4 -> 4 + float inchesToMMConversion; //Used to track whether to convert from inches, can probably be done in a way that doesn't require RAM + float feedrate; //The feedrate of the machine in mm/min + // THE FOLLOWING IS USED FOR IMPORTING SETTINGS FROM FIRMWARE v1.00 AND EARLIER + // It can be deleted at some point + byte oldSettingsFlag; +} system_t; +extern system_t sys; +extern Axis leftAxis; +extern Axis rightAxis; +extern Axis zAxis; +extern RingBuffer incSerialBuffer; +extern Kinematics kinematics; +extern byte systemRtExecAlarm; +extern int SpindlePowerControlPin; +extern int LaserPowerPin; +extern int ProbePin; + +void calibrateChainLengths(String); +void setupAxes(); +int getPCBVersion(); +void pause(); +void maslowDelay(unsigned long); +void execSystemRealtime(); +void systemSaveAxesPosition(); +void systemReset(); +byte systemExecuteCmdstring(String&); +void setPWMPrescalers(int prescalerChoice); +void configAuxLow(int A1, int A2, int A3, int A4, int A5, int A6); +void configAuxHigh(int A7, int A8, int A9); +#endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/Testing.cpp b/Firmware_1.26b/cnc_ctrl_v1/Testing.cpp new file mode 100644 index 00000000..3f8bfa39 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Testing.cpp @@ -0,0 +1,181 @@ +/*This file is part of the Maslow Control Software. + The Maslow Control Software is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + Maslow Control Software is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + You should have received a copy of the GNU General Public License + along with the Maslow Control Software. If not, see . + + Copyright 2014-2017 Bar Smith*/ + +// This file contains various testing provisions + +#include "Maslow.h" + +void PIDTestVelocity(Axis* axis, const float start, const float stop, const float steps, const float version){ + // Moves the defined Axis at series of speed steps for PID tuning + // Start Log + Serial.println(F("--PID Velocity Test Start--")); + Serial.println(axis->motorGearboxEncoder.getPIDString()); + if (version == 2) { + Serial.println(F("setpoint,input,output")); + } + + double startTime; + double print = micros(); + double current = micros(); + float error; + float reportedSpeed; + float span = stop - start; + float speed; + + // Start the steps + axis->disablePositionPID(); + axis->attach(); + for(int i = 0; i < steps; i++){ + // 1 step = start, 2 step = start & finish, 3 = start, start + 1/2 span... + speed = start; + if (i > 0){ + speed = start + (span * (i/(steps-1))); + } + startTime = micros(); + axis->motorGearboxEncoder.write(speed); + while (startTime + 2000000 > current){ + if (current - print > LOOPINTERVAL){ + if (version == 2) { + Serial.println(axis->motorGearboxEncoder.pidState()); + } + else { + reportedSpeed= axis->motorGearboxEncoder.cachedSpeed(); + error = reportedSpeed - speed; + print = current; + Serial.println(error); + } + } + current = micros(); + } + } + axis->motorGearboxEncoder.write(0); + + // Print end of log, and update axis for use again + Serial.println(F("--PID Velocity Test Stop--\n")); + axis->write(axis->read()); + axis->detach(); + axis->enablePositionPID(); + kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition, 0.0, 0.0); +} + +void positionPIDOutput (Axis* axis, float setpoint, float startingPoint){ + Serial.print((setpoint - startingPoint), 4); + Serial.print(F(",")); + Serial.print((axis->pidInput() - startingPoint),4); + Serial.print(F(",")); + Serial.print(axis->pidOutput(),4); + Serial.print(F(",")); + Serial.print(axis->motorGearboxEncoder.cachedSpeed(), 4); + Serial.print(F(",")); + Serial.println(axis->motorGearboxEncoder.motor.lastSpeed()); +} + +void PIDTestPosition(Axis* axis, float start, float stop, const float steps, const float stepTime, const float version){ + // Moves the defined Axis at series of chain distance steps for PID tuning + // Start Log + Serial.println(F("--PID Position Test Start--")); + Serial.println(axis->getPIDString()); + if (version == 2) { + Serial.println(F("setpoint,input,output,rpminput,voltage")); + } + + unsigned long startTime; + unsigned long print = micros(); + unsigned long current = micros(); + float error; + float startingPoint = axis->read(); + start = startingPoint + start; + stop = startingPoint + stop; + float span = stop - start; + float location; + + // Start the steps + axis->attach(); + for(int i = 0; i < steps; i++){ + // 1 step = start, 2 step = start & finish, 3 = start, start + 1/2 span... + location = start; + if (i > 0){ + location = start + (span * (i/(steps-1))); + } + startTime = micros(); + current = micros(); + axis->write(location); + while (startTime + (stepTime * 1000) > current){ + if (current - print > LOOPINTERVAL){ + if (version == 2) { + positionPIDOutput(axis, location, startingPoint); + } + else { + error = axis->read() - location; + Serial.println(error); + } + print = current; + } + current = micros(); + } + } + startTime = micros(); + current = micros(); + //Allow 1 seccond to settle out + while (startTime + 1000000 > current){ + if (current - print > LOOPINTERVAL){ + if (version == 2) { + positionPIDOutput(axis, location, startingPoint); + } + else { + error = axis->read() - location; + Serial.println(error); + } + print = current; + } + current = micros(); + } + // Print end of log, and update axis for use again + Serial.println(F("--PID Position Test Stop--\n")); + axis->write(axis->read()); + axis->detach(); + kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition, 0.0, 0.0); +} + +void voltageTest(Axis* axis, int start, int stop){ + // Moves the defined Axis at a series of voltages and reports the resulting + // RPM + Serial.println(F("--Voltage Test Start--")); + int direction = 1; + if (stop < start){ direction = -1;} + int steps = abs(start - stop); + unsigned long startTime = millis() + 200; + unsigned long currentTime = millis(); + unsigned long printTime = 0; + + for (int i = 0; i <= steps; i++){ + axis->motorGearboxEncoder.motor.directWrite((start + (i*direction))); + while (startTime > currentTime - (i * 200)){ + currentTime = millis(); + if ((printTime + 50) <= currentTime){ + Serial.print((start + (i*direction))); + Serial.print(F(",")); + Serial.print(axis->motorGearboxEncoder.computeSpeed(),4); + Serial.print(F("\n")); + printTime = millis(); + } + } + } + + // Print end of log, and update axis for use again + axis->motorGearboxEncoder.motor.directWrite(0); + Serial.println(F("--Voltage Test Stop--\n")); + axis->write(axis->read()); + kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition, 0.0, 0.0); +} \ No newline at end of file diff --git a/Firmware_1.26b/cnc_ctrl_v1/Testing.h b/Firmware_1.26b/cnc_ctrl_v1/Testing.h new file mode 100644 index 00000000..4673b012 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/Testing.h @@ -0,0 +1,25 @@ +/*This file is part of the Maslow Control Software. + The Maslow Control Software is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + Maslow Control Software is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + You should have received a copy of the GNU General Public License + along with the Maslow Control Software. If not, see . + + Copyright 2014-2017 Bar Smith*/ + +// This file contains various testing provisions + +#ifndef testing_h +#define testing_h + +void PIDTestVelocity(Axis*, const float, const float, const float, const float); +void positionPIDOutput (Axis*, float, float); +void PIDTestPosition(Axis*, float, float, const float, const float, const float); +void voltageTest(Axis*, int, int); + +#endif \ No newline at end of file diff --git a/Firmware_1.26b/cnc_ctrl_v1/TimerOne.cpp b/Firmware_1.26b/cnc_ctrl_v1/TimerOne.cpp new file mode 100644 index 00000000..5db3b317 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/TimerOne.cpp @@ -0,0 +1,209 @@ +/* + * Interrupt and PWM utilities for 16 bit Timer1 on ATmega168/328 + * Original code by Jesse Tane for http://labs.ideo.com August 2008 + * Modified March 2009 by Jérôme Despatis and Jesse Tane for ATmega328 support + * Modified June 2009 by Michael Polli and Jesse Tane to fix a bug in setPeriod() which caused the timer to stop + * Modified June 2011 by Lex Talionis to add a function to read the timer + * Modified Oct 2011 by Andrew Richards to avoid certain problems: + * - Add (long) assignments and casts to TimerOne::read() to ensure calculations involving tmp, ICR1 and TCNT1 aren't truncated + * - Ensure 16 bit registers accesses are atomic - run with interrupts disabled when accessing + * - Remove global enable of interrupts (sei())- could be running within an interrupt routine) + * - Disable interrupts whilst TCTN1 == 0. Datasheet vague on this, but experiment shows that overflow interrupt + * flag gets set whilst TCNT1 == 0, resulting in a phantom interrupt. Could just set to 1, but gets inaccurate + * at very short durations + * - startBottom() added to start counter at 0 and handle all interrupt enabling. + * - start() amended to enable interrupts + * - restart() amended to point at startBottom() + * Modiied 7:26 PM Sunday, October 09, 2011 by Lex Talionis + * - renamed start() to resume() to reflect it's actual role + * - renamed startBottom() to start(). This breaks some old code that expects start to continue counting where it left off + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + * See Google Code project http://code.google.com/p/arduino-timerone/ for latest + */ +#ifndef TIMERONE_cpp +#define TIMERONE_cpp + +#include "Maslow.h" + +TimerOne Timer1; // preinstatiate + +ISR(TIMER1_OVF_vect) // interrupt service routine that wraps a user defined function supplied by attachInterrupt +{ + Timer1.isrCallback(); +} + + +void TimerOne::initialize(long microseconds) +{ + TCCR1A = 0; // clear control register A + TCCR1B = _BV(WGM13); // set mode 8: phase and frequency correct pwm, stop the timer + setPeriod(microseconds); +} + + +void TimerOne::setPeriod(long microseconds) // AR modified for atomic access +{ + + long cycles = (F_CPU / 2000000) * microseconds; // the counter runs backwards after TOP, interrupt is at BOTTOM so divide microseconds by 2 + if(cycles < RESOLUTION) clockSelectBits = _BV(CS10); // no prescale, full xtal + else if((cycles >>= 3) < RESOLUTION) clockSelectBits = _BV(CS11); // prescale by /8 + else if((cycles >>= 3) < RESOLUTION) clockSelectBits = _BV(CS11) | _BV(CS10); // prescale by /64 + else if((cycles >>= 2) < RESOLUTION) clockSelectBits = _BV(CS12); // prescale by /256 + else if((cycles >>= 2) < RESOLUTION) clockSelectBits = _BV(CS12) | _BV(CS10); // prescale by /1024 + else cycles = RESOLUTION - 1, clockSelectBits = _BV(CS12) | _BV(CS10); // request was out of bounds, set as maximum + + oldSREG = SREG; + cli(); // Disable interrupts for 16 bit register access + ICR1 = pwmPeriod = cycles; // ICR1 is TOP in p & f correct pwm mode + SREG = oldSREG; + + TCCR1B &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12)); + TCCR1B |= clockSelectBits; // reset clock select register, and starts the clock +} + +void TimerOne::setPwmDuty(char pin, int duty) +{ + unsigned long dutyCycle = pwmPeriod; + + dutyCycle *= duty; + dutyCycle >>= 10; + + oldSREG = SREG; + cli(); + if(pin == 1 || pin == 9) OCR1A = dutyCycle; + else if(pin == 2 || pin == 10) OCR1B = dutyCycle; + SREG = oldSREG; +} + +void TimerOne::pwm(char pin, int duty, long microseconds) // expects duty cycle to be 10 bit (1024) +{ + if(microseconds > 0) setPeriod(microseconds); + if(pin == 1 || pin == 9) { + DDRB |= _BV(PORTB1); // sets data direction register for pwm output pin + TCCR1A |= _BV(COM1A1); // activates the output pin + } + else if(pin == 2 || pin == 10) { + DDRB |= _BV(PORTB2); + TCCR1A |= _BV(COM1B1); + } + setPwmDuty(pin, duty); + resume(); // Lex - make sure the clock is running. We don't want to restart the count, in case we are starting the second WGM + // and the first one is in the middle of a cycle +} + +void TimerOne::disablePwm(char pin) +{ + if(pin == 1 || pin == 9) TCCR1A &= ~_BV(COM1A1); // clear the bit that enables pwm on PB1 + else if(pin == 2 || pin == 10) TCCR1A &= ~_BV(COM1B1); // clear the bit that enables pwm on PB2 +} + +void TimerOne::attachInterrupt(void (*isr)(), long microseconds) +{ + if(microseconds > 0) setPeriod(microseconds); + isrCallback = isr; // register the user's callback with the real ISR + TIMSK1 = _BV(TOIE1); // sets the timer overflow interrupt enable bit + // might be running with interrupts disabled (eg inside an ISR), so don't touch the global state +// sei(); + resume(); +} + +void TimerOne::detachInterrupt() +{ + TIMSK1 &= ~_BV(TOIE1); // clears the timer overflow interrupt enable bit + // timer continues to count without calling the isr +} + +void TimerOne::resume() // AR suggested +{ + TCCR1B |= clockSelectBits; +} + +void TimerOne::restart() // Depricated - Public interface to start at zero - Lex 10/9/2011 +{ + start(); +} + +void TimerOne::start() // AR addition, renamed by Lex to reflect it's actual role +{ + unsigned int tcnt1; + + TIMSK1 &= ~_BV(TOIE1); // AR added + GTCCR |= _BV(PSRSYNC); // AR added - reset prescaler (NB: shared with all 16 bit timers); + + oldSREG = SREG; // AR - save status register + cli(); // AR - Disable interrupts + TCNT1 = 0; + SREG = oldSREG; // AR - Restore status register + resume(); + do { // Nothing -- wait until timer moved on from zero - otherwise get a phantom interrupt + oldSREG = SREG; + cli(); + tcnt1 = TCNT1; + SREG = oldSREG; + } while (tcnt1==0); + +// TIFR1 = 0xff; // AR - Clear interrupt flags +// TIMSK1 = _BV(TOIE1); // sets the timer overflow interrupt enable bit +} + +void TimerOne::stop() +{ + TCCR1B &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12)); // clears all clock selects bits +} + +unsigned long TimerOne::read() //returns the value of the timer in microseconds +{ //rember! phase and freq correct mode counts up to then down again + unsigned long tmp; // AR amended to hold more than 65536 (could be nearly double this) + unsigned int tcnt1; // AR added + + oldSREG= SREG; + cli(); + tmp=TCNT1; + SREG = oldSREG; + + char scale=0; + switch (clockSelectBits) + { + case 1:// no prescalse + scale=0; + break; + case 2:// x8 prescale + scale=3; + break; + case 3:// x64 + scale=6; + break; + case 4:// x256 + scale=8; + break; + case 5:// x1024 + scale=10; + break; + } + + do { // Nothing -- max delay here is ~1023 cycles. AR modified + oldSREG = SREG; + cli(); + tcnt1 = TCNT1; + SREG = oldSREG; + } while (tcnt1==tmp); //if the timer has not ticked yet + + //if we are counting down add the top value to how far we have counted down + tmp = ( (tcnt1>tmp) ? (tmp) : (long)(ICR1-tcnt1)+(long)ICR1 ); // AR amended to add casts and reuse previous TCNT1 + return ((tmp*1000L)/(F_CPU /1000L))<. + * + * See Google Code project http://code.google.com/p/arduino-timerone/ for latest + */ +#ifndef TIMERONE_h +#define TIMERONE_h + +#define RESOLUTION 65536 // Timer1 is 16 bit + +class TimerOne +{ + public: + + // properties + unsigned int pwmPeriod; + unsigned char clockSelectBits; + char oldSREG; // To hold Status Register while ints disabled + + // methods + void initialize(long microseconds=1000000); + void start(); + void stop(); + void restart(); + void resume(); + unsigned long read(); + void pwm(char pin, int duty, long microseconds=-1); + void disablePwm(char pin); + void attachInterrupt(void (*isr)(), long microseconds=-1); + void detachInterrupt(); + void setPeriod(long microseconds); + void setPwmDuty(char pin, int duty); + void (*isrCallback)(); +}; + +extern TimerOne Timer1; +#endif \ No newline at end of file diff --git a/Firmware_1.26b/cnc_ctrl_v1/cnc_ctrl_v1.ino b/Firmware_1.26b/cnc_ctrl_v1/cnc_ctrl_v1.ino new file mode 100644 index 00000000..3523f955 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/cnc_ctrl_v1.ino @@ -0,0 +1,120 @@ +/*This file is part of the Maslow Control Software. + The Maslow Control Software is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + Maslow Control Software is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + You should have received a copy of the GNU General Public License + along with the Maslow Control Software. If not, see . + + Copyright 2014-2017 Bar Smith*/ + + +/* To the projects contributers: + * + * it is highly recommended to activate warning output of the arduino gcc compiler. + * Compiler warnings are a great help to keep the codebase clean and can give clues + * to potentally wrong code. Also, if a codebase produces too many warnings it gets + * more likely that possibly important warnings could be overlooked. + * + * Since the Arduino IDE suppresses any compiler output by default we have to activate it. + * + * Therefore Arduino IDE users need to activate compiler output in the + * preferences dialog. Additionally Arduino IDE needs to tell the compiler to generate + * warning messages. This is done in the Arduino IDE's preferences.txt file - you can + * get there via the Preferences Dialog - there is a link to the file at the bottom. + * Edit the line "compiler.warning_level=none" to "compiler.warning_level=all" + * and restart the IDE. + */ + + +// TLE5206 v1.4 +// EastBaySource TB6643 V1.5 + +#include "Maslow.h" + +// Define system global state structure +system_t sys; + +// Define the global settings storage - treat as readonly +settings_t sysSettings; + +// Global realtime executor bitflag variable for setting various alarms. +byte systemRtExecAlarm; + +// Define axes, it might be tighter to define these within the sys struct +Axis leftAxis; +Axis rightAxis; +Axis zAxis; + +// Define kinematics, is it necessary for this to be a class? Is this really +// going to be reused? +Kinematics kinematics; + +void setup(){ + Serial.begin(57600); + Serial.print(F("PCB v1.")); + Serial.print(getPCBVersion()); + if (TLE5206 == true) { Serial.print(F(" TLE5206 ")); } + Serial.println(F(" Detected")); + sys.inchesToMMConversion = 1; + settingsLoadFromEEprom(); + setupAxes(); + settingsLoadStepsFromEEprom(); + // Set initial desired position of the machine to its current position + leftAxis.write(leftAxis.read()); + rightAxis.write(rightAxis.read()); + zAxis.write(zAxis.read()); + readyCommandString.reserve(INCBUFFERLENGTH); //Allocate memory so that this string doesn't fragment the heap as it grows and shrinks + gcodeLine.reserve(INCBUFFERLENGTH); + + #ifndef SIMAVR // Using the timer will crash simavr, so we disable it. + // Instead, we'll run runsOnATimer periodically in loop(). + Timer1.initialize(LOOPINTERVAL); + Timer1.attachInterrupt(runsOnATimer); + #endif + + Serial.println(F("Grbl v1.00")); // Why GRBL? Apparently because some programs are silly and look for this as an initialization command + Serial.println(F("ready")); + reportStatusMessage(STATUS_OK); + +} + +void runsOnATimer(){ + #if misloopDebug > 0 + if (inMovementLoop && !movementUpdated){ + movementFail = true; + } + #endif + movementUpdated = false; + leftAxis.computePID(); + rightAxis.computePID(); + zAxis.computePID(); +} + +void loop(){ + // This section is called on startup and whenever a stop command is issued + initGCode(); + if (sys.stop){ // only called on sys.stop to prevent stopping + initMotion(); // on USB disconnect. Might consider removing + setSpindlePower(false); // this restriction for safety if we are + laserOn(false); // EBS added laser + } // comfortable that USB disconnects are + // not a common occurrence anymore + kinematics.init(); + + // Let's go! + sys.stop = false; // We should consider an abort option which + // is not reset automatically such as a software + // limit + while (!sys.stop){ + gcodeExecuteLoop(); + #ifdef SIMAVR // Normally, runsOnATimer() will, well, run on a timer. See also setup(). + runsOnATimer(); + #endif + execSystemRealtime(); + } +} diff --git a/Firmware_1.26b/cnc_ctrl_v1/utility/direct_pin_read.h b/Firmware_1.26b/cnc_ctrl_v1/utility/direct_pin_read.h new file mode 100644 index 00000000..97b88620 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/utility/direct_pin_read.h @@ -0,0 +1,27 @@ +#ifndef direct_pin_read_h_ +#define direct_pin_read_h_ + +#if defined(__AVR__) || defined(__MK20DX128__) || defined(__MK20DX256__) + +#define IO_REG_TYPE uint8_t +#define PIN_TO_BASEREG(pin) (portInputRegister(digitalPinToPort(pin))) +#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin)) +#define DIRECT_PIN_READ(base, mask) (((*(base)) & (mask)) ? 1 : 0) + +#elif defined(__SAM3X8E__) + +#define IO_REG_TYPE uint32_t +#define PIN_TO_BASEREG(pin) (portInputRegister(digitalPinToPort(pin))) +#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin)) +#define DIRECT_PIN_READ(base, mask) (((*(base)) & (mask)) ? 1 : 0) + +#elif defined(__PIC32MX__) + +#define IO_REG_TYPE uint32_t +#define PIN_TO_BASEREG(pin) (portModeRegister(digitalPinToPort(pin))) +#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin)) +#define DIRECT_PIN_READ(base, mask) (((*(base+4)) & (mask)) ? 1 : 0) + +#endif + +#endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/utility/interrupt_config.h b/Firmware_1.26b/cnc_ctrl_v1/utility/interrupt_config.h new file mode 100644 index 00000000..cde6adf2 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/utility/interrupt_config.h @@ -0,0 +1,87 @@ +#if defined(__AVR__) + +#include +#include + +#define attachInterrupt(num, func, mode) enableInterrupt(num) +#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) +#define SCRAMBLE_INT_ORDER(num) ((num < 4) ? num + 2 : ((num < 6) ? num - 4 : num)) +#define DESCRAMBLE_INT_ORDER(num) ((num < 2) ? num + 4 : ((num < 6) ? num - 2 : num)) +#else +#define SCRAMBLE_INT_ORDER(num) (num) +#define DESCRAMBLE_INT_ORDER(num) (num) +#endif + +static void enableInterrupt(uint8_t num) +{ + switch (DESCRAMBLE_INT_ORDER(num)) { + #if defined(EICRA) && defined(EIMSK) + case 0: + EICRA = (EICRA & 0xFC) | 0x01; + EIMSK |= 0x01; + return; + case 1: + EICRA = (EICRA & 0xF3) | 0x04; + EIMSK |= 0x02; + return; + case 2: + EICRA = (EICRA & 0xCF) | 0x10; + EIMSK |= 0x04; + return; + case 3: + EICRA = (EICRA & 0x3F) | 0x40; + EIMSK |= 0x08; + return; + #elif defined(MCUCR) && defined(GICR) + case 0: + MCUCR = (MCUCR & ~((1 << ISC00) | (1 << ISC01))) | (mode << ISC00); + GICR |= (1 << INT0); + return; + case 1: + MCUCR = (MCUCR & ~((1 << ISC10) | (1 << ISC11))) | (mode << ISC10); + GICR |= (1 << INT1); + return; + #elif defined(MCUCR) && defined(GIMSK) + case 0: + MCUCR = (MCUCR & ~((1 << ISC00) | (1 << ISC01))) | (mode << ISC00); + GIMSK |= (1 << INT0); + return; + case 1: + MCUCR = (MCUCR & ~((1 << ISC10) | (1 << ISC11))) | (mode << ISC10); + GIMSK |= (1 << INT1); + return; + #endif + #if defined(EICRB) && defined(EIMSK) + case 4: + EICRB = (EICRB & 0xFC) | 0x01; + EIMSK |= 0x10; + return; + case 5: + EICRB = (EICRB & 0xF3) | 0x04; + EIMSK |= 0x20; + return; + case 6: + EICRB = (EICRB & 0xCF) | 0x10; + EIMSK |= 0x40; + return; + case 7: + EICRB = (EICRB & 0x3F) | 0x40; + EIMSK |= 0x80; + return; + #endif + } +} + +#elif defined(__PIC32MX__) + +#ifdef ENCODER_OPTIMIZE_INTERRUPTS +#undef ENCODER_OPTIMIZE_INTERRUPTS +#endif + +#else + +#ifdef ENCODER_OPTIMIZE_INTERRUPTS +#undef ENCODER_OPTIMIZE_INTERRUPTS +#endif + +#endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/utility/interrupt_pins.h b/Firmware_1.26b/cnc_ctrl_v1/utility/interrupt_pins.h new file mode 100644 index 00000000..e677c4f8 --- /dev/null +++ b/Firmware_1.26b/cnc_ctrl_v1/utility/interrupt_pins.h @@ -0,0 +1,156 @@ +// interrupt pins for known boards + +// Teensy (and maybe others) define these automatically +#if !defined(CORE_NUM_INTERRUPT) + +// Wiring boards +#if defined(WIRING) + #define CORE_NUM_INTERRUPT NUM_EXTERNAL_INTERRUPTS + #if NUM_EXTERNAL_INTERRUPTS > 0 + #define CORE_INT0_PIN EI0 + #endif + #if NUM_EXTERNAL_INTERRUPTS > 1 + #define CORE_INT1_PIN EI1 + #endif + #if NUM_EXTERNAL_INTERRUPTS > 2 + #define CORE_INT2_PIN EI2 + #endif + #if NUM_EXTERNAL_INTERRUPTS > 3 + #define CORE_INT3_PIN EI3 + #endif + #if NUM_EXTERNAL_INTERRUPTS > 4 + #define CORE_INT4_PIN EI4 + #endif + #if NUM_EXTERNAL_INTERRUPTS > 5 + #define CORE_INT5_PIN EI5 + #endif + #if NUM_EXTERNAL_INTERRUPTS > 6 + #define CORE_INT6_PIN EI6 + #endif + #if NUM_EXTERNAL_INTERRUPTS > 7 + #define CORE_INT7_PIN EI7 + #endif + +// Arduino Uno, Duemilanove, Diecimila, LilyPad, Mini, Fio, etc... +#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega8__) + #define CORE_NUM_INTERRUPT 2 + #define CORE_INT0_PIN 2 + #define CORE_INT1_PIN 3 + +// Arduino Mega +#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) + #define CORE_NUM_INTERRUPT 6 + #define CORE_INT0_PIN 2 + #define CORE_INT1_PIN 3 + #define CORE_INT2_PIN 21 + #define CORE_INT3_PIN 20 + #define CORE_INT4_PIN 19 + #define CORE_INT5_PIN 18 + +// Arduino Leonardo (untested) +#elif defined(__AVR_ATmega32U4__) && !defined(CORE_TEENSY) + #define CORE_NUM_INTERRUPT 4 + #define CORE_INT0_PIN 3 + #define CORE_INT1_PIN 2 + #define CORE_INT2_PIN 0 + #define CORE_INT3_PIN 1 + +// Sanguino (untested) +#elif defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644__) + #define CORE_NUM_INTERRUPT 3 + #define CORE_INT0_PIN 10 + #define CORE_INT1_PIN 11 + #define CORE_INT2_PIN 2 + +// Chipkit Uno32 - attachInterrupt may not support CHANGE option +#elif defined(__PIC32MX__) && defined(_BOARD_UNO_) + #define CORE_NUM_INTERRUPT 5 + #define CORE_INT0_PIN 38 + #define CORE_INT1_PIN 2 + #define CORE_INT2_PIN 7 + #define CORE_INT3_PIN 8 + #define CORE_INT4_PIN 35 + +// Chipkit Uno32 - attachInterrupt may not support CHANGE option +#elif defined(__PIC32MX__) && defined(_BOARD_MEGA_) + #define CORE_NUM_INTERRUPT 5 + #define CORE_INT0_PIN 3 + #define CORE_INT1_PIN 2 + #define CORE_INT2_PIN 7 + #define CORE_INT3_PIN 21 + #define CORE_INT4_PIN 20 + +// http://hlt.media.mit.edu/?p=1229 +#elif defined(__AVR_ATtiny45__) || defined(__AVR_ATtiny85__) + #define CORE_NUM_INTERRUPT 1 + #define CORE_INT0_PIN 2 + +// Arduino Due (untested) +#elif defined(__SAM3X8E__) + #define CORE_NUM_INTERRUPT 54 + #define CORE_INT0_PIN 0 + #define CORE_INT1_PIN 1 + #define CORE_INT2_PIN 2 + #define CORE_INT3_PIN 3 + #define CORE_INT4_PIN 4 + #define CORE_INT5_PIN 5 + #define CORE_INT6_PIN 6 + #define CORE_INT7_PIN 7 + #define CORE_INT8_PIN 8 + #define CORE_INT9_PIN 9 + #define CORE_INT10_PIN 10 + #define CORE_INT11_PIN 11 + #define CORE_INT12_PIN 12 + #define CORE_INT13_PIN 13 + #define CORE_INT14_PIN 14 + #define CORE_INT15_PIN 15 + #define CORE_INT16_PIN 16 + #define CORE_INT17_PIN 17 + #define CORE_INT18_PIN 18 + #define CORE_INT19_PIN 19 + #define CORE_INT20_PIN 20 + #define CORE_INT21_PIN 21 + #define CORE_INT22_PIN 22 + #define CORE_INT23_PIN 23 + #define CORE_INT24_PIN 24 + #define CORE_INT25_PIN 25 + #define CORE_INT26_PIN 26 + #define CORE_INT27_PIN 27 + #define CORE_INT28_PIN 28 + #define CORE_INT29_PIN 29 + #define CORE_INT30_PIN 30 + #define CORE_INT31_PIN 31 + #define CORE_INT32_PIN 32 + #define CORE_INT33_PIN 33 + #define CORE_INT34_PIN 34 + #define CORE_INT35_PIN 35 + #define CORE_INT36_PIN 36 + #define CORE_INT37_PIN 37 + #define CORE_INT38_PIN 38 + #define CORE_INT39_PIN 39 + #define CORE_INT40_PIN 40 + #define CORE_INT41_PIN 41 + #define CORE_INT42_PIN 42 + #define CORE_INT43_PIN 43 + #define CORE_INT44_PIN 44 + #define CORE_INT45_PIN 45 + #define CORE_INT46_PIN 46 + #define CORE_INT47_PIN 47 + #define CORE_INT48_PIN 48 + #define CORE_INT49_PIN 49 + #define CORE_INT50_PIN 50 + #define CORE_INT51_PIN 51 + #define CORE_INT52_PIN 52 + #define CORE_INT53_PIN 53 + +#endif +#endif + +#if !defined(CORE_NUM_INTERRUPT) +#error "Interrupts are unknown for this board, please add to this code" +#endif +#if CORE_NUM_INTERRUPT <= 0 +#error "Encoder requires interrupt pins, but this board does not have any :(" +#error "You could try defining ENCODER_DO_NOT_USE_INTERRUPTS as a kludge." +#endif + diff --git a/Firmware_1.26b/platformio.ini b/Firmware_1.26b/platformio.ini new file mode 100644 index 00000000..6dd2a572 --- /dev/null +++ b/Firmware_1.26b/platformio.ini @@ -0,0 +1,38 @@ +; PlatformIO Project Configuration File +; +; Build options: build flags, source filter +; Upload options: custom upload port, speed and extra flags +; Library options: dependencies, extra library storages +; Advanced options: extra scripting +; +; Please visit documentation for the other options and examples +; http://docs.platformio.org/page/projectconf.html + +[platformio] +src_dir = cnc_ctrl_v1 + +[env:megaatmega2560] +platform = atmelavr +board = megaatmega2560 +framework = arduino + +[env:simavr] +platform = atmelavr +board = megaatmega2560 +framework = arduino +extra_scripts = platformio/simavr_env.py +build_unflags = -Os +build_flags = -g -O0 -DSIMAVR -DFAKE_SERVO +monitor_port = /tmp/simavr-uart0 + +;[env:teensy36] +;platform = teensy +;board = teensy36 +;framework = arduino +;extra_scripts = platformio/teensy_env.py + +;[env:teensy35] +;platform = teensy +;board = teensy35 +;framework = arduino +;extra_scripts = platformio/teensy_env.py diff --git a/Firmware_1.26b/platformio/simavr_env.py b/Firmware_1.26b/platformio/simavr_env.py new file mode 100644 index 00000000..ab5b46bc --- /dev/null +++ b/Firmware_1.26b/platformio/simavr_env.py @@ -0,0 +1,21 @@ +from SCons.Script import ARGUMENTS, AlwaysBuild + +Import('env') + +# Run the linker with "-g", to prevent stripping of debugging symbols +env.Append( + LINKFLAGS=[ + "-g" + ] +) + +# Don't try to upload the firmware +env.Replace(UPLOADHEXCMD="echo Upload is not supported for ${PIOENV}. Skipping") + +pioenv = env.get("PIOENV") +progname = env.get("PROGNAME") + +def simulate_callback(*args, **kwargs): + env.Execute("./simduino/simduino .pioenvs/" + pioenv + "/" + progname + ".elf") + +AlwaysBuild(env.Alias("simulate", "", simulate_callback)) diff --git a/Firmware_1.26b/platformio/teensy_env.py b/Firmware_1.26b/platformio/teensy_env.py new file mode 100644 index 00000000..0f0265e5 --- /dev/null +++ b/Firmware_1.26b/platformio/teensy_env.py @@ -0,0 +1,12 @@ +import os + +Import('env') + +varname = env.get("PIOENV") + "_UPLOAD" + +if varname in os.environ: + print "$"+ varname + " is set, enabling upload." +else: + # Don't try to upload the firmware + env.Replace(UPLOADHEXCMD="echo Upload is disabled by default for ${PIOENV}. " + + "To enable upload, set " + varname + "environment variable") diff --git a/cnc_ctrl_v1/Kinematics.cpp b/cnc_ctrl_v1/Kinematics.cpp index ed2b3d97..c0162884 100644 --- a/cnc_ctrl_v1/Kinematics.cpp +++ b/cnc_ctrl_v1/Kinematics.cpp @@ -98,6 +98,8 @@ void Kinematics::_inverse(float xTarget,float yTarget, float* aChainLength, flo void Kinematics::_quadrilateralInverse(float xTarget,float yTarget, float* aChainLength, float* bChainLength){ + //Confirm that the coordinates are on the wood + _verifyValidTarget(&xTarget, &yTarget); // OK //coordinate shift to put (0,0) in the center of the plywood from the left sprocket y = (halfHeight) + sysSettings.motorOffsetY - yTarget; x = (sysSettings.distBetweenMotors/2.0) + xTarget; diff --git a/cnc_ctrl_v1/Kinematics.h b/cnc_ctrl_v1/Kinematics.h index 64fe6356..bfdeb8b3 100644 --- a/cnc_ctrl_v1/Kinematics.h +++ b/cnc_ctrl_v1/Kinematics.h @@ -50,7 +50,8 @@ float _YOffsetEqn(const float& YPlus, const float& Denominator, const float& Psi); void _MatSolv(); void _MyTrig(); - float x = 0; //target router bit coordinates. + //target router bit coordinates. + float x = 0; float y = 0; float _xCordOfMotor; float _yCordOfMotor; diff --git a/cnc_ctrl_v1/Maslow.h b/cnc_ctrl_v1/Maslow.h index 46104a7d..0ff1da08 100644 --- a/cnc_ctrl_v1/Maslow.h +++ b/cnc_ctrl_v1/Maslow.h @@ -18,7 +18,7 @@ #define maslow_h // Maslow Firmware Version tracking -#define VERSIONNUMBER 51.28 +#define VERSIONNUMBER 51.29 // Define standard libraries used by maslow. #include diff --git a/cnc_ctrl_v1/Motor.cpp b/cnc_ctrl_v1/Motor.cpp index 245694ec..76adb4eb 100644 --- a/cnc_ctrl_v1/Motor.cpp +++ b/cnc_ctrl_v1/Motor.cpp @@ -48,6 +48,15 @@ int Motor::setupMotor(const int& pwmPin, const int& pin1, const int& pin2){ digitalWrite(_pin1, LOW); digitalWrite(_pin2, LOW) ; + }else if (TB6643 == true ) { + // EBS V1.5 + pinMode(_pwmPin, INPUT); + pinMode(_pin1, OUTPUT); + pinMode(_pin2, OUTPUT); + + //stop the motor + digitalWrite(_pin1, LOW); + digitalWrite(_pin2, LOW); } else if (TLE9201 == true) { //set pinmodes pinMode(_pwmPin, OUTPUT); @@ -81,7 +90,11 @@ void Motor::detach(){ //stop the motor digitalWrite(_pin1, LOW); digitalWrite(_pin2, LOW) ; - } else if (TLE9201 == true) { + }else if (TB6643 == true){ + //stop the motor + digitalWrite(_pin1, LOW); + digitalWrite(_pin2, LOW) ; + } else if (TLE9201 == true) { //stop the motor digitalWrite(_pin2, HIGH); // TLE9201 ENABLE pin, LOW = on analogWrite(_pwmPin, 0); @@ -122,7 +135,7 @@ void Motor::write(int speed, bool force){ bool usePin1 = ((_pin1 != 4) && (_pin1 != 13) && (_pin1 != 11) && (_pin1 != 12)); // avoid PWM using timer0 or timer1 bool usePin2 = ((_pin2 != 4) && (_pin2 != 13) && (_pin2 != 11) && (_pin2 != 12)); // avoid PWM using timer0 or timer1 bool usepwmPin = ((TLE5206 == false) && (_pwmPin != 4) && (_pwmPin != 13) && (_pwmPin != 11) && (_pwmPin != 12)); // avoid PWM using timer0 or timer1 - if (!(TLE5206 || TLE9201)) { // L298 boards + if (!(TLE5206 || TLE9201)) { // NOT L298 boards if (forward){ if (usepwmPin){ digitalWrite(_pin1 , HIGH ); @@ -228,6 +241,19 @@ void Motor::write(int speed, bool force){ digitalWrite(dirPin, dirCMD); // TLE9201 DIR pin analogWrite (_pwmPin, speed); // TLE9201 PWM pin digitalWrite(enablePin, LOW); // TLE9201 ENABLE pin, HIGH = disable + }else if (TB6643) { //EBS 1.5 + if (forward) { + if (speed > 0) { + analogWrite(_pin1 , speed); + digitalWrite(_pin2 , LOW); + } else { // speed = 0 so put on the brakes + digitalWrite(_pin1 , HIGH); + digitalWrite(_pin2 , HIGH); + } + } else { // reverse + digitalWrite(_pin1 , LOW); + analogWrite(_pin2 , speed); + } } else {} // add new boards here } diff --git a/cnc_ctrl_v1/Motor.h b/cnc_ctrl_v1/Motor.h index f75e0e71..8ad61203 100644 --- a/cnc_ctrl_v1/Motor.h +++ b/cnc_ctrl_v1/Motor.h @@ -51,6 +51,7 @@ }; extern bool TLE5206; extern bool TLE9201; + extern bool TB6643; extern int ENA; extern int ENB; extern int ENC; diff --git a/cnc_ctrl_v1/Settings.cpp b/cnc_ctrl_v1/Settings.cpp index f3ae079d..431cc960 100644 --- a/cnc_ctrl_v1/Settings.cpp +++ b/cnc_ctrl_v1/Settings.cpp @@ -77,7 +77,7 @@ void settingsReset() { sysSettings.originalChainLength = 1651; // int originalChainLength; 2 sysSettings.encoderSteps = 8113.73; // float encoderSteps; 4 sysSettings.distPerRot = 63.5; // float distPerRot; 4 - sysSettings.maxFeed = 700; // int maxFeed; 2 + sysSettings.maxFeed = 900; // int maxFeed; 2 sysSettings.zAxisAttached = true; // zAxisAttached; 1 sysSettings.spindleAutomateType = SPEED_CONTROL_RELAY_ACTIVE_HIGH; // 1 bool spindleAutomate; sysSettings.maxZRPM = 12.60; // float maxZRPM; 4 diff --git a/cnc_ctrl_v1/Settings.h b/cnc_ctrl_v1/Settings.h index 86e6cc5c..5ae48609 100644 --- a/cnc_ctrl_v1/Settings.h +++ b/cnc_ctrl_v1/Settings.h @@ -20,7 +20,7 @@ Copyright 2014-2017 Bar Smith*/ #ifndef settings_h #define settings_h -#define SETTINGSVERSION 6 // The current version of settings, if this doesn't +#define SETTINGSVERSION 7 // The current version of settings, if this doesn't // match what is in EEPROM then settings on // machine are reset to defaults #define EEPROMVALIDDATA 56 // This is just a random byte value that is used diff --git a/cnc_ctrl_v1/System.cpp b/cnc_ctrl_v1/System.cpp index 88cbc9e3..3da81d13 100644 --- a/cnc_ctrl_v1/System.cpp +++ b/cnc_ctrl_v1/System.cpp @@ -22,6 +22,7 @@ Copyright 2014-2017 Bar Smith*/ bool TLE5206; bool TLE9201; +bool TB6643; // extern values using AUX pins defined in setupAxes() int SpindlePowerControlPin; //power relay or servo control to operate power switch for spindle @@ -243,6 +244,36 @@ void setupAxes(){ aux8 = 46; aux9 = 47; } + else if(pcbVersion == 5){ // EBS PCB v1.5 Detected + + //MP1 - Right Motor + encoder1A = 2; // INPUT + encoder1B = 3; // INPUT + in1 = 9; // OUTPUT + in2 = 10; // OUTPUT + //enA = 12; // errorFlag + + //MP2 - Z-axis + encoder2A = 18; // INPUT + encoder2B = 19; // INPUT + in3 = 7; // OUTPUT + in4 = 8; // OUTPUT + //enB = 8; // errorFlag + + //MP3 - Left Motor + encoder3A = 21; // INPUT + encoder3B = 20; // INPUT + in5 = 6; // OUTPUT + in6 = 5; // OUTPUT + //enC = 5; // errorFlag + //AUX pins + aux1 = 48; + aux2 = 49; + aux3 = 51; + aux4 = 50; + aux5 = 43; + aux6 = 44; + } else if (pcbVersion == 6){ // TLE9201 //TLE9201 PCB v1.6 Detected //MP1 - Right Motor @@ -337,11 +368,11 @@ void setupAxes(){ else{ // chain Under Sprocket... if (!TLE9201) { leftAxis.setup (enC, in5, in6, encoder3A, encoder3B, 'L', LOOPINTERVAL); - rightAxis.setup(enA, in2, in1, encoder1B, encoder1A, 'R', LOOPINTERVAL); + rightAxis.setup(enA, in2, in1, encoder1B, encoder1A, 'R', LOOPINTERVAL); //in2,in1 } else { leftAxis.setup (enC, in5, in6, encoder3A, encoder3B, 'L', LOOPINTERVAL); - rightAxis.setup(enA, in1, in2, encoder1B, encoder1A, 'R', LOOPINTERVAL); + rightAxis.setup(enA, in1, in2, encoder1B, encoder1A, 'R', LOOPINTERVAL); //in1,in2?? this should be backwards like everything else? } } @@ -391,19 +422,24 @@ int getPCBVersion(){ * and reported by the firmware was zero-based - a source of * confusion when creating new boards. * Beginning with board v1.6, the value from the gpio pins for new boards -* will be zero-based to match the number reported by the firmware +* will be zero based to match the number reported by the firmware * and the silkscreen. + + but version 1.5 which is 1 based overlaps with version 1.6 which is zero based. The easist way.. * * * "x" = not used * #53-#52 #27-#26 #25-#24 #23-#22 * ------- ------- ------- ------- -* GND GND PU PU PU PU GND PU -> rev.0001 PCB v1.0 aka beta release board -* GND GND PU PU PU PU PU GND -> rev.0002 PCB v1.1 -* GND GND PU PU PU PU PU PU -> rev.0003 PCB v1.2 -* x x x x GND PU GND GND -> PCB v1.3 and 1.4 TLE5206 -* x x GND GND GND PU GND PU -> reserved for v1.4 TLE5206, v1.5 is unused -* x x GND GND GND PU PU GND -> PCB v1.6 TLE9201 +* 128 64 32 16 8 4 2 1 binary math values. add if value is PU +* GND GND PU PU PU PU GND PU -> rev.0001 PCB v1.0 aka beta release board = 61 +* GND GND PU PU PU PU PU GND -> rev.0002 PCB v1.1 = 62 +* GND GND PU PU PU PU PU PU -> rev.0003 PCB v1.2 = 63 +* X X X X PU PU PU PU -> rev 0.000 PCB v1.2b = 0 -silk screened as 1.2b with all 4 pins direct connected to 5V +* x x x x GND PU GND GND -> PCB v1.3 and 1.4 TLE5206 = 4 +* x x GND GND GND PU GND PU -> reserved for v1.4 TLE5206 = 5 + X x GND GND GND PU PU GND -> PCB v1.5b is TB6643 = 6 +* x x GND GND GND PU PU [PU] -> PCB v1.6 TLE9201 = 7 --> need to manually cut trace or pin and disconnect pin 22 (vers1 label) */ pinMode(VERS1,INPUT_PULLUP); pinMode(VERS2,INPUT_PULLUP); @@ -412,19 +448,31 @@ int getPCBVersion(){ pinMode(VERS5,INPUT_PULLUP); pinMode(VERS6,INPUT_PULLUP); int pinCheck = (32*digitalRead(VERS6) + 16*digitalRead(VERS5) + 8*digitalRead(VERS4) + 4*digitalRead(VERS3) + 2*digitalRead(VERS2) + 1*digitalRead(VERS1)); + // everything should be grounded except those pulled high for counting + // according to the above pincheck should result in , 1 = 000001, 2 = 000010, 3 = 000100, 4 = 001000, 5 = 010000, 6 = 100000; + // ideally switch (pinCheck) { // boards v1.1, v1.2, v1.3 don't strap VERS3-6 low - case B111101: case B111110: case B111111: // v1.1, v1.2, v1.3 - pinCheck &= B000011; // strip off the unstrapped bits + case B111101: case B111110: case B111111: // v1.0, v1.1, v1.2, v1.3 + pinCheck &= B001111; // strip off the unstrapped bits TLE5206 = false; TLE9201 = false; break; - case B110100: case B000100: // some versions of board v1.4 don't strap VERS5-6 low - pinCheck &= B000111; // strip off the unstrapped bits + case B111100: case B000100: // some versions of board v1.4 don't strap VERS5-6 low + pinCheck &= B001111; // strip off the unstrapped bits + TB6643 = false; TLE5206 = true; TLE9201 = false; break; - case B000110: + case B001000: case B000101: // v 5 + pinCheck &= B001111; // this should be 101 for 5, not 110 for 6 !! wrong pins? + TB6643 = true; + TLE5206 = false; + TLE9201 = false; + break; + case B000110: //v 6 + pinCheck &= B001111; + TB6643 = false; TLE5206 = false; TLE9201 = true; break; @@ -592,6 +640,8 @@ void systemReset(){ rightAxis.detach(); zAxis.detach(); setSpindlePower(false); + // TODO: define in this scope: + //LaserOff(); // Reruns the initial setup function and calls stop to re-init state sys.stop = true; setup(); diff --git a/cnc_ctrl_v1/System.h b/cnc_ctrl_v1/System.h index dd0eaec7..8fa046b8 100644 --- a/cnc_ctrl_v1/System.h +++ b/cnc_ctrl_v1/System.h @@ -99,4 +99,6 @@ void systemSaveAxesPosition(); void systemReset(); byte systemExecuteCmdstring(String&); void setPWMPrescalers(int prescalerChoice); +void configAuxLow(int A1, int A2, int A3, int A4, int A5, int A6); +void configAuxHigh(int A7, int A8, int A9); #endif diff --git a/cnc_ctrl_v1/cnc_ctrl_v1.ino b/cnc_ctrl_v1/cnc_ctrl_v1.ino index 69cb0541..48532fc6 100644 --- a/cnc_ctrl_v1/cnc_ctrl_v1.ino +++ b/cnc_ctrl_v1/cnc_ctrl_v1.ino @@ -1,8 +1,4 @@ -/*This file is part of the Maslow Control Software. - The Maslow Control Software is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. +/*This file is pa Maslow Control Software is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the @@ -33,6 +29,7 @@ // TLE9201 version // TLE5206 version +// EastBaySource TB6643 V1.5 #include "Maslow.h" #include @@ -59,11 +56,12 @@ Axis zAxis; Kinematics kinematics; void setup(){ - Serial.begin(115200); + Serial.begin(57600); Serial.print(F("PCB v1.")); Serial.print(getPCBVersion()); if (TLE5206 == true) { Serial.print(F(" TLE5206 ")); } if (TLE9201 == true) { Serial.print(F(" TLE9201 ")); } + if (TB6643 = true){Serial.print(F(" TB6643 "));} Serial.println(F(" Detected")); sys.inchesToMMConversion = 1; sys.writeStepsToEEPROM = false; @@ -115,6 +113,7 @@ void loop(){ if (sys.stop){ // only called on sys.stop to prevent stopping initMotion(); // on USB disconnect. Might consider removing setSpindlePower(false); // this restriction for safety if we are + laserOff(); } // comfortable that USB disconnects are // not a common occurrence anymore kinematics.init(); From 8ee4f92179a0a1a17848b6ff0618dd8fc9d43889 Mon Sep 17 00:00:00 2001 From: Orob-Maslow <59507087+Orob-Maslow@users.noreply.github.com> Date: Tue, 24 Nov 2020 19:29:22 -0600 Subject: [PATCH 17/21] Update System.cpp board now identify as version +1 --- cnc_ctrl_v1/System.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/cnc_ctrl_v1/System.cpp b/cnc_ctrl_v1/System.cpp index 3da81d13..1b2223f8 100644 --- a/cnc_ctrl_v1/System.cpp +++ b/cnc_ctrl_v1/System.cpp @@ -453,25 +453,25 @@ int getPCBVersion(){ // ideally switch (pinCheck) { // boards v1.1, v1.2, v1.3 don't strap VERS3-6 low - case B111101: case B111110: case B111111: // v1.0, v1.1, v1.2, v1.3 - pinCheck &= B001111; // strip off the unstrapped bits + case B111101: case B111110: case B111111: case 001111:// v1.0, v1.1, v1.2, v1.3 + pinCheck &= B000011; // strip off the unstrapped bits TLE5206 = false; TLE9201 = false; break; case B111100: case B000100: // some versions of board v1.4 don't strap VERS5-6 low - pinCheck &= B001111; // strip off the unstrapped bits + pinCheck &= B000100; // strip off the unstrapped bits TB6643 = false; TLE5206 = true; TLE9201 = false; break; - case B001000: case B000101: // v 5 - pinCheck &= B001111; // this should be 101 for 5, not 110 for 6 !! wrong pins? + case B001000: case B000110: // v 5 + pinCheck &= B000110; // this should be 101 for 5, not 110 for 6 !! wrong pins? TB6643 = true; TLE5206 = false; TLE9201 = false; break; - case B000110: //v 6 - pinCheck &= B001111; + case B000111: //v 6 + pinCheck &= B00111; TB6643 = false; TLE5206 = false; TLE9201 = true; From 28837626ccd7be90799144fb31edfdd07807dba0 Mon Sep 17 00:00:00 2001 From: Orob-Maslow <59507087+Orob-Maslow@users.noreply.github.com> Date: Tue, 24 Nov 2020 20:06:02 -0600 Subject: [PATCH 18/21] Update System.cpp updated board number --- cnc_ctrl_v1/System.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cnc_ctrl_v1/System.cpp b/cnc_ctrl_v1/System.cpp index 1b2223f8..8a53b0b1 100644 --- a/cnc_ctrl_v1/System.cpp +++ b/cnc_ctrl_v1/System.cpp @@ -477,7 +477,7 @@ int getPCBVersion(){ TLE9201 = true; break; } - return pinCheck<6 ? pinCheck-1 : pinCheck; + return pinCheck<8 ? pinCheck-1 : pinCheck; } From ddb1c6c1f3912ea7789453c3dab9971efe7fd81a Mon Sep 17 00:00:00 2001 From: Orob-Maslow <59507087+Orob-Maslow@users.noreply.github.com> Date: Tue, 24 Nov 2020 21:13:47 -0600 Subject: [PATCH 19/21] Update System.cpp description changes and reserved Version 8 as the next board version to come out, reservd 15 because it is already used by board v 1.2b --- cnc_ctrl_v1/System.cpp | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/cnc_ctrl_v1/System.cpp b/cnc_ctrl_v1/System.cpp index 8a53b0b1..165cc400 100644 --- a/cnc_ctrl_v1/System.cpp +++ b/cnc_ctrl_v1/System.cpp @@ -421,12 +421,10 @@ int getPCBVersion(){ * but the board version number silkscreened on those boards * and reported by the firmware was zero-based - a source of * confusion when creating new boards. -* Beginning with board v1.6, the value from the gpio pins for new boards +* Beginning with board v1.8, the value from the gpio pins for new boards * will be zero based to match the number reported by the firmware * and the silkscreen. - - but version 1.5 which is 1 based overlaps with version 1.6 which is zero based. The easist way.. -* +* * * * "x" = not used * #53-#52 #27-#26 #25-#24 #23-#22 @@ -435,11 +433,17 @@ int getPCBVersion(){ * GND GND PU PU PU PU GND PU -> rev.0001 PCB v1.0 aka beta release board = 61 * GND GND PU PU PU PU PU GND -> rev.0002 PCB v1.1 = 62 * GND GND PU PU PU PU PU PU -> rev.0003 PCB v1.2 = 63 -* X X X X PU PU PU PU -> rev 0.000 PCB v1.2b = 0 -silk screened as 1.2b with all 4 pins direct connected to 5V +* X X X X PU PU PU PU -> rev 0.000 PCB v1.2b = 15 -silk screened as 1.2b with all 4 pins direct connected to 5V * x x x x GND PU GND GND -> PCB v1.3 and 1.4 TLE5206 = 4 * x x GND GND GND PU GND PU -> reserved for v1.4 TLE5206 = 5 X x GND GND GND PU PU GND -> PCB v1.5b is TB6643 = 6 * x x GND GND GND PU PU [PU] -> PCB v1.6 TLE9201 = 7 --> need to manually cut trace or pin and disconnect pin 22 (vers1 label) +* +* All above this line are 1 based. below this line will be zero based. 8 will = B001000 ^^^ was off by one. +* As of 11/2020, the next board will be version 1.8 and should have pin 25 pulled high with no connection and 22, 23, 24 pins all shorted to ground. +* +* X X PU GND GND GND -> RESERVED for next board = 8 +* X X PU PU PU PU -> ALREADy TAKEN AS 1.2B = 15 */ pinMode(VERS1,INPUT_PULLUP); pinMode(VERS2,INPUT_PULLUP); @@ -465,17 +469,18 @@ int getPCBVersion(){ TLE9201 = false; break; case B001000: case B000110: // v 5 - pinCheck &= B000110; // this should be 101 for 5, not 110 for 6 !! wrong pins? + pinCheck &= B000110; // this should be 101 for 5, not 110 for 6 all above are off by 1 TB6643 = true; TLE5206 = false; TLE9201 = false; break; - case B000111: //v 6 + case B000111: //v 1.6 AND V 1.7 (1.7 is a place holder and will not exist because 1.6 uses the same pins) pinCheck &= B00111; TB6643 = false; TLE5206 = false; TLE9201 = true; break; + case B00100: // V8 RESERVED for board version 1.8 } return pinCheck<8 ? pinCheck-1 : pinCheck; } From 0b0b358fd7c8668abad63c764844ac776caecfe4 Mon Sep 17 00:00:00 2001 From: Orob-Maslow <59507087+Orob-Maslow@users.noreply.github.com> Date: Tue, 24 Nov 2020 21:49:47 -0600 Subject: [PATCH 20/21] updated board detection check verification showed TB6643 board identifies when not selected. Fixed to check rather than set variable when comparing. --- cnc_ctrl_v1/System.cpp | 18 +++++++++++------- cnc_ctrl_v1/cnc_ctrl_v1.ino | 2 +- 2 files changed, 12 insertions(+), 8 deletions(-) diff --git a/cnc_ctrl_v1/System.cpp b/cnc_ctrl_v1/System.cpp index 165cc400..f9879cf3 100644 --- a/cnc_ctrl_v1/System.cpp +++ b/cnc_ctrl_v1/System.cpp @@ -244,7 +244,7 @@ void setupAxes(){ aux8 = 46; aux9 = 47; } - else if(pcbVersion == 5){ // EBS PCB v1.5 Detected + else if(pcbVersion == 5){ // EBS PCB v1.5b Detected //MP1 - Right Motor encoder1A = 2; // INPUT @@ -433,7 +433,7 @@ int getPCBVersion(){ * GND GND PU PU PU PU GND PU -> rev.0001 PCB v1.0 aka beta release board = 61 * GND GND PU PU PU PU PU GND -> rev.0002 PCB v1.1 = 62 * GND GND PU PU PU PU PU PU -> rev.0003 PCB v1.2 = 63 -* X X X X PU PU PU PU -> rev 0.000 PCB v1.2b = 15 -silk screened as 1.2b with all 4 pins direct connected to 5V +* X X X X PU PU PU PU -> rev 0.000 PCB v1.2b = 15 -silk screened as 1.2b with all 4 pins direct connected to 5V and all disconnected pins if set to pullup will read high * x x x x GND PU GND GND -> PCB v1.3 and 1.4 TLE5206 = 4 * x x GND GND GND PU GND PU -> reserved for v1.4 TLE5206 = 5 X x GND GND GND PU PU GND -> PCB v1.5b is TB6643 = 6 @@ -461,27 +461,31 @@ int getPCBVersion(){ pinCheck &= B000011; // strip off the unstrapped bits TLE5206 = false; TLE9201 = false; + TB6643 = false; break; - case B111100: case B000100: // some versions of board v1.4 don't strap VERS5-6 low - pinCheck &= B000100; // strip off the unstrapped bits + case B111100: case B000100: case B000101: // some versions of board v1.4 don't strap VERS5-6 low + pinCheck &= B000101; // strip off the unstrapped bits TB6643 = false; TLE5206 = true; TLE9201 = false; break; - case B001000: case B000110: // v 5 + case B000110: // v 5 pinCheck &= B000110; // this should be 101 for 5, not 110 for 6 all above are off by 1 TB6643 = true; TLE5206 = false; TLE9201 = false; break; case B000111: //v 1.6 AND V 1.7 (1.7 is a place holder and will not exist because 1.6 uses the same pins) - pinCheck &= B00111; + pinCheck &= B000111; TB6643 = false; TLE5206 = false; TLE9201 = true; break; - case B00100: // V8 RESERVED for board version 1.8 + case B01000: // V8 RESERVED for board version 1.8 + pinCheck &= B001000; + break; } + return pinCheck<8 ? pinCheck-1 : pinCheck; } diff --git a/cnc_ctrl_v1/cnc_ctrl_v1.ino b/cnc_ctrl_v1/cnc_ctrl_v1.ino index 48532fc6..9f8379cc 100644 --- a/cnc_ctrl_v1/cnc_ctrl_v1.ino +++ b/cnc_ctrl_v1/cnc_ctrl_v1.ino @@ -61,7 +61,7 @@ void setup(){ Serial.print(getPCBVersion()); if (TLE5206 == true) { Serial.print(F(" TLE5206 ")); } if (TLE9201 == true) { Serial.print(F(" TLE9201 ")); } - if (TB6643 = true){Serial.print(F(" TB6643 "));} + if (TB6643 == true){Serial.print(F(" TB6643 "));} Serial.println(F(" Detected")); sys.inchesToMMConversion = 1; sys.writeStepsToEEPROM = false; From 733a45a431c90b39411b053b4deac309dd2524ee Mon Sep 17 00:00:00 2001 From: Orob-Maslow <59507087+Orob-Maslow@users.noreply.github.com> Date: Tue, 24 Nov 2020 23:07:50 -0600 Subject: [PATCH 21/21] purge diff files from repo --- Firmware_1.26b/.gitignore | 17 - Firmware_1.26b/.travis.yml | 35 - Firmware_1.26b/CODE_OF_CONDUCT.md | 46 - .../Documentation/Download Firmware.jpg | Bin 87994 -> 0 bytes Firmware_1.26b/Documentation/Download IDE.jpg | Bin 102625 -> 0 bytes .../How To Contribute Pictures/Clone.png | Bin 37021 -> 0 bytes .../How To Contribute Pictures/Clone2.png | Bin 34398 -> 0 bytes .../How To Contribute Pictures/Clone3.png | Bin 14502 -> 0 bytes .../How To Contribute Pictures/Commit.png | Bin 44800 -> 0 bytes .../EditingFile.png | Bin 55394 -> 0 bytes .../How To Contribute Pictures/Fork.jpg | Bin 58378 -> 0 bytes .../How To Contribute Pictures/GithubHome.jpg | Bin 76690 -> 0 bytes .../GithubWelcome.jpg | Bin 30594 -> 0 bytes .../How To Contribute Pictures/PR0.png | Bin 46931 -> 0 bytes .../How To Contribute Pictures/PR1.png | Bin 69205 -> 0 bytes .../How To Contribute Pictures/PR2.png | Bin 64618 -> 0 bytes .../How To Contribute Pictures/PR3.png | Bin 73289 -> 0 bytes .../Push Origin.png | Bin 43035 -> 0 bytes .../Documentation/Open Firmware.jpg | Bin 91291 -> 0 bytes Firmware_1.26b/Documentation/Select Board.jpg | Bin 90579 -> 0 bytes .../Documentation/Select COM Port.jpg | Bin 77634 -> 0 bytes Firmware_1.26b/Documentation/Upload.jpg | Bin 64058 -> 0 bytes .../Documentation/posErrorAlarm/alarm.PNG | Bin 10698 -> 0 bytes .../posErrorAlarm/alarmSetting.PNG | Bin 70324 -> 0 bytes Firmware_1.26b/INSTRUCTIONS.md | 41 - Firmware_1.26b/LICENSE | 189 ---- Firmware_1.26b/README.md | 77 -- Firmware_1.26b/cnc_ctrl_v1/Axis.cpp | 301 ------ Firmware_1.26b/cnc_ctrl_v1/Axis.h | 70 -- Firmware_1.26b/cnc_ctrl_v1/Config.h | 64 -- Firmware_1.26b/cnc_ctrl_v1/Encoder.cpp | 10 - Firmware_1.26b/cnc_ctrl_v1/Encoder.h | 976 ------------------ Firmware_1.26b/cnc_ctrl_v1/GCode.cpp | 889 ---------------- Firmware_1.26b/cnc_ctrl_v1/GCode.h | 50 - Firmware_1.26b/cnc_ctrl_v1/Kinematics.cpp | 425 -------- Firmware_1.26b/cnc_ctrl_v1/Kinematics.h | 99 -- Firmware_1.26b/cnc_ctrl_v1/Maslow.h | 52 - Firmware_1.26b/cnc_ctrl_v1/Motion.cpp | 376 ------- Firmware_1.26b/cnc_ctrl_v1/Motion.h | 36 - Firmware_1.26b/cnc_ctrl_v1/Motor.cpp | 227 ---- Firmware_1.26b/cnc_ctrl_v1/Motor.h | 54 - .../cnc_ctrl_v1/MotorGearboxEncoder.cpp | 205 ---- .../cnc_ctrl_v1/MotorGearboxEncoder.h | 56 - Firmware_1.26b/cnc_ctrl_v1/NutsAndBolts.cpp | 67 -- Firmware_1.26b/cnc_ctrl_v1/NutsAndBolts.h | 31 - Firmware_1.26b/cnc_ctrl_v1/PID_v1.cpp | 236 ----- Firmware_1.26b/cnc_ctrl_v1/PID_v1.h | 98 -- Firmware_1.26b/cnc_ctrl_v1/Probe.cpp | 33 - Firmware_1.26b/cnc_ctrl_v1/Probe.h | 25 - Firmware_1.26b/cnc_ctrl_v1/Report.cpp | 316 ------ Firmware_1.26b/cnc_ctrl_v1/Report.h | 85 -- Firmware_1.26b/cnc_ctrl_v1/RingBuffer.cpp | 208 ---- Firmware_1.26b/cnc_ctrl_v1/RingBuffer.h | 42 - Firmware_1.26b/cnc_ctrl_v1/Settings.cpp | 414 -------- Firmware_1.26b/cnc_ctrl_v1/Settings.h | 109 -- Firmware_1.26b/cnc_ctrl_v1/SimavrSerial.cpp | 27 - Firmware_1.26b/cnc_ctrl_v1/SimavrSerial.h | 32 - Firmware_1.26b/cnc_ctrl_v1/Spindle.cpp | 117 --- Firmware_1.26b/cnc_ctrl_v1/Spindle.h | 24 - Firmware_1.26b/cnc_ctrl_v1/System.cpp | 658 ------------ Firmware_1.26b/cnc_ctrl_v1/System.h | 94 -- Firmware_1.26b/cnc_ctrl_v1/Testing.cpp | 181 ---- Firmware_1.26b/cnc_ctrl_v1/Testing.h | 25 - Firmware_1.26b/cnc_ctrl_v1/TimerOne.cpp | 209 ---- Firmware_1.26b/cnc_ctrl_v1/TimerOne.h | 67 -- Firmware_1.26b/cnc_ctrl_v1/cnc_ctrl_v1.ino | 120 --- .../cnc_ctrl_v1/utility/direct_pin_read.h | 27 - .../cnc_ctrl_v1/utility/interrupt_config.h | 87 -- .../cnc_ctrl_v1/utility/interrupt_pins.h | 156 --- Firmware_1.26b/platformio.ini | 38 - Firmware_1.26b/platformio/simavr_env.py | 21 - Firmware_1.26b/platformio/teensy_env.py | 12 - 72 files changed, 7854 deletions(-) delete mode 100644 Firmware_1.26b/.gitignore delete mode 100644 Firmware_1.26b/.travis.yml delete mode 100644 Firmware_1.26b/CODE_OF_CONDUCT.md delete mode 100644 Firmware_1.26b/Documentation/Download Firmware.jpg delete mode 100644 Firmware_1.26b/Documentation/Download IDE.jpg delete mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/Clone.png delete mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/Clone2.png delete mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/Clone3.png delete mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/Commit.png delete mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/EditingFile.png delete mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/Fork.jpg delete mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/GithubHome.jpg delete mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/GithubWelcome.jpg delete mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/PR0.png delete mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/PR1.png delete mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/PR2.png delete mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/PR3.png delete mode 100644 Firmware_1.26b/Documentation/How To Contribute Pictures/Push Origin.png delete mode 100644 Firmware_1.26b/Documentation/Open Firmware.jpg delete mode 100644 Firmware_1.26b/Documentation/Select Board.jpg delete mode 100644 Firmware_1.26b/Documentation/Select COM Port.jpg delete mode 100644 Firmware_1.26b/Documentation/Upload.jpg delete mode 100644 Firmware_1.26b/Documentation/posErrorAlarm/alarm.PNG delete mode 100644 Firmware_1.26b/Documentation/posErrorAlarm/alarmSetting.PNG delete mode 100644 Firmware_1.26b/INSTRUCTIONS.md delete mode 100644 Firmware_1.26b/LICENSE delete mode 100644 Firmware_1.26b/README.md delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Axis.cpp delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Axis.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Config.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Encoder.cpp delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Encoder.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/GCode.cpp delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/GCode.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Kinematics.cpp delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Kinematics.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Maslow.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Motion.cpp delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Motion.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Motor.cpp delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Motor.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/MotorGearboxEncoder.cpp delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/MotorGearboxEncoder.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/NutsAndBolts.cpp delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/NutsAndBolts.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/PID_v1.cpp delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/PID_v1.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Probe.cpp delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Probe.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Report.cpp delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Report.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/RingBuffer.cpp delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/RingBuffer.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Settings.cpp delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Settings.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/SimavrSerial.cpp delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/SimavrSerial.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Spindle.cpp delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Spindle.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/System.cpp delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/System.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Testing.cpp delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/Testing.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/TimerOne.cpp delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/TimerOne.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/cnc_ctrl_v1.ino delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/utility/direct_pin_read.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/utility/interrupt_config.h delete mode 100644 Firmware_1.26b/cnc_ctrl_v1/utility/interrupt_pins.h delete mode 100644 Firmware_1.26b/platformio.ini delete mode 100644 Firmware_1.26b/platformio/simavr_env.py delete mode 100644 Firmware_1.26b/platformio/teensy_env.py diff --git a/Firmware_1.26b/.gitignore b/Firmware_1.26b/.gitignore deleted file mode 100644 index 138190fd..00000000 --- a/Firmware_1.26b/.gitignore +++ /dev/null @@ -1,17 +0,0 @@ -.pioenvs -.piolibdeps -.clang_complete -.gcc-flags.json -lib/readme.txt -cnc_ctrl_v1/.DS_Store -cnc_ctrl_v1/.DS_Store -cnc_ctrl_v1/.DS_Store -.DS_Store -**/.DS_Store -.vscode/ -.vscode/c_cpp_properties.json -.vscode/launch.json -simduino_atmega2560_flash.bin -simduino -.vscode/*.db -obj-x86_64-apple-darwin17.4.0 diff --git a/Firmware_1.26b/.travis.yml b/Firmware_1.26b/.travis.yml deleted file mode 100644 index 7805f835..00000000 --- a/Firmware_1.26b/.travis.yml +++ /dev/null @@ -1,35 +0,0 @@ -# Continuous Integration (CI) is the practice, in software -# engineering, of merging all developer working copies with a shared mainline -# several times a day < http://docs.platformio.org/page/ci/index.html > -# -# Documentation: -# -# * Travis CI Embedded Builds with PlatformIO -# < https://docs.travis-ci.com/user/integration/platformio/ > -# -# * PlatformIO integration with Travis CI -# < http://docs.platformio.org/page/ci/travis.html > -# -# * User Guide for `platformio ci` command -# < http://docs.platformio.org/page/userguide/cmd_ci.html > -# -# -# Please choice one of the following templates (proposed below) and uncomment -# it (remove "# " before each line) or use own configuration according to the -# Travis CI documentation (see above). -# - - -# -# Template #1: General project. Test it using existing `platformio.ini`. -# - -language: python -python: - - "2.7" - -install: - - pip install -U platformio - -script: - - platformio run diff --git a/Firmware_1.26b/CODE_OF_CONDUCT.md b/Firmware_1.26b/CODE_OF_CONDUCT.md deleted file mode 100644 index f214249a..00000000 --- a/Firmware_1.26b/CODE_OF_CONDUCT.md +++ /dev/null @@ -1,46 +0,0 @@ -# Contributor Covenant Code of Conduct - -## Our Pledge - -In the interest of fostering an open and welcoming environment, we as contributors and maintainers pledge to making participation in our project and our community a harassment-free experience for everyone, regardless of age, body size, disability, ethnicity, gender identity and expression, level of experience, nationality, personal appearance, race, religion, or sexual identity and orientation. - -## Our Standards - -Examples of behavior that contributes to creating a positive environment include: - -* Using welcoming and inclusive language -* Being respectful of differing viewpoints and experiences -* Gracefully accepting constructive criticism -* Focusing on what is best for the community -* Showing empathy towards other community members - -Examples of unacceptable behavior by participants include: - -* The use of sexualized language or imagery and unwelcome sexual attention or advances -* Trolling, insulting/derogatory comments, and personal or political attacks -* Public or private harassment -* Publishing others' private information, such as a physical or electronic address, without explicit permission -* Other conduct which could reasonably be considered inappropriate in a professional setting - -## Our Responsibilities - -Project maintainers are responsible for clarifying the standards of acceptable behavior and are expected to take appropriate and fair corrective action in response to any instances of unacceptable behavior. - -Project maintainers have the right and responsibility to remove, edit, or reject comments, commits, code, wiki edits, issues, and other contributions that are not aligned to this Code of Conduct, or to ban temporarily or permanently any contributor for other behaviors that they deem inappropriate, threatening, offensive, or harmful. - -## Scope - -This Code of Conduct applies both within project spaces and in public spaces when an individual is representing the project or its community. Examples of representing a project or community include using an official project e-mail address, posting via an official social media account, or acting as an appointed representative at an online or offline event. Representation of a project may be further defined and clarified by project maintainers. - -## Enforcement - -Instances of abusive, harassing, or otherwise unacceptable behavior may be reported by contacting the project team at info@maslowcnc.com. The project team will review and investigate all complaints, and will respond in a way that it deems appropriate to the circumstances. The project team is obligated to maintain confidentiality with regard to the reporter of an incident. Further details of specific enforcement policies may be posted separately. - -Project maintainers who do not follow or enforce the Code of Conduct in good faith may face temporary or permanent repercussions as determined by other members of the project's leadership. - -## Attribution - -This Code of Conduct is adapted from the [Contributor Covenant][homepage], version 1.4, available at [http://contributor-covenant.org/version/1/4][version] - -[homepage]: http://contributor-covenant.org -[version]: http://contributor-covenant.org/version/1/4/ diff --git a/Firmware_1.26b/Documentation/Download Firmware.jpg b/Firmware_1.26b/Documentation/Download Firmware.jpg deleted file mode 100644 index 88e8e33178fe5e0d62a57df70b9ecb32359c98e6..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 87994 zcmeFZ1zeR~w=eq84T5w_2$Is>(%s!H0@BR_R8SI@bax{u-7N0%4fWfv z@80L#=R4=#bC1j4^JDrvGsgIjF~=OU#?8dd0&q)CN>&Phfq?-`p#OlI#aly?p0-v1 zpr{Bi004jtz{3atu+S8|xT!M`Vhg}S(=gBvatVoF|3Y&Bw^}wy0VHS=9r}M^=mU^$ z{{H1_`q%Fl0>2RWg}^Taej)G+f&U8;K!}3-&4a*&dJ1t-@ZZt};OO7daC{s900w_g zfA=Pk!@lD6%bWPWP-}j%{0o6!2>e3e7XrT!_yGa-`)oY?_c{6R^HH+h=jXW3&&2`! z>>U7z1Ezp8wB*eq8orII>tlXaRtFarQwv8kOBQoSdsa`=$E<8D_gMi!5zoh_=605@ zlxCLJwhlscUuqlaC~Yl-=(M>M?<+o*u(Yw2@piUU_g2y{_qH?Vv!D|Z#y}PHdEZjLj6Yt4=i2Gooyex+B!N=eyz~d%+bwNh|0~) z)`H*4)QZc@!h(z0%#_1|nT^fDl-bmRgN@mOgTsP{i;b7vip`AbkLE4RzqS6@&H2%9 zZCjYLT0XM0w{&oIfuh02O2zs+(f_VCp%8s*^r!Gcd4%TSmvFW;b+vo|eT2V?lleX; z^L;*zKSj*K$8lef^*`hjWc>=p4}|`EDgPfrOIXmtoZtK_?T*gBH?MB#^gk!7n9104GAnT6}{uP1W-as`DTJD>ELQ7KqZ}|OcZBOxLnA|oLoqhg~$ zeGF7QtXt^Vgm}b6gm{DmB;<5=NXTf(2neZIsA%c$F)}d{Q?hcfGO*JzFfx3t1O^Ei z85IQ;7Yz-Ufs~Mx;UE8QngDEM*l`3cI2bAb78?c*8|J1Bpn&c(B0zU0ziv+c@q>Yd zgGWF_LPkMFgJvkd1;E0v;)CTuxILw@bP*Cv+2#JVk@6yrVW8mcC=Hcbzmv|s4B`qT>r>>!?rLCi@XKrC> zWo={o(8blw-NVz%`^nR1!6DCIgo0naeiIWL_clH)JtH$KJ0~}<^g~&BMP*fWO-pNA zdq-zichAu9$mrPk#N^cC((=mc+WO~>&HaPJqvMm)v-69ue8B*4zq9p?v;V*sHk2<| zcz8H?q_2Fzz4kJXtq-<&`55TAemWL+O5IZY^zf}l-@ z4hXI%cx&fwRw|pP&l$GicEe*a1e4myO-QM_gK0Ew59jl;mb(JAd9c zo7X4%rSoC_4S+%)sThAE9)ax;&x=Dh%g}yzz{907h$DJl5U_zuN&BEwZij#Fz#^Cv zL!Xe|wAo$X6XY@x9cE%qBuET8nSD{taSpb}Ij0p2IpkRua5r~%>Q_oQNfUCHkOb@o zb?ugz*%m`J;-z%o#4}eM+@>UP*0AsHSR9@oSllSKEw#36X1Lvpv05=^5Lm5rzX^w3 z$|=bPPAW8yi&26z8l`k!?tRTOI?Se9BGluR!ojKht3lEn-89k2a!5F0RQKnmH5PJc zZg)uI!lX*78R~s1Qo}evAw_q1)}$sSUP6sJ(b@CZi_}GP*Kt?dFru5LvQkRY^>FY- z)yl30WdJe&^1NzVCKKhdDS#q)YjRTGu;v`xZBJ4$czeg)D38Jx{>eB|2Z|7e4sm^Q zG*i(R!r&PL8FD(c=&PA1DNtb5Ry$yrmcw0X5*s|3<;Z1d?l{Y)X$9mkhoSEhcCTma zHHsqOszM)4lIe{{bh1{G+%#sgxMTwr{)eCs!%4HsWB{wG#v{kf#>C8LxH>S;S4=z< zCNDoi`WyYzBPw%XN5h}S4lN367}u?r+jpkwrd=&&2xpdDqyfZ=$gR($qhifuj`MoX^h2bsN5D$@v_+HqGe{Lo%Hd!&8n~!CJ*=iRgq7>UJBq8DcKfT4}l2JFH4^YgUCzNM3(9jXn?+!Sk{EH( zx%-{y84*c!0Y;F{_cuTi#n~k&oMPgH;;{7wpm5yJFnrj)yILVjV@o}oAiAnkJg51{ zbizZEX3ukBM50a4DWHpdA)58I89w+twPLq3wh}Z;xlV?hg3|aiQf(>p-bWnibu%(0 zSi~hz;jrT+lW3Oo4T-Hdb>%*CL*^n>sAzC+^0YPaJoV_BL6ojq3ZVWuWjVgmIfl00 zq_KLwsvn(cLwSb`cFYd)Tp~~NVse+Xf<7v|Qw*o!DQ(e_!`fZ4eqbJPf6|Rm=x`$x z82)*USq;^ucx?lpXrk)qhj`w>KPS=%XqPn*W*6S|j?^of+9Z=31laWC?VUJ_UC>&( zSK~S!FWkDnlMvAozzi~<0QF;C`89S#ei!|S`yAzPQ5=(VS3z$mj=mSQ<2wN*BC+OX z;Hay^MIpJ(`w_A4xS0!+lUK@9aapz}RhU9GM|^~v^su1swfu_$rFwZ3Zd@=!GF`{$ zy31lLDrJ({N^?!ncF#Krc{Tfu_|>F~dj~i2nVj04XeZ0-!&c58h#y$`MT}A=FFphY ze$IN{l;v1hULYBZ}Fgu~;O*V4TN8 zbbQDz0kg>cNQBFL00uwT3yMvrBNqsl+!rwzw8;`0my+6R3>tDu$aqaK89Y;02G`6% zE*k77DObcV1q`+%*)Cxf>W(``!OzN zMp8=vnWPJGNT|K}K6xZwQK8MF%tOeSmIlN9fGqtpuT!F;ps|y&3u@*!y*zBeQ$|E^ z0epPaSmv}cKTyy9FV*i(`(KL=h6z`xd{*g;FafHwloKfVF> zd+Pr%!dg~&mD<|(b@XPK-^cL0S($2YkcwPI(3R<1!V;o~Qwm+b6S~yjhJSJ}Qm>ZUCq?9KQj6 zGl$0eDOkk&LXppXJ@#ShgqURU12bo&IX^Jq&7i^s$)3MMZ-N=-xX-Wm-oTzg;-0fI zx;M6F<01*G!=R#9Rh_m|Et5`v(&CG)4z{yPZSB9UuD6D!64RopR-Kx*rbOnkh}*qa zyffbGWS(37a*-6&81L zIeEoseMx)+Ks-UqTM$l=x$zC~)k13 zrs^0P3#sk}Hux}5lk}<{=m&jH|3N@7ktaTlWsaAQyH`sPS ziB7}*zwMr_C8aSf9-##4W>V(iFJ{rKcZ>5b-9Phgq~luIg1I)^V6-~IeU;EDePSt= z^`;!aOw*s7;}RKMhj%JbWW`c>&hajuYg(y*KeBFr>ZIZw!zgPnfxzBw%`-6s3g%Yue3QxUr4a z;GR3qcPDvE+k34PUR^FUMWK;5Er*?E(LGrS?pPzSdx>o1)z+N$p8h=r(_J$(O8OaV zcbD#>tWc;8c?K48I!112y%#+uWmk*M)YB}!YJtv{n6iwNa51_=AQvkaY!TzRf_Vw% zrLswTZi12b?44r~4BUiEB0oJG_qt@TB0dKDz;zOuM_@W3>$6bF$8`yZABg&W4>c)T zv6IWUt4-HuTG(LyoM8+_v*it7^<{M!L$-Vem$~Y$1&M+kg;(&&DFKpHtBNB*ZTLj>ai$53WYb4I7M{R{AWrlFmCT zjl4A*KN$OEgHA$r>kc5=;Kt3X`ZU2Cpz(0M*x`+PC=fcvm-Zo8;4Ng3T`Heu8umO4 ziMi}CyH~qdZo8k;!#l&-@*dGG-2&)kwtaHwCY7QbO?_S+7(MiGnDed6GBv^W2r;;3 z_`4`NZxTFS2_|#8&0ZN|nejkf47NH6O!H6^;SB~5`J4W3V#V9->`c)$Z!AosnvUT; z@TL`Ul+h$9d)_zW_0QPwu$3He_taN6U)#Vv9T8-vB0<`5!Eh>d%klNvjeq0S!iMAd{NO<*Pn^#GIZ;B@ zgq@ONHQIP7SioJh9Q9<-k7MKpxX9Q3A^(q40`|fk>T@pjQ(Zd|b>$Z%-h zuqI7DqS5Ef4_Fz`op?Cqo>$~rFFtl8CFD84H zo;rfgDXyk7*ikmHB2>!fpBqm*Zvdmn@5yS3WoC(O&~&m%C8X)_s+i-Gu>0(#V6Qo0 zze8hREs7;{!NbxdIxWV^JOJ3VqaS_x%I@NjibHMUW!Ec+H|zEO4KSYmJ((9X)fTI3 zbCkat)?pDUjU7l&*aYXVk+4U|EWE5+UKwg-zdayN%AQtC-=__igf)-!M6)0JkkO!I zMfL^|B7mGhMLhUJdf1{Nf>{dft`@se#HJ`AjQhIC=|CFfLP&VL|E=yT@4L5PoqKWp zvy$1%J6#376Y>L1xtj=e;m0VCnjG1A!D>z&gzqULdu(UX1;5MVhh$QyiP#VA|47TI z)>z@#p8mOW#a7@W8o+-3eKna&6Y2iQ_2cg2vpZEWQvyCOc5zH$+X+=H%-)?bHJPvq zMh|^Bi7Nkc4N^$5Fg&1vE+V|V0enHn8-gL<(whQ?k}NF3eS3i_*C{WBoKoc3J@C51jmn`G&)8dg+IlwMW}8ym69%{@%I+cH}F1KL-ky@vb1Bw?%2Ur5$m? z7w_|#$!L{MZtud^=UpGFdPRlF)l)y`Xs=yZjf_ zPZa7bA|!72D2Pd5);acXh!XtJ6Msm8>1^+4drsXo1xH9}Pb@^A6Z-*w*Gor^RN%i; z@I9q0`L{&|PMr#`+~cgkGE+)Os40Q{BS|8}Nq;YapdA*v>KD+y7A18~ileC?+5Ajd z^w!VyR0tOa>ASpt5WV`~uOdGk+5X=~Y(Pen=7==@Z@N?tvG(hAC(Ui#rP77{yU{K_ zIeKDwZ3i3A$xm;SRV?gY?j*o+b4xk1^|8~#IsVj;7Ck=ee85kmSH}OelG{aTY_Gn| zxp!EmphpuM#`-eMIVB9%+eI=t%vJs}BWPIVO>eYU{=Epzmn1wphsYBYwlnGi0V|=v z=c}I%V41eAl`+wV`tq!?3?br+ucN#z^`p;18{xAg?=&17cOIr7dSQJVYlqIi%K*9^ z8TtAKaB7Up7ASD~(ABIe#?+YtR}V=3&44)0=Cu5ls+>R6=0gRT!lu^t4bgdr7Dsns zKi1~_bUZ0>&W^8Oq(E_Q9|Fsc@1)H@W_9IN9_LFp_e^FNF!qzx5`97XTwIH(%ude>3=O zdeg)H;}PrsfTMT8V4-^PaitCHLL0WuhOkdTVIMqs$`UM=}~i=dx5e9?}_PqcpnaxV;OkE18r z`G~r3cN{`(r*~lZxrR!AYU995eezvboJ_msb1NF_Rm%<}qT^41cOhQinR(kO|LRG$ zY3>Gd=DckoK_W_(ZZM5nj|4qjN>M0uyRgV{39;BG)ssMV#I^eYkIM6_N(K^#4LoHe z>QqjcAyp&Cy~y_X@lXP7;?;>7?hXq2bD4J@j{UQ6BCgsQDln3Gc%OQ?-G>Ye<)T_~ zV!X)S=OH=U!0Iu6JT?wh>ns+pz;MLK5n-+$U^o@M0k9p<&9L@%w?-DQ4IwWJC$}m@ zY)h+Y3lAYrZ?(N6<+WtM{J0 z7=*g4CVX|SFjsVJ=;L}jc>(p5s%El<9c52m4QUEBI%86yo8r``qy{*KBz6|x{h$qx z#?+%vc+FS*`-rvdH-M>UDFV;Q23@QNS(^*W1BIN=tAtCEEGbX=1rNuw-nILaRV2x< zaP6?%GdGJQnUg9A!$hV`LKe!mk(D(h_osTAqv5(Te5jZG`O`xakw#NU7sM)AHS+8X zbV_g@pAIWWU(7OojD_F2gf{YFe?55HeoTFJ+CUMf8|Op|k=^BN04ZnCNa#9uS^44~ zIUdw1#(~a8y*~xM-l*tUvssU8Yp^K60!uZ0WGxX41xh4wRp5D$9AB@e$)H?$LdwZ= zv!=I*HT#mi37cJr!dogZu~PGyQb+R9^U<-lR0^_Y9#zqqT$Y}6HfE0n2z!lQVG%qN zG(<>#K6YSFwR+O(VHvPa7lE22?Y6aHG`dIuw~>UVUy}LBjdiNWD|m6Vq>{G-7vwoE z+6})MwnZ99$PR{?k`@=*h;*$h5UB@Au3+Wj!qA9tr$!I)c8O?F-vBT2#>1xEORiJ8 z`t6t)(c5uLp6BBf2KLP-1|BUOb>r_$@tQYVS)0e&hrBx1Xta$SZT#{Cf(z5T!DDNQ zpG_7%!=E_1bM&Dp=1ZLv1tF$4J>mLMccG$qhrA>FtnJCW6)-d3!b_X;xaU1#K4Y;{ z=EshgP>py-@n=;TMe(<_wS;}3TW;1yH$ckW^cx@m40`6{R+Pv!9>{#O@d2YP-dTLk zWR>D0TyjTw!!SiYXddZ`{!+oe5ISF@*ehZnq#s-xI~`~VN06;}+dDV8ITclP1Bh2w zm}h^2kFK98Q_$&|A^o!tl zGCUlg>zB0||JsAaH8*wE(GI8Wu!E>aPIpf;f>)4qT>m8QS|4&IvMBux2P_Q4qieyd zx`|od#;xJ2Fhy*scV4tr!*lJdne1XVwIa@Wp+s?vctnpLS8oa_@)!)U6z{TJRe5xB zy64?rbSbs6{u2F+529K7*Sd{MUWUG$#EN!4Na&qHhi>ZGhE6N#at`{wLPPFh_(bs< z4#;@62(ixwmMRO-Qe>!y{o5Z#-%;#$e+jeMS(brR@1-7qvT*^fC=xS=jJYi}e5_WC z5=-1Ixme4I0%@Wau+v7;aZTg?!40s>ddQjlr$!BOic9%6=)i=BkXldARXp|53?V#- zBaQ%9BI#G#af4Uo%F}mf-#oQ@LXq0F$-j)0sW4@kzcm$^m`zv+dHIW(loRaFLRyex=$>7e6qBDiq!iF@gz zLo%GaIa6LZ$JAuM#bM{_2TPS_H-OgcedSsBF!!R8hTd`28TOJGP7AH68AQtH$TQ@t zJms>^&H2;j8vr$bUX>XyOdyrC!7Yp%JguB#K&51m!2c9sQppPjaVE?~vrY^%HP_br z(1teVV5&o2{x->uDVsrw`T#{0%(mEuArW|{rxdR@6g5AtPn5T-Phi1cqZ7Z_o(T|i z>LKI-6LTC|)37f*>E=V?Tg%)GF0(mcOcap;D@x5bLx}5!1;3ygcMNd9qs{+x?;ybV z-fIGXQ5KllC?0O!+0il*8MiO^9}$BP;H?mJnZxoo5pM&*Dhy*Qjm6wdM=8QMh zXT|Qm^tk(uw#|L;kz$~wCL`jc#0NwMp940dkiT|Jy5i%*0a;!Bi}M@6IC@POXJ{#6 zOBBBb?>OXnVPZr*Na%I+b^40a-OHd<2RJ#+So9f_tExp#N5D4Raq(`$9>mDbi$L?X z_POFJ`cFKFI(!@Hk)uzRtfZdXQl z+{!^Zb6VZmDfe6|_~;0-IGEo!={?18YkEZM7_W${q|v&B3XNF z2AW?3^0-`7Q)>^I{eixNJb4|DpleaDE<6ToG%V%APRY&<;_-A_88b({|U!KS}#$v{aBd zth49puO81xQnfnIJHG8&v}h*5N`+7DyyODO)baZ#+h@({8q$8MDG;fxv5Rwia@b8T#KF{uMt z7kU_L(G@9J6wPFJo0mEPYDE7kBWAq7P0JYrmV6IOTVk2$SRR}gD(Scq2dm1|tPxd< ziafF<)$+9)Nt>JWQwLi3tGB4146GD==^9G`&&XM#y&w{gJ?MijsrB(YgZMqZ)epE# zalfWX>X5%=S0H`_13$P2hMkR+qKNCSmoQ(vG$)U+9zOS+F$|G7ysCy3^$rkia)=`= zO8%=vfHmTd0}=ttiXcgLqHP^`zKFX~+m4o+q(0a(G2<#avtB0{?D`BkZD6TBbkp-! z4-dA=vP8GaLN|r~GGM1)KpH9PM2ffeE+dpaD)~IenX{8PG2XeqMLflceeSO;Qfnrc z`)GwcBjLE6fZw2TdYGDF8jG8?q&NQ2E5dZZRPBL%NmwxaE&hZR;;ruuJOJ(d<{Cg6 zSr6cnYbx#4l^bg{y%5^lR3%rz%CEsN(UI!)r2=MocKph*xrE?3`bYkK_!FI3^-a&Z zX?vb`9ZbIwDCy(hH&k%eZ^h}v*?vHxsl^T(DaxkwZKO)U)K)F2XS{D=n{w%D&j%jO z#K{RnTqdNfnnM(&iyl~d%bd@WXm3ZGXV|pE6kS)NQ4p07Kz(cd-pJw$04A`xsPZTH zuEd~lWGXsYa*b|IPv=XzSncAj$LM-LXr-yxt)kF#OMKQfHo5y!(!Ekm#!``A{2-gx zxD0W!tOyaAkP_WOTl*(UYU*i*P!aFBSjI>Ylf0p9HFhB5?5~Y+I^o8`%U2Yd_Kl@) zo=yO5+OM}zkMG}sLsnPqvgJk6P{EQg`sZF5qmMYAWF!v*WOS=-|U4Pv= zCBbAS9qM&=;r)}Yz5Jh-M<#;nejDKC#5_;C*W8mqu;`}RB74wEyC!gH$b z7Qwtng%u58(DIRe`Oz!r3Gx&_$7@Fyq?Y-q`ALlH+LL0QK1ar#2I=J01@qnm5s!r3 zj`_vuBo{-B6gr=iM=)PPZSd3246Y@JV|TDI-~Bc-m}C^whX|`*cR_4U2 z2Q3jif4@_OojmsX6Lz#Q>l=7;(@x%#lk9KCS&gWp)x{0*ja~X?!|hnr>M~Va#Z~I2 zCUnF(|6S>FckYUPy{QcDll^I_^yg_RdDSZmnEbEgf1>dOBAcKE`K$H^ja$$SJOg-<;n+8x_SZyKR3r{=>BG$LzN#hg8_`=OIWbL>FVO z&N5Rsz`G1FAM9k0Y4fT;FjHPs5gIyvm+Aoy^2!ln3rA|_boc}y^|^fn=XG2+>eCtjli{DZ3Bq^SBQG%_eQIe+Cb z<^LydAHIe0wZ+882@^p52_ft$$1EPI_{_E#L- zC28&Uxtm%QJO?z`(=C>lOsJ1#9e3Ax$wxOwG3qnxQ=IJJRbG(RJ|AFN6O7^AR4xP_ z&!dMIl}$B1&vdUHp{)mFmC5kw1R&r^?}cHvdk|1;?SQs&Z-4>f7&Lhw^*a?o^a{ld z62u5|^K-nLo}?q0Vw6!R>e10d0eq~XPO?0$Lb`XP+^27wN-4qT$X)?=>$arFeDB>h z_A5GU4JBXUGy(;$#xkx__AEkFt9W{RR!)mu(gFn67hmcdc)n~W@V1^z>d-3JvHbAC zPDdw?d!eL+#w5vW(`BxnIFueJ<~qw=B(v5iiMatJ8|!13(|7ny62qJkn$dF;EKEqv z6D(ZDhjLP|kj}IhG3-=pphv$ejW*&{OxOI9tX>p_uA?=Rq9-IfBk^_CK~IO{VT>l0 zA5k$*dlpfn6Vl|6TDbBGwJS;jzO`941Di=W`{d;woNHT3+@Ht^O?yl6%+BGHdtJ7S zruWk3Ztq=$tFtzSgTslBYk|uB$M->GAHM4@tx*pZMDsgnJw%aoOEVIkwyqG zA}*cg>evsLBxF-(ZJ$VS4=JOyvUfhtM=`f21>(Xa15|NJ^J*53yNa_I?=H6_k=IuF zysSr3NV3IT2kY}r#$AA=6kRkk`2?CLPD-!*$)9>T;hqT zO&jrwT`7h;^m*M!DuD(~ZFdE8mYG*aMSWY%HDv3dg;$bJX5l%aRoW1I)9|9!T6#jH z3ecp1eJ8O5)bC+(NfRc$^Go82VgJnAbHXg-xge;U>f%A)(DiYNZcxiXDsd7js4SG?(H>6<2) zP0}|&yLR7eRSN>^!Q{Qc26E^^lT`Nk*Vn2y00zn8mkaoZpx2-)P2Y7%d@*-FqJMo$ z@vmjH`&@rj^$V-t73h~T{OUO0tjRBB_@xZLl;K|o&tF68@9xJhpW&B(^@r2>Ynb?- z9wyX4tx}#IP9l@U$;vXnO#_BPnS!=2IR3-zK;&O155)f-t(ErsO1R%; zY>caX!lh%u_zO)2QhI zNY2V80`Yyt8I9JC=wjB3`jOc3ggn{@Wo&#D?lioVembN#Kn=ag%OvbGgvD8^F+N`z z%o1NI9sGN!6rw3X{@KMTMSaR4Ae8@zREy(R1S4+NQpXItlhf{ljAc_aUv0 z(Cg^X%ks<86ZX&x;K>ldhcov%cU93%o-to`;~@h5T9nq)xjCOoRbhe-G)HKvdog0Qc?&1)w z5uNZDf0^0voJKrH0e9=Z_ zCM@1A*6-ARoTUQ)jj8l+ZE}4*H~J@rHs7lLdhGWbUf)^xdiwSoUf%@x_3ZHfSE{z0 z*Uvx?7KXD9&DA5$zAC)}Wm*qF&u_stQX*><`0coo6;AkE-ccv7^sz|S|KaI zMDAM7$;m~hhh9Ja?a3`HbYQi+6tIj3u3lJmUUiVk{&lnr}O{~|U>P$I+jz-W^n z^vaQ(r!tuYuN$zGxIGdv`Zjk%J6>oV8jr>IZ3W}b49Ti#lqX#|V_3GNLPacw&A2># z)+`~l!mVvBAs8W!oj>XMO4Gml!TX$y0U_&L;)0Bgaa<>pK2y8(*qXXX*>a~-4>+u0 ztU7zSaA#5A`4=V{Th8fNhCs*>^SG^02Tbz`-?5<3??ETD#g@oW$K?h&NouX$WQ^D= z3?rF{nmBcmV)a#D{0?(b>!RYDqSSo>nI|fNbd|GA;Uq<3_ik5ped&2(w2xVxch;y{ zR=uY=tZ!T4%wR0Zo=5NzalvGLwQG~{p{u3Z7mG?q$Bh@Y6pVw$250exAo+3XG3wfb zD*;>L`W3YBZ5V;~$m@BhcqV2(n8xz{|iu&^8NdrGlT_3k|drH%dad$-bomX(e6C8rPvYYR{D9&_e|YGjhk58q+yrgokuTTIF{^WQqb*meWaWpcTw<<5z0){eNr>KJ5@0Kq8jdZgE_s{UmU$FL~GZJd6z@YbaIMW zSmn2v5KP{7OYDg2m9f}a%NMI~P`2k~)A+?)X0{~NlwHh8o21}F6j^8_tb2h$Jt$v> zd5cj8pJEhE6t18-IgDe!Ff$W%V`67VrjC>ljp$#9iFC{JRU6K#l)68$Ta~2nI21SV zyacwM?j)uv+*c?~A4hPKB_mqem%-!)_$*$pt~gkRg=ljS&ObITU;0Af74NweaM|1W zs?*tSH8OOLmz;0^<;)a5q_5nVYT$myYM=aaiTMSLyt`0zo8~7Th_L>3>s7n@591W) zR$*X}XUpJQyq1mUautu~Kl@?w70HGA!H^l|gs7F5)>f63 zwBLJQR-mP5i@dE1A+Xb6#aY0OYj{@2c7L-Xii}&k!spVp?A;|d?}E*#v*1E!A9~$t zy?`@g-=+^^<@*ul-9^+P{jO4a(`E)|j-7Vl#_^~coh@(&0dfQF`^w=$$SjUtX&coc zb@v<(rXgG9I?c&?{G%9;JHwZD;=uyX8YRmsA`mKhQ2LGt;k@^%%#-Ss?842fUkLTt z-ecX`W6-N`=TD3dFj96xm%9Nbmvqu&l_REfN*+I9B@Tldft#UdDVUWM+O2e9D+#tM z-u}EYoX-6m-=&0yJx7Ix(y@teV>nD3O%k^8_>}BLgn(7N&nMwYF65&Qu$@PxN=f%x zjuhMS!-^SF6D-y4UhXYBkF2}(T;=b%Rl9NbndEYrG9aI~;Yh!%m=lJL-_y1lnNwt8 zL|zC+*1YOu3!Y_MhKU1vqwn446I3~YG!}2b$i2n7cn)3lrszpl2)TX$+KpTlB_V#q zKC54FTd%GnobEQAj(%9eQ3qQTNUj{OzRcU3y`8pK-}sYf;Ty=Kq~e4uL`;z+JJ?V{ z60ok9w_w9VxC&fXw@TD%T5s8eN~Gv8fAKdh-ML1R2xWI=G_I5G;2b!!J4MDV(;0>^Fqtd=3(-|$9>3~WKjg~u&IdXR8R|Zq4CTN*J@EjlH}|A`*#Ea?uvVo zCWN_PF@DUm-Q8u;y5l1F0a-XCQNJoh(L70KGb z;4>x8^STj~=XQB#whI1ExroKtzw{RTJy^>EtIPP4QU|3oiwweC*k^QFXS z5AOw1>$x~CMKMt{KW89$2ktfx4%D$zYV^4-DtB`CfK)0U;a}bW`tOu+U9L1dvn0WM zT;QSzc0!_RXb^=l-D%s?Im&&BhD4jjNt(>W`i2DXGqqLSUX$WDQMfNSh~DnS9G4n5 zfZe5bGTjuyi2z%7zy$%BtTVEJsiF)a4_}bN~xZV@0i*QwCe)_?Pa_%x#5M!-qdT zs>n;7VbOR)UHn);J1*Q&lVI)ap-0em(Xi7=$RXQCEnmCM<{VSa$o7$|F+WKm8>wG` zl6+V1g){>16$T0c*W%2PUL|QfF%xugU>oc}p4D9S~d5kQ%%!w=&ayPQF0X|{7 zV$KapoKLUrdYUU%uQew_EfdD8s@6$ZelV< zn8V6(r#IN~mK_h)?f(4vo&oO9Z+8vi`W1?lkv60%8;^&to|RS}k6-m`4yIqyg_q^- zm<&yQRH>}K6pY$vnKGd78&jWg?b_tfX`rZ#)Er)^BxZh-RL)r{`|=Zg++CGMCqk@Q z^SyQQ@+SF$%~$i%KHQlev?CJOeTOB{!r=)K<jFKDRqofk1e?v>%5Xt37Pc1^0^-$W^3OV3gX<~zWBG0{# z^I4ZLtmM0PGe(Q!*C@64;#WVW2#G#gQHM0b6AZF$c|fdFjBH>EkDE^P{CW#B+J#=} zPMkAoboql=iKMrkCQxHKTlKs~I0=i7J`cGLlCKs*`p^{FlX$YkT%IImge~K(Z53|j z=WrctdIasn+8Lk)A0i*kCM=bA^A z3GTz9C6ieU1GRKk!L2#j;6CkdP?=G z#k(GoZ<{~$Fa~9f!@$(+&CBQxZMulMacSm=Nc*LiAC0%W?sye4<4-MYv@9W$#nQQ& zhgF(Kbkxml8I67^g!KF6%^S2rr(A1Q9>!e>YVA-d5GCoj`JAmpYZ?x%w%#`iNH{=x zXefQ{FP$>`Zkjcu;ZCW&fU<4ju~fu^iVF1S1=TD9Vb(!j0L)ZfMPYlM@pNWOv!4sj zEG!)g2Mp`wgb0uN_*kBrY+=W2ODKI7C3J)F>n7vB^(juRqb~6D5!=fQe#=syMPw3r z`i>Qm)F*=QTWI02aJS5Hcl%6J`f=tK1N-jU276tbFWf zygIC4pm^$4jCvR8G4*5ewL0QnXNx*{w33L7>u>^J${zCK?B$C$qDKv0ai)psuW;}ZSVpZA1yH6D_POdX{Sg^Xw ztl>zX7*Q``-J(GAEbY{}b>1=?C+O8|X+b}6+Dhs(ZYC(PcM9inmMn7o1v=YqA5Ra; zl}hG#_hD$tcwB-n>xBOcrlb!`2;GZv3?un`c@)`Lg(NM_57@I z7c>N)dRhPr$X4-s{oc3kBy!=ZDv13Tlk5L<&ikwEzpVHm zFdIX}IH0%WKu32B>fMMNuY#rK`Oqes0%9$^L68;6)c~#^UpgagXI=^9Y+- zMcuA6d(s52f>@82gjm#rm1w~(&;kvNsj2h6ipSf&{3E?qJWW*K01iwF8m^XGL~Yh4 z|C_aBYiF985|c{oMoHZTQ**5rgZuv7WJ$2h2w(FL5rZmBiUh*B%PtG1u zCviJBygZs2NDE~^LuH7_&KJu>lXwi~nJP*zS7w3>b_r0DSt?dvwKdSzeh&?c8jP!H zD53gcs9^4kT6M$}{N<3$1ch>OxwUQ5{Xs6Dl@IT0z_PRQdG%!_!Em_^Rl z5~DGlUViX?=c?r%UTm90S?&`~zTsdNAwd#Vkg4N-CxDBqDBIe{!^7U5`@A55W~(eb zOiHwyP>_5ik*~dMZ2BBSj`?oVY7Jvz_5PROLhG1&T+BNtZNbPiZ!|9OC8>{#g81-t z#$@_5n=FM>hTrft)6thZNjbeLHP6W_-Q<41siGsx!cv5t#M|=fje!Li5m<4{^ZxSU z2!!5=w&ek`((T4hzBlhg=Koo^{QlFd5woI+Ra!hR0cyR_)$t{|;H)7>E)x0i>Y(0~ zcONUG@a7)Z-6#5Nml+`$LlezWK61aSx%q_4B~vZA6TeWq>XSb2&t@uc044{r=%n12p>%a@BaI zX>Y7QT!z6fe{FTZC}0CQ0w=h9MpE+&;re7Nf`3I+uqkV9m;Zb{D)3g-vn5^U$J`$P zJ|UQ9PMGnp?fl2;G~T9j!ca`5L$>Enp^;@;BFm+(CmX*&$$2Il|2HK3x62ULhLxz$ zb`eo``-{jKm(iWxg$6uih2XxYINE63iU)D$bHZrvpj>zVP5_0C@~+}<>@$qwq8C(R ze|UEOI_cd&5r|D~m{nv1>*90r1!49863hg&-FQIFXJf$ zvJR=ix`ugZFaQsF79s8YCRM3(s z!L>7Jt^8pC!*!}i^>6g2f6t(o7Wl@0m|Rp~Txg10^*mZ#-4V3h0=ih6?@1JWp0va} zZ9Ai%i~6kO9M$o=G{LtoFOx4miyR^3xEaa`QOi{|B~&1gPG5dyjwoV}BfyrD}Q z&;yC?j+f9&jnG@7-!$QU$V;&g>L)0|Q{!2k+YJw$=q2dp`(_>yU9%-IS}Qjw$}5yN zJkzDFes)*W*FmKR83{h@a3We1=f9(7FRMP{!5RdD1!I?wGB3qJ&cBl*4|4-3y@OO| zA3ppbiswI&Jo8&0P(67HS@~UG3spsXvNqXHpN0zQ-Gw{XNLkO6*R&T|?!mfPYwQWU z{d=_NuMwkv`oPF*-vChxH^3gnHL^CVp;Yk=K=~GWOjP9JR*_NE$L~wfQqT=Ritro2 zp#Ko+eS|qIFCu`PUE17`R&}IoWCXfJrcc9O z;P8CEgb*X_$tEww8_qkq`BO{}v8H$dP-j8om7;(olrqF*XoN24`oU+aJRMI@o#{AG z87rX!4PLAxh1_Tmd__elaxnD^So(fZLL#25G=TRAi+X#_u%fX4J1f#2@u@ff;6tdA-IOd zHMlm~bY88jwa#7ZoU_;7_x$#|@9y{8e>7dyRm`fIRW;@q-}uHijmjlU-V|_ql1Snj z<>*Ll1J%my%2Aj2uC9wjK>|Lui#v)ASQYlC{2zPT`v~onGn!J5RoYh2BfQaQgQ;3< zPNGj11-+6b7s)D#55rw5w0MhO=UVaX+~= zhpdY78ZXm0V>XOMQ8Vk)X5;#GxCx2A^KB*fQ#_w$hLh)7-c^G{TI7Zz5Ew7%0~M-* zaiSgS3x`E}^XwMfEpHIG7%lSB)3Q;}Sk8usGBqXFJ4h1LHoU^`y;NK&h$hc`?$5}N zbB$rVd|rMcV@i!1?AZQLCwn?-Dy*e%0~Mp$A&@g4mNnJc1eGsi`?-dsLd6)xbFTcaD^ z#poHL6!p4? z7`q{}+jI4wC&{Uh%p%(F(TX?+3`S#bD{Eg??T8Rsiox2)x|A{GKRO zKmcAo`g^o5GuJW;($q5>dFdxFFgSZDh3}%FU?R=lF9I*~Ry1=IScurUFAfa~^+i3i z>3E+*yym(#zqVL1XJFEnzZA7}X-)=7SZq4ClTWT2B2H#&oc31Cio&U{PY|MqpszV2 zy{dSI)DALH@ZVi*Ivt(nZdmDqnL_Go8vu#iYTCUS1<-4=fINB3g3)n{M%xxU?<&h= zxZ7ujhi@Z04Cj4hY-vxrozy-uN+xlZ`EVU9CaA$9=zE+Ol3VsG`kCYizYHKqjuzur zt?Xq}JC>)66f@$6?Bk54JSmNocGRODWJH=kQVa*(Y>1Pv7bIUPwMQ9xl&^`7QjNh` z2*L!zJa8FHswHc9O${aHGY*Z)Ouq}GLdHtDv@ybhTB|2Du$fAK)`+=`S{ZKW^ z)hHia2K6lMHM)fn+bE!h=*&`&OXOrO)tepTmzC#ddkZ*VeQb3(i@B2O3hWRhT=#FM zUYlzks06&PWJFuU*owM4Qxd7m}zR3~cz`n>3i7plSpsb_4 zyZ9(!U}oR#o_7zgU`?>*V>E-`BPJuHHMGL+SO=XzR!-CGW;P-Vm^#F zcTdp5U-(Xt4SH8eKplkcJ;sVpvnanDQ9cUFDSlRAXL&8q|0u9VoyR)0lKLq1AurkKc$1g>gWJTO zy2ZygYKIVLE~VMYakVYqLb|7Ox5@;Z^qdl7mqY{#AKB;2PaHmR*tqh;G;-tZEgaJ7 z8dKC_sXkW&;P?XAXoivEpqo`|g_Xrj+t)$Jv1w-OlTp*jXDSn15p+WvC<>KtN?Jm! z%?b>?rnwTMTyl>#+k|si3DZ^7N#34(d>DuO(1>g;vY|Xq^9X&anKsXSw}`8G&XR#< zyfe1_Sr4h3L(HL)W$T^VNtcDE2!V>~&H`$OmijRJG{tw1X{m^)MyGnpvG-XztATt* zdqPH1N)QcW+5S?AwDv{`JbdY)<#kZ1&3?JJnN7YfO|f050FuM=@wH7;5P4?$CkjZS z!&;i>+RAxw(YHY|&%mBcCKF+;{Y2DYF|7GzGor)L?Sp1gS8rvvl5NkuM$aV%nt4Xs zSi<{kCrv)XLJ`VQE4_&;WjsZo9p|>r&_C z0)8@_=4;`&WLkGty#$WEN}9U}fwW;QXnao&Y9nfBUUJ~hZS*~SDjdN1L3E){gbh|E zf9Ep!RBaN%#DB84qX%nD~MaV?V55?=Ap6Ghty zseU{X*B(6^l97MZT3IGtJj6Uo)c!g5t=U2G1>gEbdnv8f`_DJbb~08zQ#sHfPZv&= zonmOK{w2A~;rgv7$)uvVN3i{04cY(XZAf|-2%+9v=cpf`mw0;Dsr>jC`RwbeqCKI8J#T_UA55`5>Lx_sH=E19c?p*Y;jZDiWp_w zY`ea_xqu;#hWWiz2-C4fxlpIX7gJ-w)*fKn+cj)~!J9N}qF!qyZI<2aTU#E}CD_tg z-Mr&mMb`tZ&Q9*@*ul3f!tHhA+q(txa!{gJ9)9j8r1r?dq5@6#ljU)CwB$pZRg2~q zFe2DH-_$kA;E>Jtzc{u+r<&+JUnyLn}BjE3)S{Ov>l=DZd`*q_*fqC zgoF!|#3`h_N!ZjiUC1Oj>ih7BC~uyW8QQ)az`cd$ugeqYlCrPpBIBdJx9^g_)RH4( z9sYsteklmSlbUX!iVt1ACC`m8a8qjdcxF zR#>~?`Rd8yiIW50yxi6Oz!BO=JbT{N()C6pINZi|Y3qSonNl%R!q-Anyj?j4z=<%V>EN4VoJ2*gn2y1Wl^Ky{B} zQtOl*!RX%;*}leVu_u)e?MjoKNIw1g0(ENY-IMm-0ZC%=A-(aM6efZW>$5(=Pxwin zHL5w-201uzHDVp5sgte5%{H!BPQX)L7ZcaOFrSPll>xYW6l;h^T0{{2+2F|K1tn}u zd3d7&c7i4#gn_jgJx>KCP*^} z=Z!%_0uDb`*wY-O$Lry&f@G?3*%tZdGFg@-oCyI#p_Rz}DA9h%{*!0KMb&jczfI)} zlmKb?nJbP2Vcy9Nexb=Qo4oCrbJvNmloV;RNNE}>Hjj`F11c)i6RbnasMpgFE1cEc zG8wHJ9Bs?=H+NU()NycQ-ZFf+XAsmLVK3vhh3tiRScYcPNU9mmJ%}r5Yxj&bhJf2P z%D0yaIRWK}K_&y;+%0yoUnnP`HHIdY=4&D5hlnaV%saeu!X_PSWy+9+<{u!=*Da6} zc%&XS#cm?OwjHLLjl0X__}2+d**l*WSy-jlo6yuK7id!*W~fFpPZJi|T%Jm^Dp0$R zW>>pCk*3DB&L}F?wnH~}4Sd5LscAcXb%#Mp%0{BrPd;Y!T3>%S&X8A1>nlCp<`{!1j>eEghBH7B5 zA+@gt7A)9xBTvB(uK*8&2I!n9jHv5%08Wto!}1G!D&G1A;1b>e#gJOe`)e&#>C+CM z3L5HtQtZThySA;&61b+1N3K7j3Feg`P2xlkHdm1MSD~IS(hxAe3YkTY; zUcQz}A>qF3BKxdYvr1c6;t{pw?o<4j9QOq|)%eLEB_Ywf#oa3r6hutfGD_l*87R)8 znH$I3D7Mr}GhS-%uJbdz>)l(MA0V_tT9bk^*bk8Z1(``uUEw#l{M4C@vh`fVZFiH5 z6X)~KD3RYVQ`CKBQjeMBW4;s}G3ogfWl%XC;1UzYul=1q2_-1#mnZ9}Lk{Jk zgO^xJ1`?lwUx1J%?nv6S1<_aR9zFsLt8PrrFJMg1PcWuTRa^e@_#L95;w1B4;orzl z{+_?g0}M#tGw>xg;yq(xdCs3u8Yz=oDuf6rq9J3GE(h?aqI!T{FuMW@ck{DD=|g^R z;$Qtc()|7CM_S?z6xYY=l*1*r$y*4oZU7FI{{g~Rr^~z#HU(bH^keW6U{bmj&#f}9 z4he6sMBu7A*?#nY+FSBlIe4pC|6(0rma963f(rhyGvyy!Q5~SWlktb0Reb(=2Q9&G z=~8MAaR1Jj9=N&-p_`z(G}Htlp=}Y;{Q~WqL?9pxrD^@m#CJVZn%7N(4h* zw%^k~Uz#E!9ym1Mc(q9ahb}VDMAzfn5Q`lomLPgt87&1L0-_}2!ro1@=dR=6^ zZL3t|;`=X;8o&m@A$-ni8jd`J16+H02vvllCml$+5D*CcMI`iZf9`AjDR;NS1-?QV z`2j)#v?l@`&w}*FMb?hnc9Rf>p`1~daJ%bG@TY7)eoMOSPXT|?>YXA>Pe^2xHSJ`% z+9JDaz&GlQw|rc##fui_$#K*?=VLlO$gI)|tZ4q}UdzcJPET58;e!SJUmJj_2!S^* z(0?W4`W{e~(+t3~lt-Th0mMdB1fB?F6h4&MT}qsZTq9cmbdUQPE0S<3Ps&@Q8Xzf% zDt}ZiVC2<%0N!+6LY@PA0s=9#2m-Vq@OR)@iv>{kV@~jw_M?$oAd`Her;m6B0Veeu z1u)+SfOTJH00&YYMSKUJ-JJkXYJ8C|VZXLT*nXa|*wzO;%>U!l%AQ?3zR9=>JQ6Cn zs5oHPT0WwKlzzdCm+$nPQ=m)6Z1E@{{ z=ydPxUIN>>0eIW52!RLw!jlCYixfCmJHUv%&lGV;2^hCe`oH$q(+4bFbHWggm-&mO z<8<>1CG@@JM3}HLtsH`g{Ot>RuE-1<8%Er`l@BU0k*Qdz_gi$GTMAeXnZQ)B71f)! zQ~O(O%fRf9=ElIEUm5xT{{Gnys*^b$HQ!>{5&#uKEB3WAdtS~i-zTbhTy(lpcyLqM_e)Qfs~DI=bwOsXR-k6=T0mL8N3Erpc3NX(4o zH?;;iW|0S>hlB6V8=<&%5H0hp2)6<6vTs)2(pML4pJz^XHf06#EuzqL85S`KQJ9bv znnlsBmR=aHbg8A9r?(^bq*c-M6)6*iX55}}Z#y+xSS3Y0d+7_QotZQY7dof{`AyHFPC6n(ZmCgS8 zM8FU2Q)!mO7db-en7#wo(;pzlU@*&R<&=v3e22X;!Kozuhp&z(_E4g?@x0$X0M^+( zql#Uvuh()Bw^`?W>#;Cf2!^}S0&8uwgdoIz00Wl@UO>c)TsRc0HpMA}u`57N+uYoG z%$Z>0gkt}}VZDSvVO_HMeXj_!w16iQhWf3W3=FLRw!ZY;GXj6)Qcl-pwIxcwuIW{z z!MSvW@5q)kv10V(SW}2A}naPd+b7cSES(iThh?)>Y?ll)P>AjP?1B{CaVR zv~UpGM~3_^GV>Z|F4ZhV2OYEUnF%x1JP$q^%33)e+0B&nsCcPXKjpxLtuzSn7%y6W zG-|pE!eQUa9`cPrsBhf%7Ye>}>sh<-x14J@GBCiDjq|@|jI3*&HXdiru5D^fQGMTe z9%dEhuB4$-i8b~R#TFgSf+m>UsawXRR7bkVJi4QB#0B;1486m7ic6$|B0EmIVolK* zvhdk{eYwj=b$pjqrZ=3mwfoOwWlN>aNZTvzBDuna2|eyL1+ahH@jPNsZ#WjSD5Va# zGK$<~V$ZAAg|vQg#E}mFY|Bebl{rMtatqdq_`ZMZ0@&}*h13ly)=2eJKF?NcYc$M4 zk1O8McO6nDj08wBfI7(0+t;1(zh16tL&5hKbSy5)%*U9w%xAU?qFG5VJz-?mhLN?% zB{ycpz7Rpj(vo<%xIIZGpndv^OXdfN+lSj?eo`oqnK31XQ?2pM z8~Ypz({m-!9tS_PmGQ`onT#uBzzpc=Z#p|JKwr{@T7~39=kQ9}-&34i8#RlQ57pQT zqzMp@6N3XgSG_tVATb?KxzkKOs#wlqXvmH9% zkcvYg&Rv=Up00qu+oxFqL|aqN)bA(P);8(|1RWe4?5al%$CRzssf9D#WhAmM8TMdm z%4$D@;3Ha3Ev{8}2Mw5}x@H?=3@pOwvJwLqh@4U>`0qG~Lq5mJK6AxWCvfr6nzDUr zbzX1IRnLTykB8DV@cx~DIJ}n@IsMbNvQ_KT)(Klke66tAw^fM7Bf|`)4OgZ4HKE9R zy>dx8*@!0aCl^H1>~3MXxXG~=RKFL6u;SAi_sOEq$JeB;WONa=l!-C*Sdx6jTJQRc zW-Vk1stXBp^?2uH?eLt$x}6}Cy%B@`L_`8@VeiDt_sFphlBmN-HcC=%^m6Q09qtzR zxY^jAGH4m1&tb&RvX`#7J%4|&qe5o?z-H0xtNt6s@wHup)nliDXd%n?Cw^4XR-w{% z%B!^BHd`#1GUPps>Qv`G+;meOQO(5dw&TytJz78A?PmTEtoGqM;8rs*ewbc-M0NKq zI+0#(oIiX=s|aw%dt-no3;29D^n1cTRIk)6H|iR<+1qh;GxeN5+)2lSk@PO6YOAw= z+`aX?w3X#tF&XkHh6z7F(&T{l-P|~M-LM5vg$00w>e0JH=OqOeDIzr$`_}NUdpEBJ zDfV1?yPpP0N??}$d??aqm}zQ{Bg3eR? z3rTsEwkG$%pQiHuE5h<+VR!xBphhRL^x zu>_D5L4rJrINp^!2YcKw2Qp zbheoR7#dy59dc_uAY}f9v4EtfeIsSeHso}lcc*k2M`|u2*2ra^%D(UGyBN(GLU!#T zk@zRF6RFFQzOP_+KV7hQv<)PhZtJAtZxs|LgQl$pjccq5>Oa^_5?Ca)zd&>JRL*Uz z3tW{hh~!SH?J8X+#^MNs@ot6YGXZ5Z5=}KJx4ND3k9>${DYx{%G?Ul)8D=gCr`{Zv zac?rWE(V#W(GW-&K=`M^1VgKXod{9byzW_)h+I8iq*cl+87LMt3S3UV#k@SN;G|%`eN1+FXOFHsskt_sDZ&DQ5Ega}yxlc(RQr|#l?S1^O z6({-075IqBLL&~IM7poUnonywZS;Ia7Uo}e>vqz*qrXi833}&bU-c3zZj)7&)Vt#` z87_w(7FsQD>8|$8ki<==o9!;wM1CgzCs3(`*cQ>6zwGuUqHUdK_TYOtakFTVMI-sz zg3h9J$y2c?3l}@w5X~h6_kk5%cK1Pw7bxM$bEC%7L0JwIdH5^UCsWx87kjHOuAU@5 zOvMSuiN*#d`{e;F%+C&@3Q|p9 z&;y1k)z@-S_31gpoJb8Sgu3HeH+wS0nxri^!o$puzAkLn@r^)Kj=fK{-CrYQ%-m-s zkon2jpFHNk&W^QY{1zu3B~x27!9+8m=WY=G!QRl+mRQ*Ujohi8Y(o3p>{539jjYne zjey1^*8?r{amN0Arkv1kly-;Q`FPBlC-!{3Z{GD6tCO79S>#&vZ_f8Rm`?XB92)uc zWlMm9aJ=8!J1iyZvTR?56)i|JynHmsQR5U*)?*X$gGh!1g^=_`6oD=(zNA#u%P=(R=O|c9Y6Qu z7QfmisoG~iHcBP$x*ogr1+NR&A{xO-bBa2LK`hLhvD!XbCwoh|QWILbq9h(>sWsMq zcY!LoTDJZnXO+3nKscPsT4>8`2=U)cI?wi5o5AODJfDuSoP&+E1OjZ+c5T!qV*qJ6 zLmJO5dRjtt7c(ny-gDB;t+tk6(`)yWO%@6=^*D-xyqr9~zs3FSbXs$!rxs(;$Rn%) z65x>*y=h=7`=%BVg^A=xE(TQW;tnxn{z22k#0(B&pM6tD@5YxcKwypYnmXc67-rVd z^)9@;yi}pd^-WQ@I`b`o`H3bjW)4oAyB_3K?WU1Z?eoRP!kYbW-JD{eLQh(PHJfBH zE$awfmCK8bUWQ;adf2K-fY^h2iO5{m^2y7YgKY$l=Gsr^2co-)=1-(LR3(dO^Z3Y( z#hu>{bTYKB-z(eB?gp2hMGoz_2w4A07@}-{X>%?Ba>;ez0p%nCwg_XAnW0 z>)~{JG^aS)bkU?>*aDSHwK zXnqiyXNMa8;z0h*k2w$o0=U#Kvp*?I!o4eQBH-O1SxLPbpcb3QZkhbfgyghylYocK z9xT|bA(TEzEP+S>Btmyi=DOW&z3r)+5S9nsp3`mA*3!;*9)1^(Cp=Zye|xj|@eifL`qax4X_YhO5#@uPH)!{i7-@+`?* z*?dW(+G#6)=jAsm@RfI)XbTP63|PyeBSO+;jdXX?lk&8-9}24ZI^YUlc!hnSb>&4) zj7f?DVKp0;1N|({vlw>!19baweEbg)Q`Zwv0D7O0xJiG3&hw{>BG0@`Z2ICj=;cLY zCht!HJ~?zw<~*uqQL0L&&axPj0qgSOB766BbxTrSL$Fs3wyoSbWs|in8O0?T3;-JM zN*xVOu?LMNN^yk)l|=bnWc2=7bn@eLST*L;Cp+@W0Dk+snhc(G zY5JUpZY>;8Lk^;fDPj`^6J@2w z{_hD=ydz>81+^uR)KOS@*ZA_=f@{7#U#oRDW+V$ziQC8ZD87XbEwl+$r>8oX@zc*^ zdG>y(9fj`Hy2Vh}x+RJ^i&7;Jy&`71sIygaiuKy!vSq>CW)pWKg0N#u-g7jKU$=NM z%tJsO%kHr|F{%c^^Bd5|vKX|Zrm@wLQf9uW=6q)`u5s&HWk-%inC{=SoTfUAL+COk4BfqCWu_WW@;nISxzuEm$dT7bzYs7sEfF88Z-l(A z7sMHz{HVaea)XOp%$zwOJYGrk%0FtJmbX_fr_6%ky+X<8?}%%OzQoD5s;)e!<7b5z z!$g24>Fa87kdcLJ)pmg0nb!yJ>4kB&D7bH_sCAe(P3RX5;`y3b4tlhA-+LR*%1G$$ zG$*K?EWPxg_DDx{j<}%w$jyW4yk!nAdiJ@tzNNM)S!iM|fwgs&`+!K$S0m(w9?~slA>7*)u+gmQC1+K4g8> zv?)P?R8Af1tERmN(NlTScM-IuT*l(we(X3eaq^RE-WtN2);9x6xCMW!_qW0ox z{g#-uhGZ7DI`%9bGmsnFsEUKdxOf}k3?)axGA;P>fgS+#*S**NLZxQ9UTL}`O`S10 zrS0=b4q~;2TAVdW)-pqVl^agBetfBVO^3|KNzTp00F{-o*3xPeWIMErkFTR2cJ$av zHeMtf-_k@$=w;WrEo~gw`J#hV&&sFlKN~ukowm5js5z^xL0w`&nNa=uly_cEH&Wwt z$8rcyiRc$PlM1euIMbv$F0n1hE2yG)X(t^DU{%!^_*Ji?GhM$t z&+v9R%;>EB#heU8b$V)vIy{0l?>bS&(>J7Tn#vy>xKd*|`FWnIJ?Bi($OIhLi2T8dehq8*VM49ilb^fnznC~Uo~1=(|j(8WNRO?R(wI6>>5FkL6>G6lV=Qlru`&J$+gno|z{oTv?`W<#&ct}| zfaIT+mV`TIeU{@L<~UT!k1`@lWR5l{&(<&%fNqMTAk9SH+g2~kTSwz5c6a|=7bP=c zlk~XuhF|JBe0uLu6{|SSgrEJ;F09B#kjeln%FM{o>>Izx(0e{qS%5@c%bE8K99PrIF2$p}@9S zJOzz{J-7t(=lzVxNI3rvWPq=Cju?@xJB5+fGd&qzV)wYi?8EL}g1-hZVrK(K)oCqw zP{Ls%Kxrz;Zim72vt|n(s~@2FVQW=0vG8IVFA5+ja1R{R_T6B-?TA|hVA@>Dz_|d{ zI~D*S_*ecy1UV_gKg-y;W!W+dyoD%V;lR}4GzgL(psZjZ@z*~4iF<2 zKS0-PRy)PVPR}vzox%+dou=AXH$ubW)G8_Gei^Qdet>-L3y)#LVe&WMRX(bJ^rQxx z2O~TSZqMj`Z%#=Os0GfZyxPgQ7|q##2+)`Sl0<7D;F&&ctRG-C*mIImOlMXnAKhAt zQTkIw{J)fXfTGYOPVG0^2-2}sWTh!ak;~H$O;vY|cBJ|_k$9js;H^!{n@hSIn+iC* z6UbkqGMf*v-8+ZsUtI+w5ch?lz*8y03SbiFO(wB0$=;y<5H{!pO z`TgT>?iamnSAJmV2x7d#pn~G^;s=No`^E#9HBfbDgYt0n3i0N&TI50+-p1(;v$<66 z++Ni+*vo6?HjkDTc>VO0^`UV@1LbffW7(xcp=iE)vR6vVCmX-YRI0B7c&&?QLmkxT zhx&FOKCVb81#O#q$D{YC8W3C0wJoYlH?!CoVhznjPOw%eQo$(K3T>;N&I}d~K0ez~TtMo^i^%jFX#U_U2iApoc&=ohb0KYLc)o zIi>%`FPYBASYNoGK6$twRb|D`1X)-NJm;F4-pGSY=GL3=K5pV@vQ|!Cce^R(7RwjZMX+^;F<$tO;Bj{8cKMo8F9C` zMK-|7#^wr2@^Hd44tBTsHYEjn?4XxqRHiAN^L~Q4Ccdd=%9b|9u3~Xkc$+<+fts0J&;whu$_X@hBA8BB8wA99Cco%P)!F%mJrph)WI%)fYeF9 zDBEc1&%lufnVfy(uBT;EnD`Gi(W^IQFfn&N5%WEM>+s4`xPUo*=GbD!&a`2{@iSYv zQMoozg;Z5*RpYoVFvYc84^%$Ls=>yVi3>;>;Of@1VZ;2J97bV9OI@tb;tKS?SAP#= zI?J-7=1Dw}WO$g%@9`v{){DG=_J~WKT+Yj%dsKEm zKsf}h#T7}b*sGnR7bp5FBa;E=GM}v1V|x~C%@j{wop=~T-OTdBOH#(YHH-9@7P>uh zpqknmZw#C2ZC>HvKvS19`_|p?r)Dw+vC2#gR=2Isdeb#wsOGWSj;pV}1Pl}$uB8i! zd(Z9Ox=1$N`kGl;6>neEj_YXZ&&`WcxDDbB?4(^iURGvu8G3dtN}f<)=D1FP@!$*J zV;5dDh)2;lm)9T*o(DnV3C5>=V&O4!rnz-`nn?yf4*zhM?R1DmYiHr*Y?uw!NzeRu zr`*qB2AJdYyk80`cu`=Sz_hG7>WJ3EQz6_zl?fQt_xzZEu6<#(|kWd-tkYiLZzp>RB!-CzJOIE!&d-%3ajQpP+pa1HetBr2mD0 zrSvNl^a~vHul7+T3 zO}6{Rava0_>Q8Kru@!?xQR zVB*wN^_#F~KaKtR`XLCps2ut0q__OC5KG5-GDVT)K5C76UE*{EiUPHl%$hGo-Jl=n za5~kOr3qG_KDc$QappSX{BcsaeGaH(u>E%KWS?%jXWKKs#k)n3I;n7(A=VJIscmB= zpDZB0U_Z8ygDzR}&{q*wt}Oex_46@W6c?%P^FbG$#B&jTc7iQyGCHFvH+y?4v@Zmn zX-kncHw!Q2CkY6~)`QmeNwnrVNe`4a7y^lrQ*DR6+={kO+LmV*Gr&6$Edr~E7~ya( zUD?OgkmPNf{dks~1hv73TCdgyL2uLLQAiF6P8RmM=X4~dzox(a#7n14ywH@-Hf+@w z6ntmY&V zsU(YbYSnBDsTm#YW1@4Hx$lvg0Tvu-SwQ!N_lvf+hPuhX<~bcH+UAMrQGs9)I&sBt zEY@$e(+S&>=~(u*+BhpWu4I+epDl zQwzIVCV`=POFL=_(^W>sr*ef6>7NYko#dj_CN`4{LlJY*6qGd#&j)10Q|*vN+?Mj( zry@U;e%tna*whM{eo_mmtgnr+c}}ourAeYB%GwuhuVD1Vk$2Cdt;pT-LVC1@56)y& z{N|KqI^%J@-}5m^dugoinJB6b>F+@2`7?IAUOv}o6|i}jhD#dzijCHiA|&39$LCY- z&KIBNv`-@3tWKdeh`KzBHzmcEuCC%A8^clpqZrUp;9U-}d>8mz2+X66gS52|)&(`` zLX0mod(t>V#H7!I9-LI}LSEAMzM0;v$RBh$HtL)yGd+RMebY4s(|!EV|DwUxFDBKO zb1y}0_Xh}ttGZ48l5*2I)+$+r|D&h#Tw1DIm7h_q)q7lCA=ZZe(p#!-1xre(oqNoz zXs*6c&d~EtD^yjR_2@gd2dQVfdVtMEU+7BStSGQ5T1DmYY@5qY=#>wZ%F|u$L3o5$ z+4P_@v!anZ$WL>U8(NW@N|jbLe>~QQQiqbdSUmHS$niE`F8yTvkX5u7^7N;u2&uhu1U$n}rwcXBaRnY^tWU~zkPUIt4<$;isd>UBS- z=9Q^!5Pd|phIIOF^rGam&Px~DxVeG2mroC*senxKBu)qZ+6;m3lX^QW%j?<<9}7$j z7qWLU6GpL83rma~+KsK_J6QJjP|k-LN4>H0MRVQNNWJ9i(37QURNFon#=G&+t}EOL zU-$R-^Hi=4Xc#w5=tYQ5FTwi3(S@f<8sI*DD58Po1pj%iy!dbM{okU4t-}q+iZ3X7E`-+TM1fR!yJ$UP0(b1?MZu9t^>S;8z z!934DpmD2k9p{}t^mF-MYcuQRr>XRTAD}qNXYAo63h}%Lz&~F(hF)Y`Dz*Z_TgJXR zFjs}-4^R(a1p-M|Dy|Sy;KMU8+_tsi#tv=aws#n8yz0f$d}PVE2wsu6v_gO(`Zu?f zKR~282t2!>wyhggpzL7`h!7h^YL9%D<|)7NrVkzplKcb5h}v(abh|)1m!qw^8M&L? zvh`nD{7*;xc}g9(aUb?tPdf@L0O$5k=N$E4E(!tdxB%P#dI`se=-|HNEby!ZK$ewY z@=?_T7kC3*pH!^11YO)QwbG0=?;IpXjrS+M;x|_J*rTEW~sO5MZkd1DmQ z+JQyE@8jiiKdSg@gGbEZiEz3TD8fr*y=_I0Z3kyb1G=NeuBF$zDN5H_zS^)QB!RxI z%9(*>p+#Lam_K*r_!ShZ9<%O>oH@Uq>IL*1Q`=TGLI#270eDP887KNjnfK@l;k7_e zIda8vsrdUj_#yv?E1*muR90Wj*2C^_OMmt+=MMb-I;iO;0fiSo3(3k}7dpdGuABx* zwgl8IkWcR>KO#-$kh?(w9?ym!AZnm+!TgUa7V~ON;}% z*JAdHK|>Db;b+RLn~W2A#IvaXSPBaa+6Ab>%5v`XmUVgwPA0m z6#gQ8hAi<{#Wnxl_Ln71cmA9HK|c_gTk|^QcGM8Y61V7S^C^Y~8i=fbe+1-4fD9pTjWi-`xm?N1W zq>Z@d+@V8i{kdiAxBd7-L3Y1x^7y%*T=u`4xaRzKU;O*IxcUAMyd%8!e+PH`g+=&3 z#vcEOL;i0p;{c8)B`$(;Ag?e7fIU8du{V@P|E1vWzh~qB!R;t+zXbv1zmM5JgMcw$ zy#61^m6o^_LN)nw_ckSoHC8|58Vb1<(o&qI$T;xPmDFlwSGUzMiEIIR9Rx?JKrdPpS1k| zb+`bT9~{a5v?}NoTw4GiJmfSlJ=`CZzuEx*00rzuA)ZG4X)V(I0^3IZDsj<#OmhjE zkZ}q`E}1BvpnJ4O_>|D6XFt_A6;RGpD6PZBe^U_s`#&oi#n8x(rG~ov zL#4Qqzj>g=`@coKKfSC6B>#X-`Y-I};b4SB*piiiH+acOEy7F`DCHBsxb=VnRZUJR zgU%)*p~7uBz=Hdo-`vzcD}^@zMq@pq&C6Vy?H4BH-{8D(@(RiqoF;31JKp z>d#5CT36>+a@ec5`T>eD4Bg}sA^gPY;AUXPA;lcnT=~_HD23|rN@MDAfVf`6F*U(Z z^`3fFU-XCkNZt-sdLV)x3WqJ5<;m9sgLh`&;fPAP^ETKmm1$@%1q~!&+n}nhvH1#D z(wz#`Nc|>v{oO=5QlT^Wp^l~2L6#9yc%`KEisC>dFM{RMiPu}_f)P^a^{DS++PJ)% z-OL$JVJS4tR=~%AvkTIYzOs5M`H|3EXN@|6sF3PdJhhH3yVLP;vfWdGYNC_0>$hZE zg*^_Td}~YBv$hbHdxPFiLmNt|1;@Ie>*i}4N=g&v-IwPmFCWj8KgmWSd(Ny&=? z=b8jYmB$7z>Z;!Fucjf0KX6n5x?aXe$x(_Ue-ytNt z4zEw^fGY9L5^loJmTGLebCu?KIz?1y-+fM10gir5_6?$WA4neX6%9J$TFO1J0gojE z$#2C zN%k1y%XS&qI8A|cNl^RB@E-Qzy&fLaUOkRfbs1HDReESTlYV`U(jy!3MQ9*!1_{7N zkLnn;B8XGkMdord7ClKd0Ts2?$iL&U8>~3ogpaP*m7WW4{am69KP_`t4e@kzAEHg2 zz{`w8R}CUE2t7ffDuk7h&=B6^9dxGamt#=;1~jas@O!ANsPjGpUyu|pf^?V2ghuM- z`8>e-1eG+3L^X3&>_{8r?&zC0*lQY{Q0w@ydzjp5)FZ?pI_0-r4DT?cs~gC#*oh1c zT|XNM(Q++X)6RI%X=5KJru*va-D%^SPIAeY?{rPfls;~A=9jsEV{#e9+&0{*>%P)u zhxUE`+v86c1>0!U2a(Ud3lZ|JOHZ;KhIxEen>@XydQ!K1RlO|V6c91?&qA|9yW5U~ zg7dASzhBfrS+*Fc{0-cwE5Do+zvzc?iakoH!N0wu9FD)f7g0=?otgRT0kg_>j?DRK zrVCulkF}qjYxHQGw-*pKaN##SvS6&b#SdJ;#-F?F6z302#cjt`e$>m%`xa?AG6zL% zU-h+P0qwmK&Ns9qF-l>L07p=T;MZCV6_}7#r+AfBi`oIB2Hu)?M0keij!z(GYFc!P zv~D6@xzp=o08fIIY*bG`+;i)V0wpEGE6+&%`p@ylrX~ycZ70IyN5l-2@bQ-?&hFEd z+Sql^VFznGt1jxap~4Kga_cRhLRnkF%ep6f(xH2Wr4+6TTvjq8rP#6QhgBoGF_why zUy!0bYy(BNJCWW@H=C^d0Aas*I?W|zv(e+7iBV6Hr-IAS5~v3@8@OuH*00a7l26P? z(r!89{$8s4sD}hCWZnGC<~8F7JmcOV$=>p5P|TsWDn|joU4rGv*TP{A^{__3UjE*V z{}bQg=l|R(1>n3}>{}=BW(|DOjg}BlvY6pPSjZ$BQYLfgULn{TO4WLx6X3Ck}3|n4jzhg&*KXQpoL>-&E{o zy<>ULtT!xp8)=c%lDuM=N)Y-K?k}%oyJpn2CfjbwDl(gfTOu{%zqoR>1iHA5#qNjh}IN9P=;&A zWg~;UZC!sH5X;+cJ44os)I?m#Pps{Zn$LzkLvEWv^{UMquDY67!eqh<{l4Gu6d z@Dsh1)fO9XffcWP*^mWHvq7}W)T5l!r_Cd)H1FqL2@@T=rq?IT@fv;fpY$W44i@Cg(by?Yiz83N58*vEnW*THK)& zhf>_FElvo*orY4ZxDq{IrxHCQ)scZTb zMp7F|?5@EDsFFFZhpx7gj!uJ#I-znFr<@gc?K~+zdS7P>k7@NG)M&XYlmk=2sW+UL zqH@QFVTBEWX+xTf=HfeaC@ zo+14sQJDAzYEdqkb|ULo6iKbM%9M1`93do$dUBA78GMZh+w^5c^c<-Mno=L@ev*jG zd1tME?VDL%bm%87?p~R;1{%p&?o_g#SQ4s<>3q+F!?lPYqi#!Z?&=I?iwmSM9vrL3cbOQ?H6dg4ql?r2#>sdDfyOlM^;4TUY1pGSb*#v!8nqn7Qmg?{; zsbJuvdG$2a`}7GP-4~3n$Ad8+%Dfp=TUWKYqdP)ofma#?q-y$@HxMFTCTN!GJ+D8{ z`l7C-XszuF-EQ4x<9(*u8NWW|3N>r_ND0a?55MxrWt_X$KgIQ==FYCygZD7PeG(r3 z!gLCdzCllQx!O|=?;Tq8syINjx&$S}`W9Y$;84$P6}_$7k|HU8ceEUF1~ONOmR}v ztiM&GbHIi&Jx#ZUn$~U6h}206Tm^x0=BqvJ&*mJ+N)SFQ+Q^S)TLyxrj6A-8mOAq< zYYl>QM5E-W8TU4G$f`jf8u`!9W|VfwI1qRL_}T(+K+7(G-@YaeNV9a8)mbZ_?)s<$WmWsB`l5X?mOygY460`i>_GBhg&~>5kf#Ca?9NtU_Zq+s4&8jLI%X zCG*D;M2c7OIeSTlfuhcfiX5Cv8|ys&-x<#5Pp!o-ACz<*`*iWzOxW@IRgxI^<_9Rw z49Bbx)jndRic%se^INT;lsh^oU`Z&PhbuPuj)T8EsNq^zjXrk9WMyek`_v?nKMhYT z5`V$5!_Y-3y7jL2tps1}weHJ;zzjB&jw7;ZuOxr>!+XsP!Kn?1Du=r$X7?eU=O+j8 zlJy#(=Wu0G7{M=UeF8<{vr(XkB)_Ll9h$>Ocy;3ZMLggH+3w>mwIa~%nbkE-=<5ib zBqRx&IMC13&!d#?AHoy0rmb-M4Irxxe|SVOMpDkB1mp)2F+7A91>{k;ww6IkSEiKh zMyCkto6S!7F0P6wQp-B;h4xNF!9-UxZ&563pq~%!$VlBJC`v_6mztL^k?QG09i?8K zDqs(%+YlREyVW+*+%B${VQf1AY_D0YcRn>T!pb{B0umx+{c!h#4s+*TE)n z#lX(!*0h(s<5$zz=vY1SVkIZ-Z#UbGzFHJ;2X&=wLKX6^RC=4NBXSz!RiZYzYk12l zI!iNM0$%n-;gT*1PFCL83I&5!ntl4wc$J^}7IX%9EoQE`?iteta6(qGuJRx`V=QzH z)dnOrUA)B~AZM0FR|@EM-eaM@YEnii!y46RtUi!mU-#Z^%fPjxI|kGJOqWZDj|K8` zuzZb2q~yx(IKaSmk~^X7UBcPH89hCMMkQT1f&0r{-X7^YKD|3m#65n`L<@y|T#s{j z!~6oB9{cV~MX67fzP{2&_rYae;8oQ}r#j7X@^NcM?7m;fGL;Ed3Bp6@Kx20uvOQ9g3A6KV#UC0?);ayh2jDV4zoBwBqkOUkcK zRerXpS?4UtxXuXq2r5xjB{rwo3~)SN_txS!3-x9V6<6YlEV$1#FxLf3y?ZKbY>g=* z;m1DO#s-(nIo49DK?O<~%i&1(=`1qhAnO)^H>B~a_z#ztZA5)Zq3-n{Dv!s>@tZ%G zpt=&*3eolgyGTTaY z9}Oy`u&4^4JY#^{$JL_&aX84%gUiJPI0`iQL`De@fe9z1gN0sL;yT|F#Bc6BcbL{a~Nx2XQPr@61 zlSw0PIKz)E_5s?kb-k3NX>BJSuyx*x8eKM;^OZndb zi-^zHdeK*$_z@p@>_pG9TkGQay44tOW25_tu5==add;k_NL+i>&YE9MzZeq%H$fhP z@7yar83xU;@2FsIp}q4%#TJd4-u}daNTYU&!yv5p^hV9T;alyi=3l1ti{vFFSy9-7 z09Q%+tGv}Qyk&v(lQ9n`^6pqT9hl>WP?7v%#N?Z5*DRJb?2MA$w)UKHto z`E^5)6<94sj8n3;lR8moq%01*u=O<_(wk3mjmV2GVJhWJyRyGHhi~PZdHx0{PPQ1M zB7~_2jrVb^;cc3c&EMbtI-~iTNplsH>zSn9Qa2f~%Yoo+Ii*t^L=TW2bvl30GSln* zZu+B0Pm$Pn1?TrlPpGKVB;QHqF|=~)97!fGQNlQCDJemcn``40)B2MRs~u>ed;L`D zsT*Z7*vbh)?5A&ETyy=}E7EOMt_iElMJ>)T(%d4Xg31q4$xvTiD_U@gWcFhkYL3%{ zf2CYowv0ZsMubyiTlmc5OWwm2X*T%@M{k;|DxRaFu*#1VaxBqn5Pa1qN<8Ln6pjJ?xw@J2IEcYl|D#_CZQy)T_wMZ&!Vz7BQ&pT%bGcrFLOJkkima8&pbtpehH2JMEUj^?d4!5N zf6#NiE#k8}!;+QxH&9N=hMqb0-Q_fvOqTLhWrFWt<7aYJ`geRqj`_OUSXxNkYg9q5 z%g&Vfk1cKp6j|p*%9c2fGqYCafnMjr4h2Rb&jS`oLQ#6lZ&eakllkzScw6u33<~%X ze}TywrOMM_T|~oq(VbNTupP_OdsDiuP|_U#wfUpc%qKyHU#+oEMt3SlyaKBQN_z8| zt)G__Ew8)6p*>@`wnA9wX=NqK!EVqO73t__-``W_>XuNz}DnxtnS9;h-FH%@%vT@$ny{Gfp=!GbE zYQH?q(bSHAOS*XI0gkn+^VBXH1F9WO9!q>|0e54eYRM>Xe(hoF20_KmLs4PWMPRzVOOQ z!bq+rsu!rFW7cny^EKV#_H&f?jNeMD$@%gl+tk25*YBMek-NLf)pv?4)ksd!qAs8N zKFUlwiP2*%UyjJUD_{X88MDRvGhRWqQe_?IjTg;zV%#dm2_$ONHtejF?eW#sYZ*44 z9-Wu)9JJKOUn13xMOGCy<-C$U-AUw_?6eF0n2fpwBnJPh`h%RpiCH z0$oj~mI}Al3LkFR7|DpZ_6ueo_Px48V7nUZ%miER=saGj*wcAwLZDH-f;sO&6x#l0 z=t=QG%d>2=J+0l;s0@+~Sci7nr&etM08Nd$>AZ^X==IpjZ$QK|Q;GnO#9qIly69Z6 zZr`OpLUOYevsaRAsznyX826QN$_tgj!eH)8OE(wOckQ^_djczvZ@S;BO}MU`yWIN; zPmt66np88*HDcSiiDVo9btiS~BOBg1aN%Vc#~Mdw6!_sv-2I_c#5VIYzd z+BgH^bQ7*pLMecP^#}9(XPJ)Vojup7tXjJX1|P3Kjnzvr=}c@HgsZee8pa-iZ8i52 z7H#L%V200gTU;jpRpa5m*sOSAl5U1-P8hEvZRPENY33pd3Udq=5A+x@i~CmCXsZ`c z7NG9G@|?B1QK26Cw(ua>MN@Bf{iTPRn?O7VE>X?>YCP$k)BSFV<%$?Pd!$HkQHkoK z#0g4vTZ@Rk2Tk7-R?%OgH7qERk)g0yRsWY=`bBLaKcX)0KRGx zk|>$`KT@i6UhaLcQvd`B+U5ii8i5{1SzXs0HobYVMET`6U`mFmw2Bp+pfqsD=4Bc6*wkQM9}%e{ z*4SB0t;Cw0jj5sis5w6k-B&<`(Wc_t0(Rg@m$$f-noEUuzH@?v z(mMvN$6Jo1ji#n+DpI@3oDDW*=zw1`x|{lV<|9o8i|af`q7AWdhZ2djSrJ16cc3XD ztir9V!pO9yvED~NsP+3o@1WPNo`gRcYTZr`71q>6sYzU<1mf;$UoscxU=>z9r0qje zx(xXG3*Qddq1THZK#N0CyxVFGH z5}0dy09H;9anelncRmICV3~NXH2^vj4l-c}rgifhz!qWKAM(CSCMHr?(0fOQj(-iGWfP+`mA2} z9Um+pdxfTfvBHO$gr`qz1l6~RZ&quM5og#4h)8wPRl6HwtU22HBJPL4HUamzOU^w{+m=tV|iReNVbSk{oL59uM!z*OunDZUEiumz_TUkRI1g zn_Id+^g+G@r~}B*{ZS+KBwF^wEHG8DsPHP!FiB(5VV^PfWwbcXC#3I@;%2K|7<(B> zsAp>1co~^`ZgE$FWX1i~*DEsx*gjIo?s9Tx#>t@Hdd~6aW#o7Hm)-9+<4wlTMcTw{ zFaPj3Sp;*=u%naBJaI|vWuMxv3`$l~%S!r%n$32+^b~FoUPc+R1ZJ1Oc)L8^5hoJm zrNw#7Uu66-U5uqVGPr&NRDKFPJ{O}*6Y|L(gc8(R29Nh+JUR1bPbCX^!j}gQTmICt zT{0DgedbL?u1=OTW_mjp!J};5T*AiPrf}& z3&3amY-+Y@hPfAWwL7WO_N_>rw{h%h%b-!X~Ln7D4sPY_xSLtkm;*GC@A6?+OfE zvKFUeec}jSy@RZdv0v5X?v9l2G>v|;ba9c2<*aSD3d*;{Ai#o4PzSjpF^_(wnsxd3 z30eYu(n6^>7am)9@xk2b2&A6u*_3ZZq<=fk0X5xU+*Sgq#LYw94y*2ju4!0TU-+6F zUHB}%^n8oZG+2LV8T!&V3T=rvpskOrgp(gkG;o~Qr9FMN^Znqv3I{=T0D-x%>b>v^ zQD)sfv7XlO{MVxX#{BZ7_6d+efQIq$|t-3E2cLRt| zDMW;E&OhG0b1_XR-TAqDBR8Gpf-K!+i45J3ovs)+)^Xx3AyaUWb(_r1(R4uqKVn8~ zt0K&TYZh$FvPUXx$LM2mzt^}-(to9H{L#+{-I}{HH#@d!t;7ttrhU{Zv zY8h_$=$--GL<`%3hJJ?^7BjoLD@Ki>T#CA!5%1X3XW9k|3TIU>pu5WISEYx$5~2oCtbzT!;Dt(DhSsA_I1jkRz^ zn=n7Z;wil8HvrEwya$eKCo;YAss+)LM6`YM?X&mI+XNsa!>?w*a-y?S1|o0&cIeti zmGQMKFdy6NL-Rp530kdq#71EbO@{llvX&5Pi1Zy)UsgxeZMV^-X?%XwoF*Hp3ZZZa z=0(GkrgGU&9nY;U`{E{%G4mttyt+=54G$#sW#PmG*ptbAO!`?eoYlW_0{Ha=Zu@lD z4$^}53bT5#$855NzQl$W+yb)&%x& zZ+&AP7-AFn**&=!(;$M+M}unPjY6#(6};P-{L8f%$+lpsrVVTQ&LhUMNY959#t zKEJI%E0^_B=4;d?b%bMSp-#+v*oEPX`;Tv3oWq<5Ts9P+RAWT=<1a%IY3huUp#tJ`zutx0rwt z_*fkm;h{&?pXBvp1h>Gt4?XEzOmpPk(mv%7zeZHaXX(r~!ORV*;>2B0Osv4MHH*Y1 z;~U~8nk=dSrS%3~Oh$pG-q(D3VTK;72^ zF|sQ2&U6UdD!h1+<{n%hxaj$f~DfXkaedq&N1Ms(g`9D<01mHX|WEYozF{2TtBrnFK zLnWHOkk*p9kCH$bhbaE3f%u>2eEfgv%=ynug5}k>b(&swR6@FT@Dd#P%bIQ8!$?VF zn`F`V$K`W$YGB{U9;&@vpxCyn%qfyCF$%4e!7Zl|Ay`E?jeosh{DZ0P&zn7OzE)#h zKz%ey0i1V~RIy^D??4i6m3nM6Y`J=mR{0dzX?0S1wm{9ky^uZ`YoIs2#Ap(d_^dmc zQ6ybxcuhJVrQZ@KvT)M4JM0s$r2@v8kUf>5ipEA=R_W(X5uayQVz0(wcyC>0$6K_h z?>d16Xom6tzK^To-vK*`17t{!wW4FD3FD3e6q&3h9zvxDdB%6gotbU-Z)DedKo~*P9T4}w@iG9BMkJp8l6sL z-_f;Izl)Q?NTBT$>0NS^#;6_;qLrN}_!iZx$~&^p2pVvh-Zj@6qj&Q6lFBd)SfVs? z4VZqu8q8D282P$1`W5Db=snb=kd6t3P{#RFTJ)##4`s?KHH^x+z%~jGemwvtQof>! z$z#3NQa{qS{#i7 z)P>jIhi+j+O_gtJ7pBG4Wwcq8uvS;e>9)e`YiAQxdK;&Q0j|IhO@7% z+Zu!6bdDCOufn8=UJ+@i!%gAK^Iv{Byl)Il$D)rBjX$T-h50CmB3WTwc`Mb zNMq7h-WG1;IR_Pp#;7GFguw(2xHnDo>an zjhTd?2`U7#V+~zk!?cl!Ty=?@_eMzU8lwJ7Q4_SDCp-laIJhQ!*N5FYCP%*OSNg|0 z-A8Gk9hhZ!i(P0|8(uJ>M>X_|-)evTf205DANGK$H1BB>o49)(C+)a#j*gl3u&uXi zJ%)Go$2#rc_XBZ_Do@?bK?nu4_|9d1oC$Icir5!V^`FpJd)ku)~bRg!*-1n7I!eRVT(|N8YvcdQfk@so1c7R zdS_k1xftvQ(~~NoT%UGBXDRaXGq(!htdS!%wRZqDGiv>SOAJVUO+wP8-Lk5m>~Bnh zL3s-Ep608@E5h`H@m=qTVDHYe@q)v)T>UgxGNj)?Q@=VshBIeA4BiO0rYnSX9=#lX zcGXB{l~w{gQ7Sm_A1fS$egQdGhMxAtP(IH7-b|qFFXX6(5usIIPcj-8hFI>_6TA`Z z^4#aR+?=2+0d=H2v%0Hg!#otG*Rx?|Px$3=rjmTXq2E(%yi6QZRtHlduFjOyef0%e zz2WjXGf?AQBg)33N&at$4@tT_FJ;m+n(JYCu#Y1&sgWFss1=?3Pr>sryw`{r?->_U ztz(C!>lW#pMSXo#{}HMv>%@l>{2J{CLb!4P$G94c73KM3V6!FkzpAsK7u;L*i*09l z$`B-VM4di;8F04MJ`>-gvFMixzYxSKh(ID@+Oi>7Qm$^543|d7xQCIPzVb^{4N4VX zpZiO5P5*d5&eyB=`RBe(yui#Y7z5`ZA--dyq$&F1DBvkeQuA4nG&_wB} zYZ;l3{-KvImU?38hyy;r9?Vnb14xAaOuMwQJ(Sf6{Y z(22>vnbeA!@}r0KvcRc|3JO`@-oNKPe{+bmW@HT$=;z0OitfU@XnSfD%G?ydoFE%$ z!CR?Ugcvi|b5r3|KoVsT!X-?4CJh!Gnmx@qL^NL)qkT-lj5ge6Jo*?yk}*}Pzed>^ zDVma=@`S2{)!ij)tj*3(t1DHv&WZRYp*m4tJKurX^*O#Vh;gz)AP?DWbcz=VF-lKp z{~}P9yk8sZM`$uos%im`j%&#WHq%QUAkw`xO|QZYC+Vj+EMTN-K9uv?M(xbR-<9Qc zk|>=q$saV;AJvE5h*TsA4h-5w!DOc_v?0x|H~?fRD!{e$6g(7EV!eQ5iaJP z$m%5SHiE5i?*-|2c7C0ly3}3_w_BnQfN!%I*s3@^`K7hdkIK@`T%dW8(Ij|y@5Oz^$|)4;U_E)(aP~Z2E)%3Z zXDZ8}@OXuK@tY4-gjLA`P?EK7(rqZdg6Xqt(^G#CcjxoId zO=yWKJ~QLSJs*l}L3y1?_N&gJ*Cf7_C8oQE{L66X@=MYg=Xw6YPrf6O{ zB}%n3_h8_1%@+@^QgSCORLG1lX8cT8jZ?X2@U1#*UIE$y{)QUyWFJVEWYZjthIwDc zZw}lx0L)89T&0d8cY;TOwjWY$w&pgyE;R?cUkpYLcl+ZDV-oL0zWd-zj`0nXt+tXAW3HGrN3nisrWzey(KISi zCWdM>zTzru6F#OVI8y^3qf~LC47Us-D0ycNU$T-0_|A>00VYlAu$v*+yB_eAw0&r` zGAPi7G2*)zAP{!}Px8auUXSZVCiSGfL*T`?!61_i##`B7CaY29UZW40YOh37!?>T= z{50<3cdw*alHqt_9h1-Dk`ZcT7v&9j$UnpTF`x#zq;=dvsG4u+<)LM?hMc8+PCsg? zjz3&fq;WXI7&e%QD=n_J##%FF1@!?wrX6`IKf)g9OFFpUhe`ix)RUnZS4ORFiUU4< zBgIQf7eiKpK^5?rF5vMlt{iEkInjb>ch5nNzLj;tTm~@#8dH2a(U_Ljg(0$@9R-%y z%$=!gRZ6#QGt1%%!CiPsVv=iZg%RKv0!ViGrpMnzvT5SZ9=v}`oCr-A!~)D2zFnentW?*g~I5KR5i&e-UG3YzX^@8xW7*c zB|~RLhsByez6emJQHw6x8+^z-*=5&BnPH&bdU)g=BZ|IE?X4TM5ma~edEev(ci|0BGr-#ti-Kmgsb*K&w87qD!Of^G*o61u1bb$_)Ir}hyO zbPK`WA)WcQD1)NDGuhHV@_HgWk}*$EKZWVE0+6CNz*-ftngUt+h#6r6jjHM%2H)6r zymJYPOwimwcxSn?~+&dyFAx$W_wk*7niy7)X(GaIU?M3=R-yCN=c((7;0A_ZDp$R7J zKT`t#Gi>t@>P6|nI5_K6C4DHjyX#MLlnBx-XgAKwsabzqG@+7w_InG8cU5f)K!hiL zdjLjq0NSYVh%3s=ZGrdUJrP^KG<>+(U*Zcn`Hh9HTU3&BYAj4ZrQx7b){3kp8Aqcx zFu<`O88w}EnSF=nQiP&KbA|1!?nR1#nUsnM6PqGH?+$vxacH`4F3OX|39A)6!o!Vh zSqXUkg1e=uoMktr!Vbi~EB3RdyHPhaJ;xn&-s%$a*mL8&C?HxKuI|NgFQ9*#=P)~d z$o!d5#w!=rqvgqG=X~p{PXl{ z_wR#0Ta$Hv7CormZdu0b0XOE!k%b56d8cyK3BH{vz59)$e7&gTxiB{FI-~oVUzxrT z+mpLxR?p=c;YDaAU$5OCg?r-e;z53$(i$){!Bp{cz;;DOepEIUmG=s)_Fot81~c9l zS>~lOMQTjJ2Nt{>PDTS^ z-(4~MS6-#ko)Wlf>4I&wO49+HKT-c8w$AvQR{Fawb61JdssEF2Q8iIJ_*tU0K0=P; zU<>WluF|jPXfT}@ZjqAYu2=94C0KGr&MN~eG3+CGdBGA9ajkPsXk#&-P=@UH)>U2YcZE6<4faX`qS61ILez~q=BcH%H*Ay-x|9Hn~7Q1h8o`LI+QMH zK8kFgT%@D#&8g1nk-%3TIV(5Z*Cq^D7_qjRiop*%7RoX*->Z8)F|Gob1D+HBx%bNK z)jaN96^AG69q@Zb+#&luT@-VMitk_G&FJ#I$3M6PnagA zb04_gS~fHU31$?Sv&~UfHw1mabXdE!dHNgBsd^6ud%1!6I=_wK_~3XvDF{1QDELG< z#->{^#ou`TD5%2CXP;+n0ju^T>d2`J>uE=?uyFs@bds!8?ecl`P-U}QvC`^2quenj zJYFlzCq*DAjGMoQoJ_~08U1ds=tb}Jwe(KG>iugZEwNo24eZcJ6O&oE| zx7k&IrnF1|v7_I23mUA+wTWLK`vWj1>$ljAfSVV@!_))3JPQRzUaWK_rk?2N&(8dw z;L;zko*r<6xsoZvhjI&*oI0bwvK6EIlf2sXj#HVuLAF;VH$lv1&euQeLMcYJx`kbh za1GA(hzjb43(3sAJife+ESU1&8%V{qyBq@$ z{nqACPiN;j-6z77-ZQ?gJ}zt072x=NhM#cz{<&`rz6kPBg{oD9<)h#oR9JI#B<*P9 zt#IqD!~Re^Bx}oD%qeogbyRFCm9e1e9*C6jUcT8uTH!|s>?>nOYTQXdN>v0?z-{^* z6`YYRIL{!5nf9a$kFU)^9SUz^-VBuhy${37e^t2YP5dexXKee5l4bNWS@#W2umi-X zK2Ju_02OqPm@~^H3*Q!%7|!nwKHRUUjV*T}Xhyflu@puZ(?|al<24!?9m2_fuSt1j zkx~%c!9gtcpin>rpbt?p6~=&XI3z(@aFh!E&n3L4RYTy0M`)2s`Z|* zIBkokM+g;I7O;+kpM0yQvg-Ht&@fG>JJd9_wCXu z86PMAQ2X1AxJ-H1N;2bA=2RU>()O^DF@Rw`w^!!5B^#c8RPuE+=7VO9oOxXLL)~TW zEDyWH%0|l9IUgRAjec}lo+!0ldirgWQtqXy^YU!{gyH<5rPx$wfEo6{HRcnY3pgEo5 z$3K0Hd@H=-F(#G3aAh@u7c5(YO4E*YpZD$BqR~q_JszV;-i(_!;~vtG;+C4|!}dU! zd>oSf9=?ywQcz^NAXq*^h&-8IdPQ{vFd1O7AdpOe3WXlf%osN(X=hH%+$wSKuL5mq zlzSe8JgvmrvR=ymM(@5w_NZR3qsefOVmj|js;b>n++oY$AAW|F;+1-Y1&V< z+v4ozIr9rkvh_rqJ*{i~g>GMYK`Ckpk^iWxs&^_3_!iZBN$w8%r{|2b}_}Ph7$Y?Yr8Ab88WEv28&83r| zJ*dJYL#M(Moo=hip5J>p56)bh*c{bBQGjdEI5;Dy93Cpt#mGE(EFr1|*|>)oeL=Yn zT4+n{p7m)$+i&fU;G?ie8q-M=<`B7tzm8@ez#`6T-w1A+#gc*XMKaH;c!2THwsO#6`w>7+N2Bi*rU+}i zHu&ykl3{sjLU0ize^HezZ1q=!#oN4t1B0i%3MeOXN3ZvLiQXs&F$ zJiU!wgtO?v7#4bF);aTYKt0iX=h4e&x<~T^n=cvdjp{Q~29}(a&dNhuFfDB@3%iQ! zM1#J-!r@tj%1WL8*OGRMwE~X?IZ`>Pg*jlD=T(tZvQ4NEMB+r3)<1_u6Q& z$)Ok7mc|jz`e*Ad>9=EKz-KPNBtyU65~?N;Eb&6rtumas`o(5z;KF(8`M1vV=zKY0lI+&OB|)r;+3I2?K1r9x=psU927^LV@wOuMf7= zrUfK;#kNklDk^ArsH!4JDPvQ}A|7ZYWlMM!{RUv3{RVtqNcevJvHeJl%)7U-xT^}G zGsWE^RHTISXwY+?F%C1f?PQEG&t5E49ZNcDJyTTbnGAE^=Q@k9O(We~rlR3cdi#e= z(J6`@+n!_M?@rZsmxxX53??r1VNqF*{Z^9+xhKY4lEz<80b=s68xD7Y4r@#7Wd@+4 zS3d`Xh0JsqF+S?>>U~xjE^by5TK5V!uzR{Ag_l!5#Tw^Ts97^cC6_H@b^Vw`n~KXl z5qFfYxxfS_E>mFx*NZG4En!}qjWVSpZtamEV(zw>)oQu?f`y&42vRKo|9jvB*0__b7Fb#m3=0@{R2!ny#M&1vi@< z;6Wo#lDbpB9<^Epm~1?c=X*dPh)n^*TU#nbwNq38!Z^0vS5p)|(w|_|^`XCL5pbU` zbCG_qhpdWl9eL%eT7l&%!K&2;%bJL!UhkiiXW`g65L+iNA19ooo%}&- zA5VGN5(jf8zJNUDC(+4>LbkossWT)V?3t#?>&>M;-S2`kNro=-BQE5rf{a7Yn^WHE zvE_+7r5v4;V>adqb`+z)GFFA zZm5Zzt91$jze!M62Th&MIJ^G|Uz~UPPv~vCz`ZN}l~jpQ2lOVf)e1@1+M;0zIW^Fi zeVX{V;|JG@MZZ)3=(9pzJ`(|#I8UxABQ4}8td5h5Q#CMN#+O#j){qx z$v5Kq?j739-XDaVza%sLv)1VU9QE{nte5_0SSR~?9>YIq&F$Z-jQ><{{C|nvr14+o zPyIb17ykzP^1*-i+T%YlZm>Va?lvfb*;b1xq8-mu)X4Krq4+-XKqr-cU5RCdC##`| zTEP&oZBr?xdR4aqGTZ_Ex|4HYHV-1|W1`D?)AY$CRD_)R#a!4n>R$Y7Cifp}2kePc>jvA{*EN>GdN@k7FLocg@?#qPl>(y69qy}Txw4EmQob8& ztOCYn`#xV<6W5217D|0@YuZ&eQp(nr;X_kU0AGGpUTyL^p3V{dp(Tbj^>rDEs=-`b z#?()g4DIil==<;8wg0nT|EE~XfvlDD82cI@VF*3Vua@Z0Q&1o58h-m&0yxXw^O4`K z{)V~AD8T00_J z(vs=)*CVSt761r|=tm9FL77q}tShKiT-5;6KPna!jGi+&VbOfO}x>T>5hBA`+4Tc zO9{oxJpEp^$KYS#i7#Q1@JwF-wvwn;{Egp}r`4DX~t2xWA zy6VoLSuOa+EJ9q!*5Tr0@iBLHlde@rF&&BJ79+WY2OhiRJVG}GKTu0KNg1XPnpaP{ zJeLbwAAAPBKh2yStJ6Q4=^C1q1T1e;l*@4+Y8vHW?NOx@YaO0&`SHEgjpj3AHySfL zA$D_8^Jq^x8=*z1z`){^p#1tzAdnC9T3vU5g%vhn{uH;ICvMSeNAFGpQ8v%%(dlg+ z@}VwM)%(@KWSL<9%lvQfu5>~#l(&B@xSr2f?%R|#>}$gJpYgI#&igei&T}%e(Sj>} zhZZ#irO&>+AbOXm^3FD8ZP2Xs9+aU(?uF6T$;@5SlIk)i(o8~XY zO_P7|&LzwAq1BZd@~uKI?fC}nNm%Y@XX!5s*w9jRYI#D z_|~A=^GWNR$vS6c^Q*faQh)vcvl)8I*LWn={X*Oz*De^uxnEboRO?~r32s@TdMNQ- zJNkpzj8v89*cvz(l|XTBhHqnAC_89Xr?gnfpy@R9Xdd<{27jX3SHgTPS)311MWMfQ zNh)+RaEdB@A+6dtN`4J{!H601vr2Z2v`#p*%iw^J6RdYEt6pYmyg0%IlycNpqc7a6qfZ`PJvV83=WNJc+3pQL-| z#)R*UD)+zK^hMLI_6*bT|177gZ;IpQ@{@e+8-hn^A7;?x?}bTzGrqTDp zd*N)_laudaEJMZ=bWQ0lA^C=Ao+0B{W=%H>p%x5%>FM5kqc0mPu{iwmSJd(*neo=c zFF$^ak@N2|rKw!EW0zr2+L}QTB~yEn5=}?ZpYLdkc1YD1cfDK7pBkm52+GhreWZV! zsqYkfUYXYkl@#!qPj0cc%;?dLzrhD18~fiLq7qSa`G8m#U#%l5MJ@)~NOEWk+nMWS?Me{)abJgMowie z={OUUN4sDt!6&>b)3djsAq75f-$EG15Bvu70~5hT45*&p1LMHBo>d0+o}atdMweUL!k>mh?`!SrRPnoLvGTm) zcY;qGP8QXe%9oAPHMfe9WcP zE9W(O=2XlwF+b)9{_S(lH~4Ec)v>UflUEgGV5}?eFU(3vGzKHL4HbgwO=ApmYTddsm=F)#8r(Y`;Fb9oQ!6KQronv%eSbI0`7~DZsCiNpJ%qw zF4TzPdpUP)jbB-(QhV#PrqPBkZ?jOCey6Zvgt6bv<)wax#hM>#1-vZ?l5Wd-?{xu7tkm1=?={!K`1L^e+R$g#ob#isfD5gTq zTDamlh{JDRO)a847T9JYxGLlX8g#eK2vgtJ;%0k!vbp2j|tb9WN zceIJj-~-XR-F;fk$E5KaQ=|e=&iSI9P@LKA$8`3mKAa@_981X%PZFqQ`HpvNZ$^os zNxC(`+p4=rVOU_j#Z>19o8JJ!wCGZsW)!P8z2mij6IPIfh013&rwtO4s zzp!j;tAlV>vQRzF152YMyXRjPk0rnHN$lvx%? zZ}j4AesDhF*&SX~DqC;!)L~p~zk%%zwjK*c7nw-3?w>iSkfXr@92GI}Fnyy(>ot@N zX#AApOISskp;M_|@wa8DgMgeD4`(f!-R_|z+B&ZLrd_%Qcp0wo*Rq({9mZ$<;-`8q zVuW}hZji$&WF7h6K2w5HmAJ58>LF3ihCPiGsiyYJnco1zKavIh;oG|0vH#_`QOAJE zSaC%P-&EVD#Vhybs(Cg-GF8=I32A2d6s)z}ep0qXbWGKROncr8H8N2i)B^i}8juIl z3y|;LpYM)M9y-x5sAN6%j58yJ(`BhPDXvas>sG)C_g@V^ye*@_#mXuB-PCI+Hz(krPQ~ zOZ@QQQ=HO{31+-iM&O_4THXS=i%Ow1ySH1f^z|c|T2C~6I%$3UaM+qq9EWg;Z+ikt zeq)t#pN42PQEHnmcNNY;>dzWoPoQm^TwyNgO3q0InN8kZNIXn}g|&LILDo>B&=t0m zJG`!cbp=WjBl8Qx3;HanN2aDH3<{gS4lu?!E3s5fmtMeDQ^VplJWP5w)efreQ7ekm zd4K!7XqW}=zj3^%EQp0azp&NcKJ`b2#Q)y-f1i#2eQ*39BO5hRJ_}#_W6o|S{^v0J z55)c@lUdK<%;G{`vhbsu_ZRiv5nwegpF)?l)lG@HS<7 z+}KVAQGpAm^x|ldv;7U=SZ{>XjJ6HGVp}$?r6uwlq`kU2VifLM`mFus`^V(|ym{s( z;5w?zM~Xmi^ zN-#%C&`6jUz0byfYwx10n5CdvNU*W}F-6c1mp@f%zLkbg)N?sUqOQwcKYFUsWZM%;^~7XX zl&_TZ2v6GFICr9oS|i1x{xX(Ue;csdFb~W4W;czxHJ%Ef?Wicp>YMTf&+b#!4Xu=( z5pCx21fSbE&DtX4+qaqM{#i8G99DmjzyK|Ift=x8oYu3fthwUjOx@F3h#XaWQ`RQP zci>BJ?Kcnx85AJZ=}HYJcW-q{zYO+aBjRT{mrF9^kr(XcjtiRr<_VeheFpmm?ttR#szC?z zz~&Iz0$~vkooF-blRPQh0}nwa=e+ zLT6_#s6(wzDXiBycc7PV?k@`?tlvG-T8~p|wbZnJSqH{?YRH;r9nY>y$TEAj!9wJamUBG7~ zVY4(c5sT`n7u@pI-a{PKB#wQ$U&Juthc9X>nU^`dS(DDp`!X; z2Tb(!+r8$KtT=q$!gCXYq+0l5H{Is(J|?3KAkZ9Qr(&yDAJ$}7W_S^d-b>q7A`-ka zOm85{V?P&#rd(Yf2!&>4a2__$d@b>A8xW-kpX6{D6zZ=~lKE+H`3j&_x-t1k*GA6r z4a>#o!IksnRs0qHqsMR)xJ~GxDpFLhpTM-u&3DzJ1SSx(gv4P+^UfTmo5}Ja+xxso zo4#t}S9x7H?AF)2xybGMG^q=D={E_>c{x?D>usmNfpYWR#}~OATQ8;RI=yG zf&?Fe2&-G{+UN42M!)P)=PH-t4yC3D7lc)Ro%H1UU~)B|eW_~?&VM+kd~Gz@YhtlT zR9goVXHnN7y3Kb4DgFT4hV8o}hq_y&yKLj7rxeZ$#a-W(=hpYC`?+{T7T(w3oC&!*}l=Z?%`>Wp!oh98M5iQtE; zC0j0D83A>1eYNem%Erys8*1}D|HJLKPLPW# zl>GCH>JPF9EXni;*0InCv09!VUG?;K&aHkG!>(>3x~hw>+^MTpu#1vT=zYg2m69Qh zLoH8mEpH=pMxh)DC?|{#z=Nf5Pmwr#g;DC0m)QYd0PA|su?9`GiFByt;XT&VMyfIBa;Cx$|Sr>9x*YB34+xCDn0Y()_B32DUtQA5NmE`#O z!P0V|t?d$pX8h6^$U4p8k$n_gZJB~j5JEEdOb`;&}v`=z$L5&L$ zHyI~P!DlK6+TAiYhpYjP0-$SX$Vh}KstNKtAB@t~oV)yX$HntY5Nl^JmSBxe_B}Du zKJ#c!-QPSe-KEH7!*t=AU<N6h-y5YU29GTdiqP4O(-th`=WS7zN*X)rFU!&KwmW~$H={IfRNj;NupK34?5{WL zy?$F5J;Q67Tfd2;aSrucdaq%hO0FU_zr^D1;m_+1I~@Z&HypN_1mp=1I&5I`TsabZ zs5v3NBYzterXPWv2Isfhd_=J?j6`f^V-NRqKAnnxLbCwuJMSpd3w7SMJNX(y5#s^} zly~k)*e~<2evxo2OIcEj3|$)xbq=7VV9UkDCZJR;vGqIl>b^;1CowXD4OR8k2(9#5 zjeHWCw}4~cEw{3+3iGJDJmb<7ouDa6Yk$ zsUd;nzJW~Q;N@`|d?(#BAOjQq{@O~?Ll*&nXYBFn5#^b(1zo)<({8!0gk?f+7p+(C zn1QT0*fiz?gc$$TA8%bt1k3bQ7oGt~yUGn9|D4RHLmSKkD(CxZtI}0lMBD?E24hcH z<~5PNfy&IfCzQ05Ym?%ZPZquAeA8o}5DsDD8RDrR01WkC@`SxtRG&}+H@lrK=M?o? z?(ryHMmY2#omP~dIm&h}_>j-rV; z^;B9lG5CkW?squBS{W?)S78C@FQ4kms%@z-wtTZ7D)&`AVB<^Du2*+>v@!1XV&U=Iv(HC&9F`PZ{`bL}%B}P6%#j zl=NFm^RJD!<2ECB)JWbZhaKB_hFxuzx(xz`vxb7GH=xbL_ZA1X$Z5#pdcr1QQ;Oak zZ~huP35{58E9 zT`)h43zs|;aj(nbYLkIWxRWRqO1~rtN5jsBfu|mC%mfW;DO@4`#D8FcE53}T7C9?w zp;6nWqLd{Rv6@u0{bG@QCnELHU;+3chL?UAE1QMRtez;^+3rFBLY>5@c#OLjrhMxM z6)NCp{@5T*a|N`*kChh1fTb8|N1${g;N!(jx9lT;6$@rQv~@)Z9D@c9~ywbq{l7NPp6`K9nh>3-l?qmq+52hM1P(QmUYGi%%xtiznh;z3ji+4|oyF;{%OG;ofCgMl(a&%=D zvwARZ$`g^FvV1uFZ+8Z5@^OW?6tjEp!n`#UgBcz2IUKm}-=7OEmcs;31TprOx=>n+HFwpNf2bbN$q2L&5f1JdviGGBZ@0)*6f42O8PFxX9QhQ;@gA zW}X2d-e?nW^@~p>xYCO+O9rhkY%;vv(YC+{uVB_tXg~?z2fuw04#{I)&1u=}bVI(`79U-;9{gKB&LA>9*;XH7C)tK6b18=}Msex>H(9W(Zd{*kH8DFA3`JYA^}*uex6Z>i5AZ8;%~v6JXU9?i^?PrRwo&uc zNf%t6aiIam--TK!XyI2B%VfROipEYjy>Pfag_3n8?J*8W6-KKxDtH>&3 zeNhjcHgh$TMe+G%`Fq^5yYXK32@Ay%IroMyUp`uJFqF%DHV^k^ZJ+#XHs&sD8Fm zVO*0+_L&f4B~Opc$-6(;azg(S1@1SPVy~6TGtU7>>4Ye7H_>F)9^AX{d^Ri4>P_jo zq7itl2*U|Dwk}4jE+J{g{vk;@F4-;vW3Cdr(tVLu+er<==Rv{+Mat7Z$a5iWbqO;z zJ_F^7uKgy-^n-x9#f;%Z{C#`(lKY-|dp|AHy3Jx5Zk&GP*~{iaacLg|c~S7Si~(wQ z;LL>*rmsOFsH6hNd<_<24~o+2_{{Wl;7?OQCXJ*Qa;=Aw>Bt@7_dTsCr0-lbX0yIX+&rnK95e%1mmXO*enJGd)(s zd@Ir~AN!mI!z7rM<D9nwbSp@Q(gEwZr+=&#|*X?wShm6xHffssTay_;81(&N*b&Z0ly~D z1A)E1QxS4S-ZA>allM`r#LJL_94F75c)hi&+;TR}1ZnHOy)Atf-v7)US;PHuRQ=*esDwahzTgf<_n-vy~|d z{{}j9h6=_^D5@wD{fRdcvlnn9X5k*pP>*u#nZ~&Ts-XE zE4NL)SlmRyFW&mGw2$?&NaB=;$3+&H88ZmRVJY=(CO>BDUsog)9U@wA(7%w zH&wD-vh?YFT;cg209Xq0LRe4A-cYX=A22_=Q9e}SP#0=nDp2AM!Q8jH7+#w1yQY&W z=@}s*uBvZ^s#bTlwlrQXevKenvk@weXH$s+A2TLx=s*2kQcH_>GKaQdUB^`px7zRwh}5(3Aw}b zAfZ=f*RWL5N=!dda8Qz@P{7Zjk#Wd3Ybc?`xeWdJ!{|4V*dwpHFM<=Zq(Feo1H@Y* z#+`yvR}352QP<i#*-2SbuIW5l$X_^%&m^uD|QRT9c_M-I;jswo_C*mhs z*}UEI)0kF7r=uL$PCwQk+~kWrVT9VWkVO?|)x_FB?Z1I|HprQZ3Do059I_w>U+?QL zyM1uQSv;iWS*&WX;Vdp3dl)(CYknikNB9Xk^f6D+vXm+1xnOJdMu!MPjp;{7`#a^< zrUuy?iFxBs&WbS)*|?g=;w;BNIV&rv_oZivg~i^ivf~a@ukkaLPjbvg5HUIuJx5Yw zIPI#8?R0&85Bqh{794R)NldpbG!Ndo7G!_o>d=tChHtq7gY zVTbS0kuy85g^7;IO_d>o#EMB*c6qcnl*_8N6+G}mikcbmT2U{jtemV+<*^qF){=m^ zs>Q~QHqyG{X??k-}!FDF0QFVE8o$*sD4R zN2Ava=~+3>RS*58Yh_d+xE4H+`B7Jtf0S2_TzB5D#|;Y0t!E#b33b7F?FfWksw!OG zsMuPpkG47L<5vnO*%w+F=wuA5i2{+bv-@r#g)SlP=EhOPhIJ@F{d@o1TEosP^)bNT z3pK8tEE2p#K7UO|G;C~i1u!yBrhfnc&p!pc^It3ne@hM1#haDMs}cG$oM3}7D`HG2 z{#uC4{<;eQI0HT|pH#NXvPep7H!q>I!i^`gyPQT3ZC2S*#JDL3xML&T`i+;w_y_$-ZbJvI1d3nD=eCW! z&D5i?p$>BI|DVC5{=rF@gw9PN Y6S0^YxyIEcO~KO)rNAu3_-**#0A@A%w% z)%)J(x#NG|_{R5se-C31Ci|?Kzd6^ObFDS^=62$C9=P{ZN>&PhgM$NJ!hV3;g?mGi zZssNcATJLv0sw#tAi_NY;9(TvV*>}k-yA@M(QvRYo+c%K{|zev-21Xg3ZTG94A|cy zunQpF{M$F*>EEB<2>eFiHv+#A_>I7C1pXT$fE0o7M+AWjixfUaApW3>q9XsG5jZ#i zAS&u7{WF?C4f&4O?`Yz`q1OCn`8NW;5%`V3Zv=iL@CyQ*>>PZ8>|BBzJd_;lf*ibp zoP5Ba-2;HffC1nDt9iR{2j9%e$xe`s&Bl?{z{vKMF{`1iHJh7(9UBKLI~yP*>SkwP zXld+3`O4VT+(wvgufCa%(%eXxPMt@dUEWT@*vwqU!@>Buhr$a(4@*M2>E(oK)-)5r{5ppmx5mb31_4g96zl5p&J{DJ3S5{Xp zR$B*CHVy#+0XB9{Hcn0!SP2$KcN-@IHx?U5>c2Pe#Msf$!Q9Tt+}4KjdxHkAY@MBi zshpk7jRZ{$On6=y8S${ZGT<^|;ovYbU@q;dn*$_wJ1hfAntW z>|pgr-$sUP##YAG#x_olFf=&WsM!8C=>J`P!XWz5>7T+6;}KRyP{P63z{&Ut>=OAd zP8N1977m^l{}3@N2M4DR+y78bi0wNVzYO$$@5uj4Xo(0J844PHAG@u?-@1QpZ2!L| zZ7XvT*jC%$n1j)OBVety2bYnQkd*O1{@i{Buu{DrET zx`w8fp^>qPshPQjqm#3XtDC#WyZ63+{sDnOQPCe_V&gu>CuC%1W#{DPDuo=E$hG)Lbh2c&{7= z(eY`x7ibT@v-SsP|24*Z{--$m!Prl}AOHpe987o!*nlW-f=-{|jZRPx$n+C9)Ky9ekmFo74wDu**$DzpHkrCihxXoJb>_^q6i!><6A*w*8+|0F z2p^*%sncNqLTgDL>ID|A2j*I;qc@*Tg2wP;zFFo|fAGD$t#Y6N{-y|`EXZSU~S4jKx^1R}gR zb%K!Z&}tvvz?KMm*$_(=&ftu!qp>Z`B64LsVhcxd*mDfd-dG)POhr7tYuW^@P74#y zfZ0`^XoF9Q91Q$->AJ6~y7)~Ym}uK(TH7QfFVqDV*|4YAJ!a!^T1jI$+quU}#OH9$ z3`xdGU%JOzg?SGTx8G~=EGS9)EMe(N)>s1$T#2&&mh}<6KA0jtyhjk@^kL{NP#UrA zgsY}_O-n2~Nxo9b`^1lOWyzV*i2s=nr$CpGop?XHoyBDjQ~j2%b$XqpwwcZQI_IqTsfPYWvMJ^db5Y1&bEgmPA7Z?r_rrtmouKV@p&Gn+Z*Rnaf zI@+z~%;39@=zSy-)=X(qi21H}s<_^r1#D>6fkKNwWlmGYCi;x4n}e*z+Mez-GB0ic z61=-BIgUpH2=4}vy#+lO@ZQlIQ~GeC?#YQE;i{5MZCKICnn?1}ypqKw`&Rwt2=r+< zWk!(xC?l?DFdZT}C+ML;^xqzSP&Zz)4}i!D+E8&+vp~VSAS5<0lS1S7(Y0N>^f%EWRpP zk)8c;JL(FU4iy6B8UYLWS5hS|a}%c&N3FL2h3!G+6?rSv4YafaacurV-G0fDUq5v5q7UD#^<~B;yO4ASb!_EZejx3S#}GgP@G?ZLMeU% zRWy3gwg2oF6eheq1Sj4?fB$!qq4p!0Tnv{nqrroVeMK zYK--I=MnG2OEXg+PrI016!qU(Nks}FW3zCMd2X9Cv9)wzV zy`piQsv=mnZII?Clj*vn8;bR_#lc_ICtP~Gh-V_(OSlB(gP2ooRqRZMl=vi7p|x-# zAwRzm@lYDN=$}E$;}Ha8{@Tz_Jyg&8%R2d+j(Ss&z{+);g(bV8#|p$x)*fKmk)#vN zFOiy3!sSYpQ{O0vgn>Hpb=N5$c=FPOx$uF~v);8)K+cp}(|qG`{pwRxAH38%SbDdb zk_ht8-^N@4>=9qipJbG7DWN()WMrp-gK6yvUNTJ}h9Yx+c}I|Dav1#Ek?08}guD_% zr33k*H`IfRRinjsKQw_LJw3is_i%ebSRzY2-?U~Sb5D#bYW-H(r{r2G?XYsB-$(+A zlDIHq_LR^Loi=yRcJFX5(B5@mP)G6qxOYU>R1((C$~lbc>L)g68+Vm6W8KADwKEagJ%j;VWl7kj0}kYo3rE+z z1uUh8^`~^%!{m8n&E`8~d=BeA!W1`WmT5$m=&z8sY^fg=ZHqP+X&71B7Ko|%{HC~RD z{yGk5NAn*>@A4K1B?&v_Kl{cLTuglQbcCnNhQ+ih3L=0MHtDy*NGvs1)rFE=5HFI< z*i<5}7adOo>RP3vJR=^l(U}^UY`WOaQK3)_vZ!airLpB%eFDzGf$C*0$PQ z#L0*nrNpYL)sJpB;n9$PP<%FC0ZQ4b5%?SE}hJHezxtII>Gd zG4DQTEQ!`r`l8Er>b%p7xd{dR;h0bUaLhl{Qep%@f!x$!{{qr0Ra-01Q_6C@Ze8+V zq;jPm{W%@IL`g?4I}HvNsl9GxEbrmwJ-u#n8^_RLpQNatMpN5sJ~5prvm?4 z<6p@lO`CMv!}*$vKKR9yRkV%9oBmvE)N0f-=c`*lWVf+Sb&5XM=L>2n>zh%#$bw$c z*!z7i1*|jQM)xCGz+C5#N&71o!!@`Tp(i2WqpatG!S}dmEEF~pMV*@`PxrnZj644M zq>mtU;Z>PXIC#8iCG*w3{875q&FG1~%?t_|_p6XTPN_x>Z^nti(!iGYSPo0qmfG?| zl8Nr0*xl{lh6Rfe)2CyrdeDC^q3&=|cj2?ngG_C5wm#I8b?VK;_*OlthVrhKkjATq zV@>F2dQcth@KMrv5PGAC)VAAh@*-2}JsGQFC(F*8FA!#YJ`?`g83h#vIfTy_e)}&X zzH;?>G{u>m3Od<+U6c(pr*$U0OI_|t=|b{xw2pD}#q&WXLIZYNELQ$%naqUFwI>;Z^*q#F zCGW_;yS%o&NJ>8QSxZ!{9kt@&1~*wt^4u|ro$3qYWbv)1&U0o(-xb26jNIriiA$3- z&yY9B=k^F}a5rw?e2nPG{XUjllLm1OPF4t0R)9_~NDyX`DoI?S%_S?Sm3dA(c$K#R zmZW7iRi;<6LA5gOGY7|&5;!6ON<*PT!Evrz0F^au+`(d?2vSmGt8zdWtjJ`A{^i?3 z`jH&3@)XM|LULmq9%N8jJ7Cpm0F@`K*dT8p&nsgQv7Qf6yiA_9wPU-7k1VK35B|Cn z(I^Uyn;A+Wi=UXTIkOqaXtuNR4zFaOQX9UgTtv5aj?_xS&Ly(aq+W|23bW5$m^k`= zY3s@xgL6|~@y~X!$WFpjZMiKeVn`M759(hbQbvdNkdVDU)yI4Z9%AL5N<2-NU6Kfv z02$d3K&Hp*gzE>H?$$q_Cy=CaItV7sSnMN19w%NLm?dyDIy*tL?laG{HYj-=1w z&SamTAD6t588S;@h%^cvDWt~mL&>AADS?j4GoX1R^92x+7csu zn7&}CDI}fQYncVPL*H-%b}jjiui8iR5D*u7JAFt5=^ z|I&z{bF1$Cm8AqSCG~z+{OQ2|$;ST%=eOqko*lnU$IrFOuYq#f{~^1osa4|V%<_2b z@~*;>LTz=BhU(4}X$KjlGO8!`V>}ySCxd?#+I>S|GFZ^I)U~e)-ioi%mF|&wRofVJ zcb{r+k&Dz4EMjOn9{zN?aPHS=|CfLdPAaJJ*C<+X+jH;l>zZ#!jG5$-HVGqjS$?u5 zx`_7im`~8&#)yZ(QPZ5zH36^RZL6%iDqGD(B_0 z8OSPlv$t@J5UrPMP-qS*s2w`FqdiCj*VoYdaQe7^$bQJ1rNd8SbSdU(+0wG;lHwr^ zYzYh7HGT~`*?i=JPx04c2L%j|ZUCX!y<|uAFgnp7MSRqwd<+p&1m(Sc4!oXp}0Qbd|>-G^x zh@o)ZEg-mE$p0b)ibKuA5(JfiE$St2fhN(*0l#fj++Y!~%gC};l$ zTTw<`0K4o9PCwGOds_J9KT7?ixGnH=X6SIByRxsdt#jjMz+}R1h1_r`k#yI``d3S^ zjehB$13%xUclKJatsJ~SGg-i+hiz<0lUJ7Ick_{ufvC@7+_z99B@a->* zmS`}bJa(ksUS{xEREiht&1aprfL{1dG8Sz)!F)(gHccbdLdX~O<4dyMsz3xf3U(CA zgOK|?fcP&${Z+st$4ZDlVf#t3%#66GIZXE@M>4#^HA;OcY@zz-0}lGKDN0@%>g%79 z{gtJPDzS{z;zDsBj0!wH=VPSv#Qd3%k+18;f^!CW}b|bD0`F)$k>v zo50cn6n}#93qA#qE%@CfBYbre3ib{gmy*w|c~?_4lp#w*ds=^`7pgnXZmjV@m`1E7 zF~61=2k-Q92#(l=;%vMAe=OGj2~GH2QcVo+FK!9v9(Z zuTx=}urso7Uwp;-FZ34j+KU6i;nfkUPvzA< zgb=BqmE^21A*uCmC&p%zoyI*Ri>K37bKcUvY=mP(YX?Ms+Phy&Ummgghc$cEZQR9* z%mda);n{Rc+x(&<^8oS#Di;tPtv3qMMMdagnA=8I+TDRaowK#6=kiYa+ouhD>S@f2 z6Q8YikvbF9?G&j^4}J%%x_I{L0&f8j-exZ?KD z3s89rivDTa`C7UxD_QDlL%l0K>ECLMX~^T%mfuj7wlGA>*fuoUU$4WZ{HZ4rZeCgu zowi+N=-(o>I%I#LB*(E1?1^FjG*iD?tgkw5t1`t3841igS^f}Kh_Tcg`=B_f=W}Wa#?y2v#>)6?I zRLlq1l{PaRVVPmaaOHpH7*3L$y~hV^t&N=>%4N#sgv5EJI!Q^(486tqQHUhwG!`FL z8;9=CClk9q%CxHnn9!K67JC=O=uT1>qs`avq4 zrH`xc+TP6*Woi7zcqVoWVB222!rI^68kxt|g$5T-ZdHq#mz(q?SF}=2(Xh>EdQu$H zBS;0&r@;pu+_mhO6^he8KslxD#ut?D%?c)KkYAy6QF>#{{APpZDBM6(2^K#u(p(C6 z6yvA$8Cq>d^;^G0Crko38&aed;?uCw>5FdQPj%&5J&aE}23bb4o{J2=t&O-J-Zth7 z;Hrx*iQ>pDB;yMd?GPVc9xgC%&!fPtzTW9Rp1%dyJoc@{q12Uip)0e+`C?;3y=(2{ zMbr>w)l?%(%ASHc(llxerj%l5c}QPM69QujC+q72pAFaM^y5CfmTSQSdBm+ux8?r^vAK?65Kzz6vLql`0CsM5RnY z6)rTBmDMGGL-juIh12rzkyh?{pT$ejW&>y!)Ff3o{QMkrMsSgk3ICM7ly&?B3%_;o z&d8^OHNS1^vF9sOI`TN(IHzjJoQ~(;Q1S-#gm3bf6fYUb@os_7A3^7%9(`{=Y*crw znyr0oYceXwijw-=%T_KF1eC*$a}oJaY(K1J$e>-jL958~bEdY4Rr^yt2wNP9LcdgF zVx<={r;ik36k=d+DHY{RTh-9Lys9|uY|b6?7I7cF#vHq#p}! zggZ49i8g{Hm$CA3;b=s8(<6uYyF}HfZ-Kyq@eqhh`Au5afF&~%MmuhKKp{@?+y1%a zx5x9x-S|5Ye!~_MQ^PoG|LBVs&F0~w&3o^lxNu)L_{@#*bIC%d1(Qd2jz4{l-D{Ad zAjI^bCtN%3E|!1XA!my?V}6>r9K|9qA8dB9aqrecOi>7$L%F8E zdiJImwpgUtFA?I!;dgf3#IXts;@DDH>dgZ@>QD~3+bGzErnx=#tma% zJUDi-?}4A3HVf~>vsZ}^GEETaU&=1izjE*ln))%$ys7Pwioz$^CbxhVhBS_SnA@5+ zif|qRvW!ifoWBE>4+)WbJLFsE=}t>?pMIho)l^&2lsQ!4MMNfhM{j=%z-Pyf zL5CKW{l+x!%f_TkVq@*aN_F4as*=SUxycb#gRO$G&Xxaxh8SsXfSx55Qg7~Ea(Vgp zO2wZ&O;aA?h|o9^zaF+;N#Hp1Cn745li1%r8^bm~t9yQz*)7so&aE=v${N~lbwM>V z86;)IOnBc%^DP36dXd+^^zeB078u)rz8#ty8xsm|C&tUb!kwHxS6Mw$Hj5R8*Oup5 zma%@1UP!8vvEy$U=n$_mInO(f2@Y7Utpp#$#@)me=;&;Ijn+)mCNd6_Sf|bn)uIz|IBr@~Z6ZdO#>JoNcs^<8lRQv*-R0YAW27W~x1|Md z6v<`HSEKju3o>D+UDDQl|k68X`uEV;q~UO_cfbgKL;Wu|5* zhR(SY8alUtt!{GiUESN1SJ`|B#Pyzt_;8E(snsU)h0nnQCkIT*$OMf{bnH zlOtBNDIzs=th76o6dp5C8nmIAF|L_DMa4u9-fp6{Kia{@O#H)8IU~fzwkoCcEHc#? z+2_(t?t~3JyLkD!W$VzILU*LDK#{kBCg?NGpzdRQ17qs0!Cl?254%)#@R8itz1%iM z{zc}Q1qMT%!pO0#rPfib0%1uU>yt>Y z!X#Eoza@V>)tdV;b#nq)+H#a?B0n&In3vxsVJzj+9i?F~H+Xy#WLA%;9A>ZgGb4NX z`EEP{b|nY@RqpBlg^#HL=s6K7&DCA2SAGra30@V-89a%D2(yuj;}pJ2&Uf zT5bXKA7d8l*P41#QROd_pi9NBvZ%;ioU%%URT)9R-#_btN&lZsUzbv2dpsX4mVl_m zJM4oxUO}>xD*`O#AKuWM?&EB^`mMUf{!W{Q%QWi1)>D&!uF|+3AC9u6Bu~%h z|L~0r7)u7Vb?=^54W8(u_2x}O=z|^}M$W%PMz9rirH0g#XuB0#tB`oQ?PMyqDbuU! z9NM9f$!7nsjG6zCn)jXmVbdU2o>P{5bXq}rKXUpxSM?LaB;+*&;ZT4$HW@$P#CnxE zmEFjR-^gIlztLcm7{8($Z)mgGx~9^ehP@j-qgvR01eW2$xc-lU{tO<|P`T@u@-_~p z8*sGijkq0H(IZ=~nWzM4tU-N4l#Kxc^*iO$V%_+vGU`ZvcZ}#S&=4Iw5VU{ztsf3k z356(kLYFnw(IZ2=u-$ASXyZ_VCaiUJh8l;KGW-KWXEjG)W@Xr;#H(TonOF)Y1&(&6 zDQ*Xyp5^7_R(oo*ZX5RjiRiI^wUkoxj_SmcVR5uEl@KSemWNo&5I@GOQ>)o?N?>^h z1*wL70`D%=CtAy*h*`Icy0SbV-+8zs>3Zqm z!_?cru|xvG=qoZS*S7G8DGt33M0DAYf71(}grj{`+mBM^Q6*t(Zfi!W)q+bU&AP~a zr#756OfVXjbHdk3ZCT7)y2zkga)M@S^lk?SQ;iZ%Qu&%1(O$Q`^YTjnaualnob59- zJJMyH7IdF!FQVhEEBGu-Fa?E&K}m)N{>8G9QyQk+Vv>sd{(zc{a&mRsgmUy-MjQ}; zRw_7nl8XLhe9p3Af6>48EGd=$f%8{mChdSwgxLkEF9wsf-|isqYP=o3!RAvvKpF?VfS4*_FaaIz!U8 zb`p%HM1&}WYeb|c#|88VEl|9339S*Egj--|yw2nUp?j)ne1>I4?U#LN1UkCuxBd2e zxXNNk63(X9UZ_E*vrGZ4$Y_ixL}Zv)_Rp2YC|EZVxCL|HH%J%j_6gJthklawBXnf; z)o2o@J0iUtufC=SzrPk4w#DGMDR>gamufcKQ&FSJGUCmTP~}qjN0Ky3!1?f#@oR#m z_-pwzX`0wL6(Ze8xjdHMEN>8+5R|&6$ecv?JSGpa0a5tKz4H+H!oU~R2jgbV&>L;} z>Xhv0SQr;h?@Pb1s6utcI}z1NIULhLF@y_M*k%c)Wyh)Ok-3X2EKlF{OiOj5QBIS@ zHc5?73GM``)v#&WwG^Y_JYvYqRqN$oXl3-5{jcTIj9)aSq=ARj*e`LP6cv=z2sqv@NS`CA*5q!^0 zoSW~RC!Dp%opu{$eT~iz&B$Qm>;==@Fny}qxAAvhECgZeXk=R4V})%( z_M zO}sFKics9NLrt=Bu)gnqs9z*}`rzd@5NK_s7Nz{7b29MnnaSL&Y`t_q& z4$Ch1wF5nANea~*im8wNTf4%JPy)>OTR?28`Dz2ykr}-t5<_B8+1npKpL;$YJt|jv zl6eDBydzJwki0nc$#PfNA4;GX4Xe;Q*C*N$ey;1Gc!R(O;)Y>+5TvT|6;GVz7;w(J zY~-@t2~me}*9Yso6m~wIX1uqW`klE(I_TTD<^)ivyUMwvj@xzHU=^}Ly>DUU#bTZu zMud!E3UBCmL0yFOyt$WNBE#xL*WLwr_g}W+)~;DO%yxotu&mmY7`8=oW~i(dximsi_DrW`{j7Q+jN zQ4$UBe*#Z?^8Hf%X)56{SgBRMq2+`L%CqR~GI#SBD%xMbZ(-H%KE}!<)wDG6?`2-N zS@{+8e@Kg}=sM(Cd3w#`lI>gc5Atq-1?LUXV~ob@VVItmG>>AP6%Srme zZd#iBwZwPr9M6Jf2ymVqDISy(X2gwd#NCt!!PNNQmxDot^*1>W{2K}3dg*-xS-q++ ztvLn#sxhL!jIo10bMv_M$`B8xzOY9$zHAMF)`>hXa{tiYp9-YMAxWVQQ(nRnnDVCn zs*A}K9bSx5UpC^Bxw>II;O7^E#!}DBi+CPIGq2&t{GF9wrvJZ8$x@hj{u@m4@PD=< zhl2E%#q57KfvLZmGwy$~BIA*R(xc}7r>k6bSK+XYmS4mL#5c;i=zcuo=M*g2%?sIvw6RB6b_oA;~UzJ`gVBJ7PujSq8zKC8Bmx^w+G#?u|Pg+8`qvb|Z#ubO@ zn!{SubX8==$)8y9Pi;>79e);Cabs$E>>@p~@-g9Kl3@OG&rkVByUlCwMbBWl2?yNI zt!-X4e)8L#JZlxQq_OtlV<197N%0H%d_0h_o)L73aOnNFCyM{^Wbx161#$XY(pObB z1-hVOirtZ3!>1r@RHTncL^ShodJ79646|93{h_TCDpZ?E37pnPT!Sw>#v|O^m9G`E zi)tpuBm4$(4ib*%LWlaRFJI8hR6h#reB4TS!=>YF%Ruice2pH;sLH{j+c9==LdMsz zj=yK!6kaz$YGcmc=Eb4?M%@?6V2=4x8EKPEH%*oZn$d9BE4fb-%ig$J>rA@s-4&Dx zoRKk!emT;acrE7pnsZO^Cez6M7Kn{pJ8wq!SKw{nHroi}1apQ_4Tsb*z44b`u=V9r zC#S5DcO%>`nnMh~u-*u_*yKqKfMC6!Fi*e>nvo^wQDbJzKOS(@B?vEZX3|HTmCb%= zGJz1Y89W_yFyPPY!Lt{T>1DDpv|{|+7XRCmtTlnYXCSwvwc+$ZWoFVP|JL=D)A-r- zX58b@H}mF@)0FC*=Vb(sBBCeuIdq!a2GGI&RGLmX)UtKaEcZ4@POq8x7FA9DptSr>*LEk9t zIv}pMg{Ffj)?O6sG++8&gOXjP9akB*WhL=8AjV5t6X()j$MHKRzCf)ri8$*YEGS zts&&xm9t#95hxWB#TyyUuqeAv?WZ60csn>u(1;a8Zq683cnfIj*xnVf(NBfS_g*CR z;Z?b&mn5bM_gzG?X&n@&2izk-gO-OA2}PhNoCLqf$}SJt=t-;uQ^JzMUx>~YR9S4@ zDBS`c1tYzVS|C(qU5aD&0u%3kwqTiM*hRi+QCwS^- zhxTfwx9Xs3bmZo;gs8RE=|zGTb|jPsCAYD1Whvsxrt|3%NvgknE+`pJ$xLaqlxug~ z2+TTnps8$p!He1=xwvEy84NGfq!D>m=QO_<#{-dTY`zmijNaG19&_UiUb}JTuVeaj zpqk>HdJj1z))imLD}yF^F&-X~v6kM4qw**z%5k9h!TvM$jk-<4alF;yJaac1 zvXqd~b#VvBw;@#mM%&Vp%XeP}lE1K?y1>%ZACX$)jmj<5-vQx1gl)>&CNEZK()msD zb<53NI~cnK&>YOa_)X^+|-DSi|Ui9lIXXK*Nt z|CYUDL9g!^kx}nCF+X0#hOyxhx;Zmf&Y`a})lB0CYtJ6#f$)#*C`D)Oky0=GtNcueiR#sg;qnyyA;vOQso2 zGC4^C?E5Y(v_7kn4n%&c?~wHPH-cu$%7=~%w1KBuQ(HMAKGpn1xw*cK4DH&d=b5;xTyG*^zE~BO>;}1Bz-XUp*;cqUAWv@95 zEsHHP+-)$EvjCaLO;*_f=(QavbkSim47J(kP-Oeok?7&x19_<2^A8zyrRWkFv*$zo zv=uc`lS{8#9T`PPnMhM3kO|4y1=gw=Q$lk$1Uo*_P!CkS7wg02oat$$e3&n#k&whyB|^d*x)!|!BJ0>L&r)vzNgm^KkgVWpqh&4{;$zoV0q8wA8mQRF zk(Rv3I824RCY2rD8%Ci*W`0TfX);Zv+^TpH=54sm~AyOU9FY;aLnV_JR8(q>+ zyhc!tc`P~cu+4;Sw$S3du?NefDyr(ZCA7-jh)bf?sqO1|FMI9Oeg8SDnbTn1 znts=64p^?&u!EcR;ROVL<@rc2c&qFtoD00kWo*?0>tIyN9?K<}nlQ;xjAcns&V|iGy>Wr3Oj$lXYi%jiRppK2Q!3$xk91ICuCswp z04=(s?@lLGdg8O8J*PV}a?%8LRUvs5?aox)jieDp=mqo34g!}$YjU71ZDKDyc|L-i z=0{A8r4>i)W+l;TgU5wrQmu;ME5iZ1GFj$QsvTvj{0Cw>DUGtHEn70Lh0SlO7D+@o zZQ0~}%pW}R)5!ECsabnBh3iR1=g=>}cy07P?HSiu*~ zN!1?6Yx;rabSb=;zymXK#nNt)XT5F+`PnBy+(aBi+YhYj(Vbt-J)a~u7jrXheyZB7 zd&9W3FJM8RQ7Hf)#3a``ep+W5z`VyceRr*Rn>yVghS4NdR0{1bC3krPSZqKp-5l>(TD|6^^9p|zUr-s31RQ<;7B#l zWDFXA1M+SDx*3bFGhMzLH|J?Jn_%l0lTkhUH!zxcXBcYwy2W#tKafwWNm zT1xVbq^ABIjVZTq&5EX!MLBE1Z_}9)Rl1#BVgiUxpn=2O9h_?ryc&LHRdI1MnfkKB z2X&cQvdR(bahgNg2BW1JzvZo#wqwIK|QS31g10CHJc$_m(SP6W?cwIA;Hm>Pg3W=s}9G?T3RN7 zyoDq@m8T0IuDiA+u-?STXBV=E(DIqZSE|M4X2@qt6*~&onusz|<8;ntn|w>~Nc%vG zVvdBX{465(g7bnL6bn_`Nii7)yKseEF2N2JM}~SAiL4S;wcn@8X)F%Lr=Eow5MH(R zq6jUMj^pHYF4T91@SXOQV3kIVhFI_ogBQ0w@a!y7Ax*b{k7E7a*0SRV^_QJQ_F~!d3#bIheBL{dT$%e(#nj0dP5;i*&@ie`3AH_G>3&V3owR#Ie zYGVd{Wdt4Vyx@cA3%LIFM!)ZG_4}_}`LK5aEnQ+=t~d85sJq;EQGbw8heZbJIw=H= zw?H3P3dt7f!_F&+^#Yw~W3oTk`^tn3GSC<4eqQLNYqBI9NZ>HH&7Tw!%oWHNrrN2# zI&O~Mv_Do)lg-hTSYq0$tPEy17lklcC|PMXRPj%(qxCZ-#Hk)&mS@fJwC}W!exM~^ zFp9u?R!smLuT^|2&~a?_d^B@b6=&?ZmwPP`DCwjJz`Vkd+$~T7d)HnXkNLU6=~$=u z!Tn8kuZ(_K>&4_p+a`80XJpbfxeSMM3Uk3_%B_s~vOVL?^Ck8#)Q$5turkg?)xfh4 z-|kswgOfevNN9XDKq<8)yh%pco**rqo+={cmDQQti>gZ<*y-6PAfvj0Az#Z}YjaxP z5BuXRPy9VDv9IhjzzJ35iHtKxz8RPx0espX5*=PKv&*d5&&OnQ@phwS1Crh|q%24+ z`7}B&r7(AL*CI7}@A;LmAbJ63B!c=Ydsr_0eEN9PS#RIt${!6C8 zlisNSRv~5b`uui#Q?`$>E}<@;>Ux`(8NH*)2b0$D)^PI&l6BmY1k+iy=ibClUN(LS zqA$i2`-?>(LjAe)EkLchcH_ne4GC+srV8VY%#>7%1PdtpbOJ_~Nq~sAdem!JmULvn z5wrp3D5a$J8ub*I&i!YNK)aTsAwl%>zEp4V`InUP0@w>+|Iknno#9xWVJDSKSrYFU zW#up5=%vcqJQjXtG4lepSkMxk$&c;$0HxwzHp|weex!?POkIw*ducrzc_7--Z3v?3 z^twl+bKUjXYhjbArNC0VH<)P5QXqwhAd~v#xbV~0S2p3=XhE0t7Ecd6GY21@GZeEd z$gr_!VeD^fka}_GhJ`Qepe%&NJxtG^E&?07JBS!UdxDPmo9Nwgn3PeQ)BrUl3D*7c5$HLmJ6!`a*#!IZ7=gT!`cqwV@ z387n_#L;@^&sa-ARYG)Lq)7cIj}^Xoy$Bf(8QTqClJ}HQswUW_Cc}olWT;bMJwASz zB7#TV9i%gp`oaU>f8TF@^YJavu3p{~G&O@4ICt{!6O`Gl334u(w!vCzi-5qCJ4557 zd|aZac5oI@^)W=?=H8?y{g!7EHiv;X|;474}Se934F8noJKpae7 z_og}h6IS3J{t_&)jGj$hrKL6q_7Hf411dxuk^CbMW^VDcC61<_-|VP0^e_2q)32G}ZDpp z^*dy1YASvkofJ~fOIGW+oRBcTNvUUf`4%;dXN?*$$}u`AO2HC8DEQ&7O@RVqcOpR( zb<~=CY{%G_0R?bPgq$FRDV#ejp1IGP(+(M>N_E89{Dj}iFqvA}*oI|^9+g&{j*hOB zZYXc?agaoeX0PkY`P|XS*w}0FhqZyM+txVi+efS!>Ns*$E}@gJGQ(;Rvh`9swTe6H z4GVf=J1pr#EXi9d#KbW)Ors{(5Y_o4Szm}+tL)5yzCo%F@kLH$@HCOslo9$(4tgvE= z-K`Jvl72l(%p?^(m~`+VZI7&1%OssOra)VNs(`!t5bd4}nu>G@YQEFXtF>n%38&Li zT4KF4Hnp;NO^1=w#OacE>1vi#l+X23zm7DHo77eK_0K|PJI07!FW{9~5eeGR#s~5* zmEyVR6X`x3cc@Oy4KAD@z7w2IvKOgor#K72dhIPx;t`Z0lfW$bVmI|TG*}e7*E*-g zm?t!O*=2~kjO4?sS1ch*7;vPfh}ep-=O+q|w+O}$C9K&_ePU{>ogOlv`()SJ30FmVP6D2qTm3978Myk2cQtdYsUep1$s`}A=~5I+J<>eqx! zN!%e>O>72%CUXLo6U$z029}o}i&UJ+#>dIy3!IcCBLsM(Y+q&sF+}MPI=fd2E3*}6 z25Dkzx;#ZwA$pqfp4@*di+B*+SY1EN%;L1MGw0D*|8y$6CUU~?+LAL!C%-;{F)GAe zZR!@#ci`TuifI5^vnMn~6IbI|A`caFzqY{*h`&|e6Eb%6NbrtUEK?tOZv8c=!p4DJ z!r}U!lpX&GaxH|>ol2|ig?#1NE$|Ks%XOOSQ?cA4A(2(%APcc3H5Tti3MM_;^eR|% z%QzKw=vBoQUz_|A(UGlfj$SV%<(T9-#)CWkoK`I_d3fjC`b?w#CZF&0-cWVtvRCfT zqcT^UDKJq#N4Q1JYh{nuk`F(vh@S>hao|CwI94vaxRRFUiVc;e8C{XIGOAL>u6Z8` z6Kl-xXQ`c{Jgv2?)tHk8IZ>MJ+oio;*R&r{TRz4cI1hAc8@C~VJ<}P^QOQbJv4-F> zE*3s~b9q`Hd?)8@vkfk2TxwS5X74zKHceWc4%s3uXcJK*I<_lkM60VAODV7(OjqS>@)0X!-rb2tO1K}> z)g>H2T|*hEw#Re9>U36KT~S#EjumIlw9ip!s~+Y_qUA(X$a zH^SqYECpriek{$b+(}H>LWr9F;!sfteK@s)kL#wz=K;CKHz zccs_=!hI=nPDsrd*CE~0BKhhKdhb3g;>_z}^dxC6*Xy)j7Pl`;ozZ!CY{Su&N1tY1 zxf?3CP>>J_Py3vy{O;}U>fLCK($o2oQ_uf%WcH6pm6crQ^rS~ErAWfv#hzbaZNbjH& zDWUfs1*uX51eB`u9uPu@fOHU$8hQ)8Ce#2S{$9Vm_qpf$_SyUFbARXDyYCqLk9TB{ zgk)vDYpprgGoSfPs;4Y1grDaxN;(_CDH@Y2jCZlgyjmlfr#t~yO6I~GcIdhcvqjbQ zsy40dKLkfr#LWq^r@rat%u)4ReE067BNaW5l#*jjUHS}-be05LBCDKq+UHm0T!l;F z8P!Flh_Sib+babkhfz`4MKsYJqS5z1F9o(odmqY<%B<9L;6Gi?8BHtdzQl9M(@;-2 zKaa(KyJ=!7RmYgZ1vU}`k#V0fTtX}a=2q4x_bgjg`9~vQzN%r>v<@_F*mukG%1TFioY-jH&xJHgyQfRm9>wU|vU0Q~imI10{UH{nW zY}*oD_WLDqC_nO`1q>(e*LD{|gB^xcNRT$KfG+NwiJiirb} zk!|%~0~u}wX1jHWcjl-%FWyN~tFM3$+u4~n+_e(jykiP+AXsq$4Sc4Ik(YgPL{_5C zS$d4~JUdNti_-9?)(LtJ*PFGbNzlJ=*M(^HlFv|Uk=l(<{$>TV5hsI7?2OG{*v&Jb zK3Vc&6vuZ&I4Ld8@OKB$B8F|ALtZc4xUb1%e&=}Dy!&XN=Z25VGr`%f`I&Fy#x+v& z9ISk;8-bHut{g%xEh@%DGLI=%b zH}hVF?7Lq4n~|g9LT-JNm5A&Q-kLvqvX#s+xcA|VnZNQjn^N9Xt=T26Z^83qzSpwkWwm|dHu{y?8=2Q^ z#y8{i*T35APa2v`Gz6-XG&{y(qI%R5LK)n1>X197aAK(}hFg5mgN}}5u?#PtZJA3* zNCN?9iRGY5f(h!V0$~4V4D)V?4FSa9_JfTgzP2c~x0krsmrx=G5!~5vUvF!;#DA!M zDNmuv{)-IxA6+~6TL6YQ3M6_=NPdE{*kC3w*598>d>T@9F{BM$KS9&TB4D=Gs@d&1 zVl@L;07SY^2#*J-d2Q-I*^grz^ZrRLbZ!ESjW{agDcaN~B|jr2oH$>N0O(vP7(yK0 zCgb=>4Szf45C5$TS63V>Bs^jwtvDO_MJN?pBt5|mgLk(waPrLPT%6ob5IEWD{2bsN zhQVwzV@kA0x1^b^j?;Pm@V(##RcsI*Dm-v@#tGCXn~cgc8{{*Od&v&$O6%e&=EA_M z`vB7t@fC`pfc|bwjfD}i@aNz%w138|7YxUZxCtFt`2TL4ALTz?pouQr9h?PuuA z`7>|>#`F)r=C5tRbvpV0-`a8n^csvr{g zlDtlBSDFV;5d-MO90RBRUxTg#FFe7<@M|rOz;+d{~O}>FJ}GW ze~%5gPTL>gJHG(~SujOs`vI&>aGmLIW{nyIEUDO*v3~}zWPjbl8Q&5Lf3wd}^95gU z0~&_akYxw%_l&@A_q$^aFbLbC+Q~UUf&F!t92&UyvLOeL`$Q`oE^fBzLjuW0h{FDBFL`+IaZ$jQ`O)9yxazCx07Moor>a z&kM{tV8;EGInwWB@mY*NE{;DNxc0~2AM*zTZO&Nd97Y8FUof^C^jj>36Ng`i{#t8d zCY$oidcYFEngC1SKc7u8#lX@6G&PUYfpz$M3n-DcnBG!Yg6|{^GpGQoiyr2jnK5R2 zb!l9o}g>TM7gMbCz4*mW1ruc_#if1xE zYg3!xUpD@ijsKUk{lDbc{xy&P=YxlT+4x^J{)as8KY0-RuX+5hdHg>%kG(qsr3nhX zboFW)M>s3uxcMSk9&8zM{5V$c?15AjRWonUqw(&_WvSCM6YC3QBj}OyG?~B%u6#)n zx_>Bf{EsA;|Mi|{Aw*Y{t|d;zN53W?89}Qt z_BFURPh}<$WSP@mvY-RS{nZ!19HCa;yn~a*a?**rUo9dYbci0jkYqO3`3pfhupd9H z{<<%3M$Y}FS?&||8?}rIiawz9zxt%V44pe(m9l|Uq%E96y}&AV{BAx&oYETCg##@Q z_39b{$F@5`p=6?dn)FT1PhhS`E6p+3IEoV>Q`f`zrHAw7Gq8*+@Ys?DL`qjNP&I; z0C~kK>H<>F+=v4Lb~T>|=*u7X7(pcy zP2^rS)B(}e$?`pWNmNNL4w`^W*PRj^K#z^H0#wzIVgM5(%GeSj5FSgtlNE@Dg}M6+ zw7X!z?eWAZF#_MqnmS0n-RPVH;T0t|jkmoA+Hdl@&t0{}V1y;Z!eU2?Zaz6DT{U)m zC;f;y7$@Xe*!5+SvduXI<>HjJe}30-XXX@Y>aBBJ9F@#7aDWIc#|HNEsdXk%OQs$6 zgp<^!Wra*LJ-k~$(+SlgfiH~h; zDah}p2^H8#yl`RxV)L|)elW`?VnO;jVk(1NS}Kz?nVw}bp=(2YK?oZ&R*2J4`6S?X zH<658m#^RrMRa`veI%LG{EsTN`g1!{SRRgi(7Ke@@7|Cj!hg}XXxn4E*2cksky7o9 z=9MDxUvaY7H`z9I?lWz5OchOn5b5AHvKzrlYZA;bII&xO(B#T$JNV>|58^Bw zfQ6~5513D=4(3h|-U0K2@(o4}uapkMFGAPaOSXxE(PPO<%~Y{uYG;8T0+79jgu|<+ zbQHSD>tn~v6ap|uIDPL&X$eOmIf#`bYs@x>Ps3Xm#p=D5zO#W~1Jwo+vEVy(gCZ2P z5!U<`cl*ZgnYqY*I5mzbiQb7=4q(P6ueSMI57K&&oc6ZQ-UHOki)fFYz`qzJ@l_qc zsi6>CzAH^|^pV z$eozzdrM}GhyH`5kn7L92H>71Oe0hJ=-IUVnrp{8>ueW(2r}R+9fHgiBKD^?`_wv3 z0MW~X`jg6S>Zhy%4)!T_6Lo_g zB3zp}{HpYeSGCYk$dywG!ABMDj@czk zpY`>t6D{o`lLE3mrXFI`>H{**B#+N&wHvO~Q1v!y;> zU#KQ;Icj(GA~i{AOD8THaVS3u)rh|-n5dzZ(MgN5Hkj*TN|e0IGXS$_z^q0(Rz4B1 z`ugJ_l>=ocJHc-WZmIto$#5>y!Cc_SGgQKxzWUA4J=?ad!1`6ha{m$IM?q<3JE*em z*A?FzlM{@GfKV!R+kLN;Z&b;_UBvF+bwSqyFwd@b+M%IzYlX=b<=oRey#X9@u8WA9 zoS_HnG|*Ri-T5jN4IkSehXB}LG`y0)61?&$P?0Y2l?;f09eE2q#5oeLi%}hly;JVi z!8oHs!J!2OcWF)T4xgH??%h4o#Ww&gn7+@UJ!+)o7Z|}B{T6X7U(cR2h;8sVG@LcB z{>rk@dj)+f_4sCS=Kmg$62+sLpT5D;?E-rvs^9T+Wv(YRClCBxJ-Q*gQa1)Ci3awT za2)eR+vE>Nr@Sst$cDxqM!8Id-%;4CE;F@5W{t1=hy}V4XOulUQlWV?tt?h?z>r$b z`FZ`B$<937L!r+ci@-llbHq0QVC~?mnr&wJCTxs@JA%T*ST5&j=a!FgWv;Mb(CeXF zz2tbW#k57!5EI5>KY@Z->%p1z3OO6zPu2DDWG}BywuE=d5EX9-I8W!}lsn~tDXlaH zYzrn?C&}xOWUS{;5c}q1z*nf_`pj`sfal2Q$T*?^pNZIOVxxTUQ1nw2n)BSwvr^r} z7afF`qgy=>xr0}E4u>LR)#T5;)BKtkhO98xCAX?*Cf78pa;mVnxlWdA46`3S;$`fH4a#Z(aA7`0A z3rXVZR``?|D6|&#)_lL%SobM2iO4zAaqBVl)ofGal9HLXaY<30ZkB+!9WLK6n~^_8 zEi)gI+(36D*t^i!m9kjAC%V{|v~4~>q|G}029(YQ14);xsi}vwthD51_c2gmGV1PS zGoTn&HiwD>-ucZ$7C6>(LJ5IBX>rnrSicE zB%|Hmt6<|oo{Zq@C>oe@snBA3swb4>kji=AaO)H4mm7q8>;b~5weFW{E2ShcfRo4a zwBk8yF(e(edFO?CaD8?9{@8o9{r8G_hW$i5j%O){O0y-rix)jOYq^9>Eay$>u+Ua& zS=MT#0KS*EuDJBwQrC$QNVE>_N&7FE!cbX^euG%F)mxB5y=*|kTI5%^K zgnbzaRo*=t`n<K1DG!xY37ohKd!LU&;c;ez^nDMm;e5CCr&v!ps zpgH0VtZb`tBRVF0DSd+0_{*@8W+G?c6Pa@!8=Qasbc}!!S}lw{tw!C~fiDYZ6n7cI zXR-BIJ2Qfrta(IQX@QXmoUHGDL5geX?NbZV?1kdM^VOU5j zU5ZzrDLJ<4iK$i``0nf^!N+a31H#&$AabNg66iUk$7>ABVXgeSxQikO`3>q#+3;tskr2vpzPU3K_ampMG{#y61)mufKvC z^e0H2y*6GYUw*H0q7l8#9~o8o$Ims-~*bA4X8!RM0g%Hk;JssLyTHuPERFo;K*yDiu{;i z-Z{|cOk3IH3Z%i@oUN{hEep3pQ8_N2D1DoeQimLiiNG6r)0ws?(g0>l|YP9MM z;gl9Oxp(>JmFz7eX76vQk8HC8?T9%s6d82~2lytB%ew-drzh5WXl0;Ptrx7ViOum7 zdo7h{AJBwnk%rxuJf`Oh7RbG`4iG}ejlnr?veyRtgXU)>JLISCw=vm8`*ob8fWtc% z^yY5z3JAEzT$4%5KE8S-|LfC11wDlZzrN_8>EUXgh%Mv_&+L8wVO;cNjQ|tCJHX6m zoZ_KN@L41|%8o3? z-rPWIMQ{_`b>uRh6;F`onZObf~j$e~0lqQV4Z!7d3J&6+qc#$PY&YEM=dDf-f_hbP7ezM<3!^{JLM7DY3v% z+f(V8iG2bBopL)V#_brpjGN}@kle{kFQEW!AUpO#kY!{+T&yWbEj>}vPq9V zDzj%_ydR3Kb3M$hf(ncVf`>s%j8Gp!<=hr7d0fa6jSYdj%qxAbNSH9DQJHt&3+I z6_KJ$Tdt@ZezE^G(lvyZ26t}#t|9<(NI%9ia)A1)Xjvc>U`@U1hrBzdLn$-8VvSx1 zIetp|@y+ow*Op>|U>)jY&!FYd=K!}-)0c;6H8Sf(Y*5f-aCS!C#@i#n6L0;B`TnEP z4J}bse&k~R@B*~k?qYha*x_IoG-bF!RbkNowdbj3hx%)N=a!YQT><%%Xwz$l=Qk8v zBz42wNi^F!pJ2p}BvduzgztQl=uJ%(avB`@51ZBSY3HqQ1?Z~&CywkYg zNIl~f|1Gg7f70}|e#A0vVBzT$5w);3*`z`nUn)GgnE}iN=(h^pJOGVw`cAwI-7ck^l2vOY# z;v|r*>G0n;*JMY@a&5RyddXFuflSVH671&X#rf)Y15yJ-G@p!0n`f;ZCA(L*{she! zw3Tz?Cth0-(5}ywsJXxNF7-32N?aLo8x~eE!>F*^u_b!q*VzaO7^O-)4ib^O=g?1T zz8-i)*B&X^MiWap=2iG&iD@femYfw!Rm}%eMduZT)i1<>f{D1zF^4A*+KAL3`kRUY zJW}ljcd?=0kf-Js>b#yrruR!|p1jd-x>_^B-^4tnSfoEaWis_`Y?lFZU&x+D;{wBy zd4|ylB2cAz^CyUKpAI_=$eiv8;Yp$0;&34N1c)$euVA>R`(S{nFRSC}%_e>@Ep+;- z2zR%9^oAPS^7!WAy$h51$AhKK-a44MEpSrbL(mu=Z344nAQ&p}>s3!v(r}KLJ=BB3Z ztZHdiZmogZm&Sh|(|7)g=-I$g;4Lobk?jncvGOQ@V2E#LA?|8c^@YWRYhTm7SoU~Q z(ueiYYEdFGrm90$qX$uX#qsSnLBjWMEI`8;G6t$70EbSAFztiJ-ojFM9VqY5y=C4b zLV~vh#r6#9W(6@Z?_BQa4S<&B^sWLgzgl5pHDG4b`qrq)pLE zcoTOg^2xm{pCBB2P>_)|=g)WC^=5A^&EfLT4VmAwb}lO)3Px2$-$%uF!K z&#t`5P`@v8osZs#Xdsc^*Dt5eYBFiDBzPrjfrfQ>+p6w^>BD7~$ok8)-Oby|Qi@2R z#hSTq@9=??!F&@Rw2K;Oq*nHwxx1*blylKPc;!pB&DEC>nO?=BM{LD{Nq0Ys>Y+X# zXKgEv23Sji6;EzpYf9&?AM$-_7NqLT`v@Oi`yTaqTo}C3S83_IUTKzAxL$SI5$~R7 z!oS9EF4!db+Be2|tj3;A6T|stn_OW`n105#V{QrFG)&&-%KV~xJybNcVzWDwU;Q>T_Agsas2=wCT9uf2%XOfB2Ew0v__=mQAN5y759zf z$HP0aDn;8$k6nn)3Oj+SXo=3D`ZURJbIQYfTfD;-RD;FVGOs&VRc$mb#)A>S;j0*W{yGpq5>4CT%9zC)%I{<E$7C6NP8zjMO7wEd1*gRasA=UX+Xa0z`%i35t1Hb zhT#ifuqB!cSjrZJ9e=D5$GypR40DxSoN7tuvLT%z8~27_t56X|SAt+(2$PCYX;XWu zv^+g<3M3~xP{DI+=pG7?vr3>{w;i#h__sVC zN?}0N)%(YDXy$VwUG4|e2QgS20KP##W=65$!Swjrj1@qExA6a=h5Wyl&HF#Q5nYo+ z;sOCo2BG(|&?#5n4_o>heB$--7=q66Lli?foss-JSgYz-KsH%G!3W6In`5T_#G9v^pM-FX<9&Vvxy z&`uN-DTHgMuwlkv=MKOB1PRK6+_nCLq~u?29HqwQx%E$wN6DYnh%a?nXGWO)m+EHz z8HgMJO#04rPt*{KjDxN@nzWdJF%Y~$ujA>S+BwN)5i#yjTR%`^F$d@ga}`OtJy$E3 zZ1?(JwfD4$hZPjec`0%g?vvL_nO{1mj=p4rArrVUKHZbJ|CmF6`T15+W!w{bxusi^ zADb@T^m|-|ULGBZm%Hno>-Cj@=x#iMo;V9#(Elhi{6RJ7uqJRG^mwQdlc!0 zD$%l4P+rl#H_F|c1XcBcpVC%pAuMaoOeg%p0|x7@;>&ht)}w2WO6yh8f>6Ruy4(s! zsHOX>`p?mi_eMK};%HsG4}_mNzxDnk>~zSZl1O}NkZMWkF`zJVNE4YHkml)5mr5OY z#fdccLGGiR4QeLn#Fm5Qnb_(1`wDO4fFnXiQd8xkERkmpV}=RVMJl zEj72q5+yokJ0vm6ZfWvn)v?9=Z#~(GXugeqIOXo_!>YS6#BFJ1md;w&$yXkzjYO34<%#AlJz}jUE$c1YB8l7{c#48kKV@J~OTG=j$L}fBH7E3^ZK-1o z^gArmbtc1zXu(kgO4Sx}@_LEiR*1z*m&1z5rPv)~_bEFTuol`r0#44(gTIz7z$*I3 z$rp`9^K-axr0F64C+L)45@T=#3xe)(8bgt1z%E*|nM8>bn(6|IHK?;>03QHjKWom6 z_zRulcaImNfdeW_IAR`rdb3ocuJPY3Pmt;V+HQsa%@w|uEc|;5robIv39Z-J_|pb_ z(Lz{VUJ%$4{@ds)|3^N{3&7G~C-i)X&2I3480-a%84Fm6&9eI3n-d>$I2w#+U9^Jk zIF2%iFmh!!YA&cb$7#na#NFbJl2%(N zlH!^8Tpi156)if+kkm4e-)Y|N{lRA?iz<{qI*Fz%QB81RyrG(5m3B*NBni(p>Mk{9 zSicDq^?gu8d}3RFF*O?0vN{GoQcFJqhg6#yKW)8(Fa$_qIJS%L zA~AZ8U!XXhb+&im@~#FX_<{mIL5%QeWBd1|kn#OE=T27FA68}SMiQ8SI`@I?H~Ert z6nozbBknf^KbTY;(L$z6VK~m=?TstBL#;09M)_tBuARN~+8i+}KW#X%&+T0{FV)Yv zs`iPS&oVc8pTF+lBn=h?gY%IMv^sg2=zsod9h!7xx2TH(p?0k#S~la28IV+Eeov#j z1B;V$Kk6(HV#L`CWX~Rv_B14^V5-9^A-8PufI5HTWA#{O$6+UNrf>OoY76dEi8y<* znHKGmH_@!p>~=mA94c9u8az3zKRyuB&%S+BHun zw?H?{z2V>%nyIM90o%tIld9x{9>kbIZIBz z9nU*{{X*0^qcz9onoFeJ8SDoN_AXDOx-tSvY$}?eQqSj6J7QupDSeD*8{V$WhU347 zD7{GIj7|OEbg$)O0iok1bkwbM@v)$^L9t*~zZ)Vv7?yk2@|IyIZIYwv_d;Ux z>111S9b~m>!zVK?m6Vy;qd`B!{F*xxOZ1cm_WcoGR`C~oeS9BVaon4m;${PIE$2AU zyn7LyNxY*C%**7I-VmZ+%5NF1x6SW|jh=oHGCM9V9f{ZOA*I@UXq|JW;av{8gs_V7 z1?4#PRr8C+-J8e;vX@$N3#Rf3Xdc+OFim8-Zl^TewS z2i7HKF~=FRtXd9WqfuW8Qx}eiEUt-8Q;~po18P_fdmTd?ff>8vxFN3Y2SscWc1*>3 z=>e}vZF7`&hNPrYD;VN;l?>(e_2vsWxNBJe$Mxx#2l|J$)_(cC6J36u;A|-{ zRdbuD^J6EQw0*zVL2hfNt>)&fb%^C%(rH?)Hm*uV#dG zYDsp$XVmB1<&%p37;+`d4Z-VmO0}G2FF<$=(w>?z)+z15^HYG_aX`u)6u%sgjWb>F z12(Cp&JWXAU4x49x`vvsJdRdk@zQ~hU&M4WF!@9)QpOq|gfnHK5eB2v{hUdfd~c-Q zo_r$ZPRrgOi5yF>$o7(YIC_x6UCCW)F+wIYUhn?on89H)&UNZdyA2)8h7US_$7SFG zRc%4fAbe-eTe!+ZF-a#XJ*dEz&Uh@##(u>>e_uM?EGpINiv;*}DJFo)#s;OT&Cdjg z@%-THeO$8tzB#RSGbW+&)OEJRMz>CWw-rjxNUUrx%JGoaU?JzeUjvhm^JK1GaJLu# zT)5U=_uW)@T9bgT<*;g_owq#YT5`y{g^VlX>+d(~EGA2q7ro=fYpmONIy{0m0d1J* zOt=}=|4Zv4r0@Qdbg!M_fMK%%wkvM~{wY_{{9;^{xN@|1}6BsV1)toy_A zmR-B^VJekq(NCPMI(5n8Q8pzObqf3RQrdO){gN--b~P2}=Wg(4E%e<#1>as-`7z)! z>q;Or|58GnR;um=MzK0-5)at^J@41Xczd2~{85~tW1)0i#7=`_md&ZmyH4id9pUbV z^Rk(DRmt3%>9x}2>tkhpLKkhtFzY~&qNB?(-jGC1a&Iq-fVa~k;vR@I$H{p|_SS+{CL& zWOJ*NV1l>AD_&*g@l(Uz)LJ8}sYXt14qvEFt#fm~#@9HUPgT9AVurdgX`tJts$!dU z_3qVZu32@8mazAQWU_107XhhNMVRvRuv>+1skJV3=aa_r+GK0wmQMO}v!XcKr#7k1 z(OhZr)Q+35lUs^c@0M$*c>t$vF5vEL~(nj*TUH{!OHo zLbgG@NIF$!e5CeIP?10KM{{PWd>(z;D@Mtom8+9BI_#f3iMq|Mct0QSJ}5d)r%oRm z+Oys*F711F8BklDuJo32?Rl->HJ@B+QEW*k6lc#Dsm$Zw!0hu?1~FOO|Aj%;Rgch7 zod3S!%v3$Y_Dr&#G^_J{o3lecSz31rQv2)CXBq6T#UEbi+IeuCGr+WbZcwy-Zi9#H zN}S#uZAx=>ExMB$LAAWR=TY(EO233i0IF5YIuT|m)0CN{du4)dq?#6 zYw<8gG)2XnE@A_^Ko74(AJy_6dn6?#1}NuOdy~d>JSd6N;&JZ0G;G?8g!qdj9i@MC zn2+g;V-{)AYUT*%u72$rxyo4RpRH;__Vp`(Z>)?qy7@4)Q~sFpGIRCLg*P10MN(H^ zx%6T$>^RcWG}sv_t!14f6!m;~>qWX}h@en+T91>$#qv%WsH7i;bK}sy`f#&6 zSl+mP*g<&4=3ui@O_uwyolpX&Y*u**1a_^TW8_s$?QkWQx3sD6j)}&b@{ITpGx1~L z6O;vTY%(nn{Gy?n4L1OH;y(4O8+Lx9F7k9{s1}WFadfCw^U#lcCE77YqtPjW-&VC; zNZ~$6Ggz^IHEPhEd8;e^Wn`$#Gd7^39z);_1#aIbiDjdP@De~=&(%$5J0_UlooN2v z>;!L;DhoV(rq#%9LwC7(y<@SqB!k2zQI`tOC?*>FWOzffQ}lq)=j}s^)7MJb8|&<+&cwqGz5PnF&vPie@NM*tNZVu z(a*%Einsu=b60?br~n{6%uzo`*>w*Cs3t1CmaNk82^?>o&3$&BC`m8ID2Y$FC^bxp@}iDR~zE9lkvNB52#4remz zx5u)F@wfFRy{_A6w79v8Z(CGFTgs1riDB3ocF$hmj~C!h`qBD$+)?OJSsP0*Wsq?Vb{K{ z-1O|8+GYf5t?TbHERXv0nPZ> z`)_&1V-c;htizRu7|X=Z$V4{lxW0J1-p<)+1)=DA(+b8GqP+b!)vCS-9xjdJdoJz&R1h4 z7v$%Hx>+1LpEsUf>mJ3aec7B9_B}V~-&5r^40{<)q)$!|gk)54&Onz+Mkq&8wQGIn z8Bta46Y~cYXUBI$cIj-YnMjzJ2ZzKfKkfKIntgj-n z4PQnDr+eAQJ%7n~^OZasXZ+?6Aj*{>o;|c-C2gtH_e^I{-v|11CRB5{*p1Ih74BPr zpJv(1j=LOlnc3Ch!W7duC%V8-X|X=dWYscZ`9S9i5lVD`n@BmIaQRXsnUK*o#R=t3 z*Jb-YP1H?0(K`mJo@R5`hR_me4JaK_mJnZnawrp4zi} z$}YwsPFXT<#0eT*+_ZeTCV@`pxF{eWqmZJbGehZ3i}%G> zI}wz5HyRx&0$46^%oN;waiZ88?unZ|^?6msRphKX-9wpk+49`RybMadZaTGxjo{h^ zS7wJTPQ>~pe8~Mab!-9Cj6y`IJKi)%Q)x|NGMW;uS=0|1OyprTuTJ-p!2qUC5HB*! zJ3LKRq14dbpBr1R#{YT~PhgLYO=YlPup*=>`3b^4tvoY? zFqe1oRsgt7KJ?2YyEty+9B0~j6ym$8v#^HS;*fD5P2u~-x-{X*(op-XO{zMZ5%zd> z>mF~+?P56#lE6n~zWbdHca<8{Ejizbs6Lkm$9lg)E9B@py$WMtx1#AfEY*pSNwq)s zhQ6QW&l%Pk%sUnZ$Qf>voZ-9&Q!=-?QEAD&8e%RK&*dH#-n;LE**+{ZNGx~s{yaYM zIPR+b4rfB|h00KtNLOS;M`nRMx9hFLh}6_HQBjd?6B5n#_zjQs+b!&c3r3)EkPn%Z z&*-*eTcS@wV#)Pe{UyEy?`nGUL3hSz#AN^m^(InCUcic;V+v1rLb@p;AcmVn)WXhd z(+se2KjtQ9T0YcV&#MNjtAN8QeQV+QbhC>?0~&fB4Yyb= zy}CFe9JEhr*$LWR+%%4y8v!N59o?}FgI^P($qJH*&3G_4*|Grt1cd!P0qw*M^W~GX z5XP>Ds9@aLsJ%ejX+Y|v#)sNiUiYh|fFADU*udcC8DzAA^A03FGscQhp*(?1$xvQ1e!khL;@%-%l$on z`p@{eI_{dH*J{+toJ@)akwJIShBPqQ;&oEC<;O1w^AywlVb zJ;W(jC6R4M(`JJ&QFxy&aE`N2NMnI*992VoZ0GT#7uVK9=v+qEyhitvDGu^>!OcfJ zKS4Csbpel&5#PbV5+cE_7{#YCc$w|olsPF#Pkw1|aNzV_Ug{zTIy>fZ{9?t@iGk0V zgCoB2p)8N_&Z=4{vnF1oSws8mntvp?663hd6hqw({pdaEq39nKF+q}CzH;@Mxh3DxqzGaA2c#8q?HP(v&L?B}tRE;P2;VFEoFF)!$+a9( z!g8=My&L2xS|qXz(KGNc+O4XHx#qZ#=k*Ufm%;RQsQ$aH9j|@O1h6_j zAYpoPrp5PSpUr($dN&IR%3dyI`mCv}@El{4lv)uA_2+JX1yjA8^y+=kgfvxvk5H)` zym~~Ph)OtXb*6uI&vz7Y(>6R4>vN_KJ@E`qliL|TQCxI3p}djdx-i4miWiiMtT3tX zQF9+){z!Tm+8_leN$DMi00RuT)|{hN{F4(JJ{fdY+f{g7oP=p&wvPKHNP}YbI-Rm@5;8wg<0hG#=ItsUb8FdzDCRbROW4aI zKc+?IL@akV=6mU7@8Vt;#0A!~XWMxi-=z?>18R0V0GU+*Z5nzQ16uEO%`xB|9`7(% z6xX(xe(pCF%D$SMmow+MSCdc)P`AFX!{FOOs)Go4>F!Ov7tFHvEHvZaM15XOF3+-WQ+L*fbFEO zGamwjTvJFt4#;>fBYem^f$fzW;d9)v7ij3JT&P=b_(Yf}v89_HnhO!bQ)L7}*93uT z&k87pve%C_kS8UE{E;)63PoIIgA14C%cS|B5p99+Q`wX}Y*y=_p3PX|;CE~+>zn7` z{;cOAz3T!mdq(mvyb1Ed#_$r@L~E?l*}CN7DM)k zw~lYV_K6;E1{1rAp!d-L6hf<@) zhMi3GKX&>`^9tK3P`e5dLzJi6gv?Ri!*eO%NCW&AJMHh1eiaIeEQ^#ZqXTbe8HYvE zn9g*@>=s7&bLuQ+Tmqk7zxa%lmZR=R=@8K3_eDbd2|h`NSrK{A7%-DNxNBA?e>Qc4 zHlWa(Ijn>ZvnkGsuI_X%A4=-3tb1N^E#t$L81YjFTG-3Hx~FQ2FN&jd+kL3Q1w*w) z`L>szUk$4=A{bt#6@i&RF)FQf>gcM1k`xii=Rl}!Oqg8V}U!cB#4k>MG9YYX%&)hOjSAdM8U{OI)98fDaV{|tJR%(+> zl3zQz%LWfi<#z35en7~HE;?K`r94>YgKrD8i8;6W=1v7i8%l6o(+gprXR7U5Pfv~1 zsxIW_NgI2IVkBr25|&iRVQeeBZ+^F{&F6J9IaX)Jt25+FImWTA-e0$MZ0wXTAxy`b zGQr|wji+zQ&E!L4vxw^zPr=$k;`pE;KfC0sI z^(qZ>-n{E5{tjX{{|pdURXlX*=(D_%o?wWd)roA(_-8P^8hJr2(aC=OK!!)BA!|M} zIK@Pp=HioPrqo8CM%|b0)UdE#x~1%lX`*IH-ll0PCHD4Zw@yW5Kljvc#AIzOr#KT87&8?+F^ zCA)X(%7#&OEQTdpcth3nlm~Q^7VR8ulet-pv3J z2xq)4#hvaeRRmeTq;53%-9)DIb3Y+MO?kvI*yp=v=8)m}U5W8mT$4*7A1}mddn}>W zRVKe7Yay4z?Aztm9XlNx7OhJ&o}#b73zhQanJ4B`)ZViX4zOy*Pv0c!xZ;`|qYoT6 zvaHt&>EH2e-m%Yxa5uDTrn)#uVLGgj-Z#R|1^qP;Y#D4{5er#ob*Z^u3T-4GJxDGs zxtv|mzLITEQS7l}***EzU30boD8|rU$T+3pL!g-eR#Fs_4Woj8M5lWm6pD{Y2B_TE zz05T+9`#fSS&v~-fm?f`I z2`vyH1_EjE3p;?OBr`g}%L*St?1&=-Sf?oWZd<0SXn095azggDjc0Oj<+Gn4OGAk< z34J*!GBeR~@#eLww`-iPuH6N+IoJLqp}B?l{f7X0hrb_pB2dXZBBDyI4T$3_R1Rr~ z)p6}@j<*?pUftSiUq8R-RiZ^Y(hFoe$7vMSw!hq~3vj?vLv zTk16B$lxa^^pND?Y|pR>+T{jrcyBpoL*pA{}VC|DRW&4a#Y~vE{fEe@G9TS8=7Yz0pA89p=IvDt_C+kY@ zc`+;J#VK*d`6R2Gq)DphR>}%cMwdh+H63j63HT_R92Rs0Z_6|0XB&{kCC0@*;U?i@ z%@!mP9*z5zI4qt1d=6cj-ejZ1#7)rFuK!GqFvlk&Fo1<`Tvf{G1Mdu5S`5in=P8oJ2+UtD zn?jI$H%hZ4Yj^rU5|Gp-_4_)iMs;*c)ajE(JIYaDnYQ`++w0d+5r-Sxh6=i(`RG1fef$`f(JXo@_iLk}=W6O@ zGX!>>09|Bq8w)jOZuJKn4cb5Tbe`&z`7t}NQlMTlA9saR+M~}`m14Hq|B%DRk*yP_ zy+{nbV==We3IrjUk6 z3sHp^+K3@0sa|G1CIUGq(SMaQsab=JTW8hyq+6nAdp28{Xo2nzrG~242F@@yrX}Pr z#Ro;#*Yr#3vZ7)b)|>7i-F&BrfStO%g5?th`93%5y1z`(99P!%ow^&R!l&u}uBZ~B z4ki-Jbsr0AXL?_1tFwo9S6L2PnU%lHM_nW(!!i1c`Vp`XeN2t1na7pjeP1;`jNpau z%X#L-OA|I5*!K-Y?+T|qulsJ7R~hfAec}-i2*>d(h6m7=th`&azrSnqv74eSUn&|T z-VF+R?Ly)!Ljl1W9#VyV@KWwSYySx%nX={IIlc(V)C+ zILoFJ>@GF|waxF(qmAy7^AgY=y&g>6+f!G*>fuAGd}wgjpk}x#F9|1#IZ70s;cS(a zU!8L5Ua>P3ka)FOFC$abgt-Ab4_Y{DRNLBiJ+hctW^HkJu-Q*215u7BfNXGBe1~1% zgrZ}y9!RY-p2_piNuspiM^XIXXJQ*(`CV#NDHdTwH>qDo!Xex>f>a(O7%Nl;P~Y zT-o$g^-kNyIBoNB!CKbV-sdx2E1CHLN&t_}Z2EFU{dGd{ow+P}9JIthYWi%H`kl0U zuGd3|7o3ZK8IthokwZkYIYDaKVQF#%M?RmJH2K1AbmhR+-a^r=%hQ>d!K}So&jjmB z^?V|ZeZ3P`Cb@sy{QB96)aX_+0B!OzIsi!zmj5(n`&$&Z|4Ji5|6 zoYgI)Vs6fv6`;OqtR1V1y|I^8Has4ad^)x|^8NvHVE}xQLYKE}Jr`F06C?vBpANA@ zaaEHfRL>Mas^fm_7DJapHUP#SqF)k$8aQF}697^$p8@`D!ittodhgr{!Vpg-A=`MC zVc9##cc#>PSiZ9>O^RxSstRR`c~1JNIOw6+d4hsA_X%QbS1Z#lp0y%Ka4L?4L~)Bx zdQX(NJhVG5h_9zI=zbW~_czY3Og~y5-%Pa46OnkN-DeN|1f=qCq&gUd7*|w1Bl&Z5 z?;~MB`DNvh=eg6E5$2~Jt8WZkyb}BHyn6bR-{WE9ll|UWOVr?dw7Y>IoT?X`(xe6G zyoSF6owS$r>YVkfMg|xcm*kvo47iXPOm2$K5?z-L7cRKfI8%#5)8Iv7ij6lA=&yDM zyVrXiDr`J13NmcJ4Y9)=;JMu(85ynum!dIov%g?I{$9y^LMR#D(=0j#C zn?%)xTLl}FmQ^vOm7j@TBpCLuu5daMMy4JzHHw)L3*B7LhlUS_cY>hp?ohBgL&Wv3JTXUy~mf{wcpHo}0n@ivmP-B{WRbL#X z0(H2x$8XdSioj9+0m!x{4*!Q85?R4nkBRTUo*)=c9+*(Ruj3EI6^u}mEREDu6fW7+ z*R*%{ob++!N3TLKJ=EOHv@&e*?Go4fw>+sCMmikRBnza$x;_f!?B?ntoO6tYU9|5l zU7m^K$+x>oU0d<&6+?cUr8Y^o`iD1&sP06`X*aX2bQ2<8Kt6s^_v@FDnM;cm`p&k6 z(mvfn24OtSW#8&K~-(M(k9cuJ*op#2174rCYPt&1E7R=GL_+3E^SplVjzf zQNQS89eI3lo!;?oVBdLborO)9op(Fk22gAB1B{a7NoTHw&Z>RlO_S};sv5zgYbpiSKAK%JN;tSiWk9uB8 z67pN|lPUF9RdXUDCw`Q!#YJR1u0&WrGv8K}-quJZE4Eiv2a!-1wX!_;YsSuoRAi4< z@?-%%m7_AN8#OF?*Wb*nzR)Q6%$j6=R|>Ff&lC_IM=1RVu5v*0a){Zo9J}``Pqd%% zkGcl$o_--p-OF##3h3-wJ9OYqf)IoimO}0mGPU$MIWU2^Sxc#mLW|~6!xk_VmJDiLsi0~E_B>#N%5XYf z_KD!(UN;9iGC6cQRQ<8nSVfwmbg310BjJoPj_BK~BV@ej6YLXE_MwR%Z8T>a{((~& zsLrG>Zx*=Ya;YxsM0xvfjrSL!8=SaG>xb@5B9wVWhVr;c`em@C*MAOP$7y}@KE;%P zntEE)g&}VGj%kLL%$zXMB>&JwGGW_Zx*uHmu4CS2Y0-Vz=X8gXSG!El0X7|Bw(PEm z{I%JORb>SPR+n@nc8#quV1i^UafzpRGbJ-c6k`ea~RKBGq;SYW!HX^q&h#qmPbtD6fR3x2kR8_1xN`@s9UGY zE`I_glUC@eyi<60qThca)$1CdT@1Jr6ZC@BOdQ!uu9H;GFxJnNJ%;z|=!JE%5Pc}Y zO|AZcgTxSoB$43K=!$?2B}}r}0om#@MZ4o*)`x&%f_guyfem zkZj=dELdApGr2WQE5K!w^1$bGY|rJh#_`myv-D$r4C$`;T5ztJy*&_Av_vLOD_S}L zKei{%?ZqHEcjxt;W#KAl0aEN?AD%YtY3XJTT#GzH3k4r!6Z=Eprvv&rvJY&=uluw% z_vDNCIlzE*3`smivyDSv0fg|`D*02u9WJ|;&tlJ~Ri@MoODX|@%`hV9bG_;nRtMDE zFBl~2DIW?4mOpA2$v|xGvC;}?jT!2I!rQTC+!dohrfgze?3O^X&c*o1#*@01#Z2C= zYVn%T6BvKMQpfO)%I!y{a@37ChyH0IMk4vDd586B3#~-oq_0JT{2zOfJ*j$H&%ssK z`~^k=(L@!$Z=*j)Yfjs;m6ZeKGDxSMj+GRNIdOp#{ZV3*SxyRNdwk2Bs;88(-r|ix zQwMq-^&H8fD@f%2bWbO2!fJAEf%FbdIs5j9_s4%`>Ag?-Y*-jXrks#>JkxsEKbjLS$t>WlQ3Uk;udB?u*P(zN>Xz^0twul+^P z?45~$-8sU#a3Q!!?&TOZ)H>_3%&Twp$X$j2<_sB5UPq#2u2@?m#rBxnM+c0yIRqzB z@A5V0HuJWWg^wECx$a$#a&(c!#pXjbRGq%z%8h6NUm(2q5e{xqA{Rz-Wnw%h5Nuow z(CsI&yY}vmXGz4gfK6ifQLk^csSm!e%U@-^9!YxBuj@`)A6&R(O2IL^on)x691&Qk zD@<36j_QjAa!NpFg6 zXkB^erKWiDwI&qL_q2(@99_`-$AO?Lrmh|T8(VWkmnU~2JkmitAIS-uYA<+C!R#t6 z`tY&+^togF7-6hAS0%~h=~Hz1HO=?XvWUq}R|AxL>=j~(_?Q%1rZRGOFr>9DHBM4q zJvFWb^#L;G(L2~+P$pZ5=a+p9c@yVEZ?do-bRbHpOld`#4F%t2`fAKvF-!v|LSUXd zF|sJH9W0#VqrV{0XZ^u9v0Qsl*oD^aSGcyJbK=O;01mA#q0t(#^)dT&se|Ub)Cmhe z3Z(8FS4{)NEc0r!58B6Fid0nvZ_NEfQL=-qj{Ey_SPmZ zHNC*V!3GPJOn4N9&$D0oVrx$J4u|BVT?}|EkIOE=j{6f(-rjxj_lhJj8!T1u_|IGaapgfZDa}-*BavGw=LatY(z{ zu_~t_C!d3YKPKc@YAry?4n@t|yqd^#B{Tzzk0yNWkAFw6MB+o4!L{Fq5NKAzpuw%> zrttE9s-*|9Cdtofg*pY_Lzu(dsaC?GL??Cr$64 zYsFc9hn>GUK4#DLoi>DD=%N6Zc!W>-3p_y){K|sQc*?SA-O3_?5mj7GZ5`YzQen6e zNoTK9LVnQ4w@G*JhE31xnr$lWb8hPU@F};fDB;`PwYK(|6C)T?%OOmeO)q3fiHea| z`g7Gyl!^^{eK$s>U5%Zkr|Wnq5~0fSz&cb~t*OvRnVW4T)#s4p_1zC`^SG_j^i zv;2VY0#mjh{22T!1TmhBG*Du-7fftkv2!b+Q^^WyFVlfz`ot+c^)GRJ@}G$zM9j+ori_^ox0~$C`hRZ6c$iUPB=0Sl^j^Og28fbSh~UUm6kRB$qFRYI zejjnxAa*ncZ>xv*6PE|21cbfM=lW;K`d^S6{_hRKfAx12#nYC0nWOPoNQbM=2c%sw z>|!v;8d1`Z!^fYV?9WPSwa)viN+9a2%#y8jPhb!t{Ha0m=BlGF8ZP=5(%loH#oqyW z=GO@mHkgOI_H;a)T^OkmdoVk`Y>0n>Re|bDGh3 zDo|yw^EkL-3zX@8wWY#==O`)Ft*gB+mwSNN=t)l?UXTd1P|sg=7}7CvP|~p!VzazP z*#*A}-eD;dc}{f%w;c&e!#A^!j@HSZzMrN$Mr2eGA342V+xfv~RYuaPTR2Q{uD1eD z8WBpftWHwMF$b2FNg=y|f*t6cc!a^-8_OafT-Drsk!09!hbV+Qq2^AQPV&&r78$vi znzCmCby+=J`MmA{qB=SbW6$|Hym;eNA6t`gkOE^{N@)Eq?RRBEW5USDFhZKJYu9#UZN(wFTn}fKN>Pr+*s0fSk443o6PI(=@L1BW3WJTu(yJWiAl>`ayDr!aogdQfi7oy?8u4he5G z=WyTC-R5^eZ#C35!m<5!j=DBq1JCe9y?Nq4fOLJ})?G3^K@94c1KRMI$Eel52t25k z;Q>R15>ITP9GKq_%R7+}t6k~f;P~_Bz7#2+j_gSoU#6snAz4c((YK+pVMHGuUvL?l zw)i6x-HVVhc?hrinO$_jiW0z;zgzXSPLim%FqoV5ZIC@Xnavti%30^m4}qexbOcCo zU&O_2l)opQEdPQ!YHUR*m0m@{A(oZfM1C~FiP=Z6RG=xR-|yhvNRovbZv3{s{yUbX zpMfN3?OrawfkA3#Ee0y@K(4 z;Q&@ys*#(uzG9$aCP|D-)F@+K0lf#$w-!#5C2XbRFN@9%8NKbj%&iqhh1PW^uCK6fAa%RPxF^h=^U z-48jx-{-Hza6D0ij?#URs$`uhDbM;cOBeR7omqRmeNk*BCoL2xKct7rvvTy&WhWqL z$}+l4XF;LBVlw7(3#{r8ldk|~e|j+#>wr6(1?n%A!ql2JV}F3N%1SEX8g;k|Z zz7@q*B8eMwKRs?NG$TrMa)(m3nN_0SsB*?4O4Kq%kwq+|#&8hVTn=3iO}$Uw!F!jE zHn-(WAl}Tb#%P&PuE|?=5u=80h&TcL1^r`W1eT+JMi|m;ZdKmd_h^n}f!|E2-vXow zss;fppUWM8o$G&0k6QO{V4@>|U`jk=stj^KK6VKXy!4=aM=aDS{~~zf6_S2#6`B=B~iRa3O{PNKJbn$)%W z*RX>B6Hro#U{xcU=CRd_&#eeVsEpS^*I!6DXS^LZf(KEg2rhxvt=d1Up8wAGe<${B z)%kbx?d@LB+v{`5o8G-~Da3GmP~!BT1;xLA|F6U){A(gf1;{N)#OFo>hlrj%eyU8D z=8RMAfhv%a&{ll-7xIjI=`YXx*zwTPBdZ~>xyRMh;_3nZvVx+uQG;ZGZf@9(fFv() za5;>5BZam76#Iu{!=D+~FZumU{6W(3CjNy!lnt_&r3V@ct4sB2zx|km9|OI_+gb&Z_FvU15vZ5X zd?ZF^o>GXV@ibPK*D?FSI+DfWnKJOYy~Z-e!EK1_PJ5WbOnIhbiwXpE0<{q2ggm10 zlV9mHSQ>PHu{$BA}3K{yH&DgU=Ud`fQ{-IeGAjyW_aJN164- z6U+m-xhEmJZ;5_K;RljMaD76Ak9_Yg^@Cb`L}D6xQ=!#;P@U_wFVCD(s3@GAvq>E3 z9xAgo{&MLyP2JhaU{yt~Tk%nY3IY8iy^iEns-8SbnpSR5pfMQ|$=2}B_S!8qmXU2b z{8Bx*@lNbAdSje#svTRIHh9kURk--K2IKzcdojPDW+4eekM9gG70NB?iaiI$pDx0V z4mnPGU=+UsIj#Ug8Ll#1OOh`}9h+y(FD*OBv9QACSa<(ILfPH9)m%@NenT-Mu`l6x z_tR($a_Y3hXU%6UYe^T2*>%M9j3V^(%8MTyS}VHq#=2C006vK_MEs1FHj|@M`mXfN z7cSSleBI&a7Z*g}0@J-4xmC@&B$zr(w$Hb7Prk8)u{~|>l3lWg)LZ``=8c)8Ycrqa ztg4v_#wPZgWe-j5bHaE2kvlsn2mvoKgFzrNT%H1)u>VGR{K-1f`OAX_0u#lM*Pn|<1*#l zAbW^4tS=i}pU<9~_6GPZ7SBk*jAo)qo1XYo`fIoACYoPZX+4FVvmm6T5DY$?uu6W1 zVlZqkkX7@6DcqY56{RuaX#}^Uu~Vo7O=*rMmVbMyCz(kT0G%c>zaSE5!1=;WBQ}E6 zzq2@uxjYV#Wv_p(>)4@!?m46-g_a)98MIFAPc4Yu5GCUn@}DHr2hbM84C4F2qh6zM zBdzU10Jo}2QBz7S6-SYVDrpu9^9Rj&CJO8BxB=f2SOWTUNCpSW;FdjyG1xwsuIHgShgc3LXDq6d%dY zV0*LsavNLD(RW9Q4V{09p z`=!?b2)x7#+L^C<9B*&%_-xj@PEzN;2AdFru1Zb93Xdu59Okam_NH8xF)x|5Z8?Dp zCy^r(TCwt6zyaiUW0P?ty6tZ^xkFu*4pnjX>Pg9`*|)bxB<+)|bXK@FQ7Tt=$Sr@X z_{yuV%n;2v=-+jGSI%;Q@MXj&+kw*(Ah*xiTbON7(8XU!yeS84uskXbsQ>oI=nfw7TcByn1(vdl`o69%=LQXJ zUG>4IQj8>&@-JFU0bbgb&yA=XX3qE@|47p! z)W%AV%@QCH2_D%n$Y8aD4=cAf7ztVSiAVyt0b%GK9f%F;^kLb zVC6@a#Li*37|9>fSR0`CE8RfAsMt-59#1mFF>L_~DX&w-7=BB1)PNVVIB029yp$i{ z9L425*GmxOd_Q#{U_w(hTgKN^rw|7NSbwdLqmNbMvn>^zQ~eCE!w|VDKb<} zJ06faJJc17`<-e!9J-mpJnm=gLD{}g-W*1h4bAL4=qR5P1}c3@Eq6`bnF4o&d9tq% z!|jNeQ*zg;xm{s@?yH{ws@*>|pGTa_*d|*(_YohH3Zw}&b~QzBvtfDR_wgtWLTug} zyy))z3ZZzp+BIc0R*caXSwgbG#b-?oTzB`(`ih(*g-q2J1<+AuIjhYkl-b(8dcy#) zSn6oSv~YXhvKB@;i__P|S2q6J`dGFamdgYml@Q`@<_`SwiLIrG&CF#Pf#c zKO9;A|DZv!Jgr~l7f^Zl0-(`7(ShQn8(9fy$$>ftIHa4(taM1i=Zild{U0%T*XL5w zEd2|U)LxC{5ybzHmoSLTyW4$!rQCAH7%LgYSedO}=gX@;mGtJj{!CvK#;KtY8p`vx zbo&iu1|My2OQIYAWwu$qZ_)zH;tidH%5(<)gyX)6jOMjUwlAn6^}2ONqP|K{*W_ee z8FWfChOBT}pY541TV(T0-7t;kDc1N6mn7dTjzvXRXF=6OmQ zy=s?)4oXK{o-I9V3lw_;F7$`&H_O7>53ieG7GHQo|Ngb78j!WIHo( zi|QG^Gh0M{+bBjU5!s)I-$9T4LglGiMTK_=#1Fe<>49g$sfVr{7LYTr!SCT}zu;2m zcwA_%RW#2U<}+=*!WgWcMesLd~r7?*Rbv_PTOag;v-wQiu+#gYhAK;a~3?hSspBDFmX!M0bVdX@ZxA-4j9%7 zx6F(PSwwN(kMVlYi5#3tW^EB>?jtyhxsFvgX)v~3sep9w>UOpBcbo}^#LJzL8m`Q* z+L4HX0*RTHc`*x&R0M~Y#S?@5rG6ifq$4LH`sQWY)t_(6U zQeN>tP?9&Tux`gJ1%}#VEi6Iyj7N32!~CDW&cao!xd{*0jn=xc#N! zVdKen!}Rw)yT2AAf7zoW`QD9FKf(4}RlUKt4V~9s)5eRk5Cd$+9n?ha9rY#Vt*e3l zVv5r22@aZIdFYgNUgUPQcBK9f4xbqzN-$DdiMyKn%6;lLVW!Y%JwC`5q@l$7E?#y$ zT{dfITy0jl?&*NFAE$mL_T<5T)qy%AD$Fr$;DKDHIe#v#HQw-!V{+hY$fr*KJ}!Ov z&9no%joLXeX)r*kSYO6^`wx`XFi@X{yXbApo27-tz87NvWX-Xfa#g=*6tz{8Mj846 zbUWMaWMO2qVqyp#<8t;R_qag@9a*od&Z;)h>)H57smQ9HXoc#hR&7UP{CH+=7+JV% zNTd3N5Ut!A9@<>#@*YCEetMi);`#6lI|nD$kO|<3>}KpvXg$Ag57^a2Af_Aitk1#$ zPS{vzE1+9^^WA*|Uc*S$Kh5lI1+&SS_UxTW!WG{_6L{Y`9Eofs^H$rJKBDeVC+reK zl9f(ez5OKFRs58Qh_3D5x_`bA4G8*)-Xp*j8Q-z$|FfU3K}4d!l22`UAL^jQ-J{6% z7D9806y&7CB7Yv_r zFH~9@f`u*^{1ct`?__n-zlu>p#g=WT*T`E*H6v9oR zCfo1Z-!5Q&*%y`YTMeH+ZSjqwRHoAiIx;{+bjmwuH3t6vvMo;!?{nn#HV9iKty`(33oVnzo(jRGyTjR_1LPhdlcEBDfW0{tTUr`MNo#rByLpNk{Y1hCWpaqfjQmOs<-C=^9SQd)nkbC4QZwRC$_fS+>i(60vyqC7OLjLoBD-$sFH{7FzW&x{;O-!sNu5=UT?f8NwEmLx#* z7cdKI-L9+3)OvE%3BJ6iC}r(we_wgp8=URcyX8mgk3CBB{BvgJ{<#6T4yOb>)WrOJ z{bOxlIYD>)ey+;B{2*@Cbg)?w8_7lX=(pR;l1NUg<7=)F?n4Yp1s~N@J|EdlU$Y(_ zk#UC!gZT5s4-UV*Z|wV;x>fl1B(cO8@;#zIx29`1Seq~h8Lp@{?aDRVzr8)tIbE8}9fImmN6uB(OHmzVmH1_NYk1tq*G#l(GbE*xM7;_n zX8yJmJI>e?uew}J;l|r$#IBQj1U1|D#WtupLyafO0k`kvuN6NGbeF`=hXwb*-cr&} zaPaM42e~d2`~sCa-WWdmhE~wtnpU(YZsb?To&k!enEl1jo{_J{hY?wC*A>nc0{Ilo zd%i)~xa4+Jt0tfCOpajy)+UIZT0b9$S*+@JG!!k=mWpr#y~?w6qdp|1JsqPL5nOkw z&jHw*M$8o&cspUSXL?~Ok@}iPeQDPffx0H3U!OlaO^nEiqoPX2RuJ+ZWTP=KLNz0@ z1aqh=Zs+t8y)4~SIgAX9r^R^?ePy->gz4!$GKMaz*@if)rgOc3zU_|L1S@As{?l88 zTiYMXZ_hs)6kmL7sTAo4h1ajAGcYDTwsoB1(j%YpFC2P_x3}dhgH8BC30j;c1?GsU zPaS-jn}b3D#m3ebBj$3I>7x;HQkebAcEUz*+qX`opO&dEo1aAj?<)`pH3MQ@gNU^E zGaFNEWl4tmw(NOqfj)nZLN6+})&yR__pHwkVeNqomtH6HCy%8>t^Q>>R=jofDf7G? z!WP};u3~R>>c)fNcH7Nyij1fS0MBdy7AcXAk>f-n$#cS!%!le(4u-fZ1KFg>qpfH+ z!aS!pH{%r2V8}6|Vaj>&%7P4JSTWJLSdJKZF> zrb75naD0QhjhmjwfGqb4QZ-TU@Vm*!N+K*cv_n?%%R5(5HZw)BF~XHUz|If#XResp zwWnUV(|fDyA<5ysbCpSXOQepI7DdY3hRvZ|xWjQv#}9zE|YoiP&ZM0N=Wxy(+#^2B~Xz z04a%g!d8#Y%DT|f%_K*T)vD>JCT@ay%HX zKA-!o?T-QUZ%x<*5zoX0ukU%j*1;zMB+b5x4e~c9 zK6c~95to9r3Cd=FYKoBYrax^$AYJVQQtiG2bM)Y9zh7zINbL!g)>u!Bmn^O}fdpP# z1nSaR>!ahxMs>7MK?Iw>w2tZazC+VELyab^O|7eJtu+ zq(OVD_Rno#Sd?&JPy)l~zRsFbEK|Fir>|sKU0Evwc;0$);m-}C-8QwyE5!B*w@R^p zSzB9u61HiAr?5qiTMyn4Mswq(0R^YuL2aw`xeK~GzEId+>ckE5+FHulT1;f{iM~an zTROJifUqJ4%Zn|F<)k0j$p>Oz3h-{eNHL?2avbAvo_WbKm_Lk_e`8?W*&wL-@y5zQ zI{-N@4{hfQq2j=rWzm)?^y-?9j|BGDV=kAetbD6a8RZ9%Hk5r zu`h@D0WKTGYZ2UUNC)I%wTHAXj-O0f-L~QcGPeN9f(bT6X*$w<3>zBRb{HN+IrVbO z?PCAVNx2BJGtpa$FH|vmpeXIGxvAWun36bNI=h4bWxA6@G8!sezB8V`{_PvxV3}~V zcOXymQ^Gl`D{op%_!?8$6$4_ZHd7vl+JNmg`2#oAkjzZhXd6vv@Fa_iGwit|Uh2Bx zYC=(R%kSrNXB>i3F@F$MSEgLB3YgY6FyJ38Ott4x*pvCBH1e_q>r-Sa)?)fxEx$eX zV6lzbssX?tC{awUmZ5A86{}3T6R+oK#-*44k^AlSjiR@&rz`t%zFUndQ&Ra*#1R>~ zzl`7ME;2cmxa?`c;axqp+ruIvc!@S5t-htebkx3N5Ns4`%fSJM!In49)7Z1=?A%tc zQzX7N{*DrRrH2G-fV5}sGQ9_UVqjeU&VJWW=WB9AUJ6fey2usXIh$MhbHdCDR~IG zMMB8DE~yFu4eqcb*vHsE4Wyo<7v*l%l}~e>8Ij%b8SqZ>EmBxZP5lhpc5O#P*bdBM zk)D^@#c@yTR93Cw^a)aGpokLBcHKLe?yxHHY&x=u#vZgu?jM20D!0NE023<6QVN!R zQJC=FQUYv+EGhMhf~~u_-viJkL53(RS{yCc;VdiON>@bZy%wakbVm~zG#H87DQ5@1 zHdGj^fM)k#AC4PU@L=I`x4kVj;yEOn(yn`f0k@MHIwBs|jPk}X7GV`l-_NyV_vK2H z>iNPINw*o5B7Hb!Q)}?5OhhLcTozAU+l?C-jybwrKG_oGaTuXi+wjzKYlm%#=;i-# zn)4H$si+Gvn1flf6|_7E)ss@}tYv*47liAbJ4l=n_wfjRZ}2hPAaNlxKTHNn0h)5(HfA;Yp(iwJXJE3)%T&De{b&V}o0; zKPlEdsjS?Xw4@(d=kEnJ@z0(I(7*(_0KvstOC2(sf_w zeQcQOiTA`&CLdZ1+8BJFV7^JbgtR|>0iN}GMme16YKK0`V`f#97=kR)**QGbV1oo% z7F~>z+rMq)y#7K$Mu1C4(sn9xR))krUJDBBbZuN=CSa3&q*-Xf+6CTWadq3PWSkXq z2E)Hkxl)Mdr^ptyMzf-lC3G0Kg2ZNSyp-#%9(8qTGWzY=JCYo$raq)sb3gxi993y8 zSzJ78xJ!VHmO~#opXIsN#|aN$NmXwJlg`E7ar0(aB_{<;_{Wgy2Q5f%nWG5z6N^cH zg8Im^X9bqnC>PXam2T4+8g|kSzKP@M{1rIxHTK5sE%Hs2@WSMy7)&(K7@*lw_wjta zuGwRO#^eu|6x_dmY*eH7w*i9m?&USe9sZe{Sg&$v#Q;v$xEs~jtCRfDet39`56S!s z32cAC>%$-zQa-ogYp*$d44K;5K#5va^)MnxjiK22PTZ9xup2wr&su!oE?`h!?E)7e zIsQEj&)3ycQh3Nuby)PX)JE5Pzng>{uY1Htbp$uqImY~Sxws_y$(Fe9tGrp#*K_+p zVIekorm(nOImP1>j@*`}y2j>)C}cLa-+gqJ78XOX83WE4Kl>@1nh9s`pYz1TeZ{Xc z#@&nbO-JGgEo=OLWBd^{5Og#Dnk6l~{|90)I(ca^rQ_y3oc@rWjLkngH+n3Ej*6=- zh2(-RDKb?!h_C|3bp0zf!vB-9ApHm7I%krh^w}iJu?Ta<4E9`Gb*t%y6YwlNtB>Hh z4*KhvW^K3QxOA4>7m);%bB5OH!=`PD1WP=a8bCCLqqkn!c+94X;g%BjsV>a>q5Ztq z6+ZQQVmgKNW+C*#4vJJql>?F~_CqZ|m0o^vmV-W-I=in{;buZh+-YYe-gW7|c3_60O~CTMx1H)U*VJoa zhTf&&#(gl)uWZ8SOXVPzD;C)?qR+Qw>;C2M)1arOO9(nP(V^jW-dWG~a zq~GElhtK@$rZ8AEVso_&THQg2KqTwx$Pv)eC+O3&{aLwb>CCh9((^1r-83F}3yRI# zBopa_b>})Tn|oKOr9`@qqD3%c?IU6DA+!qu&Y@clCGP?&9Mv68%(JteuuYN}gLmE>_!-Va;5f8X^I#6Wybq zh>WolMy<5KAgu(*1ChTXfhd!M34-S+@p>N)$op+mro<-eph^Ygu$;@Gkk(-k#@zKN9kASgJS2dl&Xbj%CBn}|R z0F!?|8%^=z>cyg!B*ZhdLj6`KyJco|;`iglGr>2>p#DTaMDX~zxCEk!@&4iWKSXhr z{7;It;-ALVk`yu1W%=+v=C8G{a$|{u+zyY8(EDq%HR>|OM16gESB;EioER^ND+B%G zw9$&xCKZ0T=}PZ^fZjj1N$)>_OoA;PMGO{Or{0j@n1|$96F(73Go2DLH~=Yn{D`1+ z2yQ;MTg{3rk=+vg`-ZnjS|}WHE5reR9A1-aw}@kPnNl3atGX7Ibq~5mx*8^Y7U6mb zkZK&Tb?hYn_TvEhw;ywEPV!dXk9fSu3hK`8bwrzZ!mqfcAP*BzSQU=HqC@1CAb6K0gYde#jOPah;bwe!q;qVdirQ!T0Ap@XCh5_L=-2%lxdu& z4Bo+rT)HG)k`&p7mzgTg@sX_0xRR`@vlGIWO%z!aAA%e@iQyke(3UV}=Aw#edpDja z<%P8BTfR&D@O0TeKK|?rk33)rb+uq=@-J2=E(o1nnhldy)VW00(E{)Xd|3ZR-8vU}N_N|9j6{4rl zMHUDVDIe8h5WBjCv$L;Tq`g}@2CF<$VuaqGK3t(OPe{kRWjUyhh})>ij-rlYWLBaR zdwwjw6`KW*d@b|WKX%R&{xZ#2U`<&E9emYttLJxNhEHH_;41#vN*g zM)0_6v>AqKeO|}6)~tooT}@xW;==D&6LC$X#g}_)Rht36?KW$XEkW|)x0mIB?m40~ z`^c+wL$dVLu6fwI2j!z=jtCP!L4}d-2y)AgHW|l)h1J`5(`2=o3ftTUJu=_A2UrLq z>&?&Yy_{cU;wIRDth&*)YC+w^!o5tn$m;t0#e>)R!K#u{YEY_ElAp;&CsRyq73vaB zW;PcEG;L;vbmv5Q`YL@fJ@x4KG~UhznYb*RLB4O3gP>&K^(KHzy>^ZK)V)LXR&x6Z zV0Qo5F@8VwG)lO0U)y}#vB7R2&b=X99mQB{3AL=`X6-3su!WX-7L{Yn80_}h`7)Q)S*|%V3{!Rnc@A6h$-|`)C*j4Fqg*e-`ZjQk!F_r zEjDir?<+Oj7l>4N2i9;y{b@v-Y;hIVoM$RqT+MN~AXdQ%FA%FCa^r$I#^pzG$)O59 z+Cbmr8uCY|D?9L$$&fpLGLy3x=fZgP4Xu6pvS4x6?+fBaMvPMJ`P?{pMv+hzIDi%n zi7&?9C=wc?p`j5ANhE@eYF|Pa0tb+7GXG?#yo*izdqp2B9t6|{QkL)%8+82u)8q6T>1B+zR3zJaRogm5D59q z;32gxF+)iIUBh{d_Xmb6LqqgaUZK8?nre|^0nDI92}oIVjj*xzykjdv>2Qfoz0R;? zPvb*4i4BYdMa?rQHx#rKD5(p=fdgOKk+-;R3KNd|lrHDKjQS zgmoemndp%xVxdvqGYulX*YTxB^H!vRhf1CW<2)FP{f!GeBCjlXk``~qk+;_zWhN0` zS7VTrL1|_p;cl}@AZks?esfT!Wa!i%xDYF(bucBs6=t6XS}+)syQ)P zpoJrUkK=L=hN{aA7I@%u!12hcznC^gW6mtY*{kCM$g1^)wKLC0>JAUQSrnV0qp%O{ zN5^;F$Qf?McB=^Db46=@Mb6?3QF5he*A#4Uhj!o$zczx0TaNsmC)UU$87y0L+a)fq zllF|Uz!%P17|2f+VuokuyVg@qP$cSqORY?jgZ z!PbgHa3WqaC24rBMZDF9$1&0;{-~hs7>C)_*x8l*S)7aG3W>J$y^QwBO`NOZSf>0?b+ub~K%a|8C zakETI_HI#e|7u_I&tv~@fASygPtK#m1s3@MqCX_(j3Z2YFtL|qU=&HzNg_2u#Q@R`gb(uE4Y%$>b{>h`rc{V60nu>-k( zBJHN+&PccFQRM8vbg@70P&2UQGaJ6b>S3@2(?j>w{nc8py8UYCl`!MqS@V`fPm%-i z8}EK>%@H5m^Vqc^y;&arP)qLp(I)&R#4R z>(dRPq6~ZzdXzWK8MTndTWhkYT8$o@{U6l5Wl$X9z9$R`5(t5i;7)K0!QDb|cZU#M z26vYr85{xxcV{5L41+_0y9_$`V8PubJLlHjw`xz_yL<1}`{C?|uC9K%Yieft>8Jnl z6JKF)PVuz~>3KV+-{o!4Ydf6V$frxA)RpIRQtde zf6x`Mun;iLJP{yNeiMIUv^$Z8@^q%VPDfSz7ey6v_(XgH$&0u+ez$m?(#fMLixYK+ zXFuBr2^(Af42~3hXV#Kbt}cP9($?MxJEYpavJ4~XGgw-~-l#Iv;WeU`4jZm8Cl<}w zTKx(2cF|uL_Vj+&i=$|;+=6QApZ}mr+`*o^s=kPu=kg0+5JIIvDL{SIDIGsE?6cT+ zc9XVoFq^dwD{`!)!YR8SeMEO7Y!?;Yy1uqaj~OjFO#gYKxA7MRR8#m;RTKa}sVq8BC-5kCu*eKbg|S=NDb<~jy)KP z=$fPTK8cdfxHeo`F~U2F!jaI(n{C+u#+aV2>kc}|Jnb$Aj+|QPf|uW)>vt-N@nhtA z|EZeyOPTkdtAz*9P81}WZX?b%am$Ta^9F1#Yr2&t!H-092X`jLUX$1JLe6e}d41pO zG?bPpDblJ-?&qv-GN`amV#Nuj6yMOd=e=@e-c6d6`}yeLuHF%@3@dAI1tc!^S-Kxc zfK=$e;i%Bplt;hh;p#&1W^7YJ2q0S>&>Gx~68YeUFOIG8qF0p2OqH@zLUHS>m7!nm z?7Mb$^p|p*NXGNVWxJ+{vtjGB4XP>PM*Mar(3sTVi6LXhne=D zB+m_<%=Gqsu+FnX)=v|jhT7ao1qm;x!;q!zgX0(azvV_IZ({?!-6WLt_*r!$5-b?X zMx)&h;^54MZLoun$aU&P4S?gAPXA~P=%HsoXeHUjon7_$8tob07Z$Rq<>NPpAcVt@ ziM|v9@)-rRa;N+^7;-;L?a5N(Q>^FwK!@$A^{>esGIV*3FNV3E6{*-LrK={WCuoBG zS%PPls`o5{+R2d+xGl-IqZzjP<-lTct&B^48EnrA*q(RrJ^Xfl0fv3qxX);Dv)Cpdozh zpF<545Bc#@Vlq^pxfi>I3BPv$a=(=s4et2fBfv7^)-P5Q#ji+WFE{UI<_|dvnlcgO zK1G=uc9}AgWXd?N`YXEDtSfpED!2gJOMTBAaTQ^1=@o`467BmAulNp#)6gAEvmyRi zwI%WhF7-VV>v>UvH3b>6NV%SaJ!PFa_X(DtT1t$*0glrj;)xod_D>l%RZ*$1g_|}| z*j4Q|rtiKzj&sU4_$W}mgp1csFT9fKS~*;5wCClv_d0G0&hQ&tm!K=@CLCXw;f#1i zcCMYS0-iar>5LKwRO>NMl?rd64m`-9s9|K7JN^Pyg9_fsekVcbbVG5LaLbza?5ttc zHRjEch_My@n$C@NDh8{pkj@Wu+iR%fpV<%7ozyL9f)X#kaQDb;6H!ttI zek-FdExP{Pp>%UKG0g$(8umCaCRHq~7Gbc?La~@>WqQF)w3`c;yw_wR{RP zO)WFjFP+E&lMC_Kl;B()a27KadCM|r4dUa^g;$^C3=iK5cJCaR$84^N6jg6vBS zOg@f+HglZTKJ*+?Bx7MrTM1e*<c# za`Y`yotWe3@)h^k-uCo1RvA>!r*ruWcV~nYXT$~8?6gY3Zv9Knn@c=9(lep)!T#ZK zQJvJ8i`mY5>^-8=W1Ll+x3w7&>+wrFvFE!gFwapY1D;oOS`D2a_!okPU6OBYCL2@2 zFAIE8mZha8FMZdubf&7EOQ1rLN?DdkMG^;TnA8!%_n)R93Wqz>;9-$LK>Q#2Ca3}# z-Cl7*dYOH@3<@{NyT(u&=(l%3KJ28v0v*XeD3s`$^%J~-{C5t^A_{fjR;0YJi73%P zvcg!9^>d~?!->KWntQ_9g}Bazg0q*$T)q}ghl>sI8OvjVz7-5%EHk=3$uhcn>U+2( z6yf78k~FYC`4}o_dLO_7`1Eyx-E`$v=0~serokWyeK3DZdj#mQnKo8Hy}BZ4Vm*}5 z35Zg9C!58X`k29(XMY#em1k+I-3#_G`OzmFJ1ur;!Tn7*Jj zxS!V?*Y3M($g7TFxk5Hk!&?p>jw4o0`~CI@h-#9IUcBH%*Z#cb@{RkaPNLuUaNaz`uIUkoz`6P8}Ul*EC@JASLVe8y7OFlKzsOH6d|4;(9 z!XRdl>&={6VBxM|@zwdBpH5%~o`1kM_$1sD}M2buij9 zk3}|r`JWiWK52YwpItCNbEzX;EX9k0UtJXx&o7%SZVWc%E>OvzxbfGKQrziA5O_BE z64ZhLoLWuLJWZJ6F(U+Ub!IGC&&#n_99yyGaZ%CHYY%`gElO{;65Br1L4GtMu7)}Q~F1^a&!qK6I=Xx6S!8(wa-h!gBS_^ww;yxhB*Z3##jNM8J=Kh~9~K=+fv zRcCt=e0ic$Q$}u<^U+|$>Q$>Rnq@-j)mkp*Db<6X)M@yWtP%Cynb{*&r9$v#+@HKF zBm;dRx0#l4w-?&_sAk`e?b>j z88(K{Ka8~T_!b=<43^v|*xxm6KybKgL2sIicTY@5DYHnRl5r7$p75mA(_J;&D7ZLn zFSgr61$I%gGP_@(y^gQjIUh3V1DaL14cqz4sdD>?h)J}p?ph3_sJ18f*3vaJ`D+8> zgnN1ko7Nh+a^-fk#J^Sc`%)I|rpLIm9>u?PT3_;u=#yWY1K6Pbe88HHofQ3|1ol`e zb}~6V6O$vH{o`Drw5DWdB_F&_V}updyG^}9()8=@aTO+}qP;IzdM^@0%+tL!S;gGj zSW5-yY@6wDaOUZG8g#wttiOHpSQIqQWWL&3%6~ZyQSvU?BYGo8`4~6aFnCR5Yw+?B zm10_nchc0i)W9Ocj8RhFQ)u&UyJb{X9&sX*a^rVq2RL*N7%a(R5q0N&Xq6n$>0*jx z;sY1YB#7rQk17qD?RuUcxC>8_7npn6*9UfsvWIqLP)t+XWF2(comrj<+y*(p zpk6#sF`jr=6RHySOues>sljv#F7 z;mQaFlNqVA1SUJQ)7%Y^nh4}!*n?(g*xz=g9cgtGdOg4Wr7_oM%ZE1kQ-rttz}K&o zNWcRt>!CB4@;!6yQ9gt@u2?D&9Z54?gvw)|7^JiasSp_^&OItPyQc5_qvx)P&4kxn@LY{k{S%YFYbV{7 zzKbo_Nfq)S(3<_hf+!!Pyp9ZF-Xk;Y2UOE`LevSwU0LyJPlH77=L+p|#ZI;>LWznf z-UPetT-%(BQg_XTU~3pRbbmBF@b__CeJkVE>FfI!CF5emFXHuNtWkY*_1A zYsat9a;yoC4u)`VK9SaD?fTD3Xqk*l?Z6tpBatTye0e~)OeVLT#$YhNpd&#nb;ahB zS)6ZLI|88AG1{9v6B z1)iIEkg~I(egG$0-r-!<7H-6S`DPJouJN(_;#phgI)9{c!~R>&p`zg!y5_xL&K=Vd zQ!hsEoK|Y{6!j|)v7!~TL?mE+$lo04-i0ZIc;|R|$fVQM(9~K7QJCz7w5pyA-1E!R zN$Rh$)o8yFxU-xS@!#xqW~^{6HSR52-k&g*ah!FUYQm4;_C-|+Gf-HBdXx64_;KiT zz!07H0@-7o);TsRUvcVpP)=c)L~(w#qaXbFHvc01LhnZ7R--|X;YYH*yD9Q$4vX%^ zXvS79Wm9Dt?#p>EJT8}oUufEZvR86Q2gl~HogT81nZ8VbqJ8FZIKTh-qW@H2ak{kWV*hs(*xwT}W3lTTPgvg0UpW6E6bktVu zwT!lpFpvqo3-^1E>-FNxM}=|e*8Ki}3*?`G&JK^PDjt1`@GZByO4qI5-cWNeiUI46 z0Kd4j0@w9lSCSuv_A^!xtWJ%GMSQ+pEk}!P}>cBW18?bVVf1n?l5cke2F) z1V|4(eTmw>9VXnW$7TeG+h0XQ3;2TLNY}vWzzX_ebZb4>2bC#&0F8pm{;Q$IywA(u zS>O!Ia5Y<|_BtTW;8R7YGaIS30jY7U4O=1>;qs*HqHhrDrppsUvWoSb!VK>u$k5Pm zg=cIQ?(|;o+Uipn7Q*^7RzFs2c6@5XI=MXPVliXAdHSeh!41~dl2f@jGz!rZ*N+z~ z+B(WlNf~oDx=;rri`I^KTEGT}XiozV5U$86PJ-Jx`LfuCk*v#ThtN=ji}3~e_-J+r zm(D@siro|SB*;T#U*wSAhd!gU-Urc$_4Kp4$1$+m?IE`3cqewFy)dF|{pR`H>4WOW ztKUazuY78lk@22&bDF%xVmR{|jNE;W{gQ-4^l+@BV zuwQ*K;1@neEK2bO;jD%XSgBs=2p4qs#PpWvn`@Z^5u9Cplt0hw#8k~4eE8<0cwm42 z`$4S!faU`SmKum1-+<0VH#(^Cr*$TrOwP>84SKin*R#Z+ljPod48OXK zGCth80()WfA)~!nWR)=O(;L=f-Ju=QTZM~)3l2pwTru-QeY-R9-Yg`GEeR$>5kAJo zTT$z)e~_bWT#MB#!lBi%67&gb$}m&wIp7(S)qZ_)c(#2u0a%2EaNTMD^yxN*%)aL{ z3Y1Dd+eGDwhT(;VruMC@q{hhT(E}Vv?){+K+urTh{@0fRwQT?drQ)oS!{euMw6U7g zHhC#lDeCU70Sa7JAyKoMVUSFfc>XFNLbPcUKOej86#S}b^QzjAg;~Zi@|17$X#43J zrgP1`w@*A=&0k($xx$mq{o?zx{))x8w#}<5xn5ythSRVpSB#zLd{O)?eXKZFQ@(of zeWH9dkOiqX#|n}0SJ>aSTk(m!d$b}}vg~tAPx81S928Ss3)xxa9e(A7tW$#hjclU3 z&aiOYjrv)So}-3%3JP9S-!X5+fj(c&P&8-fJgQ)ME-U&v(`W7$`)}ee@t}B@(}co8 zUQlvPm8!kn8zgM|;*)hSRPj~}th`q>=}kEJTnww%a#D`n>!-hc#cIam)}ge1`}9U6 zTl3qYaB*Xek4f)rDzHOv@{D!Jm`jt5@L3d{&b*N;xEB3?C1&~OYyMSZ7-XV?>)+Rc zcXb`L3FNxJ>F`NtIy5EtGdVE$F4dF%gIIKJN!4Hwy^r?%3Z>zw#N@U_ySn%W5(bxd zT64f*BrY2;<{RdoFiQh5y7LyKRU`PNM))U>J_@KI&m!|~0^GjK;y=al5)KqWD%UYE za4@_})Fd;Mmj6QbkN0aS7gDG$Q(9j7-?T$uuVK0#%i;hnjmWVDB?UHglFDU2J&u|90EwqW58+|o}x!Px?r>&@q+rE7^C zQ>3YXr#qX40+n5v478R#ML?3~ZpIdpL0>~cp$_-b5Qqa!rf6Cnclh|~~;B(IF= zCa(xqd#MVrn8dw5!+uzPR^!60Dny)ji7YvU;SJv{d9~Lr?Y6|FM&{W$h>fm!sWqCC z+m0<+>4XW{h}08Pq6(1|cg$XDRfxq$6fdrfJHJtIbE;LwB6VCRh+b-NQIq6~_pP`* z1CmyUtBHBB_8Isi>|hMp)HlQi?x+ZnT$1?GUMa__+Oh4=s-q$Nf5iViF17$-+b;{;irt zHGDa0zIzlO0Vb^C^a^Kq} z90U|ZN4{xJLAhpDAbHlvYlhvJgprE3_(uMsQ;1d@ioY#zUnwbwE=P*;{0~e2#~Fa9 zL&inm7jg%Y!LM^fum#c#GZe0G-8D-QnA>`!gU3Mexx^MS;l9ci)l8>Pc$Yn%nthQ*((X+l7Cw> z^pECs2w}VSv)$bydlP7uAVkbO?>Fn_DU{BzCpJ=!FD*C`#VnBq*fp~BT0<3ktSd>? z_Qb+DV>#8k69y*IZ&W+2TLkb2V)X+N(bCV#=$wQ|m>Nw})`AZ};zrC)fOk;;8_roa zCDdoKf7DwlBfE6Z`b1*0(?FN7#{DzWgvvD|U<5@mS@@uq!x@)-DUQNX*Ppa18HbGTYzQjf_vN`BioEg~NVE z3aGDKARS3cI)KCdVn8$=&+yBBE678rV;t%7VWZRc7v<6*V(a3zV_U>?9AYcyOlOB! zxzZ2;`!ghIef}axkL!A|-MlRE8xCn}Q8aV-xdgX+g8>DKP;+c*yzN7aH>vLu6jCn= z?-$k6J9~7#dkaI_FNY|V+*BIP*B;jZ0Dy~DzC>_^k7W)v)u%c~DuXU2@*j7I241yq znL!oh(F|GgXT@O(8~nocCc|WfN8%p#MdpjS5q(mmyE%*}keR3QYvIF3(31G4#(}ge zSu8Rk4D3P1s}-(!bkZG4R)EB(nWDzzZi89cX^(T%P;~>6QY$*rWR*>>{%alIirH1p zezO~NyWqUr;9opuhI6%^&Ui}v8B{rCCM$1>&4_ZQ7l(dXM$>3aP+&T~W-D%*4jQdm zSZFh2fGactmMJA^xsF=ngBPle)Lz-|dX@&;?oTc++PV8CzMH>wlNT+E^-XAtbQE{1 zEQ-%QEkRI{LfVBsNB&tDrwEfjA`~E4tNLu|rjg;E%aiM;BSGsqhXj0c1eih%t+s{? z@aYAxaPUbbHr6d!-z8GGfLbRuFl$&#jyfyhKjx%h04FklsgjV)QxR)y1QY8gWGSaC zwCe!ZXF9K2qcfVF?*-GDIV4v0s(_neo$ra#CqzwFYpF9L$d(cMo-KU(! z#MaP_=k#mg1DFuiKmI)LhIR6~SBPg2ZFUgyoEJhE2Eo4WRLiHy{i17!gGZ&H@mdFb zzV=MppZpb`+X{ru9q$C!RhoS*&&FVB&+V(ueCREKFdt0i2u{R=Ie0REnmuzCL9Qh8 z$!mO&ksve`y}x69px4epSZr(SvZkPD4}X5uhz=uSBcZO1%xp87U7U1s|5~ss}f!t?u#8d2Dyk@ zoA^hFn4w5a)^?+{4@eZ8Fc>(mv!aUE`bKE;0#oKsC&OJ7{QfVBz@5I*@mu>z1D{A$<54D2E&I_~WQNRYlB|pO{M~`7zd2LytU5f(a(dCiLVnAy8W-JT4?7?fr*w0~V&(g1I zI$aTzn1^?chJe(bv)2_tmZ?!mv@hAspT&oq9C1sK%?YDv$$+}OS&}KuJAEqoziVNC zk`$6aw(lM*bIOp`*oUu#H}vMr+f{^RZIeZ)S&A|El?N6VInHfZ2|RCoNr-<)&=nOH zLJek@WtNhLKirQKSP?uDB+G5v8~&S}&_CyM|2Y0ZF zSLhw%ff!KMfdAIsxxkC1KI5K8qI;8(#6%VK;WEjfx4XpjBc>+O78OlyKbAJWj!pRN zVc7RaKPatr5}0;-miO1n(QCX22{lIvQ8-cqS)2M4DLJFVZM`&1t!E#`YFTT!j=rGM zJRW=)CmC~y&rJSm0myt9_s17jh1j+j>TYB83#jK6;^v!0XPFSbbT!k~im)MP( zNJs}a-BYybPMngQI=F%QhF(*MRXaNQu2KtY$`_bWGsThF0E@Cc34BM-8`@?gBX^<; zPxT!;`ZbLHeZ9}8SKmF4UyE&(Ebe9wvAz!dRPhz=GbS{6ylYTCqrUGSRCUo@U1iQ- zP+DZg!D}QqJnXPIFdkSSi9b$Kcz*7^L~@0OYn(qvE75;l=vj)DGC#a z-XLA}%W?Z?(8|3D&HiTb(SI4 zq8Q@}G0tOm36-?R+01OGq|$`fH@Pp#Es5%um0c>8d=&<1Y*Io*X45)LVvK|``=!I! z^eyqp3w(D*%0!)CY^i5^u!^w>_iKmCoGSaprzI-@(0Yp$LUb)f0fJ1~Z+Hw}*6g;3 zMH~cC-5aTR^E#0o5j;beUCGC3JkNHMywk1C+*_myl&~6P;IFM|@tT5rA38-uog7A_ zhg}N2Pwc1zY>MRcymY1eEEl`hh@t9diQ89x<1P=G;RV?p88R0)hElO?d+9`{qol;Q zxyDl4CyCnmdE_WgA>d;M&cL@Hz!4v$=+o5mgoO5dF_UyWI8=wGy0z=4Res9_V$&qQ zm>D8;S@o#jDFd;oPIX?^sp{Kk<}nWP9<>94#X3QRS&GLX% zow>)C@LGT6Ca@Z94j%hkhyQ%_Bk*c~Cl!}821#$D@Tf5bho_jH4oAlc4*H9A*6v>z zA(dcs-TzZ9xPO<0`48n{{$*{=v<18pR}B>aZlN1VUO(TJ7KS4AOhxH>gNT|=RtjZb z!sQi!s;koaA3LIEJgQ7A)clpE@yHVf?&e}{@_wfWQMA$iN}fqL+IoJ$x2IlH+HBQ) zDwL*wGUdrq>wfm3m${gruqA=?rP4}rdi%SH_VOYKLCi-@%_&V5blQ?)-bmWgOxMy( z3o^S`EXBNEd0{Goa~4Q(-SHY_sQ0hJdaWh5r{ATT>U!2-+p)G=8VL0oHHLVtM@z&V zVZ*n2RO)@a5`VIgNV7Wl>P(w)}m7v zS?IC!`k!}*z|+K8abiv3vR!pt6(~EOY_deJI2yY~M91{JM8zW5redLFCCd|i8Jt}_ zdxnMI5i7_Sj>sB3@B}?`00{4BBpNG=#^`=Ce%iVniI3@@{i&tj-Z*g#0kHmd@Vx|? zn8#0XGLJfaj9&Wbh5t<8dW);Ef0$+M3U{OUmcvIn#5!|@l9_ew8M4s^kEx7eX142p`%Jqej_Q#M=G)W zLz)oKVj`}S12O!uqmC-POr>TuFmuw$s=Z!CRE@>k6ZPRRngHzyZE#?ay5}xRDQB5* zz(@_jA+0{;cVyn5B{i_$4U zob5Y?=_0Ct9`hMFsOU~CW!rKmIc6~DS@V>Jaogk`6uxNNc=x!KJa5p=o37FQT+Qu_ zr<|jOJ5(;s9fF~781H=JcXX_EavxaldR4xiJ5xiWEiiZFb+X+P!ZKV z&3MlspZNNv2s$YfisfB0x_H}>h>6-0;qcP(P1wCgrms0Rr^VN5_V?PBzOF^oF8UW; zy|#N~xmD{5d>BpBWwRD4tcWMRW+1)o%DW<4uF6+Y!Kaq7o+U1dJ2o1|CQ>$7nMXcr z(Vo7>tO-4HEbB1|Z#(LXw4pO`u|Ihf7z^2TEK=COGFRRl;IJj}qwwv^$sg=b;*o4W zNoni27pvR^j=Mil<$n(1vlp<|%42tG>wIfE^)&Uw!w@%3%v^?EkSK_`$J*0 z&>F5B8i81ndf6niIXn@Yh=pRY-8IH0pf5apV`GT4h-j2?`iT)~l+bV+>x=VME(uyD zh*`_0NIc!AAMuLAEA_(A^S)8UFk$@b61gj@?=SBk*ROuL$8OY!?f;mquF(YG@>H2} zIjnZ*QY0kRO^LdOPkW2cr|VAFUfjpr(6(9=-Kpiq|HFQ>n+9C-(S*Ei81Obj+zvw9C=lxCX@>glF&drww~KE|s=gd>dE0 z*f+ErNkl@dW7on%xK(YhoUWR3Sy=)&PtMNIMP6oA`3ow~rSzgnR}HOe2Qenk9>K5h z`Eq*n@ZW}<3R;a%>v};-OiW+09F)c`>kn?zG#M9{Il)>f@q`Bc`0L^p`P}8C)}y5; zHHYg*lK&`}@AjpMLaP`@!|$Iaqa&o92C)Jf!Hv0oX2JW-@JZtpkgr(wplwU<5ZLRG z_6&dq6R`>VWx+}emAWj?pW&laRl%Zby{GA@x7*?Bt9E;qm+m6C7Z~*YJNew*{*!dt zJ67YyxvkCC+oFoX=0I`M^;5=Hq0Sc9=dyhqbqKZP&F5z}@!9w{)579qwWcp$UPbOH zIfQn2x;nl4M3boH;5;CBzc4O}9gu1I*ohx#Zo))d<HtXt+F1~Lz-f$*rjt1jc`mple|LFkw8GTf4*dxs0}Mbi{pV@9 ze{`=KbUEQcSme@%L5H`&86NxovIpRLWQ~HHSC3M>p#0ApdoO{OYj`UA6yoLLz}u0C zj3EHq8|Hv)0IHj+9G{-*97LdQwg6V^`AStuel3~BlY;}aBSrTic-hz0H&n-)`Q_jS z{j^7OCz7i*b_6`PtA*H70ko7)y+BpFUWOiXDJ)>{Ctoe}FDo<@A8@e~GF+!Eb)k{( z+ce(S;ZGl4T3GP1pNr?S>k6)hb?7Z@+Q5UHsJ%&U+YP6Y)@7GVe=bej`ej}}Hg9us zy%Rhe0xC5vH3fZ@b@5w-1u95 zayrqS&@iDPoCyd zQUvi!)Ks*Ql3B5CS9M7yN*64Od*E-_qGrdbZl%=>y%PD$R3Mw+dMxHLnxl8KW{=g` z2ko5-x{zg6*{HtPgQVT12_8eP6W?fyms3~sHs_~Wp=H}1+Ir-rU)8`jZ?3ns!LAjYt#HK+3>Wu*SSY~Cx-j8Cvsw28IX)QF6cPv zr(fs;_mwYD5IOBnX1tvQotn-^=e`0r5@#X~{^d?H@D(YVc-e2!2SYA$Yxef*)EfN4 z+NY&u;<>PW0rSkUk!9ohD7Q}FkAdHuE>+wWPc9N~qO=+~D~$~YMRn_b z(GP@uE|uSkK6GA=jmx*pOFvrY(7X*|5aT@mhf;yp`_B%gjRr*mFT!M_1y?E+P^0(5 zq)4yCQ#suHa_h=%r|i`kCR_M30aY>#L!8`$>`58apEcqM5o1GZLbYzD%m z0PUX*ur?_hsysXNO1{hncKoksM@}vx({FdTI!Nr!zwE zdM(JZCpDG4Em}%(wfDxdg0VZ--Qx>eZEp0cW&9c&?8%h16rL)mHp2x-MP!$<1KC)q z(e0Cas~djM0w|S?i{rhiux?#mh~ha-&*+O~aR2)9<&aro*X(S1ryLY5%H!+0Zj|tv zy>Z{pnfcpH1{CR0@|>i9L}a%9fq%BR9UO_}xD7mdE^LAniLH$F6hUH}m!H5(2x#!^ zrrb+IudNvGhWq7Co}|L!rf4a5`j7hC_;qI7+=`8O8i|4+O0#Zg3r9}e=uVpEl?2x_ zE(SqN2iITS&lCJ=tjaQy%LKgA7BjT<Z@c7aMjJvYAYoDf?}g;qW+npVmfWXNXKd1*cLWbv1ey$IKwsD zeBgLj43eCY{w9(>q08!_V%YqU`gct?qdg>Nr&RLa4Q)~WyL-KV(u6c+Go3kce)_au zdx!KVdnBfGLv%*^`%>Q{E^P9V_?^u>pMP`^|D#RL^{Jo}Z%4cGu>UUdK_W-<-%z2i zkWOGB|EbY@g(p%ksa1EcWbSVA>F}8)uZ9fQ|BPADrF^ZNgB>SKdg}YS(LPlC$yZ^l z9%nd}>t2i#%G^q+e;WbV}`H2;O>QCqa1Iro59>foEmxlkjqQ*2Q?t>-DK z1I{@28A(-WUcWf|i$d3H=RYS0@}bt9oQI}f{g6|5M?KX%D=WvkrxT?v`=Vxkh+9wj zcIdmkMmmR#HRV5|_`!dU;!EO5838|wL~IIUVPwj_H2_z);?>@Hy1x(*eand#_Bp;f> zC0Knp;Y`Hu1a0p61?&rxs>@mo!y!6)X0dEwkK|L>^mBxxJ^egVfub-ZiRN0)XgFLp$NpP@(g<|W20cMi2v85Lh)Es zhF~&|3DE)GyjOOa6xDZb#*BJjilHfrNwwD+l)(Jm-ywp8PWQ^-=`@K(nf5}!WJ|N0 z^d6}^-3jlqh~d~kt;*zLN>TYNiNw%L1<4+EO7rLFkrli zReN^Q%vE(q?b|FVZCuc#ZQPZvwctlRXYn?_IWD`x)nX)h&BniM1xr^ct0(}6 z&N#d^7aJF{FsaI83;a$ifn-=uR|J;A_r%TMX)2R%G&WKhGhNrER-D61zy)60fF;34@px=J6acC}w(Vn0a3=5SYo;r)b{$#?7uBE)DXO z2eu0^3p)CTD?=wd?v+w=S6Jv+duPy&w<^Tsl@BS^>?aFT=lumuuVnR*AOp2b>Vwgq zLMt_)E4Cf4wXDYQqe?Tn1r3{CDbFTF=;Iu@VKt*}vPcG!MzV2XN>sYUX(zp-Gq^YTk_Fk)wd{PAU>;ZJc$ItGdlR|ow;wf@!gq22D6Vp9Gwl@u%QGj|mF#IV@ ziVY6yfs7-9VJnhUwnyZFJqa!Hr;xF234!NKRiAD6YGqKH6MWYJjCTwQ1)1Cp?Y{?| zJ=x!|H4i8L`4u9xX+t#)Tc;%1P1fgVt8ixMhr3cvmk)AYPljVi=c-O|D^V5i*aK0< zRGzEITYUqyZDuY27>M8Sc33L4VlNIZUoX<1xexN;W~~RZDQ0X#fZnMaT)yc7?#A4- zd(oEG%x$>D&qH?&FVxZbrW})J`xeZ541Kj6TNkhWwJXnaedygYn`H>PkRhbxe-sS- zV~lX)FA7oTrXy0nqn7?J%EU^0*#FAb)+N4)`iATjHFs*eOjlh;%_ajcQyQ92%0K~f zCy~vFS58wq@^$y0SnSJ3ciyc--^TLbX&B7So-I5uP629&EhqN+gotU@!v|grY?RmX z7dCGw^fIr0I`T_(ov09+R<|4Fy@csFtyb&>G5#&jQk#P_I-u-J>tSspFQra zmY8Yde!TjN(n5EebUPO_sdX9bo%YCaQ+7udY!`H;BP5V|eP+Mtd*t^WPPrX(;;soh z7Hw>GC|@Y}*8QFRbX`^C6t<*0mX78{MH$|8-SRbQFFj3D@UzcX=sVG;;H0Zsg2Hba zZYlz;o$H^=e)N4WVwSc&JDxi1hzV?i@`H0Q4BE_yQi3As2zrdeADFY7A40cV*!CBx z32g5+y}XHejO945zH^N_)_v7MC6&TmxaFD;gs=SpSz&UlUOv*h!g^#gT{R}5b0yUs z`|ZK6@HCqoq&KjF`f>6Wt4d`ZM;e|JBy5IAn&d~qRk?fKYJ1EQo4%gBAWum36m%*| z@Fur0@Rki0O}HWST_&XJAHSP>7)vrl%g)WP zOJ0<>*_|$U^;5#{wkIH)ymZ=A@TQwy?P0bDB(*~i5IDHFiJSxmBmdd#_&<&RYYLeE zGs@OLI6aa#PDc$6dh2~X@fkQnPyeC}rwH7)P1F5qxpfS-9+6mMY##!4 zg4F89A7i9jMKw859nKQbbC>?21R%hm4&uG~jl;Lnc;!qI!+iU^nm!o~@|!nS?F+x> zA2?tIzdD+e-5+Pxg7bd2fJ8pRJc^$UO$iP>v0HTtPZZXrDkyn*PyL=OI*~!sxHPEElQ$a`R&{-H!(qR@tF;?RL z_ziLD?`jpu2kHfOB^xXZx;Dxr#n0+br=m%q#k%+s#@IIOp8jd6DJwP;gS5dzlL;Vp zC5_1ngYjxCs1|2Yr0TAn6G#(4nU|lC?GBgy;QhLxJ-=8NGuuqKzWpmpBA;b**p{!w z3PBYwYe^Rap3VlHU?oy;YXnqjk|T~lEO^E^G;=(pwD{=02xToh2AH=#PgV~dCtRGA zL$;btknL~5SEf9O7ku}JJW6fy)>C9N9g|k{Z%hW0wO`~&=j10Pw;gwl^R-sl)irjO zaT|yjF~lvs@x_XzdvOvHpV9w3K6O$Gk&As zx#ZwK&L;Y12r5SJr|n0LZe+%|mxuj-der}K&i}u$JpA)=@vnCL-vIi{5d4`70A}%2Rq#Gv3~VK22E{3Tx)-*4*Q4UfUtr6~Re2;5^Wk?0 z54=LD#QwD@L-rN1hVfurq9{9M2T)dpkA5JPrQdV$R8K~cb*V+S$k`{&ecnXIosnPi z;*=aM%!PBG_m%;3Te#+-@v?0bSg6-Nh77q<^t_XePnzJTT; z=K0HCpqOK96^C^rF*nkl)3MglXht#={mPVanpDx#Q6~D-1&tz2m12nEG3?G7ov2@LmZze&4wkm0^zxDr3l;FnXnft7~d)&xY~6ZOj-U={x3O_DEObJr0Dw;ZKiOtHO6kfWYji-0{hpy$;# z>eCUAT84O`M`=!GAkae_$`2*-eucjIMvD9K&(_Ck@%(cQE!xtYAIN9-#eY`e``?ZK z3nTLXXKmyEiT(c?*Z%JffAdhEA-Gjh%#(w_Lu|9EV>`dwHU7YB>PlA}Oc}y{9RQqm zqF&p-s)Cpi)P}JSWkL@Q zDoblA{bFoi3oE8nR*@Yf%WB7D z#YLl&t-mOn8h^A*7=SlEf9Cj~Iq){e%hz0zY`tvFson>F4wIxqq2iG#hQH6MBnWe` zEop<%#|$K2jG}`h>feri{6O-2vWcmdZwIV#P&?PT5q$mxA?xQoDq1|LKU{Et4LdmB zB=7kGJoXKWVDFSHT?xF1F#)-#Yor$GG!*j4{Vc6~Q#s$FYcwZEsaLBYn=wFtheXUJav zu3Idp1&ibMR%ZaUn<~o7?|z0wln!N@X{vArC$kNo*j9WzdLh-Dn?0*uo^&tYb+#(+ z^#WYqbn#E7V;aC8Vrl2pwpK~*MF1e##8p+%Pw)N7U*KBVT}pE45Dn!0i()%sKhkP2 zE7pt_d-(;!Pfu7&aq_7V@)t#G=KBdOk9XDSO7ZAw($_!?-ync1$6XfIfkYY6$|J!} zXPq;?85^WKBv-}h-B*op9K*P=e1yVQ8VO(nx@3?TI=F;_DWUPlemO73alLt}_Wea< zQ#x*$Dk=&fGXaT!z$XfXgs?@3NZ1KckX>a5 z0RctX!oEXD!n@#i=Ba0V@64QczBAuD{*{~Vy48K_R@d$B`gN6Ztu$+WqPV_>WpTcc zG*&oCvr6ze$=B-?SNIE%f899?EPQ*aKy-YV%jM4W zlJYp++ec((a-a94jj2qi9&Om8G#2(Ao_)bdDeQK)=UeNb_+Nlr zZ~H&oIL>vg81yKtH?KN<{6e)VeY~4Ds~`45g_CT;&+6$7*qGw|VeR-%HMAh_3D=>P z$-5M#6{NH0xdE3;t9?IfW${pALe$!zzscIPpPW)ime#vSjaAu=^&RoEhuqkuv`2M) zy`$HoZKBwR#@uG!#CxzPH$Y>#r*}{du>m?ZLVPFukVkktuqh*<_Vn>e`#5c$sE~oH z>C89HxMt^%E*_>`!2YyeWT`?X*02OrLGoG0G3~3|n$OLeN4xOnrK(duJmeqq4jy(| zV41#$flcp7{?)PncXn`nZJ__I|Gz}^l5NP4Rlrt=*%!0?B-jy4o#E`GLn!pLN2iD) z*d$pcP5(+~-V>YsN8{9$riEBCof_bZ$^)HA;20bRdPZJaTk$2lz9DLw`{ltXKHW6m zYu>geUUdYUmxQAtM|OINgxnr)nf1%X9_&S)y{pKlDs|i`!|AAW`b-q7t&-rb>TmX= zTnBxCzun>K(-fYE!Z+`~a?P83{PNVns65puyQG@S`Vwy!MMYE3z0VnLV=d`<)S*{3 z0${#Rti}&1{pRA;A{5v+PIv?yJ=XTUcQ-szuG+yYMMY(z#<*P1TE2STSyk?#@Pj2O zTXa#MY_4nM-I#c{=RY-!k`FtY81?Kjmw;fbfLIIf&^p72su6WnnNh4@yG|=%TI6Yn zP90*1)J`T_lqd0?%BxAy&z^T151%N`u2pw|YMT29ADpx)EG+6A zNicgg@aQSbhuv5N^)23s ze~g-YKb9I^>)o5tA$nLstFnahBwrrwZopa5l`URh^)r}jJIAVLpTK22vO77dYhT|3 zs%+|@sNHXP>YgdL<8u*2g4~15I)|b&x@jlwtI}dd-1+WSkEnChD%YSWri?q`{R*Uj z0KdnRf}8kt0e@|Mc5{gM099ET&cExnTS7$;Y~q~3SJ1cDH> zySWqSw%(aW>o-^5M0)!`66B6r46TK}y>moV_2xNIXR80+awF1hJ^iG{#@lkPZf!=2 zPs^VcoO)(^ri6Yv+Nn(N{=HXryAv3;&wa8Q4xYX7V7TJo34tpoUbiz1|;*XU%2FU(Lja^7I%B?R8;2n&}eQ&=fTU7I<&c< za7u=G?xeNAYx%q5&+9x}SW>Fd-PU=1**dVOz4Yh6)1=%uYhif)(fv>V zaj!lf*a@sleikr9LOL0}0aEM8YoDO@x<{Ko6cd|~TDbBVvLswq9$|Th6X%^5NlGyK|bOepdj;lp$QVzF0-kp(&xPl4#qen2_e<+V-ga zT5_D&_?`Jx$d3DC(RHw%AEYqMNIRk4x&m{g|F%FK)Va zUHz(ewa6a-Ia6qHVd(A{Ueooa`*FvDh_gU$<7So3a0Qw<`mQ~<`Ybvorz)GBvihHM zc@M+Xq({3!L%7)a5yvEzJn>kidyS2+b>#eu)D6g%5g6I96w|_{orcu2`d;p%@@11w zf$gPJGli&&u&Q)2~&|WEuf6K&S>4>NS^$I@ns8oaN zD{kib$1kp*c3!EscWZMi^{il|_$gjdd+?tBS5)ljGgEOcF%>9f4T7Qo*y4zf_=-c; zoWZZ4XWc%s=?g@MgtgWi2(kaHaV7ruv74516pvVC;7 z@I4BSz-gdw?KMe%0{B?vtn5>(-xU?*-y&{`PhUSr>u13rsKj+zR>m<^X@i0$)?f#G z*$-XLz<{DLag%@t%6ADIl!BaQ<3q&0yaUHQmaWlzas>_7?ips!&?Py)bNDWYznwmO z=^Q~ceA4a(?61MQy9)>RKKCY?`^^$_YF~|BEU}sPjIis ztkK=TN$|0f2_TZidyCa_b|`dB9tg&D0FgG^uGJ9;eGep|LJUqWsQ2lRs7Przmsff; zu3Jg`M!cGMfRNH5>N(5%@7fCb6>b4OS-(5I-_YVn`_Va&8N+Rrtp`?U7qokiu~){Npvm~SiD#8A*H@k`_KW4 z3PJdjGr>nGks7{~XH{0B({zeiIn4gV0rNZ$b6G|JvBtzti) zKR>Fm^n+PB8%S5c2kf}zGg_Bv%TUW)*co?=b>uoE7vcg0O<&6CFgzg3BD1hv*e$9~ zXGxxf;BI!^gf`$7e#3Gu1n+2qZjlnE(38Q1mVmaTe!-B#t9gsmaf_`fptPt>N=ncs zR}!GI1zRm^Y%(e$)PelQ)jV{0HhHVL4;V><4a0ltPWz9ol$ zN4Wq2cpaK8KsO@3)!f&w!`o{$Q>VDRBR6llYd~MoWR%}?{!I36+5qGfLgh7=iV&z9 zPkMvU&KfW3e!^uwZEInuTn&1*?~(5a2GoP6DQjDrDsV8=V8I@-o|+>eP#sC~>%A(O zHikRLh6QE|!5l04fB193hnGA+B)b{?<#T8gKBG68Mn(sktF%I zF`R5rJ}l4x#$h*wks0!rm^HxS zJtPPP3&g32w4dUGYcmQqKnCb}fPQypxp@T&S>4&SXjYFidM5N4!wt~yj{$H@!Pyaa z6WXx93+ci-YCRRp+%~aG=HoNMVX0EFOzY(Q-9%~%t=xz#{!A&Y$>!J9=DgI_%M%d%v08wzN!b9kfbn4)2u;SV{1w~Z+XIO}* z<<&?C?!MV*wRaamHpo!`+fpX8&>Y~Obi;1ql5B7|9GQ|@qZi^2sN$H3z}m<~RijXe zs1`w}Ru;MW;&D-4P;5mKpi*f!%|;VA&b2RNb>%))`oPEam|BtH*cN}8g$YNAn2Rl{ zyMVg$j^ySd5tCc%9am+8BLM#Ds>WH~-AS9b0aZ9IRby8b{Cm4aaSU@c1f8zU2DUw) z-X4cl)%ACnJ^z?$>BaBgdLw_uM_@LfU9!Y{{WWG)(@TX|r?5p)Wjx)HC#W%juLRSj z(&weZvE`2BaHX&gBW^HIK8>&3S0mTD#g1ZDWu;9-v^|^8{J^#Za!iqcM*0@bYD$DM zLGr+LFW9X1AovhxT@O%L8{GkvD45k$=biw@>n@q0DoF%o2bMBMj%2iji{9UXEf^z5 z&DETx%7kMJvdB>|c$YR)7l5FL0Ap)Y6vdL{W;~(oUMRqOOi^HM?)+vy#?%GYCX#%B zv6u!n8>JrIdU%SEDdt<&F+n$=)iB?&& mT5pPbB+7mfHfzlly7~T|S<;wj?F|qD0JAZEki?-jdj1QzSiMmI diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/Clone.png b/Firmware_1.26b/Documentation/How To Contribute Pictures/Clone.png deleted file mode 100644 index 1a619480026af4e20ec6ea8237a430c40dc110cb..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 37021 zcmdSAc{tQ<|1dlVMQ9;KsJp9DvXq^yg^FxhnqdqT$-c~xZIEkHskB)ldv-H~u?%C- zB3TAwW^7~442Dt0l4W?m({j2x_c@;9ad3Ri%z1v!^Rut>*xJ%eL`X^q z1Oka%y>i(W1mf!ifp~Lw3jpu%<=FoK9z4OeX2u{)_t9D4#jd+X*Ns4+4~fECZv4RO zJpot1!61<6NA4d_n}5+A5a`8)tCx-J?z=3|qI<-tQH$$aZ_&6=O?#(W3U-r-cbXr1 zvFp#c$3Dv+FPu+)+}wJ=_~Fg{m#e0)C(p_0yn;kRSr!8^qoj9g) z?&iaS-Y4JE%6m9!{%K}irF1Ymvk9ikjFt|5R)4$OnT=AuuH1m^tlLBHHXu;-cSJnC zRS$PME^e_ahjnwR_tKUc*J8~&I}OtBZU=112`&yl@uEibmt8B552djk=_IO)T%*6L zIqU_NXR=6D&2Ns}oUiX4%i8#8l|J0G$_UY>fddI4_6lQp9(LiJG@U8YhE5iy4pyZg ze#^-|htbD8`EQ{hyU?Uk?U9ClCN~|(M^ibJ5(wm}!M#h*8VIt|IATCa3SZR&w<3Go z5k%LYS3SBL2~W2X)H7Sx->#A?HxZEaSZ#Pcjr?t`=tz$ z{692c;(WCo3?3eBRObi|wv>c9g zDN&2wi8xTU0x2BTQJCw?Xi^OCVoRD*nOJ6m8d^6EL-B=|M~@Q4GWt8sYsS7dy^V@N~iYb z&RmU0a&o*=0o$iyeM{23-khP47W(7c!1DDkjNN-w{GZM{*={8MenlNsiNa zvoKO0XR&FqWs+ECqPV3|wmng3APsfsKq^4iNX&_MVZxoi9tV~`SiZO}p-5<0RBSqg zw}etw!nddkOQaw&v!}8@#c+EH%aXqgyS-T2HWNl-bZV9^JF`~S^TQ|$;Niv{7o7Xg zX{W_U#+7uZa+}4B9p}F+3m!r{nhL#1A#9K3Y-&K%1wHtALk%|urAum$S^k=T_IXp` z1&XEm&i2@D?Dx4Kd6m-P59xA_tY+NXBz2gO$aei$R;A!irGa(9A2>8Qc2LaMCe+7& zpQdCg`PSB54XyVnZ|UBB*Kc$>5<(pNbBmILXs~jtI-7NPG&3!Zs;fes;ArdNksVrXtM%LWzd^{?x$6oc-k8 zRP9@RO9itWUbJS)E?+yRW|fr{lpxY9oRCLrpeDOW(%hrma+EDcRxs5{MJ7XpvZX~* znb38oaw=AZsduGZGA()szq}Jd>e*uAgH!%8OyTu7b(MJDAO+*#uGm3?UvROryGt1W{14)!TaZ{%B=vRXO|r^r;-~6^QUvdC}Tn&ATC0&zX^bwH{Ihn zE{1aEKUw>{D1Gg_a`fkss4>3YU zfHmq51j#-W3f+EP3~OI_g|46*G!5pvma;9$lXHR^27k)m_f+#jnT0l#9$AfY2z5d= zY2Bg8#QXcJeDFv%PD@T`D62rWQ5PR~6T8x^6o>1DW!0#FuFh0$lP@a#h{xG@tEfR2 ztuD1(g$aEBH}VpS<=X7r;C8GFj+qXgU9m3bFxf2S8kJ4nBVTZ#L?WX?k_6>ITn(m4R^u={>Wi=+>Ym_ zAZ^2GT3zlq6w+&=yZcASY7_$7Dse-mlxf==<8TeLLMITuJ8XW=FG3 zzqiU+J%T{CZS7>4(xA{ExI_p?e_b%i4SOV?H4yBpV#_Rw#>*Km>$d5f2J@XV;nU)* z;{ii|KR_9AX1gllT3pnu`5WEs`OM_%BQI z^}`Tl=#_4v&JDm6@V&dYp_4VZAUU#;cMay}fhs_+jquaUd`F`>z23EpKhdFE;N{Fs zzM6l>QFhQ+a6aF4GFH<JRhSdV8Z+CHSo$M{yZ{ zg-3IXCAuo5@a#q7zzvO1Jmlz}j{YkSg#z@zgZh$KufB!Q?+O12)TZq(0SB;Ba$*DF z8Ghz4E1Lz3<=)PX%B#?N!Z=4(O+CoOwcxMtYN=%6Kijys!#nTt_&Y3oA|xLB_P?St z-oG~iTZ;_$r~aktTsUW~3AbmX|Bkf8P1Yr@^@^LUSl+uN2DSPR+DKqaN!#Dow0R~0 zfDiw#*pqzo|H=jS@w@26bY;CCzEw*R#B>Jb%gVq)&L+0RBV8~H*%_&E-)Ylp?$ydF zBKp+ECMme-_MuwD5oZ^y^U-nMUj+U9&AK!bqaxZL33?Fp zH=Eanw(@z%rGN9F=!@5PKK7e@kLho1op+6EX-$>q)GT+>7vFCBRYZ?fd^)$2ev+>2 zpzoh~qX)a@)O7zbcbe~X_~>3*@!tooe@k9EFisYXRj zm2%GW`e54w*A_ULo81@K`F~vA-hSsl4AL8pgw#S+hc9~a&3Ae)|6+7iX~fKJSPf-2 zMNXgi85IOcT}e$!q`7}FP4QP{uSP&RbuP2p$thk%*}PA+n-2 zq(g?X)KydT{9$9h^w+CDv$m!LJ8u&?`1**xo9x+$j*sYX{PbV`6FJAoNI0Q9b#wa*s-v;lM~;p9zVyEB73E&J zn%wOAV+h(YtvHYI_H!?Rwef+jBl)L)1*vjky~Ti_xMyK7R(r#C0vUZIiC*ioog0(+ z;b~Em;@?@Gx&sijoQ6B$yznr)T8tV|kMrz3zoxy$?i8GOqNZvPZ=Wib3t5SloB~&>%i>XOtVM7-9Q@Sc66}1oTw?Z&C_(%HDudGIP*%zK}&?~-!`P=gO|KYLv&Ti(8BbJMDSQ`mS%?>t|Ri4 z)G||*PO4Q_T|4u`GGgdrg9S95j0%4Yrgxvm97rYGLl_#-+hVVVUw;$n90PmlFVZx( zQU~cR3`%+%Yb$avDtCQ7lUcG5`nH?(3L3t}=*qBaBfb>vG-o|E>+D{91(i+Bqb@C9 zV2@wm57`MXf&Ifkk-yfel)j4nFlmINq)#W%v_D3BeY|r~g%S-}PZg=d@_V3qiW3Ma z7DWA3|H+;VnN$Ps0;OJdByr0GoQmH2KI`35D)`mjjg^r#O4=sDr#z8v7WV>eMOQzv z*CKH}uc0$;?0I=KD`HGlY&0AS=iFs+Hh<|Xu584Dp*1P9t0&p>(?99B2!gMJ>00z? zne*zSddsyB_D53N(u)((r=GP0w9>3%dt3t`B;hVA>p zI-=M~bCCha_smI=(ji;-aSJ&fQW7!O+m@257qR9}!L97}|EMk%8>2 ziS1;0I$a|@TA4a+DWreO?jJ_X)2*OL6a)9fXr3$mpF3TY)HDwy+y9T%N=1uXj71Ic z|Mme;1HcMhkIOAumHdbP<9LH-Hmu3PF!IRCW@o$ca>bR2=7-~)C)miWURt8xo)OBF zdPJ9BRWwyVRWm@^1ofYc(ZuE%;1CBHV{HUIcvOY#n6JPBM_5qf?MX3Zjf6~^-*edk zsiyK$H-7qO5B9`^BRUS#+B($^ENpq?Og2~&>f-Jqb1t<7uW*)SW`p?$WSfK1t@FKc4QeVWREOaHrZ>E?Z@-=S?+Qn_v)DwIEKfLV$Ea5|rDM=k$6DN(C#tEmLg z^;CO>_$hx4rl{E4oZG{B<6%=Dhr6yuY_|Kdzwrh4=Qp^nUOpaH01j&&y#Vhivyk;a z?dgIHiG7Q1lXEByN;*Vua7ZPuZjC8A! zx`_Mf3a^jUpA75g-1Sd5P!+bW1a`cK~&AGWeVm#ua>0r8NInbIh5&gP^0=6;7*27TQF)h@qAB z^o8)@KH^V0{1cqQ7PhQv*yTqK>v)SU-1L^sn9$QWq0-hdc_j#0<&_x*eoYDv>*&;@ z7PY76y2FFwMf$~<3Gr2QavOfQIP+b%lfrCH$Ov ztuz>lR#EmR5$#VN4+^;Z!MhS>bL^R4`aRiaxO3D4sinkHoVS6_l!t1>^~kV*_*TS) z47(JcXX6Xq3J%v31WXlD^~_1JVdz1B*jCSkh>c{>n)5WYGJbxm5ceU16apO*Uj0(U ztcjK;AN(J&QMQm%4I-0D@&Iu&~v{eDGo{VEJSxI#YL={Fr*#DI%`Tgnd1{DK8N+kxUxdu z_($HqF?j4Y>bCAwa9zq5gIWoN)YpJKOD}Lb_}E<@gQHdL(ABpmSC?|1t%f~$UDa{R zY^$!bdA`ZewW2)ppYBNf0)wUooI}uXs7C-)RSH> zYjzfF)_(Rx6=9VBp`N?w4vvC?^rDE`?!eKXcSd~E=i2|_5dhK@$^N(X9#7_e{vTdI zxD8a(K_EkZUe(|K@a*#V{p8&Z6y$-QUHejbxX<0kRQR~heTJ^w8a?P(O!Hpu(-0JU zg!_yE{jUJ%3Dn;hNKHst*a1M9?gK#f1U?sYxv=>>OHKo4or|eVoYEk0)a&2>ql^duoI)<%zdEJOBSsN2mX7s|358Pcm=gbHpWjUgB$M5XjevOX(RyLeqWnye_h- zOaK|BT`vLZ5#_QdMs%6-*4*Zbe#EvHP>TPmY+&KX531(lawD6szPSuDaF&B+f;R0==(vDx5sat*CKrbL@DMRfL7GR z5_v2wi*RG^$wF(@gDO9+%=H262~TVN@w3I;M$2KHRzdEY#~2`3mFqK8-?_rr3@~#B zEYyOrUuT@|Hal^9Gv{XXrW<69{9Cw>1D{@<3t4zjady#pdO1qjrJ$HAv%qvlpgdc=o#ekOlw}KrHK#X}cvP{m4ma&NbNHdw6P0=yrDKSzkH-j5AU7 z0Hpv(8;^wBy{@yPZwbvv&OKbH;pt5=(Gi)TN|u|Ztd#pX1^`%bsqtm;;X)`;U;{NQ zV63MwGAsP9Lkwj2w0UoKdEFs3i9EMFxoOlbD*FKmAoe3J12SNZn&KH9dzMdVHm5Kj zE(9~w;{hUO%W;)q=AhIbm)M(pk*FdvxRz;t5|C~{II{igVi)1t+w}>Kd91;?hiC_e zD(e0ZWm-4!8V_h6SHF5rj}Whsfi@ji>kY?xTwVO$_;BEFaIQ=p?733unuce=TRgw7 z08ruo-B`Ssot#eW5=_y5f()AJukWy#Wjums2qf?V!tM@WZFpp7EsT?OL?{VKaLiLs zxXFh%W>(ekt(|=To$Ww`~JvwUb52Q zS&%2!l`QY43TYhpyxw_u55^4jzz5qryjLjHPuv&fqt?Apz9g^=bQTknwL#UqfW_MQ zQ~G^Trfum+uc~C1ayQZwXN~LeLl|q(!LShpk1E7+w+uUP5+XXEv$cE zT0GGp(OI#3ZVs~)(NPh}Qw{a?&xp4Z4N(G+JxKvr#LNp@M(O^La{gDHIznu&J|MxIbypK@`hvhPP8))Wt&Zj;tYG8!7d?$_-}Q+ z=C#+E31Hn@3(V=?$^D3OU(?5p9{M<8de;F&l{5@@p)Tk!g>&RPhc^}O@PTlG0Exoi zF>@i_84W7p86V612K=+?fhr^dFWfnoyD;Wpj<9vLeiUfbCf22NPGLNt8xi`5_g)`v zzRtDOPyyq;8~{mWn~qV~`Q_|--gId>k=S2I_E z7+La_o84zo?viipb%^yZE6V0RRgA}bNVwH+)*WL8qg(u-WO1%{QPZ-6X>c3DNlUHFO z9L%^;MBX6pUdw-MTxoDDb#(34BA@i1q?|#$!cAinrnQbU(_hmUrV9B4Km|gg7}=b- z`_yZcC$=4x(Xv$~ql`T4A#`?jiPsyP%iXB+ligPx?pxkC*1c)`8TAuR^^;8H#E61s zEV$&_uOlDYQfY;mIfKl}MI1rrt~9(fs$Q;xhtBTf zJbgo%Fy+M<*JpkdTjrkoTVD4gwd_liMVC12GbVyF+nhN?{_o+&l?wa_NJ{Tnp*#q2 zF24kP3gk_2_EY}VY?_%Q zLk-!$iNQ|s7>065nH9{qt5Mn?L@Nu{i-maNJG?)TQ!e@GIfi5h_ zC>gKIl(R?1z{4@=iC&7mpqOrMxN@22Rvon3TSU^Z>dgBRgky`=CzKmMgqn6#sLTuP zK-`UWD7=I?BpCxOt(3Mprq+`|w_+EsgFtXW!0cvULEl=b(NZXrzjFsAkxd>U>Z7`+ z9935RNjjN`vGDqP>*(R|rZUq05e~FY00h_PRgF1@6)!n?Sun&aqjwB`d|pn7pi>u$ z_7#$Zh}ms8QD;MpFX*6{$8(~RDA&!HMHI*Aog~rvXF=%pm3e8XcdbDpaCZ||fqn0- z-^b|?eknph8P{^uH*yy*N6O-N+@Ehd7*b+fFoGry3ITe{k!i`@2^fUjtNES2b7Jd}mB8j00e6tO-qw_3JvHN`B*DG+wKL_rgjtqU0ZT|m0PXSL>puYOb= zFFMZ|gWGfCnl_yQhuKPlO6)epzm1pEjg|M7o_nMGx*F;&O^zh@9S{M{?Bz=LF=R)R zD8^fxXd7#o7(4;qxsbhYBcn#fS1e;+n#2oQSa+9Js1&H@x4!~;?GG00_tN%L`%yAI zm{D5n;FX<4mP*6oXU$LhMx4zMI6tDC(La1C?&;(1x0J{kZ4iit0_6LIh2Roq6ERx< z43{N3De))b7=~~Os*A{Ani8)x&V(X8MNzH<$M`0npyB7&ChA97BpgB3@tsGdZ1682cs9f>TF;JOq=gs6g{)~ousw@v1If&=oP`#YYwfcl zel0!IxCb?|H;9jhdf9*QfQfng8xT)+xdBX(1Z<}1BhewKrjLy0Cj1Ah)^;|=2~EUh z8CPEuoYG098sWD^14&n`$%rt#{6Mg(aJ-UGZP%$29 zxgWmom`vm*O{-L>;5~;$CEhsTG*~e6nc@RU@|rSKU>& zV722FK_*D)8s6Uh3vW=37F|nF1Q{}Zlc$HLMzn@zRA1LZfRB&P$N7iG5RLS#Er+uq z53#iRea>j{SL7roSU_*?UJ(8nz!l#DJ|7u)Au$6E)ny~M3v7h=(=^bXh8n)5}p3Llj5`YOy8`Ym4s8yKNRbJie?kA&pC zo-1@^gYV8xAdnPbDPlBinSMG)6`JRCqCpi70gUsc$pPKvOs{_W^5XVfxX5zB+6J1G zKPF4x0=CTkzC{q@>?Y6Yev<|uNuXIVpYK$emMnvU^wEyn94F3aAW_Bt$wgaSCsE6b zzjM#UuJ;T-1l3GYBWd(tBz{k$orcYVPRn$yMu z`pz}J(z75e6y1JLM}@-PG`NfE&N((^{Ito=#xV--h!n2cwyf1E#ex%mI%Sa7uHNX# zHO3kP!n?3NBeT)kiB{fl1nL3Dq`7SP#7}uCm5+nQB^vy%?oRWP8^sEJr zWyaL$w(um1^jdxbW6$qWLiY6$?Sc~~f}gh+4f5*6uMvSD7+pK7QWj9k z6!+vPpBuR??z+5P6p4cxnI?vkR*C+WS*7!tX4AC}-a5FlLk#%+RbrHE`^rId&f0Kv zB3A4N)o4cp9ldv#0BD*UwVjgkJWb1}fx=_T_-;`v|D@Y!tq9uK=JN$#!I8mkCd_!_ z0G-_pYgYNqQ^sLMNrNe(A4`@S&sd-NLxy8Nl9nObKjY^|>)%KsKPgkbQSDNX_!9vF zUE{(Q&;f~{l0pKZh}n=qEvj+4XmPlegvClZYbrRgcR}bJLpkZeBX1FXan#T+XIn?? z@~+)jtwJZk75>M<)bK?Tn-R?1?N%K63s&t3{o#}xg>zvRH~5c+^MW`J0RdFZ{*m+I zeVnySB#!b4o_$Y}|CC-d_R!Tg!ERLkJ@)9h8cx;NT;x1omFBvx%oVKVdpNP3X? zz^1|Jr<#G()*fsyI(VC?o%rvZ#M3?-(7D z<8+l+$S~GG1Y$JbY%CTE9}g2xRiMQ6OCCuR#2)g_@LZErnDJFQ)}ZWKo!IA&_6NnN z0OF_i*4UC_R3vH(m2?iRm`mw4vp0VakxeJ-QDpuIwtjcr&9S41!lFDM^L ziV#$?3lYTFi+Cz<#4LNE#^prHaFF5Ft+mP4zo&1MDKzkLdl|6I;Xb&249~6OaN4L88CCFNU@%Z2Euk?{70zI zoS^bR9l&oyC{k!JC)ubgQ8wOZ)}a;-1eDgZ;ZZpgkk=6}T~eCv099SUcYB^io#7Wn z4Zvr-E>qUgLSKZwk_8UlP^iY_ojj8z+$q$GZS;q%LRk1KuvJeEPy+qEiGR>qxPrIT z*g=o)VzCK0vD{tF7s1~xZPAG!_|RQ%;V*Ysbv(v=4P1jO0(DZZF;2D)z_=ePZ=_i8 zJE2CbK@6%u4wdrM(o zsk@55nr~N}^yR&tD6#TLpHafT#6Py5L$eYG5le)OZIzO#yHhR)P+|rb2i>hT9-ypLQTj&8(-HZah;eHh@70ah7TEqb2jfbSbBdC zq=n4%f1asqSWw?wYhRn)2J#1Py5)HSg(_<#PpGF;*D6%@?k71g}MN7_AV^Q zsX))71P+p_Uv%M5V{2L)vgYU1h4w&1(LQ=R{)Nh>id4hG-qrG`@){oBDbNPjlbObd zeub+X^2#X7AI5s4LY#Yq5uZcQLqZ1C$=^vqM9A~wkeV>q9k{AuyaP6~!4SFZh^Oi# zvgq;dE4(EuKotj{02EYD%pNnz>ESo!ly=Z8TgYN9LY`z#aGf6&U~nk3wDr0{pyCQv zfbLSD>;dV;6_iVEPk%RIr$M_@FmP&$h#%qobgu6aeA|N6o(|AaAZd91o?c;E*->?dyA(T>jxp6|E?z+_+J(-AH{5AB zM0b(#DH*O)Rtf*fv99nnty3JRC<{&&Yl>)b_N9nv*S__3qokbJ7)B61bm#q+_kpZM zxL|FsP+B~3IJ|nBfu@sNeJ}N+kqfhKbT77Mt3lZ~{6oGCjOF=hd_v1$`9oM2hAD^) zY;j&MiumXb7Y&}fJ9PM0X~b;8F-@ruWxobcT0DU1?K5>n!+D}Z_V^&{JU*-kyfCEY z`HvCj@aSr1@{^mw{AXw|*u!Nh>O!5(+(Qmg;|{CVEv!foatrI{Y4F}f)+dzKA=WY1 zby=AQ6vnj}`S6~?7hhUj*u^J5WU_WvMhQ-P8IkLx_F}%Bpe0_Wyp9l|YHv0-s|VSN zBboQW_6fI@LzwVF)BfR=UpFt%n~w77oQ;2Ia7ONY zlaJO$srkbYclf_h9)GXs<-wYIFtT<0^vb6rp&5B)EUHk46u&Ge#)X^tf<7*du9x<9+x*`3EwT=J9whf1R84)%Zb;^31Hwxbd-;Y3^qZuY=WxzML$?zPwHm`&kvo-PT>|b&$cQwaihp-G zJpaYn^%|!Z8n@OBQx|+?gjXB81Psw@#{-1*=Mwh2miHxhy%X+0Q8!0ECM2kKUigxn zS@~6Var4$Ts%B1F?MSPvz6fYWWFux(4ZE9s;0cVIckj z?Gbr6ZTbw!?2Mj#;HW1AB8@Y=lHBxBj_@&>7 zoi+lWfDtygtv|RQ1%dX80sQQ#Rnwv}uS(8`rj1NPNRiCW{O`8xb)&(q9kPIF6QDhV z0G(r+-uLE7sF9=Asgfn3EtK_!m1_M`@qLK*}nJ&@)7YoNZ08NX*pa?c|pqn zVAM-f?mm9(mlD)Xx5ZQu!iuRS|EF-?iU(NZkQ3e{uzQxIO2_3CUxxbN5)m@i_#Mi2MK2<6E`~p!D+gEEV!kfB!H(#ioI(C zP!i-Ww`x#X4(vBB1?i0VeM)=SecexkKOCrCDFFpQ{yvxlCUq?2rgg}2zLA0%NDv4J zxLU5qyd-@Yx?69v}GN-Cw8&kP216ie6qms0CCRyN;q91-I`CIp#*kT82*gY#p@LQNI7jnZ1j;fjI+; z&WKQJ2$tWrc&dPm>0e0s z?$U|p7xq@Cb&EJ8u#yrXs-NH#tF!mi{IH%4`|It67QAdmL${2H*u8TdYIsw~#bLl_ zfffMq*cT{B5c(ul@0gO8>=6N`DM7RS=(}5HEW!!o*M^G(>wAh!Qh4*V2Z(4O`e>2J6{JGB7c9(vaD86*@PY0 z()7G%p{uAiTKx{vBWo(l%2{6Ngrcfq;aKFaz#r#nH_7ty-h^xit7?jL2%*e9Ly7+$ z$j}?$j(D+zg`nH4QnHsjecb21aqRnpOvy#qbKdb`0`86g5vC~6+7qSwLG&aV_$_po1nHx@gjwsgf;}!aB9csOgJb?v=q22R%aUE|-b~3mG>3OFbVyi=t{VPyq+#zv%tJYtHwV`N$?XlR zR;D!JQf3kcTs9AY4E+JIdsG*92q=76U90Eufa8$`Z3rqo)KU7N&>tBPp%5K8DxyP_ zR`}YS_Ff`H-L|F`1L-0m-~nGB&WR~>Q;{4=$P7c9CE7>|TOQp7SF5A)B3`o5lP6X0B-$iUp?DvqAq5N){y8$W30)v$Q3cKqYq)>DxWiON=D}L{IE&3Qr54Omgnz7w8#8aal2lpwbO z=yTp_6LwA%k%n+of}L$}j>gKXn6c+jcOt^-7zZ`;)DA=R_@ZUB!p_ev$>7ijOC5Be zmvRJ)Ota*4rp*X9Sl?Fs`XsU2D_dXGVl26hBaPksuWFKw8TktIYeC?NUw!To(DRq0 zeI6=_XwKKjt0>Gzut(3>`zL(BJz}2E8P@qw(ktmB#Wpl3&u`|l%iA{}t^mwH^y~rd z+#>+ob99OC!=@7t6+2R}6S8)FyUBU(0F)w>QEk^og`E-W9Q8d*mB2Md+&_DVd4AP6 zGCex0pM9vDm{!~DT{lN$20;3z`m8L-q+4YUKaCFx9`Ht-*;nfL7_!;Fk>d9=n2)~% z_4bCkbwUwpUDGi)t1W1{R%Me)YTf(W2xp4`3P!URD$y`JrC5^^|H>Lnao3g6@cjy} zHDMgsY{7{m$zD!X^dQOvstG?S zVaIMQ2ptq|Y8kHNtr|Poc=*jiltO_drs(9b{#90^`!@QCQ)#?3Fw(T`D}Hgse`fWi zd{+W*Bl4^{As@YN9?BPL1g9ClmQ`go^dJ`W_BF8NjSAN3RrRk{e|K7~N-HwO3ytW0&W+V1OB#IC*k zuU;0(_ZL6{$xBWb#k5Mw#*fq;&Co1sMjNJS&ZHQKggR|B6>o|wh&HmquCdcJ{ga|$ zQnuNNh37{o)25{_{YKKLuNPsDyA|~BFWmwkv#gc%-Z*X6OKZaLb%!Bhd@(Y(ZSIRk+d3(nXAU@i++{N z9SfrPhBtPrt`_#r1LHY>3`BMFyC(@~_gT%>VFpV)5JXWf95SxC%)uEo0)Yh6)<5rr z&)I^7tGp4b9b%op$Ox6QVeHKpg!}h=6v+^_Ap@3tv7>&^&0%%~=Yi<@50H7tQ;G0P zwWSijRzk1k*_8GXXk`@(IGcEZF(68n(qqMG>^uZwO@MWV;!lA0HfUh}nGVP3^pT;X zfZ0Pt*T>d~KR_Tqm=>)1JMIGk9aG+?>SKC zJ%j-iG{12yUUw^tV%3=M?$~c^SStUu=wBJ-Wyy4h-M|uqYv}G-qb6L=Z#+Ol{}R6< zUy^LA>4$aI>`RK!0%~J`VE|RXLE?P02&$zwcEL+P1bbnS;U*y4AkUl=ge{elb5d|6 z{}lkd#PN-_$>|Nt%MO~pde6DB`QanKKmE$@A~J99KNAHE z=q=ymW&iLTHSsCw7mSz}Nnw|}X>Cc!0*Yo;4-KcjJruLq%QmOQ_94H3D4J-|bwpu`& zLAz7x^7UvY?C*sNQKG?ljMsdB6^}s6YMkVi=5l2-#(A-|$RLnmG~i{qNdNDdPXz$~ zuMN2V?+0+gBcOv<)ob~tDt#iO;Ds||9;Q!unnob+J(bch*b|HOScNKdmd;9QJ6{s) znrooHb#F+!IFU2u!S2)cXpHhVW$9^oYY-PRfF4Fq1|Z5Y`=@x>MZE_*UqLUmV?VeE zb;b=JNFy%WpaAn!{^%a8XtQ7CBqK z_f7z!?E0On04GiX)6-oe>l)eDUEEghPn4zb2BTWg9;}%U9;{@#0L|lZGG|7@BRVMT z_gL+TL_mxWpAU3(an+C;_Dy~&?Okv&qNlFYd4FpB^YoNt)kd z&{A?kWAWy#g28)j6Y#G`X-n_x7dG~+*6g7Vfq`#(2u^OM7|-voistYJqoX>D9tU^6 zQfy0Li|ZkWg{oZV-h0ZLUVrCzsBF+Nt*zCl%5P%1PJumh)#FE$?TUAD|;m8 zRQ7%2EGdL^v(`86E!w?e%T?vR7z^t3?qPB-?xP<|conhUvDj`X`SXwWrfi9n^wsfE z5s%)o^v=Uj1J`#pzeV*CO>++)S)$QrzI@JiZ}_MfsqMX5b~U*nV|!#} zxQpuzUAbempc7xj>`^iazK7HO9ORz+D~NUSX?z`gp^JDN=C&B9suj@F_~RFRb70nE znx`B*bWqSkx;14{AyY1@Pd_X3#GKc~`=1*3T@OZUzn6a96FPMV_5B3>d-MLPu;R=q zkE(NFqHDj*G+C-l2ZJ3i*&857rm zuY8QmKQpt)v3|rGwp~qA`;vA(0t#_gB&BH3?UfXSo8p^}` z+0&)e+!v6F+J&$Xlj4NByI;GBrRLaq@uCH0g%ztHVz_F!D<`&!K7+BRYe@UFbtb}K zU9n*!7VIKuP56$3_h904#&uEj<1wO{rmWg&!NhdOtc-*4!CWfs`c0*Ri*{!MhW4p@ zzt;9rPU5HYmHOOIb4{LK`S^2xRd^+y2rx3+B7raX%!@PC=<4H(U)0TBbxeg zlHmN9lFDYS*n)=nJmR*GCn8a<3Jx1&e`ahB1!#X4q%Ucojn2UROGc&i`tbEB`lO`L z%gWhz>dM6?Arq^UlDi5jNay+%hP#vb={-wJ^_2BG^ND6@#wd_CmGqs-8^$&BvsGFm68p1UrYF&H3gB~ zDEp(o9`glhlB2k9#-H{SldrM|d`E}gJz+5RZkEYzn&CVaI6$*~K zldjU$t$!}eDiH2M0#y2yZQtBmXGDjDG(cH`5&60k4 zPvdr_ZoPY^Cc&P!YEY8qvh8w8Z})Gr12nZjPg7lY+c}Pag?x}VD<|%i;GHkV4`#re zbr{;{3o2r7ImEelquL(RO1dJ_e+VWnXfQKrM-0pk=(kzCyX(M`Q9%I>mf%j|_5r(m zw$Bv%shDrr1%0BHP`}1a%%JNkb8EUaCM>MD)z888IUoI*d2M=L{MuX2>c-Z+yXQ*n zemqAueajFm%l3hNq)(?$HsgKK;7~(`vSeqwjFl<0*IT$#I z9PnG%tXls84qh^hj97>b`#KLU2~I1FU?dXHYaZb8nA`0+e14+YM`rkr-;L&_kG97} zZER9*Nsp?vuFyY%GoAonEALmVSF>GCWinDtq!Zs@RsNs$-aH=4_Wv8MgeyW_g%(S$ z7Rs76J1HumvSlozF!n)qV+=`(P|3cG$i8J~Fhhl8?7Ly6$PC63V`eaB+^70}fA{zI zdS1_ezvp?~f872Z=XspR_BlSw`~5!pZ85l(U*1j)OAp1ks@ElO>vR0SW??6>+0Lev zKq=l2NtM1|g+SV}B1W*;$CM|2aD1&oviVKJI&H4T0?iqzhiG-s^QhL+2g5XjJsCkz z0BZrqpBHJZ7p;=o1l?Q*IB=HZ42re1oV8w89^JC%Mh~27cb2vYV9QQD+II*({1bWz z$Rh41wRHBqoOAohplw zERMJ%SCiwaYf7 z&-H76l$ItDA1e<6=z@r&LOHqn56ZgV%L2tj1paPyNbAcwT~f?yoQ(-oG9AA%@fJPbABO%E|4>!Vcl+2FZXcak4H#`zVHkofyJkP?kK+0I znZ+JApar3gll1ov6~zN9R{G09>2Qljdr$SH!j>!Z5Gr1iXPDgQ_VKTv7i^#d<)2vW z2SEFd$G`vc(1CJb(T5Anh70JFencD$ANyBp+&ShGm;*ZG|6C;pa;U)O7`QGpaL9$9 zCVOBY1lT(+V!SQ~Yq=PL2V8($&4JouoV5o)QB3XwwIct&HS3#rlGjVg5HjP~`AWpS z(+1O4rhe}hRJUdstk5kr5un^OV#U!QCFk3q=!K`rin=EY-;(*T)o<>Z_S2|KrP1@v zX$;Z+NwGgybVG&{cVWhQfI6UW_BO5BJ1W>;4lTV_cQ|G3yM;nvFf|xTgPB%Z2n`4< zGnCxMF8Rtg2?dOKWMkSqjFY{lZpjK3;{7Xa$!;@%+sJ-mJe}En^V~ukmqN*NrbYRb za4ILgLW#S;xSFw61=%eV?=@swr`Cmy`DJ8JYNtg)s9$ap^I!ExJ~}<^Dw1`z{neR< zk~jvY2GYONL98dQQ1rWIe6hK42H4loZ!?0Tiaq+3MU9?&8_WIQ-u`kJ6#WZpB@}$=905 z88%0D=m>aR=~3=S-JjX>H>J`Bctx&i` z)NbxCcdD~aFY1~cvX=46H36U!b0orpe!K{NWW5UtQIfM96~sYVBo@nAJk=nuw&smX zTUdRsVggk4@pQ>GMel(!>k}cOLlk^L8&<281kgv_U65At>$fQ-JqL_Z5CgGOwL70% z3J>|N9<+@lJGA0%yNUdT&5kf4*5@}HJz7hId`myyog}9DcPdq@pD=~v6k+~4WAL!+ zFbc|pom#_AImTZS9Ntluqj%J2>{$)1(pf({Rf+X+U5SRHA4si65oz#{ela<|@d$HB zXkRqA_WWe-s+dD!r0Pj7F}L@U0p?aV%gW|5_$}~M-KS{?$%Im~qvQHG5~Y>i zc>xxV9?n$MBaY^)q=4$UX#R0BQ8|g$#I%deLkcIfyGnrrY%+wmRk=AYc8#AJnEd`exTYZiSvR(9 zQoyfCsGosMN@*t8a=7zeqImKMUnLW}*2cG*l~Ys3qCXo5-JzwWh$2rD0+YwtRjFcg z;CL3^2{~8sQ%TE%&+M%@Ju-eTHBmkLE?yS4_rYH|jEC{5vfVVZfR{L3{bcR-{UErR zU~5x1sz4?rBY{2p{kMRBIsgW4w0$Fm&3EVANOLA#q*kwn&m{qxdD_c)=kLc$AYX|l zyXVUR0vN$W>@pR%qPEl;tyEEC#fW!Ntsr>X1p&}&wI4`CQX5i#7ks^9WH9!EIsz1D}|Fw&@87*yv8*Xgf zy%FS}N7QDfsoUEbYYlf|A3nCjzXer%9;s;4Xq0YYUSm1mAMIa%)j#@3821y+IgfJP zGn-Zpkh(hjcCOQ@`7PsOWm5suw0h-aLkEa%avI4no~+Nu9io_d?opQ_>IPYcJwFC= zYy;oU=QDMDU@~g%b|tiYcr}(Il46Gz%6wpN%;~ZBq>t4l_)u0cOVeH8WP*{GHL5P? zuH|F8tb#yVN=xUCo_j&YMVNnAW|yTp%L+4EW|p!&0*l@O_F!=`-jDAk27*xe=(jv29|LdJCidqsrU81uyuPsKZX))n^m^eP zKkdLapP=$IPtmz-+Rx4{|0NxF&_=Ia`)V6$D%kq;%26&L2ouamkqnt{B;5+Q65?q} zN)^m4ltQqA&Ll2V8ifa}U^yzSLH3rrI(;@AdXWAHjIB6><#*qb;HjhmvR`H8a%(L9 z1YN6f`z{fOFUY#@qB+p#hJ9rYF_G6>8d45hL@!YDN!^&`Y<0Yt05*F*fBrk-T#87Z z)AonS6Sme5w$DJ)1>9~%69^$Y#Lq?YVX*}xiT=#Hgz6CHERf+qqa6;mjkL?a^YUnZcTwnnr$VBEb2BR zeq+7}KK^XTmmyCRUf00Jj%lxOrd({Vs9klPscsOjd1$7wbz4SY4XI+%JE@;X5>Xj0 zo6eX{Z9p?9X>~_)vjw=Z+|h|gt`(0z>};*<@NU9Mbx%Ym1B4wt7;+Q+@k(lnz$H$n z;7W1ljFN{k=(6#Lo|8ra2Muf`#3v(}KQ-@TqIF0v>r80>7mK0BJ-RWSdBrJ z;&!I7G+!&h;qBsLc;L4UIL+LO>n*pZ_pcPPT%9DKH0S9JGkKTnMeSezPFnI#@O*-g zl((%%+`-5w*vm3-M&*n`7u@Zqk6Rgqo20Nill4j2g(VDGc()*dzObVT*`>xN_J5p% z%#>}&?mXt~{pJ()eN^%7+(Ek5yH@eVVEQW9VpVIA!AS9?X}cCvb3L@}_YhxYC<8t( zK>dc~2xbeCA8|Pw&@_oh3|u=z@pg^Q8kUxydb4aKbAupa4lROmhPdn}IXdquNbiiv zwyZB%4{Xlql^3WrEacC}Vina}7tR(Bz;olYTjyTNmhzX*2G<^RBMBPyto{;hpx3G6 zo48W-0>m4=Vbxa|L;a5e{{pOV)8KdGbMA7ro zP~%BnO;2y6m9w@)Vec)DygLDki(MyWIf)7(MiG4Kd!H2`q^qY-o%h`-#+;|=Jqf55 z+I3A{Eu_x@iIRxoq=s8?-oQtDoP74SXG&%|MYHN)&347l))I%T z-l@P3DGt9htK{jzx$O^E(;WmRdRCRThE;3vt9t@axk?cV?Lsjd-yUm{V%8+<;&?VL zn^Ex~=$kE}bsKBLVTBYd9$zR81gKHO>MDV9qN`3b&WRjhXlf0cn zd5`gCHa6fyI z%~W)2CNwaUt>E5A1%ZhlokM34i`4-xKllvlj3>r(ypH6t`NPi9KF+94@hCRd@GaZl z88)5~*vT=!cb9i{mv8L5{Jm5YZLQ<@^%&j@)VQU|Agf^Y^i7AD6t?~o@B@eK5IbxN zA#vTDPQ*=9gn?h%8!1ji`XYlr9tigZrue8IGOY2wTi=KZtrTffwAPY;3POkcS>so^ zcV|E@i3d#_(J+%T7z|liP0V&)dxD1z@b+rtXx0*m-`KKze2#6v5MOFBxACRvfVEeja?aRbjc*U5>lAS1`K_=RVWK`oT?KQpFk`UX!dl z4|{h@GeOp`&5BEQlJToH@hs`4En^z9$K;pvCCtmuPy!z_K#{|!kmObOK`qPVT zOw)Pty}x+9RGM(94J(e)kyxhblCO68vZhh5sV$>&L`&S=dW2*@UtJ9VAFY-77K8cL z&Y$JMrjbo2H4Y#0`fiw*8WLYD9?7sAHxCZg?9z5Q714BL#Qbp!>hIw522eXuBfs-H9*o2lOe8%xOTJsv=bvZ(YrwOE^5FWWn5Uk-VpAiz^OP5-#asMV zYtN4NCW^LIdr;lb?0p z#|k17xjARJIbmQbdf_Ra8jMoG+4ALbJ?M_ zKE&i)yO#)U9xUg+uaZARS!{yZEcFpo-R|v zBb*+nPOtAsv6wZaVpW{Wwr)Zaa9q)QK^#-c%+;61OG?SNwe=Y> zvx1eXj9-eHT|;#cYN!{Zj20qaUmP<(+w*(r*h;~`b^ShMpQQd1&1h%%s_Wi^-J@T( zg?gt9?hr|SA;BkQ3yn_<6%E-=U9|2oLskwauPKWsb|@=;>@S;6Wwn&8`)b^8(U^9~ zz|zm<_s~oRHw|Rv$Zw%T>~W?)IxB8rI$J!k1eK9y#2v(H;k(wt#o!X>J#z>9cvL*t zD?vDb=VZe1=bOV8?fzn#Yd_#0v=_!%^R(8#00E>G#DfRqn?;7y+OoN0%|eh$E9)_L z1^RkOMdlpxdq@=OcxuLDAQwN&VROb>dEj~n#~R=Bt00VChM%nu#=*JLkZ;h$fW@%gwmp zowM_~LFpNJ?KYp-wBD^WDjs{z$ilxI?tMCIFFW5O?|V9k&2?dYRXp}NZ&_T5!H{&B z<5!V${jn)tZaT@EFw218wpEEdU8&iK%QVO3cez=kJLQnNv)>(yRqjOs`e7r6!xPI! z+94IvxZZzSJ4bRZvv@x$ngI2a*^Pl{_aLSrIN)1AiCzEz2|l$%b6m>+iS}@uts%2| zpqj<@O*U~zcgPyqYFpkTKIy5Z}dJ)I%7ui@XHadJj)7y z;oNJ;bvgh&S~q~ePX}K?M5Q^wOZyJKYth;f>#3~PShZ*S#v z(ueH%tq!SDKJU4swwLL9V^VOZVyhiMl}&svVQ+9ZkiN%9Brtog0kXObWUn|2`gVI4 zu^k!=-{ZrIi->xL?Je$g?`AOe;F{`g<(K`d6GO$btik0sb!saZhb1eJb}eSYaA>`=#s2zY)= z{8v--&hga2$HAQ5)FT1Z74PM;0X!SXaWc{8*J!Qh2svOX?PO|e}mi|P$c2>TE zuqx~VR|!`YhB301PT0;MEEWxg&g}B3bp4nalN7gmx%8#!M7Lzy*ZX`NG~cY}ZLb8} zhYlJmo_XXHII@q;;jBF`yVRMQNzNK8^E5l(TVU;_-aQb(-{Er%AS0^AF%6w35h0i+ z|GDz^*HfPPIhFQs`dD)>ib>9uJvb1ulm8sMI(6#mVMy(SH=p-r25eF0-ad1f*Tvv@ zUqV7NInIbF;@b4cE05FSCgybdc5~HvW83smb6Gz;q(MxsunMtwR9j=?vxLp_r-e&X zqBdvQUF(RfxwCsN=)KndjH`)zmK4nN7AAeqbJeDXb*qz+I$5WI{Ny>})`EyidoqlW zLp}^jY?|+2AJkys6)=LCU7$M&qvWkscfv&-l`NVUjZ(6en7eS{KN4ptZ+v!k7bUjB z<}hKOcNu#W0%zpBgSrTL;oc(ZQ8RRsYq(;lQoK}aJrMZF|IwU1a#$(-{y9Yr%R^VHkJ1N`?(*N1vAA<}1 zb(uA#6`g8etMXDc#OX&k0$xPA5QGWZ8bPqkMnL6If|RA7{C^}A4INItt3jP4YdF%+ zcDNn6>9D(s&kdLd58t&a1+_5SLil3kOiK9OQT{nngTPLh{tTN^~6S*h1j#n-(8lE89r!Q9A6E2vQt2PK6p#`Pr~t9~Dp98!fHaUVF8$Rx z(1d5QMoa4|!7k}NnAPCmNLyx7z8Zha^UWEZ0+;iHY-jzo`(T~703^VEIvCfauPBGJSHB|p;>w3U z0tjI*GUc3nH*~0Fsrm{3;`SxEKvA0PIAc-9znX~z-{e-1Z@NBibj1;-33crabGZlz{4d?DwRM$XN zIi$NRBiGY?;*7tKPh9Q4t<(N+cNfj^077{y_I#VIzi1PIj$bJ^n(XN zyP>|~1IQnqP3UUK$23aXSv;iCM7y=@_Y-w4Zq>3`n0BE%kc(3!k4dP&#Nzl)emdyg z@EQ`V(_A%n@b@5xaJf4G!fi0F_4!2F##TNfHxm8$meE!UmA(~ao%q^D4wh`9(%>m1 zfhQ7VS=O8>Ch3}kbr+#(;{NaL`R<7KE6NJRLa)r3)Kmx%KfCw7E0&C@tn>~_Oj951 zGkBu2bQCJd*8-AR&8gq0`#|j4SOZ%qaS+Ss2g*OQ@-zDqjS@o2$L=sU?~ezN;zHu3 zFoL#<3-B%O4zq#HenqlhPr!U%eGN~eB zIFh(DTG~DJ6y!SjzHWBR2s8glWHZj1zwXlqy+?NTifq=s%iHTspMNm;u{{X{N2oP= zbXhk0eC9M-rODp>uFCxYxNyYwLT4JJTShyCcarV<5s1@{>ay-qs?v z0SH1}6R57Hl|~#S|Ap0S&Mw={m2UD1*?Y*HWm&O0&Vnu8nOQvj*U=Syd;LLKg#TD3 zX6t>^6YBYxlA=%BvBZ(Zk#@zB+3F`LkndMk8gEo^#CY7nlS>!f5f8cJKozUhMS?$T zrZ7weWv6Y+zOQk1bLTq``^A_i9qm@khmi8Z$oBhc&N55959OlAWaUiXMykvN%x%E$ z|D_zM{KZI`?-d|zX{B)>G z%}-xrak_WqkPxp=+1U6q zHH#!>Y*?;@;n|Wo^M^9niKdk zQ&VT;Wn2gvYl$(>!z|W_8`!%TFLCph#?!n!qH`cbMGAKNaH+h`^ zxT}ugSy#saub;QeTyVfl1>n18P(K7uQY*^j zPBLGOJaze%RRtOOvIuG4SZQy^0&cX@aAz^uahj*q&AxtEt2WGTlhNk@k-94Db-PZ^ zxs}r;Eo>SiA*5M9S5^J}!_xel%4l9M37%CYf4!=k*L*SeEbZ+cDH}vab};HjVTO$G zMD^q^j2AB{Sd?dg$gV5Y`s5n-+hLvEgI_ysw7bft&x&uCF&~{D$qfa(8A&{h-8HL_ zw-%^6-#iQ{0Uc*8b;-N8+7Gbp=wMdBBTq6#bkmS8&cuI{nViwFts9PPE>?W_P$m9p ze4l~6{_%*k5{qX5Z3zoh`Cf&MnlJ>jN;5_Nx+C4|*CiakdK4QU=B~bZ!mLct1z@$u z{Dn2E`)7AF!D$RAv8N5HY#D z7j1XVB|m|Ib$I}kKTeljvda)zxNYmhpL-CzunUPRDA#S@m#zBm|CmCTRRd41JvG|W zl~xQ1*)bIG#}TI?M**na&A7uvQ*9=?iQa>ZHGsCv9jT#a{bCmV7$Xy#Uh<`v7wR?C zRsMybI;0(RNwS;46ahLGk4qz37wlp|uFNLD?Qwcf~d6qwEutNCG2X*pf_J_M1nP1M6-iw8X6U=p^^OH=-zA8EfVwUbYWTP%(;V+nN@ zn7X@y9*R%LAc_EW}`#K@LDOtjCsDvS3;2ES>W=Knnq zf^^w4Jh-T{{-4K8{yG@D0_--@Czt8W?&8$MOHmXXa&b~UnBi!HNn zuQF6Aqh8D}nG&$RMmyLy{GLHG_C#P&Mq?{sX}ov)XFY}1B=Q24U?Mk;ufYqo*jK{l zkNAFG((9hMG9@R(tQnO5YUxsZWM!u*L zGql50&|ZJ<1nzBB_DXkqnzTFsL6-W$0ym~cvzQ$XZ%M7*Uw6N=f~?}ww_Z$&u+Igh zp#`GmhpJCg&8Bmas^!)6$7n0sLJHQ`>q~!S$XZuIYNZwu>&5eXj~~@3-JD`|@b#3e zp=mQe1?+^<#zdz+DX(+bhOT_oeyvS0(?af6(KA$Dc_N=X4 zH3_x)(T{k=0XMQ zgoL$1(oXKDf>u_9bs}&L3Q0tL1{0@O^yw#?wlQ(Cw3_tM-GuJSSm%E&5|m=y2T&fgbirJqX#9FWnm2stJAXFQ&?$N(g1qM&>;EBf-VFV_?~@ z%{^|nD}q85;b)1WF{Jrc(Y?CXH8IMxCf9&qZ=YAxXGg_eB&x?NgQuaOz+Eyu+Hawu zj!}Gscp8>rXHs=h{fZ_y6qlqjhMQl{*>0Eg%Am(IICB!GUGoXCr8FvB^~i8KCOT|Z z(}4QhUU1}?hdAy1&DF!Dq9a*EdWu0`J$0%CFb_r909Ly9?1M)i&B7XM^4m1F8ASU@ zxEWXJu;&D9yoHYD2@PvIdYHHzZdcOMX0sGxYq!Q+&{bbiP5kqW zj_p7&yZ*O*5~RsKb9(ixaBp$3nra*w;e*zw-Zv7K_VJ%qNmyx<6?yU83XJkQbWN8A zr3C~Z7BjL%h^IEIV6xOiw_XQBH{cMxO;a-xww<)5;IP{kO5PdD0fa5>8s^HrabYd- z1jwqevmRu9+OBfbhOX_h>Oa$tV7&_d@|@JH(6?fw-PJw{mIsHrnK&7i7pQ|s?p?Zj zttw*~&6vzkpJPk24mm4qAMlONb9D@0DOi}ao>3n%+{BH5at(m!)z=kN2F ze_KE(0n_qiHp#_aRuD9znf&opz!4sff^$3{02j^-Y;Tcuwb@eJ1%2)Q%xk6BWAxtD zn6ZHm#%omvS1u{&+a`C-IHGqNeA+b3g^sybY_}(P~4VVUzNLml(qbQgdM28qp}7*`HG3${bBRq)w2N;ljG?Cfl&WG z6OckLmynBY_D}G*ESG}v8#n#^#D;Ba$Y`b-Tp471a(=vRvE7BKqbywrrG7rIEyeN9 z-2y!9Bi*x{5mH%AyS#|Zo+V*l1MhniaOwT)8%hs_&!qP6?Vk2E%!-6J4XHid`H0G3|3f{~0O|sP)48~?XhnudM*TG{j#$ij^h?rrvdpGuv;HK_T zp9obJ59w-yg|?tZ>Fzdizp=W$=i3aOCTe*#p0nrCM|8d9e?tl5kK){NiMW{xUi{quL;=ed5X z34M##;n%+Rcj;bEvh>j2M)_|yBHs=ze94M|n|fK4K0nD;B!EIF5cyG|)T z>tzJh#rz3o+mH#753W>Bgl+iGZ3NGMk?c4y)J=-628O02Fyl6IxQwzki1-tz{vyrg zy!$g4jiIddIK* z%>v+6+F&MUzF;pDrnA$gS05HC;|(hYkUC}bz%(zd+VT}j=kLKv&`y0|!cOE4z<85| zC|DDM5-E=?lYXMoLlMV+>Suc`*9Za)c*m0wO)r(M|En1jFAfO&4PBMeYbnD4t+{DmQ8b=? z#yxu>w@qs2h+@NPNuRA+%JkEHn(v>lhjZqOrco+29zlbFtO~su@>v*g&DLNI;A@Uy z-u*@pEP!+09UspqC%4=KZbr0f^(;I~FtNQNx;5Aw!Fb0>qc9S3|rN0b%k=pdEc8;gK7XBqFdkX95$wyLvzpEix* z1LPL7MTDQBAA`x`i8zrd7rdYCxNM8Czo0O(rM}s6?XuSRHeg+0d5e?tlmU}maxD1D z!ZtPa!))ZV0))QAn5`(x({@JhluLJzUWzn8V}pqnj5Ek7i1IXur6p{mITK1LJl+0} z`Tpwn+1`ZMhs|gxTqPOSj?}}K3JEHK;*9Y1K#fOsp^}p#Z$058O2Q4C#U!g8>Z^{t zgMyi4I-s}b2GEO{liTHs>&g`?PpIVE?t#HcUU}=Tf`xX$mnLOhVXT*`$7fXV<14j{ z=t`s7;SsIDRm6;94IRFgzG64N*?6(3mM{|bZN)_YV$VewXnoFZA} z&nup1@n2WfSa=iURh3Y8%g_Vqf~j3I(Clqjd0|Fo!Zc=3=}uF|oD~`xZETb3J{1y;-qT}ER&Il~`qLu&3C^7e zcN0ZVO(?dUpxm6eEr~$#rjb^+(5k1Hwyl4x!(w+^Xoz(X&VSxZ+bfh1y57@&vLS(v zpKw{tPJPw=dTPvMV#V!lwWp|!=6EQDU&UlCorgZbG+y0qL-nsfK3gX>!9Ufl} z``U}iR>4E+DjAtg<0~q)CVq^D7C50Fc{OjD)usuy!G{f7SaJK}Yhx&{moa%vH&?Z_ z$#d|vgbkDab@xWxD+I6BOf_SlF9hH#S)u;I@6eduX>!AbBJ29*&~_2~8Ps6QBDBW; zF=cuyM|Mql4b|we#TZl|;;p?@8g7(J114%H0$kkD?8nIHCqP$OZ?ft?eI)!nyTtsL z*SG9@Lt1WCM@?1^0XJOtC#%MmD->I#$3WxPJg$P9oikMVA9A=YqHi`#V)!a*D(NgL zgk+u1*1z1gTR-XTz7%`d2r=D|=akz8?-iad*`@c2+(KNfy(=HHA`VuOLE=3CDHC^9 z@Zn%w0*!Cpwm~*Mi;!-gJs6OI=R7Ivo?+-oslRTUZo>3y4gO9JfEkCpI=q%RrLSbN z=-MUSKQCsgch}5WC zBM$r0S3HKiCeB(t@!!^}@4b@bXEBkeK|6PYE64OXZMZ^%8-mA+@r?EJ#8|?VlW_~8 zFEfF+bBPbDmNOFW2wbsN-674jw9=2wjSazr+k$F!B*+Z`~$ z!rr%)$(7^Y_K*m{Gc83jNP3qT3b^%^{dslQ&3uab=+hMzRWt?sUwdB5xgNiFv3X@% zcS6#OF^Cq2S5Q_9(T>@$yxp+*gkfb%JvlQnRr73b`*6UXLqmTIQ}@B5ry1p>$c-v_ zxn>4&g)!Sh!e&&KC7?q?Wk51icH&U&6_PGEIm}2CG>u_-nwOl$VKIB!dvG6Nq6U$* zuOs#Qs9535=c=rTwJScEJNK)|H=X~6Z5z%hTOy#juem%lgwqnyJuU2SYK*!Q4{#9M zE1s>kDZ{PJqOrb-Yle0P(@DXv)OCzSrJC=6D+R23EhqivhIAKr2r>P-WAZpw`C_-O zbCF@d!nw&lLdu?6`d-YwU;FqwuYWiC;*s^Fh{-Wv6M(Ima7ynLwz~Y-KMN(BX>~bj z6bQ+AyfSasUv0Maumh{!2`Dn8mER`&g;>*N+zDn=#83IMi%@U+OO(>MK&q07N)W~D z$_g3nh~9Q+5Z!v21?gn<66nFhFVN3y3gv80r;7T3g?<_XD&Tqjk>Xh2(zRHOi$t?D zCcUb68nr$)s}}lm`OQzz=D*4TyW4JB66SQWA9wMcAA|l;paqFC)E1+-ia|f^{15IcPB)TFu(0kGahH`L3b# zIsj>A;kpS} zk1mJqx~xJXJkfGKa(B|R8?Ku)_1t84>!o9OIgnvj&z8f@00pmzCXWHFX2i}cGk;hy zCf`%z^e+=elc2lDBMaHrDk`|(p*FjKovDP@Q@y4wm9TXK=&|aNoaa^yG!mhWS6QI) zb6&i=qOtVQvB&r-HAI9s$2QaNp79Wd9oqXYS>$o%zaH209209 z;=Pk$opmPF#6!k^vZC;h(Y_xm6wzc|qQ^#IR|nT+4ht9Ue?ah-$=>iVu>bdE@qeFH zKKG`kms$X|*3~M!iS6ib|I=rCEAJ?Rg$dPas;7MPdf;zoZxOh0e-5f*(ukZatpOH^ zUr(FAi^#vdpKB8N8~c{6K}J+iS#iqyx8phb%JX^K^#9X^M1@ZGZ|ts`V%%kHTi@B> ztR_^b5G99VFnk+wZDg^gz#ENzlUU4>C>LZaA<)5wmj~uBvgzDyZAaDN0{jkd){}qk=jssK%8%v{aGkb49sg}EjbSjFaW<7P`M~I*_{!OdGEl$;S${=`U;VHzT^t@ zuI~Of0-V|MU1&L1e_=n;7o*7BH_(n^weo-rORXpZGXVbGzXg}lu=)}yMRG&Nb~&V0FXUq-vyd*{u+MS z&;RuvOKWIIf&a*rwE_astm&9AK)nKJ+2lcKP1t8ZpXeti#M14yS*aphlrFe>i~RhP zJehr8=LmRX;jcX3`~G${qOWW&n@K7T=1w4L?LLgNkFj0*JqDXeh|oFF-u;QPy0u}b zE%xDfBbCv&gepJ&_Q<_f1KW*Zwocd9?<%c7{wxPs*8_6?-F*>$^$)xCj(Mv zTR&}*`Erj!t?Y?V)eM`Z8+91%tPRk=IUtILT^{aL?VhpNEhWxGL+P0{0-dGss_oc8VyO9@7ZxlYDhqgMiU|XBonpx9a z`%ImMFt!Y=C%0h6P1Esoy>9d4dph-h*b+EiHvsnTV4-sH-Lcdo*xpgTh^D)x4a@*E zEqSf$3^&$ks-@DCzfS9lPARz_^mcTkXzXjqr&|5lvHpjbZ@7bY1^k=`7~km<14R={ z0ep@?n7a@n?s?6&y40Q~l?8BTjVn$9&Gm9__Hti53_0ZMOSQF!Qd{aMbq%{s>3}X? zu&v8K?Djmz3eMSj#n$Q*Ew(INKVBZM%Sc`vWBhm{n#}Zghv#lh(E+S!xJ=-5i`?98 z%F^qr0L)m?bWG@WMZI>U8gwMqXbXS|FVPnu;4-bP@_{{YI~ zT8w4g@54OIXuJ&&JJfr-7eMrft$hF=W~<`OAEf$B%LgHxV}bNE^iH7mV+#}b(DL96 zK$q?{Bu$J9_S2`87%`lHj&720MPE9Ac~83xx|Amlz%?Tmp2Fe7bBjw#WvVXVs-M!I z-@QK%nb{3Wi^sS}2D`!+4``;R063^a>TwHdj5BldN@K5@!m5IcC(a|| zQyR+T@{*%bvC7IA@j#8!U~OnYuwU2MPv(&#Qr*uMai3e0&URs;5RGyxfQ{a+__v+t z@GjkNVZx%uaqNTRX&JdvdM8DE-Lrf1QbiotVNAaN=vuCZCqePSc~;O265aFDYiUx$54)e4Y53z-Jc zUGqm7XHvW>Ju_nM7?&tZ$sL1=J>vj_Kw+{cUt$ZiJi1?q?}o{TjU_@TRhw)V-E9G< zWq0c~gtoI1kVQS@+o!hN1I9CT*`8j0b$R#7UyS!W}6$3){IDNC9M|U7i&M!%HDQI<#NV_v(4e)0~r+pKyk;5u;{xb9o)b z)7Y(d*>FSipYZ&|&U0H2y1K8=o_Gz=6hggwbq zmy_1CkY3D>G(Q{eoR7*$8LVw(1FJJ}xg_b-6wz$QLSGG4`+Ckzn$A?#o~;%kDMh%q z=cHGdq-$CqP<=Li{zME$(k4Ui( zMkzl#%vMv`xjnk0>>o9G!em-#Cb#Vb7na(Ryi33F$Pu6wbo)*@dC4XOl0%b6b`~Vj zg;80M!5hu-jp0g-IH@$Xu9lp_xcYo{V$^3l(B1Wv;1I@@%i!dYzCUD%Znrb0Z|R-V ziPu_wa}k{G(XyxZM5}QIEk{TGQIpMfHo4k%Q*a0uHdcG62bJt;JS@7;1~{vI3%6P{ zi+VU0cFDQv-ECP?HFZ#H_17hZz{eXM4=;Jy29m=w;#y0wwLVZ0%J?HNeq+^{%R%Ob zQTHSNrb)Ayp8gv?{p9MVWX_<`(Qj~?|X*)!n zC;o=@H}B>Nv@9@ruo*m}fcOr6dz4Y@n1a;zkP}{YFW$(07xm@^yw9if3R1xtzS%_g za~V&BOm)t6*IjKzH!Vr$$O(ZkPkW}n?e9TfTw->Ohp^?vgwluO9QEmwgYpv8e=ZNn z8z#5Er_!i0)An|n79qnmY&O6x1&xz3=k7@3G7AtX^qa=(+iryZpVBGv#q%~zS|x%# zhiitw@h=BZc1^r4jN4-wSI8d|+NMwWw_BVWRqf*{;ws~+4f{xb_aL^3XhL!!^J z2<3JJoBtZ&(wq61?jgJ-Gj%*&Y_DqPx=y+4Dq-Q9hug)L9+Bl{L>~FjkGt(Ze`MW{ zwN|S&dzShl8J0tRP;N_6Nz;pDH~rX^Cjaw(besV(IwKQ4?`dnMUl8fUXp zCn!6PMs{1vI6deGZm5l$tZCV;O}N#GvfI{j&rYNkd{bLKFW2z=dNE-IL{e=Y16%F{ zOJbrX%+H^Pk6Uxm)1!?S#+K2c_llit+OyETx-Gm$Z5NXm44YfIgj4X5dwK25V;RMu~G|L~Kp4iSnT>!%U1D5qG&L*Yua@M2u zO`Gm?nei56w-qqvl@}*2!t}R#-hD?^fKR3FIId>~#pT^wdYgseWmKmGwrE1)>%xyG z^3H`dL4RHuPimP`o!ohODas76(aoRd^)FlIV}x$)37OU9nxFo>uYs2DcTO3&L*}O6 z>oe?Ms@W!Mh!@!l2X6=7M7+))OvJvM1$bDGE)#7tqIA6bSe*(ZT>Nv9lrtYT< zZ7TYmQyb&1%B4I?Z2z#V5r;%cs8-4`A4Uls?(}5L0J%5q#0Hu4htB*MdS)1@yI9XN=#I4^E)G02+qPpwn#DDR8Lv+h zT+sC%DzSdnZr>Fe&^LQ#@D^uI_H&S<=eFsbqgVLQ#h%)}pv5lL2+zKhuoc#P`tO4q z*cPcl$50DC0dORMUs1I?JpZJgyrH{HOQPTXY84Hi?8#`GHauC)|APOO`;qdn*ue79 zOd?e?(=>rZ|#)Yj(UZpVQ^VSX*fUqh@ zvWUBIuSVTm=;5Ogc0b+qmI>B-=;!q{y;67gZ7=S?^M@$6ihVQKUU!SWlPskn3q(29 z_Jy^9zyH&%P10yZ^P`x~#$*ZDK+MbszQmx^;i)YF_`ng70cufR%ecDIj z$2cD2G!hh6@<9@sy)rYTjT+oCnU>2N@D{*T)V?*gi&_(R{lk6et!}<@2A-^}zN1>u zreHjZw-FQ9=ESeW?W3YL5NfIO9~kJH5&;!JVoxY6`7n0#Ef zb)8nxC8zvuNdF2ah@2|WNXrl^!TZFsJEg@XkNr7w>1DN3^p%3r(J8g$?ESG$TMp#hg zd@ty$#xQa<%aJG!9cs z1POeyLR9`)yLt;3;aHIBvKl{&UJ9^aSX37UeE#@6UL0FGKp%`*GYozwXxn93C6mK; zVnh9pU0u3jCpy_wJf1yr6m0&bR=RDyP_m(aVP{)1B)Vi<&!~v8*qRJ?<^%L5& z2(pm&vxSZ?w7I1&YMus#s#{n!jcX{j_&DKKNF@unZr7=vXG7YUO@CtyG)x5!SEdJ| z+$~32YyITY6ZxXX##aW3N^7+xG#Dty=Yz5}N>vpL-W!Pi;w=caOzb99T1q(+3SAe! zk}u3FrY4Aa*Yf-DPt2Ry#zw14bOdgfWY2@kj9&~`gjFlt@uPk{JSZhO7-)&FqC5!q z#t$^%NARg-)z)g718q@~W{|ja!qIAp+bK3{cu!1`Q|<+q7h8qVKg$jyP8Tkv_(>S9rp#}|xHYV7 zHd=^Pq|O9ctXAA1RR9u88|;Nj(P}5Y*EnAG#dUuF+HuU&(IBWobB3Use5r?XYxU~s z=PwEt(p0BM#ymR<3sRbL^KvhpJvw`bWb>ASp4qv~23LX6S?Ir`OTu;^;~8KkMLSEC+{B8+&G4^v5H|m(ImOl{!WAn5u+%t>47}Yub%61r)ks z-Fv2(MacE`e4r3z#~)PdXRVzc93rAJO2q0pmX)cFRbH2W-Wl>sI$c$&=f&G^tvzyi zt`ME@4gD(o@}KbS%bz!I;%q6hI7O1cLy3<|eG3zKM>Xz=fsMyuFppyyf&*<&7P55H zZ+8UDzHl81gifen0|mcEvsv#<1}AMP*@Ty($NZL@0kyez`%T!8Y0SxNIb5x@Fd?WF zQg2NaP0OdYP+bc>yZn@qTmueTw-_a4+msxrVA%t59xhGX)MBO9Tj^rh&|wUFsk%1a zys@?wDqw1L4ZCq5Y|NCn!uXP1kf)`cw_x`ryBI1yku^rst&S)yXOx`3T@6qCI6EjC zuoE#Irf~?@L=mg8h#zlz#!hvoy;^mo`<6*A+Y#dUc-wZa&2G7( zL9bS2rNUi3O)3CC*LE*x7^d7dcg!`TRKFBVp4aAf#D!2h@DK=F!n`NoJwClT%I4+s z=>tmJ3o!GEViM>LN255#LBxfEQ8$$MT^LaCaW0W)2i08qU zQW9E z^Ob8C2iL0BB$iYwNMeT=Df(luJmAmvz)c^ep=iKIJi3<${&2|(u43pS*7DHVSGTCh zg2yorqF2d8PI2GH2d&8)8pUd~M#;B$JV+=(%sQLd4azLOl2uCDr$!2Ne%*hTMOeyG zaHV#o%ir^43uKm7_cm~w`0*OQq7#2?N!a!2J}P6LP?Y#(BeVH^rO3=!-z2@`ST@=# zRryboWhT8^zglul0?TGUhhfuZtsQ%!0}s(($@O7(ReG%(4I+^r2)nar;gp!AUQT;> zR83%Ry5J7=5Ui$*d>P5;*jKd+0er-; zw+Q#eR2~`CSIddQLQB0-4q430qV&hlT{oWRhSg+6o^z2hPq!WbT7Ron+!fo(gwX^2 z7d<$YsCaOy=Br9+g;(sgt?vlOqj!DbquEIlL;^e7oBvOZo&o1o`W2LXYg4h{B~q^~ zR76?t@DGUeHqOg#7xXb@A`JfxG`jNhgO87QM+3%dHhVI&^8>CtI%oER*+6+k%^OGG z{phWR9djgK*e+sfKN7|(;`sx0ol@X*%xwQL>Z1_@#N#tSE1-p^`u{{@-Ls-tC(RVq zX7Jak32@7d!H!-j{lqOEl58%z!b1;}QMIp?xw@`~zUgW$6$c9#Wfr;pYu2warK{s* zr356JnO9yXb|r)Ir`0(~YC#_lNny1lHmuU8IgS_<{{WO%-1UO&+*J(1kC3IhtOpd2 zXeYGFN};R*)48{ThnaXimzY3)U;TNrZYUrin&>_Kkn0{B;{uKK5_w+&&Q2PYR|i(C zP=MZY@kM*3Crs8ttofFpg0)&?iZ>V&sJ8}#QdY)i3CqrJagarU`Y zuezOUY_QekDS1+I)Z)g}PP}Blmxnj(o#ej23XUGgpm}#!s@nBo=IP3Vr5a_n7*BuL z$B}f${;lHEGUtZ(g^(5-`)`-wEYL3``A#=?lmCxxZ}%4lJgJp*i`I9AAs*v@64Uu)_57?UT`U)jHU^<5IpIYNc)o8#VU4_EhUhNO8g^ z?ZnIQ@7bTE3z{CR*5B?{DAuo-zSQe`rNZyh*?KGDvLkA>pE~}*>b4mo6jKqYmocn1 ztdy2XwkwMsa#hh8zC@DT#-f+#x_Mx$r}}J(T=CPY)7~#{L06j|sG7{AjoeHir&y>N z_m)36>;K}%@tMpY3j5+Q0|8$?>G6K8EHuT{^s z-r6be*6gw$oL=^SOiW|H(>w0f zN%|t!&yDDMPG~O9-e(`iLOO9led7~>*ZpLC$KuC3aCWjF=g2UZqePb5rnP{C)Q7oG zcBF0_grz2aPoN4MQ&T8oSsBByBr{}ADbC=YVKlTUkp0ssw7$@oSFZ-;75_xo5aYda zdlnbB{(##`1`k)uO)F3?o>7*12#pIfk9fc_NZMD+QjnsB5oiV@l0xbapB&M*m{orK zHmoM8VqUGPb1mn))DN>5lXCN2M9o1H-q_&1+fWS>Xv>o{I(+en&99T;%m+oVSpzmk z@ulV39gc+obH?aJ{;-KBY%J}mHB{sYS>Jl9r{ph-GH1tpqOeFvw|mPEo~uy|*^Lgt zR=+IB*XF}=_k5j8UCn5b~yQd zZg`gj{Nx4h&Og02j@6)wtvZS9B{G6XbAAq3=wmmykNx}$Pakg^oJ^`v!hX1DoU;nw z01{N%q-;W*8JpWHfpv}p2fX9&6ve(_{_B8x#U_r|P>D$))&u0p)XWvr{RgV*ub1+E z6;&zua;nDhMnL{ExKz@qV9Nv3mH^Hp4T5Kaxbi%=7w?1mrY?+QdKy&4F@2{a0q9O@jF7cQ1rX)$Zw39yQoKu7b=6Kzq}|Y zQ1QA^R=W$_Re>~@IfV!rkNiei4v@JlhFO|wq87V7w7=oe(6=~$U#0VQJYxQRkda?a zz8s>!JKXzXbzz}*lFbP#$LCgtQ>)oAzq}scfoV?eD+D%4J_E3Yq@Lhq(?pFMRY;wx z*B7=B3wayQJfL0Rtr6j6SThI<(|VlWwpXe7Ok)HJiF*_PX^@6ins?Fr@dn()g2MeTx^ns zR(b}$8mlws<|R{4v8{NMOi0J9`~nR8d2EvyN3)R9WM@|nFK_E9FAeQ#_O!_-7kH8f zNVJ1E!)c1l4K~kr!QFiW+mjne|Ar=#$WJomlmdv07@l=NO5{zgp9xz|1B?8)W$$;itFm0s6=?Bv{RxXwN_HVG9bV> zkcQ0XEGP(r287ZeT*YYj7m+gN%E1*@y{8`ziHCtkxV5t>3PlStx@%|1KIf~`Ad_#!CUDKW{85PW>V;3uQ>0|2CRayHe(fe`|yq2Kl=8FO>i zXMV6g8n0q3e&N<+GMiF|R!J@9Tc)z!$zxVR=8SMDIp`CgKRw}@2FZ3^jms6{;qd5i zhYVSheBHi`qR3kgLocztljn>zyDIcNAM+xuQktx&wX+`cY>E}HC3Bhvzyp<58kqOt z4&*=TCn#J+zQm9Br(~Qmtq~fSCy{p<=O?g7m)C3i)sYvT(5l1V3n%h(I7@Mq;tr4M z>8Tt32245@Wn8A9ch|mzy*y!D4pDV@7$S|3kXh@1!h?~R5_+wtfSTjRO zOu9b1Pd5kV9RN`}+2X`_(;1A}q~RW^klNBn^sD3>g{;Aa1tG^AN89N36<0 z%aNb<=5H`uS>Wry2Gjx>-eftEOae%TqKBWTMAG)aM~ylJR#pzpU>u_UM~8 z;X)|6gKy=+SMGsk3|IoY#Bz{tuIT=+10`2`dgz9*tD&2Cc2oWJHB?=GPVZj`^Q48n zB$hw0gK6|^NppkG`Uh75PUWBG{3NTFx@!wyG$@0V%ld+x?D(68zf3t`2yaCF^wHr> zhdDvNJIESL{xYp1*ekDpS-1acW8wvcG5?%hto;9ioBX!`eBTdK$;8C+V~POt`u{*~ zw!7e~+yHVx1?PH-NrYAQ(P3Q5v))%o`E?#349hBWTfix^%00RT3~_VnWY{~twt{N+ z(G$HPdzeHnSzfTEV9^O>5v90WOblSn@5aQRLe5m}2Yw$spCMckFx?+rcO<3ya>1S} z4O;cxBv;$zN`o33**)uFO^5v@Va9jI&RxGjSKv?+Q?i8`kB!g-n3!(p+foHsZ8l>+ zfrx?g`@eCp%6@yVV|cr-S55*`r?##cC7>eo^ysx`9DO+D;CblGYeF*a8a4UPhMPvo zd(gl>M~6Z7H-*rQX^|3^4%0;tqr^j}pZfCvZKr6}Sl29+kdW#{7SEkJh4`H;OU z$GwB?GcTE$AhMiyM~?2pT?v+WY0ERwfGx!tFu{Pckj|oN9o0M9clmZ=f4=>;SopL*H@}7b|0%4zB~4(m%3E z=iuq5xj-~^7f{Z0B%9ZbMPg>qfDo(f>8D2_Ic1MGEZ&qo2R1nJ-?z?|J`OB`1endQ zBG^X-BD=HDR0P^y+I{Gc5n|cHcpts`@9!#_t4v$T$jdFh#?G(EmuAeXqF+E#ZaWSr z^+`a4pP!3hSvUk@1sOAKGItlHo#`~+{taxmj6IQ$J{hO)FnyuyRu77&J2bDV(GZ9mQC%w z1W|u<(6_7RHMKgc3wRB??u%vh8_6qm_hUwadm4x2>ZiB@0d zDvT#mbNbk?nVP7wQQzCQIhbn|rs8()4J|Dbvb_efq;dLRqn^gxi?U88my5dsHsk@P z<40qW~>=IHD~Qn5{)4T?68nT)93YAJ@7QsK5R(P*`$P3#81dDohZF*1@)lWHZWVbq{< zvpbN2{CxaL3TTjK9B8Sk6ew3Y%2;2KB_c1X*cRY?E!~Hay7@YFdg0cJMvSB4MV37% zqUXc0AgTm4OJiC2+QAOL*t{B53=%M*A8!I@FQKQ2j|a4^U>W;KA2S`Yy~Wd?2Zb0v zt9;`;^f|lc{kbYYS^w z11f`u<04rAKtvmL3#hhK8)Q&k>JaIHS52}zrBOY?VeHAL{C3nm%Zj}!f_9RwNndGb-r zqt@h%5qsn~fpb&X3S<{%ocpZbyXZP{6eo5@mMC<5QV+*0tc~?x%cei&twt$PWTr`S zqjg1ji$iJ$g?G$>QM99S+Pfo zv1v11JL}eq&(5pM$8S2mEB+w86FjX)AAccrI8C@_RBn}2`#^hCwPPmTL88wBIpG#t zf8^=WSjssJa=~1Wy{9y~U+0&#=ybA!E#<+n0^PIW%R(>4T+7g>gEy?>MS~x%RCMQ1 zhd&v_rIv=cYE?Uvwq_=xbF@u}UDacW^5By?HJ?vo6d^ugpc=kyGkrWR&s)Wce8To7 z+%yGWM^5v@#ysSgEQP-Hi4JgM^(w_1{5Wy9FY{d6t6(@rLoj$!JfP#)8z`bOSB(~-mh5?A08Abm zau~n&!QcFOJ+-@TxiMWue!)(Uo9NF$9ihMI0>|MB;L$i5(b8R>>gruqve59Qp|-N7 z;i0!RZS%`g?|rD!*8;E6#AJWf(Yo!>6v)LjyDG|~~=+>V|sA*eAZn+pm!Q+!i#-#&lmt2hb^ zS^qvshQ?&uf#(h(SQI!P`V#6w@(XvZZD0wF-N+FnxJVXY25DFzTZqq|+Nqh|xu=@h z4z_F^VvN}4Ld&RFZ}!z22SKj`W=U#hqL_!{{l!#1{lDyxB=!W5jk;loNoF@2T&}-2 zP^?50CguLQQ^R?Di4U_$;^DpxXnB}6H?IY!`|K1!<$Jn054`*on0>-(g0fy-Z{K%G$3kq-J zDx@qT&K%jznC|*=&ak9OS>;mA;D|O(=V$){8|N~xM3$mKOB9* zi17X5jT2}7wM+lmslG+9Qh98HPDk%Bw0Hqs?FZZ;>1$=3xJ9j%>c+bLP#q*gC&@Rh zeyKI3ZzKWaJrg5tg|zZTExUN@A(SY!mb?D0uW-)1!8f>sc=nT_`wGe(z#hBaR|pRDdKvL+Dq$JEIK{%^%VuRzNz=vC;TJC*MTy`Ml+&v4$k)zyKrO-|*l)Cs7K$ zWyBy)qoohf0mGIukP)=}d}|I3lPqgs+>|o|yQ8LV2N3mplF_1Ax;D_EHt~furT(nz zV1h#OJ!_pT>4-vIyC}ix2oAwS=YH=vm$n__QwSj?zO2iq!jteP><+mSn{rHcBoS7{3T zF*bjg`yPCT>?h5f9T)S#tk)KqD@ZjuX+B@v`E7JHF00X>TO}g!n+7 z*98LC4Q1!cb2Pe;tmlC(jf?)HVMl)Ba-Dy>N5FW;&g&kv9V_>`2|d}vN|H@W0*)%% z&4Sx^VB5XTMCe-J&TPaPMSV|R#SB#&Dc+02%G@g#vuqU*($0~*hJWY}l%1LJlv|oG zay}i|gPWOf)g21Q+8e;-T^E9=j}1>pH1V~AUZg>1rX;(V_kpTbG6G z{-$V@4^+u=_)vGE8==V5PIXKL+ulh7@B-cefS%~? zKd99U@}HN}g361?Zw{ElOSHJ(UAy(3)6uNv9VKp(G)V|V>(>Xmy!F0dUD{nRWxmGb zGS^lj1S=*7Y}^5`Y-iI+HEu#66#nuAG%R4N#n!mDEfL76`Lqg(aCwSg?dGOW>n?-N z!A52yMEu5RUPJY?o7B@fo+krS5G_5{*tQNQ9wq->5?7Kl6!N2)%*sB5( za;2`V)=Zk={%s!zW7uj33sOLQFNdJ$i9-_wU_}Au!kyZ12g3TcV6rnOu{G(zR1-=+ zwg5*NS*`c;+j%}LRLu8G2Y0DF-8+s1VX=pkiP z#T&A~tbfnFi%*;QZlViHdoFHl<*wDKQf3x|gNyG2n-djiUSHgzEQwUf5B?n^0x~YY ziHQ(6N3Lh^qDItjk0AXhV;>5AF(+a9@;N184FP+pM zP)M#7*5FvqWx3OTtQeOhjy<9BF;?Kd7ETx4Q~YU6^>Q4eWZGE-`${$tEgT`wQRkf- zU^TR+wOrAUd>bto%s10my`s*ovYyy)c%XKA$R=FUEW(-`A+oXF+txFozct2rX7geR z5Yi_Kr`eWCfgV_fjLps#%3|q?*68E5_X(lZ>bqNaNX6f3Ypb9~qa(DIG;zi}l6Eow zEPKUeC#cRQ-*1zCk;}1vy?NrT`@@8LvHv&z^Q}7&{_*{Lzi2vo&8`&m-|Fvbo3_3j zlG;Oy^i==1p7f@wq5Hq{x$VN8NB-%ZO?-CwBwGM0o!iArre+9$OgSp}n^5>aND=%; zNap`rV&XsfRDebZ*m)ef+zo|dm-jHWC!i8%TyLpghwIxh$6Wsz`W8bTsID*Cg92CX z?2-~kV=Y%IuiF~03a-m37BGHerrjWHZJR?B1CTGX5*x|cWfC<0->Rm{=A|wk2hdRj z=Qp?u0D*VzH!~9hxG>%;s(`NoFfOoVoPZf*S_ZQ8KPjQy7+?ouICeRQA1qWDpuLZR zc6lzB!(sHr@6C<0+wIsSSy{$19Nk`OUFR^-`f9mDIHNrUf)XX{FxI;2ciEtSbrTOW z$Gl4%f1t%p%+ZMM?18Py29QgtvkQS{K|sF$=Ulk%*_C!}0dH*q@bTwc@TEvX(8vxU*~ww9tp;%~g*?kF}dpKMcOyysK&)?A&(3#UB6d#;W8VVc6& zM85)P{waV~+5x^3h^+yqc;3J9$$|WlTGn!g8_yiSl5e|y$cC{OV;A^wsIF%!uk@EE$jW?i= zIJfFip^Okljq-B)S(y+y)CyGe@tT$T zg}e)cxE)`i-Um!Ks5k;89+S6hwNGS=yL!`s&$WKgS&}~}Lwk;Yg$jRXBmWD=<2Vno zE2X-<(f16&n`#YNXwf_SZinL110l7 zW~EAaRQPoy^5@|5ej}nGnq$4G#u=D1z+p=HJ@@6>2zs8NCb}#-9`AdjAX-_1+QWAa zZxgAdG2_r#S}?yJbs{1F#D&gIUwf~s=pPap4)LqYR!67FL1Qt ztg_EeW&iRlOQ_ciCBc#4go>>|XZKw)U32WWJL!bjaf6nv3Rh+~_XQaGcDTV;;ozRI z(D!QV6C4f?qPwrYe;`}}wK|Vyd}vFRYTS}Q!xBcgIJETA8Q%nWPh!=ICRt>Pwd?Mh ze-}?e1hjP^kx8DbN#DUy^?}h?bVXfFIy+o4VKcj76t6w3g}D%NW^L5dR2s7A2Y={E z)lS&=sl3$ILkU)X-@!kr%rCKMfulQmP#Y&Kj!~50ES(UbH|zG%_QOG&oq`VGRw=YU zt;LF*f{ZQ5i?kM`PE@^+-vJ!%DjWyS#iG^f_h{H`Jh$>O^slqi!5RjRIX==iGHqAi=60KVGU7>Rc<( zgPF|?vfY$!t^!P#>R-+%#E#vC&@7ur!znqjj;$iQ`#oFFKJVX59=UW*q}Gp8XlmCz z7hGv?Js6L_%cywQo}8U*#Zo@Ei2PDY&{li>qGwK=r)T~7*20(jQ7&xdIU}gR0xLdS z_|QPwWoZjfb3x_%j4DVoa{9>`mFl{o3#hq;>8bf~#V02KLQv(mUL7|?#DPuhSxMOh zZE(*E)B4XE^<0j8yunS z)FivdhqdoH)vPkCJtx~?bagF*gI?lT#is#x-W9+1Lvtq*wv{HUHZv6BbPT^xKIUA~)|QQ1}H85g~NihZccDr9~kLr-w>to{gUYnecXxbq7_` z6Be1K*&P~Xp`_8EMI0lNIEqVULQ-& z5;t1{ABn4c9qdx*>S>T>(GsXHYQBN%M7A|IwB)~ul1y;(iqLi~XV;!mSXz4)>HsK- zKsv9$BW;c`F56a{va`U}pAH=Q(7q76DZ|1_mTYz$5tX{BP`%MqT#%9IW(FH5w#P_@ zPQHyLuuxT{@Yz1H)1%0tELVXTX~Ihb#JRLlAh$%!mOd zq1$tpwYur#C;v#Az53ctJ6ps_L@c=ZTIW~&!=(4NCp-{+O}=F9v?``x*(YwA?DN65 zRK23;0@gNd@fZ`+*iUgh-kUvjN81xA=lXomXg(Ren?z&k|1}4uBcdl`#kzLtS2DV6 z?&Io*01M2d38d=)hVt>=JoSo75#bkJ)+ij{&6rLB$+q3x3G3I`$n&1d%W=keHTYTg z?f|#H5Baf#P-`<>{2)%OOT}!>yE_GdoPTwVyuMSpZJcM0o}NpV0*3n62kjp#_W|S8 z?t2Vi{lBJgCWl}b#YRPoZ}XU!`@Hf(9XCZpxCdAYY~rt~@05~)n3$G>zd1=bEf)-M#MGhw?Z|wCn`VV_Ll+f`vYh&9H zn(km%`W0#FC}k-n3s02y2TFVScqSB7l`STAA;z!s$XQ4!-Eq&CE<(9(068frV!GsO z47_RNA*l#S>E%JLed8fglDm7{tCf8Xu8(cpu`o$m4Ig9{;behK`>@i10B;W{6SiOm{B<5)pqh~7D1E{u%T%H$$6r*c6JE1;uSDE zUB(KKFj6?D5U-SIfm$8yjDF;41m6veQ!PkRei0xRKdcL)X)(pLuGz4o?0pG`d!ukPSyF< zTOslyQ)>5*rv_4jF#L4bayc4J{g$GpaM(z zvI$~hAJn-*P8j1kA8udtPFighv7oDZ&TE1?4HL&lGlQ2&cj-w@Td$S#nyYi>*dud! zTUGq3w_Nn6dZ*^2N%f?rpzqBYx7mvld%$f26lQp^`ohq0?2gCf=%E~mj1HB)ba#oO zGDyhTRBl;lLo+Sa0X|f-Iq6fEYi5j)8et^Oy;{?38)U}33->USz;@vCLqde28-lPS zrELob3r4BA3x_ze!?p%hmcOd1WHq;{9fFrk!3cZkQRc0BL#v4k{Dk9@wh#@ElV-YK zxgKOlHL)@GsciEk(`{LAHMEnZLQXu8I)p1z{s3A1M1={Aup~4O?m0#Hb?Uh*j=C;= zCV<=l0|Z+3Ue2^Qk~I|RNDREEm}*g`mQRioA0bzl>X($K>oHnPJZlt3C9x?AkPf_n zV}f{Ba%}>bi;JkVve{|7|AuP;2;DPam~=QYgRF#=aPRj#kzkqT)T2s5Bnumg>Hfi9 zI&qc%_I9jyJuNQtD9mnk95x+hpOpP3gmPpM+!hx|w_Yv^ZkseyIG@Oy(8RAF4u0p7 zqzm^x>uLuBl-+^`ZCAXmR8wGGb~b5oV-6@07pNB;g{hR_ADVes+9n)pq^cfkYG^*oUF{NsGdf4|0yp@} zOVR`Hl*!gYqL|6>VJ~(j`Y$}l4%l!7jl{uh7oP5GYdzXKLnAlqq^G?!eRZ_GQg5rizg6kz5x6MM4LdZSVC9)JHf#llUlqQ}KTorP= zW=#$``$g)>GQBj2mY=DUa;@k92%&Z-qCt@|oM}Q)I%S_jS7KOAvqd_MKe7c18$)32 zbMsw?r!R?dta4?T;Z?AH4xNRS?0pf3miBz9m~^~?^A+;%*!L_r2CfSDpq0PW1|Xvw7pkUf1TGW5$d+@zq3+< z2_fbiQr+34Y^u=OUe^x2g#*6NUwpvqn6HMU;s8qU58y{zE;t$LK)NV$6d&ANXPOB0`BC4{@FH zP8zSV!TjiW#1A(S4)^9jvX{6U_BWY}xG83^Lj;U2wScy2vhKguXRk{)Q7yc+r&@bW zO=4Sk+U;4IX<(vxl{JD&D>u@rH8T(KGUx9B$nBCmU2M$weF`{x(am2QD?J|-STP$B zYGe(TBItR@RTmH4~V-Fc=d?FY*cv2%XOqWG?O>*l7Hi-m~|61lPu%u!S^+oXB|7`&{xWW1he*j(*OIEnu zKD_)YKmr@RJ%2Y}+BLwpD|D8WzJ$xDifTW?)c&ikhV#(q$#iAUwew`jhuu8oKaa1YJh%aH)y$OVw@9;W*`zbxm$nLXHX zWHA9<+I6)9c#kRf*8$oyaIctUH4=klU`^f7p@2{N3)-;83-n?bqr}%_4aI360F*Js z{9NX~18*tGs6u3MGt!z02JFt?y1>jpk{DwJJ)dslUB->c`6p^M$c$}%Z$03;TQ~m~ z9E%tDrVTteHQqH)_aAerbsz9aYQS{emhLMKQ!c;5fq%g6U!>#jRqdvL|2EtI?dttg)BjgY zzZLj@RpNhD;y-64A}ghbwtMPbTZEyVH4 z^49DkzMPJyUJTcN;FS4U(Hg}8+`ojTJfJ|4T^#FAnhra>o)62pW3Zb=iShp03`F5T zt>!|EB32F!vPV4{u9&n{zPzUXlfGUG;P5KGGd9gc1Hx^G*Fg_OZ~m*} zJ`W)LGXF8lqiCbKu$n3>3{%hzJ7%QFD$kLhOVhi^xG5H z&8z5LM6d1fybAPqv+ybR&tD4$1nQ);w~9^U6Ei?q{8a_~$pR5q!RZI8OQGZB`LCS# zS;(_%#oHp9M#^?>5DCxYgv^qdGsS+Vq>jb{qUF6Z3OMthIjNZce<*cLdc0JU_&&vq z)4IuW2|@+5*o$nPY1GqxY&X-y8uH^o1!?!eae-RZTC{3+ws5(GMz)cGSe)s=r9yX5 zM-xy`Or4C!Oz$Rqp8BUb*bU-Z9pO^NK6a8R{btFpEM`)D?@7eJ?%M2>2bVgx6+Q^J z>iy0MDkPmpew1&x8sCxnemi%uHx=Zd=UCB_gFQte3FNZW)8N6N8c{fzWz`iS42l*Q zjrhpT&&9Cvg>H6^9J|b%QJV^Os@<-Iz?;wy`(e-t0ZltpA!Vf7(mfuux~NPfHR} zalKQli7IxBrxRgVy4h&6rp)CiCBOsAk`^qB43NpBpQ=&ah^}HJ9MC^pN$24GQdoL< z5J=zc4!>S#3@lrGG*Cx!`JM?ddN?cue4znZ6gx7C@h za0fw{eY&O)X)z|>utPMC9O0e7t((%R)m7K|h?Lh?f8O(kT<&IWzLO?FG!Vsz5J(-Q zns}>lT@cbFR248!r=5`qd>Qwt6e)l;2ASk#SQ*bEgg2shl9SZ)?BBs^RnPKVhj#1( z2cpbd3;Q2_J1pAp{#vQv*PAybpG(>bjFbu`2y(~k%}VZbyltb(Y12m2Zq?#xU~h11 zJf6mT>9}sn8+AnTb^Y61=Vcz=#eMU>45>Dx%IIJ25S}W=pQ^1NLNx}GZ2(f*@uXt< z$4)2q*uh%&#udjj;F`{TbK*umHnuU17Wl+X+QqJ7>~Z9InS2fZ5P2o1R4ds*>wC?f zO8WWMUqw@^z1~S=3xhXr2n7spsmOka^2)~hGxnPcl$ar-J~Wt zPdJQw1c&^=U4yL2$+KJ;D>I+ID)aEhR=T+L>RS|=t*7jcA)VF~hkfU`w%Ln7wQ1^l z6&ruRdeo83xHY<8L7Y|?9*y^@0w&eXmH%Xcu>k+yvz*CzF$_WIIrTFq)22s;Xje7Sft|Yj2Ug)t@p4H)%HlsAVNTToF z-+*bQvI~X+x3buisuz?#9|@yhPSEXGKF8B19Ou{|?3DhJJG$S9x5rk@>;t1&ii1_J z=)*IMou$N{7`8zDm`{Bn22)-Ux5y_LXL|#Hi+e@0A)kqA4C6dp?z@T<`uMdPhYIgQ zlE>A|6Kr_Lx|d1Yxz;NkHUW$K$0Y7l+Yvi5t@6_d`uXP>>KvbNf2b7BxVhp@OQjE} z25*0t(K}Kq4BIQl#=4Qzztrgwn9t`p%FHF>bk~D^0j^n76O`xhzBp>Edwn%;LCGtl zWlg<4y)TeuV5Os-cDYx$NQhtZHK?yPk+~q{NUD>2MuT3*z>-gd{xjejnC6tP2an@u zVyJ^&Me&_4_+G8jJAdeTaXYT=MgU8f^QC+6M_~~lV+4+w@~KvXVtq_zN?h5EhuDb= z2}b+fS_!n?Ts!JW*H!9xSJM|W-T%#-`mNH2aPsTGlQp*zJbPC?LBv)j%X93_Tv9e- zYTNqqJtW-feT#sN8@#>ZGn5ya_GHa9I27y{2^|vWjS1v(V0&AMdI- z#ybFdA1Y*@b=WmoyuSA3o7C1d^;y;TIF*Ybx0LmD0YANI{(|?J;Ta1XLjQ+c}~ z=(4rH*1yw$^d&2Edbw2m&|G2 zZ=Q}YTZ^wI{{iDT2Q%tM9jQ1Pt}mH{(J<1VsX_+G5VsZ@s}yBN%K26LzQQ|FeTxff zbfbW;ZF%7&a;I(P}-@T`G*WbQ?1Zv3`I)r0pDXWNe-DJy``8U8zSDp%ZP_T=SK{)2D%GJPUleY z{W)9SCU@l^Zes*+u$pCCQ|cYzU^F-7=`#{dn6S@rOfWfHK}yy(VeRV8LLKD-_{8St zM&$T>{IFwbQz}gV?JP24Xd70wtbDeTePfKUF`JKy_U1pQtKsgOe$*X(7g}*?P2&i> zEKAz2V=lgFDN|ZdD%hi%m9g)ZYRvKeoknu#SS8QxwZYZ6!F^6z&H*(hxr}|fJ8eb! zs$aNPVqk#*j*BhkVpCI%aRn2H6dZQiYy&JZdN&j~#tkHKE9~x}uv_<4M=j2r?cqr0 z3*EVrroS2`jOYYg4p;#fd&cRqI)6l0g9qI*!DFbPmhG0JCp1V=#+$@2yx7upds`u| z;fE^310Nr5&hzMaoy_6sEXMfh$O`gZ$DgjzfufeV${lnl-)^X!2(%vc`2~@XK-FK@ z=TL3k&t+d|QS37g4d`1aReae_(twXYhaqj-a=hr_pqzF1cI5|<`glWyJQ}SXbxNmP z+reTsIJ{D?6!;pR0lGl17|e8x#Q8sEEW zLp3yR&1#0P+p3g>V{itDwCD?;dBbW1W(=M?DqjB}9+)j=d**msIHBR)PAG1t_d)BAndA!WnvvC$V_(HY9uw6nJZ5gjwH&{5ep8LnLOP!_ zwbIg?er}uNof!p{BuqS@&b)sL1Q>nE@>hou0^2N>m(-anUa85wD^nB5kLQcEraQzB zC7M@14yNA<9AbMLgjURyvML$J^Rn+LdoNAyecQe9_h4@%3(?E2;4exn^I$}zJbRJk|{}kYjtE&tRk)4GA zZ5;6-{>%7w8p=uRW?1$2!ieJEu7;V*9bs2G(uo zqV+&y^4+q!ZIo=h@(k|D>BiviL25RmKP->OkwSO4+qBs`{@Rx((oR&G&ri{6k@eA) zf}!pFVKp`;?aNwAd*I3W>=g!6YU`6%OOjK?N+u}qRunU*LYpUacWl zJcM;M*?+zY`XN|pztp2Rm-i9o`fz6bc;YGU?~g@^4gp3o`nT}&y3eHZAkJ$;Xu;b(eGEQ0TXl(L%5uDSuBWvP>g|F>+LHH4PmD0 zVdmQ3jBeJkN=)`apF6s>fyXk2DC%**Uh$E0F<3rvi4Udg+gb_0c1d76gAycFKNgJ* z!eoSC5a$y0z)^mR(!RnR2bQ&0o7?_A6el-QTNq4JMnd(J+hV$8KxXAz?*g1?Un6Rq z`nE1;b?yDC{n45n>72(k8L6Izpo%vhazx=G2Rouu9#F0n^G=$)d+l;?z1)cApjYKN zBa&Iu0ei_KcS-R{7Hmu*hhc!|`#4)Dos#oMs|G;Z{;rLT^MH@#%`tq%j(>>h!=rk8(4hu_Z$h6OZ!o#D~(MtIJy#Y(hU zA~5;Mg#Cl$H+<=@TD1sLENiAj;TwI3zeQ2Y4H3LoCjM6E^j{&}OsxSr^P?F+asDXX zn)?}Y{=1PX4JC0LbHcdzn*2SV0DAFXH%v=k{a@{!c_7sL|L^PDIXPL+Y2lPmr?O-x z$zC~@>=7CakzL51y_16@*_ScaLL`igWz1M66vhlfj9rSc3?{}HW4-TDozwZ<`^Wv= z`{%uX8=vL4+egV^+&+)(ow7jb-Z14hENqs5s|2zd9HZIeQc z1TSRWZw+IQ&gwgS29sCxb{Oi0!xZx2e?YGHTUyD*Hxg}^%kDg(i@0r^s~V1Tb{Y47 zK@j0GWTGU-Gr5u#EN<0|)h>YdUbw`k8tQ8FLh{J0c;1CWnd>PoByWoh!!+xZ{A4Ts z)P-8;3~Qs+AZV5-2eFdu^rMMm_FfGVOgHg`wwtZTU@$T@6Mrx=rsc_#@@BTy1vv*K z(pOyB2+~!6L#FqJFJ_s(H5)$OAU#x9a(&QqOq==nKf0f?w3W!4FdTtG zz^z|KGBn|`g>g@;j&3gr6Vh6rl}ZvYV@>^dvQ-B3xiuW@ViVFF!pFf4=B%~ME3bQf zO&MRpFh`=$llnBfZPG9v9c3Tzt9Y!RMGmVE?@1|@Of%+YqR&qB7!f_48+sQl)`Wyz zx^aSJAmbRh%O{+7vGGx0Y1!R}El=#O+G-w-90r8~(4BKWN7Fpx&5B5o1*()TCI}lRu@FnB3 zL5%$)x!?Z526SfnU`J;5plMVW2i8a5R#W<^)VYY3MbID0>`5`WD@NcbUP!!m!1QKD z(ly(4w(qmn-#yjWT>Z)8j@Yjb!uCbN0oRC@C+w_MHvj4$k?|HGlsY9O^G{xpQ}(_K zBBQ|P!K$Y#7&7^R0`P`5IdOo;V!r9OYx;>3E*uNisozbppUTvq3MBL3>q=+M;gUjR zr_RV({iFee%f#pz*~9Bf%d7i>@auhF)^O6z;+BS0o%weR9mqnanZTf4vd64JzLZjV z+L77y)FWSvmi3p)>$w665FHMvJRf~?kJv@N3D;_6z-i6}BrV>5C5_C~9DG3`B<|Vxw8*SSR0Qw&;yA0*(69)-qbPY$|eMshLH^F_`o*O@t4LF z&CS+2*j;U2%42`+{dD9@=iB~xOrQ*L$A@257v@}45!8GuEu3$%MNjgIz5Hh}u_x); z9=*DXookCOQ+@E1?=PB>5(Bn2<9U!)`cIJo7u+i~S6})9_g{EDpO3_o0K(;G0quyOUlB?m2y# zyLSZOr_nei=T?#`$)K?u2&7}L z;x;_Irxx{*zij~KSX@Xnvv3vjZIT#74yTTrJRko6H@1t~J^b8v=JZKLYx?HM1$``U z$YbBEy0J~w&vqw!Ulu=+Rnw@s#vM-)(NB&v=Gh8rj;wQLty#Q-*)+Y0ZfBxT3_}ua=486`ligsv75+;5n;c8A%z1^ z0<;Ttys)%2b8{H%Q0>E@In@Ubxx^(yOxL3{2MI@5M^5(r9xVp8Tg4D1v5Zn#mNyH6 z1r?mE4vq{-yxjmDgA7i<};se!xJ}kf4@k6_(s*^aOc@lT%uAIwo&1(JI z&BjmNF%hBgv(q{DR#w{L>wa?wy9C)6Pw^L);!64ycf+cNTb0cOpRgA{=W46b*FkW2 zBtY`+jQ-ePq=|B()$GXNUnfo&hT+fi z-@eCkQ5Y)4=2F(Sx=ex%X z$Z{tl3qnBqIbW(HG5F3?(Bo%sltG3Rh!UneugJRygiS(hwyCBWTzrb>*s(;=4NQ;cc zxtqgvfu#+r3vQ%+#~bJ=&~;#60%ZdkVFJjtIwdqVF>U(Fx#Ogdnzot};1j>2_|4Ik ztPG`uRpXvXg)?Sgs~g9#FeX1D-NsW0mVmx)4fNL~E)mgC*P^Z*takiqh2Ijk*QFKe z+vU3g&8_|78upr59Cz)R(*-70k5NOb&D@nbheQ#{D8M5q+M&ILO)~{v4)e6d zF~(yEah}+7c~%69K+u8geg??x)8e7^PNWMU-)r?uibtMR7E~QHqxcn!63)CZ6ci2% zdSj@vTFigYH_%9s*43PRLX>Kefl{M4JZbb!ZfJCaiFAZd>}Fd@ueb(McIXc6_;A^N z>+nx;&da_{8z0%wOYutjF$18e-u@)d8KExeGYeINC4X2KQ1TbcJSR4ru(N!mN@XpC z$WMxmW`_yoZVNEBsXbjZ2}qMn4LevBkw6mb)lXML&|hEmW7a*^g|D@`i_x zJLvmGLf$gr8`Btwj{~JC6zS9xjcf|33L%fe;41AHCkS!CG=rwd#m^pXPj<;cP{9%v z$u-J|1yX7BzCPzkB!s?(fS5~+=558^15k?hm%4U$@;a)?j(CAQMhe4{%^S)_14pgy@xaOlqd4> zIPP?>Qo{qA#Uhw}v|-bAtkli7GPZZjU3#lavfr<<&tGQB}YSg!Y7?b zHs(z+%ty;TKMU+Y6T9oAX;ioM1>UZ}tioxGsKZO{-&uW5=(Y!>{UTpiEC)1I%&HiZ zRub~tT`n9`N`kzAYH7IP$f0Zsd=$K7oKZ$;hJ0NKd%je`)$bxRZ&3o(!I}C@rbj{i z&I!^$mDUYZI*5AoGj*!EBkWs{FPyU&ZJke6b_lPQ1;w{;(`hT-gPl*Bd+$?7(3uuD zbB$Rc_r#NjdQu&my$xNxU;6&4pf)m^QyXMw2!=74-Cdxp^#fxnkjRn7>6r5f&yg*7 z!Eu5i^8#lCuXHZ+b>ZifrO1W_I>LEj`pIlcd9EH>Dd{Q>Zx(BM{mPO{VxG-U+NmK9-xny(~o$V8=h1POw7LQ?R81~RaoZQe27DJlU#w+IiByryKGi! zrpN&08o+936cp0rqdLoIQ`LU4h*Xa*7F?NrZwN>bzZ>QyR41>fJil?vnJ0cxkjL5_ zqTQY|Y9e@REA&oIamo`*Grvr3lHgLb)8I8?3De)B5y?xJZ&v8y7fSl>+TBXtcd_O! zeyV;0z+U`i>P3q^scfHI3JbW2vV$xMq?Zt2G4FjywiUgEwwWB2J=*# zUZ*%_T>~r(Fo6$?L-t`x+U_Z%{G_MawWlty<@En2rlr9*M96J!T@Wt)`S{6~Grc3n zpn*Z?CvJH|qP$)lF4ii+WorucDb-t=b*MoFL!*rPH$Pr_O176&8lz@QpkLbC$mZ7KN(^zM*vpUUB>M`@5xGG6`M^EZo1uM_oL9z z=AA8ay!KF|TUDWkL+rTA!HKQ?7=uuR-_rAPi;Pc!&8Lij*{3D1q|lDBmAox*nIv zf1p27b}cmOrbn*z9;`J;;?7~gz2A6kJ#d^Po|T?8`5>NaZU93se93|tslKh5SFT=Z znB>1xjQi7K8OXDzbcGI+3t84#(SO##l%SZsU09T3Z?x8L z>8J5^L99YDc!IkqBObwze#M& zcC+a>MG`%6iWQ}oHp`w_SAd?XWTpW)1&|i2c*z+Cw&Bd(Hp5h=^P&+E)ydpD6>O>k zCRHJT0>zMr1K!7|HYveS?OZ7lkzg?3xeQ=j=iutmoVYczlPxB7 z^^Vpp1*;`G?KP+<7R%U#tVAmBZV5R|2efA`^;NnBKmZCTWNoG0(efX{h%M4xbX;OZ z@gmd-N{`Dzbv9!4CIzo+?;68qEpv#br>cfgdk=5jtH03=1oAGSj!qCWq=o84z2U^x zodm1kaWQHI**miE-)|ST8oqlbrC1MUZWBD7`o>U|@#eURxUW|eJwm`#Bn`|~i$BfF zMN)cHx5N~M#0Xz~QP;tp?)oqZH=-vYb!WtW%O_m=xkBK{oh@wGE}Kc>WM}|Np?q}4 zX^-X;xI~lBN4JFdue}gyViM65mPX7t(9oaGqKhSZP|P96EROHR5a3vC4}jl*V-rIB zZ{==&>L<0{VD+K(Iv9V|lgmZ5Y)@=a@B=1J8OFDv{s2+}F>ks7)(&@0%3ezuv7G#r zd{hW9h5$mM|MY21-FxoT`Q`|u@7s%2;veVytmNGgA~?CX)-1$YU^@G*n0y^Ns0W&M znK31Twi7F#9mZQ%m+%tut=Sbh(s)8~FMd1(U*5O(@vNia@($OwPB%Hc z5?*0P)_3F|_sJUL%@!-g#LI{7IWm?g{PO+Pm&p7sjbYF6??wyNU($m76hb9_y(8hq zMQ8F=EN5yj6yV?44%ANs3dx89#e0S~xYIc39BeRcy7eqhQs99R zf9PU>_cCaXCpQA5(ah^&&`HmTm2G|Jw>4+vrDB8X-CXTj{irL6v#|-m-P47(f8(c6 z$$s~SZretEBGbqY{EVf$j@ILjK}u_fe!Tuz&M&ZOAQ1Yz*Z)I*L^HLIHE@0gt5n<` z$%t19_t*_KGgM}z!i#>~>TTzTu|>@4?NCgyNAnBrxMtRFHFDWoe6}jw8(&xhfsJE# zxc`=q%wpeXhJWW8+)-5p+jQwY8K8=<9{nn39yrkodR^wQsEKu1DoRko4|hKHnZefl zlA3Osmv|CJKA(l*C%?K!S&^kY;v@`VyfF1~_0v3%I7F5N)@hPWuQ{HrYS)coJ2*6| z13OVs@EDb}n+3QnOT@YLEUa^h!p=GZN>T@oq~%OU(z(@ltqGYfo6lYYoQbT41@)7q zXNstxwR=T7(dt5F*H>wyA{P967nV(zLTms0vS)Hn+M^(YR71 z(qXta4>_r3i);XEbHJc}$0-1p5FS*opw^UYZXF8cmb4V1EQd{IR}iZ_T1oGf+e^Q< z1?r&DT+(gorT*Ggv*&I^cq8nTxUoN6hud+Sx{`DAt{z$`WaE{BVJsAR<>khK+d&FY zfw<-80})OxmBG|s?NlXn3U&}8W9A)`Arv`{_^nP zoC9{RRRE56TL$PCs_i4bakCl`!g{Ta2h4u4<@98jzW3IGpYyfBv$LlfB^nLD{HzL_ zdrB;c+(gtQOC2$0FWKV@mTilzz>Ui>h8ZMP4pz#hiM2K26Bx|J(8W*)@r#P7P=yKoR;e3@Y zBi@Z6_UGp6A(dULKQ~o>a)2w$MiK72#v!UWPYfEn!v>~Z#DS~Y)XZ)^Nc}V;g!hoa zO-*dl%h1%WnPkvLRf{qOSmD+6(MW|rzD-ZS0u&}sc!`fHVm$=-G7-V=`~opNK`Y3k zfgjAV(p1;^c*(2=&NyzzoP?ik{vHDiOTgW?m#c_GITc9aQop~*phFsB{0^&^U;o;g zmH$n^B&Zy$=(hdmyv+M%;>H3vV5)PNQrqulIGOW*u8$8eD z{QT{`_d}x7OfnIyA8(i`)5T8K*NmkM@?wRsfpfq3z<()d%WTXGf`bqHs}^>vY(`G? z0L(fd;@QjnWTxgFDJv10)38aLVJE@Z8hjAqV6a1yZMcW zmMhH#z9USw%;_J*nx5nio@Xmaza{RWn9yBHOwntQ-?;NiPaL6W)3Chq%0ax!;yCS& zJOE8yX6bo}kaA0A+3T~N4tiJqpneVu&JRMtyqK}8M=|&G6`cD(B7hCjdrgT}SttL4 z2!8CRT|W_hYUlISa5gh8Zhx|SfW3qp5Z+WiWjWh7T1H=*+~xN$y#84FtA&@&B1Y_i z>|2eh{G9pOHF>ySoi9jD#4a_`Rqo_^uA#~Gp9DMb;o)xy=Hu1D%R3GvhX31_HAUMC z+qj57!JA$Jmi!q=Am_S@MWPYC-bGsXRFisF8y%s6AU7PU0e05;0i>mX3;XEfpOaPm z0zKX{cNQlOS`g?--AAC9zF-zm9$)xh{f!B1NIaH>QI_BTyj4*_jR3E(kEUY=NF6cy z&|F?WYjc-1hZHp3FB@0SS+MyJUFy%Sl(Zk(eAJ(Yy;U&JLNajC*lKN3DB3q z_c@UL=4j}_R{x$n3T!Z|Y09bzzh@bgjBc7jK{GK;YD?R(K8$@`-Tt(wjD{y3%WI6L zcY50Fm5(*-I6~G&HQF2kpn{Fz@0C7pvV5?OkdtA2zWxEHF(Z2a!KyRQ*nnjiM&LCo~%pmxLf!+vul^ zv-oRSCM8CFg9rfajds}Thi;axiM~(bB^aWdM1uw9Q)4|Qz=CdEx>S$SB3jTFhpJk| z?viCKyS)8!XqXXCH;PqWlo1q8q|PcUYjFxFoi3L?3y^((;}a93V$(4+!*UpjH&Y3p z*Y|AD;%C2~YM~)%+(T{YM0!)Mg;rynmzVjDClDObq{TN8qn`a-2S3iyoV|$nQR@7J zcaFioFpGt@`IGf3flD~k$GLs0FD_I`r%$z=8h1lX!VNsMcFsJaTu%9(0I9vBiM?AI zd^_c>!F-~lI4*>RzLBp!nj-M~T&-YX)3;Rw)~<1Q?-Xv`+CjY2VpV%bBic>~`ziZ$ zo4$7Fca+D%u>8py{q!q4!86B13rY%`3WCX>+{@SMC;xnJ{@tpGmkhcisgmrAY?u#7 zWrTURYK1#qoFHu;{BbnwcKmN zC3K>Xq-<*@Bdb95672aW10LsX|K|4%l+ApBfguM-G;QG;R@+vC zE+(W~mF|4q^&8&=h`K<7KmKi+H2n!~3>Ji4xbJ@5^}8h$La-DNNU7-Btq<{Q(G}Tq z>(pOO)7Z-pxxGgm^O-31fZMv7n+5?+p`$phchKbvrDao%NK^U&s4tpyK~+L^m>S;V=tcRYD39CaE(mvyYce z2Me;>=__;fShCn1VP%dL=7#naZ+cAN7>{Uh1yTf0?JgAKxnjPiuoNSos~4)a1Bdn~ zvi-^mY{54wS4@KRTh~7IdF1Ks9jv2Xg>jS71FPQIOXB7x0(F;t^2n3^jO$ZikKJcm z0pQb$w8hKh)>o~KoeAb5*1~#-H<5v}(G~W~0pp{D05}_f%YS!m^~!?2!r*j2&#KY~ z&!o^tc^u{D)|=s5ds{ubXH3Dpz&iQ{1Pj5(t0+y2vhD4`Th_2eJznV&$0f{@BO$up zA$x{(0d_A#o_z-EV4p?B9N^V^E zfBeEY-pX0M5__3U@ow+mnt7chNmycReBeQT+*NTLiKXx-2`E>hIvql$b&yh}Da73D zK(R}06luz6_|=QG^2S~zSpq`yC^15=zm zQm_#Y4XCMdmUDd06(;N%9-?8VkzW{+yoI;iQ$IP%ICQoc;a^ zW~!AkChQ*udLOm2)R#-TTi8;C9t*GN_Zo!Fp|bbK`_nwir==TmDdbfNVlcv~}Ql zxuxF~KhIx-)Y(TitgTMw^sA}(-Uj)$OxqDx5J)KaZv53iZ{~-~gcc2phB6Zixer!F zd`^l_05)qK`>CK30Bcf$hqhk#QK3*6QX9cZknYHcsLaM8MYTwH3;Q>fkI4E^FbqYR zSQdlCjobK}Vp$X<2tJgs$Z4#)shQh!qjqW|qxa@Xs2wzajDhdY64aFZyWObgpxItR~(YFmk?3*eqWsCoze^$q(dmwK|5CfNrD z8O$(x%xku1=5tcd^psY(5U~e+Z9UxkDyU@Y%8(wHPE#rxGSQ2G_IhJJleW5+mn#>! z*@g0lGbV%g4zc?D{Lf-P9z3X4qiXV`$*&zn2t*_g49#0l?S)BfHz9ScGQ!shVS%e@ z>Lo5g7IY(_+1TO>l1@&$^f(C=v+8ur?xL0|6K2X2kUT>RtUkzl=H?lBq15}N?dv2kms2Kf z!=@UsMMXK<7?gQ5#7VTQN4b7{@sGjl<-rN&<<{nRZ6~T{G#Opzu=?U!Y*ouQcRv?2 zmQYXp>oby+Y3n9%W8ZapPkgsHp=Hc{h78bMTKdg=j2$R^YA|T}UJgHx4KZ;sfX*j7 z3q}LRo0rR@H7Bg9?vOT-Q?6|O{xX#AGpunA7)H`iS2`#&ale7u;_l{hxwmu>)m$3-b?74zpIJ+pAp3;6JbD zv*G;U)vE_h*FS<`0;b=QRJk%Z0WEQfYbJX(IdFb_&N96KV9*SGk|Ae^E9>Whenbj0 zIgC8CTzhK}} z?7B^{4Hr!w^N%s^_{Ck{}1s$EB)ia ziL8S#fuwhH|L;jG0jk1#)!TW(_`<*WRyQ+lRBGXGBE^0QN8at>?3BTY{PXWCXTiy^ zeQ)Syv1&mAo}rGV*$wN{gdGG+=qIJcLJ*LCqtC~1-Pq-?;_SWfmS-my$%!=#b5bc1 z$S_L3@x2=+ki4xzN;52b(tRN^qqUtA&x~V+BSHowE0UQmAR@{6~|u;>eFj+j^0PR@EDA zTGidPLXi31E_7Z;%y*#q5S>-$VT(cS-Fz+7VB;Gcm$;R$=PGcprQT;|zx!tnyeXdh zqwu3j=4QpNzog61+~vV@WL~dqk+a7-U)#X6V(VbEz zvu2$BS`flO{W^kc4+V(qJbcvHQTX#WU%HQH&wbQ`eS-bobE#vV$z%AkU?tjC&3V+^ zHT2pCE1X^SaV``|30IhCTqETvSCIyM3>&7O0oc+iglo1F`H|@Bm)#MGITei}S_%BI z6N;dDruR|yX^FDQ$_q7y+pMjWYi%L$JHB>eUT=l> zVcjM3d&71U=eJ4Ev}Sg=)QT>pXI~FtMN_ zaC3y-QGk_YzIlcizVq)o8}r1YS5=RlC960!m`5>ncAHOLQty9gcWD=Kq@+)NX#$`j z7<1`rV~({wCA=0zwMpeJ5LtNW9>;2NPPmr@i}3l)O!~WX2^!!iUa4psbDbu$zYjK& z4n6dgMYdP|$0>S7tL^YiGj9|JuRLyZHLeZA@eIi^(~Q09b)~e>?d1XMS1++XO?D{z zaT$jH{DnS$4NJzJI3xP~<;omn1A5qih{##C;x_uJg^2v@Cmxp5&pbT}&)yzy&7<&v z=K!coR(>|2ezpN8L8-r6yDGF9bxqAdGGXHCy?64*z%e_#tWPt1A#jPVpdbf^>uf{h zawf9mWC1Zg$-1;jWUsQ!Wnq1k36aZi&!_T`{r@OllM{d7-cP&|THa4=cqQg3y+3*( zalVaF|M|>>y58P!JTr#B7p8d5B(v3Uh}NZUm7CHj?~-)*vATKbr9E!qNptEB2NYXc|OnrPQs6~kY2`E8^EO9cJ9s64nz{dRAOyrKN1@^>hZX|6tD}0 zF;9Goon+7WczQ?Brw)Y%ZQy195jKt>vZsf?iaJNP4E>{Q+=`UF_j{J5s-a+6mM~8_ z|Cw@Ki+$9PG1;0YXt>HeNBq-ZoLe=D=Y?kpvGzla#BMjTkJvKpRzR*f_D~H(5f|Bf zwmq$~X&k?Q)c?VVKyt@iGq4WxeyQggqguaq8eTVban|8fGNPw?bzbI9*8%jMt{=St zAFj_gkf#0uy5@Z&)Qm2TKaC1&5F4xR2poSXf3(8K>!xFm3=?R4;9Qu`(@COE6QqM( z|B&)4FTCJ98dF^LV0Th?SK(rIXhe&GQ4y>sk@t}?*}_174Ouzm(Au@yedIAHB4Fhg zF}s=0!<2@XRUvLmD1tZ99WvYCao|RpRtu-i)1~2VNcN-57Hq1etFa`Q*0z z^^po!idY4Q2A$hYWVybmg565V$njqG*{TS;MGLJ1?LD+pKQRy5I&f87yyW(8M0boq zR4PZ(uG?0YF>e)iFI%6<&ci#OGy|BIH)1Gz-56@n!2_>jK>HE%RJgxSS^n=F^2Yqf w5C1o(#QpyZ>>pbC{|E8^WFp=2D%cLUERFVby5_yhoJlt{41Pykzw_vS0Hul!g8%>k diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/Clone3.png b/Firmware_1.26b/Documentation/How To Contribute Pictures/Clone3.png deleted file mode 100644 index e571f35ae235ad48e4df0528028683a147681ebb..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 14502 zcmeI3c~sK*`{-?&8RuJ5&P*0FnKDyjX_{JYxlhxgX-e)psHH}xrnrHCHH}$1%9smo z=wvFXDY*xVOqN-Knv&v*nE@gq2_k|B7iYWo{&CN_=lt&Pk9*F1&Jq2#H-N`~H0IKb0m~cmB9Ob}u@6=8x+qJ=&j-9Xus7 zqA8mZ(TJ65K9o~#IieM-eKap^aEKK;Z1&eP7-!j0nuD=(T=2b4T>$4wz@H80I(}zr zL>oBN@2QK?8aVxD%Q|SLjQSL+Te21!KC6{>0YlhiT=#R+DeSv@d%(=}C{3Kp3i`PM zt>|45$~PPoZ5I^Ma^$?ujTjebNzDFesT@c92`yDc+mTJ%JU=w@v(ra@t4sQJ^MC z^BvJciEKxVvTE8wI(y}bYUN)_^f6(fgLgAmg0QSID1a@`fNu6l*wK{Teb5>!1ya6k z#;|PoLs^D*5k8=?3_Q=`Z_sW7j@UT>;LGW0#{KN_W?ROPU7I43)hvITQ9tz}_`<7n zsjrPB-$5zD=zylso1I}cWNTsyT~MB7+a3`-*(SlT zC}J2<9z89mwy*39EJ?RQbiFPfLYV=$$g~EOOe$RZ2`In*?$$l&oj*iSc!lL|M6*hC zFUK^Oneuyru(M@XQu5I?#WAG4gYqXvuLdeak9QfzoTn)15UM94tt~1xpgVp!D}ivZ zjKF7Z^ilE&N~&)%7JrJfQj+#N=b%q)i#&+D1S>#ZwgQHt*CM?qsQ61tgoHPb=UKQo z+21P#4KXDgW#Jm%p~yn9F?N35K_uVFs_mCbWDw@Ay zB@)4>x=E=JctYZAg+}2sVd`(?98aF|*ygg>0Xt|HrxceXBTf^$rKsXO ztbo#(d7RSODXCQI*I`Z9rwt2`FvysL@*17W zYJa)00qB*D@$^(0c_Qz9m=*2}-Tu*qNcg^~6P6E5lFu7`EY+AnDALB23?YV9_Rxfo zx|}Y|eub_gJR5d8o1^6xIfWOC*!U0GAuw5=<8W-yA)IVx>i6h|F4hUqZ* z$=yU_Ui69x3(M zsk*^dyEAT22g!tU=mkYT^EAhTN^M&vW^=I=X0VPs&9Ps!4&RJ_)$e$slwj`riV!Fu zAfKo3a%Nb=LNIk=S}8`N+oC}JLTibm8(RLZkk4|Tm7|Arub!=!OC}x3?1Dby4l$l=7tJ(~faea{-&Fbt@vh>=Sw)dWDw6p9>!6ZFdB6u%!#yYArt zIYI#lzvQy#%h)Gj1y`7G6z>oX4ov7a778sT;UW$~2QC$L*8{g4hatW!{%M7I@f~54hUZneinkB*uUNEWyqY>>3{zNP z$Ggb!|5<7)8`!J>GLru@lW02<3udA!(j@7xSaG!Q3*CAv4}VJs{;<^ZnG zg;L#GDXe?UqT;A*9mG~#0h`Vg8eprCB{BBFmJW)E8Z4sx9*!CSlM&sF+NC5q@_C#8 zc!}=!01VP{F-V6um)O2S^t)CJ<*46g4_o{tEF6$gz7lWKvSW<`Ij@*=omD%wia zK4bd92O%Q@`un7_T{PkcN4z_y^gfGIDtg(gpZ4|ZD4@8+my=+{TAOU^=qj|O81p!s z6F9-Mu4T&127cubZ6Lg#S0sTj3*i%6YNx*w#<6B_4V!Qn&WYhJk!&oTIHfW?n=oO< zL1laG(U?(z-oCiz@#1qvx4kXbKtBsI-Z=}mK z2`4?NZG#UyK7e`9Q$_&ErG=0JOLRZAAj_*8b{#fJbV4`C`%++9Z_?gyO5ItEAb5b%rlTHd3g zm-q;dV`T4|%J_R*AHOZ7O$)H;&*%D?x`#l9`;u(B(Co*&t>7OcqKmG@$59 z;G)~ne~^@leypS#17$}lW=znnt;I5p)iPUf%f&3i%O${~GtYn#@uB5}gZgw(i>>3c zEmV8If%^u)E|X`VgEMV1Mu#|ua{8NXX@+AxT~`Mvg^uR9wT%xC{@^<&!m77wGq~8{ zY?Xw<{Wzk7J8`{!MWPH>sn;?`YgYZ3hVhP;t&LoDo=x}v6SXeuJN{pCqN4U!rQ@Gp zI#Y5tp!JR+?mc960saRIa<$X_FW>#EDXyxUmtXxwq9YK^h+JKrKl`hqsJPR`_Rmo` zrKxbVFhw(BtA$*Jic$?%{=(ADv!VO^-~C0avaBA%=I4J-^3E#YzuZx?(@qhHzB9JF z;wQX;;2=(fxat{>XIr{G6Gs+zoMX z|62WA`^XbkY(?LH_FRaG1VP5ji=wHDC{;P z;jOYWh)71(Je?wzU9=9chse96weO^rh8;OqIh=keg8%`E*w?MWKrvW?T^-CAT~}Hm zPe!lDk!_W^?SNiN*-(Z6&nS;APyz)PVn1&yH!ckSAjZ~lfT_BhXt`7}QuB_8&t$wJ zR8Zr^$lQ385B>-kWvm^oeN#Ck$r!1TleDRlStW*opQFUovmt|mJhLYTgiB(-Zs6Y= zMXfZTf#lr0gw+Aa&(9G1*n5CAzKk|!=y9eaaCbEzKv$U2$u!=vI=Gsmvo=1s>f;{L z;ZTTII$DD@U(4khnU&~-b%(k*#DUO3`sb7un+8K*tV`%eQAQB#N~z<%z#I3a>XTPGNI`2yX}xAc9XfZ#MF<5pTIaLwpX<8gdz@VtZaYsU$dwiIz^bi)XfY=Q+ImDdup4;OYsOZ$If zhHJf&9R9m=|Ach-1oavBfkZK4{nJ!#`MI!$J~#LCvID?cOr8bopY7XyLw&uRu;xY-hAZjK@` z8By8AW$fXuKz3DI#?Q^j!PfTqpy)yTMU9&Kvi$uMwWra`*G>;52K4Y6J*e<7-JfX z)Mc5^+~1#0mUbZ_e;sF6u`1teh_J`++ePJ?8(!eO@Edg{xm7>NSd6-z=AQp*@r9q# zO77-<9q(HN`_D|mLf)7>6RPwnSYA$-*0w@TD1%41lIZZH`0qBKzDOPk;nhHZsQ81M zTu!fuC467{EAHyCC|*PeyaXt4izP$sl*30Vsye`E5>j!Op#8_e9ahT;mq&o&yE!!RE5O zMEfHLJ@GAOL#>9KzuO5P!(X;^fq50enpK9q*g6rqjQ?Lgb!!YAtR@Ef4|2^L?p(lW zD2J5wgyyopO*7U?pXM2ELC<`-^!Gfl-|S^i++lyi2_nsuL`>sgy`o!OS{simp99#u z0OW%IF&(WtVcqCv2z>HNd0btOErQ>Y@b>NfqZ{q`@J`AFNhU{tLg^KqJ45rMC|`tj8}t;lKITinCUKWbJlHnkj_3=Q*wen z&5=+w{7yO*DVo2;^*~=&#*plMYuFJ`f*mSRdTQmgSoG>yZp1^u78kwW#n<5&nz`xfp3s-+=zY_Ono$2S z1tmX&NKG!6tgXWR?-8n=zTgElxU6)-(Y?GvOb320s@DJ$40^^Q-LaMbv**M6*lcrJ zYWuz+$8=)XH-6^9iSIj(cFsSGMUU+V544mdJ+`eY!-NnVQZ2J*y8LoVsR`wM<86Cb zW~pw$7dix(no5vwfG8#nR{;GGkG}7Ac3bQ&0DSzPy?u9#Mz_*U&Frx~j)@2b7vGM5 zr7b;-BU<^`O2TC8lYYmSExA{RbEt=g)G6nszwlB4pVHX~d3n0j$9e)`*gXD^JPE=> z!E0P`KIplQmezR)AMCFKb$jrjS032gfoy0>n18d@ik93>FsJxnd%BiV%6-udd!U@# z1yE5Zq^cf!q|oJk=s%n?JJi!9Z%KHNVvBAeAdkV&L9|$u74o+t2&&_8CwFAPw#6tN zF3o~|=$VP1aK7|_yOy344uIeJXKDuxX$MbW|GxcyOe(5b{}+)+p}$QPv&_>|#W>Zz zxLBmR`Sv%H?P_X2{1B=Nc;2|t^SSDSZRy{rUO(Dls(SrcGeY(H*}q@-ca{DXjeqsw zU#sz7HLbM)4X*-p?)KOw>F#2S1G{x`U3A2<`{+?xDaK;W9XlPfaXsXFRQI9STjpFo z0VoFTQVU7ajJWZM2bNKMb>Hm71qTC(an1dPvtNSS?8vA!pOU(B+1b;s66@W^9Zujc z&r%8+nf@Q0ZSpRXl%ZZD!ahAGsHwNyDB7)7`1RH@(b_)@Cds<9gF&ZDeQNdwVya_p za`q4X990Auzov3(7d?u$?R$A`r{Ef1Fyv(266+e!UaLpK0d$9c?dkem?%dxH&9GV?djj?=m!C*I}IH8Y+)}!sb5c=s2f6sq9 zsA!7n8_8rD555{^T|=b9&1Mvhvi>?@%rvW+;G)%`<8%veoHRW^q>IhGesOUB0$AmO z$5h>H7~0Fr<+L2O^QT2F{3s|b47LmSrBe`8l0ZzVzmb#n34Ng za9y@DKgqrgwo85F*L@6{Xtmkj`mUG{eY-$RXcNCx!G+b?mMtQ-k? z#o9&#UD&N%oP~L$wvf^D`QsnzJVwb+%B@mkkY&Z}*EUMBIri0JT*RX4_*@fS&tAUs z!7ClUG)P=ss|oY>jRvXbRJhDqbgwNS-I0>_g!-emccB;!Y8L&|FD+SJJ_7rD_LPf5 zoG@!xLahI?kLFo6II7M~l{mR%395>&AFCQrcW{dAuIDJjt>M>G{Z}n?$V|~gxu5&H zPvhYMod((`N7pCug2C#!c%8tJkfw6UzPM1GPN{#>uCZ#|*{8}i_DsS?K$8Nn-2NhJ z@KTjLhPO8`>zz%v@nUpaO%cP%{HdS&jbzP@6h6}|VJ$4G>n>_vG`-$2YsIq6$uaV6n(YLr+Ulo^A75xFf`Gz+3`?_Z`H=Cn!k74Y~b@Zt3U$;HXY44w| zt-O3~@*Z>9!{kMywu@HQN;@tm1LR+ng=)p?k${ja4P*Ab(yX^{Sw;o$sv>&=Z!Rmi zgTK%g^iqA~qWeC8>PUYW6?APr#lfo%e&GDGz7EZBiF1kxn0f~4#Vh${tkGjI+xZh-!|Zc)o=)~d_J{u_6beA zu}}{Z$s{thYCY;%DY$9=3~7>eC$SCJUNxsPrFBDk-(NrJgCwR`BtjREL2Mjf3K_4@$bC9|1#~kwQ9Z(N9au?!thSd*Tf<9uz491i@ z@jA=;gS#>9%g$3tk^rR~Y{(qa%Bgm-gVf7@2%S(E-;!vmiOz4?8&my8y8ZxNpXzU? zpn3IP`ECacZoMSDnGiv0FaeZ#yPv;$Or(ilDC|F!m->tj#UG{7^^b{3;H!3x*};Rl zCxPzKcEg_Dha&@vN(IFxPvxp7sD(f$4u1Tz#84f1V>0iNTQRu!Q=`@LIdV(tEtE}R zw_T7S2#fMCI<4aqleO-Ypa?k#{Eq;h4f7pc8;6C)hZ@g1dNwc?u+WhGJn+%k7SnaR zZ6R)|)56XwBR%?Py&0%OC4y$AEf>>?*4jxCj)MWZ(2*~v5yga79m(sXdBcefo_pCi z&jVzmy{rgfh8md~{C;u8yv1nCVKkDnLHT`G>T@(A52Tk#IU#vMv?(l@S#*M1yvAuQp zyd*?SsR8TBrY0L~iP>)%Z^SS2DypYXM>aRIEK0*e%b9CeEWJa^g@bR>mqiN~(N9dI zSLEL}tQ;O7B<3f1v@@RZJ^yqyTnV{TH3CX81Q+l5i<8ShSN!i1(k}j z7f9FUg($P$iQO#qgMq0P&32)O1+i-E%s)nK(8#Zb*MwW~1c`x;X#8fM{0(U@8}0o2 z6308+CN`aTprgfP2pJ5B3N0VBjSMK-01~YGr{MHPp_h`~ZcqamhA$?w@g3=Xs&pr6H`3iT;Et=caA85?rFUduq}sJeYLb%I3ng((XJD=||N^l`M}YO}WE z2nQ>u*_bPS?OAru4%gEq_Ok}!j?NxSW-kD~x&d|n!)xvkU0dBGv9xb@rfrT~NHicy z^OvB(fN7Hr&t_nDPf#PiCx~m##2JsU*)w&Hl=JF`XM!3?w~_A>go`y-S4gcn0f4D) z$qX$uSj%ppXIh~6B;?eVM83~8pt0OZ=JfUcQtsWIUc5JgZ)Or|C9aej-!FjYLUqnZ zCILj{PZQ^`5uOjbLFvSK*$3gLp-&};u$B{b#-@55AgoOx_Sq!nTm}N!Fq+W+VRPrG zMTt-rt){bo3mM+@ibJc7lj|PPcv<%>r}muc-1~4bsygEOVlsp9&VMPLm^feS?N}q( z_I$iR$ZOGL7wW$-=!hmZ)M$}{p~@5|AB98-6+ADLtDjP(HCcybyRWG2+qu>L z8QrAs=!Dd>E3c|U=I63D_jVLEesXmQv7c#%qeEJnD(_r7Pqje(+UU0Ubr!`0RK~U! zXP3rQFbjMh1w1fe)a)mG4Mu}jaL6~7ib2+0&xf%EkroN$n?CSNiKb&wmW2O$>=<r*aEKe8rv8MhWzI!KHTIMruKAB|fV4NjLWUi{!k zO6G@=hK~mjJ~H>o$7T1*Q?bI~1TnqxjM1!zX7R$E=|dNbc6NXS#~5?`oimM7Ig!NyxcjrTVl2{XT=jXz!-9oPE8-zL^>7q2b<>rw5|SkJL8Cg4<(-(3$F{$`nB$ zb}i_MeSImq;9TaWm!V{FlWcEtl({EToz9+zNyrOo7cg52Bh-$8#bxi{BM(y|(EN%0 zWVjKT+$KZd_6{vMtLLD9RWZXXS)zi5#amkhjW|(pE-1fOr0p77_mO#$sHGJaeVjiT z#_SXMu3eb^W?jxb1O+LsR6yQ~WS@&R?E&uXV%ek{0;3A^t+jGd-zfCQ^bKlbu2YR=v543}J2BCKJn zzdyGR=+x!guKUZ9Yt(2>UgsM0s>!O0msymYi z(#fc9Fbp;&-8!jef>qJ}S+>$%?CP*t(V%>eh%0PSdSFIiOYqPyxK5^&u4>m_sLO^kXi3qDC`NQTaaF%U9KGKcs?X@Uz<6 z`zmG+Ih9>Ag&nF^1@Gx>`OHW|)G#Xj3pGRg|E@?F%C8++O>OzOUGf2Zlw zUS~X9Kc9A2amz@RBZdJ(*qRXwr@iD=lrzdx099g?s9^%zVY>R=QS=C;Qu&*zBID(> zdXZK7H?lAGI&h7L(_X6*#g~`2)5>~2N8QP+Sj8?lENqntNw!6}h2FM5(+iThtO65M z;s4?dHB-FFX<+5MBb&N14U#GqOher$_AI)u;l7fm_-a!5Cg{Pw~VKG%We4z35t)tT{j3qRVTIPi* zZi$7MAqOoNOEel8o@3Oj&hyhh_z&O8o-TK9mYMS{3XQ#eHA9Vsmt^ z^6{Nq(I%OC$*4ukfjo+M6E8Y5*;VIXq;jh^?N#@wtonVTv^Wp_#_6NZ8%+sqe7oZ% zg93+N2eA(T&pLKj4aFw81=><-Q@WSljLJLOb|itjM>ht&!&Ba8wML#M+t1)%ZA8EQ zu@$LiqB{THux|yhUtzH2a0416r#jqm!+_?CX}oZn5uh7s%(dm?TgrOu~kLG@1VwaT7xJ|giZbRr~?TzPE_ zOLB^|%Kf3ukkwq_(h+D{3+6e`Yc5>kPL0Vr07N66=aV$)nf>GW*x2xZCW>AH(U24E zUNc#Kski-6pFiqDY1n4pNcA(`$XnJ*+c#Jj4qNt_DA{p@UHPQ&lDS(k6TaxP-@ti( zYT(CjNaeQ~KIxrF1U~|D^$BWIs6RQ?hcV&Yv$L(e1K7AGd2hOV8OO8%e<0`_tFhVe zpCq>XNxX-u?ci2f90BBOCz~lZEy@Y^*P`KNRX4b>Ns^PK66@cCO&M=E|womb_TK6H|P$*vmW9kd4*)q7(4 zFz49PYjtkDd_!8jq@(}M755^GH|h3(uEgGyh9A8@*D~tA>{S$tB!$a0Ikq#|VH3U` zId|BMfF|*+gxa>Ri5Dy~Mnyc5{UJzIbZO2n*rm8=$0AYE%#?N8lQFWYs1y!<%KHCSRtxxVYI;X+(J- zE#U!I@HlvPm4+HU^x7)Qr;%k;*hX8YWN?|U z=jRVDtbA>e${p`rp_d)OHivcR-A;s5$V=why0uk7sgrGX(M+YkY|YIirj(t_?Ab)p z>%-vIsp5e>(6_5IV;|lwq&5)AeVIMPPQ9{*+{rP!ig#V&@pW}|3B_p55p}sUf2X1` z$FsBkD?3&8$tN^snIJPi9Lovw515j^z)xj`Cf76e4@B~{j`D3uWj~Q$? zquag0)|l1Nu14w9vtEm(vbamB95L5$Gdz<;+h|h!UO9p`>zFpup6Z-T)5ebiA)fi0 zW4C(NExOiD1q{RO;^9>rKC+Z&xe2x61PifQLA@iRDs*caD#yQipKRibspn-$J|$%&n#~k&giM{d*-(5mx`q6pqxgY=QV8haFVJ>dS*fP4$0v>twgHo%Qj-H ziM8ErQY_U%2OS8`Wl_vF#p)<+7p2s4y8#=fl^{xi{jlr&{l996V! zp<>GqSnq^+-x$Mwl599*pZa|?)e;uaeWHPx5F$@SiFP%t-A> zWFDKIZaK#IE?JW;oMd_P8I^7X6M%L11BpkATKhNWA$zGF%*RoquxLv|0|@U8@vgwK zJmK`?F*&ILGzYdv5vPr!4mWNN%oYbRe>1?6)b$~;!8!xllu$oRR1sBN7ZYK@?R+fC zWhNiVY0jDb>`~mUhNMw_CJyfr8O`(6V?3C~^dgpQa*fQH>ch314iJDkHXd6b$MrX8 zJ=)8&Hbc)OAFo1JBp5|?!>1I-M%xFb@J2)MiyhFPOg~o(A*uARJK4z9IuV{k0$0fI z+>ISG59}D}+t6V$th2!bm`A@0Ow<^WBH6#+ z^TYOx7nqr$BV*LIXy=BmV6m3pAn+NStw3HLNqn=}Z`rtr&NNl~@KD8a|0Xv7&F21_ u!u~gJ|8I4}za<_2-_)^$+{;(}$4+C4=JEnMPIbCgJAc;gOyiFsKm8Blyq<{w diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/Commit.png b/Firmware_1.26b/Documentation/How To Contribute Pictures/Commit.png deleted file mode 100644 index 2f37f1c12bda414ff2c921e7f9892437c50522cc..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 44800 zcmd>m`6FA~*LQo}(h0q-R#CLo7FD7IHFu=unVOQSF=k>Wv{kgF+?s+Isw8GH#w@L| zMFc_2DVmsPNlf8Qd++yopXd1#-uDNQoU_l)-s`Nr*5`cIXXl;1t~&c^-qXj99b?yc z`q=Q;F&5mhV}E=;$;v#kY^&1C{C6B`sQ&O+Y44Q<=7&EWALu+dcC0+^%z@1b=I2wM zPtBpnj&Zd9`a9m~k#BeGSZR{R;|In8pcTfM6fToy%9*t-oKj_QuN*vcEnS`fb)dQ8 zReDG2gT=-`mgB*}ZjX%$myhRetoNXn*_C;v|EQ=1C83C7EpOE93W#+uvUl8y1%$^0_?uNiuIMZCHDE z?%~O6ZMg%OAW&zbgszNB`$)-#?L3xal5m z7sH8M;C~KQV40E(Mn2b-k7K|UVIG9X~@5~w;a4MG(20p zwG5`IT)pcqUR61kZ}Fbq3Jnc>w*vj4cVX7ls9pn8>7IBqLyKrcm+qA~9lZpm$$uI8 zaCmD){g?H+;uStalH+^4s@W@zKSG9o403*H$lQx=yO-UvQ+@ey6iOO`9R#83szWr$ zGXF1@8#gbs=QDYHk}#wXhjC)0@eO?ps*TjkP9J5Y2&hREh|?HX zw5)c`aTb}v(o}ywt?7DR6XxD*Zg}Qjk5foisDLClnwLh{B;S_8O&!zH*iT5Lq+kjY z7X~qMUDHQn{)1k^qr2SJ)5-KqKT05GKXXWqK<+8aq^hj79A7=i+g9one`nh0c@7{= zS<<#qSsRLXNRc6g%=gQ;<{?M1_wqb!7Tld419OUyW87BWN!FelNq#-}hMKoW1fe+J z?&OQ5ZtcXL>O(Z@VM4K=qO!9pF3m+zH0!k4Bu#1V54rB3uQ$!=VT&v(xNwgB)QoZZ zc{8FjTqt(I;whNXisWASJ3pqR+Mu9{>!?SCQDPZa`MFu{OMT`*<+s5Cfuv4ndV86m z^N9yF0*+%JJ8#V`e900ZcNK+-iiRDDd6b$AU(i))6<>>8gW5O$c)?v-vE-1p7dv1= zG7S*#q6}Rkr2F8a+!l^h_ueE}Tjw|F#dIxozy0O-#_#MT#y{uUj%&Gn*J~onbD`>D z>`ntms0&A%Gh!1j%{8TPY=U0JmYIue>%xAjIqfeScyA}61=T4}0U8Mp43v19w?f?CC3{g8oCw=zZm)&huc<J^JHAB?G+DGHIYNb5g~HxXZGY;FQVCm1o% ziQ>SzkjRxag8WL4O7DF8_@e=umoU|{61%u2Wf=U^<5=Qv12q>d2?{8+z{;HGC~MAf6@~8wZZA zxeJ%d%QiTDWOg{dIlRViQV_B*kzMZHogQ3cm01Gw$}x2N?z(tI{R&Y=Y86{0u`lC) z+vD*}ciE!?m_5xd-R=%`*e%r_XSHWf8cJS#6gYe&RZ$4w`RcuUb{sr@xH2up&`>jT z_)h;zd{I<*F zro41W>>18kksgFS0H+WIF?odSfjA|$98s4`l0U3M?^7MA50kp!G4aXE&I_fOIF)S6 zQSzvi>-5G@a!*O-qoE!br?H1Z*SE53jJxmeF+h_!e!~NnJlOR9#SG~mU(a+Dit@+| zMU#?kR2j?Q`Z-@MvXSq2-jTiEx4$~;-54gB_InA*#!Dw4r#T6K2M(~m@^&+pDB1Cf zFG5S>q4?w?@ZP%f?I}(ZS|z?AUy^WzqG4~mUm%f0pJGV33;{d4moLgyY^*rn7IjM^ zA}EH$kY}M9a%!P|4|{JE9TesTsNVl|gBOeAuenFZ$GQQk9o{#2>5iEdFavEoYrfQ1 z-hibr`W@Hj#w~IV!9y<~7~`&VXT|TprNH)CJq29TS=2@w*b$N|va{UcmjD@i+_KVdtk>mHUq=Pb+h60-PRiD}D=7GY1%W1AG-~ z&@0W3s}W!eP{=R<0X~M}6V1z_cBl2EX?hWggAShn;l6 zwLq1G{@4!>Q!xV^4xGvMi2-*^SnwrjiiM`bGi{UQi-xo+W*GYRbcS-KFeB-^Ss?XJ z%^p&&3#nasXvRYwkVc~C5RAFkYpRAJ4QZO1mTs#$&;l2gJ6N&c!4Bc9&}5gb^_%Yh zz!fIKxXCVyWZ_gUlyu?k;vBfyenv;;p`y{WPC_nYMKqOSk*YE17s09kQT>gLx-f>R z4jSPwkC@s0kXi?UyFK~JCTLV38WuL=AZPx^#NodbW@+;s!{3kd6I+y?E zzk@h=!hwGn-T$8nF;BmbPIY*rfb}UCju3h?re_5|Ih0i^@z+BQ=ExF{-#vLh|FF&X zoj&8;()nwNH<;hRb1wYYo5la18s;iU;-bdO;j!f%!2)H9w|)ZWt8xRX4FL_VgI5(r zyhy!-Q;%+`lc(?uEIxJC^@nZ=%i!qHVff3vrd~bX&^W4Mm3@GCl{7wL5lp>%FU!6N zc<$uxbJK^7n!X9*V-_V=!!NSWVp87AWA9w~?anNok-1m5TvTbr`L`Ez{oA#XECJ1-}*A9!+k{QPoFc0JZ9 zc;|${#G~bWvDGTeN!Q^&`Fto|5wn1$@#jL;0o!53@XzZ`S2MDxhR;GImtyOx`qlQ$ z%fs15K6%yc)W~vF=7cV9L93~6wO?sDPF!As*-c$OsD)EqzD21A@(k2iN;Gya_=R2z zNz6DG!OxYUJ_onyjZpU{kB-xpZw-0s(AEdKACStQhu{r&^-o)v5!yY}Cmx%u9 z4IFE=w&~P6xg=Z=cj=a53H|HFflk@0JbuG(Y+ad)T|jJ*QA_jrpn&RFCt*U2zFP$I zA?Rj-wa!*3_oS^5K>4m0c=YS`8>i<%o>M7m8>^Rz&pRm}eyV24-{PI8RlusyT7ZT- zQsv6^^E+&=KEQR89rymLp?0%Fb@%KYKM9m|Jed2*+Sicf%>AMNTgY)OQf52OKdm6B{L^rJPQ9OY z+`z*2*0_DA`cY>uk8@1|U&+@b4PqL$myUr2#d;BQ-Tn9#onC*4IUBHgAfMDL*!6jF z5=c*N92s^aid=gUoX{j$uRbLym!PiRZ5d%b@a$q=yn3W`^|Ar(al_yDIkdJ1Jo-cY?@tiM{@vLOMI zTaugL{A6j43A78{|M6gVH2Z#+x{|89X;HuK2t$c){%~(ydF7l(BCppmz!nQ_X@o{!nQ11>L)q1-6EkL%S~f2;S@ET}w$vObd8} zxNZ?9oP;mVJf8E~?X^C_P5*12@4%?ypnInU8^6eQ<#vgzO||lp-ls3nkRN$sY3&Ya zoQTHj6`wwy%8(o0OPB6*kSi(UnF3lS;P?YGsk}}16s{{Q4*m7D4!Lz5$~QW)^3gyb zB-2-U?iOM^cV*qG-^=4eb*V(CQ(DvAuwmZb1)C-{6_+Khx?G5<0%0XhB#u)8?hE24 z6Xsa5)0s&j`-X{K+CJF3uBm=UMwmge2q;ph>tDSrb5%8g&j|S34Fqbe@dZeyaIpPM z`_2>K9SZ(5^VJ#HSK=dCvK6cG>_wVg+8U32=c0!wp?F1NayeJ*^YNWp1HXsx0aTsj zOMG5`3y`}j5dm|V53X8aE-Y&=?_g!c_lpKeXaDF`np3iDo@wer&lxU0B?jKG&a01| znNvD=e@fQ-hrD0k@u(5^h=U|4oH#nHz~@l^l8GKlJ_J>#M^|=xo5|+>V9KsTd#jDy zPw6;;!(WbT6qPD$mu@)`-VmZ0Ixgma_yNG-%E5;PR{YrAww+@lnpSVMkWo7@oUHNIYhB}CB!Y*!zb^KvQm{A zMPj@0%AuovwITJ}o6D40&YH{|@42@K$~9%E$AAP@NwFu3E6LtC+X?9+TVpsBYN?K>s9<$`cx|@7}by%d*%5Ayf_*iGWTKtVU>E z8DW!+R)-ml5P?e!a4#?}5i;ej)v*ujB!kWmI}om*qV;uuuP>$nk*oxp0Ky*iNoQ5z zL3f2WU^{i$!P{HfP*^Qeihe%Bl8^04csGU}W&c?3a)6#n)BMPE-SNPMuZs`*pFf+c z>+A(cRf+2?xObkdxVFpvYSIh;XTwvxa{a-4#FK=rKpgg}cIUy)6?%xB#G$g^==VDK z;WCllYxPWjst@S0>laRIAZG=SUxRf%%ZWaEDI;s;7A2yan~VzdP_*g$c?qv2Wc>Z= z)y7koK=?G@;p$RJ)%zZmiw6qWpEG43G5r7|tZw;4#FR`b!t{2{!TYmbUb9LNERY8XL3(1z7KcS4%-h#PU z>iyOXYBQ-=PCe}BKbhHClWnek^^HST?8C2((82oHDS_kJPlw%R_*Rvv&ydk}u_RwhBX}sABvUR4lE6t&)*tKAn9^>X= z@jN<(IXaPlMu$DwLl|DyMJwFJSq!X%N(f`FaQRw6PEkIaal;4OzSD&T;LM>M&y>7l zW$+rJW^NK}4Oc)v)db5Gwerj@skgIxngaVkC#Nz$==1)fb2JJ^fcuJ*(gN;>hMQo@ zUJJ+U^*4UnX$G1td?UHG@y6_gVsl5F1LTy`J(dsp!-E1uOD<(2FL|GfObenMaV@Zw5{=IZRE%c9i+)50zge zg^VqCj|Zi_s;kODnMayy=|yaw?|33oG?q$4_LL=70TRKej4IA+gY~~7DwDO0XFVx! zR{CKzv37h-Q$`X#kmkTh)Ol(FeW~v_)LSnxUh#7*3{YdQ#(ORC&Tl&x=v4mH7>hbr zD2SB735b6mKJ!+x=cI{Vk`+9t4&GRqM)uZ$uE0heSoSKP!7q zuKXf-vu_|}aiOWG#KZRcyQHWPm-p78r*-IMXBfjgvTf8CpBQrDBt-^(ywCsbPCJM-`pY^jxYw!fzp_V0%-LM?tIbTJ$HW z&N*Wtf>qxXMh}12&t-N9qc?Lnw)jbFt^7d>rT!mS%x{rd0&s<>!yRiRaYEdPj+P>U zVZYGljb7Cy18bU(S$^^e&VNG6(uZ{VRqKv~Iid%;j#k@fD94g(nt8-Vl#@#}?w;nt z*(z>XH3T2`2w9<1GQ&2Z$&;Kpyfbslzxj%#+i2CHgkaqkaP&5Rjc>VDCH`kSruV41 zopvkO1_*fYh>B*;mG|!@R7&nq!i@2aFlFpL;jk6g8s9DV3f3@&S}Cae!3gYM5xI zS~M)`F=Q%L5Bi#2VXOAdz2LD-VY!i~sw_%B(?!HnDR+m_Yxnp{%7Ry`w&Erf{bL2` z716v~yF5fEWscq`!N6*EFX;)+k#DbZT%VZ}LjGRyr(EU>Y%dU}WdIKZ8kPq-CIWLd z1-#dhvhy5B#jmWHeos|E#$m01ZwxfwF&4H_d)tFLe0iAZPWB^LeNWpjeD)0AK)4le zuzDb*N{#zp+`pI-&@@Nb&~z;lDS5OP`#tYsl5Jlt1#!WkiRzN_w-(@b_utKjmv8)z zDP!5(uU2X;R0zv4-tiF3Ed9x-fUP4kWJ z4N)@97c&C)4PAWfALNG)m4?4Opf)nX<@Go{mNy3QSm1Y&!(-5b^%qriXhOnghp+MabHeSGBl^RfphT4#&j zA80{mxxRInBO++KS~bP?c>1O`^x()kj>kcWuM`uW2p8mcQ_k76_R)S9q-PAZ6fIH9 zf=_bRthNfzEtyj(OHjS>m1C19-);taDwQms{vFA!Qz+}H6ct`B;Z(}=Qx5K|_Z$Px z?8EiGui=rYio=|rJt|s1KiHy?&sbUUI3vrId8?LER1&yH3P1F(kLl@?2@)!Lp+BZx zADrcW=vy2liK}ywikB{{GZ7eb@AD<2D|6IFmTS^niyFQrJ?i9_4U8C{YW9l2@vGkO z2(is#cc(tpnh4yI#`Q?%1Q{wLD9UkycHz9jBTjNl!EqUasfA%G@=~8Zj;{ERz3cU? zt91k7gwKBG8FZMmWpI3;o#aWtBrZFsqg1LitZwJcd{gp;Jc-gpM&W!TGTz=`3jA5F{Y9;0d zZ(;+_yjYfRrTJ3kH}I1Kc!8;qQ|+Z!YhShX^0zjl4AcKmprCH@+{ zcGTQon@^|G!Hq3*LP|HFafX{mInNL!zsDyXru*>$zxj5Ew+qU=3wbfjUBNvK(al3H zU`OqK(&9UV3jB64kGthj0yj8cbx;p=i(?&AUM_>)`kDMbSrXR}YiglD{By}Sk#&RM z_Pq$V`!F9gWT0KyK#^5(feQ|`mVQ@tHn`VYpgvuHrD8u&*37^vWQET~YvM%xJ;(Y6 z&T=-AMY-+Y&y@0sXv-s*0< zHB#36=)7YZeTgp>5|(*4r??^P-Lp@Hsg!T|0(?o6Waxy*5;p^!4}ZjF9^Mi)Z~u0G zblPUOlf5$M^SyUekiNI2Xrn&KKc;dD9t-ImkHbSs@Kpn|NlCT!iJtxtG70)FEv)uv_bap8rOr;l=+4 znN`QMYnCA++ZuJWv2K3V!KZw zFQDYZpQlx_{mYDJ`?LTZ&uK$xU;dFSWcL#aG89j$wa4UFZ{^|Zw_{^zI$&2L^v z=K|>_T`>wn1umUN++EgI^h7JW5u0MmR1)B0rV$?L_ArSQdp_$MBY!c=@KZaUVM|-< zr~^|0>bs9xTSxfv!+pK7n|0!E`~TA3QYY+>mNuvpo2tM7KH75UyN%oZpCgssMrMA( zeh)eyDq@NHmHOvHQ8LYAcH_|FnAP?LSu@=_mQ;#N7R)7YqOSK4vaTu2K$it&8>LZ9 zN1Xv@`J5`HgNR58ovrr;!;D_J)8kUOIbA#-c}RL?f}u8gT~H2bA%{b_t@ahUIT#Hz z-!E^x{=4F}XAr5qg*ATyf%tmY-oIXx`=x=U5C*4-NCAl zuw zdmEGKD&|4f{hLjJ9Wv9o)Oy8YNM+XB73@p z^KB(mzSD*``x$H$hcC81*x8&*k)vAsi?4JcX|0Ic;$s?-^4MjwF2Tx;p;N=cBoCU3 z?Hka3IUdAf$QA_v~#MoMp0Z1(efZ@}Mn9 zH^ptXsoXUUGMA}JP}%gd9T!wq?5dxOTT<~UE$N9ur%NjdHlz7J@mQwnlLQ*(1~_!K zgrhqx@!4nGv<`PXFwGuDQM9h=1(5nkoxg-@@1s;04z*h}e?%zW&sYQIEu5{yKg#{a z1wafGjn>X}W2BOa6XpN-35ZMX3m*tO5D{Vc?6PpEw){{WWa?htfp$eq4@kLq!-W2( zvIH?q^5e%`#l|$GmY}EXqR6fGRkV4P;Y)Ro(w4uTp;brLSlvMclfQmE)yZzk)Z^XU%^J>vFNCXwfmtixV{A zGiu}Sf~&s*0ZIKC;E@{d_i|r7M#?6m#?KsHM!!j=JZuo~F8BamcFd3)pJfR>kEDi9 zt%tfoqx`B@jfOE5=usd#WbV~t3uG;VoK`Fmm3RYn@V+%yLAKo8;*mG zBATAzI^`Z%>dTo0C)JDzEN2SVvUxiM?3}-qrDg0;TUYDa5CalTuBLpPb#nH5taaCIj zX(@;6Mx_tW)PLvE;pr194sO-9tlBH0_*~G2+9aD*cFtuv)QArqZMk{Y6kvJ;g-cSL zg)>#hRc_Y+_Q0s!iEmuOd=3TV&1LaubxS;9eXUHq#5)x78X@tAPXc69sw z@5z4yy0EU*eoOC|i`{yIddh{7aS1WBdzt3CG(10Y6{Nwe6`40Q?)z9KadJx;;81~| zaN^|m7`f5-D31!Gu%N&hE#$LIYd$6g`1y%qwL=>2(uW>EYi!=da`!Q&-wdrpVEI32 zYHtZcOEDMn8U^1pc_h?VPxaTZrU&YE=ZXW#F65X zl{n7L01!g#Tl2p?R`u@a{DaVbN4v+p7|$|=Z9XD`;yfRv;Jt4%yp^b zouHAfuU(o@m7U*F_sUl?VzaxnW~?GA?*>-6p{%K8RizNCJa0Oywvk7zQMQoAS$M-D zWBfu%9VdqMtCaTdDLVX|si=I{-H~NS>~Z0F1lZS1b2GgR_(Myt9VM>^W!AXqW$y%k zwp@Ta`s2|mPc^k{T5pX^awnRz8*~~235`L8zN(?MI2@mba-P+*%o5~q|53t31sO-9 zB!*(t%ar!}X4OZ}kU>*OB&k!cE7gjp--W{M@G@F^3+3;6u-i#-NV@=k9vlvG2bU=Y z_o9Vnm86eis1^vHAan?iU7B9yhS)ZCJ9g5qzN>6Fb)m(w+BWdX?^r<1xxrHGm?G0~ zr=7iW&`Sr}M&ooC{ae}_Fz*eR4hrz?z2EskyR6A;>fF*IXv{ZLC**}DG(dxJrGMMi zCo|lQILV1Iic)roZh?)PHIUx>0WQ6#2|~Tx3sySt6w$hUMhzqE$2H?m`%@H%x4?K--B;ANn^25StvwZq>0 zFMqoig_2iTE7pQCK6`x>cRuUT4UYxf+2Yt*r2U2k+4TlDSx1T`Z#*Y>YYWf+ zu}gc4Pqx|e@UK(!;BINH#>Z#=85oVoL?O^ywda4y6yw|e!8>u=(*NQad&~ccPJZ!| z{|ht86RsTT*bLT1{BLAs^S@va6Mp?S;KbwuUh@7kcqS%j_eRNo*AaT75a&~lo^VYa z_{^Ems#qxynD@-G=C{~0oBtw;C;RM4LOT1e2PdYT3IR-5#&ZrO&-bs6!34}ic2ZZh zp|byqLJOOjxXk{33dQwbWvDTXd2QFr3fHu?kd?poN7wW)SiVDl`yuiw%gW1OPXCQr zh%Z<55D;yS9hKnq{J?NpV@!hG;Ahkqs<)eDXwlG6$S-N7wVZPm>|i&mE7I)q&2H7Q z2iUqPmC;R|nM2L(-K@hG#3P!iFhg+FvcffqagZqON}QxuMIt)t%f1r?{KlEm4phnH zdZ599h1Tvukh30L4iaX$J@J}ob;y)TmX``7%nT+_nzjr1L)!3GnI?1%FF)f&^+mlx zPDa@GBmf#8 z2s$GMvs{Mq6vJDVq#$7~L39RZj*2R3KKL`Jbd99E&KB&|AKwN`a_X%-v&Vn5Loz?t9q!X#l^Gx9RL8Ep4<=zBtO9;<{eOH}T1 zluq=;a;W(y`?zt`QY?b0B^TfA7a?=^^n<<=l=ExI?FlXT45GnaM<2+_zvRtXLUPpDRwz=q4M-N z@85Av3=o3)v+~_^n#P7rk~6~*JZf*o=~oHddqLo?>8W*)vgb+)wbTww(H%I{C! zdctPKWo>Cz{-6x-u6}4DfDAZn7hqPCGFCt1VKxRf`wULiYA=7iD$=B?^4-Sj`nQ}k znalOtg%4!y+CE^2ahyJsVa`8*eEvIkg)gPr4!s-DPggA+eU5FM_YU5VbBSi<+Blv_ zOX4lNIaKZbW*fU)cu7ue%92suVDlNeGdk(ZhpjqzpybK%QBnRfIXbcRQ7LMQ zvYUh2Wgc0LLo8W_z?_2S_tfKkbS48yYmM+DlHJzzVliI19 zxw3ROp5&5hOdS1UlH;};y>{qAA*U*oe>fXWk`eUqn>&SHA{YhlAoQo_UJpEV)`Il7 z&044E6;3yOAWOS7#|$?Z z?8ZnmUINUCR8dW&?}w`5$R-wL0R?A>I-LuZnRk8;<>eq+TT4BB7TVDJHvn6*Uu zEWYu_;+RK~uEkPLNx>k!rsI0OX{)4Y3_8eZC3vs8=Ey0hV}i2yU}G(H=jDDZ*7M7k z&lQma^fhsR9nXyf8k{Mk-Yr5O*`48*s1nW$Xb}irE`JOmi5XmJ*U@CTR<)HRL%1T* znS8gIHd;>W=(IdP>vxL@%BUy2#+4H$;4uzXGSBMv{pso~h`Yl9-PYnQRC`{IL9wLf z1H1WTw7YkBZV?-&zk?NvEDvT2(AeW9%+GgQTNn~1LN;TG%MDqIrlHFHM_S~je8WT8 z5AFZ(5w@&cR$U9NACDEBLwOP;ZauYke?o;lq>7)zFp-lSI1?`Yp7p_LvwGe?3&VE! z?o1!nj+%gi!Jg$!4bB-2*FGIj$oje-w73hO{L$qhj5HEonBZk%s71>s_QUrLRTdcn*CmCS`jOw1N3aipzBZhRcM#a!rTb3~8iS{#uSfWRxz{7)5usWMdG46_A~7>@PMc9TNR zg}s3;7BYCHAZYNsS;lNkgmBOvNM-35uh`*J{EabZj9Aoi&c zS>}*YQZ*E3+$&ki)#0%cY~g!niw``rvR{bJoZUCZYs|UpTuh~yfdbnviCfqq5~5d$(gcGcm!!dcI+T!Ha=>0uiCcbhK-oVQJ9+4QCn5b*0BpS0s z*2z5j!z6`O@OHw?(gCm1VrplBv_pg9Vd$riH`tdGBUcZ)*OL)V`g?^gxLBvZ^AP8P zBz&I&1Ni*$ZI`ACm%Le=G{O;{=gtY9g+S1y=HpcNfCsP-@JlpTH})v zs5ck7uuxMCK8jkoE~*XFmlNj_E>LL+3H*NS+cC(GBFC6+m|8v#xP%<7k+iZm;(;B? zoHSL!Ek_3S?Y8pqH>ZbM-X5YE8m6`YTk6?cXQ>EdPSD0yl$UR#N4F+Z>Z+29FJ2FE ze&i-hy-;9WyO}yDtVzuduwF!$cFRp!n;Td;-VadSy6tPdm{MkCXsB@5aQ_Id5XF`J$k1{LwOZsM z?vFAg5jQHTOl*QXuvlN)$G$WBrUg5v#puf7j{xEPVZv{_3S~K$CbY7^&TBw&;Wr>Y zQ+Zrvf4TB;)8XFIaE%9;ZZ^)m>uRRe$ORZ8*imr2VfsTG1G(M59qPBb9e06Vjkpw7 zVXc*v11Ys0bpwz4qWdxV5R7#hDZr8|f@m)+83+#!D*j$5wY4)zCutwO)&HZRYFOTiW(`XvCRRPM=BM0hr< z*2XI%`G|!ZE1XEB8|>$9!XD^l?A9XOlFbz>{lWV~eUTF}ILd_dWT^aec?j(VWfot{ zQ)o!dIi9##OioFA)&Jbwx9F?3VeMHzLxt>?S2M=sLB2{& zZY{#ikj2a}Hx{0$>gy<&iLgJTZf5L!>8bfhl8`ycxpfiksIkwb?&ZsY8{6@zE@3EO zO?~F;iOsnx+4eEbcj_m#??fRQ*?Oc7V+jXERVQz3~i|O52 zs&JBXuxP=DR-kcSnvF4k#B|r1%p*0fP58eK*SgjHW*%zT?O6>}3MJewHH3+THuK-b zF`gyzN-5iJV4dE6CB&FtL!ZlgY4ES#lvR*(0w@%7Xz;!T8O_razXhC9oz+ucuP z#l&RJQoX9V^c=cWUAUQ%k=B+8jbMfh6sBMse zi4s4op!;XnP6wMhh_|dDg!5qft{L3oeJO%fPnquhBEWL$PkzCGBwi7SXDA4(bw)Y~ zRCuA?Af)}BYIGX#?o6th_&Z|;KQnMXp?(|`HWr}5CPNJC zr<-p;Od{Od3VKwui`XTaXUuxbz$MZG!cU}fnT0VksZaVENmFm(Hf(Z&>N`EVcUXY% z)Fec~jSLkGkwh0H5%%nopcymHCI50g8`whS!^&y}kAN7iKA| z{on>n4{ms{-!QmbW_B4nL9dE6Q_uutMlL>pO%Y$g$IP=VHRaBF6fvnaPNnsiC7`DI z2#Ln^hl-ougfco}`IlO_k_C_wfjf(=9BzUIdAdYh=!c^W#(pn;8XG8Hi zPT~8xHw#5qZpU>YVfdzldY3apHR#rW4B=D(_Py=KyeZYIMmhCHyfztyJ@xWAwaC3U zw1vpj0fWhW@P4ylq2AN9n*(3!#ZiyLEho$LQ<-_{vAJ~VX<|=qX)cDp0j&q>v~eXgjTh=Qbt*GVzNNq zy1h}rNC!xzxi=en3-<#v1QcUd7uvAcBzL71?+q=O-jejwjYN`Ui6ODceRWlZ+ZtDx`BLdFzp5|MLyRyD7 zTj;%~lf?;+ zPeg+JzJP8!0{E01-3%1+_ZF8?@`s8&a25IDbw!-HA=8luD#Vm)t_UtCpC*|H%`vLo zk6moOldFv6I|&0cx8Q!=hBY z)`grH>Nk@}pF9$e87Hg`JJwMCY~!#{Pf!2OFBh|JROG9 zBEqb5R55G5y_i0&aiFKp`|x-qUJln$|1Oq=!*4C7Z_eFtB8ZDZnua?RKHAgS$ z6gZ?so#io<>>j{}9YPVRVWD3oZPT>!)BjV$xHK(=P;UB;^Wb)HMO+%&ISyNHbFUk< z$?`Ku|Ge_;q@euNR8N$aSRVcR%D4iFb>DpEwVea0Mq@H^eB$5^#wd}vjWSP)qxNnLI~fbJNV4N z?87h;=4V{@f>^N4yx#JJ=-SU@M~|S+TPy3E%eDx3a8AbOUgxw{;}p`~7KZ!RSoEI^}FBD?!95tcKfd$G^7 zckk`Bq~ZX#AITUn?O~>>T=+a~7W+Nse-7thy8f19q|B_6@8aO&1$t^$=pJO>X>zX( zs1I9+===Fux9HbYNcNfQl=RO`5z$Xh*sntKHRDufUIT~hR+o_0A$FNWxCx;%tF~4H z@@cPMIBj&wrMBr@^UpKBn%{x`Y8+WU0bhY0JI;?(fa;FoP?1P*hM>b!9o!>u0&ay)!10}I%f>sU-9mi zNTIy!lXNUU_|;SOG3I6+)mUW)tV*zxc%bO5S`MJf~O+<+vXEw~;!s{X6 zf|dvs$DXLR+lz^sY>?Acp4A>d*qz($dog&)IpI!)_YfNmu~b^)(Y$+0aNy7fwUm=X zE5RO+0krYEH3|!1*(%=cLs)O3(KD3c^pM>?ZAAi5r1C6-^Oc?oW3Xc)2*KFJhxJC~ z&Mv7kz7MS=1Dd}@-7oq2d+b0K>TWWiSnue#pAV5x5{%wjZijQ%tz#K09O0)|$K7BWK=3*5xFr#>T{-O5e_rpIKe8_Q&Yob+O&{b#$1vA*0+tYPn z^PCv`aklYm>IXfU0h^*kK(1p})>=!|ntwuGZEePh>LONZ3MJXN8@LpJ%-Qx!v;Ye# zCiITfXeJdT+n1;v8S-{z9bIu+fo3Zk$a5+$jet?5fP-i_?D|oZ3y!o z3i0J%46}j|&$^WXum@e+mK%Fvt-^dOMQALB$@F2Q*HjxM$BW5hnY~t&n_47X=bc-? z9!S^G!5Kh3fVcy1YW^0dL~HvDn1qAPe>$)zpXP&g-;;A%uY99=0EaDailNK#D&xyD z^Q(I>EW&P5SGkqrVBxRTZY!rFBulCDU#gEGd#@q`HjpQ1~e>g!tlHs($_DP zc(PBpW0wTrVMCqqHOci1-V~+7pI6LKo?kwH?Qrv-TIsqaq~x{9D9zN&mQszn7Gw^7qphuY&x^_(EU|onQ9+6xzy3#J*4&4Ha)L;9wx9yfP z*ipzrWvRBmETLIV-lGayW`Sw`olff`W6yWPhg_D6r?A?t`?+7sS>v&LRDJF+w4h*$ za~XQcY5nhMnt_koDcoQ_PR@PoXD>QL1V+}{y^vk5-&E!BXVuym$;$Enu=k#EO=esB zFdjy%$c!BjQ4tZ4B2~H-q!%etqay?YgwP>Cf(`!@TgR4>wdMqJ$l_X4Lm@d)iA{olK(&G)+Q5#UuczD$&yOfGeOVDw%lxnMKC2 zr1dOQRj-OeEYQS6bZeqJ5jY+*_BSb838tg~Zpn^<3aietzVNJ7#xnUCeqE-8;%ZO@ z>}du~dmoUAa=_}t1<1!Nq%>n!0w-a5wF-sYb1i87gfXOtDH#LXFvX1X9g&l>^VI5S z_^?pb2*=yny+7|Nr0$2RO#2jDQQbb+*I0vpa8Z-xOL=?;R7J%@al*RFy5MD~JwB`& zGb?j=Ap6M+J_+PE=|or52fee1cBph(RY>;?{mX|hf6fuP*l>1< z7Q0=uHgpFe+n@*5<^4@(=JhkT)9?fhn`^1Xd<~lF1sz#W+}zO0=PWrc*DIAwE-wa+ z_+f=-F3XL+f^-J2`8YZvAf3L0NxVdwRRm*SfpHK~YRq9J8FPmM4?w1w^5zK&kbQZr zp&k#)A6b%xyuYrw*B*B__8 zCh2v-wYk92o`V1AWv(apf^Ov1cJK%T=8F($WffDty>Lc?GqNA-hxhAR?Rw1RIA?CAIAKa%L z;W*~O(6|W&wJFhcO^fQlCtT60h=vpAd!P0F#{b;|RyUO_6+|DTp1k5PuU#dIoY$`n z>gH8hq4}s(j9&`%UBCqrMK)@tQT31otrCJp11?4FS*N^>9TK4yS34<7a4-bra)@@^ zR@Xzv^PerT1mdQW(WirwtlCZNaeLMK+`P5lj(Zu#OV(OsEH$Nz+H%vS= z)Swy^z5fy{g*^-FY}=Kad^6RL@qDX31_%?&?&#a`5ZS(DbfnQiuJ=eyF;fPiD=E|W z(kQ-BEoa@T<}3^;&9FBxWn{JLt_@zq6_f7*J7yzvRw7+hq(C8weheyU>T#JLaby!Y zffYc3BRyRHcu}XF6CjJC{aY@KrQ>QI3YDMkay7oDaV8s4({(XN%93EGpPeM2GZe~g zny=p_H}X||I5Fc;6YI~|^b4$tioLU8hVB zF~F{ltTu$R>0|Sedk;ZBm$pJ%@=xsTna_YO%)6Le*tM5fIa|c+nE&c&did8VuWvZLr_;1=&yeich?9r+{X z4m#J1{Fe$p*1f>-Wfq5%?An|QO_T@vzZpzh!j&*ZgI9H4$wsf_DoB=#)=6F|dZ~Qc zT4zc1a?_4PWu9IDvr`m2^tFKLdG(RV(f%wqlF~MQnOYp-&2#^NdNf}zdc+*z)+wX| z0-9fe6vt&^rAwV>x&`7+lnw7A(p=P*Syj1SW$0Z^wlBl{h)71STr=G|xW}QKl(-KC zu6)fmGSx}S2h7?{7nq^wQM-lmsg9b#TqWhzv;A31(Ak&Pnqkm2Tl=yG@rnz#^L1Ui zT~q%gn8!oB496@oI$xe0InxPB(wV>am)>}`0eCaj+P~>s;%|U$;g_MpXfT5UN|RP1 zJq#Ywyv)zlI=0@`e;*fE7TSJ2-!Ty_(vLs9+Kf9Z?J(^=*%OjJrJb=hn2QlZibpks z_PH`uZ;$P1%kZ+BJ>4}F^mNE9V2aw2(-2Cm(l|JK{m3r#!%R=*73emv3+cVe9Z*BJI4G*ZZK9#_5Sj9i2RayK7dv&&}pKu_;Q*y9IAL(FwE`qAjI; zt60uf=0@*|4F3@&>5x{(Nyn<>H*Mb_kb)PFMcv$%vgBre!X!O$v^A->K2VB%j>5Cvdu)wsEXoq26ZJj= zs;ET#X*VT4jQG!9I#Dmg@jAAM}?cq1V-G~g)+IXr zoX%^lJ+Lw@1M^}~v20()nr&u7p2zivQ$y|3H<&pM_Fj0~X&I*4IK)sieyg83mr=$9 z{2y%gy7URBa#+!@d-Rww3!$B>S#0WvQxt_)bb7hllzDX)|10g5;p2@48oQ?Er^sZH#DR!PUL<|}sF zv1Y=bjd3gAZPadD-9-jv#)8k;lsVDCHkFoJZyHi+T;a^f3tG%}zXjv&k&bJWvnVYI z)*oN$^+P(^)b{r5L}0=nEQa6L{IfWyJ5jA8HWkc&d&jdB3|$j1mjk7ZHU4^8`(DYO zXW+}s$PzgxoteIKHslfa*}R5NL=<=&bm3Sd2KywBPXw8N$s|nPia*R&>8|;pvT*O> z1aX)@MxI;D%m3*(h%HvkUir!y_#0r5qq`sCVtpoXRbaG~TvZ z4v^)ae`?xFq)fIYl?>zR)O8g-#}8Mti28sB(iE0-Q}vK@f0LjvzqPW)caYon?ew{u zirkPJiOCFNMMZydL-^CgIqCRxA1kfPh`!223Ob-06L4Zozq3DXj@HJfpc;;kcomIR93A`V0y1x+?v7~5A$sAoB z=dS>lOcL|iK*7*oD~T0*nX+CZm~-lMa%~{);E#AL2Suy!udX%xcrAn3S-sUc|5hwt z@ck1oQ|X*kfLOLzj;+7e#>kLo?W;Y#?HS2Dw_5KQt}7?xyOiEk>w9;kn6@NT9x+fC_bVz;d#0&fo!P3)(k@S-%>-Ft%WZQrB9G>bdjR6-c z`wb3uUU>$-r&N+XnB?nbP5bi5#G82Gs-V!OOnr{4UgdvkcIfLb5|JtQ#9N(7*C8mNklFoYLu3Y-T#So=?6Oc6Y6FG% zy>gA7F(+kw<*1h>THuh6#AlFmPwfu&I3SSBPnCB*+mhAe90yorcYo)f&sYHDo zfqE#?fWPN#MV(|7y9I@i~3gVmYMKAK;x+0ZWBF!Z2xB;4V(4-!dQ^#Zwy0f`<@ zfOV7Sv7Om#2=d#LeV)v@J{kY<$WueF_0G;J1V(TJAKsm=Y@);c%aM^j6RnB&PV!sUwP*SC+gB1i zsqtey@clqaih2gPW9G?R1=3=}b~(R@dM{f<&DZ&(JSd>gYOfeT6)?OuS070GxII)} z%l#BGtlZw(%k4BK0)D9o+=Al@9RZ~9t-yq_X4>2;%KfRkZ4t!Jo5u%ZL4Iqtk61EJQ8ZXxRc&- z>mR%Me5b8rljRSX_pzI(DkUxBhqqGy?Yc%gO=PMS9)_INmMh*8x-Vl0~ zRO0IRu+=nJV}B_1a}X2*Sz*Y=8Q_MAa2tk$eotmdmu@9lYGEH3y!tGRU0Mbax(+{h1Z zkYp>z*F!c9_&iA4&6$#Zq&#l`aI~!Gvr-D56*@RAARl9lipZZV=qi)gESy% zON_?L^-1|%21J5qzz4`q0~MbNQksTp*TrayH)^I@NvXOH3oVY@j9H}I)|~BX4ERyn zo)N?Cj(61jG2wPiSOsN)EK1l;@1MHQHCmEZ8LI!q)08^-4KxJB(o)=De>T-hX}X%k zq(l1Q1^b9Os<$uIERy}?wucs{14kV{9;$Df_dx!3f1#Sj-tKtu!p{wzvue`#MWnWs zUv6Mk^%vX}cGUbnO@!9RxP|&PzgkI}Q`KEAIP?I7+)6_9R*ZTzx@K#sZ43fjaA-%s z(8%p8Q4P#(&)R*b2dzb4lo}h|Un(}EebUtf+_TrV+fDEISR>zFy83bj4WleHOg5rk znCTq@R#tdL7zOy~wi$%2U;PxZ08Y0>mN0K2-(mOO(RBVU>ej9Ve2BdVG_P>KUb3$a zDJu)+M!XN{zwsv;W&b;o;2FM69a{-4 zeuM^WoUJ@5t~B_f=um@Y&Oe^o2811eItmc9hAklM(Usn#a$Ps~GyYV6|72+Ct8Q%| zfRv>*$E}?2y9xlwVr5ckA@K4+oS4gzT}EXd4HFFv_-SVc5R{mKJlWm4qnaJ){_r;f zMX``0;kfEiWQe<7+nHU?W}d(^e}ylKW+m3x%6lPci^)$oCIL^TW@$B2Gl{g#I8Zjk}AYxsNr_2cP&+~5pnKGErL zf7gNku_V`e&WO65f2yAGUf07V9p@X1SY$1pFj6Gqb~o$X0ax^%OuvLXyjJDyKFtm= z9krz7|2fP+{o)+2^RAMFQ-i4U<&*^}g?3hTQHMP7%747VNip=lhcV!~)e!cqCD@Q96nT6VW@riDdl0_bY0*d!FW;JSnuk^LEEv z1oQu1v8CW~2|nNS&I`2;h+w=MS{%Ubr^6S%JdIL|fgS-~ZMUw&BX}-`ueefy4tE90 zc`tG80eV1I{%^DX7{d332QXPsnbl9?#}4Ih?NjBR6CJt=e7!s);Z^fziTbHxWiP|~34}#mm>-(YhgAIsUI_yWiW^k+b{n@1QZmes3Im}U@ zv3h~^yd2Ksc3^i8EZsAQFl0j5Lj+6UZBA{v*GOoZt6W3fmq;!H7LF@Ohj&Ekvp^5^ zEiGu?gMp#uWeU*-w}x)G$^adubaW|MZksB=brG%IY4ZS_HI>?>-6{x(9a4Bmr({Ep z5z*I&Kv6TeJFeR!-z5XTnZ|kR8mS%&bpBApdO#mNBX?Fkk};hc066pu9+?Fm(O(#N4g8WuD&$e#l0%AG5Uo!e);-zp|3STqS_R=|KN#r@M~=CDmoPm=g7 zC>)wP-S1;$;Oc-+AQM|&dA?cqT0{+!-5Tk?W0cjT+!+egV7&7ESuaq5(<2*0ATG-W zfEga7AY1P3xM%H1!|WS2FNnsAohgk1JB|}Z-~>nYZ&K7pSOj$9`}U!Li@Rkxt*u^% zjqv*!PE%k#?pguN({j>H_1BFr&at)Z@_6X6sAy;rw|Uh7`PT7ZUXt@u%fP-HJ5f<> zA!Cb|s-L{~QrFzx2|JbkX-?ULF+nV^u#MAN=*S7INA?;oaC5aUHvGxrd;>5Q!J1rs zc%P5D(=q~6-{_k+;zQXCdvV4cXA$sQe?baNv5zq4$P`sQt$(?pEq~LXl@Ql~04gmD z;8*41W6|;56y;3L$z(sEGE##PZu2<$Tv$i~#&ZJMT&NpV+EIe?Ps5$jhvrl?u?`TE zpLSr@;OABY0D3We06j%^G+Gqt+$^k{d?jT+EW7A1r%oRVl69D}sGq~#r7W`rv@Ls+ z8#<(JKnyM@^*jWbqX9%!TULlUyD&YmF<5w0#d=K0r}K5^TeJorcD4 zmQ!%i_LVD4ROt!6HZD-6@(!5Z&TEPWa@nJf_~E40Sy$SLxqoGf{jqz{A^etF=l)$L z!3ca^9;A^OL%*q7w3v}H*^$=~mFCTpcVmb5o~ZlPbKTeV z$Ky0vsls>Dd_&~yt7fdWe&zk{(K=or}Wh5?V$1!l~!-WLQ z?dp&tUEknqGLsI-OQ!G-A`-?JZ81?Xy#bZJM-?cmouu$}KV<36({2k9?X_qWexhDy=$>DOPrj|o@>9g!8CrAw zu}jt3r}SI^u7o+0E!66o;vLod&h5@;RJ?|q`Nd%GNf=d)V={`4vAL|U@s_-|-zhp_!cQ6B>7_>#!8?BDg^NXX24e(-c!p>?P)&6X8q>(?Tv!e~`B0di zpP;Qn?bf}idb+#@{FdliM0O6Zmm*JZ)E2(N4}DAa2^vV;mtQlfe9RHT-qU+56%5#} z{_B+z*!tyU`{Lm;SD5`(QvVD%&Gj zn+o8@M(z#zatv-H(++nF@FxPpmCbavD$-TxU4tE0@BzOL2(`tLZQgi;9aosg`%!!) z&AJXCXQzZeDSm25)!B`%$00?+XUJjS&0Wv9BpXz|l$br!AkuUrKrQ~otG0XvmQs_g zNt)?2^pHW%n0(gMfdGAUl9?ZRpXYH#mOw&fV%Uc_`PlEPE*6PwzWQi!pA{;SSAh+`xC zhh<=Lcj`tE8ZFIMWTe$?NrOt`Iu3E1ysHHgN`-GLya$SWu-85>b5#0XDxx&T>F+G5 zSf^T*s}5ADXgR~9(CT+bfrtn2yUVqdF{L3rrMM3JVut-KRqWc}snOhLgn~b#XRB8! zPT|dL&=Car@*>NjpKBm7s|c{Oaia2V-C7>ESGJXqu{y0@zwr8B{I`Wr347l~Dlh*k zaG1lQyn)wE2iZLz+W8~rT2i7~Sj_sWM>;tgFZ#nQ?BC~oGeVU=M2Yw4k>@VwDu>Ae zpOk_rJchXEcG~oeC(H<49q*oVwzG7Yn+elKF;?L=+Q*!Q7U`Nty{J~56;=szpH8O` z};Dg=dySWTU-)b^B}_W&8Oq zQP)Z@Z|HM^|BK(ywZfI=XEt7s*i z4w-;k)kY)Qg)in|#XkzI>8NiXz$`CaNfBtgSan>VDJTa6fN_P~!g+;`wz&3(se$)n zEoO;pU+M~BGgy|M8crCGnzPikn*BtzpuB4jmNal2yWqr~TADUyX?C_ZvJ$LCHP<&2 zw#4GiG3=0;rJKSYG^<$vw>{!-c#slUm(gObMac6!{}Ao2h%zG0L~lv=t(RqC4xzvH zkrYkqwC-qL87+u66SZo9HPX{>vhuVO*e~xTi7S!jD6H5{eH zl_v}L_P|0*^ zWCvyF@o-M?sM-EB`scA&e884V=Cbzj?7;2^4vKy0!A^Y=y{gXtVp}-K1Xx#r`70eP zb+1DQhx~9Cib#pkW3de_qzlC+eI{sS=pl6iSSvs#Y3^2DH$|I`eP85I1Ggw2?OT|W zuBl$@CSt3mNhd(Fo8kn6#>%OwHv1xcSEVG5nw;`^wk}Uwz`t}zFY2v>)6*dfMO-n^ zGNjt8lweoPXnd}1W57I+BsNO!&dehMoPtGln;5}j*p$_{JH^R$Lm!G}iyd7K)~67# z9%GI6wYq(=HR(XU-T-kabRyrD$||+c*`SojNnF?arRVUgJ>5cu>%aHSRR-=>`z)sX zSWfP8a&0nJN1E%;BCo(NWydQBgd*>MRH9214n?>psacAp zd~@@utuI&HUfCHdUF(g(@4R=Ny2s3PsSD94b(+W-JjqokQi^bDNr2o#*<;xK+FBb$ z9}7AH?8rEW`XqOZ1yoXLe}A_P2=5!=YF@0Vu-6?l1%fZ>zOUQ^|8pYplDMXgh3HXM zNmvPkdGzYoy7n-UfSNNhoI3$R&=O4j4BwsrDJG)%6W&3H544L&P2z+apEV#so}&Ch zUAI*#?zvn~{$_DZ?yd%{e8+kUEG4H0MmR2_A&2sVG94cHg^SgqMppYV(m#TknicZ%Ehq^Z)dkl7tF7u8X_unm+!&BEH9Me+n0eT-UXYJ2w;c zFP`i5e}_>?iSS;-oP+s5Sk~|QW-jTkpe<8jjs);YSSr2?*>Vg!d4eZX3rJWyKL#RR zgEkZyCK>GbOJNn zL8qTX7#{<$e%!F;PoIKC?f~IE0By{gJM`BQGE9)3Hb|bB_AuG@AARtT4?l*;_H$2H ze&qB8=v+Qc3)h&qw%uyJ+pPJ6TJUEB{dK+%N~h@Iuxr(BQScODg7{~;+y7d|tA7Iv z;~0ar$U9?tWp`f?Z~;@EI4tLl2UdsMGXHLBsyX2w4fi|%_rRM3r?n}5T&}8X>tt`l z=SKJSSsU;voo>807GUYv6ukE){wFa4_#v=6Jo(jm4>=rW^Ye8|f^+QHm~%hWg4$I7 zAD_c{M2T)ZIBsglu8kVK<3qpGlS~_;QybAFJMenW)v4x5_ZUdB`Dnm~R?Hd(qbL6P zFRBW_A2WL8(o>oe771(Pa8=ekeuh|0uC&xRi&gxaQsu9kSsVN9h(F-UyBq&L+_B5y3+$p9GxEop%B1nt_K*Yj zE$TXUCnfyP|Dcpet~wwk;_zS!*ziB3M*)JCtG;p%*Z!Z6V1%Z9v5x1F1*Nr-}s>HOSz?uz7b6m!N ze&jziW?v}U)gO_vvH$^f=Z5CDA&Em)8T_>i4X!N+fW24e(NM8_<=`W1d*wZ{HgR-t z4QU>%T)yazUmg)K_Jtb{MXMM5khzllt!;{cR4Q0-W)Y;*&RKkY=-4EIQ2qwG-k0IW zU`{utYT@gGxeRP7Vzq4WkII(utiVr7#LhEez2xERo{PN5-w8$yt=g=Go=;U8x5hu1 zMaZL`xnz_Xyr81HQ)%mGuM+~U+siz{B%0_cl9=F-?$e`H-MQvvfgYx$RBjc&Fe0an zy&Cn2tx=rYU;$$nC^Ou+?sQipdnir*)cdLj z_+n4HAJQpgObZo@{x}xa#;dZbUbr7BaPo|5=THVPHqB$F1e}3%30xMdW{mcb`n|4( zLLHe#e#3X8co`=^rSA^ybDC|cV30h9jpC{*yFTwMm}rdm_IPqL&U%FhBLmOZi&(i; zpgA>Pbxo^quR#1EiK4S>qxI17IdNHsWhD2LzsAg;Im6nbV<`dbF>M?*f7pW(S6ls^ ze@_~DOmoR%D@ha;hzde&F4g57KjPlJa@hfHW*5rY6Oy|NEfe~5c zbT6LE5SlLBd~hM$H!22O(F{<#UoR9yHOFc-7^_}4$jhlK7TuYP8kfyzYbX-xP0EvbJCYgk;K}m(*^pD9p zM2q3{e)eJScB)W8Qt$EPML|bM^2(2t-_^N?NTSB;Z zhR;K4YtOpD+_B=?Tz_jseMgkisG0K`O%CLyIy}lcxOZ$6X+JA%oF{_!De_Lc=Rz41 z7sbAHI^p zJ1jBPZ=edA4594fAAA5!fE|R~Q2#+NN13W4tA430Q2?f({H11g!DszTjGx^nOyxI8 z*HLC8pZqEAoO?=!e5_na`@rL@h>>%bhcj}$JH;Vpxo`JnAV2l9U2;evkXRz9+BV7C zOgLF@T<=U!Hpy`%yPo+~l(9pUeMh0x19CA~+4w#Qg!rC(X}x}BrRi~};keN0xzADf z=D<~-UN3cQcUPt*P0uir&ABL^m$RFv{mvJ&h z8^|SgTc*1l>5W#pZyj1FVmVqcnz}e=NsRC7SWT&)Fp8Md%{LB^Un8hixZ{hvb_I`> zK4)%N=prv$HK7p7XeJzj7O|{?2fz=vLyI^y>Bt&V*!ThaZH9!(+i}%9yc?SVg6k(L zx5OjL10kQN(pN&mGAtn(W>}RQLMXnilzbF%@*-nnt9wjda}+!`c5rpMX|kzmocSyMT?5W?VM$%z zLanD%p`u^ZZ2Gq!6^cQn&{-6iBumeGkmbYSI&2_LapH3D$6H_mUysMYxb7+*sKL0; z-`iKR<9xX`%}O5f$BuYinWg-p|3xCXv75uayb+6@= zB7kvLb2ae|6DP3IzEHt9>d8oE(((KidQ_CxzoZ!Q+;P_j@rhA#j|L_J;%ePAWh`Q~y~qst&BTNY0Wk(DE7qgY7(uVe3Cn zk#*T8O=ckO2`!xT8P& zsW~idW*D8dHQ6t4$cHF73Jco;kX1J}?S+%6OYc+%7ezC?5?pnh1=>-w$+c~%k+Ywz zUaCmI*UY z@cU>`aCaJI+J@_KlKJ6QoVRLFZvp#-J75r`odgUDEbTu};_oc4zle^UvKit;-LOB7 zN9{HXV=dJcD(&zx&83(mJEzf;$4;i}J*Pydw(jng0?C~m>N+}B42j)%R*`QDbRSEs zp$ZwnHElNWsFwuPgmioBp}0enb76LSrzW?(TY6rm_FIcrTq=9sH67Hg-CO;`BL@0# zSc^H<1Kd$>-`76tv@LEG(sSafhGB{}Iy4I2yV^3Y;Q5-n^Re68A;dgO0O&gE9y)mEVOPFtQ2&O%TqaY0t_%O5ZNl7flm_OV}Mp%2Ji4!SE#$T39du!@OB@o(Q@nzXb(dh+m zn()2&ZZo@(WEzn=if9q4YSmUxW$8s3D}(fd#Sy`PqgHJALMg|QVY zH;8r!08Qd#QrVb(=g78woyp{LPzq4V2rYhD(QC)Zqg$xjoJDLwHr|v@%%!@o9hkaD zG;uLWiUq}%hesNiV7K_QVIFpBYO-#WH3A4b=0TrslTnKZUI&_4k z3E5wyRNs@)te0yL#_iSWKvgwXyiKXHAz;_gGR#8^@9EtheQ__bx%hRN=$LT0mf z4D4!(6$%$DT@7ry6>RvEPk`XvkFB>To(V{myS&%+^Y1V-{okm46*z7M);csxEUmCI z;ZBG~R^s1S0=ic_m7hv&{Pjyp&hP`<*3ijJXkJ#uS|ez#FJfet=7G$zBWg?b; zsNCbSuXSj-UhCgI$Utp|cvP+c-xsC+nQ)`dr2hB?Klh;w#mD^g4GEfa#6U++iS#2v8OS?x-lWxfMlNLCL&BX>wnrJ!| z;fe76Im{N$vr0}}3;FGSw^WQ-Ub#(Cd|oE~P*(YT^h578P?@}$C1D}W&GNv9Dm<4zy> z`BsMK%|b;3Vxv66+m#bcL+`=zlm0cLU_bD$c`R^hvpcJ@$lz z2|Qq;{t@&7e9=FrC;p7(|DLg!)%GK_uNl}yR`6u{{$<#H9KFcL5tbxx9aU zj@^Ir%YRUU046_PXJfozh8`p=f48;-}CZcb+M};|En#3)E;&}#ea>(e{JP| zU4`9)@Lx~qN7CfKp3?u%o)V)Szla|MkV0}r=5jCJ104Z|mSjOK#*%)tjd8f@&Z2r6 z(tB0F!LcYEcQ{{gS2WLwq|&6`1JLFRIiUbCOqw8joS|c+#HTmHBU zo;Xh226>UO161U9f7jgwjGi>24@5p1X@@FmN#)qS0(EANc{YPjsuX&c6eSIp_-X&3?OriV&^+WPJt zcxGqhfw`n8JFqqEMsjtT|N4ONBX0YWnDkj6$j$Xm63~fX;hXuhXN~8so+BD8lfzVO zRj5YuA11- zNwuPAz<4A36IwN4cxEaxq}`>k%pXor;*ET$>*cNwuW|0O$GA# zoQ}*T^N5c1yFjPG?ltE`pb8{~&sny~&Y3Bt;SyK1Z;F_YA7z9()yiEp(F0}*{B>0s zn$~&uF8XE9p%3vB7kXdkWf-lp9aJOZC;Tn{erfZ5V8VBF6e@3^P|*-!PoCc9jG{)f zU;aFLdcbrG)n6$c!syciSsl4c=1)7;Fr>fFTcQ$)_0k1)cD>F6dvnv(zM&$YUwGtP zot;I9fvRS>115(}SM@Z|Je%b{%S?h%0Wm;iEs|~3<*qt~8c?2;N9WRW6a9C)`GDR` z6X0GAl2o1ME01cIab!kJnLQ&$uHmv9F zsiDS|2(qXC@p3k-9@o{6+_ddN7F>4B6Q$*B)nVk@-}cT2E34@JK>z{@SBYU>*Y{ROz zc{SKOLBkv;_UOBPu3?rHV}`TQTl>j}-YUMfU8j7A!m50~MUSzd7{*sc?JmyK{n`y3 zR0}2i@o;~5Om!jzxw#zBaa=U~vxP?1w1sf*QfoH*<)rl>IaDTK+f;iRiqT{=XS1DB z!G)(n$a9WWe6-Rx2?AwuKb1yhK_nzue;s^-wo8l_RVp7iKF|~(KbL0?ycy85yL(Tw zP`gx`HzaV!HD76|->`1&FfQ4dc*Ss10t;|KVJm)XeCfYxfYGcRI8F|p&uQXBxpC7P z?H#YJcS&I8Bl~xlO_!pm9q6Z8bT>WJcWCvGRTlS^4^F zBhE-}b7;P|0_pb}!U=Akjzom$4-C}$lCK%MGQ%k+uM9uP2#&yNu}L~YeYc$aqXi@a)V~!G5{8B_vH(<_V$F4 zJvL4pzDe0<>V9=5S!v0{&R3*Ct5&&hf-y+Hkf8Rxr3~*jpdYxg687K%u>9iVkM;__ zrXDkH`D)gq9S_j^G?g>Gje94_CO?&#$DWz=z-yW>+g#^ z&FP}nRhKTwqEZFQME^c?tthYzi4(V#auxzvkCIbKJ`*f~8VOV;5hVt$HlM`ctf;4` zuhrfK)WUo#S3!$c)YfK4NLzhwHSH5srS9H!K zAIM8UmOOR8Rrxlv@>7c%`Rof!-+j0XdSgag1=MIhn$5TgkD1dp2-)(d4RQ$; zDqHO{EG5C#naUDid=wNNzo)J8`k)i%b67&s#+$s#y0pR)z^FG7^=R6 zBnyhH6cf^^(5|-;hp52(ueayrScnS>Ncf}SA#EKGyUs6p<|~Ih|5Po7_iKeY2^;yX zdIs;wtE3FP(T{swp&4q9ly)e0RLHn{Sr{!bhc36vM>0Ft~j`J23R&KtuoOr0QYqpx7^03@cUIf1lI1cZkxG36EIGV)Fj2 zbFTG-eLa?PqWxp#YSg78HR3RIN*%ihW6ObK^GrfQ@h{ds8{5w(nCcJ)O_fiez=AZU zX!ycaKBDu>D4U zubd1YdE(u^`z*lMe7A?yI;y`4$(p@+s*Y74W8n?nj%(?C8lrYOf2-s;#obm{+JmlW ztoV;NA+k+y?by+H5j2=2Pn7ovw+b)VD#IL2zDB$&P*MFlrB|^d6eK^AtOhC)?;;t# zB{F)BjyL}y-b7LwjBtI^>p7qz`!>p#h^sY~Ozq2^8gzU_28BAKv681-yYs94wQsde z!@qu+;qI6QROfYu!jF|@EL+s|y<_n|n`1paUtT^rl>`}O{vkuF~`k-_}m^ zhg2g*Q(jPMxY zMELOc!|#yM@cx7rMN&cm(oGauF~|Vb(-b}G%7B4fU2hTg?FI))7dFCgmV4AHdMr%Y zZ)dn3OVNvZ_ux8l(Vpqe5r0^_2no&bhOhd5%Xfu-5ezxd-_Rehgu@rMC^(bzzxdN8 zs`FZ2!_ze8+lRN-)w9z;|1+v!}+) zod?3~98Lt=CA|I~z6f#=v>8RbpnokNBR;~b;M|SUhjtW@k z3PqB}1tUL(twOaPXCup=b4ej_-%mdmYJmdRYi*x8RX2HfF}AoB4x`2tjivLO+5c3Y zgP&0}?g~{DP%YD-aMZP#WVDKBg-i(VdMk#J7b!e^csbS}YAYuIa66KaD{$38fY@(Z z;qY6*{YH3xLbN*UxN0qClIvk_X+H_jC1DR&L(r_}MtKvhUa!t~N{b=msI$U&QkFRB@4Angkx6q)DUI9HQ%~_K%!NfxBn?#S-sq z(X%V3*>uOheaUM*rPHa+(`aE(jhfH5muCInvCp&?hopVN^#JtF?jq+zI+Q%jWOC;D z|L7f3fId~PwGOL!@2zzP2yu>1`XB$dM=ww6mJ?;zJHM%PT!0Sk4*<{R1#|4Kh0@gi zf@AM4#xr{v2qC_p%@4iArB8*;Fa+=LdOv-iSuh%&?=9l6^2z0YUF)QxxW1f z`jr)A_vua{ZZ4g&Aic)@jSR{-U62D*FL&2{6??nq%IwRb+7Z0{YoBE2LW(En^784Y z>Ivm(sui7!5{>Zi-`~UnIN#l?|G)OGGpxyMTh9zf7!LwEa}<$gLllHa2xI^O6@`(2 zhz;oqBoJDJC}0RM4kIchN(+!k6GM@vhTft?KqMhRq$Px)NRTE&C|Y7Rr%iHCFB`;(4$!%;AuwV&78%ta#>5;AGL1#fEiFe-%BhnE9pXm=N)2aN z)VZZM<(xkhGjRuI;j<$GEK`tJL8&bXr5*@WJm8p4dORqU3P@lAdah3mHl-1PA`B6_%uhTEGGOg8YSiIb8v?9x2?)1?sOMT z2Jk9NdELtJxa6hQ3uAg&?y=UsQ9|yQLIAp$6V~S+`mqEAfC$e3Xyf3F^(+H(vfH)e z24PLjfj9Ul2DSWfAA?LFUhEp55>gMiCBRO9fuQMIASDu`<>1$tmySIkW!o>m8<~b= zj%khPTLQJx!oloT)X}1odgeH~?iOw*An`fy;!M5GDq1W5l9JYM zpZJ4QT4O*DVd3A7P4wnv>uokPzyRSvqE1^JqCh8@ei$--a1=cXBSk+4`Y7eTe3*!y zGJC5ka!t%n*?K2IJK|H2^kXgK3$`AAls&Q?@@H_y8l!y&KBn++-yo8VxwnZ(>2~h{ z;QBcS-Hx%n9M>ERQO_MdI~HWuw{db~}Ob|sjspxX$y&wx(>JiXEJ_zzQi zpS8x&ikHHpujR?Xn;B|>2}9k5w?xtNMKC>`g^m&P8F*16E>qeVtXw*;I~>@3mkz=` zQ&+k?9^Lj8tV*bXNEW(ZB02Yw(-r-fRa!5=>{uG;iOy{niHP&mqvaPBznt>)lo@hl zJk75yd4Fu8$BqaCzrmajcE{dQ5Jesr+96ODI-LilaJ=)=s#_wY>sp)^!OCU7K8QU$ zKYiRlP3{P)CO^}k{AglNr~T3UgxXoCY)y8ZcIj<7EA`q1jkLPf%6+q0g9*4L6L)dZ z3CPoxFkKLG{juZxN7hPL>nZIhup7qSKZzY^39-o?Y$@LT;B=S8bu(<-pG znR#-kjPZN?4Vhs6uCc&nhBw74%v*3|Cagy@tE%S~rG@^S{{b)P=KD}7RuC@(drWvm z`f4HGQ)i#Egg$x0^>45zKwL+c9(&aXtI6^z^R&z2$XE8Dw(}=2 z!F!dR5rH3m9ox>LEt&azXbaxQ9CMLNgP=Qnm;;fc^fK9A)bs1|ligT;? z2iEOYuB7t@FImcany6}M1ty0e^ObyziuC9n)FD0a#Ny>q6+C=*qHIju5nJVhwzT$lMw>P<6px9AmPC=%GCr8 zW&KrsoCecch???Goom_%b|t`ZCR7DkUJ*tZRtQ<;9co8GZ^cFX8qiCii#9Cd%Reqj zR`3J}UKV>E;DKnJEJT^k<`}xq&?awr{!Lm3C|^owwyiko#d)#F=xO0D9K1*BYRKq; z1|jM=e+=jy{uQQvtK{^L9qqtQzbR`Tpx{Ayl@&Bk-ZD?FaC6C2BAHz}8pjm_$o{|K zW=H7T2!2M`j(3~LIkFKxy=5vCS=NaK1v12=KVwBHcl)|gwC;;nsB^SGV29YnGM%)o zmAnzyx7svhl8Ilp6}@9*l3m&aJw1ANW2MhuvyEt)frMzdKre!}s24Sh@iX?VVCGo@ zz(e-0Q5dQX;Kh zN4eOS(%v!iS+znx_@=>6>nqUz;|%dt|H;vbb}&9QF+L~N;h?&)#zp1zQQef-On)3o zuF!r2@2QJkDY>wItWM@Bo)kZ4+ChBtOtOgw@V~upd2R-%EJcDPzrI2?Kgz*TYVeFw z?`rZ^yd~qB$;LORZPR4(feha`1jUqg4$u`|R6qDuY+b^lUx29A&)9HC3IS-ybTBIk zSmX-#!b!|T5%za>?3Z~Mg8~G?)0t;M>rz)nde{amV9|y&T7>q1SlX@!GCuO)K7LQ@ zQXCn#wyRtr$SWpwtpl;}{$r}xbQDT7d}F^dp)&vzB(QqZ?b8^$7+^5L`I zfVst!Ab{mi7{%u=;XQ|54x4ps@weXz&@I(#A@PAGK5Ld^ftLC?Ne2e5_ff%WRuMe1 zdve%awyqk@b4?|k9@JK#mQlD52(?4UrLE@pCTbp>g|WWu^%ugPS4sFdj}KvCK2?>% z2U*2QVWm1o<7+CD~345JvaG>XujT9XP7fZ2Nok@T`!R)co8&q)a za*T4nOHKOI@cH{#tOxiVxwqyY1x6wX)1IX8n$j^{a;`u_RkwDCBwgVSirE#7&Lgpe z#9yzNhtV2{09DPD%fFfFomXm%KM@YRuxO8>XpPRFXC5XWoon43&{+ztxV8#{-&f6qKC&!_T9x9~JHENTVfLQ55V{KmJ@nnd z=L-bedCj9!<68|G3YwkLQu&CqkRTxGJe^s(2YcMM;+0*aAuSzBdy|9P?4GRBpUvTm z^v3F<#k3TZYkh>~w9kwi%Z){Z_o4lnp4+sb|7-3sA#TuIqe)+32zhJ2K%kW>rK-T5Hqe1;}j*hDWZ;T7X zAaly5t9R-H4yKHohoX0RN{V8K3lk~4!x^@Aa%QI^pmfRV_vCW(7D3oRhy>5I6Mqe1 zZ)`$Rc^7J+xq6BG=E-xDkhPOXGVh;1hYk0@$gjYeL!se%xX@3B(r_2@%MnfY7{02f z#hn0u0QxC>X@lNvKQfz|=gZS+b{kc(19xH$*cxk-;ItuxJKTH_`HG8hguOSuJwzh0 z4O(ibxDDU>m-m8axOVDNFKPdvoH>F88o}qyHC{&L2c$RE~gr7wR@z}YsWggPYoHM zw=yy4ztp{tufvcrA-3Ph{r-RoFt9Sput<4m2+r@!@jUmtwKEZ(f0Sj6S#`hTeZ*K) zodND`e*+9o0bQ?-g{($c`fkN-Wi58h+T6Q}U&}T&05^Ewei1$VwSkEU!}!X?y;XE3 z7IM#hyEHGXs1Y__{~KNd>J5O#>)%EUlqds@ZbTr=Eu`r|F;V_kOvv>9A3uZx(of39 z{P&Lo>MTCK3>EpF+K7vEztWaY;D@6Yvukb&TPVnF~MUw4@DLer};$XX&2=;aeH z{^{q;x$_&b06^3mS5zExPH&V$;?jTPkwddqgHZO0Wtd;$!7}Vj<*Lgy|314X3W+jPv+<~M_TyKpxjNsE%i&oUtHcuFg~uj8El!=C3LwX2-wdY< zn9id#2ag1v2Tz`^{!6X8 zb8kx$t%JrLwyE=iseQD_q%4Sdm^V`w0t)74Kj+##yf5`>vb$lCmK#^Z1gH-FE?BsQ zEV?j199;}8^jl@t_>@hsCv<(@OSI3KFE`Yn_LAq_i2>*mt{i33n@{uLUeQRxsX6;K z6_01;sGZkOSuJksd z4%XPN1`s)57q}5<8?o-`pakmq?biLvSm;>#il24OzNWB5Xcf0-;1N;kOA4=47a87h ze=1Y|-Y82k2ZF_fa(^B&uuvy{uLqUqr1*Qm<*~OcSh6FHGJH=je1TMbmp*zNVGUpT ziR$PU6lLKPs>{yVqpcv<6!r#X75VTn476lih}0x9PF&uPx->m9imgvSe-oM3%YUKy zP>`t6_mp#KA?a~mO*q=r*?ZZgnjW_3%5EYlL+Kjs>5At2j=ZZ=`exo4T~`R|U6|le z$&{A1Yr6R)ImeN-TLIcsfVWdj+d-bG@PWK_N8V3Nho16x>O@_Emwi?Y_ND;2a)3xm z3a#8}?LS#?9|yWh2-jCjlu7s>7I^3bUY8wMc8!lQIM)(mR#0BeW%K&eQY*%7VZ`ky z_hcTZu4HifOC)JVuq(yI(6!GTm}|8o^hyDGxTmSp`Xud#N%8{YpE}DP=#s*t$Uy@l zX&65Z-Jj4H*=i9Rm?GydwqvyA$W1i#aqCAGn%iq3p;z#zbUU~emEW3N`^DL z1ERE>tqo1#)1ZH$;Z>yz^8o)!aSo!4Ch_LbcXoyNOaJNjN@|)brvATu#2P3NK-mbi z{04-ce2G#V3i`4Ewgh&Ca-$U%f9&Fj k4*#=T{%`vK@LqxP%#POrg`SHG!kF;%sWT^wPF(r(-&SdmQUCw| diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/EditingFile.png b/Firmware_1.26b/Documentation/How To Contribute Pictures/EditingFile.png deleted file mode 100644 index 73b30fdc566ae55e95f9f24563df42eed9c94db4..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 55394 zcmcG$2Ut_t+Aq#j$FVTNsG|ss5DjN8pEq7|^ovtb+4}6m?`Pe}N9R;jSVE^0$9yga&C3vffc%0+l7nh5 zgr92*i)^1amNYy>vxC^_HT6-AwIir^2O7=&doOmw%tM+gcc1;<`TIvb+i$q<-kp2u zr3=nH*Na_odf8#$S6hxn+`dVOK7H=T3ywaou6liLzVS%K_uti4eWk0m`-Fv~>t_?p zaJrybJ7;=v7MtG2xsfUm4z2Oqw=JTjrPJMZe_|5qIA$M4{NZ?awZq`knM(YL;O&2% zTI1C4jidb?-4J;U@J1EmOIhmDAYpXDvN?~!$eq;nK^tDBB2(craa0Gg=~JWEyho<@ zwZ$*e89B0%oFc5^B}D8{i_x7k=wW)Gc;0XAmg10LFS0yIkqT@9!9M%cEMPD6)T%#~ z>)%h~0A-vS`LuviyC}Uyt3V4O(sGfI15pI#`J!gal5jIT0Y#S18|28U#3qUv2@@%O zOS5Eu{;8+tk-@>i`!Nw!?pW!Jejhxl;bK+_To?WRiuMr&`b}9rgJOGO|wGCN+b#m!tXYTFld%pP{a|$U$7BV>#anTO}^+*u7)CCECaNmNO_AHFld9dWOptw(x%Qe>Bq^kBWoXqd&?AV%kmQg zk%p24DlRN zp~J%}xQe`FO{m`1$d)~_$@V*JKMz!oAtE-k{i+L0(>1kKS4GB+D6g7L+3j4s$m$c| zGj&HiDkIkd6(N%aacS4j=vR#-nqF9oi!MT~O)!%eKdtf&-&d;)b^M=hRoP`e+o2v( z5kxTyC@`LOk_FDvpf71@0~_*SQeF?i$(LB=H74k#O`ToGI$fEBb44KH8AEZdp^jca z1MkukIfa|}uH-GaQNsIesflk}mA&*Gs>HkNH2>;dc3lF56?SX3U^JW)ST;-jNd7O) z?=qlg)o~&E(34DcgoK2^Q`b9_7~v41AAm&5=wD7}BIWu#eWZLFkdY%Na|^cR?#~=p z_4g?2{@n3?eUammE___b%lY9^Y-|{94b`RyZkvnuqRz4{Dz|!t>x=Xo4@T{h2vL%V zyCuAm2--3-PP+xAJ1#5%3<{m@*B(UNsNPla0ikf&~ zur*KA&McRS%TtntXE}KmJr)wy$ubS@k?dqj02%T4wJEtj7E9Vv0^BP}8IxNkyg*GC z1aiRL)UC0lxQ3DipsB)-7R#9g8~4R^G0})lsz3LeYJxbXX=Y>;wO&>5#fO==gvO*5+0dgUYHg0-c zO}BQo#yTPc>PAacKLq{lA?%lxAhS22N1AGS531RdPUM>$=GI=Zd2OGekwm+N$_Q(@ zMIF^Qn=nm-6y^f)>cJH$`RtJtM{IN70Kb8<+_+#eN(PB~fvQEI^#%i7w$>aKgR!_7 zwNRId{uXeF!Jy))dgw`iyyQ$S!RPf}s1vvdlAyrt^ z!BeG(IC#uD5)sh}N#)bb8=(r3rED8usF+4rng!&!9)I9+Kcw~{>BL2yn2@7_qGgSZ z{mT@Tmuq^@@R8o-s7Mg+g{zv={kpM26y!9L9Dw9Bv#+6>c5{aKvCNB%YT>S&h{89k00ZLbdvEm}?+TD#X+ z47})-6I#2;+0e*FL3`vyf8C-oq1o8!C%1yaikRxoECao@ygcp zr?BRSonf;grrM!_smw zKG*b42D=p*u?Xkq`nr8f>Pv=`=(SMEJ$T^PaH!aX4f)0dF)29xzSa?A>?M^xS3vpSy^!N35J_A}hv( z;|Z(z_PAwmpHA>5!yKQr!+$rm>$rWB9lT#91spyJP+w4c@LM{zT5yDaLbTnNQ8H%d+) z$PKTJy5>|h8tQ)hK?@|W_5$eIarW+L&6`*0=!u^u^t{b$qo(V^&Djr`ylu|SJrP`M zXqU?o{v5knf{rW8CPro)qVtVqZ|qLNDzT;D2$`o2S@AFhTPx1*>yM@6Jc%I+i40bq z&Nh7NqA6Lm7i}8SGHEGEVJI%=I~^$q;Xro8Ue3NU>>PY*j5S6U9^D~1AoulKl2dUN zhwpc0n|)mHCmA(rc*N3nLYN32(F?-q1BGe%?W70!EQi!*%aYG8$UIow`@5^Rl3KT%w@ct1W~S~LdXH)?FX$fB zjmq7siKjPkwPq{Io;CNFN|&gAT(_lXgX{P+d*ZvBZw)6GMG<1W%X5CsyCi(MGlAlf z+^)q>nHnNwvXNixq3LAB?CJ*OtB)&%;e9Hop_0`3E_we4F}xHXtGzPi0F@2vq3Gpz zeBCC-vy#8K>z{a@@+&VadTW`6p-fy^IT?EEMfKV#)=TO!aKYj3)BW{p?05sU4!ZsfTEx?0@iFzuqF zjjBTR>!~lrVYNgER~|=o{eS?Q*CUcmTUZxBXHbrWx9`u@cAFo^TI9jPw5v@wgR1xIfTx7#7(^uCY(fbyx7LV5yn0)!rVl{UGK;{YiTD5#!(lt1wE+`LveXAl_=F zm?9&q0-i`OYUU8HM4l1+VJ&w47Dvmo*|qefBVy+5AEgx2ej@#3bX}>e{SlHk2He3! z*~PCG7yI4iQtH2b4Bz@wD(B<`=xjX#9(`QM-+?cP@@?x!IXKV>lMq`$u$f95OowlRtiIrZ)dvd3SJ-0vf=Bc z+3!A|$9Nk3qhRh>SRW5kQhgD*9hjb9Orjl}OoFoew(3k~bd8y75LT@~Y~^v#~M zx9H=ND1jl~cGu2@KdpJO<>q|tR3nJ?i|~d?>b@_Qm_rwk=lYupZ+X&DEhPTcd3Hcv zF+d&{PS4KDWm6;?D&3%$P^V8qUl^W11xAOnh_~+8Glk(@1(rP}b%nLC^*slNSB5dK zW7@TMreH%;hld)pNT|?ZVnEnV68ncAbQY2W5qo;-lzNrIll}eDH-AEC1QTznIj(GwlAiK}G>0>@ohHgXr z-iv3De(B$kOkSy0P*>U!x}TL=d_TTy56SF8UkTk~;B{*7Xm1_joXyIsMxt->L*jxs zbk&-p89KVOa`0vO82@=gmc^R;3&s&%@Y=RrjTNDl%ps2Dq^!8`*Oc?1 zA99|yX5BP@+UvSm^p%8+dA8Np*Ip!Mn6AnAQA*O*-w&ySu5;`@L= zv)!njyDhD{4~|ilYq-sQb)zuh;%G&1=($CI@qT`3_Fd227xxq^t(S*`yGw&O7fpyjYwhv}@_xMHTK8ztXnC>hYjhV*YCAJuHzF5qIT*de9$1Rv zyi8HBe$CXdVt4(NivOabsN~PnsPTq?0pRP1^e`lWFNyC{ee7hm@mrL7WMNNa&y-|% zL61T8g>;AqcS%Vl%i;!U%uv7%gXz-)viyc_&uH21onIf|7-udT4u{L@V{g~Z`qfVC zTeBt|M7eThXUBN>%(#GkAx#veQ)9^cY*Z7gX&2h0O-YqRBFyj`OW_y5_{DLqZ%f6)XETrRc_+7eg)a|8jl$5>>zAf1^ zTduo;{&@xx^q{g;!}>&wJv3i==4XIh%M|{J`Q0I`=^k*MknUeVrmQ{m?#@)ggRQQW z#H^IjlP?E=G`8k*1`EDnmh$58#b~|}|2qJDdw+HuPMgPurayowPRSa&+=6LOO}9dk z4xV-2-?PcKX3+g$3jSgR>O%eU@euBhx6qgRzMZd5MzauYve=)oEi!Z8-yZnwG_nZ0 z(pMV$b!~Vf+SFp)bb@;)CS7Kv zV)L%m{LiCxz=fVt%wlqhKV-#}ampweeS{T7h}-Wye0tVSN&GL~!&K}NjdfRPv~O4g z8iERb(ss2iAn!}PKVU!b!6j4W9lLvql$ZBN3C`E+I5p&?Z{QWTnw$T+Z>_vvc9bT* zIK>Fd-V#XjMhd>GJFXEEa~S-=KE3w&8!{L~3zIPLZC@Vy?(aXMn6(x<%KhIiKdn@@ zZ$2)6OTV>K#aNru0`^f}2#EgxDw>ajik5m1+F-|Al|psaW+f$u)bK~G$ViSc=6GG- zSomXpa7EzGFPzlkWBllmkFRB$e|+kX^TEKkSYg}Utd?dtI5MeybOLDUsjN}AA5qYbEDlK*6RH3ik<-63N9_yt3M4&ka-dn%q8%S$ZZ2>>% zrC#jjH-MaiQWq$@4o7yR_SFuBHToq6gcSlQ33o(Po0${N?|kzA`d}3PT=! zSqAd%Y@C%`7E7a61PkeOCiz{-o4dvcty*JtGrw!hl!WD;Bb*>V(shI=T2Ldbf;K|d_zceJUa!SQ z{jz|l$CR5}W4mb!>Be{PqS1TmEotnB`wEEzHP7GRz1^#>W}AP&nZF!Dxy*#CqjG{^+nyM0r1!RkaTG`dtb!$9b5F{7stu{-HWs{?Db9sN*FVK-x^6USojVhRsy+8 z#R<&CThtqHZIhQfK;GK6mw%S$H>V2gk|%`gJ@YEMytJQxX@#K~mbBKWyPb?@H5 zG2q=?9N>#}5o6Ch2bR#MJ~s$^*AO?RyV1vTe%{A&yog{afSAWDtUYVE`bXI3CYD~I zvyb^*w={TSfX^EvMe>+%1eDmmd^2V4K_Mg4g!*VwwwQ!ZqVNN`#WLHMtRcQ?dFpf* z3iaN!6#j8R4)wgGW86`1&CGxz%Y^>;=XC4Iv=s_ZAZ5%l=0lJ$#n|PQA!Kn8-Uh#ytM0_E^L7oJ#qqzny_p!$bdTC2M?cgd~QeS zzu(XZ3mwHaZ}$jWr`oncBrf?E^%?JXDmAK?FmyvHj;z z5ADN9Z{Ov{FJD;0utI`aapcCcEs&&_2TiuOw5}F`paKX5o|)>gSlldG&u*2yD`;JM z-P)S0Xia(l4&4H^q&BVZ_{GH z;LF758PLnf4CqFg*i3uKQx67N3oCLZDc0Nw5!jdPk}vDp1$ugY*icz%$A}4rBdnnx zEaaI%)~}F$IN?`#`Z)AY(0$$bRGh_$nQX;))$dH@lk`pSLIB0@Y7%%gMNJP#0DjO4 zDW9$Hm0lOs?+1w|*t4>7Q1csrgkx%tAik7v_3GI2(JH*ukUs(}w0=IU z^XYJfZ%6!v!hXm6nYjUWQvYV=&Y-lH?TS|}CM7exTP5WFR2DM6q{Uz()bft_Rjod+ z)8B(h(Q1Unv2|zN&6Y%uHjDgnaY8MQ7jZnbWqcn3cQF}(zSWjln%I-&gY^jpm?f&c z*gruBl5Xr(!&ms>5aI_29CgNpdO}tYS?lgKm)z;VfuP;41g+iF4&L6_+;_Df!srDM zT8(`ezBT4jFx1QmN-0ySQt}AdYP4C|pqOMg#U32D^~{f)`m3SR_zS!)jA;m{*oy=~Vd zelMk)W1hug+?Q(E2kFcQ7uj7U!kZ3dz5^^+G`i`mKRxlX&`98f$h=rDK0= zgj*KzzWyY6@y>)Z(Xr6uXuH4}khmNyH3jBhVxvzQ)*Dm^dM?I7!)momL(CuaSuC~& z?(6oIX%^S>%Le`WdE!Jp|7w?5yM$hPH>DHty41(u` zy%Zbk=zQYVJhpL(G(N9fjn!9#v(ygoPST$6VF58IqBR%2*lWEoa+Qm2U^Q#nXP=4B+R5U2gPx%hRSt}tb0mbh zGjT%6APciO%oTm&j-~bO>U1rq_KR|qnBWVssmGDj@VSSi{i*q7qzH9f;@A8NGnm_` zm?UHA9geKvg1XReh;k?}C{R#S+Kc-*&A&f zW@UmC7_C{sf2{{CaSGiiv`bpU)zUl`*O5&VZa8r+zQyUp8#L?)#D4sbajbV5U)=k+ z^==gVvTV^TVY=K_T(vGAPK)BMIW?jOtVKbVoRy85ksR}9gWxT?o?KE{z4M1GS3nqm zY{~X{RaZ2x?w7&bpeS6fwnhd+k8{GEVo8y~z-`B+D4nx~<}H2RF7 zD0kO|p}IYTltLd`fM+}_^vyq%u~aSTz%d-kPhM7_k2<}w%s4BVxMe&q9xy#Fu;gUM zup+M`lUFFWE7Txlfl>%3QJuD1Uk_K7=)Fu?aGxX=wE_LN?v5u;P=rrx;ZU_2HA}%b zJZaI+hYU!_i?*jNksR|LCY(5N$m~q$jeTbPit>KiaxKuZ$QPC3-+gPD?ieaw;xj;`odoX^G40J@?@d<(n2 z5x^tc&rXd(r0II|uF#D|Jz}C_8DUJ`iqFM~5og)9C6t<+p(63Lpcaw};~nG|pL+~~ zf1w0d>_mhY^Ll>CiSHL@Pp-suZ0VC(b&~7+!{SFAX@e~lleg(NyCMzA z9>oBE_uh(-g|@KgR{LkYmR9=P3$Vfr=2Q!Axv~E|iQjtcBl~3|wOMI$cc0df*M!HnU6+_>evZoMr%P`^Z|8h&s3YSLg9)c>Iy;ml$ac=@XU-jD2w z_GB}|bAbooVRhG6-GWEZf>#RTHn+x7hU8D#Xmv}O29;a)Hj;Ha1M4qD;`l<-X#UE?j9adORd}vBlB> zvnRy4>6PAzLMBP6x%}|N@#G#56w$o27~A*w^r$jD;)$&h*CmxyDP0O^(S!Z0ubt9b zSr*B3y<^^>`UrW0lu})bk=!jCGUgB!eIcI_;L&!=9roUqBH?$evU9v!sp4==E3XV_ zPl0&Sgr*Oe#1?DgI#QDs`^W~S25xIjU_ITaJwyO0+~8OM|eTE@BHPb@V1$gOk? zTe4S@%S~LvwTG+!q4o(yyinSlRy}d~Bsqg=qgM`*4)Ny76bE-zgF~45q;c+Ane^bB z!GMI2cOAG(d3cMbylB2oj>>JEqhsKFQ^oD&d9i7vIY_8C$kkG{+LO=IK)I+ED7gyXmfl(^aT9X~D>vx>5{>%b$x1mMwP;(G;AH(?3Z_kjOTQ;MNo`Q$>X`fGMmX+SIcW* zgx+ay@m8}4tjy_l~4gd?V0cIJ{yq{4iE_SK! z@1qsvBG=oc5k>F?rMkU+;*m&1(Hq^rm&k3wFUJ*j;B5SvAoxT_VP41GjyuntvZ81U zY}bazMUFBVM{ESNU=_(L=YPQ{Oyt+Z0~oP~+cF@;tXMMX7(Thc-@y@8`iB$LGRRP& zbh*LryU1>kmKyYj1Ks ze`iPzT;5P~ZkYGXA%{uXpgN#k-)c` zD|kFSTI-%~LRgKnSHhzX+&T9JdhUjmYi-n9r-Py8wFY!gWkMM191IkvNP3Kb)u)-< zrRG4Hp_xCTrKr4Y-i6S+nVBFQ0aaP^9!)KXU zN(o{TCuSn{*PO8nH~%q7YRT4e!QC7O-M<9!D8`ya`!3QCP!lFhOZrg!^bw2REFaMo zXzmG0V%xn69JVT2yfN$@t2mXx zgdkU4(6Rj)jKXNz`7lWD3RH<_8%t}&%VmYkg?Ud9R|+ zWM_tHQI7%Ug|o8Ip^hJ#l8oJjC%ywGdkXVAHi`FKe)Con;FVR2In^nnW(oYKaloR+ z(yV%tRnV0DnZBN9Dt}VlY}z}wJZW*#I|pbHOP5e90$G1ir<;92*-)LvuQRhN-Ijo2 zg44|wkLfPWQ=PhcW}gm8(sf~yf(hU3ylO9FyLnI=5%;8nbI%^jKEo8ePb8zIlH z!X-E1wxR<1SD@PM_shpoh00X&R$6UPOGS?7@%%mc9lwJ-5*)pN5H2lOMRu?MzS%~l zyF&k+v!N7p&orv7y+HtuB+msLpi&97i%wURX6Gel#46*)|nF~P1h^q%yU;_u4 ziZ__kbo6{TgC=>YZB7r&|8kz5Ho?mGcX-zdrTZH3Bl7Uk&3&$3P+?}WiIUSKV_MF* zo0+-3QM?acZ(AJ%W-|E#>k+C(5{+4d>QfxADs|OL@m?q980OL=CC85lQ5ED(fgjSh z#`mu%^@u(2G>@%UZx9V>51Z=bFU`K+t_)jLDHl(;UgyepUyKz!U>GL~0fdi3>cTAg1_T#u=GQ7yEZtoU$4oD8?&flHE zU6ocGaLFwjz5;q;_yX@+op96?0dsy7ci(Te)KO`` zTudnK9)yA(@8mtdTrSj#T;71cs8kaq19~#wrJQDv^ZD&_ygo8F=g#+yP%g`c%d!n= z&04ybF1D7w8#Grsje)?sMe_u~lOjAgU5Rh%PA_|he0 zK&AC+Knt$Rr8ns1n)vzB#EI0^_HRX%N7R(D53}!;h#akZ&5E0@B9@N+!VY_gvqbJc*-AW`yEH;afjkxmMVs(33{i50-cN~@f3=rycV zJ=q|H%%D3!aL{jF5&!aEI{})HSStEn&qee#Y%Z6fJj4W(LG+=UIlKy=uCFSQ)rPZ0;;ru)c z>Qw6d+!ZD=zbM*14-ZQ2?03(+*p~`bEBwOD<{R$4wTSL0V2AE) zL4~Q~Eh^4{pqW>3sE0fy0xmAX<@!(*hhzaR%4}H82R_P7NgMU6$vv8X`OUT9f(Kc4 zPK3!e#UE#eE$hX-Wz}yFtAt&T0MeM)g zcq3(mnJfUCVjl6Jn#%!Db=KmJ9&^#b%V~j#FOfx8XLam$;Adv1HN-1AwnKsA)apK} z(b9|gXQw#INGb4oiLE#D@>}5-PB5p|%v4n_Ya&5{1RtWq^D(N27Yu5ZMNV36o&033fWh2 zQXWkivp^^c!*RVjD*YiUtKko>+8VsB<_M{={391CMOS=UDT${d_Pb7*?-iynbv+GQ z3D}k7H@pVLiS>{G7Nq-xsyi z)uxPW`KxB`idsevXEAL$&0xZf%rGy&gTFr)hlGes+)e8vTG(Ct9B?#l5e~_rJY)=* zcq%>5l)C9T(v%;*<+nz7s0D#Mzg~a$M2)Q_RP90T>HJv&m=P*DUeI$8>IYx5g9S5D zL{S`Kz_jG-e`$}oSK-S__c+)dz`QO>4$U7S8G)CR*$CXCTs1X{*Pc@wtO?Kne8RUI^`H(2DP zoSdMn83V7~*GD_kd0vUw#G+kQdZGg~1N2ZwoEd)U%pGZ3d?04Wp0(yHRArRAudFDg zaq}+Kfj^WH*py4hnK)gTfQL<(`9}Ania-%t>P(8A)DZV2ZzzQcSX$L0C;22LWu-j1 z90&56xV_+o+l9xX8y)YBb<}`1g%;rCqqg7voOoGjaUfdmxYmtMB|h7&G7cw4^P=mO zm4i5<7X;Xj*mesmT{eL$mdDJ2Rit7emcO+Mb8Z;7nxSE84;|Zn-rsvM*(ge|yCn^) zUGtpFw%Fd17Uh0&E26CRgyTEk^txTBDeIdQ!*R~0P^GI%^P~Gx zWY_~JIKJP^2kRV5D*8D;oQP72ddZ6t<28EJySkdRV|hH(!h6Zl!bh`O5;u1F9|GDZ^}I~ zkg>;pyyI3(z=UZ?%r^)t>Ni$Z^sQz2Ddq0K^`P<`Q61ldQ5b}YD6ck91}#?>LsrT= zNbFgg5Wr{k0&6JMWRCv=|2D@F8Y2i@Q5N#9-o3o9k*E5CJl~ht-U@Px4aYkx{SG>I zxctFbAqcMPRIJ%J#R*tE_@{BqXuvR^89F1Ge4VMZ4j(1|yB%(X&%2+v1tb-c=;v9T z$J>m*&IP@jYA9!&-=rB?w@ZmY&i*4=dKjkCoR&5#KCMj3UV8broa}$B)~amuz=(%# z{`k#rfB$)&(?~}x#yNjpP1iE~mpeaZYbXH@8h~T+k1k#2NG50PZu~vP`{l7x~Qrq5X|KCZC~BLkLAYDH){Bu z`yB~te}7BIg%kO{fDy>u@ZWBHnZexjJqWh(@1veNvhSX+%n-8f1QZHn?X4tfGN6$C ziiK;-<%wx+XvOfdx6)k^Rx^aOB@h45@17|G;eYSox1+bd(Ss?bD7E5s4?8$bI!a~= zq}`Cykfn7?hPL$0EORIIy}OZ8ohhi|3hcUh!n6�s6IP&IXR~q4*_jtySDX#$d(k zh;=Pssf6D?oEFmFRPxekizaxQkf{w*$kH)S+LX5a-v>ZjN(Dcl&URy5 z>_qtrC)ApV9kJBqPLXZE!UgRs%J(nTDx74mJ*3ygy=+B0w5z3KI_HtFw5-NVLy+u- znyC+`_&8b#L^o3A{Vh&Q-#KtjV-#&@SK0Fg7E@n7<%ODh#;FF&qd1jdc`e3;vZNg4 zB4_oab8w7< z?3F(ak6wZ&NS(JSUgu$jfsRT^Ym;2g5@};jAS2NO3OgPt zr@apBRjaHVJQ_ms3?pR=P-NrWQf2~r0qE`&>uIrsGI8WB>vjjE;2^Pyoo?$5sB6oE zfDBbsj?;aM2?Y=74Utld#8ikZsy0gZ--P7Ep?a~xPf8FkYD);>w_I9ehd-}tqMFB7 z4AWlKn=iddRh*G!AW^>TpxoQg;8%J^kv%T6sJzE%bouBbretv5JFlGqk@Vg^7q&h3 zyZq3T`xwJdLFW;vc2cU5Fy@XA0Inw03s?vnZ^7Z7$yls1;4?L?E!EJg5of5%jDRJi z+&#~gG`U_}lroLd_7W=Q$u$C5FA|9M2>x&CLg%*(Cb3A7CC=VJtDr6jq{YRu7hv$} z6|5&mT95GINKqcHY12ZvAyA>c4(HLN1sGp8HD7wfsqfU(OBAhOkC9rHc5=X=T7C!D zA&AAdVmF62D{~c*oRl8xyN&K{pEm_8o{IC&TTd898WFoSIPY0E{qP*IrJE^f&Y=$D zh?3ILc(I%)-SM9#0L5{@oSN{HT^DOBn1V+LDT$85$OPp@mzRf$bC>%%Or&iHxGLst zBku}lWre2@xhZ~cLLExpmBMk$wwPYx^K^(kI-eakgH1&BjS>eS!Q4edSh{JEe}78U zRiwWYVN6)ur?J$9RR|c}kmf^9K70r8I;$7^Eq1+8+XwP~%rfOa^C=v&8qPoDDIHf~N|R2GiSnOW} zEXQlh9@21f`3A5TwUQ&@sXpSu+d2PPxmAY-1GC^2D`1+os#KP1(T0=K)tpBj@+l;a zNL%sd^-V2)dX^6)6kT%hCO-h(o)$Mu+XWY ziJXm+EN1X1)m8t^Tq^C(_vQd0Xy?W^tTGg)%9%07%~gqJ)NX^M$=D1HgkqbLC))!% zHpp*^J1nKTfQ~?s2vi~@dzF7yjsZ)MIC~VQFz>(FC-3a{W-y3&h_?t4n**DWD0kTm zQT_#xgQZU1^q>OMylTu`qf)TCAl@dJ*Xp&V7w^%2*G`F^+kR7J!) z|3f^&>SqWs1LPX*G>#i^We5rDi_|{NQH*T?lA=+xq*OKh-_78cF}t_963`0@0k#Gr zWMRBe3rTX9glQz&Yhrz?W)cYP)m>>I??;Hbd0Y+1ed@e&Z`uNvHI4VH8r1n3QAxCV>A_dwubP@A~0*vgDYZ-NE~6vsKW)jQm(BW~3(v8VsHM7i6F`{nEWN z9N2%j&f9CnP?mJnk|$eV{Iw%a#a`#X3dsL6(s6JhM3Xg0en!mT!`_+9;kLo={@K_@ zp2Zx<{YPQ?FPpCYbHY-;J%e{n{}rM5BVnQttF$yH0)>+ZIk34ryy0&w$pm zYnkz}4+r()xP78OO1THMkyao3d~(}er@l3?rZf0K6E)Os`tI|K)=uJneRXr8?seb6 z*n*sRX|B?r|eHSDW}MW_$TR7W{SWQFmo5s>Zsc#!u&;liU1F_K^@k z`qvgkmFpjK2_HMN{{LLZ4*>e(@xR%^@a{$ivv!P75OKJqrYO5J_CeDmAnt7Oqcdmb zUCZX~^|QDoQEj3VZqG75Tm8UT4s^w)=oSOxI7xY$EM&QDIL>)~=Yg zi8F5cDP=tYcf7y4zTJ+tZ#H~bwB=)y7nf!_c(B?XYo02SQM`Ru^4LOR1f?857k^(b z_qA1tfu&K1+R?n0Vh_EWXPczTFIiG>qNYW(9+k!7@U*CSN$gew2>(^tQgTxV05tug3`m}TDl6l#wU}$ig zS7v7~jo?s9M&;_gcZgTnvt{;^aQx8wQVoyqJZ@x}c%27}Qp%3Tn;4Z@m$0V%#u4R? zrM+=qlzun(Y4Q%0P7nARVPuGMVg$Cn6{uyI4QiN8{W8=k+W3*)>#^+}Jga|f(%pRP z|4fGe#!^jaN-$%@_2RjOF>s$Tl%ruIjIz-G_23kf2m>r-m zguC>eOx-~(Fsjzg$H**YRYejtu9pdM`E$gghN*R-G4F_b6m}oGF9!c^p*nBH4K$d# zhZy!}jDF8>MK14w$V!;be>A)E<0LlcW*7TT9NZbv@)CkH!30C+6C=&@cje@XesBCL z57e{Y>|j*zV0#ctJ%OL>X=zp&bN}H=*tf)c^%ufz-Cg%JmfhQ=57S_~Xy0|Yxr-#W z3%9Y^!~`jN#a;J0=F(abbT>lSMQv^YcW+cd>sa8C@E5z+MqEnH6@j&Ypqs12d0HCh zma*HiE{u;-1B0(ImQlgXwe*dYa^#V$H|PIrm<7HQbvq>Icu*&T^Pd;?Z5)g%9}QQ} z%yk{IF%Cmmg#Wa7PA%+Y?iJFBQm1=$c#z-uu8{hmwwPLr5|D3E{3Z}M)9>Ni4ag$n zwrJ9=lFb7nV1p1z*i=KyK$>-}{tpjiLnsAz70KC!hc*nIkX=5JlT&cUc-}hF>5@y} z#I@Nck3Cs)<8+gc^L9yB)2P1HZ;;_yUd!tUCIL$Q@7|LVG`O5sy%}U+F=9U)$Q@T-i-b`lW&1T8)qk?KML_L zhI8jLm}dg+?7};!J7z7YC*&S1Wt2OOI(M`rE+6dMY6de?i|eH4&X??j(95FErP8SZ z(S8pX8z>WcA(BT~Vh44+-i5KVieKfLN9u7%bFS+%bF%Vt>a~y<7GB8hz~}o9 zHb3Sw^3odS2?h6Dqp-m|&b{LX^gX1LtqTQmGt9yMQAEAs{a~z^wP5em?moCXXXlOc zy08bb*6cM3W64PiQhTO*4QIfFp8bg~N&hTzKGD-U?@8Ye4 zs=3rZ*jAn{N2;?uf|Fx5-wb(cr}dFXR0{hq^!sWa{`5hK3;v_7`JZf+`x^|&E>y|` zBiO>b(V!q=+MgI+S^@;P4GuDjvU}13siRFwRB)vIho4lRt{ARJzx+6c=LzE-yx3`k z#m}XM07EZ6F~YhC7sd-Cm*Yh#a6R-YjT@;VdoW03{H0=FY|mhB&L!L_il*M{@0)S! z%4(j7u6?LZ89Z0_yyo*~H_H)sR?PU)58wZwqH_Ldv~oede-d0{;ZIMoo3>p@v>^r2 zneo=1>Q3)V-SSHc4sR^&2^i2HtOK8{Sb$r# z@=FjRD+@C7XJzP^$u+0qC)zJRyL6=V(_8+Dh(PzBUvWC^{=*vF? z%lXU~H}H)a+#{p^VO|wI&D1jv5q#sr)93&B^y3dBIJA-38R1VQL-9;5x{H?rhQD3P zF>Q>VM1KeBQzE{oD(*)vQL(p<4o;}YQOJJAjEL8MpQKqu<B{z$? zaLQXu;>2`;!~)pdcD8#MM zM<_?Dyu*e!^UR)$+RBSfLG9D}q&;8HB1(yv!D(?sVCQsP4VaS@XKq!3!^@zdwGU&B z%KQ6R%?8;qvMKT5Ju7~!8lAqli4!vP!fin?d}&3nZw?Ipb|pho$3icnH|A?&inlne zfM0m@OmITmnMd3Re+=aUk!5)`zFl@G|2q4NL)dv_SZJBcQs;qSu$6REJ{ullm4gZh zMP(~$GJ0&huuNcb=z5xfA6&*!?mV9D;C1q}<2wQ6 z9`6-MLQsEc5H41gHvFRmU6n2UaTJieJ0SNl@)ump{l3WwRg&L?8|y*8yWU{ zEbDn7FD~$>)8nn%-INM2bZdWrJTh8@XfM_mxl^AD6qzIEtOe^8ix*8o>6yDOEnj<@ zcJCcFiqelE85TlwB_?3UwLblbV5Dt7=D{Q~va;`|BbIW0GGz!-65R}l6qHgq}5ha9x_1H3Uhm<#VlDo$4LDoZWSX)0EiGF(;# z_ZEh(TVo#VQLG=hS}0tg{ShpEM}5iKOh!eUk4Ih)PzITzwL#s)$-x@hs)V5@iS6>} z674+5Ik=dLa=WW-1x_TmJp|;n#f2~B@rrJVejDd&VOiZmAl z_BUYY)wJP3yh2$ur=1=v3vQWoS35gkDh}eLB53=X(dQVLd;Ij(kVww|qU}4wn#$UC zo$6RdMi>hsFlqpmHh>gq84D=V1f-WJ-OvOCq=Y!5qcSuB=_P|85L%>!PGX@5p(rhq z08v5+5JDz_1k%q2e4TmU>zs34-*>)~UnrZMwbx$zSO%sj-hXN>nEFLe&tX018bi}jO8f6lGb9vAaa8u4qxnh!XVxD0j_ zN1Z+5HSolaePf2n?q3pbuvLARX;sq`!6;INha+`80Rr}1_IubKKR!ReQQ$XQi~Z-_ z7)-9=HDRgTEbyQ=&k!mop2Y_fb5owVs5wGu?kLC^vzXd?vpuaUH_ENQggu^O4ZgTVQ#gd*$IqrK@jU(UlYM>eg|~k<7Mr{&aBDMk zXa6Sc&u6)4)ef+PAIwz`MapVDe-;>ZqwJ|XL1uo<5o72@qaH=%+!m)0jVHxFP(%C$PQ?@$U%lH+ea_S4z`~;ZVz}_5ve#gBIqgHO zJPp2xLdL!_6BbH@rG*=w7iOHsGT7SA@v|E_%oB8Fl7EVPS|GepyyqiR3XAEFWUf9V zG0o7VHH3SG@}xk}zrTv~1J$}ZZWLn!Ch-dqg#?BHCxKT!B$1{SzwZ!M)YXev>yFQT zqJV3Ui!V57+PF1N>#kXk+PKye*!T@G7gOckuN zN$1F~A2S!^z>6dpVtx%WwDG<96sc?PTet~!ksJiUIXw<9d*V_{N|+$6J(E2e(>=eA zouNKFXe4fPBN_H!Fikx*N$TZasduqYbVb#Sd&d!u*AouWNJYXEbefQB_{-)hxRWqW zuhj60KsvbkaesODW7`LlokgvG(HqA3-$A~Edh-b;76E&gMf_~3o7jQuoaNP*@AN~_ zl|x7=b#m8_^Rr4pZ)rM_nU+g)*z2Wyr7O+F7}!GzD@&e7q*BnCT|Wx3gq;`a1wA{@ zc?sselM@e+rLq@DX++&Iu8bV`8wTqfPhBlWKXLm!wtpEOnuC~G3z~aunT4l(g4>Y5YDWym1acV{Fr3y8dK{$YyvGD3`=Lr zuLz8DYQ2_u@^obg)+}F(;9ZF49yrL2!|92fz53QY%DlOCWUAbr&O)L6Or?dhN3dh+ zitv;VkB~DC-sJ{9&z9%&&t0j5n|*5*_GT^90^^^R5jx<-mzaP*X5zRIhCxE4SXRgQ zzT63Py$^{W7RFQe6MWmvQ}TH%$_V$yR>R==PI6UPS1^u_t>!&583tSXMRMcyL_mL` ze>y?*?II$)CH~?Yj89OA=y)@%PBb`ae4Ky@uSNi&ShemnyrnYh^0Z2-_~hNUzrLH! zUhO`9d7s7dtJ3e=#D#Jk76fyIxW@hP$Rno|R%BIUwLHd3FK8S^21ljFTq*2OdZ_#s ze1lb7Lp#F%)9NI_<>;l=1`Aiz?l&sfBT~tUfn^%t7O0ERAfE3+k-Z}-?MaQ|z7Xe7CS%0!n6Rm7xtNx8*wrV zyg8VZEMx}Au&|==w$zC!j1UgdG#>Dp(#JHD504lphY!yL77S8J@P31$*#(d zClcPn4|1VOO_=Aolet#hdN@C(dEy?Y8e@otpTcq=3#Fpu2W=6L_f!cY-U<(fj>D19 ziRQ9}8SN1tPg|eoJ3w12CeqsEH;z#`CCcUS-v)Lju2hAE-)tA)JEsP}?*wO@$!g2x zoF%Ka3ub>?5~A4Bp1ok|M%P9D`ccB>Gjas%5E!Sxx5oDgvTGw>XAH1C+rZ*L$oLg# zV{7_5ahUt<=ILA>9-ojbuRI1uviKelI|@+1K?RSz`4@zY?@|#P?D6R#m4GITFk3dT_f7DP7I>MV!UTDFWYr3; zQj=`B`^5@sn0w%mD9&6~T)-RWSLgeS%To}}9&&r6Pf)&W9st4}g>z5YMQq^)e#Mqw z;=e2|U0zzfx`gV5)9*Y=@{&6OKJFmC0qk?)JGbGBO$Y{Fwlm8uNAU3F zrElA&9T@G=VNW2}rYP>w9d;@1K*Bg^`v^By!h)vc?P1I7Qk99jukG8RtcmT_zXHaWPq0XT_#D) zdpxl&SRRYN=~u$0RQ>)2911JKe+a(w=xkHJO|O?=0k!?O6>g4WG~nSTd#h^MjmqGtWe%KehA}34s)Fx3bq?78Rk+#Ak8$#BluJ&As+(1 z57KKB?A(uYi>;)Wg8vA(bPN!JGQGNKB*uorzCT4&2EfuWxYa&O;7?}cx3R`}-TwQcx9b4H4KQO!Y zi(1sdkQw-{PA9ck{vSY(G+#aWCR%(1{sKO@^T7*hHfe+EC&X6BKV!tYVN>Wo)*`Y+ ztKaWzm&B(kr>x2!nl=%NqIM(1FyPEipAr54uCP3DTEpziEBWO#R~d~csTJt@=%SQD&1p#2 zhZ~|q>692a2R-)8%agqv=wc-Lg+o`|K^--%zbg4`)RddX@e6{>NhSELI>( zG&PcvS$HFX(PSbC^J!)K4^-|&gQNIA<$go(i@mgVxG!GPC#4Nm9HFv(MYld4)u_|2 z0^6|*v~>9~<0@relD) z4XX4yU#l4`k>&-0JvNL#5e#|HJiL9@yXGJKH}&mmh3h`w(xOGo(^_8a>VgBOwbXn} zZ{|u6Glva=6m&Ao8oukK-*yRBr&tv5yqDp@6C_4EJL&!XJD&C)S4Mue@hBBK6A=%u z%SJ6umU%YP&BLkUK$mA`XI#anQ`{{Eo>un%A3W*ICU7%dF$hHh<+4k4Q&EHt6q&t6 zUa!@Tf|J(c81I78)%rLrYT5io>!Yxg z)W-1lU6p0S=*V0HZF)pCK8EjAgzcSyL#Ao+2H>#VQvL0){6ZlVNP)GQs#dM5t)_G* z!nF&3Y*-ku=!+K4V{@2}1J7ND*-gGZjvh~Mcx2HOvjd~;!*qc%>EdAFWPy}$we*5# z7ifG6c6oZb+M!1j&|t>KlqX*-w4BPFOK9-0VpT6m=tAiMjS%(lfcMmmh24i}x=(dH zyafY=>^vU^$OcV{)Eo?Gese?~$kyH6$<>>J693K9) z5qL!C`d7*}^`%xZdU=!EuX94ygg6gBue@k_fDgKKqdambz|3Pza_1{S+uB95^f%S* z%3@2Tq$9tB9E8XSZ2RTT};<7B1wsXeC&l zB06W8@J_ugn+PfLjrbCAiy)kV@=6}g3Vo++sfR(P@$7(2qxUiYM0qeP>n@pY^@ zfli-Ac?zGkvjTgtDr99t;$PSJCmA4OmC}q93WkeW6^-SdEEgfqhB~EhY)kQ50cx20Qjp|}*UK?#J*l}0#t>TA zT4=^xaIl!mQ2@+BpNW|X1rTX|HlDc(AX5s2a+6`kxh46t;Cf#34|0&LrSE2V$+9|_ zlIp6eTQYDBeFH5iMG$pHXz)k+uJI-qd3!?-n7ugu(i@2S%6~`wA*W=J2Y^K`6+&A< zD`j@mmx{l(xS}=b)yFRy(#!3FPJ&^e-b;;w4k7iZ{7t{-5>+};`9Y^>*285nB$N7~ zU5KDAbu4Ta1Kmg`L#H}(;8rj)yB>b))@uJjQAMKJEY zv~8Xa!mYgLh0kWVYbZcYR_{-=uX8Ix z65PtXfTYr;sB==FJ#PB+mhmJOTv&yU4wBjxka0hvIn!Us>NqIcCR0gkgJZUPKM4!c z1~Ho;y|5zhKR_my&OYaRnqg3}t>1bozrZZL`_!L=hw)V#ttz-6@B3x~LVeJfehUU} z_F^S_->tYa85Rvh10k7{d}>tMn$OAXt7O3z<;?~tXbyh zHX+?2DqbyltSh3!KWyczA2bgGj6~X3FYba`C;AT_Ctem(hZMJyTq@A!a2FJnRTZVE z__PN&U0{gsy{*mdR`9>2r=K$4|APYOe{Ujs1fbxjgU5W)*AfBN$ia13pXkXAEc4X| zm@7gPP|1GU;(l&q`c(&K&1}+CZy6z*S{y?5UHY~H;uG_f|9AFo68djKnr(6u;P~ig zd;v)r6z%<)l}h{wY{inBM2`bN^nBj4BY~R^t-Fd#hQX_JaJhNOf9ZW12|(`viBrbO zLhVcHVilQZ5!REMghhtouLO~r<5r7in)DR$flB;w5rM&w81uUzf{%v^u%D#P@}?%gm`jgX?z|XY_i&S&3$8v5tCV$?j242H1-7Qj zu1cd}J)~>4G?tBGWjP<%!h*J9D;DM%Ojlb)K zaKAHGxT`KBlM{}F>%M9_xXXd^=51?7@sT(@G(BxM9oV%mrCU?X}tZ5bpUNuab}sz{7Im z%DDCY^!n}fnEeJARX)XHaBi~FsteH_^(gt zNCSQU?3z~WI0zld?n2C53hF5rwR%LR{Wzn(Rg^3(DZVM)DoQ~57tGL8bSXf*{mawZ zE8mu7DJ^1T{}h>?VV>lhJ;}Y|#!)3DHE{GVC_1zke0mHIjRRvr>)|hb@g2}~3jRXd z!4rMi?LfoH!C_Vacf2S4hf&7a+!6oD_Ck*tSP!(O!{xW?3P;YKN4Ij_-gQ+f?mBKg`zF8O$WL{riI(L) zwpTcG5%VWIQ6mq{1NI;L=4FDs{K%Zmj+rjUyUju?1BG3uQja`>29o;;#xI2t@flwm z62TrHX2H9!XBSzXJ`M{!dM%zQm_#bB zuq;IaTr)@$>TB+~r5`~orXB1HX`QOKbjRsjUe53~03tsFVX3Hi&OwE}ZrwRuM_V9xD5K%#OYc;+@5Beq zBU|BI&zQ^J=t&}+OLpIKL*20>@BcYs|D*odtVV)$p$#sT-JWF!tAb(+=~q;JwX~}M z`N&|zx1X^O0#JhK;%<3HwBE#mZ+(iR|E8+#wXAMS{nANg+?VL&clXl~TVjVTNy(?M z{Nk;ZQXOvskQFEo^M(HrtKTvh+maBk&#`^abs&oSE*gT-F)5V>CnBmGa3<)$IyYoZ zgK)FMYU^`BW^1ZG{p){7bb9M1K)U}Esd+K3@gIfMOa!PYKhxPyXLK_Q_bW6$HmA6_ zygVQ!rLb-l$-N!qAm1I+Mk3`**frN=*bvA1VqC^?v9I%7W?n}hg>+F;;0+$VUq$Su zuIE7M`2%c&0PUL2Atj;ttCK;-p*>509;ONCok3Kxzgg;;<0=J>c`Z6w66h09BgB&a z{ho5U)fne@VqUna{sW32XM&KfMjD?n_7k_)$2reTU4n{NE0Vv-;TY6t9p$&c2`ci;$ zY*i1_doVzJ>W#EGtYDv6bP+f6TW&s+|?VtncfTYy7%DirZwpf_1Kqr`JH9!`O8{25oMNcQZEi zq><0EaF%@GuO+8$ulh?K3itE1T`h|?3K?*kRL=|=+?#>K+}s_6nv`*EkFP5#R45IZ zD3~mhGAp>9lk6~X8G12@Z_16ybp^L~P7UPdYWwo{CEU9#Zn4!(+Btod=lf*wR%$qF zV`WO(Y((tt7jl+pKG`N=dDh1@U6@aRR|5o{yqBMOtI#949J-e+4}ilEy@d^fQn{Ul zq?eq&WwfX8shAy^e)MKm+EKA^D8vqKSE_bty#!?M-Y3FG)N<%_(q&;-kE6GMK$gWC zEAq;txZJro|Kwwf*q(fJUCb@v18K;;0=S~H8(4nW{U_#oP>{dui3>a}mi(a%ic*uh z_PV;bxWu7)?HTH~Tzb2vc>m@MwR{bT&NA1tmC@C5Up>E;zu&i3r(05ezO1Q(s-g92 zDe8)*&9f1e-avKT3oq&Gx=r&vcxT5q94S~sAc@eI9QUv*(Pri_|2@pn;`pDTQmXth zUAnJgfy!H2OHfMUda8Y+mYY8`+5*}GUEUZfPtL!&h`1Rq&KK1T`kzies+}gXWPqo! zJ4s19fd-EH>yMaHGGYe=S$&@owuG*g(CyhOXhW%9>VMBrhQSuX<8ho(^jM!(ZFSPB z?iltgJ24qGwxKO#99{JlmvczXg19!fvlvR%A7kZbpBDg~*&%nCKA;phPms~1J9KZg zjQH3vm_jWGsqs8&(q#PvG39ZGquyKD$HTf?K@-dGu zik*-$_-YyA-D{rOcj8Ln{W16xZXU@f5)3B2L@E&at%V?*t?FyW1_nH|&F&S>ATpee zUKe!r!i$HQhk)gQan?C{mFOOU=w-DzDnUQb`& znKSs*5XjHEHFm=Izj~fG5*Jx(-#0OOR1|M(DKTP?7`b_BPlK~MU z(IHzaXyH}iE3z_7bdirmqQ$@BQq#N&bDgHweTI48YhxsXhR%xjnOE;SIr6QvR9Mji zmlm+x{&y@pgylzJbFIOz0aum|FMfZ5x(T!0wY%NeRhe7dmV=~}xiw8!P-ZXsRp-e- zU=2Z#tl{=>d}=VHGJe`AOFOv8+nL>~afWN}#7K5dioG}UgV5ejIePTa<9A>O-n=$> zUhhRvN$ajiNf45J!VEZY?!q|FG3q|(qznDgTF7m2u23cbo?e@8)^_;|TWc*joDbm# za{1}kPrz2J56{K7()|&!9*cCB1XL3F1ZDj!wv!zaO!CjLUJ&#n5yVS_0Lu># zBhlDP%sbqQ^D%5pNxgjZM0jLr=Hx2RM7 zmgz9k)TkbfkpEMZEcZ1iV70Af*Wjdwq;aHhmdXpueWp3C>&1bsN5`E7r8x!#l*Cj0 zg7?uiThmDDnKDZ~P5Nz9B!K_FCK4Sk&7x}b9d54~g`e%c#Jd#yfX?^JNN9aI2>v?V zzmB*BGoMACHYkUa`Kjw6$Hqh|VHY5oN@fpYCRrW`X2ub5mUOR9-`MZr7K!gu3#Z78 z5X7j?WXqI8Qv;=+h$N3v1(CSg!P#mLzy$|8MK3Afb@w{n5zMc_W5mLK##8Np(E=Gt ze9&G8EO!Sv;Lp`z&@CBp-CRLSMCGfL2#A<=i>M@&GMISBLN9Qn`G;8YGRyV8&PbuF zZK`kU*0Vs|0*qg1T%J76~&&?kg2sUFeJauBrrzXcf(J(LU zfmW5nj|>8wd^1B4DKFo99}~-QLM}O~y^HLctlT{7tu%ntxtsWBE@&=-d*KxO$mW0E z{q_IE^!(pTY5z@{tKB9a=(stk1$3sk;v9Lx$!a+aoAY%8o?; z^ttusJRrqGOAlV8{ha|BByaAT2XV=8=i$w90iV0Yg%>^TfjwesBb)sRN(U-mpsAv{ z1TabYJNFWFEj{|Dvhg1X^|(vOK<|!iFn6Hmo$xJhq{YUkTo z_EE6rO-ANcbke_Pr9f&`LjbxXbnm*P}ajSmBgX%Kkk}DaxeDGT^!$si*W%o#y#n();*#GS-6?)`?dpg)!~vQHbsNO zRiYpwIxEh4dBKmCL1B$IBrz#P{pzFP40_pjruqpUW%!GOf-_tbPU9kZXmZ+|$^;;=} zY7$%7v^*t!A*{M!(!P_R)R3{pi$R!hV@P4Et{A^RD*8!Ew#zwvSFHLtny&{{tsQG4 zwF>nygCgyONel4JL-_a118Ec!A-gV3`UWNJY~)PvcUO|I zm&MX)tLhA1IstwxE{@C*LLPTP>4z`!bgM*#DTpx>4+AgdNTKEuHti>J{gptDzL@B3 zINp@WvZJ1RD&)kaH|6Fg))y^a=yd0X*LB9DqJ{fm#@H|v#K!>E2@fu%OOxBr7Oj_p z^BXK>`&d%M>^#1@=yfpn{1f~})&Qq)84lXSNoxND0y!yWQyy=^thn24s|qA?K{Wsi zQ=Ok#XmJL4#*dmKW7(Q}3a_EHWa!f$Sqzhn)B3SxR~4zcn-*eb@GS~*s;Lu%gSKlY zJP_pHZh!@uUhPCsM|%cqpMYzW3}V>u+}n>K)H8kG3&S$FFYVZ33)7}HWMJ4_+hzGm#>hJPP3`z+>yP@U0R zs}4lhVwT;2C}^Z6&07j7vYY_7b*_!ayLP?}B>4yqQj=COPe_3m9+G7hDLVaq8*zQD z#%5GWG~ zo8Pg!ET4)TmV2Iu%pPljeK36<(I7qBzAJ(c$;zhJUg|X7**rXrok10*xyefYJ6_jHV@@2T5@j9w)j(P;zw0Sj6@nPG%2(6#N=MNcJVV^Y6-PK@b+ z)Qhhai`JXK*D!u!7#dJG<9kOi*-NBrLNd`Dvgl<~6aS`U$CB_E+-Eu}<-PsBR?LA? z2!Y)5gkAtY@9RMnKI0AhuQ@A32>V)$OH-_mMF`WIbbGkbd&XVYQT*%;SNb>&tqZHJ! z{_nlL9;6Bnn3%n&9;D4Gj=1}-+?<=AsFi8o1^v0NHq2l>I?8$OL1h~p? z?Ny9042!NHo#a#^4w5h}+(v%Z#dFQX*T-#aGpF0QAtGj8LhBbbHKAAe1(=L`5V_dN zX8I}tR_pA+z@H3v!?Ebh%1*~82f�_i0__#Q0{|* z-K1ZcDpRC9#)tHWDC+Y)NGgk7qeFQ;B1@Sm*)9Sj1X3sAm)l{(sadOv6(+dLvr?@4 zRKoe=$M8E~hWnPAJV2qrG`HVnsc0I-_z#itW%-SvL&`3ggVR7dejWpV?=x6$%Wp1~ z8w}gb>W<>K(#w_tQ0NcsHpWNHW^UJHV-jjx{ZZ<7Cz3{rQjA1akpjp!>2V#^lQnPH zRczYwp`KbQm$a>1$d*p9cRTE>GvmB}9^Zyrw>}5!dH03xM;+&A8?n)im6k=r{L#>5 zW>h~}T-h3!&@{)UJ!-Ju{O%7=fTYW++xdi9^gEAFEW)w>9zF4&ybVJ?pK^ZCS4%39 zV!GMW{&&i_2^^UNU8z{GYxP*9D<z9t*1r^N`r? zp5Ekiq;i4&@%&7~gVzB(ksb3nx24|!8i_OmBE(7KnJ#Ld5luZ9z?x3nyYw$)ujO!x zfft$=4G=iLyD)qICAe_gu~iPuItl_l4qcwE9(x)GKbE@V=V2GwPar8k+K`8xjQ;=h z|0m}-0ktU5n532PyGw0TO+*u*+{%eK2>s}6eDTK#XiQ|;P@u&;h5zt0j^;i@d7f`= zfwjU@WXhqsj#5!ab8?nSqPg_Q0CbV{xOZ5Y;;K8h);#rQXZ1oxLS77h@r1jmwi=-l zGNEC=Mc)YM+Z@Z`o~@3k;;ej4=eFrARAGb;E=JQHTdOL65(=u*$*p4Fe#)b|fov{% zj;GHp^(i^X9;(6IbGH5}!E7;=C7iB}bMH8MzFy$lxfZ|>-D9Ja-cUBuKfO}W>qux1 z)TpT{W=pyU?6`hF6FJ3K9P{Tb`@Tlgu%4lo0t+@jvd8s=O-W?3bQBFZ(r9`(T}z9W z=QGxn4I9j?`L!^JI?fB*ViYbCvN|wF*&w`_*EMhBJACFvjO#G zE;~fgWqW-*hy-3$VwR`o0EpD6meorUmH4l^iw4s3v-(;J(@Xu0QngM=I#cq~7bcZ% zfsoA*MIw&nU>jhh-KTE$9o>7{or}^z5MbFL8$H!#2~b+S--K@vwrc4(D2*C?oQ@cX zfYAePn)h~9a?!l{yDb&sP9k$%Bgxu33z9w&@X)NMbihhJ6zo|V1GtbBrn zy-Yr(T4XVvCjZTK_;}kvE6(SETpziVp2eKZH1R|_4Fi~u1L>H-k0cMtM4pk7-4RP; zdL;1LVCkxtBAh?=U5R+MRLJ)Bfc5yd!Ds0>f4G%+ClOMaC9mgdf01)TbmvL!wbE}p zyZS>0KV+^}jh}O=OyzxwF2C$N@mYk>i_9B#($;b=q-frY=m2}zgXWhOb7HUOQ3~SyFHT{Xog{|Z^Xh*wndlDe$V>C-T))hE6Iyo(W*VdJVH@@#=s zZW0=&@UGmk!uDcWQB!=o=L0Vgd@TLFhoo~PiS-aMG0%>dHGAJG{9tT-rd!qEJ^UR< z;w{|FBn)Jom|ARjI?;!yGK!YQ|00E7)W-4Q0=o(ehHU;&&hu=FV9q;Y6 z3hXO@B5&I|W!LDIbqb^ApLQ`mKyxtreeLJHqvhz3(%-fypZ7$!pZ_5uviL{8sP7oi zW+~De4-8o${9Q7_SDKfhG;d<7@-93RnERbtEl6N8 zF~{wj5Rn$U_f_P+A7v~P%gmmRx)&{x9HMKy4y%*i5_2H;@OuW@+EOcn3@Nft4EKT* z2SXbU95Dc1fQEBA4cQ&yIi7uH-x$_+nfEEn+wsq3d>q~3cPBdil5day3B;V@>PSN8 zZ)Sg@_Yjoo)*?CFyx?4*V1LOPOv3rjDSnG{Mt3%$P{hjiTCX6}8quWtj0^T17D+*} zl3!>jpOHkqi#YKmaZwQlF8m)&5nZ=fIb~ikK!zEDMF##A3jpd z+0ImeT{>JR5 zXOi$NK=}z)t~)})QdA+z@e!C-PBicqXInJx2Ir+vAZ+5EtoqTmrMtHV9=u`1{AZWb`16O<1$WZ0I{QP*3K)MZt9nx0JPF3EbVEm?cJ5H z%#3mT5#4!bG@nw(x*((uO60-Xg?YW}RU!;Hj#5iaIcJmnnn%2uzI=P#)wBWDy$Vb8 z5y5m{*})h6La^K8cGK93<3A5sG;r2vE}nf29rI7IrWn%^q2M1;eMk8s6y)F|`sl2& z$6AyroovryRtgd;cu9j_`6hFGdCu zuAy}2Beb}L?cH}%k+m5>9s=gUfa3S_Kw3_I+5lbwlc$+6ZoKnM^pE_f z8QBwBpFS?x&spq0IXFHSSUEv4uPZ7-HZ%a{0sXo|lflOC_+UG`W?Na=nFl~Gy&UVyg1OF8JQUB;ptcC_2Y(h~e5OoM%U&Z=LX4;^vB5Ni^JG|HgQ z(*<(O#>DEW6nZ?22vOuk5Pm-aOCyFHGRbCwUHEkFN>W3(_N*v?YOeZ6z|7BhMB<=_ z7c}$>gSo@_ojt=qL|YX|$dWvPcJ_S$@PD@|=#ym6GS^}{7>6HZ|FQ0vpXpNI=&60( z`0Pq{SnF9@tXJeM8H;*n(sR87PS#3LO{CJFy<^S7dZG8q7^!23v3Ie3vCR#@!{<$5 zYsrurLm|PHG#~RUxeIn3W{nWSnb z`EwIunnppciR)zf8>x$@3$VQtQG&He(R5vazuLrK-`|i2m(yjbo}<} zU_0{FDKu{U#M7yZtyL|!futUu`;)@DV-yE1r2t(|o)D=O4n0oM4qm33{MJAKe4|w| z)|Zp>+tsr>>z>ny!ZAGSF=+ZW1{-{e`c#)M6UNJG zb-BLc5mY2%uxn|kFjU!$B@Au$BGqIYc{ppO`#^kJgU9l*cHz{GE7NU_)_8vid{JiF z!7imHJkZq6K`7}-ZV%x~6P0@5)k4z}F?;wSXy%#R4C@5B>WDcD6G$6FAAzLN-CqhN zE-oz@1ow%CtKs=GwJJc`nXQa}G+{hTwPx`E3B%GphPZ3Pd>jQ-XC20SLq(eL^AX&R*j~VFmXCJW?#bikyeeHac6b=l(>??BppZ>O;>GPb1?Q^ zFh)R=`Kt3pbrtS8@v>)i-u_diaa2eAANgN&g8g94Df2xw@#S+jFW3~dhNidS4?XNl zF8R?T%Xti)D=-M=uP)@{So3}PYXb_x8zFD5*dkma`XgKnd!Kc4qIO1#?TwD`5!U5w z8Iwf_Y}HAyOoCKd?yB>?70~o}8T;;`MmPNZN&Lh;)07gF{5{B;60W_HuzCue9`iu`0YJXqK{Cs0O3u=Mt~ z%TGS6F`wW{wPFDDjQm!l-n1tbdrdf0BI-4SOM|0riM^>I?{;Ds;0tI8V7~s625-5; z0Q#%sbzO75U>v6M+wct|!;ZN!ER)g^;q|mHdt*t_jWjjpYq)@@^2sWnIv<)LWk<~R ze*$1B7MfR1wVx23yh(nF<6qlj8>6e1xO1xkjU&hhK&YOPxZ(V{t1G>!+T*4C@ zhJ<HNN_Kd-%FKIJ@_m96$0+-IKv8@!jhw5%IHjUrX(&hg;usfgPNs;eG*MA^py4 zcAUM4KcmOf6Mx!3yldO_mVo*{-+*dv%)B$g~-8&+#VP;p7xMSiw zRCThFBb2|v{2nHju7v@YcXxOz3F=$5E0nIl_*FZE{+9aX`x=UGnc%nJ;J`ApkETI+ zgt}BmXqt&1+K1&hH?29V>)Rd1CyddnJ&G#QU)Kj^=f8Q8>>P0-`b)ZXS`$NF`=?Z` zx4omIidfGFw6PjUgK?Y06eVnQN!8e%@e8DUEF?V<6E5XfKP4o)tG0Q}m)Y&sAfLD@ z{%##?oC8{OzW(6p$&8j2R}D0s{fkyZD)gI!v$_)>c_uz7jC(lst=nJBF`ry1(V26s zlaTf+W@V6ZCsU&7PFbub2?qAL-F$S0k#C-CmeU{#n=K7V>&lr}(jsxC4of|C6dq-Y zB+QeyABehD^-F=VJ=P!JGQFNP4eMh@hI-Z!9UL|m1I*6{=n*C0#j+zkD6aX2WYx-v zFH+bicVyhx(wbQNK1ryp!S!5;gJ-L+aU9>wNyxvEzobdbiCD8tnjT6ZBxi|6Rz#r* zTCKZIMt#T%YD&v5XGPc#YwmXrtfG~LEKgDFW!7-B)E>^Uuu+FvS9CeYBQzs)jZ=PE zbLbQ#cuA`{urW%W&BH-I#F zTj$x6&RvTUJX^w-i=xTYJ5X7BX>6oHE_8qJ=Ku{`OuZy8@j-R z`W{&ff6};Z2&L!a2&!{|DoUdW0l=v@KlfT(K6l9;-tqazh5sb|w+{ZNC+L6FxNHib z=g;xc0bJG8QSZ52BGdIiQWwmOI?ETb%3dkh3N}ikP&(OJ*FCT*=(X0;AcH`An z_W234qErgV_WA&9l?nDmZ~2+6v84abDtC}U4*A2@swJG>s{Xku_a-NuqL=!AW+K`=2%t`%(^P@N*16oead{pZrejZIQLaze zZR;pVnIT1}X`rWA3i-M;N_IXYq4H4OsAa)2QLm5|)vvHRE4*o1URzEjf$Oc;-@oVO z0cLdQNT^2uV(poGlY?D*e2~n;BxRw9Dh;HXbe->(EaUG=oz1 zhtCiwk{1xK6NCYEs{ue8b42TuE+*0ITI#ByL>yoDot}TM9@xEiMy#b`QKiwD#)yJb)v4pd6RA~>Uuwf&_c>I<2-a8R@rifK&oT6iq}Jv7Ts9_{cKeEg&w^BrU%(3;-0&SxYKBXj^=>pFF=F9;cxUp!hSgaRk#{N zu^+LsT)hJ=T*B{^aA|#{tD~b-5I?+fL-pPu_ik1sf@OAG>9+9s<>Nu{8=CAWhxav! z7jIhT8U|(CKQ`9CBL4*9M%i$(?d{7U*Az3D*%w7)@uM?l^({6-C3uF`d&XoAxP%)X0Y$OSGcI^+= z>s6#Wu!R>E7(dyS!^693t!v0+Zi+lvj&|?Nx*x_|BG$-qoVkE!)DObi>LhAO!dCow z1YjtI6hiFF|Kf&Y@YykQ^`*Ol%*wQy2~ z`eWZ|=wCX%XRiEK<2K9k*zo=(lh|rwaMj?f4F@+RUHod|QooKC+1tqPr$*y5u^`J* z@KQvE)Ki#bJEVT_MZN(&aGx#L(_U>A{_`B0QA~iGCM1ma#Ub=KNUPdkSOXlp>Li;S zFC!A)bemxdf3|GI@*J&OMN3FMf?0K1(jK$B3LcHfC|gWePo)0tFJc;=F{}x|j>M z+xyvxoJIQFk-03Jacq328Ye@;_{uw(RXJ)%Se%|PWCF=KfV5U9fnS_mwQ+pah;>pU zMhXP9cVJTn6TJ7V4&dV+2p?uNx6*a-=NSpPEtremvIt-95VsISHn7irv!OxE#!cO7 ze|c2C`Mj+M_dyWCeWl$vzw}vb%4L50-e3ISS<6xIl=74i-Ui?c6O_8Eb4ZQGlQoX- zrdFvDQ_Ocwi{@`Us)M;Cx(LZ+rRaF?mK;384as~*7Tg}|slLSLWpKF}r&`2g+)=Vf zJwlKyM=t*`2FcRKA{5>jtI^i|N+RPZE^4TqM@ebqY&@oAjI9oX?Lmj!T~%IR)mr5z z>mdM0HGUe)3=ri59tV#6-fvX0pjxj6?9~_VME!NSH^wx9e{PJ2DlR)ggsl8_$XGSY zBA1qE6{LI$0y!Em@BvSuwXJyjbf$3eD$oh*W@O|nCH+?yl;3kpEAYWX)}4iR@+6(& z`Y`_bRl52C6K-sGa)wdpz)rg$7|fGKcI;4S*cBI%feBcl9(~Vrm6N#nu%kM)*}cXn z>{!6}+^&tv;fji8?ez`6Q@z1KwE1ppLgaO(S&^{02M~BdJzV3KnfiX5J@=(azv}<5 z>fSr9sjOWacC4eQj5-4%B^Cq~1OXxRjEW$FqJngY8U>{zy(AfR6qOPL1*w^lUL(CH zDkBjBM5TllqDBZLgcw44dpA1HbDr~_?{~iQ{@(A8Z~w&#d#}CL+N<2_Ue|qHwnV4N zkMZYDc`U})`_$ND5%*K{bsCXI*nHTu8ni-GQd|o$V=^*z!OY}*$UD)x9_PS*EgJ|r z-WTmGbyJJ6(pU&o(HRsz;R<&?vao&_-$+r0r-cp*9;UJmL`4`FG<7w zQV9)6h)7&G-ZfN9p_~!c5z%ApY%104rwg`8hvwjO(rgHrtBR~�JO1oLe{=lmbl5 znMVxtHWg$q75oAaB9Kgh?u-fo@{xdd^qOC#<{4EMVY91!IY1eT2^k59+Ddf)Wgr== zRd9&q0^PkV-)hF*y6dUmrD5Fi&+ptR&Y@Kovxj$YHHfNE%(#@7FM4C%q_=5!#LG2F zX64dR{pqjGH{ju!JkzMhONrVwDIkhCyj>5#E)>%tDh;AF71c4po%2yV`D=$!HuAX$ z@79U2S!6pIa{I5xTIB;Zqpi+EFpQp!Hq@?fj=)bwBWi> zg`2!7Wk3HZtx=!%GCv~-`V8@oh;e*JEc;95{9dX}dMX{OCGRB20;$use#n@epg-B# zTdlEcQZc(*;PDnQS`*lQ+r57{2ut#*>U5loxPAhIb5y48Moy`iNsCAuk=9%J!kBaN zQ_?B}R?jVJU6T8irWolOxQU~9A1QltFE7q~zgXlR7(;Eqo)5V$xj)7|=!rbs1Z+2} znwlTHn_0J`$^#FEOB@YtN8eo&#g`LlUM!x%IErPSVS(6%FRoHZkPc=DWa&dVmE+PK zGa4~8%Q;KLQI@PkQcvcF^>p}ZON6cuQ!v%ks=FfX_O3~YYq6en?~;|e4+Q5V5I11- zr>q%X*nN=_n+4APWR_{ialGY-b&I!8&!05XOEkJ3N$cDJcC0Q-PvGHSgy+oHRDGd5&j6vFTDS_#imc z=?$D~`I7r?Oy6LI^y!D=enK&w+sdN$)f ztbZs>mmFw&RxDB@T@`QV>LBz6H*y-p!Y2paFE*g|;f&K*G_9qFEoXf?>E4~!VM0roq-B=UEWcAwSaVB80W{Aan$nTGP6 zX2^&Qh)d*ia+?-@f%2nvfhK_;*_a?nMkgbVLeTF4b^&NBe6%IeZcgyv4o>cgr7mnz z=eUTcZbqpj6+)Ach-M-VaH_5_`wrLVrqbhjDytiwnjt>~6lD$I*KPjE7rUmMVg%}2 z!s>#RSzhmaU$L|6oct;mqi6K^t>YtU`{W4JA&)B~D~cz27c54xc|-O2(VU)NTEDn( zjg&R4M*HG>L9-e1`0)u%Lu@}gCaV|vGKTQRN``3Hzt-741MbUYe=G#~NsLv)z6egS zprRuT$>}DGuGnLTObW!Gz zbxX=D*Q&%>Y{L5BaoBVedxxH|4AZzOPHk$n?4Q5j#d&J(h3%Pd`aK#gvFtqrKJK)8BJXMoz-6U^MxB7m z+L)2RHd<9~A(fs01fWFb$nx&(RXJS6<(!?LBq$%~g$qoF0?I+Z1irXTi(;Qk-nOzT zz)z1*4wI1ZQR?Xl7$G~#5bNZ!EDN9z907?SCv{3b)vXDd6-QTMfMRmqnIdL6pVn%u z`^lVVc2*`j46~_)4xGMrDiu{N8~BNiE?*$h8sEx_Xihz}ylpDbn)dahTSoMo;7oxH z7JWDJ5cDVt=PQrIK?v=Vfx(q&5W2^j{K6F+~wnHao#4b-i5%u z_1>=D{WTO3@%GK7=Y->HjwX2zPpql;h44R)8O|+;{VY_bqOF`!`LYMx&|}zPkStL1 zqez)Mqyq_$D595E83f>4B z!K>$~=yO#p>nmam2>0qGbzh*o-m}%`HCFYqJ}<3SS^Vcy)uPIf0qZ_92oNy5*$n*o z4*u|8iEl@;3B)=MlA_3#(o!)t(v0mS^mXwjHY35^SA2n+X%K{}VsUg1bA^xFt?l-U zoI);mktjW~ZZyj53U!~gtoj5hbk7u0T8lnQ{>FTk71-CA_4+ zL2>3lF(4+x(~Kc;>*~5v zy5P?aSR<<6at~I?9&s=t--}xPl~IObC$~#DpD@6Wbw(Y+??8)vf{=-?q|Wz2kcgpR z*(Jy8;#LtKV;Hc;vRR(b+4st9df-6ceG~>u)n-W^wai%YbMy3R;uC1jkXUNXSY-;= zVPpr#i1+(AN(4WDqM;Htw@=GUP(b{QUElQ-P)yKYpP!&jWyq*-g%>kKL0x^(q+*;VSn$7UiDO( zE!ti5*>Z-e1;T2Rg57%NQ7D29_G!U#+Z$tzZEn$tZ?b`H#Hu%=xdwM{v8Cz>iAem( z=#$&4xGAln&8qaXi^;zW^-puS`{2D ztn_R~orD$a`6sx;1PF=)ge+!C9Uq6Z%ml^=F9i3Y_cvFq`^Pn-{OZ1uD`U?CXE4D1 z?)NOJ{O>XW;Ui8fh^1tJrwvZfyeeE_%wEx2Ubz5t-B)H7$9~&01AfeZ;r+h*XtxZy z81ErM)oBK+wtssB00VxX^WO_$E-yVQ{*7PT1b|m$lr-ez8o$bRSLgiOWB(rjE5c5G zkM8YO?MMVl_~CKNzoYt6XI6;f`euOWoRD3Fq>X!^OT@uJOM~-EWQrcTc7RTz-7mIsY)bESHe;0&Dwf(dI4i%$uiHUj>uE8Uw0@?IOfI*aYiwhnIuTS$%^eu41R-J!}X>G&>d{ z(Z4AtMp4q9ltp9qC+%uLn1;$Y8)(-AGNKs-6$RJjbzsQm7ZjoDnUk2Z8q%LEhj-T3 zvz!BX%sSD^399K|E4>TANQr#)JsUj5cA0tZQN7B-`9$A=G1I_l8|G)*ft)k%p1yn6 zzAardr=#evl&mYGUi;cLo40d^bdLHJ({JW4CEp}X7yBCIU41q?n4&a~_B1w})FxEs z7=(Z@w6oF~_t>o&(VeP#_E{DU_ED5GfdE`lPM>LBcfp@i*uT2A8H2)%v0El5KYr%T z_(}v?c)Q>>iQRhSl~iQx`L4{_zN8z6bP0l5M zU=zxrL2`g@@?n%Rn$!@{@_t>1?}oy31lCb-?Ll0^okm+`OaIzQ=qByw*fzFL?XnmKWZX$dQl@ zpKZ@j@;#bVD+{pp!{F3$uy58>wPr};@k!c9DB6^4|E#nb^Qnh4{cEnOQ`xWfXNM`7 zCe5LUXH28sJzd^0DF^LH?+z2m&;`?V1kj`9f#I!N_edF22U`4eb5(^s10Bn5LfeQ$ zl}A+lNs_22{7xP)$f@E{x&$`bK+LFyM;|tB)n|3YV@{gUr~`ST<(9dGqGkw zQR8LtVW8uM<@WreeZ`Uj5)&n!!38sGPCDyec1xgi{gAFNy7sD0L#(d@o*l&#}7ij0C#?|2#dW z1Qs5Dw3Ow$FA)S9=YXAu}JOq?jj7pv@uc|E3TqS`(Yw(u z86JO%Y1C?IfXK5XwE(*`BRU8KdLUy>Kn_b$p%@Wg9a6+c{t3Nuv8rz&9&Y(-jr8ty za_+9l7A!a}&BImrC(PX}=_^g>dXo!RR;V5Xpt3{0;4CztdhgqJ=7fNO;FKQsMaM<| z+$H=nwb}S?v(t#vc7;V<&rC@Ty)4vH^}!iuRYlc8B;GHxXWp{b#0A!6k za{qvE;h=Ugi*0a0s_HS#61l3OfjE&L`Iu@|2oewqSI4=?%le#D#1hpQ$(wd64;RK5 z<4SakYf%do*4E49`e%yqhf5%VueJLyYf+ag*j-=A0DfEn zq8eTFH!=>ikz!=Zy>1`)6nbsej9y%1r5P0v+HJ7s5 zuepIEPA)x*tqGMZEO{<4E{z83VM30)pR{9?^==^pT*9GVWXdU_$hM-b)B8~WnG)fh z-G4F({J_hEFZwYo^b~CO#-D^#m8Da6pNS(TASQ52RjHSQ4LHl;_VDOo|HRiQK*e%z zzxX|0H0zC+4h30Y_gY&A%;ed5JcbvVA#_TElhm@q#cofpdI=GO0&)zpQ>wM`vaH+Y z(Gg=pt`u#Gcoz6KPcW{7)!2=4DwkEr$ok6g+RzF{_M92^84cyJ$6ek@&0dtx2@4_x zZ1qanpGyrr_&KS5hv|Z(+TdEkG&soY&zWsYAcrYgpjyHW*m9y%kbb{zSV!l1*GkE! zUE}xZV+;0XP1F^pSnpL|p*k;)OpTlWnyv}jc|coV;?}LNT?^gjKMO;mNHdBhd!P&k zEKoQXy$>a?Bdo-%o>hHtQFFx4Io>Y^0L|J@T}AKZTbkgM0Ltd^aB1Hk;(JKE)U5}~ zW)*j>i1WR;dlHan{H>}s=Q9eWGVg& z$@K1T-M4FoQ5}b&7L1^*fM)j!0NU9_E>G=9{9~mIzy(01z5!gU>LwC>`onz8FiHPX zMiBx5#5zss;}weuO)K&|9=)(1fMdE^qhG&1{54GY+tm9-+ws~cU8Yj?kt_NZzyR=f z1p~0#=%$4)b``Nd|NX#k$(O%lZoQu%J5Sq*b1Fq$bXv{C9M?_4{&v_1FqphB1*BU_ z1B5!VkYRu^NouYT_n!!RRacDse_r)}NsO-br)bWD-2RxEs*m4Dc=WQj?O3TeAZlsi zY^0t%b2?a+5p+#>JWGH03V>%*J*1Z`{OkyjYIe(CBWp_Q6WjHmsG2GCg9jOhde1!Y z0-Wkol|Mf(H0Qp5a)UP=VtsMP5K)#_IlQD3Y(?e=*N65Q7y*&Y@9=Z9?1-Q~!Y9$KsszLv(=Wb|3#9C`B(#Db*e$a@cvdZDB7T85{L(a7_ev%4_D^Pz($v6o z1V)s0^!(6^ontjz#6tW_#@OWCG>+BbTG7w^F_qGn>T+=p zyofqlHojik?n)WHxl6&y?gO)8xdQg2LVRr;`SDhsJE~i^N3f_y8ZN>;y ztcpj4htdAo^J`84jtM4P9o81@NSa9yoxsNWbT(?T%?dDl$`7lz9)j@2$0E8eOn)nI z<%&vX5x^<|1cf(6jgA8nTy0K&ZT%%dL_5kbMJe^cylaf0Zid-^piJjp>qTGr|yD3_0-tU$c<+ao(EUd|H-Mk zw8t)9GWJ(M)Pm-6yocSMBDp9PNfX#p=&+!^3iD!ru|8Y)h%d|mQ(frq{o7E%Pzh)M zO-ZG!#%>XRVrvDgrt?r;CH}#J6RBk9NI=8 z$`Al^xJhbGF)(wz_+opuI%K3zQi-$N^he=Qu9mBE)r9$p-!D#uF_F>)ZLrp0D#M%N zGJ;*~OI>XA)(~WP%MH7#27XUh#gA&$JHaD#uH{5=trtw*Nx^Y+*n~fYfVEe-zu+W# zFR2POT_$$esuv?>OKXFQmkSc^JPN>#`-YgTp45JV@0bg zkk8GlM$u*u!X@Grq8O(-d(6XOCs9M4 z(k0G*YsfD2x~x!3AqJEH&rW(1T}RAzk>5ASyj+UN*c|n&61^N6cR1Z6hiAS!_z1bs z6S2ury@0oFP+m>-LYR<7GuV}wmL|EW;U!^Bop^pQ6Ch3(S3a`{hGoz^ofs#iYL;Lb4Q zWlU$Pi`;J+ccl09{F<&1TCSbgX<1D^AY&O~FA(7Pz80cyS^`270&$pTBo(oi(yxmR z0Zn>Q%%xt@c-=Ef3+l)6X8Xge8Ww+pVknvbP+-%UQ^Y8TiGV>d{kM6}*K#edx@0x^nT^BU6ABnd@JfCOfbSf0i=Z+n-8L4mA%ypBSz;Y6Kx* z$gUK`j6xfN*yhYfm~BN=oMj;~;dd6OT?bV%EmvQvES=FcxY5z?9W^;YM|nbvCqWe1 zPh5Dj-)|nOcN1kl{Aoj`sVKx}hwO0ra01DHb*}=?@)249X>d zC`V77u#G2d(-uE?G8q$hsu8Xt-B$~!tZiln`q9Vw%nsvwTkZu-T2k`x7$@O4MKObR zrsvy)mj8Wa1{7IGH81#we2N5O#dH2vV(GhRflnCqbKAjE*|f?CLt_b|e(`WzCZ68BdlY`T~0p92>b-RtH{| z9_U^v7op@lK{=@g3IIEWf1ZRuq%V zhpuimlPJFFaaAZ&v#v&TUth*pCy^I3+t=fBRlLqx5XM@nhSj>yhM#y05+gqN4poK? z1_OMBl`BCUXQu%*rX3qU6u%jWnOnbjdI&r!Ds73Oyv3Pr$Y`~qg!c%;uNCBAt|gqn zS;raj5@Z|hmVdRJUtF`h@{8#Pu8PjoUrkRvjwKNvKSRppOtMwlWM6yvWyL-nw)bY! zCDUD7U4ss^t+{?_e^2jP#Seend9v`!M*j^3(;rrW$BjPB*gd-NsPYrarqYYY3F%BQ zmRCOHYLEIi@A4Yz{5Z+0`=}a~2TPPp11j9}$Q96)cj^nkvV4)?w{xve!V2ffi;F-0 z6W(xq?f2M#OM6y-4?BMT)2;6wTlf1b4}ZOMuXewn{~13HaqB26qgO=pJ26{(+1(#! zViVm!lb{U7=yzJ#QNM;4^vk%aXmR!s&!M4U;~!W{h3~J7Jz$auYr=fb_BZI=)HPK} z0XPPB(+3GJ!0De?EB3&r-L2Frr48WkWt8li(tf^6gEtb=f}7HRzOs)2t`9HAbf33V zn3c3_y-V@szJ=(@vMJIJ|5P&eNOJm^Bw_BM>##iGsI+d2wI|#}nZS-B;s8nPiH;h@^qsdFQF_vIQ$gbxIbg z{UM})Az<+7G``aa3C;X?F*YwA`ih7NT*esQP`9(dc;U=^t60HkI@uLmI2w?A5l@4$ zJyDshEav2P#+PW$xqf|6E%N||QsuLx<&r~pkZ@Bx}SevDN~md!Lu-v^=ZlmT9Eo!4Zg!AGqo)Vfh`qO)g8%wER4O3ORRh9+p&3Ib=Nr-1wz(76?Pb$t-pF- z)ULqg>648=REMP{^gt(H8hP7|cFOn(ug7Z{q zFeWlE4u^cmn3UuaOOM4zKp;u9rlT_sJW9t`o#IY)Rczfv%uaXpUAM--TdHLe>)4`e z&kx0`ce0lvo-$R#k)u|KeK5Hk;=<9&KmT zDUZ$KQinqud)bAP@f#JA7qp(6_g8I^L`9Lz_`HsmiuZ_johnN6k-{wJ`@GBe0N{1L}-a(?7|b%rYO}s zRhX+dg~U2axV)PRu<_FY`CU6H?a{~9CFEW25B5j@Ph8drt zf|cRZi8R?--IG^NcKacp;@kD*IVQT}quaV_YWmV`nz8Ryvuz4w&hdjv@3_Yo0V&KT z+{;((vG9g4OTDR2q%C=`khopR zmmcvx;n4dLr^!Jd9Fszf6sK`nX&0oa(?Bcb`BlUHMp!>O^C`>nXx|_2Ns$aON|Io| zxhHb1+rCyr2$l3s)P6NyGIbQ8Jxls1)zy(NOCTeV(Ou{gcHQG-Ug33gDN-xy$O1a~ zz%r?h_jDI1`MzXB6w<(TB0{fq&QASZVN}kQ{9!)ZxaV}j%5M7wW&oIzQlVU=UT0nW zm>aQ!M!(jI+@JKbaw+#XUD9(_H!b7twGabi@7PoybfIc8jrS`uTvefASroYkl%1+C z@zdYjFdWw++JO!!$jZzGKB98vccojLnk)fyw?@Zis*ods^B$v`R2_XF&iME$kw zVuXWm*XiJ0Vxzllb35FIZ*(7&mS?u|VJh)_BM%5w+Of|IX|xzxFZDYYgl^+n^a-RW zp4?(eJ}l_?ar3CRw^7ek`OXUY!DomGYn7QnBIeGo^o+W63-CZhCETwO+MQx}4Ug9} z!0{QpXH2aL|4O9ppTnU&6UZh>p18B0_U!O`-kF0ls`FY8Y=4vY(N`wQFPBy(@)S7ZUZuj?&kzt^U5dxG7Zdl z6Jn~1oPVy%5^~Y0470`*`%;wO`BGF$shiNvz!f5XS!$AE+c@oqRx5Fzu_DJmxE(92 z4NXJoOZJ6@i>SMd*;TK)?)ntiitq+|<;!0_vr`{P;<*!R<0cFpM?>=s53qhw7&Idug#xqyGTXt{K@h<$~SKv|FRM8XBBllP&utYT_rMUkLB# zA9Kz_GNm0QF33zicoboz5{UNTTD%&TI&tMSEJzLiI!>TRK*+efCg{2&5t5V<`GNV? za#oi_(G711ru;Hl)qn6=t=+6Vw}O{5f?OYr)d;7&!v#D#9A?vqyN5&V9ek&q_YgVj)@w+dIvu|8edEu;gJAL?!^w4yH!`tu24*~ z*ttcadNg^A=cXnuT(hR`Cpyn=)kpt^0zGTko+%&Y=th~)aF2>Wd0j^zN^CFh%ix0lOAc41_} zDbZOMU$2<+i+V&~NN5`AMoV5p&Qp2OAYP0&r#6TylV*yA{5!wBbQkwC(46~?H~GIj zo{-N<5;!B{m(6;tA=K2-<%u3&i_H@)k(oe0TZJ(DW`az;N%HeFBw;7u9gx^yw?(Q9v3c1Ui;vy=@Odu;?Qq#o9{eEHGkth zc)s_)GwS|p^JV?waQRiM0vkLoai3Ezc1Q^~#3kd_ z{nps5l_~(&bCa(N?xCm8&=LE?h7qG ztByPN_wVj`;g<0Vw|RZMrRq!a>OaW zE$~!^X0M&WPwxBe0m_-QJew^fp8-=L$pMg8bZR0 zuVe95@+L(j8Vm{%&HF41DOV)>(U-erUHACA_L2B#65R{V#G``M6J^suiiA8>d8SO- zB^t}BIOueN6w%ibMKM1O$yXUy5P zP=1F`6LQ?Gp^^MzdK_BsK&JaglQy$k(@h{Srm0L4uwDiuWb%Oq`n) zZWscZ)_N{7@QIahyL{)=C`;F;ZG@xH$7&S1DfY|~sYNtl%1XQS(2D>H?O&d57Vf0+ zm7U3-4lSJ~=6Rpe3hgiEtyzZ$N4LX3j7Zw3k6WQ$SL5L;Vy_5F)ObhqMn?1e;h*Jc zzXl{!#|>To$z8n)XT~Qv$OX3V7uE?tbFi7Ld$2UMUL#0Se+rC(zr~rZMZF0 z<)e$7rMP?qNp6i;uf#)EYQCtE0K+^Faal*=!+J1G(e#30!Ewo6e>~e|KVFi0%q4j)ty#tC(*R z+88Zf{MntUq-i(w$7zA5v>*uosi@`L#=O@~T}P^wbqCtGSB`f1IfNdT&!`%4kH@Fm zwj2pwy}?blx@Wq4{=GFbP-%&9drkLU81k~a{?Ge%hV>Qs9zgf)h%4a_tsjq1CeQOg zT{z+$aLy+geW{q{XvVd@&~Pc3uyck*mZu7xN+F|&x-Y~|^SXFF>rvs@eKv9g2i^8MU$`hKO{7Tx&vNTExjG1mXV$SthLI#|B);j+3*shf zpzaIfDkRxdjuQ&fBp7>S30pl&%#W24Z=e_R1Fdm>P4fIzHwOFNbv-K4VeRr_;sz;u z2foZ20<>7%*|n}!=n>=ym4<^(4(z&hF+PR*X_QIIERJA$;d_S+t z-TkOS(p7_t`nmC;3&Rk_HGvLFr{IjviAeDv6rc!}QTMVVgI{Vr-FCy~!|sU0zE7`0 z@7@(IzxrZWGi2Nrt*V#d-zcAxHj%hK%|{A6O_f>5yAtgo^mW{Ugyo!})mBR514uC` zrOij4GbcBCkESC(x{HlxMIT?h(T*9sF4vGuwH7DpETb!yPHMbn{~}bJ^q-NDpAyO@ zA!W#c>o@}nS5SBgnaWnTHPfSqRm%LEi6dxe#3W=;HP7xePc-ns<5GHPGr|+I2r)`? zN~5Sc3RzB4%$jfWU6JaF@z>*3(E%5Z72r1gfzwyA;J(@$S9G|ee5bDM;(YK7WPMht zQeNE=siX~yuUK{d<+~RH`F9!jmHD`-Z$B_)CsqqA0zgGDJMTvRUU1L z4HQz{LK75f{2om~XpOB8#oq0vHD{FlkzmS+SQ+ zJo9(Ym$^uPhs}icdm9~P(kjZp>pGTUn>AsP0g1rR9Zm9-G@J^x%1xewS?vx>R3|)A zOc|gqJNf+bRbEm(@@$bonf{2t8z77LmJjSS-mMk?oWE_i0H#gOqaNQ3d>^ z>cb;WPqV^r$nA#?!x3o%`kdv9tAIsNBHjGA6J-b^gy39~`s3!^RtNDeuHx=3lIx_| zB`KhWWJF38E|(dy$63EVgJF*GaQB@Vm{El0-JO~jy*#eJ+KDX0qbD0PEK7rAe~ccK z#)n7sSuD^%3d1LpoBjUGEB4XX9a>UXuDuiSUNXdBh=XLY7bB*_|FrZ$4)K*=KF~`o zr^Gr`v>ZV{e~j>KE+y`lew?x<(I8;yJ6`f1-4)m?x5$_dvychodXl18?k?ic{i`L; z96MR8@*k$D117uQtEn<5;Xy~NUmX^+h6Q;V(Cir}0wO^;!MKnRx-E^1so>?&5UCwEe8?UA#$=&CoP@c&O~iPArwGxr_;`tv{d@BV|K zQ-Apq_gvQkx{5sH%ysEVn08BA7FlmGMfBujdUa2m^}S5X11R=%vyVO z6_G~u`hH3t*zi%c3cl_i|J=_TgV#b!RvIOVz4q;s{}n88+i@yX#*j-yN`P zQpoapo$m(O0DN`T<+W#H#FDz6Yy=ZlFTC3i9_dS!Ip1N@J1h|0nY@CB;i z3(BhmPx_9!9QEq}yG}yoEbIwm#DM&*g@0@!#1xzM&x$=ADOuCrH^HQR>s)>J{UiDo$#8napkEB9&k zwj5FJ*xeg;wz`2+`hq@{ax-)1w;a7zUT~E*^^`VpYotx(_cr^KuX!yU?tiU!$}sBe z0;lo?J^y#-h<|(H^V^D@<=}rSRYk-VwA%*PZnOWKNqs~}Kk(K7Q|+QDP1~>K5h|^e zRAul%RP?l(djTwD`@XNmNmPiaQ^@eH{5r^iIiY5y5H~AUSA8o}i{VNwN;a(wX`oV+ zKJSIwn%VK$f8VZYFFT#K-j%wt`}lf;L&HA<`h{uNi-4f?zyDJfyt;~w{C=AdA>iZW zK9BxR)5LrD%C*3*M0y?Wza$ z&ebyE2ZNCiTyy9M*6Xv*%GxUY%`+_hTB>43!T;Nr*}G+Wm5S#TkrEFnhlm~ll}RY|8bIyDv!Kl^VQ2jX-+=~FHr;N~or%)tMtE4} zjmX$E2n|Lynw*j*J1*AnEn}VJ6*37mkp)HMqof=fs7wlr;#(w8*yls421^I7zzxQ5 z{RnH$d#`As6gx7`tGn3a8k{j0DernVphZx*p|s?~&=A)44{TtMzXw(2V3nkMKJ9Zu zZVfV~Jr3>((=T<-1wRYwl}$`dUBo647_feuu3F>hSt6ANpEv4$9#mq;A96Yh3JPe0 zcL>{pF%>&!o)I5kz_ytESS>p*J+Ii_yKy!oYYAK82qX2>mF(CAd>Lt1=!XMprSL#s z<`otp+q~e_ov^N_QqHn>)@;i%tz`Np(^FQCh~!V}(uq-#DnEUAD^5e*^oqjgz5aOk z)`%AQSO>qyu6J_L?DkRGZ+~rq1-e5r`OlAHOmPml$l&<1H{|aVg@pry8+_h2PKMy! zcl~O?m-F&pPq%?yTNQI06P$!`uyf5?rWbc9mxMo_1fiLXDUKvgk_F#C6p`(XZ_Anl z^qWyV2lA{7mnWU&dU-^?iT>&;q-^Kr9x&6Uq%-v3&{z{m0~jKm82%QuyWNeXKArcy zhiC6;B{#kN#QyoZE;F=+CY~-7i=vjPgoHzr;$<1Nh*J--3!5dNyNyS;qvSt^%dz=W z1W%aGZE!OE@@3(Mm-UI47V1-X`TG#;j#_{=i06|geF&_emJ9IrlC?SZD$v|D(Hi1#eV^*;5dRNA)lVxU#Z;sKDw<^g$ zO~fyH<2l%2#dth&{?ws8X5jS+F~Oo^zr;n0iFd-%`8S}mQ@(9`t;-B^U z1g+Q*jE)NbNj?@w@BW3%RFG1IyNMgQw zsxR*h6yBeu-Dz}+ft0~vf`|z@1Fa0d=c}R65k8?fQ4-fgIw}qO)KDA)X*%NzqeiAX zg`eG-4{pPmEMcRu4*6eO@Uv%xhC|jQ|K`*a*kg9YN28KU)|AQq^{#m2+4bQ@?hfF{ zDeEnRJIm+UeikG%hq&y)-XPKq5a)sPksY5h)l>nS&qCB%&5%Mefks+bzFoB3xn0cg zZ`8Z=HbKimgHgy$lkfIDg>fk3S7*mHCrgVIs!wV29miVa=X~;X&m}1Izn7gX<(o_5 zsuvBp>a>(~{ z4dTqL$a?U*EgRzW2BzvFErfBp5MZ^iFm3yAz#5Zc$@#qApkGW6oAqlnNC1s6HJIkTC*j;_}; zx;oGLsG+SPo)FlWW1BlK@;fJE;9ajcFJ4_Jg=zN>x=}Y(8~Pihzi$eEKk5US<0mzO zwu-OTTkX_V#-FAhZL8h5P>A5heL)#@$zmc2XXrJHEmya);;W0&@{^&YOjqFq}o2W1aO4D@!3 zukF(xJpDsDclEv!u|^y10j>Lhmpmsjr{rY8Yu{<1!qSxNeH_QK*}nME+KmIUurbaSd4}T^8pI9mIazF!fXxj%SDSnjY@3_Y=?6?PjXO`>fN&7SQY#)@ z81ZF1lh=J2?btlIthB+^2_3~14sh#y&!xCT{jg+1;<}vnf$Y%gez-mzR$_+oC!mLXytYnOF@|QMgL?2b7QfK$sH$zO9yL)v zsgUGcX#MS3sOx6wHy7?mDLUdu?gilvvw z!1wSy)+ZdOjnc$&ybpN&6)_=O; zMFju5-a^|x%g7ot)JdSp_Hn|DLNW}zB#!euAJ0O?+8E2{o|EX!0Z!nIDMy}Y|0MZ$ zS1~@DPPlRWP4>Z{^-lSeEr0m7T|r88hT1OViLY8i)Qj$e*)pN>9lnh-kTn4VHuvwUg>9QLE7-^5|rB( zQB*`wY=|{^!QVc3ig5DW4b$4Q{CKnGn^EDG`fXSfNT`;r2c~e}VAkZ}2cWy-ZM)sD zj|~02{Rd&aOSDK5j>C)!$__#1XD;7WVIDOBc?WL)=1^^Yedpudf!ozT{WkW-{q3gf zUtC#+)`CAu6=GytWhR_siGJC#mmfp?rt`Zla0LHu3G!oi2TxD5G4`H$affmJ*kJu^ z4rPFH!}|L4Y(jU7jy{Fg<@=wXnY2vbis(A~<(6XQIy1tiYFWttE%WoM;hQW0PQre; YUo-wmVcdzovIDd~dDf=(_@&$b3pQHwlK=n! diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/Fork.jpg b/Firmware_1.26b/Documentation/How To Contribute Pictures/Fork.jpg deleted file mode 100644 index d2c2142666d988783568a7d1f21f8e27d12c5587..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 58378 zcmeFZ1yo$ix-QxT4^HsLA-KB}9D)Z3?ljgk?h*(DcL;95-CYC0-Q6Wvkl;ZAx0AKj zK4ICQl1b8vxAL(sI%O7#J9U5%dFi+C;&# zbau8EU}d#+Vlg(eGXb%f+Cf;|jqO?4S=d+sLZa^W#-?D9Gr0-K!pc^d_O$ggExDDM zFs&xHBAcSU1jy1#*3%KB=BcD^>IpXGH=`95L3=LbF5nKahk%@o$=x9~woU@>!j!+Q z3qY@bC9_hB2sxUW3%rq({!;?_OPKP{vbedqvAA)v*g0CTvh(xvv$Aopa&Rz1C77K& zY@LnWnQfh@{xl#7ax!(avUj$!vnBs!(AdPz#aWor#l^}@z}(oJ+r-R_o7u#e(~Oy& z-OQNT*o>2%*^HCZjF+38kHehZgz``KW~P7hZtvn~^V_$XDJ#eZ1OeGPJ3-N4XQgEQ zqtO3VKA{l(&FTLXerO$`G6E8gAY*5cB=k>&gN>b+nT;J<8FhAc0WLNHE?yRXJ}x2F ze~=Sm{RPIqE9if1$^RdrB_d>IDq#An>~@ZSxK{%?{O`54jg^SFvEv_=gI@n}0ksOH z95OPp5bM8p_#YAYodRVXRPS&6gldxizi|A^$v*}1zu@{8T>lgT|CI2**!3^C{wW0h zDdB&y>;GeL{o5E9WD6bGx^aKwNkAR4Zga|z_P*9Lju`sZ) zu`sZ(Uf>bqzrZ2F#lj+>ARrd7qI)VFqD92STL|yFi$-IVgL-_*)v!ez`q@^aPSB)&k&KIxjL8t7}#ge z;E~`Fkr7}Kpv8wu!@^;~V>Q+oTxtpbuIcYDYd6nmcqOG0HC+Ne>_BZ3LFW#?kAL$F1GNp00L|mWg8G4h zfk%KATK(234jU}e})B% z1rP~Uh z++M36(+-+C;1O66w=`wVNa2o6@^ylgVKj3&VdeMKP4O3PIiw#W~qk(Wbmh z6aBDnT07kg zOvoPpRi6ZvOY<5Jn_qX;F)v>GP@mr)aITUvt57f$bgFBp6?SR$Na5GfEV@+XmIc16#BdK zP7;loahaO46qdZ>2Ij#zgv{r%c2k5=t8=mVh><*LqyZhn(Hn2W12;IkgDi7_QmV?r z@GkOBkai&@hzdA_7jKy){Qa81TcETRS6^fu_uYt&-1evL;!>c7_{v3wcX=}QE0J!J zWInqEIeX1st3#`CTbE)J=cZ#9gHZL!v3+aG7cC_@B>_AN6EJtOX;c!#O2ddYyuh~@ z@I)4`_USk@*aS*6gJpsdB?R-zle9oi;StPOcckkb(<+|Ki zs76fphD{{X6C=l-`0=t7;qmF&&b8Ga3#)h}lGGd&kikoFahf_c&Cj>T5p&1mi|UXl zlAQaIJE4TSH@sm^X{ZSlrpJBWCUrU8fNxxX!B?Nxkx6{!@1$q2?W*4nGkUOSo2n+v zrACk+tkw5flhLs~34dsFM0$%qgdsO)LwS91H?06`!qqopoj-*|^tSvJDWHgGSNJ2PWOYM=>aHx0iwV6l)98Ji~-Btc(kiKUi|%Y+QxSStb-FDU|ydyqr@d6QdqeBVf7Hxo5(so_W){` zG4PI8z^ew84e9SN?f#daUu&5&>xWy8x?(7+GA-zX6u}CHG{^53wN9P7*rUBBO<3b? zuB35&7s$UWt8E(cc5SqIR#`ow9(fUTeQ#52D&SR<*McYx5ds4RKflsVxJP&^skicp z4_j}!tb$b}Lw##XeQH8;Uc)#!(Ci~iVuXaEh3XiksYGf&A0ok$-X4F21EC&FRlb9# zMG0H^V`X9ELNL;opa+q3pKOmE_pCev$*!Q9mInT>aRQ#{5-1?9BQTISWjBPoS)yD> zVi7WE+<240{er=|E-DFU8bVl6!EG-_Lola86l5F+Cf$?XU@eY8lvF5~ACfjs9Mbf6 zwCgDR@@N|nD6AT2u;P#LZgjZ6n9E6#j%@`Wqr0dy7nl1-B$(QDTvNS;q0j&RA$f;G z@;VKZJ&G5pHJ$%wQqCYz@;J-F0!R93+M5jxjcU4`4%xqmvgTmo0i%pqz_SdNcd)kr+ zB=pS}1ePTd#j`GwSf~`0X_$3!1q<^E5>*4$Ryba(QD3Yybk-OV@PHr#6n#D9h1s52 z&u=?0;I5?cFT6=n#*F&f>CYK>MUk9#xvGZwT?ioST%K)-yX-@#6~rUtw)(}@qOw<> zs=DHYA#XN2>IwqmKchtpsRWNLhU=N4I_b?xe&5WZi$RIEM^=`+68U8n`OuqXnQfo% z^<+DViH?hQDBgi;(T5ffiG$oP!~@y2`sU!3x%!cXsd=`+ z_*;_)jf{Xz$#>lt-+`ZJjV^D{or>bN(^yctUd(d{! zc2ELo^rDCESAb*zF&9INpy2}D`Vas64P7E)~95T5p$Z;?kx2<9nlHH zk&okCUWm(`z%M5-R2)$QOgna1Ke-{V3JGD@Y6?Wh6~8-@ z&i^uCsJ5m4S%Av|1o!8I?WdWvUyh2ftsRP4AbJ6w)UAB>!E%}$Dl?l^*6MH>0@S}(hl=Fav ziY>~eBH$3MlYxHfX~*Wfz`abCa@HAwN~b4)*RQ(PKLJdCUCv!;GUJjXl+?Z ze;i9#gHaX|*J2=HvR&Ej*mwfq5RnzJ+wMJH-+t8D<=te?`im9H?_!oR)T(mNzvlItnDcmk+wEjQCb za|(;t!Rv95Cjff~c!FP0P>wG?zOgPT6fx^A81E$O)GpOC0Pn>23b@;j7~fdQioG#i z1q8p`65D(H)Z1G4+k%7b!4p8W1MJJz2R{;bMw7#VJWdZV{7OC{ED^pC_1g9HCzba+ zQzyHoAblY!+)9${vTx41X%KJUeEs=iC)TlZ#ZnN){h)h{NtFV3vI|R@pimTl=1Kg? z4a<)?{9scpy&ndQQfLrd3CCg7@>V^eJESH4MCEv1XhHcoz2u;Zg#MdMeYz2i=miAv z^in|U8iTi;$dqiyn~l`VSs7*+?TSSfR;<_r1fr+V!ovVg0r|n=St?^w1}_H-jqo|- zdi=+GH6QnFMg76xN_(U4@qG)NQildd2mq$51HGU9aQL z$o+IbxwAl(ss~ejPpP*glqOirl0xCV(EZYI?t)xv&S+F}h0V(r~e8(k>Pjhn#~?rkDwy zX#Q2xcxa{Lp{?_)Rf11}yP42d$iDBptrUaWpx#n~7FCIw)aMXYw}q_jkH-5Y25r1w zdcVNpi}ARDl4<|lS%=kMVwa@9^?sWW+gtn7CX^e$#lRCDzx4j)`oACWze4E`#FONV zqj+|`zSei%>eH;>ewy%+2zOJyi@Z?&v%{SKCWnq_z$|QmX=g4;rA_# zNDH{Vh5*fyx!NvKPPI~n={l{eqcx;-+0zI1Q@4;z*VaGIwWfy$4yzd|E17T(Q7)#R z^;PIR0shV8pA1}IhDC0uF?hNBn}9A>|5xlvdY17!P)L3MBIREc|NjYh|7-$JXt(=| zXN^N4JxZYT3rDxK3zpADVmWvJ5b@;=g}B|t)vtwEJO^^i%fYLP$Rab@e)zH1dW@e} zS$3a&MF{^#C>s;`gd@FdB?9}#U1kZYBUtntZO|F++_vl`7xVKmeo|?p0JNPsaw}b+u0i&Kk2xF zN1>});XxHe$OY3MY-4rfU@h@2@iJn{Qblm8zS(Z?>2J%}^TbFVyetytQ&}+joFJ6p zUmHU>ah(N*ze0%dY!wj{S-{-P#MchXWZLAN=>$t_E>GZ)6q8e zTGX#YK8w(0GQn>N!=Gy7k0T_bS|2312AoT!BMSyiA=l6DnfzEq1HF`{!WFU)BN#qc z7m;2Veql&;GPe-al=;r3={!hhk$O|#i3JoR^fDS5ic8W0Pg%ZEqQJA8aP#+B*TyL+P&rL8;>g|%Vy+pS<6;hFY6a)pDEF1K zWA+`iZOcWUZ|0NM#SCO`MUN?8pkmhu1mlZPUh9ug|MXj4Kh@6s1q%aRB$vRd27koR z)-8%@g9XXXWg4I$Gh&n1%v9|;L0v**0Af^_)^?(H>hhrD7j9+2SJkfHmbP85f{Xg9 zJw6p>GPJz*GGvRj}-$YfXrjHOD~*#N&nDv$Yf4 z6W>U(YNKsXCiE(i_%KLaRyaIZl!o>de zA=lDos~cK~&~>zu^RTL-zBXP|OTwi(--n3zwHE9%a;39~_*#74*%WYO@iDp_i|n3l zQa{o)E@xkG$Ic9w`UwS%5;IY3t=zoa@eM2m4a+6b<>L(zLS%2L?C+nw3DdE5{}hB+ zAIr;#ARi;L{&Q7`UPxz#U}m?b76+mY;g%B83*slz8zw{{IBK+=Ps_-&VP3*VpYm); zrAyydhNaC<0`s&D!F|$Qx)zb@qUb!v$6KzGwK9w7f63#D_m$cCmA?SMa*-E6AZ{1^15-~)4? zbqT4KZQ1y3emwrdzLX@ds-`rp!l+Nr>(X8B2oTx;Ao0`$%+=1$iZGOH1PS1fp z)~at}2~?e)1dFUq)OX?$)L`@dCfq4!(C=o>lCLnA3NThuO8M?h}KPC0HH1~^5NV;E2;2a z44Dak$gSEF1ts<>ODVu-0`h~b9!kh0F1Z%mX~A`p_S&NMz1y;YZU7EhZK_`u`osX0zgyC z-l8QQ+Ftu@5|u2w>-^Lkfkb4pID*0$>19M78J$rU_givo#mH+L>+x7=^Le6Ipy4Eu zJSg~gJb7(#ntiwQ602Bkpvh-iKC5J1@DsMp8qM+oHTEnXYMwRrpQ^$>GuXXV!uhIr zIQYf?3&TTkyEdO%0&gkpa}=b~^MWh0O(pfUvUEBo%F3a%+4w;I|HIUtKYs!&J^{{Z z@BFua7yE!|a$uywrlCoc_7imZg&K!zOhFnAzi0Q0&bH11vB?0-hQ|Q$?mX36T?7hJ zC)l|Xt#tAyBZrLA+|0Nn8Fghwr>@W#YpuSU?T|?Cflz*i9G|*_NG2`+WT%#a?bbr) zh|fFL>!QUY7OOlmB6#*)k6M-Da8~1+r-9f0e)Pim&8+B8a4zjVzCPfk;}^TD=3x6 zoEZfx_w(83i7wO|`nuF;2~!Q&)b=oASjXhH&3fDo5Mk@}@B)tMe)`ZXgnZTTyU*A? z)-L0fna3{lL1isiz_o>LLsFx;#HO|T)kesv6+>MXZcr)@pYg;jD6*^Onai%6fv40v0Fd+42Jj#V12S^3=T*`d5>R>b<%N(H>vrXlIg$r zsG=oh_`7W#fALYw828;TO49%4Bm4)A+h3F{{7qv#tpAi6v8H!X$Mi#3u`cn{q%tnI zSV78JbM*)Tv55o1SoH#=YT;CElssXiR*xf2v9~!1NyI1Nhhgbix}kz|MTtIl7fmXI z97TygKTKh3^huYA%VB&CzV)R&(vYs&bu&FC6?t@8-3NvNRZSjxVqbRy}U`VF_;J6 zEaYQz(s(!cGB;Jhdg(WLSNP^JSkYS-8A@m<<6PFrl*SPPQ=%c|Cg|Vm$4C2fmjiAw za+843rMc%~aTB3tSrTmg1+i1ZG(d%$_P(!UY*leSJ7r(K0fEGjD4rm8KkjnNDu6A3 zWk5vh2@uXCgI_+SCy3Ew&nX5^MT?W5kfk%!Agg_hVFse2gKt$@i+ln|dW!a(*%(S4 zFrGzVZcNMe?G!lQ_3xko_}2!8lpb1bnBN5^^spU?Vq%8f5m{Hm7DM&&5RsVaV4fJgj*H35TKkSO8q^%HQ_fP0GQG^xQqAC!01z#rg9*=xs zBG}Nbdv9TAiD-TEQUar^Dng*8rX>J1H?Oq9)w4M}g!`gpXLZLr*U{}V!3Qz%3DC1k zsA;&rCXlMbqO&516;zXhLS{=7%-y}XY-ee(GH)onb!Pce3NBb`|Jxa=A#j+46i5R$ zR-#?14gQv{)JM`)uxEX*?k5KK4E_6CM)b*YlJ086ErNHjfm3fqZVQ7FB4XBk>)}2l%;fF^0a!A``B}1)ZY$6%>1>f#%&#m zHjrt@trCZ{BbF~vIvav~eRM7#ijXJ`91x5gQxYL|vMKN_NDYqs+v_BglO zd9i-@b|^^ucjsenU}dmY=9KoDIXI_Bq3Nljo1<6nvG6RpF%A68U;i3?$RIWGZbEs2 zY^2ikB2s>uL=tB$x^%awwDW)pBZSZ)OhWCoaP@gEAkLEqhU!OtJu2FHq~W6$=shp?L+c?%bwZ9RNrKITBGuo0U53!+BW7~( z8qzutW61)~&s@zgMPQ@=oLDm!ZXP33%irBs9S@E-WoIZa&0W+iwAw7v?@&0hu4f?=+Em zEUUd4l5o09wAExZQOtwh+B)g+ko~;>g8tiN_#Y;Hm%kV1hF)~MddY-JjsnvNntvz# zc>V-HxFs(yitm_t0yJ(aN@iRa{`~yBejsbja6>3QR%??~G`t2MeJL zRWivCS)HN%xtOjhtxxe2!0t=xZy?^`g8y(&OX=(3>vt}u`LF!{LVUtS{=%0ocLZf& zJGp+xFdt6m7xaG;2Fk(WNjRc^rTi6<|EHl*G3%l}6N_wpXj~Z4T!xYOsxOIeF=yw! zqbtl<{;#g^@4Goc_zAIJfeh_Ef5&-m*7JBR0pxppW_O1wF}!~i|BnXf$p7q`3jUN; zKqAK!>)1l;()$$fD>%s?L?Y!(NuTZChVy~;ETx180JGl6QsnqL+Vth1dt z`;Ny=-^01%?g+r{uj5Q&$kt(8If1JNC=%%$iX8AI=t8*r=t_!v(>T+-%j0c_4eiD1 ze0$`pPDeW8B6MCYDAMlRetW@Y&mMHy$_5mfg|1G2C}zmJqzVf2mnYPCvw(cm6V&Nd znF3x*_rX38%~O6|_eO1&h?zJnh}lIl9-lidSV&M4_fgwczX8@|?CMyD+kf*;F!xf6 z6c?`~EDQ#fnP#^;J=0NX%I7P>+pyc+MlD}ior+k;5~2}DPwTsfN#n_JRNG=#>4CjA zAX@j%`*B;N22T%N)VMwH(H0U#-i6o4isBEaHlLlnW31~v<@FVAud38Ia*`GLn`hB& zL`Gs!=XgHX(j4F5;kSH_*uGMa731b+WH5ClV+LP0SJ)eYQYUS_Z45Br{np}kI00Fwz5D+i;qB$PRzmSS-1Cih#`#347Lq%N zI5V3PPi-;5Z39I?5co}MO~5?U`4P=jDiW4p7b{af2HH)!KFgZPB8@D z7}v+VQx$8BDLwHl%rg6(lY%IEdCE8$b5@(Lfj5Gw@aeB^$r70<-6(rS zsrU~aSfpf%F$FH__Oe=808wp+kxsw1~-eHj&46!#SbS4%Q%X~fstt7mjDz1B{`L~ z$!t(_Tt*_5x{5mPg$&RXElxXpz}`!&J{5hW6-lVS*GYutN1m6YaVL9^!8Z8Sg3`%5 z5IdJNJ7K{!Op|Rc=neuJ@S$-NnvUDE69{m645271F2Pc-BUsqaUE0|8iuK9->KJDA z5*t}(;>Vhnj%ERFsi@{$LM>BoxcSpCh zOyQ-ht69{)CXfF;W&{)Y-Zj`=V4Oc6EDKwwF>GZhwbiF8leUP1!Q)v7Xq8%-aKnCf zuE3~Jmy?EC+`so#D-d3k4%fRPB}T1hcMd6Mracnf9d%6KyAuSIy1tvLu(VWsvF|~` z`!a^VGC+M*Hz0Ba1!C%zcDb_pnpCy01sv9jT@rv=?t(&R&9FaMn08gbDJhXLA>Dl3 z*j7HSz*SNU*RL;!2FHz4_d`mFQGM$M%ptz9ss{nG*tH$u2{ZDeBl=4q`7;60qG;Ae zAk@Y=w{}KANVD!2foDyJo^DDEBydW}Z2e`>B`vvT$jw3~NG5&S^Hu+DSSq5C^T&D( zv_$v967Q<%K~#GlwU2z}qi&%6TKPsB=nlKs-Qt}5R2z|0ev6VX**4;C*t*&%W-oJ= zW`RJnS66M-8h*T%MwGd|z!5j&zuTSW|L92FfBY5L48PEPkg~iro&+1*}Vql}s>Pa}cK*EQWL@Go{1VMhP1-jT(dZ*P;dn zb!lKe2r06(s2mc6c&GUkdI{>+9Sgc9tTn=Pe#`StSYQFF-vl8FSj+Cv(hhbQ*@2Jt z#Vk-tqFPb&%fn=MqH^$F&-clh2Bab}(^>&N=BSj|1=?7`(Gug#dk)S#1w4=~UAE&? z<|A7xSnDlPVP63N2phccQ|=T+rrJX6LvwAy*~jQGohy8X=_LIri0Lz)61_$_rHQ#{ z*#)U_HnY`jBNq}1I(x_lM68TTs>i*qezvagJQN2^s;?~KG5l>3w9=KM2nRht)HEu) z{-SLhYxe+qM!Sd9$u7(fmXDZJHZ8lgF})w<<{JzXPS?s%sh$%AoM8p2JRd}6Ey5X@ zYuV~Mtsm=#+&7R<^yi^E3eZ_QpkhBK@^O-!t!XeuF>x|wwg=Vw;S1IB6N*_1rsL<8 z>FMz1R`VeA`WZ9foN|Z*B`{~3mQEmPRYyRXSK7+;2-O8z8O{V_C;_Uo0)b88g{;M< zrW`L`z^0*kc50E{XH+1Xl0aIe)07MAk6z5G^3*iPPKe)T8SJhhgqG+sRrsevm}dbB zW-D3?0J}qtOLg}^&SLNZ{o%oin6p~XA_1gMzXHx~saRBo%k#CXnw;Mzt3Mkor3;Q! zWHq%GsH(xjJu@x5X_3_1G;JwiZuMnIRxk zb=~3^Sa}F=T7xq1>y9rJKmAoCMew=V$EJd3Bg9)x?{bjsZ}n9MU5y0@5vutqxN)AeKo8@&9-1b4EkvE+8Re)49$2&21#iO8Shyo~U`U~OKk zI?+YPKJ4%8HY8S^i8~sNSk1NVUB>99FCzEm+Es}1h}m;Bb-J!F>Mq{wDd-{0(&vOF zbMxW>mhmSgp%I_WWXNT{LvIE}Y`5yA{&W(iAQ32lpuGjG;(Bq89atGyZ`-dE{3Hk0 z+F>+|HX@oV1KRyrMs6YZ;#bXdn|uW%;ggOdEDc0MK4!6C3Rm;J$lhqkoy2>@HT={A z^!P2(*piY<(aFncsURLT#mECr0A?4-K-_cj4asRfJqyxd7R6JeIx?v@rgxB>`i^LO z-qFB~36rMiuXvoXUleNI%6gD+HiF3ruh$!?^lPmQC5;x$$pVbko0MKip`oEMnFx5g zYY`1B@cTV_?`0tBlYF7$@&$bA{9fdO!-aEHSQvFvO9a3d+B2W3{D*z3QI*&HPkbALRq31QUx&nXnsBEMCIH<4TGzx4J`5|-op%a$fD)GMwrrsgll`MzCtSUNt_58T=|~(*Jo1P5(`({r9)af0YMts!w(@ORBNMlm-w>qqd>6(zAGbr-*Up{jR^i&Shfj&LY-AUDu2p%qq zF{H<}A*|;>d8Q{Ekb2LgnPWt-`y!7(-Ms=nL~Y9%dtFoQ^-nX~hVEnZsK6BH%nA_D zM(VQn<0fZ>$lD;7Y%)RuYZBGd4Vk*^OWrVvM8D9?N!y#KwD8QdV=*V`y3CeZ<;z^j zGXX8rcX;$A`(_^mE~dujb=gGM!3)=MJiy3saP#43zeF0Y9W_^18uQ2 zUA0FMTY(xUnkltS43A9T9{V^eD@>k0i(*;(cT6|PzoRAI%LrovV=C-kI=V6z4=H)7 zDySv#nQAfxgRp&ScICn)kz29qsLV2@M}i9+V8UNf#yI|2gftq|YRTZRA{(`rdsPEl zbAR=U40ldhfzK&fU*=OsY-w7}Sb#KbHDbDX4TePXq1+#V+x9gx*^~uv$9ef_`IJ_g zdhziq>t3bA=HqntWg~LKqh_v#AMf!{Klvr_S0rJ710uuhQUq;U|B%TSm0l>7p_ncw ziCsBz@uKqb>8&IWI3Z`Q2rG$eNfanyNM^9wAxvT7K&_hhR zR4erltsUmGX%STBycjsY!M*{;$?a(m=_60`pE1z0KLO+x+I`@;jxsJkx~p>`WRLKI z4XNKvM%^#h@@(0(zr=j|x0u(K#I5*S%&WqK{}%Hf#dQ7_^PvA5g|M z_VGaTBkmKR3c7Ij@dC84<~$Vp!7L^s`4F^2oSvy79ts^ z-lDH$vvhMh{4UK-EJdpFAd^$y-!i+W$SOrseHw-E#bE95%G|Q~^6}!SdR?x9cJPL~ zIYm(4P%%3p)olIFVm0>43D2ITJ((4ZOTUaz4h>Zn0_RLWO7qULs%c(d)&3bpa7XrW z%G9B5Dt-|Eb%)A12fl9VjaIso+$I56J)iKaM6KQT%^9%g{LvZJO?5G_fuT!NZ>dlV zJec+(+#8&=3J(ylSL9=ex+>Pp2* z*o8Ey*MH0Taw}zKVz1;wE2A|v%g_|Yjed-u+gj(T&QZqh=9#woV6P*?``XCP+mKSV}1E{=CL!m^qPQQ z#nP#OqpD|*i@(!waS{6J-1E&s{+XTZM~|lW=VH4(9&w z1q}FW6|G&%y*l&d`|MrX0rn*~1nET{_8TYV8^2*U^fZH&Yo&g*qrs)k**eOu;rte1 z5@rpxYD+kry0e+Fdx6m~<(T7Tu^WB2(kXBBm=W4aBQ}B$kv4V?2(RSf{ix&Mk62G@ zGBSPeIQzV{Kk7UzfpXbZr!++I1FPR661gGprEtU$1DY83D^uLN4(`6k&kRgzONYT3TLm_h64wTdg+KH@(L0vV7BgI zQ(;Em*`p7C0G`yZuKB|3rp~*0JRqjdD$kbE1}N|9ZASf40(3na*u>??};I-ccd6^_dtmPd2g`J0J&^&U)K0*YGcy9`ESp^l8DR;^g872G?9` z>-dJy+%q)p$$mwBcxh&NIUX`W`ok1eD(%vQ5e(G!BUhkd9%*1g_nFS~n;DLvmeitY zS(9`L@^|IiUiy%J^Aocu%3*UBr&RJZPKbl?_=Dyj09nb3m8RdPJcRXGiNtzF)nbGx zh*)KpWyF9@;{>b6-7T+?$9`5c525+JL{R3uNA^Zc?XyzC9;KYTJ9_R}CW8*Lp`lfO zBVUpcDL72ZY6?l(f2ls{!;#xx%}@6!zvu%&hN?W(u)MXgO%Sbcc3$FQw^Nyom@ZuB z^N@~y-<^Q*x`K+}$%@d;RPIly!t&qrq}3$eZ^l%~pcJ68Izxl9n`mD6gqLRZrCRi4 zA8*)~^zHJ2KwSVMr#(@sjbiqqNX>wN0L;OHg2Q{dtctKE^oK+#@fV>>k%o zn0_CZd>6rXk;*FLE+yI6lvop)@W!xED1Yn;pwXzZ`2zw6i3)}fN{GY*8y7_Sxiia4 zJCBv<<4g%NRE%o|PK>JD$@KNre(c2qcThrHN#5sO1OsEl$BmaXgXNW_zCBN6;wfob z%1qQ*$h_rQ05MYo<44DJ!rOEXy-_3ZCN zYXDQ;EH0RMtyAUND3TxhEV=q#X)h%ih}IuJe)89CP0cif*$q4=yH9xnOpnTG3l<;b zr$Ap?G?oA005G_BLWyC05TB+Krc!w;h~dR{x7(#Yq$X4`Xf318KN=VfIHqpsY1nMU zUkiXe$eqk2%*UCu!XxxE9-C@onVOW-Q0kX@J0a)7w6P+<594GjHl&9{Wxezhe@hFG z^An#4W3HAnp8>vx5_M1%o$d>((J}Y)Isl4cGSJDtL8nHFGo9C;c?&0=ed^`{xH)lRHyg5t99WX|8vfPWjH~jdL7ZG%!G8 zii=*OZVLfHz_%xW`_V$c6c@fc+fVjx>oXx5`dc{eY1OVb-#Ii6qcr6S5p6tb0Uqb^ z%{C|_-_w<+3|<6H8#h_xKnU}4@peC$?xRC@yCeY)6e@(BsBzsEw%`=8wsHoqKGD6ogU~D5lHoL61g5Gj&uMboC86X8kSOG1f|BMAvIRohu1jE!DMV*&Z;8dJ}OYDNJh-w#QOtmsH3h!5^#inPNZM$CyiCr|A$(tNe zoN+W-T2g-d8S|@muHe;X%c`qFLxasS=k995yw;I~*co9I6*CV7oSHyhD~1D{qq`Z4 z^9T=cF!s9shTCqS3_{pXoxx<0reDzY?YoV5jt$nwxT%>MwmZ*I64LUsDmMNKu)e*{ zoc|OLmc2)kjO9+kRdQZaU-qO47tZB52cp1H9LKpHGI4Kb-D#691JiZ0lff8~5=u_f z9EqZ$=1Z5CO3aFys_b3?A2hH=q|IBt96MC;0{o=6o-d62sN-`1DJr63t4n`5^t9I2 zr}0AbYaX?o^63QBSQdE3XL0u<^~dAqEI551d7heRfjF};_~x-~oIlSEOLV{9n|AVn zONTM+jX)ae)hyV0fiZ=wKGA}&4qunsj~wencZ)HoKZd5h

    zbm_R1S(!=-6mCYY^6UC6bnG$K$K+uTOMK zn8zm5s~5KK9t~;J#r6-2`g6al&%SBNObmHr;t(FIGRM~;)CdfST3$BUN)vPT&yq3D zBgkN?4{B4?^Z-Q(gbkdXRj-=T#VT`e$6>0NT5 zis&2=Q;l{wPJLO9GD6}#SahC@gfITW-jtV0OjDBhyx5we*eU-j6}tm0>i{}o$mrxq zI}FaS_3Y4z#}nXmx4L$d^cf|qAoO+D|M2MPAD%@0-A_Kjuxy2M^6&?=M|twn=L`-_ zLOyYPzPkaVrNRU?SvW<-lMsrc$wSYU01a*?b+#E9oE`0HwQn$NZINGFg@-|tqnMq} zzLF$4KOpoVxY&Wg+E&3`XTRX~6H)rUd$~sx(2l*2#ainqKQWp1O~r*=I1xI@{vJlQ zD;c#`AAMzRw?+0mB9|OvK8wH&rl`)!X*EzdCp-TVB!&i8XF*WLoKeqQ#PmJ_*>_2(;7*e3_hTs+!DPIOhsW?%Pda zc}hr@cyKW=Hz=ptLk}zRvB!sKa<(ONq25d}N<00Y z{X;DEu2W3x9WNr#!md8af{oFwcu}5hZ(#c|P^y$9@3Z?UcUNekX$Dm=9|tzZ-6!RS zIOX%`%aStpfeAMd*`NVAmI(|ZDB+!y@(4BTC)o|rR1D^xpQ!tD6#276#@x1)EAJGP zgv1#>oyAdp;pn5P54V{>7PPCk^)&U*p!$;6ZKy?mV2*Bc))B|wQ%*TodxO;`m|XS* z_Oqd?NTCiB_~0gYU(TCPV8wRbCWqgga{CTFVTdi zhWcj}-{@WY*)a|eERL|+CZzm*yUK3xcSl(rihlQ{tWH(Uwe1I6<|VdIOi#-$qB?vT zHFnY?<`_Ot@d7xW;uC+PC*g8fr$}gAzmxH(xT{{0zlpjK`!KnRmHUPL?!ks2OH*}fVvvq#T4u-Mb?QxbYS z;4&b1YIaZ~ceb1$pqNOX>U*KQ;-< zo$wUQ%}sn?y``a)UjP#6K;%v=_7P0q&)f!w<3nJLht?unUCUhKer~r-zZI10I9sz6 zoPGBxU`*x$WlVH)b+mZG`oZ`Ee{w_2R{iAXl(UYCSN#|cU|kSzp@NAwuQ*MYeQ5r> z*aNihZA1vKc{1H#bR|V@*%iAT>b%QJ(r$2&-Gt+mICzy<@xPHPi{HHX!Ki}3FOi5ZG?uMByqSr zD>_=?a>{zX_it)Ui_g!fio6{#@@c3QbQS1Nx6_>b`xT1+%us-2Sibl&JG<_Rt)2b$0H z(AUE<^ifV{v)(5SiVC#gua}C#vc|1*+Z^(Cp*mavH=1lAzIJ5CS!s<{H9tciPak#2 z_B6%suPin|=gMOhfj5Waox?kgZPhNojb^Mq-==lAm8Hiu(PdH2y2W=rPXK4H|Df^t zmqyjX;6m31J`E34F)ht-x&Pi`*ENlGA?qX>44*3?_rdBVS3QB0{H~euz{44TVBrxX zTT6RG5jg-s>|yArT}xUu`eFC$?vMj?DzdSomMxh+5PY(S)$ol^H36Xz&NAR*2@fP?E4+0SL<<36AM| zt?l(l^~96lda9dEnV&^tfKkVr>-*fe8-Qc0tBhl3l}dcl5mOwcN?a21mv0c;*yHC^ z`k9p7UO96J+BF5PwJLK3E9RM#>^Gui#VTwp)|IrRG2;rdS_owFF3bvaF0J(*$x#^l zP~XvXnOuVM7v^H;w}@2pB#?^}k}JqJ43%`IsicHnS#JR9KU3sfFR6Ix3zcOel~AFh z#%3RlOreD|H3^E{Yo^cKarfHmw6v_t2$<^TLNYDX1(7l{65Ndw`cCR>Va^bN@zD2m zY@e+<3zX!vO4?g5H3rY98(*FeeP<%Rk)GPNt4l}_+g0&Y7Z6g!&wF@YDRsCYY8OU3 zyXk`WcPGuv)zb4YeGR*aUZb5mdG`=qIUWKEZH+YqkQQSo84)_x;a4(cgUrEiJQQIy{O z5=NH?M?GNHVmSwMz7TL&zW%}Xs1xpP1NdIAt*+E-W5GLq{`o#?9GhqAQX1&74Kt&F z8lEGOPP7cqzKzDtDr|bRk{;`-C1G-_WBGUu1A4Ru(R{?zp3n0rLF*#{h;P(4Nmp1x zO~l{3QA-7F@IL1aWA#{}nlGc;&$vi7m}|sluW`C9KS&UdWfb(%xDURappYiD=uELr zQPML{jP0Ya1xId0#2#r=Zut`rtL4r!N(=HddIP5LwM2^|uln~ME>yY{s97g5~ezZnCQo-P+z4Wb^(V6QA?H1`OLF5&_ zv5C2QoqAKLHPY^zAv4nfGfVR{Kx5?ln>o@fMh&WH2|dD8im~D#=8OjWIzH`>hAI9& zz2J2>j~R_&3R^3PF8QSPRBO2->|PC!h`lzVAdXm=beLk6vZL02>J}XZwOu?(T=-S0 zx8@G1wJT$sN}|g)G+-{boOaVb6N$U^eakaPA> z1QfZy#yx#)Sy>b%y&h%d(k0M(O5D+*OTk5JURgg|SApKH+#4cC6HzY!tQc}iwrdC8 zEwkp;I-|StyNnmbe(BrTfu8d=YWwjXxy|0tFNlwg4&B)@0BgsKijBOS_@Qf=YyRk8 z7*Si^&S!diX~5^wI8WJ&XQpN(v2x87kffH#_2E^w(o+BceU1WC2mSj2=)tOzfK=jP z;AHE1Ju!l%a~a17h&}FJSlyWIgHKj8_00GZdnoeFN~B3-bevV53UXA(W~2|Z4Kd#K z2sy73spT5K?m7ZH2tZdS>eQzwWQYoTjq|%1%OI;#{Lp?C*@ZW8!L{6?jTB{zwae|+ zyn-tD}U7%9j7F3m0FV8d%~AG#7c$Ge z1bhR{n~4b6QX-ex(S~l|?`x7gT~W4T-NnTi1A2N9046LDyR@_jZ>G}6z3u_0urp!h3l3X(n~JbO_UqhYtJQcBm|WH)Y?P};7Vj&aA{y844BO@8@=vur zqp@&2F|oRL*~Ij*hWmi&S^twE@S+kRZAWGV-OYG> zu^8O2`QOcYKSvQnRDXgSftH>ri@sE<5QP6<+i=Z-|5Z&}va3uhUa--f@M2 z?>N*GiPT4f(wg0pnw{oEu^L$16g!(v4slm6K0SvkD3-)`p~mu!B#leOAe*G5SiK=z z)H9TUwjRp_uc5<@Ya<@Mmf^d z3%UB?+qQMvH^M*LJg}KqqKyTCCYwhf^OKe_>7v+O+j9-o%e&@*Wg0MYa(Px|1tom5 zr^)#G`U;^D! zlIXfd(Om0G9AK#h6$AT>&W~NYGjNXV9qP}Wa{V#RnAoFr0l&-*zTg|O_GFW z_nsA)&P5%H4%@(L&E41_C&yrjbK}RlNlZWqnZz~`CJU1&d0EU|nPqi}cik2o48|{yevt(#g%QwHmIjapcWu!Y@np zMC}W09HHet+C5I@C}W~G`W)Vi#K*T!N)BLDGGf$B;qlWXsit&CjxQN|?((z0g>LYW z){Aj)KHP)Hs98*jTMQGDV-<1)RtsO z{bhx0(3E?VqGcRB_A`+lc0j_zLld`qn%?H`aE^NNW38sx8EkYoH0Bp2ky}bJkPKZY ze%W-l5DIZ!J-YAx?ufa7-f!?Umk#|v?!jd2d+x_P8fOJ;PpB+<;w>wJ2!uQsfMzzg^&^)pt5|B zP(cMGg?%S8Rdz|L9#E?8fl4Tg?jK>xF1}RhT@9$k?wLm#0ogn=d3V;D0My{0n!sT6 z&zww>cs3WeV?NUDfFR&eH@0Ytqpx9w%JNYVoZB_iUW2>vDS0c>BnN+gDXSR$hD$a0)_f#y zVu{r%U5QWf(*o;~ET3?PCju%?Kj?ga@b;NYkl;pWY)@Y`h#wdMM&L&@LIC*fX&h$= zN0WB3ac4*qh*8?$6%|Ls@%3FKHNrzyF_y}6(I2wVrB zW0}CW($$gJrzY;FlzF}RRXlRd)|7HsM`7q=f$wDs8Dnl_UilH>2a=e5G2G<6%K~9C z7iRLwQNGHFJruXNUOoL6u#`e)?IGZ3@uost& z^T3?@a+f$C$Hh>1ZPc*)`A{6n-$SBD z+mEj0@x;Ezm@j4L4Wq29tU>&Ky9yfg#>8SYLj8XsV6IfXhgVI) zDeT_&l|f-=_h$+U2bO`sRES_*IT^M5tc){X+>)Z=b5NA==RT|q3c9R%nS-25LVzAy zLuMra#3gUn;V4|n}{AOG)Oz-*%@ z))&v;Wj^CtFrHyOs0{P9nDLGK5z@6}haTWWbN+{?|8a-{UC8MY4bkN7?8~xbQ ze)@v;?ezHvaQc}pho{k`P^m?fV&Mlq1DZ0Dofb)jSBgOcVoh<<7iiEUXW2%YB_bjN z_;R|5d}&IKv8OgAeYb>jlxBFAlPrRB+&bS8I7&TlRCW!%?_AZ-&0;?rSx;IS3k7F(Etq(UihWb4TB?WP{<)1o;|7M^-Zd0v6Do|*gWude?d#B4so{LW?QUL}+K?rK3Bd99oSk8JVtFWCZP^uGDBf z@eyVpTVa|~@a!PpDq9Knoidm1gd%Qz5IAK53*D}3!GNWGsMb??`CYyz0)0M{@#K4- z8hMwnXtIu~E2xl^vw3%JWssJ1r|J+DFe-|cz!Nsx!s26rniQQNA$NSl5{}djVRhV< zAf^x1lv34r{&nB9z)U3;D$Owco{#(9Cr@RQ#e1Bkt$z6KL_^(sE_J8i6>1QRhJuFf zS90^T6oLoAsiTdkJ=&kB)*Jsl4*5o+*gQ7KtOo<<3BRI-MIhw|Ga}YzrK?GtA%3t;M-{F zUkGpmo74#W?cmwV#-$JeI=pB9^DjekG5w#qOgw_^6iJ`VmS|Ko&&j+T-Ppr9m6FlE9?|0B)OKd)B?n}&W2-*xNidZvpE3t{ z#cMFXjPGodFC(2L5PL9FwUNO4yhAq4LY=#sS0GprfVWXTHHz~TI}5`!iG`e^AKE$U zAQD1vj4t?-SL^)GydDCB3XYTaH{qGnB_bnPI44T#nL8?|S1g>uPYwo6J+o$I`-Otp zIvf}a=b(El0Tuu3`iV!OizM*+0eezu?3}HXd?$nYzULNv&P$ zZ}Zb#=AGHNhbbmN+VI+yT}KWA$S!XvUH_J8+TXqFr-h)%7V^ndu#eG?@DZ=f)!!Iq z$~jK{3A#@V#?EO}lRJytXkd8ts5wg7Kl!&4exmP^6aF`ZvBP-4S_Y*8j(Bn-( z{W_q_VWr=&%#Eb;qQ=ECO6%XS`U%}+?s4oYjLpR8(9sd9xqFks_8)TLX?5808Pmq+ zwKERE#Hloi)u2s}7C91_|4&H%d^Vwhk`@k5^tyjY#$e@wC(3hWwk~%o-Uv;8gT*AV zDK9n}37!#__7}pypMre8_2&RNSr1Bz*ZDN2C6SHh+hl^^74ofAGZgUdOOjO-;AJ3T zxsJXMD9F9>^~d-pEDYu^MDO?4%`yN0^HJu6?^poZFg`W(5@%=hhyWoC|+keU* zue8uy(Pg|iv}ORq%zRC#!@g=oeSq$tjsZTQ{PP5x@&aA7PK9&zsZcreF9a#GhY(*2 z-!I>c75@?F^JA?RvyJ60UE`YqJS^_rZ|$5@$0mHcr&KxrMetBSS@t{kc`bRvh0VVZ z5WY#c#oXZTK@C_`_UL~cBM&sf(w{k1=}J%nc*gI-0px4Z-hbw;&DhQyy{fQ=i0^_5aaOlT47O$$g;R zMz(kHHfC~KRSxJaB_+mfG^aKt_k0(%F4)K+vM1>DK1wCjzPbL47JQk@-!~YBc>%(3 z?0-s0LO1thZGqfOc-fHyS=(;Z6r#ILsglox!Avw?Q4_Dk9le00yYT4gqWO~E=$JtH zIQ=UU&?U`uDGN09 zn_u@-TH09tv@&JfHn>kVHMw`kL?-v9t<5^;Kvmu0a)vjwke8AzFS4L-(+FHQh!Dfs zAVG*6^tdlLGqA((}T?$Y$AgTtB2<20GC*B-UQjh)G2_>>aVu1vpW{s=rSO?14{-cSl z%qADtMxi(rmej+3@!Gw5u4dsgi2%i>+j8KWSfKu-s!zu{yt=OIq@k5%i}zLN@>n&z z;sBy;r^Jpn2&I7kTe4oH$%hZq)p>X&q2~_G`q2LJh+cG*dMgA%$j#H%#S8XN{3EWp z)rA<4jP4in=Qf;VEYmaKKJQ%vx7^xFZ zX(73Z6|Qe-^ZB{k7Ro3O@9Hr}>U5tv%E(xM?I`eMOsx_-PDX!i6Jc!IW_amL@?y=e z!7H+^+^A{zqLd$`k{_oOTn(C4dm@2&5^Ba7uU9(=J~d~r3+U!>c6O*~X1LyMZqy`S zz%nCaDu$#`I=KO(5b77XAhm~3o!h*(2-UdVPMn~^X^PxUYg>t-e>We$9O|-B3cTRL zE`OIKR2!804xz^?uNS6A7$Oj{GivH+f?wK{yTlwDbNFsla(wnc9N)QxQ;Uk3| zk(REOdI}&RhPJPadLrIp22Xgi=bH*npE-Td+HmS+NRSTF1zQEsVMl>Jk}sS3QB8F~ zMNs^(yf}#K${Gi_yi0M&S$HH-=t~PGLH>AU*e<&wOv8sE9rg#Gy~`V~NI=akDpcZE zZ%a#x%OMMl^os0Yf<~co!utq|ka*7<1{*yK)zA7t;jH`_;?YDwLBbxpz1s7pWuCAv za&fB6d!39e63DT(LAM9Ovd2kUBP@N4l!|pi;fA=nPTfe(g3Ys|88(Za;fRU$Iw*s? z4@tQ^6UdeHjw$2=&La9~qfnnEZwF4ie=n<8kUQrZ7+TlY38^?4jD~!4t#up4Lo@LZjz6na8e#jEzYc?QgV?=ub|zfyP&*}e?XPLJMEGQd)`8sO)1ly@!@O@}($L(E?FJfs4r(l*Bx#uswVX&P znHE-I7-r02d#;^D+b7uM$E70}$Cy?@BN`Uv(EA4up2?N@C!uGz@X>?CX=u7kN4&JR zh$bh8Rh3~{y@aXC2d|Oy15)}{!Tu-}!UExC3f$JWx&{6fqz~W5<3+}s=W#6ajcI@S zJdv(_G$M7a`9&9>ANd$sX-udtMd?Z@#!&ulTTOOM6*(fXqiyXYlB@tF$+HccG#fj= z`n0#_1WH(irdA;V?zMMr&%9&cz?#Qy(HxIqlJHzwmL-prWPDeVxQSC{Hly}jNrfSX zpwtx08BN3)eds88G2Q%A{lzDJRJ=MTl)yxaA2A_84HuSwA>i#i7{Z+T3*pCmRr#NR zW4($_xvh>bt_GWo$R&U-wS^BH;b#z>9gO6tBBxP)y~`?To}%x0g(Z=kVQxuC&iC+Kg_? zCJk5g)s8DqRfa|x@3wm%k^hANJcEb2e92BLeuO*Da4t@Gs)4q?u$5jj{n@U6+jI(c z74WNrU%md99NLYmwYE?vMyo(}@P2i`|EpU=mFsMbtI~ikhbQnIydD9c`A}xbwTLPI zXH@^u)qfE9-?jYz*wuf$#Xmi}sNn z$Y1dUs)$o3NN#YA;ii4NF>OB;5@)zw+pqjw4=?1&7r$X>_bM3qDjWBf4gO{lWFGnI zzOJ+N?ld~&F9bnh$jwpIUkD>xU*k^$3ftS}Ki`h2gnBm}P!R5TiF_$LQF*qO&9}Z9 zXc>q1pZot$l24M1w9BcY<}#T12|_NpMRDU=M|VX-P=_^|!opx83fW|MVxh!7>H zB~a|NKhy1g*#9sULbg1_xS>lOWt#X(HArnZLTjAxK%2p|lwv1o)wcJN%LkAs%YA^( za9>hJ1<<$4%Z>g8bAGAiNcihVbHXV8qgse`g(}YjI=WNQjX#phf2}M053ez-&muIQ z+G@}j7kla+Bfr$=efe?kWx=lpR-#w6odR)==#*mMDR3vj?Ff#$Qnk0Tc$#>ILvr#pPDhHZi{=-HGv4?6Cf9f$E zFMkv-DN8uW#GYrMzxB;j+ZHcq;AInR-7XHDqD^G@+lr(0gL(Jf$xg;^BDd#Bs6=@4CHBY2j(1j!$Q6-#2wTpsZmX38-KJG=EY{ z`>E%{6gS^7Bi z1A0`Fdlzjo(jU0S6ez1VjU*cXg}UHr6#&*U_Dfw(TUw^2zYvyn6<6Y_IZR{f3;CfAsB#h8i%6JylEO3d>8l^%zV4^l22jX8IM zNno$=ZT~bCsj{=YJe~>OS5~an`B_2ML)xhrsK$U7`s2BuCt5t}N4L$m#Y8$BZJe-i z$+p7@lMq>oyv&FxB0W=7_`3BmsPAHIb^kCw1^4_>B3p*@`x?_d1HJQRh0eg$0v-Y? z2%1l9LHoxR>m$7UR=hOyT??j@LG8<`6U(KbzW&UlT|DA_=)DVxCWy7jcXz<@6G`Rt za%V#|*pt^@_gR_hksjPvQWbq3qgaEU)|X^s1#pWsakGJGc@v(6`fu{BYn#;(^hRhs z=XF=>!%FEVJr7K6Smj*Kb8k11A!r&@eb&`k9J1qPIGg4Fs%?Amr!8p|`8MEPe`xqjsU#@bFramwNCv#&EEYL}X?n&QX2IAH|;i1Ba7EQ@7&5_`NJVg4U$qgF;gw zpvcZ0vSR3X;sr67e8Sgly8Di1-At@8s9K=D0-SN+k%VVby$sU6qnUyo;80E+ zKFP+57!CW-R;|@6WQZf8qf+j`m^JsfwH_;-5K5mIE&0<+|I2UaQc%Tx5oCHWKl;?g zm8&8xjaYh4keK&zU+WwUk!kVX!kIHgZvU4MsJ@846;o5_Nq@Y^tM28`67l9rl9}{R z2|SUJuGPj64{qjcT~$o+R~Y=bQQNv!>C{ljnWU`aKvn8Uimg?Ff97#(wIEDHSo*Ww0?yG0N__%g=a+uExZqZE zT52!HKW$%peq2}-hJKVqEITJ|r^+r|HOMYe>rQv`x%Rd5dt>cLPUhg}8~kb*CDyq% zAKqhGmse9nf@Ats0DF zIH8IL-$?ak66rTR9ZK;kX>?BKa<6iT9MjTHr;qQ3r`<$eCHX5gEoy%$L^g(=5xZ(2=Sf%NIA*WDyEZ{ICu`v1mk;>vN6TCi>SC$p*qWJhM=<=$!_$rR8FZ+)F zc0=83kYrQkTiOTa+@740pe$=GklY|a12;_iCJW-cYT4>2CT7ELQK9(+=4&yD0b9GB ztAA0yd7)i4-c!F9nwn+k;uXK2u6025`l{y_+3BBTC-S;KQa`ngW z3qk3TU>!BD)K~aNt-{(AhYYD19w`wrLaH^29r=EtoOZ^OGc@PY@%$dd#=sT@sW$;4 z&iV~}(i5IG-!Q!&*}rR-y&|ZyH7vIO3n4={I+gC$3SRI+-^Yv&_O6PG>FC&@C%`CY)|#fA7*0f^w&UuL-o}hMnYSNzt>xdJ*N&ihKb8EJr!~Q` z)YjhRR&J0-QS{ud;0%Q0bq-A()6b>5{_OF`qSm{O?1ehRt@dmAs$We!0YEJ3mc+q7 zGaCQSU=$wwJ}Wb!NkBKP@vD&$+|xC6=>giwb$ zK!9;%=m%)DnQ|yp95lAp56nSbGPFWK^uEyC-`_7eC@2X#iqj%_be8Wghn)Umt`Uo8 zutem&D54OM**(~g)?wOoLX09RHDNUO4vWs8xZ%a=p(Je_PkZVZbN))NTEPb~;-VsR zewTA;)IsdDqB+@}#xB%ie0{rFZEd^xh6)9_<@Gg;L96dHIW=MWx`4c@<}dwPgo^fo zBj#}X+H}s?1O!2Z{93n=T6n5Qr=Cx!t$$db=p`!%V(J=LkqnadBggsd-R=8i6r76#N(XD!`ZR(&QUwjEdS$+-?WWsu=WKt%3J53v!^ zrH5ZP{Ql&i)x?}3QRr{X5vJv{C?>HZiGi!FKj z|T(6%j}{JIq-JRc6FVAn}O@yXmho zgL>)t@uc#cGl|6X?Jj^ScC-&&1x=SOLZa*^{9b%CZy2I?T6y^c1I&!yF@<8M5R|Ew zOA609KR6)M0!pS50{A}Wb45bo7mpB*(nqf~-3lKY#lw)dML)9qt#cHyhcqFy z$S&NpoqX;nLmQg~e8`;e#TstKPORXEjU$BIPu7Px`H)BO8=b-Kb(AA^N^9uOe8WX*9A(z|L~L}#ZT>Fo6IR|=O*~!eJxa|%irL`0^J=kZ+Hxb$ zG^Oy9TI|`j-rAq2_+dGijI~YtT+)UV?C|6rBV)7sGFtQu;b(=Ay3RS=F}b!cI1QZV z!qj;h8vfOVkyF!1%C6Pwtz(XU@nj5{MRtp~<;ku7OTQ};Sudy|)F?%o(O?)tGphm) zGG?(G$e*n-0?psG-Sr({lSn%#l9wlvnz=r>GBL9N&B~SfNTUMBj6u!;kIABz!y&&9 znO24DKaV>W@`eGAJ| zCDCs+65Ovco}_+C%2DOTOj7S1+Mb;ex9r&!mg6(%2sxBkVF&5Fa0>=cWLAd>R6!`| zH_a7bgZ8w^?2)MB;Fp{@A}Hg$a2x&ZtbPJj0qk)7XhPN$$3Lr@Zqdw>hb&+d41tl( zq3QFnN0Uhp6UD!q7{Psq4X+SVII1M2#K<8693!Li(k%jAHeG-WeZ|jz>OlYGhk>dz zagx8$W%29OhaG?qSW1zycEvFl$jZhJd&I{s(j7f115yn;9LhwH3(~Uj@F13%=Y--q z5z%onUPVG<0u1vW90Bpqe;E7^2liw=JWQfIWy$O9`#b!SnRRV*4Fd!HiDU&GsR3q( zgoqCY{T#2WV3)Q4xAK2HsA^j<4b}`-Q9Q5$^F7@iq_uzOagiSi75sbv%yA)btkVgQ zu99_lHNvJPT3c5GIdGj(iIX#HQ8qcT_cdbS4%_+MXmYL;1>COYh0Exza#zK+c>S4mIJPvq${iJXS^Y$)WKv17Y- zA`{r=`1?-1b$3fNLFovqzqfQ{(-+Z{M*jFx8$p=8E$SQ<=@bNjZ`~6=O^P=%Z@+GO z@Ygieg)0CV%4o6O4T@cEnHR{@Au$vC&{KJqFZ=Q~WyYT3)*rVd6` zHhiy?yOU<_s3;aYEVHa`$E&gkR(2lh|2)z-WX}2UGu^@8j0~$Ay zc>`CTn1tW$XwWy}M-2aFKdG$%_6W}NtT^R6c#ebR)m58gfIJjk0o&CEB?23{uE@y8 z(f3x*cfy$}af9GCETuv(ajS1}V3FAG)E=xITjvcpz((597x)6bVlL*UPOVz)>fb7w zPM10Mezb7zR_=3pd%G$$T2OZilHhoXJJ!#;!(>qIfY@2Mh=^c=1^7s9)?jcLhe1}a zZ^yR(`I*rpKI8Vl=s`HMUc=v+Wz1+pDo++unLB4*Pm322&aOPTsziQw-;^I4QemKh zUM0{D-|$yNY0&}tWi5rB4+M5dL*FuPc`;;xhF9fRjYEupa_$4DGKX#^C~Mi<^;VCK zNAxZ?J(W7kn)stI=)adh|A$vYV;0`rB#A%FOw#40h;N!X*q=U=(LR=qybb;7V3=wiK|KYytZu zny6V(qzU9d$=Ha4uv#rY={oRH#7R%RytB9oJjhIcPG^~~M**lPr5eqk1#(|FehI9c zu?hkx<$rsdl-4NEN?YjqIJA&>m=9~y{M4ceN5pBKa*L%e1q>}p$~y_bC6Hn>j_otz zZS6>EDBMD_O9ya?DwgvJr+9)K-b{Bd^mh@r`dQT@g{KuS8mK6#Dlk4yBP#@Zng%`T zmwyGQ{3U+sZZMO)IXm`Ju^dYWs^n88 z9140E&76XE*+(8bk|_iRRNCehFo8qr?bS#usnL}b#nJ_z%p7OSk_!cWxE`48)d;S~ z3@s=wN{r^B`2M(#LG4F6q?M!PZb6rf@m(${{cNQvXa_;FH^C zgRugWs2*-1=a@KtT1t!H*C+4P!i{U|&d!K{(_dz$Ynw@5+z74N)3|t-hD;uj3VK2j zqmBDws}B^r9FxVLudUYB-WPt{*j%s1QxXgxC{rO7oD>vya+%bYJyC|b+m%3eKAWc4 z3hbGtKYO?$iyZ#q0<@$KOf%1`GCtMn4}YevHq|`UES!`Ppt+CI+*6kiFW|e!s+cf# zU~;(mFZtPHPAwDlsHr#|3%9b= zR#@f40&g@ofTXTe%yOz)O6i8!PX1p{TG(Dw?b?W;F4J<5xbnC;et9$9`yD4l%}U7g zfl@#!%8*$}CAOTb>W7Pin~6C)#?BcSP+|uDT0#>yfayaqy1hHK7adnG6`zC~V81jU zvM!^qNpotvx9*OUNuu`Bs{X+EaG{G(4G*qe?Z(<@EFUo~e{pXm1NMo>Pum8PU z(Cp6?<&NJ_O#3pypDU$_Z>1Ccds!r7CN$LnRa=j3E|eAY4U6nLKe6HsQ8379&&^abO)9f&c?Gj64BJ~|`T9yl zKhcj!`VAH(oP2>#4}u0m)PU2obNAq7hgUk#TnHU&d?qFvqsh9=wyt={wVaZPJFO6B z@ogU8;Ep$#eX$Okqw)K|B`hPknu_a8m74t# zJ)z|N4$0vK;jkZgwEhkP%m~s^!m5yC`BZ=$(vsfG7bqc)wv{bbfCrJiRdWjLO67iS zr03NU8;9nvN9-H5{Yw;de|tI+B=AOE+7Opf{vx6$=B~3G*WHgM+Yzh1ylT`8ns(su z)pT|M=znNl>AdlP7;d(zKlMw5N#TrL(PJQ?puS*fgOd>yVA6jd5$&rlqox5{Cw*CI z-nLF*A!M0e661=71g};fuTDEO>zQJYvxO`7#dqWXZWHYM%}P=al)MsV%G@kN^LQHg z5mTL;E?mp_8n%+{=ZPXzC~~`xg>^B5s|A!O;>AA40HJ-Ibv>DXA>3i?$c4TM4c!{} z%@|m1`>K+MRR|q1ovyQ|1;iIXu{B@en*k+G+e~8PoP^}{7BACh(LhZKK#7t=mTciGJWS@$+#W`dr|S$C$Azl{VyMs z)y7aR^JNErX8@QoN+cRYJg`t`b1cc=*aE?h!a=@EUT&3B313gV-$u%|zZDxz&{Xch zAh^fmnPT&(S>riOVf&0naXtEk551yBwzXafM-D?2`ESv*D7yrQX zI{xRpxtL+E9G`vNj%MK)PVuuhSsz3F7`e90Ua0cZ2Yx4Ly6>36T4d%jJrmDe7bK@g zI!NFw8K5uMdMMR_I!98yqiByCwILq_y&j~GtN`&gWwS9WMGc=FDv+H2X2+cIa@^Jt z94VnaEE{ivAbhg8g-aKjdA(l-*@Ot$_A{RYGI|)u{Dvrft9z)cR-JNZf0Jo{ z19d003Zo>Cyo@9n*t5rfl(Wqc0AQ;la+y9WtazD9DTwe9<3d)Xe9DzcGxN8;iI`0V zt^7tQUD+06#ESG01aLVPN4+W*KZ#*lD?W)Ubyw>awJ$a$zoIv-A@&E^Qd?vE_B1i3 zEj$nuN&yW8NYHP35b}$CGIbUN7TJxi9@OA#sg7#_8Gt-;s%RfgAQd~_CE(=Wgr_bD z*A!zOaQZfvI9ZOk%EAbN&~emA;^u*jEVl%bVxyaR~~^uchg>Qgloc~MDced z6?}Y8|7<8)=lMZ4OK9{g7D?pMjmEw~oPhY;5JtoN18CpxBEr_$bp^urgY-Q!*gqCf zP^FMYSlXEzDX42<`_0y|npuYne|zjxi0}^|@b`<9b1&fk=HfvM#0WSw5vRvMz-t)~ zeOtkaWdH4c65|hNP55Kv+I{;}Sd0dY{J>+y>!Q}!BtXO{LW~NiOW>>|J#rnl$XwEq z-16xaP|3r)(^qD(PR;+*Z`_mwZk&-OGSsQZ2TMMPj*=0vc-|$!yj*>`XMidckg^s( z>(azZp@%VUvxU$8D3pr!Npjt9I1{&}=`>0G(oU3T6WdM?Ge@YKtBaOi&idp!()bPI z!K5T7$J0T2H?6u!KV5qW^=8ddiNf_SPliRU6!lCgLhemy>d^dLJH0`QIV4QlJiVu$&gJ!)$5rS5F{0hQm|RV!}J_L?~*MVTicjP-<`lR=;pnwh&~dE-qOqsVWnWNma~ z7#a%Qhl^UY%AC{e5Fx4gN}pZ1+w_B*orYn)wwfdTQ`THZv*&Vr-MzU3JK-WL3PGRz zlX%m9Nd&V@u%3*c4*YI^m2B_`1En=rclAEU#j>12h$_6^XK7lYkdZO%B>xTFqVjYs z=r>K~eO#iBt*@DNd7n8x6UukUd2hSjw*D?m_SlP49$xr9L`~Rgo*E0;FS$0{U)T zi7ADF#{>-ZxV`8K!$hCNL1zSAiI6ku{S*inl;`+& zqXkE(DBSe*R!Z=sIot@vkd7m|^nuez-$vb@;wZmIMH7wbJ2cgnt3tA>OV0hlEniK= z3Qf80(^_`RiEbX&C6l5#yntETGGtyH=t)S9`R8;ygU6zCBhtN|C!BITG8-DC>6EIR z9CD$}0!lrc*EZT8yvCxQDtDbxCIAIR^YF*G2dwCDw$_`jL|Do3hA!+YTj2rT?Pdhm z;-R%?_^&29Yik{zdp=krL0@>b7}>%F_uL@ES1Ug#r7q0b<7-ClgsSCeXgqk;uo*dr zraDRyQ546$P_pn2w}lZG$5|-gHSS`1stVH^#esAssnDrO)%U98AyR;R#_4fL`a9=* z#&S13{KGB#*3aHkzlMJ-khYSrH!|OAQzH>lotWsN?+=YGnoX9>XgRYR;e7;iXc_@U zCL_uPf(LT?=z63qoGI!~%w}M>g_?4Z)te>`AJ?j18p@XB6IHoQ{Tc%4Y9PKYs-yR$q*SQ7nOAR0axfK2P8d3 zP*$mvn8sfF+E<#e_sI}azEWJ0E;<+@_x7Hg4y9szT)$-vRz#}1AOa_-Qtp=>(6Pn7 z?=fxUDm#!;U|m+?cMujdgK(O}i@aDsxtwos7i2U!I1?7|V>uWxkG2APc!$hbuTW@T zH10GBw4K%h$}9gZO_colR-HF;auW1==W+6|3yrRU9K0dj55vUC4SbK$ZaO~gsXL64 zmc*VVo=*bfcRUYh9Ne^!L<;N&JjhC$0WKbMJ7`t$H!2d)&Nw z_q(b84M-FyfzjJWB_h0sql2aCs@cp#!?fPzqwT)O>gE%&Tcte(u3Av-7Z(PV&Tl=3 z70R$q2;6W|5$TQD%zsHsm!m`_ud%>ZnVv(*g?p4g8k}0&V7eKX8Qa3fw}h`(z4b{1 zXC}o(CuU}5ydubLnrA^z)JatO5?Jn76$9$$;>NvJFoVQhr+oRGqv&;^4Gt%-LpD0mMUTDB?EHT3|U zt(NKEruS-8RTNI_uSc?G?>0F72&wm?Ej_3a2s)<*BSEVGmf*u zNp2nV{?gJEdoQR{MD>qWq?$UlMEZoL`Ab>kJ_=kJl~ zq_J9}u)&a`$4AjW(|{#A!KduooX))ExgM_k!ADZfvy&F6SC2X+mk&KFS6dAuXEywL3OWOZON= zvPUPNmaJ9i%2WeYn>aWMI)vEAeQWxCx+9GaJ_Z3dbC+df|CT!@N1d)WzKi;oK1b0{ zVOiF0f}Oq=`rDT+p-i8M1r|)(whi+;$Om_A6=PMT_?1jcTxIB&cyH`+9j)AJTHiLb zEtakPn-~Uu(wrj>iLJUbv@Y!}d(8ks)OxNgY}kH@_b-I4mi22s6%=!uI^nbdRs&j_ z=XIY37(6`F>`uBC{oME|Ut6Aje--|CDX7=qdnX+cq@|{r_GEwS|7!26 zj-g9ha_AUo5RirelxARN2!|3x1*Ahj8tG1{83qufK}tfpq(e{;1Qo?Q@PwZ8+|T>D z=iYPQ`^NbTHb3^>Yp=C-thLwvu5>X*<)eFV$+3Wkn0J8NHO65ojMFX|Kz93po5lhN zq^q|Tg2P$Te|{ByN1AiVZx-=qL$^@KNJzfRPUbDXPVIHXvtHzKNNl9kd}sXLwNG|g zlR(zWn86o9(XeKij0`R8&lyMl;J79N62QzMglgg`dQfh7_oQKZkO}_y;k}$6ShxuM zHjYkC##D7iM<3nepj97q!fHc7QpQik(F$2i;X(f_o4_#_Wq*=&V?J;7PtCv){F_e; z$;{1!6)6;@Wkpqyct&F={NPK7S&OV;XdM=5gFl&%z|SKIfrUxIsAhiB*iZz0CdZ-! zJ+o_X2Rkcm3kLiLheCrES=rpe9W|sErmjtW|7MAOj1NDQYcdp>o6qZ6)YCD)$KhyP z_j8j=w4j*Bg!%?gEhCIlRE@TyEGNweVX;E2d#rJr%z;ptae1}O&irsT#bbrM?1TyX zg6YqPj`Tu5ux#cu8ifET7@^`%J=KT%m8)6EA?lLw-q}?;d@^m|@we3djzYHlz-s3n zjpsBJOIjDLMW!Jw8bQw29-hFznRNcFURaHGB;>;5-szbLLxFe_#F*z4Zm#s43TOh{ z9^Tys9MVmQ?fJzQGvMlh9FC!bhw{do@HqUnC?Ym^$GqoceLGW@JQ8FVR9 zHb~cYY}F@YkA13ox+ZqiZ=`Sa2_1QD7Hy|a@-t+6Rs3_d_oO(x@Ca8!)Jiw(%b%_B zl3AE^disGawGu?Xa7VJqjcXn3YHjve_DrME>q7T9GaD9NYmKCIbQFk z*3;`yjGKeiwkb93hJunnVc6GyN<$N_03#&pnB6JUEUv6dFlW3As(_G2M6DSE-4a?lTgSzJZPYD{@1CS6jG#UMMRao``JPY&}S)feQd*|DE3%h+vu|G|FJ?abAmm zE@iY^2)jG{`Po6{^SC;G)uHgqC!Bj5oAgX9-F!7yBi7=NV8x^fQp?bY%tlUu=Hof| zb0`c=7`?qt?pl*2I)pK4&po%aj>Ba2-=IuA#K7xZxN1yVJO!SDl#ZT-LjyjuZylr? zEWGFTOdPuoG)2tv5zCS30=hD8qm=1)MpI-?rU4B;Xh5-(gyT0WAjZnZc=s=wrJ>ZQ zY1}Whfdtk9^CW98Te|KVY7St)XzB#?Y(&V zjcOqsx%dRn>4GYZxeRmE~q^?7Qj9noAiFj>Wu+v8$8qdg1X`9=$&RVL^+)WMP-Gg$$2ybthl3%RkC;Y<{wNjQ^pugnyO8qo+(SGibQ*ec9(m# zw8CF@^mMvV4gaDO$d}-$(TRyytoBDiRgl?{O?nW_yp3`4Sfio!Y`xPnwuk^{LZ={E zpr&t|cU~JjgI!yHdWaWw7)Bg;71nevyWhAYpo<@AZ0mW5NyjDHfulz&MEndp^QASA zkXSovm8dufc{px_XERt*LW=-@fVZt6>;vgoq3`-*UnDa3%c_E0Uyak$T`5xF<3eqoMj zaSwFimdi?VmY)q15LqDKYbtFYTCji)^!1B%3{(>b<$W+CL+o64w_lBsY0o(b`~qa)M6D#px9<;+h29s!)cxdBA*Ae!_YSm zCvJiC4Y5l%{4d>C2?87Q{zAh4p1JVfG{ydD&8iZ6-&O}YOW3i|AFiQ>8zg5#Fz&h? zG0dIb`KoEXFVowu9RALVvnWBGqFp+xO<0!S-g^r1VfIRGZ+omslcs%u6`&wF>sec0 zokp9zD8LMmV&;Z!X>4HAsrzLmsvO-GR8=t=f{Wj9DOpV?vuCC2G#FDnkg(`D zh~R23gF@|tczHimLZHER$I6dnKUBx$`_9Uc75%!Tm30>&YgM+Co!Lub4xIv&JYnoW zkxAl4wk|nD=A$HenmA)4J;GpK3-bHqnly+?p`;jZ$3qADCgNQm^BZY9efd=H*<$dW zPSmw(si+^;DSmz^Tx_iJ_xSKiKYe%qkQ*=W5xzmsm}(U6H>wL)p4k?dNMsj(hUFEW zFa#L+WsvxJdKEQibA4`?6g(p+4Pyj+;}Gbm$Nu_gXRmY)*9jsY9rfX!lZA z)fbBqIf|hzx1bb${a1Y*B|^8qnsLQ-mwF~t%fEN1Od6K8RG8q{DqX_P6|lP``Qkx4 z-Xxj>0^GbRP`Sl?C8-6wU7MYqadbKHsA3}G+B5vH`ZvSd&!#RxgFb4UU43hZlRj8E zgaQ18kCdL1dJ|KNpuW$N+q&kwYf64U{2-!G>$ITW^*_Ff(g!&bvYfXp+K}VR+UIyB zRp5ci5h+gpV&L0gw$%T0RaOnYn*0K>R)mhOgKz(4YL62kxNCOPHu#)~bK*d@ep=4$ zun`c4CCJ_X5>Ct~`Gt)CdhJ>$Bz@`{RMV!eGN;_EN_ zX`nvg{YlR%hn<)`v8%0SHS)FIY+htSmec|O1F!GSS}%+Rl9XHEEIH>W_jv`zNt?t8 z;%D{1Ea$ld&1I-c$ct4GoV_1ddk%`6g=;s$+bK(facr-N)2v@^Gy5KBdd~bb3|(aA zaB<>jwdp)47BMjq7M3KTC+G1Rpm>;g>{8>YXiCVyY$F8V2 zR+c=e0?TZdz0Fg|dE2@;%n(Pon?*mG*iG#%75yKBz7lZf2Jc!iRbmG{iBoTxt2%Rn zpshD4t}Tr^6+9ML6Ah^Yk6Pm^T}}RDi;PSa8MQj8%$W8QNIB}H!}I88ke*jA|doxe=K|+A)Q_{ow2xP;oS6u-!C6C_sZnR zyrYPVW1Exa8#@GV!q{@-g)`zt@TD)Gw7xA0N=POkmZRENz0$I3hYfanX+4AdsU)ga zfuj=!sH8^cT#`X^BK=1?mBZt9A7~Ulx$-ec6-25TcCb*{0u@;YCj+7QZna^5PC=Kd zj zTRt+ov=7>RLrrB~5X7@%TWRmGZ=}APnl(uaKOT06+Y-!uYalYH^2mES+4J3U;|Z8? zD9sW~(yh~UozTK@g&Hf_{yLcw3)Jis-2DEeV$L~-3SNK!aI%Zg+s&oY1VYJt%AZ`R zPent&nn#$7XcKO8HGB`vyD`28eB0|3|2k2+r(eLEFY=~nqRnSyfF;t{T|C9qK~$n^ z5BlgByES$=q}sq{+KUd7pHo;w+=3KFCbv9CBc^#m34>?Zhuz2R0h ze1kV4CJ;uZCXOWq_j2zW#u!>oi%CCmI=M|CH1zrbycZrD6e{C1E*hH|*Af^TQzI^3 z59?R0P;G4B`EDBeZoTAF0BgFV%X*yB{A+k+VuocDtOguo=_e+Gm>`MiHD;z};h%z9 zIWfV_OJtSK4lXY_iN50Dfs|~q3y+K$j`ipau!V~>Y*$~>MXyT&_o9t%g-7xI700pj z&BOq;f;30g$yGaVaYez<3IP5kkA_S~#mI6YrZDYWI}s4)J7OW39J$UOfJ*;6-d%K& z(SB7@(YuAk!mo^WH1K?yZZ3Bh4nsjRyH6eG-)~#?#!S6HezZAg2S~^q_n%w=RCu`d z%w^cj4f>gYEoDiQKE4tp=3f#fP8tp==#!l3nez^8(dgGQ5mxJmn6)v8qJ(iX&=w1r z?0v!5Lh;5uDnfbIW%s|LQ~(?U7D>Y-(x4&taof4zZ!~_9=GO{B?^)j`^~cVnJTts< zwyp11M=Y#)sk7vhfudaW8%h4mG1UsKdJNPy25B1#7MKjQ#+tuOqW_mf-G3LJ_rEUM z9(+8hi5oXEuB~aG4S)NT^_mmvu$gtUbqG}hG*`V{6&hMyKQTIPL=z=GK<3pt@R+(L zT4Na&>b#1F?+AN>6J15rti+-bq%cM!BhOy8PKoj(wlq4i|7iZj&No_i)~hmk4YJCcc&~eKcvkXb<1Keg1>JxZzQ1ox&`Hv^?5^PpfZH`dO!mJSkJ%VYc;zwpj4y!)&@SKO zVDF-qTo2q;D_d>{MaE_ZN%8V7TeoB|f^sYg-!mRFUm<2$C!iyJ0tG!M;0oo`qjG6@U&gF&@*)>6=oEK(i!yZdv)8@h$b$kqAx^4T)m& zEH#O?dhm>z&GB@SV>5PcX%SpNzgwHo(kg)uva3_+kyg|*ztU|H8x$#Ro0b@NB{y1~ zu}JtfMrzm%?+tJc;o;f7XEyf9qHYr`%ilU)mHqWG%FhQY|IphNRUJl0f>$xwtO)<0 zRS;m5_j4)0DL*sL=!;6i`veb9hk$zj{Y4izMj`GKL8O*kfO#H#^ zH8?a+mWPnr)Lz=+e8pse??ZFOt}txvd7}fHzMXnoS=w%}ak~g+Okm9KHtw?XbN;X-S{ZmV6362HExy&vhx|ZcFTKe0bCd z65|irzfu-;9!uI9GZd~Jvx1m-W#nvbDnL#A^{IIm_E-53zE+lE0*s@(wxu$Pp?@`Z2F zzlvhLAM4pA1+}zrY!I3wN3FSSgKB^gl}u@_leE^6qo>x)aedmZ>Pqv?xHT2Q2Lm}*qo5b9E3h}E@}_CTlU88b3`Y1 z76Tuoz)P&SnEUR5;|qzI&^x{y4_o_ynLj5W%}W}taOLpVjBj=muuWKT>-=weL{weM zo3rrW<8*7P3tf4geKo79G;XYwXm)ymBeZG=Z+LJ7bcSOA;ocJc`jaFjilKuh-nddvR3$8 zFqFMyJC2d|&I94eFRH8ic-cs6Xk_nx;K+0eVZ;lpH&C0gf!WH{0^dFo ztbd5BP^FNwuVWdY6wG1~xGYi7R7X-+f_TQb%Bhr~RIS)Xq0lWRJj-p!;Aqe`O;|_Q zWykCF!QXQp`x|wpWq?Uhl|sI8qgDum9O;$(bWLaX9Wxdlc6Cu!!oXS3siq;LOnA_^ z_9Z-Ems$nfPG@$hnnHv5lbtDxerfrWk~fVzMj~gq?O%+NZdc?__3w^pmeP8ly`7>hGyiD91b_HZHwu#9K$uX?}Yblqfz_?$KNX zQ36%4Q`k4_=F!s()S;#@)T+KlrSg2roxMnqy+e)NZ1k%g`b%D^85YX(&el8 zxE)ar&Yj!gY3(1+!u?(G-ew29Ixy@8VJkbRmH}!xp?(bJ ztLf6EEAdY)z*E9xr)Kc&c{wUTdnn zp2R;lr!e}(LU+w2g!_k$OQ%M!a|^vb=#jVjpJKbZC9S?5E5dZ+;jWoO_u6BgJ8g_c~|zm2+;Bd8vdm3Z2l&@%*A>~eP7R&$w0>D;YYrXZN;7J zGsnFnZVYp zTLXmE7cRBO)O+BYA1ibG+R)gPTBIPd^gvRqfOK&805#-P3lp%a^BzI<2@CKMEZZB2 z)ZaMKWbX8C?C4rNkpuus@9G%3}R5AHlgozQHc)_sn4O6G^(Pj?nl ztUoml4UTrF z=lm@$9XG&`uUcwFA!nqlMWmfM>`9F_#|lbl;7QaYm|KI(o&tV|o^Y}Y0rS2kNMLSH zO6~_18b6@f=vn={gdXWnw!9+WR1-%PP(ehWsOt>c%Sxs#r_kbndhl}9?DgiwS{X?T z3o9Kt9!$_s~UETwU+;hqO>@50>?Z$yY= zY-n=)xJ(vak7L{b*UJ}&FTNK#3Dl%66Vk0y4mnett)!e#hk-7BQsHQyM&6mfMSlG~ z??VqIm6zzk@7Xh>=fLGF~^WDWW{UnPu@~nc7_cr)~ z_wP%5GB9e5q}671_m6VR5bod0K*fX=;$Z^H$?2l&5e7;w*<$om?8Vd86HXqllQ(w< z&N7VZ(S=H*yE3H*5j#6k98m2}kblIY5)eQ#LbBJt>Q2N~|1~hIi({A*iQ2f_wiK{e zw>#75{k$V5o8XftIfzQIpRQLqEe31eUy@}@HBSGDhIVOjy4KCApetMm3t@Mz1nD#o zYBl-f|S#>H}k(+Q0yTR15?!*AB=%&$qe1G8XTV0g>x{(BAN%8<$a%s=T5rjV$tMLeo?5 z9mZh~(qS-IXmk{g;>b@kq1&x@ElofXz40*7CUk@a%igU=6FqXRW?x(UHaT18Zc{I; zaII6TZ-J5sCJ0E^={uNhk|gM~0PjqWs_-#oh<)6XMo}Ke50~^3-7TzD*WqUDnbfs= z)5GW5iyua2x!Wv2_wEtNUdk=d6K!r0Vtx!DhNeEjWr}@q=L{wNyV zR-J4h6Q4*9q?MAYC-Fcp`8G&2@G?ENDdJXvwEY0_dEnCCsZ%dIqY}l4bD~`MLhJtXwCoJC+eydvLDO|%WeRwzl^4SuUz-~jzEvP< z1iaQUxbgwo&bhac!XLH|sH(Ir>2SD)f*4a#N|If=kN%C}VA(OPh@?mcy5jmJ&M`lK{?gBS;r9tnh~Ri-5dg*ZuK? z&Ivj7A^i!lZI9+5iJM<7T@OM2zx`4A;y)&s3>8uUFUE~t7xsJ*r)~UKwfp~K$-lJZ zUlZqlY*CogBeW!N9Bo=FHQ`g+naPZGM`&=&$#X2$=HLBmf-<3}XQe-|mK9(5SY7*W z_yeosVFHl>JL}-z84wr6->it3$Fu2TqjZXU=Ddm~AF3-nWu5a`lrX-MLEEFi=$3e? zbgXUBl=@MHQHl0pw9JPwG60mU&CNf`-08?)tNh*3LqHc7T<%Fu@syIqm2kx)u49Du z0+bvYhB)NYJ8}o}X6VI=0z3IFSH20+%9w~t;YrV*GQBtwc#oY|KkW*L(APHDNj<+n7*O%Wm_W+2t1+fC;(k7{!-JERt3xyDnRpD0Sd!wI!7_Vnx6 zY^-qit)a!FORw|OFGfI4g&lR|iE0O#jBmSG2LM9&?P2z{yez4jKJ(&>%T?30$gkM> zpAru`HcW5OtKyOi8%u{Av>mrnyst|I3#>Lc10qa0Mg_QDm#3qRRtzT%u4)!mrhxZu zU1zJD7Coz(s~j3Z%FTo}M>;=HRONoU0(YesqRs#O*z=tR0 zO2>}WiHw#k%YlzWwu>a6*i8p8uB6jBbnrk6$!zMh7{5$^T&^S?paek%QUQC5b#%$u zHi>5Q)9U3S>1ivKa6AZa`i4yI$h!yel=^On<{sM~L)PL+a(3yVhPDHy_cl=(T+l15DIGNR#+SNpmbH7j{+)xs&)f8W z!f&9l{7*s{@1#I_kI{p|rOq$^?ydcQ{FL(BJI9)R(Et_i(6hF)&s&6S7qIKq6 z>m0;>V1*qT{*fB_mu>NPpIVC7?{k#3o1L8q^A6=N`yt6isG=3`L#HR-u)p9g{+6Qg z`tK{ry%^h7`@gPcf9~+_oAkb7Fft!wGLg|0 zsDM)c?lty#5j6R?18TkiiS#V|o~5`?x<;mj0iBG}9oN%Lr_Y_(JwzxltkVOVo`1Nj^7 zWKdFME1K*1q^Hty9fFrcr1BO$zTpbc*y(RjNPu*C5WjCuzkWqyNUK8}k0<4=ntf&;Xt^tmBQ* zb%7i59P{CIEH&RBzEVVfXI%F5Or+8uyEWFXsYh4G79`vw?lwJYO5W~_;HU`qb@ZVV)F8{uW#FN>^ljHxG`8P~d#w!2- diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/GithubHome.jpg b/Firmware_1.26b/Documentation/How To Contribute Pictures/GithubHome.jpg deleted file mode 100644 index c5ceef580aa5249eb3b4c70bca00643ae31e8607..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 76690 zcmeFY1ymee*DlyN1b1t^36{p4#vOvYLvVMO5HuvX1t++Z;O+zs?ykXtdw_&#^1h$n zHEX`P|GoF0HD9r)s;;x;IeR~6pQ_W5zn%*q0Q2zxo1nA)1VQNA*_w001rJ89{lqqH^?q|@S3 zU{!DuH@C8u@o_O%^HEec^|3YOGouq0LVpJF;`g$5vNv}#q4cu1b8zMN5~TiZogaGs zbeV-(2;yR9!LKSI^``{%lOXkuBI;5PHxtY4wO#@O3ihFaxu(nVEo1 z%sAM=taVsQ+|tX8Kp}PVO#tzkQpTvY6YM+nYPMxk97C#zM{V2k8GQ zpU@Ef)#?8*{Lnr^W%$Ki%uU?PC7}O8?5u1&U{*G0XVlqP`Pq5-Svi?`x%nV0|0D-t zc?!ng0sXH<{{JXiLJ%`ke$yxHjxK+=S2K71pUbwLwUC&J%O9PCp8s(IwF;#i3JMB@ zKj0D{kt)Bsp)7&vU0$6f##0009I2Ll86+Xe@ZfCvMNgp2}hw#5R#z`?=7A|Rk3 zp`v3Tz#+f@V4(uoh*UUiNVs^SD)`juCh^GZs%p-0NfVPa8gCL3bMgoXxx^$xLaS=J zrieJCG+&v!xVZ;aZ=Hf@Il09pOwC+_bGtV-pVRSp^w9I3No!f;7eJkn!T_L1o*pUw zy1~N1K+zyU8@aFnu&_`pFo+27(5p`}FtFHgI8%*@Gfj|Q zAX}JI%05J5)HBm)$9M6po(WvroP4(wGTvvTJc?1xezJHH33nis)~LFCmG7!5vX?T% zKqQ_ryM1OUfZH(L{(-KVl{s@nN;A*X*Ev9V`;6)c_=z#tHtokFp!zh_;8S6#|6*Zk zZ5;-_ySi#Wlj(ErdLE7#=56G40djBP6qDfOBS1q`N!>vE*8ITWMR|@R(3^SlAU&p; z2PPE+GOxPb@2#g-wKz8{hFjx>z0!qQds6X|-o^{Dq=|>Qe)AUD@oi zhSCHJrhyv*jjnJ=2=e(lV#2Mu8i)c`0bY4eX=dJGi70ga;m7YG3pX8LVZ6DD;x(_xbLGW8f%yjLy@z<2(FRo?=f+2=aP37sc!B zJKx{_4m@`;?eWr|$h^3BkbzwdZV*lq)v;lz(dt{gB}0QJY)t9gSO?PP-!`p!ost)j zl3tO~@~Dwk;>bKN0lSvy{^H|bYpUuevXczSVvBSc=oBHid_KcvK^*xix>6tDl^YY$ z5)OpR3UK`O{PwWbVJqs>hO1W^267j9-ggmF8dA$9DI4zai9VWW&zV#tGuFeM!Qfp> zBJ@7j%(n})MZ_GmC4^W8ZXk~caV0Gp&kZ&&j_mZWz+K1y{1rZDlDo>31QPBjyEmq8 z`ZT*WI$6=THXEM<8-98xP;sd@Ix{3#WI16O@gD5<5~4Asj$P}#PNDM%xK$_5V5D%^ zPtWtM*jzDio??A>`z<;vaT-yBpM~u>64oHh(io+a7s)B`#R|n`@Pt%rWqh!_ffbW2 zjkR}?pHi6W#7NgCKqJNjQ%Bs9erq;jfMoZbb+*#f<(r9L?|QS?)@PSa zC-KmyIv2U&9XpanM4~xiz^+|n?#3MZ%fRX{g2gl2F;guEu0OS%`VD0b*Oz9cHS1zD zJ1snqVa|n#L!2R6n!!RzTG4i1PY-O)DgHw=a8e-gZ-K44R)VNXWZ&FJ&4Dd(N6vD;-XaNtfnuA6Pg zJsh1b`$d-dPpj7H{dBvj_DY+^O6Nh)XJx(`cB)?9<|0lUsQ?TfB&1f@!R_~2t9P%T zdjDirqqvf!_??eW8c8_6MW?CxEsetxyfk4+9LoAnP-;l>w{+{itC) z&n3%F{Dr^9fOOk$x(<^J@%c+)-jR6O&<10_;hgUJBxtJ(oItaEyp6q0R( zMCw(;3888?H3)9%x@dgeZ5!^P`XOL&ySZ|WLPvJG<&!1MYh1R*&gE?76#(cvS8)Sk z7{!H@aHiH3Sv)_zuLgtjTcBWg00kNad~#OM!SD=C9iF?3WVkm?_4hsJ`@MSOU+ouBtEqVe7)A zma)7i55w6)WTtoP5&|CCN2?M66bsJ}LJV@65L*58_4Rgn`&|HgGP+-8-R-~2%il_4 zTXiz`-Hv$%EdY?kumB-c{|64w0PI+)BOutF#!wox;a*1F%`AF0WxR-lqZuX5GORg=Uu>G@#8cB+KA^F~>N88WUI}CS zXqFAYLV&Fisje)z!q?;lC5wM(n?!4Q1mLU&i#G=av`3Gi;hdhH)r)3$Ih?4rDa%Sa zHFP=GYE z8AUAf@;&n-;5zDVw#s@qQKg=@Si6tYq{21@Kn{TYgfp{5U3_>xR~LW2;nqm=?Nsqz zK#1MQ+BJ#qCYE{ituWDA1-VFz59NbtK%IX?tQ^oZb8Lf`w%QV@%W;~6ck9EVb_(zj zFhFSc2CCmD*Qqe(r~`x!{;>gU9lDS=9+yg!Jl_qFYHGGX*RhnA zeey??82;O&?Q9Dk!qA+}PVC>8t&*77nex$2qWN_hec^Zt16gJ^hLJTuQm5i;~Plf$WO1ooAq=4^^K`Oc&?4df>5RrNaj@JuDue z&IC9DppXGvQIXNy{iGy)TsalCQUK`Uw?Ms4XCG_E_1{Zzcb+15o+|qO)*<`D7pbuq zC4di&?hn_|U)Lf(EQ+A_Ehn?$X8rykZQ=M7IK)nvYF=(O!Zv{Mucg#_g{zfbzfO>f^PCAC%r*VQhhB ziMRuVt|EWd5{k$_iZ0&M7;jgXASU)TcrL})GD|>hLAQ_JM3(OwR$n;$iZlDnr{SGJFlu#M*WtR$Y)42xs|%7(veatXqyf zUg4A}Lru1A!SG+$7C2Az`Wx+a^2%@4ma_dT-#%Vj_?cx*A_!m}eS;EK=wD3y|DLdA z(_h!qL-=}~c3rcsf}{tq5J>-d)K|otX5IYGn0yvNFt zx$Y;9>qiF;0rLKSMt-U*GkdU#o!Ol!x{lmsb&~di^&3iBTxcr_YSgc>BYq+MY>5d1 zls?T$f0@RAEA1o0zW+->`U{0L7f|?tA%j#llJ=wdD4cGA8pbCrY#R(4rmV=FJiuD zK#0bUYGQQTgMctdj(AlWmOl(Wj7(W{8O-ypCC>Z`{cD;~(WlP~o_gUU+v~S4sPxM? z<&Eq=6TM9E5umJHjx7m3KNGc!wj}61C|M%%h6ABpbgI1E#}ySkGUdvAGwO_Ph5vOq zOFRt_^%oP*E<*qj{SGF=c+ThBmKV&J$F&ZX2lV{y*aa@DEoDe#0UqDa?u{^x{cjBp zEC>Vl2J9jsFX{SQDO41`OQPEYr?vP!_)$`HUT`$L@Ks{VlAwG>Csr{h7D6WdJl#KX zQhK`sgm}6o^brX|n13&hxH)YK5iLWyOmNu`?#GlI^4^~P>C)k4WON#GuTwvsA6wtV z@FQTI?(!s>NE{9%xSf1Kmnwqg7Oxh*lxN4+kfsx5y6uc+7932i?7>X;e$BD!rF+3p z<=BM6Pg0GUS)=?hGPN(W@GJ5eooWMzD2SX|N zoxh}O1ByvSG!17R`<2LtR=$;w9B+!?C|P$ue2Q0 z#dyd3L*vC*PDK_m(VSp~Z(}+Qh`o`UhY(0eupS8LB-=u;`0m*{q0h7=4s-$h0NuAb zdZ9;W(K*#}Mmpn25BZ*jn)}5Hesx`U%_QD5d4UwN9vOokK@sY>NPG&q)(}w5uOls( z(LuGFX3pABBhybj<>sl1n?laAxOgvasOa3idGwk41Tw|+#jW;cZhA}$#5p|^%dXGY z6%{%GIpanDY$!5#OQq8y?tB8e*33}fbmc8_N~~pVWpyS9j^$Vnk5*vvL;Rp&{yZ&L zdQO?Yw6fB0ZniG=U4&^e(F!QEI*=8(ie@QL3y=<~Td+(n9JVgb*wG>Bhr~t3_p}T8 zO*Li1pSBZ!bc=%!v_%_JbzZ=GmZwtp0HQ^RM6J*}zs2n8h2w@-1igP5R$Te1utTFM zUhF_~OdfaZHMZvp>l)`SdKcwM#$7#a64&hEYWI&y&Ug!(zOP*<2s=W|1ouDR_Wyb} zF()A_D1Yvxlp@dsvM>i#wM7?FLgF`R0NX(*W6=*Y(oA+Ugt(Hk)$;n4{t%82eM)E$ z?@bd7uPrAyO7r~4qt9PMKJYQ6B0w}gV?&Od{SZdnoa&-{Z);j)2PkN|5gA^z zZ9%T-azEb)b7+3hMmY9)bO4hex{^zb-K>_LeP8@S@or6BbV*^f+`#Z=RNRO>XB2!} z{}_%KX|D_hCb_NRPz#}qmWgxncLgI0wqe_kCHCz)X08Xr2R5(P3t{GMGiDn`FV4lK zF?h%I!G_6sd zpO^P(^6H8!L8UHfx;*Z30%a@p*u*OKLtCaY&6p#W*TAdx=B(8pCP~+~nIQNSePe63 zco%sk4}W#@moF`EDanSU;k+0kpi@E&~GClE8MFE zz_$+x{N4kcLe}bd*5wcLe(yj2r}_U?SWw!GI*J|vbriiSi|MDd*P8JPq{Ap??Y52K z>1)5f0K_iCY4!Onw5Eh|dGGc@)f3mR%8OXYY}2F8p{oydh7+^COjik&KCe~TOQX}+ z1>hl$QK4HvDQUsZ4$~~?T&%S^xvG!j%cNZp_B^>CE(K+jln5C{uH#mq1L-V({}J#> z_yOj@{FQe|908&*9k5SewyL8nu`wJ=FDlG;9Km5j(xo8z4Cuka`0S?XFy&>RNkN97 zUbR;kPd|qD4gIf}a`mWWfvHbi?smDR8}HI`GBEN5&bSqBoZusms#~v<{q(bjX5zd1 z`M$mxVc~Pee$(rx^e#*>n_P!M)*&RBcSufYyr9cFesL%mSXke5MUAV<_;UK#Hh9~% zM}Bd(k*gH~XlQXkRs~OgfOE>ri<{lE;P?W6>TuKAEL1Jc8je9w*VIMTxqh-G*d@U* z!kg=;s`%1h-b?nZpY}6nuHt9a9}iTm2FjyIRM`m510?cSvw2nQI$*b$^7pmBw?JW+nj7+hi*^oL6^8@zt|+u!p11<< zT(&4$pR;-eC?T|1MihZV*SAPnT|_Wq)2|DmGh(90?>%4xrNhRt^TUGl@4W~H*8jq0 z67@$wxAZN=XfBrqc(p-EV@lh>zFt3L>_$*F62jKG3s1h)D7eL_a)P7K9}Xamg66ss z-4)fKkp^i;gxt&AJWYW|yaY^ASkXqQHB1Uhx*F%V`?}K&UxBv4ih;F0KJFyVY}@ih zNk_iOw5U<@`d}c})S~2|hkq`J{TTc64?J7W=h5bsY4amI_V(Zx6={g|K)!gm*!4$% z|Cd;v(St8cq)fp6W3sPaCy6klZR4T+a=QDsnKRQy)~{0E^r8^?e65@JMIm+BbY!+o zYVNVE+iNjDUa>98Z6sV;wb^)Et-7m#<;;v9J?a%5u-mRUGP)YuqGvznL#JY3#bCQ{ zDC&mKhC(FsZKuT?TRz84l2+Z_tyx&9O9i)QD_Ou#!B?LTOJqQ(7RJ=G!}C`9cD8a8 zo%SOk%x5|{p}LH_S#A+>sr~0y#S~L3?YjmA1x3v&3NrH*6N=_Xf@*`-rae-+zqX=U z?&r$Nr?k{{ONyE%B*k?=CR1wtJi7B4uWkF^e2D?N>WzqsbGhMPs7wuNDb8^duMn|I zk(~q^e6{RA83G6|#jj`WS#t>*HhtdrHLzoe-(=RSwMjG%=fFY=_|yZ^5@*P3Z=tRR)^P%0`6?y-eJiEechV?Iyk#SA+sLCxp?)+<;;EhG9L=*w)F z-Puw`AYdm?bs`La6|wIa4|=^}XBLqSl^@3!U=_rvEyl`KAA&4^H#BBiy$}*KVb!qI zn>{DMB|x+J!%J!pRwARR*981RFpScz%v>M80Gb4&xxr;0Sk$B#axd zOf?Lgtg<;64YQB8P7RIUkD$#jYW^}8)@knjj_!kl(2h>HV_-0A8qR8=}A=lGF6O%`F0OcZ_W(E!a zKxaKDC#R+hZv=@_rgL4$E!~P92B8)&Fscjh@GcfE>(?a}GMtc-XW`7f!ae;V#^phW zb%(j27{GiU)8AgJcCET<`(nQ?U@Bn9F9gs(xI1O@v+!r4H{{OV2-=uU1zU+m^9GOq7~POfaweeobRdcM zKeq^Mk{4uAZT=5*1U9cis{!WQH$J~38bjCeNA#mTd0gFMbiAmQ zD_~nzP%CBN(kM-8?knSoV)w#hv}-;Cn6Yl3wEAgM7CpXMJ45?gO=hPNh$W7K;Qe8l zN=cmMAZ?dv__(0tLPUXM*IGNnkx}G3t5t_yWoAo0F)0$mb6r6_bjV>yH&lHt$BgR#+evh8b_oNnWgFUKgx7pQxQTR)@ z=!WZXje%b^;0wQ_VO`dh8y#bJU<`iJnAM#^&iM#!VRfXq>JQ3-(h+sh@fn%EmNINY z_h?)BVEN8YAzqNpuY^W>&AS`x=J|9N7I#w1(lDWVZh-8jYoqu|1~|w!M-r4tt+`csopeij%CC(YQ z=_@ibhwlZ2EL&Dq9wJoHU6A|JFoY?ZFT~_bDZ`VX51Nwb%|c%^@F&-RT}fEeb>m8G z*1(s{wgzF1*kA2~v|e_TO?+r0HG2VzNuB2|*{gH8GIadvyD$EWIx<7&FP+_omUE%< z9y!yxE_(h7zuHkNz}@e1bIwF%sN4lM!z(vTHX#a>eC-}Ty2e}t75Mr4q~GNzO=^JA z$s`)y3u@GxphKpsW1AZ$7z@kN0LS>+{Qc(wp%C=i`Q1iM85`YOuVs-2D z14BmI)p1d9_5N_Ef|jYfyExlMxyyN<2DPF=;uq#JC#+bnd=s5I820(NCAVjPM9c=D%-yIY*-Q%6~K`rk+Ha z?Fj9{#JR`Zdeg&s0N~o(i)1z+CH=0*hRj{s@~GS$Z*uUZwO#^^X$%)opLWdStJON6 zYpe9Tn3B2fG^tr7$40Kg#i6WDcxGqUgAgz{RsadK?bxj=I;uIvJ{p|Jh~O!!UW+A^ z)joe9Ut^moWldKR#*KuW&O)5p%gR|ba<#pM%K7uTvZnfCZo}e1sh*J%^vkHZT+?9v z8`dzc(fcZE+xNjJon6EO$gmHg>Yr_SPe`(=N6<@iA`9cSGdT)lA}S--KYYpJ=31+B zCUQC*7%5I9Att9EIMWbH{DfZ*W@Vyh^yU0iQ5ZO~aChD(%cQ$Wd~X`$glEc?V8<M4}pumwA%jxcvGJrw53%0F_riR%GZDfB0#MZ=ZmT>X!U(ONd6i;21 z=jRs}6;_twO6^Py3TW%{if%d~N`+%_k4ky=+K21w`=tVz>!(+b{oHH54v+y2G&nU_ zB8r$P3B6mX@?3-C`EmpIiILSwvJ&hkMD+}p?A0pVKC5-q^J~v9fHKS7RO%`zgS`4= zI~~2%nrSptZQebL*x#~Kog6jJjLb}66$s%a80gkr7Z2N-#Xy!?*H#Xpgh3VqVEyHQ z2QZ_d`66LUnvrb4}sfJRUc{t^n!A#WpC6vK*hN~}eS5WxTHPo1 zZfdU25Z%los4~olFNC8x#DzYW6`umefI4f9J&uLCIZzxGGqUJ?Kv)5G)du0Kg zfUCx68J>7*u*c~$&b+;yHyly7v_(j93?An)V?RAG@5O&bh>%V zNDr-#fJlaqEytpTG=Y%8UElF>j0MsQa^&JqrP11hg#ahPQAcf75x_RkXLMc!EzIoDr^xcO*Xz0|cnJL<)1O3T}M4PlJZ$YZRHKzr{T7Zv}H>{s<__ zJ_{vF^z(c27VHrJ);R986-mtSp&>w5^Q|tPZUbp4vtv}3 z=H9RsCO?W2>9UL3wR9gAvBhsYC`O<`vtyhTd_@xk^DgRrs^7FKBnvVK&v;A7GHhEwfb($ zAuOzVK@F&6$AxIMxUv)5ADqT9N%ja1tkASElhY@rH^JeaAPbI?(y5%*2 z4Yw$`kpqu)Z?g4I5n(SETzLCld-#2IG0&2!d**HU?PhcLhgr5Rq{`*~!u6pFx{7Xa z&FDEJ*01@@V!EB)*p`}Q)BCN==3$FT@b{e*eQ;Dk{jlod7N|-bep2dHkC*wk;LL#^ z1Ve)QY7UAWD%;H=l@E8(Pxj9Ku=jVTlVJlk*`xxFm}C%K-?6CI0N@XdfZCx8c`|ee z?$iv)TXVm-Zxg3jw=3ajW=HGsE(bY;3_M1~6<5#r)7|fq4JbSsJ2doi+=r^I3gadQ zfm2OKPV3IwN|0KI=JD-DCF!ZFwAJzDN5C-euZZt0EFZ6#Wz9O5Gmm{%M>2{cnuL|b zu-byh;i-@T&=>0d@qmC`_6RWk_6R`F-bY~0<$8Sx?AYM=Nf}5#AclnmRs1LUziGqi zXfM#Xl6PJ=V(ChWk|TIaEAKV=JfC*2OPrar7j}p*s;svmHNY<2h}a#?Eql*P2_)c+ zwEy0D71WakWEG*j!Gjs$_ikI`ybt_h(|Ihg9N5^`d%OAVU=jOm+w zCAq-A+OJ5z9pR7npyiALDW$*kyon6n%{W;vzzSrFoJ^cB+HFx?cEGDB$xv5U?cH%# z9Uvj?m9_R7fTQGvi|V%4$tkw{tg`T`X?fq;+S))iOfVW(Vx1jiJHL}qFCGZ*iSHl= zDEjr$UQ7|W%z<^hZTdJXw7RxOc@IvHG)rE-CX5xx>+BTyjY%!1ypA(gO`X5uOq|QC z)BPhMN#VePD5WJ)(tICV1DCBBpg`r)-yzIGLB*qGwkI%syTW&6W$4a(g$inoDsd^t@5u_ETx-~A_5Ze{!)YrFL zG$rQB+;W4hKwE&OWySv2Ts~ree6>q|Nm>*_fy~j$#x4a?Mk6NPeV^doE&?LNvBBXt z%qK&M`ID#O8VWjseeLz7$OqJRHGIL;4j3$473csb9smIG;k?{R1b?GoKX>wyfQ0`( z6zFj+HRQb+*Jg!A1k|y%?E)_9ik_+{U%J~A=0#@(eRKclsRD*vh=T0hC0qu~eD!%z z^>+E@U!a2r;hr6az$m1P=#E$=XElG5mY-D}x}yhKs@_Z?zKs}`Z({oxxQ>D3<8nkS zHpECoUv`YAHm(4fzEW-q)4UpWjw_0QF5|wBbC^d;8LG_zs4wJNQ9`d zVSm^B&7-jky^PDI#6*Xx*Jy?~4_l!o8g@2m+LLGq-ls)Dn@z&sQ(WI%IhQ^3EI5A811b!97j=UFupTye8e zxq%7Z4QuK}J4A%7F+mo=x+@)2dR<>1=2Kc~h_YE6t@~<%hJv(bQ5sjDFZxtnV@`5% zm4PO|eZ`?c`<3fz-{|ck-0~{cNmErzjmy-stUxTAy%?I!5G{9TvhB!_Z|3R-80{*t zranV%lq9Q=zQ=$k1;cA0oSKVS=swM13xaPvxjIdv6YB0<#rQ7ug9KGT&S=qCi0pi3#>eFYBKRZN zMTMWcv~6s&^;GoK=7w&XjyHOs!+AG;s|Inq3^xskOk+A?j=cTs3u4GrqH{I3s0Nd% zon82+@?^!5$hc~*@=fOrpn^4}Yv+)o(Z?gQcNR-2dp0O0MSfF58;YcK+N1Q3NZ-$p|nzoN+cecJJZ00k&sn3z1?Ag+Mr_2nE z=Xo0${GBxTJ4!bef@YrR{PU=vo{69=Xl)RnR+WEf*U%hBqSXac5?zdJ?kZ1fY-MeYWQWLUY=2QQO$o4zE&kPl^fTuX zAW<;s(z^ga5&#BaAd8SpPl>AZ%t_5T?IN{$RVd(7fv#RGJH;(au?=tQc{rcd1hD4S z#6+c^g#v8x@n3kahqeTv2<-BX3CB|N^UL%R!y)$i-Qzb{Qjqd&Jrm%)UFaZEh5>^i z<)#$4GR8f=Rp(#@G6tdpUA9QmX;xwGVTVy6ZpS{nKWu-5nXVl*)!x(Aoh5*YR)F;H z$dbCF07$$>*#iPz_a+@~ZCN~+NdI9SplwV=v(Vo+a@!sKhY>(Ej$nqL-5T^p@wcD| z>OTp!`s8w)*Ezoc7tk{89#*)Qw{d3^-!jw+jFX9^s<+;Ri>QNlFGoij zF>Tak>tHrl(6=LiKE`wz*yNYId*(SMF-ROckTpKX>hsoC^apI_xgR-40B7Fdsn^Ku zWFQUwo|V-BV=03*RhVuO*A=FzlR4PRR=(9~_RTr`F>c!8>(k6%5sHv(q{y`>CM&DW zccL`n!{OAs2{8%ua9_1_vq&p!U55&dE|(MYrwJM5EY;Ms#_*WOQs(T~S)DiH#)u5M z8}bBcb#%DYXMe!Qx3(?gW7@iS3cv-%{j{ld{HPwFMK{~7a8FpO>cB2@nqA{s!b1$q z8ZQ4{Q7B7Jroq%GZv+~JX$5aM=yLN?P`^vQ(tF_;E!Si?NYp2of4Eb#8WZcuymU8X zwI)*hP^nY_ms>%)hfk3-cvX>Ib+?e8F$aAB`4}*Ipj$)}qgSUf88uygq&lpmc#RF0 z8P>?PESkT?JGx)Dc(3DH!l5zxgVmsO(!-bzgxTGq^<67Z5H|0;NvJM+_LGzkg7h~R zf2$8w%?n`mv`=%tA|C`wN@uEueO_e9PNL^Pp9&Jaf8x&NCTV{8$T6B@3NB%*4Y8X+F-8h8GN7|SQSp*g<1n`ds`Y5A& zB$nHkj{q44_rKi!p=9sF!$?7I_xOVdL%`(w7|D!O7|Aydbb_-3-6`)^U?$%;tq04KQ9(0A{tt%9A zx~CUSs=p+9&zTdrY63SK)dFO`w4bn^NL(@!0)D#GeOPPx z8}2x=VSpg*ceeW+g&#Cn{BpBqzXqNZGgC=dBKGi@VeYoSLjnfWe#v|Zp46;4ezMx@ zVMaEe6)1MGvCpCFssCha`ZBemr4p|rp3U)}t|>QUn(fVQ`QzVRFaD(E^% zWC2jPjmdA_I4oW2%PSqE?+2f(H0(7dUQzAc!G~Vl+!fv#-~X_`W2TKc$lQPZyD_eU zv>;n#yglHx`pHX*fTIq{-Z#e?`@zCB9&5RqQne&Hm*}Xwr#A|h9XH2Mb{!AW{;G-? z=KB+M_s5Nb+n*HC*NxJij$?A zJqsbfM)d;TMOb=JEyP`tq3*6jaeZ0ytN)3QvvybLW72>44cg(j)rhuK3K6VU_%*i< z`Q6OlxIOL*_>Bb8zqRZ&CVOs@MUdZ#o$}tuUbbZ~v^Y*US3tiTmM>WA@Holcln$Vp zPd!m*LBw>6kx zzWPP$(yyo}#x*wzIm??@!F%%)t8YKy#W+xTW%z#dQN2GCy>zn@+QUc;KmLL=QB`r= zJGvZWN9C1%2W{;?gkGB{f2~d^_c{Rl2$1TlX~WfI;8>C|q!QXwOoI8D`tgpNtE_E& zg)wI39cG@X&RXF2qIAK|(2cc&@O{0Lk&eCjSV3s>&mRpxNlE&rMbVn|BX4jB!^4|N z3k>g{+Gl%KP$!Gl(w@{$Sb3Ju$=AfrkgmioOKx_cfRlwwNehfR@F=AEV!Q)=v&5H? z4Jpa@43h#L^q^fc^UdK`7j7YV1mu}Yw{{ASQ5|iwV82$UlgoaBEG-pt5VEf(T=OK5 z_ou)#3l65+pM8>+Y9NPpKjx|X6BRdapWRvKEg>5+{Cs_<@;f@VCQ~)=G|-t@9j;jz4ZY3>Y({3Ens*YS`!7%Fx>}yB~ich7qut)R$dBAOU0!Z9Vd~VIR4SS0P6eJF=!=C zbbAC$R#DV&LcIo0-N=*8y?;GXmDh$#jzR-X9thew?f%2x!7qXq;?AE7PuUSTR-O^8`Pfc8KlXzwX)X}arxUf;%<#=D^KU( z6N%9!!O_t5g`X2EEUZAoCu*k*AE)d`WVdLJuf#mwc$Zraz~DvSY3+Sx%^cF`LT@Rqk7!#_-~JGx4Pk>Mlpy zOdEU5%J3h}9fgh^$!obAcgY7*oD-MMsJmD<+HNBm-Y(EWA*||5*j!Yo<=Va^1brDd zUO%0Pk6(I1oh9q@eKEhOrvP+F7bolqPOh*B1GR=dC!85tPo*V%UdFHAY!Zet{G4ce z(XnP&(SOTMnOOrRYL38au~1Y5&B0mj`-LB=$M7sTF@MJ;GU3aDsFNqI)U2_k-#VBs z?itbxLN7jXd2iAI%8Zgf$a0c0^1vfJaJ@+QcB~l{%5Z41dTTwKF$+xYYeX;YG zv%_`-+e0_{eRG;M;jV4gF72#q+xJG3mxivOwSu<&3XY=Yf@bBdA!7Cl!{oi-(ed)@ zpv{*SH;QgUt6I>?!}eTfeNet&kX-5Go{_-w8`aD4v6bJ~M{hLU#)Un>Ym(wuj1133 zyYlun-_AS&KD#^uLdGtGeq0L9WODv|Xz<6!oNoTqR94s?>mxHWr$=7aq^dq4YQy!? zPFF!g84av{) z)MoA;Z=uCA$)ZhY)HOH5moO(8;8vbf>7G;yN{u~AQkj|K-Oq7#;r;A8Wk98u`@W)7 zuhsbEK%McUi(FRAG=HwA%+a|zt@2JIdyAz7zKrp?X6O>QU_KxC?dyb_gCWO=jnR67 zv$*F@d{~XsMN*?c1)P*-Puh@0dN}wElQKakTqH|F4(PyeXPKnF}^9kDJQ>*d6P@Mohru%+Kfw<3MZD*lz^sZdi_*`e>}cPiUNxMmy}&A5;<9GZAtA-OmjD$x;#Re8k~-7E%fHNKeONdTD{)kgPQ=XBN0&+5Tbgs!;tY)eDKbCf>kU|9TVfc|8-CKp#W!(jb1hy@ zh8;iGc{@U{xM0bnkVEC~FZ|Fil`D{_wW)rO9eZ2t=nRWjLzwuj+n--r$9 zFO=E^h#mo6hQf~ki%fN?utr|X&>Z({m)VTcn(ygt5+gv2nx=HGt5b>{_5M^oko0rz z+=aamDpcqXf<|>=+BKFGFdJiVN;DtN-h4NpkXXtu*??)G-A^v63MkaoNY=wsy7^US zRcL!Frn+PuO_T;?_nppn8-W`^osP72@Q%-n+C&O>E4Fc2^z#Du3b-nm^?d|?{&3)L zOQsh7M(ShE3p|G;JBOiV=}j>%QgJtjj4Kn%GRJ#78+01uddGp}gYE%i1dBYkG)@yJ z>mW?L+V;@p&On3`J+OW-Q9|^0RA%d;@on(SKIp1FZ*uC;a6R!$g2h+Y~WYw*iSHO5QH={OW?R~+WeNbGE5soRTtXf+SJ%J5oiv{bZB zeCujqwo4gJG0QDe9vM_1$E$d$Gtg~u+pyp=NXBN$jzKVjG@E=dyU8AF!VMSl(PpJ8 zHWB-V5`IzObHm0J9ag8lH=VN@#`SSr?C^~EvnF<44#BllGaj-7^V**E&<|?CBX6GP zJN@Dc8?d7cr2$iRtrIaMY`&mlA{B&?DME%edx1C(q#9S5AWt*Y?vX0 zDx|R|*?Q=*(&{Fnr{R3GAGGQ%CZ(J<&m6SKU*wTzwF|adiIQh4)9&jm5Lw`-r4d6^ zRU&54veS$v*6yY@c1Vt*TMH?};%$}f!NCssmN~3K{EQ31%tf0?5-t*SG2)==u$`3n zHX$R!Fnc*954_;Npjs%}GORbi?4wq`s>} zO?-MbY${h*qFMV~Mw$xiE3G!c1D~E#p%^!`w!zNip@`sOTZBIUCF_YE&km?cCzqOh ze(tIWI#DQq77T1MHQ%mtI>2GN+Wl-1IZ7^Xo?5fVF|HKdbb8!59gg^&*G0%#m047B zViXa|JqFULiL+f4?VON7wvXo zv?|>~f_HNG$$+C53en&ssd~(27Xy>)XX#PWTDaVhq3qgAXR*HU8MbQ3ZMpXrmUc#J zXQ)6s3e*iv;`4p6M;!k;N453)oz_l7=##eCCFFKR!O zF&}g`&p{TuUg-8ao8olQ)He+cJofCqBuJ?3cl>C)0rXnlaCHc)ptjD`qJbe^Vyf<2 zHpUQjck`<4QKOyNp5r$RI^$s&M#OREVk8vji-(PxRSte>LRy{!F#W&Sdh4h*zUbXM z6p9orUYue@i@UTyf#3w!LLsIMg>RXhfuZY6uv#xk)1kHxlnm=Ew#1yLu?!)krjw!Nmep&&Dlk)Mhs5BY zGrW~=DYtJW{PWX#UT_$>6S5#(Qs1>L1%mY|^SVTzd#ICoT0;ALN^ZDr6uV>~cyuae zaF1rFs?AI;Mu8TwYdW8E_LN+$Vs)mwZD?`_Lk$C?%2o$2u&C+p&F_|N4UTmFO>q%YZ7 z-`WO83`kVqOtj_M)uo&J!}CreNfik$8HgFAF06x7SF;$AS5PiElcTlD8pcxs>)7>d zuxXhXTMG>&pz&j%I3p)q0VhbbaG|15!FId}v9rpR5!C9tZgtcyG>)rLu+AXZ@s|bH zs)Js`n~C}qZ)Y(svYeeH{`!|ca0G_9WPux;Z^BHHf&^Rd9Fu(nc=+qY@dcwanm6ZX5<7QM(JZ@3-(C zAB~sa$SgpDCIf@{umW4(#AHzj>wZL+a_35SY~D6$gN$%_0FjHkLRwa8nA&zG=$0M3 zh1-NUsm`czy?ccC>oZtGtGh8~d3c>H9*KuLF=5!?=XV-3!t-pY)tF6D@xzAV81e&l z4iQ%L;_Aji5(%QzSL}Ptq3#bQYH7+5g1<|Zy?v8KIDrRIVzwX+V6#nzNu?f$KaWcR zxSeYC&I9LH9ANu-nSy34yAjp2G5m;nW`xpJn!Qh|ox>V?%N!rQOQI<8XV}m9&Ot+X z5>z3lhY#?FQ-7*yz4$XH2FtW{^jEI{5`O%ZNU;wicW;RTDN&ZEl>^Ut9OP zQ}dOy4%87+`uV1B3o?w3EX@?w!$%Fz(n#ukt}mNo`=Kt(adzI9?P0ds zU09I7x)Fya9rM~B`YBO@ZTiA}LGbnV0iBs@#OvaDM-r%ZQ=}`@l9&7l8L5WRBxbTi z4YMW_DERSmTCbV@uA08!Qv>@_xtVPxF&jOe`KreR!iXBepK@WwE^AaZLBX*OnLm z0Dz(4-7hcZZW^al)sGiE|FotTMi<9x4G2!pZ-jawkik375&!QD>3{iB)Qwf2`Dx?lV&)8XeE0`= z4Hx{yg!{(i9=H&~OJbCiEhdsO=1s;|aok9{43RhOwTNNwQdw44$6}$}t*nx}ZV%xR z1$~nDg928Z^(uB#&+1%L&5Z%3w^5=1cx4<>UeCQqWWW8PXFA1IorYM0 z630+p=yUh`F7YJiB!3V;@+Ffa*YkGXh~T0-u3#Y>N@FG*M|1QxXC$IqE13KJ{+rIM z{#77$w-*JAQXYuZcG$3D!L}1>tCL4;9cIp)B?atqK49}O=w^+hT;O;%6UxFJUNSHk zd&g`-68-GM>Ww88mksZ^YQb*Kugsy<1&pG;b8?jxowqtwy4n;ila&s{yQ`) zQ6L@kfMR0#6QX%`d+SpXEggSeLC1QxL4pOxZIRm9X*Oc(g+yzwv zC1Bf0O!^{>%>CP8E!&Vp7zKLYu~@8CL956Pu)*=x4Ua{>#ky?-gFAQu!!gx@Us&na za@fYfi%87gJ<)YENQ1zqTd{utAOv%wQSwxIH-D|nxux>ND?ER-39RMP(Ty;sYkaQc zx(c+uRN~`ahK{9prpzuFwb^5^>J>Wb74q_T6&hwP1|e|kjA0UzR_+@nK}sTT={b(c zE&D#umsr^Ccxi01uxBEYqVv&&3he{BYR?Yb?sHUE>Z}-X>oeHn1AnEWpH2cdb89GFrCla zil=D-moa?`b_}UouFl5BmL(7VpMu2y+T)^A;lzRfWZ#D*m3ULvy78`vWPss$Ovd;M z?x~*!UX1Z($#eC!qAIw^I*7ZG8(Yj z$CoE^1DVCy(~z!hORR+ED+bP*39ns$SX=LbN0KSN(lhxOB#w%z3{FQ=R~o*CBowNe z#NGA41_F=tWUwfe?<#jG=#&gEAA@R53U<)t(&8t>K$=2ZNtq z0`ep5mQ_BpM1rdVQMX>#9Y7w1|4LcVxq7zHh$wi_7*P9cjhZq3B?W;UTi8Yy^LcWD zP!j97^T9H_K5Me}oS4ZgJe`Z3Tw&BWAXck(p2d=(TMI5(NR^3BBcIhzVjJT{T*}Dk z&9XGa&|AGAMvn2hAa|5w4-Nd&~$JCCg=zaEGD2OAM9vGD^sh&u+RekfaCnQ^N z=lgw%dmZ&3f(HnYDm+J6X;4@>9Sc7OxdmngammY2lM+jUw3`Kq)k%fMZfQwy-oAPv z5TBOktWQ7#ww+3_kG`);z9b2aJ3+XS=Rv>JC3dGb?&l@+ZN-_Jmt&cqes`iEa$TU! zc}pfdNym@PDL9cpDoXI&Dmg5X=O#pX^qH-QNAQb|GH2SH<=?ysY$2p+PI3&*sq_~y?j&M^tlg&KivpYD|Rg2c>E}Vx@gZM|Uoq2LR*9?EZTPi&bn6p zX&26eGX~hlb9~~`8Xofl+f=?w)h_oatz&cRPT`H$rwLv~ZTHd$O%;4$B`lhpUck-^ zjgMu!U7Q_dC=} zn(=>9=w|u=80BEwTMMOcEc%Cyw#ozyZy|{%~d#5b}ME~v17V})R8GSKR|EP`Q77t>0{mFSBYm63;oZ7PmE)*1gYOxktnj^PU1xc^CZm{E9@EsZna4vXzQ^|j0K(tT53%!EVQEM$~WjV z&;@dNN@8m+_Q+1YA&~%4qs&yrbFSblaY=4m*GyjC2~=QPjX46&XB0up0a6q$Ck6Q# zy}}3Y!iGl0(*#ps-?(4$Hw=$J;q)xY&79_XnTATYGz)LWfHW10+6

    2_zYVsu?Gc za=%h07R&XU4g(lg1!CODflV&tAv}TkYv6kokfM;9ysLH(^OVy1;8uM2n17-xy1SOO zkZeui0E-xT=$t6l&8w2Yg!Drde4I+Ye*h9MLgeKaWtbrr^YAbD&#bgcHLObPe}HIM zA0y&6eOJ{zW}dmSVZSo>rEm^M|pQPQ}dCF zZS8-RKSqwYq#uH&@3nPBUQJQd{O#9(TgHklC&h~{W85=VtD8^xr8RF(`TXekK6JyD zeDEmCOOW$3P>yXHTDYEKDg3;d8jfbs@ekl|n>c874;`)fSoasr=OID^?wr0p@`{&* zYWfZ;u})tt5`cOnz#Eq5(A(RXlRMH}kP}x|_g=uS0fs$GK?vQS`9D`4txnyDJcOlxo5{+@EEYa9_ar;);igoUrMv}?e5BG=o+s`T^> z9{Ud!5*%NKc%gWP1+Cvc+=h4gSzE zbyhg7TE17ATQ*}5eHUu%mGRli`UMK#=Kqn_fWLM6Lk^0)Va{(ApmSB4Sq0c_;Jzp~5Hj zRZW=!Gclz;9|jUWZ&GjQmC{0NYo~JeocCOc>g1J`Jf|HkygLZqeGGW>hF^V+}Mw;-H=B- zrWDsZsjy!44cO-+t@bvvQzQ1-6F4Ph^0zRbUXz#}Re;H&HHd@W0sDz?)Y)unywK?oXY+Hgu%h1a-vufk zI~0X@L1F6Pc6J{(0v=K?Hch4)k(XX}1)JLne=yuh8KLbn^dm@`)3e7H(Av{nt^lr+ZhKx@T6XhhdA2o((R!?;9~G zL{JX5b4j+P8*Hu7ew#5NWf_z$J?Dh`w8ilV8li&-=#ZN}j4r*;*eY}4;=S<|5M58nI*I?=no5#W3H$R+J#G@_kQ$OX_aaGH z(mhv@-r)Ig!k#0H*r|hDh~+~H@ZiOXwi80lC0$5RO4Eu)W=>^Uv3(qdi6eH3>sD}W zk)=87neH6XA^E%pIrsrRMca6>MBH^yF9Sh z+_FnuU0p|urI2qx>E8aRpvt+?l(Ksh$tK|~wD$bh|H`bV#Fj^2RMCje{s|kj(nh}Z6^alV9 zp2dPp*|+!+E8HaeyJ_EDW-f9?{{dl*f>%JDI}EPya!G4hx1I#wvH2UG zj{JIj>8zQ?Z`ZUuo}cG5XB7GH5YD@yduW$UOy^~EvBgt2W{2?_0gW0!x2B~74xZ^t z?ZJiD0d2UX}X#U?+;vpuFJSWAWGcw3?0fJQ)?F6yB{Nw(L%q zIz1%qI2lCC35v}$g>B5LS$qT6i2>@;`p?w_n^!z}*T zac+FCKH-y%<`)yOyU$@)nopuRr!5gfRq{ll5j8k?ldvh^o%9cIFPiud&`NkgYRc-h zx18)$Qo#y5_6wT?wGFu8c3ml!xCNTmu>AwneZF{X4B`VOgCLJGTX)z)A{4iW9#4sa zLT9F?MfnZhetv!i_lJvz#pl|Sisw0JovxUBSUntTK%{eUn;x!o&H;4B&_C&1durSf zifx^;-U!+x@UIp*9d5Dv!ZBRszC%VsRi<%}ZckmGqBp%_@Ap-U20ZG>koYB}({23) zO4DBCixer6jyKq7RcfUdynWf^rn=dn|Dz^l%G=|MngznH^#+`9qjax)FDBlS=l$nD z`y_^Wh*${hJ=HPYp>nI*xYhw;k@}|e)^uBGy=BJu&{%+8(77K-6Fnqx+M>#3vMij? z+y)fj6R~PFidv{OjZ+fM_=GFGoh20OTwzJem=Trku2HgK=orwbeqbCT0X57=7+_)! zE9cPA0o#OyL7vOqI7*A63SumNKN5fnsI?W}atN0NvsuBcK}cG1KJ8HXulHd(HAR;q zU={&k_NjeehLTcU%&Buc9>e8E1`M6B}h1S|8 z5(4>>_xc?|&E<5A!pTA;PN_a*Ghar~Af8BvEn7*!26bnjuEV>B*0erq144epKS0ZC zH#W7|+0fiuvX7S*+Enn@hCZ=UZQX!=G{eq6OuIUPFwUxJar?M~;eja=FhcvoOIxh+ zk?6xQ|Lg>kLylG+L}i=9iGWmI#reE=I;@`pGuj4{c7?sF!BbK0>}%c;s8W5kIDaHc zkHK}G2x$4zQ4qVLMmtbe)1$9VMnjgGm#Ra#MpJuZv(`VS^eW`(P1h#1Aeg^=Zl-2> z@vMO`Mu~mj*`=iDd#PKDkGuumCZVkdZMtRn7T3_2-s3+&C_!uY8X)22I@z;)V>7Oq z#DZz)Q2@c$={lWp70})XTEVk`05gyGn^y6FTOyA}UYOxc+PJ>G89@dCCfn7>#2)P>=GLGco|Is1-#BN+ z$C4lTUnUI<_jGTHHox!hW#QoQi?ieOvJ|2OX1}2! zJVf}D%~#w8Z@zO1cTypY2$i`{O8NZ0M1`8MHAlsfiTXQ^G1^ATdF5A| z&l}D!_Mko%{{Z1;T(!PGJS`qq>N6N|qp{srk|pbvWJ6Yb zj-s+bal8>a{Lj#yyMEKPJm4^9BH-26nrdn;{cg@f^X_xmb<0!?i0K=(I?~w^+T+>( zBBC{U*n8lau&Lu7Vp|Irkd{jIKUdSJIB&KR8?F9_$+FBH>F?V+N5@hg`{fxuZ@R9< zLkW6%!-e~vnTrP=I>Q_IsL_wSL%k2;GN5)(@=2j^J^z!bApYWvztw4Z@QUwglS@Y& zZ+1LXX#OyBx!LXVOC+<{Wm2dSOOdX!JNlL4I1}LgC=H)(AdrL&eBGnhWFR>lb|@Eg z+U)ws!k3rh2RgeIQdNCxg-Vx(U`bknsb|d1@t(7|Oy5ICl-W;wh8JxCol!E;@ptH7 z2i6ULEJ9ulX`d_aAHImkDmNMemfQ0S?dy26U-#ak`0iiK zvIaA%6F5i4?b&E%Psce#&qZjCy1}FLG;Ky`hVHgJNA?mcc%1PNCnbLgQt*1p-3rX2 z{N_lC4>@J$k6Z4^V{y5&>X4NsL(DhRw7u!=n(6r-NS9x`DrhPP6W{CksMa?qmiX+Q zv>s83E?L?w3CSthjBa8KAE|Q==(3+c?bY@(Uk7+a(~NNCnxU4W=EOTF4lW(qE3kv&k`PEHcBAosvwFf{VC{0WwRsH!Dom$mas=~b)JA3fVR$P&X|%2?#6p1jQccFWBHcsc|KBpY+^Y|OtbPQj1ZS;B3W zm&#s{TBRJQ61^!~O>p@K;1-&fd8r(vykkhUWi&ZK#qmYUBLNS9Wt=WZu)Zl8xy}J< zb8i2*pZ5>2+u>&RO}s+v`}MeDgf-B$V5_PnLgKX;^EfWQ#Q9zzKoaCPiPW7;S0u;R zC}t9x`-V^1xN>q~{)=kOm(zH(Cvz#sds|<;4Pj`{0<)uMu5$BOy>%1oy<*NDy3+wy z?s?TNfB2HKrSDv3+X;h#1}uA+GHz%})P>=R6dD$@>HGfxdWXh6+>J|Qw!T4lb!zDO zF@zLKo4gYuH)U9IA_yrol+{=Jb7^7D0-LErWl3>L0v*=6SGG!$x%eQ(1Oa)op_TT(UKK4fXx%KO z89(bk;~is_yy*xBy=iB2JP6!1wyYw5N;)yEq_UZ{TP;xI>!I3{>ZG9CNI~qS)8dwM z-{vyS9K_afHaBCa75e`fbAu*fyPh*Sa?ZVX>`y(AU~nlilerLkXLzrAKs@7k>4aI` z`av00)bvVjgh~vvr4#z}ELy)O5KC_=NZ1$wDtwf^W+_I9mIVZwmX~|2?xCCD6k$o? zxzRqfLB0(y`zLGx;+{&!q`|)&cFRy@LXC(bzfySi0N0h0*==iY^C>71VH%$}C=DtT zP8P8}HnltSTZ`-&iJdKEgG=0?c!29nRHfJAfnoVJKvOIYCIArIrEG@_}@{7tI zK;gh@j(wtBm&x4H3j&?AA)KCw|cgJxwEX8W1F&R2J9TOite5_0p6& z(gwX)B%BB}=qdSs~xR>ieZ%J_2O>0-i7KF0@U}N^~rqCY5O`XN%6`8h_3`hG&lqxXq zFissRodIEa64O?7G+XQ>A{CwrSQ43hi-U$_k-a5m9kaCy3BE;>Jhfg8k$v7(Zt)t% zQ!_Q0{{R_!L97(HulO$X>7u-Ld=z2#Yo+^kpUS`R2DobvZX&r{TyVc74{o^z$j(G$(msA9ZLk619;Q$?ZK5K(|#JSBUhp&W^Vt_w(j!(4L8Sc1qXi z-BQ~ew|*fsMk!%_{On5m%OdH3C2~e_3jZmZYuwwEv*RgensCD#RjpM8r}+Z^BZZ}g zTulpM&j({{tKqqdjaO!$Il6Tu2-o!8*`PPM5MZCGn{tgq~;t|Y6{CT}+K zK3(n+U#|Cum}Up}Q{-&knomh?-Jpp+k-J<2m(7mEeZ_2nk>_PWc?tzC)`0|P~#_?+0{j5C(9QNSM%YI};b=xTqK6(-sdJt(tVB*xwuU7uN#qrx!%JnL)H1qb=@CN#d%B!cY9s2IjdzMIlc-|9o=Uy{NzQ#H-={6vT@O`WG1-%~|TJd3<+h`PJ7i7OSeRwUC zujyrWu-o}WlE>_Gjv5Nu!8;*YjW9oM+|k?_ExMpht`23wedzHmNa5_5?qea=wbH5L z;A2(}p%SC-s*LB-$H%arK`#jRAt$%MhItg)dmwRx?~!=ySTfRvEp+0I3GRJ<dbE}clLWI5ZZ?pV`D<|{QAM|`LVIL0qqT0-9CM;NdJ*39 z<`uhF%E3uLDu+bE$|8utn9&xL#$@3|^S_sNf0DV?4K?4T@kg$O+c(Hi>VEB+b~fcc zyTa7z<80Jja{TsOO!+b7(1gwkx?NynPP_$icu7sVPBLUC?D(Sb+Q=iI^dEo}m2uRm zscrN${41gR^ad5ke!gT{-yf8v&?4ClF6jb!mlf2H5ybzw0qZSaLW?s(<0}0safJf1 z75d;g2UG*Z0?Sp?WTpXXpU-f^jW|^7E!TdJG}t|!T;vk9@g%4#XZB2gkk4|se6~!K zWWK;Pfxuz1`X3O1=b=Mj`^{h>cO;=VN(zH1J8{bedCAezg5}m7-=k`?zh~{8vv>x_ zD-c^8nV$#q8<7~*?4}+?SqPO&-m13nn-IC6dS?}~zPkXCtEheXeM43{NBB`+%m-aG z)E5r|oCiGX)r+Z`5%dczBW-XlBdx{qT`?Z1X%`EdZGL@Pu8`_9$QDP*uJQ=~jW1^k zhI(tT(6kvBIDD3C#A2W`ndI_T*DLi;E%g*d!*JATjIS9fIo(~tS7BdefH;fPHxqU8 z3*YHz?dq9|vy<8{A{PCWV~qS-Hj3c@9r=Nc+ON%aBU4B~v#q41-j{$jmQ(}?c|u3P z23f3Ag0Sl+ecImauW7c}HQzNnFx9j>Ln*)BxOUpJ6xfd$J z!o!wY(gKLtJh%44*X?D1Q&@!RsFT^B@jca18v-A#8xqJ?*vcfyYLn9aP{}C)^y#keb9||Mvu80On>=D?4+jdfdu_V; z*+ab^t&+n%g5*($U5w%}W-KO!CEmkEP?NYFaoKuh-tr_!^n!9q?I%?i-uWVJwkdbj zBIQ0R<^RMjl$uQquPp%%iLlVuzTZ*1G{qVAR<)o}=q-5RBZQtK+^9WpN$ zlkt0KU5RZf|V7g`jh0S z#&=Ss10{AV+D?ZyB~ZX6l081t0Z6^YY%_rS#>uN?%&-@$O@`l0q_wlE&}pADj|lMS zB6z!7MZ);ID6S2QyAR$r-(<9oSnD76|4BO8g}J)gG1*D*l=VAvLuIA*^s- z4MVWHwCz82N-JxoZBdC$O1@HIin=Y{)ezy{4g{YzUJD>Cznq5E5UzH)+>c#bJm#Zj zG}afOuE0Wlz4RX&SQPlp8owa^+2rEUHg`KJ>&1^6VG(3j<}H;ze6n^Qdtcs6U#Iv&Tq(kX|Ar=5u9I{ zJ}9DsAV4k+F7Qya}# z3_`-@Clb{*0F^U5Ot(=$kmcN}EGZ7XyhqNbLtOZ6o)z&dSzfW7N78Lw@$9Z9dK&xM zA<+H-yaOAWCyd^?PhB%T^xWiEKV&W|5?j)qn_jUP%>_^dj5Ofm7DS%nQ`81FGJv2>T*a8eB8|ctudQ8Eew%777QG^pZzUo*mX$x zPJ%vDUcX_PZB&N;+HS({-Bq<_?iJx|ijN|Kdtq}b6-#EBzJm7qDV^HShGm{Bjb9}` z5v^6IQ8C*~$>)B~)-l=G6i^d%_zj4pSE!}w_^@DlIfc5xF(r!qIj1To@bH1%Hj7xee})m=B7U0X$wD6xE~FX00U241><^jD+)i3!!nGZd+z z$o7|@KJdStM2w%2KdZ1}Y?y7>Q;Wg-bS;CbhKv? zZb|PLuFPCgD+7`y_K&-gt@I+!&g8_(WnewnW9}^lenhkbLvL1rn3A8%GZkZ$Ik>KB zKaA0_v$In6Yuk)r`AvfpMj~VQC1T9&F?}l*L@(YMa?1v+>q6#_ExojxhH>Tk)s%cPMw^R<{1V z6)R*}Yo+h5Rs+N zCiYA&FN+GR2-DGX=F!30Nke#J5qcS`1LSR0805*nUM|BXbk&^7W7?x1KYWk~OK$r{ zq*ygu*(UgbXofUhG^5`a6hc+pke@QxC6mF@!kTg;oW@TNS~wDX?5ig`4IAD! zc5M|sr9S>PUp|9?oY9u9?thTm@*gm|oZZN0OX3)simj<&q+dM@dKjV$qs@W5`3LAL zm6=c@zdqzE^whlWBOBW*J>Z`8%NcQlei~#UMo44fo%OB^Fc;;3)kKtj-y5}v9$K{W zi<$PD_FnMd3@x9E!3m;hG*o6kUd;UiONV4x<31u?WMV(S>sP>qxtafFyJS;+xYLU%>?h( zlaF+QmgrOSM3&b&hwGhgYoZCf_2_4J|J;j~It$G@yvhElrRZKk)OK>w|01$}x<}6U zM+H1;2-@(5D0pP2p!FsLX@Rl&&qLqL-_5*MyE1?8NDw<+3I8}C$B zq_|NFz_!KvD&CZx(&65>rqXdwi=! z&gFUM#wM75WoZinstl!38n*4Joz1b7lo-fg)A_6a|}=;PFq4?1Fj7iLa-B0`mP zmm?HYHd^baQHJsjZgiP&kJyHy9s4$*H3BpwXG)qU_BzWIO6<+nN_)2xKkewkr@HWo zRgChKRVv2;<{N^&OlN${(=)jucjF_A5csISaT~P@L7IxudA+lFX_**(1^fpPEl~lx zoDOsU{yX11e=pGt^3S=!|B47z`3*a&fBQw7Cth&H*srehjxYEmfqJbeW@q*(t`cI; zUXfes#LQA?r7f;+y7>CDe*)Ej<(TV+812$$c(!zZ5J<1c1>NmFKhzP=J=)z*bl%>a z)|i*sSrWNPy5b|#1s96Dev48e^zT@;Q zsT6i78F{Hz6+%`#lP_dHr9@w}h3!;P&L8^^*ZadWrlz>HV~zXf?L_+j0cNLG@Xlti z-ofhBMK5#=IV@Wzn>vC|Sfz|ns%2I&i(hWyp8M~qn81do7`^BzeJRrt__1(Azx^J8 zD}QTvyn_Oe4a=qLS2&qZUPq z?-4tRT{{|@hk$rA{##isMb@UGX}w)^ApDI*^E>M1w;pmPYw1yh*<4$FUpn4f^0-Wt ztO%yfhRPdzd8xn+-@9j@YYUW1dBl38yKd1)&|YTSp2jywmo^N2E^>O_I59v@9Y0o} zJ(cd>$;PsDQr)jxyz+{nQKd*wlIOLQjBRvX(9$59+nqPPcmzVN5~0(yP(iNtRuZ~I z#%cFDB)XCpE5LFj5!?4JD4w)pvg5gsxS7G4*0o|Ow;o6A37Kh%rtyIynNFkq2FTn+ zvZWb|a?RXTgd?}0yaAD`t!eky;fE90vrUK9hP*Bom6hKFN!FcE zs4Q`uSad;1pSVRA_Ae=Zb~tpGI!C>IOgkp(xA?lxy*`k63D(c>Dp|r_85#Xq7HjBf z4xfjA8D9}KuGBO+@iPa_PARj7*j9Ru2Do4`gfL&wACs@1e3QR6+R|7p+uzDVta7=I zctr4Hlc`>PY@WZxO9)`kVmFX=LbQs~B(N+zH+K%^N4cDF^Yy~&owg(DSvC^Ks2Ssu z+61lO*cPJOHHzeJwW$$!@gXTTICzA3$9F+uy6$90z+q5a4GlNOKRvW#KRvQw?l*;7)1_5FVCJQHvrCTlPl-J8M zvlpCg;P_?-Yrn`8)&?i77HJ5UAmF}*hlTSc!6^!B?E`Mlg?B|3(Bob{hu`-Q*61clUUkPA&8EorX331Ed_uq+pw5 z@(_L(IVx#@(J=u|bd#qD8fBN$_g2?wTAjXjN;B%0B9y0IBi*Z-X2n~kb%^J%m+<0` z@~wNTp&OkN_{=tu67Vm^ReC#kgQrvZ7?rV-*q}#8e8^(KLy^}8vAxP(RO?~Z2y_w0{QUy7@B2gya9+S)6 zo%r!@y-!3+QX^mFDl%OvVKC?mw%Q!CJo}i%3pEN8BifnjbJ3PgA`@41kCwftk@ko- zAnh0K#yvS&q1~nD&wIylvwmaG8+;@uATZbzHLVtvI3@E38SrT8>n)*u5nv^A?UC5G zhFc+Z+Qs;LC`FUVy__9tpzCp8!_ePqJB*OAkP4udV|gV>zXm`zgit+kVvPKkkyauM z7x+;O33kfdUkW)H;W@ay&Jj6ipaWWx#kpQ}^evVSPZx4(=$<x|x% zcVwRt$14)rPI?&~>Q41Pwo&NWWB#dLE{eA{ixt<``pt0rH`jliOf3yAdM}vOc}A4D z9m2rHbgr9&65Qqn^p*8nPMb9|DZ%!%YSX`g{_oN%wmk48CCwx52Am=uQjETQvG;O9 zUQJKc&Z($VJ?^oQpD=ac4B9XMKfT|`vtL^K^ z9|? zJ^2xe=ZgIXW)C92Y+V`BEiqie9v2avOMe{`nwuKM-xG*8QQl9kGQLWop#is^?}?u3 z-mg%6Zq{1$_nM5FS>e)XY&oBT@%D?MXA%1rldJIs)ti80AnnUe+H>A_ zeuFdze?|bFmVtD{yCJk^!GkyXmLCT*+7FM&5?WGyBtp&8ei4geuU?SgHp^{uV<=3X zgl4@P(<`49_q~O4owNwf)GGEW>OG+|p}mc-wG1D(#ejw=buGwGAFQbJT&}#SB+n>r z(bAqW@f-GOi}U=j8lcAJDz_|Z7C_(|Hc9)^$7;ejzB_8+&8hY>JUDvg`w*Lfyo=bz zhC`v-CUp{^b2+K&{6OXdf{BS|Qmjp>gfcJdLN;i}c-I%1a2p@#tN+3-Q<4kD7TNzh zl5cc--3KG^xnj}8OpWmYT& zdJZOfEG2dF6_YvrkN@yW;otw0cH>ZavF?|t3}}?H{K0sPuM{+~sBX=2=wk9^)|7)D zjs`tM-liwlAy2_z=KoSWy?B_H0eNdBxDFfgzZ`wq!^}%P%j> zoJN#X0LTF=h8wQ+<~t z+xo$g(4?y;!t?~#x>uTGg*Ky|rN6tC)Wx}J@HF2epUa)>FN=SW-))pY5QWdX=dy>6 zBrFWq+Qn+Y;EBnt+cZQ!j#K;nlGiEZrv%q^8=BAc4qOk5hHSDq6hBN(a}^ib*#b5U zU%Rl-JK8*#z=8t>GR#ufe)OQZ4S~(MN}&InMEW1qlvgj2nuR>U0NoJt@W8!ccFvQ{ z0bUS3S)0&qXpR4h+v538gL90y(tvo7jvw?N;Ju2Xikz#Lqz(vSEARMf)0MGn;CJWt zT_JOdgQa#cIB>}sj#y@F(vm+oWb;9%Tp2_8MHqG~vIS>kAGPrj*(Yg@Fl;!@?&VwC zk>ESw2QlTLN%G?3vxL;8H{hg~+`2*}h60bi+tOflPiHqCkE}gWh{+ZNxC@jVuK)|r z+~eD^nHA0z4Xz2D&V7#mspHi+sLG!pAM7r$)ogr?>r@V(J!$U4jYpB{@(kT}Lw46i zr1tKw5Q0fN1yWICzOL{)7=R$pz4I;1|-q%3`f_SlpQw>I{!X+ zMdnCM(R<4)`ON#aI9KqSGg;p4PBQ0nAG?$H59pEQo10@|mQuqt@q&Y6KzP7NWnC3{ zPBssPK3*f_jAo3k=zQ-AEOrnx#ZBH++QRFVN+HVux3Rrqc7XAtU5sCZYg9DrnVmL> z7{@NLn5x_lnayH`9HUj!v~cQun@#^K)X>6gfx=us=VBlSX5*aybVoiv7uJuul7_u&gbjZ;6H$1$)4w41wf!n zt_WUfWpVq)iHnTjfek#yGxy?e#jt|8$-Am?G7{HM`fvl{ed#!Dq8ljGt%*;lP@)h>SlC>OKsyA+9pLP8TVWzk+t#h zne(T4YXfE1uii#$VCD|K)6?B1iRbY9bt*cS^&Aj=8U2`9;SW!f2Z4^+86#P?^@M0iPU`Xd=QsaZ6 zhN1GUqLgF>lP3{_QFb70)(}&y<@n%4 z5PyxQnq91!?FzS=cK4lU_ASW;;ay5ss?AJqr_8e*zuG&W8H$A}eMH2x-mlq)Ge?W~ z9t8kCP2>F}>?3HceuRgscJ_t!vfZeZ5?`cSU7+E%kHjt5%0{iDty!plQsr!jc2a0( zG0|wXD$xzUtStFN`ekVMT4u$I$J6ABp9lA9VnvP~8cvgez!)Rz$)5wXItj0m$6cj; zmucw3(?)h;@jJK0I2B+Amil&OoLo+qPK#6I@;ds;?2RyeMrid~ zrscj>Di=1%b_gUVEqO{oiF+u@aVx|ZRZtMCSJ=Ab6)NOJlO*Sz0H0BH4W{g^9Miz! z^6lM_bnh34y|7fIfd%oIrOMn#!h?p>WQNHC3i9Cx=*#U(x^XJn0mwOa4sd={3RgYk zf_PWZ|Jdr}vFpsF_Rd(>vqg9L$ZT$UM)jbG+uZi8+Yo~fUXdQHTHvJ5V3m>ko)n^; zCSv5}E}?KUksQpwYwvE_?Sz)AU~_4@<%6|d=||BBb~ew-AY6li=H}M*U;^Nchq_k+ zY}&}^fVK&=RO)n76(SzdBk|Qo?*f|AGEh$2g~eGs?Vm5Ss-{Zb#-!%W5NZ0Uwx1*W z$xYM*cI(ly=0YZ7-1gpT~LNjk82^)Z0~-f0y4yOKLEcorv=A#~X?k3P>w%@4iHUbk6#tJqfUQ-`1X+&rt}hy? zn1H+<^jt#n$lS*k)jdh~RUiC+T)kyf8{Zc$914_D+$~UOkfOyQXo2GHPN6_?ch>^N z6Ckv>dvFa>+}+)s;ze8N&F_EjdOy5hCNo)Q_Bpfn%&aqKKl^#g^Q`RG6Mru~ur793 z^$%G6c$m#ZbK0g#k!A(|VVV|v{B+o@dg6Pn+PVw3)y{nP+w~e|XGk~kRZ};F?UJC| z)fGN}i~sTf`eh(NsV!^DNxuC}kR!kOpF`T;xl@M+754delO~d1ynUYC=c`1Rg2s#X zCr1iZXK(3_H1i=($Qq^d#)?2hJ21$xQG9s0O`Rt*+dt6#JN;dD=G)QX%INpAw;Lz$ zsm=qqeNak+>F>I!l7mV%(A|n|G%6-=VjPn7Hpo8EqkZ0~S$60&)xCWx%;#iGOgxa! z`s{}gn^VWaqq~0t+=Qg8m_Bo2Jnw{g0*~i9zl~am{S#V+e0PT%Fo*8vr2K>vA} z>odK^6C=UlHC{vq8K80NaQFJ?J%04qI2{ypisaGPdor{UKMmcupX=?(jJG<_^UF-| zKhLC|ob>Fe_2N^jlP5`PTya%Pu_<_fVBv7ErUMv||YUBkxfj;IG-NAzoo`Z|bR-!H>2JAcL`3 z9UxeasV}~Pmr|6JcI~H$mG3DXd~d#HuFLXQ$aWm5NRFJ=Hg!|} zQYI+KoKgFRFijEEngWU=%JKwfmE0G(Y71uBkU>>;;dp%BJ94{OIs-T*o?a@YWo}J` zafV!rV1v!?HG@;OO*I5f9n?ROe#&4SCn_e#X1A0qB%}ZpA>*fhNB8)tZKN zSumi~nw5V)XO6^uMAPoWxdK+=%DA@dyg5YKvKilJ=b|W@jy}f!?gPqos_Gq!PINq^ zQfY$qW90A2DxnE?XAF;}fIg2e#f64-^1^z%;>95z=3#Y7^eO5mvvgPm`(hS0avyMg z_O(xxf>|Y4vWpZyu&6X||J0hrW^nzxy=(s`!$R6kvlZB|(Gtmr+d z`RpNaOPFd}F%**hY6^g1(n?QK)KI`07Akc3e=0Jju}CHs#{Ghk7kVkBbmkvGbKxE~ zM&b6=Xi5?wozAzaxI_jEfSF?~-FE|BdMVlNUc)-^w%P~pnH()`cdl46Zbh2v&E#c9 z(WyQ-`!%u1$8WS)AI0$6H*T%4e%P#j008IJKXyyhnrqjo9QjzTq?ze*tWL-4c+iM! zm+@S)Oa&zZ&&sYdhYtn~@fYve*aXjN#}(tPl%zpa#fjKOkmAI5TtlzFSfGQ5FkV|K z#-fAB7n!lG_t}lcl0t>2RTT%1u*=8=6(TDf`&6`WlKGsx6$ZW$?mzUI3V5_$_NuK~ znzN%&EbXVDI|Jt;Txz2#6F|^O)(Nw5oymbzSCyiev~?JVqJ0I(UMGvjkZG#x*ich? zNIU}IrRkSh6E&B-Lls`{4DeyP>=Ys0rp2Sj%TdW&&c;3SyU6se5fSA{*@FdknPZaLt!cBd zNfhJ1lII2(Sb3V{IZD{0bLH}zJ zA~`_Z^HZED^UawRWZ+q7=bq=uw)2jA5bv+Y#D&%4++i=_}lbJOysE9gYGaI#Jk z&u3)!YEHI=q|R-j(&<9(`G@St8ISpRkdZ*brVH|-$_R4FuXp|HMo1@ISxbztd?oyz zWF|5G0e%?3I}UuK8H4$v0!18}{{gNlAH%IBz387*gjFZ|v_K9@1A)kCxL&sGl(eCE z?W=@yqNlgVQ8M8iMQ$il9(qsfkyoInw_S&g6>;a2&mV&dj3r)8hG~M0GKsZC{sH=5 z$^LhSjkuHt_w_6!VIAX9dSNo|)tb^)N;}Gg#w($kif7!3e*lPt_Mh)>)Sf}`=Ah8) ze}FxcM9J}0{}&mMeWzn>@Wk=%6R~)qzEg|w82HI3=`ZrY+J(4ppeldUD&m6c zu~}Ri??{LG%ovFmuzK?kFpP9(J7c(K?xyg}l~3;aUSw-l%YSV&2>p_Q=f5s{#7H4e zEWfW_ue}=o^*4*?=p<+PIrjIS=u=t*YXf!)dvR)XdWpY^vj`JV1ApFkdw&9ngx@rq@`?jw`t#Xe3UR6PEHzS%TJW}$T9_&X? z3oi`Yi`8OQ7VV;B7$J$$Y3R;Y^Gj#X3Ue1KGMl1BPh(ibEwkyv(zi79uD(}+JDDKs zqHYdeV-utC6J2q7EY`n_AUG1&<~JT~yd{0UCD(9_D7DP$YzEOU0rgu}zU~${XC2@! z#lB$jF0z_NaA3G4O-SeCN1=fDql{}j63f!5CTjzEuI9(u@+M(R57sCcC}f?e%aMMc z6Q)#oat1`A587A$etmy+!SQn2?dy7bkNA^rE8aQr&ymj7x1~VWl)5E3Nqo9%nh^nQ z!3hTB8pHJFrfZ3sPbC^FPF7R!W{P7vI|~s#ZlPIuCm`j^x6RmVtaJlMb{iVkCPPQ{ zmS8em#p(K~-W{bHUU*NtO}I8!^9vgB*IG(5>x4%<+PL>mc0ik-dLlYP`+sTcKG*`u zEF5*(OzNXjirax^luEN;i*PqErm5Td_iq4&S|hItXLCj&$th@P6D|$2AWfIqi2c`6 z3@ZF;9LyW~5!f_QDBR!-nsQqnU`dP}t)O7*ZQDbML8g!I?+WzF02e%l4k;?@m+GtS z=;Ja8qU~e}bT=5<*p#}X&&_lWEX+-NmaJ}K<$g`#iW>-Vi}?pY)q&j~gl-~5d{YyY z6j=r7?ESI1gmDD#dd)Ye=fN{UfeH5%tSo0iSl*e{BHvb6xDPaYi0ZP@Jx#N`Z1ikw zLB){yv`CB&(qRB@GNk)7zK7yW3*wN=A1z#Xb@9htdsPPd&IadWmANWbfitePom(Op zDzU`Ntxr+DgfD7(fh8iLSNhvWfGU zSE|TPK%4LoiY?T(OS)LHJ;=*!hz%pc6u<_Y#& zxZ`n%_=7ll!sM;#y_qg-M8##DYPC#m5=>#2Qq&e)0}lS(r0wHQYd|2XA?%t$aA+Xb z5>Z>gK-I!5m{|)6lO2*U_D)bY`rI(Be@vyQskS)UFQ1(Shwy-+T5?+HgQ;3Hb>I{@ z!v{|BYeB`ZC6~gItk(~;Y@3|CKPW)lioluJ&CDo}Nb>KRQxY#~sH!llG+*c#Qk&<# z0lR3-F&ZSQ-y|Y;L{HBb8`Vlrh`H^8iaKD4SIR!?P7Sm3SZ2*+(2|i6;VFl50}b@) zEucNw`e?w=q8SQqLNDOE=m9HeoiRH{(G2OxQVFhu{|#qUn6vq@x4^j9#G8mk#nz8} zH^mKWOUh0WeK=>e1)4&#J;dKp;$ngAUE|jKFCPTE$JjjR-46cjtXEINHEdq{#W|!= zvj!Hm@t^P+hSX< zvcu*?d#8u8kU)@znuh!Rae+`-Z}M}M9~CE+zvr}s8kcaU7Z`YBgQpF)A{4-3syg?d zs0@RF05^HsCQursfckK8lncIa%UNSlEVirhCk2~F)~Lg097T^fSlZ(URdd7LH{tY?mKeX@LEtwBcth@8tL0XbGK8z5Z0ehkQ_saJWs? zPjqt#C~b!K1y8jG0Umnb;mk){O5sy&?KE~6a~fjL%&-ip*-KGz@RV$#pk^Ot5-}+Xc4hcjQ6QsUp@$@ zD%IEw+evxc#Bce=zxH+@<{r^I_7V;kv!?GfrBC(g%CU0Wf|e~jiOVW}DeBO7+&^*1 z%AKw9J5m;@R+*1<7X3QDSig&};_Sno0o0ouEjT%kp{45=PFj@VgfDaS723H|Kks-T zkdpPv41#8s?bEl;N3YNeL@-=-(9FjM0(IW;_SM2xB(zK3pErzrLcagdcsWYk%;+OV z7=i1g89)@M0j43jFaz7vYG|<;D)WrdezqX#X=XpaDj#}US)Y4Jqc(zR2p_%b+mc1B zo7DH)?9ly0+2P8^$|(zYi@xEfQt6JeqAAJ2d}5Up$Ug1-50h7$Ll+nh!)F7O(O_2# zU1@B^M$)S9ycUUK+N{nqDaoXMnU)rzEHNHqup^s$w^W#D-_pc;o*w@_@#$Nk`GrMR z>q^cZzVS4Kj7M^wI)1p^^edO1<}el9Rj`hed74t0G97AED9Siqv<+*gHs7|M9w-+|LKaHO*=gDlN;+i)6i$i^zzXbf6vHn`)Kfo-> zw40vhWK^Z+fd{6}nXL*!c{rjZa8H9^RiCRqWB!MsAlz?30ldNwgz2=%=!AY5K{sc3 zh5E%!mAU1ac$zay6K_WzWIn{C!2RJ2nSK8<>VE1Ve)Ib0Zui!#@-yFB`+z0n_m16r zS{L=XhL&?t6PJf*y=M!PpubBe<7r18aZa+jECE;|iR&2@bL6|&kkM_RS-c>Q4@KAD zgXCVSoq#ItA?}J4dVtI9XeCD}!Cbvgn(;lQqjL!$XMc_d^m^(QSj$3mEj%uzz+QMcaxK)b9y7GbjY zt}q%#x=O9AwwOyo`!sjW2^pXO24noRT(1?C8@ypR+8FPd?$C0uZd;<2c@wbbhgrv2i)WoB*@2JUj1Lj)$_8MeuAYP3c87 zptELl?Bzkt^9Jl_*)=QWmA^9}FwJ?TLa64x2h6V~v zfzI4j&dtxvEbqD{gtya&R0ZaflZfH~H)FXaJIdoO#U`qcZF;y&^p;Dg_Hi%|_VnU! zLYOt`)4B`78nRjkx{a^dbI_;Gl9bTRCm%n#jEpRiyI%3g4JH{JeO5prGTJ zRpt(hiSKeL@ffCbUTMiKv*+NWa_*3n!!xBAq@Wn;8dUXFuXo?koTf?5R$46}ZQevO zJ-vZME#6vtqw|rIPu#yRiz=%hA~J!}u(wu&SW4gpyPA z>lg_RaW`N>G(HB*O_U*w;VOV){?Pzo6zsCD1FlU@;5~r$2h}tqJwSaQD6z=+hj%c<~r^7@v6JT=<+8SR3 zt~5%Xju<82*Y$4TH%)H*NM`q5*{Zx;oji-$bM@eRL!6SA-YO*7b z>9z^}Z;M_LNx{gd4-}FE_?NQym#qV#~WDTC_X%L0HIXSiCUUlnEY8FvxCWSp8ao+$|0|wOST6^ll^qFq}}* zm}&)jy*fx~I0WM3krM`esFcQSoSj_VlGL6gZQd%+n^zB8tNm8q^n&MW=@f-|ZN#xF z?x`M^d5ZxH`~CPZe^F9oi({^^1=v(4j;Pq!wZsC7$4O(tLP}}QAf<;PVCIFJz>Xae z59&neJkw{kS5aTBwn@h(PX1-5$4~Qmh?)lgKyMI{fCK|n^yXfo>f4ZS%3zF^-?h^7 zaCKHY9qV+@E*Ehgj<3L#`r|3ees31}6+{tyoet>v5D%-u5$TKmw702z<3ME*(#xml z7t1_K&9xqR7q7avY5e`5OgIBshi`%uDZm&x98@VS*b3||Io$2)c2oM>dQsRf62pL_ z7$LG<%*?tzzZ0ijvNois`G%Kc)YXc2JLV%97(nBq`W7*g5E$rT_;vB7SiQwVx-Lzf zsc+fjF6mwavbxqc_Mu@&hq?>%SCTXg>)X9F*ue#~L81k3)-<$csDgi&Li<1_c%Kvu zIH$jR7mb_vd-t56BQFm-JAjQIZ}gi2*WXcVNex3#?(KkgA%&i-NQq&91H1hTTZO1H z(7k#y(7yw7#z>PfZNU zO|W7iMJbHOGdynBwy{-X@%Vi=EN_d7J*Bbv-LVw_g0({4bGbbb^02_+rl8#UOahkR zhGamd?f8^y3m;QXGZVW+QJLAN1gV#RH5a_T_Xfsm>-C<+bKfV$8b(&UvrQ}%)*EV+#<8r*XV$WI@KZN0D9uM4R?&^Q6*TFnFLYF9%(c}r??6JT zoXF8IcM`t*TQq8#`I=erbCyBOc|9wiMZBM8~}CB8(^%RoPdPj*V_L zn?lXSG@7q?Y5F2{jU2msG!^x$N-FKMbU4-3gey+IHh zivtkOCv#_VEbm9RK;_UMnMnE4k8;08Hh%Icm7rZK(>tDI$sNTsS!w<}j$WDjZHx6u z?l->yW#ZC)QHdi<2?M}|tAZd^@!*A?!D&CYWaP|p|B`L)G>P_{hK{nlck`HQT=0)@ zZESPw@4H5>2Pj#lmHwAaykQZ3S1r3S+NokR~m5}#kmPo>KSVp|@ z$#)*Qr(@f)J!9wi2%(nnxZFZZ207CapOhg5kmKV?-$)Rx?%_<)&OGnEHgjb*Hq-eZ0f=*sq+z0q(RK!Z|a<#$j!4 zM2VWQ6Pw62;xTgcvP=FW*fDSM=+lD##Syr4oql)Y)bN(+tgR)ttHSY{$y8tOz<(DczVCsj8td zWt6rspvpE?7a>$5RrW74=17pOBko zipsZW)8dlG6oAL~A#iukta89t=Tu#?YxrK6d7);9$Fi2M}I3K;_@oUoN zKb2rIgTi!0>&WJ~Kdf%zpW(}6kZZ;6y6x9=^{qoS+JAm3ox)~r_!HF1wnk=Da_S4S zZH+Uu*$QZEByHc_Y`+k#p#D2VuHic1Fl#`itd1jL(=ca{Us6;S-61O@^@$Er%Y!3g zjuuaF@B-{rrscrStc+X@tIF;Of==M|*<^k`_nN*_mai<$oBhqHvBsXvJO8+}ghW!l z<+Q-3RFqv^gUYNo7_=!nHdwO+fK@&6S{Afc$GQt=o!&=h#zpn_yKG_z?)B~@_8J>lnGuyU9JsOINa06qW9VhUV4O*J@H0!(^_B3&*WUU*UEQPKe%V z&M7zA8V0~hQ&&7{i=Z1M9hH;^?HSZMQkG^oA`a{zvx66}ZYrH*wjhY~0+-G%t^RwZ zjIHAsoyKPMHK!`ry2+y;^HxE~xf51_g?fYwWUW_1@PbbD6SKW;c}h{WZMr3&h!%0R z4!;Ti2xeTc@YgnR_i;{6pI@G9>Uqqj0d}=`=4sy3TYrB}xwII=mtjeoy>>S6B;9pT zi$?SSjO(%?!OYAV4P)!n6L+;=Be{tcy{J{b^Zjg!Qq$yWUU?Q{o6OJ`Lg#wR7TQ$6 ztNoH0>iA=!(u3xrj7A1F-xdxbFO6lmmI3?B=%+=CW?AQW{v>)X6)EqU!7MUDz(IH% zENjTL$ySP^yk2KW(<%!ZAtWm%t8ze!uVNrnE9FByG%;LqCV0LJ_5T69YO!Q5(P#C# z+f^{J@-Iqi1r!##?B^fv^=sis2@L_zB^MO3bjBt;FbvAHXJcTFo8CAe7!+Wh#U7anO?x9;n25cqU)f(r&uhL{;6h5 z(gmWaoZI_(S#}>3Bz~fou4{Y2KbP9|=K*Pb>}*5IDbL)@ej-^b0(>s~62{k6VD1=L zDJ|5jcUTCSh_<0Tvc)o(7Z^1?!Sd#bMUA@yZ$PwG6%s;UG#Q@Ab+OOgZT-(w)%@?6 zD)MbAxCh{Yb>pU-WW7fU=<%MT!c8B`(k|fq)g}jBUr*LX_84 z+?}`v`Put9&@x*DG)C_V)E|GnKg8@DEyH=i{zmTc9w~>j9C>y3WYZ(`aUn9RVfIbx z&lBa%8UA8z&-d??=qCtDwykt~mW3*u?>7&?{gQLH$FB{qk0=iiJQ8f-TK$`!gHWrz z02yu=D9YfA#hZjK+V#Yng}}O>&qhd(+Y3o8h_9p|b1(-_Hu`L&LQJy*@8A{gE|J)R z1BndgMi<^P5@?yVfbl=Ogh%CuWi-Bz%?6JHALjvbad~Rvgl9mDCJwZ0oOp$L!yBT1 zfHxuH3s^|Yj=D%K_l=vPncp#$1MD^>80U9Swj2>q%Ji>_IHFG4K-{d?Uv?@pTTtLO z{X89>7^cqI+D9k4M#mDLco@2ZOpMlF@+u9E$Q?lXTE@9&kNDr*&yRy%k0%L9Sc^~| zs3$<%kueOZI#Mm@x8NzjQQClR-hjMo4VfDN`P}oAo>LR*tiW|llvu%FtTb*sysmS> z@jgEIR5Da~0PEz9@|+@Qqvp6{k7{uN9}K+`^#=6ERQJ$NT2wBA z*%23}5LNnpVOxw0d=B*Slg00G<>X4L0iomYN*tPx$jS%2g$k{Cl&p(-oIlPj4^=h9 zw!Jkr^!FP1FDlxszt{K>i(B&8wW8+{X7ijkkm{Pf&Rx`QED11*K5u_UF?2!RkhcN* z{g&S#D7-!u8#NYn|32whzd4?ZgE*~8Q#3eJ(MSB}r<-Catz)I2e#L>ks>c~thQ{zl zmI!X29T@E;RrN>OUL&mAjX)#Vyq!Nu<6^OY(#N|&N)u=DNu!r5j$W4&rJrjZBOT|2 z68>1UJsTj0CXlXUYbvs)=<^0?yO8BHnT>})lLw6r4^sPL8f8R=8%4~SdNo?5Y{Drb zzuf;u<)w^t_14|h1Y3z3Qj#0erkYK`L+$$@yL#t!oibmy4w-aCs}6f`Q@+q zbN{^u^pDxAXEkOAZ|77Fi#fLe8!f?@JDz@x173j--C?aqBgO$|vYjlSgSC{2wqwKM z$z-@EDOK^ZM=)T!*aa=P^?5i?48Oz0>oR2@{GJ=CPEx1IZf{C{z7LvDEtrNKoyF#G z&$o=3au0Wd5mqwOl$0u6ZL+Ps!AVUvD;6GVvbu_{aPw^!BAMG-iZ@+!*fs~fSX>)P z8Npl`_iZT(VrbdZR&xFkh}j_I<0#)+unuv_o?9q@UiNCf@)*tbY2>k92Ms~m@nTFaiui(qsn`7a&rH&8h2v9PNWdn z)h#;yx_cyE;4)%ztXe>m7^Gm#;GAK1s`xu>PD4^d>V=~4f3tS()&IYvy4-#G+d@jg25y;nKyE?`bhDiF8h z8N!Vb9n!zF3#9uisLT{;XA2B8%6qCh%Itk9Exm zfUEF&O9gWg4JMYX{VUn0wGWaF_KIT$SPFAu(6)#cB}8mdU9Pv%q*)(RB>-xc22wN` z7YX55U+OHYX$lI)RGguSK9RdBT(t@k5y`a3YT~fER>wW&GnrU{!jl$Mr2fR-ruuS9 zrzA2#E9VC(zRm<)2Ee>NeRiaHof(8+zJga2SeeZVvu8Pxql@Usz9{m*fzFy7nG zv8BFlA)$Hi20~LJS&Il6=;b9Poo9aXj=#ugg6V2mxXEK(GU)Bjw!9laituEd>PsAb z-eOno&zc>8;D~(I4Ozdl=egnybS>fLmRp0R`j?HA?VmIlPwgHMIpcK#o-J|I3|^j$ zj*0419GicYpjvw0a9ai&Q&y*ck732Rb3lDkafAywDoY#o8~LazQbsN^^NfFHq#@Ze z$e!nyzq>8|T5eq3i^#o{1zI-;5d+iNk3!r^Ra{A4flR(d7sC4 zU?T!P=b9aU&h>LMq}n8^VuoLt+PXz+=}gFT$u(VFcg4H{F(p(S@mgb&f=H;894n^F zEovNq+Rjz*q%^a7LzCaMQopy2z#)B1yWh(3GPCSzQ0IZigUMGd3#-_1aK>fdN~RwJ zkB4Q8)cpd^d5sSD=xn~(^(;5|Hy^J zBC6>si{vpba8>-t){)rWbo$W?#_3*lEoG$NE+jRpvWt)kp~D#(Zpe;dmpc_JoVg*b0lQ8S=$-5VAXW+P&s2Kj<0>kE2Qj;Q5HmW;QN9ju;v+S73BHb$B5u;XOYnW&tsdn>;}2}-MrdxZC+gb+6?>YqB9=9fyH{x z$1^oO@99Tv@hiTF_Li&x&Q9+et$j0Xt4!fpj+mLE9MM+hIXX5gh<~BaI`W1n41f#F z;2-QdQ(6-uP5HF3zV}wP{>n{tP*dJy0kwP6Wdhyf&u;w!O|m1*AjY_*(eFbk+<}-l zHg;BwT(H^XHl7=JW-d5DTXs8Azl;cdaB9~u{8rpB@kv%)RSJk(1jVQB#sZ80SDU^r zoryg3w7C3SMTDwmL!{d@8sj}>mWLIp5A~S?crzTF@F!5eq2fAupQ%TF?O~_unRRU? zg7eq-mbQ$J7`<31C}G)jFruHijf~)w2a!)3p}2Ux#j5G6b+QZXDL*3>);>P{(!BP` z%Utl(-Kp69_tyk>$WT`70`I+;=)Eb-T5HrKK{!k$WakMBJ$X_>7y zur21kc5Z_f`9f6MLxvw3uTa)#SiE>bT2IehU1XaaMS`mJ{kSNHFwK zN08U?!^F4lGZF#*Rm7)e>$Di<0zF$tK3>TzDt{$^z#bt_S@*yTBsDjbru;DZ~xe`DqM{!dz zqcN|wa#Be=`Gff#+LtmlS!_vJ=Q`oLR#U_|dfA+22_FeV{Gy*uRB>CMv^oHmm6j*J zZNp~w(-w#o7T~>C8#e9xM@>8*9;9;)`eDvX$ooK(N&yYTu<-B(g=1rz6}yBXfOgPm z6I>T*;LY6ZZ{AoQt=Zv0vsgF3)y?^Ot2XG1s z^48AuZWL?o4g%=na-L5F>H(qgLWnVK_M)<)Xqb?dvJzdq+QO?&8)t@2LF~=H-}Idt zSstmzaL(@Xaav}Rd^pmU>|x-;1E-tBfg2nSD(BX?0ovVjguHoSkUzEewM&h1RepTD zoE~dQS#P53durY`2Q%mYo@6|yx55cN$|e}7Sponn%lX3m;>6X$Uuyhx zXk*7M-#ouO?|NZ*&4eb&$NIh>ei*O3h$x>zHj--YUq|5rO@5-U@>xE5xsUSxnon0& z&MT^fLd!7JWR95ZAs-jS;hy7^ z0_OsAg~9HtW5@lo{Lb+1>?iTx8-GcJzy`RkoZu93tIe|V(Cqq|&Ls;w>>2S0ev6%N z1I@S=_pCfD?oZhoM-P>1Q!^gRl0RnW2&cZ~hSr>VVNdsBWbtG`ad9y*$TjLi5oJ&L zy9iA^jzmTOXi^i0&the{Uw>^ELt^b@@yBJUB)UM(aB`=+-SE0k8^gm*>A;Buc=U$> z(#x79yK1>XF$^jO*H?q!3zij}PW^g^;oA7n;CX6gJ`rsqjap4?v+%^uO<8BEU&6_K zd<=*^=f(}YqtmIO$8_kP+JID-D%<7Y;qqNAr{`Lwn*pbH0J2uTDPen1r0LKN3|x32 zRSOPkg3D+%yWqc~_vT3OXwg5hcM=#$N!v5T(ZVafa-b^R^=DYjVj>`->gj2fU&T+E zZBT7lId?TkFFN;>K;4aiX8lN>gAH~82`?@%@i3SiH_xp4*uu|*H+PdpCtZ346X-Ih zUw)uU6-3!qA=9ok0>MMaqzZ#HN!T1jTy&29q_EkSR%XBP*!poQV)+ly!0xB$39#gB zlvXvH@?1$F@ra*rL1@o=R3WCtisZHCVPu) zbRzwCw9WXkQLL4S^L*wTZ3klp%e1W8+9@)ta$Z73r~Kwi+~%mP(TJAZMG-X4R@iX* z^ine-VnWw7w^rfEkjK2;fclNPi@DJxioJuK)Xpk(+BT3IOpLH|*qFkbFKJ8RYpLlESl)s)ByC#@T4yTTM) zJqlZFTmgQdy6(;>P9g`dNvTa5bz%&qVw;;U(GNVbXs{>-qw*jB{RfDazg1rgy}>;b zIJuG99}7u1kei#`YRxv7oY4*WL;dN2KHE~(C=cOGLuK5z!2m4&2Vjv+6I1e`Z4WGo zY1iF}85h1@LkjU=CT%!o86Q?ni(KfPojtr`{KEnoeEc@C-sSx$_Nlgznd#W7?ekUS z#i$$=5>J@P?L?GK^LsjLBB1|PxcR}_@(=Th16dp19qi-*`==#KvVUyd&ehLhem*p> zzbDkifASgvvhLO_5zkWZm*jmIpYGyM|7)lNew)pxC?@{SpsYhbgPOj|$4&}`V->&& zcp$lg_VZ`KVOWcb4}?0oh1nC_{^hhcng=)M1|eLSx1 zjC7hDkzWEqgUHeJ@>6Z0@(VZZazCY{ZSB%n2f2baBj4|(h}su#cRCL$pR#{`?0j|4y z{)gGKM>FA`9l86Mc<_eaXlr-rY!LZDk_oMhE}pXe$rLmTg|Sowbsi&AYDvcm2Y7U= z2~d_z9twXy)D0u3SRaEi+?3B@A^_O zKI(TCcU1dIQ!BmR+%<1;lB*Vyx1UDHcDc;RjJe1xSkq1Hz=6U0D1fVQo5oNS3AVO% z0B`T|8xq#LpsPs9I?9l6?E;GkXIy9$Y(@v=$=f6|%i^oHmQv`?(P&sqgWG_lKB}7+Sj$mN&v{sniSdcck@A zg?3F3gsOX6#^m~7c!CMtD`PY~*bU@jEHSkZ2unGq{z8~s3?qhoHb~rgtw4RJUZ0aW zn<=yx!v5n5sg^<>no|z$#4ZE2>QKe57QYG|m{JIox$%lj5*50YNU?@TYH~ zSYG1*phK=Bxu^b-6o=F8KftFhw;9CtmXv*E{pw*!Rpaq;l0H32{|9|FSL~@FRe&9lWCm&y+%K^ z&=IkssIpADobC{xkp}uGzAGrt;pXaHYuwk@A)&p@BxsJ|@wst)ycVSXhDvX9({EX_ z!hq!wHH5N=y+Upa&>7+)=QVsfJ55A@44rNWE?c(MR zH-Xiq?_Hqqcrq(?5N)W61oJ2M+13240n552`!fWDT58KL|HJ?fKOx=*%RGS=_~PXU zw8R_}6(SoI2@K~Tp^Us}q~bbdlZMz##Wrk8Q`*^5G%syQZ(8WsAZIa+A@*v=igXFh zaW$-38v$3iMa0efDI@wH6(HKc`Z&LR?gU?B`gpfySvMJsC>9nK8#02F(YXMXsH%^u z3n!Qbp<9a;I(Ej|!#vcM+VrlNGy}l)3S1w1vtG+pS}RzO#jG7wtkx}=w7fKRcVG81 z%WcD&bzG%eI@Pi&Y8uwyT}%Ix8WcZ$3Y_S$&1~CT;j6U#M*9h>F=S ze;b#pTJ(&dy7`5atn&sHo9*z3c8}T!JM?>(lf8=+K34<TA;$o8@GGo;hy0wKVA(Td70OvqDPHhuM4Is_nRVj^#SU@KsDOi z0pkEM7P=t{z?ymD)HkOE%2{c61A6zEeQjfzZQA$T)(;CmupQmf=XqT&Fkl%TAuau? zqH~PwT8C`)^D&vw1>b^vzib&+G`Ks;0Eel&lMPq%nVu`p2nE?ETvD*<$$He~N1QqEM0U zjJYne!*4F1x+Ez@_&q<|(lftWP5-dal860H*Vv}a9G8e2S;-6@7yMvKYo5(#Rk6T^ z;O_V|Ta=OCY@}zXZHP_iLU_7vvZb;o7^o}^M6Frl`j*r1GD z&f&*J$Kr@q{fqC7FoQ3S^Q4iM&4RS`p;)q2%w6!~oPaV`hsqU)!baW3Eozasvfs)m zW!|u6UETc>{4m(bw5R=ei;_ZotUtU%};s8l}^`%*CdwbFwvA`P& z-iZvtew;02tU_o^*kqw94Hz<0%MvO1E2oix`$kg=wz^gwF<^`5Yi`R1HH}BVJ_bw?ru9xqA4if^ zBg!g&KwV%Wds}gCBcPq98te1U?vmGuvb^Cp6x1icZ}K1Od5kAWv~fJ7BS!Q+a^eL` z%lG3yTz~*F2V7MI?V|waRDotI7NJO8?E(9&6_1>}_NfuA2sZ zODOINDx!Rh!+0I)-s)9q$O!Gg5(ozW z>#ub00h0Y)5e|1rSPE(c?qfT5) zN!_uGikjbfVuc4(B}Xbo8Cv45M6wncMbS5WbvTYk*4q=Dby(b5UwLU$5V3^O>7so? z@v)Hg0%m5nxag#a1X_Cyej%+7l%P#b9~<0f8=bRWuo*urGHXz2p-Uw#BYry_{IzUG zS1Q<3okXkB(NpIesdQn^U6?VOW;|00O^DF-ZQ}j_c?+8PrF#45Mnm{>TOd5Tw=JWp>mGA*8F>L8eovJ4^ zH&L_q8Q!Me-Y>f&NKS>Pza;YmNV!1T%(s5iSAcp&BYVM=1@2;E7=kO)Zuz$-oJGuRd^0_$YnoEZ42s@IIa!VrjMTl@4q3mh4YBpP`Sapp znV95Xc_v+~UFX+lN1SIeQKM^x#G09x8Ee@5;otsnPSgmPfPYbRuy=20;I64@j8-Qe zbGZ(S_rXO%w?y;_8^dH|51szkb^LT7Rfl`{Zx7B%jrnE_X)O~F_DJS_1~8Uw>2M#R z+b2)7LR5gu?zimiiI%;sS2H#w)AU8_l!Xi#%K`tx|84hV+Rw~TPW><`fXX1T_CM`* z)XtZ3r}ljg#Y+Fhe87M2|Ar#tznJG&(y+3PS!Dkg)Pr~b&wxiyAMzaOh+5VEf_0tz z|GT3MnX?XG_K3xV7Rg{t;J7=)9i&Tzg$0YXp?9VIB3boyO^T61$$t1P-h0z6zkziW z09!diG7|?RRHp}spAAe3X5BE$c&SYa?kP+)@A-1>-esfBVnBUp{AMUkB*bDX2RrwZ zOAK3(>%gR4#jj&XAZO~q1l`Hl6P%6M1FqIvxeU-T@@|*lOi50iSaL;PT$>EES;23+ zu7*RxVLk<@3DG@6-3Krp$6nhnF2Gr7w+x9577d*}Ssl(qm+h9l*y$=)8xh6QKXFv? z$^QrVKnK6Br~An#^6;)}aEODI)IG;-$4WOt{pFMScvfTl)Mii0dc6oj>^TpXRkCJO z`ir~dP?AZ-CUT~&=OBEFC5f6*;H05Z)XDrMJXoy{qc}?kU?!}3-;2F;Mnsx3R_`%8 zu+>FHGwu@LiguFG{n6Mc>W5{7s{X6F8cQ>wW3Xg7E3X{VR?cZc-4*_jwLMk(=>92P z)U@CX^Ho)cIFd=`d98A|vSfKBZ0d?oRE^d_@lP!ld!5z%G&HY}4sYbv{G{xy6nz`q z_+LDeZGYQLbvd4vcC~y}eUs*AvzcMb|(1JGBA-00=yP zGM{!HN9^SAQ=@ZFdRdNVj#a1iuD@r@ueP82$9+jgbX}+qI{RaP&vE`_JdpAox%eu< z>}bw$-ntDhMf!?E4I!?u!+D;ZR6}K!;?~?A!p=61sEh|Wo^WAsaTwbt3O+uIF8=`X zmwE<_Z^Fm9dJ9POX-{M662n(&wrQhdqne&p-z#R4TAHF-+`LF-3~S4_YXdypfzC3u zN)q)JN^w_51F&dYwcAWHQ}*jEvdn7aq;*}&x2R(!U}@kZgpx>hzyeMjP5?@`LFy*! z5vAE343#dW?X9Y1TTLOPEaUAxcP^`kek1Z@J1fSb(1xR;yH&7XqhsULcN&L%%Rc>( zfsh@xFn9HpWuHk_R9gI#L2{s)uH(_oHKvn_Q6CjUClc^w#|`3Z9Noy=?~JXENWLH4 zSk4k#{qsdf^(_sfqC4Hu^;RpfH+mSU?iSjX)HR-Ly<~h?4r%wKf(Ax0kfSV?s*24! zTX}@U>T7(k$2)lZ_VuKOJ0Axv#(YTGZ0jxSO7tP9q11Hjw%1i(E$)hnX_zW_8rgx6 z#tuVCI0WhW@P(Z%@>UxGm-1EcZf%x^3 znVKrSL7}a*mar;ot#vgfs+F$-SGHo;HfFS(ylh%=k}xx}=*KryzU<@A1*+fO5!CuR z`91lzXjw}oL+M>t42_%^XM{AKHb0SR0PnXWoMAe3uAYlVU(2Vq+$tfip=@KDUq>{cp@h#gsP)3-L&7E0H)H_gQM!^92?nhxL-yRf6WHowKE zG^OU`XsN5Eis3+GhG*c7rOVllP5|t84J01moyuOHd$LeV*YAR(sBJZtN#mxk>X}sN z#E++I_@swCn;_)Z<9;0EXM7!$t>;QpQRpjfppNxymZqjzgpe|Gv4K)Z(=e{4SElCAgZ*w>e#y1T7_sefN=2<)#DsoJMd?V z9ogAMT6EQA%GT?omG-M$2U=l{qT^H`WYPc$Yc?d12qf|u86jOM?3L8rDmPTiS59mZ zT>Pr*w`gxv_&UzBW1RJe-tc?wBaC;bi={1IuhDj|)crqbp5I$q+NwC-(IjGdM3KwF zNXtm`ONPL+d?>lLipD822De0N3VlNrmRRW=-yo@PQ4KqRJ!9net!Nvbeb~u3 zSdT>23j1eSd9gm*Upa-h7_0M4*S7`Hx%@d~m^lEqe1*{K`noHd^wZgAsJPc?yLB}q zD&-EPsFpW}n7G55-#dixo*)aF2302aHTuhmOd(NV{NIHE+AZEWKx$9-e(_D=Y_cL zS-K*sx<9^CMN|z z86MXW!HzB?xC*hZq>c9N8Y6oj!KSI0?iT`DM6&F0$nG{#m1+C=m5HvEve#bbnUs!# zD5;_|RMgZ;B8CXT#}nLn0(Jv(PbE1%mAOMLv_nyEt*5xoDXFUIDtgEaxd5@wz%6j% z1cEtkv7nePdP`7g%4uR{&aO&Ys%YeqtnDHfKaM83#11SxI5eI3cHLR@#XOpN-DtL5 z-5fR5`ihRNl&^bB;D#pfE= zrC@95F1#)-7;!CjH}5C&sE&^7sVH?+eYUBTan#aOQVOS>Hl6as<~BlmfFxx1Wlbw6 z)h0$?G?jfNwzA<*akE__q9e98-C8DnI46WT;{(mlo5V6Qn$+}hdy(`|Np;h-wU-zp zo`#a5=GIM8*%}KtTaAe)hYl^t*kxF4c6*kPqSRL{LlkrnI?+>Zr-}11#;$3a8o?N8 zJZ)|`%Z9)=o>Dsh07q&Y=B3kBcGzL;QdzB{TDMfj*y#fzX>+C|<}e4HzcI@x)K<&y z*Z4DCJ-&bNa=Kk1ce{B;NoAn3(pzQ}^_6!@j?WZR9DxpSOQbv}&1fe8ld@$WMjE!S zRm-O-VzV}$1zE34{z{Wi6=>Ui{>n#-tbBGq-5 zK|yegnQCcfYZ}SnXnQ!zOAcBx>^vNERoW|+?hBRL&8Vqt7KdB(Ey_At8+?r&oJ#Jq ztCP=mBqX`q1;l{iu;i$sx%=S9Ieq@Lb4_2NE>;T!SLR)8SDRz%dnA=Mn&D8`CgCm- zzhGKRLx?ya@SGi#ev8sKEmI|P>1Uy$qPM~)t*)=A5YyAJyM???!QIXwt!M<3-QK6H z^2Ry>)UY~8#IDpf*ENO1h=B!8NF4FF-`1AsWw-a!Y6z?X%XD+;q7_v$$O*f}2n2 zty5qXP{X8dcl#aEj;`GL^E4Kj=Z(?9E?ivbTP|=~@=HeNWmnRgZu8OhpVn7RUrx(p zRaQESJsc8G8>FqMnattpn%5pSG&H=(Jlp|;k`_JAoscT;s6S20>8QW#hwC;(#)KT0kWv#PN(c5k>w^dYDR|unI%^Ai>$p^atli}XA z8hY)hdQH&!s?y47borpNnXXT(iI7v8c;aNumCkVBdtAp36S>;}J0;&A;5a5?`@60PHi%bn^LY zx$5@m+pe6BI=Vw>qoSR{b~I5<12`lS@i=e|xWkUbJ7bk64P=*HA5m$w3r4QGTJJS8 zRCcz$Nh;!ztZQl^1?_XjSXz0z1RP^2=-%wM-;#x^?Nzoq(@9<;aePglDPWLE6!AD^ zuZ`npG=OpVLUF9LO(mzJt2U>LP}!;~YUG?v1XaQAcx#v%*q9rV=J6gepEqu44wCDx z;;!9nywcieq_@!sp`^EvL=1D>{s-aC!}8)t$;L+{>Z(#YGSN4<>AQ6mj`de1&8%=H zAZ3N^4jjO62L~7^YS->Yd0xzpJs)Z)VVWmZS&h~Tb5k{$w+5Spafa~{V#mG>^NRzE zfaW`v_6;X;xLW9L6Wwf9n64y>23+gKJe6P)(&je@&Egy(&cM%lwclpc^jiAktTgVN z(Q?okr@7JUM+`*hpTv0F_f3H=99mdg#l^P{6?XpsWV>r?UXi)!T4?L3p|Vq3Dx+la zx3NzNczb0IaO&7W4-Y#K?s-yRruZi;+Fq)oqy0rqTLlHO<7?Cu@Kw~@C2S&=KBitK zx#uSZ+#YLlla6W|^$Dn|H7&lwMEiYw_c~YAP)|)%A5T>q8shE;fzQlv!2suCv3RKw z^lPdqU#KI!&fQr?J7|=T|gd8tp$XM z_;bF*?Tq-Wl27OwnM}Rt`;E56QFvv}%W|irm5|npeR!Spj($UW#^7KQ2*@rO7|K=- zk8jh8T6b31>8_QLHfmcLM{1nsuz9S>6!T^(zoBcm=fHtq=A z;0y6u!ayDSbH}Y%^=_TI>TZ?)09F=?if8G|jbt|#-Jev(K}i#M3)?X+%x{l`w}6b2 z1_8=lJbcEszhb9ZLeJKDwE}>7Q0li)mvvuuBeIXVc>DhV+W4s3w?=x70b5Sm>kU=f zh8Is)W~R9|TKF2#m*y}qT)+u)TIVnj^1i&s6t*1^)7?q)m#Cui!K?miBD zx8==3X#FdA(w!|gSzfB?Mw_+N%W{3;wQO`1(KtM?L_@P9<>G620LbDzKwzv7M$h7g4fVA>n*n7;EJFqgp}8!-*N$O5bdEO?lDYjGszUvbolp zI-70AmN}T$(n{*7W@FwQMk8}29)GDJ}$UxioWY2Sz%A3)>!E)u2BiC*1EfcVyvr-=YX;@G3Vg$@j1L* z+`@CFG%d>GYkktPy3b>xZA+;eE!wlQi6(A1*ulc*63mV)j0}vfji?RVQ0kj*tI|44 zN!_jWG}MwsbEp`76p+IkT*`+Tnj$f}K4bt!2+C`x->NTmI=ZoG)7sLOs_|1jO{_49 zD5@StW{u5rUdZGFAI zu4xVga|JI?Pq5ip^?sR#pHki#VR@*x+aZEVfcoZ4X^WcB=!3}}Zv)9@S)NKF2=j#& z%ZT<|{?#WXCPDL5#BmHPx)4?-V`W;ZhamZ?BC>;Hvb#-82s(pmld{NgQ74WuvEs}kDI`tXX9~5=R z#chR>eR?|e8P^{ab;rdP7D@H$Q%cWK<;XiNbQDwX)yY4+amTzrFD>>}j=1=vuG@Xn z;>p{Zmw}@#GED09a8p5WwAa^BQQ9s>;>MV1>RRaKW;c0gaSh+rl(ElQJ1vc})I`QI z=P#7n+1ST889dV9PF&L7SjyymXz(90mb7X*%Vcb2JTwn|MVy&0i*(Fo%JX9mDW85Pd z;>QU%ZZWa>mp--Jr?%W6ucY8?@VkkH&BzDj{3#h~Op?A=aPd9G&cMdxS}85}`}v&$+jJ51e8{J(cU9$PGDyUmn0RvGkAuxi-fCtM-(gOpn&+}(gq^_i)rK1!z!LTz?J)!+}a~1%}Jj+jy zddugRByu=;xOK1k)K-IO|nZ|dUlq!N_b~wMNxZt_B(?y z?UD%raxS;jJ$o#5jo)FvJ-McjwA!bqeZ72F%j9f&)~UGf{{Zv&Iu@v&u01JD74CLR zay74XUv*@U5b*E2Ndcte3ZvJk&bz>)t}BN=ZtSjzX3gA{(I?lVuTh(pmld{NgGmKIlfXP1vg0sjD9hxnYhs5x@$eJ{*TkRRib ze-oD=joEtok7PUP{{VJHbHP`Dj-@nvt@93F-tP3gvWDml38}>?oe%A%KdSuxSd9Aw7TC8Lwki75n3ZZM6%cN{s z$O`KDGQzp;vUYAxY3@JFudCrDUl9eBGo-A>@pBQsEvJvpl#dS&!l749=+=})W)l!N zrgunrV^z4G3AslQNYg#r5>ur}hyqY)*@!yaFduV_b@jD(F zPwyAzT4Rcunl?IjH;WGB(c`l7*7n)yHt$SIyxqRvR4MD}-vf`m;u{~rq$#8?Zb8De zG4z_JNz~KS@UrDk2$~biC!WDn?O+(%2pPiJCFl`vhCgP05?O?-#}-B~oJS9-AjXZ# z!{B50>X=E+e9^jd99yUKQAXE^CBS1c=M&&Lrd#YRpQ#kf9nz*gwg_0jM#bbbxF+y6 zqK>W9)sUFv2P6@lzZ`6Ha7T7Bq%~9&m9~alX~yxq7CZZra7W-& zNj?cTD79;2oOGk5V7_UoZZwqfvgJaqq*CfFv@DVBVhjLi*L+A>*-~C9KA#m-4?A2Aa(YMt^obh z10y)th0>}inBWVT*JE%CM$4G=b_?}I0|zl7C-4Hg?5x{xy*zC4`ju@E&!=YyZv${S z401_2A)YJ@jz_#HSH<9(%D^@X$mSztU<8l=C!PXpBS#*1MtpnJjLid|G|FryprMqE zU_3#L;^&?n)9ZE0(FGf*?)qku?7<i2I38&qAqkv`rAgm!1sS5T z9BSLmMxeUBx~d9z2Uf^or-h_N1WagaBWO81AOX*xGtEPAvAM$@!*w_$p;(~s zIdBf@pLm~lCy9+B2I)5w$T&DVXLTLL-GPq`E$Uy#E03)tuC_#*wrpLuAhpkk2jy5o zaV*=2<86=}dxJ-;1+GwlQWR^q_pSBprLC2`1afbz56q#0%N$zlgbbuzAg*J8;tY4n z6N6mW0mX-7mUqIZ#a3DdN?ca$%|D>}iwu>Z3^xFJfKl}|0q*1p@xqKXMdtx82K$nd zTp4yR8v~ui!rbRM#`#W}8y<*Lzao09Gp=bmt#O7AsC&Q1za(dNV^c1buH@l52wIpJtNpc3+u zk$*JNHbs+8>K!{tYGn=kL(pE`1df&(metEkG2+H!l(T6g$k=(LWPsqCYMbqTs?@c2 z>ziP0O-tH%A!iJ6HLVO|7&pUO*0rO4K|!^-I0{CJE-WUKY)GVslu$Lq6B|i9$!Jsb zH0*H&%xk;18BA^Pc!gk~hnC7k2b7Sv4f7kfExCN23Ra!C#>uriFaW}R7{(F|IEg9- zQcNjUxdO8eU?Y-A&;#6@0#@KB*xv~e?I%_n)@K34oq-F3 z@UE3}6M_3HrSbJOZ%z_8Karlt(nIe1JXS zp{!wWbDU4T1BKh3;HM(c_5F#jZe*%+%LEaC;C%Kp5a8?(c=Mn38~9&I{l8J6?0%Ql zKT^s1^Gp4$kIO&yA-yw7U60h*{I~xAVy)C@+k{r9R}%}E$q13r$k#?0!U%sDI5{VT z4rKmqpP{b|ox&P+&N|)(0V70?9bt?(vpE2`V?36A71I9zX#W6%^p*L3rLHcP=9Bv$ zX#M&B0I@9Il_o#9Odr0_*i{y3&c|@4r@GcdNfgl;TRdb;!qJd1!gtG?k5Z7S(ndI7 ze09cG%Mp>Glbw*FQzc_X=hjJkI6~Bb^pWF2${gcxF0B_W@N77`kAbA!s`{@0I zyE;Ub-?=f5-zV%Udo-=-nBtC=nBwCmsendD2rY5W8sJ{gLEm(o7Q2(`Wu|RDCW@)F zk87R>46Y;w{{Z1Tqwt=S`$9g-=^pxirPuYtkaM+1`APdI{cz;p{pyeMllD~>?QXbR zsasW4$b@b!1h!_lu()wIj02YBZ@+<0?>chfLs>Kw(nna>S~#2}VB>ga8`~J-CHyTQ zoNtZD9qRp;(l6=ykN8hV{l8M#`r%3Usz1t4*+=VzC*HXK04YCZQew5v%bisnbwpI+ ziUU1M<04|lf(Hl3~zLviz zeihOG0B_W{$FHP+D`Z3W!TTx1dd_Ez`8py00DgYTsyj{G;hL&2$2+N#DB^pg;B4jK zor&0B0-oEfcL}XAS1`t1FPz9sjccDD2N-j5a!xa_++hpZT`#Ome#z-Sx9VCV)f2q` z0Kj4&_s8s~EWXq@f5Bn=ar-K{1vGNp*+p)tZEsn^Ba?@KIFZYKN^Y9ZaxgYt&H!^d z#14-s~J9?A;4bp#a)K9~D zZ|xdOsOlsC0GY&p?~mC`sx_4HAK2*6{rUSTdaDK5+CO3i41TtuvWmC`@y`j+$4ET7uw{ImZ6V#|7D zkpBQ<&HS_f0AlBLmJ6LN40V-Ef+%Hk85w;;0daF$;enjv4g{VyHkMPsI*M%@ov^}w}}4N@L?x)(7Kk-Y^k|i zsH3N+rJc~cnuyDZYns;!R3xuB8ohj#0K3+dPNiTGzn9FCVp0a!rXMB zDgDH6M0ck?SdC?7p3UNwD@;NiXU8mK|TLD)j{=YzzZNOJ7Ba{YVt6e%63ai>8; z_S*^vQ`7bI{b&T1>`#DKirABTl^*rhbQx%{(qrJC<13T7rLG|J3!?OOSl8P6gYTko z1ZTx^bt>X@^lfW8wW9`&$Gl*w)~R#be{pdorHn24FsF3wLo#A{!(1@8y4oSQJ+aL5 z6w%}|MvUYh?~!pW)gAGY$CFbU=))uLROA!F1Gu~~gO#-lKqQV_M+!;`YFiDmMn^H8 zvUczX5sWv#ZsfuYFb4Mpk7Yy3YI3wpQ-F6)*u@nEOJiwsj=*H)KeOCvt}*e&kU4^J zxJoTLvFuQ-Zn3!9Dw`Pdx|d@K+c`?3jQXdVy0{S)vd_Ljyx%j~N5I9D;PTrr7ziER>L2+8YoD zo)@0=^xRz_UyN-8n%57^2lFoeY9pqleDb(9IGA4d9_E3PyvJKq`-Q@)xKfWeWv7YKamxvNck^+Kj}_A7rq)B=+-!3Ew30XY zoT~j5=<8ixoqf*fLfMT>pK#)Hh9hp-*p6pEGP6md^x)409MS&(fmJJi^Dja+d3hWKwpwfH$mT?1M*Qtsw)1SM95L3$U+^F1yXH7kf2qH*ys~m6Vr_oU0W%0=%h0ogk!NT}*FxKeayl8T3N6rCx+QITkpusdugalJ;w{3k7b z+|(M}svOAig%?{k0U1lpF5J{L!hMeGC%cX|2ls<#O;?rPCONs;d- zh?E6_jH@I?nB5zp35*18gdoZ?3dr&BTC9W`ZOv}dlUWM}v3R+u3Su@5yxvKTOk{FXkBco#>L4y0mKGo- zZsj0Yd=$jg`|?QkQhSz!hA=`&Vf>F~P!?JMFn=s)h9+r%;!(5eVO`7DRT#BOyEGbr<(`FR23IKA)1m-QuX2P68 z?ZRZuq4Z1`TbMEyuoWjm6K0+$osb^(w2%fsC)Pmu)uXvNIwEDI1aeHSlTO=vX!@vH z#>Dsp&5W6w6Wzq{2{_#Pmt=N@vzob@`Rn72u`$hygt}puy`|-$oInl{u>f!Hv4Ws3 zT31h&*05C6x5?D8)l@msH}1@QS;Gc4JZ@mY&d&7|&OU-ErMoy*pt)5`s%kFmji-(? z2Ujz49Tx`yYkn?)~&S~I@1kAlzpn9vW~IMna*zu zTFDsP7UP~Cch7QOlS$B4YD*QJ)K!$xR2jsr%X;|(T>cZBV<&`TZvONp?0IRTi>Yeq zt}|1LI$q69O-?D|ZZWqJc5#!9+;+)HoBhTLcSBDN96VSuIgpTKA~!G-z5&CI;0&G4 zS672WSScm8O)WipYAfYydnHrY?#Y^CA!MV3aUA0w_Z&kZH??$aV6LyDiM4h0FxAsC zwSpN3SjZ)OamSF>IF|<*OSZrb1n`WNMIS?&QjHwS`>Dl65T~J}Y$jJeN~gV}GQIAN z#NZrrj2!pm>=bMorsYX+tFI8z$t_JwYMs_ZNMx-fwaoyITt{P&x`f>rS_MTlu)6B$ zs?SkRbmELrI;G}D#}Nn41+HU5uun2i2*QG~Xgej_P+zFvr@dUMXe#NcVeC>cNJNtL za!le{M*~PM?%SCh*6!*0k#dYy$2!#7noE=&mKs>8;d^20OF`=;baC(kic1FOo;Hk-Vp+*!T`TG7lO5rxz(JsauTO1c`UpHXmyoDc0&@ERKP zBWDH}+l=wY)rTF=Bal4Y#b0zLn5G8hS5JAGh`ENYrrFfC3v(GAIdGA#{jJy z0p4&Bt8`W~S6&Wt9;B^p-mc`~Pb2FC+ffskOma2Y%W<8CKqChrfS%2*F0)8oD`{TB z$4Awe+*%mughjdH&%FbD=R4%5TK7u9q&00lt|IGzq!F6g4jl}Vlhzp9jfm=uc^S@J zRk}?LVIoRcgiVqY)V^Q=AMU4v6Tr^>TL~Vb6Gt4Rwi(J1b6b{?lgpVSak@gmVx+CPT!ez5t&ZgSa4E}pX_@DdEAly~}PQyjT6WHjc>m`~uW$qhb0Cw94=PK9wrL3r_o^Z%o=_HZyIJYi@ zJO+^6@HPXu{sj$eu+g=QA{&g{6yjDoH#df~mNnRmY>aUp=WGsec2)~+oTYsiT<2EC zMBrl$bGS^r96NcuW1cvP^(vw{DT+GvRZ%n(7^#@(C3Ni#k7qsDB)cT%l8}c|ktmY3 znX`3RbPZ_Pt{hk-xRakdp8o(M*|u6nHSB9=d25V~iKKP1eatv85&;>{BHZoCZC7Hq zfan=K#&XxauPFieeGUmQ6x2#}y4CBse9cxG#1D^;yyfLz; zUM$oR*V^f!sG3$+5iVJR=ECf7;CwH9r!CzZ9!iz^{{UN6O;HP?q-S2oM)$HZAJv!j zomeEFH;aEB?5HY@S8{+cjE0P!21hfU5iY1>80Iyv^S1yvjj(xmE`xQ_7N)~jE9z?5 z!U1C%3(Q%Mj2HQt0G+(<9BU)j517FD;i$Y!;TOhNfR4OCe(j4KQ&%pf}bZz&6g#^(U2@ zE}5*Iw2ioSn8dAy2{=pYI3E}jFahrz9^;Mij%Rd>Q1VNU*pE8W_bhcWKeBMuGP#ms z3~gBEx@>Q;%SR7~tw~(9?e6DjxZ7$e?ZKBPhg8WN4r`r)(l9uN>E>bo>jFyxGvVeSE^VZ+SeZ@Jtj5$S3W01#bf;HNV&(Ux%6o~^Fn zhhjkm#Bz7NJdVq4v`=L0DLO;H(=wRD6}huQA#9Z$n3*aBF}gT}hl>O?uRMcuu{px3 zvu3moKme|E+Dh8@M%g5$(JdTVuBi9J}hhrnG!OnB|F_pbGlAw+XCR`14HC1n9 zTpUejROdQi2?S(-BW~Ms=gAb`>=0_`rn7eiCqOv_zNw?4q_3nF`e~ttS{Nn!q?~+C za{+M&<<5P63rY|+Ta9jXH%Obew{Wa9EaafA!*Hy0Ba-#7t&T~uMgRZ_cAe5u4>c$k zK?W(6qlz+CuRdug0STSrno3f$A2_Dcm5qf7J;;l4lX1yg#mp#8l!_#26r=!PDB3ou zNOnrMGE8vMvPyC0l)EVNXlC}cO#^hywgArF;CBZY_>=DkSuKBSn75)GFsmgiQMD-d=9U5#?gY{oWAvAA2P z6d0HX2}s!IE!y0kN##5s<7Cm1l7kb5l(-C~#kx5GjqDCPomokvr!H#2(_g z)~3)GYkQwPy^gP?8|8!UjUKl5{Go1aYD&?Nn}f3TV!FdK88kCB>^z7n(GACrG3R9W zFFVlJSKB8&M305w?$SSu6=k<;y0}1XML2(pnCyOK=1-@Rc8^9qR3yG5t<*`z^741} zq}wp%l|h4EP`nPf%NNST{-0M`pTBO6zb-ky}5W9WQUWZ zQq+$3C#;wekl?w%*7g|pb<&^k5>j&Xlc(Va6_1dQff*}SIX^;fQ1W!g)Q)5Td{b9T z#P03aDy!*Y+}!qhI;oGWhN|V~q^&`8%`Lhf#vixbviT3ld%psta813@IcCQd$$061 zSV2o^lTXpg9aB&-P+ITnOz&wvC-Vi*v?iac)mN5MLLACS$aPHE*^K)~xO}BZ=?;uF z4fb}`-Z<^ljyz6uyUi!a)4$;>y6MX$w!v(U-)yIBFt>BwUheYa-dA=wXh)f!I+NIQ zOG_0sG*qpt70H4B|||9BC(sQrY)6fpys5Un( zE>~`mbMTarrzsbO86weUu6bEww^})D&S6GH(DIwOsVE(QqiOaDtsn;V3nL5AaHuyD#v3oOBQJAP?s z-MVVdX?7H>2Q4X9xi(=+G@u7ea$Xm1nlPoKb_&B$DNg=MQkmIq>JFXWwJS>gLn_dF zi6Tk6jHIWJE##Dl_br|mN1-ymaHS3o$R9F>mXpuU6|$xva+tc4iQJNQ?d)C|bfOX( z9PPpsy{ZbDI;K@pJ<-g}@V&goK?k3xkfbQ>{vaueS{9Dw(T}ItmQJV8t+LJt1AubJ zC70N;Gr~S)bB2+l8z%yhnA|E$0SDCEC{$MJyKQSLXj~zvj2;O%1B*!*BxD>M9gi{i z6eV4vvN|fNINsq;R9NYm&y28=-28-}opp0W!aeFnYg}&qs++}J2YSu}a?@|$?thtA zq_$MiR>M&QP3vNjvNMV>;l$ICmXJZ;xPlj=>ueE7512k=!rf$!j(U^)!qF10w^Msd^q; zl`&+v;$d@K*KouDl$HPq$;ie%eA9Sp=$k$UTl+trgdx9 ztV)VNPporKNd>rByW4KCTga)**cJPqBl0TkXv_I49mr%AUaI%_T$u|* zN-C;|Xy&7iP8cV1Osx$We-7Xi&l%qt#!^ggEtc3>Xi~A{Y|xcp0IdNDNXGe39tpL$ zt3caewOHWYWqOGU6(nnKHTGkf44YGG2_Z_>JW-azO@~THJrq)+mMNBbYsAGF1 zj6JV};oK*`9FOK*Gf!90-Dp`^Z=I6Fd^xoE5!_ca)LLRqHE^i7Nl5#}wSmzVJ=t^v z*Wx{D3s2lH8cME~b8MQxIzQ6FC$e+uZj8>8JndV$TVxmKFE@?RW$Ed{;BryHtemW`&eHu}})OWs>U zt!e0^1BM5&rQSI>BjzfRri_$Jl?O$dKA3|0eAO-=8&KjtVTEh7SgiJzhTCm)l)kv) z0pCA0I_gr=MmZcTbp&sWCzdmdQ)6&ER?XOel`-SijtqRMbTHtKS%6$51%R^5u0m~&C}BRNitAgY_WP_@zQRfegY%80FEZ6+eOQ6A~5 znx!gPxlE;ENh0uL7qwZREtG)lIknt`sLp8V6Q*?Fi+$x}rb*wUfoyBST^?>XIQtckZ^ge)FwObnwaLJTs6 zg_Hq<&15VS;IotfApxyO0lUixl1u%3$P^`l8mUHj&M$#F-uvftzwmwlKHq{4%8HW^Og$S>YZ5I5GN`3l?fN#_nJv zkVrnAyg=i0?6qoJy4AQ?n-~Xj-x*l}ZH<=6j}|2DiqY5uBVv_s$0X9OP{tLo_?-;S zbJG1QC%1K&1<|`8;d2XgxFb1T8>K4twt?*>a=UcdJk+}7rfBKu*TP)w^6n0M)WmXS zpeoI}U4ol}T(oYb2e40(#OKW_BD3D9H#;MmV^-YqSuslOc*{zHsDzi5YpJK=$--eR z7ZbCE%aInx8!PRn^(}=zsHxt?>RIf2a>|Vz9leMiqkZ#*vmzsI^)UKecO?5hHo{~i zv612zWh%&APbDE0HhYuEsRjnYI*5y6J{XI8l!X|^68)4862r{cV3!wX% zhBfWO{FeU!1wP{n!>8-2t?qlNi#+^iiM&H@ zO0`1%EGs3kfxu;YSQVTZS|lK+6Y+JeYs2zf(%p`Ej4m~;EHt`XQ@OVqdYY?5@wwDN zuRdq@A1FVY3%gOo(S)V{08ZO=9imHR&K|NC?$-^S8@rs-+<%RAyn3Q>xl!g@ZEg2X zO$Ew=T8aZZNn^ijD}7^;{3=T8(k`;Er!Y@blm(&L8+aB$;t>Kbcmo9(3`Kk#s+E^&qY3PT1lyBbG_e`K@vOJS~RE*{esVWub0e zf!4D|x0h4fQE0d8Sk2d?rZ39;KYd6h&)sl{;77 zqH3ANos%F@EA=eqnM%%TVyY}3QjeLO)a1*>5szl;ENg+UBu z2to|7LJ)%i2toi5gdhxpg@k1W*_E(bp#W~(iggS3=9z+WmW9|THZF;}H|{r6bWY{E zuF^Yjrs!O76r^=PoTqnkbkmf=oac1UVAyr$EWtH}VQvnCA)tjr*ypN9PNx6Cor`QZOFnB?|@<3L}sdtPRT!2AVgV^VscP1F@jnMe>+>@tw78B+)5VeY;Ff`!v2{TGO z6rhjPw-F5YD9s&M;zSBhP(h^Il9}qgK_@I=D719e#0=D zxeKLxoHo|={{ZC2{{Sl*{L9ay)YLz0 z;CJO`v=0=>7oO#iB=A2nG_y6K?`iNU-4xtKMK!V?+PmgbHprex=bw>N93G)3HCJVt z*_RNlcDA@Qb5+|s2MzI8D_uUrE7!vcN1c{-Nl`W1e2QL}5slMYcvPJz1LWf?+w5uXUNY%%jU6j$ z5YKztGWps7+%*3H66+r2sG99|B_npyO^=j-xu%vewzeYt zV4M|y=mxcxj*}_r=6GXX=_$!48<0T!`1#PD!?m&M@U(Cp>tJ?RaX~gRs*H0{)eRe| zT7%6;RAFBqBqoT8rt`v$pKPgGvNBX%P8V84MshsiH*}>dFErXgx+u*ilE`pVDcpBX zWE&>3g_IgbbBv}lH=2=`l4UZ>D56DGG;iLcCuqsan5habq;91)S}`N104C>}buQ_% z_FS`eUI-n@Au-u*=WLqKBIbOZ6|l;!+|(s=)SX?l0gt2d#v6nW@kPMj>qp^;4=pZJ>Y2joU zq!MZ{vO5xm9671;IREFxb3NDdy!yWWy}7UZ_r31#{gL#fQusq2Dp6Fy&XVQh`iH8lBW0a%bQhA!vfgkF`wK;;$Nm$|2@lvI(^H0O! zRwgG!SAkh!-WrVpOq&^QXdn@tjpNzGuS%UTX1~jyxQo1xSa-j4a*j(M>`8q#(dcsmz`(&{&LCa>C%71*n~L- z+jBZt(a-My^>k@};mANxE|pMWE*V*?jThKdYlmjWxrx+r<(qn9TjgjFoK3w_!+3;g z_6RfWM*7db2UlstJ4KtgCl^~qXp=HD#;2O2l|B5_vKOS=wp*3I4jn^$KIP#oLpgT* z%YHW{B;r^%;fXwW6@B0`R|)BS#0hh)E5lB6zcREMx624)aKnY{cU89=MoG0=i^eB9 zl(9OXBBzk%VEs2@G6J^&;p2c1D+4tZ?_S78`aD>VhYi(C5qo`%iWfifT+)nr1>2Fk z)O3f3S)t39u`PCn8V3%U@S^+-lL!2ndz(h`|s#pCfCgs1uM@1?{x(FZ~eCSYdxvv^VTD@(k4Ar^QZZ(JNg|}YO zE33$|#3B3VlR6^dbGw;IKZ{XCnaG8PR^LBMm^u+5CV}pGL90l=>ZMy3#x{Q%$mMKH zDnzS1#O3Dx#cT&j1SKDQ4-Gx{PWA<-5c7st2s$DYdX<-oe;pGEF>n>GW98gJm6K0$ zGwU;cOH6z)9mN`H&g-34M0;-J{{mdktLDZti9>uhUUEHr8y`icY#s+d{boK>RZlPD zd3)Gzd9P%>D&|`}Jj25ddS2HKMjb!ZYsuRfoZHI&3#n8)2VW_I@8V&O9o-0bfAhX& z-D24p97Ud99wW&5_TNi>@JG`UzpCVi>XCj(mAAWjrK`$C{Xm3~`V2N{n^qgM3-x8) zhdxS*SpK6{Ss8S|*GUOajbm>Kaa~UOM2D9%B39VtSI5)8^H*(s?* z`1XVPbnh_{xXvDqA4#ztsk>B{pjEVA+ct?V7`Y*~y7N40Q8ww-Oreu$Y%IDBP-e_F8vK(WJ9O1wl-mTcS zh5p&|DaHI?cf;PA!Z?0_ZJX-wX%{;0Fqam`&*0wdvaO~S^kvo1Sjp7fA@@9mN{kNy zqmUB<`rpd@pPll58^yYLf8a5x=9sz4YBoQu!sd3RP7VM#7k@sj!(rvABW#!SWk&p7 zqqA|l(ibo`$CZidWM+>azti|mjqmknP{4KcI~7CsR)xEuXNLO*usRsOcU(hRdl z-GR1d6EvL>)Xf&|jb9MQh~5cL%*r2izr{!3?ADJbvxeo*i< z2>D7!?bC@_PY}rVT!qae|l-f%DK|w))B%#l| z(WCWjvLA4zahpKIA!CK8ajAzk%nLp8!pNH)7twb9T;{}dZDQ`{+WclG<5}5Ir`xQS zahx6i-#IRhw-z;3rg%w>Hh0@Dn>+ysgr<>01IbdX$Fa^oR~Jb%8s_s~}WZ?cELEbr&Q%>wPxOwRfuCN>oJ{Z^l77guD5 zR9>W0_U!Ag`gTw$q^5rN7%|^w+u^-BH+Lxe!iqFZ@m$|7h*0X3x~?GFP$JZy%X>#7 zh49v*r}zOKRDI0ic1fCJaT()#_>86uVC+RQLD_VGD=CrEy}zeE{y2(WRWP@4wSTGz zq1X7#ZcnrX&W1i;H!dj%3V7~S6bb$jx6^x2ED2&HHqq#OyI8s3mr6K_)Yu;|sAN-I z5NI^{saFIaG}#TE7gOA7pqk57Q?{N`v>OpPjA%(1UKM+D$Hz{a)kdmqI_Kv8Ynk04 z{9sG!8aB|2d%Lt{Km98BbO2>Ce4c!jKgp{FE2X2T9c0?;=LtyGvTHvrU$}7anA#-4 z!ddU6@0CpfBn7WU-C^{#gd5HbXDt-PD_`<;00V_vu*6%=ZoH6t4(N68-p9y z?^^vFyI6lN!q=^GAyPSl_#o66XfK+y0c?&~aq4YC)%BfiLcOy9B~{1flvpXZ2tbdK zM!q)4@;vtRnx#15M-Pg6{=C}hM;{NQ9*7Eb%vd{ehx|30kusvZjI}-E@&<|&t?tti z+qR4TZbEUcr?7v!KW^yZ(Qt9}4D0OoLa=}G9RAgXVa!+BB4qYSmhU6w6VL06pA6nK z&QlZgOndY{+>sROjt+ZdI=PpjCZr6tWZqowtK~OmY`FN>zP{!+^|zB^+s- z9}?)>87nR_F#DksvAt!(fGXTCZQfW-Le1ytAvqH4cV0m+7AhGJLKyNvaj1|)^kciA zkwpkbXR-H{D^XWY0xT^Cle_(YhgV;x+}``{i;|}BOIlK|Ww8HR<=LPW&EbcJA9SuE zqJSKL5Y@W&$g!cao`5x_8zb<$7TO|wp4c3-!Bnyifap)&SlS1C?1;JTYPnUyW{Sr_tialec3fi!AL+;`mlZjwl|x-gat@-R$r&T!hZo<eWRL4Of(ZM5_PJPD_&$is@jk?w=T79x6GRc)z;9XAZmZ5G zXrK#2Q*mwyn*k+N2@1GQi-F4?`?CKL%XV*3_+XwRF7TdzcZVotcFxE-syW zr$TA2z+)(wGo9!pUlxI|=A&b2xh2}fMe5Tl{s(7zJ*@M0emQl0nyy4(PMB6@-E_pJ ztIEaZR%R&)ozMsY0hme!9_+SoH|yC?QjwCO-f1Uz2b^d2zOgdUq63_40w5=jMw-K4 z9q6%TI=f769^Z4573>Xw&UYiK0gu zF~Xc-nfq{0qth4$vgrHbrUHL?nGbdPB|u!mLj>3v%kaN=6nB2qneux7*>!g~v0CWi zC}_6Io+K1EKhBbAKkC%k{6W|NHTim2yLx5=-e2+U*r1w|XKI-54kzNSy<)zFuSzL1 z_LJ`JAp+X2&p5VcqqONJJRt}y+c0w`8QU9|)-tY=yU&$0o{5#e8aNVlha(2~B(Rq| zsG1{3dNcYmib`U?lxPr3B7)-tEQ#j0SXs$6+{Y)2F!^!=7HI0~GsfMooS@b>4eGl2 zJ=?vou#%k5l^^FC1yXxgjc=>_NXb__8x~cZoO%S%PE8|1dTDb@IbGK_6QAIvhEPu1 z^0N~qx-rHsQ@(EftzcR9Y?fY4Nm)IovL+`sg!1_q8L(5soQPPSH?hZY>#pY{X7|_` z!4yOE4~KF5E85kEu$vXG)Pm>%p->CDzR-I@tad4=G^k`H_Ya z12xX!I8pWgh%p#XBY!0Y8^n{3vfCSP6ZK}M=A(J&FK;v~AKgmbtsZC~>KE^QQP;Pa z31k3#$)&Q)!D5(S0dd+o3eh3$LTa=M|B1}LprR@P)@lWrSeM!AEU`O@P+mNkf%>7L zaM%lqhsifwKfK<~iZtcHMu zX@R+)fgBYHFsgOF)Bw~e*X;H(H2!y7JQydQ7zzzpB|`jlhk;-nC9uD_^rf^3FIm`& zi)O2qca&g?-1fWQQBS+Mog_v~36bJAN(xcP=gnesV&4F_CMnBW2QG4lNYsiI!XwOJwU!CtG z38@&Oq5gW<${#@VmxM>LiJxjrMOy8%EV5j`X{+4^>o@H=$GSm@k z0NLFXll#71$AQYEuQwf5LX#zanGm%o z)voO^NJTmr#krt`+^y_=a>(X~tq+zdN~9<{sSYPWe4OUrLF1lU&}(eTGgR8prq= i=XVqI_jI4Xe7#PFDFSaRy#;O-vW-90$LW#LYc;3T*vkl?PtA-KB+g1ohN?{j*e z?sM-ueO|x&?z>+vzWS)SYLtvowQ7#~|54BL&uhR7IVo8w0165UFoygA&+907*6!}k z{46YvZp3 zmm;g8vxJ4Ujf}6Wg}SejhMBLO8J{_=h%g$mpf|s_gR_H$y9tH2gT130zqb(8@2&Gg z^1pq}LM1HdYHrD|_FC!>3CNQW)gNQ=^73N#;$U`iwPIo8`tzK>0aH!<^S1i+uI0>o4Ec(IY|C58Az*; zC5MEBB*^mT4*%W)zkdT+agcidzCIx}DgGCH{?*ApWaNLD>tE*jhb-_93IA(#{mWec zkOlrB;eV~J|DT!buRgAYBgC=wf_SjcOMnD`00##T2a5m?2akw=fQXEV0`W1BaWP(? zViMpI5fb1M;1iS4QWBHWkm3_iF;mgdy<%WwAfjO5V4-KHrDvf3tq~{$L_}mHWE>O} z9C{K068eAm^V|hsB0|MLE5Sff0nnIGFqlx!JpefXK*2%0_}?7)KR!^+LREJQj0QVzgk!eLReiNRy5njlcQ;IIcLy+;Iz*M7xSn>?fD zFm(+qno4bdn zm$#2^Xjpi}yU3_$aB@m&T6#uiR$)K>`OB~ zWM`2TuH1944fvw9fvXmG!+h%&&ot9LVoYWzf?L{;jjx9U1%62s1y+XkXu7sTYMGkr@5B~Vs}GvZdXwQkAaYn01pcAoDnhTf!1btq{~%qm@(ffy14h9IcwVZj z^ZF~_#G<{^G=$$rNMF`StbdI1P{z|gB#L{eZ3O@5;HFOs@3C9Xdz9Wb=nLJ*WD>E` zAAXloy_${ML`a+Bf22IXKBLVa`vm;dUk^Z0YJaEHIg5z(W=vGyc;1F2xlig0-Zr=9 z_~H)Sr2SOohwChY*+_gyj`fqCfnhkt`^3XN-aSG~jNam{7VywLKSx?EQMkv?xY!x- z_NAgn)gns{C|grjZ7W{x&gXQ0)Yki>4jDyY1pg<+h)cByE#;HsdeG%4bLDr8hs;BF z?VO*bs5z(k~Ef5f>o5!2f zvB$z3TRXruM`9e`;NFe_sx9ou@17+p?Nx5HyYH(nvso0&E&NnFy?gORl6UzCf%X~r zxP;3|tMSui^BAO%tkwRV6U`-yp!X=xJna%a!$~6P{$8bxc18$8t*|3}?fdm<{2S1u z@%K~4hSR!lml-sash-joAH3CiE=2b*sx`kiJOh|NY5R#h->rAPFdVhnz_CtkM7YfQ z9!y-U<`*s)cweShvV$RiM>Z+xy&LB)e;RSqBuqQ`AW^x(scl2L#nb%qbtW<2=GkLF zrPBsWw1r}z+}Y=*dc08FE6a^bHLz#|?>k9xZ`64Zr!PYJK92S~yYx1rkm~nyf~1>s z-HT@;^_t$(@Ttu3|Qd;P|tOG;p!}%w8F?cm`xeT7PvOwA}H}$!-i+ zp2F|>@`MY%@^X1u0vY*>mDS;$4ml;=C{T_g!4(dZX}*5w&+08-N!(qIhgZ3bdivz} zhr^ZhC-PA&Na9cX`}w|eKW#Q*I&r*}N55;JNsW0mw9&H?&i$-CL40r%C6&BBZpt>{ zI=&i)Yd|yyOYu#~L%ZZV>4}gf(NVPA&OuZLu%>pn>R~@l8+ZQ#D0wn)-E7`F zdJ5x3Q*ybDdK$KYUb!sAH*hHe2^O&DdsFRw#bhB&Az$^S9c05|Pi4q~VB1N~W8g{4 zJI=eW!)=6jbmDO=BG-0y(poxNra%>b$~4PGo1it=CoNaGyS)5%Lc7gv#ek`3FYq8u z4Of<)2Wo=McY01ae~bAUU>P}J6x2(95}N5?Pm7H!T`C@RHhQ-b554)L#*Rn#oVmo} z+^+i`7K`FjXH%B!OaY^=X5`o732m4nZ|I@jjhoJ*rs}FE>|d3iifr*!JYr0+(O5ACj7Y5idxNwJW!WOmuL6G5jX5X6+{Zdj9%;qXT0jK;H0N zI)>2$3A148v?Ip245woIKJOWD*9v@~{lfbU6k2#Z1EHMHzy<@)+VN=bZe)jpo1e9P z4Na$Z+CsihRFr>>_n46N$wQ|GhEx7s-bYEF)35r&**}1e=4PyA*_(xQ{~Ci$P;Aya zna^#3i^Ojl{4%o^I9nDd*|DMnJqF$cUD#a9-!HCDe)+L$I^Jz4b^i<)p67VYrQ^SH zs2U_e;jG%AhWk{3wC0C=de|#S{{DcB>f9^NUR$Ge+Pz_x#%FP~NnRk`7(ei=3`mY| z#VvQSEB9wV{}6LyX!=WS;yUVSkn8hRpHzgzt*-LsJ-MyCCb{Gt%*w;Kc40If@J~)K zqfZ>-H@?D28#*sC8x+O)qDVd2px$kWf6otXQpbQFu6~oVa+vPAIurn94|TOE66aO- zI$6pr6YsTSMK{G04i&X(Sez!N6m(e^4in2`pgzp(kGbpC%ehF-!Rd{F-QYshHqXY& zuWt`TS|m7vf95~9Yx|x1y-w2)KrskaB+C5~}weyM$1NOVy|#P-U}2}X(5 z+Kj!dE3s@@gb18A$lSfMd|`QR^$pvcrg74JI6H!zCP$AwGqatU+l+6sTJL8lEZ*W= zcS|*s+7#~h%>`I%Ofy2G6uLF-;*!)VwY%CSad2RO8SvzOM;WapmB#7%j!su>F+jS6 zjm%_&q1+$g+~h$$z=5;vWuy6D#;|pu?jMwwQZg;9vBm665%4_+!ix0d_ zEobR*^83d&0-sBkq(*Uj6na7s5xxXInpPRuBAxSW;Dz0zs(p!iFE_{Wqr<+EI>$kB zV7K65eDi=qzuWn}BW1h_KZ45q!~SGn5`|2XDuSeH5S<}0`iNj-=^zr+_z)fb&qrl}gPNdWk2s4Oh$*V_4c7n;o!!i{gMtM4JC`|D)b2s59( z>GX`}JS6VN=b%r!xV8Vvdrv-;-j7eKSAX^l#CK2;Ylcd-d4YLTgVUJfH8AtI@4d!t zulA|pt%nq1sK|a_q|!LfeONd;6YiP>FlWUzsU0U6+CNE1eh_wm9y6@!+p`YN({DXr z!Q53nrhh;X)XWcmOa5h|gO)n0=dI#Ri3iQrr)OZC=@IAG+S|st>eLFwostFyTEh)i zj9qmV1isB5D1qNh)($_vA~nmcrD<=LO!6`KMV24u>Wk4EV@Nd0nGnfpuus&O6}hsC zXT1v;^C#uC-20L%E0^swg=|5&pt=T6@Wc1-N_}nJyx)zwdIm@zeH8+tA2OAoLS;xLR6VlR(;t4qxC{L* z!gjr5gmQP@pYRMEy?O@fW#42g#3L43Sr@*xK{u!f(z(yq z-VmJI*V)W@HrEMS%49?()k1y?(-%}FXHpd&oe5bd1x#Db(E)4<4D`pA32bnt0_JWB z;taFfjm^2;qp)i1S5~4jrHE9zvBOwMI>s%kEeQ$}4K|&J@-VZ9_p7_H-W+}0Z*b4^ zVV%pU0)5V6?>~ z4Q^iFeAM_w)2fSqbncM2-S_pKaOrF=4x4B;MI6ZJq%cTC4lk`!d4k-C?MhV=!1*U9 ztNto6rq3No#j(>P#+U#P1GI!y9``ZzBk!@+)WNFS2H&O|`48l^ zd7M}%>*}+1Ebl0zN{snvL)UaK_oj}Ndr?OV8+_ClH`O&0eg?QmB`22jBlSGPEn|m@ zm^~6K9Nm5?2mSb(5b>o-{-0Kzl~Svj5bQ z4BvPs3G#fKuvV+pt7s{y2$^PTi;!A#5HATj25mGy6wPW0+~>Hhb3wPyRf?d#I@B|y zuUGq8u;-D(0u}2L-1;X8>IQyaz1&b^DO#7^4;^^uvK;_crS7@Z!LBTi7h}<~$GWZ^>KV68@ zq-n7l$h)`^;O)JUMCYL+`;H!$62F5VEwjRGVfKaneW=U`BDG12P$kt4;Rt_YTuDcA zFVpAY%Fp#6>e#nyrmX8x)MgVN8^zXpZcv zl(GEA(~+>4Zq01BPi&L-fk8r6-02!6<2@L~W(AosQl%ZPTX=e4943*YnKQyVCQ{E0 zdXz9#O2H&zO*j>&IZvy^$);Y|-BtMUhnLA4w$t{j8vBx!zD6_3=De3NDxTh^4NFAK zbA~(OoovR^6q|XHwsx;Xme#XS%v|cmwjAhmb@Ew|-?j*P?Zl^(>l4{{IWXFvFTdU^ zwPSCgAeR$fvWpyFH0deD%xCp~29))-P8coQ|tTu?jB)W1v*s^Iz8RUD%QbzJ74 zUzfNhiushs93na5ZE)#CiyG>&=DSgtymjc$L3fjFXNa;ra`-%hnbDKn7optR+O=|Z zUGnR-uvhY~^v*Nj=Dad3BpjwqN!oC1tEC!wa%2)meuQN}+Rm!M{%I*hcFSvg+Df9% zFF;){&D`~3xew3Ez^9_=95q2TcST^QVllXOhgO9D%rg)2#-33(Z;8OM%+lG^N~nzaB4%K#><`P9$!p5V6DkoRUD)xzrEW|lS#w#3?I;p zO$Bno)Hvc%h(z5TJRB3NJ_^bcqgJK^C^<0SQdTvhzX!E!75HxcK$`#90q+sRtggYkji$E zj;ft)(lowrvh!imv&+sj4WB4S+QH88Brv&~6WKiUnO2c6JVfhQ^lvitawsQ>-CNS_ z4C601TzPeaUbV;MukOHg#huQ5srUKo5=whNm4L@m8@DkA0Bx1#cc6%|urw85F zIM0^hGmqZ%hndDvkaF(n+AJ*+d74-rlBzZ+AyWd5Z~tq_-2DZQM z&F-2k(dj%wmKj032!c5_Q$9kG?M$=z+cNjhFY3JCE>4TJ*3B|GO4#z$>EoaWVKQ6n zzkE1@67tjZ_>`caUq(K>BoNU%x01R9>pl?tM(@_54cv zxj_^DY}#BK-g}HCX1ES^pF~zmp|d)?K6tn2y~<2|yIhG4!E}7B3#PnuYrOBP?6@U~ z4@af%DMd-#N8MFMXcK%Z%a*mVDAm9AODx4>xQsFf&w&5HM}Nae|Jx~qz1WIuvk^xH z7B4MnLEJ3H4bSxC#C5D^3miCJqAZC6sQxKwsOn3j^;}X2>>7_JFVn$X;WGV40ZoQc zHkOXwtc^7Z`eQIoGV+IZ4{GL8PYU3!auQS|>|ad9*!4;FN^sAgAxYXJ(Ux?sjLu$%P^ z{GdvBDRQ^dc{@;mFsX21_6+3NJp=yHe=QFpm*f~sc=Gx9ctQ8qav%U_{Ev!7|5gfh z^}j{45{#f9*<_S4&rSr2-t z9G{X}j;xS&t`laehGw4=5@{SW#{Nc$Qd?HrG&?tIoxYxgOlMby%-5~wsb^r7Gn*I9 zL!VKL1M|PN?G?r&s?n)XTeDUm09qOqa#gMA-FJ8Qgx_4V+kOVJGb{~MF_CSoB}T;q zgVZ?yLOC^Z>;Y>x*{=tk5a$mYuML;2V%bV<@z@TySsXanBfg@4)(nQlyrLi~5l#&d z=odJ^M2QTg`qXsC{R!BX_ZUFndtfM@Z+%%=`g)tDvr&pv^Mi^s;q?{86scAZn`B4u z77P_vsyunRbJuvOh}^g`nk2UL_SjdmME;Og-WNW+l9s`kaE%I8ZMOJjY+O=cN9NA(sC>th08xYn_N%8Iknhp2nyN1xtjpdh;9EaV+~Tw}A*OqN=5YR<=kM`eRhg)jB> z-WFLKmw_pfs&37M+Zm`Ato-?1)9O8o63Tw4&1a%F?2PJnQx$Ng?}G+~f8K|x{!EZa zH>%@)8&Ib&6I)k&ljkznM~c4Qn4UxCvrD1{;XQ&!SC+={N~sl?&DtVU{i|Xyz+UWa zX>b9^Ik%wb4gUBLAuENna|hEI2eR$jCfr>4oSOBET@m-ttDX0sXA7sV5t&Yocj5)! zv6T#(UtD13?CvbX<6OpS!Kbd>9XDnY`IsdrHMK|h>6j&?n>Wb>ue2l_npPTNZDOiP0HQ@*-aGxc$-7N zAH@7^2%Tdp7Zh1!7p2Ao?# z`9tZ)FM^Xfy|0()F--viXJOMGxUMbZAOVd)lO*cMzO|&pF)8n*;IEuejjMKs-2PX#)_R)vErEHQlZp`vNVWx&*0uVcDHHmfW z!BVUop>w#EoD70eJd8NE()59>VignnT4@(mpFlLGpl?iu7)?+~j9 zMPU;WU_*RB1)RgxdJOta!RwhrRD+Pupnn(+eO$x@DdkLfipj6N~s&fftEFwo-ZdT6=$GV<8lH! zc;<|rcJe4souQvHCGmBh+lhhI`!UhG?BIS*pl7yvD~nU6lztm3-D)WO%bwtFazC(k z-AmI{OS=87A9^h+))k&!=1vx2o0gQHEI_mpq||_UXNp-*@6z%NU?^`ZHclNg-UQ@v zlfB_SNy>JF0$h~|XrqCU0MFUg3p-tyyV?(Hm5nhM@BjkEcF-2;PU4|$`@=AC1LpZF z`qE)X=TfvmK{LW%-Mpg;_d>DYjs$Ex|J~b-mGG~>&Vx4quEjD zr*4<70r#;OVxnkZANY$TFRqJIc5Cca2QcM(3Bb zzhWL1gJ>(#7Y)-&oH+4kCx=P)>l9+~40Z`gt}ETu6-(V;CQs%xKQI_Uj+YY*&%jH_ zp1Dz3($pM1HOt^dU>|fVnZH-qA{?5$w2GoiLBYVrU+oL>m5h|ti%~~L zs;cfLr6-CB$eX#K{@{7zJMj<{Ki)Ho-^Os@lBNSnkz^T3*v<(Ct46QE!zL=hvHq+W zSrKGiT2c5^i!B$)-Sd9PiH{ zrl608V8mgYvQ3jV%{rX~QbL4JmF|iPJm`3094LB{ zLmYNmWZoy~YHwR_8p~M1=5$KJ{&LZ__c-)BmaLjZi8QinP^Jg!VFTi|Ve<%r2M7m1 zpe*}5qABxCbMBF>x#+jTYi$u!`7?+4$US5EV~ZCkHeXP(}gmmUnkkO0(toR%I#hb3DJ*o%(2p z75OUy02&F_tn{+v!fbbYOi4+WZnyM_m$xOk4C<=s*#v7AWvy!Nc>2g ztSB6g>hB3X^ilf(sWY>j9&+3W?8?5&0{`6sm{KQKgN`AHO}LTwFN7 zk5ylmUFlOH{L4~RQMAY1!YB8)my?0~9{)>=popvDfjeowL)m|ln*Uuh5)&OMkonMF zm;PsTn-=vKwzCJGX1utHt~tD+V@?t;jIJ!R)Cy7Avv*}tu}|I&Y4+(9Y|D3BXHSO^I^`Kb1O@EHiyf3SwOr6;fJKcszp zbUH8kKly70Q-#-9O0yQQ_t28^e`iAyuC)AWJ#YTgZsqr_fpz0pMv{VWG>(RrbV9y% zvw`?XWp_!wzdXyUHM6<#L#)|qu=B%fYsR0qSwV@K)ae|Ox%d_25<6Ff&fYKt2Rhh-@E{K&NIj*0$k6&HAdzB&jVzP)s-W?J^M5W&z6J!=4 zh5`(}TUOfOXhjrqWo4M6D=G=v^2aV*-Jj)=(1^c>&*GhxIdR02WQ0OJ(44=_lkIcn zt#MPDx?Yi2YFlt&x^BvK&hnQ<8|(Yr94|ig;tpVg!{;MEn77KhhF2NV45F7p1XW8r zIKbuB=`V_ryy#<1dL67OT>uj-b+TSp+qGmv2AbZA-&p;&e;k``LmK*~NT^Mw{8K&0 zTF^j0kORNb;E!K$;K_sJQq#|pO_pr~O-PFcm!$cy3WJ%GI_!01S67%w=7JVqRQ9u5 z6+DL0E~&d zdi&|k_=`Ajm88zNC|a1Bb%OPs$3VxUJ|hwvSmy4X?;c%YvB}?{U4M&y{p~X>kI}*OQycA5 z7`<)8;iF#Q+-rz08?Gn{hr7dbe^X?$+5W-qaIczjmgzWZwb~Knt$zE~Xq8d7g~Hg1 zZxh#6nf#!c$kaezPw#bGc<#*2Yq>Wv3KaRPHEaWm$`SXNNgmd#FJ(gAkG^UO?=c|bnMHReOhE&x} zBaYDBvYf=2ltQ8}vss7@4CEHeQ7~Jl?H?+&y}Tdh^2`OqW5J%WB&b2`l1S&|TCLO6 ztqoI0w@bPPD+Y|opU7KN-lK${#$HaP&RuT_a7>of=*yfNjumY<9sSDIIi^e_=bm%1 zw3)L7OF%V;%roS~WB86h7>$}IkrxL0ZH6f-& zGz$zd#7qb}_-)9yd)pr!JES^LwzhGMcwvKBmk3~T90c>WkVhvUoLtP-MXpkHcj~9A zPBeE@PIF5v)xkczi+s05)!}ZC5kWr#z5H=wjioI*6w@2CFPj%|yL~Pq3sYVU#yZfr z#onm@h{HhpS*ka;8E-YsW`Dk z1@Jq{Cm$cLpMlw;e=FjT1{}?w4j^c^(W5N~?XC6`ByRCgz3gAI|8Lu&6029oINqDD zR9*TW!bQ6W>UsPgFeKseR4sB?7`P|?q0BL!N-c2rw|w!X`mgTG0%U3NDWwk{*d+_Z z8xq7tj(LtQv8R2$F0;AlaUb-TM_rss^(2M5sBF~Ww33CqUa$ueHSd((zT1_~%3meV z1yp0Y?>SjzQTY{PU1SNOHs#Hc2aqUb`a#q=?t@%LI%g{%nk#H>dG=Aybfd(YvM{OS zJD|qAHwpLb^hcFXF~$z~J>(KOjGEYQ@}FkMa2;;}d_30?W=iV@zW z>!JLxWdG3ZCcL%@`!0?pi_&muK|F1Y16%+d08iilyC!6|f!=T3q2zy|$e`JG%h#>g zJOgCANBbE*$f@JlzWQ z`1VVqUClDXIW6m<;CDcUd3HBqii<+^F7mQVAO_IxNTWnni7!>#4fBbF(!I`JC zhdrnnb^qTpf0-WyRmI;kMZX&>h*Xm2&sOum`Eylh0i$at2t!Q%42W}aN!Yq!V?F~y ze|h@5&@pzF>sL>EHTWA=F*W{7rHwPJqk_(NqP?gQLOT+)jBDm}7r)GCA{4z;1Iv|f zB{e&zsv8kxX;#4n^we>mWP~F3q-)`WSUZq52(OP{nYYB7uQ=fj`TS%o6yG$VK;5(y z>yxY7%~O_e@wxF^k`KuKGIi8mf9qV*NtV*2#kzl%aokNh+PX4d&v#Az3lItdG`#Lz zf83$cX07V`2o7wA)ofGa3bIm!Ady4^6{|GU1&ht#J1oKYVD9=g#t5OU;ENj3L0%XT zZB~c~t{x*eW<;V%9gEszJ852)KA>0WNggvq`Ar7lCw~$9*}ASvrB!z{)OfiQhY{WE z5A5<}^EYMdXT2#z;ML;#Ogtk_=;3C84^B#%ErEjp7Z~zv2+{8Qg|hZL*nRqF7czwD zX1wOaZ~en~L7}0cNzvfBo<)lpt$6A*^2TrVRHG;#z8lM|%6v->4N~Ui9i{qdJL>4L zb4knOMB-A$$SO`9&Cy?6eTUIk_>)%tlESBXY+|YU%YIQ*W~vynm;F#8h9<*=3e`>K z$0ggjbT&Q4JOfN=+Klr$ydUj9bzowd-6nRU^+hoEwJ)U7n)UOvR0*sXyiT+%ECvYG zFh6yNHeAY=?hTg?3U=DJwxwBvsisrb)jgLTR3A5WZ}PBY)*HZ^Ds4QolRZgeA4FE{ zwG1nejYB_wIit<%P@Un&dj{5DPN%EjePmuaB#c+A(nz<|M0E)pG(hVyKjW*I6=tc+ zSByS6eUX`pEP?2=byuj1uBk2vPY41LP{*#xJ_Cr2O_)R%$L~>IfT;$XjF@7|ozjJr zc|n}R%7}~m8z2)uA16i`5LS6?tr0Wlq8BAeWa8DBbSVx~BU$*b&u+@KZQQr&DJhb> zteEud)t!7v6 zYVcUG!nEvP45wuY3yr~NHU|pswd!3*e4nOM(BkJO>oEHYYn8W%!+%VNRi_JxfME!o z%e$f!0f|Ab4izUC8RSlwb5pssL?Da1TqgFsLIESeR7?D-u9t`gmD`gsED&8qQZiyT!^d0rBT=5B@$(xn3mPwpY>K@F3}sTU^`JH za`1!aBYQ(HuIQB&{7mCR4ut%bi#gHgSJ)&iRDY$9gx5D4FQub}KpBKc!P`v!4C#?e zTvjOO;6SDD)a+)D8*PB2E+^m}ghkybtUnuV%xo61Y0W%2t$m2cITH^NI&J4@Rb-^Cvy|~0)+XX#1*35D zr;)XJ`A9Yic1zfQ^enn3@hrZ4F^DQ98!^aDse)4GsX1tH!Pepho$s{%%Ps(KQ$g3l z+L6bRSCSzqw1GbSP3D>h^=%ns^$;}+yAoFx!B#U=!G4%uR5+#gJb8L~AVZu$$_lil zM}le_>a&P#wt12fH?>1FmS({7;@SXNQN9V796!pvd=)N!Jt_w}?Aw}g4g;1pa+S9h zFRCxLw&PJz2PTp{#;e6v4Ohm2W`FE6HcW{f{4@eHG4e!c7`KG7I_qbsY%L#FX@ z@0BflT7HG@LFBQ;t3*n|A$D`JFh>}AKi0JyF2_1fBeaD*Hb!4Jc8b0=swkcyRv27S zeNtDS+iG9q|5KS;8q_i-DZH!FP@l$oQYw>Y)Kc~KcBK3nc+a2k^F;v) zjyiQ7Zyt5hw}$FE*1*WM9E>jPpT84W5UwEQX}>$xoc#iW_i(xqkp11uXZP7`3f{^6 zCQX!PDFl%2UqKu?uAG-E3wQDGP@KTQpMXKi#%Dn58MvN&2ChKr8r+=+Kc3n|p2BQx z{|>D%|BJs@k@OWaPBw}kV;$#|iu`UX9}>xc!l~)>N4{v_-IEV3By<6K6j%S>@)wkl zFbBxy;2#atOKSb~NiZ^S7aaJ5Du{7Xv*V9^!oM2*M{Sz($FkI5r7BLS6+h!g_5F(z z4}~^&54n9;69rjI$XV~(Aak96Jt=ZUsjdP~vzl9efM2J#Vo)%((40&@3`)4$3HYq+ z(re$3C5haN6((s|QNfDii|m1m8KPLHq2|R`cJ-)5j>esU+h98>rAiyWR*)%nL!6r7 zArwXXvfSXOlUhrAgtsbXG+$^j2Ak8X*Ei#_zwX$%5nw2^EhKFM9MvW^s3y4HLEZt! zW~pl4JK#kDFq9L$rYpOz#dP@~3~g4k$@_!Z+ZT_Y?k>uMs(&o%-_jNBCODm2!CL)n zHowB1Rh8l4y`A8)o|BKBr+~b$tZY79Mp;sR&8E(CEh6O`9JkFPMNzA-MJWx7&^IL_ z7%4Rmlj{kMABjsayQ-;(hH*=+J-c~t^HG9vj$;s3pU^_rEk{ZM6guC^)aL{G@MO*#t;ik~ z-_|_rhqdBX7Z7`@v(9A@;>{6#{|$5Hj%?GW75FIa<4*14!s-HO22b+zmSeTemJTNN zT{nMiT|9ZiC}PH)Hl5Y4q*TLELXxc%m>lwqJcgo)V<#rgVnZcWrmfg1g|01lOIqt2 z7$AT_Jo>ktjpDZ`tbgD)|B?K@_&1hXAHsvjQbkN{+^ofYLose|x(D}aV3ZRcYe7zr z8u=&DB`k}K*EY=S4Sp>=+L#$c>!2tTMkGze9_$dQ4Z}9i z`wjn$UX>t{w;)8Xs4%ssN9zF(@3~BK;U4!#T@A0;9Wj;h50*0^SQF0jDz+?|Eum&d zoQFW?7+X2Yt9^mQACo0W`aC$)7h9>B{CKjh$|$7H+*(xY;iX|GR9yK(+{cPbFVW#XS`Dj=~npmUFyZ%o#1> z%KgoTI^3O>UFXFh^kzETgLjhpWjQ^7OD9VEQm+rJN?+RAaadpY3LADk=~igCJ@m3m;%a&A^Lodq6<^ovmQ>c2T^68FIJAdH!}+`8;Xp#LDnf{v>?>t z>uxeMz!N9_kO8_!T5s2fa0z?2LqT}yya}@IXx!-Yyw8Df(NF-yMNcCU9^%pCFmCE;f`S&l% zD~LZ{+d$5w*pM?RE*GHrWv05}mvl>>SfkQJyd(tAB09` z(S>ce(YD8BkqJ3IUq$E~PY`Y+H@S*b$?Oi~cD{VTEsbf|uUk99U#lnJvu}+r@)f z?Phi{2L{fhtwb{mRH#KcFl!eXJBKEtzpRBHsuI=)PwKWt?2?QUD44}Ze{O57Csv%sv$!ZCmNo51#bJZZi|r?^mH9&2gjc_GcMC_OJMm&&!H&VvxESyj zLK?h>TuqNR!nCQT>Z?<*u(Y_4Z1`fj=_sq%p5i||2>5r;RxEfo^_|K#cP53&QaPrW z%uD$T&y`}qE8i?lW1Fuuwxu;svARdCW8UNO%c_50>q`@ z`BFmlq;BNpx+XkNyqk*NFt#d_1b5@WX%fVE;$+01eLn zX_63-syYyIv?{mdolMQlCJADtm;3z$@@MWr<*!>x8Bkcu!qvLfmaH)CV2=Om6OqL? zs=#rBTe8q{u3D@%(HPKO9evQ46c4!pdMajC@oS*qc4UN~*gd`7ai55xm2tt0e9# z7G&X)uD;Td9syDZgpQ!PkojR8HSzoo*Eev<3{yP2nipQeiEip?7O; z;Uw5-&@oiCxX}F6nl24%8kQJ5JM64amRB<`1qDYNi}hYy{&qh z@5fpL?Yv;wx}93+)Pm>i9AJYP*wBTIbjusS@tp|*S5U}+H4H|kiACF3!M#1MzM0 z#Gs=hzAnD6$E)vaXFco=^`$!eRB47J1YaU*E~-JZ7{h3xCF_ zrY*^aoY=`PTqBx#pHRe>QJaqu!1K}ryA+PRUHgUsY!K>O<~M2!_D?6*h`C37$Q@*9 z2wxQk;j8}krG=}uq~6q)J{;TPP%`I>i(0UjsBA#KLq9ANT@r%|mH!O_utIK1s7J8z zI+WV^kyw#e3w|P%fuOS1#mlXI>-p8p)<9vh^B6nFewIP#Y7p`(o{tbPTxw0qmF+MK z(EHX;>a3ocg3XE^yyS;@);rk938EnVd6a{i>s%7G2z>U)W3x$qbubqP3lts zSD45ugvf=%qcVmR-c4Ws%47nU7j#*GR93v&LhIahILh>Q!0&$sa{LF1;7=%qS7YW!;je()eoH8{+41ppVc+*JQ*rAnHtFK=(@Ln{sl@=Ku7%VfJsiu*)jQ6l; zGyRl9o)aY7zgButZq*jOT#y=XM5(D!Ymb@(H7*CFMbp!rn5H%{nA{1F;M&8)u3g67 z?pZ_Yy-HRj?OyrzY@rYg$1Kx77mNI7w<=whnW zQsBa#@k0+MLmVuj-zQt0I@MHVgdjHjPNjBhv*0P944TaXm_a+4<+yvRV|pZBBS!Ix zm#}LLftPS!ecCjQujmJA43&A@fGayX#sQm{a~=JQ1^Z28na!Ci@;HG1k6Sv3f91%& zqkX)GuwgZjOX%;3vi>f%hjpoYYS>|W+&g~K1)kzt*(y0Y59u8})RxP>T6aN}x&&Ji zYVFas=~65Q7(Wl{N318zXS+#J!csXC(u-bBm+VZ~+P3ZyN45~3yH?<)LUBEaX++ha z{B8{O>@J8B0Ypd=G9q@I7Xdj}p!Cp0DT4Ig1nFWRbWrIK6ltNUH0d4b9T6#^ z6M6}q1du8n1msN4nOU>WJMWtH%{TMwoA1xw``LZ%XRYVC@9VyZquUnQhcq&179ML2p(bd{m%@XyJjc5d*hCIaTdL$Y<W+4G zA>5{^=j%&rZK}XxH*q=TL$W;qH)bn4_LVA0D->4pjM#f4Q<3Svde%p39Ws>VJTvC* zOFxE-0L6X`FLuk@&a1sy5SKymrcI)D?3#in;C^Y=vbKGX8pwJ*+S1M|4uEyeWOCv! zHn}q$N?4rTt4{R>0yui-c|&Nrz;-nHUI~`ubHNQ7A3-RH42+`;hh(d35_I1l16%4~TZbVoMa~ok^D_NcY55xL_yVbv z#-BIi;jeTJ+uw?m^4rPDtXv};-QZOX!OD3v9YUfdaaoC>?sXP4(XXv(4X@KbL{?N5 z)7i<1P3ZW%K`JX8mNrSS;>PdBJ&w1epeSSnASI!fcKKN!|7rC6kE1EE{hvqr&&}79 zlQLg(d|kl>*xq;HW1RUDWKy|g(;Yi3O?VU`sxq!kYo)IQU`^QIgRfao1v2^y8DO;S>vO0s5TYw_KMgx%RaNY`^6?rshRbiFlI+ky^K_2*=%N45Tr zcCWdQhOx!6L&Wv)=p}T2X-BExkJR&mZnB~^V1&&j!&lD++kM$#DKoBAHY&Ou%7~QO zI1#=E(vIw{umQQ4%_uC6ha;>pIf2zg-z?ZB&~+v|o$zXjKH$I}o? zH&X=Ay$4eKH1ra&0CN8NZaDQ+Wb(R029=HUL!;`)ly_pWHr9a(&^36vUol&UEMs%Tq(Nhq2(LiGH#<{f(#p%F4}CLLPmXkJEOLYnaK)Z>MeOXV&MPR9B%Vpp1-fv&0cySPUO;v^2HQC?3&Vo`>&B< z`Tq^O1Fah_93B2uDtY&BV6EQYxHy1(zao?M<0$xuGf6Ek7yr*``J>}v;U+bZ^Io-j z@3pA6y`L2$avC{;Uu+lh%dJz&_-nl`XA!5yILRL#7Q~1iakxLz1)oMw(AP6qjrPRJ zzp1uw2SZHI&Zr zNY)f&M^`G?6 z>0g$*K%b%_3tBM>WWfrcTMD8ko9(+SVn&vRaR!fYSjmUx;O??!AZoU=Dg^sd3xqeX zg5`v26pj3XR#S<|%D3CN_JGI8I%)-in7eZtuZXm6fSEu6Lg0&jvgMl^FVgBlt>Ywe z$L)Qclf2R*%Gu+VT8XwvdTyESKgfU&U2YnymtQ>~o8DWAorCcbizS)&hH*<{nx`sT zkDIF+=b&2M*68Hv)`tLSx)kNUe+w%68I7rPLVxAM3V4Cyqt4IPycZc%Zbp=zl8i+o zr-GQ(L1w3>;vPIoJn9YRp;zs-o|!nejGgm2U&8oI4Au0U@4OTCylus+Wt8c8P9nPv zOLq<{(qV%&SZ&!{mhSg@y#YyI{`7)}l~@u#thK%H?9N2Vw^QY9CXR!gWJk_uqm{%d zXIFNuIRG$JOBlddDlZKChj{xIj%daha7NTrolz4}puaN{{wXANJ0lB&%Lt*WdpL$X zy1c93eM%k_F-l;9E>~IXZ?rG^r@33*jaZct#P(Uv_}+s}rh0aIK)zqz0Rr0_RoIU3 zM2^F4lgEe$zu`ParP~5{0Jm1*9qvVvApqHvt924QaN{rQEzobZEj58^{1Zc+U~f(b zf%eCINwa-y0_Bv%-b+Vy`16ffwV>^tOo@Znqt4lx>{=pbW&9*KpKKN6`7?RjG8uO) z<`C$b_JxIg>9$|QTiN( z*XL!GJfWty^u4KmyVttTq%C}zGxr`2bLQ9B=gU&vz0uJ{F#wK1%^E^|eKs2AwnKjK z>xrP4dhjcQ62E!k$RUxRLSLkkngU)^uxSZ=Q z5b%7dp5IGY6fq|K6Pf}!$SF)+dDohRGI!pON8LY6A$)_#dV*)W;VY0^fwTy1tT?Bz zGT8pt$S>`*=_r4fulq-5qnpTe>y$ms_iXL&kY4ih7AXR={?>>C7AARxqq(Dk>Sy$` z8?W}N;-syanwn~-sX0|TxJYKE8$A}$Jy;f9rI@H6rO}_5I`u~ni=Xmq@GnoV4IXr> z_6Tk_L~AyztCA^3PWa!`%-^WO87sJW&vfbV`xVuiMF*$H%Q)O2Jo(LNYr$?clf!C1r-4}# ziEE@iS2R+!(`&Sg6xZ1O2)4~@ZfZB=ck@NDeU8!kdv{(QPCJ^X(1H52;-JY4fY(WG zX?X6S?0FZ%PkWEHdG1oe`6KFT=SKxSPHW*<4T8s^?6~V2YpCJ%jt0c9{T z`L#*J2us*XN_Kj+s9ORc>Xi5uuzjgeQrLT1Gjy=)nD&s=>>B$X%ha%FQ_4px@jGTp zkEsce%OzW2`l||7A|TpnD;IU7GHxYiFyMC1WF|J%>Hr_gsiJZdTayuS#qc%Y>LCu_ zH@i%fBE-x@cvwTVzWb&J6#FdbJFz%3i`G>%me=@>=$_AY@QRIJ()84a!vnp}_7+Sf z<0iQ5jhSL;eh8O#Y4_mw@@9Hmyb&y&Ej{-Vy&*yEz=gfSKmgz>;Kvm)_N<7PaZp%w zTw@kHe}5N={Dx`{Y)pGHmuO$0PLug5i;^-T^OGOR;LRTaynX;$UCQCoHu*tNbZ+A7 zSXlg7%;0C@pft4-?U1BmZWD#lPasfl+<;a=ueBK9LL{F{Xh#y#+oSV{x_bZ$5EAPP z@-AAv9OGq^bcN>8Vl>u3!5Oa+a_9#{Ux9ygYan;7f2aC`MO8Kgng6STXxa8BPFF~< zu^jV%6fnz{2oOqPyC5Qg8!=*XzlbR0I2W4jglt9muciF;)h;44i-;m-55!#l2~DaJ zlz)H!rTy1Zi}c@bSa4uXte*b~SL*l@VKSt@-oLE?EiVHOh=5}ee2VBT@F(J_m;Tpt zS^pn@IuPOe?(GlrwZM)&RYZ%G(YeF%Ua;wVExu+Dpt zn3Py(!TThLf6=spJ1T_l$}^#z9rIR}XxRP{R)fz@=+?}Wopkk$y#&e}p6`x#;7AQ* zcK}5YToV+pgr1p|?xp3wtLs*=@LhWM=FXr3ApqjK6|sBzYJZ}QF(ZiysuC;J+pnVv za?Xt*ljP681Zt}-HLbtBacmoO*Jy-gCB!n5B*l^|5uW;cC)M3fh;dr8X=}nHv=^Nd zbEPF1w!&BAuWdFM-Cb|pk;qzTpEO81E(D{cmF|iV)2+r}mR*He4J9d$ zO%tt6tpOKT7|JKCY1dRs@a38Ad)nKL(I<8H<>K&pEn;& z#h9>$%-UsUEm&-fs0%{WyyS!Q5}%8Nh6Kf*n5LfmkZ!>~Zm9Kpq$ZwRCw);%v&9aB z@{su8s7U&d62M%u+6l|1rd!Ii8DiUU!pug2*I3*y6bp((P8&z)m`i?snz4$OSf<*) zx)7X642aSZle8WB&BLB_waHo={ru^o(eyJFwJl;xBJTAbeBFam&pn4-F8b_@@1i7D zL>@SFZ1u45#x<}9U1D`7^20lhPi{ABO)VrD?zcZ+rkkm!?4XPU2P;283DGpaa!&L1 zb@{l%pT6P!_U7ESJ{KVMk zrPXRV@!AYDklZon!UF=gbA+J-(YKYbH>E!@LCsG{+s?lMF1!{_5NL=9x-boh^e&3? z$-^-_+9i$bGL8vHX&cYl2I1(Uk$P)W_PGH0d6qP~$fwt1L>V7$^+vv@8psFWSAR8n z0ynP5+)#Vqwz}p~#>|aQtNP5Nt-081y5T-iD)$bd{n>*-THh%9itZ}iOrmyb{6Qq8 zySDgy{6f+XQ+5Yv$2Ndp?zzL<+Zh=0H$*F`bcuQt`(LV)%;i)U23E^EL>At zfr@lMVpDIY!hm4U0bNbT=_ehEj(+SEp^e}7NzakFRdsU0Kb4wD@20djM($Pq&LW@7 zVpn4pNsu+=N&)~7eOIyIn5NO|;^Ac-d!@N!t}_C?Ppjh_J8eRYFhU1h|VSzwGj-q$D1N||a{CBFZe_$?qkPQ2IOb-jD7 zU^$QVZXKoa2mU}YrXj&w^b|Me2{y+A%4`t`vx0LD9E!SjRS!pf0_fOji_8S$<76B+ z1iG__J;^x_mXq$Svs>mVkvc!)zd$1K8FJob>N=X_=4k?p^^MWS=`bcQJNB~ai)PC| z0JXq?qfHCMb5lPHC!*mNp4H?L!0Kl_BrkP8B38`r)Z*Goex=4}eh*mMH zwWhIjp9Fcf4hV+v&Az+e`cX?|Rg*6N)n!wgFq=LJFRcY>=bf2KWtp>+QZ`iC z2+nd+#m45bLQ^0Jd)LAcKxg}`X(msi)HKQqx1b@O#rJMm6|PCq5MH5f=mp7q_e4#&|s>bT7mBewfM-NK-kp67rEU=tNy z!17v8@nH*%q~pDW8f-GFs)*Q13{O=Y&^l>LlCe|Ob=hY6G71#2;6P25aH9m&!;HW2 zc^S_h@FZD|2G>KXK4hj0M!$pDT|YqS7&2P-AtcDY}S@?L6>WbZS)wkbW&Gu}O{E|iO>#xN;T^IR8L`mv$&u4AtsF>!oZBXd`Z!(?O zlGQnQlah-lW-IjaSWL`Gr(HMVqPLi~yjin4XM--LWtIROvu7&$+F5~`2ai#XG-B@* zm%N71#1_zU{-{?^K;);!H2dq$&)xyON95P^p131|ql#m{V;4q}WJwW^ zj&Ans!t3e_Sl~>*ie}YO*c?ERjCg5tqk}`*<#_|L=%%bgj^A*-n?4 z5ZIr#d_9T&To!BVLXT~zdM-?7iS2{En>vY6^ueyK1uuvn}z zcv>W@0}wCc2E*bNO^qMz9Y@0e!W4j^wQR!{)09b#;k2$ATLO>-bbUEY$l6P@S2Z?`Ufz_H!mdWK+A zcU!66R1yJzKQgQW8L?nIaG#EAioYM3Ssh{nq!vnoF=B*UQe8W3zI-UCY4`mgQi2e6 zgt;w9%yz9@E`A3B+43|@aGT<2a|MJu%v0}%IF0}u=m@Q36&BIu8=`_e)z#d-o|a!R z_TGtET0hLPE_haIJMv!9)md23sB}flD~{2Z_D|!dO}q0?EjS>BGF^pSdnKVGHG1~3 zbKO|z;9%ZTMb)5zR`#j?)AmTuPQ%O2acDH-MNhW*7w8Q?$eIs(NPIVw8EZCZcng2g zN|;pim|mZhwc(tfF#lxuFk;4yF3_!y6`P#ox0}z#HWqh5f9$c=~+f+dRtTa z3`(vW2TYw+wnCzP4Mf?R6nqx5$;Yk=^sozCR};X8qL3eF`SD2q>H9tRpQtbhlAR3= z2X*7b2rN0Q)0u5@{S+EAcj6q9J(4PL?^Ud8qc!h$t0X|c)V+AJ(kD3c5cSHMs0y?m zZ$p?jKnmbGq*pud9ebsXR{~G562#g7AFD~~ELHLEatf9mpt|;4IZ5vAj!XZ(-%~|S zbY8zvUp}te*sH>UmS8Ud_rQv}MJV#sezqA=h8VY6a0)Ope&E*Bp^|toIdb@mf}x_; znsx3|n8sYgOtb_>Lq_DqI4ue2*q}~j-4j9C$0=TdM%{@1gf-K7uVw|Vc<&Re4!gI- z=o-}=eF2aS&dUm9Pr{7Y+9pph0qv1K-v?b&FBSJ`7q-sz!~2367jd#m(V|z#L8Kxu zbo|U$$%Cwi0?CH- zBe+S!^4?k5uQ6_C+b8StHDPk!2{lvVGh}3hc{I>=Oz;97TH`mX(cI$($}CLvJ?saD z1sN1^j#3^NUBS;UR-fN7A1XW`|Dg%Kd~o{UT-r_m;Rxb4s(@i=<9xV+CQAO9vGiXl zY5bqhNzpusSyvkUjX%>O9abfVg+7-F2)TK=+&_!B|34j5xhfUsUtRrAn!*3ZY(s+m z1JGul&#J?mWYJHD^!xQfZb^h_h5q?<+4+jxY0*KqGt7k%yBo7&kZA7!-~Jc_3hrk> zvZ#OvmrP}!jl;a_2)@@D^tZg_c0U;fV82fO-v4}|&-V9*?;ikMc&Qq*njpOTIkSXB zs{|ALaQ$IF-`9{$Ph;ZGW7=%3{s73HJUi(P*wYL6drN=q55No7YQN(7564k1>}M;A zLpLK!06le$UFXF_ji$lYePvgW`@@-Rv|{$FV38ZXY&gHou?IrG7(9NS9T78ldAfz* zPL1Z|4~oS%Ec8uvgoYo}t+QnQUrKZTqg3~Q+9nI-z(BOq+p2BHw(aT5xIW$?AHO4$ zQM@hNfQR5}J}>zfv4nb0gx%jyn!U!Rt`pE!K28K2jDS#HVb#UFr!bNgT4{)BSR;r9EZtW#%1xjiuFmb?{488<6q`VDG^{yluE9{bhFo z?D|&f0UhhO?zqD3Xt1rvC*3Mkx{i diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/PR0.png b/Firmware_1.26b/Documentation/How To Contribute Pictures/PR0.png deleted file mode 100644 index e3ae792c2d9a5b2d476411387c099d82c6f23b3d..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 46931 zcmd43d0bL!_cm^t+0kP*I5aqPo=$05>S@p%sXS(7YUY%pf;kUprs52lnU$%X$~iSP zwN%6jNKvt@sGLPbL8Kya03<~~Mc~Cc=XrX+?{9iPzdzpZAAbD6X5V}7`(F22*LAJ6 z_T5W%){64G<)x&g6wjag^RkqbOplb5blK)jl5b>6oxe%`ZHT;VeMYLTPkmPMVPn8) z+tX4~4Ot3n-m;R%6w(!^W2UQ|Hc|*>UdN=JUUA-Tuoa>E8x^%e6C^eWo8Z zr14A0A6wFoZNWRFxozo2HhoRF6`}m?*Qc9xj2z1D@4awoZ&{xJ14>}qbE}|9)veXo zYAk<#IsqZ~g2ZnMrGNkdnHwa0a~T`m-68c*%rFb;kZ?AY*)aN#5LF@(J8_ z|D-|5+CmUIaU=lZ7=Toqwga2 zmf=)tSRVP<<&Yj3xJT-2<=5pv>$qT-@g0h6fn}3V+DnT$EEWSxn~JglffE%W_`Xpy_Tobi6Ltr8iiCG!mD_M z;XD&^!t@&o+2a8=RsOj_X#26XOdN`5Rr3BKuE$03fB?WMNHQGj`284M`el^scw}o$ zIi=5Zf4xWd{gDtSppbhzDd_D$yrUkwF%4uNfU5Trf4l(XWg878WaNskq;c*t_`qqd zTDCng0LHnu7^LDdhTtCf^`=FNd$rpax+ zd{P|>lHHy0mrKW4)G$cCN0((2bPjexzR}SHmpc*Uy={H@7xyER-PUeQ+^atvE$1&L zO~t$4&k~FURY>OUNMwWz=WSsP>VnZLd>w|D5DyXIZ&wy+q~bC|`t(6zWeYNqGoqa# zvms8FLTAl9R;LW~ZHChLtEI4-dz}(9e4rn$9hl1^m8kdEWk&N{Me(+d=9^1SV!BKS!kEd#8pOdPMp4qpy)N;S?%R2f z!p1RPCi~kLXlOnDAi{dtO`-&9s=-!mm9l($ELIrCW6)3yS+f zDjQYl>7l3b?Ow#ifrzsN0uerWBB55hD27p{Fce)zq`iiQP#;+k1$=U^!bF=fy15I& z_5zx^5`uAOM=%xKcoxZ7P!=a(wTAGoh!I}7{48WsruqEJ9xvgP96g2imC}t6HdrpG zH?iID4W7ITx$ydf_~85$-nYv1axw|;6oM5b&~p+SIe#)@zX3-hR)+7zrFq47lJo)i zOhSAW)yMuU;Y(+t7{jzN3SNByeU|}ha((ocQ9a;O=fB+P!8*p4qkrW|Cm9lmSRa-O zw2Z7NC3Q+h`7mRfdraGKq}dKuUeZQ-werO@G}2&uT7PhI9B&JQxm=s{Wg{Y?ps3yO zS|df-IWr_!`F>QwYS7@(s__pBP^;hSjv9pQL4>v6$NFI}ZHvKs1!z}sZl8ItTo}QC zh2ZA?B~a)!E$wxw*Z_Zru=I|8hY*xa$KsMqI?yq95tODb|7YajL*m_Zp&+!kLhpeK zpl_L*b!M?wp)YG%_%@1S4%|U7&{omD z2@wk70cccj>^_8m>$-BHC!n^Yzxc3cS8b=+hzo4$R6G?a!%J1+uoU$7^Of_eYGHeS zX_wQ&WO9bK!e$~u07(@|pT`#sLuBbRI(NK$!56~#GX(y|iut)4UfVU85Iqw~k6^Q^ zOIAX`ql`$m>-n$o<$?<07AdKx%ZuuHo>xY3BGy3TKIa(l=nQfGR@6J@XQYO?z)>wb zhgu(JeJy`5s5aG&l1W*3{3|&+^7q&H=(RHQ(I(!}aFRL}ngy&oyE8;qzu6D#qa^E( z`aPf+c`nhzVe9PO60FW%b}(j_!%VtNlyZluaFpPG2xVaXO55aJF>h)%dhA3d0j~dM zSXzXEawY~Cf0?Nj)s*2axJ~FFu{o5%?Peh@=^1ayEilpa1yKvzA9m#^)xY1#X7TRmg40p+FmJo?nhSg_ zMx*_t(BtT!t}I=*ZSQ2D8jDFo_`Ou6&y~c9QHSB4Q^;n@GHOqOB!FCUic{<qlp&2-~5-v^4`0gdEx_Y}R8;f#4y?XjqPRDQ`#vs!uS-9ZC9rEz3r z`QFS<-eb>x56!%q)RyM`#`5nAkAKTKdm!uPoty72xv~%FV*QOx(B{Fi!yUou0ajo; zEk5(w`;mp*$$i>S!lyk)yfsqze{KMNMmKbtH6uQrs?=A727NlgM*_lka$V`W>5YQ( zU>CKym&NV)O5}2xIcN2>Y3y^e-(3}YSw%(2Ce9J5W4xGQq?Gs5*B0%(ju_f=0pb z6`5hXOymf9v{zxn4&U?yYN_j4<`Ot?)+gcpCjg^?c{y`Kq$vo3-S*V8mcOB@yl$T6Kcb zQ1PlWkqH`)Bl1alF`)v!)doBe85HF))t{{J6ds*H7Mr7I3sfc-a?`452mWCmOSdvYO<6GkC+)aWDSe*as7)L+p$VD@12*zu-1{_7Z z4-#*|qRopiRm8gXYcuJa6ARXp)fr6;&@A!S}x_U`oWpl08^W;CAd8r@X zly!P+8Ln-A>MS)rF+tRpszYVt10kRur<4Pd==P-pk!9d+zTv!&WdDpM7)kxJKvKvl3u< zt4ybQm&&R@`XY3rztnFV{r6hy+$$?^D8=b_`dWiGZCyu?|L1>H016+=b$Jq4!c3gl zQsMY;wK%#qw$sa=eWIqAX*Ot5e1U!6%_?hZOfTVRyR}O5mX1&m4vQb1XdZN-G`~f! z2{}-MBIhR9!X3!?%ANL{NsT(#%9~t>fCVf|3T-}7hzqrEFT4n!LmH7h?X@x8j5utJ z@TvKde>`6;3rO|Xpotp;hR$<|3?8>=533R<>S%vtcYe+dTa%1`DlbghaKKdh*p030 zu)J4amcA!+YA&5s7eF{4u`Ta~`UutmJTc+JH(Q8Im`<{drFtc-olf|wHrShDKQ<}a z?cMlSXW}=q!xa%wF#jr6n49hbf$+X}(nfkm<;`NjUlJ)^vk75A1dJzL1t*esw{5xwb>C*=6 zRRZQHrH#m@U`E~qKHswA+xW4nfRb3Zz$>TGvWAl?=`-Vwjo zZJvv)ZT92Cx;w7XjG-QF8OZUP54AH-z0mp)ci(^~QCFKMov^xFrq6>#b3UGU!tu+TV_fDNR9`S)HC>!0gfaD=tEAc?5s1RN&`n_FBM~=4FZM zy3v5I7Nr~gpYGb+BX#DTv4NHkzT_B{qzWgg>Yewvc0I7g#hB7p6qBr>^27*gm)CMQ ze!}`42C%#!YnXJgMCR*xj>PwnOYsOFdM~d(V*58~&Z{(L&IqVEVCdF01NmZtDNfBE z=j}y0gzzh49cJ9EWXv0dq4#t+#L2!mv+#IC>Dg~9Pt8ej4Jb;<@7_j8Wmx-=1t5RZ zwSQ0&U1?0s8OuokvGUfVE_=bEPZ##vXOniej8oH^THlv4~ zzS|6p+L!FcowsK(Vq(S%xI$j)v3&}2QxL%F|!5cJoWO@nybLkil;{CxX@-7q`;QRZiL~FzyrlG1EQ68zLXSdVAdH%B$OyGJ7_6E=6jem*>Nq6HfZ-U z*Tf@}_Gat`-|HT7B~3`^B)Dn1*WUd;fp!;|HzHj$Iv~{fRuW?m-dpi3b!Bj=7;CS_ zDtmmBmdmo9ZNDckONW5;ai9X^sX5fDOOVjHT}B)z(^0n=_@JDgI*Y?K9T2yH_VGPvC&~*uk$t1948<}1%e4d z6sbJ{JcC%`SXvW-uCnwEBU|$}+`10}TZHAHP@Z7x+w`Id7uDVN1?^*ftLLHw`;I~8 znfZn&76E@kCH$XqcIKYtk2o z!6lu;RR~gnYB-feMMT;a_QoJ4wJiGet~@vlk0T!z%%n{$T*Nq*ebNdKc$H|%DGyo} z56nVGpG3t+9X?i7^!Os+i&LR{fknUFok|TAmbJk3ie07k7kuO`jX087VIjH`WC71C zdMfnK45z2MULmh&Ym>7um@$8tN7f%LSziKS*>e6A@!Y)?D6z?5c}bdciO5(qS^lI5 z?J}CYBfaR7u=Jocni>i+`Gm3ysQ#A$Zpo@JiDns*er?4pbs-%g{7VM<4cz>hs8#RR zCF_rSi>+b~wpX{vcyW(f_w=F|EqoZwCL{R+%xrK-~7 z?qQ#A8bcFz|4YoIamuBVT9YnuGEY+aGNhRYtpkPj}=bB}weqL%lF?4{7u;dEup-%;d|#n&-CP+$ZwInb+X z+Oe;%DZc{0kP97M`x=2|m7gpCjd!Y#BUdA`m@!{I0gSuc++&l>fT{SpQo*_u z?nnFR@gokgUOCXFzML})+D7J&Lybs$KzQrR;b^Rx0U#iz2s6~NHJtv`JW_nYG;B=O zKb84nkd^z$=b&>&=h{$`VS?rMF(ElklN{`5=m!r@FR15!$z@e?Q+RxR(Z`3U8>wh5 z^QEj0I^*(h3dIqDH);nr(x*GT47c-Z#KYl6LZLm)ZJ$z)CoeVX83Z?{(BmNd!a(~0 zvrtCH1|=<_DJ=E-XOOKyO3?Avm8xgn#zijf?AXFMA(Ro*%?qzLRLjE}jv**vtE$*| z_Z5q)TJ2*l;cP8Zm>3E)*Ij8Or*ewO318shML^9rS^20@^en7Z*h_LXVUt(|=vVYu z@_3s!R`H!+S91|VZxmlRx&Fo34R1Bk_2<__M;$Xi!$>z67&~n&`r!YhzA@nqo$!R+u$*@7iC1K!;ch z{toS`()M_8CeG<38J>AN6T@8oa>HxN_)O_>oOH5rb-;Yb%VAk}?y3)etZ_)nBR!Pp zQ-|Yj5WJq61cTB#{8;!tjDFkWiC!1=d$`3D*wbW_S#=jz>V#KV*9G$>TBssS)wp3Vz(7oFLmTS zI(u+QA-o|>)+zOCmt6xo<2;{kh`*)UU%s&*R|rHM!+vW=P5l&Czck0Wusn`}`PI|WjQ>#QSq^4n?rRo(YBouG z9L{f@wIry9-5hN0u%AKr} zi(L)9K=c;Vq*(27Hx2+2*$?Q-ye}s-8M267R5!Ir=D&$EglD!I)+lf<7Sihe&^%yJ zQ`1}rv7q-4t-L5mj(b%L#?&rG+hHQr^qLgxOe;h4mt$42btG8s?3`y~+9=?iU12VB z-=4gH;+*?=o>&`b95_>}yUiFnuPzIPo80@(2(s5~e~I~EC(X(EcEc_I+b%gm9SRyh ze%)C*a<=0U6FyCPVM*`+7pqX}RPv?|8AxE|RU`JY@2Pr;l8f{FXTe-{ZjtqY$Gf_^ zj+=B{kb8Gw)2zFHWED2#w)m+0qYs@|axtD;WhYjpo6gMqLQtzBr;ipD-I||EUePi2 zuH-e1Rpz9Qe>}BXh4%y>Bb>&m>UmuaDA{V8m1Ujs;D}Au35{PbG7@KgHI0ECP5S)h zEp#5AnOUV}%(~}Wz>gJn*6NWXkHahN_GZ?XSM_4hu`BjK@{?I;bIx6-P4s=tTM9YO z9$Fb!OV=sYez@c7j9^%UZjbH6famFwxS9OccS*hN*P$+E3 zvKB|m+lD{4fo^k(`k-kIhc*_SfHxE+d4M(LQ`YI4WZqwF&!e33l7D)1ESy|tpSu#M z>`q8-dl>T2z5yNWY1w`DH`MVNVtuml(W#?A;)!9|#QFrpkQxauB?HHE)wXxdi3M>DN7a6zxJZ`V90YT z0poWa`x?WzO}b& zc=%!^#1gLl@DVOch=w2pD+j^8>v(&&e9xCO|KASFAg0bVS;Qz?IrKgspza1Y?lX|t z9CXqk{Y;ZW&n>^FT-C!K%JBKWY3;EewDxFO=V3jAH2Q`>#sBc)^?SLmW5Ad$Un=ZA zx>)k?0<7<~Ec=RC>(oUoly(+q&RFhQl=`0uvSg&%kb@)UPRa$A-M{J!h4_qaRvV{E zyRzu2)=8fX*8NJhhpBn}7K0Xt^#^*0J4j&OTsg*i-b2lAEi%CS7YTDe$7vP#6VwtV zydkLR(HTy~=xPJ5xrt7^0>9#{NyXF0r<$t9OZ=;pXenACFu{IHzvUm_QKF7P_}Dez zK?7a0w47aDyYq}Zw&%(1{bzsf@&jA6^wNuWY-!Va0!{5TW4-^>_HZ{t+g&-&dgghg zDp__T{mlA=?TW|^mG#>N$z|T_G>b{$S`#pcVWACkR3t>>60ndx7h6L?So2j3ygUhN zX+M-<+L|;{8wf1WqG&PQLn6yqPdd=LtvE`Z@HzSzWi&d(6f+h_!XIXp<423&FHs1_ zU4Cwq0vpq-+jlQ(-?)7)gb**>^95489^xSPyei22 zQkCu#auT*j|@l&6k`X9%0J`mOLC1<@CQ`Wtug7UMhMo0RepE+-Q%E;DZ zB}FIkB>EE{ICM;cd2jkbUj=a%eN8@eEo+doW6z1tH z={0cdhuaouD^0YrDb>EF9nC^n4l@>!a8CUAM)&$Gw-(AKBkFej8UqC6*D#Om z$Vhr4FccVrQ*6zlMUkfj#uNTwccdHXxp$>wO|*6@eD@+>!!MjP(1N{|g`OsFFVw=+ z>!Dw0Wu9T<%f9WBr8L=zx=Tagj9+`SdoBX~ZH8Q&!iD?#z0}8CBrZOxE#hfWFrgc* zHb`6kCTkcYl7&9Qt=*C4I1K)w-+&IBJnwY_xhqfTGOaU)?{-$t3OQ}@+U^4IVU{uc z^wN{QX5-a=?Iqc*g$KpmKe28s3ram)Ngz02pakhs>PaK3r%p)XEQ|gskhFjfq=B0y z+fVBvu(%%-LK$2%MV16D$#DU}Q0SB0z03$%X;G26;jGXzh_fLvZ#DYuldppi9_28v zXe7sF63YaG`ChK;Y)1QuT1=HoZm4aIseyHtu9qDlCD{!zuTaJ+{%cQ^6PnAs1hyEpE1Yf( z#>SP^4cFE1{(?F+Q@bUz=fmnj?}yI+6689UZ*vG~Zy}jH`>NSLWaW<5sOHr~eaOUK z6|Y1Uj!3-fMc`xmyp~S?UK>g3o(1k%k0Z*a23qI|Lu^Y6zh%W=nrG`*f3gg(6K6D4smvrre( zzv5rZ&UQN63khWx2vtPQ_k4-Y-ekdaayqV;X6Ra$|R4`t;!| zHiBHZ5IXTzkU)jE4!aA#*yxi(#3J@WGuv!6Pq>P}d|{cb=~Elw317}9@F_90DJRnH zoIw~UcA;Vjeehne-MT*iNJFwCHm{d&_~+hyE^%rK`fY(Yv5-xRgRjxFXb)<(B21!Y zE~!6&tI2|8DcU8gUS_u40AWf1P3j4vM97@x5nPqtU{FU=Lm?88n3^fQOk048XaLbZ zud^H{Ii(H_ea4wabm^1?zg+$pa zfH$lBk;}EJ(|DX9JVK%2HS&VE^%7zL@j!^Bwrf#|QJ5#Mn{f6K9LeDS%L8fUInT)p z*Esrb5FPS8!4A+PeK3hfap%ePo2kixDZG?xh6Xi$Kyh_r@`@TR*1W^k!71d>5??lt zxeoC*_ngW+j%`eKIXf*budhcIS=AdQjR? zM{rRfeEHsas;D;{9@1|n@Mr_vE1RqNU)J4!q!7329P~+F?S>c^ZlSK!$ECS?-R+7* zbu#O$U0g#IzjEi2WfbN7A+%|vFkwOnq%>%W=f!s||47a+D{%dP%8|eu;bK_V*M{ZjyQ zdiexsw7ek+S7fceZ}p zX0UgxS}3C9EcQz zS!<4E{8t{>;897ej%@8eCnn887w;{hwB&vemR}_K#OKEwBokRcI`UrLD6QlwWX~#1 zVCwqBPb)9lh7_G}PJG*jnHSain&|DQ*8~)tKz7#^^L{IAa=-{!P1Ep`^8P_P=cr(a zqlJ@vaG?Z2<}*A33GwICE6_2kCpSGmJ9WY!R~o6mHLnY4U6~rk*={<2%VvmwYDqMf zm{An>^(~YEjskFscTZev&~OO;Fpn7tC<&+`aNo&%k4I5wBxZWZ_M0kQ(QvxlCN%Pz z*Poy1_nj?|yz#m=bjrJCx;Q}F&Uk;23Qszl>TVo`yACpSwX>auU}~y-U%UUlg;bbp zEjZa<=Z-Pobtm+uZlXfuH?EFS5836(!&y2Ykl~;7p0pJ2Pj!@7UD=K{gCr3tBB|)$ z_gv)nEg>-lf7FbImMp;p>8(d`4OuwvpflGf5(RpOw^S#$z!618Q@hD@w2DK$gc=f9 zO(X8Aa@g9Wsr}GJ>%PKoGBzp}1~zXQe|Uf=!!dofSg!z#%6QAw>fQ;1E2~6Mcd*K>f2%!yA9db!@^0|ujr8FGMrmi_Jx`Q*k=oot z^ZhK(t)!gFUiYi%l_N7OgR?)I{TDg<`%gS)L(Z_TL0xPoBAfi^+Y?2jN#Q)|80$^! zjk*`m5pH){rK@7kps)@#2(t*)I?3#UF4m%;HGuGI32VTC1@Ps;HCmrtD+`J&@+zo| zzTLWLchO3zXT&ROp3$FPrDX_k3z#OQ6Hb4&@U+V0{4GL*+5LmQ z|JYw18|e$z852t;Q=M&XAAP`@aQU7cw15{s-Syp04=XW!3QGSx3${;QiL(NSO?-N1 z!+aB=$?Oh-3O_5s>$S`{wdPAW+^+TLi8dFnDL`iiN~7-1ammyUAHdomXTebC-bdFT zyL!KLQ&p0iNg2;OpGrTnRXTFtL+Uk)(2oP$J{n@YqP}LJ<{M*Pyf%#-7q4KnneF_^ z^eX3?co~j8$Q+Clae=eu_sR~O`DZlF@0Q>`jK8a)0XCl7nS63)v|94pbp7^F94x)_ zqQj0CKURNxa@@n;45ooiHSS;$%alEqRW`dGjeYdn*BZ^g2X#q&A~GP zhq3dMbE^nHDont7DJu{Q=v_Ps?Lkq6^TJrSdu8wH{_DuWVBYI`_W}@Hm=U|mhKmyt z=F!2sGu;zGn z)KPTwVcZHUoUmVlg3kW!zyS_7q#r2t>d9Uf$K>HSGd>I4_pooycSfV}VnJcno8f|5 z?pmjZWN7zXuAoo8gH%@sge^6&b9hyPjsEv`ljVN|8~FBu&ETtL|0#fwXk7oPYLM*h z?Gm)L?H|=g;(h=8xx_)@=e9`z#CHV@4 z4mw+ACK?DXbsoFKHG-IlhJ!CNK0FJjT^76<)M`{x7pd{??k}v>ufI6PGGx@pK|`)h z#*X{B+M9RR&CB--dhS1B)puF=MjA1jfXL-~TOdlez+#)0wdjY-`{#xt1@AIOi7^4G z^Yfb6)wvqhN8Q}9A;0d>09V(x(7-*9&h`hep6sBHw`x+@%@vLSU$x1`s_QLJpGZ<^ z99I3V5)@^8b|XFKr}C2v(Q zs#=|Pb3uA(^s61&Lwe^M5kgK29X&GH%+h5wztDwLVJ=?HMPR?EoATawv1HPcp4aMf zJ_70E%C>;TC}907lwHi&kfZqZ7SqE8uw~Ggam@tk%dAO=C4@u7x>vy*{X&-y=}7z{fi;#M_VJ?Yz*@a6_P{S)*z!+ne?6*0_xg4J89z#{&FVw< zzk7A8K9fv+_ZAxZB4JsRoY-p&y`|7N*hXj*#vBH8TSV9@lSV4m-s|iQx36S(_;m=U zK66n9ax#(4?HoWH3Wdi%P^UI5n7I3+5jMoP-+p*^oW5k&T<$v36YL2+?N--1cZe}F z<|5y{kuE7hjXtn5hBTs85>|5F^6P`&1Gl7}(~sT4a~D*{8M2-|V(HUd+|;fL{XVi| zJR&QLnktQo^c)84rXgOi>m(EA-J7+o4+NecANgp+fk%0Vcst})y(9*Ut3Md&LPC%k z?e7w<3qB;n@^vPMqI1s%Xf->*&{(EEi+3xooBm)wjxiIQuTTBF-fC+fP=@kx@JUg;$IOwY-08+ z0VcMXt{w)qEmStf6(Y}P9W%MT&+cSZ6y>`0_$hA&Lvz3B&b)o5;cid1{Hv07l0u&> z%VCirr-KSIGs4EZes+tJeJwIipzTdeNJy}i?^$R2T^3HuRjA^;RlgWpm@sS$5p=Lz@K8p_t3k3Q$x&E z3L6#xh^3D&gIwXuU0TdEK>Q?3K#mzY$R+l}MDDdJ+<7dUgfn08WeWLJ`>IUO)Z&^; z8N8F+HpU8(aj9m`yx8AW7epHzCF52Q!kN@umY{!apjbGl0R6_IK8p+{>Q65F)fTU2 ziI}fo*E%>`KKwPcR692wjfa6d8mhgGXmC476lM=^XfCDH6zI@63o=328xdxJC%pX^@5FiNdU>x zHj}pnlRVNB% zVn8I{EI1;I2jRFb@!`yx$r~ml+EPi$KUcn!yb^;;pn4^)sF*rUwOo2H{7?h1VLQ9* zOJ3myw!p=28ME!B)ke*SW)6Kjv|N2=!%G*5@FTSoxE}ZmJWB_%6?^1wh(+n3F#;g= zok+s=L)QhLp}Q?NKT5taEUsGtz^1Y<=dDiZ!-K?&NGdu_#5ZC|q#ctj$4GP>OfVQ* zpmU}Atu3NaN!*S35{KJ-Ynw(2&>Dl%(7PP+QqA0Z9V^}SFxV_ zo!p(xNg7q7a0$d~47XU*UofmrjnPOSm1xAXHF96@bH%#m9p7~$cDTjWbtu=C!HlR@ z88QdNCnALc9G>ByQV*w6ToinHEsNdedMJO!$!6iY{1cJu-AjOhRzBF%;z<58+)J}3 zQIn4bBdhR>A9VqDF{MM1)w3od?c&5kFba1y7(2g0z>O5+8V<=`MGf7)z!{Eqhkcvi zM0|3J6|IEe>H}cQXAT|?kZF>Bk<)#9AcmUIUz{Ma5{w|bK}u@w@P$=<+WhF^=qn5@ zPVZ~0-^4=OY7_B`&vm{~@9PN99=u5k9J&sof}kw}Q)ixD_^iDr&+{DgGq1BBrb->X z4zQPLY*o_rNOjjzd9QrZdA$DlY@I@rbft7283QueqPF{lxB)NDYG0`Vz2!$!zU{C# z_rtB&Za+C0H(j)R1;&vCxhz`@oXY^=In6kUHU<9@7k^QHK#l;WJWq;LqTe3hCm>a~y)34<|B6|{kcK%9vM1ax}L+}}vwNyPZ< z1v2M{?I9thxsFspM>}`)RjjcqsWQRqi~hzke%9;d*c|ty5Y*NHU|uwE1Hl}bvC%)f z)uF~pV6ESw-cFp%s0wP)>iBk9J&zl|wn~(vF>+8!fUoz$LJAHk-*En)XXxOSksWzL zsppK-aOGaOw)~56gK0VI)GMjf?}}S@1-g9E@@b-YR_n35Lk+63dW|+?J^0;no$MT~6h5i<;tCE7!E*1dWw%!+Xit$5pJ$UCu zw1fA@?8<{zUc9}Mt>_f|Hc7Oi_Qk~m&|IzjyGrr!;&MtraXOIz5i+C;w4|E^)y|>_ z-xOaR1Kr^lHqnMxR`F#YEi7E+(_vtj?t1rflm<(8IND<>+`e1qNe#-SKPA%*Uu+H& z!%*b$j~05_rgh9Vcce9M0V^Qc@r<1%EdhUS?pgR0sE@mftJ%KOGI?C7GXrfPm>TW9 z?IMQlOCEPd2^sB6Ls@B?G#vL6U{`TUZT8iFQ?2j*{@!JSDB`DT-PwMSfd5j~4N-nb zR!7#iH&@Lo_Kz)&t%ytXR!7}ajNMmLwPkmv+C-Bxh4Gy)MkK~9zd=th5VG4hMH*&>?+Plyk#JK@3z zOwz!jOXvH-t?@MwT>Pg~iTC5p#ygn+S6I*<(&PX~95&&u72kvM%3{)D_)YyUYVPjL zbC!dN*b#wIM1MxK;{)e!PA6S-qKW=l2Mib_Kh)t6U_7h2N1}d4yPa}b;ioC|M2rcO z;>HkYILom-3ddt3@faGvzuzle3%>8Cn9*G3abxJI!(4UYMnvhOC|MoU@wryek@Bt2 zA4QFrI-GMnH~RFF{E)ld=kwlYFevj>6WKFr1I+-`p^zew^=HfEQ^_9P7tkZ5Y%Qil z)vbWc?i?|97teJZ+M|h5j5&M=j)k@0pWm;HSs?D~Nv>@}}#)X7?mo z!rOmy=Krg2ew5VzCmR31K#m`IlOO!{KWz4IBL5HW`JvMNhrNCmZhnGEe^dB>>iPeB zUi>dQaSyLTMVq9}hUvAliN7U85ne!}rujnxpDRdsuS+p3%RGOw=n2=HaS|QEEJ<0f z1J%{6ClatbI{t6!{;|aWk0f>ARJ55g3|+i} zJ%Sc~237FAFxI?iEBwpB`CpPIZXaX?jIcoHfFS{_UHqnf5V|M!u)|L#uwL#z1$}!D z!J8?KdRUX<5LjeH_0O^f*I~B6x=G<{?y%RMRvOJ|MwC#HqJ@++r=A<89B;%QGq+!x zn2ZDMn8Xk@;RBj0sbM$>wIu_D;?pkZXepNSj2X2)7Xh5pjVq@)n1)_Z?fDmvSSNJd8* zvz2l%-R<$>>mfLCIy&@Ua`ZOTZ5OA-HMk_-a5J9Tk-%3a3u1?cfNn@KF@|S!&;St5 z|Faur)IRM>NnV-7p`78u(0Dxa1#U7h=ETlC%tR6r#ZSbx$qGADMqzwO(WmJzl1AfZ z>2-KVcilZ!EG$5@t)=sVO-7i;SjM8Hdkx?EvDFtRI+u&GHI?)ZK&w%ZcpXoRU!b7) zZ<`9Qhwc__F%KvKMPzEkFz*`reMsVsB)F0qk!{=bA!(A*|B2X$X69Y!L~}N8C7{Wc z?66XLq$8=sJW<>WeRtk{+Fvl292MW3QSPV_;U3$i*`DCn=5hVL(pY+OZ_SqWr5h+v zu{v!qh%afLqCg)mvhf&PS=|@ycUevp^;5ca}yXvJ*fV= zvQk})4fO2AG7f4u4QWhj!2O7P-}W>~KUUp9ympa~kz`f&D^)ET1D4;r6xL0ZL2U1O zVYLZ(4K02OwK221>OlVo3e^U)&3VZ^F~~8#XRr;sbcHr8NauZXJ=)K|RipE!4yn3b zC1=FSwBqS%x^-xG-+IqNRoI|A@`9xH0^%nHqZYS>V=2w-Z32f%T#UM}R_tq0Dcq(F zc|w>q7Bbs*S;yrH6u+ItNe+yk74?-)(d6f;vYcs2iKnI@fz6Gjv*VeQ(;d_+{Ke=0 z$dc>Jl^gPTnEO$U>=`68R*FZHRQT2bQ}%JmE8_{wd$!a=D6@`uoWd*l@b%__3AeS= zg6Ta~XE{RxIjt;9zsAtx;a!Tn)BwWpwq8cwu0X5aP4q`}avlC*bTgGU@yANH6}N|? zMqaWbvbaypcN{VGBhV~2430?pAB0QUmiWI$uO-KQoRhl%I;3NuWrXb4v^84jS#Q4m zYsqGVDHx=KQqKhd}OTMbVEWNOmS*$&2r+s{To->=&twaf7 z5OYD=h`rcgj<}H>{8|9O!0+5#oy0#1BlscSOL`rMzxE*UL|y7qOuzOHs1|5TPz(3=@08dT@XmvikD8E1=~;Xx(&grFJU(09<3gdX*m-De%ka|A_n<< zfJpRJm5R>lqyVj4pivy`cIGP_zyqu&KKdI>Q!5H|dAUE%2?+=*!9}$67UwokVu^@V zpX$V-FGG>7zBB2`_om^mhb65pWLzlVf`m%#H3%29s?~Q}R!TE3>0Zko1&s)BjqFLH z52O5>z%I)5G+J14yI4al)H!1#{WA~HOqpg)lG!Ns+5ELnT`6dxchUxlw~>14{5@%l zTkC{&c3g{7eq6Fz=K0y(?^yE6?eNDatIF(OpzBSF^rS(ri|p#=u!9C^XWY@%x4%5E z?o-%EKUDhdlTnx+s&n;3D40io>)A+iiOl9DH3=hUW`nMRHRBZqtVnoW8_!KH z*3kikz;Q=@>04)_?rH0#2b>zSdX2i{ct$-EukDQyu9L|vk^Xo(9(zz z^u)_F@sg4;;kerpQIo~de;aeOVoI-`7yfd3p>!tJL#IE~F>Bh4Pipg43U7^F?o`(Z z8j7~yxDUs6fZAd@C=X#lN25$4EuNS~pP( zgLQe90x62hL~%Es@i$bKbmI;#z@t&T$ZFO-!s`u!0HZtEXwThwwT)ZM6H1Px%NY=S zTJ()!iZ1Bi$0wPJO5?e0^~N4xs7&BnN@+RXygjNt649v+(bjy)_|vowZ{A<`aH?bJ z>7K-p3JN!m41yM>G4m60waNL!F!5UUdXMMir%>w>SVNK*fg>qpiJ#844rQZ#JC6u0 z7AMnSyJNCl+Iio=i`Wl*t5=Pao$7~Ugx80h<9qvXDE6}>#C?iAYyjU6i1cB^y@BQ1 z)i_TH1~-2eeFA+qkMA$j@L~*J3@q0PPSpJm$ok-;;bb#^9>^M82)gl1=g_5p5-SpO z@|ydQFkOXX)lfH1x>`r>4~utC7Qy<}{>`Yf`R z^-iC3EbaJo0+cvwH0BD*QtKXG$F!0cbmYe&;eHj-X4#W39PFXRSBTf0Q1R4%I#EMM zZ1+HV=?Sb-8Fm#XnCJ*^ADoXjX+P%CE^rjAQq0i@NcieP^jKZmklLDB)>uxFB;bE& zUySFF(MiHwR{nCIfLAWJO5s2zZrM!;c$&ZXHom-4GDB^>GanR3G82Pe^q0Hd}FfD z=q1OQF;HonAi@r7rgiv%4-3K+eKHlWl$a=(l51s7?oO7p!magCAsCi;iKD|i%N3D% z!x&sRZkXksJdRwC!G+>M*jMR!T_w^gF2S(f(Y`$l#GY;JkRUwJ0Xc6uP~t#`$iu9u z?(ekTcP-B=O%uZ-U`Sm-de6#CzFCD}CD8I}e9X&3N-Z1d5j8TB9)tDP)uk}Bq`jRh zM+aGXqwu27YO|iWImMpwsbUdO()21h;Hov#z>|X&Ozv^}$(C)ARjZ*FBxJ+1G=3d8 zRun}H-GweSI3gef8Q#_1bt=-iNmCJmxs2(t2<=`Bup^?=3trnzvdhXbPijdLxnVxZ zphMrv@Meri5Hvb+^w;_j)mR7X$tZmcE%+J4xnGw4d!3o>7vHEvfGJv zW6eHmjK|$W<4PJD+_1V^Z;U)__a{qGPvw#EihC*FQg}shQb`oi3rFpkzll=#uu9bE zwiWWY;a1+`IFRZaOMxr6Uym63)BN?;eSZDQKPasA|O8J)34ZR*BIB7!+$rxt&v#e`~Zco~K!;X$v1d!egqX@v@CGUCZ&;JwA2c z)K0KNY;HcU13mpesQU7FsK4+3!5cL~izR!#E0ipitXZO{RH$sjpk&EpH^#n|v{))N zq%1>rV;{@NT9L*w!c1cf*_Xj&8G|wWUWNDf^ZS#>yk4(+?>YCJ=Xu_9&h?j7D)`P( z!d@<%p+)DKI9WhRJjgxQ-T4ANx2c<-b86-tQxtZQz&fuL|E7rPc3i2z7rl(6zk@}O zDh)US)!IPh84^TKTX*ZD7$1jLvCJK}D)U`=d|bA=$Xco_bbtry!2eQ3%YlVB?EnOZ zN6M~Ju^s12)E3|zO;{f(Nvcq)EkUPO57dv9LHqN?CyloJAn|^wuC*iQHf0|J+>qR4 zM-|Ddz%xKLd{je=$VRMbJd4cZ=2t24_x&lZe~{F{HT(yz zMKOvmw&ufiimU!7NHKqdg&JG2zM>AG__dwwu&N>_G<#13`St%x0g`#miQ+ld0V~?p zD(Ch#bPa?=$Q#v)w^DM9^A9FvhJ?ZCdEJ|~akY;u&?bqq0T1v+s!E1I{=PlxDz)dp zi|)?RgC${uCR$2Ex4_e%fjZUAk3l!>wvd>v)BNpe17ilV@hdgc_iBg5zKpNWxCMO- zdx74f%FOm5610ENwnmtKT{`f()i5YHirK8A_FCO^MMs7=)5tL64MirmK^p+0r~km{iflg83p8huhO2T&K;${x=?F>@lysZHLPc!ZPM14Qpg*ik%)Qd)(UFrjH5rF>@ z=-;8j>UFjn*2STpwUD>xVqEOD#Al?7@}25kaw#=Won=3dQM@FgueXfF3^ zwb?s)5vPYa$|Xcadtob2qGydrLKDTo9q#zh%+~5z_bTK3`o*yK{+Vdfnj>@mecJ~{ z8nX;-L7Yf697zk$S5%6Ys|i)7v`(;A7+qNxgFi;Bv4C))qkk|xL`!S%F13S3uG1nL zHE`CA(|)8?=9mAEgl)__?5~;j`u|Tj^&0oD((T^I0Hby>b7kLbxkMeuLIY~8tiS^w z$mIUhVe1>mpX0!q)9mLi->3#WhH`#+P@~GjAqT|lz@dE|619w$B{E_*FNqtZYx{?t z-o;#^Sua1G0pn2k+2*p`w+~8k<>MS?D9q4r=`xq}p8q@A+}q?LtIWJ>1(nmsv5j7a zhC*d=H+zDJc0vxg5U*j#x?nQgPK&(^$37bI-vOwvo|0&&>cc#h{fCuO2bkp^#s}Mb zBlDOQO7V)qNpP08@pAH%5icbt5iAY<-)~)6yK5zn>*HeQXn9XvFA#DR{xQH*`7_AW zFa|^|Fm{z0@htLxzjF}9R=)vD-rJFMW!biUNPWF!lkX!ec(!TU__dmiZTTguv28jY> zwaZ&rU@>M?Bfi|R4)fH&V&KA<^doP1;I@i=&-zakokP=nLYf@kpV)m$`Mnf!{Eb8oS0V?<{$HSc zDpRT0*_O0-IE=hLG+Q=^i^Qqu|2Lj&vyiltOg&R*8Ix=M5sn?C^a>zpO_Tey3QjBI z4v^!Ya&z*?>xiNb*@0XDtxva7nXh?NvJWJ?52#502i$51moyVf&LW{Z{`-jtF!!{$ zt(;}m-^a-DKoK0sJGOD3a<^HC#oLtA-ycA8&d>Ev;GZdilurTb01@T1<_M~32wAtT z4oa7)J`Dl|0QIuT4}TR!lpUxTZ*XT7dlBclxhDU6M0CJDlW3LULl8AY5%>-lL@m`j8@|O(IQ5e^Uy|%F+0vo7?Am6b}ws2mX}f4 zR@Dvp4x4gd@eZ<|Q{n=2W6nWS$K3B;0HLTn5=S_wu^@rw*`mL!V{{&^-NNaVCS)=V z;SEmwpO*bnWadBDE@kP&S$TFi+Hbbht_;E&fKt1n-i^}~RwZi{4Ita$#^7(8()Fy@ z@L}urV!c%Q+30$-%1Qy>6>DTEF|HUc0BS7%~@n zinFMaCESCn4jPmZp&p*hX)rqL+ULfoA%CK6&&tRH8VQODfAu7qnYNiyC#<+?7&PCO zCd2&Bb)6Qf6;U&C2D%gpWsDtV!at=={Ty12MN?j$4jNV+lDn}*Hx6?!u3zG2PO!Q^ zJ*+-iYv&fE__Kd%p?Z3y$L>U{ZN4wr{r$H@NZN@yogWrfSq#UoOr^s~cI6)RhrrF_ z^6f+|k&v5%{Po*gtv_XYMMzsRWhz?FKwK%~<;H5)NJz?tBV{XvG9=Lf(*szk z>s|e(Lr?V<#5~Aw>+@SD$iHu4c_paKhANNHwJiU@fw{h@e$j}UnU#^3hqRvfV`Z5B zFO5EjAj@d)W|<`mjTi1TY)%)?VV8|k0|7*>*XteJ(s}OtrmaN%-0xKeQXdzOG$7dG z>y-G4Noi9{d1lNn5;9+*rGgWETADA?D%e5F9Dqj2knn{Ojmo-7Shr|oBK{f8MO={6 zoH_lzDPV*fzZKjewjx11J8O3Enq3)HG7LE5i(CwvKC4i;-b5de$z(Ye{CoV;spii- zep_PGe#!fjSoY;hSt#Vft;^(|(t5@Zu|X_Y@iX^?E1B6v+-R5dmjkPMY!EglHZ7ji zA3vfb-0Yc_Wn!`sn2_;{rMiB$&8>hB0GLBJ5Q7iH`WJM* zZyKnB+eHU(P|Xin=EEl8f*nhVW`_~P{n0DqxwRF@KCh@aVNkgFQKiiN1R7Kd0XN^H zg{D@h`8!43Y;Jj>nY{(WZ3%vm3XJ))y9F^BGhb@IxA_4(xQ^9;uux#6H7uk8`@PnW zxOKsP32P_IQy>Vmh0FCUi&##!n2nHC(pih0^5bD&f*DK6S{n#yvzXWI38TdTlBrDe zZ$pO6xdknvbz0=9UcwM|pELWGtiIPf1Fb<`2LeYK`x_>gZF&8;i~sf2`z2Q3j{j`x zV)5b}`s?5Bs|ND}6%1+X-l}h%9gC;!2BkrKf(y=2kE{bR#stK6I{aS;k|;j!^KH9XWOS2biHj4d^Aphv4f@RX#|XZGd@peC^0_lW(G0wREpFT( zkQdGmp&VZcV|0ubn1s6MOlAj9`>Xk>`ug_uPYu`I0IAwdC6AY;Bb_j|1t+k59M9N5 zCj9K@q?H*y*S8$3t6}!%atqR63ur?Zv5t(QIMig*-jvn2LF3s@slZ330S(g-uUkV~ z*&#hr19BQo@nPSynKzg>*U9CgV>9oIn7+!i0ona69Ei&}Tj8kZR7ok({YD&6Erx&k zc@;i>8cEg8h+(#(S+4UeGDzdMr7~+PHZDXtf~2*1-?KEg_xXn74P&lp??-X0)#<7y z*!zhcFCtkzrs;}NDS$q|)p~dHT4`uEV=G;9>X1R^ zh6k%y(ixJ{G!DSy`lwzL|HE>F=i8gsbVDEC+#@>7|1FEH8ghQmVTeapqc*uu)y3Lx z4#P`kD34WkYI%jv*CzmNhO76qC*e1SOh_xFH z|I`vv&tJ;LJ}Nt;u^@jO03EjgCu2|nw}Y%OuG{^SFNScjx_%w}-Sw*Z6mQh90fzST z5H}5QVn@1wFonmA+Kk?>^pVW~*Lun7Q_Z!QNo?=>(nxn@?B7JVG?*e=M5ximSLBB--BYk$bXyn564 znfl)RLWN#bI{6{Fmca#>_(h-=SovKM%Dl=eEd4A-IU4D9=RZJlGHL?vp+fC<0-6~= zD$OY=Bn+8Uy9q*t(X1zN+#OjLe<~k-k0rgRFY)BSOouvmrMpoj?Mqbb{{g0yFqQ1e z>NTr0vs%{dM!^ACxxg9zCsW-3W<~SX^lH887{=Tr6SkbHR)&OZBpq_XX!Y69f&tkm zUp=3tJaR41SJY(Pt*}Lpb!~hgB#n(6J`DIHX*D0>J4cyk+Of+L5a;8-VuA3vfEJb8 z^aQzm#dIVKL4?q%lJYpK#}gBHpIq}XJbf}bdw-!ht8+dgNe?qs$7?LUn8u5xx-mN|X0JKP@S*bNz#KuU1d;1}-tgUe6{ zI_Muuz3aaFv_}}kxXzaO|AX} z@g#AVM6O5lfAG)vU?{Kn`TN!ae&-b{ZXR=SEGqKo zvOn3Lk3m#VeusZ`|41LC#YrS9YVZ;J3l;jYQV_nReZcrr;(msHsea_ZNvX|*Z zR=P(cKTpME!>uj`czTxP*Ks_`n*Vg{vYbzn6p}8=M=UD{pG8^}c)GlMX@Z#DKQ|QR zG#8DJX#-NT_USjE3d3h_{$8%l2uY*zD3D!u==&ziZhQNA?8G_0)B`qL$8tM{BH~t%eh@;@fh?qUFe>$rzq;TAh@M3H!DDyQZ8~P=&4>|ty9e)^(Cw5CkkoD z(EjGGxP0g~rh3%-7~JQ^Iq747g2xoB7oCb4@4?;_ODy`C`KO}t_h){PtR(Qhz6MqC zn5_O!ub%jztXK9oWL2js%~TmgW6hYv5~h4}f2DPC|5LJ+yC#GP?{dHIc_w`iu&zx& zcBs9#Nv;=L&H?L8&>P;*qGLv=N-f^2sQLcdb%RaKF0ebQRf$xsD6t$|?O9;{%azE( zyjuhDgxe+GFNXPL+R3FedkWh4_$KVmp+`Fv_yq(bL}b<2&zZcx$u7v%d+QKZ+xX}u znG#6$pt*?sg&1Go*&^B1^^2DB-${-FA6Sl;P#U#1$7UYfkUzUczqOyRG+ZRY2Y9ePcI;TpQ26Z{ceF;9z)L_-iPN9tZ&D39k#4P2f?uT*%! zB@^r7sB>o!K{%?V$_D$0-~E2WL=j?QW7&}{Gm2coi|GO{AusLpP+rXf}% zb@tP%3UiJCAjAg8HSX(0x?S$R`YAG+y~4c~`N6 zdB;R{*GcnTq2E1OQjw1d=Q4;6EB&;qmAio@ zvJGgvl0{T7(z;mPe;ydrFwr%Hux$PqqS}}gcTQPK79d$nJOReSe}3$|vT=2&$e~w} zFJa>_PIwiNBQY=S`_)gHI(c%f8KuLQ+!t9gMK?QAR2j47*yeA;Uo_fNPnX=+!TlUy zUIfG=L~_xo3EI3FnU21ZqRIR*+(c-VnVx+6k3yk|w!=yEB>GRopnzzq$g$Bi#7RxA ze@rd`Eh>KjdhbT}mGi~jH%#Mfc_HST*SGw>9o)8V!SN{8@BTx(DKEhksvZ>9{y4CD zkh6mir=h@_2zIf3N>!5!csAh~>n&=j( z1g^MTC$KG-$(PNzqw!WW`T)2BqgTfB1H)dkNqF$?p{hG^o$_s{2K~U^y!a75cy~Jj zN>?^>^H(iRJjU1tUN)6IT?u&$kNggAPXh8e1}$&7nD4oLq$ihzauhw&FGTp{9d8#F z)ccycIk->w7Ut8|(k+xDAV2!XI`00XDyA6moBc!gl;Jq3Z|8P~t)ZjD^gWm>RD!=i zJo`^fbm>E=-*Re~ZR>^pB2og~=VRLITh+cOv*j!sbeiXn3ss*sRiaWg0X?hz^o5^7 zavX4!>95z(GNQh4uN8X0Yo8rfj$^+Juqc0Zc>)qI_!9nODlKN_l39P_oW{RV-M{I%ZV5Tl_C;{*?5!!)1>-g zyzS@V$g&BheAnkF(~wuUs61L)lY#T}%{F%&MuT597bW(N3@7=~E;DL>&>x2#iQln> z>4!Jc4vHFy;!grR{fzqSw8Z2>G;Rdq(pM&)tOzk!qAX=eDxk(ihnvgpbFX`A2`yvq z!0J|N90yeTAaikvjWHQO)(a=lFF5?(;Td-8tLR5y3x$f+qj@4&CigwC<=lf8V^{8T zknfM!CYV$`2w@xMcEk*-Xr89}xd83a?VcaZa9GmE40=E;TCdm}bOUDS&%V<=BU@7a z`xv$ue;e&sV%{jp{~5j}k2T>bx788WzC3IOO{G4Vlemd40h}84j`O5r&74aB1wp*? zA}#?K6!40_gWBkU=O}!vHW7q$<|y5Et6-F7JGdL{X+I~Nq&hbs7WQtKy`ZNs{dA~h zXT3!QKV#eoO-;Rwb9#i~`Q{Eq@G3`$T)w<5XwceZk)64}ND;HJ%Y#>3F;>#Y^klG8 znwY9a*tv%5_?3YbeRONlWwOU~Q44f*7D*q9o=>9GZ_va41sYdu59hYr@Rdh7L;Y%! z(o1k${c$C#Ow#)3k^Wi50~H|+K?s%8uzHxp3Wvw}qRTb|rC8*Ht##L`m|A`TfKmJ7 zWk6$T%^fbGljbP1qis>|OVe51H>y4a@fs{ap2*^{N(CX0o6D#g=(W#LaCur>AAH(R zp4cC6-3dMQ%b4RifSdmq5>QKAq=B)(!IWXhLd)ys4ohfHA*gRwsP|t_`Nq)nzMxBt z^B%{$-VJeD7kl`Lg<2Ld;B9{76^@Fn6HmzqmoblY*bt~S_O>RvYN~fVa`L(sFKA;@=K->C?VCC=32{~PpS9j2p!rqY%wEsLhd?o30uvG zW(SJ;5j{5Hegm83^8LE6cFeD?&q?3esT)Nn%`JaFNY;CN+f5|uyAuNE_899@Thep7 zUlLjZ>j{!s9yqBc=Sw)`La*;;wxSCdx2H6`>V)Q5IdjBvH{q$T9?$%UcqYwitF*V= z?MU(N*wqEVWf!f`2-grXcY8VF!8r)?61jV&<=n%mYJvKV)?V4DGm+k`*ONdMIO2qS zIX%?tVBnS+tb^#id6u+xG*Gb`KJ(y=-!R1P&EpAu@8dI6R8C zqxdp9d{bKwmu@)#D*}B;$zg;C={(iT%kC2k7d!L1A!iK{NQTFcsQ$4}Re;i5a(#h^anE}Nd0YJ0zKgJjo>w`KXAT8js(U>7L>;xU6M#ePnCGHbW ztG}POqRr!FH}Z7wQEX^wMq>dIRuwzUwd#G>3O8d(!D1yKlCuBqtc*)cZT+2ymH{~osPi|j*Cq1VGE|XyBMkDlN(~O z<`+)3Sd8(>@gM6Iyl$lM}xR+phs(Ij}l5!7-L#<#--pQu+u# ze$3cIFa-I)G1aEhmp8UjyWc*aQCz>=UHPRUSeGUfa^O&Z^w0}ER7kX{nx)p=ptIg# z=a$8z>pu}f;Kc|#yF>Ga2b53S$D5gho#(4M?5QxyT`FuX!OG}a`y zTYK-Rgy#*p*jzieWC8;AdbYS8QcoB989(?KfTeArJ-dpAK<+_aO!aF zWRGF-tBq}|sh~o1>xpt=b-gopvcI3td54G{h@oB;Lm^KxYWO+~&(zrJ&udw94K2?m z<^*<4ZSlK9L%K(~A4I7WeJ%o^01HbY_!*GP{_QtxUCGFpRclc%I|E6P^v7hiv5= z734oI^8o>@m&{Y?mP&}b*GqgO7^UjZ@=~Qdg8(r^* zw5*GxgW@Q#M;k}}x&#FUqG3B`kC%r&Y%3XRh$OhLLs3n`m(l}$x5QxD!tYWCKBbTYKL3L!5R`+w2Q|E z68H7Bh~b%5OLR_47j0>kzp6bk(w4esZR?TWQHXDC|JEnA);ee3X4Q8?it{`&A(b1` z3iuku?3QGypD$L|t8v$Cgzqv!+n+SHU8gn8!po`*(}?J9pRusg^zK6Xr<&i=fjU$p zVV#XrvP|4+6!{Uzk|2IfdXI3msK>c#)0pZ%~K!0H3;4C^}b}p zrZ;f)!_6d_pyJ1_O+PWe<0iBCE^Cwg0M1S&13JskQ+2cw z-J$Sdg0Y2Tq7MTD4GU0~W@>kOZ_y^yJ7u=#ckj1;$xY8E%(SARTcZTjdzIkFt!@TO!K#7?tk{#xR9;agPS+(sv;2mRyX1Y zJx9f>88w^pPbM7hZQ}_AF2-EN)QTr`qBrBioS*7|Mv~3);E~h(@4f-oLa62Y>7`n% zTfd!iFKoS5oV30?*PUp`Q3@f)N8a`y^%=Ub9@($eg<2ayb`K5U zgRei_-tS*g3F0~+rVh`@ZEE?@V)~&hym!*Ta_X;;Gan)Lsj~9=3f01xsB2vfsW6t2 zr9tY{R?YfD?3N5Qq>#M6h1u*2zJb`Xo4`Ha-917nS7yGDIGtJ4Xi3B^c~=a|Oe8m6 z+j{=oxN))2$JS)+$@%gd>HkRcMcreN3S0dd<`+k|E%S@3GF?T~6qwf!W#Nx>UWA_n z2vgG)zjfjc=7^T$z%%tU5Bm|%Fx7#fy(}FoG(Zv(8c4cYgLd^Oubt_PSE)@`Zpxs^ zm*>j%RwOg`IdV*2stL7Z61}GU^_JLTv{-fcUk^Uhr@S9w1l`0V+rs}Ml$xIdQzZAt zHy5m1LBi}c?(Y7Zn5Ub*Df?mTmsZby$2hGO=Y)n?w6;G}11awsp}gAMA&Kj38WrNw zGQvo@DSLDgJq*v$4+$$(xgDNN13X_Rfy*;Ru=j@~$cT*XrGO zgzstsMYWl%2oZPGi&>ihMjO6 z!I6&?FiMZ=o!8`ca}a;Z9Ca{SZY?ek3VE?vejB7@yZvB9o1xB014~JDEd)4ibZw)C za368{L^sRLRE@AvHeTmGx~$9=KCy!rrDgPbzSU44w`O803%W4U%=J+r+TiB*aTbxp z>J_iM0ZI?pb)sjAFy`o5hlQ_?B7Y;HGq>gtHG>XSIp{XhIQ%;JtGjP7q7IIp9|MKI z+C`%+dDgYf&T`f;%^6TH>A&jl(~0+ZcGeMAvgoI z_Bn6G$0S*3W(IxaQzjxkeiwbYryN5#$0~pRxU*IVZlQs*o%>ZBvy30Mq$;O%&lnWfk{#`qRn@0&zcZ5yESn9Hd@~!S`5NIw8 ziYs*Q$5LjyYuP||xAzQ4Nn?TDY_HMyj_1D6@kUn> z|E~H1lU9$ijMbQnwv3u^)#2`w1#;hu9EGZ`yGZ`0u59UNTv@T!Z|n94Sqr>ApPR_V z0Hb^Mxas)Hmq!L*VDC~)guS+lH~$7-4g>IJg)in*J&G)}*yg~OOmbh5<4RQMwdZLs z*~1Cj#?T;D_Dycz4Wd_m)(y6ckHik_Q$h;76ud&W-Phsqc(4Z(%I8{57;~l07yW>W zf$%ol)BARa(?RF38dwN59%1e!UvrFAW}w5Jr5L=yD6Pz+zKy0{gU;oAtkA;Vmoy`8f5IE)(}WQl&`*1Ocx0`6I}Hj3cQ1NA|5pEo7$`+RtG1!MfxGIeWWN?H}Y~vHI@Y1(#&-`@6vgUtoE*m)3M$4U!mwwCv zdIE&}e-Za64&K+vw@2k5_#4*go%>IalFIHkf=`Z}Qj${xa(qD2|LwG}P}Mmgiz{)sdV_BSq(s_XjV~Dr{hwKv%rZ5Co`n8z zWu*ABxWb)wZCP7WYz8{565L@3n?jVGKZu2_y{Gg^Hm>fzy3N6v7EWKhecRy_)5k8x zo=*U{I`eNt4ML-e=nAqu&HMs~{`=RkUfHG@ah9y{z>#Y=YCf#v8uH^=1y=yLgB#LO z$1OOaw{*rE{Iv*9;vK0hSACalihr+FA{M@|V=H3PI_K|?-D8O*^H(JEc#6J!jvo*Q zf1mN2YhGNLUsU)B#%*3mMI0I0aSjW>@u2^0OLEet!8ufb@AAL{<%hyg`dAvvBtP`} zrguy#@0jrR5S1!@Z=ne?Uh+2pdypBlGWL-e%2W&S(sOa=!w4}i22@X)rorpx71WkU z+>1bqj6bS-*jnSHpUk(TwIcgmZh04nxeQwV)-TtyaS`dAfW*?X^y?l4&P_?!A5l6o zxih5F9M6md2Sg+~44!r|Tw1Y?|G2V8;S^4sNIt48g_&OS8MauyV9wJt6FFyxD{Npx zjf1WSZ*TR+)nQR5wLqx>$tX1b!dP_uzMe@Eey>Jc&IdY$Oi+}$*4du}S#E#rs0mLZIOc;`FOL4N7o}v{?5xUi z)?>&rMOa8zZYM+r<(tyDIWH8IN{BRECb1?kdOj{z%87bqRM9SB0T&?u{jb&6J+JV4 zFZ8Kl%ht4PYHR5z_REVQc}bUTr0fLJl?VGju6wm)*p;1CPZx+`rBS^pzhJQtz8J1u zAJx#A`b=v|7!|PWGW<}hP8Di`1k(8)=`g;+BAj*|;6l!!wP%~>+C2O8~4`4&BKVp4zagE`<`;VuI962%dyI&h#GlnYx3eBDND6}QXLd?Z zA>s{GlJ>L`MGcU-?a~ReC&0$I%mH<7Nq{*{u%4Ok3>klVy-hsj!>QR7ngnUDYdrDP zN01~W`{}Yj88M-#RPeqa4oZA}@S4(rGmXNK9S^5lzDnGepA~Ri{>!FHCBithu}~3g zKt8Kut71@$;ps>~%V~jjMd0t3K9fxSa}`K5vf~yt-`W{5q_Mz%XC0Lj~das;J6-7z}KFPdNP`^}_*v}Cx{i95X$57GR5Cj|brteX<};?a%h`;q?^(H&p(aMcV}3JWnWD2*)V`JOSfKu=^4ebDWf`4i@A_H^Jhx!5>Nc7lCS z@?~_3!s^^JcjwPE0u;DgH$!M**4t_x;>0=mYO~TuvU>8kvSL?Y&(MP+#BWv5H?iFn z8pB$_N{UQC^DA5&Jq@+%Pp}>qqoMC>zHx+4F97UIDxF3V-qJ3Y6hn#V9@sIdF4FJ@ zctmxGvl`IS;yuMXITdQ&3!baY!`pmOsNWtQv~^xm3V5b_S8yu4v*SfpNY^IPR-L1% zEP>t*wj?=HMZ7e-27LA>Tl`b|gG#< zMgb($qDKSqBn9ZI$k2z7Bf zq6FIE*FJcFrRM+X?WRZmIYEwCc*)zD5nib1Kj5MA!kwx$SEa!(Q_*nYR``c~N4*it zRe9y_)4JGA#JBg!TGky(wlu!$cffepkin2iUGXR70!1%;>&||kHqzO&W%~x4hy&(m zVx#}{=IMB>L+yjjuBufWd*h{#iW|#}Yj(>AlG(<#kN3OdG;~Y758j+vPl$jEQ0S)|t)c8k+Wv z_1x!gA2C?7aN+CV4uAG^*S<(asIM&=qpTtV&TdGb55Kny1r`kLCG{-1Udrqk9HmX5 zRqspV|NeUYYF>mQ`8PS^uc1;h%?qk5dO(ovN3DUB26uKS=+Il9_L-uaE?i2xiU^WE z%ThRp5^21&%e5y>{V@QicGUZD7%PZ-O+D-G@(MrF;E+W)pF9W1VHa4p49x+SEreS~ z?)(ResY`Yg@Sa^haI_2a;mHKs|KblIPWZM>768~e?4OBOWRm7#L?2%VN4WVeSoky3 zcbj$kT@t{c{Qr0U>b&gPlQ(rVzfO@rEuy<_KqsocGd1GZg?;h(efFPrz0mVU{*IY^ z2?!S`d3UTP0t(89lGtJdcV-4K-AJ~W9fxEeJS+0k85;7avIgccyV7|dFOw6}n(Dv4 zGS5b>_c;P)vq{_wBq{^fru~6lG4h;_aIp@qu|U~N9;Ea8x!v4kDniC?8*ka4R^|sO zdF^a-2g9R?o=y}f*w8l!F%(W;;r}@paZyZMyv&(qe<8%ME8LAD$oCUG=o-Q|$Fr6} zyj|?&B57clc5c{6`fn$JzhC2p=b7`AM!vc^DENdGZo|*AiDR#1uaNq1{?u=zi)h4= zh5?vJa&$K-DfH@P7cM+_TQ3@adS)_aK5CJZ2likt09iT0CBd$!JBT^_=9$tOqLMOy zW~O5Da@OlqyO2@=V66;*Y=uAS&Dzaz8jAd$)8BE2n3`-gM`nOSf-DGm90)TS-mj4O|;2VJK4xUDEOOe_224Vqyqp3mJj(XCw zl`)Ov1?l2;Bzfo&B$WkAfx^mbi`P(e<@6+}51747@_f-fq*A{bKAr(O$0C} z2HPKXxGaI`cZK@!Z&D$A%a;vZBwL;^gFdFYQ-{QCxj<#x#^8*tuigyA_fkW==%37& zfypDv{0^;APFN?7+#R6X@~F8?jAVsYU$@XfUvg==f7w1&ZB_H1|2}3kb7~giX=6!f z%j4r)}O6CS70f}&b4jRrNH@aQ2R3&U=#F8~@#l)t-E{_MJ zH$5zB8N>eGtq1?VpZ0neD$PbaLiP#FCt3OwxY@bn~;Bc>p`M_b__Fv`byquTy zNh371KY1~Kplgf_yo+!(7kd|ot?0L&n!*;4&~Yu{*9@X$txs1vFQ2px&p925$AQzV z@j=zc6W8WF)-H)$;y-M(Dqad#!Mu0B#P-e|+B%T1E*xR4TWEgmP4-ltg^^SIOb*j@eZ@ zAS>(4J^kJFIMC^E7C1Ssz}}Bu(HR_Y*w?`!4V+p@?;PoaMsHATDB;(@l`{~u{QxN; z#zkUl;1&lPDW_z%5>1%FZ_2Q<`-D!jG_AN^`apk_4>(`na+;j>X;l-HJ-cIjM;{=z z@VeJr?@B&U;_IKRf-n+qPQlrWVW>X3rtkI9qv{6iK9V(QACmW>tm3=tEX10U*#7V7 zi}E+YMe~m#^4~MTI8(LGn?1n2jO2`xPkAtpJZnFKG$+0BOxy{?X;eVc&yD@+B6{V` z#i0mNP8wJ5D6xSQux-Zk&C^Ey|B61n8U*{vEVWlpdT5A zGE))mlv*ZNA%&a`c?C7`v$3BzE_GOf5s>x}+Re7Z5iFvr!t4gnYjLuxd3_bk&SyI7 zh3s=~5A5MObv;RAIqA#Am6@$W_2<^yEZj6hB{Lca#JrALR+V2QrO^Nt1sUuxK;O8d z^o7~W(Ust+^=H!Zqrk-u$0>Sn2{fV454iZF=iV43r8lLYKYw0y?6j&Kn}u&mX=G_! zR(B(Myzl!gO%=zQ?Y&<+DBxg3y9-TK5~+3NNMPGG$uIfAMWH5x)#d9nu=DhND5@NZ z4~#3~C+umA<-0B@>@y5gMgD_;?M?ON020bhwk zWZE9el?3-08zbl?_xpY!d?Ew9vO7%C5hhlXB~e~V zDcm_JUQ2dWhqIN6s`mTJqv+yuisa{V*lbI52KeVp3;GCJfkJtu$(Vhik3rs^;&ZE# z6s1F2RR?J2Vf77)v4wL|1(D_Tpx=hw(n=16`;#MfBdNvDQKzD`bd;To54Z~gp;m)6 z!i>h3x-nSBMV*P)FMluDKj=A-Zes<;7M&R2w2yM_=y4%$J|#o4AwT_a*B}2Li94ap z|Mge&AGamXaU^WpBSdUmX`V7kyccC5Y$JG(vRpcXedIyAS#+Wvt(;FcS@o&Xr}7(8 znxSe%eP3<5B4F}Hc*x%em@VhK&U z<9X-Xvi{wIRdk2K?A0LOec+WMPI=$Xk%Z@sAF^8We;2ZH9n~wYBWowD zhP8naacdb{`z-|FK`&Kz-;*nsqn8Tt(?5!*WyoVINm66^w%`N>aoF#|hX`lGqgG5` zbj>=kqkxh0{&H&pYsyl8sr(6Y5^^g>F{I{;M+C>(4kjNnbVi)rgXH=Qj?y)C>DYYp zqeUX$^)?jg%DzQ^Fx}*gLf6&FNBnK|PIyj;!g}Z*gDHO5%_rAvb;E znc5?B(ZBa=A@P3sA___c=R*wzzLhi0EcvyF4rm<>ZNPSq{feHTbUSNR>Kp>t4TtGw_#0XOqJ2=AWi?NLNJEEvsZRuBXHV;t&bFOZj z^{^wGn-JXKK7ZbRqcubEgx-=;KsCOd-mV+EtB~Cdh$%*(;Htp$zVqZLy@moW@x}}? zxrdrsby?;Y#2~_QSWUSxaW?lyU?DYb6feTvg;F4Z1CH@_f`@0Gr10YAv6Fa>zT9yL zbqWXM?rGTt@-2^t&%@N^bxaLp{NlBg`4e7fX9jUKFM+OK*jcaoYWs27hxv{_r9jt* zRWvOV*~{1~bZ%69fTRf?sXa?R!0AmCm4le$WRKUn_y4%!$p?hjqE)rUqd&@A)%_|$ zw(1*h2q!@iURvDPK?rjXoMvuR0i-vFOa(~7=DmO`{Qe8;j@a3h+^X)d{rrKq7SfWY z2!84Mz$|?^k=GPf$b(t8AmbDgcsn6C*{pl?kKJ`nWIQU%u0`5$LWCn>-5ULAp~;5i zTL>7U{bufa6(Bw8&zIk-Y6Aq1;yJ!oDKo&L6*SyK6oB z>^-C_o?c+O-`o;TRqHR-`|WwrY6;`P8F1tF9&@=ep2}lc4*Z-5_H&DR#Pihhj4lrs z?eK-&J@o=+*6DY($bfhpw&qHdj;?TqxQL;S1T*y`wmcp79&lWy->niM!rD4Glm@Exi+r9I*qsEV7vn8xzkkIl|SC z?QJijn;p9g3!~!~k6xAY7X8rkGJmv#%Q45?zVjBYw7Hy|SXqGd6n>%){U%X$b4p#3 zU-ZKbA{E{NRt1K$qe=)u40v@unsS_d~U^wl^7j!VfKV*urX>aoDB)?ZyK~X z;oaw3`m?cbVEAHu;4O{8QxO`M$T&Z4qMsg4!@UOYv+ug{%-&&zRudN|0XO@Ro%nk3 zE4<5Bz69$|iqbKZub)qLAg+@oC>BZPMrN3_H{X9e3s7;1dsC~Tt_(^n_I2~>kF-_P zlJY{(o?@Md;PK>1Nrx$QF6n=Dl&L(q__LrE$sM1nNNPM?^wtXcin148zIxF|d1lUa zt~od}g2d^D`A7ugGTdNRA@BAF#zj24hO)YA#SsxT!ErcfR|#h4jhj=4#x2q9^H?Z6 z%-rP;(XHWq*#t}iK5mXH-|W~_C`S_4lZ&Z|=WnnP;l+M>#B2OH00HXY-Fnt$s>Ai8 zV=|DP*NfyyTC}j5fnP#Vb?Ob z6h!3+D1 zjVExRsyNwdIe|M&=r{nJr!BEEH@|ttpHt?~{Tl14^Qs=izRTzy3A3pNM_pV9bN$}E z=Lh{CM?=a-Oe*A!{*u^us6xJZ!HS8+^jIkXDCoiK?7Eb1EH@y$vYOVS1%?2ypmgW# zX)K<{0;M!njkK}(cebs?_MPXR+{$Cc?B54ZHp=Vh5^u~*GRsh z8)!Qa2ZY}*Ka4|i3r~c}xq%fCSB8m-GmursXk-^QHf!rf* z)fXFk&%T8kZqN-1QX6et*CeEsm;$MNi=XZWg?%boxjm=h+zqO`@9`_X#DACqhx=X^z}`fQ4fmrDB@<;C znz$mm1@tRRsn|ip%^o?sJZALheyTC0|NMym)EXx!-F9amY*r6lSpm{8J!O@!j!(q) z$rbd{Yvbt3XRDCH@HL^R0ESq{{9%C+mbtC)FTr(+FdGJY$6~Z{avmnOdA_qh9+K4e zV>UY~)fxm6-Jxp6;tdeyzsRCdy|Y~kd1Op;{?N?qL=BVfdR(bCHTSvu6Zk;;Zrrhbaz;c#xGSeKXghI z>pQDF;)%`TQTH0g?+6$O-suaZX4iyU&Os(!HxxQD2rxKHa=w4^bc413)M4L3cROsQ znr4_y@~anda0BX+Ly+*Q_#NjvfrWU3>%dU z)%2W(fWXV-8(VN@yQHB!0vlG>Dy9=kQ}reDbAf5;(thn>}9~g+hDLAy0S?7!aGttC;TbDY>0CrQElQ#Q}(jVV&UCTf; zNxy6E<##2Cz>Y<|qn%M2Q5S?aM_Q*g`+_{z%{P8aaMPX!K^HeAIsVjb z{b3&LgHIl5y?6rbf=ZZo^)oiu4tK$d7 z0JpGje@%8u_EXf&B(VeFPIqM&;e!R7PS8;?aNCR|dVcWz54x`%?m;h1qP!tC@ID7R zvWlDtDT5czO`n;ndV}$pD;Vr9qw==b(t3Sf%^G%HomzYNxVe3>sf*KY$Vrap%Y$^V z#35;JojX)56oVVu6!G8Dtya|kYwz2`q1@iTC&EV2uB3=+@7iiJ*byOzlG<%KRZcU8 zk(|v)%m|Is4z-DP+D3%rw8IRU6Eg-;sm6JjF*6R8j5KDX!C;Jjk81zEzwh z^}fG<-s}DE!DFrU+-t4-zSrlz*XOS7JM%H*((i=E*E2u?Dm(ow51*3VqvK;ZR|{fy zPjM-{u;R};4fGJ#r^c%Bx*QIYj}kUOp2>t%GAX4SqmEXYQ|A1qLh;lCdys(+sQ z`R?p{9T`?5n>vu;JJr8;cfkI)Ae|`iK&fO$GXGoH=((@H9HFdDAlEPfiKLX{YI8NaVPuEAWg2P63XzbGK9bT4biZ*YkxKPO!$H;0ACU+ zn~?oTZ-hQkeNLVTJ-t0q;|9sv)>!{+aFWD3hr+Ts^&7agdlQ4Wzs!Bm>c{zFdE

    B$J`1iemHT7Z%(@F13)WgdVCJ<`NTDBF0;KIcqX$${D8;d5o@>a`*c3 zo7O9faf+;gXlNWYKUL}hE24fxWpMocIBYMYEc)VOZXt3CzpfavjF z38_)xg%zQHmLIWf#{KylURx*PC5f>yi1^2;2{rl@D9d*=#T)#DQ*U5Ji$_dUBE!db zHkI+n==rG~c3d=AFsxjqaB6vWT_7Ofv7$`P}8I64Fb23p$u{t%`ewUYT)1-uT{; zt*OdgZBMH_-tRxD*SfjZuxG2~nc|SQJKhj8W2D({>ae=XFh5*LWf-xrDe;wKZ&iZt z5S^AZ`*f*0@YdD)5+i5h#d+VTvY?DHPf$VRU`pI%F#37Q()IJ^T;(bRQI#J7E*vMr z3yZGCn;I2-erzHFsFu-pyJG>HDFbf%y(|5`VCZMuwo7T&X)T}NMXTDDO}dUWX*&~o z{P-|QO|REs`*mhsg0)M)!g*KV-l%IX8%XQ4W_^rKetTsWp)fI!V7WEE7ZhR*#Io&y zm<({dIG5t4H*DE&m?pf@j!vWFHCSoA`^%sCA5*C;-L`Uj|I@Id(t2#gGIGz`?0w3# zmr*};7LKq2UW6|p%p_VrpQV+QX~p|)D`hKev;TDO=cLj7YR~>$lIdO@-H_FqE=N$D z892iDkdAv`kcmZc?=S11qoD5w)Szfo+};-SLeIdeMgOWkp6d&V9a?~qF$s~)FhCCh zZWd_o$x{90xBE5^hrU>}FHjxcD16@Z8oFYBXLBpw{ixcLKl=n5_u2yWX|x(0*#w_RqVzK;d3 z*~fsda!vNGnJfSC0ry(2tbO9Dwq;)F#BYthn_fP~+LC`=T~cCB?TxcJ(W{aCvh+<` zZ9o1jA!@dwnc}^s;5D5TZw*ajIR1U+jufkgZzRRiuYy*Ac z$l0@0clFb_-YB>;TQn{ zQaiYJosSyS7r$A7?`ke+aBIluA9QP=7*eJkc^%^9^@Owa0bq#t?z$;#!Q$A zdb@bU7%F&ld&{2j7DO&CA5-eoTHoz~6q0%bn!{<#D&9ONGXfLa;3K((V4*Rz(MCI1 zOEB-@!YGT^G8p8y6Re4&gh2-y=t)UcxPrnM)e;-o3Fzg3SW8SUxTs|i-x`%j6goz5 z+A|}bu`cljS`$;cVMFdzbyMKJ9WW-MZ=yV5Qw;Z(XAfC*;x*5&z{Uq&OuHDqyFr4& z6Pq+o?USq+@+e6qDE$3!P2BJfqpG%R{i)ixa6h8&X9PNsI5IOSoQs!HV4+OS+Pd#P zNToc)w1X!X0ntbILi6hwc}zENQS)XS zW+IJpPJA3d z4vw7t<3zRS^uGBOGg?Ss@G&EiGu?FBhF&KzqkVeFQs5)>4I9Xfj z$4X!J#1l0T`Vlp@Iw4zt!#)TULU&W*dt+mU^KjNtJ6W>^b$_&%73wkYW8YJN3t5SE zO^D;Uas*nUg-%2bVj2;u8QRSY)92kuX$&%gM6xOMX>m!Cc&MqBb^2d|hcXsWcY?%V z?wV081EM199|5S?<*sNm-T~}%{5#>}T?9%V|7DyBWw=5$H%^7Y>>2kdFt2XA@2Jw{ z`%&=}5Q+!>i#YbTyg1}6x$Rhe=%enSdLvT+Bwin`wVXKL6)T!H!z`W)pQrg3@?;v_RK$)=zNd+)U6@q43NCL-WXuxn!;l#3!&u#7#%HM8I59m3^`;l zJHpY9^yI0}QaTrfQXgYeQ0|{L>MK6iZH)GPX%&76s76P}$XKI1%?v2%J98(ZHNulu zM;$M=IbpJ;f6A^TBdi3w<;%h_J`9+&{xeiaDr()Q7`v?Z`DJ24sz5&Xrj63A>w*38 zrPIJ*Kw;qrjpbheULNpleE6$l3p}>H_;&ULo`3un<^~?K0HWfrse1nhFPr}3?zmi& zQ-jY;i>rG5-;2F(u~eOufIeKIfDfQIEtSkF8E-J%TA;kH`r2L$>f{eKXjn!m0R}T} z6UN#8i%R_Rd(?o=m)~nCKlvsoz&NU{*B=6X$&s}H^16UFAb^&C_idg1W9-)F>VN)n zopMSO4;fL2WL8xfHoxHFeFC8g_6#$ZS?V(S%^$cYaipvmYxw$&LZEFNyS!~A$Q)fI zkt}e@+L{~(O~Zx-+1izf^3P_pD^G5*fb;IV?cWwTUx|NVs=CQ6!9AEmjOxdfkx1X? zyBU02JCGgul32gU=&A7#`kc&{hM4xD8H*aMd3c}kA_J59A&;KcgGDWEtg6w*1fJ*c zYNp{?>eXI9&By@ez%+S&MH{h}#>5GqBLyvw!E2t3PD))QWg#=DQ{Zzn;n8R%;*deO z_M?izfk5U$jE_*Cdq?Kd+85*(SB6sC-?_zz^2rQJ+G~-m8d~vuBj8o7%dRdhCGPLQ zSm^fO>Y8!v#n6=&Lz)fDw=_ny0Gkw`a1BkGuw4pcm_VjRzEPIkRd&m}L^ETT68Z>N zO6su@P!n5VR|69oTFz8IBk+i6{yUxt021AsX>yW$hEf;q4CoVyTqV zc5E=rKuC^Rxx%aFxyuu>^;P)Oi2+h1L7%zMz^ffmGEV$vOi2fgXEWtQ4xu02jbW}B zP(5apJpH`FOwztgHsq#5Fu<2KqrBg?&5%B_Hg&1AXyWP-)KQ?sR-ZE)h#UX#&0w?EdEQ{Qs8)|4&Q9wOfb$@w_Id)}8jMYPR`h5V)!A8n>Q^nQsSRIJ_`j&)>YFD-_tVUR`9DB;6Ha>Tv0dQa(bqqn zIU%AhI0{D`DBg92&cLo%&zAYJ)-Ft(K$hU>Gh3n8I_(bA4UA)XV1^MP+7|U^k?ax2 zETG?sT+ut8eqJ}9X66%42ns36oEh@9x$ z!iHetP4+!20-<71C$)re47@1tGgf$hxj8> zU4ie!m>OPo4?|+KCJCAps+~>2b+ft4CRiTW`V45C9!KiF_jnN5Z)RBr zKNkH6$16$~Cy#39@s=}@nG&}n#-5z)_Sq(cxp&6m&^Cpsd)VP29eZ&AK*&oHr&oI7 zbJO1zFQ8v$rJ)g3i@$8qVGo&2oVOSADLArIsORER{>0STUi%fV(KQhK&VP>f6*P@f z+ibcERJ%Q&!W$wybp4RgYE9uxmQcCeQQ4hR1j0M+Cah&ly+Iz3j{|ur`yi-}I%w$4 zp6Yg7h#4+8po(~2>j*f!apvB^rgR7#PcCXCUA5;YjyNQ=QO$gUu_uqmo#OsHLq)2C zbDQe6G&h%-V&IptFe^RfE|~!PoOf{Bp6C)B>?kkDu<51QOzm0)2(-??@^u*i^Q*KN zL4HQq!QonkZR8&(wN--q1H%;f7&POK1$u~I{>;+K1^fiqWL}iUfn4qWvztJ; zGbF*NfdGUzkuSnEVGu2YaQ?%EsM|V_u|wk?oHozsJT4^dY~qx!W>(w}hU&yPWI>*q6IlHjKlLD>~64_^z1Sb%J zeZn%$|ISA=!&oMW||xW zwA1M8?ASRAo4O5+RBLH7CgO*=@4RaejzfW3rlsT4E3_)L6oBc+L* z*F6%(_^!*To`Wxl#vxRCIE7{T4n)ZCuNE9mn^a;Vwq%1zyG#a$#9IqnkxqM?)rP4K(KFRn>6JoX z%8MZU$gXkS{$K9S$rEC&qPwDlz>i7OSVfos%j;Uo59Vb#2=pnB>Sw5((jAA(}A z=L5^~i;^}X_(rs$M;p4GtrG~cs?b7VYf^Pb9zy8C7rrOv2BEo5;Z`&GA!A9F2{qkk z{IFN)DBjFc41L0gcW+VUeS-zlaz@MC2vUWxr&^b^H;{KZwg>LcXP*=#{XELQV<^x^ zL>G>39~a$%Mt(j`MM7zm?z?0YS%D7v6!CMehvXD9>-FEXSGZ#Wt~yvLe5QH}mOUf5PP) zk@`s<-4r_9WwLv=3r?(HiY>* zA-m)8^{R)%tTe>RzO#|RGW5CVNfU0!-|}tVcb`}N6eySw zVGHy83Vdp6L!-hUvE^{Asa>iCP=5=0U!c;P9 zq~2KNE(fRxlhAR_iZTe{1&4EYaJ6tI0|5t3&ca2RmE908R=Z7jKZ5m_VnMdMJ4D$8 z+*O#@d$YI$&C{u41Lo~i4$3Vd&{0+?L=VRCX3~+?l?V4DKV+S_m@)cbVf(?dE#{qR zG{jhQ2tD`V?U8%B?7VPt<(mr|E)$9#L-x6p5<0SPoCuv1Z&4;1f0l5H$PT<2QN#2U z;_)-+kzUm<$W%iq>clJZHk}TfBbhso3jKAA8ITDR%o^v^am53>(s;S}m+8ZwT>V(> zBXnk^!@f8U+4`jnU(_GK3(KT5EsTgY6a?>=S7s}w%6swm=tKBvXUfDO^)3RUXS3A= z8!btnL??d4U^nthjXcs*LqDbUp#|&&aJ>3LSR8$iE$SwCtWPtN(i-iwJqXJM$0Jiq z9=$VpoFM-2X>tJZv~vq4@vGUDd|2{gN@{g`*X{P{)qXnRi}c+S$GhIC%a?T~xKa_q>zj~XJwe8X07F+bTg!27jhYJLdj<|XlC?3?6Glb?k$@J3@IKDgOt$AX){5$8d>R6JGo;}hbY zIuwFt85yOarSQM|8lQ2^94Pv76(<4?y9k`1+F>$n7<{qLUrjNH!wlADBPb>|6(Yvk zW4%|DvbGWb8aW)X!@8xqH&Zk_O)B(=9iDT$>Y^wKGdA`k9Ko#pTv7rq8Pif&v#v;z zE!^iT^4H#*T)o+yA4?+9Bxj#V&1Ltim2Q~V9X8hY@-(cPURk~0+FTal9sGU{l>fe9 zYrZWZ2r*q~GP*bg976cOk#)J!u+$_dj(zxa%oW>cXRT95z=JyRdD_;V``$Ff_zuX1 zNj}SZ!YEI{Icy)X@XBA8OBeV+5-YwSR_IzY^J`9N)}D}Np6IC5^hN&xdzjno!P!p` zpc+~`?~aK0Cs5U4S84s$5AmyygyAfg^eM ze5*!)wd&AGsO-pwc<7$2xMua?4*gm7AF0c(;g_pf6EzFXclYz~n_5)5pb<}4^G(XA zmxgIeZ2_6tfZs-k1b;pDzJhFD{ zE3OFK!400L^=KJ~_E%IKZw*RURL$HxykoP$Uuwt&Tf-ZvBiW{X<=}coUWi?FSDR;l z6e0`imAkMejZ?W^FlGlIV+JCkVyE9pG6gDKZmzNNi86JCS8aAd9O0&U6t97Cr}M!= z_P|1SfvY&q z!|RQL%Tv5(OSjU;A4*_{UjJO~yMsO}x}h7qn%E53qt!c0))y@D*?kF6`RN0{4>&No zy&+n)hP3-j^4E*3CkB9C0k6pxSdB`GioYdg#Xy-Ovf3FcNDFW;`>v^UO{QQ5&d3KI z4bg17j=A;{?pJZV@)t08mT_z0#*+(|SGa z|9wEQ#>zNWD0+;M+Grk&Q!+-+TMSP9GHYe0bJwk`DNymYe{F{ zl<8NbIO{BcgvQ*#=Yflofh4Gv)gxQ;9M&Vjz@Yxdm9}kKPoD*z|2x6j{{jQA5B7sL zahg3te&k34W&Mazqs1$wmN5T?IP+a_!y4-!`afW__Ig6lbC>tgT3_+RQvm56pR4nSqvp6O@?`OPK{TG0|C10C3lV>9s6Ya3c{OayCikWI@bVpqt zheb8Qbese{sRa*<7I^ISyn3Ogh6)8d%IQ&p5poxc3UL-30)-bAQWY<%Ft{ZlI<`B* zy%D|L>=jZrvq~6}P>>WHf1iqDg*i!bpuJAx#g_^~mId6|+F>kzI$z`N=r1>QI}Y?e zMhcv%)Nl(O$(=&!tLy-m`MS#B9MoZze-mTR2Vh2KAY#~lH(?rz8W(EIn{|-<`xee z=IjVcLn=h2y>&U=d$XO)OV4I21a%jZ!eTjVKh^weXKhMp+7KqZ;8>R$9?~K=8DB>u zpLmcucMH1s^bJ#;mpHs2j|=x_wH8dJ)~Dh`0&-;_rTa*=ir7(M93YKYBJ&9DHyb=5%sISpi=u`;oCI=Zv}4ttmU{8r+EB16Ql#|` zArr;$h>a$Bb;4>*fB;-ScFcHitB$4G{uBS&gB$sZhc5iQsrrb=kCy~gsDd339E{`O zdsJ?zWT;?pYF*s)?3Z9ch*V|8yd0oTwscOSp9178;6?~12;Ywaq)!N!;}AiO284OU zZy#i|b`<+PHPM^#NCVP|lIh5R`k?>T-S>SUZ+zk7)cX)mjSCt!Ktx+nFmTNL<6o>$ z6x<^=Dh)1#vLUod9k$%aE}Wm>DCXA2pngqdZgI9BbD=JKh-9F@sYXCah@d({8KK2_ z%ovH3#m$C17$wUl?0)#BEI)pZoXtjTNl)FYVwT~Ua&EW9Nn-fB?S@O-r&Q*~^X-a8 zkmM|QdS!Ky$3`HQb!nrCsk@N)1E8|^{+M6-D6C5334mVgda}vM-3s>|5TtwYT~J6h zH`D=`7P}yee9F{k*!P!nge2W3sesZy%y`ngXI8wg;0>CsCIR5SYRZb^w^vh&zxA+5 z?`!k^N58e*q5QSsozCm8o-*#Z{H3kbUFq8ZJ$?K8F5~+EjJZC}H~-eeoJH$p#__Z0 TK?MLx0fEjqIG@CyfT#Wk_U%(( diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/PR1.png b/Firmware_1.26b/Documentation/How To Contribute Pictures/PR1.png deleted file mode 100644 index 1ad8c1e07fc4aed3503589dc47ff0ee9a83dd098..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 69205 zcmd4&2T)UO-vB2oegAwWoggoF*Z<$2!s`(}4$XJ>Y=8DL1RbFP0czwlJmGOu*#bS-O2`tQw?T)^EOETDUNtkRw^UfuHMi1&FI-JDiU@%(c~mMjl8co~XO z-;=In%q6IL_GsZTw%qZoYLM&ho=E>)t4sa}Wk;qw7Z(pl8oxYXP8bNd4*J zmGNrbe8VgW8il}d=+BPotOI}c)cT2pf6~UV;w&&;J09L=Rr%gMG3No+nGIpt`7^+SCQq_R; zOK1tjlYkwcjvm04H&e!4n{ubLIDQ>Gu+m7UV6NV6qT=8YIN1!gY{?}bM7>?-3G-U7 zM^Z69P*ShLd;^b-$SxMNqgA9F*T;YTK)ED3w3M#)1;CgEbiqvEc7yr)72dOLf?(1@ z?|PSLS%;-(Q)02euQRgg1D`fl8i)p(Ls?8|FJL~xnrmjkf}hcuGnztFqar$INkS;T z_Hf4VN%G2rfB58=tV1wJ_wE-)rF`!)L#azG=jA^3>DIoY>+i8aZt7>=$I-mruc$6f z_EaQtT+Vg4W4OdJq58KttAq?y*KYG=!h$};YfU!{`q?xWKIU6&-Aw;oG8U2j^&Ov^u8N&#(!H*S2_^&wP`bZG;q_qQbrGF^6Rb{D2Q zdKISKLIbU_-vYrYM&?Q&eo;qll?RY~<(;}us?cTMR={P)IHWajYg5=UK3|IpW!v`YJB*R`!&YJUT%VSNJ#neY$v-hj+ArS|Ulr8^xNlGUZ0 z4KNCXu&K^hTx!!aK5>ul$Sunf#y;~ppS(ueO2a+Q-&Qlu1`UPrr^D148=6sESB$e8 zWY^OX{+W!sA{vBFBa@=Z6YX(A$-FWS9ZBMr;rrg1M2G|nhC`0KNOrKtvRPm+uZK3cf$2lb8i%Q=F|XUQp#IZraEsxnKL1Uvhc)H> zDVs=!5T78orA!MBx#WXUXufa~D3=duM&1Gv!I7>(y>cVB!DrL>%Vzyj0qP(3_!-}| z-nh@A;=e2v$8q>zj#|#4M%6<8U%ZSTr`Mx|((3`&C*73&;wlEJP;Bs5{2wWPg|H!y ze@sD8lg!|iI@x35-=U>2|J4E2(n^P39qfp`Ch3d1aBD+=ZIy*U*uS@hefHG+Qt4t;|48-ueNaLV>w@9dlx zB@U>WnYd+-59Yugz^_b&?Lt$OeDmE#5f{#?*M;uP3MpJzLT!)ij;r!W%f`VE0hP-n zK6FPe+`x_WG^q$ed#w|`8OST&1YH`9E=Va`QUO^Swtl^QK13oFpwP?OaBnRBbs4q& z8PTj#@7y{0{oR+3a+Qb{nSN+2f6?N7Uy8S^oim-xHGD^apO7fviGRZmlT~nE zyCm5l8gIH&P4}xuMpT0MT5yj8x1zbbbsTv|6o9H1Tp?eGo9@9{lyj;go`Q;R(j-4} zJ|Lr^La8-(_w+_q^!nDmuW_x7f1%VQLzwAv7SN4P%~0A~zTc);#g=1hasVAA6gqnL zh$+n#;Zm9CKoRc3Jt-j9DAP7DwkBcQRzxwikS#B%03S5Az~wHrJPso0unHq#9+A|c3yvq=j0a94B-wce$pJSXYbx}_bo=6yIDs6)_MeB{?wW5D z59vvzcszNCyw+V3?Yi@xrLs3=o-dy)i&wxxo_T!9%P*oy??+)P-}U+y zn6GvoE;7<0)<4(G@{anbo7k+OD9qStD)M!pW_NIR%BSJsZ=42|Gi9m6G8S!FNl97A zd*9oZ8ovc4AiF$uhnF|7c3*a-Z`s65nKnH^n?#`1*jfi)EqfqfF1sVM8gXnq0>cR3 zwVz*`d`4iUu3ulBo~Yg{8<@-e1#Q;E9wqs+uRYGRnydHCD=*)CW>mRLSn{g&(RITh zdv^l*TO!yZo+S{O3CHEu1M*Tq7FXY_viHv~evAv6k*wGosa{g&R4I25Fnif>>zbI5 z^A=akzy~bDES^{uTkdW(sh|1OhZifzffAs_Ude02 zc>M76(Om|9z3fi&A}idpV}l>A_N3b5x1ggI#EoevLAD^(+Qm4tC10~-G4scQuE&pP z2H&zyF8v)`vaJzu2LgUPW9uQNZY?SXx5N54N(Fk*`g_O@p1)s6ktDMYjY;pCkIb6#tK= zt52fZTOCq;wc+f?6K32HBbUvo45HFL~COBX1PXa|x+Wu-kp0*19{5%VHS$F}AdJ5+G} zAKD1>9cx{G?KyE(@+xTCbh9|%9+1e%6vz$3l#;Er>!xa48v(1|%I5KtFzVf>Mu*2; z$nmT}4+a{Ven+nHg9?gG$k_fMVyY*IeojhJ#7~NslcIUEoPHtm&ce1*p zC7a*(eSk3NS|{@Ban@lT<`-sJzORgG)H)Uf=Gf2Ml9y+sRmI!WB*iVU<%8)6+42X7 z)E-AXW~Uv_*YfdD+G~P;_s}M?r!W>N$d|7?J4r5Radi-sd?SZh87ld~WdaG_!L~a@ zpgVZ9yTZ1(4G=JoEb$L0nspts@UZ{#^0@S)uYxko@D`lhh}FrXM&NVtSoc%O_=Nw2F~0Yap&ebY!NVpwWksioCCm`n4@Q@Q zx95}7vi+8ReqE0O?A%n}-R^hH{08IZVest!1lip}XYI@hr$|$8E7%d-X+D!?=6lDj z1`?Y#dqzm$Ad$oF)s#|`l9RvuOQRu2LCQJw<4qWh7?^*3gD3S6eB8W1Kg~h#$a0jf zi7JT$^yVakxQm%EuYuAiJ+k7YT@sOD%?As`r%m_h5oKsn6GIJZz7X(ZlrgPTkcZJ} zMYKR;5jbmj)7m8<>`4 zZv@IvZXTNGEKZ?J^L#@>uPr*HX=)o6vatPeGz&d@D~?;J$rX%-nJkzWhaMh3iIZ^v z7Mr!infN)L(zMil(j3?03piv^V&4{yGtE)&!ci5fo?o4<@rN&P}Fx@6Jq@!2*CY9=jEt# zEVr6LNURXRBlMvT(FMAcm)sMFBtN%6s)O#dnuMGDzV7MN2Pre?<|L%IjDnAweZK$7 z?Pb~aC_&+%#@fY^bug8gxa^2iO=_^x*~M=kRDTCO7M5(DYe#|P_WVpJ#azi}?yiL1 ztuJPK#D1II>x}+ghqzm8$@I->!`57*_s?H)5&#!AYX6AgY0FIsGc;D#-_P%T_ToT} zX3Kf@B;nPSW$(y;#O zpG_LOcUsZ^oD@D(`Rg|D8l%5$%+brTgGcPGBh16mHc7Up|6Fp2j};!s4h%N`t0R`P zPREKD_6}eN<{Sy54raZD{MlVHJ6isvt=>=AY!d0-AQlu@u9qQi+y+o;VfH@h1{~rt z$CmvOL0hYj#t@GpZpbzXSK$Z2QTa8WCmSGXUiehk(s)lO-trC<;J<7p)7z&Iw6WOZ z(|g(M#r0#w`+psyVYvETSCSY1J<*oDI&-Napi??UafvrY%KMe-4TkgfVC~u+XxS|K zt8P+ipr-wXW5em-@q>5f4ojY$J{#DTwDFS3``{yg%;8g~euI;OU}6Dgq*9zjquK(E|F4A{L7I?>yf^*gSB_BF=*2o46`ZnjvkPHOD4093s=P!_0_*6GzcSn2r}DiOhuje1I-4A19>e%UYs{5F#?(|5G2cmv){))6awOIBpH0ZNkAa3d2`ke8}*UARO z$JP7b%=+_rmrI^?@5U|vYi5LQBlP%5@IcuXM#V(Vmb3Q*E^51U<+*YT4kZ|fWPd15 zWwb)**3u6Xxp?PUq1Qx-*N@)bbQ(xaLEZUe*2cmP1zB+NJu zY1|Jx>!>|S;Mj<>0_p4@ciSD8B(-h3pJX%kPN*efvb@et=KEnAziR~*K&$(4H$X$4 z?owky5hla{Sz1SlV~A?L`};J(_;c7G8__ZwkPt>~hx-~+HctiTnrSNuOgLn?kccS#8h%)tgTjICG^Ws7sCLCwezUQ~N49cICZGqW1EktlNJtg{_y>U1K-IHPA zyn43&X`JM8`)j<1#&^wq&+2?j?yV+1?;z#6Q)({oKmPjYL0<2W?N!cPHe&>zI%7Q1 zBg3@*F7Y7zTTt$-x}R11v&C8up-Q!r#S5KP=I4+08;%fQUK3Zbu~US75^8=^tV{+M z_t}Ke!GUD7>1#s(y{fZ(Sq4a^GohvLOUj7m!E2%p^iF>NOHbPgA?TE4 zjYouAh`Vv>tbT@k>qIYX2F7gA>g~ynt_R`tYY(fD6$Z>kw0h~`%E+#@W)6%mwWb5s zf(vURHguYHkQg;INrMHKTWF1bc2&6m-;vX75cK}G0jl&&rgdENIQSu#MU(Pnd-36Q zcXOMUP7CFO7rSqDoDEZfyVs1hRS*`x*~-;j8rwP$C_Q$1n|`)``fPHK<)bXSE}i_P zuU;#;R+4_crk{hJEnA03@Ldz44n#dhNgJGbO?wq0qOX(jV=%)|jx=g(f~_1(&z9x+ zf-5xIKG@A>Ci}gwK-r!R?|5&x@-F_Q;jT{O{l1_|a?IN2^2@4bJV$Q6rBDu>kV&6d zo1Z2pW;l!_a39{0eid;XuwWPA+xlWV(cySJ=34*~wTJnUrQMs_$JmTfxNGbu`X`hF?G@VtOPVuUJanbsSvubK z8e8@W+*w*fpxj^6&w55T^jAV*4m2eQno4TGckDd5HfBIF{ODw{hTKcyRk6%!E2ZH9 z{V1LXwe{khihoZbk-k(PBf+0*fS~rs3=XQ?cSi)xbsQh7CxcUz-ShP_lr{Yc`Aj0K9k1|d=rvf&L!B=L8$d;G@Ie~-c;h%Iy2gG>AzNGcD zzIdhr)Fc}*Ev!Dq7|Bl9(U5(~c_N|ZWASo5eaXN&cgc`qgn*5%eiKOk9?=48c%9Fc zN4o(c=F`3q`9)QZgrmbb9_{9iJ&!lYb_zFAcvscpC~fA|4zrA8S4T-pq@K8c&5V3Y zA7#Lm?fIga>!MRp!01 zud&@5CMpso#uHo~0ZB?+($GnXG@3>*%>g_(;ZCI17Iku0^` zW}sUFvK+>zCfk>+U#w+kOiu#FNSY6mbJbIZWH2i>&>jRv@OTO`w$Rei+Vg%!W5uR+ z`#(@3D>PvIxi5^j}Bixs^x8!p_cDY7R6@}WJl=q@Vfg}Yyis2TtuOxe#eSYt<*N1Gq z45nSM1aWX0y4S)W@H1;e#)f%0FbU(^8Mfq3Vd0Pc2Gw!<5BJuDZ0n@R2BxNrz?h(p zdm@D&PvuLs(GE9hZ#h;x&N5(jD)TfeT>n7Z^%j_E7B1(5X;ip-H2#6rw9n4`bq|P+ zDk>OTn8Ox<)|+f3FBkC@ClO9&*yOG7Sj&Ws0oXI?L=E$#0sr?1^r50U@?6A_Thl2{wpRx}_8e@MQ9lbbn~;*@kuaZldj6bK zEq-9r0#~@<-9v?Vsb8t1P`#_PjNS8=3@Lu-=>w z3zN=&mI0g(gj;h0voZ$`10lqzOWjE&Z%&IU_t2VxH#=pF3(|zDzXt|iGOOMOiArk- z9{e%7e4nM1s%cs?>2FE!YcP#KztxaDSx>e{xP)54Z+T%ya%9cW(oJ5KCm8-oo)D+T z7Vb-I76=^iWTo0T@fBu>TmA7wwD*;BwiGCWk1a2>sp4jlZsK`)lwg=Zovn%Hsol?* zrn8V+XEr|r&Rx8GA@|!DTYgMH$dls==S2>mn+W0b!~Tp=Y|vD zPc|`I+%@O z0Ptg2d!|Ahrji%>lJ6xHq+-h{Z68>u%dsZafEVzR(rEY53Zb%!acl`NWu%&^3!|;1 zH|&#*Ud*E6bn+mLR&<)fpQ#XwhaegCQ>9d%_cykq z7k8}FbSQWV^ms9lU8juM>3BV@`ITd$?9U z&39`c&Hg0#U7tZuuSA1q-RkON3k^JI^SG2rWDn!v{uYxY4a_Md^aVZ5QhqGbPQ>(% zll6)`bx;N)R2XNO%u+|WUvG)Eo&HB^mfsyO^kE@Dtk}gC_3$&?wPH6qE-HloQ2&+V zl+o|kQv8n+G>tu)K}i(C%Um%3emr}>&?3(nPw0hIAAZ(Yo&f^48-VUHuZ$oq#hI(gfFs!-f~Sy-wd<~7hfRZXxq^6b zFL-R6_79p@{sf6~6bs73XSp(*ODJiZ0elarfYNOjDgi8`6pRF4b1x_k7NO8;=C%5Cf`Yf@$ zaAwtZ`QzQl2RqT;0*pXP?lkA|9gUWw7@rUJ{0S3M7x<6aCEZxu&{#c2nD$F&msnZ* z933DqR&g;muzf7?VC$gi+%bI4Vt9+_W9wN5x@W!zHJF%Y~Ym@ zM93<-YZYfS@MK`#m;WqL29jdYZ`QkfGGnEWSRGx2!WfKEsh9-ou);|az2sS+(BU$d z;ksf28uqns*N6`vzWbnu17?z3YnLonOX6wjufC_6ZXIWdL_uB_(GAaFITG#Av77GxG)3qz1yNfoo`DESUH1jx3 z2Xm%=pElpj%7Q`iakDIL`FTX}1bD}|qXsh3X*>&NGHCv|_% z>$dOwZofd!P3GyIyJkG7VoBJkcPs2+I3 zg&o?KjGEfCJ{j<0$eH}|K);)k!9X&{HGWe2Gt2W|bVZKfV(zCbn9`b9HaneC`~-!! z2G2_w0}qvP)hT1~kHfVZ1o>lAsi$A0AH*zqB;ZOE8U)dzsJL+SPH2o2X;HC2O^5Oi zihw+)V20kT6m0uKK}T6kf|mY@h(1<Czug7oz3$Etfc4dsX~uXRN&>~iNSBiBI|sfEMce1(oVY_< zSEleQzj`};HQT5?ZD z)yeN+Qj2QKrVNv&9HX#eooWRhm_5M4zUX8zEZWBAaWkbXr$~7|Wrrk~6&-bxteJx3eNsd)%S+5>wNvP5NQx`St54k$s_u3&}ZyKe5`$U<9v9Jtic%B+k z)g>BC)_8)Xfjz;rWfPjyQ|bQ#KP=9bs>ibyQWL|_hhWqQ6XxS(%t@uJvb41q`6K0) zEiji>^b{9xk38IyeX7{PS$u`9@X9mhMS>Z-6o}DNj zZlh6mvbjz69a0YY%Dcz3?Z7~yEgIIZk9LF^WXQ`f3zX&&Zw!(%-4RA*(p$m$7Y39X zSTsP4m;Ub$&ztq?BF4K<`~j+1K50bQ%1JWuIu+;dmjkgGkhc$&BrE)1B1f?j7WKC%=K=;?Uy-PLnr5Pi-7@R6b zaeyz+oJ2%QM1K=aspD5bNx*F;MS{5nxgt47gDFwA+L{>z45S0uVHC!GPsqh1>Hw1ud-0p{%%%q2?pUixmhs z#?5n1k>TI#{|k!!nJsA%8YOU%ixD*esO9!H9WNB?uup0K~%v=AgC+m_dKf=Up2PHiZ)SoMaljgCgyI=5tAN#=ICm^;=-x*?dQI z_6T$*&WOV!axMT(F;YXwKlXay+b?R}f+55S-lH7l_2ZE_$UioF?&UAiA7f~3v1T?-8Kxs|Uijl%U;KX?3C4yQWi|i062b15{UV!K;geB+Z3xr( zhv)w@!qKHPic0(Z>Wsly*pD~MlMoHc@}$s1CPd8~I5>Ho=h>2mD< zB-me{Q+;B!D)!$3VSyjx&)WW^-?BQ4T+=M;*>W-EhOfUnkGKt=SedmzA&sY@ltLN^ z*fZW`-v5?U2^Wwo0Vne-*zZ5Xgwe<6xr!sAxY#t`D7*0HRM0+WG*I5#>TV`X-6)uq zeR$>YB0ru|#u!SjA9p-t4C3!#-dO@W$RJks_r{OK=Q!`V%jzFWYo-svyR|#ng)^5G zb%2)>>Oa527$!wuT{esiiUb~l^R+E$b*A%RJ5#IidbR~jJiK5~hZsJguJ2L%BXsGo zK3*8uG+6wKKJOvRX(G1)l(VYNfr0yUNp_^9k%(@--q42I%}W8TUvQ9ym2|~h&D&}7 zovS{)!7YbVn$-Z)wg@;Kj@r1wFIYz}z#*C)CNB(@^-|!THY)o53k&elCD%!@4=P+6 zboiOc#9}Oj-mdq}PasQNbP84H`$8#eu795Z>fQo5-?3k4+x}HP899C^XU!UUB}|eW z68uk$^@-Fo6-|Bp;~)Ycgk1TG0B4S;fCbf(nk9z;hSf+Y)mZ4x?c0B%&SMOw%a(lC zu^@dDfVxyxYMB-DPrEgg?nN3u%6ZfGCT{({v`^rAGsn@7w&+N2zTC)sxN>ikQ|DNJ zgh>+%#|uIJ%wUbuEgEUg7bJMykwHHk=(L6m7?15;U#~Rm>@{T=Dv@Hh>*j|TUOZ)o z1npa3;K8JlmU$9QyxFXbuM`PFj90sh;6TAPDPjOxDW!}ww=633Hqi0_={6;*`6K;H zvjvelA@X{1IDZTMX%0*wZ`BT+Jj!ohUdVNdZv?C>mvDM%@m$}`!-C7A)2FW#+ z{Ui)JYe7aMlQ>@FI#{jj#1lD&D{QL)=0hGZ1JN|WDno{iyh;scI;n;^u_Cme+OO5X zUA&@5(~oUjo37VG#ZbC8Ufl#URKIhD?J_eHE$)w(Bd?pGe{6Jv)J7)ksZ0Ht@iC|C zsP+6k%sa#9npezBk2_dxlfIP$YZCEpXF8In)a6BNi_4ZrC3$_Z zmJ&+W>W+L%m zdD5tSS7s~_9)7`h7{U&c6%bZy@O+EgDGY1=m-<>L69Nn?6~R56aH6} zyc=HLOOXQGKQ8gVH{k{*%wN4q12p-ThfLd30;_ub3bJJ3mL7qgD%JgU_QVaUgGGC8 z^YYnc(ETuFQa7Z#=VP3EmVZOYimS)2%cv0bE#VRpHN-nSQvA#oO>pJwxxV%sQJr6*SAdi3D zryC2D?Lq;STkfbYYFSt8!Lt)1rsEAvvyP^|KFVonLJxVo`A^?T3we3<72TR^zFg&W zc`rfp;~ps6Y3}MU7psCQE19wp!z0PeJm@C*Cmy?NAzX+$WKEN3{!(Tcz3$i1k$=JQ z1Z-+5{;2l*H&ttkPbaL)?!9CVAx!N!)E7m^mTYIsuWj5Z{< zayjmhnw>&OwrDFO#hh2cEpM&;wI4dDpZ!*Lfchwkh-)vs$3$A%6WQQjK{uAIqbZ5i ze)W)No|4PU>RmQxVPnvQf26!SSw};Jo_N8@zyzm^!<_^{MH| zpXzu%90?kL_Bh?;zR9^<~-(`-mF zya(!8sjLmztnDxEe@A?Gn(RwE4cfIDoF}!97tFowVOU9WTPr`5*dC-Vhs4vDtd8@Q z`P*CM6RLW98EEJ?#mEW*zhc{`UhjBY#tJtZxv#-{dXwh)-GHH_tZe#~ zn6?>s@<*QgSs_EljdvL~yAvZk_5BYy)fVowk1gf(n^(KPQzBlb5{g>;n8Qn|Z#@Ah zZd2#5nx=#$B-aZ%3p4Ag{VFoQB5N92Tq=#w4+KkrOw`iwO|%cdZhmTsuNjYqp3-2H zv()Qt5-pf2wD6mGB&oBrMhR~d%AyYlfsWZpDtEOhG~8X2TwUG>fY!TJa;(}){j8m@ zyRlA|1YNG__0Eb{Gz&Lr3UFOS`l?TKtVHj;ctZJH@yJ#vhzABs;@ONCQ17QCtk)-Q zrc7x0I%I~_9>Z0Z<}eaDfW9}aS{Vb$ZbIesygp`*dyVNOn5IAzF`F~=jIs6=>Cg__ zg0#R^dvm(4esaIiGh35>o&y)mz?(TLrDIj;ed^wr>a{6AW<{(2ZY1Rqy2st2%@trVH9(ppMJpF$c!aj^;>E|oe+orUcsSaa(OtkaWD0L_ywz=LpROFy{=12kJ8U~N41bsBlLA=_H7nhldW-#2yK znBCz>`0~Rv@T93>y;d`$T6b>2Ijzb0z$Ozh&KvZliMuWx4D$&3@%e^aL%K^+FJbVm zu}!U5P1d`SlEAEclKC=t_L7=HNrj{2GUdHTrplaIXy$y{Aa5?AoDvil`M471H(hFQa@0Lxk5h|0-KN9n8%7qUg4BZ#bH<5h3g1 zlxm^eWQQv1mDozNQOtKpmceP+XM?^RS}<%g;Q*4M)#@i}o@Lay@xP+^6o%#XKP*{| zLI1bqF^6p0^|C*l=^;{%LwF}0pUtWwLngO<^;<2l+%!G3(v;T^UO3aCAAzjl2Hj~@ z)#@r^?lp6b(rSL$))PX*TOSS`Q^j_nPkFGPB1h8pN# zpL@zI!WG-xJizq4#T4R-FHl$L;E$yhw#lhn-B!m*#4Z1VSVJ*%jj>X8AKvwudJKQEU zxdGp5^R9Mw$OT|?8oCIP_{7J-A3*=1r_nk=4HljmU=HULvK6W^(xu|Yb4%ykQbdA5|AI8-Wy(m9kNLWd;J8Ef9W zx&1X~>A*^}EZAGZ0X`%?>gYF4H&B}lqG60C9IYehx)I2-4B=!|qy^H`Qk>g5Ff#<& z^LB?BBXcCj)F0Dy?`N$QL}5jbM4mX%?%cRL(Y#2G>ye&0-Hsg3M}JwhX~Ed6M6lH&gZF|0Yg{0)F;fgHMAT}x z04;i;n#*L)RT&`o$enli>)R7)>JwN}zZto&KZP+>?F#}qhc)UGDjQTjMLEE1r75z%+HcI%p0CS11klH1-j=^^FbAjh z4IVui>+;E^m$ig3vfTncSKc^sF-LvR#8_-dlKGaFS#g>oN-!!QIEmVvoA{1nC}G-)|FV zi4rH-PJIg)1awo~h6k))TP^@DC+|!K-bX1LGG_9ZDwL1ald%oF^uSw#t)$b-o~~C1 zoZlm%j~%urq{pYzp|ibN;@wN8&RNmz_O!dNNm2FSe?Um2OAZ4~plvXlr^SI_=uCzQbEZla+zcEM zLVJDVR>$!j6`|dQibbr*n6wVo53;3(BF3kSF(|4r==&_D*@7t&U`AQPLTkYk-40OR@pRIGgV7xY=i7vb){jx81d2UVMNmqq~xIkJ)8L zwEuNx-eNAG#pz-gUn%azOZ77v2Y>>@94DCFtlzi>w@FEhO8@ootQB=*a_;v-1v#r9 z#x|ZUXdFHQV>YtG$+FK8Wx%k^HzrtorvA!Pf)*Q&A#U8y9aOsLdDAPb96}9D34U+y zLE9M%hin+;LrWCHqQ)lVMfh=(y*}SF% zj-UAhO`YG<2{q@k!k@uU7M8Q8p8pE~{vI!6VfmDO@mB=;1H`f%I{mBl{QH4a;o*M) zz`w(#Pj71dlH}hlN3Y-d7q|O+kgd`2f03lWL#r$iuYOtV-)qi3{C|yfcFC=Cwo5|1(Ryqxw?*l;@VtCx82T)-MQanJq))!o!t;Ja4qeO-kb7Ek)30X(Ch55 zp~1P6Ac5=2v1f&ify6hnLYGOJS>@1mDWxmp3I$eMh+?(Om~%aU3H9R*H+fpRezTxB z!z((Sc8~vKQtRq7?;$`GkEF`nDt zjS|P1?pw36fg8iF^Ar8)XZn3rT3kS_0&u~>5Qgsi zESc_JokSY<@m;+n?AOuE{Wfs_a+;TUMf3fNi@Xp!k`-@oua-}n@T`x)*>wdU%6v`7 z2M&s`?>n!MsN(mlh%ts=pmB1v-RPoo1=5b>3*NRxi8VsZEc&jQstMD2(r1DcMkQw@ z4TjyroW!oXer2tJ{`5bm1kN~j%~>cp0HBDmAGd#}XU^mK@Pk1Ky8;-Xs{HtUIy8wi z>yo7^JjLVNL>D>&gh=+Sv^$OIK#i2D%ok$#ue9#LJZImEWmS#6o;{PiQ6%UT+^|ze zIr}oMK-aT|-f52gdh)yai7)4}xE*V{tCmD~QH{5DrzS7VYJ)_vrengttWnDLyxGCR zj&Zg=y<73aQx0`7~;_ZMiQ! zcc>0W_kB$fx<(Rr6>7CioBt-Hbkm}5aBhNaxHF$wIb{e)Gy6rd7Ij}PPq9aq6;cRr zCD}lN5%rnE&XY*lH*0>sfsN+nieYTEdHWQd9KfFQX^t^(s-`Ghbj$fcf3 zuI83^PIkzV_{HRgCDTN&=Kw4cSubSKN{aQ{{F7(9iO$boX-0M-*a|ww6_n>YE`U*P z7E(9wC_gfPls(64cS##`Rand3TA@@ESuh`yfbY{8_WkMXGdm$5jla$rZIIxr-Jhu6 zFbnnosp+ryeIE7|!lW0UkLEXu%{o^ic^$h97fiYahbV&MhL>0$X!U=rw$JdH5no>% zimj5+_V-Lu+EmUNQfTj_*zxkzNIVf#)HYDWW2HmEK9Kn}0cl4oo)xnuaJnkBcafaH z)A_y#e`LITu5X^(zas#v-S-M})n(U{OMd}>2T?y;*Td*7m0W)fmUjHCChhj6>a#6) zdF%fANd0nuTj%Fq+TeVCEzP#0S{iRuQQZCtL#QXluSt%|4@xV~ean&yXC!#ooLgiQ zccTfMoXgF9avf*P(N0%YUx-YX#Ac@Tn4a=jc|UyENrwDSjq48KHB!m>%fy7gTxRET zwd))O?b~ZzjAgw19XxHbnc>#xAFjH=NV$^w*5!bxn5up^HT;Weyd$7K{uXNv>=k%mOD*M^~ z_#61QYg{x3fY@w8+1IGijnVDSb;rnL2!6fur;24_R}0L-4>E5V%}>+E2p{wF6mrB{ z4a?K)`+Bjm!y{;06U^vvaEDPHY5oXktj3P2?`>TZS3~gk8FKtA0RCDVZ1?C9J+3?b zI8w+;w9?1K%>+YyscD{33Q>ZyWtZl_j zBkFzUE9_L{)qtTq_Ls7cP8TK549M0E^|@wcnMX}B)nT_CeHE*zRwEGx^$gSmas%ma z#B@JEBfCB@^qYikL$9zS4C`@9N^fJhen#T0j{@T)5iOZh|5()vuh+KV;_^?AkhiSr zzV(f`h4CCO=^iHaSt&T($Ee`X%2%q|stfkgMjWO(K9#>gx^`OE-*_#x`SIIIq!Ko! zbR+l|7mJ(BNd7Pv-2yv#Iq{$cS37p&H1l2sY8fM4FCg^vL;$+9w{c7y;CG_{>x|lFjP*SyFyV^mBROHfBWw46>XqsB%Qn}y#=4YdnI@KIj{ zCUv#oN}?0I559Z;9E{1o5yr&C?<|J+w~)Mai^e@Kex7;6G8yMtobZBUp=*on16`3B z&IJhV8zUQ+bR*CbHBH8M@)}$+wtX>Gnr)yrdhppd!P0b{-T32C%kf#NAdexeAP=48 z_v`FO7575d%mlC54JpyD>`|~VXv17zuk3l(6MfapUYuQrIXS<(mvlBO^j3jPBF7sg z=1IyoEi21Bl3C%-Eas~r7Fiw#;r5S$Ps1o_FPYQwSY=+o&z*J9Cqpq#V8aCE_3Uh! zkQ3GI^~(xdbe(2X(spPy)MfpN`I2fur?7;;72{>@;$L;tr>8HN<-o<)jw+czK^0f?dBM$8hB5>M|F;}E5BgR0{aau>w4d}G6l!p$ez@Jc7-A5~#Ixt`v(z`QKWuNIJ$J>QgRY2JVSb3yR)j&BVI{s{#}(hJOZ6> zf3_>!1p7^>S5V(5iaWNux!2de=S9}5ZeTxbUDfQjN5t)UL>v2K16AWY%@Y~eeN6A~ z*YASSXH8~6nsEhWe}u)Aqkc#^(sDOfolISK`Nqgj#;VtORyge{2Fyw^=E6obF`wku z@3Z|H`Yz{m3y$IJY-y!jJx9^S3Y}!Wcc2VFn9OT`kL^$7Pw=_*$eX$t_bSe>u$!`$ zoYxO3VJIH^O^YFumZ3+Jp7Tff+ZL^p_!|UY%7$_>c8=^zKdJg6l-|@Ij!u}LxC%)1 z+nK-boSg*aa;h%#5K2)NvmVhn474XHDygIZ`Ob<`PgCutN)N*OtWk;7cx};e^mmo} z{IWRS)G|5u=>V(t6ln*rbOj5iygPKg1%@FS;8T7Kvirl;>VMI~Lgi-$Jh?IT9PffL z=7ZBqBl>2-+NmLln;kfIpGl#{Pm2S-(mm?Q4^X$P-IYxX7I zfOCWw(0%9c(2k-fOf&f*#b>76Qv&_5%-3BeeR3H$*5|_;6sIkOpY*ASrx+3}5UB)h zK(e`(A?sGQ@fm~6G|pp8bc_jwo;ldr{(<~)_sz@YB3pEZ|7Y_Lc8_ij3W4aBN+V0A z%-6`LUQtUk9PbXPdtRQ^T;ztRZKa#uiHd2Gb0OyXw(`%;P1w<`sWUfzOWBv{k1n%^ zGXBX@)s_&5-!bbC|57wN*LS>i?kFun?%5}ilZu?Y*INbCuewen0M9Ey^5XB$U&_GV z$UL5SJVpwB$WDL%;Jd3Nx&2+;bGf>5=XTzuhm{#`PNvzuEcfR_x9tOpW)Jdc`+Ooorr)Vg;q+x_*k%R#*^Ba%erI*nkGjsaF)E!Ia`$Vrh zC?8Pq(Ya*tiAI3+^mq|>H=^tgt&{s0oay^N9gFL4t~>jzEY?*xLn=y`Vd~nZ&E`d1kY-S7)rGCemb_0!c#i-t#r81jQbu|{ z5O9>W4g$QO^TQ>H1jEJVzQp*6cz2xCh)QXDC%7KqM>XH1Iu zt^QkXavvIwGd1^tXi-Cb-q&$d+%K@SGf>!%)S)kacUC)Ad?x^MhL-6~d#vT)$Y-NcgnQpFxcw@q) zGlv`yE{hXlzWXu$v$bEBOuyiVP}kbY9%ck>tldhLD($oDd|#o^LUYm-%+_SdO4!&V zE;gcn^o<%0^)0Af;x5J9Ijy>x5a*UD`lPI`(7U}Bsp+Sx?t(XV%t$Vep)7v}%PM@iAwLhc(d!zMJW~Jz&iLmHvF8W}nM-}UrYFCJL-T5(S zj!LXn^{hO&oP4cj7kDN~U6NAk7PMTkky7Bex;JyYw-zrlLyQrBINHaJmcEhFZ8!J4 zu7dK~K*{Isq-0u>VM6&x`t+7}(aHY!`0nlNL9PhET`*G{-|tH^UVtkmtNsu2-aD+R z?Q0j^>Q;0kU`IfRovjEcRa&AO6_uuy$ceREC%)6KB%)s31EU`VOkM)ba)g2*dpZol)_ zqWDJPZ`))Bxv}rbLHPE18>2y4^;VWCKx%oK4h=%ZK`ZPMmN*+E_Qk>Y7=;D>zxg=?zq@Zd*>> zsxs%9aLyCcp>A{h32^_aKmq2>(Ua#nkdG#^rZOjT+dpo%j$A(K_Ht{9@BUJlH;P+xoS*)R4d&fhU1i-`A<7XCWa9`0BphT0)|1`{f;gHQ&&G z#D$NYck1j=-)?OLe4+;Mr)oqFa>CuE9*1q2)Lo?>d`}0oGUGzUi1DscX=!eodVN%3 zF%a_r{10isfBkYBKl?#8P9FomeIYb`Jx_o2;HKD9$IvWwjO?zh17=I!h5H@d(j@C! zS7z=}W%{}dSu5k0O+AcWxy!a;ePHQkwyCd;^wRx0Rw!+ayUb^xGk!71+<8@hl4r|K zoJgp%k`jdL^v2!zwX$`XJ{(>tD7|$al%?yCK$VS64JxX_B!!b}X&&4foD+8R21t`# z|JvVl8;0tEDX$k5x1_^&`)-s1T*a@h;9-DrVbRGk!ocN2mMI^{ zdc%Jc6&6_vINe;1m(kp^Vc|W+O3{%~&wE{U`M$x76kp0?xGVo1Rc5q~*hw3)`9O@P zkSr8^(eh#L!?f-T?GZ;OEAvFY*k-Ivv(5=OuE|#$pG>W?%)~k4VR&^bbBl*UL!H)~ z&9*|OChhXf$dLi-9R-L`YBC1e*~^W2Yq^c#MfqefuE{2O3CuQbRf_nz?FdlyYac5Q z>ZJ&VOd^A^dmImTSoF!fGp`ADHexo2BjnwW3*N07E==NH8DMazM#9DTkd*46O|eRS z7_^F4w9@I&R-SRm&-AoiU%DE!;arkyidc1DxhQ@pLH#d9xCL3!HgGO#J$w~`+0{-*w z5EKsWTu-C4N?Ioc`bK8(1}ZB<01mL%HlV_0b=uMP(opQPU~tffyO0KD(EONWO4rtW zr*VRd*K6F#p#EA1(izk7NLt$6jY+L9_1l-DnL2M7{jvKTtUV%Mhh!6rG8G~a=<3^0a8LtS3 z;{gp5VwY95zff{=_AvwjN}VDd!S!ZousIb!rvx!lDdcf2oOJ)H5Bvp#p6|Pe4H-ef z%@nh^&*sl|mL7A4-i6FsgH~`S(z8h|>gq~ZHl2&1CMYd~A7cBV$jYdE@FpQ5iBhng zpz0)~4IpIaO>YjnHZ-O9`G3VaQyr2d>kY39ZXKX_Rxw=#_QOr>EM-dhu*kU&j1RA( ze{fOYF;@5vJZ>`DwW`yT0y+A=1WmX#rXd)A?_Dr{)9xmrVv(#xDO7Xb=peUWUNh#7 z_S@Pxu60#9i`blwRPy0dy$<74n>!S6y%Pe`gXuIOqu=0yK2weN-8_?(R_=@hw z*p|90L+O9S>IhAZFDiW7-<2cjr_d6s^lSEkm`CoMIkax`w zu<(Ui$60U6#m>Or2F6sluTj0ZG&)YxD&~c+D^`72efZ^|FWo494e)IH0T1N$V&krn z+1%D^YQh_%fh~-OosRjk@JEs|iaCu#Un^gzon*^q)HOIQW}NHSYMeS_hbpJ0prMw3 zz?RWRv{VPAd3Eb<6s@y_`h-t)KaY^gOuVRGb{>t(mEGzdTLci>oJ3z8&UQ1&*8@Z9 zxrltmcIa8_F>-Fmwl(B$q4qq)V7Ml8-|;BJ&suX5N@FZzZNUpDeKJ(CH|M>7d+59M zkY5Hrlp4kIoi3GI3fxHh#}~g)Km|VHD0mk0^qB6jxNNao@edY4eWd3kJg?f~x(6>& zwCj~hNpR*TcRZ6^>c?t0r*AYIQsdPZ^=ck#?#4e|7mhigW!3;FS!TM4W%bsAi-QLVqP)u(AzV+?7o+#(p z^jlis7+lYHa0f|`tTPv^+DXx|$|it-2U2Vd6saC*?^io+s($qsHF_VTk7bfZgqvR&whgQFe}Sa=R~CRm}YS+eM7PemRV z_wzi9?u_fP$4{s6ix8=Rp)>CrsAB6CcbuMOh4!#>Fh9*DwC&A$5PK{0)KjvL&+{fy?sm~d#m=*UYg3>_f4zeD_Pi-q@*3Z-hGQEUq ze(e5&v3vI{?0SV!pl_crOwAFKTdMBfPA2MQUtcrV7;7NASHhhcwqa)5C{{S_an@J; zQ|YwE`%3uA>$vyfk*Q==1n4xx3Z|)6uLM&xU*>yOSmM`-nP}ZwP-RFvx#asn&7ZlK z%Uq4ls@mB+R1i&lJLa(V81eOO+_s)jhQ|H+{nar8SaU&8G!S*Q)#R2%y5Jv+y!*NB zuaimr>Ya0BZN5dc%hjTNf5fN1R0rulu$@yIFtp{QoTD+E%1Et3{8Hb~$*hLw&CHvV zzJc`kCxZ_g@2w2194VNrv9Z_1jOH!NHG~{kIHtR<_KP*Z7@epN@&f_tA6k!q_}~|F z@T$r?+2dPfFY%kfO)jTu!}>XVS+Ct5PS@b_?zfLTyy(g}P}bRaAwI{5TvV0N>GX%2 z+KAzAzA5)(qMU>wZj|cwFSZllU#iO-P?f$*ef+1~m_*7(GvCXp!FPKeCF7f2=P6rH z&dQ$CEXIv71;I&bcKrS8E|C4-xl?Dh5})KYfZQ0jFfv;i`2#AP`p1(XPoQM|ryA^jN_SyXEr~ME5+l;8xDFvlNQgF{kpdoCr7m z)glXUyuQagJ=ryY-cD8-Rd(IXq?hO4r;ryk_0?`5W1(w8?4{SFQ?X89))Y4DqmGKb zE7VI+-y7er943^_AStjkKr{6=lx)u5npG7ONdf`$zj|l?(T!T;CjWU35TzxzyRcky$8>X7t#Fv%%UOYOwjJhWGjo=qn8*5 zoTBiuFK(vmXJIh)J`LvhSV$}YBY3z>Ut{dCT%)Tu{vJpW@!R6nH%YnWtGfl z9l;}q2`Gi>LK?$$=2YF;1nd_oH|)HcvK2Dst45F)e*apH%}mDXB#9~maEJ$-@;I^_ zSJde8E@oA$rgbd;5dkwb(E)E;js3Wi%)cIZWYG_m!sKj99o0GMn_fs{7)-={NEKa}cXZG`^;w zEa>yk4>oe9v;yChsbVs$s^OO@Zz)zI)Z%YtZ=efk;qN%8yr8{0-%8mEW!9+JAWo;Y z{#4K{6z#!X_89Kt>UE|?Y~{O|xj^0K?Z>&|It?u&)O3HH2gx1VT~==c8o08RVdF#P zlH}Gl!5qJ5P2ui)I8;t|#F9$r_ch0dZH9T9=`TJpm)ESmrraO)v+IvUqCJM7CqGeo z&IJ5Kj}GKyf5?!M$do7%*X7OWyj|U5>My!HaW}wgc9N{Ea6Y4QY$*^Yh#Oqc;dh>9 zg#yvj7YECRsQz_BakUWqf>LmknumS9_SA;zHQWjgoY5o(_Ui%i7;iQKago%*1w;<$Gbnj*ZvVYQKh~!@JJI(np`(eT+YNzqD{RZ{Vfl zuftF+U5}B%?~|uhk(YvBO=IsT$DTtIp*aN5(Jn6DcUDzau6L1Hl^7b*=~ddPg7e|M z?PfNlV>t!9yBD$kmpn%FOy9xL-sFX+NG!o<7qid@ZVd0bMMA+V83Ah9o&1Y1!Ao3} zuygPZ|GJrnAdgeWJaDu=zI)C1SulDoR0l$S`{NnOkgqt2|k4~stt-mDv@jM0}BD|#XT;jD*hfo=Xdx0=jZb;hEyYQNox z4M~uRGrAG}fb^;a_Bb8aKQrOGdTK)_|++l9d-HI zV*@FpLC4zRv=pgx>8Uj~0UPSOe&q2# zy?ItCiSR;h8xoUmlo~!%*#3HJ-r!4 zU$pA;_wxbdIB-7ZPyg3!_5-8&^Z4I_D>xmv)NL`04Z<{haFzL+8+V|H+!G-s)yD!X zcKgD{;RQ&TZ301%-LNK>_?xz5`^MRTp{+G>y4nCR*Z#f@?C#>fe{F4r$>rF~zd-}# zuA<)&$wyXWHvf$`X_>Flx?u3bZ*TgCmh?GdPw8*<|7ZU7=+U9lCUI-19k1hoUDL|` zOQpF=x)H)Z5>%31OBQ{xs0e%hPxsbnjs~?%2K)R`Zo|(de;LK)&9)N$MNW;m!&~-{ z!wM^MF*AVA_gm>W+p<$u1{9y5V1&SKQ(Hfe=O69S%((WH$UbRZTSK{N&I)wIvt+ZQ!fKL66#+7E?X4^!&uT&d3eJglCP%{{8)I zb8$cKr%vFuY(Q%DL;lz^EsdI^sm%{=q7QncO+>V0c}uLFZ9aWZaQ&abN9fza#qYK@ zFOS`UylrB$B4=7uFbyjsHRQf8N<{082xhEgApa*!1C|>yw~~Cw^U1n)^#*_>2V~7c z0gl+4&0|v5vZ{7RbjJf@ZUU;uTDL_rTT|UyYpzFLTuE5llyWy(t{i;m7baj`@zS55|ejzV?0TZo}|2f8Xjh>n(y#GE#ZL^x@;^@LqfFfd_lYY*iD$0iT z_zxTB`VINNhUV=By2H^Wh>RabY0hl{&OQQc=rxM~Cg4!hKa>6uYg{qwGE)Y>>8r(;*f)3cF` z>mZl336iwBT?+j69^&wKdFMkz8_$N6{_`TmjSAXY-2m3Kk~d#0dz|}(;jriiY2&xZ zY%B-h1-fhPnP?N0Zt9B(Rg8b?ZbHKy#8N&e^9Fuc$a-iqU(bAQI{n99%apz4X-6X) z=KPNjG>JZ!f1*joP{VFDDXK;en57y{2L}`x>{FtW1mchhMSy%8QA*(qt4`bEu+3eX+c>eW7VzZf4>_nf+bOOsmt6y4KKMnKNX2k(rbjg4J=WFh zLz>D4B!b~164s^mPWQ!iE%ss#L}B-WD{&mGmXw{YCW~0q2pZq13e_s5rAL^+YdeI? zOB%eVdNENKS{Mw&jl;|++n6U*t_J5M z_HIm{vxEPdj#&8pOvLxZb)n!nAyuKkC!R#32k09f@SeD@U4p_W{ivYvp}rH@J{Z7=&k0WHC?AMW#lr9?^j7`|_9 zQ06_qx#mSgGdy)$vPr_WLfptP6KbLWA$ViBQb_C;^clK`zH2&ZC|t3bW-E(tWCOxh zl+!ZOqBubETS=mXrI8$EByE8F@ax$!6~F8=)L1nxM9dVp&D1$ndQNHJ1(C~NU=8I~ zw6{kJJN8>iYo&Z>exT8?{2tUnv=qLM@?Mp!SKGLxeQ$6tss_ zBBo|Wt35)?#sez&yje%VTz`qifOI$hngxHcA5YS=89XO#-N?4Jfx|0>lRdo3o4qgv z=u3qjLp!k1$@0bQQ#PH~JjK^%7Qm+?XT+!ZnE}~`wKr4c)Ts&)HNtyC_;@z+RjXc5 zFRN^2x}qq{AvGO&_O5ApD^rFRX_IvZigfdK<<}9XO>-LU%WI1O zeV0?}iV131^`*yy_MM*5sE(}Ng&o(Z3hD~^vCLq8Gp8~FkQ3Trtxh;ux3u9CJb^r$ z4tNfenNG`?EO}p3SA`m(F@se2=<^3RBdnscuJ6EhgF5F8u7Y3a2WsgVh;3OFOKi|! zsuY`$y4TN%l($l+>&SWBFpDQO<+{TetB=SHzgKqX49byK#(>?-az=yLlkl=pAX6|^ zoC4ifnxYPpD52I(#;nX8(QVH<7RtYw&Z|nIy|`=R*`v*)#m4wn@ar_Y(azpOMuaOF zmHFaQxS+qtAIU&*g?MKrVZ5fMW73KzCNpHa!T zaSX31b!;S=L9v0!j)H-lPTk%OtYgHNWDU>p-}Lw-gGz7eCcGe9Koc%Ho}nWJ_vUQb z#py^UKVD;U#-UrtuM1!^(mCljIN6citNvmUuKV%^t5G6PvM4!lutqm+*~Up=r5Uwa zHg!^~_Do&vhA1DY!63&*m0`A(#7KjZ->E=f7C-47JFYxSHp!RdyZSGtwzuTXwRm*+ zslo))MR6tWD_q&>LVMEaV^NK^9r+Wwps5gLw;u%!bBOv-&LDHL!ZI6NNK>l*F);I# z#W{3+{p180WU0n&DqVy!^m{CqE zWY_8QeqlZhT9pfNa%K;)RAVXWywE?c#uW$UG}@629xb7f8FhJSr-ea1 ztaWgyhG;E)t~WzmM(p_PS#XX10XF?H)5L9I5u{BV4c}lN#Rsh(9Ik;84#jt*X~J@a zv&G)s=QL&>eOQ@!<=X!t$SgbS>~I%y;!A3JpfpS=i5HvFW_}Fmp3vUKedE_P{=XhskQ+Td$Qrd}rBAtJSVnSno5@zz7^8#;Ap)_ivpSZIrXCQ{*_kldP5=o4$}lC=IhRkisz%v3&uxc zWRzI1`(2e@Lcq(f?T~kKOh08vW~ZHkA-T7Cb6K;8-VDG@=vlxkD%m>+d6Wodhei>z z1Z_#~5>tHtw7{e&5hfq3kR0-rmSmnbpN$HJV|p7c)hgIR&WXS^$FYPL^vvp}S0=bL za2c$0gim4PEszs4UX6UqKiq0(quwJ;E#%Kpvlge8U)7DZr z;>N2acG9bMeCS;*mP@ds3@m~1{3bORryeorI%pK?#5o95XXFv#_t$!A^hvIP0^0IF$^lQ2iwRrmAVSB-~_YVSAtTvc0wBIjfJpDsAf{AR0eW?B27 zU_pPrI!B?@4}C^g2oxwNh z>HPVpfE(W(cj0B%+qb6Tmr$fam}~khk@hTZhi0}y#<`Q$Cui#ie7BqfTX8!3= zh1|*W&iXTwfuDMv&oUfD0jHUVRW<-rTa&Jux?0ZGH8(UVl{O#0@VS`q0;=GFeJQZaI}JOe{6p8^S7nceXUMpA%ksu%Vb!OULfJWaX+wS1wW?7px}N4q zsJ(pPGOhNAjfbcQJTm468U|xJ>*0utU+Gg=93|D!i&}R^4tzK%34Sjc4d1iYJv$U} zT$-TCiFNi@A2PW^v57Gj6kTQi`nzczAZ4cycX8cQ`ruiUuD(fk7&kl!F>u3!fmNKz z!i#IVJwTS3oUGAMI;LAMkl15Xx%TnM03;iEPJeAYEJ=>U9z!7l(WPGXHjE}2xVGXW@K%Vrgfoy!*pSu}jTr$9Ij1VH5!vr*hh>kT z5EYj&b?h3P8E^=#OU#%$uYV;!Fl7!agB&mQ=NPwRGYQ_ySVpK~e1d3DA?ahJNnp9t zo zcyx%3O{Vd)?2hPe2lvtSLKN1*WJD4ztFvj}T&G#oQFU2p z;N?|2H+(}AypY$hH>V!efnFQ+7Vj>F1$yfdViP=7=`Ob|`sv42p<8Ynm2=LAqF{=o zWx|UDh*3E*b6bhOC$@K0aHOBgw=tl7Z}kF6=?xne-)k+m7&fBY%t54s#bXNOPDacW z?ZD`6&eKKn1U~r|UfX_V<&;2^8KNccFW!+D#nP+uj&>A3_cCf1J8fM3W)lNGsW5IK zPUj9&rk}zmxH3$n5soq^7Utd+Im|2~FZsy)ue9dp5(1A2(ikWUQCrA-54y#9;=NzH z=v(Zz$o|rczdOe<7z_%m{fP|Zqz!aKGe{yPfvV_a=Dp5i#;QM8>msI09%#JUccX1o zk>*8*kqa69ock5UE%FEON0{Q-JR0dHEOSohb>HtDY8cKSfA;dXE;{gLV+UTusYm-K zZS{wBu#Z_JTcQwO{s4o{$ztPO2D=FGrZ`1$%WU52!gRTk6RUP1Bh*++c#21ATds7m z8nx!;*{GACNDX_U=VH>kc74f|CPYP;h=8<}{u;gz69hPRl7AyvJmY6_a)q?@*h@GqB zsE+Ps*#`pm)H>a9ouEfKj_dV{-GR^VT05kYcUEy|OioWg|lpR0Wn> zm_+>ruIO0**3~S$Pm@0_Xkb?{zR0wu@eWu!O*TsfdYx6N*?E~>6xpkH2OQXAIX#}v z=!R5QFLd#)Zb2Hwyk$74yC&6ZtDyaZ)AJqNzH0aDt!7c&T0u7`~`%_(km@9Y}3jO`3I1-p0%x9Zup_y5()nl7vBI-T^WSXDrgf%c2&Q0kr*~n z9G>l@mGgkkNQg}-Ujo;*!nXerJta9W_$oOsm5I$Tu(oNe>xn}9&3Ady+CIQEWcQ%` z6?GpKkK_4`orqu6y8%U8EiJX{FUYdcx1V99^A+2+^0m)PWdsiaUOKz67CQbx-^rN~ z*%GhYsSOd~4Y{9_+5^8ZtTbg?B9?i>(DpLmeOWZ`!#ERVrI)w1M&Q@FW*f()-paP$ z-?b|h_Hf`<_-X>EV@?@yy*%T9YNm5slL9m?N_5lCo%EhfY@Rn^^+_g9TNF<8c0NAm znaQ&;dJEfYr0$w8Ir;%JFLZEQ=vz<7eUi&;cU-^HA~DmsT~xk)PF zN|#Xv)EOE=i2ON-PRt$61-u(DMNN)|AoT?ybTVxNz z!ygV*`sCoCQr$n7EJJp5RXF6hRAgZMLqW7cU|AC{t=-g=0qLCv%9uAA4J9mx^Wv(=fr5$=bfFj0IEw;53HMYtDwx4pgFS5QVt zBy7>K^&P!mGNrYh#961&V|;C^R3bndnsX}#tVGOkU;o?_`4QxF6|Ozbsm^h<(5EeE zb#{}THv1-ieo@N>e%79300N{=vkWFVC!6P!teul_{C>@fRVGp@2v(D3BjzNTAR;wSm38{MwysIg$}( zMO8?FWB^DJKJR;CEE#S%E3g4r5iZ|!p0!RWe0WrP5 zwk!Z42!2=G@Z8wVaz8*1`^MatCO{{@KFS6ty2>L$uYhcsis;KN$S|KQ;S!PDwqir- zU~P$+&W+jdQrm}ZXlijhJUjM2;%+VsP|ku&zg0tiU)s%HI45PoQF)u{81OFq=ii-I z{i%4H?40_;II!rKZ0EOKVce~n4Pm_NJTa}s4M>-R&W?y>>8fTqnRU&MqtN?m)}#FS zl@e09uB=eg6XH+$u=X)CkO5Q@?0N}l6z9l`2GAG-gX!|#E3&_|J3-L?%xCJ>t<1O? zl)8@Ah53b1^#OnJZ-GY^UX$gzk@pX!h3d=ZFAJ<_kBOx8-yhI#!S{U})>xq(3xJcr zr=jwJ*-=ae;Veu#M6J)jL;aN`I1+N0Pp6A*-j(K_dBWLPOa|FjeN z@s&tc)=JWP&%QAoD}qHjG6r#H)e#SDA5{905yN$%*>R#Vb|t55-ERzI)Sx#2b|Av3 zcFsg1t=Cd*77IAPN!F*?Ml{P0C$0SG`F$v5d`@U$wzO1}OHVfln&N_O)M}R`XBf}* z38ywPr_3m8muZW4PCH-U{{AD z`F94cS$Sq)P!FgiN#-4l-%GhF=u7Ch&gr^!$YF1iuhtaDdy=(cYE!B~m~T3we_%D? zSCKppahbE!k29aGnB(YnIh93xXaax^nv6AynpDl?M41Q3Xtz@s5P9cxUFA27r4}^w zpjV#Fu}$+PEYizi_ZZ^&Z*wg0^XP7H`XO}?CjdyIhUFV!ou*jK{+2QPVRb(Df+kRE zlgh-U!As!HAVi33a8H9F&~Y=OXJLR@pBFS^$~OPiwWm?iSqIRcA61CgMO}Z+|05ft z{X2Zx(lTvj)w@^BPt`kuO4+y?oJ|4)9wB=+ir04x`5HsJH5m0%d>Mh zAltf8?wG)g_Y~fye~GN{M*CcdBg9DvQ3H8!%{>4sI^M4NaX)!c)L&rX zfz?cGRM3JxePnep6-cbeN@UBlUDg{)8B-&}N)8*=JJs#KHU^a;#C`Pij3D1&$5J~& zf0hb}XZ4j1rTT3)7e%od0)#gok0?J&v{=H<9@kD-!zE6^A03)EJV}7h-enJMHnJFF1_>IYvrvw+O3FG1 zQ8T)tX-By#jR<5|V_f`9=jt&uWP~VdlB0e_jWiK5ld}z4r>?IP!jBLYmLd>#>JoW` z7PNtZ+d@*mXBI9mBm+<&64g1rwIWyp8yk?L*qHx_4T=Fb)fhB5@BEE1W~F00_;Sz* ztI{faeDO2Lo}tRPQ%vm$#8d1CF7tb+XJv9N)w;l7;;ClA57ywqs}S*Qm~deDNNhR-?% zN%U^gY-n*j?|9ZPCLKAJ1bMZgf4uIEFgSQZWP9vv)<)(uBLs*VEC{O??J6Ossgeg_ zO~N;hS;DKIO~4|!+__^-6$y-_pX(qQY6c+6TD{ICfKeYr+Z!mN;u&=|Gu}UC zIlE9+g2n5B@dfwsVt$CC2fk==cByGgjCsXd+Wg9zn44QfUC?A_vWugy_lMt! z8H-?{T163EqAQKZDk^##Y1>NrEA)tSioA9JE6#!*g{6Z!c(0>;SHtA;AH5O>c~gS% zhP)Si6EGaWZ-!T$q8fqbmg;s8uJ#6iK>WRO^;*TSN)gcLYMJ^ZOz}N8Y7lRC@&sgP z^_3;`sB86TuwXOYR1`D(ochYd*)%#tSl-@_*O9YG(IsXD?Hu8au}c)*rq8j$p+IXx zZ6!Y-5?ktN52Z{^gi+A0OEuR5@!*K&EN^0Dvty-_1HqTQg;=BM)al*-WBVZ@!BO1t zAPCqLVHdo@bt=?{n!v%*Rtj)&b2W9I{)oH7BA67>k=OTJr{eiwdmscNHa9gSniwyc`qFN zwfEpSeV+s18TOVQ#bW+-40oD~OF+fN@>d_cDV~pn+5d=RBKpfg_ER>EODtnkZF&M;rbRb#xV6?0ni$J#rCaz-sqV`4a zWS(3(Ed5K!V21{J<5!(7p`h^H zpSX<}I-v_6dRFGYx?`8`5+&RxKj01aYufup0(>|aavym9{$JbuoH158O0q$Lj1qudeavM+5pcD`SPKAfKxxuP9lN*q zUmzjC?o{RcV0`7;_lfTkc9+grtFNxE_fI`@EkWA<4Oa1<{sC6$`~g<^H=q0gRw+i@ z7_9$kRmJ+5t&@>ohuSJ|y>XAft``dZ^Lk+5dcCIqY-Vl?{71xhNcJBb!T%MYo&RqS z;?YG=X=u}N-2?+Cup#T0@TeGFU*aX6pBA%T66QuUP(#1#Oh|e6=>E{>6KkEi>b1vb zhfe7C{;k+M=1@)^1r&N~Lgrj+%F59v4FGwg*PtVJ3pqG^ zCntND325tHS_uEQ?p7~RA{kn?JprfW6c8J={=Q^d!V;}UO~Yv$G{!s`eB#YY1sR4n znyqXZyXbX(-w|7LKr4Eapbp9D;_t9-8Tf(Ya!~y@g`xwEgUB9jF+{W)`3(QgLw@Aq zV(K+3i`3qx3VTwo5fm)^=2|(99&c%$FMn$D$Kq?nKlYUBymG0LIBx5!48U{%1xehA ze{ercpgY@*JB<+&zRls|6kT(~S=J%BDsTirjNp~R{R=5BA>wUz`t)CTi}vGF)K?0! zelPRe4e>4^i$~=&-HWn3W)x3D(yH{)WNqi3fXPe4?*_(44<~szoq$FeDj`RbY}(WA z2!c8tnEV{*+M6ht(5_!lH4O?z`BndA%nnpqhRd-7JY}9yduuXlNUb*528~@20N?`MtxT(C2v(V z+*7tzQ^v5N^Q3Oy2SW|!gOhN2=2$8VI~<`s6Y`srzd=x^-arRVyF9brER<43N%u2t z=Eu%2^xC*1KeqtE8e?Hmwn{ObW5*^sHE^r?VP;^#xZOu{3f%}EHW*@f|EhJG> z8FbauvU;7iw{phjwdVsl6pw7P3jR!>9B+DV<-;{pd$E&=8>7-;I(DijQ6+WT) zWu0U|{l6{7S~{I@CHW+mDdy7@`gNjwT1^A`hTkUWEQuydF9-HjcS=;wKdqILh4@Pn=d_{kM}D->%VJ&*-<`vzcXnqAU*!DWlYr(H)Dl` z^8@Di_=)p3I@PGl3K$CuBcGpA%c*AmXBH)#43sTmQ_X*St5tgaG2TaStM5b;YE-V~ zDLkj2qT`!6*Uqo2GPhH~zIULyP_M?3lE+fxBc@YLH#c<&ha*}klRn->W}ZXaO6L&E zBUf;~rLt#rHWMFn3PZSb6iJpN;hS0@IHuZS7t=$p_VyA?ELL zq-^h3ea3wA7cJY67Sc4a9IRvD+#_WTQ~iqJLQf=dPq3SimkJpOuyt@Uj6vP zMyD#u%N(j*%=@an2k_hGnWX$`RpGAUk5O`$Nkav}j=bvDI^%&5csB!+vZz4tAt0YJ zW>S(=G|AXUU`Cn~7~<~{;gS=hN&&I7`~}xLWpMEnNXFouLRr>8U)`7(q<VGW2+N;8E^SKY+^5&6-{?^JvJHf6Y__%Mp#0w-TYvx$C-WaCKfZzP! z&<%dCzQ`->U7rLBv5ydZ>3>pqV$vTC7Z zj12l-Cnj5ZSHEWk!Hjqu_iq2l<)&paa}9F=X@$o2CckGU4y*Gtf+2X0_nDj=vML0M zBz6dn)l0)NNF@)EvOX~e$nx@Z{_%`C9$aZur^@_VS_ap~l0GEE$#qQsf!j6u^&iiD z5Wsa7Pdq5Qp{>zmz=;Td>-wt85^h%hO=Dp!_uAFrT7l+Q!&Gf?vx;KqleY5*8=X)3 zLXJwT8O)P~%$0-?mTkylX-N0hT=U0+9wA-8+x%)rq9y|e>$g5r^Am#X`<$So`Z8M%g0K; zJj&j6Oy9_n(7>w%_(pyR0&@R1%A97i$Z1b0-#5c)97@nNs_2cc;l|(+g6$NcedIV^ z9S?rS#s=r4F+&+V!|=~cxyyL%O)kxCDxP}50L1^E4MqI32!6aEWqn82tZZ*_!Cm(m z2J?fd=bX%i6VRuYzjdID#BjW;ov>?wYTiEwBpKKd9{R9G`bMl(&dYZg@7mfsDQbsK zpc+PgrD{tb?|r2J9Y0)Rt(xj&k5SHF`RZ9(oI>g_UvFEa!zA3{+sT5_uBKkxWkVDtVOX3bfOsKk zh#=qoDfQ9`+9+JU*n1eIsd0D&!PhKPxuyR)XNOay}~!` z&K#R5a(2$FrH!5q2rqY@TR8zgtxIr7{pzBvF_3*MkMEwkM$S=z>^L)^(N(Q4$p3!u zm+EkmFpvfeXCmNEAE*JF-gGIoH)bS0{1+}-z6KiO0J75gvqcBD^q=&{{yixSZ8vkoN6Fn1FXi<;K7B{rLzc<@Se_sK^ZhqK`mkUJYc#yxdd5zT0aJWc z#wcu8+?z-|;mwE&NdvZAw{G0{VZk5w zZ`~M8^1lCj=nuWZ%@Wjw*CGj-z2$#>cvR;m2F;PT$GqD#@qz=fSf`%Jw^d8>!?yxi3Ohs;}oy$_b%k7vK2NU#ER` zw;LdhDEyyci2Tndn~wldZA$|8byUdAmz58NO>sls4{`>YWapFqGKUe+!s;&*&-zvH zS6d6GU6XoJj!25Fqf6JLv*g=VFpbL**T2!L7w?01a?JlU{O9b%e`23tU0Wm1)-NZ& z%U22&UKxkeYHXmEb`Q(vp5!(?|ML<{f zxPo|g3i=E8zn|T}7A`am>_`N@nV7p=vdtN&-o&Yqcov~cPlXL14dWDu2L zU}|9}#J!?-5TOZBIgeW17>GVAw)wvg#!sRI$Zf*`Qr}R;G;rG)P|>Tun+iq# zC*OmEQ4#>(oFE_Dz)~;}BvZF}87R?k`8FuD+(PExmOSyVB@q=71yNDWWbbfV9mQ?< zRZZo@kTs8$k&_-EUwm5J@T~jzU!9IVkEi@=NZ?ji&3L`+rjr}t2)9-K@^p<)*zkn* z3d9)<6%+H==C%B)__gCT&xd(E&b+}C36)gh(sw2B-0r{0PYXaFtG{vnfO5T5jhH=p zd?7YUuP-& zmw2PP!y0O6B4)=z%Qz1Lh%!(}U2p`Ka~<#A>!G(Kj%?4`jRc>>_^4zce<%3apFsDY z3~k~?Y8o!9j(ulpe3)PH6-Imo^=$utof#sL+{y>po>!=DJrfJWgvv}!N5wnu0sq7u z#Ka36k{rr!t`s27Qvx;Bs zvwkieCQLg7(W&pGp;vFjyMzeN<9QOYZM1CHRChXK-APLfQwL~6Wd-I}u99ndoS`b zm@CvOsB}{J>^a_*=9Mxfizi(Nl5HZx05F~szfq3G2JR^g>q9aR z_YVESW4D09m)Olsa$5V2j#PwHIDcESt{737*<$f{(D^JmCgbOlAta9$adB z(bo1rZ_m!UsrdUV%}VL@%k}Xb{GmuvDZML1y?th_TKEhZWuuQWOX}>H4_Y{Zr+-w^ z6QewK%o*|%M-xktkL@_2=`Yn%e@=){E|m6;k+<1ue!M$Shz57n zg}T%J;8E#GmpGT2t$RxMlwwgo`T?E4G5GQJqQ&4YZ7rw4`}(NpvfR0l|D63fMh4RO zE{4r%DTjGW+@q-~faB1qe6gTGB@;Gw#B+Xqt4#Ync*Mt?wYDHke4+!kOfz?Ux#!yQ zsv^UUnAzK54q* zP}|lP>kDha8|&o@kd;Isw`N&`dG*kRj5k^tnBBKVm>=#gEQAe3zkA9yV3=;{bgc{< zs0fRi<05U8Sl{|Ii>aAawCs>6nw~=C1BKZYgCv&_PgnST#f%il^_d6D8$|H+_y`!4i{@9hB&m~B62*d1j}xBeCer}tG!e%6xa~X zuezOYk6H1zLBHA74<&hQ6gv?VJ7R}h&k;zQa3fG@6F{Y}Jb&fUMUSuXk*OgH%)Ba$ zVFz0rm9d6{BrMVAwneS9wqEk~^{*gh(=64+RYr^M)8GLu}g6FhPKyrr8#CK1(TZVXSkf%6@IoS5IZc;5Xn z2bEeShRa&&PdR?XHNh>-tGm{)cEUTOgJgsqR!|l&h!T)4dfPe@@V3yduC-88!?d}~ z?!3ic?^7XJ0r~`0Y!81OAQF`y5FgFHX|n;`6FRcx>|EQ$^;h$Ju6jzfL3y(-@2G?C+@FX1753$3ojgBm1S5SuFB|Ez z%&Z~}k~O~B3_W@$riiXu{#478EL>7m)1|%Hi>&La%=H^18rF%F`HP9NFL>EHW;K-e zDqF_r+Me+C|EL~at0-?(*Q2uKl?ih31@+3{!gpe3{5wu~`P9>mTHKd;vYfHNoO~Ny zTnlo7$)m>{%WZZ$bN;eX zpevZKlLVLlhiR6P14pMb&r#=MWz8e)CmXJ6Q^!=NxvS83-UG54`ohn-8wEAIQ)Dkr z0l2P}ONS56@rS)NK*-#%okSp}cW#mO)PlCpc8%v{5a&5RZ=D#%D)IA)VT(lWDr8Pn zH1G z-Y}yVwd6cSKAJ=+w0D?G|DVxn!QtY^Lk<1LJkSzVdYpASipAq};;Jm&SgTr7R_Z+8 zO2$x!d)3t_Q9RJMW>0kU`P!JqF!lAyuJH@N9Ki&IEbBnWGIa+1LfPhDZIr+XknMS(e5YiAr z_bR*5p__I00O^+DaLS7QNZ`>GQjbC*J-<&+0}7n=tN%oa9!?usPNx-A7~dRmRp|UXtk(S76s_j4cV(Gmvbm$yCGLuvS}YPI{f=cuGrtD8VuA))0Y9;n*C3wI_kQx zO%91}8p+o?2%+NneJPIv^j*$juVQ7NVbWaQc*93Bmf;=_4W>e0S`1WHLdxZL!ZMu3 zMhTFO+Fr5L>fBtJooe1(qK*iz*7PMz>>F`42soHeQq~RsJ6pS4U%h9Wv1Hnv5(MdZ zSiFX;XY_EL^S-mq!XN1v;bLn$^gs~Z$l5HXkf?LsUqiKM zNr~pQYZJCea*da;@uZS|_QaoGvc=kkTTutwN>sH^ITt&(R=x;PJ|>meM~abyOr2#^ zDg(z7RVK`Qc&|P) z^jXfT&Zub`IAc~%#!}!n7|oIJ;unA=mWi_!lv z1d6nlNiXdlRGxKVcGPw1$9+KFk4ssUlQD{(=qkY#nzVwBE;?kyivwI{|1cpm@*^X+ zCi=TU##-3mTWh19ThAe?UE61EV|UevrkZI^3*W8`q(ypxrnkakoR(R$v?Vz$aMZIp z=+Jo2$l*v~tuyIpFqZtedZlwIj1N5orO)k8^N7MajVLc7FAwI!qkv#lS9@d$Wm#% z_Sq!h|JZ7^6w89cdTB-)81md&q&x`^#*9$jatQWSSL|9sI?1b1@FC-s7gU)LpGMj2 z#iQQFF(LuDXDJ_eJ;`~YxzWhg#{A!cw(<=E6JKo+j3AvzA8ZE2THe-^{fC#p%Ka`Ma_0 zxm!?OY;aS?lQXN0d6fy2zD3}yvGIgyWTY}5ML+cc6;dB=1_+oRS~VX;iHuK#(h z$i&e7@Ykr0P_OSOol4Dj{*(f4N64r=j%(bj%tpV)X~Kw~8qix;F*IBXs?8ByCn*}> z6vio(h2u-6(6GvgPC?7omJuc~3HO9?x7$C(Abxzn4>zSTQdm}2=c+L_Z_qG8v0PtD zrN|?)bS%+tRN^~SHDXSm`TkCcxmrT-M{l5l3Zj>dh#d%)^j-XHmuvz`%|O3`i{M%rO}Vfv-D@lSH1w`;y_$|C=6w_2lWC6;9iF(y2&1%iVffd|tAh zWAl4CrR~Nf;4-F8;~7Vka@|c0cTcGR%es5!D|+~j{jTqTcYxmfqmyiNyrks!B{>R6 zFJzltZ2EiBaBDCF+q4Iw$Xl#f;Ae{#U}huw`{u#~hsRMnO}`f;2&!iizQ94f=0x8< z7|pwk|F&~~6U0Un`-u&k{`-b{qabpEJnZ)!?vfw*A*5ffy+xj$^G5sB!hZ#v0O&4f znO+^f^{gNJY)YqJ5*4wwExfXIzuf01s!U1zz3hTH$y_?j5Vh53{radPaTEZmg|+Ya z{9rJWM%rl(xo35%)zxbLQ@p<{7-4I4Za{r<^iN_T`X1Fj%UibLfuAGhfe!25 zbL6i!d_VL3(Xn^wwUC|Rm7nBP%wOc-gHaxCKZ%9j?Gi@rejbG0lji)%+_VM$d5Pr) zS6RVNY?lT4tLzJHHA+9R`>(J)25w!g|4D^==Quqe%+*hw;*Y#Q2wFCo`KKJ`qkk{# zgVcY{cSEn&ANk}S8PbvZRY$SA`J4?a3#%;K(bfw=Ar7@0}Jfer~Oo zU1pcM8w(K5(&Q!KZj!`YcD+udeV3!*+%tu+qh4HIJf{TaTGoMOu7ly4j#3aWQ;ExZuo4STl-Y$bZ_K9 zc%;zj-@4%wOs)0GjAn3Yrq;BR|7!4i77mMuLuRjKFR;6h>DFAdTS~0q*6X6?7{zxb zuq&;bK2f?x7O^7Q$H8?$16i^3H30*bUJ8#!JAOZ%2!@v$!Qeasbw65d| z=?_FEJ1b9be9N(`SY*UkBegr7(v_bk^0zS;)l|3nLq1P4x}NSk0#Nq+aSVLL%+k<$ zF1=uTaw$8?u_o*HBDj2JG1pm~k7?!iZf$qfVX-)3$tif^5gs!fAJ-Qn??0Om(DHz!mB-Fy9rUBAC;Y(_kpeaGb-#xWYcM%~i}!!Tb;4KhfoB zknnE@ZR$}jD~@E@;AY5?mHWo`V0E2ah$w?JtWstLZtNunm7-BPQh9t?eM#-KnW=QU zOa_;M!fdW9)%uSMQP01Fi&K9n&>-CfpDTjqm1e(qFjXs8RZRl6YlEbSwEL9$r!*vC z7z@k0zD|Q)!N2#{9cB&@&>sVK0xh#aU7lAI&?1vEae?QzJ-^oS&OUE@o_!!(8iISD z$QZA!Uf6nG-4R2LF#xOCI@8lmZ`-;K6*06Of|hTxEc+4%#W!H78~%E2>bQ_hx7?*q z=zewSQuf66{~5NI`qw(^i+W>PimM#1VV;Hn8k#oB>Gnz(VaynpzK58G@R%QuUmTYq ziGJHM8ni@Q~la1tZObc12SX$=;=nVq0F%?@VbbPU|fKTwMw~(|L5cpp}M|h z$~nSvCL4YIP_@p-j$88IAVXcL{ZuFye5&HB&om#SDVbuv1XKLp>bae}zF9Kj`zrbb z#me;~y>Gjh-shX#4r<+=4BbgZY}7STfQtbawPsoZSNmm;do-^@0)y+2)&IX9n-RJp7(S1%Dx+eT@bnl(!>@Pse6=qUlkr^cXE#dy*9q8aroyp|$Nr#v}0PvDA|nnF^%y%`7jjrFcckJ5Mwb zox8b))BM}MzM=cr0Yjv#A_(vAC(4@#J-Z^{SDC4#{zFw^Qx*H?^6*IcnaQA<$wus7 zLc@n^X1M-1Co=-Ef8Sx{Oz>ZNjlI1?u-AstweKH&TEqsh`=XYnbGYtjUJ$R}c|9IN zTM8NgG3pk|1NEJrkakF$)a`0^ziWFsoR-T<$>j+HA@d>es{H1U-b7Gk-GHv z{S|pkqW<0>70%_*z!eAtrI^Put=*U>g&(Wsta=6gA%6+rqTgMG`_s+KVCU>r99-l! z%CQ==iJH0UG1$kHf-NhFLf5ntbva_<9K7cwwXf+dW}oJ{3OyUsyJ)0$G4XK{Q~pk; z0E{|yImMUeS2gu^h<+|Wd78KH9396zpmUl-TXpt10pLH9)TKSI-JY9bZ;EbFcNhj&OjN#%s0TX8#ST znGQrklNp%}vB+gTUq8eMPKpffc1Roy#gx$6Wc+Uy2MhQ32?HCZ{Zy%>`h6s(GKL7sfV!#rrNX&1il|w$STN3;{+<)s|XW#6#`rB<4J4OZ36pT ze~XAN`}obh3QZ{0Y^7^w>9AJL?mu_mNUgnX9j>Ug6{J?)mrmH%`}+hkyE}o1x~G;b z&=zt_2BfUazjNtRNI@ent}#yIQ-`)*p4@UAZf|qnZtF*P?w>oj@g8v`u=P6?U`vvi zSS1M-X^((Mlc!R6zX?IRuBO}18cKHf%vioX|nlT`Mszm)zfKGZsgCD;19c}2gOMlR*earnUxax=K0)}%0kha_o@W22J9S?Y&8BuuQWm~ab!qgdUQmnN zsZaiYTS_xktk!`R(P;gyok`<(jTKvm^dG#wb*dWu$!DXVT^*KnvX``DPZ>_*P5I*a zKiUb)JI711jZ(~ysXDz8Pc)fV&+3|Q)GwI4J;JgS2aO4{-xtdLdt~TXeuMnz1$&iP zYLip5#wQku%fOTN1=e#mTZfK65PI|<=W>AMl+@f+%M&Gis;>9Y-mapzpOjqz9%fnE z|9dbiXZ3cQe0e!|H^6-0{M#`7|0pp1neG4OsQDc~!2iJpW%?@sJkS4pAiszA7w^rL zFY0WGeUtckQI>}X(j8ACtz=RQ3^ZvOMbssb!!q`#I1O(aFc#1~$2R}65l z|FvFWVcpda9{<|1sUsKkCi*>2VxbZU<@Y`uQown$#!f=VBzts${Y~sIIp+rt0byNT z9#_a)_j7i?w2e<)1dd$|{*7)FKB8wU0{eBD<-ie}x4jCJIe#V15C)F9@y*Fn zWA@)9caxwZlg(cft~0l`GafYH?siSCn`^qyNcjKm_H6*Q zU15v5f#64~uv=vq4+s2GCeq#cM-5OvzJ;6PQYmnfw#RvW{+9+E%j=z81<+T{IyS&N zhrN$*&N#`Pr}#2n1x;(8#a)%5w4sjQmMNS3$y#5lEx)HGb$$5reuIoRtoGxNt|oZy zAJ9qj;;1`yJ&k?VGL}V)8)Ko;jm&oxB(Ir;%3ejRfQFQ)oON`O`=e%5u3K0q1jDWu zWap}FX>X}$bZ?%m7+9cOxq8V)7`$Msrnz{jk?&=oTSL;?jR9Hu1OJt2w#*2g{!L(& zQXczOXgOT$P{63NhJcJJr)kU5YWqF3=Uzsxy1R9{!Lq=2#3H4&(xf$_D@iY6rH|Cd zQ~8(wF!4a87_Yz~j#kH-Ud*1@x`my<#srD}k@K%WAf+XK<#xN@a(tp@e`HKlt= zvhLem3m<-xQx;j?7(x)Du98&?rpPVvRqLbF=Tdp@hj=FOd?-*rO2xyB!=pVL7c>1+ z4nOe(Vts=LMN@F9Vp}nHxAM?&{>e)t^%-W;+fpl_gq2B>pQ zf8U4xPoBWhhl{80AE;Rze(&|bHO6Zzjn&Pe^CXvQVbQ*PPI==8vt!cp2ZNj=#eeif z2R1=^D<84+BZphq6(^XUT3L6@U)TWtJ||qT1=J1==#GWUNsl{FH65Q_22LH zEyY~i%6u`f(F<^x|9sT`DbH*NB0Y|)ch-hEWp4fm|3lOJ#vEIg@9P=1ijSAvWUi5i z=X(K>M*VvOE%bi{~QU4rp(Se>wb0kXzeW%+%+2G`n~{Lox*xJsn#i$GLYWVnU&kFQJN)ka-F*zxNWv8 z&HNl!@RF#VCx<8O0>bB7`baXQ64Kl20@;lujx3`sWQa!bdo~8`- zvOkSTxPePQe3E_t`}aTO<6$c79C&r-A{~sb*oE+X37^Ydh|xx=+@B?ml211TtY)V@}ZgroU*+m<(#MY2Z$q zPm(TX6|Vov@!dP%)bg(%|BdGS+@%Rkzrj7hJ|LLbO_S?Ca`vCHfg)@GqN2Z&SOTQ! z|7ScffNNXG*`d44FD@pw$8hmahOd_ks3)Fk8UEIzbj9P|2GpoyRgBPv5G|u31O2$X= z{wjLOzbUZhExaiRn@-3afdNF;4vxSH$kMd}Z?>B6iBJw`we! zTmM+g9$WjB$_-9n`V-0rwxymJQaV4jJ0!{G)Lm~Sw0c4L050VJ0ZA5q(M% zR_rP)W~4{6Y=wUPd$$a74?@=O(aF#jGvMeyr>RdpB#%B9{x{P{0U^bPwBz3{dh8QCe!?3F_+ij_8$IX9%MuxQo0}qGBeDuJ6tF zTRU}|WgtKE*{q!xblymW>T~CcKV>`~S*KNS_n+Z78r2bfu`OK$Y~6ONT)N|wXH>6o zr`3Ct@+X`+AO2vst@l;GcIi~?L9p(hf4;@f4b2T)zGdiMd=B`jbZTf_qhGtOC1}aa zyr`+9c!EJilI`thD>ox4#KB_5l6?`&>l3FCEVxt37UYh%8)+rmWT<^yNnuGOc_&VF zLL!m@DnJEHR!sSHeWl1#i&mCZ+{!YWjD_YkT;t6vA!$A75e~)d%*$nsr65WcHs16> z1@no41ABpw5<&h+Y$;UtWcZ9MpqtZw)o)c9;RFgq%1qe`y=(y4iS@UnEgh08zm2sP zJ23KV-Zz5ES?nv6cSkOucKYqh+cnL|(Y8SuE=9{DK?9m+PUp9D$w&P0&bV$R8J&S{ z*9@vzS$$O-i$A#2XrO|e6zwnF&bCYU>~HXg$GQ{^67v)+Omza_J!uiI>;P{3HM?5? zE7Wjz)MRk*`@-2T3r`egA3doQLv^HGvW{fnD_zOYJlQb6;@en90r-j|OoVuvp)gx5%{|k=bOD z@oUAjS{K5;+OoHr+S|gaSWD(qa4lZUc+LOw7mLmzPmi_7>lrr$L!V5Uc3HNrCT{s; z*{(F%EH7EL2Q=>LV7-PfhA!|_hF>j7;)g-Pk_6X+YoXNVP~b&UvjhX*yHn^SVy2a> zWDdih@qlkc6A>Prd$!j1|t4Ri8+mI=4+6sxJf(j7k zJY#aAIW*eR%qojWgo>KV4ykE+r{$teK2B2!bzKu25MB?OvA_39Ds;i9@d^eqX@+%b zBc`OTZ`|CsZozQ^VeJpDSSeoVI>D1)2)=_n%Gn*oK7b`lS| zMtz}aJgD_rGCFZGThTu#66&@bTIlS6i89rc@>hlxL{+Xcu?Z2D-3cjcU+mYcatO@w z9@_NPE|Q^B*${E;CHE{Y2DdI4^#$s5xfb2&-!Eb9wAOr0hKaG^rJn9R;COwc@p9{$ zFabhVO+V#w3em#8+x_o)^x}Gt;0EM%HLj(t$Ws}pND&x1dD%2>tO$}4QrfXN+&a&G zOdJ?Jf_j!kC9gs~7oBRw8%jk{0Xae>(T0l9#jT8)h7!P%xvV27qf2W#t>wnrj387u zbSGRQqLj8_<&AXbGjGDU7b75_OD?I|pNbN9>K$O4ZurLSx82*mHkM_{w=So8*9^R> z*>Hcp@QkthH3zYj$knh)KkOY|eh0}qhwRMFVu-@)i3PTp0-v_43Z%8^t?fI!8W+z? zqD!d`7jy&$xkr^P`r&Hq+lJg`oCC6jtUsv0@B?@xqm<*wXBxiKJRp;8cdWq+2_L9w zS1UE2`8zQb8m_PR2t|E8g%FO#&gYsdsH$mizRJy)?&}P`<()lC1%>Id9u-P{NaNv) zs#Pl7R~TQqIWC2OvBh3gUc7(KLk4)w1U#s2k)F^2v}`xSYnDfM>Ovo9{!PW|FT!#s zBhrZ}dbM+(thFyo z^b$f}ZSz1^z61r?RaD&NZx5y*%iDh>Ia_)_rEE<7vT~N&cD+`?vE1{6ZmtzcB+H^dG zHa*is>D+Os$DJxEX#h=Jn6z#dSF5#b-RY+}K_)N3oqK(bVr#R&VyNrQE=cd-@B6Cu z-#5YMv1mpqDxdU8D3TVISG7p7jl^uN2k{${- zjaPUR;a#%Id{-($XTyjVxl1=v69Uu4FeMCiRaso^;IIXO8XPin3SRrg2VZPJQ1jK0 zPh4_b^FovYf#GXJFsRKmDLvQyZX=BwGE?MnZ(Gtt+OvHq(VVZe)xajv^3D$xX|~e} zfcsW|;FEfEDMU--)&M8iJmOhaYIL|~;tZln%Gw+m9tN61vlujhRQ8R66w zw?6$GQI@!lSE}y$IB0c0M}E}tnuLYgcHRxn4nf5lhW@_#5G$Zr1DObqR+SGnki;Ps zi=}O@?u2Q9So2grfhe59@hrySp;`}?Q9^pF-BN0|!n(woN4$%t^OpSWv=?#J@EnMf zduC+T==q}7iuBU`**c$| zgLCX;?X?Oba8 z4N9~{bxGR7GV~8Djs)FW-u|pj?b#U>vlMIens)$~2{cCV9E1B^k$= z4-ax2SF$1~SYYW0LRnHp<7EqvmQi;XpysIx?)-=oI(H!!1vVYXa73JWL}5u5XsUZq zqUywHi(R9LrLLBE29z)z&6!s$8c{eM2O>XWI0AevdwcviKw#XX>0>U;cCVn!%6Owx zBM`eX4C6B+r_IK9zxO$cSF!Mkpu}bh2`29Ynr(hz06RV8ax`OV-rs;AZy}qoj@|;V zdk(#l=ECl0JS^@GL5$k~+;|2L5fAt>IaUZea2U8-J#_x2+_t)+gbiC@)50gEdYJd?&wn z#6keKUM9n-r_Ar~-O1(M#Y#lKw||izWZ`>MR1(O{XAaj-=G`jN5-#b}Q&D1X)<<`XhXn#2o1! zqH9W@Rn@Q3KbDUv@yT!0L$suya4dXKapcp%L0vq)*uAi1BcRCG{G+M`Ii~m|FfYGo zT~D`z;$G61QUde)tr!GLqR)(13ba{XEpXifbDJ?X>4Wk@o^1RoJ6%H9hDPhxH#V;K0?;y0; zZ-uOH`P}=ujg^m9fx8-P1@mN;r=H`}TOacDpwuv(*!8M`MC!ScI~z~d{CltWpTb+M zuXC#vIv+IQ)q_L^YRnzEQD>)N?42CyWwR(-K{(Uj?sCshZ+`r$U>d;ybu zr>|=au8}jgoR-MRa<@oHkJu4IPrA-}6j1S@BM_7$Ih$;gIJ;y@WSl;!`xuCOjKD|0 zWcK2U5(a3-WRIw#mkmtVTJyi=23%4lTs1mJRQ%P zN-ppT7RNXBh^yQ+4eC5V5m;FE9&cf(;}A;G7t(OD$TIocy`)w1o}EdSdKU2)F2Yj! z&gx()CVcB#4CWXfUkHCSvl^pA7s39!5VLs*^!e2Zbw=&+e^Lg%J{$xlH6FmD>|J=u z9c%tT=26A3ME{9S?Ee5t_49Mu1Q>^nhkix3EV`My!QSy$^S%2IF7A4#Ge8CRKE6O& zpRNLb+WY+-NbB_r;7@zMKOFvly8sCpdGO;vCI^2j)Sn91Nk@Q!?EkIchj|MEo>Tw| zXTMeMaqK|jdjL#e`K$%zA0e~T30PWS`n7Bw@bs11c37`k|u04gnylGuu_{eYVA?lPkbmITJ;_VfeMK15q&-(wmz@qqkuLi%a{Qv(Evu?u-&?^vg zVR-F_tWehRQ9wn(Ew2>iopR-DOjY*&rz!tKlgL5d7B_A`o9x7-)OCK1w_jU`&poeP zACclYUW+@0SlRh@AY_H1(-}50=`f+a+1FIL^X`(`{X_mIzKi|r^}VJw;%&S|F0ica zj?dMq^w`wq9o3LREsYB&MN>Giefi#mpd}TIySHQOW~+xQWr5NV)Bz!VtwnaQeBU#l zp7ScrboVF~uEm#CvlCr?KNEi7{YEd3uLL0Oefcfw?Amtj+0Sl(zD?x{`3lBK8M8ox zzVrp#i9si^Ov)BT@<5a|Y~P1HBTZe6%?dVCxl{IYq#7M|S6T+d3Q#bCq*r+z#2*#% zYJQ7<-&WUD7h~gsbx#a)sbflBL7XUSDj10mCO<9xX|`q1^3k%}=0t?KyyZ_HP{^vx zw<&m0G$vjsC9lJ@d+rOrpHv$BMX%jTu!V1>5)>(`7*8md< z9n>v-uX6iWQjIXaxa~tM_V~1nk`B|>6LEh2=A*Wn4 zMT?}D4SQpD{8F5rvVcEW*~!EtsJH=$Jb)|}%P_`?h0R8c^!axu9!NndyBO7^UJ!68+HUE05rlkBn+P}j4)EW+CxSkpTvLLH;quQiC9 zxM+lC;nuJ#%LzK}w}yi@g%bF^jr!!tp@tNl221Ult(S}2HvnnDk6lci#+_8PIt`BQ z1Sh09tTY|G5~WzV{tTk90_RDS*PMm>6Nki)y0B^J2F6uC4;rFJ@*37+>NHRLqw9^b z!xXjn?mCf;{XPPr?Ihbsyj!=`&ilgQ<*n?<2J(7JDn(;w?dsZB%Ie}Z{#XjOS#-Ra z$vqP9oDX(aSUFpm4)9zproTEdFxLFs+RwBp7EWykL z83?O`0I}j)!;|7?UwS-|qUvDs8;@yV%HTH;`kn2XR@E{PH#TY$I-n8 z@CaQ+_($EdV_i1B+f46JxY6#icr~35k>>%KI5^u?5LA{F!4~60eDuO;=%8vB&X~g` zMurbj1hfo$g1p(r&A%gdjo1upq-23dhP%+U);H}ab;EV4J{Mg0S>*R-gEt*2*U2@g zOnOa=?BlY(N>!xq%2~j=v_O+*H#K!6u(rtWyOpd-@>S=I!>=m(jXFSr0g$5BtFz`3 z5GOpeVg0u8Cat0ofD?d%1a(D^z16J0UN#VTo@3_Z{m)j)zWom8BWfm(?T$`6cV5I5 zm}rjKEcUrb*v<<-!!@;;WS6CgJDfVSmt&iRZ=SUJ<{wkkwVZxa?E~Y?H?f}9(wkc9 z=g&H%&$y!&Usj~^C(ljroqwIg^G!FjHZka($UDi@LtX)z^yyjE0KFP^0V? zXwWSOzwmF~4KAm5?v&R-rerDIMJQ9;dWwV@ZvN*#wACawrG&b>g%V^Lca0``kJcn#EagE^Rg>M!^$m$X&P;=m(F2xSC6!I8QeK zNsT!o<6AZ!NY!g@xIWaKNC!=b38QbFM4tLnOT)|1&>F40VUW-&AkNeEad_-pL|8Ww zDNURHYSTbYuhv#KDGPPFsIhBb^6~+g1>cahFkyi5cE-oas!nx65}G|7FzFZ?{$s~M z66*J{-w6&cOcHZOmROHun{=mN1;!mT`0rYQix)cdKq<44TTeX?WqZu)=Ez(4Or|z# zGv16vuAcL2$BFk=fcc>kJNHIRZD+r^;UrHXj;a2Pf(!i?k}RKE_fol<9$zfIGu|>?IobjP@Nc5eszr`_14K@T zN1$}hkTnq3vydaE&U%rHjUo-iG*zdaA9otA8e>o`*+MDcO1eH9WGc66ZD^Id^748Y z2ljow(ZIxy56?sq({}#hC`~sz6qggJJJ%`fTG4RrsP(|-I~xvln3B;E&gWfQrLER z3!PIbxGRXBBcly4j;{Iqo>i{vW_^RQFzVV$S2wv`A@E*#aAq49o7q|5-Dd!bYhqOT zZfyXFmjCX|E*(|yeQt5Zz4W$^!??T4n#HSp410{t>$GLiGqKF-O zj4>5Vpb>2)FE8yL62WB^+f^*gjeP8KdG)bU=04KPc*07{qs4nH@~XG#8v5IOon*YF zr!A%gN`HrH%^ak$J*gPAhmp5$wHDM?%%mfqi2T`U$r(FlR{@%>k9K%^60=Y?Ox&+5nZt$r&=Y4)LafqggFQXH zX0V5ht_u6gFSj)nFYv&wRp?_WZ%=1W)3pXbr_x-A zUBaRrE2j+N>r5t}dSprf07}~6z1k_A2&*#Fc<8sTckVX?g+nIiNd*QuJPc15n~&$n zRQIR5i{`%G7sKLbFI&5nN_jr<)1^0CQj)8%BXMx7yG6~Ami(8Ixi0CNBJy}0P z=iOk7hbc`1CMzD6b2v-bJ<5~lYvWwIpW@+xO{#Z^6o0W%A5#6m)?pN85k~Y%EPd@Y zm-pCWN_WCel08A8tkWV}WrZ7SrF9c!3Ur%e=x1v%fP2y-)_A{%!8*H1IwH`_#U1z# zSuy0!2lYVOi?rgBoU6Bb8PsxQlU4|06V@ryyS`Pf*&r2W^p2YIvOy>EW;CpbxU{|0 zqOgg!OUw6V zWzGa!Fbn*^J2Jd#k#?*!v^dlu(Y~}Cz%7$~c=Vh2nE)rgT* z&Y+BbgJC8V)jc<|>9mn_!f$Djov6{DukhXz@d14T;S4k8kDgum~`QKNx?e~n2uchEDzr((ypso zRQ2&xPA!ziWSdfy*MRL2?5wSYpOrhcCHe&mP@9;eh#)mWO zx&0sDrPnjTu)6R7wu?vVVmZ@+60lb@Uim{`t}-j`@GY_e67Cw;Do5h z(Xd%(5X}dIQ~~<2PG2KJA@ZU!!zCgzDb|Sw^!;g}#=FRw8Mj)-tj_3IFmk{u;^y+F zq>}B14+&-N;{cwgK!R^}vs(>|ix+dZnjU4m?0eLlVZO|WwLcBNM=o_~6EimImX zL~LH49@U5a<-Fk4#bz@b;OF3uoRB6hH4{D=0)c_rufSkb`8q+%$FbP!i0IpjTc-|| z_LL6(?JDQy3D)b+L4UH&DiI@T%1)}!n7BW+@^x`GPHKP;ytiWfcs!QZZ;Tf%C<(^6 z1E4WkMEP70cFo>py7W75i5DM2L8hPicfW9gZT7Wpt^1cFsc;c$D)X4R5NYmdxX4KB zboQcJSpIVV0p9!+-}QV}uQITvBKq3>Qx zx_I6g*~f>NBCRB-RiP4XEqxL=NzzM)OGk|?jc58>1xD6%w`1{|D~kZJu2itD3WsoV z1WEX%kA0-IpC-)3PGzhZ!3$s8j&Yj)`f_7j%~Jbwk5#WlL*)0`no1v<81J>{N^ti` zKaX<16{BDBy0 zq0O7fhRzw(-~|`y#|#LoDq`G6XDBo=z=Vu^06!5X1aGL4y&u;j&D90XVOTf#yzq{R z!{2Ypu4w#P@k$DIt0__&VF!btO*p%`;$w$*lbUu zFItmUy~$yY%~!gJaev>SI-Rn)Y_d>cs2#`-v5t zL`BCcsr3q`q*J4k^z06GgX}f}t-g1y_5O})fQB>py^v}lI#b(A!1iiRdZeezVvdhn_O|D7^hDHD~~He?XsKIy4F!A zvGDdTc}DlnLQFz`au*=^1~=_xdNlZwfq5jgKt@ze&?O1rPq<|PW<+YsN{SVfs zO=W2%^tsI#+!V%&q2os|^-eY=t-e6L@%&!P8V{Fv@K!A*LKBlSRQT9L`C;(Cz~nn1Jd>z$-%c;-w$0eY z&Tdf4wv}mrr-TPtMN&sc7SHb{%Ce!LIAW!>#G6)AdjPYLzvfX9S8=3*`zN^m&lAA* zMQoZYu)Ykr9%s0|nf1(z2ea@8Zg|WAR&nIje|gdqStt?L<1m4-dh%rtkKaqi46_T~ zl!ud+f@0m$m`jW$a)v`!D934&Jv{#BbMF%G@FViTK7Yh@&C8TpezD5ZhW-Zx+}m_` zm$-@rF>GpAMy1c{!}t%}vJAo$j#&w6U%VS@t}IyuH^~mQbqIxc41rmE_rRflYm=ga zKI4%Ss^>sx0#1Qzi0H#|l=PgW2DV*Wb`SW_jtZm)VoK6WG=f&(--fwXi(Da`MJmQWUkHX>aVO9fRXU;)We05`1Oz5rvDjxBB62?$MXJYJOH%)i-iltn(x(YA@-<%z^mPT1!-GQ*2w`Y<(V7yH~jA)FE9R=(&Tm- za&~LcqKO*>7h=oijw5A$aVeD8%swCeD}2#tW6DX&BdnCKOH~xl2y|xAjPG z_5EQl_rG1kdPn=fg8su_}+K!THp7r zZ>^g@lbn6_+56eQ=l9ejI5rgnKrwT7K70mO-L+ZPj8ls6};c=+KC?9OR1r)DSFdIR?NQE6K&i6 zOMbrze3PL83s}iq*lg_so81Ew!P-NTx*8oJ>&pHE8o|r_wVcQFnYz}g7v6<-C8>p+Z>vV9+F~w9R&)v)Y=c62|w00755~ z&pwSZvZ7}2$^HWOrKM#U@^J&)@{BYd!CbC~{+mEAJ{e3ic~>qhY()npE3gmwFIHBC zOdodaUcwO}x$P8nB<;aTyNj9=9>Oa*1@&ch%j*=7EvtHQgtl+1>f?yxlO6k8I1~Z4 zN)1UEPxC;D-ukgs?YsNKijOXo3V@=uda}kFOrR4s!B@-7l2r&f8D=w8*Gz?nIIT{k zL?YdLc0n)-+z|wxF26mURPK@CbPzEGI z948@+^W_2A8g*`4UMJ>LFE)YpB_VKI7m9SMI?c_!qSrTYj4p7qB1*^DA>2Tt;}7E}!$swkD+JPN(glb$ zpr(XVe{A<)z7~l!sD@n++LmEyclY1t16_Hsg#ProTUFnaxi#nL#hWw z8BPOMD~+cI4Q-c~1gWcUM^llsbc~dY_e0G_)**lQ^_qs&dR1;rLGuN#bH^t1a)9nl z1x_2R7Qs|V~ zn|a)x1Gu(jm9WJg?j0z~KtVIDSaVXXiJgX7CAhid!e34cIh*(C*2<99Ub+nSO| z5zab}Skk;%+~B1+I>|ELz!CO$#hfI-%GFt~tV8b80t`}u*L#{JD@tv}>s#YE6}UKl z?e>krq4ozFf$>4C$Mw;DEP~vFwi17&SC-BOlS$Yg1&)Uo%q@l$qjv(SG1(mJibiYQ zEXE>wc#^a5D*pQMg94JgM&zsR&=N(9_!M!M*LX;Y<%Yqyxy>a^rR}5glwxiW!sNtM z^dBe;jrm=e;lehTx24&*nOjz^PGoJf_L3XTFLO6!xZbSaMiQ~gw@d4tII5y~E3Ds5 z*(CZlnKso%^mh%WtkfE6aC+UMolM0}K)@twJi2x#*bd5?-WnoywReec|A0a8%j&|b zxQS_dsz~kLZ(-0l^e@S0I!qryC9XxEA`@V}Su(KHs${fj2`lzTX(-&ZwCM_6e_D?& z#_Pc6{Pd-prV?rLjI2&1=g}83{J=LDFGy8vQu}Z!VS(7YNJS9@IBVLN**84}u|J5# za04NBTPC)LX1M;7nUTvBM-EM52G6^4DwH{PYxv@Z&BepZFmQ0KFsck~CSQ(i;;(m{WnF!m?=F0Y8f8;gD-@00Rd?mO?*(%JUsvnd{+=IggKkeP0QKj zI*JRW4H;F-2hvq-{#i?MDR<(4Lp_SHh*1rjAy}PIl`sa^8N@#A2j2PzeW=&fZVWR4 zsQ5C|msZwBY?~M2!&q5!JCEDnyai?E@s)^oEWC~`v$XpMreN9Z8ri^LsuC)J+fAx) zyj>6vq>7sb^LNC32MqxWVrm_fkz035hEDF-mcJ=cN&{EKe};HwC_-m_`ag#&ftIpW zvSI)5G;Te={Vy%#E_8*LwL0a>SnrX1KI+JEyl-aqTM2oRgWB$#Ej-W+%LO6SUgB{58kW|+<5l}(wOs4;}3LvHHtEunH@J9-Alv%;Z7O03Z`)5 zs^KouKaV3}3a%{{R2h=^X~OYO0{)(xRrNQsYrI<$OeIIAlZtDT1q0IE`W~E6^$#-n zpZ>pSwvB6CrqDL=N1a1Fa>m&BGr_G%=ti2$L+(tnJ=}cAuv*Hhu&m(Kp^lW&`?(8Q z-Za|u_PJOO)st6;9EAOTS+-<8UOFVK&0WIYsPC}HR>l+zoq&*Gn({`FFAJt zpZ-!vjZYk4!waYLntl;fG-U)NwXt0Xd;~Byq!!khQwt+$OX_u>nw*+f3}#Ybc9ZI_ z(Hi<`sO|9q>E(!ZSGMK)T{+mc$nzr+U%k11_#Vy%1hkujiydGg6PkIHreJSr>aF}< z5Z-9gaU5vW`Q(k#p0&`xd5t2FhN8)9uLxvEL>mj-<%!lyo^^ zvyw%+dEtBnIQ{gOGjpiJGpsl2(ntHluQ>y*F!Nd>-v9+*Nr;@8;Mk zLRQkyO}9-(Lu`Y1sl&a9=xH-Lf?o21FViN5v=Sacx!rMyQM+8-Z4lr3s!FHG2211k zRUM+><2O#UHnL7qR|YSd*^1VKCYbUoe5T6FzMt`-=yZg_aBv1;8G~jHarlRgESrTt zQhK{_4nRjXU%ZSc8$~CsD+G?$Om~+$4^ZB^t<#cH?KW)3CBv?R;U>v;-Xv<|+;nzb zG@9r-7P93FiRTXvDdM(gE+zOlWgzO4lc=m@zi|rWQ@_k-29{VKY?IHp4dIpquu8C- zD*05(vK;JABGG4m_NlY~c2~aTSKUDUMmTWuR+sOXCjl>nu$)wF!s8+AH#`=c+I(JmU z-PM&P=w5V;$uR4j^beiHwgI=M4YvncP=h_#U@xW>jZ8x8iQ}l7^5JMm?=TpioKfiX zg?e`kE0&w1zPV~oxa*%GgnE#n?r-*#MtQxYftg%kq6Q8Xc=k6*vm1knbeE;b1`wK^ zQ@6eOWl1K!c-C)!9#1B2gP*L$z%;&d({lVnIzSF$X|#JH`1k?EJcwMqao$o0{LfVqV?9* zXOw>oMKnA z4UinbF9+sf@11gO>3I=&YQ+6sN68Jw&HY_!J9Xj$KLi|Y#HMWh zj-Pr1Bj3<7R9B;yvTq|u>#pf?+TdY&Pn&V9=$TG>c+?h&=NCknje|fq4$--YaLE+%!8}6 zpVCxLRmGRW4#FlTn((-b)sw*@(XL=bz;@a_J9&y`bLTa6Ex7ZFoA-GAeKJh4!sR5+ zT{HGx#z#a2zwUhO8wBLHfm&EeYHCy2b_7Iak}MDyKdWRdWh!~OG@qadT4zIw+O)ZB z^8h#+N6;wm@THi{eQY)LpeWnAzh_6E3lAx%mV65bl=jx!G}K&HXn{xf5mh#1 zj*}H8&upq`t?(vjQSU4dc)eq!CiMr@_~Ja?SqmCi7A{$1Az&-TwcLyFNB{?%eCVwF z`JH5-kQ<=AGz)-zHphwipm=pOAI@XW4YWJchJm(QnQFynn5e_dxzJ#)ulbzPQGUJ% z_Z%lsQf1l)M{GC@1h545(sWS87=i_G^O!<%uL*|n1QUql_Nzhp;I?L;=yzaKdaZn= z;m5Ax&^C-sDBpEaP=$bQG7ow}Dr0H&13sQqy|Iy9gSk88O|5&@je$LjDTb*j;B7{$ zgH^xyKOs-(+xfk)13rc_fd0#-fxhDF|TJ$e*K}8{FH-7chXrMgXo=MuU zQZFu+2t4)?cpI1;jruUhx9t;mEX^@2&q*E=Dd&1$G_U}>)Nb2^yK97&U9E=ImojeH z=gg9(JVN*|X3ZuDRY#Q8b^{v05N*T%=!%Bib84k_EQ=y-qIe5EvB=f?>Qd7Sxq z_zd9%)0xWv-9v(&QusZTtb#SrM48dw#;DHKA;=BnVj{eCOlA26Q0NJ(HAeNNw=IgI zIjDHkHaNbY9^p66N);&g67{ih8TX&GwKG`{9o~nSkZ5(p1oOI`Lw>|pYl>XD`MopDP# zoy=2QJq46Z$txC@J1b73FJ{Dh9#2}zbDhwMPYzPl8OSPSJjK^5eWU~6-Ftc{k>!^g zba3irbk^IpjPVV=nFQCA_eaK7*6q$s?H7yjN13TcUy40@+`B-w`GORuFLkrQl-hd- zY-2zgPIgoCw+Now_nhYayAn8NG2CCb+w|aN@|DZDZeLq}P@ogP|Kb*r zqUAKK?D-6hI1tr--QOY}(yx5NZ#joA&{nir>X;M5r2*ejE;xN)_+27j{jjZ*t!<{6 z^}cBMl86Ky15*tI`cduQ&z*5wse4VhA2;kFI)pA?S_^NeGsE8*7{P$6rN)`eRu8)3 zB^sSryx1%YGHMz)1YSAZ^|jV9swcdwO}Mq-@?&Z;srs(FV$mW}8>~#gkOw{YscK?T zsF2cv6_llE;IOoon8$Z|zzG7*pMy!IqS3t|MQ#=9C#Y=y@{?S$EGk?iL;7R!1?@^+^ zk85%ceFjASVN!|N?p&ZZ z=IISuN*3R|G)J^nce+*%6BcK
  • j&{@?KB|JoGu__I?5!~P2IUrzLAsec5QuBj*K zY5x^O_z3+YY-ManwCpg5zfpu+Kz_~n>RBYc2j$NZEr)X_@_Fx0gstsJ|3QcGnN(U|S)^x1Yp4BKHF>#5Rff9-2_z2jSap4(pM__7rJ zV}+gOr1o3|i^>kt@QqYQssrFPld@;N;kheGbT!F5J$D-3Z?6X08$~iNYEWb}{si&; zY5zpekA9r&X*o|NBz!8e6A|e)Av`t9ky8qYgv76xtf@t3&mv25SJZdy`dV-P*FI+G zPaZTf?pFYiT27xvO8GM~qCBh;8#Kt%Q@M_qlY|rwOD$I8IC5PoxGBJkU5;zN_=G&-y^V2<9Q& zo_;?e(F%{#X9WT6lh>=!`rTV4o3G@XG`gxknx8PvD2+xK0;Bv>t|1>o-bCUSS{nY9 z5~6K){Jsma!z<$Ik2h~n1S*knl(Oci3H{vrPnc%wPmje&MHe=!4MFWpa%4*m?-Lu#xq{u9jUp*Sd84pbx(bRKI{Q zD-N+NIH1kIte<&#KY0MPs*wDA4`321Tg>jtD+gLBi&u+gLA|UJzy+%S+W=epIBMdZ z7F4g#xvM&-r+X2@YLZWIVyvQ4N6W^iWwz5E4?Y{-Xb0xqb%x=4GSe$;lmSN zHkisO^_E`ouye_{k*ZXTicG&{iI9%n>z%{fPntXMrbG zKf=2Shmv~2%55grf@>8Kb|#t5V`T!*Ovm~1(VnSmnRrNzzLRh#!}LL?z!KuMU3DZG zfG8o|XH(&`eII2O3aTl?=fYATMm;kA{H_Wi4@%@a3L8w-xNDs2D@L~Na8nO6y3~P- zjG4Z$*KBOg$=x#H6lJ5zo@L!(Fx`)&R{A@)6T2aY@U`l}f@NgYmFm~+>30~m_V?ID zOPQ6z+Ut_lvFa%a|Jrrr0;zHtJ#`WlX$Dp2)D+%ZNU!79ulH!@mO0$92y}uhSL|uQpA2?D@0?#;~!T) zRBLP3558X}=TSQvR8#?UZ$jMq85^Xs{o=~pl;oN1F-aF$MWNM2lc*{v@}-eQu#F($ zfr#-bt2?H_9`+>$_$dYC^cRma(S6MYDTF-VRkDV7y^HY#f>l;#;J!&4P#jR~?B7Fp zn!y)i(6MN^{o^j+?wz#D2mT&SpEk_D(p%WW<{UKbh-PBv)&sgvASXF56u3d+eb*}$n!jqqWVgvZ3Qh0B^)Jwsi zkhwbP745bvM}a*RqMKcS!sW6#zMe}&wMt<9E3eu_bX#mZ(}u6Bz?47G$^C}K zM(v}r$?)LJhD_H<)Yhaigi!EWPU_--O zb?rbEh#q&!d`#8jEt(mrDse9|kofj^(%B@PKt1i&0^*a0 zVmyMb6HD8JoiMnMrO7FaUDRG_f@mwS{uwuqRG~Bf@37H5xm};tY2aU~4yG>vn*z{q z?QHADr>@edduA-(s%_E-U79CbP||c4!aM&wmshSG`?ssVk=~+x|2Cs1Xtb?M>9S4)SNGgSiA zHNH(eN#i@JO6>YDXuCnhpTDa{Ts<%QrPEf~sk1{w=1Sn77kqa84xy%@_NLF4HRIv4 zYccmnDXZVCi))^tI}eH^aCPpv{r36ul#Icg&}gn`1gQAR37iprHKkE;Wgsgm#(Cc>CGIp#Ui1^t=v z#U9}OduuW}%fONR`w+d9e-puL(Zsh|K?XOgsqx0|DZa8-SsA0Ow$JTfjJ)AP?j)|I z#vFneCIGL(h1@L?-Y2>&*yD}MAa-KN+|lLIEZ@!!+H}%>Z~-)t+@DRCIVgFVTqG1m z<<>Y~SdmpUp5#_Tci`P1(b!U<&RmYHr)(KM9N!*ydGw|{aMrhPuZjnNBhq^i>lwW+ z&sHx_g^WtHwh0adAj60mBT1E0-i`QPH*v$JxTaed*qp7hfeVW)2Dd5h*X|X6gOks< zqhWy6J)_RNBZO%bo^p(eypkdUm0c2a-FPw*OwAm&=;sM`7X8#{Ut%irMxfx=tMY`d zO{e7cxRzR1=9UM_HyocE*l>OjDB;=pH0|21DS;dIB{ zwiO;`)2lTOJ}SGFz{j-R%h@GxWjw^0IXeLQ( zQbq!+?;*5axFIFe%I(+|Qb#LJdZH?kJ+9-ee5Z#ff8TEvx=?>t%ykkRmc&;LZc1^{ zV`CLzX)SDMDA^;~GFd63%t4H)u%Id7LEfKicu+ap{8&``%lX;X-kj(lU@Bu>RQIla zztrg6=-n9oOZD({fgfjUrX}CCOBv+C7lmxIk&0VYacBo?r6td>#6r@tztAj(zO?xm zc~mxtEd59b*HzBDHz8rT=8X15OQ=X{JX8zP--0Ws&uEqmzlg1l;pyrLzs0V-VZ&=1 zN?@MveeYDMoRCL)!UtNN@x^Skm$==tZOQp(v7vM5H z`n-EV5I~Je@#PqB>VBw}N7O_4#^f|NOSc?2ps$_M^l7}i-`>RJZk0AverC0XN{Sld ze6a64TFs03#7jM#srpDj_FbMy!laxu&~9|@W`4K`K>(4fV?#P(iFR^n)GizIb+O3| zD+i^Q$eXJ73zQ?@k9cG>zY(lZTpsCVRm#LfmJ7)Yn~B8Q#1flsf09~Eh@ZHyeY(19 z+-;=A@Krw5Sj6qHQZt@>Ra6M2htH!H`-*>Ju(FH1jT=PSAD%;&qfwsj~gd^uleIRa!+)wG5lV5x>Vp1bY>3 zx%4B6x}ud^waW+@|1Kv$*{t%@mmib)0!lsa z<;}y!Ivv}1pD(RERCsiS29KBn6NX}5W^I^eBqsCSu%RQ`rsYLPq1Plf@$g3^5xu!W zyL3{ydqrLpwoK$>4UF(&Ag1qbwVu#ix`78QMF!fBuDx4T3m*33w}SmDuU6QXbGAEd zM6eY{$dTCUTy(|YBvuL6b#ot`SmujuD1GELLCK1$ualyASBkWc^m)gzsw3WX^ z2oUYM0+*m@q-FdqQj+@txEp1&GU^x1CSh~!^mgO>rH)0+>XTAoZr=UEk2@7zDb~CS zs7nV9WXOQ|0#urQbyT{V&3kI^5I(uZ>ZZ2CwO8}UQSMVEx25?e9ch^cZ@U~vdU}A* zx%SZbIiz3C6pt2a?Nw!G|Lxz#9JC6aPT{d_-3DXt1$uSTx+8QYaE1pz)+`cU9R1uA zwn;_sq)kQSc>IeSW66`^T0L5O-L%tq%i=fk=MSZTD|T}_@;vp73K5GRqr+dRZMn;x z9T(+KqI4;Qqk$!hO>K8?FP7yMnYnhGeVm&gdKY~bzHYja?AGjZtJww?qtoo6qoLoR zvz;>BK82r@+gvqtXWt*2l_yx^^}1MtS!H%A9Fh1ehNnOW$=@WpJ;6nJiveR=aEJJ{ v%V64tTjvrqCWPW@i^iY+Sfs)M+V<{|q4JS|#~s68)rigw{p+P#_K*JylG{By diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/PR2.png b/Firmware_1.26b/Documentation/How To Contribute Pictures/PR2.png deleted file mode 100644 index 8da9e576fa795312dec596e84fd18d374df52d63..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 64618 zcmd?RXH-+&w=ayMC>&+<-_X0k!crE^x%=oK^E3OC zyQZEjEIe&{Kl?hM`L--9REGAg8xMW0R%m{uqS&;Ba1{z^IRNa{SSt!|SdA2$ifo4O zWM3J4So>j;;GtD(DV?Y{_ToZAhOJSpE!XJ&Gv+6_M!(!?zhiwTqE5DR_oB}# zul6Bd25k#6Rt}N1Y3KT6mQULW;nle7e~n4{zvFsB)B*JJNJ-)X5@Dt2I(}9wTI}|U zqmtXi`3n2~1fMBC$))dqCbO81^MDxJ9e^%QnZ}c7;}V|GhcBD*$@YYi@s@pmW(6`Q z)wqnEuCVKkWj(}mfc4@htB2GIvNK`&&lDC7*F)%%#*NpP!OdzX^iPq?$4jaZtbZ|8f71Braf|F*c{rqKGP9b^_%=5UT)pBMq;1*E!tpokZrRb3U9A!wQ$Np^n}J{ zCa*#jZa`(JCMtZuk@fysP<;NQIE~LWuDEK8!*i$`OL+j=lJy&*2MgycKD!xF>&QN| z6=DZ~e*d_XnQgiR_lwLlZ!8K}?nj)rCH&?lX=c4c+@Q?}C@x>VXz!EU$C;LAdU!0d z6~&gvSYyl~xI@vsxm7wXW;YR1G^{bW_n=`jm@z)0YwbU554cp)L{7Hw>{Zy<+h792 zV?L=J!C0fG?aoR9uC_E56Birnb@K~T*L2@jWQ!K48i`ULTc@8Qe=ZY`t&nWyPaPJY zPV)7xEV7yV{Gl>iCQ2%O_-2v47OsEj^J+>3r5sK?4%|z$3rLen)^+=zSIjTimn`Nh9K^&mAL#wa8R9K zUQ2Ovz}Bjln5c%w?8}`(;^>a~i|Wj$tDj%-&xzXCM&Z4YaPrtQzD?1j6OjPwN+vI; zs*pF0uo|B4#t)W9y3zphielAv!C2S+&R)h(URl^}8_J+hLRXi1-;>)V%@lk-55MOO zELES_5jI3Grdd&2!kam)JEBDAVf!*qdYv44nkWGKr6$)!2TQ2b)&gqw*P>j_0C`Tm z26YqQ#7S7jzuRb}k#QS8!ew%wImE060INd6=H1iO1H4sQq=l0u$+rb@{gQG4mi)R= zqL=LLgS+p-{e4z$C0!e8MGd!=q+}N`J_+a@c0oP{PFlm(H4$gx5*2b`H@OX4HsVXZ zO!`cxMPd3?q>t8y{w6fKxgXLQdv3lHYsfe5NUCBLDo$7Pll{wi^`Br?YwT7*{hB2V zKA&VCo0Dnj&!pHTLuDWn^`PL~6oLUyQgBWvG_R39p-~q!dq(`~sihWb4P&@bKvq5) z%?45_k1mP_gZCQ64eBeZ+yI{$4bMv|SyBa?8?=2sdou89GC-;KK!f&J zOk@eAe*cPKNe6c-iGBEvs4yX36uSI|9mHu> z_6C`EU#lolKYZDEw~FRfUma2b7HY-s_gjRD#X|aIi_H@?q|rW~kXvp6I^N>fPKJ@! z`g;YwvK3H9Xd=lqcL`hL4AQkHgCqM~ChM_kRVd=~j|2MX60uRHFMIIY$e;T2aex#I z;ftAJ5t&b_%tL@FMU~|#4j^&WA{>4NQ`L&1Z`5g+`fvaIZvAr>wPt{Qv)NBy=?}(e z;v4HDm{KgR=2+9s#~&zBX%SUKVtj%m_7$X!a8qNST(yiAIIHN@)>Eri<2GhpWo;?p z(i{5r_S(JP193}=cOWU{6ZN(2CG1ylsiwt`%nT~h+#Jx5_BOYMl>Ylk>(vTf{m)DG zP0D&r$8UnFFB{Xm}t2iwuh;{^x zMH?RqVQ$x;2oEp`{MmX)oBOwy@fY7h(}l7^r;w+Pk4 zfxL}P^Z*66V7NF-6{pi$luj)nCgc{*gdF!)Vcf1p_E9-uH$VOM=!4QD%8Obs?0w+u2SFXsJIKn z_}}T?#(dqtC~A*iOH(p~eg*Bgb|$CMvm&VA_D=NRLb*Xy^#v{ra1|U@vd7=Kc>{kv z44q^C7+38&-x0tga*dBGHLzcesLLOVYN1Z91ruvENJBcb64Ana&)3EtqCk{b`&h7;OX~aegV{KzYN9N#y5!i1BqD(Si$a8~a8dl1`1%kNu zSL~Zom34PfbIDaUs7&U&D%i&sAQcSUy0otU4n3C#v7PTelofd$g9M2Lw`bZ{i#X@f z?Iu^N6}!A@l*QJE0<2;Wo3?(K4H~>x!soTxhOd1p(T1xEi6xcu(w4 z43}}+^~DZ;=IsRRw)Ji}ZNwvBTVF?P=h6pMLBd4&3Vwjq9IE4)7_SDUDiCf41heyT z+)yoQj=gTcL8(;wCEV+lPeL#$ZuQ#peQB43mE7c;e}3e&OV!8t-E6(IDNeoR6f^mH zxXAPg3d5E~&$&0z6i}nKHQ_n$+>x1aVRmnEnjWsybDWv0p{J*VGhZOAKsg`4&!9+-Co_0iDiqDh(()T*Eqv$fGJ zqjX~_>mcW>Qp--{E(y$l&5IUMJia4HC3K*~!zMfmEeqj#<@QBolxMEKtkPd?(fzyU z#;i7x6qqKq7sBCAz~uwKO-yNXpG0r8{9PbPZtdXjJ`--LdLz>o>O6vcB2zqiHmv^9gd#9H`}B=P3=2c|8=w6!nH$M1?uSYuCqi5dYb z)@0&&JED3o%f08ZD|KqNS__0}5Q849*pX@nX4gdNB*ue6vx~9?y6>>eQ)wPrU`O|-hKJbc)ChRC4ukAuThpBbpGf+r%wMF zkIN3AU;Z7(&Y9f4^=A~GZ@u_u+Udu)*+F3+Al(U_7z2P*G=P5X&!xvBD8b=WWl!7b zW_W9=^EI7Pl`q96WgorT&uB#*{7CL<+{U2-ZGEg+H*J@E-_J0!K3Fcfp=ct2N+aOpcVhUP0P0R435&{G~6pi4n;hC*hxKg!`S;sKTRsFmrd*R&r`tF+Y zd!_!^9`G0YAoV-dB6vBxz37Pe@m-41hD=Gn|8lwS_^N%&ImSkmy{(Vhi424E+U%<> z;R#gUe)2g@DHCt4aFTp>El=7Rt1w3-SjHes$F;^S1=nonS2MZx=AfOfve_YY$eCQKJL9Pctc`7GWU*%>`j?cU8H z{b8t)R~P(r1l^Y=-Qn_E;f@0C)Z9Z1*x z!0;eCMzuMWD;`oefjz0r6Kyp&c%@3myV(cK{6I&6x zZF~pNxmHs_C6z6d8&|mG_6^T2de@7;%YZe?dkj6|D|EW@sBJ%SXZ2(0Wp3edj=OBq zCfsb-?<3y1XpIs$H=`}U_x6vwFvcZ4C8)0ahm73gYLUwZ*CL895K@gPo!=@;$foM^ z;glk7iH55tq$sV5=n4P!4x91Nx}_tX?!^mL^H^cLO~6yejXevrW~pPA{&UIB#aHnQ z7ay{NYFww&n{|L~n52sIL>iU%OKZp>j30Sr>58_Rh1Ya1RwW7byuY#egag#p z0k(8pZv1M%CSwvg%rCl?IitdJOR@&u!=qc8EQzsuc0~tuHhODVbj|A>gGJstLANHTfryWKHcYmbFD5L^X76WO;(F>*-cQ3S$Vx16tMt}(3zJiGmwRx z!))4J^D!z`s;^Uh)O3UFrm+y6$O~W8ECav0Oq4|2(0D76qyKZMFE828r4&URbJRCX z=6no$n734sfR*Q+jG9%#)t1$u11m+IUObl`tvDqYEt&Y zki^JkyYY`lk48u1atGb$HDnIuI092qfD8(MvhnU6`L2zn{!^@EB$Z@H&=m9=lz>RXws zP}M7Vd>RR0&)B6YO1Sp;r%lxwwa;!f04bc+7@4;QGSNSw;s?3b;g{2#*6OAs`_|n4 z)|0Un55L`|_0ksCNZJW#ctd{$9QBy0Y=ET@8Gw!-h2l(baAUP$O^8$huuL3;Xfn-&iHX#0YCjY%6jS!Nr3jrmjj`{EUBcLR6Fo zWanTtC=A7Cf;d1h!8{lK@ttQ5e8OiXLbOfCU{p+6{VfdgM20o6?0dGVG=wDt=p(Er zn!MT(*kr!S-vYgCZpBx4eBv-wsaGPxYyWNj=k=NIxi#WigC#+evbsNaUUUw=efgjj zCE!GXd0c_0K69L&?OYGE6I6N=xqK`v?_PPjZqo#bLhP6g4y&YX&QEba5F(^mN(ik5 z9vjiEAgqODIS-#jRzNyhuiy8@6YPtSY=D+ zk*1U`gE1!5R_eQ})_ymgzxHJl*5FcYNgx-#qTDw-2W^-k_d_+$9OiJ11N4C<%z9I6 z-Fml5c-pD*81kxyKJsG3A;Rt|y)#`rtNtjd^L_f5_ZHqJbdvn?OC{_UR%O{g96uZ1 zB%`9gVqaq*)Z^a-Pm)gA6v(se8XQf`wOZY9+_6fzHB&*rI<&Z?kvgAldseUb3i{w) zbOIa~O6NA26ioYfj3>0P&3jbIUY+VKUU?O2c!W(ILZQ>0}UEM8TFXKcIb+Nd# zfBM%nl$}m|uvRcqf~q%kv!Q#*uk>Y%e7L1OlseY+3Ifg)+{h7^2t}UPW8)0Q_OxZL zs^tU&8SL2WN%t}?>o}IKv{(9Y#Xxu*UP6*3Rvo@`xzGDkNTjP5Kxy($q8BZpR!qXSB6r!jYI4WjEKheQ ziQ??1SolgqYlgH`>FX_ZX^4DJF{9HJ-M}kF_oj3pM~b;WQqNWBBgQOR*1HZDU3zG* zV`rA3@oZy4BX4^lz6(ZnUw#icHl*&!b!WS6-G9Zuf?B1fZ^?;6`Hi_XdB7Djmo$`W zmk0W*#ReA~rV`+|N*nLMpVxSb8+Pbj1Ozjlc~C29GtnQe%Ex#_FO@qO=lnYh~Nhyc0b=d3+UgmfljsKi+DJnRDhr}>eYk~0E@PA`8< z`!*=e=zsY!wH>DU{Om1x73zn#N1~yZf3O`m_$_RU;MDzX$QinX#)4Fo^CW4h?UH8N{j!fa{E1|+%=wnaZehPeLO=tS_#uB zhv|(hi74}DxE2a{v^^P=0xz+0LqAXbM`sQ3IL)~M! z6I-??hRinRW8(b0R9Rj3?-|Iu32&UM1knR|7u&C*pBK+enD8we*7H3J7~_45C5-+c z`nj=6$BLw_s*!~*3??^atBj`|%@Vru3Rso$5vxD)S<$6Jyrg`5t0*C91ZEh5HQY{k z!#>&gL`wY2u|$k_shJAXX86vd?G^ z{t07Qf4oY+bXZ>YyOt~?Ie*1Ab@=8G_VeT4OJ->GCG5@ho4ypC-F@vuZhdBtEUC zOBIAZfY!bn!mx<@w^Pky;ni1t+qa1N)t5L!xxMQ?c>9yC5GB^ShL+;@C--=V&38w47qyijGDL@Uhacso ze$yb01B_y7#WFKGGP)NOuT0sm%EnKXC67s}Or}jc3m744(#lDs8p#H_VZ#E|oHY%= zX9XwQ1kR#9enBa?Gw8OTjS^$8sS zVAi?vCxefPetX6AxEux}X-?R!cggQ@s|2^ARNj8aUoXaS>yacr!lgcB-45@$rrKn> zZDu=WO=_76C}VHDiLZ3}^o)sKN-lQ4cpJGh^FfO5$GM{iVeR?4L^RFnDfL#Ru1Ylj zt|Q;O3ztHS!z|K>u&b?EmeJf=dbHO!`+^BxHQJ=%6w7FQJm6NVQxM?JJ3p^fjF=wz zRSTh7M2VT7*9m`{h;(5kK1c1G%KIXto3JC5eqL`uiCD=2I-|QdmbKg2r&gDtB>t{` zE+=k+bjuEDU38)lujg~^_D{EVh3khWdh)v4GoP|qO1w)|t2^TLj;}2#;rIhSzH7vJ zR4%FOpnB$qGhmQiT~_I-0_S2isPIs&+m83E3p@_xIMHMofPT$6qr7kQ&SBN5pqio| zeqUW*l4Ef6F`8rN>PWk{^RZ-CWJQFW5r&q6laP`GGrW>)gQ(66^!iU>w?{1-C3w~s6dNE4UTf$|&ITr2WQvv1`(oaiA(V{jSEE|AJNEb7)dc=7 zb{|k9VKm`ntIt7)&?xaIq4R==4_$m%)l8=>C-u#tF%*6j3KD|-9>(?p`>~_Xh_A4^ z`{@C+=xIJf^)Dv$ zl#P;+F>gxo!cR2?#FahP!1b7*yXLHvb8 z+4>TyMs#b8Nfkc8h?It676|vIb5KawM73)Z zQ6C8Y1$pgF+Z+Co-oe=VdrUCypTfN;x;L(u+$c>>WCCmd3jmF}i81J2LolfCb^c6e z@lw)?5{b!6_rLfK#%<3II%G=AsZyHqJ+qYX>w(PQlilCj!XQ(PezNv`sn){^spm{Y z_b1AL-O??X@ZE3J@yL+|U~lQ(!2p#^;GDN;GYtm*ff;Xodi_t~A29LsY0z8iV}I`| z%ldEVByGSGgXI5vqi;b>?D{V=!{ReD zhDfQNee6*_|AF&JirTkVFb`B&<&-va%=_GsEx(=_r;TUc~gGwl$he~MNf(BGV~hfw>$k_=5>HfPdrgHh2d z;5}x1dM5YZI6*ex)|mKN`TF17z;n4;v~~U3&jbQ^ayW6mCq+iizR7TGhx7QsZZx{7 z9#O_{0`Nv^{rjA&|M46z6%%Y;;c)Tv8+Mb;iYRn9zsVsUF`m$qz#-Y25Z)K6J_N<+031dH(vOH!aD0(=P}XnJWR62 z!8&-Th0=zGsaW#xxdiyv!idQY`Q%WPkUv_ec-#<6>2mh8oynDIg+$u5M8+P88c_$* z9Y@j(BIAy@LswO*e;{3u@z#)0dhT&cgo43 z9)+1mNl3L6E5vh~oZmFr`azSWi1#P9P;kWALWGDUuk`3~16EqG>cwEEppsw3$H??$=HL}GkV5E z-bt1VQ)0>d)Dbgp6NX(RE2q-t)l+SJY}v!|vz)q@%AYXEMQ=OYPDt4=?aXu=cTal8 z5yR}2R=^64B|iul$J+*@p$VKXvg|BYcVpH#hwWOOluU=*Q2Ne_>Wgo78RgizBA>o# z#k*Jp-vGj*lKKH3RWUvLMVQedjgiTwZCG?>s361&+87Mx;aWq-ADd-XF$&jcxE9qB zH3;RE0bD}x(ngbWi5&BMsp1K2ZK!+ptxj&&lx?li<~=5iJ>>8CBMe2({Un;lOix<H6X1D?&l=pvmZ$iZ8Y5*jGhfloYQ()yP*eL$bl))5k$uBM1zw~}@pdmo zK`6_D9GcWFxU1%1vpk!d^knH7@jzSFij7vM@(H6(x&hL{rFl)3s%AE?oQJGLnY;Nx zRjc~zAZwcxJF||g=9LpG;QI)bW$4;lQ*Cja#?0{@v`jq>{YYu^98SvxQ6O80s9*~Q z)|5D&Ph2sm(W{_#FY|WFMoL=Ez}^$7`_kCyLKsQu&3OZ=6QExl?m0IvlP(GHyDB(E z4&MCD65D#n($d!y3a3nHMhYJ%kGxkERNr38+!tuNZ zG(+r4Z^<_Dd$vHMMJ3%WBZ+ecA+D5*=o> z&(NzPpEy5VBal>ge-pZ$C47fi=McDTjh!&OmiaoME!NUo>!F>-iNO+9%A>HgF0EpH zq)B9l0xu}MiGbhe7mhjKijWzn_0xA+_x8}EIU>86ZDEF zM{@9>0sGxIZVMmJb=o6@UsDU6^ASaX@_2*kpa-CF_e|YIFRP4*U~SJM!vnDM5_ad zHEya2k`~8T0%Invo-Z zxd+mV8$iN0bDU(Du~_EP@<2=x9-s6b-Ls&k%=Hd?8On@s@QR*R#d?w3gI!@YRdp+* zG!D98#yJMo6@?NcFXZu8uU5K_MaO#^Wt7^n{3yjhB0)%3AIJ1VEae^fiqR3OwKVFWri zA!K)5-Rrm;;yq43^LvIB!_{9}ju_g99t&FCa#k>R`?i~^%tQ5A6?P%9199z6i)cC> zy?+y^Oji@E5^eN+*sNZqE<}h!rbDOi5s+g7uiO9^Rt_;U1Ja*dZqHo-7&78e!NPH$ zQoO9`$4rON;5;4SM~>H0U3Cr8eItk0aDCA>7nsg}vLv!$28al(vj#>&yF8xVYu%n# zxy{>dr-BB^;N5KOTAup>Y1eDq`A;cI&kh4cF%i9kJ2ANm@%+-Z7rgX zFEeB9=t174W}-YMh151smy2A8<}fJq#?+mbw<3&GZtiAMajMmoQZRpJ9~f0a{m_AN z^*z_IN?u;L*mk3d=tlHRN&~EBN7{6yNd`7Ty17LJl4eQ~3(c+7fL4_BOn;ox)bRGi zHgv4n?&`=coC%n=w>qx# zqt~x(y~28H4)LWO28CN4G_Y~%w1$81JLjIA0LqSrDplR-6>U0jDqeGR?+ zkmB(m??zRF-LbWiF(UBWM8Yo>V`P9y8vwhVPnni7rmVq<(;<-;;hzX=Zww#G% zB_d@(EKO{eQGw%SW);hhzbeh)Dg6WJ*R=JE01KEVFfH!{{Kw|zu2F%GTknCq-l;NF zt78t6&X>$t^Bribl(+zV+tl0InIR8=)iKLWRVC}ll<=(eofHmF{)OqMR3*{&#n26b zzU`jK$C{HGfR)iE`^*XY9C5Zwa=0ru68E4c58!}RGm+Y@`hKI@0c@J0zvcGR(_hKk z4scD$YgL15>RN7SaPYiRST1iZ_3O~*x+E#18f)aBQN%Dr&Xrj##Ok747rMCDc9ALo9n^_qOZ1SFbs5->Ac|Ly8p z+DP2o?o8973DbcRM*4xFAs}{8w#Jx)=2oo-AdDJF7e!C)C}XDg{K7>-v~hv3lB*-L z36jFSw4KZ3Sylh1o}Dvp{aK8bZEqEmDr)!ih@&XS|4{D&Yb-nrFR4LFvUQnp1f}H? zD?dKZ7AiH9yMboF=s)=jmp084QXXwJq2@bBy>`Ax@2p>J`aV+9xnoc?F3j(f+Luja z(+uv3%xXGyck|<$-R<4VSDZwpQ|_bqcN3+y9Rkyb=h9W=z;o&b^out1v{#wdRp#l} zRiFGUWp4n|EMWDB5b>|B)63~*v2~fwelzdPo}6)j(v4D9hz{!XUYCmcxdel*E0`WV zPn*UDT@k}uGkOe{Vf%{Ebf*dVts8=*IbwDYtT~Vrx?l@A>9stcCrIQj2)5T9T4i>7sRl7zsw2vXF#XvVBJh%I5ei)z!w%n=DSLAv+QkrG8HRObT~muq0wl>afX!=K z)Ds?O`w6Jf-j|9qF`!}0f282Yxb;Z|4;in3+{WF{QBC(GgMq;5GL+Iu^putPwrzYU zO2r_)1PjX+l4c&X0Ymo9@fDOn2H?3)zGg80lBGlFNjoeZs|VMPhEhlH{ru%CfrMmU zB-^yrR0}GdcY-$!~Ch4}okDmb9pcfU6u0ZYT_ssk45vT(uQ+}xi~e8UtB z0R9GdhwnCtl^JB??F0JCM=p%#DLjQGE=kQuI{C>mL7_18pEQmggv*O-MWK{VQ|J%3 z3MBrt!U1cvLU?IaZcRHJ2hX6GD5lqxn+t2xt0DON(BL%?CZN~KZ~vvCmii_cl9C#J z&1251Icnk@nA14Go$;7a#Q?07WXh_#%{$LJ!8NgODA6rW4rb6%3iiMrJN^^oz$`Iw zs<0Beu~Rpy`$d=Lzi7%z^nXwo_7})nw*BoBnLU2wQ-AsuKdJnNld2M}tKf(K;7n!u ze~SBaCa&Ut@v_3W|0|Eihsj^LQCJZcEu!<|#-hx4XlC`FcFUF9dr%PI?X1LKWR<0D zzi?DDdE7bvzu;Pyr;pfMFaDi!{q|wd-wsKZi#PwP36jO|NHFm4yr-}E{(`_PEDxXm z?Pz6ovz9wI=PcLyV4DPt1Sb4dq(`M9Bb`gPH$dj za+a0@eWtrj>4^J=eqo;~Iif##UNZLfKCZt^SLbZKcpWfGr4)Ho6TR>k5bjYHDyyfG zHa7PA*;uW}#X;k*o+)o#wr^%+xhyOJOZf_i)6WQl6SZfgyFJn^UYrQVCRbRrOLow18?paZA3PhA zieo&@=WV`90{dgup<;RxmES@{W#=9U7Y99T@3~kfG9=8rQS-No8QL>7@1Ez)geecu zKVI;M(#iE_1i`U0CEX;&w=^`k%gKtJYbL^Q@`pgleP9J?tmP))(6A@DZ za0Fxcp#20)N|TZgQn&7G0q&d;1S+ej8*c6TAq2Zii7rgKID$l0LWipP6H*3EDU($N^)6SSA037WZ_Rh_d6h<5uF&BR-*6l+&j7_;2xcd_P9;hfC+ma z!wsu6@_DW;*L00JUQgJnY-uo05Hm>V9cXC9Pc7}x<%6_k(K$sL{1}w0!A|(qjh?83 zAtwr}H4^ldXVmJN7SlRat=>ADS88XA{!yM#P9~i>Pd>(aN_L0Zx*$ya!?}$&_7w@g z*GuwFO7+HT&8=J#kF^J_zBzL!`p#+`H&Md=X8Olc_l}4=d=vqJ&gVb3>4@M$QXa!f zyJjoj1^mMeD!lyUW{);zHKG3&lCisdUo{WMU*tT;mGtdEW1giD2Va1^Nz+22?0iIY zSDla48-g~!n5nX9y1QI&H8tYPD~FUyS69KAJn1*w@ahPKjUIJv!86itJPCoULWSvX za(vPf)f9w94FIW^p)M1Nn0FsljD(yT8CcwX>Y^Y6=YT6TQ)C6WiPP5)o;q*svu!=Hr|8afjO{lF@~?%% zzXfCOSOPo|t6*{2_c(DvxP9v5WYLl$$1=vRXql0>=U!g$8&(Mx7B@2rKW5|}`SCpc zB*}fh-WutEU?Eqpq5wp-=+2=zo+?Y z=p{nnY6QSo_2-#!kIFu}Oj!d%o+nmR?Fj1qP_mm||Kr4>(hQ2i?TpnqFOnYtl7M?RF>b%}WV z%L5|ks$`Gaj%yJM^Mxm1c>5zEm4M<|wbBdb0(|T&5>R{4`s*A^NW-10_n=mVi zN(?NeJvyjLxG<>l6My_?09WpFRsxG^Zr4G(w1cjr3aw6(lpc?|N%Go1fT!n#CA-J8 zCz&XB*tl=6%pBq@rmHDE^tDO06jhAu} z@aMwH!a%f!f)%Gb({Cn6aFu>PLVfO0a|oTbC?`1^i98G6jc~U0j(cOVV9AUnU1wNZ zowUYB2})-qxly1eL}niT)s&Cbn?m81@bRWgI@?Iq*S4FD6u zU8MW?T%}H47dd$5F||;<(>``5;+b`ok?RUu39=4y17ibQYixkT8pk(b5EtTxkE#>! z&pTTsorMWt`~|CD>bQ7;nOjj>$ptpE{jS#k_>D`-yt%5Rmta3H^+qY8r2Fk5x3@Zg z1$ykZ*4zYjM4sE2$$W@M4EvUbw7`U%CJ3q*^e_*a-5BFnGovgUq+R>zjLdHS{SG<$ z18I-$R};-1p}ImoNrAfE9L*gbPnhqNYDLTIHq+)J%SQ@k4iKGJ5<9n3r0)$6x|RA{ z4OI&b1wHJef4B8(+r5@h3=Jzxr|Z;xlZmaD=WGRxo{zgTx}%@iA2@xXV@wNKHwUUy zOv+mh!M-F@brlZ)2y4YLucqj!zH@%_;u3vuTaPndTnEu8doOs+5=vTtVQI zeRqmDvpjDv(|%V$liYjR^i_i_m1lZ#2Gm)I?DyW`8}}scsy17=K|yrEg-!xg5dnR# zAvk*YQTT3tD!hN=`Zv|PtxmV*FMLZ~__FPw3QPB`owQa!%|wZA^!Q8+;I?Kw9OERz zxmE4HO|qiGzXix zZJ{KG{ggmKLB`_hB7pUVv%#iet{{KZMWNGbX_* z-@pBvB&J)axRt9_c!Z^%-*M}(ctdX0FjXOe7CMckwoVHYKP;DLu0YpCCeN3sJ&CmV zHoO+m^0uO1^vsAs`YAML$UrNTz%$NvU$(pZ!;zsw<@6sSb>Hw|vytx`nE|aON?atK zTLy5}rVm=#jYLR~+t=vE=Rj&&t6l9F5i#o+!tyD9854!ghJN|c23sd@1b!oN`l3<7 zsQ=r;pm=ZGXzTEjoW2Q~x*LpMOSnK(3d@)q@m(9y5YehR2)cm63&Gjy0CdhzsO&>_BHtaQkq zulVD~L-<59rq_*7Yrq_g?NdgzQSU_&1a4hNL^&jb4p$RwE z!1D~qRyWGl@M=c_9pQS7M7*wgU2-wqhLi1Gv+KrIVxttJL}$1&8{S!aPb5YQv0c6E z*LxG(e+wXQS*{Fs2ib3hkQkD07g*;+HKO;ro5K+9X zPD1B-Mul70mO%NJ;aV0U0>#`g}VO zs+Q`gC@-hv|7`t;o#;}f-Hno(DGB1Zu+!un)s~i`R?@uN-5G-8fmFTy2EzX&e^9wF z!p+U9)G#K@UVZF{(^BQ%{Wf;z?Xv!{A@ny#`GOkClzT2NB zTT$e#-lt~QFtfhCyV_fsHl4OQf-y(pcw=4D(<-B-1y&A)Puk>mHb-=s#p8@M#_Go@ zqom@CD*BD&9s<#>+kZI%H{#myq@}EO&Td>Lq{cEx)o&rKHmH-HlAx>8P42$<|55jz zVNGUV`>2j>7zM^*6s2V>$RJHYIwUG8DosUt2}&;^^qQimpo4&d(jfv0N()jFdPEe2 zPz?|ugou;?A+!)62}#bw%+Gnx`+hvvdH>fr&*wbZ``Kmfwf4I2d)bgZD8EYlxuGJA zi07FUh|7m652BHN`VGWd%5UR>g|LV7w{AOk6?d)3k+Gp5?;+F(Y&~uN_w4pcb|7Bi zn68)xzjH0zA#R3$f!I6Lfs0m8&oh;dVz3hFGkj%=^-43FelycACA?G{f;qWcKscD> z`+~8dgzxqfdbv;(j~c%1uv^)9y%8$U$o z-W{7T{e8z-r&E>?P-i=4BRDgkXBl&y=NsTA?pM-d$v#^+DM|dCD8wj zDW|6!Cb&X8R{zAiG5-VB_;7T}^bnDn_?9rM>JHtKV9T^d8NJsTnA2@=p4YM?CDm=9+Wrw5-RNn(lS5 z=W8qZD?3AY(#(U{-X)0kAK%b;G;Gx0Vt^1b zK7%|-ko5=ksZ-bOYii%~A4Tw5Rn(GjDHO<9C~j8#;0RZdvno~X(;5+VQ|L8h9)>Q0 z$=IePmFruE!wFLi%S*W2zZ|q#x|T_PPAr}R)Ojx)G%HB#UFi>c#Mjo9Ys9H8NZ!o& zOg_2@US~+j@^Gps4ywt}beO(78A-x_zK|s%Mctt$#*n(>`J3wKvYO}~*bSRA1nH@a z(ApN)m1>;>e%2s0)3qm^zNYbvWU*+*S6Cz8Ijt;_S|r7QQ&?*lA^J76KIKM@pvPH9+Kd9eF3TD%Rj_ExbRXkO(=z`=k zSJt0=eZ9onWcSyP-r+k&*1h_jTX6B-2It zRPNiPZE>sIiu9R>#|r(BHK-B6pdV(fK$HaTYs`t^7j%GcZq?KA^2djlesY`ftwC48 z#v9R_=dxy=j|e`X6dPa%A0bb^vnZ!tU&}dw`ZDwCeu=c4l=_5=&W^4S|Kf8l@^}c-dV_s(ym`c!n498`QIFzFkkMcf8Fb*sh_~it{Qq0MfjWDHR z5P&I8y8r~TF;;n5ib-P$N#oDbi}DPbq?N+$U1bHLiDI7g1eJPSGk+X4QbXHaG?P|Q zV+)TWy&=wuCJPdZ=D7Re3o+Wh_2pBilmc1@=L^fcoH$HhoY_RBx_kB8ERM`+NEO1M z$H}5OSFUVS`69(&(I|octR2>%JfT+$ONN7-P6hk9&D)LTCb)l(9K&5N+Jn<|X#aq7 zZJMi~uF`CudcO%&4N;qc^_ZzWfOfoR)e?NMHs|h7q!>24=lLFFV?d*E zp|U*Sk@jj#@X3C>kL?!=x?$p+ZGiM0V&3}67zljw3Q1?~$csO3*=#E8QKF8qg zMe8p#%5xv^bWe>fo|PXxLlz5b$iiC&NH>KocMLVXf>i%maKDOLZ#wF~hdEIVV+kfm zrN|ROFfWFjZMlokz8b0S{w8#d_!lE9qv#T?hM#g?~nC9IRLL4l05i-k)C}0jQL<9~Eq;BCXLmcg|l+@4R+=px)`WqFD z|FdU4_gKDPdb68XM{(x3Px6`7Hib`@>!o1XnDO+(2j5x*Lats-dqVWDS3|~7KoX0_ z*QmkB;||zD;=Epy;P*5-E;10^{mf3)q|oWam>!2DHML>!R;XkjOTh5KYiKr%x^8~s4nDd zS3obqQorFZ;}SpfY|}JYFK6|Ss$cL<{U%YOhn|oq;fq-3oL9F=TiB{wK4Y0?J@w#w z+xm2o=FbDVM?!p#3UG?`h*y49WqF)K@SHuoFEB>F%OLo@)Bym2%m$qQ*`KyA(ht(! zKK$udUgG_zu(Hjo<)k*}U})j8_96hHK4>^6(n* z_$!fwQ}Y*>uTHQUe?OmEM$!oVGWNKgdJogE2VO-l+$6@ht%K{-=+ z2rF^0E6CholYNdd{MLr#Zp0Y))&d>(-AByz-iT(>YvNjH@D9}b&{aSqqjt%*dtDxG z_gNWJ9lSOIO@bAC+uTvo_~FXgN&8&SRoF-=b75-{=SJ@(lW1ukI!xF5Om(EHzF|Wn zE71yX)>Qcy{zPVPq-WuXWCvo@V?sR-HQ0cP_z#9rj55-IzJ}^zmba4;EOR7Pxo$O|J+C|d zw08{>-u!`65D>k^e^Kpjk8`jFI$LyfJ?+UdPQygzLtUO@O?atCYs*keF`?Y6UR06) z;j07sW`wPbRQ+aX_uj-pKkdeaVA}gk>J_xzXIkPF>EU~p^pUADni}~#z^5pvg-Nkh ze6nigoRRzIB|*f?^j`thk`^E>^6IB`kHWn0g30kejwDNm8%Li=R$&Nc+fMxY^KA8) z=sQ<`q{z(7rygz9)B3mZ>4+x2bm3t}H}&Vw6vvQB->d#Z3)m)l=j}1rF0Y>k0(oShR8YCz!A6vDWrU@iu4F?F)FT9Q5pe*&2YX?WxABW(TNa6*0>Cg`w491ON zN!Zbm^}aB_Q9R6H_vq-tuA(tN0@2@Qt2zuNm*y9V6LfRoE`(X!VOb-yUPXU9XW^F@ z`$+X31U_PYpMJ z`0M3k@__k1FZcI*K=>3}9{pDV@#1dQLo56~qYep2!{4S_moEr!#-K*zW`y#FYr^IU zAh8I%^kO>$w-*#MD3Be{1UeH8B~z)0D8q=Vkg~C;p*-+`S*QRJzf( zBXoO{?&d-sBKL_ApFpx-q%5KD0my~zXU}|7)wq#F`9BH_NkS32)MT1j_x*>d(v zZ+6Zf0M1&GwUPsQ!khmPl#buEZA#nwRs#rWqP;&Nyn zNQ9mj`4`4e0w@gq)1800BZDVxAJuQ?5PtfBYWU>yTj@Xj+4+M?a#vHtI&X11pa$~S z|4?84W|xI;pE-TR7Qp&b+(#Ug+&e1qzrK%&8k=2_&?~>4SeAz$1WS3%?Rv~4)`dmr z56}ZI$wd74uU9q?teS2hJzG!dau)+RtsNWPI(%N-lv?Wn4MzinvY!9i=7>z~#N_aN z;vE>8DsB{LX%2EppXfONGF&hB8?M#WBl~MiI_dVzLrQr7#cH8@)QdVcHJ{2K*S<7(jM0p=Xcs_E({5N4ilZ?nmXaC-M$h$IpK{(|W*0dd5+| zF%IA~F_eBx;(?F~?pI${%p}E1?G{=XmooGHC1GnCE)>N2uLI38mTrtaBkkKH(s~3= z)ow@IN6rYOM}?1V#s3{#KuA>Z@l6mv0S`#+>YEu29z0>}-WGa2+GsU;>8I2?u}4)Q zGQTi^KlA;+eM7BX#b^in%veq&VZ>W_9#mbarZP0!eIATHB2h_1Hy(#SaJWhOzQH4EpL z76@s&*38aX%DhoGxV0F7o^N2T+}tJw5fuwC&#B{UWgXR6!{(9z&c}%|i!bDScX&E9 zNTA*tZS&;>WXqTX_q@b5WSer}w21SmatUqloV!DzotG`$vh;;pn9D4_>3BdVg*7A* zM704c76Gc3h+EBCfp28GO5yPa0pl4#)RLt_3N7G;K_&aOjHAAZ93m=5rqo_2B^r0J z;dJ}ZSG;u_5)u5hU8yu{BB(VFIbdo?b2MBpg5|(V)^<8!*6+VjvQEt;%vYoe`Jlx8 z>+i#9`o}CFyleztIxU0c;l;_nqtZK|Ki}#;lN2XOOzPI1stTgtf^%0s2R+a&;+xJ$ zszMF6+RXYZB@K@`nDo#>HX|^NK^ypKEToXlsoi2*C4K39(6JW2LEPdQf2Pxt_yvv| zT{96|E3TC=ra|P?shqO3d9#kZ4aOmUm(LxogW@&ia@4lR-;r zpl5L)WEVoLo75#3AU}*l^Y(BUmIM`xwK|d(aTgtVOF%&<0m3#JxBQ>9_JDfDO&Lkj zMIGAtS^Ojf(>bHYBW=N%V7s_=1;LWVGE8-uPc_`vG?M7*N?ymF4@bZYi(NB9YgyLO0k$bqsv8)+V|kEgU+=0 z4D72`dsv7sNkub<16#njRc4L)OtG&!lbcZIUA6#insi}f3xb&ni}uem!j@l3PgM)$ za(r`wtqx7P4C*Jb$tt9&c6{$kc2u*2u+lMnXm0h1NFXvC!ZOrlmSQ@TknL_83`o2H z6WDA};hdInoTjrBy*hc8uGND#mZEo2ky+DE&fe73R?!k3d08GG3{#{SlJ8m-2%@Gr z>f8>LcyPR0y&Pijdc78U*%`G_4Qi z(0rB~!ui^oB~2n59LER;Hr&=OC%Dv@M$QF^+)ISM|7eX4J1&TISK4n*}U zB8iv2e5s$`d#xghGuWRXEXtP_?&=89wl!3@K?SsB^yALqZW1B29x$n^jajAbxYolY zt%QmKAsb5zD9PemyK`E6UWSG*EvrVJ)N?kk^A3#b^o7?hh(`8Dmm!UaT9#rjTU4j&}2U0=|DmZ;=_x>+%b;ON-$J7?iUg`V0A&boJtKq+<*1E(uV z9OoIw6linAFd+S#?Y+2my>*eJ`Spb?+mlI2$#3Srq>ZxZ_L1LA`i0Wj%kP#Eb%KMO zWYIg!TCWCZSWnH0Fpi7ohl2b!9Ekyg6Pvb7a%k_40|dKOgT%*83O{Vv8o+4>Om(v) zv~iw%VUjR05hoXEiVEX7tqx0AWMH2rHh+(<^qcn4K(16C3hEX|ojjqsndzv<{Uy@9 zM>=R>bIF}N&JUtfH#+u6Ivw=2bt?r5w*O0)~-r=rLZ|5~V(o`>f5MgR<$$yiI%E zU(19a;$JGdPnuy{Q<$KpPJU9^JVl_{X-TSl`KqiJZ6Mk`Lv86 zF%Z&brU&|`_ETYo?kNq1_+o+CI9ShTrgwwW9jMErt#T1#8&b^3Dv>9vypwk0Yu#94 z5}Xv8*g1e51N)3O>p8B+Hl_eO3%uM@*j*@Yz+W(}o2h4LAkPZIU!}BT&N0*$g0Ib7#fR=~)uyU@G_$p=fn3>}>&nWoR@ zCWRm!oC!8pMk597f7Y==sfo$-tm@|H?OGY&GKcHS`4pq9<~Tj3U2lOYSWm`w8F5k_h>n*C~vJ7L@%nq*F?jm)w` z_lG8@Vp|DZc55NR@CvJ)cUTv(P`fqX66d}uVM$`eP@8LMkmFUT651tQC$PG@o_W|M zA>kbPsAngg03ohP=b)*UG+!C*{nK^CeRI ziv*))Y!f7HUdNq@$eEl(->72yHVF$Nb2#y_G{@?bc;UhKa{nGJ@O>pKk4na$Hb_=|O?S|_8w`;$f2@`)tFV;f__dop@l zfBW&7GVb_5mU}l>)MMs=?qkx?n-EwiPP&RVS|$;)#IkK)ZDvE4cFi*IUf z>T1~{XZzbtAG0acCqZQv zm^Srkc?y3nYo@cjl{Yn=)%hl-5qYA?_-_g^MMelttL z{Kmp-hqM-HN1>w6NsB!Svr1H9QlhHLwCAJzRFJ+eIdS^|0zuZCS^wGKbM-sPXvbP` zeaFxTzsXcs(4Zzc16^7%J!e)QyDQ}syTKDA`fGcAtH%qWBm$cUDG|#YyYpm>FesQ^L}NXGX)dGLZ(Z>+wM>CPbV5MOHtY zn9JX1CXARHoE?kii+b4hhSTci?d=Y;<)fR2Ry9Ac$=H@eaCb4?PxO*zZ9l3il43q0 zJ$Tv3t^q7+T_YoUJ2X=IX9oA&jV9lZNDr_Ip`w?MdjFKfmzAY4@>x#}7kRndFhtK; z3o^we5L4<@C!q5S=^_MF8 z_E2~8F{wnJ<2zPD*-`^<`pt?bQPJ}`WI;Ise@yD;4iB9AT&D zbdUVVI$3M8!arPHMu`40w*+`Cx=WetxwW<+dayR-k?`fmjYpiYrIcE`Qx=?@ zt=ZU>{x#Xkjc<22>{fyq)?{t75A716s&|Tgq>d%I(IH=O#h85D#ErO~GZUo%4hN-B zmYUnQj4Hq#Wz$=y^>S;nciq&zOulB{y!UOCBO`D@Zb`3n5`9<}9pxxg7qzAl{V;PI zo|lAJH1Dm9Er?m5VXloWPOoFUU29scS_6rN2%6cx?!<|Rx=8$GNrMC1b<*TWYu1A8VdU-JUml(BwVz$9Z@gdnuLK zFm*pp?)ef@7&jv#CQFl~n)+^XYD}(N)}Be}7L6Z2>Gh{uZemb1pg2lm&vF5U&^w~> zW6#2%A*3KuS$O80){DM-ovK*&Aa~Ympi~m7#lVsNdJ2z)r$#QxzD#S&QN+|TR3x~F z;jv+@7%L6odYyXU0=^*YYgI~7R7jmfrEgnk|8o1Z(qz$>M$tfrku2vXJKE}{>O>&= ziBArdiyzVq_N(67yxdO*xcjSavi(tjtL0JM)7vRaG*4fiXNi};bdAoJ&N_Lcn%y&7 zY7!@DrsDuM@F-kRpRl^s?pdy$myYUD!OBIOENE z%V|sNd1;XadU36Do$Q+Wq^O~gWJvvH4vCxb_L%j+cD{EP_Mhjy7i&NYuZHa6cQRO0 zMcTAeG^yY>y3Qeu!Np(c%mmyVx!x}Y zd3Wfj(Dg#2-}wDuktQb9kkqgN3XPH_OC(T%v_E5o+bh37LnwQORAgK zV+P^GoAk6%t5!};i?XbfHLB8F;k}{gEfsuLAKI8U9#VH#@^edZE`7)>SuK|f%cwNr znaFsx@sBM!M4=qdvc>8UQ+2DHDMkG%$B@K&dbY-NE8S6kqs!h`aLk0*lbv*KnH+qz ze!NEgY@~hF0Ov}YF78@xvz}gDZg5rCm_P9eV=33d`Ky9844UM(MRU6f|Ue_hA<+pb)OjMtnlh!X)llNX^5$JpFNv5%EHB#;$$|4PwQFpSBcIi z>O6Qxh{eI8^2s?skIrTKT-{vf{%IB+aSL3^`>2dpo2P@cEwqxN{hpWB@M(tD1$Tn^ z$qR(o(cUH&^8N#)objje=Ra<)^bVGy7!8m!+RIT!*j8?2jAVJ{#>i#XyRhc4Y=YOj z@Chl%v0tSU;cu7B;BU#WVZU5krhro0$YJV-oP)4QX^rV1K!|)HcSR#Zml3-;SL~I0XajjH z6XK&EOrnn|>oI+YT>aNIpZO0!a1plf)m81N=~QvrLK+0OCGFcZLSWJ*OlfG?c$T_W zWK^H1V`!wPCC#?Nwp`c|AyGL`vQ4=6%8?ojqqC>mz^gn&7*uY!LWe?U+8AlH_-rNZ z_82a+IAhyQ)^12zC1r^+1j`#YmBc~1r^vJj2k90c4!BPzPBX?ze@w?y&YW(uaiujO zcqw{j%d@vBN)X(ewvK@DZ2cMqZMwYkQl&nGN|L7A*E3$NGq4WfKEI05h_BY|-oKVI zR*1dglnM`9yAYyx z2i9?@6JfnIQOa|n51b*xfq=gn!bKPmD0FshP;W1{{=f!EaxMJ^lVb;^-yseu)L~_L zuEDamLvp6lgj+sFu63i)cEuqhqu@dcIZ35r3a zH~m6SNLY>mEKxVQR1Z*00mWLCB}tcRVd3irxtMXkbeBW#oBwsM0VNer&*o=f+39&e z#$)%(@dZG)sGhiC+;nwtndKD%uo-5Rr3Bq4Ql=@iCi~RJ8hh?K=*2z|x2*2waJ73} z-G#m)OLp5ujQQXlp4?R@lyKt24AoUCao*;taYFOQ#-Gl^x%j2A6KYLhH9VOAOYZpV zE`-2cqtT^9oij7->gF863jSkMU_)$1zkoMYhe2r7 z9SrN#m+D4)%cRSN`d^vs_3Zp&Jd}RVhkhJ+=);IQ@LhpOYm4Mw;4%!cVgk{!5R=U* zvgk@oevYYcAL~kAcMOO_j5cb+lDnK5EW-SqmDCK+^&8xLS?=pxU>FV#w%T(0%RlQK z?Pf-F7RqYPv2Hc*a-|0uJkl7IXu36MQpt(fs$P@?ji!5Jx>E>q%Gk-tRr)FIkSxId z1#hrtt8y0o@nQ=1pLjzl<8xcarpwEpSv}eoGi^*{`O__~XE#|Q6lEzG)Nn7tQTA&S z6}rN%5Iu$@G9LDV1Z}@ZGH#qh_+gY0%X15Yer|}D4x$Pw82%c*G-qRm$psS;$lE;J zxED4eI;RUU;m(=s#$VAE^4teA*&dB3voR-B|JOq^HdONE_89QNH_*u;>{~hTdaj79 zmfwg^uFqf=JEuP|!;U};^L`6llW6f~S7zHNOjfkJ2XG8FpPQDYDvD=;31_6hr+ep8 zhU*E5^C97wORXLl)A+O`ZtdO@ad;xQ0f<4!PbR|rzr;5i_H~{{x=`E9JZL`9C$;_NTiAdagbFd*p;e^Z-QeL0qjgnN6>4JOLIaWAh=I&uGX$s{YKAno#7YQbWBR;2QTzA&CK=ZG$duNJFxmV zL7jHmL=*j_&K?{8#Lff(ZuWjUyq%f?mkPG zc@T!$*cu(~apTUkPfptQ#_9PbzH8%}A-{4aT{Wod8~Ky#jD8&ScNnkQivr`!3k+WQI4MVG> z?#_%tvRKh*Z*HBlO}eW>eNW%&8VKi4P}19*KY3yMSZviBZ@y9hr|k@;2Gc&#(iz$L zjFSWe((Kk`1SD5xi8b}DKYTh(9PH-o@T&b?1Ja*Be#V->HncwxZ7blIL3C|SDaV6B z&Poym9CiLxdeZued_Vj1<{rJqwylB|`cguoSx&RH@TN5uI@Bqc6}B3OtEN4%xJ1@z zF9^+avFhd5JHECgn2W}(Lyiv_{YW0oUaBbesrA7)*3@gWxoabh-yIu!o=iLAJU&uA_^_atu$Ji<(cwNbcLSM*X}XiXHD%e~ z2-Sv0H=L-S=#%!#K?6CsRcc8AbE_Sj;Xcy^O?QBvupK^JB*qjmkBJpc2yJqKy7(xK(ueWQ`e}x$G+|{!d9+*k-Vbx4I28+e z61@65EIy4K;5Xr_{Y4UT5Z$!?A}L2D&D8d!emGc`dK>8=N1Ib!+PkM?m8+fU??1cd z0g+0CK;&qz=hoIv863p{oGNN;SQtw5p2f9X)Ym&CK@mzrY%GK$N}38PTRMt)LBvED zG}{d@*G9<$aEeUbr1Ul3EG_}9D2kwR!|&E^dJx!^dZiN?0@v0D;*is{+BM2dA$OWg z|14at@WpPedEzr%zceydahNREyRE6PxwEg^ALc+?&+-rco&!y~*7T0-x)KWH%arxQ z+w*SLqXCC%(>>Min&(I5qXK~ zu@K%*bQAu*DoeE&akOi(pDL)^i;>Vc(tj=hmV3Oz zD3cQrlpNRPoTBLLZ%7&JDkh#K=t8Y%bURr0|i)@+@#t=B4i1Q5ifnejs#l%(u%tihHN zMJ<1_tLboUcw`Wj#hYye3I9lKj<+JxN+CacCcUd_R+)6}V_za0MO)L<}EAofyQCYEN~*F?AHx5rWz>)UsixzBjkas#~nXB^Mtu}P;# zrGGu8x(vFsKplZte;`T3GVlitQ6!1TW0YCyU zA1R?ZL|QT0C{Gqh)bmA|f1@Z7P-Dne0mXhly{Gl#d@S(TL{3gFFRf>Ytiw!zdD{a{9Jaa)(fW^ou>SYY3pItMvE&?We$aWznJ6s#8gJtJeRVl zqV2W#j9&ge^yuB1vhs{$`bMOvPE{Y0Y6wRyUm%Q^Z}E1gat3sYp5}pL_x3LQjqLib zDZR1b5;|V~re$Tw)dc%#y3;Rj9M<>QyQ0-_a^lX_^pwSd8AS`dr08z=E z$&mbl0dpRgh8BqjRMayP`X?0JPT3tTHxvnMSrI#hGQymAZ-dDl5v?cY~G$nV!PD(*u4BTJlwCcbjd;)@Wf z+$~*BaXG8+I%kkX|AO&8YBBz2FDy9K_f~stqr>$3%VeT%e~83s44?`MHN`=E3gV#| z#|TlUxqghX{4RAZQESPbXN<4p-D3(wYNR?=;>+HvgTrLd#1IsrsH#k+Y`Hod%_^fgMMWj-i8Yir%->){ObtUc8fDlTk(XhuuZ zk6P%n(#+~!Gzq8pHA%7b^2+f!b<^42-FVINtOnCCN);u;-=u{bKflmx%utux(i1u781C z17~ej4i#VV&kfGontQ=>`z#{stSC{4um`ihceWW^tKhydK_en(VYKp+Ty8l--@-py-x&jM6!doJR(X6GRY~CTyHjjB zA6jL(vsN3XK>4uEstoMs3!d?MqaQZl9=&P13Z1~u4ym<=R=}3O?x&r*4?A(7yn?!C zW|zFCi1XJ!PKnqrAWqo^#vGBwu`<7P=HO0pWYR`{UJcQazNl5*lBhv_K{=ARt7c)9 zh@Keico!%7?JGNLE@7Jg%9n1b@!dV;S4Gj1WEWKj^9v5Om=obwV0R#%YdAB?Or0B& z>1R2V44WU)9@hS?Ak=-sy+DpLoqSJC1C7gF!Rb(>PLqz}cKX&s8*%-xtl2$J6F$6m z;d|%sIR)&?{0o#f(}JtSfT28=E>p@L-5SwQ)t=&C;$-3F@Ykr;2)!<}fu+FuJryKg z#M(DHGJt)H*@jk%0rdm^bLtUWd}jIY+>HiPmf)#zMJRiLU)bao#OHYWB_dTmKKcAv zQEO_2Cg*(#B>I?hkEnHcHyOJQRkT<#n?VX68*KQU<9pLP%-hFGc8oWh2>e#*Q(SlR z$5F?{5WhL!T0P%?9{hbLesW-1?}? z(2*Ky$~5t5yQVfM=H2~o?ILlj7T>%#le;kcMI?eJZZ$6Y=~}CGT?-*gm*aiIq*qz` zj5DEOACHsIH&LU`!S+KQo<0M;^864^QI?Fbcctdd)i)2ZZL*f634R3hBgRZ>ijoEy zcOT41cLGD;9#JlsI2aBx<~_cysR9|(@)vqp+2lCaS{O0Hc<5Q%KKEqyBd$+a!!{Ch zpYxC7W_Hj;b4@U?n&aipav>`l%3~$>r?>BQT6>in;7};fukSTUl?D9{?tfantx|0A_na$d(v#zM+ znQfP(0rxrcOi^s~uhxdEo=xvB=cUb;7TEP2N}q{)p256k$|xsh1v*C;#^N<=2$UCz zzTmR{!unn+dy1TO;#ElBhztOTo$_~lMxll|u8@JaAop#guh^@9mkk4uKb!D* zb3;=drN`#2F0XRbwb=*jE)pv&;!YiNpPcKx%5oms+=mSr7Ck=cvc_9oTR#!xf+;|C z(^Qvir=M7Dbl8&}e;qw;3)>zHg_*2BbgNLj-(el<#3R6fTu74$(iD$%tjTtBc4`jU z{7o!C>b}RTaeo~*Wii~{oY1M%&=4FYF_>|)UZqQ~QOhiZNF46bdNY}6;aloZ6vs%@ zhFX)5DOt27=pJ?$*E9gFEn>~r>Q-IC(z4`+>223}tq#WZrHN{@zHJEV7C5z}gra(s z#q>#K78BMKRwYMhEjNJIwQ=QOCsj0NU8d#UWSjI7AH{uq-lzs?0wFl zIVvbwD?fL#$13Enehn`zf6?BhZ`n%}yiIi-1QcmygQuH>xm`K$D2QC(;JQBIHy?6g zUACmV^Bf7RAlcg+`$zN0nJ<~*;p%r%q(5z5AxT|GlwR=4xWBCI)#!L?$Ldf<3Elys z?|3BYoj*01txM8avSr5`HaX-**P1fes>(>=I4+irmmkMp zhTZM#Uf>}dKCx<<=}fgc7)+{^%lx)Pi(z{fdhWUeuw1V5P7uUM@N&f{{v*xC>;?;? zP#CUPgJk+a8c+vfPEO?O&8%DAa<&J-Y1@Etv4{VzB4SIiJ^Pv!d$>}XWf5y{GjCad zNrgAnVGrKw$x*X_NDDs-FlI+{I4@C<#|G;?mO=c12xny32bw`}N#hHS51~L1B(#*W z2e@3^g{L~N4Jyp#vLf%S?%%?s2*KTZ1AJ{K6TrKr@Ib|y8XsHCtZEg<0mP&y_RW+*-yuKzBBhDS!~?So8Q$IiGD`? zTbz4}{r*Xy!pmF><{{i8kqoKH)(M-t0pnr#4$X|A*Jf6%wL5x->SXP^RTP;)qOSx# zds}F-#HJpR0)ClAD>DHCOLbE2WIoqDZG((af`}-S)Vr!r^9sHl`K3B?Xe+22=jjGo`(hL>SXN38a*0B8JG(FIqM_q z#9h1;WKU*vRLGYE#^4rvTXyg%C?5KLd~?x9LpL)uDOz_Nseqh;^pSYpMbyo}!8g zuRnEQZ=8U_Gd@XsQ}fPLeKFc;#CqiCX;&jLQS2PxPpNYl7k+!-wq0;-$9Z@G85fmc zQVWz7%8A*gq>T0(9V=YQGm3K;3XCe@&<|c)Ef3;ii0^<>9E#3bjoH|t8mBcVOT=nh z73G!xtY*100~qWOKuG+Hep1FFVY=Z$0qgRKs3 z<5>+4h{gNU7N74!H^|p6eDWI6^xf!a@siDRM^Y{mPXEmfx?x;9v}eaX^S=qeHzMXr zEMBNO&vbjn!>(JgO&MF zRY$+=b#UHk!X7AvuD55K_i}OK&C>k`E0#r)PwnL~!cK=(?GsX{MIyWd$VI-1%+#zd z<$kJWu1?3Zh$yh#Iy({>^lisK(t&_BZrT1HBbB!d#3Lmp>t7(K;Flt|dbx42QqNG{ zQ`b4{0>CmIl%%KCrMav&H@$00aznq2yvX4qgTaj(7y5m@xJ&c7@}yL!u# z6rLVh%eW2PBiagkz`79?E9ZP00^W;kw-Wm3zdows{k` z;&%%EvWj+}o=3hbIc|d;QJ~;JSBb0C=E-}FOV2InS4?xroC~Lg#)SZIrpQ$D*H9x;*g&P0-(P^<(=BSKk8BSZ{b)=pFSuoX zv59v={G?G?f6;ESOOiFlNwR6-Nd$#<8qaXss(rs#Le7m6Ehgtjnb{xSUOE3Pn7)c2 zo!uo?Mpl>AOp}_T9mjcm(9|c8c_+xcIceK4=zN>6DRO==U*q+%;&0WIf40E6($eUP zQOpgi{{5uzB;mN@a4td!2>b)*(FIHF1-AX)zl{Z~`n})0Z088BRu68AYL#Jx*BRlZ z>&8gy}L)*F?#J{Y* zjCSu5AL^{@*Bc8(DHgXv9IJ0Fa;HztF+3|q&EFRP!)yC~1E8?&*kJ^y*Pa*g0}$ii zj%94j_-CwbT64Om%2pZ1RpT3s?jRx+P^_pXO>+AHNC6rE(%8z5mBxaVtdcI9HEMVst|0Y| zMSHUr)5wx|el@U!pr2gF@sbj`1O5R-g1y4;*1y6`Nd30x=;qV_;m>U3OMc@0aPiVXM zj{X0{u)qGIh6KuvT16b%vAwX?E2)P{$JI)b@7N*GVMkt_nkBvUe>Q5$yRGz(Na}?@ z8`qehU99Hbfw1-w@!3K1DwSu>se~q(HgAU1Ek7~5?|o=&<+WqP{2TR1W0z5v5z){i zekROGF+CZ|5x|?e5=NIOk#^^b8+Yu%_ohsCtQoNsI)>q&up+g~`;t0}y_)MF2{U!U zdD*5jBP*Ms>fbwQ9f?jF?tbTJ58_iq+O<0uDA?5fYnr{@E@}H+9s!*32p6xo0>R3RfO0H}HOucq@m|zMxtg5TmSeaCw+!0p&G^hBE&!-{p{%VFB*ZMh|(0uXA7`S(LmA+h){gtFTJrVoK zzCmSZ#bQc_o@%3haojul^~mLqH-l2jL9av>^{q5-v-<TM<3@i!|}k-i}Sf6;E`e2D9v1(8QyD zJ>jrI6}IWJGim}=_pJ!q8CYd1GkmyQUt;{UvD;#If%~V=lT!k3Vt&1R!A_Yq5i9Bc zi@o=biz@lzL>m#5&=^pVtfGJ*L2{6!f|5a?$_?}beB*HU_5AemL{bry) z?ycHFJ%JOdQ{@t+=<8N{{~qVco4m@dVy4NPk_~ey$+I`xr>YDa0C5iWfE)5y#~yyl z11^&Eed{vv-xT}S#H`mXdboYe1@Afxt_8Fd*+q=e0cFt+x3&Shq=0eUvABU>4G+JH zR3O?*?mGYu!}vDCGo=^UsvX|*Zt@q92nl@UA1Xzrc?9cU?8)oOD<=9#gor5Kv)G&E z1?Y`1TmGyy$3i*W8&k_&XGB#edc!xm!eO!+D)2dq)vWJx0`JlRhv|n__fCDVCjmVm zZNB}%BI58nOwoW^Bh%nDZoU7l6_H668Di968msTNP3vjWY^T#`+-N&CrWzVwU!mpa zg%5$|!>#k-Ds@Hvtc|PDbKYNSO-2(>CF_afFnhw+CiA5gF}6^O3Th;~W((Sn2tk{A z`&l*#tGyv@vPzn@_?*THXK4wKk8QX645dO)vo#9o^U8dAM%ifWu0vQ0w(anBLVy58 zINzKA$y%wadJIhQVWX|*e*c)BQ9?L5b6)f-9znbSWMm5T*wzK#i7j|a{jtGdvmv~7+P=Hgf97FvzUB&$tQ z75zm#h2RpdUP~!X_zNko_$a;FiqBVl3LP>Hm5}lJ_B+zw#k@2%ru5T}+P6uL;+TOb zyYLW!{(9XuL+{{;tp}w=nXaLMnqeuZyEMcO4n{=j>l)jR(`B6q5L6hrKdyQP%yGf0 zq-Ooq1pbrx{%6U;SAG5>$B7Nw_I*Y-sG~gfAV`eO8Es#I0L?U($-23K2|;5M9t};v zdIsvBGaQ$$+m3N(6&sk0%oM4MF9cq7!i&?HX#wBNSq`?UfTF!K`KfJN6F>EUn+F4W zN$R2<*C>kxOPqtM^siaIN41I02K0glZL8vn<88jaKxZo_T<0O#O_WH$^7Fg3dAnA+ z_EbohIaFxW#*#sjDhrJ&EvKhfhdIi7Wr*Y! z;QM7cg1UU0)ztb3rlbP$wheAj+r8+ty*~h7*JZfpl-xaa^@74c4WMMmC%idqiq&a< z$PuJ6c7|=I9WmS;rG@*{j)3l+YT0Lmfb_-BdYpQ-v_4LUeq=FYe}0NEL5M6X7vfP=$xDf}i&u@=jp;<1@)IhaDl5)2%s zS7B^il4!&-G$J!+-bTHu z0if~9+4(c_;L!&JS}ebZ1(o_JmfN&p+Jsk+wX}bL&_0y^h(|HFwHA+BL2G6S?@^gPEptqZ?-&zBqisk7{?{$Vs zirIv_p4;6feEm`lG>+6bz)*q^!c)Dfzob;L#B0DElH`tD_Er

    ^~;tySzJLdaw!fTws>9?U-!r!>v&^6tuRn}G=m+gyId z(yYs6c{e}EMgl;*+Aq(lKZL2@)CQw7s&8XCX?js%m9_{JP(b=#c~6Gp>x3N+U3+t% z{NraEy}afO&s_f+oRD!P50D@h(~-%&?UaO=JM&iT4| zizN3tynxF#Dh@z?w4IMajd-`da|orDR>kzVvmSO(%QHOOd%RtyEoH*=&V=u!bj%xM zMfRmQDW-La5X~2P3M@>H+#0CNg5SUI7v|Om7pbgF^L~J#?K*_>CO<>PXyfB1GhtaZ zNBpA{%HF{!?gG8s?)L{Zu=U`E*N(nrb9n5R(HllwryHy6)biqabIQik6;C6Rj-&6{ zC*>(@Bk&N0hAp@NU=V7V#W{+vuW*PJm?O4Avt2tH}@;!gUhcy5W08)coK2_*}Sf+D& zftsstoAXRg4VhZtj~`u0mFSW;TVJU88uwM}IH^AV^i%K1PAfzNWB_#?($Ahnv|dE+ zq*uGAU51}(686BZ{GoXBHZKPy&8mmEF*@xlajyJ6Zk&Y4^Pj?rHG z)p@Id8v^ha>c>T|#MZF4eE(FMy8*@f$LDAv@N*RO(F;c7cO)DAV?5={>4sHZ+cw3_ z)~6o+`9AU=?_&mf)DfW+T~ofH-9s4%XuRD3ShJ!C_uvmdc>VS7rpRqUdN5I5VR;u2 zri$}iuiqWag9tRO%EFGyi*Qfpescz}6{oE+$M3*Yn8A0u=-Ja#yGWy0uIqapjPF>< zEn02s&`JXH$^zGwNBMA#>amG;Hc__YD1|BU;O%BDbHCj}0%Y`zIY-S(7}Un=$)gH@Ba8Qe z1Muq4RH)0HQbY)oVg^>`qLe#pDpp{n64Kz+L>gS)s>B(PS~Kno_k> zN)#bV*8mWN1X4>5JY3}Yxiew}OBJ1GBT`-#-wY=%W|n24BJz>j6T)^Uy)o;o=xUoS zw=Gjvpru_#fM{LMb0&?9_5*6B>lx#eX~iL@Ri`803Mu{gaa}Dv*?b9Nci#G1}ERJDlt zwIdt|RfMz!GT@ZY=L6LgF0bV@r%==y8`Kop2EgZ9rL*}OEOp%L_USoShIP8E-i%T> zYA432S8+NDW3-Ljsy{h2x6yGEE>fv!ET2NrTTFALSP6j^ zuL6hj`nf-Vqv2Q};lN~x%0rYaXi*}iVC-T)^A!o}{DnltKH_lH-MoqSW=Ep3UD;+V z#=n)?GWRRKZymH|sDs@_s+b&638mkqfIM`4xl+7on)Z8yB^6TEb(3&FmZ1*k5aOD; zdcd5LeigI~ug%uaDU8I_A+GG&oTSUE<=yv{tCiv^GG^c;8+DH9 zw45tMQI1jx&kJKWQ19|3o;8*El+aqXTuEU>PsfQ%0cok|LF7!Qvv`aS>tU$f`PeBy z*X`u0Ua3%d;gp)o&wv7x$x_h#nKZxFDdIqubeH*iDxz^DG_F-VW8s9@b2#-}V%D>^ zD5P>ydKZgpKlC2lp6%AEzsDj`bnx~7?xQ4w&1eD);i1c1;%0Q?V&;a6T@lQ{$#rOZ z%-CLR!gz8w!3xBa{C#_CatR8!OrV@A>rR@_b-eY;z~*2dpCXqa)eFQN+7UsbLU+R- zHf^nZ?l~jjpGdM!+f^f-Ny5Ol>3st_Qwm_Am+mGy;hbb#VK11T$X-FSS`~Zv0D918 zC)y##?)%Nl%3=JjJ*bMt9?_zAbwOH{tD>ZV=-(Cf%;E^YTjL-RxW4T&Wr{0Ule5OR zCgqd}{djU9bcZ4DM5W^lh@A0s<7aiY&O21|%$=bJo~JW97>v>Z$6kv2H2aardB~;% z0mb)0R~4;*0rI9(f1lo2gl829K(9dg=k!Mjew^w5k^kmP7WXD_?<)JS(JU*u&=H5B zZAKDyY7RSBOh0^7YeV?&se7*N$ItC;>_%62I&Y7q<<4Cxn5!fkb^Q}`1oo{pBUcjv z=%uIKjsnY9?Q&C3-dueDt30+vD?xBgXsDl9>sHyb2ZVBTQ&!Niura_fw&gJ(^*sZO z$Z@6Zq+Q$kWaV`7xweSL$+PKhK03B|J#Ko}-~py-u7Axh;Mt>~^K{oNJ@{3tnxAX7 zM6sr&PC-iYZ@i4lAy5#?ypbTGw);VSDCQnGQ7P!y_P5r-!+xg-94w z9u`7)V46?NC_y`HIcAmCO`9+EA>^{%dHBk*hV}rg3Y&{t2}u@JO1n=EjE*Z$WzI_E zpu#c?yatzemnR)P^0@ISE(@p^eEnVVnf{Bl1`mu==-@k-Ghpwmubp5fdSUT9 z(&9$dzPf#^l~b;1BB}h3Tz8{Jlv>cGmMIm<{gT6r!rtAefA5lX2L9&`Efhk+6~zSo z{U3>MWsDLmYN022^}GBcCVSUIsoZ@0`%7JPz`?a(uxN!{#;5Y}a`v%2KLJ~(T|``g z*-AOPbUGI$Y3yCmLU~o9)~aWw#UXH77YxiYcSpK1ZFkovbAe^|FnfU;hsXF~fC6AO zM?k(^BjRkVfJWPH*Hx{3a60Ziojk}gC8%!hMopsli;JP7jjl@=qI zlY*|~;FgALb#-)u;c@U8c<)MOPRNHH0YcH9!pb!vhPB*L!nYE*!=@ODm7P$R1)E@0 z&M|YauV@WWql2GA3zoO~?EM8sSd$e#RctC}dH>Nu*}_XzOL#MauH3p2`R#c{VHkYQ zQV($|g!>Cmd12%;Fk}|A^+qq5t_i5{99GwazW;i;cQnut43UZJ2x4B3*X+0m8YZL5 z#W+ZxESH2h?i9$=UAaRWvM9V;z|91f>U@4(LbnK>kq(5IbJOnZu@Tw5mr1krLULz9{1_$T+jfoDwg$fJ~@`GIGf%%l}2w|sE z*hlkps;$M$F5I%)Tg>$BI5r8~(K^vCbdqrFq98)l_)qv>>o+M>Y^)qRs4O)AST`tL z{g2sDK+HM{$BVzNeC6z_zmE1U70@w%8B&_ZG7G3Ll*Okx^;1~+8*T!ne%2E2n7~SE z_WU-tmTi4s3e-40Ss2<_0=Eh$)GIs=d7x{d{}eJSrww+X6S{4ZcROOH&tlnRG-J_e zjR&OB+(6t!OnsmgDll9=qyGdfDi*KeUv}>Kf0xQ%h1?h>1MN&ZqMe zOo9YMW~|Yw=uCnHF!Cy1%Q21E#c`p4gVqwmdhJFySnJ`~vF>naXF9%V$Mpy?XVqWq zJJ|sFKz!o0Hne|qy^^NJhvuiv_!YoN+~E>d)`3rbodm%8^}7fb0;~C}XRJzSW4wPu z-<_?KZ%S$;B?JoK3|@47U+Qt4M3v9DfM((T!1CFQd2zU#PAgcB@0k@nT(Hx%Wzg2a zx-)!UDM$;f%SXToOj62_ z!(AyCK=2IX6vhQwQOk7Wisk~^1JX+0z+o_t=re;nra`L|7oYKBLcP_YO3ipWa@%yA zHMVTL9R3z0aHr4LX;gwCe+Yj69revEFHl(I5NOn2T#8{p5bc(KU@E}he>~VL`P|Y0 ze!@14R9O){z(+k;yEoqL1}MEhq#H4_wo>Cxnx}llrI6*ViJ`pMK+ThF5SUM;J}!F* zxWo5CBVHdwd;T{{I_dl)q)MuwXQ_Z{2wiGhS{83NFX}Gq2cm$^vApU-)(^Iexgig3 z;)mmj%~L)U4M~V2FnQ((KQpa&&uq)`?u3%Uv})@ibP^aTVg5o%%UUbFJr(4#pPi6K zg=Jbv@i_;yV^69oJ!v_&Rby$@$*WH*y;{UzBHX>94kv@eSOiMlO{jkjm{FDQiovcc z(!TaNM$EMK53A|BniK>S1~)oP`%IMY_(@a%@28oQrh?pIeFVM-+$P+y8oXW;9+J6J z+{)RNHgA&V6EWW<(YhR50a7Kw-^yabER}%IKTvTSXEi|gtG_&Ija#x#1FiOX*@6Tv z5-8MKrr6@KxN`m^Vw_1J`ia62XgHymoR)N1@;qD0-O-%y{K1_N$5>obclBuyt29d1Kw*EX{d z49G=9@GZ%JEv*aFK{;H46BALKdM$D>X3#wCmUOv22fEP${6Cf*2kIjhn0Vt?;Mh{gVSWlR~^nPBlirEFk!| z9{K-`|Jn*;A^{mEU^18J-c4ko6H1tYlRb5-PN^5W0;Ca@{-eC8R8K#d@+mO`MBjf8 z3wZfQb=iQ#=GN~uI)|?o0q>`)KMx#)132R_IhWw~aEqcp;ty_Kc>@8`Fs7UT0~iSC z<@FyRWo~k~_3J~k>&31ry$RQuWg}0$X3_UFMQ$P(Pg3q;ifTAdZw0;indN0O`EcorO34LA~z0WUar;@kbv1*gG;jR)h zE)*_krtg3=xhx>ly%E8S-$BflayRI%rB3E|W$ee8BJViA(ccSdH;wf(!AJS>?(VF7 zc~3UGA#}e|GL`0ffG@jdn(pLy<>>RmmZv{ho7C64FQ6GHy(h*a-5KQ8fkzyW%wpV&pEvDSrAj@C@CiZwhQ%C)7x@GQO@Bii*2L9TkJmDrSal{D9xP&`yd+&{kuZ~l~73z{n zoR6#yB*rwOIu^+ucP!E|##GaJG;%y2VAX(G!b2LC*BjZT;tBq-RTh6!Z`7SLEHOMD zmJ`9DPVSuSDg~ZWRoHY{pujMxW)v<{OmyvcsB2%jBk$*fgwolsmqhF)xVfkA%gajE z+)JJL#m6@hw6Pc?7T2+AG{rVeFQRMbzyE|qTfi*xol3pzp<~8Gnj!}&q^E=gQv6B| z5iLitpPB#6#zZPvY0fVM=UT#$yO9{}^NtNdUAY&BypX%IBoD8l@A`tydd zrw1GW5WJKQI`FqCi>SmaF#Ax~B*jKxiBm@6$=m7uXQmh^cFY>zA*MCy)1!wrEMBg#`91O+LeHOd8Z3UJ#w1bSq^-D{2 z^EJhPP4kqo^Su2_&YbGNfEN6{^fQ#_7xv$OT1yes1iefuj{tCeRlZZ@0zkN^zbl)~ ze+iz`w}7ZS?(a}}klc@fpPsoTP9W87ykcy9hXdb^a=oH*wV5aHm2`W!zRU8dHH&;X zGM8C^kG^s3T3pwjI(N(+-wr6}IIB9Bh(Q~-9Pzop+m&$=c0l*1z&MCF{>StOHlUh8 z{R(!m8}V<*FhCmf1VQZ3D~>FRW@`lO`&ujte%FQmo>U42M1T!_z03@nC{-f*@gkDy zdwTMIn_p%rN{6)Gd-Ggfh9EWMab9Yw2SO3>h|@ZZFXeUZ75IrbHpRxx1edbpR}66_ zu&XB$A>>|F@Efoc)apIf^Rx8su2Q{b@le=ZuWp|g_o^@poYcc{wR_8>ehsyceKWqM zTFWsdN(Wo0uqq3*@^c%fDR>@tE4;zf!i{aW-!scW=|;fmoQ) z`mI}C&&`#^JaE6Q7>}9}j<|?D0Gu$?qa5#TW6JFGv?M=ub+4z0zJ>kL8?(gZ);Nc~J!v;ov?f|tv%HlJJ~}?# zG@ie%5jo_jsq4btw`XsKqA2g?RNXM->JRHT>;5(l>bb0I@v>2Zo2@H0AwjaP;cZj7 z>ZE#Uh9TEA^!EH2F){yqM$vkxfuDHbwlxZNsoLyJMm84WC-!(zka$<2L}L8gCVn`9 zQP*%Ztvrw9?j%Zy#P(r`LlXb;<w`%t|YpvSt zV`10i2n4q_Gs-+ld`}76!_7Rrqg-w7{lJx+D7pE-w5xBlCt<2Q>cir<;gt^zC}_YmunJ<0vV5MoLyfG;JSkY;;6QTs$ht; zhc~RxyZh^PAJEP%;9r*=>+4-L!HA>?m4Im;9CZ~cc+}M5_PrigZ7X5!`YqV|r2)f| z`W~P7H=~iw3q(ULvxN!t4!>kFEsFqG{wL1oeJ+8&Q@pQ##nPIASGs^?>E(j^3RTuj zBAq4CdtS=t22|wCbXV?L#BYq+ERUbxh7%$Dq{hxvGKOSFOl~I}@Q*j>({KVA#l$a) z62Dk*-Ax!TRzeAh)$1_5$esLL;hh^fC20Bt(*d(6PH{TIPTSc_E-Wt(vl^Y22HYdp zIfY+Cav~!%x=o3^ zql>C765i`14wP$}9}#&Btya92@aFZ%=7?gx1t$MN3EUJVHokLn&~wPM?%>V&tx~fu zD={|MZa>Yi1BK^8>wCBT_QwzA^Hv;8yzZ;qzYSyn#3|y$n768 zB1>HbNx^g`;|}@V1XWs~>2>obX@FC&`+mU^aRCqjcPd2mfAA9^a6zD(@m|_`H+k$RgR(@QAS`F@dF2f~H@CDzRL^Qwn+xcg;ol+*9i45Yve41-tks{BAmdb= zKd1Qy6?hLmGYQpv_(_e#VZp$3Uht@Na?Vw^3@TvVQeOA~`-ywKJEq9!&X^zQn#A7& z_)~_~+|YJy`6ycgpFPZ@Eqj)c^G-2HQI&?AyiCPFmro@qj<+C+M2c>f?nc4xEn7?d zN4nGcU*Cd#hW0NX8Y`Ii2rh1qCXpB<5h0HG{psp(LM&atnGaC-Ay5C(FvJ4U=NTFV zk30RCFVZhU(Y{_~;OH8x>z;Am2sc=d^3c&OLGirRqEU%8N*z0TteNTMc1v67qwT|( zCjK%drFp`DnZGR4zk0O+dIgiT8;XI7&#;{*Kl+AOKpAdO7FU<>U11ZQ9Sj&Qto;pD z$kc3oS+Os2IZj!~tk$@6lRcn&!8A$tEP}WeTwQwV`1%hcP6|W|Cp!l{0H515;=EuS zC?%Fg_jNx5YCgsx`IX;RWMcH(1os6@$K}^F>lv)(T=!kq&xQvJQt|I`J~A|^xdy3d}RAP#Sr7%g#o$$&sjs{ey(&<_ItZ>PWg zFF0@-IMj8tf%$js>ryHIQdYly0G99nc1`%?1UHFyr=Lq%*kGDh8K1mZRE=937x#8! zah5w%9j*A$V;9-$6?^ew%e}CUW?^X>A7S&DcP+xgv={H)e54o{Gxq33#LZ-a83hpb zh3#Ei=S$(R@zSPuoOEIj#(XLpT$jAy2TKr12ts#z3-8*yTfSTX&*L(%*7DVdy8%M5 z>9ptz2*kz=sC`neZKVrrE+NmPo~q;^DH`Bc&`VP?d4n+M)vrL+7~sXu)7sXmxAat( zfkPT#@m+^kl?D0;xH%s9bo8b+(f#kbP5>|PE9goG)tefsX7*1sr&=ZG%_X3Z^e3qF z;R>K(->D7)N)JEnL#C7{r%0xR)C0Jf1-xkX2sn&v(VT3q{}YEOwUIi#{Zv~@?BCz& zZX8m#n5!qFexIh2e4i6*c#TBCAL5_rSNVVQuA!_MM0wRnG+k-a8OHua>G}A5MIbo*3KsCQJ6ubLBb2WY>k5S&lb+u6 zbIjT)^yIll>_=J6TT;^JA1_vQ@N!r1A_^9m@Db~QuiAzBn#jAXAm#Z6qz<)`SUuJ4}Pbe-6FUgves zns{FC+nlCu0(UX(LKmXn?-$Zn2x{YAk2T-)R+t!oEU!A8T*;n+yDq#)k4oZ9`s|J$jn{qu_T|Yz{35N+AdRB` zEU!-O?ftUl&2RHkQ4@|P!&(bMkdEB1I`DZuNa&o{#$II7n&3Rq{OD3aS?s6bI%iFV zw7i;=SRwYl-{#bS5UyVqMfWQ54DJzd7r;(qGXbz);YQXu1b6#?-Gu-zBke%44LI;Fo z&-ck)qzy@MtnE~Zm&g(zeVVnuWx>afz9;~;qg3OeJ6ABz-{y74S=4}O4T#LEe)seC zFTV)bb>vDxny{{OnO2}guxyWUN?TPeKXRG7gLM6k(%Su=(7OHoSw}!*@wopoB`Vnx z+WwijAYRNHsDNbJq@~K0DwbmQ>EaiFRGRPodB6jKBoIPceK&6VLp9J2RKV-5RG|Yu zvv%m(GwCJ1v;_EyCi7ds{Si?8%MmSq6^LF8Lw0}VC6(jwkG4OXUJ;}j>rF4!!=3ap zw<|QqIKZach=wVoX#0Q=)cr3y1)_;EHrk0npv0D+N2Dfp4l$EbuwQFV0NU*Q<(W4z zVk7I!UW^}zE%|4;n&sAD0?73H|NoKvzovHNYc?;xtIT7230M1lWPWuTb?z{=(7#*|NF5HLT;g{yzBY0wt?T7m8Z;{a_k8EqA)`kbLi#!wV>) zJdM%UHP=;rtxjxWRR!*pDG_Qn{mKvk!KO@sd?gcB`&sv<(Ddf>VeP}axuz~h#5A5_ zjAyB?)zhKLpRQ;+X>okw`{n!;f+60f_@z4{LY}IEezgjs5Q?q>51*D?clq@Q1E&){ zb;qD2XXYcP^}-`w+6#o6H~zbnJ!@DACW$z)Z`VAO>}ds~R7^sj23l1>1slC_-{LB+ z>E~lV@PHih*t^DbAf+D2x_fy^TY@b{8VhK7Ir!Yg0Rjf0!dJ%&D$mP008UPUIdFR% zaPa#xy7&%EMvEH0m6Eq~O`>|gExq3Pg^T_DWN&)u;r8l!m5=q6TrV(o ztMT*pBA6Fb8Hvwxby1SreUj`_3j{vqzv@@K z+^C(R;MCM@KrjKCF7Ltksuse2S9+;2N1>tYHdv80ifD7$hDAFi8aHilGt5r^Mm-@j zuLy(S8Ry?5NTt#W5-lVwVjmOyOCbl=h}Pc|UA@>l{9Hi0-v6>>Oc#rMvt| zW!wiN!wQWx+&IlPpR;yq^@-imDmiAByO=bE?sWq;(+@AZBj;Zi?l9H9LleaW;_CVD z*C+**t|5zlUo#}4VgoD2)T;GZ6tPId{R(1R@0zsR9k+Vt_rGWAgLn{omK>{eOV@ zXT=dAYQ4<{K40Z^xyu--1aQoT$qfMH68nYrx->{PZlfDvaThvGC$g!WN<=Y3GK*v& z=U*^}{2U-tK)6P5EFc&@3H^GSDIjxW=`KKR%z-KqCZzS-YD-7`w#hOUQ@2P3c<+eTwL9 z_@!9 zsMiqz$oyA2nKds5_V1Yhh2eXQe;!eON)Y;M@9?2P87RQh?3ZWaLFhd-fO(rzm@)&|3FUkl4|n8%r@qZlh}9zGKlAC(77^W?Y23cW`8u02-6 z8fM|hqGVv+kvXu@c9_3#BFcBET@AaoQI6|6Qo|N8TVcUbk73-5%Gl#IqfFGo1z=3G ztZLZxV@?=8O)>(5YD_>K6<5KM21Yg>4ew0QSz%8MnJUD^;!sCvX)>_Bx>S_w@qKGN z&c+Hm>UXI^oZ&F>Hq2=HVgFfO@+8w`Q+tFnCL6i}CUIX%@<#Mh@Gsos^H;kj#d;17wpt_QmYr^0H7&IA!eG_~i=m8V;D=1~wn}I>icG ze?nVv)NiRrQz?G<8^&##PYwH!I~z9bDQNBeb-x@}+oGn|w?2r{?2`eqhXN0qOy6U}P zX*J}V?UHsI7IhY{wbY=5aY^Iwy$~(vYyYM}OD?G)RDOCWTWQ)RXWe%&xBdB`$t|lP zlgCT%-jpxh%UvUnY{|x1I3_VB$t5wC$w$p(D@DO_+PwyI8wut8S)&Dy4Ac&4W6GD- z-waN_%U1H=eRIsk0y_|cZ@CLv(UJQ##va?T0)H28@m;qX>LbocyDFFD7s7U=D2Lf9 zlU=e<8O%+Slb6f_x>|jDpc7ZVWRX1BSC_3MNfzrT2y~TDu*Js@G==1(RRB$iIgS*S zfu_1k7VbdPC3(r&7@(=vfxYx#?ujhhkr1$r=qi^QIpva$ld`s^)3cRMU{4S1HG#(= zcaDTOt%m$p-W+4&%a=w)`GIJ~Ww$+d`P0oU#TvF;LoA^0- z%+|z{rRt|ZQ&suC0-)*WQ?IpHplQOOb2-p-@=a>jZJ=r1Rx&rxR61uN1Zc{~E*=Vu zYU1fqwK>o^txJ?N2_e$lMG!Ea|Ruf0oJi^7MyFaY^Jf=TJJ^-_rT%6&W?) z#|#M}LbOk%X0pL$2_*hjjAH+2%5L(j8T+H%T|lb+(|eHf$EP~Af3fW3Prq_SCidMg zZ1k@W{K|H}59^9%+pp~M`%Kv2;egBFCqKa-^U$CH92Wmzqdp{%-NST+H9w~b(O!t? zQD&?3(Wl*kzGei9$=69{ZlM~&hwmKj4V}-MuG#k1pi-HkT3=HKMuR-awKDyggUkjT})Wb4jxQ!0bcUG!U#h&*^-uD5U zug<27z9O6(`5xx;WM`~RAcHrpivsUFCDBJ$5a%zn|yUjtCUi>({&*xGXbE z&pn?Kh!&+@>#6fdtt4~2z+K8A?N0B8%}pqD@vpq4ZScDQkm32wmOJ&OYzTKK6rIoF zBPa+t@SMy%q5tU5NKJzjz0%As!`b~4{Sx*`AuX>~&Ryu3j8lb5pG647jdq7Ec-CIr z#oZL!JdWy8cQ?>&qGWVFi%`3SJWvZJMr=}>k8lQ}$HSnpnbv?u=O1pIZk3Y6=O+8F z6hkA#D1*WljO(=v$@BcJQ>%mSQQv(|T~+OEmZxe2>7L;+097T^uNzY9$(5}Zqws&Z;F(iSX zkIIL%g-k@`jFx!K$J?^sr@J&B>S&uoX^&p`4g0AcwD&AUELrz54X?ec5~s1)q0!jA zA#xd&bM$y-;nB61n1lP@5J9o~Sxe!rh&M11R72TjqVLK0L(144%Z7(mX*0qmG;QVE zHmKQK{`xrrSVxU@_o3v+Q6`)2`MfwEdYfuj_+9MGE~`#)9{URYkzY0zdf4zb7Jr|@ z-#-S%-;N&V+T29Id5<1rU)MdJ@o@IeeS;k;!t*pfS{d%)fX)W_nN}X@U_~0d!N(4MvL5nu`J> zDxp2w9Y}k-`oX14*G?mi1&&pYDxM-mYQw7bmABLLiPXLOX06l{8|4GMr5UXQtW5Hu z71Q0VHTPgu5^dhE_3~_|$30ip)@zQ&IF`Aw7UkWx!mlAmumVH#9pOQ^*R)N&)<${4 zarY6eauV4ib}SQ^^(dt4-qb?=v@Z6ohTyOwhkIonO|E$$dg72ayX}Vg6?ksO;%g&@ zm;Sxea=Hx2#Ag=5$!FuuPo!m}^I=C7tL{iajQf>bS@%lW%>=Bz_RRlfjykl(P zcx0AtW77U?=F{rwoPDtomnj$hZMTtW?w#qziIQptb2HQ(8j2ACon5%ErJYtv-*21l z{P|hUjaLtx&HbFm_vhwOBICK3b(kF;-?~AG|H_VDeen?N<@7@5;T4&LpSjHDB_zbi z!Ge39Z?@vwjC9e~d%i?NZs8uX{_^C5VOQR^gw0&)$v84M9A86Kp>Arzp<1Hb*vA(kU?JKOC!6gIK= z+mwE23HxTwEMJ#Er`ruXL)AQd&W@W7cYcH*mN)abdpq(#Fg`^CV@^iUjatR)di(c{ zs1)5@kJ%~2zFA9KhBtD?9sLGo89Xu+@STX;(yFL;)T{DKkYcG#Dgh3pi-t<21JUc~v5*1REk=4A%jb6rA z^TZA^j~3kAy>T)wY~QZyrjK^(E;agtKw!lrKdMFEo+D~4bPf8ryTdlA`Yu+~TCeT| zu_HGD@%B$zVd%3*Iy))ymlqe}(=yorKlVQ)q?H$NW&_$)8=(%G{+gU{`g^{loc zj()3#tIP(DCHD&UCJPz3rSR~mi>8Q!kTp<>&boez(TDA$wU)g&I?l4`WwS54YF^Do zHolp#N?7Q)7HS%U_eS}Zn(5`48hpdTfb;k+ymGaD`~l@=Jse}Wx!3QfLBfqUTQfM{q zCP;i+;X9><0UTu#ck~p!YujQjzyot*8d+pj2m5g)b(I!o*}2~@#CjuQ{bau^C{5?J z?Nq?VugJ*!e2RL&5F3MTb8b<@1NcO+shiKR1ut@zcZjx6yJzckqg+pK6LvP-JR^8m z4PlbiMm6hEX#G$BF@Cx#oPlRVV?RcEx#Y;FL=M==0ds*Xzcg_%G(%`MFN!6;U zzMJIjA(k!@{Jjy5>Gf4J;@1NP$Pwu9c}P|o?wP5Jkj;Gq;fXyy2yVt=!s5_*I1kSU zp~GR3xn~goD@vGU*K>`^>UNB#vxq~nw#V(4jnpyNV6;Swyu?=4AM`M~UdzP3{WjJJfgYc6zMy;@NlYbqjqBR`?{b)G}%Ss`+d5 zLT*8`bxPPmcdLUBL6YGcS?WaETp8+^jbKx4j`yDi>RyrK<=aMU#)i$_QdgVL0bFUG z+ljA>lwG&c#ka@xqt>w2H&~zU_{D5qrNV7RcxhvKpl>eq>IN@@yK@%RStEXBRbf_~ zq$R*ZzeImCX{(|e*W;Je*uc7U(1&WY*)_T2oKha`$Bx@Eflr~vb`*B1I*U$h*EP%Q zlOpybTuGA4e7;C5}$LjaMs&tX$#JX{w{Lz{k0x-{+Ci;z;;kJxX6P&>cKc7XZD z#d#vt&}Jb>Kq1ZrLLK&F&lY%vE-T=T5YORq2{0h6{~zA{idgjLrh9d>Wjo(mYKs#u zUOxQ-a^x&xAjMs-(R*3qa%SDtDP!FgosvQ}aR2<0hkg}srBOTUu1tx%TF$9vA4Ax@ zP(P*V*GDCCweohfBY=C)eC=LoDRs0|d|!c`qzl)(@v!~9T2o-2dsd>fb-nzWHPJs{ zd}|waa=M@x;8J2(@5A6`>GFyE<->&1k=s*~BS^oO$jm_W7vJLHGZ&J%b9keu`gxhS zKY4OyLn{~}D{=vyQ6{!jmlioyqhV+0lXl;k*N&V4fUC7{rU>OUFYmS0=FFnN-*PFs zZ)^KHhxshfA*8AJR&o^8BpIy`#tQ7HY zSK`P%*{3x2E=}GhJaTG}Xx{5Jb2^FRUo5Q9Z_0MhXUQmt!>Jr?Mv?Y=g3|uR>;AHn z07WQLdHqdAN|)*Eiu7!&@1TFzWa(1>Ba`N3%f<;Go8oZGd{0Mt*%7YTNC7c3b0^gr zYVO$M0h$!%STZwySf|{#=QL-1Jg;J+et?S=%7T@RZVgVE2bD)RS$i=mmUsSK^Tk1Db@9hay;|E7 zX!9um$-D$IXm)UUY?;-(+#SidbpGUxQOg+A!za|%i^cu%r!|QseV;V)rS5}P?XdWc zgCn&!qLf?c1pg~i7CeO^1+IbUkT|jr-~5-2id}U7b}0^vj!$@-)&L`zwBY`z<*!`z z=Y%U7wvsjal(y*wM2yhRT1lQ4AcV7$I_4ANm`{9=xw<-$eoEi!;m<%=RvY_xcAsVn zecbv77=zFxr%eoZO3k$`@4n~~@j4CxZOq=QjoVt4#nBPovkukDCA!Yl0j>WnmkTg3 zA2DHLC1s6@$ZcCRlSeRjSwr{OiRxG@{(Yygrf`{5I4=>V?bvb_xX zjp<-+Va`OX;Vu)tWxB(k{H2y5oiBP;Hi{|UA@)Bs>D+FtmXUyGEU%w%cof^#A62uHRlW z_$#P6vx`U4w*H5C%)yUWzO-N)ZZSD4auD0^KlU2{QUPd~*72U`{?`%VyV!%) z(+(#?wuP;SeTWc~U0NSAfuJB7p@Mx1h`RH6h`^OKnioK_C9WUj{T?qXQ~mAnXlH0D zKGR2-&Cs)cSPK}wfc>c}>$&@@MCnt|ZLjCYw)-!ooo856N!!QS7Zs7FqAOC@f}luw zKm=*QvY;TKtAw85BB)3Wy(CdkuuxP$Kp?0npaepPP!cf;LV%z#^kR%5gn-lpLPGMM zh(5d5K0fc4cfQ@Z&NXw+nUk5hfA{?F0sH~6GwFKHDmaLR8UL+qq{ji_%(BuvC&nN+ z@cP}EccX;lZfIp+AM}Ai%RbZ*_GROyx!i!+Ed%`%d{w+ox~F4`j7{B^pm9K;1=*pU zq7@Nw^(JRal9J50T@m@yArxujQSxs_JJ1QNEe`o^`5p5$Y92Ekq09nl-_oM)F>}4$ z$B89vw@*KtKDu3AQ{3|EU-QothXz! zQ%WrMN7yWh*gifv1IjYJ?%M%m>laEH_jf=g2bcJNK+J?GDUx|ya)3+o9@GrIi2f?n#9l`^ zvlIh2_dqf8w5hN%)8*Wxt~U|gIAK|C_TWJzG!Q--W#5Z3)*;U%hP=zJBDKTk=8Y2W zTI^QRS}<23ErcH8+bE(3i;N&?o5OwUlsER7qsm4(Gm$3`=Nq=FFW~B&z^vs0>(`u$ z0w(ML>)ydSdtu-7&_Rg@@aONkd&TcMFCgW+?vMDBwG};SL^lP z=;3yG8bToZhD(Qpz5_2u@M_78tQy9}Dfgb4lmIMzZ04eS9i!t*{y3bbo5XdTm z6PkB}({t}w9K~{3t*w=tE1N@}IO2pr^|;4V^o;YS`A@?)y9JsrFm5x;%bXeo)<>>| z|5)>NK3`XI8!4cAQOj}r=E-{rJ~{i5uOIsA-I!N*o@SPg%8t~cT0B9U(K-i#K{Mz@ zS>&=jjNQYCTZvtcw&S}Z`!_0IwO4a6Xm)$3PD@qp{q;!D#MKO@niRQ>Q2E4HKq4j> z9~wU66-k%$H{S1NO%o)7iC{bMB~C|2z1q+U|G1fua-8K&x(OUXFB}g~AV{QnvhN4g zM@M@_%~iw3+b=s0u>z1y=nzu7lh*26R#D4K*;MO=)Z`-K-8f35kTMM#HJVY&)W($E zQwrtRV%o!~p~+48>_lBTV1C%X9c}eXQPkHRH&Zi0sIH8X5E*brnL}mnN#WC{vYLAt3 z;W21(4$lxz@){3Xtg1+EjdoIzA76jUlF_AW`}=~76`W&s6)AU+wNrnHaLmpAWpNCUH1+*fm~pIS@5Av1WGM~rJ*(5^*B2aHO=BhzD0b2wsEzs1)q87o`$ zbu2T{`(V`8SG<{b*9j%`!E&`BT(FjCD%2H)4YYsEG6tERlzkvOeRm{o??!{;MN`6_ zoTC>G!Ike&B*6N%EeazZoo|n-@ZP~N(~!ieAZ>A zlizUK1BF#BoDxW8I&R<43I`9e0%Q6UD+E*v>BO$E9(LvQ-C|4!Kb!93$Z-ikIuZlC zp6Vkzm1XN%`k^Mdeo#)9UY#zAoPcgUeL;XfjJ&qu@pWf8qc)J*?pnx};jI*K^im02!HaaH!GdtMq~BX6pb2esJv4 zM3!Hq`eik4p`ZORLZravmVz86)=kO2qjwc65X{W&uK>_1~ww4#otDYj zT806}*JY_=x#-qtSHskhmcargUGgc6ni19aZ0ALwL&#$9l~rGCI&S~yO;1csZSQ}xhq-9rHJ_I0)GnUb_S#clT873g_;ij3)y+xuOE2Nf zNET%a$k+9fnnOsb-h|tNoC4#TAho%-zs@RyR=R>3Of?)52$#C0 ziQ+BGrHs!*rX&j$w!E&cG&l_2J^3zlRi9{ZtiQEZm=kXHzfo`@In`(Ttp(v2{0{^0Cvt%Uai zGYwWae~Gu7YygZUS|$k1O{{L&=VS@?3plBxzp;I+Kq8L0)HK)S8C!%lK_T3Pivue2 z?l9}iWQjx`CGaxOPpJu;f01+|Z(gi(Xko$ba`p@a^*oFq*1YRj^R68&b!{FvlJ z;nk?4b^bo7=uHgFsI^-%{5)RhSh=68f6y?*9iqTXj2!ulpq=FjwLQizj$Bge{f~c( zh>O=|$~En7MBv*@lJ`qaZdFWreiW*6W7CY7a_49mQxTo8`iSbbZO~i1{DfXW6lRhA zhA5S}ees-@ng6kJMV;eIPS5lGUS;|_@Q6zu%yWG&wg&Z%g-;XQg)ixpksZuvt9jt% zBi>Cn`ZDMAh7fwZ_tcBL*W4tpwyC1gS{7-5wkN{Rhf}dDRyUawWCFMn)6?Shfc7{E4j|YtW0~k2GIR@p^}(~|3DeC84R~gv!27@5T+w`=e4e3gOVA&hdg_VR z_pli5sP;ZyeJ`Y3@#Je_xo>QgW2f}^%lP)#lUaVY+fd$Zj&d6FEEC_+`#F-DUGV3- zE)7C)GpF+}Jl>ItX`Ft~`JEQ0FFtimr+|ag>pMqJJeLuc+^6M|IeDdum8KK(aJ9#4 zF~=0u5FeZ|P4a_I`;+h>o1spD79m)jm39S?P>EUU@LHhl8RC8G*~|$xknJ>rU{yZY zvnX|8Iq^#QV7g#D&^fihN)&hc%Z<-W>!OSy_2gBt>D{IgHG~Fi@jAF>bM(w}?cV?) zqLwrm8Rc;%KLui_w*c!02GK`|UD8S|zUNkQ@Kj>&x9wp+cG{iJwm(d06egK&&e<(w z3~CwzZ`iqCC+3qb{f-7kX3_-vC#?qdT;y-lM2@j2y8ahspc@Y)2^US5ikO);gu2B5 zSHYnn4PeYIFZbZA;?uPbyDKGJY?_aLAzB2B;{X3Z8Fyd0RFGz!NNfzz@ zm$x4KDF(SqE%q~T<%$C^=-z_v^y&8(z4o7Qmfx|Q_p;cjHsl^PK2t+;@_|jN+JAA~ zy;p7V59QFS_3oSkd~JfyHb=~2{d=1Af2sJxnbR}Ie7O=~?$cbGRHe)_jz4Ms|BHDj zvAHbOn3y|Hixt=ZL({nY6Z9e$`x7Q1hWiN}`6ra(s6={GuZK%pUM}YO!Ws*80xT*39bdYb09~Mc&XKKM^ONDt%xewM>$#iQWOyU>!K}zEG!;$8erf*s|chYh>x*6U+MK)^i6ML2Ww+F5+{WFfT ze*jl$Ytr{MJ!A*1&=qLp@#eohwSP&LXV|fXhY_ciUY#&=7iC@F_Ihoa72V8Zf5UBP zlv3IgUgjz5p4y34@5=CrppOB7lz{Y2KARKA{8jgUqw0_b?tmN^qn(u5@?sFXe$Qvzhf%ryOtWLehHoH8=-dw&K{Ov<8n$pjl0J06 zcuSLS#Clx+{#-y}F~ixCGR@(SAR2V{h!RbY-E%Ee7w2|ZWfP)olSq3y7Z3CGv9eFL z*s|f-)rih@dqN`6KoD4_a47U7?_&Z2%k72ie6Pp;oSuaCIG}Phyrc6Or{esIHH~?! z#UvJxwcyNu3q(l`I;f^6o1n=?ThZg0N{jgLo5dbm{^N$%G&7kW1u`(FtpN$Uo^QB2u&K>)eMw0iqT0zj;f0+v zm}Y84xFB;dgta{dA9<#CtXEy7uJi$$;03b*j*0JA>?-l8Wv^S97-^7MSJDbIwDhQk zIls>Fpj6!U9JXMRO&vp61w*lu*@hpUM9gxeJ0|LPa{kAX1$;Jjj~)o+qE|HI6?YhY Q%g}!6cl#4%$2{Zy7wt4!WB>pF diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/PR3.png b/Firmware_1.26b/Documentation/How To Contribute Pictures/PR3.png deleted file mode 100644 index d639bd7e689b4ccc07b96f6f5c54c6a0ab2895da..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 73289 zcmd42cT`hb*Egz10i}oy5TvLms5Gf6RYbu;Q6M3d0MdI8RfvFs6;z~36=_KbAU%{A zP+F)$2oNA5O$Z^hPyz{e>p7n1`QCfS9e3RE{qe0a#KC6mHRqahu33I_?PvE4^>{di zIQQ(?!*l!A4dXp~*uZ=C{55od9e9#_wnz#1Z?C_x-t|4`Zs9rLm;KJ#2HJb}l*M!H zJYWNUKj?GI+<(uWL(RYb?QQigbl9_JH}CchZPQ@u1?ItbB7}^B7oo5XN`yCv3=5+- zz-Smk^E~lu1N1n-lynVdk9Dh4Kb~JIFZ%g}v;hBKmPgwTa3Ap4t8gmv9M?Go#RI2Uf?tUcf@kpi|6mz`72Vnm9cy!+JAUJ4o^a2;Z z^lOc<^;>uEa@kc^<>YA3^km7^1yVUJuKbyM?Oh-TGFi?h=?RxWN0lcj{WPClkSVFW z%H5OvXU-nq5fRiPsoH3!>%F9;VY&~y>C>_Mo;@Sz%J6-ECVg=YDrMj}#M)Y3oy?dx zZWjb5RaSZb`Rk)AR8BCjn5MM*0`(D7rrc_ei0ez-uq{g#|R%v7K$+)L_;au zd56QIMj9(K{vmK}*8gYkY4a+NRQ(K9LSYF^^xC=J8C&}1@}#k)rIdkzLHD(bXw3sI zz1iA+)JkFpoDsj<2h7Wq^)HSdBDif22BN7Aheyg`L^L$xgBRD|RI>~GCz{xfebiiO z6E}pVChh%sXG9oOF!>f0);EaNs1OQXhi2Uc zn+S0eidkFw_oaBoBpWC-hcPJe^*RG(x1o;>n}>w2ygrcQp?sb>LTsGjHio*HH-S(} zl^O0~M4~Ssp|kFTDEWrl&<8HHV;C56VXW@*km}zAul3k>yt`1lWJ-wBJJ+%J?R|1pnjf3&*zC zr&nxtDey#W?YhMzcDr0F!8tReMLh(HcQJ>yg3P`_6((kS+PaPfUQHTql+@8uG#$s+ zqe|-}M$_%;sAZnp1VUh2h^vJRfk2rqbT^koP@$x7VIFX`$FN=KTTE21A9DB6FB8_> zno6+c{l^4C52;2VMA8wyKk!DG>Vndd>mPDl<(m}}pGsY$w%r4@Ka{Yrv~*k?t^MTO zBkH_|520;3bd1j0rd?iLo152*6K+rJn^Sb|P9a)INM}h@cn<dx@$l-P|+$42M|k z?>gpS_Ar8ze3Bt3$gsXLW)MXfS_Zq7GJfX9cRW6L?C2_BFfV$7iU4*Ss^BL@IKO|# zMLX5(F*`hR#O*Ww+SuQm_8#jaF(+|F%zJaj_?+9t0-Xg7yulE!OC?ycA4$ zUjP`aln?B0^1D}5Gw~Q0MZX7RcG$uTHnf+=OwPLg#KJ!(=337wP3~)jaRqMib#7|F z$+GoyksAZ}Xu9^BkN(unwSFVV@%oUJK0UFk&61>^i1l)bv&`~c%C5rX^F$)SCR_s7$C5_`DAZ)N<9df3ULT74)N|u6V;3%hqI7Jy|#J8S7GbUHJW)<%=Ywbio+}-ZM$8tn(1(uG~>wvpb#oupawUs1)yL5|y zU3WJdzV22>TrZ*Rdyh|+!?T#%YL!I9Aq}5}p|by24m%nUB;oRSaPv=2Gbv?Am-DHw z#b=*WjcQQe)~_0VWk)im{Hf-lj5Sy1B?shWf!i$x5zZubPs>)K(76;$((J$^S%LhP z(4e#>S<#Q|{dq~|dyB=6#%O=kNJ5H1RKuKFLVeOcD}kNW_a8D?hg1#{!nr6iHCYoF zx3X|qepE~HlUWr_t=>L+(7ygstEpi7S!*J55i2AiHc!dRoyIb&$?XUq^U3QWbD3_# z`6d3ic~Nt%X`SJ4_4EDg&DSbrau5irH3{3u`{QQC|64oewR;L}#0B$Q^x&h_h7=wf?XzqOl>f!YYNI6W8>3 zqme*+LoR+QOR@@&?;M|LP{FxXc4k~M3slm>J5)B{fL+>wsXG=Tp$@NB&YTJ?yb)td``>h*|+F8rnk)Z`F1thC+qVv$8XUn2K$bT)?> zrr!!Wxn4=McE4^6W30_}D^w{ub+#p9XVTo$9Unp`vYZdgw&<9tjY?HXLm~6;(H^aA z$Zk&(|JbZC4iUEd5LO$6ZpNrdK}4X`%7%lVBH$JJ{LS}3yCWq~#}`F^SdE3uT|ptu zN>rLHYMOfE?p5cJe&rOv_<7-R^WK+YTI1@(vvJ*AVJJ8A^I~7G_uJtyX?A$$DL4bWOIwj+eZ{`kVv<>x&DU7l-G1{NFZkON;mZQGwy^J? zBfI@thKiROg}$>*WQUXL3)n;7keDxI{9~RAski9#bf4h-JTBml`5rOCPj(&yd+oxq z{Htl(l&kSF1$;ixE11 z)m#VMvCh$-u~F;m|88jrH|O7@A&F0tQ4D&9;1ZBkS`A1|@?|UO4Lp-^LIivfFTiC2S?CgAbA_kd>SK5gz8|CR=$v9vEUH*_1< zktmhd*f=g2lVmy89Vem|rSZ3x_xu!ev7HZn4JwosH+_PZ0F`1MZmoQH;Cz~f-HkZ* z4sBj}hqV-|)kfZBlJ#0#2)HM^UD&P5Z|>12V#VSHBB#sloqFYILgr;OKJ{PzannDn zQ8tJzXIf>U60yDiZz8?@y@&ME#9Ut^=G|LNpWMlDC`G)gtg0I1<`m{l{uVq*#LAlO zY-PRAguQz8>W!ntEPQigS5p8n?z>HWGYye2;04ujNLQJ8)&W%DDefg8kyubzabSxM z%9O`%V`2E%pYX9~PXPP5Xpo4Uao9|4Q(lGU(&v3EaF*C^>_Ld~0nS-ULRa%W`m-Dz zafY{L-e- zWU8X`KZdwxPxjkBZuhN~X^9>`M`(k26v416KVKKfzoz5iJGoYk56yv8^l^#_>2Vd$ zKN5L#N4uFIsOWU196c_LbCX0u3;C{tq(A=GgzJhjW`lo|Y_=uv6`qdy>z|iRkM2j_ zJ_uGbj{@n7|MTqHIqlN4cea%Y=OAB|8ky^){ER=sf0y7t+bvlBEz_3%Ia0UCvi6P> zu{)uNW_prd+1>AmhGC+qhrsXC(x!mqM;Vh8^jIu>?alJqTz~iU^ita!af#7ylbFdk zwU><0rpE`J%pr?;$=1(NW_Nzk$6fq~PQd;b0&*%&c`~^9xqfE{!hEH|1afQxx=SyGefPH4sk$y(FpclgRKh1yeE^O|bN^&i`<bEcw-Pndk7wWYG_>@20WjN(_~KCe7`)?BkXyxc}4coeD~xnUEy zvzp`%4%N({TX-r*WK4Q0d{Pe?f1e!JUSgSK|F@t8(mbDpBsF$lAGEFXnszJ7P}CCm zXjp=NjscaX1Lx_1Nr^xCbbRo|p?ie8FUduJDbM;fFp6y>wVv+x_E18Yg&_bSr2SZHqy- zq-n09A7Z(p2;$|730fiH_Lrv1=V9JhXP6b@CwH@cw!-a^b z8u_-6B(B_xN)Y;n9Jrb&D)B_IY0|$U{)Q!IRISUlTT))akJ*+(Z1#H}@V1KRRzG=% zLnvcI=FU=7w)q;Ne~U-cXdQM%;R(>u*V%{~}dVe?}*UTYjD*4eWzgNoA(R zn6MPESkLCSvw84p$ch8HvoBZAkv^|1;XtremM)=;z!FKa)G~{MfH-QK2}@u2PhPH6 z1kxa*R;AVFsTVf6&q8FBGKiXsZ)dZK`;kKVXZI=a5J!a9*P3iWI(aVHdAMAu&9!}f zw-Z`Sol1qc@ag+;qsDr#`FRf7YeVIgD)3JpHC%weu)8C=7+d9UVEZ9r&;Es*Xzw+P zurJYOzj=32++L?9P)XG%3yiY7{7^nGLE#zz4l?Q|WBF1VH^0Is)iqQUQ8Hkz;EX0m zmetmp&r`JCX4D1F`qd9t`WtwIdCY!QLulmNuHz`MaiNe!w+|@(c6?VOlRU_WK%hT8 z(Lae|#V6AadYv{3WlC+R5^txd^p^i+#B-49xs_wrVM{1$xOMBKm)>p+>6S=E%lhd; zq#=cu;I81^By8$>$&K%Pyy~lwR%fLB-*7Fw#ko2# z|H5T*jcx1%zF1gj<^17@mXT+0{l2$bA#vf) zyv2SiRl$E@NWNc6Ir9N?-VFQpm(Qoe9@hS<*xHVwy3>>;iN}<=!9D3$#ltoh6NW2S z9o83W{Wg6P(p6!1+?)nyqCikRB8*`E%!w1+{9XQq&=<`79s3h0PWOScoY>-%1;uwb zj@S|o?T2CpZ@aMNcTeY(`8^3mVb*m3GniKek4dz>;`m@Ff^)MYEl&?N2IC6?@0AJ} z>aDj{?TaR8h0L>=^L5JaE#!NiKVK%qjsRaZF}fncUc!1OJX~6Kt<>VwfoB{F5-%(M zx_RvJNRGpahwKS#p{Nm9%J)^vg!*%$MNtGup&(h3%cPnwMa3X(Dp`>-6p6yxLO;4vBifEX>W_b13b|vKOvm4BZnm}d%Gy~y%xmJm&F4y)!1S#Oi5fK!}5zETM{rLupjuj}h$y4CCsnJYlTMT((|ME$+toDkow={9@h?&QrKTRvt z+e3FTNzP@>(V$;&lF&gg7sWy{M;yYl?^>=%aQ*@CUG|r*QH0>$_o@K_`;l?>s~dSs zEdFXL4pCymve633(${e4qJ6eiRycmGUw^BSuOj~t*j~d_oSyPs*~VF0>B_U%3!*~m z!xK;06PGXbjpZt(NFPS&s>Y5u8nYpnMGcf(O0{$s5|yk8PGeI>@>eX8LLlfKgN z!gm*j?1}9*)<1*QJ2hLo3kKiR9ZGO;UA%IaD)rm+D+EODf>zPKlPzriE06KtURI9` z+QLF%nh;Mn)idrybTXZCIgO|nFPdOpKARG2;X2%X0NlJ&A}nY-le4GE2Nd>Uy((vq z2VL8&M{D=tOhBDUG~rC7b=l`~lW5SYPq7~d(!yDKRNt}6mY_^7+;$Q(3E~3Zj1?$t z8YneGDi2%}R`bB;Mm`fcP`j@a%?oB`D>d5mWe-Rg9DYA)`0(U2Tje8hAw!W#e5HIm zBI0|K#O$V%*dvp>drIs$EYYv=&ExT-?mXCv#fNSA+kAuWG<)rZP`+~b7RHa#is$=0 z-e^?zs9O_kRy$RHLoI$G88rUhyJOBT;|R8D5Vq8nwfc>y*o%Zc`GG?yK7IMbMB;?v8Mo*mvDT}fUo52xxYGxSh2(p z5yp@buV#|u_RhI=#ZZqol%jXs^3d59D^UAt-hYCL!_Ye?InuOu?Q#V=4{?vF#-tole{Hqm*F|(>6)ExgA271_XwXf7!#nJ#KY($ zHB(TffE&3nyvw&Mi>6iFnJ3$?FhAZ9fyo@~<^gLM6ee?XsGWrt*>N{ zk228Tm7P7rp0guy@?Sz>y$6=`+t&alOE$3 z*BOfAG_I6HilN*}j~-k-Q}p!1gWKvu2b*rFp_C>Z1*1Xbjg_P3SdHSF_2JK7J`wUF zlfe}pN%G)wAhl4s8uc;wN?yN_u8xe_(-*ORPO2!P^ za}!p+Y)>y)w?dY;WZ|QaefN@#RgZ6a8S|23w7erML}8&kUeWNGPmjD@*{e;KTDK1K zY(~|*uXX>>R{X+KtQcFgK2*#15li`Q#goy%Nf`UIJ$`H(0Y#bc;#JYGg|ci@-%tCI96~1@=hX-;LHP|*isKm< z+y~JK%I<^h^UCgB6ig!WqtncSRnK5)J(_|jKk8{xiU@S9899>URw$A-&+8Bdc?8T( z37J^2n{Yqf&yL)koDS1JFlU@xJ9q&l7OYDti)y@aD^-pb`_eTUWOVEzJ85ZN$%q=y zR%6lt^K(S)G24d^-jjaWvJ}CXaH}akCHyKj^9Yx4LAbt~M_nJau#8c69zu`4*YJdV z(YXUsP3O=6llwTpY>wg&JiJcqA(x7(ZT1qMaeurer`E4SP;YAog4;**jrea?Atw2z zrSlK2_Z+1ged;(HHSS>RMohMJ@NQKciB`5Ro#$>+X@`x^fhr*9u0 z_GtBU^;+;BBnZPS9FNuUb2T+lF;Nx4&^Pp>tpbM^+&?r9$rrL3&-J`8l0Nm)R;(In z<(DaX*C8vND2XAnmPxZ6atUheG@)}*)Tx8U1&ifm1s+?A@l(2OS7Lip0t^t;~X zQxLmWFS&kVJ5L(3&08vhYPU^;Xnivj{zq%n$JIN?AaZzh2qY0v(!BLm)PnErIS7aX zMypga-CYpf>B^FJU7aIVg$TFb9g?d&Gzbxko;LUJFGaL8gUnLnN^`Fhde7ZWnhHf@ z1{^&Pf(R8jH=2n~m&b(tmW=SJYW$&tVEkkE^N*xcd?fgXf?e8va1L9!d{3zrc+ zMBcst5sJjJ7yaEBlc6ATN8M&Vm}jwIGCg*6(V$KV+{OH|y8X!1XJeXViVo<}p`6@M z)Nj<_ns>eo&aE)+J;EN*jm}6uc^70uso%$e=}AHO{@dbHX=~t zJE`06530K-{s-6rBhntoSXSw$y?>u^)y(_x zD&hangYh2#$TK2?`_D`37opm&;Dg{lkkXMdvpLQ?<#$S-{|gv3+%dbC28sgxyUYRz z6ZH*s6!jmF5)4(+7+ zkNJgB>2RstRjJEu0$2tNwP*LoynDv#k+59G@W-tC=pNbM+xxPZEp@)@BJSdPsPfs~ z&ujX3?;g%g(#6lKW^KQhyF&3O5rTY)=3cM>B$jX#{aXTdL4?0|A66;HTujuDbQ6Yd zRAa-2&4a=|7Pw8{E`6S2s)e-5dhoYM6Vd;WxKmkB6pn<4^yjNYn`CUmZr0QcIVvF-4IZP->ZmHS^W>R1DchA%eM)>|a8_vRatku){~n=l|Ao!yPK< zS1frt2#w1`qL==v0|UCQM)zC-B=V(-AprM}ez-jSA~TDB2kB@|c z>lR=buiX-InNEIB;hX5#Lmd9!aw$JCz}Y@Hv-wlSiq!Mre==0eqHBOwF3VMQz~Rfs zc4^+x*ugcMjj;Y&*)w+hfLs*|c@fW7+a`7V@$^cOQa4*S(l@`sP9k-pzW@I<+epF}?}cqU;*zhXEU3H-+zxQ2aKR9$XD) zQ~(vGg<&T5nl+`OyGN!xDHb09Ep7%~w)=H<rNBET?J~^a-L?e6kn$PIu z|I$k_t3ZsU&1yDrp4K{~X0}9wW6C!kKNfl#gDV;--KgnI3%Vy^CiZ&X{MDxriu~1x zop-*Jb$bQ-z+7{%;%xSU*A-FoWFJ0xz*z0>G?O+bhpN}ALBxA|p08WL5{+`D>Tgk` zxK!GoyEbRw8#j?|=4HNl`piUo^P8&LGoGVoS0iW^gSFt$QpP}kvtyfFmXEB?!Y%0E zX6i}TvRU0&DZpNt95!AmN%Acw9pec@#0(Z+J;M}3CwuQsI&JkmDmK=ryPp=9{!U!a zDD5*Hy3D@?klSX>^i0CI<6q5cse)=J9z)+gc-(@sG1k> zMBpkMdr!q?O`;(oO6)Riu^%Xks3 z;fwuF>^MZhx-s*?ZZYssCuP#U{abLR{ii~lC%CeSbEW1~J zF)0f@eG%u@nj!%q_?Yk%D4U9GmUDeeyr`%1GbbJ>YW(DV(Gbdy|H2{cSoSD4&!UG}mn(wDlz~ZUD+|d9_~@!!JW}s# zQeIVg4>YI-%!~iRyR+(cvQdxZxWJ5is?l09>XT5<(oIy~ppd6#n8_6E>D_g;V^cQc z@O!N3aE>m@?pkdewMZz!sWu6gSYWtaz3XlS;sGhEGpCm_RzAxGw#j9VUEtDEmu`*A zcx&HPFcqC=pr8a<-&9m{)TL^d8)nQdYP5ExAkm(u)_=tWlR~4lp!;#-h$`6t68h6` zNpNu>k2$zOhY|=FI+>g8`-TS(K1RcO>;Y>0IjvZ$i+1j0Qi$6~$7twDe*LyYIgBU4 zL(7VvoDV0#0~&0%$0=_1i_~QHJ_)dKt$HQH+MTC z*s~sZ4+if+Hdr=0J`hobZ?5J#{46aHU!{g-3NE{EEpE`1=*%C_9ynRd203|~FN|R{ zn-v5f+pLmB#dB>=h}(~+iQlE`bwv?BW+5Mrik?Ji%1+M6B;^q@j%3q!Y(eo<#?VUa zxWyaGab=vFCEE8gCpdYa?Fvn!nC4EOi*2Nxe}6v;^hLBN2Ju3(7mj82IPjS5;%&kQ z&8u>GHgJ_FyHg?^Va1X}%pz|rP`TlS{HAVPJ@R^NLgf5NF?>(;SJsc(` znk1P?ava>6(;+$Pdgi8I3F)Zi`7-|N_;ON$77o~TtE+N9LVAP+u+@+#L09le-}tO+ zq>rOU_U5J@YBrL(r4;#*?>UC2$*|4}MJ#OKUH05==6{THd{{p)A@PV_KqXdf*(#f5 zjoB+3V+$0obQ`tCn-`2l`h8Qv0rGtEmjRSNCR^2W<5GBVo17oTrFK>~E=i4sQ4^>c z(YQ~qgvO&!vLn~4U?YdTkEq=tIzuF)m+*(GM8hoim25bSj)7~huMgQ)D(SG34xVnhYKPA@+7X%uT+q05QN#q~y-OS~6hh1w?*doNIy9Iz1fnXft zFJ3<6=d<`u)#|ljX>Wru@1)wQ$RSH0>g(sci00tEimz(Du3-;#ygSD!XEl=JgbN8g z;mQ%e{Q8@#^iTj>wuRAQu*8O>&A8wcKh#WyABAa#6icQj7n;OteQFH%_-dfm;&vit zq`Lp`b4;8z^APelMPB%KgvOW@Uu z27uq4+90}~(JS?W{?sVKsds7g{Fg|=lFIpwXlDmIPnO=;hY_MfZ*miC@tq{=l3vo_ z7CtEyFVTImK3uts_vSp7)!Ku9x3Q`rncOWTsl_?ZJzF%hi4BNX*KqXpvH{D!7q|cR zxaZufC$J|~CN2?0?jM~rI3_}=@}nhWti);qcD0q9U>Vq8uA-;AD_cd|h)cS#y0TsC z*Dfr$aqrU0Yr(|@^%5qX#fza2`}~8LIuWUP<7*oM8P{8(--TvJx=Ys5_v7osQ#J=O zaE+~KP#F`nJF!;~>Ip4BmoR;>d;$M$_lb~sg>(wmqf9?UWmGpz<|t~MV)G)gyrr$n zY5baC^=EQPYyIlcs`q_5)(Pf!*D7bX$Jag&DYrF{>o;a;#gn}`HxRA2c9)oxdZ%%i z&=p-ovq}L)KV%$h{d8z~08_5?&TDmQ2J#vM2_h z{5O0RZ#=?7#}!2WvTZBTe5g$R6i!0##{XL~RL!nPupuraY;a z(n1m~p#d{qxpF5;G0}vb;*Cfgk2w{yu4*gJO+(3@x=`-j?x@7HQh$aavzZ zVQ9L#%1_^r#o~>f98OLTn^y}ueGJ;NPM#`!I9^nAlIas_!X7@iy%Js5u$oQkd%e6E zHWjw(Q@L|~DA`<2Yq2ZLO4qFCf={~ntC(K~;1BrCW1W5;B~IScW+p^oEA9rLRF z&dO<`D4}ndKR)C^j^z5rf;_l5b$B}hU&XmY1CFx5=u;gUt)WEHW?X7UoGl32SH8pOQioA=f1psN?gIjZro z_%uI?tB8eJJu7Y;{^icE^!mvYuRfyWR$WK+SJsBc;Q=8>#!DgREn`d*SMoF`I5#rS zQys$d*SEhkG+?A>@&@9hs_1(`mk=}YIgnDJ0dFy*h0SyvV$i(0H{}ZNP5oo2`R3e( zQzp%ZAe+`!U7lC51wt+S^JNIP@Ia0A6F_1(#P>VB*l)>dM(X12qoaIes_IcVgm~K> z1ielNWk>2E&e3$18O@e&qeEaX96O$7OBTD6Y*xG}hbX@;I+vdlOo$u(qY60CjXE{+^208q22jWK z3F=*J*jMw$cYxb<42uG3z2o+tl{>B=5e*{n-doiTd&+J!5kxro7`aSudaazEMf)m5 zj%c*1@hY42;XvY8YGFV5RjAF#1xsf0J!R7Z>a>ORtotdU?*872d+{JMjR}BON!nLz!I+=;n=OxowSoT#upMwilfh+Eyqwr%fWl<7-9KO4#eskItVsrZ5_D zcu_ihyWJ||P55~WIAoTvLI}%BzIaSFhS%J0!TqNe_qzh}pl9&xbhTsfx6m9Fe1%7 z^(3-l%2%?djvTl)xLL|V=8g7RT)o*gr5ps2xWB~ z{V8teCKlpRxRriqveY?7jdH$vV%-XV$2B%#n)@8={G(!0d^;+HBhRT@JA{(4Z)L|j z2;ZL@h?k3{y@LzabnQpDWwA(80zHdsNz}Kq)}t~Yla2QmEtMLxu@*%PX;&M zp~zOb=4Qw=hq3}=f@7+TyghlEpR-PZ14&+;nG1el&9slvJf(#pky`Nm9~q8V&0{UD zOp}&2dtR*zxdrtCYuwyb@M*<-$*B%UTKgAgvDdK?A}nM0$_kr+N*Xk;A#RZTtnK?Fm@wV2*{K{GqogehJ+CXA?qPZB8+WZq z12D>4dsNJ1dN*&2GqbNb*YO9cUHiRPiFT>bNlx3fr?JyBQq8{inHzeGu%*w%rI+Wv zS$J!4%xxi-<1cUU4~N547BN{9DNQGCOs#R;%;PMa6-? z&IIP06oB4uJQQ*!bi)Skdo@#Qlk)EGYxj$Nt13JHa`=@WF`U$?Qz$C3{zlq-{H$7_ z3On?fts3xSU&rjLXy%w?=JXL%(83I~lBxk_&>A>xMqoL|)> zgys#zVJveD-%bBksA0^NL-L?pL8F&Gs13!a0|FU!K%LL+FyuAk1=^Mv6X1QpL=c%M+Pdb-$? z1D-P^BRFrI8brnM3t>e({CQYS2Ii{*g}3M3-0hjZRbv;mC)I$D45^|DSM=W?akhM` z2)m-&;o$DxSf;|KdBQcdx|{b-g-omRArkFfvLt?I$qK7wkje5LN*EZoe!j|@oXvBy zX6?v^?{=NaZZOH*Y!;@3qF>*n#a-wxUIJ9*p*YLo-61E&dA+MTYc0Cx(hgy~*rsCx zBC=7Jw&P1^l;C~R%=V=Om%R8)B$h1euj6o~By}S*eBL0{kvjQp!`-1`RdL@DwT{M( zwVno!{*fcid%y5hPXix_WU7Z)jAuq%^J?@juN{N;+N(KGV{)Bb9%ai@xSm9 zuVrBszvP3Ucu|dWCohX7;IN~oFGrARU5uG`OyFMTmvI32wz~sE^&jTZsT6Q$#);sB z-vD(^JH^|yT}12RShHzZj;6*=NV%c>h++&A@SG3Bd1;ght&&!B{ZPK zE3cnUmu|wj*B*v=pI#TGepY&c#&ozkdrH1owxt(nl_ZDIMBehekAD_djcDFG`auJ% zAr{6EH?Oa6e~jSLx+1+#tVj}aQ~Jy=hUl&Ew$vp4Rnyy41GiY@Y2fBqEM|#$Q@iMg zuzJ8yZG^=njxDg^U-C_23+E4l0m^p75s@fR_$9)lSc>Bk07Wo$=BGI}Jm{?uCQf22 z0xRQ3&K>_`vv?_Iej}p(i7j8*Q(zUr3U3n8N12=LNArFcZ!nR8VE^RmV&n}X9Fi$j zI19NMKw)rG=8m##^=_ATgmIN!uKU@%(|fLbw$ndp?$t~bL5u;EzIo;Yutore{rL{a z9dZMCK_a5pW?g$gJWzsCq|1fp^k4%(g8vI{Dvum_c5@#HWK-9%rc3u~yG`Keyn+yV zoi<)1H~?G2fdMyp*WP}65p`q16+o_?lvt;bRXfp8ZXOVc@%f^qS#Ts&3U~2?CDHlB zFPJ!~m5g1-ph&@{p^m}0mb%~ zPyL=C=6@HUyNA&6 z29Qxngvt@bKj1cyZ<5b0H*xgL-_LYzu^8eP5|rwb|C)WZ?*oXbz!FqxTSxG;{QKVz}Iqe z5uvva|GQ4u3&8IF9sl!A?f+)#|L2k_YpwBy=XwlP+#K{AdJJ92@3O=U$XHglN47+F z2O8^-+;fG_)|F2)_=&J?)&44Lu`i2&&-!gM>j#uC4OfQ6SEQ@SWm)YEboOJj_QO*b z>*p#dm+zRZ&J|?cv7f~0PaN_rTnjj7W%-0+85~NDF~FJ6tB&}EAFlgzuX#w^3hVl! zB3(l=%j#tekA4s<;M^1M5&v$2wbi$nJ4R+5m7to&MPS`JO$g}IFDB0ahlwRu<etrA7cc>#+ z_d(ACc8O@oyQMlOFEXp&qKlj81}rLiw=8l<8pVyn&R=cfHo#eP7UcO zyb`d&19n-K%dL|TZ-07Ue}>i=@THGmdUU4h*s&;rUuOKBbP34K1@&K0 ztqTV-FRCB-cJ4Nzm%7peEM`;!lc}cf>xD;nM@z$Gy^&BsR7~q}e=Czx^{-o3Yit@# zJhnz+9GG7_)J8Y!Sbp2DEv`;M_`S%Lua>T)2`sJ@z+u;fCMiIZ(k`|rvgZkyM^JX9 z`o%8Vngop|tXJoJ#m_smuV4nI>qz7~n5sK^Q1Y<9KpR!79uHCT)^6WQT&u2QwX)j< z{qnp|0!uAADsb~!Vi>H;&%rDHdWVPTFKuCSS9WWT?JZzWjI*u$?km6z=HloJmF?$1 zQXHC~OvffSqJohWgt;S5U*RJm#Pjv>4EC)KqiVdFwfEbkO$H$Mp$Aox$JIt2UY9UJ zCW)s)a|`FRGSE%E2M<= zS2wyh_2+iAPQxR%Vn$bdSZ{12Mi{F8nExSMQ`~$F^K0}qf3>h^)4W4x%ZJ*5qEj?q zc6D!&Sc__tvtIaIG|5=>-Ble1Ud~xKK$;5(4L5F}Aj_71%E1KITI_w(erei(K= zE(cp*spYs8Xz0uXj+YUZt!9nEX4K(}>k|sQwxyqQeKV^UR>!v*X7Jx=(;&YE- z%%iK<)1$)}H%^6&Tjyg@W}mNBYij&3VEZVd&@*uusNe`=B~Wm=S8+&%X}+2+pnOkutPYh&>kVgEkdxy^{Crk&3y5*bSg8PN3ZANGZK6 z8o<6SBsO^JKnx7qCI9Zk`YCVL5Z7SF0Wj0g@!<25?$gOZJPB9FtJ!A#lnqLS;#Sk@ zWN~Fbw@7dc{+FcFa8XemNLEm~TD)-58zawTt=0V91y+W_r^Slu#hb%h6JE8G5m0#D z&X#yxo?Gix?6}WZ7WIwt;ChfD`m&?eMoZaf{R>GU$Lyr=#`|eqYw{t^O|o0v(Gd;v zvsue=b8TODRNsWFoi)<>FpZjAU*E`^4Qc~v(TUjk*>O!dT770OaHxEhm->887njd; z_OKlk$`-vEsD58}c6b7TJ|>q7T&;BXLI(Fb z@sI=MP)VMW4Fa<#9p)cVrk-bEC7lDbnMl9p#C?uUNlsVGcQr!hk!JWu!!nq&%7FEw zJYAN*@ku<|?RtStD999j<1U#4pboBr)ULEbd$Oq(gP2hE=)O-Phe6yCx{_ksYKNWm{Qf!9J>aLw9FK#XD0BC5jZ4uGUn&!%m*hs6NCE zF1IExspe;tr1eCJHJqcQ#o>=knmgBis9I&F(V0YyLyeU$@hnYa=#29~5*V(H4^!Ce zpiC9r91lY~Cca!6hgTbZViCpJ0BETHcN;ENPT%O&_&dOUI*)T zyxP3_t;Lo;=NoE3he<=i9STO5SE+uj-Y2JUr>ua=2^rX)#WQ-E*KkNCC=B0)(ORtv zH>7wbnHdbZX6;U{%-d^Um3rr8{zL1YlzMW$X9)d}FzJ-Iq*B|Y_&n27vqo?5;n4xU zMbf-O4%5Ts22sc#w=AYJIXz5dOhr1QkWkT6m- zg(6?=x%0~JYw5Y8U(`Qs7n7!*@2#vI4{&vHUjomcAZNa%QPaUtN#iU&)C?sEh-mAQ zmqn~72*~;5Q0CEoa~-wlxg&!6k$Y!UIdBN0a{UIPno-7aRQ^@#2C7X7Nhe-2(^Awr zh*~KmR|4;Hj@)P@JIjXJY+K7WIKfXdcRR^@iy8i$JwH<7R437qX6Y4j81psS5{}6Ln#u4( zsL5v>May$4mOpYpIS+<@UaID0izZN4oVCa@ioDgT^T^~@N>pZHR%QYlmS>(hXIL~M zwswX&_4MUVs@CotoyB-S8;InxJVPH_OX((`Q#9I~9<0ylSDPXVVYnu$N-iN%VZDoJRd^&n^YuL+t^u!;d7oV7r3G?#wvPh2`kL4nRynG?^%^@KV>b1|ECOmh`kjdVahcd5 z(CU@suSaZqv9Ix5mh$!z+ty-l?Mh#5vvFRIn-@7kMk-)ivYuwBLwmRD`|2`{p*CI1 z8z(Rv5do*u3I$pq^qV5|A1ODsuJ=n3QCxP3FDu;Q339ixZu2;O+kX{Y>h@Q*dkf@& zmFuVdYUU%a4V@2~kuw!!%*l;KerAWGW+=Q-1U^*}t4Zhl4z=iAL-fiFd>u`6pdQ5T z=qY9;(IVz7Om;yV#5T=iZPV2u#COfsB=eK*YOD2Clf_uG>hMZ+^(OCQtn~`(9-m!d zfQ*##&@7<&N%A*vX2!p2DPnf|7O5U@1sZH>Xy6Nw&G}afb|Ej? zLa1e-8QhsfUyYU{zjNOU710D^r-R^xoNSRh{9NEwZD_aEcfs{DGRNCmqCn-mPojn( z=EqLVPzc$eWWGaz3EHl{P{1561au#rEq#>~>H=~p)zFyDf`7DbwA=dDlCA&7mcF=E zHlF?;)3v^Tj`gX&bTTd^Lqfj^R zpO>olb8n4+qE9dy)0a9tQ-hHYC+n)&wUIGsVp`@4XCvAh8MPh;T@3XmD;TCxZBY$x z;~m#U9b7LkcVoAaf^Q{UG!I)srEeDAiBO*QDP~#I0Ps{Lg=Lq%jyb3v1Y>L{#f-9tc9` zixgCmxEx2jYOrx3j;*x6um4PHA*X4SYl}vh5Ym~gWYyvBlI68yhsrgLU28HAKbYPg zK5L?0bwzFg1nW9*0t#;Aytz!0yRPQ9ICfb2JNuG)@K(=^_4&ERSXW_ccNzgVxe z_R*~8Z6*KP(hLzlYL;2TPzDvP5MCAHeStGm#ko0s7xRlKVGQ|8`nOjB%6+QI4-Cpw9~n4K zG?>Ut0Zi}53t9qGwQtuI2$PgKw+ zLoLGB#x05Nqtk-~UapBA3kDNW?G2W6MrgV{?b;fJ6n+?q zf+Xmnd}n7g8NbslXI>L7-OEoOxk9iRh!wP!F$>$i$G2?-rpsWp+fOb!x@y(X7_Tii znCU(P4YEHK<-06JR@s$Utbt;yg!Z70^sn$*2x1vLbaA}vGFqlU+kTZDVw znI)dlhY+6V<}DGqDXLYYePyNo7l!nl$whZ=Wvo55PIR2vqVSR!=r8?yt z?N%~{^2Hl@rM57Eg>=G(@V;iAKUzWmU1pR!uHnhsF`qbkaEtQpgEz>hOLyuQ(joQ2 zGp?f0A33r>ICS()Y{C6Xb_B!jI^S`L=ePr6F6ArooO6GsT)akKI0A%n_g$E+FJaKv zBDO{Sr0>~b=UTSs5F@bhMvwOK1!5EqIfZIf;6WYb()v-uj#ynkK7=2#gR~A_(;N?B zCE`TRe$;-fv5ar5^a?C9y!!cTPuSWS)OJ!>g^Hk&Vr@daonp9GD}#S_c1Y*;?Zsg7 z5Hf*{GhD9Z)0-J7wscP*0H%{%Wo^9Um$L|l8WMr9*7bN z@2cWSYmm0lD5|%?TTB(!hK8hsiU)E<2_t~VLMe<^=aFM}5xg78jx6oSsGQhJa^Jq! z7XW`=Q>i2}su~5MuZ|3it3f>pR7fk?+$HFS5ZApZVm;ldx#@^$Y0$N^NOo+u;-VCt zXD8L_$@F@KRjYZWjc-WFyze2z^-MIKpoiDq6>qg_izi=;{|9Ku6H1LiKRCwrB|Qpf zHxU@~^VY*&e+*nC{Oqx_2ItZUkJY8)j4V}aoM{~d(-bpjbsttw7fbVNhFq@N?D_39 zJS_ZH>-1O>P-674H;D7HKD7_t_ZrxkcnbM93FB)j?gHULjWd|Zq3za#FT`BxA_9yC zSL`1Kj7LAm86^;Z2BRHjkGMCJCJxH`#VW=DyTmKE4}HGP5DVF-IlIG$I136VGt^~x zKe#-DW9H+>L!8=5K(lAP)gH2nE)N{V*UmaIK20p_HYz@d*i7_*@1%rwXNHH~f723L zFA{*RSC$k>_exUHDotG;3n&V8_`~hJmDm(SNBNqylww(m-GxkfE*s%&saOjOV&69s z+LI9p#Rf%;O9^K?1WVUsO^ToLY6MgY$_mT1<3&a<_?Ze_DG#%j8)xXMS=XxSl?{kW zJyveNMqv-sm@5w+5U8-^tya==NRG(#o&GdcNFUSJ`EBtQ3F0UCcF|CO>=Q^nTZP_X zrR`hY^2G4cu{a~_druDHijMnCbgq?@*_i1?>f`zvHgCpDMNP)0zwzX2-kBC#hDrM9 z9C~7wqtZcn6T9w7a!~Q8%|@Fr?O^rvhTl6Eiz=-N&yFsXTP$o^4Y(_L&`RbfGs*DM zHz~@b#>s~x0_ID$%9OB%;*m^^rVdWFmFh`k()5IHWzV>Y{yF!~OaS(O0HAYC^C<(= z1vJ^rW%tj3c@%COn|3#!KJsf+kdy8Bi(==q8kfyn6L9Ry-6O%qvpkLc3kEsd0N-&Q z0B#F?d|{p!jAaT_VYn$v(Hr`Qo;1I*!<`U~(X^Chu63#l9XV%ms2D>NUl$~F_Doysi<;Yc0}6eA8J2)$@0C3oL{Q^Gpj%l zn@iY(s{$&*UDnD)6y_#HJtP&;F0UqbcIow^(j^l+rB1pyGh0?wDCx~k)Qg?9H-Vkg z$${;wK0&hW{zfA3pyA9R%V^fT!71;!)JbZ|SSiothS}wroxsA`V4;P81i1*!<~$yF z!z`P5AwjL;&QI>Tk%+rJ)WFV{+T9mxmsN9U`p(BDxjP59y_0&=*I8`!Q#)o(+J0qU z7$81oAU){-!}h7kmSKN7 zkLeqcTz88oKR@dPrOe*fkBF?qK^{|aEQP#i{ig9wlN@yxtfkSzh6rh0n`JRfmVp5) zm!{e)+sN1olv~8B)sQlJg5v^OaBac6Xfd*1Z;@MyXL3wCDi`mB@1Pz;(jV&rY4{?5 zj{D(0ml48Q?rMZJ_Kl_Fjltj7_!=%ghv1I#wjS?#;b~g7z!4FYKlMc%DpQuDCVDJh zOt>bR%zIQDf7e6~wFH`2-%v%sd2oLgcK_4+O0P!p(MnYl>R&O;)15ps^ zi~YBBKYsa8L8hkxD6DM$!#sM6rMBD|ZNIgZGTGvFAmsu1x=^-FIhjyfNA6d1{YZ2Fx<&4nOSfz8+Zy+50MOfC{dlw81?NZ`TXfE@&w8L<>hi+8QuL(I zA)sKuA3$NRH>|W0XP1YB8c$-&8q=rpAOMU4U5&}>NQbt6^(Pqx((S4RNgsha>=!_2 zv5Ft;xgH6pS)tNFa_d{!AoOz}*)jk?a^EKq^Qerqe~)+j?PsCI-a9~&-Gk9z&l3?t z?B%-nZ6 z)uy_eG#~-cnTjH0QGQ(X{8E*28tEH09)PEd{Dq1CW@18Ks0q+IW+`gKxmN={W&727 zbq@z947z%#OLC}N|L3^TC;x}z-tuR;lqztYEpx|NK5KkHxr|RWj#YYSfoCjv)HnZt zWmoo8p@6Wz5deArj(qRe|0gq3|Mzo4#h}$$QI#9NjS9+_cR8-5jM`L<*NvX~pM2hl z6DC2yy=R?$Vm{pQ1eXLv|Fy)hHGpH?{{B!&NOgv@>-fMIN*k`^pTt<>9yR{uhfWqp z!r_~i{j_N}vww^?{8ME786U=ip1O)3?>vpX|-@IRRyg}uDrwUk4M zKHe}3N*O4!{LI+ArxLtaC#W*I_z(aY zWf0`L1-FDl2vEYF*c<~OG%NYtG0eJ=Zc+qmmX+fL3cL_xzx;f#_+PVxWbWPg86>;t z>OMtOLkXg%X7oO0VPhdM%B(NFs;1`7x4~O(^}fdOK#pTgHC@fy{xR7U^<)TdVz6C* zf2sHIqH1+^xX`4q-0c@zT z=~L`6ZYmecEpiPgl`6tky>+*Ca6mCDvPsB%Pa`8-9dRLLXaW%Nz+IP-xx-}!(6u(+ z*s>a!Q{A=Ce{pBP3vwYg6ti(bY3c6rg-G8Y?QxjFJA6-wH`7N?>(kC}(8A50T6EI5 zj~VyaL3U#bvxi#l^K@p3(MVrNKrZUNWSZvsh`j!+f@&)4xhHGv%jX8$CC_R$=OQEscL zHl5|TG)*u-=-lci%={GLPJV^p-o$b%wRf@&%%pSd-uGg5S9}k4%cy~L(%1oE6aeVa zvW>{U0u_%rVye@zW%r9mXCM{8)kfstV=-; z-OAhmCTK7I=wZG!vD}b)?5$h@oeb{wPpb)?-IMhO&0A>AweO8;S;Wp&zWdzc_)f5f zwdt2wlpn}Ul7FYoaglkJ8CZ6=%;MfzRd2YgRLz)c8dJ?&6-tqvH2WqB+10w)vL1~W z9n2}(k3?|eLM60E;q-b%@p0!UvfpR5ut|WAuqX>Sh5?_pTCXm8=7XewfDOK&Zf&~Q z=BY!Ko|Cn$qK?faynp(If9FOy33%AZ>bYlxkqsf)lteh`XJ?ZEhoe#J*<#@dqvoxs z)rvvO8X_fcE#J0T65O(_#BhrQc23Z*Q30eEP}-Nv%Iw9Gc4m*wRzKol`?$VQO|yc% zJ8TLXimUkc>kkkte;0XJFl5AcW%tHL?V1m`l$6`+oJkOdOk-vgYI>gIr-~+q%fcv7!*6~ z_Z&ir|jV~>IpKlcmv~BW&^vr@fD5p?drnA)l4p4ck<=UWI}9W~ z)Ou}=;nH1;?+82lT_a)I-gWW%9Wc+v`bD#eft|6A?!ZG~OTApXetDCY_HsBG`JE-g z=iT@0h_~J<8seRKWd6~0U70uhEk9LJ_)7uV=cimfvY}-Qwj3>SRTuXyOOChY+M0UQ z4-B^?PnC~SuC6VcMMlV-BDII_J|)2%9D{tUO$o5*?c*VG#1h;22$M$LZMDfIK;>Z= zzCeGsl5u*chveQ9*snCJu`@%u8@W#M*bc}Z+P+YZUa|Nwde18;TmzUoqdk&KGG|D^ zPc59WniZ~MmDnM&C>tf$^Gf7exg467u=ZQWaH;JsGIT>P5DzD{DIU7HdGMl!El?S{ z%IFt)TQ1T+5j5dq!<(_ZYximgAU9@is?y82CDCHVJK8%yY19}91rjhKVuNrg}*1A(J{d-^%bo*^?%bc@b9g3;=x`wey zdqi~boc%;sNeS7*1fl>BWbu$5P~!We6*tHGxM)?b`pz~-0!y`&rLDGFKtP&2YRq=b z6A_(CNZw?w#2SQ#Z>Td!7lONf%r^EUg?U<$plREL>);2v%;R!rkXyCuG+@Mse?k>$ zsdhM9;S8P=CNXJz0IhN9XQbe}D~9LWS)^|y>WJx68G>mrK%|dGMe$@;Y zbo{bP65XsKUSYQ|pk~WjPQ49IHr?Gc-mmI^ze)cgNO?=eDUADjPaK?dT^(FPORr;3 zQvI{cX4EKjqlVYq%f{>{9dMey_w4b&PH{#-SbxT7cDU7Ofd_lXXRq3tRCG6xAr4IW*bTN$PdTHyv=W6bi;$1SoVkHAQeKS(7x@J|bE|MXVTq2^h)3ov?U?$c%+T2C* z*{wo>qoQy|)BEgQm_}pkP={*v2W7Gw9uNm=R08 z1D$|^onKE@B_EaEGWXVKd6#<)c#iG#akY90fUS5+D@yY~rGxTmJM|@TY+o?dzpnX< z<1Y`%KL6bT7@XC3e{FKca8M(ByXkX!0RMKNd=N5v5=?7JV^BX$Dq1-a_>nPZx0I`; zssO2`II34drA4UZvkx>_zn{rxR{f~+AEpzR=`_g^r;=Jg?<07O`7!V@+F?R)A-|EXONjQF5bfEf)gOvr~{aX%fK^FTjS2 zL2eDPWb6Qu|} zx$3Y|h!R!go88I+M_~A}Qjh+10+KLpW1GH#_1`dw-jRuytTJbjDP zy8ctU^CAs9z^d<;CQqKbV9V-^2t=4e+=V&xl#k1rMb=iTb3M-(klF8BohSve%w;gnqEn!lwOKEXgnr*_bJi>b& zk0r#O2G(lIRG>z+eQz_f6%nx1(=E4?Ef)})Gb=b7f4|pks<&)L(cQL;ACLs_Z3$h< z2!{PgJ2R@hw`MQwtywtOs&yYOydi8j6OvZIctYj~N=*_uImJ6}OxDr2a|~P73uL~j z0qSh7n23QNZj8-Qd{=D{Q#_|basUmsxyZRCzvI@kU`^#MhpSKGo{K2= zGdkQ)Wz2=ucxG(u&U&ulUMA?`YRdGd?5eFm{r@^+wm>cCoiL%I!L@f7cr0s!8IBVW z-|xEp9Kut{3T5>Z*76BMlwqy?l0Rq$uaF{x_U&8;f4i5SVy_C9BrgY+ctn1rtr4+3 zzpEaW!O7LJ!Y7b${@c)Hii;$#Z5xlq;#v~r$3mwZw$yp{j5IH9#J$=z_8}N_*K0%L zx)&3ZFaJ0lq*Uo$uwe>0W^Gc9!hX9c8H`fz4vMp#hBo%e4*^QKd?i?G48+V;q@}q> zo}#d}{Fw};tUuhG#BK&BMI1!?7GClJcr_qiwcV*|&Qik?dikT4ECp zkXD>Ro}0H>8x$vU-m-RC@@cceL!5lNS1ICVb=>!ZiO9181Ih>rmubrrEXudA;K!FK z*Q^KFMuAnk>US=lp0Jpr=)pBg!SyIyoh!DQ@bqv$+hf+4B+2=<3g_q;*zFXCmY#JM@y3vO zE{t2jhMhhT!QKNw^yasW?sXB&J)4jj6A9(QaL`?r@JZSo9Dd5#bdzISGIhk0?&w6^ zvBUH2s12K1!&1lFJ!jl{xggdH5nJ#Qr}5UAK8Y7_0KE8%KKugWuD-_0I%WJV1xlzN zBFCftK|+)OBmIjobe{NE=fw2g-$VXi04)A5U?~8Nnc8*|m|hQ~Tor-aj{8RbSC9q= zRPSKCCH^CAv+tSB{{L#+?%Q|s&f$MW*Z004f9t;rwEOlYo_PLO!RPOh&)y#YM|tP( zC&w3dXa4@N_e)g#5aPcd_VJ1RSAluozV^fazqr)++kJ?=I*#8^i`5% z+b{9vM?Su2kn5@pLw-VQYhHLw4cyVo=J+@w?QchfUR9 z4pami#_3y*3+i)(R^5gd%B2ZmE&wOGX=LBs5Vy8^iPzwzc}D~cygyhTSP2xOBZ~8? z=Bs5$FY;adD?myjMClL$ec(Bc`%!IIrmEiAC2om>+$C9;AnUcA(RQks0#lVbhiqw! zGUJIH8*zw9*kp-~WVO^n!TclR5=q{I4updZMLI|g+Tyk)oxZxGIufp+&Bkkljjz^o zyhBB{(@3aMnKoHAr@dwP=mln>tz5M7S0MmG?#)u4VLXI~^ZC0zG5MB@P^c+D=JqXy z@Z%xaIi2nHVOemYq%(i&U0hkDe4WHlrtATXTdjoWwm6h>jvJNiYQozwdiVM06?YQ8 zy(&fL`TULU2g-;$@QL(`*UutTah7DKs3!<%mQS93f8u&}^n<`TU*ieP2&$xtV!z*VxJ-(hd=F%Wv0YaUDGf zi~@=@uho>Ta!U*<|FpXheqh59cuq%uXcjk&^PDINwkzAX9@&ADw+qm@0Kl`_uJE4h z-4d`wCKE88|9=&lZO0=p`YQwh?y@?&%Q!@T3Rqfk=o`f_l zwRc4N((|A_V~YV3o&vm2ZicvgxS*Vwc)QIM)f3AA+nUDX#Sp_$t$ai z{<}xLbBko(<1R(hSLmkSkXe!^_(yWKm9rCX2T{&2xjPqa@ zz?eSRy}7Y-nH9DCF^@$=vEtXZi#iivBO2KnVp8ylcRV~7$yj-VvZEjXd3sjkTWs?) z9Jd=guP2A!UPt;6^`@hOoTBWiB>^})K^^age#@?r((!(QVCV^fs1_kk`2pyA4ZeCd3h;1Ttp zp8El|8c>U}dHO%KJ`QHRv?gg}kMxY6pk2!jB#52ajKm@tPqsK3; zygLpHXGpb(DvyC~OGvvVUT-i0UQ;OdZ~3fGuyIxBorm7~^zRFL-4)HjZ#kQ{&oZpa zx)D1|N_fkkIWi4L{1`i(mGC#GSZn z?Uv+OsblVW3n0_fdnb**nONyT!$Nagw7r@m-s@YNNzZi0RK~f4SPFaOyM$m@MA*&0 ztry10!#>l6>*kMPYEWbgx5JKp6A~RJbhXhRdbkQ1yzFS-jupnOuC#nzIXD2l8*ZSb zLa12k)zkXii(=4`tY&Zhi8J0w=b@nG?Apw4!QQJqM*T+}HhDfD&CSUjF&DUCl0!MF zof5o!-L%b6Mv3!gym*CwVJ$_QF@xu{POMNy@qv}7HNZ4|thM7nkdUGSifDku)zTCF zi4DtvaZ6!GloP{mkn#83LTCz@D;xfM5BqHd@~OmOO@*6WvsauS^Kc)CBJ0M2_qV0K zeV6HH|FX50CpDeJEQR}{tRj}9cRcmjW9#sxNDEi1^z%@I`)Nz~!SkRJi$KG7`*Q=4 zyusa`^1;?xKpF#8(YV#|hcvdy#&@+CBbA*3ytPTnopau?nwGy1&7eC&yy3%jX5%OM z?mLE2{dgYgIi#+D4PPtywoWgnxOfw}P0{XZu4QKqs}2U#R@`g|UI7ImzXxHx8(9Dg zm>%9iw(6-_wC+74N0$m;dbrGtgFcY_Aa??pQ<_#D7(=3;<-0$pdU~e9%0)%yk|7aP z7m)O@8+w_53c6&7!!`x_dpr!uA=Mu+f?s(C{^`1?6n+uVTwmls)Eg@wjvdf=e`Qg~ zaw$`E&!U!vxVT%B#LO7Tyfn2tsJo8vVRG zU3Q?D1ZUxGLe6CpY9EiFLmyn&Xw2*LImO|=9vSeNyO%YpCNGj>t>|&DLusMVKSUs; zb~5I5ZLKe$5LAse^a_9U4(Z~;-BTO5Q$_b$Vp5af!DF3Ho+(#mCYCe}N`UWcAdmyZt4ID5nt?Wr%6$OFl} za<1pGmUl`-$ZC$=m9H<7-Z*-y{oKDf^HIdb&=Ph*rMWnMa^YO~SA%@%ocrRC>v%Sd z+wrRA+{c3Z6Y>SR!Y>4O0}7EhOMe2I#rxJh_IMp_QTv9rwl+2d zX;P0+T6GKFx5ExXUJpTQcn2d>M{_{`d08tZE~hL6-%Y_~Qah*CG|LC!0B85`PgnGx z!uu7Uj7cb#>D^-01Cm@WEvKbh>}TN5YmX}%3Z0v`pF8>`9(Ty8gijKpc1-Xl_GHkN z;i9o~l`2S|ABcRr(xFtykPId#`|3}(8Ff(Q=M@<$N#OGp-UHPndq>9atJHG{w>+B9 zgqpK`<`LnHvjygl*|)=R&+b(;-UMV*-&kpxf4&4heW#o@bft0f3T~p47g^)A5!LxA zZ@hp#-6y0B&EZDWziR1fEkBkULG+ZjcfL9hO@ z;_|XQ8Bpriv6?M3GTCB2zvvJ%gkcIMS{fXYW1XX-yyw@uuyII>&$El$LuXYBNN z(kU|U;}*)~^shFVUsa_xsm-NE%v|y7W)vg!?#bhvCqDAzUb#2zmi{NDn**ULfh0#l zqb0BQ?8#eixGfAJukU}%&$6Ssriav-b0c&tyO_ilfa`ir-HbcdiSG7cfdjEaMmT+- zN6Xo^tyic^XFmAPZuOX37jmxa^x*@PKG&~{-)b9XTRC->>(4Q+;;)~$X>R|MlI$3m z_w0vV+(B~s;YbTJw#Z_&u5#C`(;K&&9>2Z4BjP*$<@aW3a#8AOy;M+5Q^v7aRSjr$ z$+*GgpI@sN^kdpwT>;H!^~EvPkf&xn;Uq-@Pb=X&zy2m3kq+iHLq9ywt$6UHc_To3ud*d0@^5X-`mlra)V-LKH`IOtf zc4C5FnYWC6Ww*7sR9v68PnQD`UF&Rg3VF*Y*6xg`)b=H!SBKoW44Y9&@o&O~Y^}GX zp1q`I`90zSCm#NY?E4H&6!3jKalA#i_x9oU$F%h}Y9PL1_Z41RfaT|e(iZmH{P>p7 z`T0nVe9k2~1AtXcam1+0nJ? zT3-wrJl{`?r^#M5DVifMus{6SH zD@O^87w^p)_n{6LUCeaUTbaVWhUB}MeIgTY?+q9soBuY zs@lc0wWWTbpz=R)M`DuawD*QqloSWH>pbW{Em|;D%13}vz-;}p_4%m4>qEx%u?MNi z4$#R^x};*xeE0V+%b=Y)#cUv!l?cUO5 z4cteCkz%=7W8!bzVdFs+8+}AOulJQ9X4toZP4dfKN$Gk@mQ#x-(+klL-BYpgmFF!L zpw^rB`wjw0HQ-?%O%OqbFUF>CDIZp_9tbbv57jxQ5b285OuzoekbzWYrP(gXIUp{5 z$lIp?^*j=VBWi-$@a-?Xt;whm)LSSY3fv3|Y4C!T%eCzr7Xh4T>EYVh$5&UMN&Ptb zNO#AO-*Ww4iNWN;WFa^ zs6b|okWedx5SsMYTf&6e2A6C^F?E3`(vV=Z39hz1+lx%%LvUNJ8)D0;BD%P@DHY=x zML9Bkt5uR|@tZsuaC4dH81rWTtumx_#oa=P`(g4ntxLPYhZ3&h`R?JaJ%qvG!2r3P z;u*Vgdu0W_d7}cbUSDJX*R?JcE_pEbPL1ize>}sAGT8`(kA!vYcY<_4{%ceF3}d+>ldeeF9myoSvp~Sg%hJv%od2tXi5(@Q5^+GDhvw z9<^jd;l$+EKa$TKgZ}R8^(am`aj;o1ti{$ZQ(dX?X690bT{X*7g`U%bu=qurmmXtB z1~9++kTuOFluT$ygYJTa&jAa9=7M_ablF@7Dz_(?S1CerOBAsg@W6pKz# zgpalDei!X(;tdRI?hFv3r$hG;2&sP&h(vy}>n@%%2~I>fY9ArB99JLfPz=aZG;~`1 zD)W_JRrCaM=!KY0XW7pNPgUUq#8}n#O(|c8 zmxKVfbu5)0I%QK*9uV56CO1{T&9qB5?{W8Y$<`l;)v-QY$W`P-&Eik5QT^fUW)VLZ z;O1y!nQL1cQr`rE)JUOAtL#Ls2E~$k6?cuQ|BxwO*)K`62~uXFS)hFiwXjFb_U?&Gr!3 zNR-%)bj$nQEX#HElBwx&k4-3d%Wm!BVRrar`oHhtG_`cx>5WnyWtO2%zb{8?$2Sh1 znt#KLeKy#V5%M6cAx}~MSB37K7ic+aPcgr;VCz-inDdmm=i_Yv#Xsnnq} zd_@FOg~+#A;n2NN|31ZzXlCr8FloSk!?U;FT-*y{zQqD{l*EG83%O_088?qhUIfvdT=iLCUg5KkJC%7j&~T{pncWD)^?)r$T=MIU z!MOe#ii_H$k$wz(Jb#@A_(l(x)e$|Gl^Pc{bew^BDj?(hhR3OZa}yJ^#~k5%?hIR? zIW~HkR|iDfY;!H~6lmx89xrwr5G1-hVGFcckjxY;tpf}}1n~(<>#gT_Q{yo_<<_~; zO94poi)ob2lL1Nd`!S0lZGX%kR7<9Q%vimPB{U9*9JR}l2A%9`|JKnh@8A|U=oOz` zlq}H2e8=;-!B|f9?br8bVx#x~o9xrzhvuk;U|xLKnM{!K4Q9ZrF~SEo^nqaSfj!%2 z{M&a_zFV20eZ)EQnv0XzCHQ{aFX+dKpFu{mT1Rjvnmj{PIBiOk!=snDn*EJu!Qpz% z!bX98XV{_I3lC(g+iMn-9mAWXQqJ_8J$By$J>8 zM3)d5?8W@Yvtmnw+k7-Wec*#vdAIrdkoR9`PGD45CZO6bBrVD}JI7Rbd}l z>#-GELG-vPg>i~#f(k8twA-`x9BKyWjM|6nYT1BB=Wqi!2S3tst7XIY=eFh>+S0(Y zDEKh4@DL4|Np&O6gscsd)?wD*-;nfrqTNm;c&||X^VF~9gZq+$X=Mm`|)742~>#>Tp~*^yFOQ=L|gvbw~&6O1o_ zg3=b8o{tpT&id8zq``>{dUAwkTl;SUt7xZml3bw`hBY;NOAf8wxLowl)T zh}wHC`$xIa6wtMMrZYX`nj=cv5CkiTfRNqD6#$%!G=K_!HI&L68_#!yhb?UgHYr^I z4|!l>@1OB*OX`iLy+F)H8h2RkRI1mxMTDURnVY^>iNF8Y7iX$rmr=oA?y7L487`;& zs8)OcL4Wq~3H}~28i7N?Ds~@Tm1}cSL3_SxLZL0NDmH&H!E*~k9xKg=>}yj_1*3zZ zzZU-i1x48ymd^&_HC-Gg*Cut~e?W(Y&|9BuE-ANsMlU0C5~82iMlE+Z)R$qW6l*)? zQe={B{Cb}0_BS9C;fX*E7sPzI%gw@xu&Kc~{$q+H+$Zd9dVB!rJlv(#WJS;u%&+Y} zBX?#}d78wbhwGuefNP)x+HQvka@>h!m$WT|yDWcY9!xtrUyVvr4mN|wIeK~5-h)K; zWTD7EPmkLUhz~R#>WAUE*#8^r~qPd5Cf;A*xho|J|9(SWYu0u%Qc z$|#T1YD4fynWBHCw9VDt7a5T2XFC>dBR7`V2#D8)V4~89- z7i7M=Hr)DQu6%{}!fAfQ`f!6A-;-U>aJgGD+YHN@*=?PUt}#@{<>wIMgGywn@Wq48 zEaI3FIB>vI-p&!_aSWk*3V9{Xf|(N=Xt@m|!hBh^=&cxocj=b8^v|mKXfF}UCFK|B z*%C&@SSbB?dLkKR-fRa^sTm_osUQ2HoLK%``A_k=bRd$9PG(CJ@9!!Nk$*qGp~gb=996-~DYY2PQ6cm?TlF z(B##J*sZ7n@ws;txo}zk8*w8gbVMy$8ejC*(|ocL(%MA!G11sSFDyUzt6ln7brvOM zpcYT961sXXAW*w5xER8{1if^O)RTM}7vAm`>YS=yY<*rYP%!D(k9g{!mwA(&z5n=p zrQ_%raiXDn?Vd66^k`%C5-WO*woxYRy=@}|y7c5 z;DdWvyS_XZBSY|Qf%EGW>AzbPfT#)l&1?z1qz>*{Ub^RTSATEo+H2%-Y%iJTFE~{9 z#g;#J6|?8c?fskqFywvv9G#~H)}XMk)pE5=z^$2TMeV)sjo8=!ZI=qGaU_7$%%X|wx zsgC=n-P6909Do1onO|)4*pOfLpclG(Av?I*iW*qk(M<;RCb zgSr3n)vtT55nIW}a^?T@{@kYlSn9G*^jq}(eb02KzG){7h`h=ACJQNzw0WZ&Q}bXX zAXaIw#fb4?ARanhckAbbftYT8qZdMB0;mj>C(?$pHNC~wnH7zKaZs&Q_V>(Rmn z-dPZR*h+<8Kkd9bgZAgBV;LDXaA93!9Sm;#!}>jHgtXe5;s$|#M_I!Uw`rN-_=k-? z)7Pd$tj}%%&7p!o(XuSzrjKk@vjB zq6z<8UNb$*SR*prjym`)Ny1o2!M8zrJ>E%c{8swf#)eXCj*c@=nnqYGDPel!Y;o|y z{UEOZ4UaEfcCaXYk74}p{#FXH*%_7+AXs4w1 z`c^($V&7X2R$}?6nBpJLafzfr1D}#zGnk3fbWwPE>UyT5{lFu0->sJ-6*d~@tEus@ zhQBxby&B^`Y&rj`-uKFfkLPSVwtL`WI zA%u?Ow`U}xZRp6la;6|QBoS8H9>Is6KqKQC<`(FY?qKZf>yB_s#@dbavflEhqQ(}} zaP>0NfX3A7`~SN;rO-`x^?SmDZ7eiE&NgKA5XpVnMJ~ON5OiOfVZizK9sB_ff~%umf~1d7}T9XL;TpNj{&S zU4>?$SG4(NP(|SORy!DtCL>Se-SK3Eu_vT3)Z`Ai2W5FDYCFVYjh6eVXd;~}4c;(~ z`6fD6?G1^K&X`gv?8=qas){cca3qm=g4c!Lzk*FQ>l~rOMhZLRH!f`jCvx^XsECaB zI%&!a9Cx^xi$!+ri z(d&D9>1A|nnUgaO2htM?<14@Q8LWLz%T2pvdI4MT;9z9{8^ZLaKundy3oM6ELrbkb z=ucWNn}7DXU$CcT3(Z5W6H!S4Q&Xjt7`Hb&A${Qqr-MuDX#?IO{qC!B?9%TOP7;58 z!8e5AJuu#Do);${QmrA&hIxg;=i>r=r{}!i;zRB;u#(Weszj?xyD~8KOr52ilI)>+yh`7PG5dhHu zo!1NCXg#vH7B!lhTwSr!6jLu8p?--VkRRzKW^#f@XDRq$PKfiHtWLHlg9;aq6lp@3 zRZp&lDAs0hMP6j+1vo20HK00+XJ|D-9V`hBThvZR)1C>Aqm6%#kx~SHv+BI4N3Ce# z@4-_BlO&l^_r&~d<@QBVl(Byl_s!!>m)cuWfn}q%Tk7}4Ia;qBQxFa7;(4~Mu4Hr8 zGl3mB)y&ObX-r!Jme(w_iNzf8N&iD3VTjX2F>B>>?3l?r$In?ciIQrK(!?g##JrbR zdVa9g&k1=$opXyMutO{kN3uYx!OcvbLeEe8?VfVhKhsROrv7-D`rT^fcW#1J{qGFz zq4mOi%`Za!n`8pEw&9x+Po+`Pvo0RO;_>hA%S#Pjh-OvBxAH(+eXa*cYcg(a3)i#9 zY;H{{zC<}tY}Y=Fxqt%D_XG(gtF_b1MMA%S#!CfsGuI}X-ujaNv0)T+UStIn=BL;d^Eb4-ztoHFUTR{hBum1VDmKzy=Kck z)G3gUZm|v1PJN0EFbew>f*N21Jr?3JZe>UuQj_+c+p4c{tK$kW4{y|KqHt!yxBtj( zuMW0ic5cH?v}D96YOCV@{OqP1Z$7x;_J%2_`#`^TEe4YQ~!wsw9BVLTolT7H&V*+t-v3P!k7!Go>ul=iry+J*Xq0cW;*;Pe)(1SrWtZz7DT{Fv#CGi zo9*F)HFIk|tdQqxx$PJS$Xa`k#mJXe6GV1K6g!{{47YdFGD%Ty^hOB|uB;_Y__ozd z7k*=Y?M^6fun$j}-#$f}U-#2^tmS97XJ+_0qVF~4loy-YDrL6j#I92~@Upd< z)!AsC{85lKdyo@5+Oy8seYcZ9+uR~?v3VOW^y>e zLITE>9@~CX70>&SFqCPl%x{=_6zy@Ia9@z1JLGK=Oel!|p~3Ttbqy~n+&)a$s7>Q> zJ7c}X{lw!FsV{QfO0vW=^+wOrtNf+;*~C*M8N<&_4!aH{m2j^=12NA@m-v2uk*NFi zOh2l-_!tOiogwSYRv3QsjHNI?P@z0v@7*SP?m8wzC})06^mjFNq0VWc&}!r=^L4D< z2|#53NEvhAMwnX#Y?L7BepDDG(-J&Ru>;U{$u;&5eWeeGk>NKWmz;@qSeSkfAp&Y*M zOZXMAP-_JC;39ki6objoy(V@3%6q`h@1uOvF?FfMVy~PCc-=~6uu0ighegnNv&V3c zrkU=>x_dcXX}PErfp0_(W@717B3+f!6h-XcdXsr{JxZA$o|OR}J9>eAld%Aw~g$3g)M#{P7R7`kqSO4@XxrUSMe+X)!)M8uGcm76^ zHo(^9IKS$e>+nqH28&rWm7!B%Trb}TTJ?UyxJ8neImbe+BK2hl2W|5Bq0#$IKRd&n&pmd9 zE*Pk3b>B_Q;IwBYN*|u4$!zQx(rQrlct>+%$rs1ymo^31;o1i$Uf3JMBO#lBQ4J0Y zY_M-|M#;B0+slUYs@L>QxYql~f_$^E?d^X_*a-}fEI_wN12UVqNwT5FxxS%24A z9vf6KBQPinao4>)uM#<6&F2Aeig5#ZPOTK$(HO$t9f zY5&`BQh-jA6C=Lz*SBu(=e$5J`2%9fj(*0 z;_aVtSIh2-9Pw)&S5@zf>5tEML8y3(E1&NvBMhZsMJ%sf`O8`+l)bOchanmh`CnkD z?frjb11B96gI;Bz3CX*laa+-EG%9^XEuV7k7~sG>i_IekBBd_+3EG zB91ZcssRJ|iH*H|7+w12eZyYYF>lcnC} zyZV`qULS88=GgskaKaIS_L^$%Glp^Sg2XX<+;p>y?cdaEJ$KG^$KIbuo;e-$^3fHk z8x^ko!UWj5@(|jy{OJbGjR^C<{&ImdKE%-P2Mv#>!RS0>8g%5QS99Dkm(r6OIJYO> z1~ZP8l`Dq)Xu4Y6p_r=r<1v?#JN3;P7cV=e(IE4H>;0t~rHcFFtuCco`YNS0;5|ZdDEB>E@~`QF#Psrw3zI zg&Rbkm&TED#A|6(MqF3FxiI?R<*!~U-#wUIFiEXik zxBw|Qx9vPXW3r5Lu|^SN65&as!|s~KZNMLZT%3#HHVlKLaaEP6Ji1i!JrE?$0hz7w zs`jJ&m@&oo?3BTtKI`nfQkZR4gV(&?fs?p+#&OT{SEEA)`>ENDQk7oIMu+Dq6LYWC z{^~7~H-?HuhSAgi1S-&hZI{3NC*-Z-E`U0`bsRExf^gAI-PKOhSgY19DY7pXu$SiD zF}+zma;r}=7#e5+YI!Jc#NWM`%y+iiUWCtWxmCE1*bp;A68kLAL)VhsUW!+5E2V&2 z$?p8tp9=^fjSgM)fs^Sy?obygk-WWcyJ_!ZhB$S?Uw_!SHo}fN7d_mdh2BsmdR`D-NYIY7Oyd@6GS6v2gyyqrkQ+a#%NNJuSbS-1tOL$N!F z#@ZCH)MZ-F@+w^wg>|*C&oJ~F+N~@d-NE3yx_2=ew^);Gl}jx~?d({QJcAK_(?ntV z9BujPRj@|93@~UIIg*dlGe4t@n$92XvB1zG?|w0t&RHzHW`kc->-+qkm;^gcMEZ{ZS3W{w^Eche$%$j?A3f zM560s-$m2K`v*HO5OHgcMEdH7Ai7uBvyS;WI{{ZuMHsZ@KS`*0E>HTry-wQ@>}U%B z6Qe25PoKUVd>H=!mzWB>?PlwSroTo1ve?|}`pHHI>-X5MOP@%W){`}Ru3fGNvGg=dfhhn59Aho?gA!K%MZgT=wT7PLi)`N(qTQ%(qd31s)+xkv(2N zrpAv7Dh7x%H-IetXVjvD8{n%2d*9j*!J!ELS3uv06M6++RvYB$%%H?tQA&hf$Z5=+~XF|kx>89^v zpHmN0p^vU*AbnmV5sE09;4==aBskq^! z_vb%vTd2R8~`M-CujdKcn>w40##oA;A_&?ill;ySm0tn!?zx$@O9CtXD2qaTU zz$!i=9HVcq-wV5YW}45`35hNjK6>M4he+%zw_poG6%kzhs~xGi)9FHBK^C*nf>QyPsH*<<&y|O$#kboF*13&PFp+Tx8fMOS6qjTNf; zx&Bd!f?@C8VIc`b@Y(=%bjsWCgjpKNb3)!K9F!39F4~;qxpVmZQ=Pa+_&ZY$>L-yc zi4hq7OJgE+j38jHeecAngl&$Ww%VWPL+$!VK1yIHSm0{8G}qA z=k#fsUxAu07u*anckJfUD(5x?^`1huRS<{#w8#YqN(l4k%Kjspu#&6wBc)NpOu!d1 ze9BWx4RDDSOO@jn3|qn!j%_FUZ3H?setpX3Pn0d08e?`V+qfhxv+Zx>zHxeJsVan6 z$T(`+Uj~(M!W;Fw#T}a#JX9~A zKG?AkAF7a>LlWE4!Xo2?4nti2P`LnnQy^Kz$wD(Y&)_&2#In!&CF6{5Y$z zk*)ecd^ov_uA-p}A=`BRc)_w2X_9A>oTmFBrE$F?B%*bpAvdlLobZGEnv4B1s(zOu zsr7=~^?s<4?e<|+A%FNu^(O26af{yjsNhU2dd03&#KoteBS65A4B+~F+Ql<3n%tq& zW)sl*0;}28O2^rvZ1~r`l3CFp?)W<0EV82RuFur&G7KWWXaUM+SbsjjkVG<`N|S{d z+MP;S`Ee&8MQ(wkV5%kvm+|a0vyq}5)4qg+Ax_Fi(9_#5<(a=n-JsV3e02an>x5Te zM2|f$auiOgs#vamH{l?eK6NKssR(g+JeKw2dY{d%R`$IH4%O<<(BVO=a{C}u!!Q4# z1mwY|`Q33_=w6w%?P-ID4oMa7`A?J!+A_Zw13FzP(eMF-ftAEgbB=D+DNdwYJIl~Y zHZAvPof@~Tbxt|g&W_};qmJ{U@8i1SDHQ64^3hkY7H@RE5_uC>ygBq#w%)vY#)48j zQ&wkgmj3-6(+*}qSfI1pS68KCHJFPCjGz3;qwkydy$2Gy;&!I262b0&b2+f{`K`-3 zlqW`4g5Gf3dB{{cpZB_l3)3c%ZvYkfs@6$Q>YSJZu%7Z^qrl|9LPtA|t>M)89H4p= zl`JWbASP zUE1Qi9*n+P!kE|IQIjY;iV=KFy~coS>ED>y-ReNB@d9WMb7$uh%2;$dx@RJ52o=Y>;9GIKYck^e7G9sf7I5U~_FgC^Y4bJ(X z)bMZE4R4yuzM3~h-@oMM$PC*`tO~#P%HK(|U{B0&t{ML+%3PB91e3{B_qD?k#px9> zY-?TgdZYfMrTo%*7gL8Q>T*JSL+U=Ok*RfA{$JhjfdCQEw;neore3SdpVW`krQ0c_ z>sQe}Bq6qYzms&faDqn1DY+4O+4ANqkgQTU1pfqOq{w`ng6C!M+ks{rv#m`nYjp4k zh}~7-sZ67XYfiAxaA`(hA8^oE45OW{(0tN}gtk)KNo*JKa#&tY5wZdXOnCM@6ro$0 zONdUVq9uEGHFTxTy{-1j+}K_lIp$ciz+6UWxX@F^>6p|8KU*|_IhEzT3JiN?=_z}J z^Jg5}lq&GL^x!bo`C)de-)iHvz(>z$Q^`^_7W~@zgJ)V;@#2{+oD=C*0Rf#1-V^m=D;Lb4h^pe55AFV}uoMira^tMsma?3kb#2m=Oel3&jd)e0S1zPc^0 zzG+gX$dSyM7F}7g9-8ote1Aawd8Hy|r1HhpIo|EnHxZ-NX)6-OuU|P~N)7*|7f&G3 z-!TR}d&)NK3jBgRe|4ALc(SKTKA3I5B>LL6_N=9~_Oxwc5*yOEg01LV9-H3Ha~c*c zINx8945jipdw5o8r+eClKn}>xx>vuwFeyT{VzMu8D)^e&U5rCQ0)%;MdY*ZKH<6xK z{sA@e?oVk;>oR}A==n3qs#o1|)lMyy$Yah33-Q4Uc1HED6J%;+n*Wad)j_G^?X=04 z=#v=!vt-N%dCpe;zbKeKaY{5%&U3G#7qA=|#}H&4tOy8;%TfVxUQ(4lo)uEf#m8bf zlpe>wJ39h&gD#OGb(=qf;DE7q1$w+5z<>zTmgiqmKRs*B_Z*tTTcOknQYv14GWAF> zuXH5P4*2-XmJF9Bgcq>VLsWiYIy~Af$}RA#0*ol|W6GhcE!pX*s7ZTindy#0t+}|< zPrtf;0tFQC_Qg_IWKdw^?v;X1{Sr>h2B#fNxi(Xj`%=OGuF}5wlfs4{`+pe1PZa(U~balY4vdG7~%ooKrE>FW{+iYKeo88 zy4Hk!mcVZ32`*v@vhr`ej25p`(wI8*_d@0z1TLaxWny1(xM(bH395X>k!$6E-pkGO z%)p3Nhw+LFJSG0mI)C9saMC#Pd`)oMx8fNe6w5q$zLPLp-sHD!ND0}^QT7=6R{o|N zl>BczMMd@Cx1UIjgq{JV&zF@YYoB0iJ}kY@2*g5E9UYNtEa?7{*w;aDdkvF<%1?Kn z4v$|QR*9OX}o7Du=$M*fGN!K@gyG^OtpqHg2wr z?K7RhnZraH;OLs?kR7>B%&|{@%wtLZ&MBAKC(|Hrh4`MX4Px{;TM_PJZ|)2DReT%d zdG%lgN9Df94%HA%=fSr>2DchhULc)3ga5dwS^wv}_5Yvah#rYQO$qy`kLt1xDRp%H zUsiWc_5Z1wJ~HYolhDVL0Xyq6@ANmdH;YZ@k| z2}y9;kQF+NIb(oX5ic0*RA6sDy6UFL2)0C|MNQcRkL^bD=t|@CJQL!0YYTkqs%i=s z?j1;`Jv^H5=9{>~ZqP6XXr-7y5jIcioGe=04Z}Aa5&U1?BhzOWgC*0G2n15Ko&p(^l$F>DUfO|)q2js#4z_=SPMKSDwyg(?Hl(Pj@}N9BzOWs z)qYrxOk+9@HC=dA;RJs$08~}j-d)X zu`mY~V4&f3+@4y|ViZx^?H2%V9CqBa^t}$a8ZX>_11ry&aVL;-;qCMRHP{n*lKzT? zCqEPF97AjOy?}9yWZ$T{p!9jm-<>qSd1)S6a3atX7RU}-78UxlAo2hCXD_=v-2>by zkbR^Be#GwqIR9|Y;#5kKHW$lIn5+aQA08S}ER&zzBlnZ9eo?Z{vw@V4er^;!q~?dN z5w6koGFt$OqydupCYsPE$KJq)CoM^j-W@dVIf77HwoHR09onLQsPAs(*d%1Gu z=b54UCVsShLn^`(n=gHpo^Et}WXf#QDcZGgDK`5W56}(~4#F) z`F&>pU}8G{2`iLCB%;w~T5|E0{C5WvIsdOLR#<#co%U$3%f^sEgFWdA@~F$oVDt^c z&Z&2vc&*5t{SxsKPlL>PX^)YkW&2)W%bnG8@uL;!o@$gJK;oGA8u6qssyd+S$P0$o zb?QlgMjn>KokbX-oCX;9waSuWe>^&G?C~;W0Foa%uJ+JtXV{=iFo3)Y+7^6DK zUFiex)V7%mXFb6sw03=#!`{KFXqY>FwtdBoVz#$NX1^Y&-Wi+E!w%IO7J+{>z=`Ay zksxEPkeHxm&}#puyS+S8srB^Q@%ddPSx&}AH|Xh^g*hdvjE*UIPR;K-6eKX-s4pQ0r1bX`ymHQerc2-jAJN2=|0f93e{y?^ey);!m%2G zK{yg5_X>i2AGz|L_U09LXXa(KxI@{QbO8$_qmyJ2O zYM%R0Crz3^4N_wb;Z*cCjw=|k=*P9U za9?=gd$vBVO!F~4aKHjKPaZmf*CTwaHCHeluvRu-043cpTqsIK+%4MaXGKD{d$A?U z3rs}F-YaRJayD43?h^xQWSF~pqS8h^DF>sxWEdxGcFW~l(%96G((%#p-khc7T~{{z z)k690T)8!8y#m@shoAM;tIuV-Rf>TgQL`I9em?s<0Evi3Qps}H&Ze#GkJc^SOQ=|V zA;vDt#hM)vPuT%?+4=$n8^d~lzd2#6=qXf*6=f-yl_?++ANwMM8WD)T0ym@iDhp4P zfGk|?cUq9&4@ZM&s7sODrFZtPq z!|O(e+q%yWzMvp5egCb#{3%AbuRuRJ*VBG!uo;sy`7K1R%c(_MC3tL~^8|7N9JH4B z+2-wLCUn}={(Zc*JwS<@lWcNkUQ%(f_bzd$1=L#=kqN012G&u4ll4R*kbO5e}0pK(=&3^;mEa zulpmf4t8PPQOVYrzVzc90q{^U>bc;?UuD(8Q$Fv3BC9fOlgZAOJ^bnhBQi06fN49L zPSmyoXhh0krdSp0V!t)PbsDx{(qNTtQxzuZ$b)GzZuv-8^5kpaSnVn3NbfU3W)P+3 z*@CtA$cVC(2FHMvH1lZpn@0Ky4J9^CQSOgvNcTAp@0(SE#Y-YC4Z^CG?6<)N3jJeT z6R2%t7lqvQ?l!302qGipxQJ85{^(}{y00<&)e#3d_xxEd zTrgv#;eqMPv+OyaAI?o{pl^3%6>1O8tPQ|41!#uDZ*@OUYZ`|oeun}3((QLkyAk&8 z_EHDk{=&I>`V$-CPAUAErziy9b>GHhGp4%j#)fOxzGEC~P+uAhQZAz$y7kx<#gosq zJcb7h4M(lDk2+${JzjWL&Q=G)hMxsDaUkhLDQA|9BOpSgKw{1;!rE@DZjmV(iZpN@ zDupC48DN?}bu{ue#NY!I%+7J7@~hOjUBaC_+a=k$+Y_=kM<={C{_u*@sH{ynz(8A#eSvOE=MTVjK|60mcN7XoUaXWn@QpTI_D`nW z$ld_gXVLW*IR%;yv)NATDd&B7bmjjzdeorH>Uv0vOh&msz$diw4#w{C3n zm+}(EKd|F=3y@X!X?!)iGEJ5-BEGT4S%g;kx}m)9-9!oP_~1Gsy}`m^W}WonQDz+v z4+dd&${IV@)X6mCC&J#B?85K27LNR$tf~0AR7I|IZ$$cZVB@n<5s}VQuWiiT6xWBr z3Jvf88K&bW7p}8hH3rVXEfaS#NO$M>HH%ny=Tg*{FqT`!5km?su1#K-N4s|`c8O%y z;qg35GBM&lW_a%E)eMaCxb-?g5Wj2d+Bfo{8f_3R%)-A(=P!2Jc<%>xm-YN^lKav$ zvG>_jhFC{``s*M~?MwrMzTnjk`6g)M89m|l@U}71zKU_$0dpY%8pj#xqUd5vjg&d@ zg55NzF}p6@F||Ois~EiSP`u343K`^OS~P3c{UzN+vK1Ie^fe!}+DG}0Ik}ezWOO~f zvi9kWez!0uKYS-#{2)A(EpkY4Nm#dgvwjemo9;r zn<6UdwHp<45J^VGhDzZe=h4%M!djIe2! z6!Hh_@9ekQ_jvX|P}Vg7)d?@IsjX;Vr&_qvPb2OW$a(FF6!BE(HE836 z@Y`{@J=aV;bLDUnM84;BL?+W*MBJy2H-f9fRD}hPFvRCu6Is?ph&sJj#B`>v*6>Zl zD~`N9;`o`BvGOLU&Xx#bXT~kfV5%MwWU)8l|C9A8kPvbCXET}GJO?z@;l{iW>w2&p zO6^inEb;?)?tJvzO@9lu*;d0bHWPvMKH?MamVJA8wfhD0237b6&%Zjiy;3E+TgiGS zkkrSua9&Q)6pJ+V&5crA56+8~U2;^Gp6q{FMnP4z!{}DB7%aOgh)+}=%o%%sV{9(_ z&8q&g%QwXBvCY@jViq$Fy8(YafQMH~ z8iobORIIp>MX0vN@*LlFoelo$bPhg~Umvt_3|z44R6YUBn%y|aU_%Yu-e_q@d_p70 z9NJ|sTc+B32C$;pF6Un)esZr8kYTPrH^sSO-U9T_lmOi))Q?FBOSbK{sI_OjnaJuc z`Qb@*)Q;=O zc%U7N5Ha$m;@tXT0-{#2#8>?A-hB_|wGNSLm*v2HC+*ZH&#k}K7`}zRx@oX{`Dx2R z51^L!EpBti?8z8%?4B-BL0YrN0lPOKS*E4nr#M~8RK!-Rn@Nr7}H{jk=g5$59 zrxn9LKOk2;DQ~|O!zEu0xA&m6q5Sc@YWMF4 zBOG;hfwf*~o6>&icW=^>6@rZlZ4lU7A zflwWW#@7#VokP2gb_Yl=Zc2Cjmh5tIAm~87BT&@GCQyt`_F4<-0@CTUFd!Kh;Q{?K1B|}9=9hNKi%eR zuO7heg}#3MK}IwVXQla+&|4hfGhe;aQ5}+kzq)a6pnNJ;(2!1?5-U76T##Qq1&pRV zj?=A7G2t1kj2-g|^xpR-SeR+5stVYQKkKEioeREb?EQuIQQ53hz$wK4szv?IwBQq6TMnL!z#D%OK`(E>)39(+%zfL$2Aw3DU3M25@>9*n^TLNI&yd0`Gy zp;9Jlt4xQ&zGK4e(>$oiI~RR+R8FjWXQ-X?p$IW`w{}&MPU5R?A=NhHgZ=k4f%Nh~ z$^4g#nWF2(r-;>W8Y^g=@Rw0RuQ9btgH*2b=~NzCSShj;l9rmP?$}Xe@sijUonyVR zllfR4`DiRJL}p`D&3g|xBSL;aUp%+QCgYd0yS4AswXDC;7l7RTHIyPc4-CCY^YM?b zB@ZZ+hHZJ}_);EM?!0AFOrAGv8(DeB*=Y zGkpAa&fPgVm$akOK3vd1C!6aKC7r3(?${SkQDG42YCMDuR2dpCR}|P(n(#&eW7~xE^Lo$nZr!iM^wJp%88_!<-7*Ty zzro0RoZ9$--thX_tYi3~pt3Cccg+`b3%hH_?zngPj*;YfY~7|lx5-9OJbfW;erb2y zd)d=E5=zDN5aJ+IVgySCW(3Nb)!>4BDn0MJxA6|^kun6owfY_#6xw^HD=opfMb9+x zAU(0mB|HnxHe1*YV_P4T0HbQ=bi%zw;XlV?2PjufzS@w7E|r=mz*{+568Cf}oH%Vu z!=?ki7<`{`3=NuN#JxVR%$H}PQ}1mmL5SZZ#^2vr4}FP%Iucz~$qg9KAbLd*{BvYM zK=abZf%CV6O$!7Ak{oZ4#kpO`(qZeX~TPI7uRUkL~Z5{eg6wx3mZJnx3|itJ%vG@++OADkh7N_*1840P+L|c z=jEpgKA5Lp?Zz#{33ts!2+1I}e~It8jduDH69fw}`+v0%zbJ{zjBNgTRBg3=%q0)e z^BA=BeDuI=p+tE8N*pWG(w#%dWZTWR!K1(j6cnV>+N$B+jNr>M)qaP4FeMcE1|y+y z5Mo`k7q)G_5NWPJ{X)g^j5y&R?UEC(>%~UR^F$EE3qdE&gBxd;Dp-QYSMls-yCWPHyNNYbT26ZILfZZ zKiAyxFS}m-a50jg^~n(XZ4OHmBkx2*`>fwpJ#CCH;L*D%0YW(>FR14UC_;)8X_JV2 zg>_v!8P?${Ws8C`BM*yNZU|axXH2;0;t2eGC3uvOE$5~~hXR%t%)d67Z*Em#PDyQL z^Ho00UCmpXoII~JP*0!o9K(>f)3ZO}Qg5}W?1||TlhG#K=ltsvW@kVe(seHnVSlff zrh{QoeQ)j_iCUS&{~$ET@^WKeiJNLD*6P}7AhxibbO6oqn+jcNS?}{BYsx~$zRH)B z9^~>`Z1hmsuRHe|94rUz`jTE$>SL!<5XOjEi4mx|!ZTAwfnmprCoX#K-gq4&|D_jf zym^M8zU=_N^SyQsXLW%WO%JjxFP=`x8Ex<$iOH5hHIst0yTLTNduA;&Vkzn*rzvNU zneEOUZ6q*HxtUMIl}DX`V#pzgSd=^=O~>o`v7V8v=u#iBt7hg;y6ZZqr%KZ>FapZOzW zF$U!6)VNp%Bp}_Vx%=+uE`}Er>!fYyB(?Xz2jH99j-Kn)dB&;3-Nsmg=ZI=ro(xF2 zn1$v*KRxSd7^zLNb_$SVS(CE}~sz5}w}z+9yF*{*YQ+AEnmhUO*7kRotxMRo)Ql z6O$RKT+1CP-c_<;mL=?u`Fs0QieN)d@Fur~FyC9?Gu*)1H?IiZ+E~=B>qPWABQpKpX*Yet-#+j3-FybX(=Rp0EJUfy+Cj0JQ+w}2H1Q8*t(PTIvdf4?pF=M`WdsM>%1VP412hT5Szbx8fpZWZn5@HN3`o2!^vsdpfNbif<1&^Pl@ zeG>SyN4099*tT=ce1~^Vb2tAR(IPBk4}W|eDf0j3XJI{5fj_7~;~h3H5>u~L4D2?r zrbcEu0BgrI8^kaI9Q?|b38}cdf^;K}n5|X|FNwiIQ~OjY%iGejL`DCtceIaC7mwaj z)cN0tZEuw4JrQOrn>qc(w=7KVL(#7DA{_~n~`pK zZ+Sh;dC{0%npZs{>?2xbBXd*lhF2bfGA!_i5*Gn312(kyY;VY+%=^yeSMtH~9bQUb zj$TY#bS(X|tVZrXzrf~%puh%Q8skSj!5SB64C37%8odU%j7rI9{*?#tZ0h4{)(5Wc zjrV_(z^=#948Wp){@$O{?;+0)4_mo^88cBmWcd|XHU#@Q1n9 zplLa1_XR4krr$(Ae+76oDyr8AC=BIAz8_%go2`*$m|_WheN4xH`jgmZ1n=S$DrVoh z%mn4IBIBzQRr^Yq_rRyKwymbarw=;eTH{>Wsh=g*uYOE_v$66iG$4$7#?1QiSDA){ z?792#Nz<9szu+@ixHfJa&)GBvsqOfc%6+F<5LMc=vfqL+n&_Nhj#}|C6~%WJ6kdg; zPJT3=>kwFS=4Ynk^83w|FTWfzG!>V=pdk2~*SI|sGF!j=-H${|vDg^j*k3xq3nc|5 z`A=UW=0Za?9R0>h$j{e&%TVRrHL0^Zi5KFtVmBu12E)P?pQi@aW1J z7)2r_jyKZNZ01?5V(eNLC8eN6W)qP-anhpZw+{Ue%6b+%#KVnCKxdUGi(0X9FV2~7 z=Vqm*So>61XyKswk}x9}XC{hm1e2v8<6>^qxyVP(I;L-snV-70qCw z??5nVsyo5IwH}uUAP-bjr?HSY5l3d5*-GuGh3!(CNXqMkTG*_Blh(rVfqwhQCPsbXa5*`lJgy3)GvGN*J1zHFLXB+M-r_Z zkwcQBIx_RM=X?#j;WjKU62ARAFFBOF!&c>%V!l?LK>3;0LK;arcZg=5MraMOEGrxT zoD&^p0|qwW(0iq09@VvQ_IMKwwN)~YG-PFKKHi{tE>FiK1;`XiWo({zBpad&jaoqQ zl~R$)u8XXot&dr({#F9i$D5iD+nFmL-cc&1v5@)K zE{AF#%EUXz(V3T)m%n)YEu6GWNrxo6jH~&VCi%xALjO{nFTXr1J_DpuK6K4L`!6%Y zC1U#Yh;L1SgUi45@#+7DCAAWmlJK%!@tdZ7g6h%ZKH*;GJWDf!A85U4Juz64VDv(p z#iJTw1DHGasIly1*IGeza8Ohu7khMYfwcLeA2;*UH%xKjyD%VW`rSX(+xd^ZLK5Yt z>ueH6ytS?Fu{O_McU*nWB0hII-H?4r{7@`KQXc)o+ML!hVoEZOarhwZ{3P*{VG7_l zOCPG$)6D;{GB3ZxxEJRU^&aaGFF!ZtNP+oBL02DY7bB<*WcK{3OYvs9rq4hF<1r=K zx!O5qeS-8@esJ_vM_*`yHDLj+g=CXPbiyh+FDcd1TD)q@eD+Ct{NmutI5+|T#e4^&L7rMU|oqf+AjhdH4>uGik2&8Q!1c}p;( zL#ZR?0r*i2qj9VouTUKV^Z5q2MoZ3A5Ltp3$%-?3cjE@wIfSHD7-KoJZ~d-s7-u!r z9pl9dYlw~#&`UIGX_OY4@&Al}aCV@5Zn@JXUpAoO>Xf(n?2WR_`zo~JKvVZt$SSUz(TTLrCq-3 z0z7PN?bm49{ElOHp7>~Gt+S$ZYIadsgwq?6xb;@VeNXetLOY)(%sCbUxWr#J4v0s_Q2l1xwHXEi}Vo^;(#1Xg`P3_1kX3co? zYd0;vFtcV!yd~YngzU(^R3$sImn(g;xTdAkEO=?qWKO)Wr81)aRUcY$Xal#HBwn}Z zdp#S2o~SM4zIL$3x}@2)8jG7SS8x~Lr#N$(0H@R^kLc8ni5Er0yY^Yh#aIIT1|kApuV>?n-N4mHpcZg!NWUp5gQ<<$AX)+i zGsbk_K`F;A!oH0WCO zjE(GnrR{b_r7bz9YYu7DBGrsYSmb4|`{ljhZqwzMf=fz)EXiNgo_iMVYr~m>i~PXG zLy?kg$(!0+sCOpG;pUO$isgqX8l86cihU*rZ*gDeQEL4c31=<)7@WMb^ear?oxLXb z^;cB;ND3+L?Tm+6&UW_pa0#L${Fc`frue7#Gd89e>-qFhyk?bk`Bhu(jIZuD+AO)# zb-N{qiW;dy72}}~T9}-cwQqVQExZ&N{-w^2Vx1eLGW=NOFfP(NK)tOVb~W2HU#GiPGQ}!x z(XmqoaK4_5{3B#I)a4TGdWjk3qFG|VP1pad)5C7VuKO(6sXAVVmT`71&a zK)T9#zW=oT9~1U}#gZ@GnC#REuQrD$KLPVMrudY1KHlqQlnBt9Il|3)>w+l{g zAZO3B`bE1Py4H<998Hea9Jmsjvt$>KcUg)Y3YBPmCR!1B#{^2Or7qbG>9IZ`QvUfK zVl2JJy&DtzSUgN#=d2-@#~(MAYKA&zALqB1%kVqA>XY|z!q+?&cUwJE?WmLURJzy* z+))i0VAuNo*RdY-qlK&GkY2R$%gF7c5ay_yq{Hr7ohFpL+9}Go*B}V1#DqE0-_TRl zY1jf#Zv`yW)VAXnB+ zIHseBvGyvx=vyoe8R|YR<`zJ~`}EzRfMEf~d|xG>cmi9Y?^tI^MrDogwQjFA%hE2d z1j@pxEOW(TxR*vM#2?v_!Wz-ACzFL?F|9tbMDftelT;Fr1%0s5xs9Ecer>9hK ztwrrnfL>VKc#~Uwtvo6zi}FH;EjFj2LCL1u~M;wu2j6G z%lUJd-QOqJ!8p;uk8=aYdHEBDiu+F_$Hny9^_LteRka~h+&!rq-fkZ~vAVU1hcb>z}s^fr*0No=)n!ZyxVZ>$Cc@pshgccs?_N z&Ojl4euS^dM!BpjRj1lD)w$AaYOJ4oZl}fC+Dg4dSVkue?_hJXwpX~Y*BU^7BZUjU zc1-*Z%anwUBIi#hc+w)#WrpQTUeq@eD31<&dc0r$_#>l{p+}MU$G2uBi}m@U&waEe z*SWoS7Fn&yyRp4#e%qIy2_>_^OCKi>!wMYMy%D|;pR82@FbDOEgfG7%rWdA1aoQJE zwx}_@bFRPY0iK^Y6KK^Y_H*QaiLM=+%s4DfpnCD_-*K`(;*WOy!<9fJ^x@xF1Tche|5&e9069IBaVq7>Kh!D!Ga+reQ)BgVblTdY zd9>BkblO8M-OnI+O5N#9bk^+)=os@RrC8@5{TtOr^^F--09oQPK!$?Q`dHdpA5;Im z=}&TlaE+P(xS?HwY~dM)(bOF*@6%?Y-W*#Uk1|e`N@#!V?-G+j}XFf8RT&!=y@GLUGfl zbM^O|g#C#Mxp3A@$nK|bvjU?kbp=XR%BrsULcF;`6a(_nx)4^lauZ{FV4u@rR%DXu z)Qos9}m@V4%QFa zx^!*7tcNS>E6w+P_dXd-4c$5gk#|6TJXeeC1%%@v%r z3883y1g?LMuKv+>38JZI37z38tlG!n`|GVAsUW^n6gO6-4y^jbd*Yi$3HbN>?fls> zDcdqbtZ-(pEn>FiV8dBo5VVnb;8J`0@isXiY`)Kl?b4Ymh%rz?KZAIZWMYBGaRP@e| z!gG3u(hMvR^oJcEPAnAPmR=v8>up$i5du86JsXy>IIrkXzh~Z%JIh1Q5d%FC=Ys8# zj#b~`k;%W7NP1}pF`F7U=ahgIIovlP2vw6x4cd4XM`LMy*Yn#`6xQcVppAvW(dj3# zM&@ygc)l6UphS{6;Wea5|MqUKK-J76<_9PB;G2*en=xKL+ZBKYK3ep?9D4~K1@HPc z=I7b~x->la4lD36^bZhV9{p_9tzbIZRovMN8VV}igV)8bq&P}y-cLG3_2q9~Q8}wG zsAoP>XHH%WXjTotxkBTSJKFm#5fL9<_Homrh_!}lgZkw{bjQRozwKbVVR6a%4?L+H z2!WirAD&ojltG>z zsqAiDqkUm{S?TQbXrA%sdjIw3qBm<|!u)ZrGWlBe#XCF8XVy$Xg5Zr%)c%t$q3w}) zSi9~1%)RaPd8r+Ac%QvJ0G`>g@Pa9ebs(Q0`FqKXUOqgIEa=l%%l<^L;EmucQugdt z5RQ~i(M!OUzK=_fT}id<0lC0ki+6HA%EIzj)NC491)0j23iE|;w+NxTW<|Y<6Fd68+&)ERVcdsS=3LM{S+cG(;4otp z3j?N{*Oxwyyg857%_nw<&X7G*?+bZ{Iq^eRGH!_a_5@ASd~(QUL~>&okjA;N)wKSX z34bt7D!s(v9<;vMp6>+Oa6wFylln&kDR+0L=k5%kS9aH#f+r~l-b&8qUP{hpHRk)o zn$hfs*s}7aI2S^(Vj{U@#B=l5jL$S6upj6GOWZdfl@|D+CsWI~FeCR6_l%8y-kZ12 zwnH(#_mci7XuIIqZ)9%fm2TTZOnFt3u+e-k)5SbxJ7r<2XW}96jRoi|aPGKd@6F7q zxi>1~C1jhztJe$uZc>=nRg9U3*>ECS8c~($R&-Qf#E5<;6m?9496}Pc7J-13_%j-vX!iadGs(K{N|-xf!9r zw9$ZLj{`KJgt@ZkT2%aGTc=8i%fao#!wSDmiZF&W?3E}BI837@PJ>#$JJmR7&jN*r z!I3cyra0k-X=V}zDN3CKx@z-X9X0;+m>vDxDi+N?VF-nE?aaEr>wJx-_a<8As}0y* zPN)HZbO#IB=1}aU&_i1j`}hgI>ip%Y3E3s=;7lyUuRYspg-t|Pe0g^u8lKs z1v7HuZ%~!*JI^ISqtN=DqsUZQ@Eurrg|cxG`w&+s2^Hg^>0FFxM*2S;`Bse$G~&ywm0k1&sSF|Fl{#W^*^bIYMa?Zl$_sI_p zS0>>6NJibx_htAJa*2mXqUVgl)R*=7jRZ7iz)SL72IW{R4qi@_tSg>ty?jusClpcg zc>=13I7c7R8lIvK9nYssMg_cIve|1J4)hGgmKBv+wO7g9%QfkMVk(DwdviC?SRT@z9j(uaw6NpKLVSYVW&=5{RO~^NAqn&-dQ^19WVc}1RhTD)p zbgj59l)^{a`0Jze-yVU8IV5%@1z~O&>;EA(oS%Y0j#zFCCz0DTBkFF#Wg`+v`Lh#L zLO5A)ra;Z!jqSZDZaswah=*zcrLvBW5m|o2DodlUBwtjUghm*PI1GJ^bF`_S9ZfKv zf<8d&*KJ_4)_iExeK|cIo^81~5HHBO@ancL#S_bWe_`S$o9t+?8YHmtif315J0M(g zp5bQX-DVOmBzT`g*oAx;*NI$W-~&g?YQfiR6&BM*h7!AS@EVw&$qOf3i)R`0hBC1A zN#$9h)F$QcQH)5Lt~%sxlPlQ>j6U?;1D7Ws>*hqYr<{KTMa@U>Dj_G3H}c$hP%fsQ zOB%$RttyuDJK~=O>tR=hGH|2L*&g`@sG7bJ+|OG7XlrJ`la%;l*d6R%B49ZV35Xs7 zMhFyZf|_O0>pYl(7;OQmCFLgMb|%tBOSj?Puh7*9gQciBm+@rfP z(Z=pr{QEm^k{CZ3=Ry}p`hSTeFm~eOd3Sz^7PwVroBZ^~8Km*9_HGzq^l?mCNn?pH6J>Urw6ERJPnmB*n zJKtFnQtzb*xPcEEEz2J#f)!TH;a-SpbpLx_L;nL*9mFxAJP8^BKZRUF;o8Z`E3V1H z-}pjJie{EGwysgI%0<{_1boxxQWRXbay%}jCLp#%d^}t;zAYy5`?q(XHJOdAY(-F6 zS{4H`q{A^+@1qSwFJ+smgZ7VSntUhLas%U9jJRk2VOliJ>E|OVyEjkIw5hj@}PxUo`M*anv4~;b+KqjeXTW27^NIC*EN{e_RYB=ZlV_ z@Iuk~>c_18bs>EK=JlaIDACgZh&le&m(RNFifghdk>245#?MoW{l|Nt>!JBI92ti4 zOeL^THT&g7Q^23$Z8j)MaO?UX<-K=QQ)&AyjQTpxjD=AV1{D|!AR;hQL_olfbftt2 zO7BPwArN$Clo5nT4LwQ~2w>dKm-g(OQeKI2#F9Nge2tbSmxEYeCPY)ob~(G z`uvaO-aETI&;8u@bzj%@DF0Z07{&K)hAV6x;?RF1C~a4J)xV(&es!i37X94FE-xdm zL@a!G@sI@2XzcY{fv^7D;1_V!q?g|Aa6{F6i*mnEP&$Z#Z z+=19XoZp^4rO)p;5;`(}xuBTF8jqvQb`N|?qI;;ZybH%v@5zan>S+D+l zUB4f1V8-jR-fRCe-|q2b9L;+zl|Kq!+xFaQ>PyQ0xd;~NRbO-4UeF{%2|B-#yxC^( z50U51U-J4-RS-}g9{r|5`=2N={-cl`Vb+i{O7 z@ox|K>EiU?mAx?Q1@POepVy85fBgCDwr^p&k5B#UHlPBwBth6tEbbDpWR_7kOjf|F zrD{PoupM8Tcps1a<+e|9Iru4Kf)!G1W$FeW+A98i-scJwINX0nu34RwsiD-yP5!Sd011nzf$%=}w+5k=b5&#ZL9KLy= z;?fxE6d(rGe@Y0BMz$}9oGi8bh;DpObQiBEWe25I>11^MR;}`=L2D66 z*uRq;{y_u2^-tp=0J0s7b%~bnmGji9u+?ofABJI^#@b0o{E$CC+Ph(GvX6U1WW&T7 z!Oyk+3OxCZs;E*LlKl~kxO3gq9v!v(gPk7xJ3EdQ?@uK)^E}t^NvvH5P0HL#dgpb@ zIk#|sE9aQ$TXxb)BWtTWJOrbW>aTt05jH-mF3uWV2%B4TUnoAD9(-A@=O;AEs!|c8 zLzz!43>lkMl05VVzCb?Z$A0)ASL^sfomih(#bV7mmFqs+o4HGWKw+f6`NA+mLUMdU zAz*-6p^3Xk|Ac^%B;Siwlm%3HFmj6r{Xo0wGQNeAfDc5W03YZR9#=kmpkfiU68NUE zNU)jHcT8kVJi?G^KB)r=N>A5saS-oKoI`?ZQExM0s0}4ZeW_(&u0*vT!&IuK|C})q z)=AqRVxx*#tZ1~yZ>fRWgCF7{rOh4yPxLiKL|F? z8wJJX;^nj@H$v74DR#0v_PtZd0UzfhTV@$Wc2#x5&a<&chYvrt^)$^Uw_ zEBcJ;5>}xIXb=A)sC_fRU1-ty{m!r2*L%;oK;{!*7l`eeE~oMSQllOPD}luM4;1T9 zQ&;L=j?I!#y6$BEY-29KTJASt+ebug%fB3Ar=qtrLV2}+JYFok%7}&n2Ue&5MHp-V^&kVm^syvfKWCun{H9h?drUEul$e`XhaydOvJvu z$!;5!)%PrrLk!jTm>hu5!B@F!;YSCA!fBEH7rtth0biU!#78=Fho12k)`B1i{;Zmf zaNwx1=4ZAEN0VB=W{~s2(^(xfO|S}!;iWbZE(C?He9a_y!8!n4ogQP)DRu|h**}YD zUk=Tx zjPyso?C^DqJtS7K-vD^|`-KtjZ+;`e<~=b%QA)r^FlE>|i!s}2tYfXcla-A1HZfv+ zh_#ECnu`_DJM7Sm)X+mqouY;O12q$~;>{MudFGDtjnF0Dr5Yj2qe584|nYxuavYvaXi4^oa; zg(bl8yHobyE8YPxVP6A&wYo~M`@Wl#71RP-YXB!>?+SykD-R3=n3}-KE}_d$faH-( z-O*_D*akavTbuC8X9Unx*YI+Hobs#2x5FeIvO2xoSGXOppy!n;SWJ37Gn*?E@%PB6 zNDXfEJvcf1m-=;-9@r$mncXrALBz`2RF5eV&0R*6V^^AYxKANA%{=GVy*CvFZV3o%*Rb^TqVI3`Zr2SSzZ&i*nP7@BCQx{vT1VKnhR3n?29A zXdXndgD5?+@a`#aD&(lwcgQqukXgR0Z$s;K?ZO$S;HdM`^S0iLBNrj>Z>shY-<=^2 z^bKpp&o!_6;b)V3g7M%mR*b43p4N<^L(M^ifUsSQF?p*?XY87M6AoAUx88NjYP)aJ z+Z;jm((*`WpDST`y2azbh3vI*huI#ui+kt1o(ehoq_fTadS?2F+AmHvw5H-31>G>O z{Iv0c)o6bT$@`a9!njWPxY>S08j-Vy&deD16jWwKyr35k>O56k{h-%>Oiw(KKY6tm zZA6A{NH?iyt8}X)d$@kr_f#8`T?WV#JbH*JwluDQeRV^#QUE*kAjz1qn==ggVUhfk zi1+EQcosl{pjz$h*ba#vsL|lta)*{ICd!6Z+c8kYQ%MSO=;$Y70@wvL6ZfB4IH!2i9dT|THoh1&rir|12Tikr6 zUd!3^`=si$BGp+cZ5NHJ65OW>eO{#dUm6)lU%6VDa+|Ab)BO@!5TiD3f5awxpO4S- zy{q#ZDu@Ix7p1&~hOT23;@SL){{52nDy;fl&A&R0q%L2_g%A2fA?Vs+GMI(iva)Y* z${3@nHU({QI2fPj5|3|H9I+a&DV*F{9MGM;ZmZjVRXl5ET+XS)TU!>Rc?Iv7dHB#| zb?cZrgp~K^+8J!^)iV@-*6lFo`nS#R6!Ei9aE)Ch439xiXF>S#b?4+#f-Z(#?%rHH zctFZHv?}8`K~z^N@7N?*_kP8&0k_4OfmO&COeaYhz92s5oIU-M(jkmj*hD&hdZxyO zyo155vj#P?>RV+q$CK8`*b)h8hfPVi(y!eZ+tWmMDws<_kAT7xJp!EBEE7bRqr?l8L< zz62R|W9N_h@m!+AJ+C(y;MUD7>B?!`)w2Q8zsiCy#Wr?xvco&T#fnj)RwO8*sw>tr zV0p8}KO)D`bF+PQ-C0T^1woQ;O~v9%NJGC*hJ>$ZM!&FO7;p0b6qI-YW@lyr&jt5I z&L`9t*-kcC0JXr!3gEBXgnf1xC17Ksf8aiKxq!rQnbtwckylwO+`2L&h${6>wy+*T zd8(XQ9p3=<=~9m}s0MNkH`07WSWZXtJ!@sA|$c7RkdKak+mJ2?;5)Q&#>XqANrR zQWgE!!d?=BQyZN_$(nWQ9z!z8t)F zBs|(Cs^0+lF(?s84!O?Fc8Bc}UzBU(&Z=&_ zSMr?P98^*|u?X+R)!@no+~&t6z`3neOZ|m{+(f-*_2$qI%-NnCnMbDEB3{vq8gBJy zV^|i?^3o^#AIx-OgU?7rzqc2{Wk`pV8` zIbOb*(TF=ta}%o}IQ{*nH<>Ys9vii>1X-ZAo`3syxpkBPq@Ly&mO<@9l27>!?S5FG zZ^g$UpA*yW3uuJY&{Wi%#GV-m^`2T@Yw7Is8PTqnvv$c4u+|*nXyA?HTKJ`fKHPn; z7=_Ji+_k%IHQZ7g2kykRC&?(NSsmQ7-0!#IYsa>aWk~`1sqvzoObGX}(Kt~E$AQ_S z_&mvpTY8|w`n9Tpq+XDCMf%7gftF6mMRc|aK^Gq0Kl)(HXc56qgV5P_LL1ghxO9!7 z`p}u`6O-W^E#cv)t&(oKA#$Ay!=-h zHRH7|UY=tg)3C}@AWGMFcIUi`SL6#PU9IuGqoFCb;6_?>0(7GYd}Fchz04wQ{Y1To zHxd;ged+PI-9#!+#)6gk8$F7(woT;v!@rA=SxyS<4>Fr#xzT0?C4oxp`kejqvGXBJ zSo4yue)!Si@~e$@j%HIoNn#)0=wCMDp!w2Nx0jMWQ;+zWm9W{dXgUw-u*~Eotgopk zx5uX)UCN8o;9fud!lEd7YoD5V3#sQUH&QxOpG5a|&ncBoz1MxagiaFN;bcPRW@Z{N z-Gy7}xLvjp)ei}*Ji@3Yp{pcl9&M~2LVAy0$qV{4yxjV=YT++hb=;dXf;VogxTh&@ z+Co=g&dnyC#jGss1Mi80x>qCi(jZcn1-5-UE;HBGbh*-h_Al+@=OiSx>RqZYV~0iU zDICcq2j~pC{q*kRixiUW?Ni3ErB|LRsHHCTd;;>~pq23(-{741gwYkj zZF`n2x0ucei*0f{Ad>x=DC<*;Fkrt_e1&of9#rfR zP>34@w@(J=hZA+-J_-k=m@1Wz45YE<(xZDTXAUiK&EVD2u}-kz#*lcw^ymcvYG)za zpAvNQd`mClT4Ez1d1YrcKoUr#WmF|DL8@Xfi9iq1mv&B~JDrU}m@1CsxDC7}2ZWS* zuG(r*hvbz&Dm;f~6YQhDjo)gFM#pBM8@)*fmb7@@t8M3MJj)z0s=C8fD>0uxPo*+w zQMJwFOhQP(%p!w^)fv8gZiIDSGQhXkQzv@w>u)qw=dJO8U8T|g$8qsQJB ziqy!`+)UHUv&%l5xHBNZNadtc#WpJ)dG#L4U7KyK(?B9z!k-LrSbl$JrziQSlMY?( zjF${qS1w0;Y#P4bWgQ%{T8;_%rIwH=anNh68li)Yfbe!xTgWbUCoyv^Fd#HslBG&& zJ)0A6ew%haR?$WoVzQ@{P@#_B-E&M+zFOs==E6)s&26H%7H#5yXw)#=9q zTQ&X+0bh?o)O8F2sk;-`yn8KuXX;G#%t{t=f%1Ib9ag=<_>0c+oY6U7;o^FLCBvPp zNP#~$!0{V^u@_dJSDoytp}L;A3f><}$Dpy}T`%M--HNFTzIIKW+Q_OE{wlD3%#mn* zO)WEq3k>QUd8kllxa*}#F~JjaO)uoiie8i|vrqCFVq7S%z4&VVHyD-6YU0DOo~qBdS?^q9iD|Q&K`)evIo+o4`Luf$iOq(Pyv{a zj>^t&)(b^=9lkuZxhxm0UZr;ED>0ugLz&$-raeP>Rhq6c#LJOg3c!D{v> zQ@CA8Q5-Uzw-1UDxwG^|P8EH{*}2Y8wTy-oV9h-N^(3fPA_p!NGu-L|83?H# z)rkrh$|s&j+FPK^en`|mBeehe)HDDJ!LFPhACRO(PU1PQdXx#BBg8#3A6!%d_2rc@ zoN7hxWPD;D2?35a0C`IfMneea5n!_Y-br!b*w=r4h$qh8*b-eNBO>=16$Y?}Ia7*y z#lr;Cm@2yaM1A@AHKd==6#1e28y$dCkxKYG9b731$+jNu@MI?^lK6^hExUoE9^d%3 zjK4<$(6^qpw{L+E>bU=tUbQsL z9;Ix5G(jTZ(UiNDb+nCihc7Wr3520C9Sd#ygm^{f(XSr;$A8GJCzvXMbTlJ({;ITB zg6;o^X!gX4^A?gOr0>2hI!t@Oykm;Pf!j)0YaR`S3x?E$*pd19mb`sogCl2c|f8~s~?vfMoKX56vUd{mXOi@{oqQ>zpp^t=2OGV{x?YK69o z6`R0N-0bc-5UjMG)~uWqev$%k=uGqvuYgdU!V zdCzG1{cF}>j{>56JY3!O@+f`;g)O;UvAk&PL9UER@^GmRc)75&n3Gh| z%hX{kwaf%>hI%uNF;ioFGqTJKk{K0-S>tr&j<-}-udTk(b)MNhPG?*6MXyC1ipiTt z$GZ=ERpYbeEp!30NZof|L6vu(_vX41mFwsQUCL1_U`)=y13Qv(Tw1k%Ptwrf38mL` z@@}PkKq;Z7G<~Raxl=LElL^*FN-~vp`Vss60xaRh^_%MLuKvLN9k@G;?os5NT&U7A zujg6>z2!OA2DP*=5gPGMh#0*=a$@!f6(A~5%Pp?8;QZQdvEP>BUgW8S9%hkMmel=X z=A*M#JqU*NCY6nV(52^Vm=qWaWww=KTJ6Ca*wz}#^?)rUHLSND<^0ws9Y9DPyMipw z(x1w)X`WeJu8PRwjbt^d%!PX~H z=q;0WZn_dD@As!Z429cZZs{`87cbLU@01avfuw~n+`{deq~48OPFQwe<8$s0B6l7L z$)jIXxj$uQ0V~4xT#_9^sjB>5N)|&2>Wi1P%(uIeF4-_Q5MI1J8@Ne|MGH#dN$#}5 zm_g7Bgh>TGRvksK?W@vPrVid}oDFrU?Tgtxx9;(yYNO*y&WEVph0rxq9PzN1Uw*Hu z7PUKyA0F4&QiCt;jSlZ`tR!)M#TC@#M`r8z%N%mDF+GyKrxjPx|BTzx7o}D`Zr`t! z#L&z10@l&DRDeIKE5C8jriW$*c64JZ0jjmf-#!2cmHiT@TxK%wCShbapdoK+zxhTy zqDRaO*ae~SuZ6lgliFC#3I4CeRy9@L(Xr;Fywtsx_Qm7%>}qW@Ym za#$OKiw-mNMbD&WXd7*h7kRuwr#AM`{23rL=q6>wT+6`c#(Br=o!76JA!&A8(8KqJq%B)ewcv-jL%Z2iN)3VQTkWFLLYnK~OiC-yJGt;{XOD!Ob) zv3G>)dS%nFZis){PbvF=wOc zQIX73|0-+&RmUCwNGku2U6K;D#>ta=Zt@w@0Oa2O(ubq-J}K$n0eok5>i-)t z%8F|!JrDfRGvNCll*KBZ|5f~7btb@9{wSM&bbTn^HN45|L2v$0zWZHA==kq7f-qI| zqZ{)s+-ECN#^2plxccwiaiM(nBZ=V$jla8`QIW{7*ixr4M&!k-Df7E^YOO*2eh3O2 zE_W=^FB{J| zdBZ-Kh-@v8qZXGNo`P{ByBO|PABVaN_X~rCvXtrS zPWT>gE^Xg@)LN6BNs|Agj)5lP`1A!W-Cr>Hpo}vye?4!@@wmc#63H8#83YR~nj@Um zVT`SI6ER(o!x!3;hE()UG`e7ak=Cp>Uc(u0+g|{FT2frr$-WWGzOkic*H5aSlGd+o z#|MIrntOyAGT1VKvFx9uW; z8ss|uQ^qRP?SC{w*yn3+g90(d101XX#~4eL9JoAtid!(Hlm7@XY2JN}{qmz`LkSc& zLtb3<1qF@EJF&(oRf)uxVe8lGP@BDC6@|+yY>6&9#Ms@#9Jvd5`qt{Nc`Cifcy9#xG8J{n~)GD^*l&)k(Oa&a#1j)o9_adEzv^%i<@1dH1xq#d5-Rgu!95D$Q&@G)2H9GhgugBEGJomis@eH|MFJj zUF+3LY@POzF+ZBzu+J<37mg7eO%ts67K%zY?|xy3eD#(}{LxVnCf~)P0pbfYh3}Ob z{9OGp`04VZAhYZ<^YZRzj$bNSy7=^+VI@rZx>522^T zS9;+SprF_(XU;W(_3{%J7)WpBwis-=_B|mq4bG#TWNofus)gZ6m4E4*e78@$qA{q| zMvwRYz_KR6MOGqEV8F>a!JG9;M#^k-cpb`bq$4H#F-Cg49DE=5EqhZA@CoT!0Zd4~ zQrD|Hpf>ds(V>01@M zX9AHm0=ugGy4AYS@dGbCWah?Sk>O! z$x~$?q&MDWn?wKe-IXK|k+Jrh8>1>++X*puk-Xg31mPLa2_K{1qo2Ngqo#mq3b&58 zswVh}vXeJU{R0MjS4!Q~UAc>No{ov#58Rh~)VE^qY-Lbv)C1n?TpvlXWn)7u6cJHEcRaX*&p>eTFJ;- zSTuutsYSG%ttni5O2FU#$h@nyFtE1ij^uq{Rm-s zXvK@|6LTf5czjn-noZb;mCpMJ(bZA~(4pK$Yke>Nx+{~LBV2cfbiS!$hWydm3kDMS zIBBe-Ufq0%mSBmHg`C+VQzl+ve+o91)jmCIt9m2B8u*E@CJR*dRHEwR-|bOmw__|l z)-y)Fn|(97cXWCAuMFgC=+oILy9%5Ns1YWJ&f+FaWe0=(`}#GdLS`jce$MzXf~Ee% zvBn^l>7kVI>QQ;8-`joa2UepullL;~HYAg)I-s*ERb_HcgeilyZWrF|t}OlThAo6T zZ={4w+N-SK{9V#%1Wi>Jv0BmLcK(&SZWf1hOSUbifyds!+XZA6f05*KTrdF=bjI^d z6A=#teWn*zg8UC+M+|d;Xgv<-pD3P1(hMDD!%;*K#ChHlw#)e?Y_ zsiJ(w@;Y^9E9?x7sp52Q32For~Fb8BG&Q z;dId4FDJ->xdUfivS=AkQf*P5J&Kk;o33PPShOe4XZb_~Vq*3CE(^99LW)mk9rXFu zGy#T;aT$o zEvb}~_hyWjZa3P|pM~Yj8=^OGiKNA1e0Iz*Uyaq5T6~FddR;%ALc@}XHIzK>cX<*X zb}e}bRLq(2%ErxmHPcPusDf4I`YVraznZrTK_94GCh|Ej)R0W9fC)q*O@Jsh)SO#n ztE73aLDxFo+Vn1^_KEFoO)-FTI92@7=!cjF_+^Rw^qF*i{w5F->czN=9>EtpV6Z^m zRGn?iBFL^99NdmEZTBmYe^ok+mraLEQ>qj06W$l4E_lpWDMRRW;!ovgyC=1E6+n~# z$+OGMkOzTYtXRCW()Wb?M^e8#)vOS`+|MU;bd_n=@p9$yq}QMi0g{IqDGqCu2q}A` ze5pq}@*~!4V&!Cu#N&U*jo{-EBY5#z(WQm1v^39Ve9EePhp)PDOs%*h>wh(!YiyK| zs7OXjcyxp=t@NIL-q1ia1{G@@O@{r%$Fa1+HX zPK>kFmm1_|>TkyoAcm+`+ew4%Z=hj!FiA}-hch%-s8xFzr=*cW?sc8MBu-bTHoP7S z2$ZsLqgOqmF*>33Z$HGeol{uMuL1UZR`8%xPEwpLXtqObSCYJPg69kI@-vDa2~J`j z`c+JaMki@X^^h5CZ+eM^uN?S+X9H8|enEH%?k^?%#i^wv^noBWE$!My)X=IGwca_F z!W*mB%96%>2j%o=tzzbSLPkTKT4Q}WIS%U`DjtFAdR&>ED@?a`lpz^D-!?!-a%IGM zvC!d~bSyV)lOCnG)LxoraM_kR785&GU29p4-BB>|n5m^}w$?HkK&%=H=ybZ8v#}%43kOu9fM2^$>KnO zjDzvv-I3bGyDtbmvL(-;4iRmK6PdB3i5D&Gcf^5nhG^}lc>eVU?|H}^gcI1(?zA*n zRhlID^`MzikN1Ys{K~7P<=-zgcD~Yv-3)R(+>S19=`CAbE(_a`nO?sA?pZBXJI2KV zHO2~pUi~h7A_rS(GLoV?>0E3(DIuz#D^?+zGw*{wsFYKsvXK?2;(SJ1JoZ|Hi`IAJ z1#XXev5I=mb3Z@iMpe3M~crq`DP$(7;G|zd7?9=Z)pk=2-O*v>hjz{~CH? zV_wlF+_4Zp{)&2q`wkjABB$)gSclbTo-Tf9y^>j=DruIG85Q@^=IC!{O)(>B4-|Hx_I0Ltci*;nYTcs>%~tk0U_u;JQLq~H(ROj(JB7Nm zGnLloY1s_k+|P2XaYO1-B{^TbZ$Y=yOqF~6 zfw&>)NV-Dq^wK6}(CwhajpmN@Q5kM#GgUS!FP)Vf8l7rERJy1Z8>`iU<>xn&7uMG4 zWcO8OuXObl+C&c-DG2I}rO(W`$>{6q&EKBmQ*wyR=8x>mZ4E$w0X!NX2kSO~M24wVZvp|k&}tuo48@`NlzzFmljTV;>&(QpSbT@@|d z$-b8BgCzVa>FIS2;mNjLX##=$9 z{jh1eNQNjF=)Z*iJ;WMpb%Q8m{0Z;E;}9`DIaamu(zhV_Iz(!BmJk=2(4( z!uFwgdkeYorkO~KwZ+6Z(>41muFI|FZKm>THR(&k5xPT)_uOhkgV9mfq$3bO;F?j^ zA)Wr2y{gwzZjXv8g@Yd=y5QtUr~c#ct!G)otPq0QQj{;d-c}CSC@+MGCx%$ZvipXv zg~>!SgMwBV^+xD|D-RuNtP&9ZK9)L%qXiuyC~Z zNGRK=F4I<47Nrkfv{X>0UwoM*j?lD!YQ=w!ncGgNt+pis`YdHAVK2g(+fjbT^4&^P^@3w zL&@re6`sL&f_4Y$>BR8<8fuT0G+^M`%Fym`X~~7|@k2gQ0^(M6hlgXYwBh04GQ&lLdzOyJkdFCe%7~L*)>WWB>HAU+mT+8G_b=ZiM_<)z zno>&?oXbrsiJO^%nzaS!xyI5aoBmQ`0Sl@VV@J&u{q)UJs>f)8)N;^`Kr@)~#B#cK zi#0GJIB)!_7c#vedD21D>6I${Ohv&|WR_YXwhv_<+Yt0=wVTaKt|u<(%;;!))H&!i zl}1DvSVZVG%1c*?Rd_~)Bh|(YVIX`@7*BMzdG_b9vs`ZC`=1{QqEad3Nkzq>#iEXK zU0pAJI-kpLESgyz>C1cOWybsKA=ssquYHgMA&JU=kgkD|xXXkhHKRfn7uK#awu8(a z&*??jrr$tq7~{v_GB${SXbk9!m$Oi}ACaOlv%1QSKh17BTYb!|jxc{N{KuRqTvJQcS(01T_!+#8M~Zw4iSCp- zu#ww(dWds!96ro6t7gOr+TPIJEc{DicgQ7*SIl8hvD@YekXCkLGSpF?;kuxIOorFzRe(gu>Ek4U@6r7s!SF&Efi;oU8NE)xS;4Packtw5AvQ|on8qKjFOJ?Ag9#> zPU?fKU9Q8(bm_)Tt0a|+B@IML!z|-OyI*R@Qk$6(&v>GDvrcb_ zYe}^vuX17vqPu!uent8uWIaYd(;IzILT3#(TOSFiKxyhqzC77St$R!{9*0hXOzrHI zE-eOFCCEavd?EHs4UdB2`%dNFS&#PQkn?^!nm4CxV+b=$%~LUYbaPEuSRO&eHi5It*A zYPhF!O>e8O#5Tgc*1|!B6feHPmi5h&lLI=|*y`?fSNE zeH_Sd_&9l~{&wV`TlOvoW&*vr!i8r|coGwx7e4-~MQVZXJ$!?uJ#EDvaVDQ#=(j^i zanHKL4Hut12=`aT8U#}b`f~MDIkU~BN{H?nIY$>6^tPyl5ln6@dShY)jH&66rGieG z?eA1TGq|m@>4lO5dZ!qpzf>%GmC#@mv05O@etqr>UI=8_Og?$}Za5;l*9exR6MaI# zRJ3?Vd)5%MeHorJtJutnwt=N_KpTyeH#s>)uS^yy#VVHCg2#45blqIuZnnI3#Eu;& zwIr2|gWW74jIC_5i>1NS0iQdcD0(8JN6&pN7FGVeK0mT-O0IA)`xP8 z1KN`9f;x%uBVrvv=a3E=*;_~K+f^sis#b@0i2MxyMBVx2R{-|O6F7MCH-?t)y11OI zl{SQ#4NR>)**~Wtdf4B8v-h?=N*aqrb4p*{##*D!s0y?W!pHz_gK19v!F$#Vzp^b62S>1jqwdOg89)Tui!ITDZiBeY3FBGf%N0)Z1l=u~i*OEB zsnm@5NG5nk&3*DXsPPs{7eFNdCNiz7ib{~M&mfa4+9Hd~U6>?TLyzNE7HxdWt2 zvEghS@cRD~S~%1}i;Xtv=XP|Yw~;sU0HjSa|3~H%Z2a1b{|+7A$NHdfyKA_wmw7}9~&ER&GYFWcZT|M`gk{1Xi0GM8=Gu-uSzle5%1 zTmHQKZ1v`X+guDC`k%o`C6I=_(Y#cw{iD6Ac?C=dBVnK8_{6u!DqtY`Nm*-o`Wy7_ z6OQ@Q#fyN}@Z)d3x%fXDUjHX9T?Z(`|Gn?}xr_2j>Yp;9?OXpZ z-aJbm+`r`f$7lcS$wI)vRwV7k=T=f?>vuNY%&QHNDwjXC6tk)Z{2VcW$KV$!^WFbs zR%cuWXpB-n1tg#?Ec~Yy|3C5P9m)5jRB*P4+7~-2;jP?}eD}ZaqzVrd5xHxeV1>C9 zPR&Os7W*EA=88W%|Ne7G68^U*3NYGMg_^bYwg(hGJU(MFUk6Z-JR|AP_YY3${8Acz zbG*lUY~Q@DtK1gLd{UyXMA>QziTL9mU%X|2YuxNqrOdBtcGZVw^vuYoBzGRM0}pM@ z;u3w)+HYej>S6#>ChHy93Luxs6X3}=7Zef<5v25TaAo_Mus3Oy*}uodoh&Zz-}a>w zCzRQVsDYwwXco=Kqft%WQ@?kw^V#HIG^-|0VnFDR3^RbRbxZ1Y z&p@(QtNW5o;e6bL3lC?;T7uph>fP#n~;doY3xk~~BLEMF!7D?7KA z%juRqNvo9^euW%Rke;%eo0}@{vX?q)+?<-YHuX_``*ejIThW`}YQGWwqHU3;{v7DH zzX4cA!}%g5nWf2V$;kP-3eA7x9MQpV7GpI0@sN70FeABDp7i z#kjQp>H;R n$cY7f!2h32R8JKy3%1?bN~&C;|BwV6E@F7a>~ht`o4@@p%iLSF diff --git a/Firmware_1.26b/Documentation/How To Contribute Pictures/Push Origin.png b/Firmware_1.26b/Documentation/How To Contribute Pictures/Push Origin.png deleted file mode 100644 index 42d71da738f500bdb52fc9e1830294310fd54251..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 43035 zcmeFYc{rPG_bwb1Eky^aszjd-v>LRO8iTg9)zZ-rf>zB_O;JKZRkc;s5vArDiWn0^ zB4Q}2hL}T4RV9c}LV`%LBwbnY%weEF2zhQ1FCUQsw z004+xxqR^!03gr-0Ptt+6yn_x$h`ZT_rVu%%hVW9+;w=4cd^6O=(-UAP!=z`bx)9Y zz3bs+n*abnylMNNuhlpI0RWI!dgY?gok#XGwrI7TbLtWc3ri2`BC{4M26a5sE0_>s zUFvvDxYvTuo?Xrv$_XT9@! zy@LOhV@ICXB(a=l5KdjAC(1~4@RU}|qr&k+bX4-)bA>K<<2E_r23-Yyg*U6z5NmZ) zazLG#p{d=xSpop>|4*q!VL9 z73wJM;D>_3oAQ%^TxF)UT$`4P^~{yv(g6+#`+5g)#y&d^G1Cy zF2&TqL)zXyI-F4yV3v#gwf=4)tG)QSJoh%ECZNv4p=P%H?FP-TBonS*Qo}ib`{8Lt zPEUV$_2IC~!7t4Go8{?EW&{pMcX@>f#yfdYNQZlt{+~TH+mu zdC8JP+VX}`pX{W%D?3P1v*cM*MG9|F{DpWu5y%PwP8uZ?EB+&N;PM;OmsV2|4ri z3sshP`|fW|D)m=SV|?5`PJRn;v{c)TxvJG@YO(nl>OZYDMes>(oS<}VTy68GwMcYi zvW}uYF5Nu(0PFzNrB(PXJ(l3QFUP!fQP|e5zyx#gj-QYH)f>z2$R$D7KXh-s4juer zSyTUorE-i_b#Cb;G2PP&%1o^`TiQspb8nR=tt&uJ?xc<`Dibzn>&pcHo*X|dHxLC_ zul%frbggf+PU{6EVW4sAi~76Lyu~3TeC}NIA{Mdprdcu8)q#ylq0JKrZ3avdMGV4G z1;Z^z@7nYQIkXoxL#kxkB))}CsJt8pV-lzcH}E-V3GGs%yrI-f5wm z4#Uo*Fl7X4tuAaPfFfC0LNu+#e{=5%I6SX^stN=`wnvW;+^2%oMt-5rMm%kl&9*1XOG_q zUA%q1$6o|)g`l@QN<#ulLOOl${Z6>W8j&h##PzYVcM(5gUI!2f$Hezx*>9#SUNyxt znC;RW=%n5(fipj0a&KNocW!^)NIGKm*ZSyv_CT#kFLlzsPdVF>K1VoJXE4pUy?O}e zh$7ju3I>Cii0X$WY%3+bX;rW+IDx-rr0z~={3&m(;%63OI|p^)=j9a$`Uby+8aqX%i`pM}$Jx^j0DBrV7aLaF}Ek z_zRdx{l6)&)LVShHW&SKjukTJG?f&5zlkWudPxKCqbAaIZAJPU5<0!NT)U4&i0=;pC9ywRwgqh;(eDeK4U@J_S?Px_PvWhC5vG%G*B zA5=ogd!3VTjazo;Qap8B6>~71sg>A*n*PA(LvqJpU4&mR&i`_rkmz9()8R&=^Myp5 zaldKrZ-+Vk0yGE&Bn%>#mmBpk5vRU-5?06DS{&_$iJ9ZFG{SgAw?X)308&oy2SN2E zY$?r_Q8Bwn6&7Vb{F$q}c{=|RnV`x!8@G>KnO5R?ZxH^PZRf^iGkXcN%1ky1PFdvH z<}aH(p_vBz^e4Bp1iyAIr~YaGhJJ}F9B&%(TsB<7s)pU`#L7Ii zNDkZhp)#DDD0VU~H{(m|dIyF0+?Yk8Wh+X9Z>T(ZfU{?j)Hr#^BhXvW8Dott z9*@fiwwe#j#rAdSl|kif2hY5Z4R8<8C{= zb`h26urczPisftyl%BiF2$-E9F21vmk5wgTBE&GCxT9Mm9QFcbxb5lC0^3By+m=Y= zIU}CsY*my*zqjT2ScQ0=kF^qMi4*Uxy1CcV<1B`}mdR7on zCQ8!R*sp(04AxZ6p9=kXGS0V?{$WHl`dCok-C*b#n7*KTci}Cnbf#p&O{7w1=?~V}qw&kNhdMZ7OX*1?6wfXjSP{_VIe8bm6SB_jSiN%$aA|@xo^$oyPqlkG7 z{->?+8)q2(d=G+?asWC|O2|elz zjtN~v22Te?A83obbkYWRM;dSu+|uj^tzkFLCA< zjww(#s6pQm;yl<~xq7eqP-c*=bH3q%ae$jWszAIWE9$nOqg)^r7PeR@eQWDYS*lB5 zYl45n9p;5d8;T-ga+E$5nT~c4xphc;$f0WQsE*LEsu)XKDMq4Rx= zAcG24a6>ra*k4kDFY*V}Y%9nVMIPVkQ1{z&8NMhnw9S3`C6g`*C$B79q~3G`tWi{kEY{(vP)m&#PQflY%HI&>SC4poKxn2fOW@nb zL3Ku`F3u_vXxH?&$H)t?~K{?3+gEWAhY1+jwXfZ3yzEMB|qG9?#)5^ z)e^CbTwBg;_hew{3BegN2Q;Y1rKJV+NFdx6r^nsg*Ey2*Xg*p0X*QG7o7o*zm@!jX&4`uD+~N z=QPrYAefQl&Y!eV-A)y**C7$k&-*x-v5r1Dv5XXU@*}55lvdEV+6IGZ(E4ZnR@X(^ z+g2}cg_)PWQ%&}I*PBoSyq4nVO7&A`1&@IB-1H|lJj&UR;1a__W~+zav1WZh`heMp zrH!D(mzZ74!3#H2ey7IL&UdyO%$)3DPGDYxyPYU46HTgQOkeIWhBPXRlmI^ZVUNo% zWvdQPM=xze!8Q~tSXzB1sYu8@aCbQQ4>dx7YbbaZzL|w_vlLZVTlrIZ2a+u67LTL^ zvZbTwr{pgaUy5G^e|*~ORwKNa>gbwtWW_@D;{mx}_Fjq}P+qB$`ZHRC?v3fgW4%gMbDl~vRftMCV0qT^7OL(`LNiDK?Sq`rEzw7@fFTv zi|b1xs;bX86J9jpyC4f7m^g^Nn@v+CIprK-e+){ltUn>?Q-ZD{iMd^=h_p`ue@ROS z2t2xNB?*Eqf=yWQ&r=6-fBNf_@<3H@Dq3?vhJtOO(Q8xFbq`46i{fc9vjrQ&s~kn& z>$cH)7=Przf|raDQ49J z?#~GOnRCV@&uKnG(=eha^)st*$!_LMyf%Xl8_$QMD3PY`5@=;sCVi4g@P*OFvprK^ zS*c;%*uMSKOo_4laDKWVV@!Im61ERNSZ@m|uvGQ4&_Vde? zZW`S59@$~>yHbbA5txEVn^Q45Kn34tzc|1?KA63+Jav(ZXNK#VG8H!>hoe_QG$(sS z7k*x$|6C+H3k0BNek!(-o3-?v+drhZvrRs1t0xbMC)Nk!7+sH}&y2}?Y`(4=b&|No zfsr4l?3F7zfRjvjq})CKnjz6L@K}AmeNN9}F480LwJkLgEguZYuyt2b18WR-^-lOl z+AzVJ$90*yJq=9!JK92gf<#Aj6f;mZia%gd`#8#Hf3bF-dEJaXt1Hnqs91@76C?~s zvSM}p(;RQ=K8E3%k)Q_6({W-AtlX=52qAV*FH3<&KY=eD4%Oj@V zt|;8>Kv$K z4P95cpUk=Ox1e+)3?`k@U(Q8@=FeSV-RezU)=eb0Ejt=2jy$JWlzIj!gmpbg(J_Li z3q^$=y&SnLNKlNxl70u{cBx0JQW>da*bJijkQ--w4g zie1}D0~xfujvU6tGlEtW!A^-tdamQa;t!SCv}pOfecR?%AP`U^;EoJk8blqZ?mj7Z zP+6vy(o-#{=>B~3zT}B_d;y5=0M9^2o3Ti=@$7K6{M9OH6ddlaX3sHP>z_5Wj;Ftd z-reUSEZi%BT(p!;5#L;^zo1UjNu?ZIiWgE0)fgiMs;Qyq(upmU3n$va546IxWqwe8 zdCFhQ4Iz>wI_Asujp$P<>54<{q-zyvk2cb+iBD`7G(h`h4kuZZR``Yoc5n0;@^p_Q z;mBdypgK2;J(D4s?4YOpGZS>#;`C35))xZL#6mlWCKK(Cx=R9o6u*en#?p{nyb+<1 zCrgb_0`#R5>+_RQL+kN0O9e_&ozL6UbdA!W?+c}6NBgl|E!*h z3-PkXjzW8G-F7?x)+pTBZWvG#MGqDK?pz&dbI(Tj*C|>o;dD33WCi|FY<Rj^IoE zoL0Xz*m!A9kznl$+F5ncla<*j#^dfgzibBq;&yuzB4=<+4sbB&hRT}IOd>bLK2-Tj zXcXUTtD_tEz;Y>w(Co2k?1R?tJ6u}tx}{x6^a3>9wQ@XQl^Fsco8lvfKVa{9svT`S z+kJkAi^5GDs9x@aMC{rS^9;;VK7jV3#?t z@pUp)>9z50;u-U3$R~T-!nMr zL>!<}v-*8q_)HJ2`|LTt2@1*K8bMc}a{7a=_hS~vBtRORY|wR`NM5P?8SNw#I#If7 zlauC`*SQ2jm<8iG?Y}0XjW10Eppa`*44ChvsE4h+g{m%{zShGw7%4Z8A9nS%c#&Jf z7Jz(~6QIjXd~^pVeHolgA9_Nqdw&f)?IC-P*7JxgpkGC9yEzo+YX*~znn^w2O>YQH zQKt=>833(k&g(9=@AvAxFo!NnG#R<&nC3#V4=A}lfR2$z7aG8gR}Lcm%Alloi$uIW ztUK5&%CU_3-BcacOlMM~snSd!&UTK^eO}B@R-I5$LXz0SR zkKh=$=djRgV|hVcWkT}>=R;u;38YX6A;D+JU>p0e!t6tJ4HUK3BifQlDALUM`%is` zg>B?kyQ+It(vnYm3Q)Zllay&K(vojG6TpX1@IKi}WgRzry`$Lhx!PIBa0P7Qj@k3q z@{X+IZo86$RR=0nOVeA9gha-z$-9<`Hans5vwl-7X=@_9=cvT#vb6OY0Ie`b7%;~S zaU6^7VS2sqgeLAF*D+nl&54MK1D?68Bh+49@6CSSuSb}x%c5CJwku2ZL&2+1TX(QN zaROEu9pbf>Z9SoT<+6e6{M%W->?Ll$oBiRWwIsVLDO$FiKtK&x4q(y?*l?*CV)eKu~ISoN2Kge`=e3Hh*5O( z#{_5eJJ{}y*6>M79L6>GdYr8_u)NSfCVE`ebW&XeOG@K5|EwY06`I)&Qz``Al?$pk zZ6tlkA;H8>HS#GoS?nT?u9w0Zc{PZt921In4+jxzAM9IMZ67bD>7l|1qov@B%d zdtj>9fm~yp&x*A!D;b`>)>}O7c5>Td?SyBXTuz_C+!fosN^Vb-m#)&Vb#OqlHP&0= z&+U_R*RKGjY>(q&kC3f>|-L70u{fXeC72M_z*h(EaNA%H~;%E7U zhF-dd9}(@DaAbKz!<$;ekqz;VRs)~*Y*ur?F-mh{Q7^+h zo`O6|wkK}{IO6g6KLUQ+KRUco8y9{ryw=xGY;~9{eU>GT&NScEk!RXo&>G`G(iQ!= zR4^#Z!pbU~E~w*0<0oZ^KVG=mwpD2jkIzjxpfSy=`D-ZnnGMc9o<>0AlgzN1%Ae9) zD5uVwF!Rjonv1X7UL@9?ldJZaxh4z0uCr&zv;=)qB3~Ch@giBtJC2P`)t}F7G`tV4 zW{=EmbZ|ERV*Bz{*A5?R7o3@8oU|f~`KX~j-c-W>>Ub3D_oMWqCMQ|xU<`kNWEan{ zMs&C#w`$`)YR+%Y!fL|>mmYxStAmrFi$aH3{U}YNz7`iDT&93Od+K4KvP z`tIQ;ukq**n!0zx?B`#HJ~^jWM^R)X}#lGrf%8v4=nICY zw*ri!3fTM~8Cq&yf-~k1ZlNFdy4tZAw+*nt)zdUfsN3am4$or5E=fD1_dHSTVe z_{En0&K~!PPqcFbXSj-s1q+WqLmqGw`(Eu*84>UI-zsTg7dCP@@klm7a*^s=qe6l# zaTzpjWoa6{#FXtYMJZ`$Fs5d*e*gCrh?m1u2iWUeHi=uoj-hiESp)~R@6^NDC;Xq4 z9#wiqtO{>zE|qLCmo?&^(sJiuFgXhM{G!E_rCU{z1@U7K`p6bcXSFFk9Xj&@0FCePDGQ|PK#Xx`eM>B#0RN^Km;liw_c0RzN z*!ofDOOA_myh4c$W_P3MPlY*SM+|4}2~tkDgtoL)Zo!^ieH+583qt-bgEUA~ix4?_ zf|s>Q#vUV%rmC^OHqs^W6GT*!tla?skKfOzDDwv}rFfZoRZKo-z{&N)j*}a~w>jaX z{sn-I_5rTl56JN`e=dv3Wj0o75GB$*%EIA&jg4ED%eIN&u!$JqP7>Xp&ZfLmjIC0s z;Lg1I?Tq$;JKH^!0~k8(Nx~KF>=?7+sdc)fi_{+W@6Rj`8OvBdH#yTtNPFRjv$_^z zh%p8^6IVX5f?Dj)be8-)b~eN-Xbt)8HTNL}sZ?X(CKNGqL@n56ZxXI#XNMt2NfO(w z>>*a1qgxI{SJ1cUk8?htIy`KGSefCcm=_`*qiu_CcU>ut=0-)pUx~DF(0ak9!V#8# z{HKpPrPHiP%X?QF&Z51v5rrtB#_wI+K~XKq8PDN`tvCMdW)q-=7{*ETOQp-KlIK|W zm;~yb;j|rDz_aC-Hnd=+V=9JvjO8+W9QTlsJV^O;4oU6K)qE)-H#AreQV6l z%-OkBy?oLY>~lb071_V!fwl3JBOJG+u%9MSkA?bfktV;pmYmwyUA?%%385rgn5hFa z#3O6kU(}C=Uvd;$Y4DYjH@CKoEgyNs@8TxYy0j0J>73jER;)=-ne>QeFty;j3e2a1 zYhb7uL~MC+4T>1~z|@QcPfWCg0o;!B2P8^G*05gi+((q?8xL=k*6CQFiE^s+LO$je zD#4?9cc-rq7u${z*U4=t8O4gc$#mAaG#hkdC&MN5xCz}s|hPdvS zsr$g_ST|dkY6ZHs9_Gs6e)b$6%$vidVU&vzgRo}Nn*(dc!=JtcU;n?#4QRi-jGJ}8~X?)@sYDor}C0MR`eyisB*-KkP* z@H4o6UqxcR9d_M$nQ9dPP+D26*>uCD#Dw zyo%i%0RVQRItAzvczw=0O~%@>Qxd2613Cv%BSWh61J<+_WO(o3-tYL*y`^_!Xf@qc z5!T5t-KENGikuL%1@B&mt__HwUN6k(+Lg!vJo;uLL!PgNEp)9wy{GE8-gk00@~d$S zQ;z@pPTF+}3jV!rGf{E)OlyL9d=n|#cgVtb^JVz2p?3>YT6j0xw>CEo9NfWmkiPhe z{VL(3GY0d*m@!S{Ei!1!DRF4Xs#nY-l>jE0KO5AZams$1u%uaRC*;D7d1tf~)94>) z%RCNsCF!cuUaZpn8YjYtX*P)*rTxBCKe)@hU=PLdE!%C2;=TFeK|;aOhntK6#j%(o z^*=X8xNY*2=-6Wa_jzFxvBy%7V(13w+o3W&^h-z=o2jmQwt9wIen)3%43w=x=9~pY zd?)LwErpi(iGcHT zH;<+Kwy%AU59?FRc1(DhStmFcFn%REqcW`JgC-+LnvAyZz5j&<9W~-BxGfNH!om3TBoasXBi{7SfI39I8fDbILqdIT zoE){=^eT%U5;Z@h!E066y?Oo)vW}GeI2<%xn#{lJJ$s*R;5NDPYbqY7grp``Yl;6hx(Tu5U7F?^1;W zkD}H2h;;mPNWPM79(=Vh6eN)Dtjf&+iWu{t!hv@HeMK2;l-sA05PKvFPf2L2kJFwejM-Yx*MulAl zGMG;J^2`T=H;!p1?3qIhUy_S0R_Xl1e zv1@}fOUVlOKp&l!2bf$<5uVBK4`(=Oku9ti%yAIr@Jc#ZUj8`lAu{JWcuJPhSMBP9 z-g-At8oygAX`pk{SF*e>1UFu~>o~L=?3$K(o~ay}R=Islr{o;kPJTncZBAG~OymHh zICULbUO2Zaa0pxT6Xau@E}h@@UgE_XO1|WEwt~@lbKNl{*7xlC3&M zRyWky@#g-(Hen!i*qbyxkn?erPTHu=bS6g|7mrx&0^K%e=yYT;?TIzAp^^Z@?4XN| zK6ml@C-p6~O$VMw)~w~!kJcpS@Myx=bx=Gfq}`)tq2(sn)zG{ptLj9T-wQJeaI4cYY{QnP0toOdhg+ z`H0#V=b98-8Maz7-p5b(+pBq$%3#y5X;2d>e+aR}KZiE+;xkm z;pG6^vlnW5LqXftlvTfFN-9zdl=zD+&DwJmti~jF7Ut~DAERcgPa-YlN}h1J+ZBzw9$ z>~NewIaeoWL>oU$HQ1lbm(d>+s3xW`VeEhaY*2)Pdvo3!)89PeQLwj>r5e@{x0>4C z_#KNiq9k{rh%AZd6a3#KcuPv{_n+tQ_56PdE%Y zv9#J0*#!?SiF#jCU zJcYWwd1H3%O^RIn<=|w6>dbWBlM6gJ>X}D>g!2ZdnG$v3!zaa_4aPwS_ySe`89JOA zEh};)Cg6r=cE)V*6-&=>w;G@2*{tE?s6{NwJ=2*_!S~;O(_=@xNm4#L*x!B#Ukth_ z4kCg23yKDvnaR%(?{|Sj0U@`791R|=KSNEF_9T>8yAy2d{zf2JG7O4OBm;5Yi z9Gh|?=cm$}+B2-$FnBic!}dCB3w6|#clwT^+cqT*7r8aH#PyWRJ{|#Vmjdua*);w= z)$?(C##!#!+w)mtD9Tya4N9vh$y4aHE3Y~%ryb!M&K7>G=|lDknAy_f6tc_`SK?z}3 zO{n_Hi&&7aQ*p2ni}Xj0@`&}lDQmM%l{vwlwO($rP$yDHt+`dZbk!g5IB z81<+fUDj}%SCNZkE&efrcU@8lKyU)!vzanwBqZBJ?|S>w${rA`_EBv3^7245i$xjp z0nUX~J@~ky15&f7bUN`QO*XOy`sY9iH>4d8Cb>Ty5*&w2OVG3ZfhY- zUbh9es$e}{c{38OcvWmj*!#Msg?*9>Sh#W=`jJw5X1J?w^_^-Z>p=D3+<+#vkvL@f zDlQkum0=B5$o9?6>Cla-hcV|=$J4HXIbpcDX6@rfu!_N(q-7`YJxUyWc<^(dDD->w zoOI_WPj%z%_dl$CW|bR^CsSTq{GF;|9V{z@dlQ?Didoa<<+qEIontrO&Mnt9$M3(6 zEX9GfI(exEY&_UlbL?3Rk)To`gckwz(N>#Y!s9NYmOtrAC`fpSbcnQB7;IFWR{$HZ z6r)Rv+>=cm%_T256$HP69@yF8DNh*cI?OEW2o&tJ7#grRe(#Z~_*3mwMH-vX6eU#PSl(hssjq(kBfGs~W|^1Q6>VwGt{Q@)V! zv*E3>w`sAhR;0$myE}RqKASW9E0xA$9&o!}l6uZojcf%%HH0H&W(_#g$ep03JhQ7C zq$8Gz%x?cN6*%4{mDF*(6A*|^woMwqE<7&Znl%Mi4tNe8XgnKPW9OKbva3aw_Pk{5 zJ~8h|xzeuW<~?(Q#7KPQ>~I@wEwQUgwFOnK@^!QQ{kQ|YUy6Z}X6E)C7a`BpPRFOG zSBk^46be;-Are;}I8Y@z$m1EU&jr}_a1JiLjDDh{tcqj>f2HNY^I6zf{&LaNB3+rz zH*^VtA1r59cx4`SeG zgW>E~oUPe2i=Y~N8IMZ0P2g(b|T_(WJ6=gvK_J~h3RUbiQDLqmb8N0|(2du1XoP(Im4#Fb^Wo6$JwH zf{BvK4}}Qe?r#R5Z08FjvnQe>E6wYMT54y7DBsC$#CY6!k}{v*cKz_S@S2)5o-@;22Qq6>Kyv;i~jNj zd)1pI!Y189-B)<2W45qFv(ft4rC8-#j)S~YBN<}v<;rA3{?rECXGzMiW(@W|3tCa* zMd}Vkga=Qq?PKR(a1-i2$!q*A(g5R@?o7!U!}iGW^6TB!^Ye?shS)lZPJ(82m{-fm zKzHHpy*oQX@_a^@*W%y#OeE^BA3(M9IKgf}T<~@lVpqg&eoYOr%ap1vDx`CMMjmni zKo;DttmMU$8m)pBQ0tw@ZOjf-FK!G_o=JG(lDfYO)5wQb{|gWSZsLLukbBfHIxz_s zPKuc@mvXmQjnv$c-8Y0YpgeHhCIN=@E&nxe;toRh*@M^khPh=%C8?0~3+?>dH14k_ z0>YOt&;4fmj=wXe@69b9n*Y9NT!HlfW8Gj6Z2)dke~)H}>%BaDXsbQirRN!$hqW0} ze_<^jfOd`Ym`d(IxLFp4yV(E^x&wO~G$O)8!#DTt5ni!uO#QW++B^op`+ft+ zuYPH|mM3mrVQl#SH25DW{f}z=KW7gaGUD>u9x05&&$&-$+AG-tm3iE#A9?_Q4qxQQ zEPs1m>Z7yt9_gNKDJKFn=C5`z*~%9zNpz^4tIr7Go$(U+#|I=E9SON2nQ$RB#bgnc5NPn^-pB;`M1 zyGJ3RY$UF1RlkRznCTp8sqnX5WqjP~UI4D{OX%?#b?w8PF8pA_T+>49nLLGTtr^U& z#s%q04Et&wTk3mdz!5Wo|J!bOyQrwB_(SG&gyqdd2kGzSeXGN3iOt{q!FJUNh-jBF ztN4h8azo`kNheQHc!1OGh0yXkskP@|_tiyu&64B3j{e7ASZKAX1kny1WJoaAa4Y-i zVxO5H?eX8(T;-TkFW$wqv`(XYHnZC-8+ z3Lh$0Etl>bBp%>q09gOW;kpS$i%0+Tr^uYrD8xKFpvOCWdG!AcS7g##7X=*ZVhVc& zb0g&R_Sy4}V`SX^dlygf9B60Aq4+kQ3mu30&C*IBzwj`E`zc~O9l z%-`DoQc^CWurL==ps~|>BJ;OD0ODynQJ(>33!I+|8CDg*$mS3 zBu9k-vl{;>6hNfiM}zeyYy3p$Xg4RLOk-zC=z4w%epXmi>qg3=@2I|`XR!ReQq2tU zf0|_A=2oAXq!!vKM+X`QOnn)_i8g1F!e0lm+a|=?!clo^!F3kA`WB^s8^AGH&e}Zt zJQylA@Zzuz*RD_U@z}wASvNpfykq#jBx&Cj15x*9_L8VV+KN2iz5i;cb6Qu#Ka<_m zE&1TW(PZkm0f0|tP}m{7UAyXY15uyk!GI&7lbgTPvuISmtsuVb1v7bu7_s;seLCT3 zk>$_w+nC#;WfNINmcP1{et8@j+`18ASvsf(n#w&MslBU*oHl{6jh7DHongE8Z!3;i z%&wo}zk$0UdLl8U@D=0(wEKgZcf(aBLhJ>R^4kCyr02KJm(mT*x(pM{cre*ha7D~$K3o;Y2J}(Z2Lpo z#EH1Z{>{`FFJJDPeV)OGUr?e4zX+l_rfItCMn^gdFv0nx??KI$rNxY(HJnq-Oe~`b zqgfbRxfqimfc@9q&Z;!ILoIK}um6ZD7nj?pAH3M0jrPH~Ig8Vq%Ey~BAuy@eV=Ep~ z;-LNe=3mKWwFYO}#9weTsrus|s~@|NX~LH$&vWYHPk+6heCmSTNLXp|$AFcpfhNYF z=FsqgOS-z<$+EcT)(W&xJ%cScSL zppEg_PRvE!Tl=02WPO5~Gz>eKNETGI4`d||_Uq9nR0Z$hFNv!bU-QU{N5epJFT#n_B}NnqAWP!bx<5s z#dUNic?r_G{Rie5zzjPpFTq=a5av=G#BTsgRkgit{mM3?{mFgOTc|g+yc#K6ff`%$ z5}keUw`E1H1S;eUfNy%fp!y``6vr?AC>xPj>8Z1O{e|~h;9OE77J@4ts`D~KWBpwd zzg*IkgzYEYDntgr)})$BIjL_FY<{tsx~ znGrwHE_d)M?6+)2>Tbo;5|;#!8%8$$=iuiP-}__Fso|KOlY2^{feCBA#2dUF&w$0> zq{fGTNFdeqe1GX<^v@1=MBkH3dO8!Us~`q#6m-jRdFqTg&*Jq|KKiWm^w^;!WYxJ1 z=EZ_tjniE=2S{RsThxkNt)u-|z7`Mn8X=v%e>-SLx5XdlG%U^|WoVa;zNL|7HlI#Njm!-$_2FbC$d7~Ae%+^~pIllh;rFX?-U6CI{0yoY7V#*eqnp9&f3QFD zyNGbO?04X*`yM$^wm^S(Sca5c@R-XkjG9?CBnfv$jjBzpkzlThlhjQh8%wufyLT$Y z|AX}(?)IU&LGR?k54cHb&EBe*OXg*nHVY#gp6Z^hR9&rI=?cm$)^IUC_j6oO_7E@u zOM?weUlMk=d-#n zIXlR=S`I3o_dx-v1^Vf>k(IYDzlsW6UAmKFSd65iuT{!cd9sW9M^1R&4NY6aohuRu zJoHcBAv)GU!oPJVfX^iC*a5~twy5tqhSPd3Xwh)J+p@E=H~K%Pce9&8(QHa(&Zm#06(xdc<0Zj+l)e$}hUq`r9n4=R(NLwrKmBa)%C zEd{&9)qUVV*F?X(R5uo9^)yNqOM`r#u$cgIJ5@w~3I4t98D~kMMG-|&CS1om!Uf5> z0uao6pl9Jha*RQgh~iQA5zf&lUKs5v4zi8QG`6w#Mml6_>`E-JW!|`}Z@KFGHlZXi z5JjF-A?m^?Be!avljk zfRq+QvQa0t1X7><6Q}=*LY~Zg^SS-9vp@ybofHuAg_rw3Kr${&;JpLsIh(v>ue$bd z7syIfI^no(cOtbcgPCJT#SlSLm0t!ust7w=eo6hq)4#>smmX^9*U5i4Z5#`Hd+46k z#G51`4y3k*bF-o%5|vWTJl5|G87pRI6eavHiE$ni@9cAm?uuo&Pi);l5mN>S4E80x z3I2x}C;%m`?bi2>S$gUA;A>MO7QSz@3;YVf@A3(>oo(_td&(aD=SS|wcxhVWA{GXND2Dr!-tY=%{^I5t^cs3%;hX`LZYyA$ zGZ@~b98FyCoHC*K{)*p4P8&hwuMJ_`SfH`#>VQvUktpa`;sjp!1kC7TuZY$rz zH}v^>dqw*g_zp`8&jhj02=$dd9X7$8yX8^!5-0IX z>>okThKXo3)pVhZ3yt53Y8^F-H`N-uwWxov3oesoNNp^VKPs63CAoJ3PZfEFkfcU} z=3pRF=;5kQx_9f-h5pmeL2Z#kIF_);Q;%lZD zP=61~WY1?=05gX9_X0gwA#n^zKSZiERMG0<^T9LOQ(l=16x=7DV za3k$o%ylNhVe#qSJwhu_{@Fy01mo6ReN&-0|I;EeB70v^AKR8+L#G)#XXB;^jiG4h zkh`RJyvoprxe9t0wxJ~TafPw#Io=v%!x5v{&6m+#`$_OggKRS5+z2evek;K(SRBv& zIKUV!AMlc$z4Pz>o{pZk{XR+3S-MuF{eH!7l992G^ z?Qb+9Q8(0`bS_6rK|zxcotMn8OPk| zE70nd{Ekk)PsxN+b@g>5jYa2V_jlNbL8R#K-ztF~ZmJxvj>s-9-=EMd zxZz=28fk9wZwJ{4&eD+YLArOJ-R%C2YaiV2C0PkAJbL69cgxa+pj!u79;3MBN7idt z7}E)e-5=WkZq-AN-WYXizj4nd{>uU9aA4qwKI5SQ)ll)@6eT7gQ$g~Cq}x_~ z*8gJfP2-{5!~gM-gCeHWv6OA?1o#DxsCKFNI!y_uQZLTHe?Dx-RK2=6Ms0oA=vy z(Rb4e;yjOYb;Q0$pPu={i2+s?ZSreGQTO>JsL5nvD>=jH3Tn~Re|8%P8%)nS@xYV5 zqSB|kafMsgwL44f$nb5Yu&SSnk~8;O2}U{)L%BOrLCY)UWg<5fyOP}vrfsNy-JZhg zJz^)5raI-re%szT8-wIuWbV|_e+LZI=T|kyQ#8*0dg+JS>^+FkU^pLl!)~ul9$1ePgfF4!uA;&}U*(`m8u^7! z8}=b&LFKPSZ_OZr3AK5zif_S+yaIgD%fn=pEvvt7~%>kO0fIL6N1%0r07! z&V^`OB}^d2PF}t;yM~rF*1A6`&CJM+(Sj!vAP0wDju&KbwvL$2M3@b;UhyZrO`trj zcXo)YBzJFe0a}`a`s4V}%&A=`XdP@_m^FJxvWHCfStI<Zd__7mz=m`O?g!@DV6ShuN_11{AS zJg#N@vfw!&^1U}A?Q&9@g&T?!0*(%ciL)2@vvZ1h&%EC(ZaHB8G z1g{mMy=YuxYFC_$`ZG6cE(Px!MO$NyMj4GE=Evp2B(^6x1?>n+DB-Pw>v-VPB0A;C zhL*Y`433}}Lb-K>S& zl8WOahoR;N$9mi)10rmXYDe%|MX*6e$R~1v#sxk-WUxok3OsO2NG=|WKJaZrgpv&J zXNGKi7nbKf?-y{_igz0WUyf6L*kDYLdnW4}=g~LGo4l+X47)|6pOV`_cy5@)4p0^U z#763Sv}U*++DJ*xV}svS=O7MB$L24Wq(b7Pp76a~M}CX#`Kre;- zV#XFMj;BT_9QPHH7MeIG2bMM`qn1`@v0;qYV%*!bmnP0*QLF5`t@?hC`SL!E8>mIu zh<`7@=M<0RoTBv-M*Yw`##xaIVS~3bYFuBtdMM5r-#FY5+l7mxC-O{8H_Tr>b?$pJ zTpd9e1ixGjyy;dEK{`^M)%2TlgP~~OuUb9d%iedLn}|kNGZ*-fmZA?jK?R|Ff?Re6 zXG>t}K*p*Ei>YSe&+Sq}a8#NNqmZDa^jl^s1xO|odo(5Sm)_HL^e4AWi@v9Br-n!4 z7s}D&!SCW)RrZ6rHv*Hb2ebTjJ(Y{6B*%Y_Yo*5(qN+pTEe&2v6W@q27_IH|Qj{bw zB+rF-Z`2+z#2ONk5dDdN!ga#5VvqiGl>~ATm;?cOe zt`8J_SMv#M&BVQMi0FG3!8y%=>tMp%(uwrP68SK)9{KAF-zqU&+?U=e!NSvAvnLye zt~4H?iL%;q*;+)yvG|C|_+!QKW=j*E*b@~;oa5^f@xw+fMX2o)*%cT(5Wu&9)-O`L zeuHar6+Q_MpmgG$GOGE+^;^?|`yyAlrb%Vu!zEqfq|Ex@o!fxQbWCW858+qc_kjw6 zt~H>t7 z+cTD>Nmx9y_t5v4_{dhOwt*F>FnHTQq1`23F^b3!QidX;xs4>xK75=DekFm)gfuk) z^jgcFe(EnE*?(hvLm#jtKV$U6pI=N&ZcJ&0zvAFsEyig#)R9)bs@1W7Dxpdy35#gu z@M8c;`@g3y(j>)by10QQ$v^*qAAK z7KR8oqzvqg?YBkpcR&SVD(>{0eCxS*@jH5z|w+7o2j(7T+B+M3~On> zJF$}oD_2N%6Z$&;!wfKSV2U8(zJJZrIMG+4rG5gvy@MdP)(OL(AvS(YahSwKQ&_pw z&1LOTfu^$nf61kQrkkc+FAK8ShLJ(#1*Vl^uT%?3Q94Q%DxJuci?DL#yskJ^49g1wZRfY4{maE3^CE&4 zZ-2+=6HofB4Et1%Ll9v)O8n20@#$ErylVX`j&mVdj|Mn1x5Yt+Qn!2%-86)iouiYC zq-?)}bb0bkv|%(*u@O?N?!pSOF~jb3ggUBx!uPy<0rL2^rLWA(f)n3D_S|i||8P1= zZzlH(F{U8Ocz3u?dB`VpMb!ur7P}5ht-o1cx|jz_c({#C<=s*pg&(WRGMiZ}BSINd zg}G5A`vgvwlu*D;;FQX2ozk$qLc5YdSBYwv?3=YWUok|{L9cyByG&M^f3KwmeL}l1 zmBx_nwMz=SRKOtk?kybv1m=^S$WqX^n6arsOs-hZXlVYK)&cx_?bJKo!z%WUT2eS~ z8jlnN$!2VOUqjXc!$L4yL}>XrCjpX5$>M!R^OGxg@V zNrg#WPVxIVe863GM7K)H$&_)WBXE}E@)E{n74<$B-b~xr3JBkqPevp=<)yGyk4!UfU-~jo;1b^4Wq@>IX%xBb&gFjtfBD%P9Z4m zUq^&kpJGB2?^a|+f_m+>u)P9i~CsPRgO<(T!^6>LNdq zw-*Q0Q&hFAszmtQ)RZM1_aBS^BFd{CW>n+7H&BA;ZsYN77#3=Qw$^<>I$&M2VqDkQ zSJ>_fH=HZ8nFqLi2aqltiFe#HqERIxC_$p^ww54`)-Zx%7JvxZ<|Cjofmb_w(uxWz zk!01A)l_GSkjvH4f=-4+nC8|IGG+kjl76BH%K?POZ`mmp)p_O}sH;x2YBL}k4@QRRr>P z{(JC;O3BJZueD&HiRj3(-bN$~fTvg;tZb@XFAx=w|CL8ez>-S+lFEkr)))|AR= z;^uX(x$OUWT+21cLCGNt5n))@viKb{6WwR*Zfv-{HJ~f)uXZelCPg*69j=noY`$oI zJMM{1Y76h}4!H34?Mw(6;+Y6!g!(h=;I`v83WItO$)D^NZVB3^_s5AVoOsk7N@!zWedaCsKSI!(gBj3t0cJcT=UKS&S_E|X%DzRH+ zThGCp(+JdPqMGUALVx>c%&I@W@FWAJDC)*am4;@)Qfr|(K#ZN_B~zSe z{;w~NCLag5U%$+S4L86E!x9>2fL@=dea1lsj(a1DvC$s}Z)k1)r^$&;wf1<#K zyzz38po|N4Fn%;>P;U3qnWem!Z&B@|owx+eFhDSY0#zEoun=x@rvS!&^U; zOr%-SYW18oHBvGK68?=D0S{z)eog{!#t}{74wj)WS)*}IZiGpjra1Qaq3^Ng^-OtH zfJ0yi`nDaT0HuA!dn%t)URqV@nd z9*&|_@GUO`s9HFgwB+xE(qtOS_c3mVJ|7ls4c4Od2^0=)A8eu$l33;c(;o2#5$k~X z!5*OYuI43m)VlOxPty%9;mN;iR1cooxi3L~8=fz;9rByMIgw~4nAFaG9q?Y-%T_ED z)p#;Obup-lIksyIu{WFik+XEH;O?-!#JVsj@4qDuq1A>POxb|OM;+yNUpjb$x_*tz z3~_it_U>H-c|^r+KDjEPfSo91YXK{*xP4oR=VeE_gucGd0SgNTrC zj%d$Q^D)*H7ItS3Ba9~@9j&-0Ti`#KG_5qTc}%D4PgQLm*+m+w&4}?92LM)F_OJDN z&!fdn7k_xTM8y$iQ1JbrnX_AGN3Wpw*D(zJ4m$Pb?e*7Uo^TzH7ruMclf7h~gt;VY zM~~M6+7n4mZ?D5g01?H#u^)aT@a`2w`eM+u*cF{J=RV77Yq*=+&!XpvZJ_P2!*p-y zgLw(#ya{s?vxB;T{USR0`J`@VB z%)71t`KDZJbazpw0LbIT){e7WW!KIZnV5`P*+uxv99{EDL=|UV!Rl61BOAWC()~`3 zhpD$54b4|OB?Ow0-(Ha{vF=e88DLb*%04F*NMMwO;8;U8pfcre*GX2LF~X?o0u_WO zCzL^X_x`z1p>*hTz~!aAp=oUVP+6}95!08F3f7wkz_GWyLEBM`Q2LLKH+U=_q_X?9 zV3>3s8SQqcC^E7P@duE%5q4rrFy&bZ#shR*nJ4c9gN2Fv$GBP=)pEc-|Mw5pc# zQrO*V)}P)Y0DUHa0obBjLH($zDUD5w{eKun02Qfl8+j2_+pOeT9*H^^Lc`+Wf6B~#%3wz@G!$ZN+8;aGAtQ_U&Y z*vL!5u_4ldy8Eo%>lbU7F&pP4cWA5q21-DgZRxUo&Z3_XIIzTD!!~!^8ks@z7;GMq z)BhaB1-~<01c8{_=DvD}WJp$kj?>OI%MvP;3whJbx0okB1p9wZDi%x;{yLk3g5d0_ z#R<(WEZ(sTZmqqvHbv0)dMefT#GMjM)*xa5?0?8&FVc&jyZrWbiectMeGwlt`Ndo&PW1WJLaskptAaHlq;;-2$9~R6O(+#7p{pV&FFU}6wsP6H4 z6}^n(Kkf73bo^)+7hy&;r}zWH>h1E_XOFNR*2$>8rSatHqF~AFVU?WF=K>nr`|RP# zG*~c^_Xc88MnAAS-k1iJ4?C-TLN=bnI`Q5*!!T!HKyffb%3!8}#mq%8NMSpqNz|1c zhJG0ZzZ30U-$_vgDeoiL)`T~^q3PiDmn%@~M7xP#0X-%!al__ZR zDb^hqJZ_YryR8u^8F*LT7f1A8MN_pyqReW*Xf-}Afk=tfny~sBw+iN8*!{E|A^jz=z zzr=EI^8p!|XSplj9zhUhdx`d4SchY3%Zz+K-Zcx2+I0l*EfxyH6V3bS#O0s`qZITv z&XNBqXRaT9HRW`5B+%Bu>3hd%m2S9jZ0S&T(+#`tbw}|KXxxkUyxJ9yAVsL9QPs?o zU)NzffJz?!+zRyPf{yta!$X6`{Y%dWjwG!?yw-?gs!4jYAs&0PQ%E5j4!>q^7CZhM zM>DTb`s=3(KqS?;hp=*J3ocM|9*-uXmKEMG*~iL+F_w(elpI5A%YnYVMLL%Zl9xIp zH_}Vwwmo^}SJ5~L(_wKyRF`L(-iM|-B9)nq2M{<2h6|P$X%m6Ga~1m|OTrYpv=UMv zXS(RYn)rd*e-^y&!q$E2zo_~xXyI;DgKd@B!AN@zE0vEa8HW#!I=BAeoJsN;`UL4O z@NoJh~R1(P+8F{nb+8p_y%<+{3t z>H>vSSw>~@*5?9I`7IIm?GgbyP*4X@kHm|5tHPr6Llw!5;~w&1OXVuGTpYBTp(amc zfZXV&6^saY0rcQ_=XtmyC5Q0siqekRQ5l42lJO6Ozu9P`!t(2?-pmKOhe=>uri~>t z$@5A$zfSTHEGsv3KV{9p;E}Y5MXAeLOhbPH?@_{_MB)ly5`=|G z%gBeP$H3#Peqlbr$YVr-ytMK;-Gkh1)z-OMGLcH93oy7FWdiC1%++}rjR0uEouWr_8*UG~M{ zk`E%56?RET<6<{{b(uH+E4^|Ay8BbQShxH)!H&rmHjN~u@F07~Vm_ZwBE&kzfX0<5 z`8c^KeV;&$cm{{|b~zDQ%uZ|p7qKtsK-Dx900~Tu*D$1`eAx%7fO*Y~i7#YY6xeq$ z+m|oEWBbIahogLALyjxK_Fkkq?=#o{%>B_HN^2)hRxCRu0&L%4Voh^D)8B@qVWgx7 z(AV37HXA_1A2`igZC?%(8-AIOslrX-baJH+k>_5phT?3(=?8oo zS410%7w=2mmx`*`HO8*AoWW%}D%Wi^IJ0W)XsDLs=9zKY1GBqmBldDL!uBHG*k61) zYW-(v2+O$oE@_of-_%SN#=asVtJ}Q}nW2(iidc{CLXCc~ioQ7AS(1VuMRI>5v6%#ik3i3si+OpxT>7u$ugd`){ zi2t}tiSOUku_>v zFzR}G;yBPRU{>@>n+^mZOEm-s)RlojXPj=$kro}EI4T#xeGOr~$Ys6dwiw5VR z(-oaCEZQ|xmc@`5d)V z4e4&W_y7##ZfOCvB0;*=R*BAnsM%bv@D2x?%>5b2n!9%75iaZASn~(P*kX-6MvK-t zVvEPlE<)D&SKIM@{46(@`Z((*7+}%Z1C=Wd6lh#T$-f>@eJ@(A+Hm49e)iD&a1r-b zWu2@WMRLQsFJn>lW(@E-T02a;YUuqKtn^bssY6o{w3k*pN^X>*__`DIMSFD7i2`j2 zYd~8kM1opgU8RGU?LIf0Yf>aLZ5c^(+548)eI*Kh!=0rANR1B=KiYYfS zoLAWp@Ys*75r9C$K;s1j1|k0Wr7Ed7^Lp}Cqr+Jx3;N8r;mP5xOV}fv3N65vu}1(& zbTKDn45cLa(hfAmx!j4Unc(o=FwMiMrM@jfUqOTvg+cM%q$yG*-m#v3eYp}I^R7x?)N65RLm9>Gqkr>JTdMtp_ za7xo}NJ%cV^D%BdNH^*4WSIj6Lr?7vTB{I>_RK`|OXpGN!6Ei4$rohO&)jgp5$Z}F zRCb1;8&?_A_JqE)V*cT$pTQVmuKDhwT#e>RMUW~C2&b_*fLBABBx zxRLl3I@)Zt%$@Tg>v;$xJ*SB>9vfK3tf0$Juaiq^^t+_FkTkX;Z57|#c&g=sZ6jc= zJ+PKT9ZB-=Rj;(!DVa=~fB9sb8b&0s^d(a!PGY-Hc-}K|%B)jY_{&n-g6a&!0aZqG zPqOVIg5nL*a-07U{m7EVJmoY3$lS~omcI@pmGeoHu;NFE&(ttFD)A#IfHmY9ws6c;21I9dHyZk3 zA9ihiZ`4#VBpYyP;O=>H&oZiNM<+jwg56;V{_J7LF7LEj=dJ-g+ZFC4RV-`tam4*M zw%4QldtW!>z9;kiyUT4g=h7jR9KFX=s20j~1GSSlN48xSTW>z4|9*3-!n;;G{0 ze3u-Ie@*~~e)I^f-6Bo)I=49+*_Jt4X{xb=+A^pZ?U8HHcp^{Aej|rF`ht!t zPF!v&FfJn&@s+hZ24_czh=d*Zot#Lz)^-7E?HrP#HUwVS`0}vkq)8RM3FZDs4ilp z!JYwJ|GeVq&}ZaI>Td-pW1(!yGo;aaofT)$N0VxuKkomyrM2|%;fx#%UOk>;moq=U z|9yCwVFM{sbwVnzzN#&k)Zd&Mz09tEbj>w!0y@kqB)X zbYnjERFh=2_!$^fo7>s*ahzpmO=h~@BNE-#AhR-a6o;-o)@k6M`ZOOKrxav&<>{s{ zIxhDNw&w~NVU(ac?h4=~Lf+`sV^DL!nBz8?h*zY>e&yzbDrv?SiEmTFGN~fUi%I@x z=@(N-$9>A%=35PAFSwXE*AMp?EI~6gn5n(Lf_u!kK}F9OpC|U(hI+U)h53vXuaRZc z?)pCQPo9AhxYYDKozGrDosV$I~=XZT`;9mCIVA3R=d1#3d1D&(a{duYpD3+ug5p{ZYZMsMzfocVe+-` z9#oMHER7$UE|p7WU+Rr^BOKb*E&5Khvq+%D)9yKGGB4KRk&T>4-!&NoR-Y`FE7cA- zJ93${$iAZRPqu(&?#~b@T8V02lARIxg%*)jxmBCNh1I zeAQuL7(No`;m}pvUOTO|q}yHLRx_GfZ+_4|qIl1$X+~Pk_4 zt0EI4nU5zckFf?6lIhsKQOqT=ItWl<7L!6Bd2C>v9ijWjxnWm8U$wf{gh*-*pPmPU zN`qWZJCX5%9D>pTWn&)WUZx$RZigoTf+q>@wL1`jepBp)y>D8}C{@A!LbtJTQ*u+T z;aGOPo*L=r@OkT+Fb|SDjofxkcLJL6>)bdx6RuM2z#}sB2gVj9Hl5n)t0L3!xwRCB z^|%Q6+u?arJ{y+4Vv8l#{(_)+%rn*gvG4Ex40;8l}m*47U4IZ_RL-o z{)(SW38aWw`CrB51yaE5^W3YwjQ&Z7o!#FXyGr)Wr^=!Lb+i`p_Tm@KXo*nGdB6Sf zE#-(>C{*e--^*-BmSKt}4RUI`Jd^4&9otAt#PcJgQvi2*wra{Tk(B)TA|_qYI%~Qg zH}sSW{!m?xDS z*&*7k;4IqhwoqEGyJ-TEA7PZS!u@|P*vTM-JgmBez591kvdg5WL+HnRmLaQ!L3~eJ zki8Z%kKvkrv!+)Z#nASn+3!?5p@e8rbW!QZF5Oe<;3?zJcv%P$W&PqECYncHqt57+ z1NCWEfV8!d#7J$tiaNwivy0_XqxM>0^P*Xj#T{xsp)ROe&<`V4Lg+_RPEwrW&kvt@ zHbDzh5*_W=+>!P8PaC(IgQG2wCwcy4zk>Wah95H}&|*-sm!Ij&?J&(mBqOsz&(YRz zPZtpy8P&gKCvwhuC_el%i?yi$oN>=Em(COd8Ym7Rx$h`$FX+9_5dnqH?dq;t4*yvC zZEe~QzVe_!YE+1>p;R%fCHEu`=&)d^(ka@VN+{_@NjWHJx~q5_c9 z%|#G-GKshwQ;;oKXZ~@WT9NhsYD9x-L&&Sn>Zs{SrsLY>zAyBo-`)`jT*`p3(lFq!qVU1UcGJ7m~n&~9G?$-ZmdwuoE`H* z)8TqWUJCWDGiQV;X;G#PgQq03_n(u4Lx9>e<4l5ot2urgM~>r@I1OGm8YDBd0!M!f zbfkifSV+C7C9vCr-qImtsd;rg?jTx+uDqn(C?Qt-bT-)I z8{ns%`(m&1Ru>c~8Bp!&gp!oNAtw}EAu~r;6^Hg_o?|4J3c{`RRv*>SBXk^;>w3jV zVd3!(@S(<@_448D>hLgMrSPYuiTQA#E+mP(#??HssCkylXHoX*Iz}lC|Kh!I+Q}?= zyb=m61t8}H^H;~!1!weuVj6Wbr_Wy)QD#yq87B~U=yQIT#qlu~Q*GSw87HasCZ;`{ z^T;lBu+8-@9#xTA-|D9GbVuEeC|u4B)bpaSC=U|&AT#8yGSE`N;gIn(3*fnGIHd4Q2|Tczp@br)YChM_%kazMB4oIu21Rs3kU6HN7DiC4o~w*bchDW*vu@Oz=h2fw?-T3+8~;2 z(up0zdxf_k;f*1(3P9~TOjX5FHZzHkqb!fWx7S8r{@NZoa4$|>qT{J)BRmpKy`1RW zmt^vnjT+FlA$2nX*JH9()hd5NTH=03BC$Wg-OoNfX=?iILCoH8EGcSER3Y2F!VhRG zyRr$RTB!70IIk++myRe>?PQ82`5&~F%#LX4YwT`2zl8?rWK zQiGI$6_Qd=X;Q*dJqX1;umR}JSv3^_D1W;f4qb~tw%2!jRBi}eCslZlOEFzR#TpRJ zy8$GBvs?%{Znfw*tt?_-q?kI{v!a{ae#_ zp_5XT%aaMwZd4BV7k76M=rtfW|1R65s5Q4-Z1wT{$Xt|y=-uX7owtU0^zuyCyb}GP zon&Mlu?gD9I7uM6hf8rgnmArJ5_OuYMJJJjmgIg$;jf)$)oOs}1lS3iP@HZ?6(mt7KM76msh=MJQjctFxeD5{ zt);Ok8y+I*XRE`%*-S69y;BCrXUUvlANBR<^VN=rS9vYSvUsjVbx8?%s2TTkJ}ont z^8&@y>Q(GVm9$3fW)6cmNBPJQ42proDn> zS5Y$&1w&q8UL3=(YY4ID|Dxf)J#M{pW=_1jh>TO(H5dh1E#aCKom$Ed7fsd{(v^vU z{Ty7RLiph(wpRy|$qS5|ezRx74jM?dOnz3d9YGn9ZjI}Kn41Al1%M$~7%G2%N3BHR zFlE2)jH*vp3-~LMe$)HqXICo^l1}Srm+E_x!X1}N?EM{8!pzs<3pLlys|Z8me+f+f zzU-^D=w}+}5V|AO*j=`esx(qAq%GmgWCqqI` zUoMzjOgw?Ho{GPMrgnfeFj)J@W5*_v}t2G`L z{m4K`jHGi@sbe*Seg1VCKd|jp&{E}akt~}+doiHrlf_qu;CKSwur}WP>bMY)jRh*W zS(CXeq8o|{jM}}ivaVU{+h_cdp(Q_e5fW99(t(v$mLD{b9saX#M>vl}Pa(lQJb|#t zYeB&9!_;f5bCbb0QY;h6LY_YTA70ppPmu-|lVSUYb^40}bVMgb2PsI@0rgIy8JmhA zC3R&u@1O&9e1G#%O1w}w4Kie)U(B~R=G0gBx1Z@tlU0qn#P|4IUBUFFM&%M0E3@#! zDdY4grNe`1vT4N-*P&JU)k=ZC35kDi#pQ*RpB|cF52!nfKF^m|ECVT@QpG?W5uovv zi{vf-!n}yLRVc0au^0FQRn*}2PXP-0kZ7yuJ4!y}nN(>VIhM4DUfQ?(XFXheKsqiS zVWEZ4NR9HjWf%&&y-70s=ZwufvcPW0&r+GfU6f zf_ybtL?4N^g);}#*%-%Y^U-qKSEnW`>0jvn!{cG7$9`Xl8s~d(^k=b zRGjM6Q`bXUk+6x3b&i5x20|6_?mD+)7Yu8w!XMe2k!^Ke*!j(^Hf!az+p68as^G&7>xUOV&zOO5v8Y!h#GQ;n-m7z=oE?J1fEs zB|7>;$&4b0YcM0{t2bV#3Jt?WGGZRI^j&z69)0kZo8Y%>#!8__rDfXttS5d+kjMn& zFs994&%Nftpd0pu568_#8}TUZF2R4|D!BEzY7F3bJ=avtiz{e;j+z`N{JfB(iM%xM zKAOV#u9?{*>s9A=W4JVJzn4LO5;F#SY`x-MU~A3D_}UkR@4DAn&%DI2kJ@W-53{i+ zVYr&Q=z#B!4L(k0$X<`oUwa*(pWA&mE2oZ_Pf#1pIEDGsE&#|H1WlDs{h4ShGNMZ~ zEM$G?H>rpIA%zpsdC|6Cp-?%-oI80y5rVNO(hw~z5?p<7_}x*u-!T)EdcdH8x%|$7 z*gG9ae1WW|rO}>uZyj|t)-htiYp3Ggd z;Ijp>Rdu^DWk-dluXV8~N>2>skBpRL$AwiiKTxf<(Vb03XG1H|eWNde!4`>HZg?Bf z?(4;%mNR*|;@u^zX91}t@%M{GYJh@~b*I2;mlf3p+vlt6IUj>Hk)&&>j&*S^JlEjn zubL%#-wlr?<`h$kfUsY}o@CWz1mCF`a^W4;iBOZdbn(2YrU^k)wBM%!Hd&p4>yoJ+i2^f8X3ZI%3cHzQXYf)!wJa2dm^Ugzg2 zrPtwr83fWW8+cu?W-s&oa14R8ad_w4UUPoRqkMtb@9yLu=+JkM+sYS4{NBd`klJ|P z`GFjhN3juoU3_BUDItk-eFl-@kI09XpaL@zR-)Y&B?)?};w_@3+@}!G{LEz+&fLiy z4e#t`#Q-yO3pne=$cwLS^VkK4-QA)slld4d9%kv`K)g%_AZ#W8O#pSy3Rh$mpJgbH z`=$C=-y>KPZZy7r!3Zr+|6sC`5~%2K4HrD={gPIZ3V>CL!+&&=J`^=gka}m|1Y3Uy zcK!oRPuH>4M@6JElJTAs532y4JEifT`e};*#t==FppmTq9>Y! zNXy~eob8@!4jiY8H!ORm5w2zNpe2>V`eWCW2rulOlXK+zK*x zkDZCOpN-1qPIt_Dc=ksgFEVO{@_A# zeYGYy1(UOQ70Gkrt=m%OusXyr24H!HyG*fsY$eYCu}h#AIjBc#zOBiNfoqr=5xPbr zX*h;`EG_@AS=k7<>n#9Cx)H+_Os<)~l)Y-Kn+2F$J=??Rkmw$*IjKd{Je6l@du6jV z!QXj zQi0I@&K}9(_5rT-L`QQ!_tcWXW{XB(49l-{fi8^$^#FndN!ZK}Tp!+okbn=%D@)sU z7cTDkd*fEO3UqHi1U$RxECWBznf>F113v<}ZU1mIBAoreWBR=xjOx*0tC?i~wL_Mc zW#Sj8*#TlV7w77~zl`=@vwY64@OXP@az63gmq1x^H0Ginuq3u$c?FVj%xs@|Y{$RO!X&forCH@`Ccp79ki{*H>wpu-}_)o8~- z$384|V5(ZqfR;b;=%mYW^%UH1BGZwn%*5~6icI$W%UQ4h&wqXC?t8lJGZx8tpA)^D z30qBFiX1~u#&ZzS{yz+oW2th?#V1SO1D~ylxjbo6m818a(9e?duD(+yV61gui}nL+ zdO(;uCl^m0#GPz`?e6aKw#MWrI{WKMz*k~%{=Ixu$I^R}OH!~^wkEByz#)%G-9u=?F0HLKW8efjR%ntIP(mwo@j5q z)th4uGW1Rfe_YuynKH23G4c0=iQ3~O?D{gTnNt!LyyaVIEsffNbFk0=XUbE9ar)0Q zgNz4;jvJ>03dOdzen#~rx?Pz*mbV)O!1oO1-S4(a%N-Mm$(*E|f|_%zIFn!(W%{Kz zkfvFY(GJb{RqdQN8lr7|v;ezl_TuzQR5i}sFr+n2(ddY;Q2ttW!2MEy3_XSWtzKH~ zudxgQ9D*AcYOOhLYonNl6D3qp-+P_rO5OCSR=s4TU(=JH{{U#%qUH0Rs`M*+5!mky zCW?Bfdi18sRJT8*&X3n0 zzSR^fA`|ajM7GauZp* z@(*?ddQz{wASeiG1B8gei7i2NQ)0f(%ZSifC6>NN0<;Ox7yUDSP$4|oK-xXW8CIzb zOOgd00B{ns2}L<__)ybbB)AKbd(MESVLf~=A z0JbMUm1nxZ-TG1q{?zpn&iq#n5QY3GlD=knzssu5ZF>4kKaM&P+F2co-Uq>e>1~3$#@w_@e%T>w=Sj!`CzIM z5fblcW7u3y^mH{>ier`$t4>KT_2FXW{@Jj?w3FEZWGi>4kRIyO(9)6cjFZcmRG&rG zbGQ-I*0uDgi(B3I$L@7$MUjG*%)}fY>dnth-rpgi$$a<{pVP(cXWrwDD#V3Ph~_jL z&zXGwxPP7+@U;o{Hgd{8W;TE6hx4mPY-jQ8b!TS%IpAm^&#Nt; znR*$J=mo-vCN>Hi#dG-$FG)hA%6PZ90}^f4O?5^R_o^$;vy3?2dsiiYr?-%0A}q%7 z8%a0D=j*xD$716d9n*cqt)ksf}%b79t-f>6A~k zT|?z)!8)IYgPzN-at4H6(9nqr%@OAef0Z#c$TK~w0s}5zNk34u2cZBoO;6idU+4wiVt!8lc*3R&5(?gkW70M(RxMvHA7cE+S>IY3VS62#R_07!60v5MA! zsw(4_BuyTFTu`$=f_A+x@Io2-1_k*EV@iJEvZD^lU<91^BS+_uRV=38sa|1k?AZzapKp%nVj$;l{VjM3o6E&e zUk=2*^_Mg7iPaDIv=;jvlLlzH-`p?a^I0%{Hs527c_Ct;pF5Hv{Q~x9oyfvEzq=`I z(Pwm~e{N3aeQ9s}sXcCB>e}pYObg4@K~#4Evc6|jexeEix%d-kVxKokzdH$e6FHk9 z+#J}8qkfHTp_yC9BNjBJGGSWO99o7rVP2~)l?Ju2j_+|W-(V^`tD)ZE_}*yP4Voyg z1mQ3OnP~c;=rUZ;O~v&0DiHePmOuIF8Dw)U$mrU;v%J04TJh+-r&SRou2xy|4jknj zf;3`>bi?$*#0Hovl9|{Zr@g8`x38|5pI@iLax(m}vB?2dSoin!+>y`;cdz(IRng?% z19OfC&@;<4M_=|&7U)F;Y6KKChq>b~V~ohHwa1)M<#b0@_-K6(i*WrVKe(xv&1`It z!%;1gr#$nVR+HLV?B$rNOOgCCcpf2cQt?=1vtka92ai@}LP{&|=MO#%8@HuOGpWu- zqp$|{$s3-z278RS-~L$Yn)zdIe3gau8;FW%)A&OVkMUMwT#(Ds{`=`#OQY@!f6;)b z!183@WGW|TC1YgfXPx1D#T$RDIkRC4n6wO|f^7?McCxdJ-=1G^=16u{OfR=8A7O{I zY%$V0yD0s#;N#B~eVJHR2~(0AoYOz<# z16gAkEfe|UK>(#GkRY+d#vRi-!_z@J6CfM%&~AqTik* z6cM3>zPLy-pJR!(V;er%_q#efqcp9x^+j^*+EOwpM>zXT-&5Zs-57PX9D`F);xg3q z8_j?*dU?sUOigj@&sP7u*tHK>&VZ^xnbKiZ>Yn6xXE={Yc7^v%$KFlMTW7)uZ?x5* z>@jxW8}ZpVbc~<9>}4sCgTG0*ZAIEO0cGiS7a&yV-0?+HS;n(4QORCnEO><^7SA$N^$Q{a1b z96MUo!s2p9C`ljrXduLh`{Z32&S)eni<0^o%bm$&&sKx*PC!e*W>NZp1&GS|IWYaR znYL*wORkL_No@Staq-l%qeeT?^@g#e;y$9AN_F34kDdRAo3Y?=R=M&4XQ&W6ltevQ4;Vr0k8Msy9ZhQGIz7C0Le$g!e&NblIs<#FfgSQpx(V<5%^ z;GCEUdNv|Ih=%yV>}~9S#zb6S0>d?|7RTBgp=G0q&b0SZH?c;#WQq#Asb0rdV7%ej zEXfsV6pQ`EJG_|$2CC_C+y|E(d2`TAsoUXvzr2mgW%rHPfnn$(CbyKpa6#zF`d^~< zvPAY4v3+*}0Tr!&fsOxD+nI(XnYMkr(bP#Ro7@`L*-TqVDswlg$)#};n!#4S*9%Us6XH5Ei4GrP5T&ivFpZtBlXJq2e)$!4WUbKg3mHUKRb3QwaMw@uaG7W zXCS`T`*X!@-XP#lYL4q_atd0yX8d>S?okIe!b3%^Z9tvoNwZF>lCcw1x#y}4J&4WL z)7HnbRle?`tQFE~H6hMpHVlTX_R0KhR^k4t!*QMBUnrHGK7WCz4G~n}Jy(z%R12Yv zt0FXeZ7QN*UNcR(OTr-8sCvz6U*wf&OUA0RCe*Ba z+ru(C$kxYZSjUW5qZ#miO#gz56=;4{dVVSW_&Y&!hUtoBfvzSiSjGKtz|ZWQ(>ar& zmJ5Od(+Q-7oyT%KwxIyY8Tx!H3aiSfQd(M@dT+6-@LcC2Q@CXH%Gf9&O^I+RY$Smi z=&L*@m9S8+YE!kxT=qEybZ1ie3QD^*)~~xVB~E!~klA2{ZneW#f9)$(wRaOOJ-n;f z#Y$9e^~*&*@2eh|b5&>Rsv4?kCP%t{nsE`=EoY9)`D|!&kjPY73BP`ImN$?wgrl=X zXQ$Ds=`M^Ayz^*oHiAB4BU0v-Bf8;Nec@br(Tk&C$g6`mseI$fLopQx71tD$Vx-HN zZStJ;DND0fTWEB%dQETFv)&-F^(Ey!L9F*pB}nTC^YbGjZXx}pLu%N=UWHRsAkY6L zB|3M0;y8+T-BdWX}td2vb{5y zD1ikQCQvmbUGWxyE|xiPvanYzg8D5a*F3C)ut23>HfTEX?TPK2%T7J%kdH>I>kNh_L~JVDca`KB@-~IO5$8V9LqgIC+yLS2<(rBuSmnt zBQ)NG+KFS}S&8XF4eF-GG{c8zU(25r?89a2!TyZeK$ol#;=>`;E2qug>0_gi=5(ol zMnuShWI{_jT|}>w1VLS2)K6}!0%|p;oc?#6kvOTcHvKRVvN#1i5ZW!EmSGuuuuK5{)LXcOA(*1};g5+5Z z7q#^KXLIsvVimc!xYkJpQrak`Q&$qbs9nWs4~woWbcu?dM5OH^UAtB4g_%bBwsLF6 z(>jiA_+bWaHyDk6atQi$xZghvF+MidH=7@lmXA`9mjnaZa6)NcUN3B^=FoOG!aHnU zFLS`KuPvt?K@(IKwdCZ!j*V1E*sl@$ z@8S2%Lb0m=Uq9P|ujsl3kL)A&Lh*Dh;}SI)4~=brNcu8NpJ`$>y2<^7kQY={e2u;k zblJZs?OUFI3t(P728tLOR(%<<3jA%htZpbuIr_6fc5ra2Zh~hKPs?&&F9d4h?JfuJ z;%*sv-bsP zw&ws5=`#&yi~X|6pZiCte%>|)9Ig*gU^X#wn@NHHx2d*y;og6v_kfQn{muXVTSDXU zkvSl&UnH6k-ZXHeJuAC<;{;=hLjP)0Iml+Y z=ro|R`kBfK@Y5*|P&ckb4<*gMAFLsWUXd-I7_%*YDv0>@Lr8_7Dk zkr&e4R|gJj=}@fLf%!#^DR=2V*`JgS02W&JM8Hx>!7x>9lkt4gmL1gFPHg>#Fp^X6 zbG(f@4TRAb%v_Yn!}N@kJ-6*tf5|V)BnKkG1=hkfl1~xk$0KKh5Z9C+H3CGcH`XDj z$#pMjykHQgjZ3sPk!*&YD+9dH#ynh1i_+w#fK5CcAN1++QdK+@MmOkzsadx#E&Lek zIyS-G^ad-0T(lO%_tkQN0HdKw33>AoLHmKvotX-A)Z@-KZQ4JBDAt_UD%)zWHA3{% zE$0z0bPDje3uPJm zfpor~<=uF|&zscO zT*Bq(ikdi6tABk}?G>||@svA9$?%z7zE6gX`@sssT&z$k24h)w=dX!B8m{?L5(|H$ z?Ia94ztrEZvNZ$%$ew9KD3sn*cWsz&a<$kL)fwk^$j|SOcP6@*->1R?l&e$UB{gXg z#&;O0-=1mXy4@lk1L{q>_ZJfD<@zTK=b=#@{waqdyYg~n1>;kzjt{cg{^aj=Pfk~; z$y5TU^wpiCdiA=~A+GcG1LB6@p2OJaet#2h;mpdyL?dDH=-w^2T=b&BK{#N*tCeV| z*V;+ct&Ww7o7|=o%A-(z&dD_QY(M;5Q8KfM94K%kkxYFjV9ks?>W< zr2N?fv`ZdJDn-59lRn7zj{%CD0LRisQfq;W+I2&i2YR~k_t(42c7c!!}RO?m0V zGvjayqs9Cs(R40Bo6u&{SXPw(%&OW!_}DnpOVj^3s0r zy;`qCH0W=@`7IXxN-3U}+EnV67mIo;R&)9J#b2Jn_h36AiNY;n>nOihQ${XVs` zO!!0i`mg-l%+HS&NY|PdoUSgVMm{{B1*snTmbsN>*#vVsoo3>%oL*@+qWu^n+F{9| zL22yuh#DRHG{*dZjxZ%r$G1I-r-=0uqgtDyZp2G@dPe0c2}5-bJU#bO9tv1uzNB}Z zUf+-r97Uvi2JwcLx`itvLFF1@*okCeN;6IQ_t2Zlp>>8pn>i3;D zIvjqZ#(Hu2Gjo!Yg(g~8@SHrP0A%-b170a`m_`grLOsogsN5Bz{wujNTM?e^mtlQ# z$P0_@TUs=Mgc0Kr;0SR-c z=`Po!>@B_~Y^w_kfW2YiR@i#Dln>)|DWu79+ikxCr)9Wb=!kw5ggg=%xSf-_wHPs9 zwl$Uf5lO8d6P3nqH1C9c?1l+G@X@S}cKT5RgvW8+wR@gmKFsHM>2Ick$-Fprmd8Y+ z^UmT7?s>;y^Y!CGV!I1tJwp5y%vj)RX#;m|TvA4}?;MhsyDIngYADh5+?$UaQy-dl zQI_g?%MQny>#3lbLvTBfnzEitAps$p={XS#db~JH$zWi)dFfDH(5r4SdfI$SVAi5~Y0ZhHb^8Ve63RO>UgkBby{jf$h!6Z{IaXEdo;Z?N7A8 z=moT;fNI1@;Q3P}Agv9;EGof0R*_^^2brbNJNqXR0T9MkKo&{@wo@;*8znTuH7ioP z%8n0yR|6n0`4!DIum3y)#*OUHvKpEdy7A>}O59@Q#Gx2e6m!qfA=7))t9bJ>zpVs97oT!E)*+5-Y z6ytG@ps#==-p<(~9Ib-F<>CV^B|I?g%v=mZW<%yOlTz8~x9O(bHtwKUHq3hC@kkQvnAz}{ z;Wmw*XP){F;+u`ZLj)*oF+$vCc%w+x4TnnYen8ez?3z)>g;mYjVUqSB_JtnCWD4?{ zvNC0}`bDKoQ9&{MK3gQV%O*-gi=k2Oz3`~@cp1k{_@x@AHr8d#@C+6M3s9} z$7U~RFFA0JsywBB^?7E04n@UAfB*i}UPs^3-CeS-iC?6MTN+9jg`pQe1dX230+P)@ o>;LbRJ@AG9NVZ_KUu{6XVG%!}@oMqFkGGw(aXedk26_8`0JOXCKmY&$ diff --git a/Firmware_1.26b/Documentation/Open Firmware.jpg b/Firmware_1.26b/Documentation/Open Firmware.jpg deleted file mode 100644 index bc58a474d7460d4162537839a6a069c8c41a96a6..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 91291 zcmeFZ1z1&Gw?Dd&1_4o8NU1;^WA&yx&QMVx6gW9d+jmj9OE})jydO8AP13?z=be~bU<^URaj{^R1CqCiqe~<#W@L`z}zyxp4 zgWtu$3!q&7_RHD*pU)oz{vhxNfjD;a~4j zdHDe#BI4KmuWSM<=nStv*~I@stNA1H9|Zm&@CSiE2>e0dHw3sjxdencd4#$6Xt_9r zdANi*`G9})3;=Ed`hY#y5;=uSV&>>*E6l-R?ZB>YWMg2=ZfIl0;i_-T!NtzW0f<6e zZS@T;jU8zXj7`n0#h5m#VNA5j2pwDB(#>Hi%&!%t0!^LLA!($}C$0f*Z!ev1BeRw0opQGD4 z*+2R^wvi!+@grj^V{1nT5DhL4I*xBl|5uF(LiBUce+WM)BS<5B%idVu(fBraiJz&H zjgyCsi%;c;irIPjc|MkmT~2F7oU{?~H;pF&Gq)W}fS@QimG`)|YFH@5qKr|n1P z;^0=>H{rnhZ#Q7CpvhrlV~cY9KHz^u;Oi66;=p!4?GtQC``_^SGswRM@*lYV!1Zq- z@NW_Sv93RG{aXn9Tf~2?>wg$rzj9n-YcR2O0W(VuB0j3CV~l$jOMwNH0?}UAaufNJUCU$4hKi1k1|CbIc!9qIXoTn&uW(6VTvF1i7 zMSruXo>;kilYz&;-VYmxgp`b&g7GTTHD(rGK7Ii~A>muMC8eZgWbfQpQB_laprL7K zWNcz;W^Uo&=;Z9;>gN9V$NoiSmMP=28 zhQ_Amme#h9J-vNj`UeJwhNq@yX6NP?7MGT{ws&^-_74t^j?d&m0Z_k*^;5FH$wdgt zbq);;6%F%DE|haF;Dt(vhJJ+$@PE;j&Z>^j{+OcSwC_z z9FndS#kpAbTsb1pKDu=Wa;Qd4iv*H_1rSI;76~*e(>$Z5g>3J=k7A73NG;wgOh@gu^5JR6s78c}@0IUbPMZBV-#+2+P z0B1o07oc68aYz7~h6JXWp;HfBA0xbZCr(b8kN}}>ktE;-fwR(pM9n{lt|5V^`qKnQ zhrO_k-6XiAdlMgntOQq81zHx1gP$Osk7%YR*FX!r#{ApZuMotEFeCt>aQOyWf!f=a z>-KLK6LjpQRA!AR36DNwM$tUeL;`U5_a>o-YQn#LtyQIB4A$jWmm*iYA10m2D}CKT zikej8!mhCp=2kKRD8y640wmDYobW>q$kc-sB(SrU0sV^Vo;iceE64oIO4RGN+zOa0 z3QVY1eMFNG#GxQ4Gv7fWf_^AEgUlTE6|!1Qp^IkyG6_0l#u^F|)XfPus1=a_PD3Nj z&ejiYfy4X-t~`dK#^jI7K4Hm4&9Z{$A~aI{u133&2=*B#3mv4iF z9;zbF>>)wqyFIAqFch_8MGFzn=vN4rNl;g2CL%id0@A8{No@8c(*Rk-MuBc0%3Q;g z|L?5BHgiQK&M^LNm<10~zRDN!75E?4dWO^QimN3;nMDGdxt?E}epgTGcT^O9mdjSmF--mZ}7C7!Sfw;5S_y_W7_zuF;PK(Jp*0fE22N`e=qhLY8w*x zhO6UuGyKO?u)h*X|1jnsM!?!{mP`Oz@mHCTdZAy9mF9=Ee*@|t8p1dGtu+V)wxNG_ zT&2I;!d~ESod0kjIgqOTH%Ru}uc3Z~Olf?zn(w%r(RAsZ1%+Qm0HUc1KJNYb7y^2u zG@Mob8+LHeIV9clh*0MAHuLz9z*k=c1Jf30!zBYqU}5Hm_LfWTVMhJ!AxKpEkBI*A zkO;P!=k#08#LF+ioz6TauOH;L2D_4eRpmsg05B>#HxOC1mrvM_?JPQk%;YX zoP6Uuf$02p*P+@lD8#|{7{UZ+)%ndVbh9K;oZa+(KK$D5%AxsRoSgNGS+ev?=!bV- zo%WlqK*QAi8ee}w*?oihOjo~a;cp7iE%+7XI)7NtS(H0-mZP6h?ssPq{%$@$oaJX+ zJ#!W?q+j_hq)TkV8tD6daA?@5XvIoZi>rzS*h!7jQV(W)A!o2=0&3zz_`* z(SSUCCmI8Zk~VW{ekV$Xvu&XufmaDXrWo}+5CUlsg5pNV&QC{EJXB4*au#`hlI4SB zk|0?DXs>%eA{+I!qSVvy(kMNN({4M*9bwWvPI9N()qs2^haEG z4^+cVye&@R>H}^6HS&)%1o;WWS$O`9^PJfNIUg>Eiq<)U;Nn%^sck{ zM&~zOT{+a6J||fDLn+0hl2nbhJcxbm)qB_sC~f=H3w`)|Y$OuSZUo<9`#CIYK#0{c zo)@zormCY0!0=$%+Cys)w(QmKaNhb1Pd&1mYt(s!ChDUv9MhXkUG z?eNy$lq*Nl49%~o1kRg*!6JXeC(dB}wQ83X+E)C4+!Sy?%}`k>OMN>;=-x&pDSmkI zn*eIbR+G!df}>5UeMUWFo>w==I+hZ|2dvX(8_uWdFN|JRZgSy>TUTjxkZ?nprzrqamaCK$x2+nfn$knBX%&Tzx^c@Lc23q zgl_+ScgDA?L-kEfEh*QX19>`G4>nkM(aooqw>o)}Ub?_V`uB)GdOXv8;j&-R-tIL& zO8lt|MtdS+8ukA2GhuthJ96zGVn1kgdF_*VmYQ|7itb;R&@L1coOIYxd)o9)N9v+l z)D59e$|a^d%6Qi=7aiC`)ZS4m?s9V7=PBE= zs?c7S2)N}{-&++Q??TKUltZ0FNB2~N#Hnl6WxtKtt`MW zHaaKo{XC!Cs~w}V#MAO7yL0K)bn~jC{%-HPw6{4ixB^RJYo0A%R;$!2xx7RlaUJgi zCuP30zE90T-Y~Nx>MNaFO0i8DTKz#y8H{b`cts}WJMD$3YB3-<#r)}Z`$t4NN6NY3 zx%?g~N3Hd;)>1QHD$!8N6Zc?};>o6#N>ckpGFv&KE*Dk}Dp_OH1;w)KitH#OwF-t2 z9aOcQOs~uurP~?Z9!lGF(I;sRrG$}}krFPGu%gcorE>+4>xxqeT*wPDOsH%!X&059 z5|PoJ#u}F66wMMee`WUZ&8lK|wVe(l5irzPqrDjawXNcr!-&b53*L?{8dE5b%q#Be(c{*VnTy6oI#xr-UV`TjAYdnl6NrQ)O>oY$0dYoP;j zoatNN+R~9UgOHw%t_0j{emd_&hUNow-3`rL z(QytHeS+-FutvlKTN#mt{K3{?;Ibm4f-LH}jO4X!z5adSW7eSP z^`lZtSH~l^+z-oKP4rj~Vu~%RIs7kIht_)utuE)@(U){kC)pfy4b#)n8X3zQ``Cil zDV=0-!ZjDFBFN;&RWVB#siDd7+ls9jiuk%`I(qvEPiS4CdI%WfATVp^U~#ZDk?Fh`_x1O5NB%d_0(K(W6rt>BfF|3~kVXYMXO>la6wlxtql zqngYd*zx*rv{H<&nQa6sdRxwjNK@WZXa~_vo$5P?yNS_P$-#G1mEt8{Ll#f&@41o=2l^KV>tndzSi@dhuQ ziwe-XV^5EnsZ{Lal`|VS(hFzJ)Vt02FnX(;wpBsq7#d8YwnMN6UH67;5@cSDl&O%C z-5p|7f4ExkR^}Eb8QPq%4}dwG2es4!^E{C*_&G4u3n+*#5T(l0lF}s!nZ(bI!8@XO zPn&b$y&pc7Smts0Yp5j>aM(fuK3-1q=BW1s8WbYeo;)0dn#j%*26?T;EHz!;^{R#z z>)Axj8lG_9b%TzcB)N>Fdq$aC@~!n~4Zl6o6H%u%MHNFtr6K{W{9+^^4m~17K6 z`R~IHAT)=VeS}y2&oveMb2MqGgaHC#b&RV7;ElALjbGXX0e`wgRq zF6UZInM7v~3SL2{i2I=nT}Xf~uQSL6SG|^5@mO~5 z?}#@M#LdmPe8S*~cM|^{r!ViI2JP4F+tZ8NF2&G0_slYq#YbbBq9r=4s6$Hgz-%#L z0f7Q$;f(_yA-{8r1fHmCfa?heJTPfS`b$m2iQY+4C>(V;t?zoO8?}gKl(~YDap6l+ z!Dhv_E`Z=e&fQq5PqyjJ5yo@Y2`YYbAADhlEU~m zo6Ff?<9)Gm;+B6sEdopJUjIgV>&G>ERuZARrmTta^QG!4rII*>W7)nw=s|<1h{J-A z#nk0fb{cT4ISPkP(ik9tznEs~iRJ{tZ5%pDGy#|QbdvmSs3PcJ#O*%Kvq1u)8<0&L z8^qN*;gsKWKL{J{2X~t~caQ)8E}W*#5dG!g0@x+#5M2NXT+*Xb`VEj(y){ed(SjRj z@b{rxynl0*kj&KOasBTeyU(#-3WM*|Ac6PHu*2BD;oqX7v}ePK7(gt{fa9K!{w@m5 zUm3ET$-ed%b9(U?X+nSJh;Qo)k(bsdNGTGiJOoD;Z~Ch=(tqLUa5+#sZ~hOyfAIYl z>i^j9pZM^5%=(`eA0pOx@$T$@VP~@{Z#)_vHwc=Xsoc+k{gwxG{}yzQtN&Hdon5No z%aK6sV9W0dmgCwXnnZ~lf4BHA;&7cs`9q?e@rvWcEAeywwT5a*jHP1dsX10e$Jg=< z?>8^-b3zC77A?A-IPRA9kjxfrSaZwn-m}HrgIg2?!)BTZj#p0c^fuF{bNGAV$ z#K1mprD3`Z!ZOR|HO>0*Hnh`y_lC3$2FBn_u($7x{KxHr!30ujTem+e2(*~UIlvzX z>TSVU%VL*ttzc$}g5{1ol2R^-+3y1bgDY8Ht#w!ab%$Lwd)x+5*AXnZaHa8AK=d^TbHjkIC znZ)5a(AKxyrcOF_Z`-P!7A@O;M822_*A5RXuM`XErl(a=pNOp*U#zp43fF z#Fazp89&rf>$uGE{B*YH)bmZ}^UDtKs6S5{`Pc%BJmC+h`H?_aA7pPGc6>=);<8&+ zR8a`|jY~W{mz{5547o?VINciE_DV*CD4jjnLJ*=VorbRoE0!5#-t;`oodK z*wfO55H02)!TRzCZ4q3jt4>XXE$~++n!Mr<}Juu}x8j1PTHmyY#BeBt%M*!2d~?%Q0S$hATg73<~ST)<$r* zM8r;>^!P(^#nra9&`y5+=V8(-N!u)?v2sj4Q*s_k4)ivv_u)b&mtpkBecem3jnPY% z0z-7v_X5@XVkh`|Vd%47qQ71b8O;IPm zVF4V?`({nQZ*rcQ-n^%KY+KIf_8rJcbH$bz0hH+k%F(yv2`-MPzk0o8bno8f1nyaR zvlFdU)K>jPNtfY*amD6H+0T1y&My9UN-g~*DhqEurJfCAeI%^gxt3^cF63ns!Bzc^ zn{Ml)8x;1=3JI)2Fn4nE^coK|(@cnzY*3c7?X{LIKZ8eZI<6TAU+57RDH0$CkD3aI zkicgSByg1u%xH70&7jy6v;?gMaE*zb&Ff_=OF);Hy6gb{VuC2+-;egN4P z&HivKFMKSLd9EaU0i{`*HgrWxZ!^w9Z>M>xoeb?X zL3Yn0fwt$c!)&29@K*1i-3cll%9nB+&44=a1QU5;4b8V%;suVyqq!CzeSx40ToE3T zE4pv~)(2!t_YBFT?@01OVsL*-i()fZpeEl=51N5x8DFL#bvVLzYoi)hR#D`5jO5$KdT6&~hL=6WSv z-+#cJG|M`~iepX`5x7h6LvW>^bVBO3`#p&JU5f=bes)dsuo6TMdbpVi3ihq(hJ5a{ z5_!-%J?(wOFHu<5IsR48b|)ZL3%lycUVaM*aD6uOA@nB$AFKV#UTr5rCI5lA-{tvl zXvzFeQ;~wibu%@qmDfIh`V0x*lUQ50 zuY&}Bn3ebM>iL&l&-`Z;|DUxPre8=kor#Mg=~6V@#S-yc29q)j3=n@YDW?7ZACUa2 z-EVe200*b+7XQN@Bw#uQ?c#vDLW6%8U7vdLZ%=844)k`~L2c8_fPVB9&OPEq$gig| z{iH1ELE88gwB0{V+GT4<`;KpqXx5@Vy2y$63c?LK(*QR=bNDkuP||&Tngo^th{Cp} z5WLWz9Q^R|W!BHo;&s@?n3bmQ6C3P zsvbPjU38Q_9g2h;QA+pjnx=P4+LFfFS&=q{LydLCi^Se0=h+vQ4RyDZU7(KO|KJ1Q zkL3z>640rOEp@cKndp^mvJ;N>-@hDeG9lMHD~J8CcQ*POJ%a*zW0Dy_P&3bXZ=%t@ za+x)?yMLICg1E3G_T!-Sc5=d;S{qx&UWx9Bp4*7cQM>yWsFos+=Py0Cu~^}w-1 zyX;UaRih1ecuc49VT3F_HdTeHsj-RRc2Rta;YsxkvU4T-7HyT9h_~MT*78yUMKIHB zt%<>UH*<~{^hV3;ihcsD=N~_Aojk~r{}_@B5pFNp)OIG})YP=pjJMTlF1npmA)+b; zw7p>RRUMg{i_9P5lb7uM6d@lvOUy=lrSrV&ERVNoe~1hc;D$q6^W8?K;IL19Mg7y5@10d+~l0V$W#k@G6`5L~C(B-?fzS?MLU%V>q)?*54;x=^SoHpC<)>cQ% zuPFD8o6E3|Oq0I{Z0TEWuy7ozQV5))@j*_GXpq3={EEJ}5!w?;N7U%rbv4U(WUWWw zio7A)%sTx7?NYW4RCpp?m;GjE{oL)25PXZ!&5RO&%&YkRkw2t1G*K3@kahJXoc6Qa zrTsBQ22KV!YVSv;hhqM7s%z#*KwtqO1s$pgnFv@&w5g@GsdcA>VDVn|e9pmlt-kqY z8yQXX$6K2&Hw>=`#3mXm=X(w!9)dfdh-|Su$UIn3(+VlJqk>)P@|ioY{}DdOYloA;quHc&_Xx9n zFz<{5lMPx#N24=bQFNzyvQmgPG2R;*%mJ$CnfC=V#()#+j0m!ejG+*I9yoQwb_&fC z3cR}8q_Hm_&Rj7HB4{_J?oZnBhR)J_gHhH#g4yVi&m9EqBqAkY{$$_{Q~d-%TAhKe zg~YbP2EXXez@e~154gkoHz9u^YPkhxCrOT8UOP^_@&0rc z3YRVgi+_SIBm5|mPT}CM!QDR*jX6U!{#Cc+)fP{FZd>g4d*Y8*?r_lYxZS*=_t4YB zvBUiioUxlY;pu+HD3>t|e0kMt+9I0T(8CbLO?R+R z!;8q2^f;`o?R3@?%;AN9$;U+%$`gBhja;>z~!Pzx&gB0**riS0+SOMcwkoKTis zhs{^Fxvzr}`Tl5frnr$8J_!AXSnycJky*6kU^r&yk|APWTw2tt%R#y{0}eU|=Dsz3 z(So;4EyF8TA}jhbVhIy*AN4m$kLzg6gWm2a@8DvL&9}t+hOT=kL+W7!vhz08eQ}@2 zJlknHK!fzwP00M4HHcmElR*PhReBmkm7c(OEiQuSz<;0UL^rkQIiqLmrY%7EXcsk5 z>QHEEL5092i}S|KXA#^0c&4TQ8&9Av4&pZCEniAWn$$a#dUawWZVbGE)prrJmDJ9^ zZBn<0yl#}aFCr*@YQ7Dp`<#JuwYD#wxfMg^c!p+l_v%j_j7r-y?!W}bQ!8GblITKx zkO0f>Ys5vfu;z;*Yw{|N)Q>!&GcV^sPk9$*d3x866Y2&=55n)PptiG?f~>TFj@IEu ziSzd61lRBzl_DncMe%2~JP2Z`U?d=cr-(p+?$x}M2g2`sbKp4UnhVDU{p4imy8ES{ zG8ucf#7R09GaHR!*zLTze?+LbhFS^5rX$6UU)f!-1l3>F|rlT~mVjC*2Jr}-&6%I73m4kNfKX!IhJ@>o4-KWoxl8(-Gq#_wh@j9)nU z4-kVv-mPwLG2D~xbFy;b__9pef?0$pL4zqVSQ7YqDD3&okqbt)L_4ve&TeP>XP<+G z|<b{su zBC2UYzDZU|f1hwWjq3ub#tpaM$fC$XxZY2CbmQ&bFJ|EytyO)QMdM4n*f2Ta|9Im> zHywr}06Ni{5asGVO_a<8)-HdTP+i{vI&1iK!^c5L0JHEn-UfFH1jfTgQ@C0Aam&7I z{uvCjM*O)d`yQiCeIY~8`Nv`23z_LQkB@O9bPtq;ycW1y+D6Jx65|d28mp#+-Eznw zBFqoPp7Fq&?&29QJ6jp%={^{W!5NOraZL!N$3Hh4!qc*(&|6IYGW-eS4V7}PpxN2U z2#=t|c(pu@!5xNpotVsPxdHds-X`lZT_Srsb_MNR%^LYev-oRXg+R7Bt|q#hU08!E zS#0y3Ei1i=yMzw9fq4dT7j>Q+K5u*dIe(NL(|UA1_cOPM&EejQ(|UN8Neu1tHs&i5 zs81PYx3d}2T?ndovLsgR;F-9wylSfHPxP<% z%R!^^LSxC@%iDs-;blChEV!BTR>HJaG4muj{$@ji{K5q5Ne;);zS{i}>tyf9Uxy)d ziE*h$Tnqts2Zd+TB2TZ-+xXp0n9B6N>@8D89D=6yhEs z>DJNMb}9D}oi=w^XLe&bl{@7Cs$3-gnC2`Os zKV7=yBS;xxncQz;#@lS^xAd)$5XPucw{1$EOGw~4V}4Fk zgqto6M?8v?WrPPbOMj8=1VuyD<`R{l|;{`8F5m}>61}6-W(zaw%tSZ z)p;jMGoJIdv0GD3SHi*?&ig*5d*LR*WQ%4LG($!{6WGj^nKqi3fES;&olabE|84)? zVaa`~i$h};q~+FXpN4$18MspH|3EI2Y5JkxtQhdYI>-5*qkS{3be zONBzKEt@_4ZHK;-({(G`aH;5auF=aljSRj;!H0+|W$~&9h*H9(UG+q`+U9!Bw55oL z803yX5f&5kb!H3WXOlkkBKatT@nxD^^XEv>R4pe^b+wl%^79=VBh`fS6YLBfd#;4j z2V3qwvrX9%h6i98$98c?M4$7u0m){n-UR=y6`IJtpRn+xW*WTHRz^fVb&x@}kme-LeSv+(1K=J`e?WsbQWXj_|zkT<(ijXX|P;P$AX3Cqc#7K z6QylIkn)^s0Ym8~b&jZ>sUlu5`&2WkAzfUkc|{kq5=rEG-^BW6vqoqQ+lL zv)QjNFTo*p8PCdl-pH(5KQuK&pNhV}E%P48ppQ?wyQLCg#j)ZnU*-9LjK*R@C4>Q!HxV5B7sOCq~kO=19OGZZx}&e&o4s)elEgw8Tc zFgCs*Lk~=eragC~6Eic1^W)X0jM`6~&hreQsmHnce;5uPubg)2DIwt76XTwzhk8(z z?T06;ga|Tfh&J7nW~K8DlhOa&-3Pyvr#O{XSke2ox+3&mh?m0r=lT$D6 zS$AAyzbIuTwX#}71U!YZ&9)nbaFH)1+UeREPKxA+oCK64P#D8dfqs5$&5d|{xQSl zI(BQbMP9+)_(WLsF?6jQzAHu-I3p@%m3OFj^OZvJ=i8eN>~Gj|1Zt>Qg}lx>s`gu*YOwMsOrJPeOF^2tlrsG6-RamJj1CeB$jP~VijY@^dGo`uuM=hrg6=?P-gSFZr zoT%Iz>ZGZzcV_BISD5@=CWe*;Q1;B;I$h-bWIJHyO0&_-$;s_QSbA~?0M`Z@k6eo% zfajIq?XIB`VSd1x)!YCde+1T8@M*IgEz_x`S`Z1zYnsJE=tPljP&VV$&;&QnY>$sx z@rj=oRo@%y`(d@x#edA@e9ze`NMA9lZXHbm-C4psJt5jC)BsO&(r6A=mG|3=XoegR zMz*`^cKf)Hqus}d(?IchQ}8q^4D49COy}_lJM>cs{s=-0tX#8&vP4w-W@uakG)8;` zf!j6SFTMP_5MH$4>}QZvrt{=oR{9pbe@b=e&mq8rlkeT?4ms28gXc&wlw!oAznc9< zy7uZJqCIKnpLHPiZuLLKEOp@eZz2p{2TKNf2u}8|?Y9>~jk}J*8@hG&-X<6gd}h@c z2{XDU5#YA4q;+vA_V$IE;=v(lN(+s#sTSYu_r--LzG2vmk+Xk|xigKQmjiCF9lP+|&8$S|l);*f7aBGCc%c z`KWk`FT5lwOB=W<;`qS#c-s=S9+jFk5>Yb?t}SNr{To>*5Mu9X#vZpG@I{GrF0DRn zv!Wj=u{dFHh_)%v+gVc@lg6nhtl=t&dr1-&;;kQBEBVOC$>|t>OL)qrLSAtLU=1I#?PrU3e;SXoTW&d7{YyNK#8E+kMlksz;=x^!IBGp-9u zVTFFUGF5O)T2cT%2ksyR?;$WAiut}4N|ey9zRfEP>{_(Sl&3Wpsfu%aVD4gp(-?mG0RQK1_(J7h1Dg9X1U zp{EpI@-QWIoWuo|?RyVN-#9V%^<}91%PJ2=V!`FbmbA@Aqn-0++KyJKkOaVFN!%397;7?* zj{d1$qRnPc*`>ps%2v};sb#u@$$$lcPbb_TK3QB}w9dLM2He zK-J^Liig&V2TYMhuk6X*=%j5tOmCgZ_?Wh{q{bS%W!y4Yig)g4ZR4un@X@fLxj9<{ zE&p~VBfZ)qW1miu&zN$m8ytDNhss)&q9tz1#3Hio)#yqsS+weyeB*C250iB?*lS*K zxS>ACX>dSKE`ERUDD%D4WpSH}cwjBQ&1Sz)$rk!p4faF6#~yWGO0Rw~sE9_Z)~X0u z41bQnDca*1amh?Oya`tgRw9Be1$<2Ykl72M#T|i1ndujmQTa*|cs@m% z1gAY!HwFf?7G)4ojESLX9d5H7DNDD>+RsJHaQR`v^6n^ZFoG#(4|LHay4kC$&%FFf zDr@|17vzL#MUPL8`2I+fkeJ2?aRJkC|F&(P& zO-~3QE?znXt3|L$hrC;1Llc9#P`IbH6~gq@_QI*!1mr-^1Ja}c85+M@);rb5JG2+W z_u@tE&8u?N0TjHUq!^TqEgzLC4TeWNeB&wAdmJkpte^!e2<$QN%!Ka^^fM{=()W9C zmktLqMe!N7h?@bOq=P;+JmgueUWXRLrWm(HD-Mu=wcFv2+gR}$O-(0P0<3zeJmHI6 zQ=JW*f$8KH;v&a8uW*pKum(JPIUF5kQp)+6X!>)J3OzMkIp)#BAxY`xy_#dUi*L~u zE7g)2Q4+Vdimiy$(~PKx=~__J$yIwKMRc&eHMn#kIFCC+aa_p$a@CVO0@RTX^G&cs zsl4i$4ATn*Uxq+QmevoPShU+%yBSspz2Js7mcOeLjD}eKPr(K{B1iz`5}Z{b@P-NW zUueO+`v!T^X0VywE_yF)lMwPD^iZmV8DNE^2Yppmnu$hc)w3QkIb)kAG zn^Y;*U;}qfMHe69t4*`KV6ng2jTa$xBZB+=j2ITZAAtcRQPRywINw*G;Z(ebRcq|S zjf3ze+pOymh8xi=E*#p1WH~gL#&s0~dmmJrldx2RD%(aMgr)5=5GZbVe8$XeW4T4{ zrlW+ZX6OTRGCaTn!2Mf}@KX3K8| z6`$T8efbcgIU}lvM(WL2R45hH!IxX-5_v)5qDb@kAdk&=4-+Q=Zp-H88H@W_t5fND zS&4MSVu1+)d5BXh!?K<|IeAOD$M<@Tck(i{QzwHaCpX>DE=bDrHQI9fk8Ai|QRa8> z?VChhh6uBHb`@WVig`Ud_Z|~%6CWT)4a{=ytV(~|eC@4}K;be57{)~jnyc-I7vu=m z3`%>U{II;vK->9OtOk0P!zOXoCN>}6u>TZeIlVF}UdO3!mWD=8Q zSK_Y6O{$HuWv@71IlN65=1fVL5Zm8Af$4?6n1+z(nH{G*Skk4c?Pu6lGuNCD4C3Lu zXPehHIG!M~-zE;(B3l8y8eBZIoSh_FEz=kydI!A6i}_&tULji;U`<~^5?L3OoeE!Z z%DA3ucF%l+(h;I2 z)H^zxsM)QQb1g5@REJsU{tJ&GiV`JBBeTD+$=!@(Hm31pgOXUryPhr}+{^1AcLv_Y zs)rK>8cXbOW;{;h>M)fgf{su;Nz~jpv1;ikPuj~HFMTw%9rLpZg~l_9|=!F@dNm*vT%nXh%TSkibed5)jVO_|$_|2HQF! zICa!p(7gmqo?4FOL1(sUju&B_HBw{V_xEyRaupx`o@;$x`I&2hD^))qYL-ZvodqU@ zKb0c|_{Tz^8K?F%pT69udlMx|q&80{a3@`)q6$m8RVDn{N^fQhEKkQe>dy2y|Eo_T z2l%hUec;7`K>Ax**24yQ{O82h48Su6B#;TUao@$6%r#KmdKNu%CDxp$t^Twzp-SBo zL+7#D-4H7_5~w91X{F*}GP zbPx%kb9H`KlRp{MN+3lgX-*gzWtH&qf_iu?(BPJk=1ifRU;VlWWz7~_XdSUD!7AbW zie^Z-x@!0Qe#N4+Ip#sIwO7=s`cCRre-Iz*VEO*WFB@!qHw*``^Q^8fo z2#C@!8@m$jWD!2)P+6UdJ zh9X2B_)BjteSws8H4K88V#2~{?$D51orwd?8@}Ep)ajrD8PfX#6&C-9$T{lnpPIdo z7)wIA%3K{tc+Fs`CM>4z0VultN4zaZ(OepO!%X^0n0ApR476Qm?Ak`T0() zYa$dnU*2hr^1hShY4Q=xB0bawUwN_UKVdyCSdji|7{IgG#dpnZbpBFg#`=?}jC zCKJ8Bn2R&@Ov(&33_OH&OTFS$>Jj%qdk0M+UAk~IEps1DZU0r;kXae7>D%{(H!}n& zqnWZ8wq^JD(to*#BZ|~|2Zy0#c*0Hb&3lszXijkNQX);sC+t*K;b}D6J&Fl1{!yjuvgdCV<@H>BTa7LwJuOe-}>ydn*;l*@UL8I-rF?y3|(*N>#I)G-OZbt)m2T0#5=dypycbhZxf%xNio1 zLY3*X|D+LM!Vn?L6gi&TH}Q)njk4MG12%@Ja6DpxU!K=Pjz`R*Rh?4E`iz`B{VVe~ zE_C1j-P>+S%6}a~-v z?{FB${>STli>2^;A5#KZ9SAR{D@8jC;E_hmvWweF3BfIP9JAFqF<-fc5BP>0q(mFXe|hF)~CIDj9^>7rlHnBp>gzrIdQDDbJ`!?@JYRs3eg(^WfRU&vpEzQShna z30)RUv*Ix)7&%Rkm7`WyF-g-sWkT<7-gaN=y-Nx)D|@Cz5`T#-@wSTXi5t4nc|r1e z$_tihdKb-XoIEUI`x6I9u#9S+>s;|LrqYy%Po`>XvU7k7_km@R#G7;JQDgDK&l01< zEYQ}uMjOs&v7vNy4wW3>G7eYU#xVhuo`>RZW#o%PzxNCnpnZ?O0QsW_rq7 z%c3K(Hzq!fWt~#`a%BAWybx8H&jcqb4bKHPoLmnzb$?OTX)MQDRQUl&u~ptK5e7+d z!aBvg(q*aKkr_ocscGln#&~-`340@>I8Lb|u!VpSx(_Sbgw{r8#-zKmr^m?+-Y@>8?&70cj3h(8cYHaeY?S1L%S2QNGWD^%m@v1k9 z?w?8@KGY@jRc&pfgx5Swt0NgmtDqPx@4?79&3x7TepGhfo@BH>RHS_jh6yGw9EI9Y zV#o>ts|u-FLoQ>_yg-@@I)IJ7(bir2; zBo~J2LN{@om&Onl6Hhx6YE-B8de-*n^UeP+>fSOau5H~KZW2O5uq3#JB)Ge4Ab4=6 zk>EiZck6@%NN@@6u8l+E?i#Fdx8Uy3dDlMo-o5uZ_uO0cRlW6AeLtvzMR%{&-E+-3 zo-xKVW{XjMbU(cA*3?&hB#NhK3)AsQ>(&>=BSa;@THyq6?VI%8iq65tptQdCNdXSY znD_RKQPoFbl}6k#=V3`X!Cwj4=D`NLguLm+iw0)61H_IU{h$oxC!+3JO3U{zp*UBp zGGnYHw5i==d{iHu$|_2*=RY}IspO;$oc{)WzSoO352DNdBLxYS!Ia=td*R6wq@?RC zdJia>49A-y$BBeC=-g}RnZfofA|ZQwbY`BpNd9Hg*`QtBbCAm0P zm*IeCsOZ}BIu^k8wbt-qh5z8Y@?jwB4Sxe^jCNyQ~yzma< zkmG}$dD%HjkVq{MR-LE&L{>-Wwo2hEq?cdFWKijL-$znpx08fBq(;R67}h6-5lmy? z9}Xzd`QKBPzRk_=vbdOC;SK<r{ z)ATKH!vFDNL9e;@!?!-l4=IHxRLf33HT})4Ds|C#E|YYq!m&tmH_Z4^pNBl(m%-K& zJI+qbEsm`ZND%(&wllWvC{uU3rZRjewG7XFa>0zyplvFP%(5ib$%6Fia>yk=kL-Dj z8lJ&z%dh&equVhrqYLEGXn2A*A-a39_8TNsZTB~wA zY9ADXhvuSg+A;{*yemeeR31>f^NXJG?LrL!=x_$01&Qm#_M?wIL23V~>cJNNWc1}s z)j9GrgXTM>wl!Exr+ct%%PRTbR`&1MefHxjgV8j3q;mRh3qi64A zfyKI*i3LZ10wY$WzOXkagwKjp;5R(cr4kaOLgy>#9snxr91rS2|Yrm`j7C%XUi zXxALya?(Mw!WX*f(jB5_>x`#?5o)|RXHYq2DvNm;p&(?F4#9XX)|$K}+NkF+eO5x} zEfcMrq~cyRBsV1;E~cQtnhAE|GWwdG0;7Cj|5+VRl+ETY8}|Ten0Cz>BiXV$+>@!I zN9D^@7p&hLQs0RKVJ0qJakOv!6s5ewqPLNLK=t1f`Z1JT+FaKB$(@Bxt;J@ABR&4 zf>A@l0#PTbgvq}v?yN}SsS^E9(BR)4S9?wRA>?JhXpBf=+RoH3I+O`5`s`gd1iO2o z;j_h@)ootrYrnaH2cngdG+oNtse0#3vZ7*?iCdkTgp0V~1-UnHI5XB6hD}DwP~+GK z5&P$IbRasrIO;GNmZ>|@XP&;IpQlFkHdA~GXv3foWTo_~|*UmzGD7N;Ae^{g-fA_@|@2xGl<7W5fdLK`U1y(V22?oxY`_p;?e$Wdv!~pLgXa#$A z?q+t&P11g-c$ZR3Ab95y~}5gXU)i(-&gbK1fe$)+g*ZWIZ&I5DeAV+6=1++VB>dopYx- zIj$y6Q9W2!;7OihZx7#CzJ9eQGsOh573;pk{j7YYq*wpEB&iT;yRZWV`q_M!9@XrM z8=az<*rFQq0MoEZU76Acmyg)(LCa_Na!6V3TYe$wLV5gRw%*E`M86vXmQ^K|d5PE% zf8`Jpo2Y5#Fd79fRl~2kH6`4SQjueb^Na=zV(3DGP)(%REES5Du zB0;A$S7~M|`|L}dPQ(Z16NfAC5P7@D2Om-*yvG_XTc_EhdW5mjNkrI=$#1~!mO=uo zB+Rzw&r9|Y54N9w&nA7>^O1?LKP7cgZ^%uwD6Rpu`DvfcL3tvQHg7qsyccZ^k&!VKH%39|ABw)FKa zN9DPa#1BlO6hRg9AA9n!-BBwTYQ!dcPB*NNrod`O;`seEN|5h~$ zFGBm5#R*jU5I{p(2G<7YrvI@X<+?L%bt(O4>4`wL0MhpMZ;)Q#Dffu`tF128|5TFy z#%}7W{>5RA)Ha1`DzsIESK1L%oppWWmFusojtnWS5ZSPE>U5@}ACtkLAP_a@~uxUs>q>6F}VV`ea`ijKf>})g&7tbxscG=~mam-7<`A*Zw-p~8t zL=6dUI?es@OA+U9ZFG_^V-AM8<E53{*!t}7+EN7|$*>ti z#=JdX`a0HbY*r2ny2S+W=lx@n4m4?G(H#9_PgX)Dq>1KD1TSJXzU5xR&+mOvB^P;x zJ%dgGa`w3dD#<&`we&>psZ_ILiUjky9Px%%OB>gW5qc+eA_knvlR9@QFlc*Uv=VY* zY_E7F3J+e>+!#jF{5=!3zdRm8PM!diou8ij^vDrV*l+G0|2*qw?Cl9y7?uWKdx0-UL{c8}TX5UDLbL28ua$jCMkm?dqB8EQ-8^_u4W&c3hoF?P>{T3Lzk z%_IO4CTVXo3q*ArC~mTWr>YVs<%8#ikE4i4-mw>M=tw`qD6#X@9kwzoTE#!gj`?Me72jTts3mqQ0JIZ=9gZoxv5_sRaC&GL! zd6F4TDHUZyn#lJlD*3;jB%gcq$zEO4-dJJc3Zv``&>=}CgmneMPiNoieamqP|$zg%8TxRerwoJs9?JS|ZbALOz)x z@L##oyxCG1&m*LO)J8p{^nd$c0(Eu}XW;V3UEKigXMKb4f{{XS!-6H@topa<=LYe? zY?QA*e_wEzBOW0OODLfD9_8Z;;TeD5QX4d@@@VMJSd<3+>Er3v+K8ip{tT5`(qz$T2fO=qNzqF zEyFEu{{0x^_9e~ctFNFz6ZfNe=gz=f{w}RiZ%NA%a*4g43t~(xA|tf3%WSbCy0Q_l zQr~(*q7!;>@gV2<>1CYsY6SJ@$jZ0JPQadx~!JJcewgWC^jf{`s6{ zQivNnizkDvHj18`RNH2Y2(wvEupDIn)`+ph(V?w}tWx`^!^$%!=ROynzs;%Je)OtB z-c_|&J(c?Vk+0;sNl>}TDu%vUqA+Wl=ZR!5AYQV+?^!>smCF>MbdUGi%+X-$fqd!-hQ*&%=MNl77uNhuwAZz5z zoI2MpL+z+S;aEHzug7;gr=<6=TQL>@K&{u{bXp6SdjQEMlp$)zhhS9|VBg(=Fm1os z;E)Hr59(enhbvo?bhOKwu+>6LH0tU-1}||3IOyv{R6;c-pKDo_Jb9WGfkVsh8?zdJ z&J1MTs3$2jkFS+QX>WvW^_!bKyY7!)m{|5}@+=@PJP0mSD6(AL@u9htpZAq1C3&+~ zi^_YDZU30B?bY#E*x}6tn5qSa+3QWoWN4YvC|fL_KluH{4mR`Mbe1O5b9HgbHl`V- zugT}j#_d;{Bgp6S`)KmP1;!JU3AQEral?^0!p%KFtJ4Mtb_O z{~%t=_0;rUd^|=Ck&PSqUd>p`vPn-X<&TimKz&xIFaLbLAvHH&&s(OfZ1nKZMW0r^ zEUN88lsvyGLCjjhh4h=f$cO@)@TSPB<8gt+-=N^L794HMDK~SSwTY69>KcMyM3r*B zn(HBSWYKrSkA&?`@0}bva(dC|DJ*9( zj4q;3y6rzU#WPMvDLv3Fj#SFCs*g?b!0(#ab+Z{I?CMN4jf{!n5l^a#jOm@_-%YU| zdO>f-#Z$i*&oBCIUT5*9ablxLirqoYx(RW zfv#_~`H2vL=66g8{iC1~u|5zc65mM3UaH9<*TCILv*MQN!RG3Y2eVMT5q0a2nBUX^DCN}bp zSjBhL3JMhSnE=N;=zsc2{U=08`j^_V>sgtQ{h*Pg)Ayihv+-rG??HKFv69S@(p~7E zAo4FeqV~(De-}330D%U;Vx^mP(S)LGNePA^I@sVl+Zc^?ttGf9{j4MVkgjb^w8O*d z&OylVroF0u$3`pJdGGesW%?sPeu=CExR^g|ZV8M{isxINdgh{p+g3(TQBRGoei=tB zYh}{@ld@4bZy8Idg_weCYL4sc+TIGCyemFBAcBNQX;GF4OcpZYe#rdijCPc8L`e^_ zKy(3L_D?MGiL(uegbLWhxjz2_*f0|_5gbgJ0JSqKSno$UF3Y{2F0Z6Kzxio-_EBs9!v++(9L%^M&BG{ZslKfv^OMPmjV$-WKeLkWZYY za4O!)G>;vuoi?5;ME$@Zf!H>{dHF$*EtnZBHm7+0EwtduRt9pmFJNspUP}FWqsij| z8jZ0@aC8x&p%}hOBCM_52dGoIf=u5Qj=Id-DPTRb)OJ~@*2cEPq_*QkAjnyCHNtNdMKQZfO!9^1hMJ}hJ0MP{eyBl0gQk8yU7ip;VJP5RM@GtNA{!5H z$dmwLhc~clw>C*(;%uB#Y6xp*nt>3*Z!}np@F&3sq7@&;n#>@`!u;3bVnAGa{l9T| z{}j>9BYJLqhPPt_{ezu&7*RiV{tEe~M#fZfikmNrKZ}13rN*DyyP*FWWyAxAQ^+~- zB*M9GYr>lkq5SYsK)P8RDhe6YJdw@b^KLlnAp%a9TZL@EYPd(-4jZb%Cz%>0U{R_iczT49)YY2w%D&mpI6UCeGuEfwQu3l9b)C#v0t=j-dR*z z^B8Od>A>?ScVbZTMU^Vr!QnkH?@|VkNR_h`BWUH_i_IrjCw*tfrE9p9LpSg-!Gou` zWDk-Q-7JC-HC2;b+umRgh~?&pi__M0&nDez|LnU@rfG33U!B4dwuhXZRmS6PwvjUO z($HOi^;ct=QV4&4R5;CDWLT`3L-lFjyiU;fgIh#)Iql&ybfLrzA>oznVi)R$z;+Xb z3f_J0oNskOqI-8>JWHY4VA?}c#%kGzu4`Ws4}WD9`E+DTKQc2bl%}b41E>RJ9eK*U zN=A9K+PB3%nk}Z|VOnZsG$J*QwawY0J554~$?PkI;%#P|0S^~z_t@A9Azx#rq`N9N z!-$qaULHkRs!Fo*{g0Wm+Lp6&(&+i_Z#G4-dyVTFC(o_F1LP@>b&tP}QNRjW=2vyG zLZR;MDB1O6bygw#;-+H6;(I6XHe9pp*RLp$WLbTXCD9fLqORRK>_8yB*yX8#cL=*X zyoScDc2;Qu0&fJSfe{gM-{UfX%f}Uh(|%)+mobn_^XY}odVMOv?Yr-|Z;B1nS_WdN zD)(DKAV=35ygvpH{e%k?G55ezdzni<9>^WnTi7Y5cyi?^gW%ie_7TTn(u<|KCN(t+ z<@s`ACgt&jP1d(@WRhJ1ae$xnywk-IiqAl$ZVd2l} zs+dm3i^s}s@h^%63c982?WM%{AC{Hab&8%m`^O}kZl?v^HEoe#`1h0qs>j{G5as{3 zm~-&tm%rKP?KGXZK52cOffkm!mOcUKR}Jl61Z~z8;1KQ7qP_R%1C+!beYAgKC1{aS zb)vh&e{{wCa{2emhN@-O^w1{DB%ev`2MW2G1xA7$jv>y^G(xR%*O1faKf|X^@IJYw zajCjD$Z4-j8F3{%ZH>H5VEl>OmAw77`7`#Yj za12%acI@O0(WB<;kJAKhjiV~AmK!uH=;ff{onyQ&!}il@0oS~=%Qt|7CT8J>WuEnWu>w=7Z~74B5* z0F6((iKaVIJ)F{ZD2w6(&77Obj_DSUVIVVaspiTAu0xz9jIBVG$eemGscZ?=vu@6m zvLZG#sc#lUyE-+^A`?ln0A%~|igQP&EN#g4Eo~%s%848bBolyryR|J z7av8YE=u2sR@t1~?SJtd+_F8W9pNhsPycw*=Xhet!*Us1vynK1p6t?*?A`Gh@$J_+ zvLzeGaQ9}%!QMSiz4|jvb@lk!5H&Y=+Kwf290(bLOXAW+F*1q{>gsWP=>utAl&)gb zox?<>j}{iw$fm6A_dT45YeO+H3y)Ey#SK||=Xt)`e9={NHxa9=h1b^pJex7EiOKWR zstQe{Cx&wtP%?Bi8%tB2DmEQ$1{P>1F-uF0AMC&HUTzaE6!6H7GPER`muIIfrA34V z-vEf8{oH2#u+gw|c2~C|%aYkF+ls(7O58Ylqz<>3e^z4Ui6!VzF?^TtiT3c6}w7+Dg5l>Z7m1=<0{@g(B(QQv( z5{In$4f=BP5YCc@2tS7x`~>Roum5V_{9pfW6>r6ez+;i6B_hfjS4aDbM*PVB?V+^T zjt3%j)LmZl7}HfiAveW^Ij2E)dYa7|FdWA6WgFuw#qX)}sC~-X^d_@#PwE)^MZ=F4 zG5bZDJX_a1mnK9wr6=jOBjCeIwmIq#tj1&!P^oyuQO%cJD$AT-7nKw8^K+d0!j($wLTKuAuT@ux0ZoDux-6Ob+s%Fhn>@>$spuPz?rEZLhiMK#v&pnZjsdR^p;cQpLPVl`AtYm^Hj zs3_C2s*f`b%L=xasMi!!chvLW65VMUa)H@BT%aD1AXOsapvsZj(0o<)I3Kle-L3U3 z6T_X^gdT!vpCu@x$^8_AooT4YQI_hGDzWCg{`3wEjV`CxWe`c5TKAaxmZ89?d0c!E zHH0glF+0H3?Pe}!R)?uxPA#UljEOR>u}{o=MnPn_Er4@jke209P7HDL@G|8&7%pR2 zMr&{16UN|GOWY5I)uqY~J|{K{k)%pO+Y*y~s$|d0OR-O(n`gbUK+ru*D$o3~eQ_4e zJctOQ@`9r^fFb?E3!*P!>1n#DX>U?1TFxt^QGD2DK z^E&2x^WSz92Q^0QWub(7VJn=$aZsxFL{AM6!AXrO7GEiVEJlESJrlfrEKooJYC7W^!8b* zr*Bk}k3M~H8d0orwuFLxb?=el3jpI^x_fqN5h+>3^b+@2F^S7FNTKi-p+HCrq^!2a zu-e0hR)h1+0nx`JLLvIRt5}b%E9-(Q`kd&Y@jcqwRIyI>iZE6VZ0M{BnZ?vV+*p(A zsba+h9!rLWopXkcSSqzQnrbmW`O_$ze7>AGrHWMkC~H0{*_9J&t?x2XBEC{30*VtX;3hAT2lj-@)_9Vk{z#b(M1~@-sCcmHpc(Ye z!w3@J4YugVaSB>(#LfAoHH((A%2>;6>#|LF&!`gr&@oP!Dj2$`4Eu4?*80$vUBB@U zT*N5k?(~ji1|b!i7pi>TOi-|u%JUmk+cUQ-^Q9NrFd}-I>FMYy#*{IL-J%J(!>^a1Q3|ET=Emxu(t%t9NnXz3O832| zG|F9Da~K>f%e_sGuBM;6Tsjmh^f_<&ZT7puW7h9~yld8q3$d9Af%Fh{GqmSRK22x% z{0X%D6wYjTzI4~a>U9IaNXp)-IsCGpcV?xc{z8Hd>qAAgEoql=xcjk&3w;znI0A`8 zo7S;YQ*!f>Cc4d&`iLFZ{8qBmN6w-%HKHb|<9h&(Hm_wd5A4^Eilb`Y=*C`Ebef{& z4lFIqIg|Uu@J$SaiPD!}vnba_>jvdPp0fOV>}4#3WW9cBMR9)X@Eeq+Tb=%kk>+0y zl;m~aE9ycYoU#1F=mu41iBnf5~ zujQg6T|z>Qz4H99y>(`SQ+9`{^wW;wEK>~-hE)oFwbxJ=T8iGO z?0?dOeDGAXlODNC)p5BdZe~s?mVIZn)fei3+n>&xTIBaq?qGQ}nai)ho_eHOp6Lt7 zni>xue)Nw|m8A+(@Z`fZZdd3lnm;*Z!su>iS40RAv+nC(a!-g}9%=d~UtHo!W8!u( zRj|DaB_lAW1%U*jtY-rK8$|>@>RKRCdXRW4E1{^)qg+dOsNr{v)3M&EKZRuM_cG5D zx~`rQDB)fwDR!4fTbq1|^$!$1s7T9txY+cjVAhhvHjO^EL#etZqGar-HDBhemz)pZ zu@TdNau?qxCp@dosJTc|tqJ)4O4Q0s{&XOy`c}J&p35SCr9WkGDAk8fRZ-mFRZD1B zQdreYyzo$cR|^lf+MjJ5BuoxDb0vF@$g8U*NIW}a(xRrS`N}8>p-PV!TQ^f*JH#0- zGBnItx9_lfw98))w@d6c1EEKLr%DHb(AR&WE;39WR>3%^M?VCtsWrq)SmRw!5BcpW z^0!KwT&v-B>+()B+uE{_P*m&W%*z;ykl74*!w}BE%^#41(-?B&>V!j(wM2b4hhX?4E#ryO>acuwYIDG-K zzyYW;TQR^ZU~BwV8;i%}AAgZ6g2j)yCqj#xOQAVS+Lq-^c`D;sA6KME@20^Vd`zEF zsGeVTtGoH_b_(nl&%TQFq0(C-3P}|GvAI3Djxs|!xcn{z<3$KI;+P2c00UXr|2wI=*~qF94`uYN+Q36)10Jy?6)NtzVnGY1u0MDq>lqXrMA>uvnqWWK3;C&pQ?;P__ zLE7MJ>iLI1CPuvu?(GrU6Ja`jnPovHV0WR@6u{W<-ImHv0&7fyH`b5)g_+Q>;_5IS zc6fxf?p6nh|H#+u@zse}HO=+4w+ibO;#1G%gR9_$TQp>2h49c5oayu@H_lV(FE$e@7&}P zot|cm&vYeofz9sVH7Avv19jfXwuV3GUOFtlP<+fdmXfh>6?&)QWm06g?N;L&`^!LH zSVZ1cCwZMl*Msvbu@Fvk>bWl~j-*}DwwCLdhy8Xe$BZ=E{DxlFmjhkUzSQ8^uiCdsMEr_&lqqK}{!?g0Mo zK#=5&kxnHi)tN?FgvhO@0qPY~{3h@HNq zWSF>;oq)EIC#G63_As4jBJ&M(J#Ngp6JFIfq@H^hC_kE|{;@aP`jR~|@_@;T0w=vW zS~JpaJ!D6~WQKvLgNj4Qm^T@7y<9!Sgz~HCB9|!ZE_BFlQyt<0-L<s3Bl7@*htq~BW~@IRn%+_aA;wuo#gvUabZ0SYi72LGk7{yvVw5t z=icq93ey*6`B707l_`Vjb?Jv6zkJriUn;2*uMVx$8*}Hi_~g8VdEX*xbjy096n%O3 zT~(=}A#{#?Voms$AwkpB-HX^RC6cR>HL)q@U_3;X0`}q!>36C|#2c2REcQo|_h%Bc zgC-Ma+o~h01sRijHtCHOO`KNcGkPAbBNS1vkK;%35uFjmPnH=?qBz04y1cXADtXo~ zeV5AS^xm%T4gUslbvq>=hqLBlJI&$8i28j+zVcBht@Y91#wCotpOdhw6l~aXb=VI( ziw(XxL`quPMc)nyQ+D2HHaIW|n4a{S=&z*CYDcLL^L8I(nCblny&xb9^B~Rw_L6== z`;VqNR#bO1)<+FFwWEvA38Tp_Zp7yn>c2#8y)Su}2QuB$OSL-u)6JtWmm#bZ1D>_J z`?7imO(-T=90xLV3D@q1Uj4tsUF)?JThIce%XyA>AZmP+BJ>;3ci1geF5-9P?e7f+ zwk-gtFTfyLI0aBa_oBNINb|biphwb`U8)o}PX7`5fc0M%QL6%6^*@?H(pv$G=;om& zX^#1V)RN^id5!ETMe@2yK80R5;uG3J(7-ucOyS&*ey~thH*T8oMUEq$59cjQQlalK#xESGqN&jk98fP zlfEbp(I=+Zv`LO|UkjoH3|jzZIC{)zH3dxJxDr~&+0QNExF6ePbKp(z8n@J8Gk^Ge zF>8f5zFr7?!NiY0-TgO6A*qYRHPQlWW6-USlX+HWWaA6zo1;YoghcJ#N=*p1uaP=y zGr33s0nE-Pf3C+Ye*ia0o>BI7FgjmM!jHk$-em|&26`XWOLkuzbVKlxC1G78Zry*)D>w8NibjnG*Q$*-!?|4BbZtMvRwq9>(fKZn; z3P0?_<@n4H#vg9K?io~}z4lG>mh?4IQj&d)3EjRYXNG*K!mYDtarS_G%jmjRy#lUvnW)(U^_H zxwM7*g?Z!PSzcs~(&5x0T1#omUAW|g3!?(f$iD8^W_1x$2isZjrrVP&5bgjQMW}8m z6F5b_lj8B2*F$WW@LBAv#`uzluaVCbopvDq{LZrm(`P8CN7f}rF*%zl(9&te%afV6 z-nrfK+t~>r5LBBs(}-9zY{R;?-u<8wFi)C1lHfOp-C5udujhlmRippw@Bgp~(@*?i z^(y_T^7E;HVpGoUfa9$2p4)e8-bkiM(|n)8X{^y&qu$>A2@)7Zurs~w*{$|D(d?Qk z^M#CG&9-;|b$N(?CnSJREeySP7;p6gVTbqj!GN7p(M~ydreBK~%kn{0L1e%*fz$!V zSIyMQJT9$8+<^9(p{CfZQ;&}_LF|?S4}8$%0HYuF*_8D5wG|Ki%-dX(&i=fRWS5-cUD;7n zyOolqo7I}~1k+jH!OV$td{&>-^a-I;Z5W7;nDPk;pm^)YU8m3=D~54TjEPKi@AqnS zau5aoSi~KgtMna7GT)!`=w{%%Gs@J{)?d_~AIN`e!3R$$W;UyT-Ctz%&Z;Yb$T9u% zZd-}b2Vgy}ig(_f@Tl%}p*z4TDt|ZrJ zD|bM(#3iW3umH7Vde4|K_Sj2Om?I50kPy!dW;458*OtB;PI-l6p12~*I8XoLICMMn zgE+LEVQbfr!T_7>AXuwNj7T_4*Sd!0pv@LRK8?21Z*6Xi(yOB(OC&7T)1+20wmg1E zgwPG@1LT!ZuMJAVgn5D={^6TUgM;>sr(I44WG_1MU&EDfe}hb!kC7wtkv#jE(}$;x zr<>Q{(=rheZijwox6H?&R+ zPgq5(N?auB&c0##?uC08{k#V~aO)lRlQ+1R!#dY3EOS% zUMO2pl{6ET<6O|PXA!H^YG`}3h7{L z<6R{6rGZv7Z!A!%B=&zlS)*j?=O?pB)&$xs3n&hLgXB)U4AFPXy%~SLOKh%ViWEs6 z`*>(=OTY$yPN0hVKpF3Whj(aW6sLkUqsZ>@qw-&gBj3-4&^8fs%DfQa*#-&xoUfOP z{Yh@*<&@9R&ezvqaaPvik?jw6AlnB-AI34>L)++-mVWMS)R!Aluj$gYI9JMOuJu|T^GIn0fS|9-gSd|ae(VI14bf<0 zD;<~~>fgAP3Xc!qkZc#~Ra}R(KI6L|Y*{h*nzHk^WU>DcTwK3KE z9sC+o0;0WMjH+ZG%S?x++@3OuwmNDrS(DtK?c*hOSiLAJ zS{n+&7gQ13Aq+Y=1i*N=Xg*S^JUhia$aND|+?>9U(K`a3SDbWA(kMN|%zbyeywc6UGE$on-a{w_<<_M;$1uiEkYW5p z#h|#%hU3`+qpq7wwZ3Ka>O07d)L;=AZC0+}vc`O={o2r~V8AWLy+^0Sn;Xbe%(7&c zMmOS8$sQAGv5M4}<$a>Hj{cH=Ieej6E{gM)kE);Usn6lvNKD)_bC#Ud0>_fnVZxKC zIOuNm&1=@qC*NlZe@#6UJwZ%Pg5bD~zA>_`~CF3O`irHs*m=y#k#G{7w+hPqZ$_BElnI@(KMo%#9TrFgD(Ar6|6 z_=j|lsomEtA~(L=lMFrU{1`So22rJ^D(YBgs_8JTRZezaHApdr5>Yst*rkhv8S_gM5>rgn82iN5sH05$xtQuBO9eneTJ9pqt>nm||;++h6R zPL>*(X6^JSHUna9ji>dMjpLgbF*~-XS8bGRALGx5;Fm=8O|^)|cZpw&RvP@@F>=b1 z@mKpNC`X9sccy;fA4an*rlz-pHeEyGfvzlv=LmK`ASnRIKjrFvyCQf6QJwMDDV9W) zBcR()X&ZRTA+JaB^8|0;ib+=ZWF9ddH zc~dsZW#l5<)twPuy`zZlJHjR||HJX2?TT3Yk$@wake8E(8Tn#(7W1IPcBGY?u~!Ry zR+vKP8&C-OZ;iuf~y`Y`iv~7=ENjEj%8r}(vSIc(JhQU`c67XFE zqOQ>&j^7(L>AWPFaCW3<*S+6QCx_Uj?X&SNOKFK@))UcygWWg71*yb#)5JNI^3EC1 z?|6KRMd9oxK_PkW7naJnG#1f=x>C^$y1`MXxC-Uj`=rYN;08 z4o3RtPnvp2;(z)dN>p59}z0gP|aQ3$U zmnYB7Ex4_|A2GT!ytm3yPy!rvSu^5uf4o2Wzb@;qYc1s+uYQ}yLxPnqF<)Ij5}SZ!p5TS;1)aW}SEE8KCKO)-hv8Fk-!h3ewxhWCcL*G^IV zX+MHKV5+Jw-{5TtyBuCI0>Z)PC8!m2oZ`+4=(Uo*$h&6;)PNQsW@1)}CT&gMdC5xa z#jJGR-28s6L&ZE{?Lrj@MD(_=kB^uZKcV2QgUgEhM%1plzMb+5B@=5q4=Qth3etzD zuWUkWuo~#6Ud3*B@wsAqEKVU|PGitNzplT1^rxDMM^;0H!uO-Kfx5v;w*tfMxajJt zm^yRG<{M3+Cft%fCC{>K$ipAI{gDQ}YSEr36~_#0yy(e~N=QjbS=6`Ym0T z74F3Vvuzb^X}<*PbPG0vxbEB6$IL|ObD-E#Y`HRTZhRJHEJL}u%SPL76V|9AtV)_m z{eEBY8}uG}e2A>3m`ytavd3NmxffcImWk^~wuWO&0h%T|2jK-+@dcvX3jCN;^AJ=fSPCP-SB{mtcR@%h*dfHFtb(UHD%jHrH5+f}D%25s;klM|#4)`$4_< zD@PY`{^8F?eDEZYq>F#jRs6xWZHuNkuQb{?xu`{W$aKiq=lKdy8RE-Br?UUZ!mS3V z&Hqf*F}{*OO2z$G55BeGUp@GAdkhVK#N;|Buky-eIauTNHGQ!VtaU{5aY$@jU}#+U z^-!c8Pl?FV5o<2d5@jG7*e=6#|Bo(vzyIb!=l-jg@jtX{Q=iZ`6FCk3DYPGy>myU@ zhD8OYiXpn!&U1pnaPd{n%eURKd=$ftjqSK;R7S_VW)NPUJUVfX9~W}JK@P8i3DI2L zJaCTL?-=ZWxeZ9w2K)g>z;`?$2ngyx{0!H|aeo}?-V?o(cQdbico6Kpr*yOfN+YX= zn@+z$5VI4{i93pG@|4O-83}eu@*&;A*p^+T+iKhTlZyq6%FLQ*zyRAYs0i-7c{EY) zpIf&w;m_?Q)q##ZS@-S!*L3(G?#~J9wFZYug=5L0j{@Ib73%S^zpuURV_gv4g1IOm za_YwS&Kaq{s8k2+yg)NaWZND8iSVunsapnmUC$`L=cz_zeGli*rAf(-vmNr_{x#ZV zZ9qIxjY7Q?=pvYe&VuI=j9V7u%SN<+7=n4)il30-j-y{4xL03OVDEf1!=pL8$2HB zc-Py1dp1lMk%#JicmFuOB)mjjZkWQQW%;FZ1=Azl)G_?2?7Fz+A91U8R?WoK2u+-t zIlZE}D5F?lo6PlaO4P@pF`p>&hp`{0=k~3DiB&gD%VWAGj`bAcBI2T$lSujZH}a;) zwrDC@xs|@@x|SQ|7G3!wH*dX)t;vcuI^!28$wDwISe;_YT=HEEUtU#q#35?xM*?kV zydnle?Yzq6irz%YKdiEiK~s7U7{BwihkOYyp^-E9(X>YzK!X81>NjYt*iv>yv!=ej z<>%K}UH>+w_b{QFx$mU$bKmhXo{1c_jqnR?gs*^MnzOH0-3YamWppu8IQaKSxG5jG zF%8~bUYEJAg-p_1r4)7eaEJDMVRPSD_+IKomCH;5}gBG+IZs4 z+5P9LVOp*Wt(o4_eGgG1W!=(u$`%wHR{EH2%p0PI8m$}XZM_js^0QGGAnp0&r`MYp zh9p;|YK=|R0O#|a`bRL{=9=2ujmkH*sE@WbT!e71kKYUY28HBRhpij9i+3-6e7Qmu zdmzjEE}bA!=CxdC2lG!;U)m|$S=NJ(1S+bc_%f`wzN{xUV>L%t3Ub1_JJYg7K0mP84z`B6upL`HyIA2Q(o&+6=+A9E!U|?O^X}2w zeg|IAZ@Moe&9(J~{i~c{bq}fd&95E4OpR4U>qM>TjdOKgl|Nd)32_u|n3ecQ=@UX| zD?yR){nZDuJv%ulIOPm*e&HAZd??iXr*7kW=m|hX*MN@&lI$>abPcE{o4$Sr+3Kt2t|l?UD!>9CxNd2Ly&rkvUuWfrqg1N?Pq8X|PH(*D~(+KEa0GVS83 zttlj}yfsT^A!LkP3SVb>?OU=x2TuHlPXb{Khj(vML0@#jdbB5uCR{uy24t#*)do|5 zwuY}v9QOSVVP8E*&x0E1d__0xZ&I;Ih8v(O!M{Os$ug59Z>wv^?iA3iOt@g zvZqbR+TzQaW38Z6zPz%!BjgWROCnihG{=P=%8A!yNrQwEdPlzA%$5DeU9XR>^Btzf zr$)kTE51hKO}ygA0ZGLR3dWZ_HM1dZylk-Vb(#rd#JZwvv{+xtQsc=v98|Yd^SaOW z>hFGo`n#lZNijjv`)xC`i-XWIWU&3F!f_7T$?}dz=>B=i3EiUEqaB%hr#y z%f76=Q|Ji2=wUSYhsyrahyQ>5E7vDh_SN)Jou=ONsuOnb830z)Ti!~;U8fDY44r~% zjx<8E3#izZIExDyg}VmfSTuuss$;Q`!l7EaSGHSI0&W6w3q#i2UBzJ+Q3)A*M*oMn zw+w5mUDriJp`}QnP@uS5ad$1ni#x%!NC@r_pv4^uv}kd6_ZD||cX#*h(QmFf_ndRD zwa>b)v(9yX@FQ;+$w)Gi_kNz|mhvk$^N3dZvhAttF#%BzySzOvzN0i~?w~QM3sv#a zV22s^a#;C?x%PhRFbuz!G@Q>|OAZ!Xy{Ja1LKrRIw>Zcr84#<+&{7<~rN{003GcGR zv!RyS3)3GX$f%z1yKcAD@3o_>IcG>v>O?*I{sd1u#*TpXgbNJsYCF%!I-l$`&3W;(*B%<-sG$#wD)8LQ+=a`g!tl z!3w_Z5beN_OCAn_VzYLM+Pd;8izUfa;DRy_U_$wUQKJ=7gB8UB$H4B>Ts`LeR6|le zHBGAUaz?T+C#QxzDeKqs?6|LWx~YcmoxgKEv=|bUciE}*uI^hHOc;9bB3rs~8@wep zGsZ|2z4cZDBKC&0T^^|4q*xg1vcOEe${C0+OIXQ=dT`O{ZIDglxS>Pq*S74+TCSlQ zlZKNq?P4JWi$bRm|LVt+Fure@u?_+jq$3sijt93} zRC|ed>XK1IqM>PmBd>Tfz|AOxfIpL`4kIP2kWVtK%zzEFLbx*JNzB&LJjO^_F&br= zkTA_;y({o#yQI^gS?uOqUFH>d&uW4I;eIZpI^F+lb`fN&F8oMyN)WyA;ag2)Y?eldF8sn<``L%6qATduezFKh3y? zSBE3$>|CA5=DS%A=MFnku#_8RN%i6S;1Qa<8yfeqV!Q4R&%GgD2iJ{VFU=2f)|UsY zu*68E#9j5Mnt~*(;}DTuhp{}&or^eS&Fv?*g0UY%W*6tADPNv84^!9m(S?eVY@zHi+^*Vz4AlJvv@GUZl`E9Y`7c9Mg#l*S%<*N}riI z->BDiMR!#{EEv0>&B50GPWp8w2v7dyuMK;lj6&`}i1tw5^Z^4|nTeH&ZhIdsOC3dO zvd8B^CuBS1v@5Gb1w7~pTGAS{%oyP61LBhNmhCh;$?KZ)T5osM^=jhTS}SKjqRS}? zb`a7>uu##Q(IygFB_EINuQ|(2}y7} zAH$78wp`oA0K4pEt5+)y;j>)|#WwqMSGk6z77g;jIokR<`eFi|CC7=g6q;cMXXR4T zLIwwXN_J}&443ru?+ywybq5FpSG|P7j z87)|4;9rg$w*ss7wW77ccax#Lufo=k>>^U`&Og?d1(3|9Z$9-`10mY5{9L@N{Y3r zVb3*Np@$sMx%bqMJm>uUzlk5==zJd%?)8;fn=J9~R?hK&TqKvC;!vp=sy0-UjTn1{ ziR+@CfAwW4Dfqi9Xf+h`eUg#xj~Khut!%*BJF6_?U*)2pf4cq5cqwp2 zI^o=q;(x1T>;bjcrb_Yru69mfLLWxbU~B76h#x4=mX8D|A0MR?w{q!V1Bv$+yik-+ zZetryqvINb=Mh4qFJFZhKCUJ^6&+*kB*3di-t)`F_MJ(155v)?3_gyAU6g*vqNJrv zhU=xNhRSE=hPWm*yX%XE!=M-90%h*S{}gmVjo9U)BeL1j251FTd}I*6uYOX z(QnzSh`@9Ay-j<6vdQ^e!5&{%k^}1Nc}uQXnd$g>;|M1+;a0Jqh-1|>si&9k7!OVT zC?l|9*JG4H3QV>s+|#L1NVo5ipUl%ycVBVi8F>bmesQ%=QPe>C0WQ?v)Aj5bAU zaXHG=tcGH2Os7Hfl>U1!(6y%~A0#teJwG@d8Y_$=%$~K(J4W4p>vBG#;OW`j*QVX4 zv^*_yG(fIM_7fCGxx0-x=D(ewvTahI(5LSXdq$@F_r2qXT|zOv#AHmxy`YVrjgpREGV&Zmq6ZNk*>RY5-J zn>}yZrg7_>y4FPcP=fD=TnqDEjO%i_?ucQV;LXESTYGw-i2VZJ5&LOmS0#mx--8JG zTDm5V$;3H%pu9k8&lv6n#m2LlVT9>yaVMz2xH#%*FI6MLcZ^@G<#0ZRGb^7z&wN%M zee}k82vN3JSapIv(_K<;=1Ma}Wr=z(P*W+8P6+o@{Kp0pUcl~iCUw#p%JA!* z#KFPTBvjzynAZh&dr=g0zY7bLWCV>2g~n(|Zc`x%j;^q?*fZ@};`Zmw8OnO0*h(o^iELiQXn0sG(y)WgkFa`;r1 z+*n`TYOHv`8ej&T)A$<{tDpCu8MFQSn#zmg%BN$3tB1x0bF90+$)N#mF&YWd-q3Y) zf9~#_Zff3WyOVK_PF0!p!Z61G9tGS6f`oIrfS>02<{oD_9YjoVWV`m$D98P}9j%cl zok6?+Gm!)NWjAQ*%UkDZHU*;U4i&+sRGof;09GM*hyfoV3y)yXWnNdVK^LfYs$-#N zR5Uo@x}<)gaCksss)sN{_agzrjN{R=2f@-lU zA!bg}?u|}c$l3c6l#CkZm}U`vFk%aOwo3CUad1vWNoLXRRoJ;3GEKt=Mkcr!Ht#E3 zLZ=P)u>(LBrsxHJYAwWtZ`bZf{1str)S%iB=3W$5(fF}~uJq{r0jTtwZ&TaPb^6L? z3&|`?^|X`NVN=Gs`iY$LqR>i+1kPwjjO9DpnXtTj|drVtiKU1A+Z~Am4%ffU{S`+In$T#x~EoA;=v++~GpD-nMIZ`d4QUrCi}17hTHER|mMI@??js zNz0FuO3?k3$~~&3lN3wbsao`qoU%4)9^(WP+-rU-ik$=O$iJXQX-R{8L?0|1i=i^p z5bbTTiGxd8j4O^B7bLbq1EQ>a3Let+rKCoiHEoG*dXfN7@$4OkISZ0mMhCX`EuFxa zIj!KhjXD+b%sBnzpdN&hEdfIO;zCzMrKty@odnoP0qCpgt2ckk#Ae7~v3 z(Chj>N#QI{r`=YDm7Or9TL>ixPCjra;AnsQp5yhar5B*GpaSBNXCmD{7>2y)8!|#% z3<0Mc*GarD=zr0EF?ZuzkjIM2Myq%(_qnTLbj2A}**WYpdp;y_$EazVTn_V;ibp@L3|A~!HL_6|?qW}4<}Z(Mcg!@0?ThS~+ywr*@}@eKh;=KRvA7FJ zGltqnLOot4ut^!s^%Z5=V$`pkUlw5AFkLpuOpnS!h-$9}T>3%=@QlE3pjEHxUNuJX z8Mn9=?~~xTx~K%~LAdqDj@Bv_*ftN3jiU|pyv<1;GC%iTaGFa`bELR09&rdN_bdAo z826gn#?sZW`>95uy6j;v)Y=7*Js(oVmADrKcCI;AA9`x=4 zXfy*cZ*mfS1WEpGo&#UH`+m9zO(;1B6%@tmRbM7O-IJ`UK_Q3MSDvv#K=4Js z2y5icE64LpGc*^D*ZWRB$Wp%P^T*ByY7{LS4AX>1Op=B#8yA9zmTQQ?#{xao zR;`%f?8cbtzl-?zD+C?<| z9cMu&X@e$Bxbf|P%uBis996lW8*smflf+4;S0CBjDY_-Yn`Bu|j#El38jKb!)UVCF zB=-0}w0!>-{ASCyedYNrMy6pa?}l;NNkk)4`WnQnZC~qYJaKWhX09K~SlobzOJ|BD z6$4`FCj+b}w~6Agj!Tzsfbv6DBRApl9B8mdq5fUlRiN-6mNHmyspt=?Z;hW)41h$> z&Ae)dr@*(5Uh}Y>o85*Gk%mmZWqt6_$PdTrT1>z6Gz;NIYr^<~y!h#aXs}$-9>YHQ zN7B?qax}GCW@;)yl^=rPAcLE8)u*1*?SLb+#;hH;$`<{qz1{|jbMV6txAKQ>LeIrW zY<;Ea%g)JaFNtAYXqm-aOB&==vhDj(1+0B&t3wo)6sr0I**` zF7?}Do!pzAl5AF@m-jD^g$7rB%1+9+`(n+Od9P_Ddmy>qpaR*o`I#y&c?f-HCU|@; zU^IK`<7?p=d}-&w0jWG^$@4=487EJ_=k9UX^a}fc=u4OddUqd*1;f=S;m%43<(Nt!yWtzBKWS0$_9OTRstk?E`9r6Er&X*ItF)wOkrc6!==f z>rcaDt@deitQ?|E%S-QEZbM5b=p&gE*Q-j2tTc$RVxE>eQ3{q}ZTwCiZqL9XFOt|K za;V!%RLf~LJp+ExfpAOBC`dy(BHL<|TnTT~OzZBE%DIFLP0u|m{MnO@ozZgy3*3bP z6nU$eSM3C21{@JTDj-R|MXfa{Z#z9JOTW;XO(0t&_EB3oIH#8t0 z16WbtVQv)ADy7yvOH)1cLe2EB1a$V~e*Yap?Z1&}(J*^TzNE6$j1;d{$IGeHd(dWt z(NR`t&-*xsp+4)3EaQZ#k8(URYn~`pSNogRwA|AvY(}#8f%zj7Ty)Hn-OqJBqr~aE z&N?DSxo&2^Vut&%0hc)51$CMnKX~(o9`9&Uz%Vl#lBTtQMj*uxv48Yq6gwaQTpIgpp~%Y7NeutQsvlaVH~Rtef`S= z!Qd#m_=8fUfXms#kJ01%`o3-InhTn;llhyePd`G&y1H&Y8vC(?gw!aq8=xUN=*D3= z)+XG-qT*s(FB@U`L$el9^RC2OjApBlmRW?#J#PNCFBYN}1P&&kdQx*AEN5)r)nX5? z4fV2{+LDfOgtqT&&Mi?8oxLjoH1*DHe_*>{Cmu z>6I++lF6sBT_G3e4^)xgB%YmM**kRVzh*qj&z{$^41Pz9Gr^GVmi-YWDWD^ePgONM|@D~HFHmRPIu6c}PuHmn#-Pj#BB-$g47X;|& z3ya$ArCqFUxgUS(a*o_)eNDejVoW$^^+P*YYXsCR0E1g4pVOn{53%(OEilyLPCno1 zB=Fu`F=S|JX}IkzS53y8bG&R^4C#DUAMHmsV`P-G?o{66hj&?f!TGvYi394+mAbR@ z^HkMe57`bP?J)T(s5NiD7(?MCX#|{9)#@z)!TN8|7O&N#J1lyO4>Hu6?Ml;ypPiFw zN>p6jRm#}(zB6pJuTn+~57i&n#GF`veSayls;1_Qx1U31z)QLqKi}!83f8CuX=Zq} zxIEa}`VjOfBg9Bx>fZ&|Y=~bhwS8iE@mdz`Vk+Q%gBZaxQyrLK1Me;9{hjbl;%+|G zFtbW(vVLV`y5YNti}>j$SD@_#3k1Fq^5+oP_Lt@B8`vpl8Xt39w36~|P3w6Z^!@=j zQea;Hc9r|_iR3{}$dRxpB&5|8YUS3t@tte^NgEz0jelBBU#XQAEnfq?cx2uY`%3(O z+VCa+|GSIppRC{%-t4-k49_|-KHKh_sCwMu(Rn)BBp}FymW+N*ZAoUCij=PnQH>T@ z?D-X-X-sia$eEmI+Ns%dvJ~x*Wl`};=CTx8lFj{=ouskJhovRtnU7EkXvK9Z4SHW8 zRq9!aT0v4@;@(IwF38=MNlg0>MATn;nfW-kA;3x+*>M0CKHVib=s}*Z_u-+ zxZ*EQ=dfkrM|Z!yK9uGb;~uVU0+Hg6L)MdSg_(SUIl@zex5&j@(Ewr+G<)y|IdGAj zaqa3~&M7>;p>o+>s{0KpYlp0Pk*&GmCIymk32%R?o}qCcgQ0o}tDB>T04dmi9QVz9 z{~|ls(sXK9mt?!5MlXmHP4txad}}KT10guBxV)&gesD1)LxEw{6puS|r$0zioIYzv zMQaF2V;n!Q>m~|xu-yWZG}0$V)ee~tnb$D2bUOKn!wCWkvHP6=IGz1xSVM&5CT$V@ z&IuUezK_q}=dxu7FTGxKtgli05C%u=eyM2deY(d#aV>0FJC&14k91@dzeM>8MS`Vo z3=?fj{}{Q{^?EuVl|E~+^C=d-vghPbO-n79Cn`0>9U0Vh+EVFayyk`0#t2p)hcFc% zWqsY{vu%o-MI~cv`IyB#G)pFFo!Dr%-pEg+2jSBdR{hR!^rNC-0zoOrD8^I_51P!1 z(DUO^rRox7kTka)0IT7YC6ZXynBXXEq}>eRwf@3bZ$hid63*+49ZDgVVf)B>K^;-9pwhHF9AJ zM=eY`;1`57h%Df}K^za~vzxOyesKH*hnI#zgFm_JL2d+f{EEyy#q4HJKQMh~!t+Ip z|GAYzj8X+)=D14zWv4r}DTOw*qN~8FU}b739FD*RpQbHb$*eoZ$WZ zDN5PfRI0><5BKY{6`Z1hw-u`K!XCCi^YviUup7|f_}$!c@xw!y+D!sZl+%1Grlg$} zAzw0=bG*hYC~9;iSdvVPf+w`(YQd!2KwhMH@NKsGiL>onm?8y7 zaDc%!jpN5w>J|H!lqNy2RekMS2Pvl%%{@$gs+)I4Uqtp zDP?WZrdy@DrLO$5a!qx}7OhHO)f+Lik&URq21#K@UY)Q*+>)jG+Xn(eJK`TP!;Y{j zX2w!#$bQrb@Y$SQ2+3^o3ZzQn?$D0)1DT58AVBgi0_-)Q|JENc;{3}2xcjNt+b_b$ zeonsD%lK_b_UWrVJ*HTfGhD`|GKzZ+WoxzP!JEU%9kCbBcuPFR4ZT)5n8}fPhq-o z6dWnUy3+F}8Xu8LyW$?Z@>qaZGi2w}zmeJa8W8~pvtgTtkkGE5GZK|6w?JEe z&dNO^ma~ZY846{sDP5=Znr0f}hMojZHh>v?1dm#a-#)x~Rh?pD3B;F(6lZBSX@hqQ zvCO#CRaK}D8?SF8)0%5PbuFB0aAX!+ns=z<2edLaO}U3iVlVnvDc#y7xth%3h({SS z%`(=VPuM=6IPogjx5^WIya?T99G_#)jivf2;%D^i#bOouSC)@H&fAGqPsBB@oOM$k zK|@uYxsC?-Y=)Zl$#!Qy1h$hOY43%AK^60)aO^FTr}iNrZ+(it&17yLEUxu~G7~7( zPcj{S7`GU7Af$cLLytl02)F=>hORJCx)G~i8QbBWRj%ER z8p>~x$DD3-M0s}D!TYI4?PV8NFQebgn#puE)s1)|Al%YAK4gSy6O@%FJkG}UTVTD) z5W#j~dO<*%xABVSf68>2S+g4Wc&8c@aK6TR=mR!l6h5(??&Gd58bD7S+6k}yfzN*4 z@{p*pNM(>m+JKr8qXsMgzA*ttlWlpE&~+EP(}3E55-OV%n&ifb?K(MtLGUF&D#9Kf zkFdlGwp!T`F@|g!0)9RQ+Cji?y!o6)8HnoUExM}ydGtB+93lFW=OEgll}2n3@_~nJ`y6@ zsVv<4tXc1YmAHAKHTITSz>4M=^*sZ&8R&C_>o)f84m)P#l@*33g+a^fij$SZ?E`0h z^Rs39+rZvvU3=&Cn9l-e>|=>H)km!>elwk?U4Pqvy8f{NecQ#iZTb#uK=yxaKnwmv z^}FK3!DgZQ73Gx^%!EwUL@C>ItHGjTM&l42TGBV=5w>DBgiOz!-r|clcQu<9Huf+v ztR}vkz$h!qM!{rFemb-pc9^Q%Jn>Frs+f!Iw>5=`Iz3BDfPSk1g6!Z49BK`R*psij zvHnBSe#4gbrG?^?H~Rz=BZoP|NcUDDUOJ3RaAvWF7caK9pFGoH{Bwlg{^KWrBwyLY zznXRjj-$`3zO^xb+%6?zt#?15xlVclqy_t{oCKT1qS0a3a$k;U>PfRp zc%VE4e$S&!7DLmFSTfrcrv)BhOP63ev(49NUn~ znJfEmD3LG8%e*-UnHZr7b}A+sJxH(!%DLO*IEL%>6mO;B{OErw!BcX1vsW|&Ph|hf zb}qu#9Es7;jr!Yy(bByG8QzB925YxKK&Kbl8}={c>B{_{Jcqbx^ObEJHyfJ+Zr&lg zZjD?pBg{9Syr7?=AMzy2*b82hg}m1^wBlKh6B1`&>x;BLzZ@W?ut9?W$=5w}V^DFJ+1NmH|m2xN&APo~I~`zS@`;w>$=Rs;8?aKn zYxEpf_;*p-nZ7hJKMC(I(~N7vs6x%_jF?-7&NW=|304d>31`|3jo+MKjq=qaP}udX zr%w78xXN6?aF*mA18k1WnyM2NrW0Lz$5+CQ(Q&kzM(ksV^0M^@Z-e>`beSKm9%0{> zrUl7E&N*+~&F|kekET0t2bYvWdrbyvau0>{&H*`(dn=8wmoH&8Q``!FIQhPGa~Y5% za5b*oIPh!Q-r|4;L$Z+<$h#@Wy$4)bUPL7R27zH|E12r;Fz|0s!dj&0|3xG2a2FT} zaa@#D4)CH-wPK|E5OJ>@PX5VYA>@{h@?6H>srRMG#s$K3s@Tb~TEjS}`Gf#d(e;bA z%>$E&Ulj3c^Z{-UUqewo6R;J^%+GM)73O*|gE3vxWXet!rl#h$<7=iB7#rs2Bp~F$ zpXqw^>8pLzl#xI-prdE=!%qZHFDFaQ+*x?>2t$y5Qa6p=|C$c$n5J?RuGSHp%-o$j zjVE>7q0nsajA>Kbq~uqUsZBb^i0>%-lz5;$=^s3rbI+I?R8q}7fqHT)hgHa{TiEKo zVx~r#wxmk^oIy>rSGKOERn4LT{0_!0{0nW}%861F5{>cirIgXx zASi96{fW~Gh?exHtWM$YhgIs-VipgMieCjs%y9-QtvP>n+iUzBLr$eB{4suzU%&r} z(0KgJmZX|l2*eW&F&X!!1t>6MoL z-E8YvchRVx(n;=zXvl+L0r(RnM{S!psa~n-^e4RM?f!VN6zD4^RRC#Kxly$bokk({fGD-PrJ_7C2-bk%<>3(@LWNoVc-VvBNRJmMP zV6__9AtrIyv(xcKzY{@{Sp660X_G40v-v%RTPMn)6YhYl_7+fPTWWUy~G*2yu_X1qpeZGS-8-MrDdIb|vkVOP3) zByD#}-qtSJ+C1r)qTD9?+)tWeQ%YMS!hDu6v_j&2c7@QD#CZ3|J*y|?u?IoJT;0X* z=8?(`0aG*JA4Y@kZox4uKkOCGd9XkKPa31^CU7?W2E7t4ZSpUI0tLniy38Ns&M6GE zb=8R?LlRV))yl@4-d$`Ng%%WaG0sHrJn!(gXThZ&pCEJqgAwBI(Iq|-deO(9luuni zgu2@k8W0AF!i;8}q;dlf#y*7ldo_0W2Eo&Bu5h_^4@xfs*33_hi0=uQgA=``;+WDM zvi9O%!_0aMz>n#M)JHFWG8xZOylSUEYZ*UB_q6^bL>&pPud7awZyq~lT#qoTX+Epv zP)MnG7rrP(rRmf|XOD>8wY!X7jRFmLBkCczc~s{q%#;SPu%jen#9P1349m#d^m{cl z;H`A-G;Fv!{OT1}uZt7RE#LAjh9p+P+W^77AhekYiJ){*GeI_4!q_gxY?nV4GCsU+ zFfi;F+4uvPDPM4J=Egxi9!1*x^CADC8g&dcZJ*CzW4tn)snVXf)zJKRY2~a^(o5|2 zQs1N4He&i`^y3A4k}5b?+saXG`|Lf&!qfh zx;vg|{(B9|H3*_WQ0|3t%9dcQ$?>daII`887&G zUhT>JI{dE%rN2OGu975!2Vza(!|*Y|KcQCnj0nvubcn`n+7kC)4=ni?3{DXzEI%Ng zD?Jx(g8sD-$@u5F`9gS&X9WMkw99`j5NrQIwoX{~-DMt@tpiV|Eq^TtR6VUdsqWEk zMjBjA!oEMQd;YcH_UA0~CzSe$fBo}$7kalpO5Ler+su$GL}t5bg-A;*!O}02d3mKL zw_N5gIh!1P4QqZru|E_JL2Zf;IUA*!aw8D9&Ou{5it;;ky`|!({l@|GkLM4C;l&k? zwmawNv$X5;UI`lpltE-MADllcq+XOq>vSP_YcRa*f{Sum=N)$Uq^H`rvXiy5CI3_+ z^^X3X6DFwyC1A9K=JmL5A9A!QU=FT$D!xtbsI84OH>Z%ruZp)5fKs(fHYlUn7UT{* zkt8fHRddSvLa4r0$Zo!;Ay;Sg2X);ncyUAam$9=fxijOk>lQV8i}_FeBDsCE$t zoF&2My#hWR%*5@!yZYiZ?kACf;9M}NfXLry0>B@sm=Bweqqm4J(`+#@^{482%C#&f>N7F|(s{J7HH()#{ zBvmck^E>6x&mD&|xL(}eT$e|;ke;2q5_H;K-2r46jV~ zxK5TVA#W_W-bP~4cFAVI!F?}7>{(tEPBAOA;KJW*u09IRo*URiWfQCZ#%lByl#!a5 zw;O$94RqK4OACF_R7TT%cZ2>_Ys3RL^wB?S|664Xv|{hf`itk(ZxD-+Y8uP%wMVKY zxD;z2$KC&?B2uomQRBX_>kJ{P1b9>M5v+29@vN`@f`eE2A z!>PcNbPeD8$6Ea~=~_&1pJ(3My@ZJoKXE%sa_BPsThezdzd?m`Qi#Wi0>FSRZL78Lvm8H67uNf@6!>FQPdM*pyc56W zyW6Yc4jek_ahsx2p)Mnf;_ZeRp%3+D$RaB7v@-F^p~=D3UIenSPj42%s(v$8Tn_IU zop=n-wj=D!5#!0dbsfk+q{b=pZoR$5Ko7pSb-+S*mbhBnR)d&nI-{i}4pyl=Ez?w0 zQC}HD!@eNUkHHXw2*>;FxpH`;;f8rAt7{jqF=oc_t9i7(*4?#f)WpDgZ(sD{xH%}6 zCYQ!H+IOe5l==JvVC-25OP^EHduLc=S@u92D%a>GWJQ0BtlRqxOmSQ0ru4kO-iVOs zVO7K8=WWBZR_;w{hf69Og#P20x-N~pE924TJn?D^wgdG!Uxjaz;RohMi`xKi?V4hk zZXlH@Ouub;%jFUar{=1>Li-mX?a>%pm#-K*VI`ppWsHKo)!>6@@gA2q!_?(6szS~% z)M~ZSW6JHbOf5!M0%JKc3%u>{aLfzDzS;G$^sjPI!XE~F0idg%LAfem#QOCb-HKL{64KYV>KKYPN5kiTam-z!^`&?EW>m|@T|1aa3{@nMj9QZu-f8?sD{Go>t zft;{^?Z(gqWS)K>kKT-Pk{X+({=Q*h7BjU#YHl=OfAB)yR?uHI&((WcYSQyH1zS_i z^&ygT+*LhSEyIxtze}Y_e3!iYxXjh9H{H7B^z9QORNSu2D^e8Tt_PQHSbPwZs%}V0 z)%bc!HOjLf{{j)2hsfV-uZ6gJ!jl*6yH_@N2}odwu*zl!t#wJWws>{Non4dX>n9&7 zvi70?EzH-JL(5asj|v|$nnsI@6FSiIU&mOL-9!-J9uYjcL~l~>R8E_J)qCH}9^Yjp zCIe97y2B2gLV2K$J)BgjsuPHFqMga8T470{7`?r_lCxW9tsB2V)Kt#5u;RIg(Zx}n zgaA)^sNo8K5&;3&i%wSyII6~9jnpj=M0bd2bg0Lg(roXb)q+9OejRh;JSU8%)oJcd zQ6JN{eBif30A;a`^zgngbTN%kG>`C|8!X));MM>Prkaj-N_obs`02fjJMaO^)431& zmQ}Thg6~X84C|jsJNHsp4}a_MoDDh&?O$0z!P0;BAZ>+eMrH-cZyPzSz(lQ&5Wp0u zzAqg2$3ym3V%(XP){_x(790dIhHi-?sX`|c*l@37N80UVy3B-b7B+cyKXqQa`2+(j zotA-jyXO+{*U2&lnkat_RnRZtAD4Ia_$?gPC{Cd5(F)nS7CCN-25;ZxON~SBKk_Sl zH9(2&l6Vr7<18xPYJDv$o7yk#b{*;1dI%%Bv01)Hk)CEX_gpre+?aiNTl{3;nJ;9R zc62Q;DccXURKB!~O>*4xiyE&<8FyxZKc=11JKshU1T9t(qQ|KkhsavB?t{^mW6g8a zWdG`NZVHjOW_EbL3%nOoAB&lmZLEDWCliW0ANy2FFAz?Hc#IYLTwWs?t>ka*(0G+21UVM=)aPX7^g(si%F^IhbsXk_!{tpV&Tpa1LM z!g%+Qv}To((cqPJUzxP$3cbB1sV92- zK+^);`6J;;Bog>0W(o11lI`aKcG@q2l$^xvyv#X;M)dsE*6juF4G-a;`WTjp-JPLQ zP6VZVoVDNEZY}HhSyMrmoR^j^rN9H23*R!}EMM*lKYi9WpmBF1uw=Y?)N(XL_8j%A zXjS+CfQzE=f!5cb0KsU3RK@v2ijo2I8izr}DNmZmQoG{*t7V#d z4Jmvxf#M}~)LfWS+GR7(eY4woW=16Qe%VCgJdn%c9_e$$WH|9WHQj=+ww86MQb&uw zxm?yMkd^IYSmfCTkAO*-OR=0wn|dl)^%$d*7|~`;ntf$2_67<|Lx=n~1J@yaXInQS zK|W;KrqV(%!Rt0xc;z-Y(IJ@r>qx zK@HW0kiC7%rYI3Z1%o`TAlysi1@Sns#hzg^Z;l~OF(=E91JNT-*5=@!0pB;u=9**XOyRGVk|Fm}}-l}{MEz$?? z;Uua@OqDI^bTYOt>U9mjs$xA{=v4b!PBj5n?;e}VVmaqJu24M!VXBtX8&->1&Bho^ z2g};W(s47DcW<#Ea|Q5{Nq4znF|AJHFH zarrIk?53Zj1u`BoK@3JX>WYuLn8;*l+di_VrHHgU40Dv(s$K2r|=yse(V2jI63vbaLUbPcNwGcDGYol&R#CI!|+=8!yXhIsbJ z^843ykzdL1+ZxPzlZN;s<;@3_+W8~7J=2GE! zQ(ha5VWLjgNA#8cwd%G7&&mY_X@It?M*9?seGMPZck5a^H*RtQo{^8=y1IYfCJ-8& zD%1htLoNm2Jq>NHG{MKRXDIoMO4&hZA{rF*VaW!QFHWZeW4iY4WP3Bqs~x48iHA&m zLwUlmzUK74SbL!w#h1#PQybaD7flG$W^>vp!t*kDx?_CqCQXGM|b(lE? zz$2c%T;SwX`7oAQ>-y$nrKaA3c9YTKvnmRnurT}24xY`tLe);HfMtt*)*P7w3!cT7)#DUO{o;zr_gvI8lEw&Hl2-r`>sO!BL3E zgyUQjCPnl1`B%s?shn>TiL3ulydf6B7c}upNE^Xh0ldVB=j7&!A0d8?2_vgPJqJ?9 zIxYTdR=`h!7a-G@Z7CZ!(gIXv5~FQl+_z;lCbnA7o=H(0hvglAcUWh1pC3qc8fTnV z2$))Xn)=|t5NbyTr&R0XuWC%m;*4PU9Q3Elvjvy}s)g@5I6w%h{8%Y`1MCQ(;*|EP ztTYzuvE9^#mP@!JPPY`Xx}zM6a%<0xt@@?5Xwel>;6qA<(hKx0=lml8BZT)uw4=H8 z!PzMM4>NQ{^(e$>Y)I#Cqa)mAJhj#YC5Ct$mk%mEP&HgI7o-sa2(kj8j0l#LeQwDq zoyoLBB&1^vKtQOJGi-Xr8Dl3=RXfI#)gs=)i;#SgNqrF^^!1K!c~r|Ho%#4dR>U4J zBdKH4@SIu(flkThmY?NYWcMlBlp;)3dRhtJ0{o2W87uQMOS1X)YOHZ>#+!V^_SP9|o1iQxYF zUB&K|N>M0hGA2U>Lj_{6{Iw3mxSJB9L!9~PqJ)cta1YZJ+@bw7zUEZH)aWigIg3>b z62cptY|cx~o{aH}h)&Ra?fGS3+tf58BjYj{`P3^$Zb^IiwK0>eLluKfd#VWGdE$%M zQHqv~jDPi}mn-DQOquNZD|owvqaQA}+lZmqKN&302z%#QH6yCS#KIy%G2*KdfCMsI zq1$*;8~UUj8RXOhar$xRR1@v&r&*-EBvE(v&6IGkiPngvQ=l@kvF>qCZfu7m2#BT|HFo zm9-x;vnU6(f;uPQa2+H2C%B%?;!BeGh9w_uu&lTMUzb9lVBpTZ+~F9Fion*#I*jt3cTW$){nk zWX#^n6=x-SU%UDMELOO;yelDxdJ3GzQ7i^MFAZ4GTliI%4LJeTMR5QyQu%o^zUC5q z>BYU45CkbIdB{_~yej<~h_`VjnO|byy5C`(llgb>C%d-&5Vwp8o8E_!=|G_BS(DOQ zm*zwQoJgX)qTDt;JFTmNr!i1 z?ml`H*5RmGCI1z1mN&u>-azrJ3bLo5&J zYr{(c?uYxxh5rshkF*dv5c)6P=<9isOMQROU-}A~HRKQU2^jCB=_@NyBvPm!la*Ud zjnS{ZM74gocmO7Kf2$INrdvF{?3b|1hJiKoN1V%T%p0hv!gH={o7&n06br&)JFC2T zK5=>$)R=kW!EmgU#$M8tx>bL95*g{l>8b1px{xDI^gtEad~i-UO)POHCC2VlZT6g1 z%xTw=+7xM6p2;t0Lhi>?`Gi%yY~#{h9Q@`Bb@jWVa4d}&twmC_y1s)LO3#OOL;`v5 zYeXVM!EqjKdS?>U?5S)HoW!H=oY_spUR@aoy9o3tbz~Wsn3{QTiW_CuT}8ww;~V3g z=-eInMhX_3HS?#AhgOsh^sCNA5(+HXM0I#QxYWKWZw~fi{_-GZU*9VB8iJ0OFJc@hSr|e7fcQN;0n%UlD|1GD$>=O_Yb?%xbUo%Nl z-eB&(YLGqatrGWY!f`cFJFiQ5jBevE-`H^85{laQV>K_>$7#-rW}0MkdJBb8w%ByY z5!*}P5by3irUmnF;#VP?b$+x--c#Ydi)AL;5rGJ3srAP?FA5752lHONm+q}sMTazo{ktr5D4MS@?mSuOZ$^?Q{ocOO8C!U#f?fH-i6%zjJyRMOLv=GI5q`0 zQwnhaj*z}?JbZec+pzw5c@IQ2%|V}Ze=n#a)gt>!zSksz*R1w@&2?kGnF#(J1#Q;r zK2fC!6Jn$LRU^Im8EL_;1P?C==fc=;kj3t^y(tw3nr}B>dXQiLgz)#mlWud)?%gd0 z1X{-Ku{8t}N@Cfzoy*c=q~zm28?r_Ei3oZ#f*<>F;;=egkeT6Q&Rd2ba`0_?Y9UcQ zD{N7sxTK2wl~JLqzx3Y%SLKq$_CZBfd4YwmX&3{sMl4~DSOsBB8w(HRnS=VF5Xmo` zw2YZ0J+GWs+|p?uqdkjT-1{h=x17#LGUp1qpXz#1(X|RFX;r8I+3s+lw(7e ztU;~gdn011yhI1xKr`m0TE@gdbINBIKxj`#Dj^#ca7_SaM>{iz|MV!nR7 z@IN-E^m@#^paD1P zp1+sc3`h|l{O-Whr|N7Ef|)I$IUH}_>RZ((x-r?%U>s<~NH92;$WP+^#Nz>(#12{l z3Euyb(hcy~|I^zn&!%qF=Q?c(@P2h`dvWpv17u*|i4BF%m-NLFvWvz_6%C2|J$@T= z+MET|O+dcLoZkC`0q5j00_mUoNqUqg?yd=1<#kO@gIqOrG~UU?$7HqGvVh51qeNQ( z91?{<*lBi_Yoy%&YVWK}3>B&PkAr2u;q=1O-82BOp0v z0m(V%oI!HVIXBR>Z?X42`{_RS+&_Pj<$aopF-M+NMjTPQl`)6*G%dFswXs6$%1q#Jp)&vaRjb~9#BQE(N#8LtTc zf&&4C+@0e&pO%LlaC}_^U4uFK>hoN^e^&9fP6r9 zA?4KSV6Q4%jcCxPF}S z?GAqU*LUHmc>?SoOy=a4q&pYLvC!eNX#+0VQ`7SuoKps9wHn?K2E4{w&zjz)VWrU+ zhIi)J2RpXt`e@pp$DQN3*h$)eX=}r|Z@)kbNQH{hH1k z8lRr=Tke%*bslyR^b&DTX}3M9lEhi-t9CkeBDnDHmXoIr(v!!~O}e`kYhPXP^wczb z51j1Pew+8Md+FTEMUdh#9(oteD1gJ)a?Ty?#P+(=uuR2t*5XNN;Eo!1z{@pNM`C4S z{SNQg3Zekc9CrcX$_ggVE9Vuc`9mVLkCF+CY1GcfQ=&>7;Xw*#PSXIrXwUD^JIvoC zQns$`dlG#oUX!I(s4qP}=?P{Rb#M~ex=>2SD3y6US>`2ZNKHMXF)BOq%JHQz-t zYTr?;!saJs!f=ooAs@gz5Qm2bIfz&1bBoYr~0+1|aa=+kBB@;yb5t&z|0_`c8V zfZ&8^su{nYzx|+{cjOykB7^vtj8vX60xBi-k!ZFD+Q`2uzce85L%?wJv zC2meCTP>H<7=Y$#;~jFe^+tv*oHJY&-Qv70(PPIo;9Zy|&rnxME>w;O?}_peXE~nk z@f0Ayz}AhL2Z2igOFON@*ljo>bQ?d07oO^wnSyI-5^Am`Y^KVzC`vl;1u9%@KJ>H2 zt6uhvThWvjS62C;RzZnLUwjZgd4KD92o8Ogm=sw(0ur(`q%)VW9L%9HYQHT+BW*`J zW64yh;}MBZahm9FjS=d;9yvR#K)v__^eO2`-5qcj>*d2g*pyAW>-+#gYnJ3MufZ#f z!9Pa^0~w}Y`)>V5X{Pl_MT)C-daUXrXY}WKA8ePnC1tTD``q31flX@1ADh&biieDv zoRj(a_79%4TYR!FPuv?b(WDWd9((1-s*xJ?2ubiV_EbJ3KM6wvup%7*8^4FOEeZ#F z!GI=uFxNn3!P*Edi~fEmAjV5rtD8c=>rH&}YjorVlW#zH6kWri41Z{=u9yuEy zqriUh-lPs?Od|Rq!@c0)dqeQ5sm7zefnE!)T3K@bI=_tc4K1rkq0i0w%t3p_VWLRy ziyO!x*!)TF=(3W<$zyp3*Q-Y%WpC#3q~B6SKw=Ny-7UDdi11Cc8&nGpZJAYDR+SZA zLE`Eq!ZI0GYH^H^#Uo;k4w22Z=35Dm>|R)_76guSJbWiox%E$v_8RPx&2cr#iprzq zrB-oYWt^|h_a1Bdf<))Ty-?BcWtPUE{cfU**Hi*7nLhF?G%>f(iwSILx{x_mzeEXy z_Oe!ffKz;x%$78z(#(^&lgKx%P(irowGb{0K+i7t@LJV6WPCeV>H_KzYSo?-5}ggo z(AcD7JQ0v2lM>@T{P4)x7!zA`vyZ4eP3Zo@>&&Tvj?B^Y3co3tN-J9Dh1qW$nDJHy zE__066XWJ{^&;2tfWzRMHUOIY19XYy0U+A~D36z(U;8QW>ma|`{QGXzjuP+~AGOlfi(XaU6Bp5u1v*iZjqYnfXQ%79c zuAXtXm%m5tK=zBK7WoKolgw>niVFX@>_oLS`%#tNn;j1Vx&vo?+EU%uUt=&aVxDhk zL2WY87s382A-+IZ!MTH8D(pjSPzjq_sQxh1J6&YW+Rv^Kwe8FHx&I4mW4 zYsyBaTa`cAEs46E#mVm&_-*f`ju?5GCMC`84J6d`U$4KiE3Xh_2Xihuac2>hIM`%w z^C-~A4ogKHe2w6gEeoLzH3PAd?}>J{GXh!F+LxP%=bPZ|!i$)BoD)lRF<}BtGPR=u zdrgTHtm#ez9~IUMnQ!nSR+M%SiWgrOfJCK^C9dp*sNH*D<-`eGOFif#Xi9}6imYKEmFVuvy#R>8n0}%7pT19J$^@* z@r1UXYQQl!cK$Wt88^=&;aoqXfSa}&bn2=*?3+x$t#G`QCNz5&`qS0B=Q;6KouWh-KR7g>w3ol3dFxP%lI-MK>xl6pnpq5M$BIh&rf{Wzjoih zcEKJw$?KuG=dATO%>^aO-^NmKD?K@aJNedJmLcx8@1~X(KAvp$R(1X;yEs={Q$^6r zI1SM|Pb&9Rio%=rD2DSD)mEl!j^Vmp(hS)JezezZnH1SigA^rwWgRkU zVN`|7eq`66;G!z}G$WLsb^bLLAwq~uF_8Jz_&C}3hkau);~G6*ErPnK(X|rzJH-RZ%!NuYt6@9sEu!mDv~VRx3O2pG2LqpB0LyCUIBXB>g*}q!y)#n<^@y z9N<9FJjzza>+eq(z|@lixIAn%sXX}7hvvp-nBG`XF{Ps;Co>=)U629A4CJa4*G(qe>Y&pf@*SQaMkC}5s#fqhaO z&8T-48Qx_n-R@kL_OSSLFhNkrHWk1<S z2$t{Q(w@qNYQH6^6hBS}gJPF`%Ga8#0uQ=H`P!8ITRt+Cm5$O?myFqeJ|^wU7nQj6 zBFLBSK-JqbPKweYWfNc=9m0an=G5{>2bqP!q1RdD_bwhP%Vkg4Fb$AGNyhQ!3>l{8 zS(Sv9H_X?YE(ZtoG`J70LwMC(*qrV}Qk&c@7y=*Pf=b-cA@?2j&s-?`-kKUXdl2de zR8SmS9Z}lf8M%&?wmg2g3Kb_o@35Z2k)2r%Vc4{0%`V72Zd8vNcNK|tumW?DnN~+( z1f-VB7$IAtYLc@o5tEY}Qrf99*Wwn=_PJql+gwC(h@&(MjY_GeTYr>TBl}!}$=ZE{ zZPSOL>$8SJP$|gh@*uN_xu=;zx-p8^Dt}d=A~zAaCNOy3<95)3O&8$;%npc-V0j=h z*F7g=o^rpvCtEv;!4|D&%?deEA3q41jszf?0SUj0a zGwWt~gxp|=2f%NaH)KvgSKs0?3F}`s`a3i;zRBuIvg_0^e z(lZM8pfDspe57E&0Gu@INpS30l%{7!8u$He5tBMY_Ntm{7=bZnIy*G|o@l4g_Qv-8 ztK8Mrx8WnAZ~JAIT?RhvG;E(hHgI&P;i4kn)z8Wg-m>a$spWv3)q!L_@y}j?Mn}l{ z`%k{mRFPK@^A@Zxn-BOg{r=2rT6KQ}K|rgy+PW_NCr%5eA-Z8sZ5aK~cVr%Z=qqT) znqbh^yj$eZ6{Ck}1}-@#4I~?}OyS~&$*=1IKl#!S@u!w_AGNKlyEa!Ue1P5Nd$%5> zP9P2*Zhv6qIOP;-$?1ZJ#V9xWZpX0PIn9}iOQzK+TsOfAnOEn%YNP1UiYZjaO3*xQ z&bj+auXc!w$SwPo4Bl2=>$#HL%y#T=I}OWQHF0 z+}n)yk%b`%tC)QU_sdD3Z-b+k;>grw6Wi=Ezt5F#_b|HowR14N?06U-SVV4)Z$U1V z9mtxS2Exg35f1pO3)7QnNECW)Dc?B(rmQWFeDjn{nxEJc<1s{|diIQt&DMMzJJSq`gg~zB8ros7m2@+%pm_LT~Wmwu|Lg zE0)(|D^JPq^BVioK<_Q{uBXsXSWx0Q`&wD5`-)VO;qGl!ynJN3G`nyZird#2HHvz5~7Fc1}<+rO9~^Z22$j zxHtA)b`|qS_R^$u#*|WCR?1uK=$+@t${Wd;`4}zZuOC)KGQqoy6UAuGIm$0g45WK_ zJR5pXX%e&;l5cDjI3e|vZ>QuE4#nCPwzMpFXQHFAFof!ko)hp;A7IM&D;L=Kj?}rt zSu#1^A`-l1`|NVU@X!wNaz8+1`?MjffV(sgE-k{rFVY;yV|@6k81{Nv>Way2QNLIx zA}W@^VDmoCv;Ot@6>>|0h9&urj<4y4hueREv+YC)-9gH=p| z8Ds$~jssksiZ46)XLb!>{=5gJu7VLTABvLcx>BkhZPsUuMZRt(~f|QYj3A=lBUC)B6uc5a@kAvw?uk^NtmWbJ z?w+<-|BpK-0;Qv1_s@7;IRTh91w&8ZL+k$+E*~!?s9jyD+ zu#{g7pUyuJ^8dJNxu5@L1kX)IyA+4Sj>gCQ77xm2bcr2fu>*>yH=}D= zmT2s98ejrJUuWs1Dn^-BtE!_;Gc58x(1J6c-Rj)}-CY2IZhLE~ez;C^GfbJB-UM4< z&86hcOmzrNafY{DP0m0AyEVc|6nLI8@$JYqP69y{wk=oZKxi==uwpK4{N;W-tojff zuz;9gn>D*n=WkL$^c0!B=PU|`y%=W>=W)@!PTDgz>a}(Y)0Y!v9%4$`IV`0gIlI7_ zMKX_7hgUe=+F!(V*W4!oKh4&!@CsZ?oN{bLPGm zBw1vXm8!c250-~4?QugHJSA*jGCnqVPH@}yNK#P$FzFx+mN~6ACN;)sQ7->YGgS;f z|CTiEXjsW|--R}4PfqHQy3I6{S@#C)*_AP208Sl6G2ie5)D+zD14JbG>#ZgNq#51( z#%d)*v+Z;td?_fk#3NTHEFFsKX0$vyX7Lp8$O^N8v8yLP#hI^0ZAOwI1kZdi7-m~I z_zUDD3?pu5VwYn_b3+!%zag%FfDo8gBCu+aU+&ru65?G=QkGzrQ%)~N$Gj^mp{89W zUf1Uav#@pV#zuk-xq^3G3gFv=R~^bwo5EITS_y0HLq?pYH>>nufp@s%_{m_v88aUfqA;jDO-3wLs9{ zZT`0;ZH45gYj2*}=uGvv7Uz#u`%H}RKFSoQ^s_~$4DZY%4av(f=NSf%tc)^Su`+vh zChR{*Yf*rhmonRfnS&CaJtE>^a11)K<{cnux8?{0)%;On z5AC)wPrzx-uI_HF^cjPt14+K&ryX4B56T_%Xek|w>LSH(z^E%0icnhm0U`yz7a527 zBU++Gu9)o|Hq;BBIFK8p8DD=tI}yCZr&fyn91mo1)v+M5gs!8P<}b-1N6|#Ep`WhD zucB~^M56#BQ6YCld2#tcy?^1PI1Zd9T3vy;ZLlLr@Izx&K)-F1iu4iQa~DIO>1 z1QRIQhw7C)j62z&P|cdtgW)&y&LMgZ!PnR#7c!sVWO;e$?6Ky~(tK2FsUc-5AxwAZ5zurYb zB(hQfi$FAJU))``D27!5j$x%ICg zq2*QeMSXo>88~c$h1$sB&ABP_p`R||LD|FTPe7iDkn^c)L!0?+nCCRb@ma&=?TOE7 zpY6Q~PP3bVVj4le?aWpF*`EZc?#Tg!3`)hdt31%l#P>UMrAaLm@?$YAOVNcJ{zL!P z=sLDFFEax&EW&6=$74*h+sMFDd%NSRYVGW|Z~OYVB8Hy4dPc$C>ws=yO=3w^iJ#m^m>MBR;=U(YW1Knt% zo7$fhP~X*)57CdZJk1NAz&c=kmTeTp&i&b>T~i9Ae;8Osm}HE}T_k3XY%}S_ z98RS`iS#nqm*Q!+)N)aqMyeM(*qw24S2~qH#5Ys-iwviU8}IxZlbKc{o2Zq`#J5Ak zoa4darB_Np&_~L*7V;AM`Rxt69t_YGC_cki79UO>TNyJLVH#14KK*#ZPIq_W{Ce^3pyjy+ft4Ic?+3DM_T#hPL_)RNRj_#IjT5_2$u|1G`K!6xdBc>2|VHbpXJG^lr zu;e-&vfjOX9Qp$kn06%vL@Y*jtOJ=&1kc_XwV?zR^?{eLw6zZjg1X9f9Axph-^cq9 zf814oqVGwa^|LwB9>lXZ(eUH7pB*x>7Mt1L#(h7ZI>=@TP0QVYEuI12|tRT)G3 zMG#Lycd3D}PIZcS2wW9ps#klzJL~26={4THJKUF^A#o(12u+2J^AcJUt!?H>y7;+c z6C>aDaL}Hd`{Da(PjcqG7S}+(GGqr48W~6%fj~%tu@OHDq2$>YOz&O#XZ<;qJB>76 z{5(0y7^8oHZMuxdU(WE5qL$gLZJ2> zaf}R+&%L*;Ym99>wdDKe7JMb`#@Vsnjr zg)X2#zKWa!0VId`9@YB@k2gSFg7qJukJ)FRMb_t+dd?hvfY#R+LU5!!C|(RF$rl}P ze=Cx`7r2t}=(aAXvbVDRNR)3NC(luJNmXB_XKd^2E1+A_|00jkOV;p6F|j4y7u*A5|P= zeWVKHx*MLEP^N+n0zE_#LEr(0pcKPaJ=jyg44s$$3pFICfnCx1IK>qL0t*z%r?@zW zeLGWaxEVY6FAs_>p60hjd)r^Rb<$MC2=)zif6%mJ#0_)Vuu$Fws=I9C0Otb{xVUCX zC68LO+Oy!Q&)M&mF(q|yUMlCK$&S3YbWA*-0`RbT6=Sn=<wFIm zAMu}!Z)l@xI0%^ri~vc183G94DX0@$G9T~<;tRKTAtz{sPxH;;bPf(*fW1db7_iqs z+Da-(f=6KhNX|(>Vr=2J`*rS+E509~E`0z)u@Erio{(N4VRQUy#!v4&O`{$!;Uo-v z6{^K9WQJt+`!`-!E@Xtj;i3Ue`b?przt>^?a(WG!n84`r8(-!Tqd{#Z_DT#%MZF+p*-0}95|DH+(y$^)nX~EV3}9zh4Y}VW%~K-jD6HEMxPp#ORJHshH#fdRnV+OYO(PN^fhvGo;)*nx&C~l-Lb-x0ntQAl;;?p zCI_+avFdwxP(aXw6vDInxMmeop5Vc}cYeWgZ3TaQ9$}IrEnV|tMT6iKWC7n2m(`f^ z5_T)T>BiO}m@view2;!i>L}Q#ghzMNzO7a=k&#Hgv=<*Fq(!@^?UJEn!PHi08^~0VqZ#2lnExjcGb{;vN(CaOYRaI z3#V+o`GI$|A#ZMd(@a-zd~d8!367>oRChWwe7oOF7#-U(SGT(*#*|~j708ZG8w0xY zsCysT^7U;L0SVD{_JPGXms)0vlr|>^Fu@luQ5zDmC&ZeXWNS+4tEje>+ikeVd-Zz_ z6W}jGJ3-rpANf7La<5;BC`P%gLGN3To3BZ1vbXs4c(LzQHu0eeJt@dIlo20hR@mY` zC#>*up@cRsEsc{H7~Sn)Iz}Jp-jJA}@dx~w-0Mv|75RCyB&o%9qYh-6W4miCj{?!2 z6I;D<@i#Z%-t9-~L{7kgJ%6MSF}+P1Px=Ka8KEL}CsB7%jPW)}D6%945-K;QVf?4X ziOcDOx#i)t@tEAEyeUx^gF@PbwpzOuyU1xu_jsg)Nzg4@(1qWfb)vUr8A;#Aa9ONq z10G35(s{t9lfG1uO@>HF8xGp@^~G9E3`VXI^v~--Ow20IQ=Cdsom3E4;CD}#tVKvS z@}fsioKJgjO>GS=;gLvN~l%(a$PgQ`oYDbXA1 zf=t)xb2e3{7u(W>DYa+m%s96R*s8y4Poap18wX7Kq2IRtAi*|4pBOpZlj)L3Sw1E> z<3cz*eWC4nb|%qpH*NaLDOatyA>ju|zExYNx#TeY`QD)eQE*Cy)EHL${g+4GMlr-s zP?#X2>qv6KRvK7i$%4iyG5J(PwpKM$_peEH9+@(vidEp^Eo9@A?jbu6__`eQV>EEB zRh3mm4BT&du=+6;G-tFU)~*94uB6UxQkdLT5<57}FDRX~Ec}`;o``WBAtU2NQOiyc zkY>yfoRC4$i;NT>Uqo04+u+&xG@TuPUk<60V7RMUF zaO!y9;9P8e-=Ks(?U$d_OQq6dEnKL=WUyK>k;5uCdcs7vB+w~+fC9XNbC?{0PFPFK zhPxXy%C1_dwjucJ$ZW);?w`(aj=Ec;4e6>ZUhbO=vl}GW zC_XSrFigkd=PP)PD^zZR-{v4S$G!n}2vju(W@w{5onxutzc|#mZt4zN-+=2u?AeB1)MadQakZrQ zgULR)q~#PcIgnri3}yr8wZ-euLmb32R)9@@|H4K~Y>_>w6-czwL;~zyXt|#KkRuJ| zhV5a%!QH7~bqxOVZMuTF|U>!8(GJV+jp@{T(niQ;pBY`ZF3%x)SY=}fq zta*5dyZZtteI$ps5uQ7c16(tp9AFU48`vf~ionoIZGRhu=)luei2p^Bo}wP*4^WGQ z`!isZRzm?t))HAv6Q+a=%!VRvF_VWQi~(Ox*xy55p!zG7Rk350;t$Nr)S&97sC6-!v{2k3kg(j59fy%R&O#5gd93|B^V>Z!1l$Z+z9w5xaM zsk1MXx<3}>u?&TH*$)VwofJkwev&VWpV#paz|zeQhjj9-!V7`CC60t&Z7o`)XBAFM zLazJjqvamCyYQ}87G*Mq5h1gT!jTg3)4Cn9T*yiK0In{^zl%C{gGzShoU{hcDI_j@ z6I>6NtenSHv2p~s-?)qN4W4BLE$ItV=C?h@@-w z1HK|qUhiL5sQ`RnD^lCM8Im?>!@^*cR8oZ_i-`tmj0!@UjznSkdD zX&}X8y%Xlkj9*MfRP|LAN(#jgJ?ca%AKw7Txq!b5AM`)*PhFew2Pi`Zae;8?QrFnR z>YW5G?PH|M0OTlLMp?}Vw`ij8=AvEY>&QAK@m05F*SX9V5q%d|K z5nVku0$ex7+c7D(Z?K~b{zIYqkKq3PZ~cESOZ|A|k@FlR!MbcNq21j2`^CUWbLvFCuvwP7KS0%|jf3TAl>oQjoO%9p<+T2r zwIle>^oeG8-O(v&UB|-}ZL(XQ1^=GL4-o$=v;IRhf8mHUYI%osaDqhd^?YPrSV2h} zk+N+1S38dK$F<>h=#ZeL^~{5XvrvY4&R$^ha}K(x;Zt~nE1C7fmwzg z6Ui!NAJ>{MUPv4DahAg`m(;thfJ`Z@~|$TJEV!Zr#c$$ zy9yWi@|ARclpwKPT%4(c7-U-cRqr1uR4P_cuZQnILl`kQEA|Wq6=OslSLb=a>RfN5Au71%j4R`EV%2Abs@rm+q5p`*T};lMYyF63q7a-I-M58K|Cb)=;mi z`k(P3-_>bPY@0gg4A8m#B{MSvB#Xo9K%=_4a=FJz(a+d}EU&pGu<+Qkz2Q z2&Z=8-R4*0VRPLCua0yr!|8a)9Ep4MB_3UzFBg*4DE2;VJFzHSuq{bW9lfKzqc?yG%DV&^)}sKi25-(7y7E7E>tc%OXou z!lrN}nuy9LBDcM2@$8($?A1Uvcf7LLn926|3)f_PhjK^-D;$JtXx0Dx0mDUTv@Cks=WzVTTW@T8G`1 zBL-6b#8LejAGHV1#_hN`5RB9%dI?ix40B&=hV}*AV;6~)7|v99dEqQ5;UeOeO{O*A zR~n})^D2;+>Fbi)Rb|Y2m2Ghw-U|hp=!e?S-n*-;eZCdsP+Rlbul8 zzeMG*%(E4eWXpLxh3c6Won8fkwq)HJ@&`bblucpc0ffAIWr zsr=pP$CE-Ly_pTI(x_O^6hjC8T-lW+F)&N3u^J_Nr>7#+MTtK!i;7y7GtMnuoM3EI zHce;KXIWdyYJZQm0cu{rG9&$EL7J+c*!IXuCrrl3yPwTXZlso$J1x6xQWR%$*TfHf zk7(ui(L8&aU^WkRSTdpED1iYs5tmuVizOdR3fX>`%%hFo3;<7Jr|^Z2m>HQ8WA)HYlKBh$#h8bW=(p!j>w zy+-X)a`EPeuGf1j41nDnNtcHE=&D0^&$%x(F0Po5R1~I3s2dEwH2hE%ewEElyEaB(Q)b zV}uiS8vK%3Qdx74WG!Tu#pVv~4$5fw`TO@Q&S+&;ooBWb_co%5)Xv7wc^n77lcb~P z-4(YUY!JdvVzh&dJeSvUpSqVlC#!c^HXx8%N2t8mr>;Hnrl!(IMn;Hsp+cD|+fkONc(wbU}J#T+Tg%w)H(Gn+gphn?L}sduuMs891Y#H1K5N5ILIEt8&yT ze_rEWFEbV5yJ2Z(3EC^^cj+M)C`ja9+(E}W?Jpxd+&t-V#KAq+ z!4}KfcU13fis#cO;@eRr8wIb13PzMh>yRh1y5v(kS;w}=Paz7;-Pk*{Jy>>-W;mnaN;dlJGm+K!2b##w8J!BKi}4KpPSobM{7cb1;ht?= z4X1`)snrnTIrE9~sr#D~g|@}`EiKu3ecQMw_ z#X&k=S%!rk=be7C%TJZ3It*LCn4n`!*Dye6C&6je zAjj>?B723f3EDLZaCe4SmCILZB}KJYC%Fq7W6_*r^SzrtK#Na+_~gX<2r)PiEb~5h z1mP@yfpb`3YL=Ycre2;i({m+)1#kESIP)@unMx^+njxK#U>*eCw%plqXd@)pj?zx1 zNM2DAXev^2Fy8}fIOYe#WGn$RiTNzpFr-=A0&tNYdnPUG^hl&7XL@0YSSnXSOcxuX z4&+M^M8J$e`CaVJ1--Kt}tBkE(fw+StO{&=P^P?etfreOpE@9OpV zh-YLkwyYq-N!ql^9>pXKyb9O5NZ^N+_n!LLz;F(;04PL7GgmPi001NOut0|)8D7V5 zHYVVI=1Fz|AwrnSxvQFqtbXWN`K`wq`HMxHi>I&&w#vlP8qw`vUMKQU)%$8_1}F6~ z5Uii8ddMB+dYuiKrUg!&NexLVtQEN3_;z6Xz@S>q|W#I|nAsx!1gnxGn_Z zTXX`0JD}!Ja&DA|Q(4xCffmS9AeFFp2eL>r@@&%q_M!o<3y{`Q#OaPhs2(!}mb+re z#Y)ecv775e@sEM42+Cwa?$uIAsRJp$$*^eIf$j>^ZM@Ly#45whSJd%}Kx3R8_|qfA zQ+R)=bF|E!RmXLa9)cwn!7w}u_c`>heJOJ0x)K;-(=i;g>fQIpd_aDi4%^QPVj z5W(;Hd;eK4DV%mq5tBeHKaq~hGjUFdsvD9&{l_mf!m{LcD(DfQ2DmCKte}H}Ngeqr zHFR6Y_d!;mszC>)-7mCkS-P3!q?=i`g%vkm!wS?l0wHH_SBk`crHRPmCn!L>s@I$HrdtCTY@jY?XDg(uMx% z4dnr1^87~3LIj=%qsY<4AGFDoUit)rI6N4E)RBf>f0=mFeLp$-Rgl}z&(AcuD`q9t zJs1=@?E|LM2~KlqrW08+ko6fLmraatW;*uGp#J1al{qFLdq5`DV_6X>=c@!D5gmCt z@BL1qH7VlFSKpI=<@h&;a!GKunLpkd(yRysBnTFW?0>jn&ZwgaD;o(m`JYAP@uBXQ zO-vxL4VVGNr5cul8OS^%f~)s4vdX*4%~+u_xuriDb6Ya7bbm=E%1+q57D8UL6t#U#Q>UqtGSvatQqw3PmY#P-(--kfMFr-2Uw zQk8=!U0$krIHW@X0~~h2wh~+?$pv%oZ^%gW52n`~ z+jkV-e9)hbAsZT2X@@6c6022MCIRLr1qZ$!d1nxZ7vPY66WoS(QLHdbftW-LIPgMpnJ{g;Kn z`vhFzM_svaOzFdhJUPCg|L@QkoDgN16SqOBWhx4dNM0Ttq@Ry_VyCn znf#oOHcvof%_*{&mC!17WB?8tv%vv1Mugd+sU;xlphRQsS^#X+37tg;&}1E%i} zjPnJbHICb-$*0=P1`@^@VB;q_H?sjC;)iqhQ5HPDE+FB z0U_OKSP%YfdZpYoO#%6(hx^0E+hY!{Ue+F(dfRtdJw<*0JFG$6+n}qq1Pn1`@?5j8rYWrCo-d2A?f$IwIYK|>i>&`9770;XM3v!Z z^&|l#mlLIs=BR^B*fD^=AV19|vNQk9BdhP&@VLUVpQFS|WPxkBdM^n(W{Fv%`Boo6 h{^++9TMPnqO4A3hoX@KwALl|IMq*rXStR|K{9h#W3-15` diff --git a/Firmware_1.26b/Documentation/Select Board.jpg b/Firmware_1.26b/Documentation/Select Board.jpg deleted file mode 100644 index 8de7256a88ca7759f9e30a62152460a64a31fc3f..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 90579 zcmeFZ1yo$iwl3T_K|&xva1uPYLvWH{AwVFw26qn*X(T{!3lKcGySoOL;7Q}|?$F)* zEBll&Ze{cDo3=_d-%e5`=(&0D1%bfo_-X zjY+tgn}9%aav(+!2!swoMi2xc0wv_9`VOE#a}Y96MgShXNKX0jAD{r;>)0j(p#eoK z;JXNLfylQ1_T)$T=jSH^KN0wez)u8zBJdM|{|6C3iA4Ivg1`qXg-?;lzm|)lqkbtP z@pFPe(b2z^f3qggLx14))0+5yP-=d%{1btn2>e9gCjvha_#FbA>>PXo>|6pIJP$e8 z1-PCFaB+hE**y^GDM%mW0K9p-gh^=j_N|=&8=H+ItGpgz8xC}D?1xV zNYvF%-_X+d?Lz}&Q*#?(`h&(+`iJI5!t`o9a_n+;&y3B?rQIEjU%SgI8@gK>J~5&f z6~V?3ausm3wzD>VtN+l|+RDaJz*U&)m)Zq@@{ikWR3btSMkWGE&n5p(0elmt`g>no zTwGXPxL9o+OxZY|JbA*#&dJ8f$pTQYIJ()q)pupFaisox1<#Eg4IRww-kRImJp56i zzJaaNTVX0ECvzhK6MYjN10y3I76W}QBNh%0BYhTqBQ6dWBQ7o@J{}H!P7@9Ts=qgH zWcX|Ac1{jfzqD;+$YyM1Y;A1w))7F1gN=&qZ=L?{Y7>Cy*GB&-`~Z&tjleSpWBs?r z&w)$i$8fT+bFpynDF0)KS@}75gxLN>C&cyxjNf(izqjXq2`v#JBSQhhAAPrV_*?U@ zjqU&UM%&6<1PHbLjX9wFw*pWrAaZx^+!12?eS`lIfnV+b5(m8Zt9$})KKvi}{A}dk z0{JIgKjHef5cs!jGG?w=pdUmH~(=KugQyHdb z#Kx6mEmfPF>mntrtr7;qCQgwTvC_s{EYoYUGVvSU>V#|XOWw_zsc2PO=q-l%7vF-u z8VuZmP!4WEJ$dkssawz{hw&}Q_u>|`GP#j1nYX z7vd5p8x()>h54F>+NSF8?J?Jl+Sq43%<{xK3Qy4&gG1ydtew1A zXB5Y?Pl|0a@jB_o8b5~m`65t;iJG&q)q^8F_^)6G(82$Tf#QLk9XZZ^+2*IqOqON= zx*FPyrTk=R4k#)*9&)zWVB3(0%Q&z2y;Qfb!2Ozoxmwbe1O9HWd=D8nuK}pvclw0` z@Vdz@=#M;#mQ}Z2V`+dFn{PpvXEr+XGvBsO^mO{EYJ9nvqxmFWaVo4ygzdFt=eBzo zG9=C~^F%)eQ9DFM+PP6ald6i32S!16Sa@On7BtxTFYx@{G*QeR)EL?pO{ieA9 zLuGC~)V&2k-6MWK;5v9^##mgwT)pkke6#cD#z7 zy>hI?)=>6lS)#eD&!waCzRy>E(ioqp(2ZaoYloia;dHHTAuqoe1VA9NK}J3FR`!J) zNcBia%@k9*dJeashv%}^?=IjbrhgQ>%o|LtThQk(@o>zATTp~*TxIFjJIXOVrKwWt z$|~{bW2BgNe$0!6GMs({p|^PlO|m)W4YAd+yOlk(qvB*~#4pP?bmjcqQATl5{;Ll37t z*owH?+tZ=N|Hs_v83E>w!*nX)#2Mxj7F!-!V*N<{k6Q;LaLJ+pwm_G2wJ2@Md$9EM zTaZ#M;TY$a8J`U`HwlWdzl(50Goz(#Smb(&C)H%~~QGt^~=;FY^TDf|vv|jW82;!_XCK{*vzCKZ-1R z6J>sfRgEQYqg5tHS5AAmFQ^Z8pp7#z`3GUvA;*Um{Sfu1=ZgOf>px9HH7NFiZl=)3 zg$EU|B=~*71?t`#(U^1l%7Jd)y@iM#;sYI?`1fa)q?jJkXN{)PRO+#*?IHIvLCLby z!8>MunriVB#8b${^yfo48c)+sQTNiWtq(Lbr#p+KG@HvCOf93S@dDRJcwQww~wExJTL1>WQ`1q{RUABN$$s$^?v7>X6a+nu2oE3X=Em824lzMC}lE9t0s2|+o5~jGLPlmD0AG)sH(9d zX?5C8UOs^h(Dds+s#&gE5c)pQckv`q=mWsWq{xKh&Y8mfc)^!!ws2t`p8uNLaEMKAw{OX7z5uiKSx1jef8i4&Vlm^F~ z`C)%#x71s@l+K#-hAbgVc}(i5M!4l}kjUP+BrHNCzCQN05I(Y+7Y_cbNv#=za=l*P0p7z%-T z^=j+u*PT&PI6>9M0X$*vhOF!gKsVzm3LjK|cmujGcF69K#T`rce|bIV+PhE|fIhDm zH{;e7Yuj1c+65_xsKH2P{2~tIbeJ-FL&MW!12Cc@rLvW?2e_f}tD&Ycs+o*l2Un>) zmL+Ci%_Fz)bTp*P=Za^fg5ce~{5K-&gP%qYo+ve5J`CP_N2wK2HsFRI!iEIC^L#jjl@S5dyW3Nj4?Q-?{$!wCt#0S-=0ZP2|fQR4@C2FIT1jf2OnPOXC{ zT3-CvBUA9j2+3Qe~)Rzu>w((YX6XaUx8?;(B(&lgLU-#!(+uUsuKjw#F={gJtsHNZDR*9Ghkv%VO%duES@#&~z#E zRmO%w=6cK?a)4&$5$}lrUQPl!_3BJGQ}!hENrtQUbDlj)g^8{w$1O7!F>Y?%&iiP@ zZChJv*2SMIs)HfJM0N9<0G_zobl(f>zO2s++2LCEPMBa$n|UWs%t7M z>iLdjStex9KeAh^vP!-dJkJwEpGB2i(h2nCzRJAR&osXnoz;|srI0D5&*7Joe-iOm ze`nBO(N}kv7HD(kQ>e2^qJ16RP}dYU%=?LR#e80JHx!HP$VaX*Cr$5CbX{=9kiJ82 zhA&1|q>gpTS_C&2C9rLYyLYe$wNH)a$ieeOXJyP)$QndZO?b7iuirsNTi%i~~JUpb>r^Vmikb4jrWf z*>Ub6!ge-_{dL~7k=P7>{fLWD3JIy1x`G_u( zzlK=M;3G2)>#kc+1Da+2U{VnBV=T$>x`_tO?Y-qo=t?Q}D~npxgCVY4kSQ#1er~I)BJ?S)Ijt@4#wBhsQ)FtSt(W<6g?V7Ba0mG;nP$oM|*K zAKogyaD6qqau(#oqOerbnyaHe$D4omxw>%8uP{s$1qv4@ASMpoLcbM$PJg;mKb4(Z7x(iBO1=+lNo2Bh~# z^g%36dm{avFUzJWmd>mN6y`V8$}$RcJN5?;?x`TC1kr@Y&W%cd01!X~1FjuoJ6#q+ zT;>*Ae@0!itZWa`*@Xt|DVQoxz@5E*1ym4ct?Z#79id z{w;<~&S@-hBMW`@&=)Ck_^(jag2Af_Q{bHrFpO}rzc@B$6ds17aJ9}(?gR$Bn{foz`#Xd& z=Y?W>_GmMi3+M_hIxfb}7bEg#vYlziTowywd)Bw0bUE#sB*)S%U5ulEeDl2TQkItX zg#)(t$_=?4iYg+zpFNT!Chm#9ypDax77dM3Hgvu2UkJGcQIEZ8s;Q4wuBi()eeWM@ zXxGiD%#KFRnML7o&%)verl&Vq6;wSF#=B2SS-qngrL+A2ujsK=KnLBdky*C-@sgS& zHBJ&49{On-hR&>>t7^yc`Sr-Fl$ERfBGda4tanKL3i1qn`Y^qDm|wh8BR@Y; zqn(6GWw?4iciJ;l7)SmNDB8D?SDyeyOU>WAwWCJcTwPnOm9VcLjLJx;7KuXp0RutE zK^kcyN}E2yNntmF!qsANr$Ih2NpS5(z9=a}l&7^HEs1i_zGvv$k$MZ)5km8X&2H`y z-gASA(^1nb8pS9lBsnD5XR-(Sb!D@~WmfITCocqMhTt`i3n>b%U93GwWlZe}I+&`g zM)}_m%M;6xwsObimbsgQBg1V%iMJ^Wb}@iVCA02kaOr3zWt}_>1<5vSFn+%0VE2R|tBCyBBdjc= zdk*NOkEVHK1+nS7S|~@)NLfsVWwDjkmLpJiUVJR943ZXgO8G9iSacUvFPaj(g6%xr zQP$g#CE&Chf26hW%%0{|P6STeI;SyvpU)#@*iKN{3R`-Q7Va{X8;BGf+extAig>=Mv>(^f(&OwY4#jeo<3egg?K`!=K z5`lTxp}|R=0{;8yi-6^|Cm7@6XzA!-WAUqKtb_2p-Kz?n}mz2vnT z&GuP%C`Illb31%ltEdx3fA}W&>o_Z2ocWabOCOaNs|ca{BVxiRt{3l}>a8Di2zVy8 zJgOVFo?;OgQ^(4#DL0Md)8iUwBQl!_B?~p0E;Xk-Io|_aqpzXy>@kXT@54h0H|(L>4{1xK zVMdjc+;vq4RhB5lYvV@I1}#>N-XG-)?rfl$QUsKAE_*q`37OrM6T1^~H9Dq_I&e0|t;|Kaarxp7T` z@<(#}@k=S3{i63vLL*&ur?&fN#WAbrMmc?m=Cf+{f_Yhqj;g{P_i9F%;d#MPa4bvyxU#Z%qG<^ne*7{GZpNLbiWj^I~r05m;_Jt zqE=J}X(b(UGAm8T!GEeF6HZ9za|;rkO1tC$Dqg8x99T4KYE8Vlxc<;B$~;9;x^z=a zjYCK4oqR_b%mK;W-lqzPW^2JVGV z58ysO=`VlkKQ~Muwwk!j48^7HCOKb~?75`YUOCF#-l+pyDqJZ7LA!s|tCRKg#rnk$ zeTIAxj=r#X%XbvjgOMs9-iV_iQ%rd2xZv!W-+~xL@&TRZ{~0`TmJ7$S7QNh~{8PQ9 zpQ?&kt#!9P*O*PlV#YjrX!y_>ZK}F;>COarqq!7zx&W1EaGrXDe`uo9X8Q5)=rIoj4d*7ON@Xa0-kB>D3D}P{=+ww zS_!GzsOep*KN6|fDl|0KM4P6`)?IaY<4H%nyskSdyajzx>~pfk?&3Wj!IKm5{Pexe zoSoA-JQpb@I6>uOY=UAoQDX#rDhBT3l6Enn2i2j3jDf$hp1`jG>mVdoQG+C5v_NY4 z@mcJ6HBOa+C3)dvS7&5NXJqWFVWTG-V}K-D%G`p)8b@xn+2E{6_V(D>Rq+p$da!UG zxzR@X7BCRg#I%823KCTtvna z`H3|ub;@jA**Pqc4~yXA(#Ms$hrWWiVmSY)q!sO{bwTd>bK6_G&!^<{QSCo(Y7D1Z z$q_T)WZX;HE6Fq^pHFkdo~$Ztc=9tcx&`Usf(7ylt3tO&qLXtP=!PTyq+6@Nf7F*P zDj5weC5@?+f77Qbe|r2M)MTus z{%?w^;9n`xShHVM_nF!sb)wmy-t{b$_*I`4wEoxXbWM}tx?!IZG7eYvQUSt8m}0k} zv>gQ~5d?e$5&h%4dW@q|lhbzaskGzF?b1K3JAgv`^&o!I-_RBcXI700d8T4Nyd6a;!9 za}AQi1k9@z3&2!~=mqa&+=2wIRRAMQc`7Fz{krw*e!D>`m6EmQ6ik8P_hwYF*;M(~ zH8VPUYvbL$eMy;u1!Be5T~qq_3^#0I98k%$blqnKoA!l!4*6>@1HT!j<(1SynMU79 z`GmoRnq~PQ+0Ai@w#1#?Qv2u02lSuuBYWsFGttlZRrwOwH=8TRH{Dg8asyNsUgHT3 z(I(S--s7M*q-c%5x|o_^GaTPFuK%?7a1rc!P9XJY(3P`Yb$@?Z470;C`&?)h9@|)G z$qO;!q#i7EFkr(Ypts*37yjbda(5z5@MAJ_mwm5fD6*hoqHDNEk=6GA@B-Lx7TojKG*IcmTLbv4j%!VH=@nSlv_FhvDxBT z5cD_1h6BA)td=21x}W1A?dn=@?bzbbH|5=KK{y@WT5&=^l=@MA>&{&3DQ)r9gQ1E2 z=P@rp2`b9koFLvWU(xgqQhQ=f(U96jk4ci?&4BmzRC9}*HDiL6n8hTD;??$O#bQ|b zEofWT2ecX86Q62r7l4vwnh7lHVUCY_BqcnLeJshcli~;%`5=c=vFk zT8B?;f(Q5Wr|7A5G;hi9_cC@OZUnqD$!>e<7Ogq3ie{_?Y&Utq=NRrrL=c<3?P%sMF`0j)T(db(Qy-|*^hwKh z+>ninDQ#{~fyWnn46#+TA63GAjX-aD4X*b=PgZnCvh}rJV{5}i3$|;3M`3AAUPX&E zn`c>?g}+LNtUtoLHwgXSxp^R5*@A77^^m1G`Wr3X%8HtXhH$1ZrLkTy=JewP9}&lX z@5%zYbE2!G&`8V1jCd$co9H53bk%J?w%AfLwfHk6%to>@!8V&uai$9!`fA`_(6F*M zvHDshsBO(YmMYv2yd0*=b~k$@xa8iByK-%GldAJ#+tHPlXHz;QU&4tEcCu$9m(Mo7 z;@HBp-ie-__Ayfg<@Ry=QqZG`Xvn^Y7IDd9v~(0}*VuboR%%SaNF+kY(fj^Xx01A_ zj1Me4jT$^bw)>AJ_urSjG{8YMb-1G}LG5}~zj9MY2ISiWx8dN#`;hrGU&}MV0gFVz zR}}k8mmLJPJj0w%AT_phZboxQO*3?ahVLbEZNV5NZ6t1j+Q7F=Gya*{Jf7K6saIQu zeQyOrZur$+lpP88*4H1&O;&&7nBgvabR+9mJ8&htr#65nj5^PxCf|5OkQ-nV5nxqZ zGJEN}XKY?V!mGm9MaI~*=$lrz-b&sA@ekh9{IC@&m%$97cNz^k5kfD)cbJ znRUaQ6>%g_DSLt*|NT(;BD?qAZj}6F@P`p?(`jlMm$`6>q|!??ctG`rGJcS?=*ltW z^=9jEORQdlNbHG9F7(~ATaeC!tLd>qK%3Vei6XxPr|++kj;vj$>KujNF*%aRjk(_! zqU)T`e+8-2qMPL2i4YijykZl0VT$aI8+>{|(H(Ueg>055GT6k>b0jRWw1BdmN>>}V z+|`cHQPXi!kB~&%)+Um9QsQrnJhK@=O}MQqoZa7Bn&sj5V0@7W5(i{NpX? zQ$(Sm=*GCvD~)+3#F}y6C&-en#W$k3JIJrw#Gw-P3(1pvptx!2r9lA^phl>ZV29I0#_&!S7 zaeVVo1GWYJkxeDO4r|xPR2vEgXyQyKK-fU>cl}FPZ*VRz9VpP05|mrx?k)WUx{}2@ zscA_rMe%!CA8>P@A?$OKWg&&QYCGkpQuh)oxsnJ=x{oPO=Cpoj^T>0?uMz0Z&2VeMjgT8HE-qEF z7BKQr)PYbXWd?mG71RjSzIUhni*Re{qeAlj!S$mh-mxN!;0^~h!)SSBto`0L`iFNV z?`+^rCz!)=r^mYIm)9q5L1y1J<1lSTI5{i}-DnMotx^lxW#2v;5w@VjbEQ_A*gMTX zV74j6GpVba*xmI{>aE4wWtg$?33_jl!`>EvL@IwL=hPYAT6#&|0R(AhuAv?jKE;+% zn|)TTM)fTXjq!c8)z#lyR58>S8yQ0x%lq`l$)XW#(n>qQ1-!}Dti?9b!%X$mDauxN zhtuVWpl#jXyQN;<*SMbZPU<8i9N$cgD>1}f(r*Z6>LsJcyMy%sDO}vh?ww(%uVoC7 zUsvlo+2IukZ#LtxbgkMkJFwD}4r+9YGeDpzsFWlp@_TO>eOD~AxCzL9>>NG#-WtE% z`fRN9p!jr1U>$y~zzCV5OEiVZPbfy)JrTM)$!t^6UGb>D3=1cZXH^Z1!*)-V9AHdULu%fXON>vVWu zf|0?o6{poz?c+IOlPdv78B5#vZ5%nECkiKEdx*I}6Uk83I3(*s+3b)-hZq72zCTgu z{ch!znXyu}RP%X^`id!L9;0zpVKGzD4p~^Zf~eW>yCoLlZvyv|P3fBNhJUb? z;chKfSCqgJANGt-!Js-k)}J1UH2;{935krx?pUPDcBc=s#)?)X zWs0f4)XML8A=K%FD8pZS|Hd_?K9EjJ(`Y^T4(RV2M({z;RoY?ZKMENGbsjI$`t5$B z%KTN^0{c;o6=0V@2oH`A{2XHT7-*Br5(9o})kNC9|!n(A_ z2!7o58(qY&7)*mwzW{~vE79+Ox&>9_!lB>RwZz;QSd|aW zMferZ--Z!bWX_cV2QA`6bm?Whd?Ld@bSS>j;%L7gWCH%$@1LS{^|t=Ict6%T&C#{e z?-2OEmT#$F5s-+t`yu9Qk0zVMkssqr8cRXiPu=R>v(2<_ zKQaf=!lCoZtKP_B8}y~b%gxq5?y)}B#Jz$Cel?1AI1ejX$ZrQ^5H1OfV<~Vl;A?8* z!uwm$F~g6z6ktt!&bAW~23(^k(Vg$$Q~HvNB`(trt_ay_%FAUHRXE}mvHmS+)mk)R zR)wR;Jm7IQNmzRLydu`fMhUfp7)Fl}uQZX+YH+=_T#KJ49KUv~gxf6IQseDr_NP8# zz98%l?r?jk;4^kC7ra5<>#Hp~FS0e-ihU;}t+DV=PPqBslkVBs_;*~1Z4fOaJFOJ! zsH(l{ea3|4dsm#GPsi-yaGTHN>o>0)o~gJqmZ-0!AK+bO(R}w1@bKOlh^%`ty>yKb zAIk{tQJgqUVO=MR((Rp>Y?10me|4816l%xcgTMFfh3%f1nL@$VR4oq5B&>)_>Q2f^ zw6UsskJ`gjeD~9$>Z6hXI5|m|T6rI-2G90PQJ#qr#-Nzaf~%ViM`~WD5J`lB@3Upu zkh)#{=E{}?HkPwTj08ae0%PQUf*5MhyMTmx{IExGa)WIzm0pa6&)XAWi8$ zw@fYnH|Pc+!OVxz{QAlF#LTH^pDakso|0tR7n|4A7;Ia96N(ENl2pT9rxQaFTdU9z z>vmATyId%@yl_`bTLz`)19x3cP_PVHe0d=?k}o>FFOEh2(j4KA!o=BwCW(8J>!f7t zqV=p}8|3wobfR04B4@n&W*aVMNhBuegoRn(w|U#U`0Qwo0*T&~qz8B%T1*;W>JEDe zc900iuD;XxQXP7)KLO3M$O650@mNqb8^5G7Pb7RfT^R&$udye+! zZXzRu?Qz&53(UB4E=KN3C%B~&Z^T!;5Isl>TdRk#oIgY`YD46ZleCvGx;M!?DIS;! zMj+7#5061D8gj}V(d&XC5Mepy&l*KJ8YV+|A2U%Ob}#NfG46gq)Hg)_EPJ>kc%y28 z!qrg~Ysx+7cxtj#==YqgxH|FVXkJ4G zkP4nW(!yg*CeNjqJ*D#gHl0zYcJyTd%IwBX6W7&_H5g&N+L~ynjvU62SL*PEY<29oA_{>|04*oioA}pNWw05tMKb9Y-b#|@6$Nhlt$XG* z7a<%$UD>N~>gV`3GZn#z)^l}Hp+^eWP*&EoX%BK0f*{I}s)VXO+jPFM9^{snUwd+9 zxsOD+0=%Wx*^tR%yU~TQO)evr@5W}kT6pYttn0E5F-Q4>j&z z^+o9A4v3u#uL%x^JmbmYtU(fBB756MK+9XS`@%)-hp*oe%8N6=4Z<`LkNyYl13Vt40kb6iO|NmqjeQoNVD8YNi{ z3q{8{jaL%sTRrtDk1!H-4G`N@Z=I#=4+;9xB%-ehPEclCp@|0V?3?}iD8U0$!HW8o zywOv;Z~S-fY;0m9>Y=aIA>OC$Aa!~@k~na+iubtNHDIvcZ}29K{i-FkS!(0e5W;i6 zKDEeabj#VtgX~hOBDq4TljO}+LH0-uZy5U(sMnac#h?|U7)VOs8ps~Y`6s*2c%JRu z?ypmqiGqV@!!TiA2T>2Qm8+`E{3Bi4aJBH?C3DQcu~l-an*=Px$@Dm?)n{yG_mR@+ zYjcFJUolneSa7(7k%{L-86O8rsy%^d)l&o>p=Jkf(csx)-*( zh82R;o3SX(TX8H@oYH#$-O|0Yagt-!R57ov-iI6+s=h(y82#A)yS+)!qy~+o8ov_J zy`Gur^c>;Y$5e#^-tFPblA~4Ll3orL<-v9X{Qf~VQb}tzq~6CsJn+dzF(*GObu_W= z%)14lihW|zS=@-uQ)vF(-R6zY2`lsznrJ4%?2dqsp7_>*CXa$%?e*x#Rg#e#{AEs` za8)9Ffv9N3ApViFmBezB=;xtE8nQBv=sg}&hv(XWwq}IQFe~is?_fR8_qQ%`xr>v2 zk#+Nu;#JIW#DGmi(;K*`Ptiuu%GlInmI+So$I(&;b}OgX*NJcQsrsL*`s zPE;WM`j$ej^Xq;3sw4AnC`AW>@jZa-0nWxUTXXF}cuSh5qXNbtmH8{_xqD@OP{x#@ zO#UX^ZVuYKa1p=ttGe^;s+l|+qXtrH*g^{FnzOeUQ?%o-tFYiZWt8uX+lnugwWwza z+2BQ`q|#{l6qyv=IpO>CKG`P6zT_n|g3grBRH(yUSqb1nG(Im^R*m8GSU5D!L;T{R z*XI$;rYA2ShOU^jag7UOBQ~-I;nwUq2?ngSZwpJUiwYRbJwI`?Xp0Wsc3^MYAUeCr zDahh#JM1lsfA|6e70KotOW>TS2S1MYM4Vev+Lf@pON*MZ(^+afcS~%)+d^QMM7u-q z6RU`Rtdk1kg1ki+iLYEP&p`~geL*}z8&(_ED%Qj_;nz7yymi{BXQ&8)_HxZ(+2i|E zAB?PZ%m=@Du_9VZnH zNAP;umkv+lpNhX7CTKdvQ$tM?FGbKz4m-%K$ zp<|vXBC+4E=68RnjZgr;(1wySg|-jjwgSRx|B6%1^$velga+ z+)up3VDYj*$8RlN?Zh*HYvHDq?bH(y2aB)Sh8l6J*K>@2;D+e*kBhDg&Pt*!K9*WHn3Y* ztWoL_o1YWYjz^G_oC7frXCzDUm*$9gGLe_57IC4yU;4n!Cm<;#TP4j)x?KxD#R;bm z`!-t2I+6;EBmGZRC)&#;&mTHA(!|W9R!@(LwU&Ne&OXHFa0M$=HcZgEzMUgkk#`RG z79S~H?z{cDy!ZH0o7eH`%i{Y! zh%g^3$Bwwqw0vc)*28Si(VL$MT1mX4X=(YI%(Oqj2qdXfv-(i4$$lDA3+&CFxh}KW zw|C#@>^*Z`4YIKo8LnM`dI86!?Z%dQckPCy z=v8q*+G;yiq_)uJGRwvqa~u8$zbN|%c`-fUBj!Q|gh8 zjj9)Sb8>(ArztKQ<36MSl#~|x)HZaQOGgh1-?znFy5SJwQ~$A&@4HCxDt8IS@22A% z5Z!Y@GJ>t=WC;Am8*IN(f+gHh@I7oF!u#RCMyOj5^2s&RSBA_PH?(uLi{IX$nCTU*Xl=a& zw+q38PcazI=fz>Muv<_k9Ej$qeO8pJImX#7J%CdlDv0LogIA{XE^v-ZpJ$}i9HV`l z^928+kMX~w%VhFvH)M6wOmueKx$cRbCfS8j_9GmiM22{Kr4PG8TgT; zASm#VmY6Ao-Q6X;zg_Xst<>XPPL3b2El(2IS*2UEa7}imrRUJ_u^`Q>zu?9*Gp(~& zZmHY(h_%S*RW9(80H`BJa(gmG;9gDJOB}c_Bkd7z8YjFCD#~|NN#()8{Fp>g@_xFK zBNS%;yd6*afgx_=Iuo&eSe65rq*8*Np>@EXCS(JVRt&Mwni@obhSn@g=B?WcO2R^$ zS7S;}UIBukCc&Ug6B<5=keAB&Gy)Zi8?%dP*&6lj)sgpln4rWXTSKxEOy+MMlV{33 zLg}{e!Lyl*7@^D-ar4t+C43$CI^uC5G>= z>T8@{o$#+7>Yz(H-^p9LT{v6XOF3=eq(-+B5u1LkrAbR&ib+)QnB=|p{tKY{9o+~RgZ4v~ zGnbU&)&7eC^Q&5dS-uks!(Sy;#i@2bv~(d%kTD?D$}?IXpl?FnkIUIxGY;`|%r=$H z$zoplau7bFMiddR@)o1cbM=buP9xFkQWxUk{+Y?rHIXusJugodp_Ftz8;|tJ(#`Zde#u6xR>)G>qNd{ zMpq8mXU$;D;5lHlB*zZVqmg0B&l8SnVt#nn7DDhPcxy~Dv^QtY#ef}wRBV1Wl*0Xx zq0XZgJgs;9L|EaAK!Iy2rruphx8hmeUWwe?&9bp28$Zfx(ksJhnI`IUFOfWHi|1TpI-MJu=iWOrIfpQF(6)cteRxlOPn&GRCzaiC7{$=g>>19)rmRXm*R9(#^638f8VMW!vQBUkIr>q?WXk%Q%WmEJNCwP$S0^qK1 zYHOOJiHfHlYY@D&c-kvJ*E5Kn^6jRMU|N+MjyJk7xuC>8LeLdj%3j-)NVH+RX%t3A z6G%k-#sNf*LT-a&NmdiHLWxJ0+-f_{T(ZA^Hj^Uojpa(^RT#%rL^OK=6$UzT+3Mn< zaoJJiSE#7HeSS{57xj*d>eiZ;f_=HjH$x-`YHJ8OB$v1wA+S2dHpQO6)qOf=V!R?X-x3yV>$@1#%yE6G;W@nZkTI^k92@JZCByFntn z73Y#VHgyh&@IyxjFN;gq^vfpSyEir9+eu%jp5K=2%!J|9JDAG+b=gDebN~1m2#{(uYyx z|E4JsfvQ%;o;1&CCDX|1j5}f}jC{HN!*_=8ZC4vw3FlY3EU6kG3efSmk53PEG4ALN z%o46QZDco6xP6@)Qq`!#_^mkkwS~>7T(JUiq8U9p=Dkp7;|gk;60%UwkQ8jnp7=P? zyQey8T~jgIx(m#rJYh}K7~8wSI)ipgr0eu1PpC2EEeop;*JDjR$mgm{`c^Ch)J}*N zhnLnClRXDN-#C8}l>5p(M=z@*Fg(}N9ZvozRV~5rp)cYAy%{nhsEue5Lsmk+k%USVD`r;=eW&fyJ3-)q-rvszzhIO+|(qpjyTlF4>;GpkiA z4%cIHejI1>?R!XKg=1@$*M*+x)fm9#mlD#~w=z2(9(M)jgSQ-Rnop@V!%IfsEu!a1 zQ^m%X3){Q5pdBFRY~GCNpxbSYuc-Cue`iO+k3A3%xLdE#d*D0ZO}c~vSNTq@skj@p zIVXJQZuDaHC=x>Yw<+(AkU_59vuE9;W-o@n$fE~8Mc+Fn3E5MlJegOx*`0blJ0^(f z2rT~wP{G!5|H1gjw#Ih(G`Z{F0~m8R(e*k%Zz=v*-2+upO}|#ty6JrUt`Mo7c4acj z2{={&6ame8o3v1=P2d17uqQDp6WEmH#FtZ-Eehmzf>+KG{%9as>2ABBQ;vjn9bP)X~* zO+gj%%`FSnWs3W-BDY^@%;?R^+FIp_^hVbvQHyQzk$>wlihF~KCRNdTHV*Bv*4%Yx zulFf|OqztwQr#iBx8j~pgGya;M~Q3Ki!rwJ!>R0^k~Qam`uINE;@mpq+1m(a4|!4t zq$t1k-sO5q#BDy!)(@EzJg907^@nrsV>nB`4jQG=6A^8E^FmQOY>Ca^P7F+AcD6Hz z=r-qTO9{vi*>e%o$@%kwLQbOP*M~>jMv$9lptm5jHy&OK!S$PQ)9kuhQjX@_j_r&A z;p)kpz_B1|U&a?l&0Jk-i7xL?J#6=Yl%Ygm=b^UwD7pc7PY^hlUbZc}Vg>w+m)=E+ z8&RN6us(gryP0L#LMERA^XVAP^>1$W;7k*}L{8^Nz1Yd`c5Oz6;-;HzcRav)A0U;r zXD|y76@qok~FN@U6P@mvB)XlVyyj~jY)l_?L!`!;mR zS;E}GpH_==)2;wjFteRFADiA5W2u>vnt~rzPSaSY9-Bnm#w;n1uw3-T$=05xyj{ql z35!rg3b|Vv_zAJEi+&>p*!H??6ZfTgN#@S;v$q6R31g@QhyM{$%be?j&%mZejZD zt-Ih(;!DdrUP^t>FHonbZ0@5#=Me2*S%;5Zo zLmNT+r!bnDH1`VbTJPs2nhR?hWOVz1Wg?R^QdDwyvY16t4FPJeBil|NUf{oNJ*x{; zWeZ9&PN{TD)p$V0%QXU=WP=w#ii$m8I%zOZ@E%`I?fq{Xshi#3;;bXqAEDb{$aBr) z>Y5+*Rct@E3^bj0?y~Rg_Tofq*3PKmVEC@U9Bm+z;aTzm4do+@H}u_;LPyRbW?cma z7te4}k;kX65xqZ(q+m+fmpvBSBi0o#{r}i|>!`T8HE*zRCkX+9ySuxF-~ocW1b25x z3JC;v*I>cjB}j00E8K%yaH!15oxXkF_ey^=-7~$uS<`>iVo~eVsZ;yNex9FgAtUuB zVuR-@5@h>rQ5^-ck|5>w7Ec;NQ#Di=@)V5aYdk8baqNk^p5TWvTkRL_#7$j?r@uf4 zr9V~R_(ljW;HVA^N6C8qFC3-krw=vIu;TR!spz$Cj|8FM0rfNx>K8f?j31IUDA%4H zeaQi?E z=l$H)VMZ2^d=+`lUgt`7D#Y(tNR@D+Q)Rj`7uDwGkdo)caHk%}8hG|9n2u6>d|xH8 zzNedvab{^{feFM!!sx#K#cTcBZ~aeR@YfxO>Ck4`-|ca!Mmcz%_sKaPfF!v!YO;1? z7s`vl1FrzNKqdVz&`(wM0>I&{?#6ltdti9ABMJ?(uIq69K;QA(@{9t0anCw4GXdVV zoCP1wE&T#XWaZ6?ZZq>fA^{CN4$YriY!X06Om5Y&E_#n#n%sY37)K%cY!qsnCyA{J zDtgxe+14`uoewE<~5BFUZHHiJwn*B14&g_UFv$P(|^W z=zTn?m-xVuBKk06A*NTP}zm6wI}<*f{*;`nGc;^MumiyItw!Fa&I`&f?e zy+vFFpbU{MXfy9cMME>=+8xp|c%BBTJ~!vWEKI($UEgq8}=`NO_KBC(l8)8_>%6CAYDx7^`c$PQpa0e7{ae(dzBr7Ss)A)D| z9t3}nX71Rlg~~&*VW@FPlh!U5e}SlhQ55>09shR@MPlTph2_z4CVOJG(9P4*T;<=+ z#PB)1_4S+;9Tt7lo+pxMtGA7laD=Lp$ ziTMnYtPJ&d2N*LGbhBhaS>@QMgb!)YI7co_)-p~OIJ3)bjd_k@E!g1$p2vvy%Y}?O z;xvb*8^z$Lh!OW2e2Dh08>lGIm!LmD9^mSNrQqmH?914F<<(Rj~W29!|?8ykiU(d{8*5UVwk@6$}%dBARgu1F!~S%dM+t-_K{mcJkreNnz;VfNLqZWWzWV((crZr-7sNjS+*pz8f_tkRzCTKS#@%fB7t$c{>Hn5E^EokLqyN zJhEsbH%W(Ba^w~qMd~qC?>_AXFN^i-#V~+3D|ydJ(pd^N0lXAVikNby|GMf!2OT|1 zcm?u6q7nEPNS$%<@Chup1(X|^(PHtcRl(2bdO*!%GE$tk(i-uQ~`?u=rP$-roZpuurOz|Xw_<)=uZ#+u>e$0}k|DJ8Or_fMjQi$mH{2edrTEg@AQ``-1Drx`^3*ER|9o+@xJ>N3`=e%ER5 zeZ{dF{Xq?`Q6^r-lwQwUN>$zJ@nBHNd{tfm6uO-94p=E0UZ&a;w#o^pt-;RS4op_{ z4u|(gEXjs*YrD~sxox{^y^w8sPi{j#LPqT?+1@tUT{MpfJQGlaJ^B=SR=YI+VA%>` z&no#WSwjs8MU)aC77{Pg7J8+dVk;P{h&fuT zibmuaf#xo=MU$B%{yf#W7=>uv0t`VQ}I{k<%Tt?zA>`(2!nuHPhw zG@^zmB^@HgkS3xoMU>^UlVO6&H-)9f6-k7r99T@kmFFl)7w00Js8=74$(ZDZX3POWY2U*GFGdfsqM>pml*&cULd%X zuY76k{*k6*I=)99XEyOF^IK9xRgVHh$T3x%%E5@2(@bV@&{zr-yrmCJ-+ej)t2X8~ zt>EX1ah9d1a8?8oj+FL@k2QXa#uD~-Vz61s(6)||#E-h|YkAmD^kM{p^U{PtfH5Uw4iI0(RO9fVwCDpOuvV^gV5z zoBLMLdw{uuIOxFdwAO&`2*=Y!*ru1Gvao)ecN_S3`H$xE`_76o z0t80_B9#*pkoEnRssRWgr1o}xxX~u|M%D?C6CrC1B=k!BVI#(VEOa$nPx8lH) z9AT6d`kEa`{ad?7DNpO00>tr@qz~l)u93D_R@j{H&M5?d928%HcMMd)KM-r?PofK~ zJ>#L03cAoX0Q#T6FslUG5QkfvS!lpt;(fUP^@CaV3((L{0>KOO<&DtK!qR_}1MK{k z1B66(UxL%=0Bp6BA=l91Vt)7z@;aimNzY?UB+A$fw)1Dmsoc!|jI4FO!AR zxf6>gB6CPH+Q55SWygG(Y-a|pzDuz~`CYH^SuJ)PH#Mr6@t#OwmVyYOroZ8^Wnwzs z5-zsMk}#Nn8)kFo<2X@`Z)@jwKdrq9lX89*4s>GEWrRmG-qBw|JF!!aZFW9ZE zHo}A`V%ng8RDF$hG>Pf;78M}#c`nMp4Ljn@RQ>twvB;O`J!P(oWCt41L7^4(nd~(V zlkCo$B20Hb&O_xCQ>>TRIm%Ho^zo;G+52yiD_M+fbVIs{S9POX92KA8@28~$f{mCS zAR-7LS=4P>J#bawC{hxM1CI7`PP4&swZIt|Fb4nDPB0dtJSrvM5jAye0LAD?jwH5b zk(aSY33G)NeF+A8y*zaXE$qZHZJHwI4QE!y&wb6-`SgQVex9wGwY&{+4zp$31X}R= zZ{Ik^{OD>@@7uZ{!D)X#V?nPY>%sMjzjE7K0jEdX=BDQGAi5;gzI{cA^T&6(ON5rw zB^ubfK=OAd<_sR|n3AT8x3!vWbu$F>>Y7qEG>!4Ds)P2_O$!4{#**l-Ksn250AC_k zl36~}VZsR5TaUcoPIudpraCdaNe?)Q4Ty*X;R_FvJ#&#~s_sG?<}7o{P4aN@`{G7* zjkA|UIb+7_Vl|((<<)R=&E9KtE=8~_%7M$7L1!$Fi?2tv6k*=VEF@WKsnYA>@sx)? z%B3Q^lhVj?t&)OAN$Medo^_?1&C@ePRLrCAv!r#LwJV>Z0&iT&C<9xJWCi~dN$7*M z_qMMrk)c)1#4%TC=4%uZ-KAC^k7z+>r+CVuUFmVd4Iy=XTFqHjdsji+rmQg;qh{S7 zsD0y9FffE;r45oYPA=(n8yo{Rz~7tR%?P07T|hBpYH z#FV1SZ*HDL`ly=I_}*2CO|iYx%7BSqjssP)D_CD&91t!k7_A+I=dQ^aX}u%l{{?dO z{gUI^g$KE_=cnZ^ciBQ=si+{7oF#8+jA9nt`)pF=WiKbg891ni?taZBmFsQ@$P4Hv zZSF7SuLOq}LuzN;{EKw-<%@;RmaT8xNln=Lie3n9eqz&K`kaL55&*#1pWmEIPHLT4 z%qr&Z4(@eSzv#n==&V=>p1_wi9&C86bv)+D#ZY?xvndmw^>DOu;^@RpL1YYK6W)4g zN#@@m&s57$X4j7{+bIJerqvu}?~qPR4)GQ!Fx2)bx6o@*V2Z9Nu1yImRvC-R3$m!PjQZ$OJFQ@!j`NE9q@1P#J?tC9EvI`} z^wGmnoW3Ox;iAohV#mKZXE8UVZT0F1B^lMPlo!nQpgvnQ^~7AeeLnOH)LBZhd9i;r zdoCPVE9>EwzxpkKL(0QT`OZKk@o*+M?(wUsMmpz%ddff}T6G z$4FjQ*sEX@h9zIkKSnj_FQs=|(uN;Xh;nteIiO_NFU{j`aZ#_dC9CMrUaqOLBihstjDO&7&tP-UE;!*aRqkdfc+bq`;R}VMgp^XHmZTNVq>WG8n;PwNm z)a=ih*;fi5Ue7u#+v}=wgld`aqhw^k2n%Y^MsVBl;QazspE}sun$Fm5OE#s-vVY}1a_e0Aos~q8x+&c8IQsjbW8y=N!_{||M5zh2-zva01 zKM@oG^17pvGatG%)uyzVfV&^`7q+$RRs9=P)czSXC(v&phmYaWlg{bk2;C zY(TGgT&N~WF!s>EaH2R1L#7H<2Z-Q|wL_@jwu5$8#Z0N({I8e1s{!1*tba2^PC@i26eXbdMFu&pJ zR%x~Ot}1zCuI^4M0y}&uu6ilvyy_#4+=*zb5T);MhQAF}NBP7(kM}Xoo(?$l3Z?B` zwMc{6H|SJTV>57>P}m)-ejKcNHHwc$=wQyUY7W|Q3VOd4=??8z_Yt-;jU3Cmu5k$1 z)K%u5PdaZOP{#TG9F=%S={)V#Hyby^GJvfpxAi{m9l?#cYjlx@_eta(*pS*KS2Mk# z@)MTDVfNw;chiP0I^`dbP=Q6Jm8XpZ72@y$S0#5l`!=flLs_)!6^eMa>}`t9qFPyU zHto#6A8JFV(^eK6Aj1yKG!Q_R+cjbLdx%wpN*>Um)oZ zN)Pm=%$pb*_hY=0%giSlyJFNLtIEbcAGa~T)_k4&dgc(In7XmFQ80*bQgpqmof}1u zi@$)}?rCa8wEg~-6&ddcUyiM6WV-yf4$%wYhOkSYQ6Ixs_g`~Js?L|J?!RW+C!smK zh?3dU1+#JDumbRwRxvu8_X!?s_9HF9uxFu;KFhiNM)26(=Jbx|P8!M=GxZg0Cq^<_ zC)6oHftZh~Qfu>Z;G(1koAQpAvvieI*?npGxZaZ!zKU67jSW?`iL6-GqOsCt&zm33T}K zr}sAi#VF2gUt$dyUg6sTAjnJf=Swj>S7k|8yuZ^BHP{f!1NCGC_@ogUU}OFlR&wMY zRlUWVN_RNi4)+)7zsbv_|5s?qyp}LUUWE4a3KH=mUZ3z$@U1$Oaq`acx%6_E$H#=_nCU~#0PJA1oKFBQnz*HXYI z52Kb~+fl_w{Q^B%gIsGvwBhKe}a;2f*{#9%HK zPrmiOX_)S}tR{E|p+@;wGi*44zQ!y+~GCoqTf8(OQn1yc^iY$Uq$gZn}? z%;Rv?qEVd}U4BRt`OK*3v@Uby(#bohlT`#OLHYSPFZ^1+FksL;ltt}ASJUVy#%=a=*rv4r_dtscn4IZ zV+#oH`QTn?N~%)0l9Byi*^%xmf~WF^Z@6*iBNoZSkS?joZ)WeuT&56@mwh&p+No>5 z&ABnN%<*rxOwVv)d|~P*`b4!J8k2oBf*V)b=-a1&i(0ekY6pm~~e^ zqa|4)w*ji>;_!j;hqKH+zz-Mww=WC*S6`+x-DXp0EpXKkQ>DMOyrLC;`}RkU4#x<# zV^1)-yiru9qccM3Gi)tu1NvDmG_#ZyE2o~zfp^H`DJZCg{8T1cY@Ao!_s6=B0Yl)z z0h|*lyikJKO6JE_uM;LxM-jW`PYuGNo@MN}=II5VQhUma?I!n`f;y-7cSQgCD*P{=iSGL=#o_zA@B^-gj>B!Ue{n-- z^oMWS@#u?L>3m+~l}d7seg5DhXeW+!mmVxjH1OPLk8iNpbqxn%&HG$zuF>7)t(ihH z!@3RqkY%J1_883=1ykg2VWj%`% zTCI6}zW1cC2ZaHsk)Fw?9MZ@0HlS7G2ck7BlzQPe(B*eHH?k!>R1*t0@-0#N0jb}IU(15!=R z)lR~Vg|9$kz$Hw<%ztJZJ(ewo^B*6zl)VuKLu%d%G6vnMh?tb~2R=YP^yiPfO*=OW zkeM+2K9Y}uHS~JGX~qnB;0E4D?ZQA;5^I>bN0yM@%-st5?a%wfZ&$nOEzQNe34r!3(Jnf0Iybkajd$oYr>Q0(2r8 z>bVMDCjz3jURbC3-b7jBvSEsbl082Q`FuIDs-?lv1U0^`Sfktt~;R$|j)WquV zNjm&20N0FF)%Y!4>-Y%=fPm6d_5TC`=6&Qo0BTXz-|KZG`_lV36xl!udNZ<2rB>lr z>Y_AcXM>*!J(m;(n6H1+jjKO{)zY_WCp$;yRd`7$pn#MlOTnAu(QS(UT>CRVUa#RF zL~jn8cdUaiNQ3S>MiVS^!;EmAw|wfWz}rZ-yi;`9kE&<3C}=H~6-wpxN@Yyk%KGMW zey0LE(C(j5#Tr>qWAZ-sa5~Kq_{eyZ-!~6>q@}=7)nIy)+BkAMmOY8Mv3v`>tu*g$ zjtli|QAXHam;ST!{-!Tzuot*|2(?WtJUrqec|hu*uKNlBeQP zrVyhR)jwbEuHLm=Fc4s+BZR2U%Yyhiv7gqX>KM{G^ncQPU#fvzw*?_$;nVP|(qoN- zW3K&rG@l|S<=hMVw~jqHYdajiHMA?sFbf>WKpYMZGn%yHzR4)fncBJ4I2Q!o+dtW` zskNgT)uuoa9+s^!I2B(ogtvt7o!ScFYBV+>QDUG;J&yA&a&1sf45Ey|P?m>g9{1 zz9jz*hoezRRu)&h)eAfG>y1>MnOW0%%YNXj)_Q#h+JVj|5}F`8?Re$cGKx zKRmbURkAnE8k%PIrd)MBO+RbaHcjbJgkO7#`;G6oJXFafJ4e{>1;!dAO7cB4G%8K4 zZS$OzjnjvB2~63fU5zIevlP3tN;VV{CE3{TlR41qh#^csP%ALi<$z!}9Oj>?rZc`0 z?{hpAg}I11zT^L_z1EgNw0ax#u2!PMT-zh#Wk7d^W~BnU=5tw$9xEmldg;g+j+)p2 zWMT1=7K8ADAMT?Lx%&;?u9y!HMj2dc^G}&9d})!G?;p1 zxB9Yt>!a2(m8DzQ6foyQ9n&}cl88xYVDeol@pty9FgDK2a>F+tbbB>4aYYF11a^6! zxs;18&a@e*(toDgmEQ4#bg~Y~2(kF+(0QLwf9+4SGC-gCIZ$pk-Nx5|W#zPl782)K zTdF|hR~IJX?2ZJPIyN>19m8=?1BKWD??<$AD(6l+*7_V5D)*y}G~#pQNv&c^cO2O+ zGAuD#{EC(^LOW4GC=ZY%`l80FBI!|dV_Ya(p?#hk@th^lK5BA5Db8wVTODzeo^}n* zLq$UZpUSD}2C>+>9dRBbsTe1PL*A`W2W2}-W@hCrOF`N$d)sqfBr*p=%=KsZmG5%X z5eheMbssx$y>xE1_96CJ^CAT8?Nj9#)55_y)Dcp1QVSZ6F*Vz-U^5TOddzq%w9&+CpR#w5}%LQ>8u_pn5s@h`Dwy&y~$|KRkF!g?h2{E2} z*L7-(+~$IN5L*7N~OcrrkXxBPWBTOoB0*8beJgkwD4QptIFyg;KRyC4jP~ktsJZZ zWP|Ack$+Pm8U3dN}(Rc>N&k2j4%w}VAmF9#BP1b-(ezu(OSN|EsdK! zVWFKlIkj^=OwT@=3P-Q5d#|2wn&8~k49^Ps$vp>9Qq08mNUTmJD^;^B8y%+gVOk~; zAu(mjEqywQseI^4v~W!nCEC{6rftp5`m*MAc8XkC=id=5p<`_FAZ*_yDJhsoo7&vS zj!Ll~PE(!%cSk#Et3NpI1OofIumg9hUSwtZKl!+Gmmjszw&hN^wn#SE4K*RtFwvGIw8wAby3w_tX0LhAYnH|R_faO-& zyB>y6&MZz@6o; zWiDfXsUC*-mdzsb=7RC-P%273KB~;FRR3+j)Bbku3L6fvCtmPn3hcR85>aff?&Qv# z=;^#+=b}nQyx|vR z^(Bd!L>l>)h;>z3Wxf!kH9Wl$zfM7S-sMDbhV!y6jGcFA>VJdwhb?Hb3c7zz`u9MBi7;LQRFla)j8Bvsd&@d5;-~o%;VLp^vfD@s=iN+_f2}HdjYRA?x&gv z)HHl^?(A;Rhmpxjn$Xvj46QXT6?V6n!gyi7yxGRtio!(tn8(#w`$sX-hP{|++g%0X zi?9Gfhn2lb(!H>g(!ZJQHclTk%NK7yzhi*-Sh))ne9f{`Xno2xo-97T;riR?d}|T1sk$c)!lfc^ zI@378uJ?}Bkp=7lCS9s+JGDW5&vfF(yXJX-Bv5Pr0{W3?GS?S>7M#s5a?=f4CRJLHC(Xn<5gx7h5!pJdM3AO9dvZyS-%kTn##c

    mE?I*?vRGt#fuSX(q|RanZ+rN_z!_L1DvfVup3#a8 z9g{mYO^@TXlu86if)YV|RIYquQr^#>DeKgMfEZR#cCWVg=a90x6&Izc3ZZG?JG+SR zglJ;ktfgqUnYqGqO_+*Xi(c>ElV%?akHUphcIpUCTsy8$V!i{*GPMj}_vJ~{)=fkb zS`MpRg<*>p4$iCzf(tBAWooRZnK+U`h~|-|gkJlfiJiu5K7TvQyt=rJS51B+^=*cQ znb?R^iYjZxByha(Sq7+&R|N%i0iSQTRNK==b^3&Qrc8*Fx}Z(qNOQvK-6$xg`&yJL z=xIGt#+=rEoedLZi>q<|{q)sHR?{dCn@{#$9?_`UO|~1+DwyH-Cm1YQ;55Uiy}VKKFcd1SRh2L;sg&gf zVni8ykzHVpmp3T}n|}zAr=R&^6Vmw(UFM5v6YWkno1U`=sj(y}q7`dFZ&91K(lv47 zXs3@Irz^M#21n~SGWDekta~wK^L7l!QrA2yQshPyIsUAPC)Z7Em%8+47Z4JI&^|S- z(B*!Zl2YqEw9TLKhdWPWwsqPD?yBV+icmFG80?VKpn;Bya-C#q1VnrM={`dM&oqy7!rb7v?z+aNjNpqj%MX;vdPq(RVKC7(@ z0_dS&4SwX2X;aoOR2BzHQ-yzMGyel`75LSkt;}HzVfhqyd8+t}54{m4GaYQ zy8o!a5}R-7vP#7i^KH0nLqjt}U?&bK@|}ai$QbecCjnfe3r6G{S|uwt%Pw+I-}wel{%Yl_`X zk_wUE!>2|eei?70hG-9Y(CfJ_6#*)f_t~4~oIBLA+WG31wyhiTYiR+Km;n@U<`fP!NkOvv}%f zx#e$ZzzozgSbYQBZPf!uc1gw+WgKN9A9FlGZU@Zna3#6TcaQo768wqvd~s8Fl_ah_ zHLpa?&9t@H*5RoFc;Xfbm59nn_|BesGmnQ1T6#^3F1;G2`g-+Z2`Op<$()f@{DOgN zU}~$D_eUANknVfl&!=w0+*#Vp>4Oi#JxUH_nN?Ukve+C+Oeq7~Y?S4u2L@ELCN^uV z>JxS0ADH?b+`LNOK-GJPDcWbA4!mrF4P>3=UqmPGiURtFgHP@W8WNs)veB9f>=ncn zS|v$QtI|RE$(OKX0O_&m#ney-q-qUQ9|B^ozd{N;EIvj zi;+8vuV41UG*2mOwPc4f*~tdEA(!uo+cDzXAVV;qf^uf@l@D7o^eu2Skm45ej*p9SzUbq7{6P?I z->)g@lGjf_q@c*|bP^o&EilMO*vjgZEwL5fah|4eQJsJU3elJ^Xs+sJ4&?SS%Uy(IoG%~AuDBLy znj`gPLo*P_g2j;;Abquy$SNq^G-*nLb*-J<-q76?91{g?vlo z+j$21L2uW_UZ8X9{s9$mfRASJhOYah62UtKglUJW_k-v`?!8v#4kxrv*Wm9Ff8DL} zHlbij)h(lV@b`lW$f$sRNq&vK{-{ua+72jjxg|)bVu~kA>KPX)f~B2t(pR($>aOOO zPc7g&eAFW*^R->x;fss@oz5Si^0I&5Wok!L_6=aiMFox2pM4Frus;(w3V2ncFPvv? zuF7pm5t#)Ntu!fvk(>0P z0gS)+=?|g6a+W~${Rl7J(yfnteOuT8nqB;BdsN<(engLFtngdAM$Z~;QNyOcr%^{> zAbbn(Vm3{}Ac`0(w{NY+M^}^{Tk+!Gt-IvCc?o?G-H_e0G+Cj$gHJpQ`3zn+@ko{j&%>@@JtQ=S^P3F|fUi8AOxD78ELB-^^`9#kETBkV5urdsb>B|q#kTGugdljXlXwjPjpSA<6i@+8>@q#F z`?lnJq?P~VjT0V+oTTCDz+1@lIOg_gSA8)HwV-uGDuflb>AFcCFYPa|p48T{iA|Ux z%NiMxWe*wd>6$jd1`#jysVgG!ANIvAI6-fOEpp1+7)!#`MFnVz*r4{_t4gl zU$Pln_yX63r7mQ5XRnsL_L3Os5|$S55;Y($Z0kckNnYp$}^)kwHocq%=O`s z@1T2xk86TAV4n!DHJ|p?Kq1$ks`i_Uy7!Q^*x_5B@4Pxfb7)>A{a!ZtOWYONSUPu# zA?^`FOG_h0MR{ao2TlV$-u;1<+=SnhZLd6!xsI)r-3Z-l*C^k=W{(m(tf~POI=8dO zh8@xsv^Ej-t_9-maGT1nF}tBX$ali?Uwk4_8oX&9kDrgQ|KT*u)JE!JRV+oQCd-w= zx-&yohuf4OPwq}$uof&f#SbDAb;af5KPbw(f9x1UlK-v6`iIy5$0tM_(#4HSp>Z1F zyRqXu{`;APckotr@V0LqrSc=Nijc4a=9bCD;or*+>IWhgs7eDSp_HbLf4C zgRrnoRfXIQRQ!hYYOo{Gtv+Lv3;;~bfoR3wRqHOV$E!xt=WdpD`&Z4}j30C+?WTB} zdDxfk*y_HEL%;Zbl?c4tj&KRXt*LUg{dvzAVMutuX=djtL!f=7T{nyq_gIv;$#Lq1 z9C2sUKp_Per^tpxqt#|ov{GMRko1}Gz;+(?0EN|E8rgrAsLUV5S-xUI-TB#wCSHM4 zy@kaSSVQ1|F>DG-rc}c85`zOWH}m7%x{-6m@JI{ivGZlfn4<~4Js;IIXukF~@`H~J zR{zE(aP9PEka_I{aZKQUN=?IdY{KJ@7M5A*n>g5uFWR`1k1PFrcus*-W!i3 zG@qPa8ygQFo{XvTo0RkA9x5iDJ0rZoP(RziX$FRd%&lV=^>78AcDzPyZX24mT5Y$t zu*Hp@F(FZF?X8Z4{C5q`^kBoHqp^#yb<$1$GzDhYZ-^(C$L?%~dhk&mmMSV@>K8d~ zOgtTHmh=9>hmqf2^>}}+_M#cZ;;M>*`tUTp`qC1TCdq+K$Hx=~g3nIb3mS9>&&M=C zTQjL~lAQ`x_myk|5$bVb3z%iZlY$r5Y`^<$cXR|cZ;U)$RGhwj4Qq&R*jAjx(Sw5tON~g4EVRJ4!{HewHu>C`c6gD?Kk&dZlG(3rSBGWK!$N%}ZH&{{f(omB>ZDpO(=kzBCM}W>p}V~|h@RBlHdTvzDNm;{rgS5QM-19b)(uXo_V?Nn9QJuK#^Vav3s-6in4%Y1tgoO= zdGpS0F-U3kaWqbh2yqPYW8|it+*%JLsG-s()c&feOarHtqu*BKdrjP@qM^7?TWG^r zUWZepC_l;z4YcZ0Em?hQ`8Z{?BP@#|2;Fy#DBrS??TC+g6}{?&z-lYlCe5SLHt81A zyqdo2Q-7DMB>3@cNen)CFJq6USX=aP=ohHy9<1Ln($jVhk)WC{R7lLPZJgD9XHb(D zE{h|>fH-9sfC67gW3EWO! zZ#+C{LMc0WFdh-n8QqVLiuL0=sP$SD@uukdOAmM()C1RK;18JRsf+Ly4 ztO=H&m(jW@3#WfpKyo11|%@R@frpldoqT$K-r!`RO&sJ4fD^ zyKY;B9XRFfi(ZnOKUw5)} zrHm(Zimb12Ul8!8J$OOCb)UM|oM zMMrk{F}k#rFSRNu5jSz#ZNEi_%ms9iz7e-5cI9n=jQBv5Seekw;YIt# z;1xf3eh-ka$*q9P!2@Bec%ff$_f17+=EG5YrcKyV9@j)qeqLPmiJUEET_FVuIq-&? zy9+RnCgy#oZD@+)?~FxRXZKX*H3|%Yh|lk?zij8S6SB!(f?bpZR$YS*@7aqU+}JNg zY*qT2m;Qj_PjjJ|+R?KZNyDSLcyV^&(elZp4v~%DsF@VX;Z#0>4ZvOkO90p%k#2~u zzkI-6J*Dg#db%^c(fZ0OWfw}oOBm}aj!yR1_=_Ky-2jKo#1u3ATEQ5ja?Gtf4ca%k z>%P6$t*yue}73n-K*h6Nbv{NKTE1ma+JMid`di{2_;X|qf+w+X(K5GimfSdyp7 zscW0W7cp1HU&4RUC{!h6M~Uv9b7me2&nZs)t$%SRk%ni~hf{)(DnN1(|3kIkIuRLM z1ADJdba#u|N2y`G4*=(I`wQf`#&p`@a@fU)XdT#~b$9 zSSrSy`yi?U9hyz3dv)5ds%u=dB!)`LB(6z@0~cXB_x*Np{ahn6C!M=Fc*~U4*3NCsfNFStbvrV%I34y=}cJtIw-Y3Z&@gEeIqrHXO(#ri3_d|O3CH5z&F4=d_4Eutc-V-z?QtW)s?DTDW0w-C* zdNZJ$%wa4>Nh5Rgg6_aN)+=nOQ!-01e(0d@+vsrPdRa4|hd%&WuUs6bbXIcwXBhaF z<+e_qT=Wb6mYA-7Tz9A|*gBkU*`VMY$y4r;U)5S;1P_#wN(0{JsavLuZtwSJ` zHkQ?rN`{8pBF;`_`tek-#bvsHSS)z!dz$cA)|`q?OOJil8J8xOG{xHy?Mx~S%uh)U zEzdfwp#|dhO@GcJa(4`a=+_6=x54u~w zjk(C4NhKEEekA7E#c2^;jI~O}!WyCpg>!1;GtiGFx}5jd09wP`1tAB7x=|{R*GKZg z%eDL|QYM(%3rTk<2C}3v<$_PIhvjPGE>&9t#^#v3;+N$p-wbvRV}Z8)6{hRuF^oqY zxY7@84$Y~Uu4|b>WY!~xWJ+4?s%-%;o^g$*i(JHOta%d2?c_=5dAs)Z+PC|gOVX%} zGd^tXTMxM^==cM5W%5(H{oGtfo5@b!k_Rho#*u-d5~kC;* z1hsb@vb27nQyK3DV^VlaGHoy18=i6#P(#o$YoUMJ7hqB&diBl=CiLKgg5Kxu7Co#k zDvkexy|)aDYirYlA!u+24#6P=ceg-r3+|Et!GgP10)gNz!9BRU76fdZdx zH9dV!Pxsq1-`Df6|4{6zZENkl)_UZ=@2Ayx_0V7-`e*-_n$s(?O2O4-3S>`&uqkb< zoP=O?E>sa*MO8I>E>HE%RXGd9{4lkzp9&F8F9j*pG{-^<$(YGhYmov~Jy&N5LN3EF z*iZ%6odRd@uxuv&Lw#C(llf)J`Be)_469vHBe9+ww=$setKDa0-(THv*p!U@#5ad7 zif$Y243`INY^)v%q4*!aS2XM9=nO$iJ~6Hhkyhn$Wi2-iHE2PwuI># zS+=LXf1mtp8mTuBP8%J=POiOeRV`DU{ksSaB^&>c@e+Yc9P2>sfsEDZ)@PA@>(2$f z<9U2O{UN$v#oLjoEfZ_vGX{MXX6p&!uFjG0kA$1`qz~_4cmln4lM;WDHI7Dx1G~MA z+Ac<7gcV=^UJj+plr>}gF@T}SN%!FEl71s{rJtZC5%AAar~l?RH18%9>GpvG2L|!8 zc%6R>c=?~mrxHQ7@{Ok8RlQC5!tr=A0ZayDmC2cPXD4+Kfmd`G5Y_Ik4F?}hrBcDhIwpj_cZdlAsf3?0KXETe={+buam~x~4K?9=4=M9cL?_-KlLgN5C22f%AGB zV8N1yO@im!-sM&l+p*QsFA%yDeZDlX`c|!1=(*>n^#P6MtrOUt^NNrpzh3?h27b4+ zHedLVnJDc7;3s!yKFvr1=xj(5jv->*%x(YE%|b!&{_nh#Pcl1jPJsiwQxkvj3C-hW z2}KqOxTjssEE=Iuz);s5TPjx|_K4*$7|F=nd6B!w%GcuTDv&IyBe97{DHZA3%(js)NZ+ z{euNL{=c&z3pQVxrTx}#l{}&eR}7+8k)YPay+OqB>;3$1q)mvrNX=6{!hJtn{v3zU z1?;$cQ*z399s!tGCh)&%nJA;cWFmE7?RMa6!6Sv!sa1nQFKUc_68fK((Pml<3CX$8 zSPq@=8&H~H3$q?pEd6zoT79iiUuz~(dJ4YNpwS{i>_b?k|Ht|abz$8Q=B$*g8GszG zm_aZ!#EaV4y{*VF62G%;2h)4DSzFS8`B6gw{hqMAKkJE$#lRf?fa_Ho3rtL)t978B zrLz=9qjH8bd`7k&MksqFhr^cqA}3L47tdRhlj$GQC<7OT|yF zaM0c&^20b)*B}*}LHbp%!IJ`LJYO83jb3Q_6^QRmQH}y^#1g@YW|AxyTb95t&g4QT zF-Ztw_Yi2cI&a11-dK#iBh+p^x_iN2%jK`PdYb@LB$fm519X|9J*n-_ZYNEI^IR|K z;QB^BP`rdhm%F$h75eR^`nvA5n44h7=aE-z&Y~Xe_^kAxBUgaAaBX!pAY$$47LG}y zto^FEF@(+T)DBLS*G_V5(*6Tic2G$0dX`4KmaD-ZaCnEenS^1guU4cOs(&pTFOR-1 zXxOp9vC~B6fgwrc%@eJ*?oP7i;v z`+yqwv(AfZUg5Oi;CXi5c5PjDb|_i<7bBWbOKN+5B*_lT;qKU0CKHqh_!E3}7#NwC zSr`CN6+Ti}i-)=qyDhS67(UVOwB5!mSov$pK1mYE4G#u%m^n{j4*WyOVzC^MHR!8Z zeLI(|*k;i5v9`mr?!j2_bAT0zmWMRC!obUA$-1bqe9DCR5;dv$3&2@Q42_IaoIV$^ zQN>-+U$K2G`~iKR3JopLWxtIt`}k42DM7BMpG1kKmd~AU*|)3e-Re24zWmU;A?Wk! zo4VEjH7}OwgZM7@H@G}VY6UpCflqxXHta*PpwxDXFzdx&Ai0tVEUW+L;(GrgWG8o8 zohMwSr54w-4u7O*_#;BC-p@zs93ppQ>3uowUF2vi&`JIBnnj{0y_wdf5dED_N%l%o zdB-5b+Irm;ecC2l;BKAJ$JW_hRH+ev2y4X%|Eg%zoF=XBhy9^WbIUXGTizuAkn^v^a6_Un zAO&yP3Y2F6?V}qlkYkD{%c8~kn8@1qWAO`=2mdNiNGEK#r+NAVj<^3y;`}S9)C?9j zg;9*^b5hL0Vx0WNZTom0C5)!or`$!k1{^hZctYD0PxfICtdtpeQF?P&mW;wM74Lo} zQrNSYpza<9zM}z4<-j_XfED%%Ag!;h!TK^=-XxI?UyL<3MWM%Z`XgDL>D{HS6hxI< z7Ao(0&8I93HEZ@O_cy2_%*+$retzxoG`4mVNbv_8KvjZ|eju7xXpzAX@hUO*?#%a> zwjw00Y1p~{=GL_(QsSPPz~7iWH_7~?I`LCX6)|0IQ@<$3)^z&hbBdHLxIO&Y zw67xupxaTyq$_Lh!`)?j*tk1|=v?`sbQ@7?q)Um%Dsf1>1y0VfsC4EQbR%dd>YQDB zf`Z4W>)TP>^y0@uq5zZc8wYHy*DXjKN`!q$dPl*G;qIBG$h?pt+LiyL8V=t7JOw_7 zKS=ga(_K_{bCe6iXWPa|htEt*cG(nXGQ+HhFEUXix25lKKcWCYv_W=b*$v`B9+V@W z0kWK5vEL5M9o`>sJ1gSQ7Yv$TNxpu1c@7{>%aVs_V)Nik&tri_~|zH@LWT2*5K6nxtT}N^p zB4ctH;{x=#3Z7Gf+v}hDVO5{WirM4jCdKg1Aw{ojg+> zLvck#{@IpWX8!nQk$tL1F&sUqJ~rPF#T1_2YujZ$Y$nITQ@he(82ar3>vKkXo(UgV z4JE*z@+E(UxQiuS-E;$puULEo>m217fd&dZFVcUA)}60_*)QoY2tVJIvqRBLcEw>h zXKaQEN zXpo*zu@tr(whSM;FRkxc86(o-M(ZV+geg=|Mu^U^efiFM);=|cR`5hhs9dy788C)! z2h&k;H_$Q3(gx8-d7_}add~P>e{#=$$^7KQ)81YNK7R{JneN>HzmODDW*WJO&Lni$ z#e7%fDchCY;=6|dI2b{Obu1ll7-P!jo{w4D16)Obcu^v)cComO@(e7OR47l`V`pp4D6n|=APL~b3)L5OQ!m8XYzCa?kjDcqV0$p zl4&q#CUTaTj-|!<{yW1koCi?_W0S>HI5l)uu4im))tDxV4E3|v%BZ5+8+T2u*zwf^?Ip_YqZ6SXjsWzR0cT&T z>51c1i|MjdJbNVoJq~7#e;Ys2692Ps03JBxnds2QO8kVivi#=iZ5HD-eD6U{CmHJ>Ny^0 zmf`>)s2i5`C-C*{KdSO!cX{)|zVYQ)6zP=(%PZw+>%rRsyk%cP7Gm=!zf)*KCNRTO zh6Cz4{a3tZFgyor(8Qane)PD#AESuQSrX$6IC?Ogvy^MoQ7JxNF?z1 z`~Kp8Jy$lGrq(a{@x-4?qhfG)d}|V z6TV;6Jj@Re^ZgOY=c0&d>e5%}%o4f|IpA1moFfLt|lC{sHZ+{iD?m>JjxhdZywi163 z+FNQT@2D5zH7pTk2F32};@fEF=P4VlLC0Uui4fS89+`cJ+m-9KyZVHlaZkLy7X^1y zk=lxVF9ANJ2LR;aPfU9^;dab&9Zx_}Frvp`?ptOuZkE791XF*8cCDyRHG3QFjz{jX zV1txTONFR{dR|uGin5tAL;K3?`*4kx*@_eUFXf8Fb5nxl5plTKV-e&EFLs70G%q3^ zb>yl&YxaZd&c_o;p2|HuLl*AT;@%$R-tVe&+U9o00)k#|VjG?vnTIolu~{qc01>bz z^MxW`^?;jnlkLSJqkHGmecQ%MYlV58WWrM#E-J5V%^#yb0Nn}3p?6e#$ez2UOIG?p z3FCg&*@Jc%`YlG?g}p4o(8`*J_w3`dxZ~U2J ztBeHiQ|AIpKr@qAtF&;@@F}oP(Ml)G)o18~?q8kQhiuTFuhzT#TDDZ>9OkX4$mQn3 zD;EiyWRo(B!4^gF)hZo-xeNpltfcd;_meyb=j>S9oSD!I<#k7XWa@4GPO>KxcvJ2! z^&7@-80(YM+z%i3L0rN5{13RON%@Z(57?%0O5#8Bs}or3I?hb4$c9SWOQu1$ckWr5 zQD(}Mdpb|#-UinCZnNvnPdJbU;w`PMJM-M+7=(IxM0-*B-?sXn%SmnBm;5r80g7<+ z-qMPmQ5mKkdqVM3cRQICBiYVMY>X^|D6O976!uLfWqk|qehs%@R)Ee*KF;P>!yP^H zl^4oFHNrpg$lsWMfhB^By7fovFF`xomd}yV?FU7}Q%(-2>fm+f{%)PM^NfZ9AEcYk zD;itdQWqO_I@}<07phl`%fvB15c!qjwOB=PJ?wIpAWIAVwk}RNhI(rQubr>B`e?D< zJyieb+Czv!W}akq6GvZV*!R`=gpyxID;|$yD(K`o z<)CM8@ePtc;0nReA3#K-@T5q89@eqpLkb-;1kbN}-WIMuZ8*5uS=%umY^epS*7i(r zFH1BGQ@$`YqZ2^ELU!MF3DoqJ&8?3Pw$E>!tgtWNn!+HgSs8_k>+15|rnNKbios?i z4?>e50NkDPh(F+_*I>Yuc{Iyh31^+$ShZ^0ZSCZSEKl85l$QxTFH%rLqO!a+Oz76HCJ;bG+!ouGXjYksn(GSS~`$ zwENwVVz!;qv2FUJyGgUJ2nD9-z^%<;P$Ck(QQ?6y&P?}OHlb*K(Nb`8TKAlJc-AZH z{qB;K4~;vmyvgjLzKqc|tUf1P?oq2_@-LxHMM>PKb z{2Y*i-o&0;YcJn3TN^tguovHcKDq#BRx)iZ=CTL=iicv{(uR54R6(lO*)id~dZy<{ zY_{jO?;DNwL#;U3IfGwzTgOkxN-G}_??L*_*Iwn?hz>cQVTsapnBK~|hl=aMbYQj1 z)nPZ3G(ffjUR2;{s`hc0#2`ueWU{?OR&t2*?rw|ttZlu~V{uTtvu~0|S%H#5xnxC` z%p%qv&zhF-0KeJoGGy_oUs#83z*DdjZZ6Z|R79%-&}3})@$o{fO{5DPkkCNZrucl> z&jR-N>Pa52pQm)umgS)^{Sj~kl9DZ|Z#s*Kx;up8$+9HA$-%Biy03fD$t2&>j}|6B zgl^vlLlV}(C%}xzoUYX$Y%Sb8}~jwx)m<)v>J#)VB=`gt@AeD zvZm?)i2v5S8t^*31toq;1Civ$`Lg2|iXhIIQI2IrlXO{n?sea~@86D9Oq-xAagL)2 zifGOCPo|UVw8DT3(J*c|6=|xd5SmQDDg z5B74(a!P~~Zw<$RE#tJpX+q?O6Xn-VD05~QnbGH6L8$HK3EL_0f{=BC&fC`=8xz%U zT%yg4en9C~fdE%_?++NVER1(sT0vvaW+nPlUGYTsvvGPtnn%1&LmIu0huwi)V|AWk zRwR$@v%j6#uxhRDh;yh)*%aK|PuMyJadqeIQ~QGv_+GwE6!5FUv7s2z|8V-#y4S9W z|MaZ>bm|&JeqYN?{tmh1DJy}G?Og7kS%;55hAW)&_}hK(fPO1)oIPUbg4WGJTN0T6 zd!B?nL_|7gd?Q1Jk=NiYecYJVdxJXqP)RsAH(tCyOLT*4R3Y1>ghsvu z=FMW@xwSjbetIO%ZBNOK#4TuQ_ChN{f}ChzWNCaw_Jb=Mj#OBhbHV6va{M+Bg%Xb@ z4;Pocl>;rE4UUO?Vjs9S>|@MQKpJb_Oa&=0y5Jc2C92YhPbR@p2Nz0N? z4qfK*=`$>By~aW?yZk6;o}i{S&f|W2smg5^#mjaQu?`<+g;Ws|7iQD+*_7Y65QRzB z)br+ODdQh9`2SgVxS=o1L2d} zHe^6sV+>aM9XYTTQC1_HsAg`Edh>ON**LcHio3D|rrzm0Vc=#(?50_x2{j@K3;nE>`(V+*CP+xYI^XBv21L%}p zx`IVZA4KP` zYueDYp#jy+3J3iQ-oCU=17Sw0Fh$FwFGV-6F*+vpm!ov zYQ}dp;_2CZtN(ZlIZCtbX(C)>(U6RVQ?P$XsMDjR4W<=61VgDwW8-}G=2_RYTDrg@f1(UX!UL=Q9z)_$KBEt%zO$o9whfSm2l@rx(4@EMZ`ZKw-Rh^Y(yVWb*+>`p zbO);2aum5(zDaU^D5RoHh#;q6BDmMV;IdZFZ&5y;N-JNwwYIb!RPKm41Crbig>UWF z0EIu=T;eimdK)*oxGO*KNc+bP_8*Tcv$Giu(KLnzNYVZ8=KI#q#r@7b8E@I3AECZI zdT~iTC_0VV!Hg~vylXZS6_5i8o*Vx%)lls3rr~pY;da{$WRv4P#Xn#9w!yvFdW~W@ z=l?r$zNO>rC};AyG+MskPiF-PX6+GS1$rU!llG)0bjwHU#;eAyu6k`|GWK=_nO|W< zRJ`kAu6BOewS~O)<9hfE$0nIi-z3znNxatKl)63sq-?UERN;X9qpF^s#3z>^@~zz$ zt>~)ACbBFI^DRBx)|kceMd7+%Mx1Nw`m|&d2D)N6QQ+}2^4^dj8;N&WD$FE*sG1Qe zZD`9h2)^WM#8G6H->x~`E_O(~igD>9E>_D?R2DB6|I^eXV3{U9d+NJ6sz|-NY`k&j z6(IqUZuowzz=h3(fKn%57~ojPRgQVUTlxH+a?rLkH`)yQpaxV|&EGx`L!i7AWWSd{ z{O(uUO98OIccqH#w4pD;Tum@VSSl#CRDGIJE|!<&siEO!*A*3EqCw(2D5++47Fw0c z;>;x4tArD*a8G=ph5b>Ri`)-eyao825@}SSv?iyyU&R&t2y!E|2eyj!3sj?&A6tX) z)illjMaP5SpHQx|v9tDb!|qf^Ui?pZ4>I_%;gR%K8Yp>X%m z0Z9v~LoUn`U$DkF)Xl=yV)HYh_5>s}2XBBTg5i#3(JU%|-DR$+*d8gf9;m%+$R%%w zqk)f2MaPpu^1;#TwV!RWmkN`mG~K>H4c^{(%HVy{hNw|DUriPWD#>%=tk=7fNp zd!04wV8#+s#DLnW@?Z@208+3wf*KHISG0A$`@qwvb`XoYhL|Pb_5DPAbxg=*yxrAR zZ6L}bByRq3b@z2|d$(=cm|zO&8v|{3-A<$Kk>wWwQsxw1XR$i$ud`?E>@m~_iGy{= z6N0KnK74hW7FK-|Hj!JJ5N+#Y^rg%>)Luy*-9W*9Ua?VEHAyv*{ftBPPEK@OiBf+u z6PbIt?p!3P@4;B}a@Z?$oAD{zx7%OHn^Iu`HCJ*&Qy322EDqU``#x(dLp|G?Maupb z1_V%PvocYH{OX(+y@vGF1LRWQktRLhXP?zYsc;4kjOw%i3=JIgQoX&zx*j=+$dovv zaOqBZgw{ekpy z_)9bvvQSl?d$QyH;{LS`{eK}@NaeHUBo?RkoREP!kXpeMq87ptY~ve zS{?0MUGjRsySD=*gT-t8$qnINgax^D{Kc>HlVYTOc3FP!YT$o_m|hMzU72zq#OMc= zAg97wUl$NW=h_l^hnp-Nx^pg?=nmj%25gN-22xpAIG3oRq!&>I&X}fSGWX(Hfl*vD z>>uoT$&%_CKfLsavo>c6k3--b<`{&JHhkgv28!K-*9@67G%Ad|v3vKW{7ah$+N4O1FgE!?XisRF}tB>0G? zV?fbE5nXo~7R(r$u_PJj2!BV&}%&?ux&l;zN!C5ZG^@gBVS0(9*fG?B z5}VPA&TDrVKw1aX*(CmDUi<6k|BE^9H`p3e=C-?+RCU3DjkR$Ja8wzzl^6WE1IIOt zc>x>*7Lc@g2ZTqUFF_ZTM$f;%+g6j{qgkN3w$KIXb}>WdGtqXmKmG^Dm!G{O?JHH0Vn$P{by&DvdT%!k9R|2nQstlt<3E7a z>V*l^RwzucU|BSheaFNJh>HB}YI!ic*S4^LI{-&gDT z+iHvQQjNM7reIokq~d?Sp7>uI$eSTeK6Og*-~IXD{rSJf*nhvD|K50?_B1h?-M#RS zCT}S?>bpB$hk%51)e1th-4c%G0w>zj6q{_Zk5O2o*~`?Wr4+Jmajdw)@5q-_9*1Vxf zP4xGQJV!^?7*|OUo)_dUcnOYT0Rn ziLAz-vTG+mVg&IdchWZay~O;^33~zeQ&Y8(klbVnKBVGU29DN>3=$hSZj5B>mirZK zhT|#x-pGPix<1B;EJoyqeDx(b%@JaJpoIUW@6EIsh6 z_YHi9`_NMLSsiYunrhvgT)TaAr9EBJU~scBq9xnQkddVai3F&g2fv(}6glz5rN$Gx zJI-Lq;Q8AWnW9_0+-6H6!G>|H9Kny&41b+vK@n${$v<^tbF+hQ=Qa;Fm(YJ&G&L~2 z38h2YWZ`Q4y5lTJa>&>U5PDLNNX-n>+-B@BHbJ#NzaKRzHhLsS?76R{IT*U={QFem ze@d3}1>*Yue4W#BQEX2Bf3|j>5CNlZ{`!7rmfe`YIZ}^wW586`95++iFZEA=&88@T z*H-3-b!-C3)n30Q;5(*m$gj#3SipB$(&$73>Bmf@CuPvUWFBa~^bfdww@u!YwYqs| zBq{&1HyHNAFsayXBWa4ZWx}vokH;%XgtcwtW~gLvE&IiPN0jg&+60!t{2p^~m$ zoKDDo5+pvF=_l>YS9rcO#!ft%*O2RalyOI-YD?2wGdJl`XF2NiV{C{B?a9+r?}xYI zdO0$r2XArpKENPc^?0z-EKOC>Yg<A#ZZGgmO+e!(XEZvzXGWY<~ms+kE8WlE!lQIME&I{eeG}p zVm5B5OA>S}W`$nmC*%>>qYCiEH)~fV=y>>Sgp2ZbCS6G*r+E~s zerk#AO5Ft2b)yduC|NayFm6!~3ofg`y(qSQwXZ|*x^9O0e755!8!wUW)YPGSZ26X2 zvtEIRQBTX)E?Fkee*8zs~9v9W#K-%>5V*Nw7kR?jEvezZ?&V0KLoCmW=r{~Rgz9;2i;FtOVyoxGAE zsHnn4Q^(*$P;Z)%OhrAI_7ciGyy38FDpq-oSli-@!T2wKg$UE}Ivx1Ug%eAty736UF{MXwch zR56I{LSCD{S-|=nc0zNWYGd;1#*SNMdM~wKHPb6~Y}Qzhlo;}?@AgS`DElg6`8^cb9A%`}9#$X1?8P|L<2a2Q@%1QQUe zq$y929t)W5D2;Bu;&&{9EiNymRs%$f3}TCS#8lrh1rJT}bu`>Im<3qa@L2WbdBYWX z+L~(l(mtVf$!jJ1>&+U;Bf&i_n0-q#W)A%QX!3(+SebBf7Z5znZHl|xUEGQ(HII*V z9^B`9@Dp4~rO2AEeBjVO0i-IdwiwH^(5)I$VKs9)kD=3_2(MIcqiILccXDD*$-W`j zG}68i*vjNR_9e?d6iN(xSE-WfpM!XUG_&MSAxJ}Fp2SJL)I_pe@EFA%gMIY)^mS{$ zqCi9tXdK%vOcmEKgN8qfcrRLMd5p80Q29Qea~$vb-=v$cEEhC55hBCI&Dr` z60n%&Zk|DwR2Xn9kXv?Ci2q7iZjihI}%82=X|i^9(`=%WaK*b&sMlaSdtB5I0GMDQepRV2JI2aA64pkDqIOg$U$P zD%dEAlPuJ;yrl-rr3=R&Q*PUPf+Vv6e~ZAxUQb4q4$J1#Oas}pb0oo<{JQdseq%z9 zrJLiqDQmpLm%Ih}TsR-ZhZM#ptDYAHWvQ}~nVe-_X9ndeW9|Y>!&S%u$LQ-eZcIUA zuZ)C7POnx?xWYGHCtsa`q<&@J+E1XK8xUp6$ZaJSAt{h(0pIS0(ANlQ4ZYvR6d%`% z?OGV{C?4!ns4~QQc(67-M>F)4+0rr6(sm6t2r+dFCEO%lE_PjE{JD)x^k+4dr?rF~)f^CFDl~M*XFMVcs>_ux4B{eYCTg%Q)3bGI6+vlM=kBKRMGNGu`QB9RN@sRW(* zler%-Tn}7yeuFNBtg>!#0{?)MVfA}5!O^#N*UrMf7WN^TWYsIHFpHB*rGezh!!a2v zaleWpj_i-XLV;YnHi1k$|5P3YC{|{h8IrKG9@3=JU;CuNxje7%^p`u&Q70!t*-*x5 znwRsbmkM)^rrL$?i>+;aDzbh)>RzP*^#gTO@0Ed`{U1|M%Up)w4{Q+G79&VMEEP?S2@sV+@ zwEE-$FiDz(n5Z6A?`U{#=_V_*v{ug~ZapzH^Wd>CzIzfWq561vNuauw>7sphbB1G8 zT4JDBHt3F&5wzHrv_$nq+j>=SMN9KVNSGlY&+XeAY&%tyS9r6Fxpo1ahw_hH9Vx4C z8BABydGdlzhJ_(J^^G&PvQH2Y3xGW0`KVUKpKSqW@l}v&R@nzoI`E)i^(ve$ce4)Q zOCu~MyzXe!B_h0F+g^DZ=de?kV~@ky$dc#inJzmaB~epg36j~-2#^r{wj@q{pjzhOAcBr>eMA-59W2O(O3E|UW~-@&~FQeGcq%M)j;wT zE?&3~>{Z-2BC9P^E;2e?C2wtyqP0Z}v8T};BL1EIM)(1<>D4qs*o_V2!LvK)e1q&w zW%9aL##(eidrPwewk_YCd$qxVTQ?b&XOd)q1K9ICO&@bJ%oS zOG@lj3Gq|yVqr!O&koPjYc4~+V(h-`mCM$*)5u9@J!cc(Be3+Ypgs`c@IY6)|iJ0HUv8I1lsgugtdCDS>DSYRW1Jhd?UwxkqD60P9Z%O~Z zspq==JE(hC?c%xD?X{(O#PruY>AZ z>-0oUgpVc4Q|B)dUx{5g0yXdSuT7$p z9V+klRBD1>;l~Wq$0dFFAsiEYODQIfVCY}JF-kKmpLy9WbHUwZ>CU>QmcYKqre$Co zvnjs9NeeF@U->42NbQJdyZnw7gwN!|yZZ+mKTK()>0&;F?eqiy(`9>|U}PHp8p7<6 z({15gyvkVxT4v$@iE~t2?CnfnHANxOf@xC}LkPN`&?;jFF-}*mChB@H)u~2ouMzls zhDhvfShp0btu1c?f6&d#?&l0rq{QKt+-){h>A`h4`CjAdbCy?-Lu5Pc(Je)IKkE`% zVb+S?6tftiI^&PDPQSmBQJL~>=&=Ka%&762$IX2T&?#q-3by>F#*7NuDE{EhzL%zG zfvALpQluy3m?a!9`!&?DDek`;8jQ_rUn)De&sWQ{e#aW-#vmM~2BZ&AzSTP-&-R`$ zZ&Z|)9bPWzt{5m067Pj=65BIGd2Vm$`8K5_nB#bqtOsDB_FC#$6Iv?Iug}<>=FPe` zwavITsWRg7IMr}{p^qL@SzmXWm}-%zcZbz4bf;=(Zpx=qSrb>Ie#6Ie`CSBuZ3;)w zB;ruX7W^o?l+EWX(QwJECt)l%pMbH${~G*Te(1K>R7crq{a2$wvv{LxGj&5%6jUkP zsm8*6sp$J}G2a*tM|gqpp#>kRm6$^@!TB5cywu%O;+?2{W3QwJM@X#-cPL4oG+Xx@ zq}rLsY0w7G9C85?R7yEu6Dd}+D}Sk{j847cwKhiuS{z5`jaa>l(LJd6-g{WJeWrps zYV1*sXo(a(WR6DSOU%VvrvMc*ECI2_Xq|J@iF$!@UTmEGGNoUFBd-(yc;gmT6K+x$ z<%%|wr)gmrpF2`Ruvlf;>QS=VcoC0uZiF=HI|p*yzOV81>bzPAbeSmX%F213(drW- z8^4B8<-<~Fni|43`Iwx`Yoslfxf~Y;2D`TB(#6o5XWHC~JbhH$B2O$5UTE89C6bYQ zeMojFitvtMI)hRvI+&G9m97~a=sb!-IYyn_xVa(mrLtX3Fl4b zz`NMBTr6$YmAZb}UEUS*uj+?IZZDJ$xcv@rGvp)3NzAFv1=ls5J)<<%e~R#9&m(v>YiGNOE~-xUt;E_fbTbt_pM&e6nt|__{u`b>2Dwud z(@s`5HqPq(2iu9>r=$j-{P5#D#5Vc##-FsD2tl9lo6NrT(=r{7UQa(l#o>;CaK1?> zkc)lER^-Zl9LU2kZJC5_@ZRDj*uRTyjf3ITJ-E+Dlkagi$JXW7IO4i|L5v+YX;s7z z_H^7};ZTvis(mDT&wk+RZv3@ph3e<8RMWJ-TAtH|B$lU*NawmII>P{?wOtkr_SOvA;!XzIuHk zG-PDblK6mj%^RQVnWc4p9%HT1OY9*J^0C8*&?%j`trnU^_5`c0lT$=(jOyV;kHCo2vb0`ITDw`ZV=+sYt2A%hsur(WlhG*y86RK0;U(Ma>GJ)S|@FMB=BT7o{|W(?IQ zni|`xrt{bJiJ5tr`SfA@+yHX@L4Q{^2k(R+|*jEplKA-VlpVRo6)nyAA9Cy0QE zrJlC(3*CIOb^Q-GobC+}E?Y5g-5rB~MHFv z?Z;pTu=9^6hB44$>uObnamhK0hJ{UEecOkp11zBzL3!4$)6i}=|3Bc0?Vtu_V%1o` zJ~tYKQ1e~n>iw=Nd(ZK9`#bK5Fof0~Yb!Ou6Jp38zpTt#(3N4P9k!?1m`Z>fP=xnJ zGPDj4d4l8R>mv>AbI~%s+vtMBxwzBGHTBq$aT>$p*xBy_AshmRCyrf`<7C!!E@DOpw zu&3ORlJAn~Az~h3zK-xMK0}woKGI}XTUVV9x zBc9EW3FlMa=A@heoo_Q88|E8ZFKd7ZL z8iSS7%#23F-kW7)XQpqxcEnc7LcLk6=dWvMscpr{OWCbc44os?)?(D6VKZO@yUCGn zN05uN1LgK`t((Igw#xmNV2T43tiFq+3}}yjt+KCVI7yT}VWeH((G@J3rS2@=X(UWFJRwitcCjVt@iTr2WrBZnJ> zBs^##%HJ;Ej_Ru;CiOY oO=s3XzlQgvJJVM-3^$WEKWnd$&}%(ng1ZvSE^;d8JTa z>8cw$DbK8NRk%7n-SrJYsr7oXz3ZzI#d2%Dj}~z&N+_+kG4peTWPU+G{;k?Y}B*Pw# z;{3{tTv+2HcSdU`LsHm)0+edv2wm_I)JA|k@N}-GZK8w}TI-#%bR`WOoYX2eC>dlu zeC8xx66Fj)c@cfDOF?D#$xmCJ=fT0A7FV99MXNL}N5K?<1c6B*-HaA)??r{wIqXXB z;#Xt76~)Jfsht>}ntqn!BD#fUU9-=hoW%~kGvRoiRD)7))xX~n z!7)k5r6l0UvXw^tKnWuRgj-KQ>_^au-ix`Gq|Z}tSw4Mz$fEPMsDa<*sx`yC7@{UV zsCSA$%M=e;Wr!Y!c-X>XcSE@g4PFnw9SI%rrNxtfce%YsvKu$uIj>`4CRKcJKJHWm z;D)jH2w4253=Ol0wUx+|!}1?B*aK{ywQo}3Ziq6{fDE-~&kBfi;lqNoIIR%6CV z#ivY8G7**6?_`*FkO>Z5u59#<8~q1)4VVBSIM$!^y@mDdzq1BsJFD9 zM)F9;skTsfMs>QJt@Y{0@|RZQU0MG}dv6^U<-Ych4h<60g0z&hbeBqrNJ*!Fz%bO% zJ%pfi2`H&FN=ObJ(%s!4-QDAPTzjwgUCXuB-upV|-S7FG>+C<~n(K*q=6=5Yz3S#o5?W$L_P$l(qYy47wk`V4Q3DYXyCx;k-rQl4)#AZAfuMJ+mDp0XYDyeeWs zygtPa=`f9em`SKj_Um(t-P2a@CL>fgrZK&KD$Bt}o^E%_9Ld>7bqzB7XLX`r`|3)- zc^1TcplSGViH$>0fB5)wBwxRep6R_6`gWzYisi-={=93AMo2yRfnl*{q2c80#;ItJ zf+%jS$`I1^)}UQsZRnTwReL)=IMNmVNZ1G#>r|#dY_?# zKIieGUEeWranFm{+Y4~Htqc+rIb(;)Y2yqAGsCqPj&_>YK-}RY{tqkAp9y~&GrT); zd=>1>b{nS?Y=>7va(wqWuN1?Bo5)T&m>azsdGK^44vN29FUJX@0-ykE^Z-CoW9?ad zeQ@Ykjw~}Lb8wTv8`%e$L^aIJWT^HIa^ycK+OXV$j-FI=WR>yi>q0{4Aa6P~tKxJ? z7zB8v#MV$Kqc!)gaa}E|Gw+fnP-<#vy5NeJseQtpq)(Yzq)0XRTSBDiNI*KGCO|PK zZ8c%JYUA+&k#;Ki0m}h@h+%7n6)9=#=+%(xnd~PvnoXS<9w$ZWk_M zsUIjTIsx-t6=6-!7y%1FVH--#)1dpt!`VDDs8KAjSnx5P?b^T&VbSV@KxZA!y_dDa zk`>l^n((UBj!v5Er}y;u-&_|qJ!3?wr~+;GXB(ZIPl!x+A1j}TQ->V&ay7x}pAY2J z4$&!!GB(6hD5OwX>#PJXM1rE@Zb9L!uZ*dQDZ8!FOi1c7L{n&<>4Q_!K%U73Q74{mo~q-m$Q2N0-~nvc;yC@QZYa!JLWn83&JRLS@{j=h{>SV{He5FrTyg zCGAx_ibsukW_4c-OsOSOcH{<;tMb;F=wGcHK++lQ;+$+l|AyPAteOnfZzZ;+ux7*W zlUMnW97x`Hx>{~_!1R&%b%B$~U?@bVc4C6L&zSoqAT91xdw>BkWYYeSVZad|k zT0wiwQ?g9;ch2y#*SuS5gJzyiHX}QrgZjHG@;2-5zt%cH-h>-c4FwSPidTzwL@Y#) zHh5Q>R*V^WjiC`Ejr1?aSB`P*rAZC>TS4E}m1|ZJ=o8V#LM2@GUGFby*jZ<2LSx{;`TGCz}QtP^UG;BvrmPp~5r|TS#%J2on>{CHmF}*|a zwgZUdwG7B^#;vG#U}dwck@LfUimLB;X8RdQ}b|@C%u_^7(&YTMmXA+d{bX8QYvTcOYR5cYV626 z-OwCGj8lVGuCddM`IjN&wHKxa8K~qqrgX%F_=LRu%wjjh71epFNmvqJ7Z$FPI3Jj=_nME-+HdAcgO@WsSA?>YV4W;8vp=2-`=KT@ws zy055#WSfWg_!~aG6x}Xy>TbEPc1m6G(jN2h%DN7&;bE!zF*-_!-bH*^U976aukFKNO>oP;bShZ zr#CtQL5m>RZMn?W#aYftljy97RdUYSk!b%QXthZd9kFqtI4B!JeIGFae{Uo+v{P7U zMyNm6MD#xAMT~Oac3zBwSGoR;P(CY*HZI3)T@k9$mMv3=``WaEwc5ANK%F}fg5r@i z)CdL2;|;xWNdnsIjd;ZaoW!{CF!vF zrpA{D)tV;QNs1Pf}NgzT8#G*t{p4rGtFh}E9WQ^7~9H^=Y1T~ zYGU4}E8Zh7YADmm9858dTXMiB;6srnXLozU6u?-u(WVL{IKT^D}yy|rFaui zcRIR1=)XT+JF-N)APvoKW{7_$fu2e)0d8)xA54Ar(*`oV$XnNA9-sP@RTyGJ2KSx6ZpO)X0fZ!k< zD>TmHR`UUBWLy1Zk#8+C5MIj;{tkM9DS2!%K3|3dBw>J*m$HE5*VU6EB7JZ@V`+&$ zW@f1o`zB$9>tiMuCskdQy<_Uvh&&9%6b_PL=Ve^HzCD$S%9?1i;fG22dQUWYnw}Ic zRI*QxTlwn*H=+hS=ToN8-Av57CX$Q;;4r3UcjvUfxd?P~YiW{e(nzY*f<#V8Ymi1& z^{)|}Lm!j7rjixFI9ib+6gt>xr9AohWcJ8}(i95T;W-hSw<+CxmikUtxC~56p1aph zgH25e<-?@&m!%B3|}?Kor*8vhWwB9v`dP+**`u7nZ=;EzrpHkn%z)XPr~gR(UXGP zIDL`jq(ZfMAYJ#C@L}vYs95MsqMQTjK@&*}!<*VnrEe&!-~m^_weXv5IPZazKiEuK z=e_Xdj%#9AIQWba%C{qv-2D|Veic^AM-;2j#7?cM! z(A6?dpL;Vi8FT|>?*^lnr_wC13XmJ+cxe{HZ;#65VMM0K73Ndfx(s?LRYknu-d_zm zqA076QKwwYs?;!MFkzyZGc9}Jpm2)^!mN4VG*uDfbir4H?e-l6Enhrx<%$X7Z`;7U zdW8~wO}p=)EGZ+H%R$vEd3%dqYK(3~HU$i0$0@pH@cv=OXLPNb>5mKq12MuIT7cnT zJ7;I+>wAd|#WP|K>^$C?Z^#85BADiQYZypr7od%W9wDxq=&f)7 zZ*v=GhHQms)Q!MD_><2g|73ApqZ?yrcg$}B zP%?^Q)w}~A7Z?w==cw1t4!j3?JA1@pSt2WkBkMT|JAcSe&v4dXs8?UWltrCE*{&?{ z)bf%R0ej!~S#mpnhISo4VN=7v9y#npEyE zr)A;2#3NQ#tKmbVm|MTVDg=PB!rb!L0pow;8*=`;MhaQr!UEWZHqv1e4{zU)m7nc^ zeptbLpp|^y&~~b;9QIssiA|4q@D+!6=xjRwc=Ck3N^(WV{(|Y}TgP@wpA^zJHtb-a z3UqOq+1S2k?CZS% z+a6Y*vsLRD(1L(H@39?`l_r8|grnS3U(vOo)#OXTWW4B$QdJqTRuPD~#+PRlMiJ&0 zJwH4hw7WM__BiN-zAR=4v&gIUoqm@|n5Z?i4xWTHI>-TA^OGA*^Wda+v^CbNR!1yc zC>^6MCa+n1C%cqzpPV&7_=RJ6`FaX>_FWW^zi&f#L`K6Y!2XW*`iJ1tgT{q5KRKBj zR}8!UBh710-p6B{C!`JKBip7W^~F&Pd1&ov6zEc2T`SL1ZwsqPW8^kTKr=QISJU>} z`n88S_@#4a#6uKa^R0IHwC*Xy>7=V2S@&&IrsLDlGeQmjd5X+u7?LGv_48_LRU--( z5`1ZX^UG@f)=r(^}g~*NvZ9# z3ntCBG}eC{=wnZH=vZ1Pt3WG`VCr7mx{c@O$QY4AHK~|Vnj5{-Y>U%I!=e%L09C#{ z`#GiG2n`OH1Fc2bdKb?7NUU`&I#J;sCcQ~(Y4l2t546w0(NGy}-9g!#&VNN+MF(xP z)^#|O@FKLl^OcZN3$-?8B0vwp%}+zMCE_u&yT4K!)cw>zZR>6{ z1sw$m6{U!5~*$?DivBJf>_*ZfNlJF#a|v_A8f_TQ}avL36k13 zGXx4zREwtJZD_$DS2Bg)K@~dKKsRw~_Cj$X3TU6Vl@mMJP=$SE%M3TOik5Rk8zXXu z*CjF}7=OKp{`@M+uT7g8M1_XelbSaE@^U6`fl66p%nLhf^X~fV9aqxzmBm=scbFJZ z3St(q6)9Se#P!XH$P67z5s!%tFoR21OQxM@7tu}J+_O=tx5jv1i_~M4W)2uhNL`x^!?t$0Zg8}wLjiA9J^dd}mBE?~i~c?fOL*L5 zvKMT7DQ0oxd!iOA@rJjoOg$}L8yOE9hyUc9A`vtUJ(N~n^eH-eAw#Tb4s2+DkCyv4 z9-}wB0%*;h1|_%YFc4w7SEu#J`)St^iOe^zXupF7Lydd}egOB7VI*>lqqTzg)7@e~ zXywq<0x7exb4nx`?-{G|QW5vTvyU*>C0s>~VJF;2s&}!1Ic$yHP%YOVC!nlF>+h=J z@2C%)Y&^LHLKE^F*{^d({xbWmNTTk5Gka@E>DjoR8z5j5DsOymP9S0m%hc~%C9|!9 zhU<&iGP8J8JYK#uf^aVN5q{JIR99WS^B~M3ew|l}lu;BUpi*Ca+$HX+hyKuras^1y z3H%~5>pQ5R&?CcOI%~$INK6sR%G-`*Pc;gy4BV9J=-i1`8;?_34mUAi-P~kf9YM_Kys zx;|eB7T166EthVF#?#(bgFY9d$?MIX-jsF*;IWv@Sm3;!$g{0tMclzaxv7@$F3>VY z6eMB)WVIpVnr?7Uvdp^YX|d^3vAhPe8Lq@CYzjN``*Y@?73jKC{HKLu7homui|ox` ze*a#sOYgVoX#*H*<-gJAy>m=+LC!aSc@+xG@+7BA0FMmyzXf+sbYL4E8d6E72zoy83>v+uBS&(`}>nbjFQ3JE8(Ff!{JccVctj>TXb$ z#Vz>~@Gv`10tnqa+>F9~<24nu&l35Bgy`v(E9Jc@O*vWfWRi(jrnjU;OB|rSau^KI z_rTiN-yW+_`N_eyZta7*`hd@}XD;FHro`DZ{NJpe3w&jwlb_4M(<&p1 zy2XDnL1x71{6pL#k0Bo!n4n9>eGGsQK{e6NU-}Cc&#UCT&MME#Z5Tla_D3$zC68hhC?k?iz3O~pGX%F+O z4EnzqdUXAneUk7`b{3 zIBslAyR!Ea-q`VdPM^|y#NV1-nNC_676*B+@loxODFaHMJ$EOGEx>s&?h^V*`Xd! zDebzmfaBoA2B`mkT=oA@8T@GKH#;2c%iGssiFP;MtpKTB$Q2Y&6Vz()_`^BP$aBaj zA_#IGIp~w)_tV_%>AJ%YxS3?bfyHqV@R;#8gX&8cT%Bl=uL1n`|G66#O^MjgGe%pw zH_4v~vy+@DAC%;E;-Web&Kx?dWec^BRRBBiEgKZg;se=?TwSYplV-IPrqnS#46w9z zj2L^m3c3qQ7j;?r`0#a*+E6Wos;|_}2I^|ZpVgNJ7Q16Vtw5Hjld3_(!cnXo|A3;Z zP2paw-hn^{ptVxgfHSu-K*PFIXwgs>^IYq7*M%%YWaQl8q%n8IhcTP+fP`iQr4!Mt z70~fs>Vf0CA?B^u=LU1aZZkw{FNLjHcRHq3bLLVA%GV2=xpVaTN*}pem$D!A zbo6ueHj2hYDlhHKr6djapTJL6gSN9)0OEUq28v1V%R#}bYR*v4ymm+P%Y6KfhV_zK z?y`4Cx*BSs@y6&&ywO`K^XGGeUNYHW5q*Dm<`JcoZt>bAfO^mziwT+c^F4ngYX?k> zOlrn`f`i*{3Qm}7%e5B|Z^=PTm|{?f>&;&{EXXtj+P#edt%Z0QV%JA%l}2r;RwS9` zb>}vLPsJ3fWnvxpYWAggipf-@7IwE}!{_@?jP?~KC6$M-yA3%G82bWFRbSXqH81Yk z#vL8%wnp+N(6k=ir_rr(UP__vR=+~)om6OrPt9CBQxo#Bn-lZ3k-4CVr~k6ctEjfG zky>7)Z>3u>dz2r)VS_^oFP(ZbK&VZ_Dl=c1>NqL&$;AhRzj3DNs+%0!E)hu`MJ7`| zNRTyk!SHP-3Qta>-wSKw#vK?KuH}GLQxVs>q;CZbpPlpMsv|6%GzqQXbAGI@5^=rt zk(kvjk)SF2ccRcEqGYGBssr4Z&1juRFk*+S^|D0f3RlimqWdz&QtEKr%3U&4XR#N( z3kJ$6g5!7V>rl_&0%KoV8ARMegc9e>N+iCBq;=RT zG`I8HX@FpK!r=C0*QipKoANBMk*Ty zf@Fqg-NQV=Iajp#Wu`vZcCfWPlkiOwG{z-*<#??KE^^8A8fKBJm<#cED|i-;tVgdm zMd3EY&u}xet4P?+EVN*Z=KzLn^&>D&KFm$Q^k7Xq^R4i$MZJQjGInc^3aG@jAU51L zWzw;It~SDb(A0^gyv}7@18Xlu&(m;DVZJw<$zUF-rBxa(*Eo9k`=gA&nFk>cX1Lo0 z=bK!W-S(+;CAWq73G(<80PQ^QRSd$NBlxn#J3&)(Putv+G&Cz}y400&1M`WTNzMZ6 zp1bY}^hAa8bKFrEzBu+Dk!Y!#iHf+=uF)=MvbuW<$FI2%kL$4yIOZC}mlR=Ho2LWq zMA;v+WYxI1;kK^=7~a1`QlP6A>Y%#pT05q}n*&c}UZxi1N_%>8lxg}-0WUvxzndVA z^IL^M)ohq4$T8KwP_sTrwXPheyfO6Z5F-5g0ESf27_bpcF>HOkNMKM*k9AW3zQh)}Jz3^0Jcm_eXjc+! z{vIbViLv8Ckh`g|Q|!49(>Rg(0s1>mU|YU8Y$z^GXFv$a;OLee_|%~}k3kXUYumMq znhI4~M*uyaV^8mLYAt(EpE8wqL;!PA?Mv^$S1^$}xD$5-(lLZ&dB*zOMB z9pkFjJM|2sKz@s*kwvLMqWV_MRQ`sW>x?_}Sw1!G2UO1YG`tp;3@ojpke72`H(+dt zJEC1|e&?Y}@0@D36p6=ooRUJ_Xw;_pr=)Ce;nTlfrDt7pk-OseS#JLXCscfC0@u|S z5wSWn2n{bZg))sko<8C}Y}ZunTni&E*8=#p$aacORuGn3>qTM`tYc2|#8yOGx*p9H z-Opr7g08#qc?}fE?OX4xA_e&vx*)|ofEezz-k)QPRQ6sXJwDn5}u76S6Xw%&vKex@lRHUFPq3>6F(#)`DPp;i?xQ=|6?h| zEiQ;?_?%RxDntAK(#9+8I|yuf-9WhB%nlpOl;i~z%f@Qe>S}(DA6VuccqM%EPisDc z{UFyX<@-x}|Jg?J|HgIx>z~4S<@=!hr z<%y5So2so@koNj`iztT=-$Y4ZvcM({dSPl)6C^_D!o}cn#-F7sZq$7JtUN%a zsy>8Wf0mVfh?Lp>=?)n)2)EsD(<%@i$fqcu9fFN^xK@5e8C_HQ`BBxhIazcVKyB^U zE(My%-(hRfWvV>P4$jxM;=mIdEvr^|>b_9}7FzeXRE4aIYi2u9qwJs5)s3)$MMEpq zuu>tDE78$pC7|sUKQ#qZd^s|)TZ!FG)l>obQMz4290RpS=GF09;8*4x+kGv?6VOh{ z6kAoPus7E%>2eUTH9NtF(z2K?GC->mzfxsgn%SQ2PN6dOYFdVyqtbxaaE_e7#lz2? zP-l*oKrK-%udp6svqkB~&c<(JSr$fak&lP@$*lP~OqI)OE8Amjpia@9OwZ6qnVFd* zLk-%$@||?jN3O8|fL423sJL z#~o2vK=yq$nwr+_Es;k_h{plu>qk^A2anHguY4_Bd>ZcWk}LiUNr=iX@0W1Z?*d}K z^^W{O>DD3=4c2z}_hB@5gCr@VkgPtqgO#@`9T+K-I(=Xu}l`{W2@ z*yW*(eh0zXX_FbVb1Ed~3tQO*Wl3ltgo5``!l?6n-K;#FQINi>B85om#wQQnHyXj-$ADgceE6!Kjwm7Z(Ew0_nF~@ zCTJ-2U|!V8^N$WbLew8{NbC(?TBL#R_Lb*t-9`H_mI)CKJkH(}b@OWoAvYlq?utTT zqbvcDQ5N!K0%<#f>SNcA1>n2Z0^o7i&?|uv_2L!r=z-yy70>`w>xx17C~{k}xNc&+oz5v?c1%j!b4m3iRrrWM z5HbYhm!A<1t54JHjhn<%WZa4@52kpF)OMS8Tv1+LM>t^4yVS*D*#CCQ4IF`Lry|x9Zvi9l#Ay~6v+zNr@)xL z7txi`<{C;v@nU(6ZQd--`u1!OHL3@@7)f8qhUOe<>c|( zo{OSeD+f$DoNvNCbM2KzlVy_Q!H^W)$@}5rvd341wNNYl5-$LN9 z1xSs|DD6O5y9PgKG#aS-pD=?G zSDn6ts5e9sUZo$P)oMMQTnjC}Fv>nkvIBQ{vNU{9TExTxpyw zJMo>8)^E*pwD_(0c-#KKRubdP377rw5#o7N%YT5cJde=cNtWFYxR7lkPqB zmvIr*8Mkd$KTQ6XQfwYVTyAM zrUaQACq&fFXVF`1ulM_3+2+?OLSO}Ya!|(Xa2p%k?hZ!oo+5$$ta|G}X9|FI|1w&G z-wu1;z^(dpVLi>Ny0We!v048J5QpCXpmgx6)!IypHg zI<2iz7$Cc5|00mJI9#BMee*=sVy*S6BGG$)=EVdTcBL8BR)b&in1~y;4%TA-jvnq4 zw{54-ZlvNOig!HOUYQt_+DquKNVvTd?Ch6G7uj36oN*XB-GKF+va%)Z+X4CS#U`W7 zRV5MF-Lp?NE#BI2vCFzz9yW{FSo=*w7YHGlnanlPf9BZ#w>$KWe#7NwNN*&6ZM%;V zTq#Ht2oIW;DOLbicyR5x!TlCaRb1p_K^x>U$0l?>+=50~gxH0lhBO-}+G9 zdr8)d_KB7rL*9#t-;H>0^JE0JqZ^4J)@o6{L~8yH3J_IBi0UL#10;aAukRPVNjpXX z3JBdL?b;>sT-As`avkF~0%u3^ddbr?S%gsK^#@c7b*>s z{{E#MR`Q;Lyq5T=R=1;%0i7sJlij~4gU4e#RaVv11+G5E>&XqhTSCfgO6VG1NlCen z)F5L#cV47C@K|7uwg&mA^T(&ojUu3q+_Fj;5f8bM6sr$$l7;=@k@w6ai#hD z(KOr9!zOl3o+rLf(%v5FLfsl<(zHa(1l1_gxIbzN481YbAh#S-tJf21>I!18u@w@c z4p}&!nNBYeWB#mMc>YLn)OLt3^>CCa+647JJC8jUGfg;T*s8A)02lq<_4iM379{KQ z`yV720ZeaY!#OvQC$#+b4>P9U5R%Gf(eK zo6ya)BR_lw5<^P7bO%DIzYUva^>P7-4rN50O~bM9r$o1yBh`blM5Z`O0%?<)y_Yp= z3_i(^-(yhT97XrRYAPeOhMkIt0rZEJ6={W`O+K~Jl!f-$;%c8DL9&^TQ-VjDf047I z!INd3q41TQ%lE^o&yB^gG$~#i;>j_O4CkgG6b~OigeqiTHuNTmG+etE-8j*7jPWbx zxn(qulWrD6F4Z5{Lr>RVn<7TdVYcfH$CN`2`w}z=*3uR4(9@{h&=C!qo!L8xfJ7|> z2C&3vRlTW62MXTt3E&(*hXH;>Bjf+v_MZazPYe0~V_&$FcCZNj4$@D$(0ZXy(pQ?P z2xf;u?pnu)@O)z2e%d3y0HR>H((;r^WKmEw2Zs53ul^;yJz(oY!aaIOm>7C@1+~j*2-$9F*BVn=g5>>W9df;1+Fh?q}3-0Ph zT9y?ohv$XcUKiw)$&QnQ8USYXJBWcJE`s=4DBeIso6|X(VOVbys=zvBgH}W-Y+Q4W z74d#;L^J5~LfQ^n-tHZh2VG+o(GR^+z6x_>gH=0bkC0oCYwd4~eRF=U3I#mRMzD3W z^+fT$R6AQ|wuwEiz0BKuUm9P8p{acO6!^{;wA&J+Y>gC1)7%j&T|U%MMsAAevSGa# z!Y^q$j*yZr{)`_sV+*gs5m636LNVGJ^ zO^Ej9(=pNO7PU1eBca3Tvj_>h2i`LQ0SU?ruVUuagV^RdxQYrmN8EJ|11n#lUd;=5 zrPi9dK8o=8bYEArXiM)k@bc{}HVd5#wSH;p;X4K8@13Tg*b{bi%mnmV}TXPy_K`wON3s#j8n07S*0(nuti_ia~*gSGC zNhA<zTTeP6Tu6#5AQ&_wHXuF6qZu@brFsZ7|lQ0I&cc3okVy>`+Y zamFmS0~r}jvj>y3rLey#`KSqM^9Z=Ur2Y`ys{ycxzD+y}@sflt);*!{c2$bk;b43m z&P8u-eqRcN(#c%T`a^@2Au+qoX#J^Kmg*$HD!O7s4uGXCO94=f(M|GridOoy1po$3 z??=?ZPF;#biXKYd0#xA+C;HEVF9D$1)0KZ)q%_XP!c(hCn*riBLEnYHtts5d{DB!G z(o_|oktwjWw}+L$h-S!g)_Y|1+}bVYfgtr77KO*>=O16``-5rxvy|^E~P=_WC9_u|Zq?WHk3Vw69?Nybxh85e1IjcuhOjTQ~BsvG$xcSTK3&&^Uc zG3^l0gW(tE7=@JGn&;*qYQxw+37_gjZR0C{8AY~a$|}F;1LIMtaTk?F+!anUK2>dK ziO>e?`UP#OzHnZdte8$X)Wa8mz81Q8=C=At3z~5r`2^8lmY|*TK0hPHqFBNqsUmtZ z?9Bm>Zwmp1ozSfeq-vbC`T^LYQC7aoeu|!Ct@)DF99VSZO@v%RVAET?99vn1o-33b z3IoNDJ?bqy&UehmnDE{clptX~p4(*o+DMm+z5+%`IhI}bM;wAVL&63?_ZVGd9(l>YK3ti;YV|0nN!Jaz)RIm%>tt z4WDADXRqLusA_~F_M5=K@1R7+@ZIQJc5KvR3wfwEboB>ocR7{~WQFlkm_lv&OMNO- zrwc9wcHTXm?wK=O5MYC@tkL2aua>Dd&e0eMEH&*gr&7ccyqz)ZWq&0*ouNu!W&f#} zP8wu(&+^6x8YzZBp|M=BIxtuc(L-?buuNtZPxkiOw^-$Mp_0X{hCLRLP?HcGMX%%e(Zo zYuo|oS&V^YS^_(ChXcLrT_rmkH6Cr5m)vV1>r4CDkx0Xd*zWhd`BMsJIbUjaM;Upd z_awbRgYV9`3-j~uy*{pcqBve(rqg@#p|lF8H<%9XjlKm+!jCkj1+}TUM?<}?0GZRF z5E~b%6=^E-I6pXb>2U0Ds$;{$Q?Z2q$dVxJ!;Ts`=$il}uV%kK+=Ka!0P9yz%N>2Tk|m*uvKRKU zL-{R1`uNa(6#Pi^b^lfluh1~Yjv6A0$(~i?8rS#mi&r}r?xu$a!y#5(b4F_bdMRLR zui--PhB~6fxtqWDMy=@w?MHHfj`FdO^`yw`>`>8Nwb6vCGt! zJ79IAq3+tc3peC|$Eu&bx69c$0N|B_ZQ)Q8L4h&U{F&C}$V!=QiQ6#eGXwR@MWjpLg4+B(SIlnm{@{ z+4rKxU!D;}M47AMON(#sEse2m#X5apoAKfkL{)#o1jezo2h)BRq3C z1{)6(g|NUX%seJmA!Z8J{!Q{^5SHT2`a`B^^|SK%^=m{m*HKYcoR8{pKDQ*Q5A5U4 zON#!L%QW8e_N6JeW{seOW76`&^uw|=M`j37LhTqkEnpxs8?1D1#jfcM)h?VMQhJmh}PNn#xkfk!-s zS-gNH9KcrT4ql-kUI1P7m*=rG?7x>1*>H%w@}RkvAy)nS-O@KHfe544@1S?Ub-mO? zvxZ-uCb`J{J6j_2NB7RT4sUO7a~&eM06U1teq+Z|8$fM}oa+~>LhfJo8h!`)e+SVb z`o01Q6HDJgJ&%^}V_bh-0X#gwz|`_%z515s7&`$Fntc5oL?A=#ZC(Uxf<^smxscme zl<%MiRdP3VzB8+@@8}gUMPj{|5ieOY70gfN91+$OTdMKbrACv;_O+Hr!#;pY16061z{Om_CMNI#umRP0{c4fzZwh74lrAS2etqN zl9%oy=HYv$_knlz`%$|xG&-N>_l>^MOimcBTpL}4-qhJmb*X;`*|Y=yssPj`8r+iw zws-zZEB`~wBE+^GQ%k#Y`%&D}`>_634d?j3vElW9+0ZaO@E!E)W!1tafF2AeIiTVE zvE+~nr(;{+{_R1MaJuiHG;+y(THq~J<;JYeuJ2r6oVwh(fZaiuggfA!s{Q@7L{=)l zgA!PjZ{UC4W15#RCD*>%U1I{5QCdjX3c`MGYQU8!_H_f`DdvX33nCSTfB8!i^Ko_m z6{`Af)*YLMt)_m^caZDce>c3}bee>n`0t>jJ+2!B&9xGZH5{t+v2HD&cp~{2)*rgMX-w({9J1Iiss<$@4^TJ)FuW>pQ5S`8z215ABU;=M=!b zME?Cx!SmK|agG(q(+SuC-_Pat;ZP{f?EE)3V*gqe53UU0*ZZ*m z6#6!TDYAST){iCm=P%V=%|BZM8N2nR1FI?w`6UL;17J~8Uzr}#=gg=&C#S?NE`s&R zYWxRoRsfKl{44w^z+uH9L()Uk%cs&y86(xi_}KobwUjZLixBP61Q4G>D%=^`71c^* ztc)XHepQLLSvm9Ygx1XLv?I?lJ;IkHS?p1IMVXWH=r&%i$VBMdqjrjh(KXj+9!}{Y zq$OX(3oU_3_gCQIUw&&S86l(+=1=yR5&o9xz7os;0HbXl;aBqOaR2w?m|u_6tN-5n z7yf$~H9G%gq^0=VNE?eFqOiL}?*<$Me>z;;0j|R?(G~xGJyU`kPIL6vqbR$NfIo{y yTLP1YA9*#Giv-_6UBJ+5l^zljXQ9f-8FXxaoNF}s*=XeZOJ4N=X~FN?sNao-OFb_%r(}SW4!NgyyML=MT{Y4f$MTovQhvN5)$wf{0AWB zt`A7MnVSNDq9Sk)002w?6-gLC2JcWG7&-uf<^U>qj|Bc8m-PPoU$6&o{p&gffC1j( zg5Sl!3!qs4+b`em|N8uez+VXbg}`43{Dr_@2>dTZ04);bHxGgk^c3DkqW*E88y)rA zJqiyO07OUsdH<(3ff@Q8ufM#B|AkWX7t4Pk@D~DqA@COhe1rRpd~#lQ4O1F5}@~qUNEbZscKUBxuYC z5yQh4aT9X0wzD>IGNf^{wz6>)aucQfZFC{<{(Cb!t(b^|v8j;iL#f|;fZs%Ef2YOO z)s@Yao6Xk2jGa?ZP>`L2i=B&$73{(4=x*a==*DW}NcZ~y4^1469L(*U%x!IGz7J^l z%+}dSl-AkV+*rue(3JO?u`w^}Ged4;R!&Z1Lsmm$ZcbKXZf;|KUQPinQ_g3!zfW&$ z^vCRW&JI?;&24PNZenF(ZDQl(2%^EsPRsr`qW`Pr1R?rk(tij)$RpTCNW#Iy(8=T> zc!_;qPF4bX;iHR5+2^oE--PYl6)2o@- z|G%xamAM$0YWo{=;Qiljz)?Yw!@|N6VgGT$|A@eEEuh4K&;22v;FC1}4WGXz`L{s+ z3$DN5`nM4Hw>tkNU4Oy#Zz1q+b^c4b{(lD7pFXaM4d~dqf*vel0+0YO(9qD)P%+Ta z&@nMEFtG`6Kpz8}2>&`R0V&ZfGEyQ^5^^fW+vJoClq96IY_tqacbQq3Z_%)Gv)|)l zyvKa+`yfadn3&jD*n~JZg!d>&DenE-A4CH{fQg)mf{lVi3m_99p%5S;ngMFC&WHw9 zCchUafBzsMqoAUpV_;%oiXRE+O@AtAeh7YYF?+HFqs8{#S$hW0mUxqLARA4Gj9Y{a7DR^26f z=FpE#OwTjNu=ky{-#Gi%81wtT;_MH`{^Sb=;G!Ubi-$r0K!D>AX5sgy2Wn=+1+3B2 zs}dA;EV}pi(`@G-IL3>vkMC9|S8ZpW=^}u=?2yKNmaLpA0cZY84y%5q8Vu8VHHcE1wWt|^4?bVa+syQ=yPj{cJWkKNt zW(Xh^99A3ww0uSYFSQZCs&E$k5p*wme?qr_Qrm!cC^0?iW2~6<*1mV5UXvZRUK!v0 zwuy;>TF0iulB$;QV!g&=&$gr{XZ*{9SdZ{b|3<3j$LgwnbrFm8Z7W}&t<4)RbTZZR zA%LzN1b|tL0Qy|jE>jV}f;#jo3j#Q#96|t0kket?el1T~ckj;22?NaE+B;@oDpTD)=pv4;$1uvVa_jnF9B(N?F1{ z0JqY9TCePtAl?lFyw!aR{w$utw0l8$gI?jyvuI>wqVN|ZFS(`dZ7KQ$+|nPdHl-nR z;jx>uvsXeRJq6Cbj|=%fkDK#gL9@JkG`A#B7Vq04w=y}vhZdA-m9zq>d160yn8VL4 zi+X#$EN&?zdo$=W%?%{mgcl7Mj7hV0So0CTPr~%uB)0!#5}#nv^qRUQxcKJ6%1QkJ z2V{;IdVXyk`iA<_BI3vAa-^Gy>vv=C_%7;QWo%8)%JmTiS`eaQ2uwoV>Ro9Zqwxt1 zEK^K|KMYzsZFE1Fi#2|?IjyDpd^|YNk?wPggkAN!B@vY^hEK3F_I-RaYDg^tNYMNV z$zLSDG~dl{^uDfyE81keMMd}&UJcqX*`hky#P;XT@bsHKNFr*CdpBUG;WKiTgX|yW zGdXoo(^S|MHgzUlG? zS&jc`v3`YI(6b&z+^e5=q##T9!9<$vBy#3DZRV64EBkGN-h7KOTv9?e72hM=LO;gvM73EC{ZBW0}F<$|t_fSDp)blR=n})~*&B zAf~THagCgJL`AwJK7O*kO*F|1egZe+w4HTh^-7`B8j5cVX^*%Phb7r}={N0vhR*40 zFWa8JTdy|7rR4usyew$N9`75|-awXL7VI3*$j7W9WrTfUmH#jtep=N|L@Pqh6{WSU}J()J<%@hRo~?+dK*^RtiZe_8LhKPp`5 zpB~k?BK(^f@&C`Q$RVf~{v!GB_V}NpEHh2W8U|bbWal98kGJ5-C9S~`#qY-a@lXwt zWzO3E*t$?%CT~f_^t%sFX8i;S{D-jDf7N$A?`9(c64Fg;hC5~9U*3I)UlF;i*%uy_ z1%)8~N}BgKi?4_G^RhaI%XYY5s0}9@;g5Hw zuTib;D-D*SOUZ8N)&4wy-To!>VCJj26oWmAD47gBYE=d;DomPiNpqdkJIu@i*4Cx( z6>t0ThVxuC!cw1Jdv-`P_{-K3{gFUW3jbu^iRTx|YOgR4CfX~Z+I&1Rqw8XzT z2KfP%SB_7Ht&XmQW%>>~g*QSvbwfT`b}pC6j1a$)L3rw;lnj!2*9N#iLHNqmQOE3sD+9&6l$2=nsa)9MPin^DR!bCL zSSHSxbI6)D8;t}-&b1MZ*z5j5jjOF6K$pt5TX{hWYtCIe2+4-^HDmeCLN3D)YgxqM zTMww0T1?H&18C~UJieOvb?Z~joejtl9CG-O_x0Yj&d$4^JBr>pd@how%zhF?CeoeT z55Y~Br=gGXyFN1W$_Ea*)CLO(;Gu*b65xl~CMu~G&oa1g5Y3S#srhkssucQ8L<*m1 zErK%d4V9Br_nlxY*w?!+r+vJ7Cl^uAf?$M^=<0r01uDA%$;Y>DCD6v92x@AXUhI8r ziAuG>=q}@>ccCA?@FtNfsp99WGD+f2TGrYc)>Gf|^3a!lU*vY8d z=~V7nNt|-i-BjC7;WvIh^w8NiL75H75-mNuyyK1TdO;Mv)O1RC9OE zTZo)|X;6f;JArOshmDo>EpoFh7R4(&84>@Z<;u<-^!6(d3R{E!H1@@z}$6xlsyVqY^c4PzfNJ?O{?g;SV4&b3;0P- zqjmF>#IPcuu7h$Gdt`bd>>ukwO*PgdDiJWJ>sU_i2u4Zn0&Jg|RJ_Fkj$IoK(L4wl(yTfK0li6oozg6iHQUo(t$Z=x2Us+l|aKDqF)@%N$mnP7Qy>a7tzP z4V>|9c9ah>n+{iLPZu`Y z7L#JR%&A*@@MY?Spp^$JVO+{+8~yeKyu32R-O!maoTv7IK)KGum|hdzHi~6+gSt@x zE#GBbY>QCjQ0xVHeeP;?$>ePngARd3St7DafmF-lk(p-%g7jk?|@c4X52~zs-U^8)QdHOc${6`GfhD2Q*Ujv0pG#D)N8#l~(D? zmS`F@~fh{=_(YvtJT0bnApmCO|fpClG)fU2f?` z+L}%>7XpYfRX#r}LjVIo8>~L7=Nb{Gmc#G>%hQN{pHC65l*qMvFA)F&*upf2X@>E5 z+l)OiPg9LUzMh^bTlFwf7!6H34JlBN-WaL9VY#@Da;7XNRd1$^P_(PRqmlbXw>1`x z*>vRU4BCr7*VjABzL!cLvfO+;vhr=*|We{#{9vy zHEmWSM{RRv4>;}z@A*7-rO}%*Nz?5fd+Bw0WhwS{1Z2TE+)|;Ru{4%~RxP%+GtD#Q z%_$e_bf*;;?;~^DdWW9QQh0rCO_7^F^5;$YR!}DEm_H6{{{(9xR~mpVlLu&jx+6#- zey0KD+N*2if`=V^uvepDJmppX%{SJG&oB3%loWPZrIqhzUN15`xo>Suru>e6XK`S) zK0o!aKKhFNEIHOZOGiIei=jCWyXR@Ffv9 z%#I6DhIEMy*FxwG#TUHMm#5`}w#~E%=2dv&)LNp?!s(>K5`ZXquCVslMT%K}-J?bR zJ&OZ3hXa}2jIu1p4BgU@vDO^(g9jtgd6Q-xs%-`Iav>FEq@NAy9A8vT`q0EH573f$ zT)h#_N6+IQx6L;ud8=5h0h5_&M*!L-Eed)_PZn_Gp$4Oe)vxLcHqK`XHwg4}dwKdL zL>y#o8t*)`Q?R=Kl+;ClX7-q7NOfH!(jpG#RJ2uH6)tNSVJ;kt9Vpm>&R?K5v!QQ@ z{w`}R`ZV8?dJCLsv82NCMLb<^8D|6AEd~b_)A>iAA#N4e0DwIZ|DbH-Xa^sUw?_I} zJmve-IQQk+fLYGxd^z%bcOJ>mdpuLCU1tLLXIK4yn2{V z-z(#p*q&K;yyUv0uz6kcm0=OST?zV-Ygx;3Z7+jHHxKYyDbZ!fMBDOV=AXx15dd9u ze(`Ae*}KAyftDhcQ5p_Z^r)eOb*#4YTfygWQGVr$y4vbwX3OV^+6LW@rG&;wC}1Y= z39H|FYjbDChJ^a9u*S**g&D&O>fWWT-ff?q*sv5a$CUZp*s>9}8g3|dYe6UU&TFT{ z63rZ8Nrrv}rk9WorLEI_AH9m+-C;*_r}`YI>{-k$%fxO3pb5|Q$d(z9%8$Pp`xH~m zaUUWyIG`7LbH~-YXqMzzGhVjm==BKCONMREuM1Ut>6PuId`wKG zT|+dcNYrYg@}=h_=-3!sMOiRct65`*o%J=&E8Z=^v9{8KHdk$Q?3?b-EFWmAh&?ej zNsy)sJqWJ+Y%pQ&VcmUonEW^|SCMDHnzfYBBph9K)}?^CbT_%0s7g`^~kj zJK@J=b4ED!1ST~18IbNX#3rMzbQv}ffJww!&!t!u&YEi*sCW4D(;dLLPi z-qLDoJnVD6lKNsyvMjUyH1t({*P*JW=62MkeOpmWk(5I|%H1RM_xdt}>)dVy>ZPR> zdngvfuvfua-%yl~1=QMoKi#mV(ju3?Q3P#3pLg7F;vMSN@0gP$R3%lBBn18kT}ZDM z*w2WK5kSE^+bgEn?LG*F1IRxYBz3_EhM69l(2TZ)a* z5wFgT#;f-b%rk8`(J@09&gi~oB|Od$6lX~DzBo@_K>#>0P0#}bV1@ubfHR^o**;R(;nj9!LI@ zOpm(pH%9s^{KI?&ziasD;2@AvOBaKPvlJQV*Tvl#(5#Mw3AD3_0XCq~MAx^tnu!qgY%2;frDZRe#3<5j`}CELzcoo&2bJ!5R>N_gc-foJZg zDaKA>4>!3K9sev9OHXs?MpoFdwGrGM45(*D5y1TO3%)`GAhHSF*#M(V-eO7VvJ`0B z#xcj%+1nYj5lE#G0)QGIfY&*3>{&3W^^uWi67O*mmWo;YZECs7%f|{E#3)a0304|x zp$ZxeB>#LqY#Y%)S?#3!=hxv8Dn3YVyE6iZjO7(fwZAC z=*+~c%jswluhOEG&z8qf?gJT%dR({@45Vzq;xEs15WuW1bgxQmDht{hTL4EZM*!rY zZ;1*2u_5iJzR_uAm45p$;dioW$yn+<4$X71jjQ4m1otr}O4-l$OA$Z==+G@Vc~`4~ zV$W=FiDL`rS5>)BaP?z@^iQ3g83>W6e`@*b@qZaQV~P3qcNQKCdDjfe(>M|&3d`zD z3akg%)oDGI;@j?V+xP~U{}b$;;!Ymv!CD>7c^n&Q1H-kFxT=z05;PJ~z5fhbhnduU z$n0FvnQWmCR?Kj{ONN1p47mlw|0EGVNl&h|L5q;mD=201M_vM+t{d!ha#in*pW#?* zhVyAyA=_PZ<1MG~(~6eFB^u(u%}^Fg-N!FXMgJ!R{@cQ#EwmG6wA*FZp3jh%s}`Nb z_@2(MiNf$1a9eNMw} zeW~T~zotqJ`1_@YXQ^SO7vJ@F`Y+1=KdQ=it7+@I_**(x@e6RX0qWgK5wHRQIfkBb zBY?KUUp4n=_aUf>F^=v4yHzu2{3raL&5Zph9hez7$Xzf5*k7c5o)z=sRQeIU!;w|_M%zZy}m8A)o*7f_4Q&3ftsvB+PI z#;=yG&h}$OP6KGe{sR8L7x)@i_;uy;AkbI9hj&DribK}v5I`j4;+|Lm0n}3C`|62? z{3oKZ+ilxqFg7A(tIh`J25Y{Fo)}$vD!W4C2f^Nf;NWK-gi$1*Q@u|Azu4>8zX6((L^-GE8_$>+ZdaA;B zY%)#wV$Mtn+rYV#T*x(1)aNoihV9wTqTLd9(oJpKZvj(shjGM-Vb9|Tc8Z{ci3vczfbv*aOXNdqh9EF2CP zCqn0%pkm-IxN3$RXSf{mjS}c7^L~BkC;2Fcd>hXAOu3_e=1MT14sK>}5d__mL!wGc zOMuML4!WS-J$^GSyNG*yX|G?dFaI$P^eID>0lYd7G=pJWXP{1+kdBaFnB~ z>nf5&T^{pLBKPztx72mT`Gx+CBi7p^9Q`|J<=Sdfupp!<#N@+vM z;@+5|Suw=wBs=)z08*ZxxNaOiM|VMk(F3O@ z6#pb{&EvWU!JiNuW%^)kyHS2gttT}#g#hyFS57Fz$_?`j zyzUj1R9~nJ>*(HOZV5iPO+s*^8Bj0sjcL@!T2tJk%vg#YiAB%*>=vRjfa;1qzo4v5 zJliAZF8(T!&I)JwklZnBDyQmW;Ach?qb|n6J(03oFGpi6X^$tqu3L|gr9T=qR>CKU zEMOw%LU)HrOY&5G^39c?Dl1D23|iz^&GLNy_1FRQ{7$M1{SUl{u6id|wsFCnyb>4@ z&%mL6IACeR^~{ImKzJeF0&;yzvvW9)HPmlKcf;fK-v+ z6Rc4?YM-n-J4LlEtc*FfHJWF=xtWi5soLp$<0=D}{Ba1uo1U#yua`C`bapxCY%vR{ zyAdyG2MSnA7R&r@JKMS&(#gDhFuT*-zvQ59)gs>5OIjfDG5Z8w3+-ZaOlBypN>SOZ zmcH4&Xz@{YnyF{Vpty^ls#;2hB6(I*T9WY9l@D~8P(>2>ei1DhfPv2=zvfQjz8;4D>wz$N5X z?^Bq1RJR%HyuTAGYJ=`@K zL(^<(6qzEvv7_M6-J+UXMIkAHbo}a~P4g6M=Lr5jCn$fTWo92O5MDV=^bF zPPdP?=BGaxp>CtR_a7SNw=~KbS6qhWJcQ@a9vrPC?$j89A*we5xB&BYA4keXcz365 zuRkwb=UQjBh`G6x8rVgTET!DV*~U9EX@prR7P2pLFRDP7MD;z>)D+w->AhNWi)h7t zXbrMyk=dZLd_tn`OLKag+=080p4whG;m(ybbYB^i-?Sg@bFWI-mQz$(!JxnX8#G}K zMS2LS%^&0H2+SFbme=nwlo%o%5IP-T7gC2i>NkSwz!jcWf5r%g#$Yu4!Ya*_7USz+Aew))CdeQd+{&5p)IvDKTQ84DQOd`+thzj(xk(kAHSr1x8&d@Q&Kze`%C?PZ4p@tt2rx1y^YNF?6$5x#ysa z|6R2U0^qTkN?H-z&|mwJk0DoT%scY#w?ztt@Iu5 zo82{>h==y05vn|CEn?i$Alnl$YLR$w!EMF4u;tm(FE#~N67~9`E11_i5AI`}yc%05 zSR*D}P!)OL#{ zS-oIy=fPcyg-B@&Fp>CjMN-jm({Y`cKu6Xb?OW-=G)?$y$3D};UR3xF9qNjxK<><` z#1XTe*j*NQ6YExfwS9IgY7v)&K-A*bYE%X-mKXk|Upj=s&7C7K*KchmPEAb;d1>mz zz2F%ek{iIx=t{p_LK=@(vX3dxM1D1MK5^MmRBbSFd6Nvk`oi^R#V{aWJq~lSy+q$yY7DORwR%3Q^5Wyt z?arATizTS$a9j+yu|4gOk3lE6IJh2vR4B^k2z&zVtdjHV z{M@)qL|ZU_f?cLnMj9hU04lQ7JB>?qV%WZ(>GtC!NfC!v993Kmq*B~p%JA<2}OJrZXSJFr*W0&BHC)OI0a#CtaH=fk*QmYyN%bK+P;F39o!9So+l-RU6`(&^Rh;wlX{#R>GCqzMlahYB&!ZT7CMBivnh}GZ!a2Vu zTca*zN>y=J08?qh3V*iIwrX$(?(%^QlOkqK5tSE%R5}0D#yFs z!#!@PV{l7guRE7#Yit*?38tgY=D=EZ!D;_h7`U@UAba06+zzA&vQ`fl1eJN(1s(hy zn9WJK@;G9>Iq$xHEbwnW#(I4vXKWS$6c&J5Fc2 zX$Kt}MF0m)2!PsPFYV$M0)V?g7dGI$(|?XH{pX}QxBmw+HRNa>b^|#Yqa6j+DC-+> zP||vSApSo=5OfiLTjPlT4U5%kwTE$esRx|}9Sakw-s{lbZ=-NjFtU0KCZPWip2k0b z39onZX6|s>xFf$I`~Jm*D=7@aU>Zq3_j_{;k#U+Wr0-lIPBm6g&{d?Vg?gVK+zd4- z=d6~aV${&KKyXijPQ^KAPTQs7j~-a9?c9RRE^(rFI`tVr_8#PGMCZOB7&)GiX&`{| z`onZ5)lQ1*HG@K}6c*Z3;mE%2cZ#5Mto?Q0h(=+?`^yy<(VtaTjF@WzU{{QpubRqbB#nP z-9Mbnh$g~Lh6lFE)Ljtqpe}ELl3Ss0*d#2yGDXpM*^TZs+`9r59b3Hd9%<;y9$mtX z2;#9+lM?OBMBxxEld!pHcIIBUH#RI4xWp#bnK6C>jo)OwAldRCEfbldyRCLU*6cGd zgudD)OIarUnjLT0GA|`$gtn7vK|*}8Y-CL_nwS?0Z;nb(c}6@jDlE>(AttcGoMb!) zqZfP(uY>Mh^IM*07M9JoAm2BUAEhFJA{wIaD}ZB4-4g2j>-N`}5z zZTGscybPrXUW*0@v_CQlX|D1fYPVr6Rp@BMc$cn6d(g_#{{o{@fO3Ov=4*VU8;Mqb z;{089_S8hoCHgI#C3lW(fnLn4YX6??+5!12)i)^(&TmvCWeewhz!F#Fr+Dz})ie0B zT9=xTCg?sP7-?+e8gyyqk18=PhI(^ui#g5dKHRx6$>T#?J5)Mz z-AFm+(N*)UC(ot@KDc5VCFC6!zfyTIK#`o5hf)mnj*$KMC09hv(laOQj<9EM84W9K zTM(aQ2~k3jm6g|vip9t#6ie%t;Zo1~Q|;I3?+rAIONccNq_3r9vaHcZumn$Ap4}iF z#ZF_0bQauEf@MtVkqcWezb)CDiXADSj6Zfs!{yRfeimPp{){-8^&%#awJj{jx>{Lb zg+@@s)(R$4RXA`&Gzgx^WM#wt22VD&iwb%pTVcasUqiDBmXBECfi46AI`f zvy|)UNdEo@HjMuFwZRx1vM-7pycE+~rmr|xImj!lofnNoR~AQqz@}k(mmrim>VTt# zG|ONfM@NS`=;H_s4k^?dQ_Sr8GAZHqnM|vtpi%0n6otbzQSK368_Rxu1H*+d4N498 z`L<=&W=%*!9!)alTzL($-WTua`_*Hy)O`Dnwc6sUcuqc$;q8(fJ@UprboK=eBlwWEg6dG^pc?XI}5 z{OYI3=>5<|#YLqnJ}=Y<%QB$cHj;eSd|gSFw2^GT!pergW-qkgAYJb#U5LwDov|$F8N2XFZ+1Pp8Q;W;%x6(qpH@8G1+&6L;GU5G zSoDX=_jCJkOvBTfV<=*MVyYgq=jy{~!`V|j$db}w^phP6G-0_y-ZH6H8kN^uKCPm< z^mbAioSPk{dydi3b6<^Jeti&)e9$A^Hz1Fa8zpN|xXknXD<>?K!sFV6G!fF^q^=@1 z*ZboT~b|`pAtYlL_I|RSXts; zH(K)fAg@_IxpjGC>j2xNJELp#_REl^*8~l0QUFcV3l5K)F`yrt%8NQgH5X-_idq;W zX31q_gmg7H3JH`;U?*ueO;E6jD2zmIb>VIi+7W9x-sTBTSk0%>UI1BBFv%NTwA?u{prD{A_2Wt zb^`0(<{_3MiiA<5;|(!(&+e0t@l!bZ-D4PB(eldc-||#1_feAKHx36^?@ImJX8Ca` z9^dZ$;QRhSq3s)fz;Wg;m@@keP^)9_{ z=q`rU(9OIF?}T6}W9`>pV@mKs1qF_F!sp*DK9O+5c=Nft=-Ia-LSkou9jaif?SI1DKS)@FV5NnZ@$&J|{n4h~|+d*K=%V_CLRc-dZ~#QD`Qt7a;RUi+v#+ zqw*Ww^hC=5hJ#2E%KJ#nP%sLv8$o+Yk87 zeD{;Crc1eIBp2x;DqU~zZP9~gD^U8vOZBH=`$KHazHPp=f^Wjr%OS3HlA_jkUOwC- zjDCz??S2o-1y`ADTj&w1Jf1UlZm2=f!VOLo0kvePge*}0}c(d-8KXwDbzvyShFZAeYR*XPDQglphdtaD^TGS7N}Bd#M#j}@hw>tcz< z(@>XAcF==s^|;W8(UZjsR(8A|7Q$qV|Gx66&_bC-qvW%UH#ahAqWXqhIeGf;WdW}V zDi3k7;Oe+e+^s@!K{5V**pcFgGzZF`KfF$hn|m87Ph%LNm<`F0zfS-|0D0x0Qf@{7 z{a>5on`y zCt9mRH8h&dA-5c0%?xd$x*OhNFwMD0C8<1TP!C25qhNiq|N4mc1zKIDsQ|JR{kenr zOo`sOp7OKmBtJN1SxuDGkYA!~)c-tyT8x^JbH6v^Y=9pAjgS_3> z3DtLMkGg8w*%K<2J5Qh+Mvx)kVeT_P){ zpBUa3B3#E&dVbYM?jm&*6@NPE(&Di%JIX-!!2*}VBB ziLnC-Wu&TuX=j;z<51xE)Y+0DqclBnyJ)2BTG3kHSs~K1wG%ST2*)i7q`UUvsYiJm zc{i8`GkB-E_B%f*vC&0tp=%P9xPvbiNyNNDNphJl`JCy3!OiZ++T5?4xekkaZ;x6m za$}-I;hAiZ`E49}t4~}Vq{vvPcK7Gs+t0p}T}+&{;NLTlb*7x3Zs~WAl8X#-WnxlW zzAug@a~2LPP%;pfQTE6k%q_i|%C*N+Q}a{4Gfy58v>4G?}T8hf>>s>}_R_CLTJg^|}pch^#e>sqUZ9t)=mRIAQ|GN9=7&~NT0D5u! z`~q#|@*E71eY#xaBncDUT<0*%yiuQ1!~fC zme6$dM{8QeV1W+o5z96f(|zPSD-jv4Z&bEY3`Mf>ycFi(jqc#-E711O6ifeoO3R9m z5mp!Y|K>CiU-Y59>0rHVbJSjvYWx^~vjWO30R5x2{}`wD>@Wp>mAK86HX+t{6_3Ac zhW|&S*q?;xeIxWV8-oy8KfCz^C*qF26j{6XfMsvS>9n|t{q6za=3WF3th zu~`?5OCpPW69NS3rmK&@^95?BIq>^XRGRM)0*NwVU zzW(@BUZk9gd}yg6TAN-dceW&7FB};>0UwGKA@2K4Im`b}8jBW#js}~33(^{B#=`V= zC1dMSY;z{GTbI68y}s>w)32|&HD+5;vlb-&BI0~~rYGjKPJUndp%3-D%W)}BfqZ)D zNaIW;G-i?u3xb=3*y3KHjuBqRS)V_lk!y!& zr3!wMEGdQkPPeio$2~<-zP+H$p2z<8Uih0{^Y*+@TXx5JpfN24n+V6=Yb4zmO-%7P zd&iG=+B10&p+hu0#KmDEiYZ8lB$=l*ouF;P=w{+Pz8@~ozOtWlsHUOrVj`_!a?wB$ zb(D%dvaY%Wls#9;|6q7xf70i|JFdwxv%w1H2?mKQ{#$*6h#E*k&YOBwM^lTg!lm+eh;tbM5PQ9SE5i zDeVA?V?gcc;O3SpT3Lx7QF-V$%y62I^a36E7${2=_~L7_>4W;R-VN`{6PBsS_o#9* zPwA9P2dEXx1EqJD>OMdw(p>qmCBlLmM>~Os4vP>LF@3@Ds=e@fst?}wggRaxCIKHz zEE#Gd+id7{Uj;(McC*#HuLhG-*tk5}YxqA*;@r0XxV9e#p*EVa2s^eiqSBXc?{jJu z*Dz4{65n&ck~h;E#Srf#=hdoUZMqQ6myfk*O%oVt!>dFnk_^J4$`fR*_@E3Yz%8mY0XXn@8;o@caE#ejR zlJWpXjZ)6kr_nc7x~K(I8}4AP^-^}OdMHHS-#2$rIzA|EW*J#kP%Z3~$)w<9WC*;I z7TA=?P^@2C7na!!dqKO~Y7ugrv?6AT(VLW9xo+Xp4Za$3S<~v=?dg0aTM}OzBj=~6 zBtu^rbl~4WELn8({_f8aQl9Wsr&2?vJ+vtWOQ9r7Pl`A@uF7pyPfK>8S(^_AUK!h2WWX6x zJGp(b<2P3g52~0<4r_>fQK<=AL!(WQxR>ygc6KJ-(bwm_^wmX;cSsJI$?IMrVOH8i#BcM(xnFHc^Qi zbTa0;H8lp=Z!i+GXIN0t4q06muy!?;_tJP@lr1o6nhv%KS6^G-5bxh{mf>Zdy4Nxf zpG3kNDr?*S<{wqs*49YB>p9e<@I~*PRbFd6_mexc25}laD-?FEj>bpA5qZk;9`F~( z@TxoYZF{cqkB6+-ORF^pa;XLz`zObx(fs|5Y830+44L-FHtFmr`EV)g`BSG(BcAjd z_T{Db=Q}6ZjM1NHSmMg8bh^MoSR0-=Qgq@vS_T!1!h4lU!QFd1Xx5J-$X~EQrQy?z?S>}YkkJ*oVO%fKdsO{t z0De!bZnLk^BpsHwUP#Sa6Qe|$WWUcL#VCNJld-FnxG>LFoISa7!=lP0Z=j_azD>un zabuypEn5b@XR*Ebr8rSGJ#hew%B?0rI}Np+8bU|4alnreuAC=mZ9TA-uZlV1B2F%M z9i0j5w(Q0WFcFtXoD#8cwFslPqExKLjX@Q;O4rIfAs5uwiU|m zf=8_?!NV)Kjq1hMfyHQ#M@W){zh8HbW{T~mLbrMaGA41ZW45hx5Byo%yo-}vl*55m zx5}7@1T^ ziQc*>Rbu@$Rh&TKcD;OfUnt^c9?fQ*K@V`SE$ILPs^=&S~E*{6p!v zv-O)|i*JNTN^7|Ba)ecpfyTV^)h=I>C1n1U z6mj3P<`Z&#le}9-Z}IxJmMrRFub1c04KJF3*U^IEc!-{&nP~UzFW`Eky}o=LZ#J*U{b<-^ zaEl>PHjU+za#6=^Q?-D{ZwunOu8Ctehf+&~DbE)OR>Wu(R}Wj&;1GZQsO#CT4?Av8 z3mDlzO>1NcM%jr>dBa^GNPd4wze#Q-ZAfGEt~0ra{JmE$4;Wsj399)w0Wu5zec|G? zHRaM@hPStzI@Pi_4ko&@rEG>^>%^)O)Z@#OxG^2u>R%LM?NS#=8F@)wQ#W^~c3LA_ zsyw+WR*jopC*5K2%54_EuBFF8CUbA#CMix>Ca)rxV%IlVIY7%c7=`YS7Orc+Vl$?O zmr84@mkJ}L?W$$Qz7aLFQ(Wd|h92cwvQxV`J}R!LDzABOSYBc|V!oLf=!G-#@S1;@ z%6h`OsHF6qr)R}c%8hP!)WWNe>ljjQ9j_t%w^1Vu-V(IhN!lM%-5k-KGprbX((P_L zSGl?Av}&b)mzGP4pV@EI*s&03&_@95BCO?`^^E7?cjcyCL^b%ejkK>XX`y2b-STx7 zMjtObo;-`;t$OzOEaS;`sADHyUeu7aSnSHE$~t%;bC3>dd*>q?D|-AfR74xcI_j*> zbY^lz%w>mr<)RuIP&mKarIBKMkXIuM_n-HCZNsPNbNUKQ*swi>DeXE^>2diORqT(u zXqF#Ufti$=h(gz^=QFFGL_~{@t@9~mr-`zqlzP1Qcdo4SZV&D#*u2wfFnTLv-H2jH zu3|vrC(9_7k~V%7C{yO&RT1lFGQDgT_n5~?j%H@gX#@C*4OPe$622wuiA?d`$Y?&JGrF6^FCakea-D1JS7^v96nF_JR z*FIHN8FbdQ-0*}JcJ%9X74ngwKdw~yf=?iZ8H!dVxT{gzp-=3Dn8Qv)TS`r%k&_YIl?f&dJg>KY zZ%>|v+ciY^47aehDQg&?4SNQ1O=OGr0LN_TfRND3?(K{}Q04(VnA(%mSvq@}xIJ!ks7dvA5` zXUEy+{hjlD=j=a>>BKSS9Al1q+;Lsk;F26a)8$jHfdp<3%#u8X$h<}AUqeyjLM=7A zX<)<%3^Zp%+%=?w_f2~^zK%-`1V(HzOe5D#&l=t!Z)Y7d^o2tB1(gz>k%S>-)RGNA|d@_h^$N7M&(nl?~~Ns8-cxpGDQOw+?(b~!n| zFm3!|P4fukjP)2lAy(Z2?oEh&9w&#zaw4~yBQt3tql$A6n`1_ves*1Ds9N7MmJh_e z_~?Y?Lb%i!?%;9#JF{KlHoe_VqSr;=^6&F>4v@u%)|C+LJ<4@>^T>0$aKuQtHYqY< z%G+{E;r;_H)izZA_N?~KoM?5TjD6ULEH28d=mlI$e8W!(@JPh&J&wcr*$KX*p11nRN3s1yRZ+s3(0>05tW5bD@oST2P6Fnf&{IpNfcDXZC z)}CcVs3nR{F*E|!vy!Is6J6G>(Xo#))?^=8}gaIW)n@*T8RYYx1bbAjX+(#k;X@p<)uAn+D3S+C+OVqD5r)1I0`XV?_-s)A@Byqc>6HX{M4tsWAkcp~`fEa3k=+mAoV})W~(6jr`aQ}(?!hk^u+;MZba2JRxHVw-VnV$`YLrFktp80NP?Uc`+UY_|p+6S!-WSk0K4@ zbnak^Je47s;s#=iE{sRnMSv(l1mNtZ?t+ETjf2 zH8(wSCz>9hy;l~VwE{nC`JR?3)vI8V%;ow-NvD6^!^Y%z(v>LH7+=8oAS^iyG@>0x z_7-LF12itEzhkvdb0iVh z$(#@uGTNtNr1j2UXm=Zwb%E( zq%5-%sJbT)kOpM5$J`dRNnbX3FbotM7S*q>4rJsaU>qI{z@~F?1nKdm%+5Jhp9V5RtKbNd|1|r* zVGsZl#@Hsi7eH_im7AxRtj3sh_ONX9PZKsHSHtRUhGdbq?Y&w++|3kDTTa78$x&&} z$R9_x2*oFKz8*&?zBs~isA_)k1)o5aS zopvPdgK@bzmx>d8fTcn@01YhSA)_AvjDRTLmOx z*8XAa_U|Gh|IV-EUsk#rP@?%^1;Xo}M|SJV!$h3Gv({jMI9`+VPu+C#OHD)051HGp z^{gIBjf2I+;p4K4&+vA?tOktPbSVrx^|UVqal z*+YIF#+h4j&oSsAk&h!32Q4@*oJ>xsoFB0F_>86C zlklQOWzt+t+@)irijfX+X2d%Q(2aK!G1Spc!|`;M)81=6?psn%i0z80kyIc-FPI3y z>N@I%FH%F;(5WQ4-b`;OS_`Ig+~|p_&tFHvjGFr)rmF#2HtL>(n{Y(vErhNalRIg=L?@_`mD zzK2_g!ljpj*jfg__So0xD%R>+(Uvl!KH>2elQmVYThXMHIw$WNL<)OJF(I-eeZ5nE zc1QNjb@DPvrY`baDnI_EQC00wi7f@C=yTL7gN8m-?h$$Jkw<8JU5QV!DdxHhi~GqU zUR~=B@$WHZq_YOK-z>8GrA9OOO`Y!9w$KqN&glnFaWHAE?0>SO$``F-bVLGkW;> z^Skaj>}!|3v%1VA+!=Oc>R1Fzxac5qWeY(=zA4a$er}>8SwYsZmkDW;+jLL#M$auU zB^RkI-QEs(nAjt*g8UJeF3Z6R)h%J0+ATLYLzQ9`b9y$BxMqpi{tJ9h{gUQ`xfP^n zg%OTk)VU@3JZWi)9N2n!@s`PM*>Bl2#!&k$oS7(FBSv+!Fd2z3Pd4uyO#jCI3erFl zp?wX#Ov2xnKj({jBw_e`v09=yl(MNNf;jU#rNwJ|01yH(kQm+x z>p7w-c&l`NJTY>j+3;>R*@|gMQ_bwg_`!P*t75{z9)M2MFp8ZBaesd0Qz!5+>_k@n z<&4s%X7a#A7s|P;bPt*U=C-*$c`U*QU&^Zh#8=gJ9ZH|j8a|kYbn#-(MV(7;&wkY0 zHsX^kr%rUHRMsXN*`#cu+@=woC4xdI;gD6y0>VKEm>sS*b}h_J zu36{(En?>#tTo{3E5uzL0{&eOFIoz_z4?Z2KC7g&CjCP(S#Pkor>a_#Vr_^@{bX*E z?evh74E7uOp+Xhbk!P%}p4YP}-?(@qHbc3zbatwjB+8(aJ+AM+P-VAdGD{wZqGH3r zK9at`FLs4jd8be_r7U+ue4b;Qqwn3y(sC-^EU5Seiv-V6ZGP>x0p9*;?5zF{P$6&k zG1XpLht&hbG_e`#M*qcSsf|eLwA+S+1$YXBw32iHaq*~qs&-YaNiD~bIPm(DyZ`Y> zuf8Tl%+o2u7(;6%6yzm|)WRfqMme_6bGc#F{62Iy_My2ciqn${$M!RG6U2h2JzKTm zh&+M83y(Q5YH^N{DPx_$`u@LxSgGE4%pcj`M(Jc1S)79nCzvu%n5hgtxHW!QkFH!> ze;+rM&ilw01S+YStFEM5)By~R*uM;i|HX;_HC2`BhF!;|W+_uboUYv{oJsttg6Edk zC~`t)vMCne%jAct+3LufdqF6rW;E75gQB?()V~e0A@i zIIaKaK8l(`ZRdh`AfiRX=*^BCtgiuf3;qCXJ8?gXSPW{Fi5r!l*UttY*uHl2AV6lH zkBZN@x{NGkStOOt=+-|5+5fJWHGVXO@~?Zh|Ki?uUt|-5V=a|Znp?18^it)F!0%No z>$-_TX~WKeFi!Vcge^mVH`$LL#XIczw0+r{^JM#kxdm2iwYUo(-x>BW|G_0TLDX)I@n z!AGCo0(_vzds?L>#&F=m)5p(46d4jQyOf%El$-w&+Ss%qP6i|Ben#|jooV)Os!n`= zsyfNYnxc1%ewBo&K>y@QjUmLV`25ME&H0Px3rB@R`WH|6FP<+*>ZQaFSDF7$F10YG zqT{r>r`eZ=1zKCt{W#%zN-`XA4GVI5;>??Ii=o_GYF7X8(f{WHl~P@Mm?$pz zY(Re_q3p+G_0I&el(z3-x5~G?UTw&$ln$dU8xs9rSnJ>I02&%8OppqQS@mz8m1zx( z11y>q{p)prY4~uu)U>hGm9<3`h*lAScoYypA|)37o?iyzfcxMezsuxF^eTK`^aZ!i zfjCQ4{fIRCPL}i!eN^?^Kh8v3z*u5$V=yj#>`zR-Gg2vHDU2Er;KReGxhs;z!*Sr( zsO60#1Fm3C%Xtq(8yRB4Bd6gt8J?C%k*g{-T>039J9m>|@?GZoONl#@E)gJ|A(58R z%ni-N%Ge*rk3!-6+DGw)W>T4up|BXv&EDYz1mnptW$X8PLcH>+>nZE~t0eC;k)(u@ zYLJ)24bzGu(_3O*;Z>$BU<4tU_%%lc&{QC%+V-P_u06_(_{uDKx)o;pS@f&jVyErS zLFyg2CqnpRMB8&4oCWrPDU}CQU4fFQqE8o*dEjS-CUK0ia4)?=O}@l>wM0M$h02~i zNqVZe7n1nxiF;TgJSu-TKxmrP*YVfBa-PScXwY1FNQkev!IBAcnf&QCD-iP>O4uNtZ4DgT3K5WOUCs|BdyUvJj@Yz3JvQo5kuB)_t zL)H0`X$EoHw|?N!-X$lHeT910B1V{2EQ;8gI=Yp&zS}AJ;IB8wQ^y&uVP^TnRGvM& z`fmUIO0w4c^%C?@Wa|?4aI;`>o3jo}>!lk@;zgXtW3=1@@6yY!j>kDf>D&d2OCrX| ziCecdmY8G?@hFhby&YH51j;jyuuR+k!J-u=%F+(k`E>9_^-N(kEBjjidIzQ- zMqCSPfs7uSdo@LrY)@>JFx#yJ(YT+dV|+-EbBvVc0)X|Dvvdg2IirNf$ow196spw0eZeIxR*2lVK2zcRTp_R%qhcYU-QEvxe}dFyF&-8j{(aorSo z@C5G6E0~oot3B)LjWA14xE=Qu8-(RZVe$)DyJGT4%nCpy>IzlF@$N+7eVdu7t4H+M z)Nbur;?w3Sh*eb%b|kVGQgA#mwr3cn;7xRMfPU_9v+Dku{ydhGUL}EoBEVlTBzg6W zR{PTudBc0L!cT@Sc^#(KZuy$E3yBq2lCD=)v5%2m$l@7}qdn%+?RMQeS58FZw5DA6 z&@U6U`%LO4?aJYrmR@DQsExsq<8PxRHmsgB=eYSnewv2M$1r7=)adHAwehaU^-AN*&G47STa~?vvvn9a zfM)juV4mK>*TCi{ABU7?xU^O0v?!18YSUR)dNTKobfQUUoo^{AoNKg$C4fY{a-%EL zZGp(Zz|&Eh*)2_QZ|*0)PmTbD%2-~1yr3DXu7cEkpuR$tA&W_N@+EK>>EVwi^u2E; z;=RJRN7KnRUsti2mli(k6zay^0wp^Ui+6muClYI_&PcirPmrGgUA%GjXt#~t3^#j0&jBHdVo0z}ZNHa{HP>6JDad$@ zwQ+5}X=pjh5UIN;#u`dJMNBHmfF%>SLjU+yVJYl4(9Ah+imbg{+YHNTvv%}Flh0_) zr&_-#&wV|~j=s|oI*wsC*%@=lyH`!xA(Q)PWn-#j611R%ethn}EkNg#h4FbASGOk& zl4Dsd|Jq(@k%C^;?rH2C4(fw;aw=8I^Luho|f zfFG^P8HXQw83!XrAOXaGkF5 z3jrVlJ*R703z1`tDg{K@uIg2|Z~k7F0T`|KujzfZ{)NlV~jEKgygr9S}}}c zm}o5W9nQF{yJgR$P-_2?p2|Qw>cIkP3CcThupWm*%~d=@XqAQ z(SzXumy`DhSaQN}V#b44#2+a7^B&9bc}|*4Wk%WEh8G$=02K;$Z5|KvYuO4HIkNes zf8FFiiIF*1X!a^HdG`=+y`ztqH$X;#ka5zx$S4R9C~X9VgQ247_2eIr5?9}_t*!dA zAM8mRP_GVSNpkm$;o;v_%ifTk1o~?t&M@LpfYMuAzrl?)S4&snP!WQPSHt1Ay{)u@ zxu4Luo#Z+#M0Yr5w7*dE(51TQ%mU9O9p_DK+X-d zYQLv(d$__NYar;^iS2KooYlhba0>t}a0TMJ^O^^LyWGAHz%f+-wS-pvZ_+S|Q~jcx zpP2#EC{O@e*#J1#Ww(HL{Iedv3JZ7@whC*iKPe;a1_b$^3ZW0fZ2SR-94_>s1Dj(z zb%}&GN+(gQplp{d%}yjwZ>^?H0yj7J*BDi$;VuU3YQ&eKC4n7l#x%*oQdCoprGW>6 z8uxw0pjT5deU!Qb_~_^HMYj>cOs0bNDQxxc{d`n?3l8F*HxqDL9^LKX!ns7zUL%qS&f#yaCvk7sJxs(OoueXrAcLF5FG{9Eo9H7J zEsm)-=U;8}Zl!0nre1D(K~MZXA|(2a%LRuODCrT>9!RSmI@2`YO$HzMmECGlP}kjUd*S}~y4%d8O7G4Xfc%{@71B{^>P-v{tN zWUJ*oC0tGWart*iHxepUH8;lh>rVDD_>UbsO>TQ*CV?X8H3L5&;P519*l&9G<$A8T z^*d*$bQ4+-Rhn~x4o3fKi~>5IyKPyS9bVTHP5)ytoSN)&f$9cs`Vem8Sj77v>v0t< z-3h80$_e9X#tfxUHz|{PWHS+8CuKh04&vr8#^-yas&Ru8XWE3b9elR?N@9LBaX~aU zJHLUv(G|tN>StFiPuu0r=6&>Lv)CJJz%%C~w0iOB(y>1#ME}an`$$aU=+)d^dG_l? z!RL*22DUkk4YWzDtmIS+h25%k^@r){r*PxrI{87XDDRqOQbsZ7x3s8ox!AQzA#=g9 z$1jFR54!Q;k%t~hwNv^H+ss|YiM6$aP4sF`?%SEY8x6y^i&>KV4b)crNctv{7A=CF zfs+N}Tiji9-^}YPq3Y`M#Ux3e!SKzYjw`{foyd@h96^S|?X9xHI!N9-98>W|u9z#4 z_ogB?tCWw0_t8MsiW*OP-`br*tCqAh=9etl`H?SVJVFF*!orM&1G%r_k9Rs&pNr4- zD#{dEmvB$2O^Rb)WfQ-Uayuq6&HQ{1KEPi;oqIC?hW?e9*`-FE)N)n3OhT^Sn{!sO zt)->Of@!5@hX0!iJ)SXR3C8DkR9jUa>63t%!Zw<~OK$67+ou^UDZ1^DlxFjU^uU8F z=N)0fcy+Fv%bIOLrm0&Y50kni&Ig1HrAtObuPl!54^%9$WnT30zbWqaeseZm0GD-?N#c1v0^Gc_p0K8prZS|8zrpmrL7uyuy@A>}+&T68H;S$|b8u>znZWVc zj$ zSwP;0yYtDq^9fF@SWaWtOXiwZ+AxVCZNRIh#5Al&J7Ng*0k;$g@T%2ImlWs@zOgx$ zw>mGamco}9kuFI<>mzyw7c$$b^^Z?OsC0o`Ap?c;SvqjC%5`~F6aUPp2MP*-_F&>J z*C2fCJ$vH#Sn++|RRJfmpV5NfaTM5v*RkMli--#qaNtZT>el7zEe3ppSBh4t&$jVB9WKb=y9Dcmj~;i5ewBPltm>B%7m( zY<%`J3dv7wI8G)4l0e;6D1wao#(w|H5a!p%LLsTCo|A1;oaTdZK6`C?h`VQJy>gyY zh;!ho_e!+JI{x?i7M+04QdTA)4<%F~lB$ zFW;}-Q$RKjN3RfEJ;|3rsE%iU2_J-(KpFjDYyPZoZeo4x-av{Ga~b|FK` zJ=o?)XJs;Jp4)^)MjFfXkppZ6mDiIIbgHgz^VB#J)?Q<)KL=Evh@rP9A+Rff~7ya0))2c`d;8Nj|?jUr*2SiB}!F_JZ7z=#p9I z1jF0Uo2;h{ea3wUf^o~b+Ml@2*)6RN3&|$4J~rZE2|!{gTy4i~CHnYA`y4OuHUOl= zVay`HC*%en#KAbgof2+977Fl8+vG1Nuk*B_KrX|Ege^{u=TeY#aUN>*&e_nuSX*b% zje||LLQf0^ailePIG%Mia24hpl|oRWe;DOn(_0{C#}r(E8X4i~f@oG>Z;5@S?K6VA zx~^A_;nzdRV+Aa_z{mrb2cRh9m2s2?6>o6>-VcCLQ| z`G((+KCt>|r7%Cjagsl`UH>Fk-I{{%!xLrl;{ois2DWG&o`G`C@FQ?%8*$4R#~tQ~ z`|BBPVvc!Peydk)W(v#remB*@G~ARydH<+iNCg9YkCGeYtPGHR)Yh$UYZMY=9&za#30Y-x-OPT)-qR{hwojfP^ZRBI1=3ZdVv#8} zXo9&fD*x_BK^0J(24n|z6x;`7wXb0{w7p*kvy+_`2&L2}fpD%Qm@Cllrn?a_s(z0xD1--~2ifuFdCjN%lTTe@)2ROA$YzRJUBOD^HB#Bqg z@XOi*d`kXA(WMhDOzAqU@R`HKp1OWQ4>!g9V}yW21uksEcIsyIOUZpeE-6*$q91_W z2rW|p*`{=WYXzmbwY-xnuZPvjpW@BZ;a|%Kw@BsYzq6!Dk1PDL|M*+})(ZNTpQZS+{CxR2<;TjJ$dQeiFUub`W9_*t5MR>zsoY1%WQtob zrat(2rTsDl{8Z{CuyRtJ-0<2%=-c2@{ug9`pM|M{Vn{rdVeTF%OUibo9bkF_D?JQ@ z?5WN}(HFJ61htW)<_>I4BhLb5YGmoN(0??SCHC7h^=m@qliLn@&uW0@a(mfUslUs;Uu%p1 zIf8RlId)|S{DDrM!qdKCY2so&n4rHrt%a(5!F^C3ASRImX#RET5UxpdW>!06)^`qV zYJ0oG8<-jak%$c1Kdr;4UuF~+vv^9LK&k|+O?8bnZS#C53P;QZCo%<`KVMAfzVGsY z%)+D}N|X4pso5Z+(J-9Im~vYFvAe$Nk?vlnm6V~eC2`ttS@kFOQOYH|G1M@{dxZ}l z2y4?c^vFVg>FC!_$6Kxt)+l|!Hv7rv>64E~j{~HlRHPJ`0^O9n(^fDzyaw0p(2_>4 zt2^ldS$?$|Cft?5F5Jfh#62GjxzjfXOd>7!O*Qew{@cu#?x+~2X&LdB{8 z`=qRtrEKEc>zaRH&{>M6NoVPZnQ(@GF_yr7|5M9T+adq={>+ovYyKw*>$$TLlreLa zF-)N(+EP8Uh70A7*xPBi`w&!qcBxdTrZ*tRwsubgyD5(l3FRq<^mv}P-o*fNO=E(y zuv?Z(HTD8}rJ9JMsR)fFYGRzmpYJLDe4(_-5dA5;4xmlFUI4hd|MkC>0DUS;$SFE7 zvk(**wsQ!1$V)r$&;Rtx#s8N3Vx~Zy>;`vI3!tH0qO&6i#A&4cW2 zBKppVoCFitnb#O5DF}+0lbEo`q(B%rbn$b&`1l70BXn?v7369i%{!5~K!Q};-Da3G_%U`h#IIxPEq zO^3h4M&|0RSVSWQ1YEHxg;pZr);gm!|NemRS^H+u%@mx=4|J(j-ozk64h5^Y?)Y2^D zN6#EoMfe?K<>=6-O6*r|7z$O(GSe+dOoNOVKES?iLF z8kxrpi2x&xc0lnh*}cIA2M0tAza6!e@w&T|J>Hk4qb_6if`8Pue$1 zMwj1MCipMvia|ym8Ji3;mNm{Ma1)$%T;#Lp?>P0Ocu^q0~x-OgbtOs3Xowdul>Mqn~4(w(z2009nR6%th$~E%_g1zLi+R2sb*bT`KgF0;0h!p;h0VgrL z@)V4Ae|&FcI^82xi_jS%ve^(7@i0%^qgP3ePXT4921Xf1=%KgWbNqk;<73b?N>j6~ z5@#jx8*_?@lHL_diZ}(X>(_@8wj7R`Ot?}G4N6`^=1i$;sBXhrB&0zrE=|o%jWOZi z*7*Fdl^;zNYlV9x_)V@)yQ(af%UP&`&o|&bYWfN*tJXk`gwbc9M@|BT2ztTdiP&zT z%Vq?ujrWs2e~r1qk}p2TRkWP*;!M0^?QB-5V*@jy_ra;r!p8#QP0`+vJ16~hWfe~S zWAu6;Cn|GWY_(`(1S~Vw-@)qtMDFUzlb@5b2|p3)a7unh+8ew74J{r9cnHz(;Mw7N zSX5-Dev@E={P&al0)IcMDOnKb=6duF9Ce3*rT};We9iM^BIqL6sjn233Q%qZpjx*B6E=_#5ws>EChmhQ%yVp z8zYQoQOwP!(P{UPdFJY3lV_7)?PxB)#U&wis7Qt$ZJCe!_*$2%2|2nys(U zvrsc>h(JzFi1Fh#Y6jGO$Ih=6?k6Nr#ljPo_&Go3lXLLuE>9>e(|z~6hOuic4u7Lj z(iF|TK@)MOP?Cv|mcr@LO7oLY&h(&e>RPfJw1V4fAY$|BCN%^+&kPOl!RMlHMVm=Z zjTE0N&Ix6qM?2_uH`tILcOhXd9mApi_K&x#ppnzdU-;WSjiOvMw4bLj3i` zB78@K-BLaIAm^mtI`hPUQ-_aj1)-RmQ0M#Qsh9aV&Xng2PixF*&8at768zX6KXUN7 zaE_dcUz>2-yNvqMb6yVySYEE+zdU))E@#Hc_qV~>&ZR&vMp}e zT31fQ1vT=-s|p^UejD$pAR!V`1%8)bf40MrWUDt>)fDvNa0**Jub-qhWt166 zuGuw@-g?Ud1Ryk0J0RhZQ3N?yF237|A1~!-Rg#&%Gb4PHCO31fVo3vP%~TiE5cLSR znfru4;^y+4nYFc4DZcDYTE=`ikhs{kzqz!yae?06{ob5M_jG<5SBT4^)txbHzOEq+ zbIbRnEKTDrCVRhvNYq2Yb6AMufLLLj-^#F?dduRuM?vJ$GG3}AQ?|v?8QFS%|Q^h(F4Kc;9rM9d4sGn}-M^;r`o)PS22t)bk`@ zWj_Aptnak4X@&`be6|+&gZbVp_~eZ1?v~?6o0-`qu>x-aI}HBII884;-CxmF!;W21 zS8k>skrbjUZGvQj`;5>p@nHVeyp>VaiD?9RbTV@idWAA9S4i_fwwwy4`uykErGnh% z4M2`p22LmWr>8Og_ZLvrmx)`uD+0^OTg8a_-Gar#v-B6beMJC5`0RY1&W~-n;-{m~ zMK54N`$B+s&pV-y*Y6|w_Ew1Ns_MV+*!&MiYnxA~T+%hZJhbaDaJ?adiz?uN%X+C0 z=AJm*-BMYoiA*I)j$N;#U~Yt?bh6GCgoy@u)+_h^w(#B^PR4obII~>>2<@gLpe4Xp zfY;e?rd*r-dFiWN%@1&tQCa}mEQ_gYkRzIbQ^uDxDw-tKct=Ts18g57I95883762v z!|!-!31|8v8UdJZ%rhdJp9pnYs=V|0bBx!!a>|iNBU}?wFF1lbUSg}@(j2KiI7NH1 zqyA2{al*!I$`JI@gQ|*S+%MIzuW#Fvbb~YVexdS=lP*Tp34QfO8D z&yRSoVZ5e0Xjzwc?8W)YbhL1@7DlSLIFCrfZ7Yvp&Bny(Meqh*Wt~NN53@pNo*AL& za*v>WJlv?kec4b*TgF8Pkf~(-Q=`Hdme;nCF(!$gstK(T#h7X+7Kt1>sj2k7NYBl3 z{@^_T65`)JkTgC2pC@7bFI{}+AYy^Ng$@E>97gsB1$T$w-x-MiFE>gy1%Qjkg?3iZ z@1E3-EPc@xxckIZGnB7J_I8wiR>sk0R^ffVDXpXsttnYRv=bpkGy{@e=pJ=V*xbfG zJ6i*loe97Hd;Yj>Fz>f4%?VGY5zkXq)soLS=Y)`}vlKwtOz;y>#}KRrL#q{gpASlZ zBy3&?MYa^2xLr*(-U_Rx95PDjZ)#$}L%Mq^hrT)N;_c)e(|;!EW}t*gWe!ckcVl&b`XUEC=F{}hGdC2+K-wo82O&-y6SES0IxubJO>-4|x3d-vVm_ zw?f#O`pIvEpr$=D{7&N29eaLT${o({L@4WLUvb4R*irUx!jqBaQ4Lj5mOjdHel$Hm z*9cBM+4i`8C|FN*uHdaEG}K2Z#$5mKT5r7x(1}26djVyJrbMOqA_)Z3gFos!Hf ztVT z6wSi4%uhw&S^vG*5n?^$WVM%54-hT2)Hd*=7`x(TXCu?-%l;C*+OJ%(^ka~QYybzy zivU~wpQRGvVqa916MZDzZPZ_vSHKZ1Y=;N(I=`P2^{+Cw0loBrTe=*9-Y`PN$y0Ju zrn<($){QE!gc}__lVY+fjXo%=*hwM$;MddsZJ}!LPQ?{T$xDy@gp~@c?Q>oPYr!Z> zk5Ww;@TQa{LpQbs1&M|}2d!WXu+w}@t`FwZx0BtXS?%W|v(Lz@~yt|dO zJ7H1QNYAOJkgyhgW0I1FZ$YPfOwXO}w{-E_ZkVB;1#FOL-W`a=+*AUgQ!BVXa`gHN zoGgGFww!h3_SS`za6x0sQ@TG-Qx;oY2`9<{9kUr!Ub zE7LN)&*9q?6xww2yovW!hBH3uUZc1+Qx6K+#Zz@WnKWCR0B_?03#@Gt+Qvi!!!XNr z1piF@6(kVqsh{JhlD9awE<%LdyvpHjfP(*y&Sdgs{~JSr2AKueiQxx4SCkjx3#*1j zkh42ausU&+Ms~|P-BuEo!}6Tc6n8rnsr;=iTb?d6`I;9eIYgXrZYp+<_}fDAv?pv< zDjO%WGz=$zViS+oBHMIGLP5sIAy$HRLJc@tKJ`2EMWp9y(Ca;zLBcdpkOBDppfh@g zo?36-QL)464L`SRO&w_cXX?cLK62RScY87ATLH!wrOs*VehZR58jo%|v|i20Cgy^x z#iPs}UCpW|jze~fDpkV8rI|O?yo)6XTb*TOcwPe&79E)$c9KTgEyy~(GA``>Xi3&u zF7}-IhH-@H7Q#XvlFYS#f+X6^b8{z)#@Ain6cTiFvtuhwBVx3HFm-e2=^iV9%f9G=?I5&PJ6p?ces=1n%iqN!)Eg4sHPFQ1&HA z>>R*=wQ}77QP@$=Zp?2WPx~7fu)8ZO3O~M!6*~AHPeE@j(c)pqy2r@Ee3bK8l%Dj&F#2_gNJ1v!1la={D5y$*pAn2AL;r!y9rB+_; zZ3V~Jwmg2K_`--kcPBf^TKR1$IN-TxA)Nh10+lkTPS ziz$xJuW#;13&t0p(WKM!mMJB z!wSJWKV0?jT^pD3@-W^7H#*tuEjQdG+*w}R+%a9-n-@;PrPa0|w6Ecu_X;=1JeB6Y zU7NlQ)YzIy?7VOKuHR325LLvWf#{y_2=7;we?ntF9hRHam|Sh0TxSy@C&LvNN5CvC zErnAK+MgE$O~;UwW1#=fe=S|(z7EV(4K zqKNf+_4(Bqh=McQJ??$6GswPOpw3D*LdPQ(NO2VkLbUTzZqKD#G}BLN)#TjPa8Y;z&y;-Fk;;|4y)?k zcOwQ4_B)*V05 z=k8uBpQOIKISRL1JTWi#*pZ$y4OqIXEG?VcA-me3f<_aFEQTKv`<@%|B?A&~re7|N zg(u6_1LVg}=QYe+Vl}?jMBpsSslJ7eMJG!St_4mWV-U;N(7wyqJy$#OPGrX>e5!h^ zuu9)R3hX3)z3>y6w(t^fjBVy*-wBUXB2w6-yt0r2(9boPlEiS&vtEMK-^o?^t0toG zxv$ByTjxqYyb32c6oyfQGL+Z=(Yl|c0sn=+YcxS`0~rB-F&;9^VD&QwQ8{uYv74SY zyPoyGQW5{=iD|(5a&UkzFOy)6;N8wzYla_0Z2GxvS6QYtuvLU!FR3N!yjP~W1C78( z=k!!kvEOSV3V)3*EO7VVV1Pc9aIv{rPS@6?u)%12H6HEY@y)X2uZY@8vwnN&BlBv( z+KmUqF85wt5W3YFzCEc`aZE*pYsb<1OU|WrnHv4>WBX$?;2aK--$07!Wfn5n;^x%& zp$ks0teme^W#{y%uAUlHe3uO#R@Cy;E6d%{x8T(bUT0c6UW>6kOlgJ3`Q(FeMv|S` z+F)T%Od%;6Zs0+;b(%M#PA-?FEve3}B!Xa2Ne2Jz!RlcN*f#0rd)7PKt*Jqr3EXN#G+7fh1Ff;XhO2gX-ts5K2VhHS(=2G$e z3%D8m?o$3RCk=^QTt?smh59S@GozMc37>{LdJ${P1Pbs#cgO)@(auttcb)$J_qqwz zE$xpMMgpP>nO0=pQ>yZ{jpM1&5X3n9%^#N6HHID#UWgk%6sLJx?P1Yy?k}>20;IAhA+)fU_3x$-Iobh)- z-DAP%b6-SA-`@XDd0YNN%3JvkFK#)WDz17ud3Q$0#2Xgo^RHJ)%>~BLP5UPP>Vyu( zdN{{#LUY&lcL+@2gJZydApQA*4`4KbuVC#w@Ruc5ttEdD*4BDI@YFoQbE7Yy7ejO#?29bzg;x zRODnBQJ_c;k?Vn)+9- zfs*k1_gdM18Oon8^3&1)$M)dP1L^Dvtk3Dt1U_##60MGKsa2gS2PhI|xM-#)S0Zjc zt9)LiHg_Al`!M?MNvb3E&pXN(<-PX&YO(!xAD153p0Imob8ESoyJ4i-y`|;8k4>ar z{L8ETa*>!ZdzLxh3^{|GwxZLePijUEs(L@Ru4{7XsYj6!=&oHzVzObvaJ#QA6Rb$4 z;Ly>I!~+-f8irFjWqL%_Qh#w>yO>uVhaN{czA)EInXfrr-%Wwbh-GlMY>B`UaLP2UDpY$4y+#HqMbLG?r~LIwSUdY4 zya$|JSkW(S|Ju{o{U-W?^R^V=pkEaIo7?ZlH~w@XjQg!P*son(Bn!|%UuyRB` zz6~N>xh@8vv&jJ?Ci6SgZA4L*Gy(ng5GZi6Tq^z_xTyv{uZw*?y6gHZ?<#6YLl0_q zcBZ6`2F(&c&*~T<3i#oz6k4|-O+MdKV)!x?&C|J9%2cD<^GsAw;9-S;1M3&*Q>(Wh zzC0o4$1Fqy(`yYkS4~v0^2=a5xLdru$LQEAP@GNHS%}pGFk)~p0cu3it?J)MQ9!>- z9V7p()NzLTNjb9hZM(w>3r9ps!x`4hMGj~^!;!bE}1Cn#hY*xG&r^;<$NlOtL@mT8Pe zox*#IIO9m~606sfjP7b#HuT-+=)lXohatBYQ9#xMu!}1e0Kj*rlk{Xs=oUT+po``t z>ITd!!AvhgU$WfN=sgBd)JC8vAL+xWBQ;&oZDp>KmZ-2Hf7J%K(`6a`>VOmmH~1T)er*E?&SnFJHe0}#NG!jBup}6p zk?Qhp2M;jA^#7_6p}!i6^(2GyDaZ%!6-Al9Zsf0qf~abjWG?B1rA7Kbo&@Wq~(9d1`Wn+4+qR#gl2nD?pID;HW`NmFyj{v6H&t3e* z;(sf7Kg-YMu|kTW(f@|>v85~8M(-Lc9-CC}(N`Nip}@`XvkuMw?iXRa{A;|anqB>> z0Fv5d;y~xlP($Jd)aVMc+>s4y5cM_U?;5Z=aVpa{kTHdLQ_hux>^u2qMT=mmr_rH{~Bk9#-exJN1|h8 zWj(CO?%;%FT*13;iji{R1;SVSs;?d&PJzQD6Fa{O+daj?@*{9;<{n|4%|c8Y?;m9D zno^N*hS%Xh;V?5Lu=s@5?in+auo)(Bv;OjU_RYHQT+6XH5>ke-aA`knVcY*;@2!L4 zYWj82A!vdG2=2iX+})Dk?(Xhx0Wt&vgux*=!QFjucXxMpcYDvuSGCXfy8G^1bqn;TZz3p0LqXDY-pVy2359)W2!PHHO$?ONB%Pb7A;+nG z^m_0Y9lJN3s}cRov0T$gzN91iPQu~)(g*w8uak`S$H$sVnz%z|q8NdM;X7~81XwK^ z;PC~b%pk=J0mY7|sU8`GDQ{Ut@fQ{)4-X@9J=-_ZfZwT87U)t$fGfR)B}0j36CHCJ ztl$8g4I?ulwEuKj`G4!@s~Ny9@qGyC!+i)~1CD)o2o%h5s=bl&eWsN#zEazWPikXP69zFEU&;tqPq-r zPI(ojRo$hO=cbR04w}4vLfc6XGXic@9)Cu}=tj<9a8b@RI5CJi(GfLm-sm$|qA_uL zBs!c-W8h^>ig(+2%*E8ChSag!AUXrp6=p$Szvx9J7`3GLZl(sSUNHh1d;07Gw1Z@& zXGcI*ro`b~oW0Udiv@4F5oBO5`H)*V<%aUs=Ds-?~PB~Z1nI$i8M`vAzr)*Z1b~#Y~oH zHdWVoC1Nu?O-G-+?rQwyX_W&*l(M@`b1w9`LX;@~+lrP&YY{jq#?tVk{%6W@)Zm+@ zXpx?Kf2N)KmzwymVdmKk#d{I_4_4a6Vxmi>=~wvu{S+s=v7}lD`5B!ez37vT`qL*I z8gT}S@s@2gq+GC3PxV)MilUlB|CL+0|I^QCO$u$X7z1@R7Vw@?vk%}nuO4Zcc7X>d zQ_B)suUPb201rR9ApGiY;Ee0~w`X|=-ZhWHDBfymq?d=d7aTjP`(RQN&2JxdSg&x# z%QjfwUX-zyN~Qgw*4-BT;ntOBLg?6p{|C&)|7eYXExyzJ3qx7r|;1bW8uf09CF;DjXIQ9i%N{gK3TQzN? zv@9d?6p-+holebJZ#ID+1iI5s!3 zPm^^GPUbI#TuFH2uP1P5KQbuYcz`R4v*K>RHO!D5af>z<>{>U8p1(j%ik+qo!hD6< zy!!rz_L#g>C-vs$_HZ*X3oC?9$=P9=a(9A8$We9aaBmx46FM{QqKdk4rjm>w8A^JK z=N>MeT;owx`N*LF>5Jc$RqyV+$K`BfBwoeB|ERPL0cvZhV$S(xRmu_ zQ>lMM>Gz`QD&cD=hlc4JLFZMc%jfNvxnZN~{OBkxNYG-s(zOmQN3*D+Qa2wuvGwVMQ9*>Gf4mowH zuy$Ybs7_dWL`$E!jThShC<7KJo5I?3F1XliCAyqEAsjvQ7f|q)`CnO7Eb$L@c&nA>w^qC(*VO?Oz~1 zMETee9LVZ<*lo2QDd51fRUf)cOy+~kPb-IDII}U!?l0>?1(_61vF#l z+DI6ZUtD&qDcD5;v0tGt{4Cekt-P%qimn0kJ=$V#)&8=a$On55!-Gc5=aU!n>;y+( zdYXMyo%r%Isrc^UXA~h zTPvJ@FLh-khqT~=s~nQqn1+6*-;pHdr^MjUQd>JF7j+sN=S-f3{rbjKg-|DQ#oF9r z&2F7vemxC!KlL3~lIZYNLqPKu;5|Kb#Gh-ioWO4nXT~{zQKKcy?6k}(z{pY3G(rNQ z8yiyl%G4uGOfA4B-%uNwZvc4t5v6X@qIH-RMds3hNi7U7rlQ;7s;xK?Bv5_ zOByi*UN0DJK3{4m^zOkc^}$SWVKnr#n0TggtBvO-`;6(aM7)?(7)69p*_cpazTNsM1*m;3cv&dq?uk-Eb`D zsa-EY$x&=BdBcYkUF-=DX{iYgIv*<^D^w}NJWZcc_VOr|TFNgU7o*Ar9o)f4N)F3( zYKxsMc)0P=`ix~aLPz=6d@hiU_w>T$2s8tRmGWquYlgKc$GKPP;6I#^ms4S_My5mi zOL1UHaU-A!I1%i*V6343+We@c`7xv(%N@ zjCLq|78mQYA(34^%|YlzD6Ji$`A$J2;kAq=&xM@Gr3ZcbW?>+|LdDrg)H|)tGR;Hg zWh<@FI0X@+pAn`|0}`WZ&p)J@R@#d@{L$g|BJ7E&jlI$q2AYnU7HqDhvYVonlA{^z zqut;Pqe46>STb%x-}$uU((QdMTtWB=@c|8k31_fbBU>z>(I>ZfnfW2y0PZW3@3Th7BfaPDY{e`$QlnCayZwY^i8 zo8%x?QY@3^=R_Bt7^K&3Q;sZZp7|j4!3@@|XX|^96K{!p#|p+o#>`0)s?*J?TwLGh zEnTt9FLgg!cAQ@?z!0%0$Zf-`>=drfj&$%JK(3nk)<;4Zrl)`3WUxESJJR!7<4d^B zWA?d!DsPcGRandpb#U+;<&XLylM0kZ zkv+$uC2QsAe=Io09bW}~2XX2fwWKX*GzJF-d7@MyKOR{NQA;K4IjX81xEy?#RU0)tnUBqTPPy5vSPp_^A4E zI#QP!OKvPEEV;i&KH*V2)Mkr|LsCzts5!uk?p|j-zwFbw`wxDOTub$dy|jfQM=Q;s zg%gS>DTYbyO=NP2f*BvUScs)=tQzs7*nF4Y?<5*N=;trW62w5HC<>H zJMH6jxO_Mr4 zkJ=x#QuQOwB>2wt$spBcx+7={e2`Q)tZ}|T&GLAv&zsjuC+zT*P#N#8wy@ccNXtFq z3M=vO1?`Hu4M=%+?)eK#mdpz)^V;nWiIYEMx2yBv{sLK0_8q+#kZ3L>%WZEN)mt1b z%D0rqYgg1u^9;z>L}sKCF9EzaxK}V(6OH9%IRotKMS9eM4e>$OIpMvUp)1QlK@#I` zbPGL&g9*AACLiLceo_$O*ftqA=WO>v=*wIrT$UyD_K*3U^et{~9JRzs&#NaovO8ER zTFjP^$TrES#OTL>h;a?tYxuxzSZqm7>LZ6=>dyA- zvM5@}gAujEmU+o_HJTYsVd9A-{4pfPe5!-A_{-4}eZ9;FUpa$0qq3=^vaB3dbS(E> zojqnVH4OCyHa&^qc#zw+m|@8bQljGk7aA|%=*wjbm>Ut9Vy}9{cYMPxZ;6l@ceM@) zlM@iN*{Km>pOC2kIFxUj`KImr1%mg<+Ift04++WHb68-kGzm1J-Sc^qDw1#M`(IEo z{gZYbX2zQlC^ThcfM-Wv2CR=vfm6CZ(bK>CPD^OLO#K1>A1dNBrYHA?)WJ>IrTI~+ z<}S{&Ca11#O+0frj6T8Z_9c(1E_L@az2(D)>|3{kLDa7JX!a-sJcD96VG957n*B7K zt2qvEM5M-YJi0WBpuy)rQ&4oF7bXH?eJP)sGnjUutFt5U(%Ab&TqFEC%gQi!R#Tp8Wloq6x94jLNV^n{VFM=eXX#npH-q zS?pe+^e_r|5-F@!xc{a_IR7TM^H;ysfh2`*9VWj8ajbLy8wt40 zS}`9{H!eZAD#(Tg+0Wtk~?dzX*v z1PCh+Pb?W0Z*$`X|8&u2E5$E%wL~G`K}t`O$VS11H~Kvm3S49l%B-b?gIF{@ygG|E zefXqxon$}Z+rc-5Jtwt$AFqFky;MjD|8{0-_jZ7LXxZ`-Fn8d}IUU=!J7si5?q@tb zp=zj)g-WuI=q^3P@yDpqa|~-sLF=Fs*V2o$cJVgni%b00%rOPj@`mG^mU zrE?1)D$c1S#Wi{sS~lpVIVjpz*J%-YjG-g!G7fn@cBRUfmwYH@SUU?ZKppvQPm+^! zps-l8A{W2T8$a*y2$C?eUd8TJz!IjXfBPMHV(!;*` z{3R=}o!?ZK`Y5a2G2=psR$yaK-wE!MO?KVY2fMHa>UGJu>V_*tAS zwr9ymG%SMO!7(7i($O0CVqw_nX4}?0l~dwJauWA~Y~BtY+y{Ih?b&i=IM^x*r=a*C zX?tMFS}S%ZiaL)TsOXLpvhR$v;w(>4QRDw#Ik2v)cQ zOVVuBS!$wt!G08Ho$ayx)urdIPA3+9DW%7dvG+hwLO*=APWb%VQCTM;)l?1M3BM$f zo0^jdrVev$SdOL9C9kx@PnEYD>fUGS6iIGX(Cg+_7G1W4$tFd{-+5M%$jI6uzm;ep zUiaB)qe$J7ur}Z2htjtSXd<1^K8BS-3+FAN1U{*Gp7y4$FD(mnK^oheq^$mdn=@Hc zM}f&jx|+y883US1@KRTV&j(=IOby!+ORPoF5`{Vs3u5Hv^A}cyOTJE4Fjms%8OUJ^ z13|Yuqugtv)1_+A3W>XTU0Xa$M6D^b1Q6gYC=`w0ZfxfEM~En^+?BLbkL75sHIk9v zi!o&B?sD-%Fr9_Fc;Si^{Yfxca-3hlZb5gts*!7isJwuH$JWpWTtC;MoPmWM0`Gk`3zq(_`%W022>uZN)dcjzZV z3nr>?+D@FgjGwTS(H_^7Qw20YrkGA14)mq92t5t`P+aR}j<@-K8u6*sCkMDgX#~>I z-F;SguQn3xOAlt;-PP5Sa*l9uzsK!ZloIPX^wJZ5A2hjeo~gYeru))zrkCegA~(Ze z>SI^rY7Z;V9zrgi@WV`0#uU~hQW&+r58I9j^yyaGhC|aN)|K{{#=@qPQb8hMGmU{f zRpnjv_fVp!9?K#=u-4*Jf2;oC=Y$y5R9Q4sI;7gMkz0UQ`+M%=cDQGoFk-HJiBf4H zP}n}}h6XTP<8g$kNf+$aL#TLNjClB)lbyVe(%-k!pw8lLGT3X~f$g(ATu=4&tGw&nv|QyiD6-A~wOy4N3b z5j6)1Q9VbfD#Ht}FVeRXBl;P(Jvdy&J;L=abj{_e{f6Yg31fqTCf8c9eKgr`f+7bw>&swKNNt5L=rU zgM1;|R=G?~*pr}#o<{_iFrL_zc#9T&c61Y|OXAyC-61o;HJG6FXj08lgELb7D(f={qGmsMPSbaW>tZsh@-Ve$87U&uue0|Krs4hQqO()uDbo&aq9$lulz?(GTa%v_p zdGoit)LG7mzfGa-367|_b#lZn?oJr=_<{YX7<~Tg5ta!L>rMhv2*1FFW(j@t>x?)_ zTS`mH*yHu3M)CM})#;#KM#CtHO(%?`t&v1qCSP^6;5WM32l}Rol@hU(p$(3yZxUA1 zcO9;B#vhoveAJ7c-rVZZ%$`=)OftC+OKr5j3aCyx5fA?KJcgd)xETI%^od50;d%8* zm0P1&I>wT1k~tph(sUtt^W^D^=6E=b8ZR2i zJ5sWWQ#^%)#yFDKI!Sg=zm6 zTwfzbkX%?HeYea$T2LErgBI6l@{9I9c+*n$hxD%1rN={-!$L#_YQY#Q%j@zxw6 z3l(Q%O=mhulU73J4LBFN;+C`lUn(dJVuw~N_vXmS>vimiqQEM5p4khQ$~tp*;Tt<9 z-*Y6WCckLcwi6v8zt+Z+R54G1;`I*8Y3Tt@0oVBqS`}fX9;d3aF4_XDo41Zyyu5Yw zb+PkNQUybmbvmy+gtJmpP)rY6$Y*NS(PueAo+Un~(H+Oja}I5CFUhfepPZ;E^X9X4 z_go*8MF7qO3*{iHI^T}Pr`^za5)=QhW_5g!cm0TkH75aTNww0R)^<$>Cv6zBm-J0bL)qkyag&Y*)2VZRGXl?MZ~yU{wYU~7#-;32|d}2D^l@E2>VUH z%LY$~&&B{6p}^%#!=il9SN1qeS@(^2P4Xm<)uUQE$9Kg_;&>*JGF*0-Srp%&G%4`e zv(FexnpWp$c?TJ*KFU(nRBG7;%y2ruN;hGfT`Ynq(9|hS);UWYOEgEJ!5lr~;EF}f zDYV2;pP$P@F`*|tL&t}say4qZ3QbLcD};mfyO3%AI!sMzdb*Tj1^EHCIdu`o^8k{)tfQ5erT4it*Yqesn|P@gy9kPrEdu!*iH{)fl|u^+TNE6)Nn)e4zoALO z#367gN4_Q6oFaf*klG~dA)$72dLf@q=<7R?y$W)E5C8hU{-bbjF2Y9%e%p;A^~B>Q z+2T*Ln4VSa?iU47X9zo;P7a{{E9{*02>3wC7)Yy1aWH0aE@cJL(j?YV5^Upem@gUX4G1UM3c4yb`3Ia9;+*`+^&6CxAPjor@ zTBCIAv&x@cj;$-k3cKd?S1KEPpS<&(Q+7iMEvQOcXCT|wX;^oDH#`(gv#xwUVl_=P z?I{fox^Up$^-+lkX1|rnG0fN7SFc#HjCY=27XKZyI56H|VzB-l&OzeIx?)O@R3kUv z#>Lk2WGnE2k1wyj;sS@^yy^Qa+O{u7ix^DbCeN^mbpt|F-rd(u)d`M}qU)Aa4YdzP za0o1Ty4^pc?)hdxCI%NG8)2q>KW))v)S;4t?w6H!z>&f%_clw2wI|paQ z2H~@{LTyvMBT-!3*`oGOr%bHiPx*RIyyj&}vN}`ilcengvfJUmZ?wy50)T5H1(77i|GDIsF6@Vb82pO7ec@C3viyOGsR zm*gc@0YhRsU5_BGmg)CXr>y2DPV^d3BfIw_%;678qT;v1_N-G$Nx-5aQi zOgkb(@z!2su~Wux^m!=0_jsu-m-(}MJua$Lo}&OK9k&@)>E{&eACHouq6zKRqv2pz-g#KyN2Tl<95gLOq@?jTeKuzn(e3)-I5 z!~rXUu#=Lnw@EqM-N#c2s{%tM6txHln!z-_@H&;}>OWl;-<#)IH~h}YS5t(;jV1^6 z(sTNUzMGway1a$AOgeI(&C<2jWnJ-DgJ}P%4b;^9RY65nFAB01AP(LPuS@Q1eOt^? zqIA=7*fmowY42v6X>E+s;W&DV#ojlPM}*WB>Vt?+0_Z4~n0#cAn#2swe)j|*B$^W} z^VwAeKaj781bF`|W<H_@51!1TrX9Z$qVtC+0StHR{sSk0dBPJ>XNjpGo4+uWlCfH zHN7WwMoB9oRmuy~Bm)P7AnK=ulN~;HhVL=~axZ?q;kj&WCVF=&wXRRr- z$s>b0Z5Pg&%nk79yaC7pT0*zHr~Dg%S+8I!q(KQ zSX`ybAlP-2> z{G{>X2mFW^bLq|BAgF|5Vqt@mk)y-b_-LC@t7gv97$eMNHN9-{}yhf;IfDWiR2ak;FmIZsmnxucf}Cc^DdK=-CADjh(LlbUw^pOzR=Vs)bxE1p6H0xuTHkTyR3g+TQfh|N+Ej1 zWv~xEd>Fg@N>?_)|32Fa$L*F&Yk9lcp7>ChswWzP_K^TBtD*q=n@y zr!|m~Tv|Z32F}vVPu$v`#wIEf52n6S&~TJ!H`E~R$`a8zDHF=ils9Lk4g}~)beLA9 zO1p6Gd~uWb{bGihp<~;}ZJ1&zv9|9)(;i1cj|TmE_0?s?0mA+1%gH?ca>cfo;T+P8 z7!6d$muubqDHav^r3HMWtZ)1$xbyCC-4}KvE)eU4)M{*e$1F_079g~TzDdiY^Ch$i)KG?`eg$H>%rtQrM~RAha`7QR*InAtr~e*b0&Q!K{Xzl3F~SfT6)oPis@9J0 zOp?oT9mQZy&{?V#4}G&C-eH|5TtpP2<;E-K{h$d_i+`fjs(of@S$xkc(H$rJJUZMs znd;-*2Alq>$|4t0k|v^NpL%l3e6oE~H+B4-WR1!Xs1mw3v`m1T|9YpWdlOX)75r$0 zkwyG9Hy zgtLA#1zpY*Gj-WxlCv^&$4xrT8W1y19sdrODSB*;eJ~6}YU`nk&y0;EbX#GZE^)DR zse5Ugslqh5tRA#9al3CZrV!I9Uzy|S8^y~%;a4nJ-j~i>dJfl!W)Cy<5rpMd?HS)a zx?~1{yq6Jp9W}9(VePfgzg2DEX)!2So2e%sV|wB!2%E;h**g<_aK7YXNX?t6s$P~l zl$bJVncTwA`6M?(Tgn56uKFDXi4t7|j)Utl>Alq!V zPxQxTmK(2a3Hpc|V#pMBp=tuSW5$9I&{E@hV1xNBf!yD-pRznmh0Wxe|8d3#3#KaDqe|@$+@T5_ z3l2Jy_p__xpzF|wW^FI;P?(@O@V=5HN@~r$Yi6+Jn721*X#ma_lz!4RO<%%P`zRAa z#cBMw4KFHSiLK)^gYpRp>><}-G_qc(g8SqFp+8ulVc8)=3T4}U19}1jAU=sVbv%k zH9oA}e4h4Q?BCRl-yWKhlB&^lCBg^^tu-#d)zJnSN}rtqf)VM9xgHr$F2L`0=Z+IEN_6 zUf*L>vo&yrN2}+(*}=`Ib?%~e6D5mb&1RSeYFCOmK2PC8Yw)$K(=u6W^s=EON+z8) zw{28PD6VO+3Y&p34RxhOI;!rwu74>r4O(>_R2cf zSat~Arw~^LaWQ|X1{~^%x`Af64;P$8O_QOe6CXxUx#plbQJ4ZRH$!_iev z)E9U4B0kCH+jsRwGGO;s7#}pxfe)+N-^(`2&_@B^sFg!5#bQ~fdyQXPUwq-ekcxu7 zVe5;|oO%o8m)s=YI65TET`q`ne?ofyOQIO|6#^bggjR+qRpuB;V{(*7uUg>Ajtc?! zL2Z;5Vd6Lmf$n$7R>D(xC(X{Aw?m#=Qw`?fHOC}kKD^f42}75qE{oQ_*RLYhs=mz9RG0cTLh{V#H`Oa3-#ZL_`>Ug})SM)+c(Ndm$&T zUWaDq=$6NZQ9I20{iq>Lp*%kQ81NUk^aEYrLvQmAUYHx2&zo0&UTtwk>tN#G-{`=9 zN=C7H1Mj-n^XBR>wPs{om~gY_;dGIvF3!txxT7ZmwfhHV2b?hy4(_MmYD|P_Jh<;u z6Z0OcI+Gb5#aoqOTI(kkGnRmzCEDx$@NLmq2}bj ziIPM2Lo&sr1GRk*gr%4%?FF_QbVZ5dE|WKzfg0M9H5QTzpUQvsmNTQQGAnrUU;G(Y zD^=&Ejiwx36-(`OOFGH9*2%Qyi!6uao@fnO8pixv13Cd_M zJnGm@C(X!#J)Ht0IkwQtnfikdnp$nPvKzxnKJe_8xblyfZ)4S^Yt<1!IG1o9L?PFND@RV2La&$?+7&_wDEwoGuo4$_TFAx~(`mwK8 zoR0nR6P=hU44fYp$a%!dhpYGNO%$DE-k|9_d_7Y@mtuD@UDb^ow>e0Ngz!yAi{2Jl=KDXlK! zyoquEd{aBgbJxdhsL5uuH4X%{n%vW{+&x_~6|ITfsQsfpe4l;MB{4@ia+EBTE#<=f zT@3I;Q~b(>2g>tFpqQcHA@{; zZV^|Sr^}9H&RkJ_gf}hd+pE0VbNJ^{h)aIUfX%|Xos^_0N~nomkk@+~w;o47F=jbu z+6;^0?*}I%g+jr4G?2R$s_FOzLbAPbLGWP=EZDWzR z`H6q>Jdi9-`k)C@kZ~8GaCQ{kpYt5bKUk5p(Sz&<1BcE(Wt$#Iwuz6JGQB87bQp)h z?-s4mRpM~_A&hk{!PFoliQITd{7tK~9Wx7nG;N21xZr+;vDQPNCU44d!wM+K%fi3? zyYEU!|47JDX3zf|cH&wsNbf&R0+$`d`hByB>bWmtLKmueKqX3}HL8p?Gw)AW>l^T& zuvQ@SZ)ohFlK=jveg54y|9R5m-+l9U-~4yx^WWpa_yRTi%FxK=S~rxzV?PRo!C53!5;Bi0Ie9Ku>J$5TQMubwH>82uLt`0H>yZ(?ZbS4g9+Y{~m*X zPm;fvng5v!HIQXLm0jT&-X1;&$Deca56dy1;)&Bz>FW?t8@h8^Z(7!-? zOn=Y-VEzFpl>QbcvpMet-?;~Th5HAJ0IMVbW5)j-`dPqs=a*Rm;GuJ#_6+|7{9Ewu zAJ77KGJ1@@_`Q$}`B0FA(Z(CGdz(A_ZU|A#iBA^$rPz!@0r z3I3eR?@2n(`XM(fYuMV{ndI&`H#VDZj;zh1?Vz(&>NWsS!~M%GK@5Q9f*cVKFQgCT z9|y)bhQ+nd1G7+^8Aw1fyfz@1-fi_A-`NX>qq z#Hq?tiw`6igSJ(|3oS`E#5?bqvYMk`5E{eWvX6~FM2Yhw%t!JFB^DLD<}7Yt>c{J7 zrp-->cK1#b zXL~%PFR=0e>hA&8ih$b{_=+gvFAz)~@ZwyY={>q2K~&xjO&Pa^Qn@0N*Tjz~2#o(@mNKZ`oAo~7N%zxYQ1hK}sOV6%(3lYgQC zUUna_%OL>2aEVhsBL3a-zx({}(ef`R^xre|@3rOcRq_AWsyM5t2Z(oo3HdK!@zDGQ zr_~R@Nj8A=R|P)D`e#rK!0rVAbM{RC83BBuX8%GSai{fy3_$Sci_|b6AXEI`fa`{( z4s3pq_1nQ$z;3Hwv-J)lv~GRJ^x`jcPY1})G5#43=M;6oPYhsq0O!pCLoYMHITqW_GvhN8fE{jBCsPK-#}Q!L%}Zw z^5$*v*o*6JmU~y}gog!R&p4aBm5iO(wxG8+5hklZ@ITD0iy726-Uf0Ea$g-YDPNxC z*82}e99;nRku2N4(0peOfZNN$Xse`F_Xl{M9%nno2d1gBRfy1q&yH>wut1iqP`^eWJkI8Epgyy6?@403fRjWIPtgN3l%9#2Z82w2ra~8qe@cPj zX)XV~4$JeB^$xax(=wtK<0EDU>U|@)ou@P1%2=ErqlSDetQ}gqQQz~NxLn0=*Ryn< zGUMtR)JF&= zU2WO-Dlq3lU?42N%0>s#F<2d=9g~MssW=;1eTi`TKq;k8h(pX0 z?YqQiyv`e5+Ivz~J13Hi>}eIcI+;a$5>P!SE=oH>CH5^p(CPPNrMrpAM=h^Km4>jS zN419F+I-VTl{ZmfT!l`WF_&RnpMazFr(RsO;_Ag_QO2Z^ceK^MOY(uRCI-IRsZHhk z!>)0H>=i-k_04tC<+HENF4-*_OSNcghl$dd@2Q+LQYG6cF+IA^dg{>v1die{_y-+d zeXbDhgmJ_QEgAh3RsJMC6VlSLi0Ut>zkHHC{0m;#A0~?Pol;`kh1F!Ofhny zD_U|oM$~b%P1_xYg-;Sl8hj#DEB{23@$g3xTnqb}#l*FV3e6p#^vg8>BC(j%cwO!8G zL?UljqwW)WPvLs%@)G55YA%=owl_6PHSHcM!jg>SVk3fyY1_Ijm=$ZaaD5$6KcBmK zY*J35rf+aMI^@`6t?4cK`aCYEaPTImW>T$NiU{WwTqw6bwZ0G%2LohoYBD9qPQImk$}hyg9))*H{-# z)VF~UQh99uT00XNW;CBGGk&`>ar1;mDm#AaYR^2M?Pb*Fp5zh$!_&63g_1&qvb8qV z+nE%tIqJ+RVi(CD)v%=7jTI1c8X#scBrXTD8(w{kAd7>a6R+)+z6S$EU!?4B ze)@XLjn55tg;3nSe)t%MeXS9eHc#<*G&@FDa9`ete6r-miNHFyMle3^t!SOGKc-C` zk9x>H%rL3L4)Ih#=Wo%eZ7*>eyNx@@dND(2?!+X?iNIE9|Xf@!+MwS?{nO zg1DZKbfu@|Jm7Ari_$>XPO4Z%uWeibjaH^CS+^jwpgJCWxZ{kSlji|enl@ma zYb$LWvTiW>OyP?*g(BkCPQ)lrG1F*|ahL>1HTfqF*mOUmZcq2&C>3#3@_r##S!fGT z`y4<;XtBj8YPxi|Lfkyd=<3gzWB#=R12!j9hJp^0uK!X7?PC2WWi4+?MW4=aNfZ>O7&wk2<(BPIev`p-F~1bu z5>yIkvz@S8$i`6+Aq(rAQfp2N&8mP_ItyGMF8U;!hIQooAp~sN?hSm6!q=}uBic^5 z&=m^4S}gLkv1h#I%QuHc)3hYPvGt%t_C*zXCeY@R2pYarl*8jj)_>3j)E$ovDP0Y! zN4({edavw}3+bgk+cAV1grhkzixW*n?|luWGtyh7%V%RKqJ(rPl`5?Hfqxob?`w@6 z;wazsGh(L_ezu@DPBMTc!&x<#)Oh6}(wXuOQuQ|2hM}6z8aaVF`c$sQ<2YNkIG87T z?F5dCuGYjRVk6XT=lA?atmPBn`UOqzX2eJEWnw_}cu_-qNg@50%!mPbe zn9Du=lQ@=IX<4D(($bfSFWOGhx2hcj>Db%f$%S99q2>1E64wxYWw) zXee)hy#2V87&~u*8<|k<&y)yzqy&Qx=f^4_s&lSZpXcGPIl24U?L7nrb!dXo)LUxT zVVMHcjWt|5zZdkTy5T0)&?#y!DYwGhg4|;|t2&IzH%@Fdjs4VY-cKYnl#!dzayj@D zu4NSoDT-D6yFt_@w@ZE-+*|j^%Dygh8yiAQPNaKfnuVknqNz#w@av6W!$=BeXOeAo zZZ*^8dX+8jA<%A#OWX^0typKj50RqI>jmy{i7D||Oy1E;6hsy~A#l7M8cgwFn7LfT z27L1TxO#A-P=w=m|x=X2x4;``9<~)w}3^_w_w=C7pU$%(} z3nLvw#dX;Z)#6gQaoblk$iCaQj3dE^l+*={%52g&Tp~#95VMXvc=O*PZkgdO5s)i}VR5Z@iB6iA7X@I#yj1plp)EsNkq=(s3 z|KX+a7wMNNmsmZu zL~A+-&7dX?tW0rf7D=LCSpHXA*BaEs6@|BhHngRqP5B!tZhjJ&7zi~#4!yh z1}RM`%}^_asi06ASVi6z8I=S($YcbWnAWH`0}Noz5KFMo0#X_WT0ve$WT*s;Y{;_d z-RuT7%DM(KI)8zekf1@PIpc_NTHbl5h}hdS(~#R}$Swz)*}SodCpG-CEZ+)e;$6u9jls)G z&l$Ul)-)8>6&-gsultDa1r_#$2~INDa9yI@ZD2)xkf=d3~2)Xglh=yD2fDqW3PhN*~)84h&PNj9Wh8B zO(ak=!q`IP;M7i|A3S{q%$D|zQ)hY*O~Uu!o92{Qfw8#K0xe?`VC&UW7axL~sU_uO zpkK%e$2N12nUPlk3nk)31P3igfqzD7;8ktaj9XKH@9Y>h-_>b5rY~5aGYW927LyKy zMw7PM2`y-CsI~zdG350dZ{5PKfGe*jRi)PsJVV#d$=D_+LpusyR8=CkD#rH+05@di z?r=LF4=DDUYXvVq%wa0y!3JLu%DWEhwOv-R)%Yq?TdXfR%scB#1=7Oky=j5&v8QBl z>}GM|f^!cJ{@@!(M`Kgtq=Y}Dq(AmZVvnga+ez%IVs34e`qAm9LS)oo*j&=+79=Nl z3@4o3b=3EL)JhzU1_rh{eWNOmGy(WF-Lr z1w#ZKVJ>zST>KpAl9nzIm7t(UBqH zpk=*GC}NF{XDIImqSv9~RBKt` zH55OwvNgZN3EMu9)elu{b5gHe1^-I-tn<7YulxcVv_QqxlNRXt1miL2jvsWf!$ZDi znv4ZA2<~&i{4vsX4F;F>h692{wNB^ZnTPM1)E3BfU+`Hbmf2!Gw)46}q`pE3gVw^Z z5^Or(;ZF*sM+|Fnp#Eld3P|lw1KY4U63-5Uog&cnvoXY~EqFeG+YN3CysGcpp&qhs zoB$HM_^V&X1g#JBXIdJD5)T!~NoB6mk7>!}82Dj$L;coGs>Tgvsp{s}=AUIM=G7c* z?l8d#-S`|tvwPup`Z3)>`D$+qRL&Dwb+5q(%JD3J#9)DNANy40qkA?1-9pHLAmej$ zM5Y<=WyQ9aZQyPw$0d^_#;M`eh`#fI1p+;t;j1(&LQ(p30G_xAPItXaMt+pe2B1V5 z9`Ep9Qa!=-KL>g!Im-RbpbuoTiH_!M&IU@?Q%b`Ppi0Rp)2XDemSEQaiQv1pE=P9$ zk<&Oz6oy`SN=7R!cGP=fn`T8bW3iEK5z z2jqYJaiaE?_>&n%L7e73}d2E#MK$QVF3OxhyRv$tk-Nh(>G` zxHYKP)l$y!^Ls_m>1mbVtLMzW)K7sR``> diff --git a/Firmware_1.26b/Documentation/Upload.jpg b/Firmware_1.26b/Documentation/Upload.jpg deleted file mode 100644 index 7c78e5189d74fc99d41d2076ae7215df2c87a168..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 64058 zcmeFZ2UJwcwl2KL2neF&EJ2chB*`?2WF<;Yl0kA#LMsX?0!>B{$p}c29F-_J=bUrS zvFZMoy0>n<=e={!d-uQN-0^lh*08!))vP(c8EUSYwLlIdr-4iI(sI%O3JMDF0Q?6a zXD;<06K~YfC{$IZyPxQ&#eG-u#E!VkdJ%!^?$GjaH(#U3cv!J zc;I(&@B*k-zu)=V{`>Pc0)Hd$Hv)en@HYZ~Bk=zq0vMra-!cdyFjIIPivFXW9Uk_r zjV34v0O8?3+ds1j?4YlB{hdwxKWH_7i~KhNeEhxb%*AEr%xPq5Z*0bCVsFdkVdTKY&3S_h z5QTU+7@1g`xzHJ#Syh5?Gt*g_iZN^Q-@9?oLDJ09O4iHCOwCL2zKNH$iI6EX zMEoL-sE4qJt%I$ZixHiNt&N?tu!k7^H|oM*`|HnK^x~pUrsl$`cclO50e%ys|AQBI zcXv*AUQT-_3odRUAtA0CJX}0H9AFO)XHPp9BM%NcXNErr+%a=Dak6r7v9hSXh6Zc`I3GaEBoGdmY&5DjiFdamzG|5wckLiA(Oe+WM)BiKh+(#g!o#q17v ziGNim#|>T%ZvOj!s+dzykXMxJw|=5rU%~hbqyM#>|EJIr7d15zHu=iCz0>#U)yy3K z@3d`WB@S-2eHRXFe{Xhmv^a3w5Bmg1()~Al{+{Gt0{L&a z{)X#cLf~KO{I_-e4cEVfz`xY_Z|nLW2G`FV*USz~Y~8^O7C8n;0$3Orm>B3-m>8JY zSXkINgt%aifkRAi36GGBn1Y;)n2eN?hWRQbH4`-{89gUG6ALT*b#@9mE?zD+9%eRn zwy#7`u&}XlF5nR1;u5h@kx{Yz%O7M7K!}Z+fkugjLJy!4qM#9?AR7Q$u+E49Rwlm| zC;#}MprWB;U}9lkz`+GO6kh^RQP9v((a|t4(801KiVt`nKqthwe3kna<`oqqEP6*G zo+n{R*bKMxYl&5Rwi$Vio%}A~kdTs*Q!rg)W?^OHHMa3nh zW#tuh^$lMdo0?l%d;9ta28V`6MrUT{<`)*1mRDAHcK7xV4v&scPQS{90-${t>xX2& z$wdgtg^G@jhK}`BE)-OE@IoU*$GFOkdHI$KmXYHXdY&iPM7P6|@@p?J@TzVT8$0#j zkTCMiFztL5?VDu(Il=t?k0kpc*iX4e0X#GmPl1o z+%4r`G;#>#6;!ubazGrd=o)Tkm?440Vyb$t;%Nq$8ZXki=xg2{^kLWe2 z5XyTLUy3iPE^~(vtJYp}b;42!#}qu>(ZAUCMw->8g0qQn0mo%RK6vx=^LdCNf*7xQ zpO*F*0||_=AOU|#u5+v=1Pb)9wXqLwHMf_oKwcEPlPDD1KJw%v%@hls;7Y{F&<9K5 z2CvQFi~Ej6*GIICpr5Wh4N&V#I{c84uH^001`m0}$r->}Ok)b)tX6yW3t7mFavKu3 zwSxp68=e<@;t6aTRcPBZoOeGHJUQQjck%wx+wl0lDiY}Sfo|g>ffCKMes|JKqq+)? zuGbxI;gE)Fld&Z~36~QEu)M@lcF$r?unG;JAR@e-kQo&PaGHbfP|3jAgrLjf)!)Qq z@6Id6)fZ7H>$hjRU}cM|bUl#-Cs2T-rbQHgK-8|FvEXX!N4)fY3bE8mu5xIo_jkqw zK*r<*&asA&08o8qM!TJP4b;Uc5|}1M0yep8Izuj9_*PC2DJJIK-148s_@++Bu~6mL zhyrq7l)N)WR}QnBJ-K3VTd3s6O4R*>XdM3x# z+N!Tcc)OP>A8<&FGu`z1MDx7=O->WVyD6^Ve zoDL4t9c>d~=@hsTtZTd!+~I%pr|jQU)=3J=KJ^34@3PN*SD(9A?x(cn;D;4y>uy_~ zJhk?erbW5!L>MY93o*=zor)OJlMH=ohWZq8%pp6SSA4Rwh=NOf2O{&LJ4%@?jU5Q6 zK=Y{jynwj1K9n$t1lnhiz%P~!JHF5J7t4LGB2yF-GhW>+7WW8ogs^yn1nQDNRs6vY z?Ju5f@J5QJ*TB#T3D6xn?ww7Y#9JT%oB+d90@!!Efc|x?ml=__oG0jYPe+=%wxEli z32-)Y(Apv2d`9J$kx?s=DjQ4-M_juE7POF0NZ`#P^p~kYPx(1k^WU25zZx0X{;LUk z>Hh{vI-HI5M*v`j&Zyq|85|6ven;C1#4H3vJMUW{1Y;1WiJvj(H%-QZnoRxaRG{7? z2u@(%hwgu1ISl_EmtfzlWDg`(2>p{57~1O6-XflY0r6WfycYPUP0f7^24e`~>r?wQ ze*}Z-?aZaW`jzZ&ekA~6pal8uhA<>Rm4YA^MFQW<9|Cv!ME`^Mko(t2Gxh!USL)zx z*s=N*P)JYcHZ~I2Y26QGIfQ);%QPMC-vVj}Xx?gFe}Kk-1e(4s7AoLuF`z$voh=V! z#}fYCA->U{LlEBqr~i#UZ_ye z*?)uZPfnFUyng_ynf8yA^AllEInMv<&i~ja|BUc?cYnkCYaIJE?EN)X|Ff_Mdi+1_ z{wwvb_WsAxZxHjl$^IE2zS|wR$jbe)$o^?p-(%Gt?Xg-fwEGeC+tQVSAlgs(GY4Sr z%lHx8ziYl7GNV}iXHo#RA?J9sCrn_vz}~m~54wUTfdqEJwYNkSTK5)uN`M6BK^w8j zQ~nJ;E)YIY%{QRmZi7sWf%XSQ0*v6|>gE5N|3cxc=|~{y>G#{raMt&Kd_w|Y@8I8h zyTe(dfAkiH%-k*ggXfWOIIDgVp+O*v#0@F=$BcSLQ$=>Rx~2?hkV1 zKcyBvVEYkUzB|V5)UoOkB7guMfdtlmNxsl{h{JRT{q%Yk$ESJ6 zm&R9EaGhx|4R{k?vx;ar+-j62m-}HO-`p1oAc+1t9agO$WbsdOXbM9duCFSGvq`kC z7KYv#(v^u|jC+2^W+9L;K(L0HobiS}+pk``Q%wlxv&Z-FUAm7LI#UWOJTf#NsdV;V ztD4)gNOOEJuUYyCR6)3VCTLk)=M+&hY)F75O-+k=?G&HlUY=6_sb3&V#`PKB%SfO( z??={~;Y+Veub1}GX3M}p9bn1-V?Bh zEGbXXTN#YCiP6xcH40HTt0F}mRih70!)`;YiI6(9sLHZA$Rr`Fy3 zhB@?RykywJZdrhTg757)%UMlB@N^7tD}Aof3W!7&7G?-_-p;4Fno^S}lqupJ88fIP>Re|jhET;2x5-5Ui%iJ|hVwBi$8jCa1Flog4Osf^vhxxv z`ioAIOM2(=4d^}=_!A-l&$#?)Q@?n>Vz?#tc5#L%?FNSk5>U9B8=YlnbvPPTQ0q;0ophFqA2>$}Y7Lj7N zIyI!U3)fyer11S@pQZiK*SDB)&%^KVLQ=eEEJh&`kmX*acYD?xlr<;%82<(<0#pC~ zYRN?h*B!U(^N0zGHwo*DOYAV__7m}=H!z0zv7uw@9?R6C3nC>*AZH8A3Ti%;zWYqK ze8i3yjP7N-Dw=db-8_6agE^6r{egS!ey)g)?%9TG@mmE$!cl{VBsUXARHO^(rP!Jm z1{ajql?5{C4P!7$<`+NR4kU@*MFLL|#$H)e)h`wjw70v@ZYFrZNb(;Buo_(*G5!Q| zd5i~tty)`M*+s0W7VBM2yYlj3MO1B3*)?77cVdIR6Qb#u9!sMiI^F$i-Ork^v9F7; zvFJbz66OUySh6Gsq7$h|0soyBF?G9=Sa!aYXml4nv34?!0gp5q=d>n6Ml(Y{MR*{v z2qs*l14v-mdk5?MxDN@OkW}DW#^Y)wM|*M_@Zt2y6Nx^5PCX5qRi`W};eXZTFz zz3c1m%wn{H$dFf;zYPVA+bhW5Skib1~^PoXCD#wV`TGZnz z4QIXoqUZtvm0$K)zlsD^UPIRjvrc;N*JwZ8?5kq1w&)DLg#@J2Jb2D~G`VK- zG*1a>XCYFj@jIT09tDV93wx4RxF%P36N~b1-?j*6QOnwqRM$r-grQk$`-Ascopqyp;@|be z@m_aHao2ILJX5ON6G%FSrt(xC>+1FImqkkl_bF9#keM;^gt|ZQ!)C~DP7Nm@@sN6U zc%5fSKXh_0Cehz64@$*?VJ^`RHDZfPn!m8?tCC06{Nt7I+ z6mxnOa;g<)>(0b-rj<3hx;a#`HffN#a!f%2z4VCLlQQ<$6}cCw%BE)sYS0mle&Dt8t~X zKl!Bnf-yAFgjgkGAoBEJ-<;pUWif7hW4YJSJ1Z;4D>tTK=zV(1F|T%i)jg)eV%`@; zFZJrv$DY-i-M$qWj&kxz7*A8vKy3T-_^?O15~*;1h8-M&9({P%2v=~=f=P3Ja*T&; zrT}->@v)fGrmS&6yh8LCj&uiubKR4cxzP^^JgIS|H=1@uO=sl1Ge>kwq7Qt|3VHgz z#1iix_2@n<$sWAINQ&N!no>TR6;aFd*#Po_aIl1Zaf4F-V=o-{W|-;q+)bwV$=$J* z2NrlSRtOj;%1NL!l?fFUF%`*hf0f*vw#MW=$uC~|!Nn)#0Y;8aC5~FHmC&9^L#Du% z02_9v+ZK+ZaWjUoY^~sipWzUkd(7~9uy8?D|APdMh02FR1#%^MyDQ%By)pAZ21wqil zXN~-R=&U_*lCj{iwic*68F%9cgpSY^w1PyikAMYD(CN7?J*&C>z zmM*&*Q1-wj-|NetZoPmO8;3JBm`|AO&UdxnqW;jCK1YkUT>8FCYlkKxeS!t=LB;1l zW?)}L`$_7yU8Zx+F@tpfR^Z#WSuAO<6Kgo{n?4z1E>_uj4i69oA5D#_&x^})qQqsI zD^KJ2v*fGZ$)&!lV2plM(7lozb?qgS|Df!IBtug31FuWofwo^7ZbtWx>nl)Qy6rz7 zEsc|rXd12rpiEY6Deg$8JI)qAJ#+5t$4_^(b)1=EU zxU!!x71~7U1VrBXNWFb_Gq7Imqwpj5y3^s2w!*fuJV@qOTpZF z#~LK3r=FW7-0z*byT@0@5pgffeC+VG8;q}0lOgC`+$oNE&a98KDy&h%D?0zZB$b<2 zB<*mQ$18`hRQrXB+W8AY$~k4Nt&*34Y4-5qA!`H}?Rljri&tYNy>EYX#e2pR7J93h zKDsK|kmRBAama2X?d9v5B&8)cv@Dac74(}JmC0{4PuAF*w}uslHw2-q?(>jl@D z&^mA%9QEJm!dIKMhey0qTOmaR%Ws=OSn@oN--6GfOZQKukU)xR)kURNwgouZ?NeYaM{ z&Zn&w%3`-t+noEF(K*XG=0k~-W4aFoXl&D}{rPy2fEb5s8V^CDb`(@TM8SGZ4Cm-> z{tn4=S6e8(oJ;tsa!N}n7D{`^3M|cYz~8?!-J3csh=Z?}iY;&Nka%+B5sTZin@O3^ zLPJ!^j!=%nc~3OMVDZ}EmO)kjg8kN6_&I^eg@%((w#mjwJ>$XC9DbdaDJ8XTTg1&{ zH=tx_P(Y(MakR~@N9pohK}9LUGTUb6TnAP|Jn`qk!hYjo>oJR$2D6LUt#;^6IduGU z6-c1|oupiecb1UUJ~qz`80!wkI%Rsxww)Y2i9gd6U)LwqB~Ves^@Sm52N)> zDf;y(a&k3&Ee%ff#cX{>BT6lXhWXmwPH^2kHd>W0ZcOzTb9vVt5(F2|XnKYRR-a zogE~~1$<2WSVVAw0PUbQ7~ChJ&Wnf4T0*E!G-&>YCN3HVc! z^%Cs(wkz$)mNgRa5dhOD8TeIU82qRh348_};$_xp#ildVTIob(AM)!+P(XkGL}=GR zIs(rYa=h`VBg-;ISRmps<|TY$>`{RtcSt$fVD<`v zwX*LtpZ^n@U_}XAF$J{84d@oQJ2d-{9fmbErqd=Gp-cP{_oIeQD5eh!$Rh1%AL70b zITFCdl|TXsYf5mkQRvPnkd&2uQ^8)aiv>f0CR($IgfHa zEz7LwlfDpTHOZ;v#Wo2!R884nq{=|ISlbQKoO{!&Ae?#7Ho7_)tGi&=G`7IW#hJeD zZM`G><9Fz(3L<{E?R2MD` zZE2ir9mi2gs;DI?D$S|hdsKRU(GbmN4J@dEwZua8a!EOiKHN7N`hB+7Rw7w1azYjo zfs0R%9c$NGbUtGuftamS=o!D&b@#9f$~xnhOhdC6a}6p?ijNCO<-jgoZFG$JX62e zPw8;&<$FKbs2=r4jp%Wr&kF@4>Z`j^zBoemz{4ivl1Sj8#!_U+np*5GICj- zv&XobPS#j;u_5VBrdLw*#$tpb%i3*+l7#3htf(?^=-n^&=L*i_FHJ$79Cj$+YVjT4 z)o|mf3#olgiWN~h09NdUeF_?!5#YXm48a+gwiOIk`|pZ!TNjzmZ1WB+J#5~Yf|o(Z zl+L4zt8RRG#9>pb5K85*XA0kF;(Oj*S2eh3Nc@F;Ofg<|x8w7s*4{Bqa)po7q!PhI zRoIEmV5j_*ch#)335+WIz2n8Ns&@Rql%LbFOVQ`~`M%ipgvu*R_l8WvarqmL%bs(4 z?-|-bFOu>nQjx&;H@avdvJDlm!mKUmnK~Mtpb3a;37zC0Q>kNAmG_OyS3IdMC8afg z!w9nmH)0CB!Q8hrXXR)#>Pxo9F5?a9NfU*jf{!atj(h7<$2&Z!8*|(^A4R-Qxigwn zUFCC+2Zx3yR;WlYmYn3)q5p!em~zf64o zF?IZi_aQ>vWi41&A+$JE4Vdzz;8Cx}S>=Sxtr{LZ-zDx{HY7NJU9!r8K0NHMnSaJx ziFz!^2&4!3u@4=YV3&)(+7+iS%u*v(C7N@0KZ!Hi(a1Ha=>wo!p7yZTkM@uvu3Vbg zU2=u^oP|&To;3{a<*Tk$?;WK>r$9rWWdR=t6u|0K*CZ$flokoR$YwiZ3oGTX^yDo? zyKZ;6R5+zQK3vI4YBS+v^Ihx!4cEh%?t9c7v5Fzjo#ZIu3G#_YM;_f7ntsN#_?q)I z!9l$4RfwMB35qU7UOmBO%L|8DvJCwXoX^_4uUWW2CUGR14~fHVHxkME53u(~u(UQe z?9`u^5)v91uoJ}08Al7V7EdXauOzKs$F#lu=tR#<*l9plqbiNqn}2f9JBK_X_qeb@ zc%8%UaLd+a%8SLssCre2d8M~Jrl>5~T@L-l=j>-VTRM{+FBPbD#*|}#1Qd(dexAnfq3 zCTwTAPMw_fRd3CK--)1gX+zMZEkz_y4MPGAnm!OSMI1I=8fo6O;i@}ptx@IgHpbc( z@)w|Ez6=QX)G>ZF{GNqPzwg*#^)-7)`=0xW%$9{vBlqB^7z8nACAiVz<$ex_BIuLL zj@9#O?HRK;BEJwNa0*d6d*fx0!>tv)pzTiQhGbFaZ$<0R>>Hp{pfRF=8-g!We)*Og z%^_@Mf{(*u6c(X`XiYfVL0G`q6*!k@ixPI@^!HCcr!SlrUyEt$oEo1aZ}cKCQqx%# z-iRvD9X)BeZ1L~}m}3@e`s6w_qJ{)~A?=_k(f(|b=r?V!L0Q{=L5HuU*#43d?ibcK z;Zkh%>(i!$PvQJvX~|6K96V3Liy(sjXlc6>SV0y92|iAM)|owZwBB<_S$%Tw7I7X6 zmh=kJ5pXDYN(Kk=qjkOVc~K@j9py(i@p^Y8AYKTaD%78^aOsiOi+qs6j2Ty3!MboMqwG#zQD;&3V8U!p9s`kU8wfY(voVD9F(qyz5xyN5gDfEKTXZiX|j)cpnK& z!S*0CGCx{UF%E}OkjUwutji4BA%Ueq`?EvqN|;i-jO&S}Q7vPC!cU;7GQ@IZ4i(YX z1)zIt0_SIZK0m|(jb%L(l#6x|S_k{ldc`^ORWmg|`~6#sUHzwNvixWiY|`|m@5W*M zz{c|I;uQQ8JQ?QO0qXoGHow?o{pfv!+T))+X^lX9611zgM!*1g#s=MLIss3)&i5?^ z_xNf|I$-lTB_0-&jtDCKFpB>h6a3fp{ogBi%AW`%x0QLzC$u{JgeT=s)8e1{>8ix! zeM?uaLs_r$;CrM*VHIb5ZmIi!z@m8cg)LJ!c` z%%7J0S3f8Ew$yliTi!|Zzs1n!#l>ZTKD)QrSTx#rE@8Dk+=a9X<+Pp2Y08zq`S{_( zE%dz=z25Rsb{I+a*WCAg3*&;KZEpH7c&f#bW@ZmOjJtEdbvD(lSq>LR0$~LAkbo@sL3y+q*o8iwr&LE%AJ(6OmgRbf>L^oYm8 z5%(dbF0hYjONTizBl>~Yk$~mBpqk4PHq)WRA!4vJijByMgy*j8loo^?u2$E%%LPZ< zpP`+^E*|J}X%BF?w79&x)+by3RP{`fqekxb6PulvR99<-u1cWCU)u4*ir?21k7jLs zNGgA>zi~`4Iu*1ph9w_@*gO?7c_*oxR(OGCPV6S&dAfh}-UIUGaFVC*+UJ78@{&N- zN7PpJ13sB-D{ z(c_JcVp`lak_#WK(v17FHO`&AUhOug;W|vuhw#Sj#Az~QYQ`V-*nKS>ozO~AUBg;! z<-B+QZIS8ztCCX@ev*AvAA6VVjTMUYm!M#6%4HRwpCXugJWC0$e=xlTi?r>+2m!Fj z8F9LH2!e}p7^I?SdpB{{O4W6(t+h2|qQ+V80$!JvNA~H0<}I-9cD<~k&6P>jmUQ6a z*lM775+xv_*uF+0zB|nmFcD;}kVOK&QM3t$0Id_}<)w8^)# z8rw~;f@8Ig)9;oJ7=^wPN~#EyW@_vszc+QmX3iekTd>bnylQZ1N9p;NU-e7XK?M^# zU)5DQ!aJ?He%YQ~cgvTtb3LTfgq(!D3=Mb1Y@{AtTw#T}8DEFGY_JFH6|YVbLIgCm+`Ey3&d(b6XgL8)qJ)i1CIj3C#s9CMUR`vin4s z_@szyu}8cZOSrqUHmpp_S=@mAp^NWfHc#qDAVla~W=U1UFosd!W=-v4Nz2#+hK2D} z$1W-h;v`#2NoyiScOE)bA6X()BWEN)Q-B1@piy!v<6uEAyLyv$K~-ypJISQ2d!d*fADncX*LcYcIfR?vQcH4e_M2J+%@aOV zw~nNcF<#rlm9299D=h6NL_!cJuz%QbuR z=9UGy`~t&eY{hU@5{LG5GC732VLR#BvyfRiyte_^4~}cr;980NoHCAh z4KLmYHv{jo@iDmba-x!GoCM+)E(M@pf$fT?s`KZ^tcTtqlCEo+H3{1-$3Jx5@C!y&}&e=W<@O8je}{_=_9nXohESU<)f7A#&_q;XX56> z#G~Rln05JIwKAm^$;#nDTxzHyx~gsVGgFJ*tOE#xKD8^RGeqgXfutytn&pdfaKAK@ zq(6|TXV`wvKh8Z)X6hUi?R0IDpt>^{Gka=CvZ;~Pr8ax+zig{qB4bc&_++tdep+9Xo{XD zuV}14*a=dG@c6I=Y4mRTPnbehFs1j%<BVV6iwCC-A4?6OdkQjRiVRZJ;cnB(E=;kK~G z0ZEu463|ZW6!0W^QIhS>D-^-7c=Fn0sCt=X9{0O9OEhI4ct@-9Cv0CVDo6#RedMTInvOdQaaLngjOo3C z?dp!t#P}$IPS0xz*5A!u;1VlD9xX%|NOeO4%YN{6Olb3FCjG}?N!|bq2RUl!^tH^i z)D7T8W>8w8WL4N+ep5$N_rXC@&eEGD$1A#Hy9NsJ5U+EwuMGmpUQR#_TtWnTl~x%Ut2 z@AMiucG>Iaf?`AN+?A0<595uURI#Om4_h11gMo`VKpZ%Vsuqk-c zCYsphd=X_2{spy?^E`J7;Y)uu=6k%ha*)oqon3b=3O%?77cZeMb9|KdRV|gtWt|su z%i{KLVRl*fDgqW2k_sRbCq17vEzwcSnMIeL_LVM3=!fT~5v55Lh}9Y+fz{TXqQ_og ztK91kEjMR9C^YO@u8z)1mKyEzs|qgp%^0rt$`W;oOB>EQ)a=UG^gX)*?%P`KHbVL8 zusd(spo#HzgPL6qqqG}RE3?z1N$K}B*~|Dce$6)CIOsz`i8Q5~Bh0YkVS%J50p6<% zPUwk=4{mNfsLwMBa#Ut|S69FA+S6NbdaBHf%&u#iN7!4L)EqWyOyhQl{jp@wf)4*N z5>Qda#7m0wOEtaZ!7puX)gE49Z@B-2Znt&QXu*HZo!ZBTb`)0AUj(1HKx0R^6k!{+4os ze79CFPI~;*0%lP6W})R`$HyC`)e<@^wXQeY*bp;-8OLjvQZA0!(vg_qxczLvzGX2*9Mz1 z;cVke3mJ7`z9)4cBQar1=C0v%+gs`KO0z7znIxbiJFhE4+uBmAIcHGT4;+iHkQQmK>-x1O6m0(A(a8IsRF7*YKsI4CXSmZlA@wZU0 zcBak_V>EDr|}DIJ4O6s9@h|20dFLL z1};%+e)#f%TdoNwBwNsF=qa@WTTYQCC%Yw>he$5(8qT!M`$S0*X%cSG^8Mwp3s#?Z za>-@u3_MzuVo-=6fi_qAfMY@L?xd&nz?yMi@2e36sS zVFvbjX6_^6TXi%PvCW^$^GZkg&kin%1__p`HTz>d5IK!q&3YlDsoz}tJVPk)hOq=) zl%Sv(+lt4M zfKgqnlOf3&!;4xT_Hwe>vnHbTK3^JYJo~tpIKAVQ$ZN87q#p!ozfebGjOcwY=+US* z)w}63*#2QKIa8r^>m*6N-G^eZ zbd}eIcUC?zO6$!zJdpNby_->hZlS!pp4_`4t*#}TrZuBD zH(s{kLuKNf~YXtdD;=fDL7<0-jnpSrFx3?6g!i>S_3~RGC-9F zTg=Mp%$`nL=_lR0p0mMqq8ZuJx1)jBpCSpev3Iki{KkXS&uKxCx8m;yWrPhVP;t%$ z#k&4_OUENz0>;K3AE=IzIV$0>B=25?hBWih2PI4v?lxoCCJw| zakY}#p3_ssbqd;9$rjDpn^r;ug!f`2vo`ogXq)$j;rN7iR8a%@Y{gj(EDdv z`OOdysGCmn5vS1Q+n+86`i?czsJZ?hS@1tc^gr?*0G9q}FN4RLxz1m!SAJ4#ZJZs% zZOfR6-c;g5cdHG{k0V$(pmSy5*&*>JDR`9!`>HAr-@LBpT##>}d$pP+FWHv~e1}$e z06MO8PFB1(nlZ}GHXt;ckhkn5NX0c!p5(o8nqa6RMcnC5rCGOiLJHQ&*3PT<@4Lhn zqWOsG!FR>i-IP5+KWdDbfx;hi{c+ose+v#BhYo2VTq}=1E9^=W9{bwwS>PMf@DK5< zuvrdL%F3CTlJXqPQ#quZ3@MLc%+dvI4Bu+7uyev*BHPfg%wFkR7+4({32ZpC)2el< zV{5TrJ=HJGf^vkj)JMM21LqXYB_p;?bPf^5AMZm!zz3qnB@MFwkx|jH}H9@ypp`d)URH7>XZ`m$C*2cN0;r+1)%ai^WHOh&#&ss z4J$gvd)?nx#vsLI__8~m%vKG#sic^mXZP+QGjDZt2V*{B!|_GjOyxW(L`BC%71-!7 zmmyc9dL0Vm3ys%xkefdj_BAhBevj!|*`9L^2?#zVxAC;E_d;!o*sn<+C3)51Nnvr9 zlLxjHhZdokk%~cVGg62BM%{rCCx|k=Pp~UZ;QT6%=xrHvp2ufpz`Uu~90PNFRFV`R zWs@DQSG^lqdGlK?Wg}`h^5Dj zGF_;N%KI?w-jpR($D+N+E~WV-lt3{KQS1~bp;~gsUPvO2gn4TVjTQzSOi|Wo_mp$| zd?ULidOjr46g()yE**Fs(;N3GWzpM#H+3Zw^8l7IN*8mlU;AJQ!l)dNEPy2!Uu@@C z!=DHxL0Fy<#XL%xZun8D^YQe#FlEc_f{hzi8dLajR)3 zNAfTWcCy8MerQc@XH6YwAY2kYG^0LI)K}adI#y5Fer|fTn?#5?Vkk2YM+>21&@(5L z7Ew!)5iVo2z>L>`1lsQB(WswD2|+J>mfa!_-IWe^Y zn6uIz(H;y`zmwT+Hj(Uye2ZMJO#dh}nSynM8>nckSV?63Zx%+d?eUDMGU#lZ&@2(v zIaWQgc!y=-g7bIEz`x0Kb5>%MK&@t_FMmzr`n)H-@op0*B}!PmuPF-r!xy5O6mY+U zwrxT7C0Dd_LHc@><7$6Ied;9&w%&9m_oj@Fc_iz!_jXF_A&^ z%p{&b`Qe@D3D*mEY)KAPqEva>FPuM|AVP^}4x1BKA3WlYHdC&yWGGb>6Uxl7@P7H` zvzf$G9LJ~e&)<8ge_(xLuw}6chkJ^Aww(}mOt423OMWIB(6}%-Niy#4cSDH^b=){l zMHX+VJQQ_t{;HPbdfl$`Rwuzh=G`QFIqP(sT6wzKi*fsNkSM+6$E;1P-Yvv-10@24 zkIF@z#GqYXvdnn(K6S0x&sx*TU~n;^uRdZ;e%0~~on^D8eH8Yzo#2Xs_rmMQd-T${ zj*EDihxFMhckzzrwPu3vwAhl5yC;#E#E%s|nIak)6$<`X@lK6BJl&2UsUA(|zAEb5 z8-e>-_?W;%-UAlEGoq=z4m-XcS zI-}!Q(2g9{E}xpHrZw-ijZA-0H&M_VvoW2yY^*p?tRPcx{FgTY=`n^Kf6;JtAY_xWWB;4OH zIh2U;Qdl$CR6c2J#eFobsmnp!uQS7@5x+Cf-` zJp>VtXywC2UVjOS*KhESdNCE&sO#sz-IdFBKvdJI&E$Q1%SA%_@!q9ON{_7|!mc!N zYk$Jqsz;XQZ2Eri`l0ky!P9|NRun}mRaOr8SSqvV<|xk%UwiwyMr7L4xP$>-(h z>KVhL@~sM}f{YJhU5QX`>z0HZbH#pmTNi0gE=27Zgb+&N)RHF{z4JEJ6x;0(i&|tK zzIqNCqYLlV&%v<^j3!s?rZ0ZN7leC=M{%1gxFxvNv!iOk%06MOXpBg*;-O$=Fys)` zBpxx@zKh;)$VHWRgHI+NLIT*vsTv60E}``tFYV5zCO>A;yF0rR##urTXhtOO zl5DBXv3(KCqugO>aRH4$JhMhm~#EqvA144*>#W^f%&DzylJGLmzVA48>xx|W9j zs{CYLk~c}SU7!u7yE^4$9?AOrAq`KuXwd25xz7g{yCp$hPpzg0G9vD-%xOAjd?>H5 z8OBFihIyO^Bi28f(A@FZA7()n(M}JSBbiZ`e=LE96?c{(A8z5wl5dN*5%jT{$|8M6 zDTHhWU5X-6>~;ou(wv;8O-AnLARg8y8XB>dDv}=r-sA^9?dn4()JV|}`w$U_FUPpF z*TJ8Y=&EjMVrE!@gGZ1i3#g+=0C<3iGKL9b@<#nViiRXbaxv#AzGl>{IeDNgeu?6T}m|!T*Jfou3k&v_!YiQuhH@>M~`xuR8%42Ci z(@u`?F{v4MyKD)qYgt60C z)v^E7{UCWlLq>8@A^+Ly_MG7$_x&utLE!&m?>*z1dfRl-(0eb^L5g%G0qMPlA~hgV z1nD3hrAq<`A_fQ@G199v=^!egNbexM8j1*rbVG@I`G05T_5IDBnKNhh@9Yof{jk0y zD{DP@*0b*CF4uM4jHG;chN?5N$_-V7hA+7IoreR{30#X?*=~(zjcSgQvGHG*2b(1SoS=>g_P*}?;?jawYyeG@$^GMc z=!1@us>v;~5KW(~XJx9|05?+k*lGTQ6NJTaDYR)UcQ~dwl2n+|17=T~XK#v6l(F5L zUZkaMzEBCXKeq?t9#q}zS8pX9mt$8KR;ttCj|gEBYHT)lrqyJ6gNP>1+!+mtuuJ6{ z-1P25UJBt8T+JR9PF(jIIJJyCMJUmzR9TlLRJ9425o+nE8r#F-U&S+l%sD{Bpb{cE z^SS*l2UFi7x@$}!O4^U!34aN4N#IP~3{nU2pk0$kI7Q&sZpaKBObp_1z(|v;@?6A5 zyDg6eh;Q+T&gqMO0;Q*Cz%cF#u_OV@N1f&NR40M32#wc72Q%2D_i(GwdDRz98f@QL zJcU@f(xRpo&C~7UL?5lt+E3u$%rL5(-RCj;Gvf*)pF)x(b*pwlCSf%sl*=P53|ci!nuoS;HAzwW zA*@yWddug^?L8U;H2=piWL^#$sXwID(>+z?6TIu^V$ z9Js?WGLD*?PbasJdvye8C`<6ZZOP%l;z7+9W?6ftQK}bP1Vfx%k0DtXpNOpa4@fj} z@g@L^ee0@_!EWY3Jf@;txCO17-6lL$_sm@us^Arvg|hZ!7r$;i{i5hFd`5UT?| zK4BU$@6ndis8W zK5)fxeb>}fWJk5|^(S$Ozf^L5E9Lw*k84kGO5fYJQ9$)zs=_=Aj#=8qwbEQtc{DnT z4>{H*U}&)P4}H$oa?fsx_AVzM!#h$_!g!d?wK!n&OpJkki#_TiG9A9_M9y=wlx;&Nl{DTEsPKw6G+ho%cp_C)-SJ4~t#{c8sbLZpvX0R| zDT9uS0?U1}`Er0tFM% zsmTVU#W_CpeT_^4>Uh`#;;`tXEw!+$$GVS`(Wp<$EEpyAUm!iyoTelA<+*O(CB`YY zI>7LL@Z3%9C3ST4yE+w)4HTVj$XZ+Ft5@n#?O-`s<%I{^&>Pkx(7Ed^lxl+Re5D2v zjaM5G2uer1K)kO)VU|UyVZ@851vvucmSG{hf-iP*lOLq7u1BAAhdN%Ik6YU|eq7CW zA_^k@7|}{_G^CfYUsT1rx3Cz%M+>L?61R(aTFh_r&eckU6jXv%hk;-*=;=Q0O zz0;Gms3bpDMmORoq|#=?+goPm+qdS5e6YD~s6TY7&69f_dYiSA??=ztExDc5fDD>R z?qj4J=h^XTF>@{1V}$gIF1K9A$X&^J5Fj#_PNB=;SjKLHM)_?)Q(KzE2HxCS$N#>E ze%OKeQTog>x}Jy!1&`a$Y1vHrknF_^b7ue1BM1R+%8lHm0)eZYS?mN1UVKR2@ayfB z`*e#k)-sxD&R>mnm{hjpnI(c7zV6lWoL%lzZX??h!+Vn`ia*DNf+6)-`C^pt7`7zQ z3a%9EXA!n%Kion_-1I1v-hUoGk|pgQ*b2H-m6hty43dHHfk4K$snEwKn9_IZ|L$cn z5HGy*cB~!9(v~D74agQr`=)f2V!x7Q*qhlwn zRJEzS3h4+DU7I8ml;reWv2-oxEM*Xg+P3Y%9^lAY&M6_CMA3($u7^Wxk^G)J&(rZ` z@;sA<^RrjKBu@{R;(HtAX2^BR1Ae;5OBinqYsWEv?%=qh+fMPc0QK#e3H;aZ;3@+W zV7#bW;~o+mwp;F)iFZWOMk)e2R~6NH&V>dR+{DmZ7dy!fD)h^0RTX1uDheMqz47ap zL(>p2$&X=S4?+`LU4f6<_Omhk^w6)5dJcv}48P3OU*D2RqiB2YH%*ZA;U#C02|ld^ zHW1m{LolDCLe4xcpl#Al=^wzy6@Wfo86{xbFo`*U^}QA5a^*lqqhX`H&T(MdQhqx0 zN_4ziV;tTo&SHTqxjr`_$9+umb;;x~#7NBOu!Qh-0_57y=ZL%cun1SB_vp{@iPml< zUgN@oEV2#|C2D!xO#zT<^K}~r7CK2Li^buHtgW6Z$ijlIVuC0rGLF2G6tKhrXOkb6 zZl(rPp;Hq!L1!4*0@2`A2eSwx+i^*_Bou!`Cw_5BqOxByR+fpe&PFIM#(4cCjRvJn zW2$BOkUGZ3+0s5f&Pu(Ami=n8Q=3x`8h!Y40$=dGGi;vB)pL!ii<09ZdDyvm*79J2 zoxANv*?UnUDs}3NLQ4|5gwWZ|8o438ibhq|4wkhI#8sk<@3#(RGG0+nASpNJmCF10 zE=#ohV$2Ee)%PebEgdDfGxQG6_j$L!wWnD{n?7@!@{#gcf^QW%9t;cPanBXevEHTB zYIuG1;87&YFA$sCyR@#|lYmxehd`RNp?o@%$eeo7MNt&#M=%e;R~mvJg*(Y1&Sa?a z?f_A)+ypknL;&xHoqGd?yCOx&+d0HxXD~Y-xHu^y(_Ysu3q!)0mODs}p3|J=SJwCG zO@4#ndh4g>s7B^p>BTUAxStKN=n1d~M zkHlYS^);~995lBMk~?!OC&)gGr?ihY{p5{G zaa=AT$Q@tzk)BMp)X1H-7VH0a+juvvo%OpZ7oGBLC8_ z%QXRNL;@V}j}Z?Z>EPN&aPjdO{}vPbeDuK*c&HrX;72gn_A}SE}znzg#sGNYrJ)YEe1ECb_RI*wWYI`O?uw-pV5{Tksbjs!huq7zA@oS3o z1p0ntVJUk*M@~%Jue~^gP&U~cIT#XOFulbB{cI%1-%9vMR;gZJ;B}yYQ*ftkB?AlJ zK6gKgWG>dIca4P9h;u)Bx|BCE;Q8QPgI2Ss85XW5Rnq!eLA@E8tW=HAZXJz@xf~SZ z^P)(rtU^eS;xCZcIE81o zM(_GelpQikKCov?!zv?AFjuIvPmVAZeahXRMIqk%G#=}Hu5DSyEd)^3(sJ)}`59d| zz$eB@A5Oe?zdH}VXhPAqS+hs@)NozaLZ=WJU3Ee(79I25@_}cjc>BFp?vD15EI!Uo zpxVzC#`((fh(M|rBPvxV4OzoW?4SYsEqQ2HZJo^Gy=VjS?K15jigCz!QX*Kn;w80+ znm;M))6V7B(Mf6NhX&_d8XI3s?O0WAc)u*mSiC6L)CtoIIPdN-ODrUqF~xT)K7^qv z^T2ogh86a2r7vE4=5C9ehl-A;k3GJcLlO~ilukq%K>SXUZO{5C zD1e96?N)A&5m$|;QWuRCr4?xU4uZV=_(L&5ww$Ns3IVS$ts_rMx0`-of?nl;S2rVP z`;D!Otx=6No%+Ebf|4D8jA}rXVkeGbbfKR22S*-nRJ<=_wD-|A)$MRGLHp$xiVW61 zbrhNfopS2D16OsDt+#0!dl7*rCQ$Ak1Z?{{nRUYa^w-ygNK~r$mUTF`=`6%%y1~mc zXk6M!vr97f2#S$q<%UWzmDhXQA+Z-h#IwoGd_P8ftn5Yl4G#E(jq~VGa@)fJySoPG z_H&k>c-Zx?t71EjHnCsO;=Slz7u1@4IR!HG!APjjEb(}WJL#NxK=V4uMABxq72>BW zgX>ywFKBgt^hgobNN>I4;v=omihr00UXGluQkFWvz!pXt90NE~k4p&33gSUPGVA}- zV-yhO!F;hh13(M)AdD4oF^dAT!Jqr%Fe{f*UB&q$y#No~sxPAw#QE-wt!|~k zlMw;!;CE$$%`|<+*R)HE70D9wLmr=*PLgG8TuVSR+|#At)8CbAZs6AP&wWD|*RG@fO{z`pOcg z9vQ&kJ*P{a|CHQ_WMcY935yHXQlABdUxalfd?b14AuP3eZF!0AagQOcz5L?qB!%1R zm~E&;FNTSHMD(>V2+Z8Qdx4n-c0NO5Vj|Vo(5ePK#Y#Z-OT}RG%nVO!jUPB-rz(*I*vSDuc1CX5>rnQ>dlTP;pZf4L z20JBN(jm;jNt5Hc9*5n`AsU>ss}kT*r0Y92#Nk8wD1e2X9*@@UA&lUzqPP9XAQUKf zFa1MmZV8e4S;SWpnF=o|T&)as7)HrM%|`;vl%cX%z2vBfdq3$xfctzUi@}c{1!2Sp zmMV!@y_(Y4y=Ht>Aq%|Byuq!J-Dp6HdFe#Y6-iC4##z5W&fAjc;*4y9;cHyI+iqe~ z$q;?rCFwM}!Im1lkgI2X-={uPr43u#<^I}lH+2Z4%U@0(wRYeOB24{B9&>|0HO1>3 zc&Ygx_SpFSoUH2}HZQcVE{z&U#yY`xr|ywt2pYY&No74AIeq7bf2Z0Z`qG^bi58aS zD&-Wq0(AvD-1^9Yb>%q!QjjzDo%H%X$90H9AIWFK;LA{05@oEzem|`QUhG1S5{>u! zGz8JYHAiO5TMk+nG9nlEM*Gd>;JCkg z?909AxVRn`+-Wfg+U)zf*Kv~OP1uo=eArR`_b*yvnonq6N3!;+7?@EtB$f`Q>#q=9 zl^~`LVcpEjv(~RYH7I`mF}fZ^mpHri2?U)6zbaS2-9r(28m%Maola{%(%A>SY(ubi zD>xzieoi>oLw4NRT(hp3Iiq%d0Q901$eF^uM z5)rCoE1T`jN(yF^w0Yn@f)rvAI>ryHMTd@^Ec5F*Xbk#%0&jFtORmenh;tvek@j66GCQ6mX)1bJ4#Qa+pG25 zLuUKEiQ{dujAg|$PQ~IS-#Tz{(GE#Ve>6k4;>gmmxx7?xAHP#S%eK>}om!i0!~l@U zvWoPxgv6SmwADDj;RUw41v{}@N)Uih{<3}DMEYzy3Af25zz0a04%iJJQORTxs&P?d zzHGPb_Kq-sCvMc*U|jHrC~tN0m67BtPfos#(&}$#4{|C8C3zkfohwu;`;JvG!zf|} zb0l*^W7%~D8lm3}@$-$_v~^g9)p*7yDf|plHeGgVjQe3Y?G*PZBFfb`ewuWBxQKIO zb8_4IV^>^=R{i1HWU97v68XF(ZAWsB+K>cq*rx={LRIY~DzIrM>BKKPxtjM@s~{zW z)Kpt(M9tvf+ETTPg-E4b()9jTM;W)Ft0pnD4@S{iFbrM@_{1Z2S*$#Iuj@su+`+Ki z=_h^T1_*0&Q9c2P#j{WLXfyHs@l6R{{TS!u*E7hKgit57C@m7b4^s~`}p{4%ZyEi$rgKM1xu95 zAQG)~>FjrOsoHYD^IW)wK8KfsPWmiD0fSC!D@l6~Hqr~8S2L@L-Ge#0BU6VZhaZ*U zyYLHl^!0$UYp8Z0-RyzOseZk(r=5FA9dNEg(SI+NiS4I$4Meo$DB?1cw&U2*{|gcpV1g++ZIHVl}qvEu5G6y`Fc zjnvH$$M!@NWaR0JPYCpX)zpU(K6G7M0U9qZnbSw7@d}szk*`iYU_u5 z4h&c6c&@hq^VUi1;x)*^gOd`%wEw26xtkln65YRX=@0PvV?3rT{(bN>bfE^2N3R&4 zefrC*_$>f6{hkNt$?yz*{Oq@IcL+TV%Jgr31@~WmMG6p`G5T{;2ai9z0aOE3&O}6R z{Hs?{xH@tX_3uBf!c7BB7&^TU;V*c8M|KP`f`ls%IKT0~iNq`ksKroryzbwe9xwLX zRS1#ATr2Bwy@5)G@){@C#i|?nE2rVPf4`Stn*+mBK2;JP>rbiv`qDPk*-*>kz?+{T zBK)dU{c+V-;8xN78;2^JHXTiA$^!9ade?B^-jj{!Kw`Cc)sC|H zgSE~5R~u6s&>58s_5pGhIYs1o5OJlHDSJy187s_`f_XFdF}PKLm41xYoFlzYUwZU|H7Cm4Dv;i3 zd~#8&9C>YLx3a1HX0GFelCX1|WzhqnwE`auN0PS(gS*@;*SaN!l0Y+&M!Cy?0)^?gIx8Q#2LQzDDuJUhxOYWL74f5D`e z+Omlb>}jsz?f!CHEX*~YA4H687lYrO#Dlz%l&~;`ts<0!Lg*Dk5-U<8TQGv-g^`x5 zY|t?Zx$dz(&ZkO4SHKOgnUDx9k?t{Z7Gb7DH}`|5Y2Rc(I(cj30|Ar*n&Sn`TP>KI zB(o*@Atrjg2hJJ_$uZp|vN!qocWNapFSy!x-$7!AIrS?@4}a42@z5?{X!X^cN9m@+0sv zPVrtU9dzwG<#(M!2*_Bh2C;sjK)VKSZ|P0b7Cv?_v`}Jv-B-q6@3WYO?JuW#&MKLj z;;*#DHD!t{=dfqdyq_t^ohT2F0ojygd?N{juIoJPondh)W}TCv~9RzHlWVE__ zHaRug;JNda@il>RfHE8~A7XVy;7k;Pq?|x`VO*&T{Q8c7rUQgPf;eT}DJ&2gmC{i& zIMb~&I!WKDI9OcxET)sa561&<+f`+_e6^gk+%pV5Obi%*x$$L1({j^Ei5V|Oo|z=^6j)<4wvT3j1XGKJ8<_0{C#GK1^hry(XRCy!aZ zRnHvHCYa|Qw$X=I5`g>CTStsCSs3x|dD}a?+$pp#6w@Gxgf<86u_n7B%eoC$yB~Q7 z@uX8)XGkzhTZnWW7(P;Jx59@u6R4RvoUl z$!5_g*`C^01+16@&HL=6(pg_LIzefteg`Li{g6r%ZLCNRYSLFo#XP&~pg?lo$y?=ASfY?%vko#6B+Pc(74 zm$-DVSI*Tm0G;y-G@MgA#NaJ7p6)-}I}iolMke(~(m(69X1|jdFvi||ce3C+{TTA~ zA+ec|s!F1WaE9(2WE2Xb`p}EV^}LgbLhHePnPq&4ABX_tzwiLt@>Ph{t9sRTRy@tV z5}zR|H1N`$`QQqQH=|E6Vi$3-zvIyw@6PW^TgRNNOL;pT`-sLt#CM#c+`8Al4MZZ^ z$9j62M-|y6RhhBZG0#=kBUwhgCFgS%zv6#lnkCebE@b6Jq|$vkBrS9Wn%WUJ%dyX7)o7|ptW1d`>dJlWN&1x+kf)LVMJ%io5rKh)05m~2+e{D*BZFWekt#Z!v#NleLDq`p@3 zJ&(`#>Trrxe;dJDp`AkY$!pDgCP?!Dzw!}@Am^oswbR2OEI;&zM4d7w*W0L3LLkE_ zMnkuaaK+1X0msBWf0Y8=Y~yt>A7pUU9X1w>{1F2S!ggL|AwUF7^S-EEImi~uR;}Hc zZ}H~JnM8!VMM$te?WICJMsi`h!DbdAP3T%12`)<#LNCV@y)z8jrKVg!O$3&FYUE)L zzRs6ok)XTuPR&#$*D6fHTr2)_ma zfG_Yi2Gw!{fv3{uiJ4|uGxq*MSGXSEcN&;4cL4&-O-zn-|2QP>$GNh}az00dTwYJW z2S#{?*9Yi_L{hm9{!=MD=bEd=MfIE?6UuttD^SZ7%lLtwY+mgdh@06wD%0!F7~oDB z9^m0G=ay!dTRSaxh4?&ky1r`d$5X>WmuU13B$nyhwQd{7S56M)HXAj*aaFeG`61Zk zyyTk-xvF!#j``yjmjw<9kn42&mH`X}Ept>b)qaF!ksIL*$Z^AWYSHC$y|sS3+9dL# zc1UK|H%oD4&`cp%1APh3MktM|TPWNn%#;&**T?ts-8V_9e)WCQ*=WM6D3KMUYXz4t z$-3$lOuDmeuc2fVDNj-_SdOZft4n>5FZb{E3ri{6$L%< z?p-G8U_?Lt+rj`g2Q;&r7+9-oMy{cwP!=XwzwGqa`yWp_ODap;@ zHsX;x;w0H5-C8anva{6u+LO@kTn94ROaZ*RS>IG;w~xzmKCdN8{OGFmZ_8}UyZ=~C(>cjf_F3*ZxZFeg9hbHUun2eZ zMc)~={9x|TVX2qACcQ4(jkh;a%yYf*^BXXYqKA&L4W-$*<+>POvP})ieOD%^Xw**~ zp-A$JQUMKDmScj(JIxB&cO*J(>tuvU@;GV6v*>lje9IucWn>*?@8E6?jwVFA#b4p!F32slQgt7L*@^mor|RU@?7-{Cv~w!C zUuB?p+b8yXVb)IkBzahFc-e5$hT1owU#?4 zb&uo&0czV=#{H+yi8@?-9f2)j#Z{?YSv zMKWE*@NzHnTva_+FpY)dw3qYj;TObplRN7!=Pp*d3>)k^89StyD7E?RNwb1}!>Sk2 zZ!8EU{P8h~Zy)wZRTF&^l?E%YTFJb)22p+B+&PjjE4USDAr_5~OLac&`rSBxjMIm6`7H1hj5+3CP<$cb}S~Cqa@y`QEnSKKPs?ocIz`~2DwID1cw(i4)>(!&brdyfs+wBaujdi!-Qk94Iv zUPD1Cz9gpZOwnb|SJRMDG*&eaakW9uqr7AfqFsaDt6Z8Jh~aFkb1V@Fs$GV@IyNzU z$Bc;21?6>*-(Me)WTt4o=jn>xMALLXXV<$)+5Eimd8BQkDrc)=ggWAekKKz6?i)*+ zrBjcS`Blg2-sHpp>6Yen^9`0<@1W~P0o}xY0B%4y%3w~9(V#R$j!xRwy2ca7F@e9! zWICI}e#iD=*0-x{ZkCTA&l@h^L=EGhOCBBlKjC-(SJ(J&`sIQefL{)e)A2zZ6CWKU z;k5J)EOQ@tJSzXoHIII>&s}h7R0LE5HDvexp_cY12v3a@0Dy!9%y)C9;N^?4(3jxa93a1GiO~gVx z|1PCf)Be=)eUbuMU32@D)t%-AgTsfM;=-Fl760{zmU6D<*N- z%HFo1tVdDkdQ8P9^mjZ`l@AbKVJ}X$GyBv^td>G7Bt-co{OkxXFup3J;a$rip|{hA zW>yZa=dZ?>WM)T;KWyH3P9a1U9XWHjjGx{yUQjMom#(dA`E-q4NequnjgcXoz<}a`MM(C;w+C~<-BTd3L_EJ9+4;URHVujUy_Bhd;#D*= zNnaQRw z%sO`x*JqoNgS`8rWkC_=9+d}HZ5iVFUbTM!TCz2?fKiLJF7@3 zkB+t&%CKV+l}JWl9WYX-XH#Io8MVqxEkA4>W-W00DdfWPU?=n_i?Jqa2j3{y?IU8>rEIGsvP7k6g8^>!klq2vq zT5-d_WHOY~UxHQyvhewFF{bwLO(z{@Cr<4RrcZ@9ItjNCMb7W|5-X#}e5Hh5O+nPh zAgW`i>SYnSjs?H*RFi{GZ?FXr#ZMim6@c(UZf{jk7JCjU!CJ5^S|T1ZnRQF2$nD{n z$QQ~}gWp)r=4tce9X2a+|KJ#JVM{ZY6r*@V7x?s=)75V6fNmnO0PP#=YVrz9EH>3@ zeV9b|NbmS^FPZ1O8{1(_0tMvC8bAHPdq(XCxQ{npHnSVbgr4M4Fq#X07au}bP>vN8 ztT2hd(A=2-Gyo)<`VHLAM~h zT91S%?NS;UAy=?+_kRkI`Y(Mr@qK>G>e8!6%qjp+9uqjN^0jZo<3#0Y`@yYa_$eR) zq%9uIe+8r(9pqv57l}yYFA~wzq=^=9;*HfO@>DpL&ELfNhvNT6Kjr>N*Q`ECa;fs0 zTU7Lik=#D8O95Ml|BXWAKrSRmkX`QO$3G6yYq7Z1uR7<4O}!|?Ut}`pENr|=y>X}~ z>~E;-NqJi2UX4c=&AiWJI!{f?rzAPOpGWb)+^E5zA3y6e!r@aSKtkf!zZ3}zau+WQ z>fSK!aqHMX@E4TphVVl7!{597pxs#^K)UAEtefS-8=;jQ35aSuOzIwv5$`6G&R}}w z`eCX1Cp$M)^A|DnGm(OokVHx(4_}xAE5jOydT+kF$3kK{|hs6Y#ZXVk&Meb*Jgu zV;>Y=>w#Z4oDFyd%GrCKK0!0q43;_^^BiwaaK1~p(;Sqt$YtPtFE`CGaS~5}36__> z?tU!=QWM#D62onX-h3xA1a|gGb!=5_QFwAUASd)e9)*-S)TQMim!nQ5vM$~1U?uVG z;nd>{pV|y}2lw#TE1qA$3$7Q!Ho!dlKsG&y52Aa6dFUA(l@yLniUQrmKgwMlS8dhi z;m)GY9i71UBPT-^1|CR6I3^7gbE${me1_Ut0O0S1Wc(wum)0W?ABV`a@D$YTQua`; z_PcJt-@W6K_NI1ry)BI#Z$bVr_hX4Lss|iW>>gkLSOt!mwycW zp&pcV)hMF9irX_owOim@r-`0FH6-8=?<^kJ++IB@2oYZie*1cyvy#Pif8`v0yv3ih z>wJKDYMZX+i5ENk$kMU&9mu92HFS^El9=zR?nVZH_~#Q*8&Q73WO~!7F{^vGEdXTu z3`2O94Qkd>b7#;2Ev?VK_Sfg$xW(}HgWEVWl9=%2HzT7i<0Je~k^GkD6X6k7F-T}< zq}+(?$<}nXiCDY4*LZg_sPw)dpBzRG*v89>sEhk!i89MZc%OJB*ZXyh2;w7{@Qo6#-m@f9~DOSc87Z78W3$-5aQ%~VyBtQ9_+P(oZE*P zOuXWY{NA{Z&`Y?Ly=B2Gk_?5X5*d!uVK0+iw~T zm^QqK_@c}dsi!mp8+%t1M>0WZOil~#p~Iceyve8vmNVp$GA<2IoJqH|)gnDe-AbYb zOCzU*{ZhnWz-iLYu;J;zh`eZJ*^CE9twFh3)s^zb|5Fe(-dbd$d%eC;(81f+e6~Yx zxnI<*Pt-`^ImA~wwcJmr#om*C@=e@{CvK0%)YYd38^f`D>XO zq>t~rg7O!H-?2(AcMLz?`{Dki-aycMYi{uA$hIoOn0dw> z!mwwk0XEXL)D8Z;-jy?EuJ;XqgH+0Y3W$16imA=A&<89yaZdq})A)+mJ<70j%Vf0c zey`%0F<=UcWUkN;4cfg~(Ds$>dH+2$)P$&O&#%ci3R0XFIh{Nj%x@%w zDmhFOL@_?VEZ1N(uPCfS^c$JrNh+dYNj`@|5`qN?e~8?Fp2z-w;0u>_VUl9s0GP)T zcc28!{60MTUZn0(O&;!A^8s)7kqAR->iw7E+iu3}Rn^4*d_a_uaZ=0H^GOgFeLO+O9dQeBe?zYF>lo!&3 z-Hn$JcFQBq8g2UWEJv=VRL`vmp}RrqNQ3@PDw$iQ3tZD{Rp4o?V*3(SXXyC2*wR6J zA-SLljLPE(HT#-J_~5o_b$;40p%a_y>?-CId{O9z)gc%M_`tmPtpm+1q99kkM@7eH z#0%kry+Fod8CqPV8yN{n@LE6a^{g`8;xB$V&JSyf)2!8DSiq;;-Na0540w%mi z)@K_{cqyU>5IuxGyo#G7Ixlqlf(C&=5+teswTNZ3>wt_+%JnW1<`f|nLW_+x5|+uS zYH-3yoeAOJY>r{Qb2UK^iO)!Ba^i*$!Gd=kGuVl#fd8a(5*%K0qc3S-IB=KcqU^pK zr@0l&>}_D61Y5vFk-jR+HzqRa0NIn@YkoYi!BPl$xD2q`%7yZXNqOm?6GHiwEQR_m z-1(YguZc5)^Z5v0MFPL0w7hEWY>5JBdW-?b`T0*LE4q zjH8KxNn+

    1uP((i-+HWK5#;mw;#^Re6|=gG0Vfp8rvgd&f9q~TZVtqLB9#% zJtgnqPizm>$PnC$4-;}0>7dmn1vuTtg!g^O`FOS13LmYLgQWhNbjm*_osM3Lg6);i zS4Ml|uXVzA7$G_Nv1-6DMBe8l4hErEo9Wg|?LN6jd^%s297!GQmf11Dg?S7y;u+5n zw4WXj@O-3=qli#&H|^49(UHvadDqCt3go{$J~QH3?`RU@e=(+ASA~Hh*xhdxvJ$)~ zZx-U=5aj;3YgvF0ZOnJfXhESJ157in3n%SR9_9&P&8?9C_8WZ`sX*k(HsRLe? zPvfw8R&;Gw=&6>&$kCS(R<&9nGd8DtcQg|kYtv`BsFj+=Un=RnhBR@kKgr}Ce1x-V z))K{oSt8mrN17FC>l9t5zmJ~qT2P4%uZJ>2hgJ6H8UeYV7eo+jtPAki*L!kDyaZ2z z55vb4qYO5EVT8YX%zDRL;J>cty&+~ZP|q@FPQ!gVB;j8Bs;=@e@bLMP0CqZOMVc9Y z-o&W3BmHZ2f0zyz&1zG0X@xeQyJf+V8AmX8>|C=J2qy2(RR_lSoVA>VKAI!WDNy}l zK`k$n$)$s7sv1*eis(>WmKlZvq&>co&8FlBYv%T;@+2%?anF)}idzHH1_-N7{5yAH zILs@1oW2>PqWrdTe`pkhN}RC+)X}l>U$6lF>xATueU8W2#D;Fl>I6kQRL z!0Y2qkR6_1<+3hAt$Zg)q~Uz@?km0rprhO66Umq;L%5LVDA+9c3siM0cI$Z)G~wk= ze#eJeR!ns$`S0!1N5PQH?JhWVfL5)u$I%^T4D9zlQ}HO`OJzjQML%h)46L}NPK;&*&WHGZ8IRDW0v^M%%5IcodSTH zTMSI7bQ#hZrt{yf9UM+B7mHTV5FS|zzVL%mFv28kC?b;?XxsDYHNO`mwELXjVxl1qo5odT=M5(ql8B=6*ou! zF;b40o?&uKZjaQA_nlm)xY?zC4oYD@W$afW{7+0)b6-cK${a;s|Ip>Yy*p)z}x+8h~3M#RKO6g^GKHGlC;vfwK7l+ z{KKrOGnn|jWWzU_DH#LoG%xfrQ%S-{ne3)Pp(Ej*vtcI@z@hOQqtD6^5$A3d_T@%s&J3(b@8CdG<n7!Hk}YL?epn9y>Yn&|VMcY$t-jpb;w5U>0QJ!2~m;6W=6L0co!Sp zbo>wRs@C5hHBbBa&~9DM;zLxsA^6Nxsrsu0SS%i|kI&n3Q%*7TKf38l5r{X2*5^L{PEcS@n!{{kv)4wy?X}- z0qCP+#*&HeyDjPJwf3O9WFyV*Y|r)JBSk7N0C*zok3}Fi>JO=y-^+wQ=lwxI#N*ww zjWx5FcGuX12DU~79vH2Dhs(GA`NaOXOhDe6({&0yBCkpv64p+}6d=i8{3o;C zTlOE$Rb_m9=0AVg|IZoX`2W#Lm}zKkYH8HvnkA49i1o3nx^=>CggyP;#J(FaAC;X2 z&F?<~F{1MJ?}qU|fj(aUSHAuHKwdL*{Eqh2P!QYqU}k?OlOBN}Cu*Gyp-r{^-UslX zKQnQy@SP8JH-CYM`d)dA1eJaZn9+%-U@qtI%2mF};dSJVe`cTSyQpdLqoeC1t-3ZD zVU7xeDNJ`UBR#n%T)Q!TWL3NPzQ>EJu}iWTo76^)G6KPzsP{fF1+7Qmec_-Bh0nLo z2Uz}!i}Bz1&dC;dPyQxe{S6@90uZmX{oyp-QoBaKnW0bP8;-+teRi(zdR4F0Wtcnb z#~~J3kAWa!n_HcR@5PVUcO_eaXK6C0Q%wgqzyC-zEQ1~tvUV!T-fUSC`f&~xw0ym` ziBsVNQZlU%j_gu+IUm_=47L+&O@}JSKA7LVt{^PF#y1?Rx&@@eZ^?fri9~e-b}N4y zDu?%~+kM26xBUW<$vkQQ3cd$)CrSPVO1PbR=SRc%l~mYkvC!OR!Jm`N#sxtCHjiL4 zTvQ*}BH(Qh;J4|ao1-sd9v3(%mn!aS2Z z?yVf)4GRbNY0%J($V>7&l{<;d>RLH7@`Z(q?pxef?yW z;PXLi$HaBcL;+J@5<$fMA>;6d@*Ed21Wi;sH8Z6bK>p1}8%8M_& z-B|swt>!cnkVOKcL3FX6eUn-KHEQ-b-6q zhwjjDy$drdj}s~=OmX`XoIFn@>Zz7kN>qy#E>h|PL=jT?lXwfA3%nAQsPTH%v_Q)7 z$Xo0-ig@k8@zn!~h!i{^`DO(4xnc+UXd3|eW8?n{5AuKfd$S(LASnl^mrF8@wq+m5 zewpZ-rk0$ERjRJ3dR@W_o_T&x^H^t-POi^GPpfu>Tjx#`B+~fqj6C0BX+GtEp8y2z z3#<)%x#V~2-TE6qYubJc?o#F_%eY+zTAd2lM1s1i+D(@7qX~Tg%*a&xX^%uyy zW=(SABRuSf0B#UCDOWV<{Ad~IeEa7GpW*1m@8hDc05LVNMPqC?KZz$X;`q^fNmT={;r8RWz+k(7n7Kb6 z#qBpHI#cU2DzDw)3W_)W9QExK;j5?~h?KW{1ts0j+wX5D1h?a~7d3Ei;A++;)!+1n zxB~BGXprf`kT2SrHym=7_h>e);&R(KEL`_*oPWel)jjI8d7djtSe{y53&@lnvmUI~^;~wwjrD6L zr;uM}rN(e-@6Hm`NZHISuoIidYP?|oq($ye0LhxzZYJRRJX$9TxV8>YM4;!TgiaBJ zN!>5?Q8krHQZrrIg9{#-w+Ix)%l72V8fs?!a!bA|Nq*86@3QzIzSxj-pJAa4c~!ya z`FVX}hmfoiv5wwynQKGy8}k3v-j|0{*}eO3$yB^TCF4$r$Pg+~c9J$BNf9y>Lgpbe zPm#=XD076&$sF2|d7kIlM&^0md;6_T_4Z!p{I2gg*Y*8=&w0<)A1)sI+3Q*BUZ4BE z*K?1&>7%dD)NXk&kn{;{T~95c>48cGSzQ|!jdOU}COXf0bXi(y3{<_J7vPFh9gxvA zWqJqc>J~YDOe6R9XRichLzZ1RPOMFqSVeKhzq(nZ+?L*GF+XT<@P@D~H=3*bWk;fI zLY)a$-!sKpOqHvAc%x8pF`rJu;lZ=PTvz2I=-dfow@`LLNMZCwhKtt&59q!g!byum zrssI)wVEX4y4ja(Zh!t~lnCK1duqFl^rlNTb6+Q|n+nV$^)k-+*i1!>EZtGK8{#vm z(4evlQ=>pq-^eI>rbXJHAU{fZDoXNbJ-*7qKV3roBdMs~kz2e0k(#jNzLXv}AnqQ! zQ*X`{4O`DRo|A@=NSRtsHPy9WEPoe}LgMVi9d=BzD{=T!RJX|Lx56EnUIjyWfiMi~ zr!FkP0_b^iY!_DMzlnUBxlK3(n%4lui%ogQh{B-ub>y8Zt=HpJ-R&<@DZ5M{U zcLRGc0pq@@@R!k@l$@F&lMz&?CdjiD?9tDp--W#>(g2F}6$(@VJcRgV{FJ6olym(T zm+R&=CmeW=jcNW#9po?Luc>T^V~bwmRGjKCO}cT#hB)du2b{|toCF3GxA}E&u~e~d zh5(0J10?J73|qPzd@EN%iw!GwVape$;cIQ%zs~RDd`4o) zCkO8&0U4IMb4(6O?fSKm8BG@j>feukdoM0JxZRh%atg=33$ukpxjU7*Zf8Q26`tfsNo=@M63YIqkG)=-JnFk6G zn^FKYhw-410cSev7{-@kY@ZR6oroEYr%LEKCVRe`6DfE5g3Z-FM;o<(b-Swqq5>S? z4x%=}HQ65kKH_-zkU>jn(`PJY3b4L>+TDt~w?U8i>+=vJEI{S+K|tm6 z;m$`%GPce$SB5QT7X0JYb54N1_d=);r%M07KFrz7hmEZLIP0v61;Ws{i%Aeo-{#$UKEKmbz<MWj*=oRx`zFuX6k1GS-`cvR! z9edz!`16PR7tQ6%215%7ocEKBa?=3i=bMx`q^~Fzq{X!uYb>LzlY6b#x`FXOybIF+VNY+*o8=6)02>4K5Bi+= z2LV|>GDZKl{U&JMq`@JL5kNu!QVaz6x)ig1iCGo}PEF-K)|vpa=OxFme<~0?LyRS$ z`Z|l`QKbozvLRZ#rH>#2ECu=|_khO+etZ{(wvyjolgE;!x+kvt$6*3Om-l%qpzLob zbMSKV57#fKWs&<%I(wuT^aa=f)^(_QQX4ewLIBRnjd%QkozDz=*h$m}*!i+4KiVWF z@SPeS8Fizsv`cqo9eVk2FV-qMuEYb@VlOVyoB)JL{@X&QWY~X;F%6na0z!G+>fr}v zA6pI_@-W}K7yzZNj?W7BN5$|md5B`E4m8tg2YE0?T8?x}7jZXip_vY7^8ozm{=z!?Dv5ajYV1rEg!5fCv0daK}#Su)qYwy>AG#*wbd zn+Gwl|DSMFE%#YuDO`D*egt>Pp09no)r&J-*5Bnb+sdfaIbd)024bef;(Vv$^-D`c zK)EMLf|}ifg(8Kkcz^d5;O_?Dd4KkwB`5#gk z;`*>P(5j+xd@3d`@nbP75KIy`;d_F|P4ehHx)?%7@yQ2yAoE)s#O5;>s!m_FFU^g( zlf*jf8VJe}GZ)$y&Vxu(kC#pR7;*t*`dc1)C^AU_hMG)49f5Hmf8;ctr7wG}ERaFf zbtG6z5GN*i#m37SIGJ{G0g=R8tt0W$85mG+v#v~5ATJ&#!9^j~(?Zifm82<<0Vj= z20%dre|Qc{zj}*nd@tVfnieq8;oFC7;M<2dJ8q^DJCI)(S-+KpTF^=3`i3!}E=^Xc zbR{shg|BzsoaDY4ktw;wD&hb_mOsRKaSL9J``5PA{8zQ>BvkwgEz@gmk05ZK_I*la z{-Ifpz!=O@QKfkb!cwmlTpkiv-HY+2*)Qa72MW2rL4u>TuL}H5w*K=&#=;a`Se=kY zW#riXdex9{+CL;S2bm}r*fK0~l0N}?B$$-Fuj;dfz*+jg-5=(E!*|Z_(WD*Jm!{dn z&6hRzk*p~5tH4ve|BpbEp`rBs&|wKsmV;`WuYIQzSacgGpItTv59ShW5+1x)b6yT~ zc4uKfQzQoZcC6q}-x8zkmh2&^%!z_Sh|2bR5iQg?*M^9%L~3a{O{8>8XTAicZe-;s zNCsElaszR2U;b5Zv|LKLQ9O6XV*`!Rk37#vWWClt$^62{?@EQFy3=~@+kSm&eY5nk z^kOo!dQPF|__cZ||2p!b`XKVqE6P`dLwk9t4iT)Rq( zfNdQX&hk<%!ecn!cRXB)jL|&#u{8$_CKBYJY1S5I% zy1TlowgM{@M_#IV1~J$Us_1CF_egl-`3=S-XC;?xKsmzpfxj1#OwuCONzmYi|_rvo>WtFbD8eRtb6;Iv|z=R^M$F>rOVZmgfQ|^ z@Tg2(<{%`MJb!K8l<197+Q*Us$-VWl)CBWab*n+6khTa=i0TD4X*Sg6qKJGLTVU^z zzz6A_!`D(4WjRwrnAD=vp0t0;bZ6~IitgpU;i37YwJcrl)w$wBJU3cVHnzfw8}4Dk_UMx*1w87-d#v&UL_txEdM^Ewn}laYrUj?3K?zVg#nl}(5Hg*L|P{4bf@aw-mrCVs$(5-eXkBl2g;S7mOR1eJf|5v zHRE+DMr+;tQ*jZFn4wReDMy)F;#BE5T|cF3$7;vSNZwZ7a1!9+n%{-xISL2qTT|Eb zu3|5YqNyKgow$6&E#T#iE!o;Rm$a*l$=^&jH7GdlE#1R(=2^paWa@4}0&p?JNt2Zi zP8+fw1FtKofg0M4^$Z5(WQk@e(QbjX9j8_o^t zhOLuV$U)yZBvG;H+13wIW4MV;aMB^8gz8eXh#1`_|?V1XRL zfA!q!Lk(fW<3@ohSRLKs#GA2*w;3hx_}P>c>P+$^w1W@Xp(%O1_>Iu8^g72ce#(eI zjZ#P;cMb|^JX9t3xqVzer;ppa=9rCuT6yb{D^i3BGQ{qw>MC+}#tDNBhQuR6OMOLb z4mZ>+37$W%X}VcB(*7}^@jTDNv!|{F@f61yhw+kC%0B5njPLY7EFjfY*u|5vy7N3) zbE+$5X;p(QOE+8vt#^h?O3|%f!JpHt=w_rvpH1`YvOg}GE?>%yn~qftP8=k#tH|FL zb>4+x8^uh^-WF#SwPmOd-Odf~d^#Q%E#QM7Y_Q1}JJUMPmt^T+%BY-Ozv#gejmSz1 zkb^ILaIM!hxb1Rrm|M$dw9r>?HlJTr+~9p*KcqV~!u+sA@+)2UoR7duHZtUG;Tx+* z&xplG3A5W4yzQh_Vv2OTH!^xKIEq>j`RwghCHB1)#)D^!=GeWSdOluOtPi8A z$X{@|;C9=*=PHrqfW9vi5uK|1c2*7a=n1L^>ILDuF~BetgUZei*~r6Uv@@CPmu`u{ zJ0)kW^`t)2-bvgX-Vt1Qx^~zna6z3X#zUyjcD2vQz1h;qMShSBL-SeiH`I4d3b*1zjJH6#t1}w zm91ONp~gXpoXER*`9}uM=QK+*mF0b7nD zU7&?zs^ot6a=UY~>O-BWS;p}WqyPhxYww+ZaX_61{%h`Iv6{)_4%Mq@58`?W6#mj1&=;yHkGjL2y@rZNy*gWkj~wQ|cQD8dwxHbib-Q+` z;!&^U@&G7spMRlgLYVLpAo4Rq&GImNS=`As_U4Syygq8r`B;z2tXg(x5SEp6z1#UN z$+V?%mqK27UG(8QR)S}3ecgp_0wXb1kpJ}-W*eFgsx;thaf$`J% zM*k&xg67>2neox{Wej=)q^u_ks%pV3FgNR~r(CsWcYTf+a3>cQwv8>V z$T&9_8yt~Nuv*dHk;?CF<%cb3icVZ+^jWl2o?Y{&C{2A}_o2Ja)ZFP&u%L>r<8y}e zw#o|={P$g8UoH5BM^?njQ>2S5pJr96_CC;jkWli9x?i59Op==R@iswCa%}5UhSZI$ zytetoBH4v}zvBk9Oct>^kJ9yRjxYIM>zvlfqs{w#?SWL9(&-hdWowsimP3n_gXx4% zwJn*G5q8ZBe(fBTc4+(**DS8or|fzAYel>HCJvWr=3HweKM5c_#Ye{>? zqqP~g@uw)1?qSV{?ZS!%^1Lo;adU9?evipR-*h<8oTS5Y#^w5*PLb9$Wyc|fK4OH>=&{rlXhI=aq4gA-wBP~6R4lOcSkd;% zPOCgNi!U_C9aXrumI8uFiE!7U$0JbK5;SprJ2B|vL-KjlpkfR*G&Vx*gHH@^@6=L% z0AgL0Gk)g01MV=!4IANx)2!Hqy-~zbO9|K*ET{NQpn*Bc@3y1N6Jj~HFU%{HxKm!7 z+Z`ZQ)CIKJ!!?5Z2EI`coG-sAJx9tQG!y4AaU1x({5ligI2k8@sSl80^lrWI+H!L) z&Pyy;88wWmMr40L)or3yPWK;qY$(mj)D%sLtGh$V(kvv^cqIvrkvn?lKY4)BOW{|v zxdoFgrNB=1M8@*r#le+$F*gvhEGgePV}qgHqR=hS9LH#Gg;GT2FG?|VH^$=bzgH#I zo{&m7Jk18;2Xw&{^40KDfO-n#@wdL<))hR~XZ6lL6JDEytG6-jzuG8*t|!6ONrDuP ze5e!xVb0n7G5F~+3K{x-IUf&m*ct=g&g2^}C*3@~?aADCVKkCQKj*7`0@2hIy07=f z4Vh?@`*3>t+#$a?3lv7~u5z|D%RzUha#su|$kOPX|2&Snx?In(jN`*p&E*JpTgazP zBN9~d+s0lGzw`cfJ=T9*@@O>g-UOh>4-xn+RFgZz(Rg{*uh@U_J-X%E8O|Uv5zH_& zo1-8<^Rx(TpX-hw83qL$j)KhN(Z|a#@CmQU1Y+{;8uFB)rvwS6d4a2~hchm9<{o~t zJ#h^`_Rg%(gHc+~0)=eC)yW!mE6F+qIWoVfC7H_eI`f?hKX9b4DrsQpTc+RiRtri{ zGd_K;Sqix`w!f-{O}=Hy*?vC!s;b%B1}JOvMEw;`g8CCrBIBf%iQiaBtpyXV^hqAY zjyG>9 zLl-H5ZR2dhxhhDN9&*bL$+uZ~25#1mi|I_+09ZJ@BYJp`7U!7Cuf92pzQ9NJm6XRmVfnri_frCMH^uBsVuFvn@(dF1Wr-oOXy%=W;` zEhkvkrzszx-HC>ljvdyhjW=u6(_Nzl5nmp0UNXm&@o=Erx%hn+-pOb}Y#3lA2;hZE z1{>D{3hdmgyyCdD3oBQURNkL84K`|@0bg&R?tc-uFH4d$ybGHR(U7wkKuo}`pt)E; zP5rpA{o5&jF0wBDYIkFl6~V#;CGK>RNK|ycw}by%vwhy)+iv$Cy#2Z*MI57aQQS$w zbr<%reQBWYra)f4xRXj2xNMPxtL_mS{(WnLS^Si+13BY}VjZwD-FM-JCoJeb48D8{ z-{JX_O<8`x}$a!jH|$&-0ESWlc6=; zv4vwKk1Bkh?X^Fd1bTIxzg11jy}2GN=OG#9!t9VV_#WVWrze?sLGgnIf;J7Vx)-rH zuqxIDYNr_kBsLE()P9WlCk4I@o^hVb8QNHcmV~A*Aa`NBtL+wa)~#u` zAX=PG^j)1La+FUjkRuIQ)K@({;j8^%Iv`1G5AHwj)6jWXo15dkFzJsw9rcN3JBtZrXtF<~=FFk2wn0m5VE=6QX2OrhNV)t^ZCNeehO;ke-XC9ryR{Oxig zX(xw!@H>OQ`Z@TI6$(waxK{Wi?LYb!{X1m3&sSU@p!ZKA|F{$0n>U72X9wAfV?d}S z&?gi!s^aJ5zK6%N_x^)+X1L?_HjpUoSq;N!*)L;etcgSRHS~@rc5)O{+EYbhsM?T} Nw_Kit=Qi#3{69{2?!f>6 diff --git a/Firmware_1.26b/Documentation/posErrorAlarm/alarm.PNG b/Firmware_1.26b/Documentation/posErrorAlarm/alarm.PNG deleted file mode 100644 index 27187a124d1b7623824ff1922fa3db694d37357c..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 10698 zcmeHtXH-+|)-8yFN(l&31OmcqK};}=`K+~`x%OUjhCS3(r@eaPDj69W zt)_;mJ{cJ~5_mCPrUcH6$T!*mf5_eR)$fs&4st93Z!X#>>nM|vRUoO4tu6uYuQ+Qw zaU&z6>pXvvqn+}flabxF&{S16L_AwdKPbDUc5v3_9|S856a3QoT~tC`qEB=%i#v4n zLMIQdoSLSHo195a`T1D=rCxPjG1R5I7ZWdr;hAsUf2hn$|38Q$x^{?mtq zn^uSa(|KL_wbB1{-gJ5^;lG2>R)y|PdvBziqm`KL-+pdYIUt3r4vy$~{^}63+2o+; zc`ec$n$p2=eIa67e|kG(FEmtxTnC0_`qaSmu_9dEKr(+7?7jM^>S(LsF%Z=N$XY1OPRbJoD4IVO$nc)|FR@LO65-z|yw?vpvrx04mSMS`Q45>sgvC5Z2ym=sZIY2xkN?v?AR z9Q1Uj7~LYVD+$6uyD02algj79NwT7g0uhAp>8@Wlo>X2Reo63of$o;q&B)-Le)^>P z)gytfwen87nlkgMmpVe+`?Cnj%CQJ_=!z0?BEYoijlcWmr=YT~&1Jau1aP=SrM>?MRE#ZBJBHA!PV=c_Vvs;w!S5 z2oQ<|J^na#2uuaP4suMaceqD>9mEjRdkx>7O}?(UuQoK%m?Dj57?MY9l_5eywKEK% zZ>Bv7*gbr}Tm!n95u|7ve1{{Vm zW&e*3BYWCTNoC8C5`(XzOf}NH*Bizd^`MUwPWR_Zh&?1BRyf+? z>=3gI^55@#>CwF2xUyU?S$vVQQJum%g>7Y^oNS5p8?8r$EEYZ$ zr@iRQnI#BG+3oKVMK&3pU++5B&i66Ll(2Wh$z*gnB+-+eX1=5`3A_Q(q{YjFbh6>! zMi;4t zHX7_*EVt3Tedw9PO@Fyt#Q&gwS-R~&=WHR8Df@iCv!fXd&u$Md((oM1(F>4Wtl2L!iSKW? zR}WXp%GR5=2bY6bp5?E%>`i;6is6@50K%LN_^&f_9&$F4O#2U~uM%Ar&qD3{<7-R^+s?$6fjZ~5W^CT8tb>{E))zEYs4 zcLsT*&?tWZeNFmgJg4_+MNKx^uXLcMx4g1xA{xPM62jrCpj0uY>nN@7%Zw?7G@VwC3n2pd4$Qqw}V)#GzcWSP1gx=UGEGkWrAd+F<36-`TFNpXOW%g$Sii|CMYo0c^ zzBp?%X{j3PJh1NyXo{o)BeJ-t(4240Jn&(BPNXnUm z!MCr~$C&qEXWKB6ifQzSJje*QH{i-F47&C_A0*CS*+@mXxe=oVsowbXDg{39yInN@ zoMIy39-M>JKQMOCF&aiyB*4TqUTTiZ6lA!6e2)n^^#)hsm|0ujV7<|@S2`%SQaoO7 zsTF}9|DhZEMt2!Cg{PBW{m}-&tOww2CHhdp zTiv>S*6cTjzpjnuPS10m(0f31Qf$iSqUFb3BFirGigfT7Mfl#{@x%e4ZNF+zCNll5*9-?6OPw^*9Zr-1UGiv3dW@2v|<+kKMWD z=FyskpkV;j*3ilQ$y)xQ0xHp!Tgq7mI)?w*jrFIYHboJeKxsCD9~Q)FS<#Dc*6+>+ zfJ&p~*XzB?)qD(~!3!WN4ritFJ!y1K@(xgZC~q*GM&DwJ%+RmcYir7f%4_Yaa?API zg`FT+^B~er7UZ2|80P}C{;}Gs!|>|cH^HMZSKe;*^6d?U4b>c#BMy_jEN9+RflWBy zOjvoGj@};5JCDQBTAjrdXukVyoK{Nh;qT2*_@o-EZir~#vbDw4-*KFTYL+DfWm$mf z?bu~?SH{P=%u&9vW*LErk#||gLjaop;#;4vivt?#T3l1Lh2!z&cSh4><1UF{O(cxX zu+3#??BE0b=Sr6{UfE`ZKTU#c5a{}T(|l>p_Y@vFUoIBpKU=LD0?Tkm!%p{?li<+> z#>(H6x_;jGxdU!Eu1JJ0>p^F^gK2x*KdB66#F=?J)7n-fUkPfd7Gey(q6Vd)^=?=o z$Uy93=|K>&r6r3}K4FZoIX24cA?B5|QNSoKN(rmm;3Z~wNjEXGX-OhY>y38lBGIYx$!13$ zY_QNes# zLolc9Gv#7@efP`UjzHbL1OsBvf}U?Oy?ubHm(gh_<#Pk5>u%0GHlP-jvH1Fv8|0}> zjEr8H?FR(6OfhSP*c#fbX&&F%kaIGydx0+Lu{^;6FP1+&ALgc8$L}oOHFO^u{44Q8 zXO05fp4r>QWSj9KA0vF%@BKlUxkx{DDYQ}*%#{>X9%q*EP<*`cyU=o{`6b<>0Ip+8 z|08~kUqkZ~8fWcvUIjQylV-nXm0tr?J-KN6Qg^o41UKZ7+&5VW4HZ3_#?px6b^zqk z3(;d?SArTCaCzFQcu%$?{4Q;m@ruHQdd%)0~P?-ad) zJa3fFuuC-aNp&Mn6NZP)NfEgn%-CN%bV_?rrT7R{-$kK+lu}-D@8p&D#l&4}!59%9 zZFW?Rc{lu_FRx&31ma<4DO{+pe?W+X2_t62BY2LwNrv9obX0WH4_0^*#01YC8A&YtwPCIIpj4qe%+&3WM+dFS z3&jTR3*+0nvK3`ib}M;-5^C6&BHS}uAA~<_@!ZtHR&xbUd6s+e(V@Xs6_t6#!n=2^ z1k+smZlA=9ScOs^od&|;W;pkqfzzHb=?;BY&xGh2VYdjk+CnMENt5(9SX*Cjx3$E6 zcJ|b_;CCmF&R(8C!~oc%dPEIM_IU_{XBF2_A@WLliP%|1$otsEOJ+mUfeq|vBTX35tBd09dL#RxipphbtBnMgD++<^|&SlFE(VxS5&o_G`LiM^Sf)|Dq z1u^2UT(I+}8jXKidcJdF!uV8n8iLO;k!Dc}r| zuo}HCrdj8nB}OSwhDOfKG6f_&&lMX zT8?qFncw0Qs>5q*<4ruQxdbxnAwhHt<8p)lSe~WzBhc!CCmEvx{$2Zh*@?+W>QLTH z8T8GM7IEoziB`nlW)pqwihb6rIV4?NfmVwqy9bZnRyNK0WgeZYaJtklGfB?#>QBs9 z?E+RRZqo9aZ?hS?(MTR;+rjeYxBe=AUff=;_?KSCu>74xa(COdPehf&uO$wo{sqm$ zPYrSwNw0|?mw3{s&v1D4_e69~JHza&Cnc5Q;1|a_9j&$Pz#A+$Z2IDLD|c+_*as4A3})oEJ%;GmD9l`*6euEo~^VKs7`#D4;( z&ZRtZ@?7%S${yi`VPnTcam-fgRlcnI)zT!#BJVrkIA!^&t8+S&^}#~dut7W36rT5i zX8_OJ=D1fT@}OlA{tEWsc$IX1Dq>dJBKz+jFSTSiuvR9VTJ{d%>T*&|wYHco*8}2x zIpV0qFugjftvXxXO>i}_+!Izz7uTCQ|J!ZYU3OE;0e=_Qx{8&KwOsDvrDQO@7~tm+ z8LiQl7q+qfJB>2j$2nO0^)tG;l*O`a29}uvm5{oV3s1ag=li1G-mC?>+@feW9DUj(I2zc|OmMZ?9<5d2c(_uqs6}s zJB8jF+81x?;oDnzwKSg{QxRW66%7}a>gF|eq+y~|Oz)PZyM&_}d&??zr8o02`@v6U z8GlOaKr#9Qor|lKeUW3JH=i<`+M;|^pe74eFkjV{uuk1&jf`rAr6u`RPsy~`4-&WZ z8>=6crsEEaMjdGizTQlyCdY;|HA1-!(# zc59?~*or>Y@LboD-qvMYqmsD>Oapq~0cUntUF_0{NP9rkkY~v2swFFWKKyfY$^4@8 z;Kk@G;HyJIJOUJyOi?Tt>7bj#XwU5w;RTe^?{QiD+#YvI-ORTshS*ExRcu_bqUOZP zrx3vsY91w444jH0i2UBswwiNsU{bw{0$O|ZksqySDK(IhPj=a*C%Dxz{U)uxc7_~` zq%HPS5xk(}hZ+?1_?d89DgKeTBW_Uv2mkJUtezw}@&nadbMhD;`EdMoHqvf(2W$>h%qLy?=qvD!+@*IVoJNA*(jQ5*mVAGe z>Fxw}`75#)_0Fn@tf>GNz-BXO8NK4Nntgi1(u~FZw#Y5aeeE@q z5Ft-DXgH#Jz#C<7jtT?Z5(y+Kc0kA%^l}j&6O^xNTh_8#KkhJBZ8RS6-z|Ki#;7;l zV4-doP9=3sFC^Guz|M6c+B?fqz*Y-#(;;vUm29ww;GbjyE%%F^X#sirubo6QaC)bP zy)kY?4VqFrzbq480!$Bvw;JcwQ!PQhgBLz@UnZV!pZicxIlkhb z+&sje=g;zWcK}X_@|vlxJDn+S1!&-|J9BKBUhih68|8!f029&n37m~(Rs1Kv3)#16 zavV-CJlRe$YnTJ`XKUXZwq(ha`@BA(ITeOhcJ;jjc2Q`nW|kV(>+~BC%GCmx3!ATX zR!cGtoBENPCXD}CovX#E<&YkQaDJx$Eb%x=>$}!r+T0EcOKP9~Fq0NAHg?gWY$VGy(GO{JOPFb5D^cEsa28d&fmRs!QlVE4@IEOQ{;{Z_SiAFT=Z8tcr^-M@TIg$zh}A zelB)Z-QmgD9914(9OYYmS-JHNdCHsCn~44Km+`X)7^yyzlc|3^mbSq)pZXxzN++e( zy#Of0i6lqHT)5lhf=4eXL=`-md?o|IYs&Z4M4O4^#R zkB02%z$9?BYoGk|e}EK4Sr}q?m_UGt@Dku)M~l=tBrrlqFJJ^tB`f^vctV|eKH1Mc z1{wa9E2#hHasKPu4qR=iwDT(I_%!6{PhBF>c>3Kx9;W73=!pBx^Ig;i z&0@%;uDd#^DCLppI2WI*r2~taquEgnck*PV2p=?&L&El9Uj5EYNahrZc$TZZ@+~h} zbMftcu)Qg@D)PJm%=0c;ry?HaW@nU^zB|+j>xiu`XiKrjO46mg$%#~fV(l|j6|hM~ zuC;-T={x(YAMh0NY>21YCT>R(Kln=%zs-Df*dOA}r^g41-U zQ$$3at@?vdDht`42?=#CdfDZ9X%84sQV&uGvd4LAU)1}V98qN_jND(E2(+4e2VcDJ z!*~H6ey9fZB<{L?&%O-8E=#QwugJ=$l7vfGwm*t;m`!MNIDO8Wu~afU9B-g`d8eC# zsyi@rqv7{au=CfLud)vtq)zAx%?{~79LhM6rCiZX0zMJ1uMwhC%@!LX`E5Rr&Os`M z4jtoX%;?Y|OA)e9Plm6LRgUBjk(*x)ubv+u5vNpQm~o+b{=BqSN(dL%|B#eSOyRx;;p^?+kv)lgZ5eaf$Zm%UnYey!f$Aor0U zdrZO`^&cAjg?EP+yRy$Q$Jm|m!&qz5Ah~b}X}WTXCis{h^hMrKdOn{nnB8{opW*%0 zJy<=RJu1)@up)zgiGsLYcL@`z@!YfP;5%?ceCGGqsTRl@=QW?eMf> zx1BJu>b|a9XltOY2r&*MkBxEOa$qD2wXoIhOi{(YY(j~&L}@`AM|m-)wvCo?uEWm! zoT&{i-{xON1Xo0CLpb5r_`nA-igmL|!0xiPdAjjvd2F0ZY;l6nz4u-RyN0Jw;&6K9Row$R|qPrE#NHruD9jeJ7I=l2kV}#N+c~pl_gAmI{ znr*gaJg8h#LIjdW2RY+$UA*hym)?Z-@C3v~UOc=;%iCqTx4cFG8eoccCVo3~DLon1Mb>^E8co!-&QeO7lbWOyBJ4TXJow zzPVpCo09=T@A6dubV>F(+1kqk{(}ut_zDL3S1|jIu<~wt-1C6Y>Ns`Z{Tc240G*EV z#JL^JLa0-fXPj3g4;VlOuoQO-CHLsxkfGV3ibF$U1}NVFJaiPc|1Zku^^=u@?GFMOWnMyv3Bq*`L_p>c;i z@KQhrc4z52ygF?(p&Qn3+qah&@L5irE|hi%cV1RIdI(t>sZWaZSybHm>NH%-b`kRs zW<*za`>S+iEA{Vi5xHc zbq0SZwP@|LxN1M%RQ+u9efelGtJ@OmoNz$-CYQPYZRZ=Gb@Ftf&&2}~^Jy`m-~E|D zZ0zA7Jv&*5o{3P0cfvSB9`UySEv^5H%KrZk|KT?HAI9O=7rgRKm&(^;g{Q<%x3mt? ztZZnUeU;7`0#J2I&fv3vq&>reT&uuk==iy|4!w+=yDng~ zgJcnUItoL*MY}Ao5I0;nFy4flJmPvTxCj4^DER@=q|MLQV<|V$$oQG(3sQleFYuA4 z-_-E}#AF?qTs*$QWe&BBj}R$s`12(KSXIzw?Ed$!T^_&mcuQSBl zoCU7h9~@28%|&n^X5W`Y{l&wR8ZcxC1#Yx}yDcObxUbS+3s(mLBZ?fF?(7i2t)U-` z|EU5j=e7#*&u2gZkNb?+c?h^Q`W`~P&V}`BXJ2lZIy*)d_cvR~M)<;|p--@(EdT5-2xTqdSL^&GHAW|KsgmC%Q4~FdLWq1`vBVnby z$E8i{h3D$Fu4j1*YDSI4+%U5dicnk=4JXd9`5A9%$@uJ$AEv~ z#_LenxlnSh&rkEnAO6WMI@e6-oEVYHp6(1tQ^$r}W~q#9OFo=+4s5H3_sCWi`;Yhp zIioU<=lM+M44l8!O?$0Gimq#eJ?8;Ym;dF?R?%DEN+~uv<%U){-iPEmB+p^rxVr} zq7OQk+@>ExDHmcGk@dA}NcpcCyu*K&=SN`Jz24s5sVhfKKB{;1%F#k z*RwG9T!@z_Z8%&mvO|BD8Xf-&40sw`d^0{o#oW)K{YL_L{4M=)0vUDl zJ0ElfxOFW91yOn~RUXPxW}@)O>aMfR5Lhwn1*u`kxAfeeadMVylTk2Z69!fLM;i1y zp4g;6j-YZ%oI`8?O5pMw*V+C{jPH_`Md5}Lebl+5f|T9Z$pOPz%%5!ai(quq%K@pq zf4QBCtN0nGNg)8A*I3G3yF#@H=CSxWa%5;| zWG2uXN>AIYyTe~E^u?1pIJuh7y<>`=)1g$98vy%^0XzSxaiBa1yxZ030$>8|KMsTg z;x}nK8nA<50EbjFkkIcS;)M4`%gPWp+!-pVPHtTC^zn=?Q8WaZ+>Y;#ctO6^h-oRk zYo>|QSf+vF>w!bqK1fI6} zj`@dVHcR$Re1sHPW>OuW46p-UFnqi0kz+ph5G2ucbK?ODCj7LKI#mpASphhIl> zUytFw!$-}iC_cdqc;|RY6>hg~w5xUj7D8sJe+~tDOlE^}YyX4e5P_=^GE-%S{Oj-_ zB=XWU!hxD4CMfKm&cuJQCWtfdr@#MC-*lepbDLqz-s3Z_SFXgEGWdfBfd7(AQ%zU3 J^q%F1{{_YY5bpp0 diff --git a/Firmware_1.26b/Documentation/posErrorAlarm/alarmSetting.PNG b/Firmware_1.26b/Documentation/posErrorAlarm/alarmSetting.PNG deleted file mode 100644 index d774fdb37f62df1fb78bd6f00bc909909874dca0..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 70324 zcmd43XIN8fw*?weP=kmlh=Pc2RGNTFQ9wXJKzdC;YAkdDDosj)f`|>UP(um5gc6hv zLd1qjFCjocRHP*!3WSo7V78>T5&FI`&P2A2zw2H8~4`Jd5L9yT}cG z-g@=?1wRO6`)kgh4K2QfS0E5}p24}Z);FAHMz$u$zrDr&c@_KDNyFMX+2N#{X%F^2 zzAMGE>8!cnS;0*fJ2nYCVraInnmIUDbniLY(Cxj`aQPg-{lQFq4;0R-WQZ!{3)_jWF3yspwGM5tk$3OA79VM3k_8aj3hSI#v zGXMG3=U2AD*()ttn9bs0T|Hj^xXQ0=>One+_=JLJ!rS7Td zwK4JV#j-0F_6Mugk@rNR>gOrNk!L;M&kNb4EPo1}%Q3V1^-$JL^A(e5*YAv3RNm5O zaq%_xt$!|TNR%-+c;z@xG1SzHSR}g5=IPLNIS>7>W%%$Bp8Vbpj1OD=;@7>dloYr8 zs3MD?;owPqtf`dQtfGYG=_$1z{dZ9lMRAyqgter)Zd8C5r{?;l zBx{x3uW8cnc0$d0_u_E5V)s=26v{77r#m;aI{3|sDAL+ICWHwqx|eE0K9vkkMDlB{ zxNp66Nr$+Y`GX)|_hyZxk8dTMi)fA09yMCyqnGq`!al2`5Z%J~{Z(T4J|Q{2i_u+)Mt*RwH-y`zhLfzt_sg zdyX=p<+!h0MD1vtOp(OT*W#>Wa<9&g-H} z9@dwntXreskwucW2&ePT)gM!)C{w)5!sL|IR4DC1qigPFIG^rS1CiC@v6>ap2kpBQ zPXFwde6FB|&KeWRqu%~K?N3IZe7ti)D*s8PMp@}VwW^)WX=hPhIw7bj#mnH+`DwBRI$F)WyEZKq@T-n?@$)(arqjZgWglW z+}v2SBQ{!PoFD~BXZiL{=IkNwc|hTFR3?&v1!i2xZKz`bLiy;YxDXW zA9gNGr21mWtl7YY*}1TmJ2;oF zXY@9<+#X+yxOyjfGC|ur&af!aXnhlX$W}FP70H%K>veN*H?*}o{WfY$Bn#&! zc=8EMB91s&t?#R-KvwhAcx%-5J ziTYnP;p3yd+PxlbCN*qWEzY6@o$A+0U{Uq4+mi}rN|(`hlcjGiMs!p{PV9^rvY&gJ zI99_Pon+N%I5{`$^R1H+FAKt=u$3Aq{d-CImY8wQG8{iA>*Hk1oo$e_8%4=!f|9ma z6#H0Q#Vzcs=gA(X{b(;}3f69et&bs?-w%zo0!7#ESGkj)L|9b`U1Ibmu6%Ep!?@Tu z2y8Rg+3g&d5vOY3* zdmbX-T_KB)b0+G-PcL`>E9n@@=bf`=^cX3m95zzm=P7D35_WcFE!7ZEi_*WMK%O+z zO6Z|UlgssEn;y*Ti=QYsa@bC=EXlRQQA5foC;QK`6f_((y1K1IFY8kX8R`12PSI!+ z&aLxQ%Nl{be0X7r>>J*fy1v~EJ?>8!64wf{UK;h~zog}h51(7nmGI1u^^w&0u(B)5zhRQ#b!n zwtc9|s~w~41%aH&aCo)^?M3KBS|3mj9{GmQ${cWLobdGP4{%FyA}ya#KG|=~3s0{X zrD6_JqmvJNC2dOD0D;JeyXbtp8!sfS_}57;mf7dYvCFQkwN=;V2yWMuQqF>_f;Z@ z7R;5Xu}CaHZV8bm{&LZkw>`|csc+z>Cer*mwgzs3KwK12-~Fu^^r52iqR}37Gy05+ z%4~#3V6LaTpjRtVZmaDENa34!p*lpu@RswF%&;FDxgcknR&!R9xgfA~*1@dF=NTUC z^z2&pR@W4K@8PHZiJYFmB96L3w#4a z>gI9b7=s2m%(1PKe+ifC6>RC6Lh9kUAm*xn-txY}y%1-gsl&XvD@xBxU;H{O$k9>p zTJsx3I0RyTdJFv4jZMX17#?#SVlPb|@xlyPgl09pyru-R+OiE{OY6IlV+XJ@TUj<6IAde(N_Qdf<*Ou;mAG;rs*NsEJ9C8U3M&E%zq;~%6 zN>SPvd*#0E2aFHmURi57AcJ5H2xsu5O@BXWb0u$n9@jyWtve_i4-9^O8`=AcsF}39 zb!j66G9LZsDfdqWx(f45Z=KB2gq(QL(eQC&DY#|Zzds1E_Ub42A!EwzJ@fSODnI~) z9{hbS82nYmv9-NL(aj%{AH3Vd0JHiE%;>KN*^Dm#xUcxkcOD0o12o0AktP2&7N5^; zg}ZfTAUV-51-tf5vU#bn%8MkDP+V3oGvL&A0?9~I^=p%>8NS3?EYL~``V`!Pbu$YSwRfEdy5hz?lseKJ* zc{F_V1whynPmJWZF8zd!BWR+dD|dott4M9nF1NHPlN>ICt$LZYHmQ{=i4E)F>B{On z#{>bG-6o5F@#L9lcv$$P`lvy%x_~|!G=?T^n~lo!kRbopGHi_X>i}n(rm(sl*pVy zF=?cB0+US0BjW9AI?%4K@9=rhu07|2n^}u6XCq+DG2KG2R;7+c5ZCJFniy@)ta)L@ zpzp(#bPlgMz0jsuwEXvHWk1HrZ^CE>g_N7QR3n@WP`$Jnenwojy9)KkLRxWepvBLX`veC;wLI@bwr`|MQ{NzMW)Cmu3&u;Rwg zOXTV+A9gmRjkUz37GTk8Rbg5$`$|{o!t5lckPk0bCsHS#wd_|cw!xcL$!=?8E|F*D z79xs|$ua8VVh!QV>zr{*}UAz&D%vJU= zJb^C37;h*}tyIpa2qw2wPIf46QrKXv9r zHtI>gYB(!w0S|VKN+$7H*Q8E>ovD;127;`$SpZEYyVV9&w{>&ZSeUcy|dMst=4xk%5}h zUP>{q1y6NlSvMpWA^Re+eJlX(^4lHr0;U!1O!JXJ0T%Svi{1L-Ran?m*z!manQ3jG zA3#A>TWz=2wGAX3ybgE3br`5Kbr>(K^)~vr$O6WdEtFFYolzH#&spj$VDu=fQl? z4D!5{mKhRWwRH)AkSP6fj5y}2p>8Cv_N=CsEldiReG7sXXG%1%;DHjRPgzZ^6LXgF zeCx63TW7_P--S*D_T%~Rfww~KbvR9^r1On0QI(y#uMJ}M6VpsFcvvr2t=5XtN2^=7 zi2hau!f;wRYcne?fWz?x8d=0j{u-lkw&DP#j zOdmT%Uv)2+5q9){EcT^Xde@?Utv&kLlwUBmuk(psWHcSJo@LtknW*AP$kbeid+PUi z`VgsUciLr`gpu;p%Msf6%wRs59ww61XORtEvKee_HN%=mR(|m@p4NJ?;)oBPc8Opr<+(wy?x4B z5#-$2Qu_4nVCGp|umv+v_@QgXtR~X}_tiJLhB1e0-wN{h?W61u6U zF&sMA=)uTat+O6}{p$WLcATIH-+l^6#n3o}a=8C;zh9?@n@+!b<* zE*SIiB#UOhkgK`+?P;|se{7F9N(OyuS}%gK-lU!r|Yf~ zPqZ}Cs7ddQC)4hZI1lyU1*jhgMywsMm8s5a3GLO4iS|^truhW?Kyb<8UX48G@RxK6 zUByx>38c`wCXm3E;>fl2J)4R{@LGvg+mK1IMb%ci5;nxL$94Q#Yvt*&XBQ!5=2x98 zlAQsF{Cc(=<4h-8Hse@4R$WDeK^5OmY5kHSCHHxh+z;Gj<@b$ZTVlnGygEU|$tM_D zsBqA%;QPV{`gwXIsv(6$0Pu?YB1_G~1nKlSA-m!!m1Be^+v5a)ZQe%yL2MgL8W0$< zYm?E%**9Ug1UAUdo79AQyeZxPF!OOS#_~*#2zvf0b`wKbV!{UC@*989wbbVNs=5!D zBOYIHwKoIattv)fH-6OSC-qow!I++@2}J>z^Q>3pHhs4!^YU%Rs{5bdiT(pe<0VY^ zyRHYcR$hfI-rPUJGJbh~SGtzgwN4j}NDg9KJ@^|onr~2wNRZ~b=}(X5W^Sv+M&IK- z!ovZU^I!x2q6=IetoP{6kwR$DC|13%U>7&Z znhIW)7kOI$-OIbMSqBWjb;*SRxevd~Y{~FRI!u!;E_MR*8F~e6mpfU#E_@oeICBF$!G?5c4NI zZ)nuamN2i#qQY7a3~UAuVw`bWRnGdbE%y@+gE4<=j8z}uao#8|iqMgbF_$x%O5hi{ zHx*sMa=#!c(gi(hznZG%>q%LOtG#lLvgYnz*^%DiGPN)1PJWSl1un+1tbfVxW8>bEShINIO}FTRcn2?n+dx* z8~Z@ik;37}H(s=UG&%X@l~vIG#c%AcYA&$Rb_nC3zo{GK&Gj5-l>DOrK_B`>N8Om% zc1htKyG3JGwjq6k51s-WfMNiJMS;mr+FjC-d|YB+E8yh9EaXJ2c*p&Q@!_O7fdnao zmI18^mP5S{h9|-b0>R}QXW_PqsvH$6c_O-DdQtH)6fS9;jOfr<9!BVcC3-3Ik%CCi z{qWWXg%CyqUglvLu@}V0Bdlv(uk(kWS$2u3RYM@3-#j)c#C78uLzhjti@)gs#@HEw zK4RJI$)wXvqPL3~FMl5~Dzz#wb?K?|o6PRdGfK)P0Rm;1Wnbf?tKbg^bl0`>`n^kw z)j~%qO+Zn`g;?gO-di6)eP~zdev#5w^b`vB`w(*zr>DhBPdU#G*3$ZM({d}E>-X!g z+_JnlB)NKGsynB-8h5Uy*`^pSH;`CNAr_|sG*3QA&sxH{e|>Y$72J>O+xtSzOV6by zypB)PrN33dh^t!al3zOoz}0Tv@2>Q)V!TY%iQb;lA|5^*M(@R%dij2OQMU>Rly62j zD|msUj5UCQifP`|kQWi>vNSj9>vZD__d>tDZ_4KVH(oBzjcQQ?A>0BbZ6BT-HuAO= zxc+XhoAn?f01Qh}!GyB+K-bJrRjZOmPwqKFm{k6m_oH(Thvf8IEJzPo1=%Qm+J{6! z#-+yHIV7`#csXV#iM>}NY^A*J%N^0SfoGSkP%6lwD|!$2JPskab?zrGgWtJ=$m{xj zxGw)}Bu~-Oym>!07OY4Rv~+9PEJnMPnT8ACaBkL%JN6MA&rX3Fg*#z#ah6P4YYAVA z4xV||VhqG0B%{C7zWsqhlRF>>u5=pJ?R)Lm_Jv`;&b*0`w!ZC|2O<)J{oV@MBo|o~ zzR=T(zbo4y85F4 zh>vs1aka1Z_Sh}&;I85`?4C4E7qq(&x0M6mzyx&RV6qHn?!0aUj6We{Ji(@?X>96j zs|vy1iON6FW3k5Y`KEGlS+lsaEAXzhO1MSxG+dXuY5-#qJ5 zutb^WY&q#YfY_)&l;qY93Bmd#k?Je8UPtqrRV4(dD_Q!_4pl8BawGNePK}m~sks{Z zJEY&R+SkOfZF^4~Dn<1bT2yP2{cRmcX^bs)fY!}CZ8#3EwDOG7bm5@hqX9@Ee;}+T^2(5 z+~`H?JKM!PH&+%;$s-7HdM_yrM)`q+?Pr|0WfzXf+rpBw>U66agHDCUf{ZSk?r zMupkBpQ}{q#j51Wbh`KOwU|2vt4-Cz)kaFT#Jj|fbanE9-cm)Ya+&%GfFpY<)uj8B zr^TQ4thKdp7aL5f_bPKrzmUO?M{J49dA?y|q7(XB^vBGy>^Tb=ksIHZL#MK$XO@h#TyYE3{G1}wGN$%KCZHfLuV~% zZW+P(7n;I??VORMZy%oSN_x6jH>Gw+e$CL%wC7pZ@vAk^yL!DIDU#{_mfqz<&o1kW zO0Bl|{`lM+80<2#y%7#6bf#mB?FoHC4$?QRQVF951gKm`-Q2Ed1Nt z**9dQ(Et2!7)uo92%%ERr9CYYCw1 z(K4Tv9iv(B8ofFLUDW??w)xM+Yn1$o0A7hd3MM9xvfZ;#2>l zi*^?ieFR7f+CfJ}lsyGSOFZKp{TtF8s&y_F`9$_h=|%a}3pLXo@MK@(JYe_u%K!L) z*%EM_=Ud^*J&H<~s?15b;l_pwisHg0N7CnvNrIf&ydo=YOFWYbg5to<#ZfkMw7sHJ z(`)X9pM)iI?rXL{QN6@5s|M%I2k;YU%=7STFF)pELPo`nn$EdJ%LBWNPu2G&#)rMi#OxS z^l4k$zu?9v7??gUc5?iLo2I<2iP~sN84!FRkoR!Qa!PN!yDx!RE%q>H5?)x_Af65u z*Sn4^%s*zx0)v2^jn-55TukLUG$PUn1Tluut2z8Jql59U_H$cfj4WEa2;a`>>}U@t zDmP-$s6y&L&jB(Ko<33?@=GA;LV)-enA^V}}|=G??m7s?X776AiZ zfbd2X1>2uTPE{7MY?Y-3PN|@2y$*6iCz(dc^o+3i57pT9WhyPTkTkaZ*uC6t$Zu?c zWHse=+(Z3ote28)`*PJdX?$l1Wlwqtr6@2LN1qB`V@>AnAmutST5^Afu7Kgy4u2EC z_#tPi7sd46^22G3KdMMhMvSKX$wVnz;z&>kds2(7DtCw&lo&LMB55Z5mHI2sruOg@ zhm^i_pYF*EjBwFdai=d%AJ%&;-8R$^gikr?o593qD3#d<6L&+;3fk2b;JtEFL+K&w z^K2LWN))-Uwz^=n>GHMK4`A)`nv<(8w`^C3nxTjjo3&YPpvV(2TqQT8$Bim0Eg@%h z$J4n>>)TULl2HN7HD*7f7THl5J9Rw_WGzEKpD-3DiW?3G8iD}jq{UL1qz+yG2y`h$ zXnc+DsE_ZnI8DJ;o4Z~;T1WC$Q{s5x#N9znTY)?S#D633qz4itGj6;J;}DjEUUQ!s z+d1xn1rmX!tX!+#+tRo;-#Rf<(OEre!O>$y^C{|=RMxZLg+)Qv+2K0H0l3Jj-F8z4 z2OZ9Gy6FuPZ+E;$%_zEo&r0agC&1&EQiRGJBQGf>>+@HIfFf)gN4cdh&tU`9Z$@l^ z@79Qb3G$X5dxSvJ9z`UqzX1PvquKEH%QG(!hkw63;8ecz z_sbm$wg8f@A9saI+8RJQPL_A9-$c$nVw&b22&6W6iLHQlryh+$Z2vjdVnXdNjhr3N z@*z`(UNM{aHhAi;!yW?CW( z(yrgXQ01ARAr1n`37tFJKH&I%eexL$!sU|-CxlG`_z;22v*-q}NBY>hURoaVB}zD- zBC70pg#!d@a^R(Q6T7f0w^jY89;pH@k8G&^3Fb;AfZDH&qAwng<`-81E2ndS<5L31 z0h96*ZX0>F9ZNmwTYYf4m0KFIy7pgLs-$;Fc z$`rZ$V&rspPIM`$5H6>K7mEo5AQ&lQOH^aJ$UD>?D4qR4yoRXNc`BGPjU88bE!aS-gWN{tS21GAmyX z@i$Dkgde}MtHf3D5*WSGKvCsae&60d4onG2_ppDeSE3gQYs@%)`3|4FkeZjesFFLP z0NV9T2so!333CPrw;hmQWI1kjdbqBFFMz2@FR7L- zYR3arhjSpfW&N_dlQG4;cq>~_X#qSS@Vi+Qx(o>xXVIAxA|*Ji-o^T5k+Zl*^SMt= zKYEqpEUM~f9WQ#eCd!$_h$x@%@$!g(A(N<*`my_t1F`tz<#!LCEo9M=KDUdUg(U&v zI)J0e<_7rXd8XJ^j{#` zkZh!O^!IUN?qr&zsw}PO$CYZTgLU{ug#g$q=eQ{Zc*@GpvG$J%vb_|CU#R4BovLMt?yYCUX=B$YYJtOO{13;wS8Fq>Jo4O{2%mJk# zHD#O*evahjE`|!zF0iZ7-SJ#Q@DX{uiiVWo!NQDetcQJ0>*A;z*udCIbbA!;avr1) z3shKB=4L}(uq=={i6laJxac{ra3zHjE}JTb-@AHAwpRwp7)U1TM-RBse1z}9M7zqN zbdAtzv8W;h3<(uYl6UmnsHJh&uqL&^A}gy1qEz(~)Ee4j#nfkB7Yka-#9OCEoR`z7 z`RSEm9pl5tT`XdNqqSqTw2*_@J1orBY#tRNm-MraAiexkSPXBlpy9_#q_2 z+{`~@|8s9Cbp1?-VB`ND*g^Sy{dmLsPh$Riq9H&3kuMI*0^0TG?JMR|I!yEbAzA!+ z)Bk?W|4%vSAD5k&xwU!!v6|uQMs|)MW3(-FYGH9$wE)~+Ep(Wjc!6s>=7=4K-TMJg z5(cCgZY?Xg0r|_7-ruA8a;t=GN`-s*Q29ljg#|2oIBYI-R1s(#)d4jlfvI(%Y-oiF zlecvQypj{Fl|B2U{1~$}sUXC@UYzcgT&a70*QaHEycG#a<5XTb$IGp9wke8Qwxv#u z^>x&;hPJ0>njRPxq+Pb}U0%3C)5_OMI)K&590#B)V`TfHX z1eHi7g~r7vbz`yW#vl_~&awheGiE9R8_Q~G(bdWxjdo3pH64D9E1$v^Od3W+0;meV zgXft%LGa1E@X1cB?}ca_Z1j<;fz7eErm4qTccsp1)b75L+FB z#}j@L`HWB>ik~x+V$&`Wclr_!2zxw$o1+(V#4nVMjK+e*l}aqON#&Gr1L<5y{mQs2 zc6eSmn^ShL=um6j1_IzP0EH7L39BZad)J2%)J{tgE**j;no9$h0}oAtg7>9~wiK&u zGnHn~N~s^#$v^=r9Bv5m9dcU+$s0{8cFy~x_4CcH2}SIxF{LrWoVyZ}eP%9)EP#O? z7?SJ_aV*D~6RXTJP7n5bY$`4O{p9A-AaCR&U^OGuEGv;JI;9wo0T3sb_Th+a06(7c zsjdI7h(%$TZQB?$z`oN@3s;(b?A{lIY!U1k~d7!`cJn9NkFbZaKRF z@=8F%i{e&g+XQDeo#YCFxJQ6pORt$0(%H*@I!h;d=B^E?EZ7`osyZ&n(5x53C@A+@ zLsI_ZYOwAtW-*ItDo6|p8;1x0CWNJfmPw9*Dbs@$1sCf5i-N%}n0=ksR~Bqd`-avy zcW;1`=2T!qKLR2~Jpi|4O{ZfV!_oVY6P@QGr;N2UOMU=tYy z3YjN?1%tO*Nc%Xq_Uh1b?)cQcsjxsw--qv^g=W=jG(oR&k;bJpq=T(k`SQk;9S5UUE5!yfvELUW*W z7(n3xj1>SSX63%^I%0gj>ZH%`z)}0^wtb*B&7;jxw;3;{oZSWMr-UCQ0s^Pm@B$$1 zyu?ZRDQNNuIcGN1e=O$Y&{fZlG}Wbm&I}Etd0x0&&j}?#=Pa`tpOH48XU|Bz0<2`< zrBUm7=xvU+?VF?pWJVAb9_-Z&yMZ&IcF*_aJ7+l7`#+;yV@zrmJkAE-T^a2C=j3i+ zIvGI4ktcfg>$tstbkJiqM=$0%c-v03SR8+;q&VqbwNA^0Ny|xVj-(mizkkSdtC$V3 z0ZClatr@JEt~a(r=lfBBHNXw*5LXZcmpH=FC+Z&R3TJo0CR-l;4gqdm3;+dM?NWX>+q!XcJ5UpNwV%WAl$6oTd*E?RwnGvi_ z13svHpOJc%DQnwo`x2(h$_9APd>=_%BdIcMq^b0!#X%V00&UX;SRda4_?Fxsdep9_ zFwjI$L$!ICGyXUH=PDc5-*`|TSs!D6D>)JWI0IS$OpR{g9x^Yj3iD>wW-EJV=BrFn zmdvuAXe<mC%o^#QNpzVxr83CVKY0mWrxk-6iIt?(NqPSN)3Tj1#EhWW_#+t?MZ5 zxCR#Gt{N+BjCxu352cWYj`s4CefM~ZMV<}S`MHT+sSj|4!gWc*c}Y$fxMWoQ5$5Hc z8j}XCF}(1n9YOhC>(Nt26m`<78*zld%8K6qd^BoJ4I(51)aXG|?yKM43-mUjLVL4x zHmlz+1q-mK8sxB~Ei|BY4bLwQ@drOi)N*ax<2MpO%A>eUcBB^}X!)r=hD7QD*yDzc zBzHArr-5WT(9Z&A2D*6+S@j@!d)EL@RHssFl7bl(fB9ta{I`dU0?1Y1#>@|1m{7TC zc{LAWiexoOBKUt6$&OJK3$1kOe`tttdKP9FC268$DgwsD z*HdtRw9_e7GdmxLa*ThI;%{MjaO%6I5K3!-8V=I);M`Rpl|liD5am8HxT#n~x6mH1 z?3*ioNEQ9)5U_sNoNipw$;ch|(w=(zK)67zg&!_dxr&5V_&=yc7uAg`0Ys!?OO$Gu zI3{Z@Gz5KVxa@(@*W{R_|v7s{`*j@kojxrz%c^~76Tdo z{z(6+8fH(P_Ncqo?Ai0T%;YkrS3)11)0Kb+BxN~o&eR5ycs`&udR@|cdbXS;Xy8h~ z+vfwQgo)5aDsUi`TGc3kI>N{uXQ*VA1}Hda?h+F#6hMmz6p`lxO4e8*_->Q|qkx

    ASxr;4HX#>8)8h~C^AsB}p5PJ6Wa=To5~tAFs=zm%|BEzut~0pj`nrN^ zvYxIpaorWitcS%CIutukzXsODYXA?#a6JW8e5jRDwxz_3pyl)um790>fU^vm4Srqk zVk;piwEwW2^M)MlBkjz>)g$_G`_olgaN?h&jQa>Xr5C#=E5nd+KKSL02T9J>;T->q z19U!Q8VZ(OI4*&uWyA1JT%py zS*u&ZP)fo$wyN|S<+CMM2Sf>&d^j&&Uf*vI)q6k>fPP7SY4TADSIkmF?=>CSCB26(d*9uY)qg`7&Hh1{CFL3^&;#&to_UF-0et%ZdfFxztjte#+SE? zYkFf&`tG0M{dLlTIiO#O9z)z5d=Xs1XW-V3aoH}W77vAsp7iksHeJ`({V}2^F@W@w zLt^T!_fQ^+D1Yn^qV~6!0K4m*Xi*jKV;UigtK%MXRoh7gK)(zO<{%m%z zFrp`fMj3o*b}&cVv|SbVXz|5DM@5dDkj(c{!ssV8e5cGgntq8)rgdS_<4nM3Rjl%j zpVbU_se%|k_|O(8ki{eKfIge@SVDiug%XgDG!c0w!Uv~?ynDD;WgBd&WY!xX>~xtk zEuL@g3M|>Cqv_KsN04D0l#h#0zG1zvMc6Y-x?O3 z{>qTMSWM0T7)W|b!1-xh1qiX4(0Q<}XrS^A1A@>ancUOUxliXsN<6Jgee!IQhn~9_ zSpjtPkZcEvBjj=V2XKGJfFrjjAHUoNEX+y$)qay5*5xAEDzu+ePAJ%j_#=h=8lA^a zd3PT@U+mXRd3kFi^79^LkDfzhU@N_^=SSI%8o|xcPlA-?+l-5_A8Eo{WY+VA1G8tf zCQ!h30+AS39X?d);rjFITMr~ie_}0D$9wJ)r+W(uh`(uqR5HTF^j(~|FTBhl1rEes zAQugpn@i|01A&`LCce+DA!yFWx6>vQ_tKJ0ylciC&zc03kfIVgVuvRU9T^G1+y4~0 z>pIjQ2I4y{9H83u&yuquPnij1j%fh2Q2F<&2Lt*Pl=FwW^MI^Vy>Q3V6B6|h3KzQJ zxme_5Z?jTJ{;phK1suyu6+mK~qkWd-&V^bjzp`rWiHFc%aD8k-F@{J_CC#dlfN<6P zpjNPu%xr1y%2EtJ92sIBuiXXo3DvP`y`*VECrIU*9!yaDu4(ZE%Abc{3FYDimJV)T z_;;JAX1k0DuNaQIpL3Y+0Az(WH#+M5>BZokTu#={IVMzsGr2g{lV>y=nYnmCX5`g( zy{J3+TwQ%!K!;RT51c9I$6KB+GPguR|Ek(H@(v$tsa&rtSmJr8sQ+X*Ypv4dL4<+E zPvw`LQDO#*z$k6 z=Kodd^IPK3PZmb+>~Vx0(|^YKzz(zIKh{3K~3SGsk3s$FCqSeSM&S;q(&>UuzKq zcc4b`ChhCIW44ko5^cgCz<~y*YqMx~kcm(gAvDhgAj-Tob<3Q+ zyY$$Y8qiF^vKA%%`Y*Vp06hr9aq6xC+08)iZygXgpHd=-E&D^;Vu!eJ{CbAK zBYH2e7;~v0+~rg5Y}EN#PR>>^mgi1#dJ8P)us6PLT}bH+ zJ3@0hTgYW+av^iMyGuz)Xk7@ZN5HahURWUgm-cS4v-zWrS#E((7;}mfHs^5`#rP&V z4wQtAa40bNODdskMJ8jp=ImuqUEl9SYzz(R1^qXbnjnE!qXdWOG^pZe=$r;9WQj4* zfKE+->UYhC;#XbAFTcyBDFDAkI}iXVqjWq;2Bf9)4A8U2Ic{cyx@L-23l6lTr%y;~ zt==ngY^X+sgC-ozDD!(zQ6SI(`P!dRrmC5sH~eK7#R_X!j0Ke|W{J;uP=E-AscIq84Mb4vlCFFrMNrvc1hMC*Q$Bjdsc9|x7;s=+ER8@u%W)x};j zGD*ZSWUA|+`d4C=*M92+D^u0CO>sQM|0&h|x-zW$u4&8+N2=p9#D-9$7qr+5T1)US zjhB=!(c;x-FUvPmfLDE1Cs)2<=0tCWn^}ebwB>s1O|(&w<3b_j12g1mAMjNpu?pd< ztrK;V84uDg)7BO`YZjU*8|;1Px7@MDRA9dRHDI`SAj@huDNRS9fw6JTwf z^nLO3PP&3hpZ=47D3a3upCIf18a26z)ku3k5Y!O%^4s^FLe%?D@ANk60TW;aXgk9G z!ne?1SofQIyV}8$Zoe-i8!_u*QAm{$e^R!!Ea`bMQ1w;OYqcH#Lk&^QK}Q@g`@%s@ z_#~FSHrWnJ5WY?!(}(>)V@RrLx*9hF6qZL{fNeHWfn|D^i=C+hzN9N)C#!tkqB{0a z@xF{La-cj5EPy27C^RV75dAIkRp1w%y}18v&Pe`AV$S6p&|_mDwT<_exsVT@Lppa5 zp9BzG9`l8mX4t?mXuois8F*Ht$ti$K=si5&I9lNrHyaATWCdVJpeM_rH}hx2?Mgg=zoQP1sAHW}1c5t#Y)>p@LEWru4m4xuk5f3YBM zXce>oVZsDBdC1M{evGZyV;8k?jlfUm3IsV7DcH+ifWRs{)&JDxo4Y_=z70e>;B6f~ zA$R~eQct|24?eZtW(f83=ZPR_2fyrxzB^o=g>!RK$ciEExF_Je)ZVB*=UU{f=v)&$T=MN1H< z${&u!>)i(lwST|DtPwB}MliCQvY4iJ`oq`L4(i;=t%~Cij+R-Y#jrYovMk!SvHG6C zsZ*VR6gb(0XaGP{`R{f@7VSypn(?~Q)se0Hpsg)Mah6((AU2YY_y62`(#HYUk<{sR z!hgTc?P1sDns7+%Ci)N?qt`jxsK$ulhnCp`gXC#K-4^lse=`u@hT!AO?!dvL3S^YE*2ufkGscWU zjxxB2zaVm<5Mq{2Lr@}&5r18m=|95kJmlutCsDl=dw|4XX*W461WJ7+Vx^6un%YG#b+1<;!oz!zq8 zeTpdrEsbZoIjiu$`U?#gCIv1uh6LPuWSTPq%p?i$f^uCTL!A)B4g2?+6oqIFSb|P- z{fnI(;Uy`{T(8xG!-W(@wia}z`S%zsp&ZP2*Szpv2K}G0OABZMz$4@_e}EA3^$2Qe z{Q$_Do^A>$g_ui(DXUha4P zC=uBu^0u(6oltc^)C5_Zd}19!*<&wQO(t@g!FxH8E41M`rLxhknpJha zIUzz9btDy`TnQ%Bf*KRMy>E+F%-ufZs#-NVypc53lsi@|P*Jb!5MUSnFAE~!j|CA( zzhT_PgZmfE%R>Mh84@U7*WdsjY7H@E)&u$ol_E+iMHeTg&Usnl|D|vnEvR$y66AhN zzIiC8QukSGBqqrkRQ=*VpMbRYtLG#RDPJbdHY2ssG&~(U#UQtRardcmxkpYiKA23%2y?K3!m9{s&UAc62%h}WG4!`9 zaTiNPpZqbzH2pbGG5sOeIB+VF?PqfM-_8qt<@koD(puzB0<)6+@amCu*k*35R5*T5 zGUM3jYDbXwdtj{eU3d$=T4;@i50^W>=lw+)NT&NH*;~7wfE=*+TakpGwJI3_EKS82 zwK|^E4%$mDW3LHNWPfdYF3CfGcW4k zrdC*hnCiE-a*fkmf(Q+s8mcNT0^zm%kI64@H}EC`i!LaWCWF3g3_xCkSC#rCMZ4Gg zHe3hFFCM0k|5b0yMuGZiJIKg0tlFh8pd0>&nb2?%m=5!i4PWoe8dmJU|bAd5Hg?njOWNe7T%;8@>YWzYCh(o`GBxhX)3Nd-)rQ#Bn3 ziSZ=P-D0xrBynB{K#v}SU_Q7q zu9{PlGe!cVRgp!G-aDim2${3jnZU*sp!AkAM0CU%&ise1QuO|M&s}9yIy97FY8xEbXi;1>sI44>yYi z9Ph%58`tdYtAQ_Yk+`@CqCj+;^+G=NX(Vki=gv;4Rt6SC zAEq_3$emsUMi^Lq&Zu~%~`xfT& zn3oqIU|%xyu%4eRqvGmkoh~8(DV%Z3X~uo>Qp)GDj4BfOQsm-c2the*$eY+nq<(lR zNv;N8kMP+7OY@})n@DFOiKUC4y^-015tOYAa7X_Sd2b#M_1gcBw;ZRMj-zu9DU#Fa zlr5A{C?reBmL=JSO4dkLU;mu*C^7Hlx~|vj`FbvB5yK6b(q~Zj*3i6*EFRG*IXX9CwyfX@ZZ z&VKWyuI^_LK|xH-?`6bcsdNj;9A&<%Hs`&1;rEGji(ssju30b=VS}d?>kuuNk3++g zXeUAi-P^uks2+Te63%L}cb|N{2joz>v=!Z*g>O3M^9J|Xe8mB5QvbYxB4w7O9#_(4 zucDzqSzB;U2>1fEUYmTcCQUA~EDl{81(Ru*J@hxfw^>)IFTZcElyAD+3>hhxeyw9+}XM=8%Da zKqo^tlF96bY0PZX$&l+-!dZ&!SD8klLB@JfB0`=q=0DUgvWFzEz^-9eME2@dZ71pp z7;fqsE${Jq{aY_T)CDPT2Bc}wE25S^#mb+KD~|`2yh?sS%eAu@{!dQZR6FO{f1-?Cre)o8mqd(&~ml>saZ zFM6d0jX-m;9FhvN!`yrnM(x22+a3ea3oO7uo_`x3%BJ@`U+;3;iP6>234^m&)4;4K z-yB(*0tNKNZh2gUt*);I8l&jlcV~wJu`eDOo5&%lRSuy;bwB%7)7|I&ySL!ZeFpU{ z(4*3-bBC#6(*j+QnmKHtI8Ey3PeL$b)nM8sPsd8|h!Mp&e8pQV!1>n=3xs@FzB6#r zHAr+0As%W!TKPnsxOcgQ3{cETt3n4Hz{It;fQm&UnAWBI;!D=F;ecb;GDWUhY(lsJpXo&Ix!P zAUR8Kv#Kr|M>H!qobK`5OZGd8$>XNMEX2J$2P&De?jDoyB22V6!gv85MlkUNQJm8- z7AKy^oox>Ne(acXy+XV9vl4z}_<+7F?(kk+5m^jPaHcXuy4988%k?s*z)qS7O3YhG+0-dBNg1@PM)%2ctcLByCPQu0535D_Ckf+&vP1;% z0p@MQN8^ULcjR7-&Si}2K41YJqdrW?JQfcvR9W5U37gQbFhms2BS#z_iuH=hyF6tc zujFAhT)j;5CcKAg`6&;}5&JT_z_-qQa;de*-b!~0DK9p4TAEAVV!rNHQ?b3{U{6~C z59ci!S2{Wwtv0qD-rU>#zgtcQP&Lef2Wpi%81Itomi5hU;K${k1Uaa^13H=_t)fIM zIdH&_s%kxHq707@0Lnb#>QL?1*vbWQMS67xDSlQwToGk_Z;X{oSY?E7IUY} z&!nEMGa(F{yK$gAaAFUaeF7!crq`6i*d(al95PCv=4pH(xQ-OFjDp;XU}8a!FmoGg z0k%h4fYYv%uRWLdxwU6z3?m3#G?sK3YM#zYnC+Dk)cyC&aXPZ!4SGwCJ1Vs+&oCFB zwk97OZs~b-q&XI~RvBh32D$C|Qy5VuE!+d@6r)mqL_kU&EBkb?am~#^vJ%$)&^pQZ z*d(d#dk_uF19#5@OZIikIY$A>$jb=-p|zpio#VsPXmGu}WqC^1?RyD5Q=I9ZU6+LA zjhR0+O%FS;**Q7i`tIT2HYmDY=^jJ=EASF3DB#Y0X4Xm{fI0+<7c?6bh-k}h1O*PQ z#q4crzkp@cYAfdPxuwg$y@iV26-PMW(q+UK9v{0&x)q-SmM+R+9gnVcb?`wa*IvAn z?>vCB#i;`W>eDJ!qpaJ>{e^4Hh=(Z}iH?-0Yv>;*Srx80mlF(BQIlMaQ*Xjxksp43 zKVae@(EOi+Ky1{N3NEsYjV3qn_P3c6!bKh=0Su8M=u#W1LFyR}X`W`-GV@g05fn;wHGO!h40VLNUH9R`(fAQ}NX zcr-XmBt8hB>J@BZtsS0=d&iZZ;U})NYOIg^Ve^P0ANeM>eMMLBL{laRS?X%S4}JYp zKaVd##{chXjjw664wLBtdjr%vtgK*vP=uXcS;i`FWtni5)`p+509Nb=NlPa5KXp^j zNI<RYqaQK_ukN1;l3m7Fh#|#fHR8I#PYR=CDeZY(-oiYn- zuF3*Tko}PV&FEZg;jwC{73fy4&Qb>PxfA%QS1yUrd;>d+^)jpm`l2$~cHYgua|(5f z^SNp-z=7paa)FR5sofs=7#K7OFw&!6 zxdT}H38ac!2YvcE{{6#n?4A?WzaD5@u45~cin3$?Ow;0bA+*3I{<~I$(i*oIvz)w#l=*QAL=!F9I zDWn+sR&lE3tli-_Y)ED0WSe38FrsvZ?sC)4>LilWdu+XdYtmN(-FQ$?3=Ll7n%>Hm`5eP)pbsn`;3=x+Oo0{Qv*`Psj0y%S=y@JB7l9j(p!o1j2{PK) z!4;tFUk*G0k(Z|omOh3NrHh`a)JpSHcWf_moF%PW6iPq zYiI#dRXPQa z=0NGTBonbvCWQer-_Wk>o#UbEf!$=rlX0TQ;rc(SO~?ytVPl=NX$NS(ua8zQTvevx2Q~nS&EJ-c5!x2k z)Q3rbb-3&jxNPF~%|PlU_6q*$>UDtdG3K<>Rifj*GrwcA%>2kVt%!|X0|lk1I7H&^R(;iYv0kT zuFD{@?Gs=LoG?aJ5O-!@ERqrg~@Kjmd>D$eT zPNn=von7B78;ZoNM-sMbhHASJXxtX>=KkqS?Ls=DSmfE1K9dWA_R)dLh&RdXq5GtZX z^MFzoUZ>8xTp;-Z-SHl33V={Szv7E%JT0mFLCgIGD!0^p3BwCpjpGe#M9-`8lr&H| z>;$ROP9)C%f6ds{+iY0+H&8ih<-P8I)D6m0WLXpjO^vus@8bw5SJgx(9(@Cfw=e9N zXMe@TtDWr;N0;v`M!$K{mPhpe2uT;!56Zrse#)*b4~&KG98)^_cx6zYu?EN22PhvP z+f+gN1%@9Z@|VxV9ccs$i$tMrxkNSmCdNw5chK>BKn>BebGL;N3pk;Dn>$Pe{&+`F z)X$a&0^0N?`jo6G*)(YO>Dx;IdPF$d`tnl6I#O99^E%WEx1fPd1di1$kh;p{<9Iq4 zrJuean_7snd^P@mL&~+C#EWv_vEvAtxTY;2F0sVT!$AM}yC;|0X`iP|JlfVjDc^6C z|Gn~k9LxgAY;Xc23F8(IEYg~mfqzH$ z!@_1(IrCDcU`v_1x^?N$J~PZdh;Vp+nJ!|VIj;_MKXy73jW9Om0<@k5)6WQJHwUZv zdw*iY=uUQm)cqdF7(}nVNZw12erQodQVx%TiCL+@*|u}pFm*~65fVwjXqvA^zFj~F zdZd2eU{i*ceyLPshk~zYZNENcuoLk0tLZj9&=t4G%ED+tf-5u9q0AF{sN84ua!6?~6yljaIB>KuN+g^57{J7AH%Bwg2s=_jeuW|M&Fj zsbKG4_zgSG3Qhb!P4<{p{fSn4;$be;1(q)TVA`BJ3*M$)(;nb`S66eh2}XURJ4QgS zccBbnMrDn1Re9RB2h^kS9q@-u&@rFGWmv+brb;6u0BHHotEXRk0B9LIJbiM0>LgCFb~~6}>;&M|gn2=Fs(0b$huue0k~1BE)!_ms2d`#Ai(JReu-sVZ z4m)fUa`&F#jED9FgNdgi=(?1kb5laNhr=UEUt?V2KuW0kOREE5rBUqk7I0Yev{8^# zDj$?%{RQkoA&I=}SvH zYdQPuaLrNVJ9;CV$_2Te{g&b08+uD_#W*s7(QBMrXhu9g3)CLRGVu55i9j9i92)1I zX8>|#oI7oq`T6!J04TK0yod(xtwjqHVc$Q5AV5V-XOQI!vXNj81G@_W^#L$3AC;^_ zeLxv-e!;e|AM{U^ocmh2aN1|6i}PprvdeV0sUvm1!C9aY*B3l0Wy3l+!M5}7#&4mO zL?MP+W4pytX`UHfjF?(yr<*v_f%p@C8?c^rcwUBTV-=eznYfRa#OGwKiyrLZ&h+*J zaI64(OFChkCZg==$}R-{*;qM?hYcbjKzU1Ut?p6vxet#{JP2Ew)2st%WlC}5$CI{T z1WwFXL#$$ae6+pfl7qC69Kf`BZr>|g5Q^1b)x#+e6B?$Ke(%p89(~=bw-#*Q4{>x- z2f@-W-b%u|jx;HEH76}2ozG2O^vopv>p%wGkg?0)d9S431SPe2Woq)&l_<^+^-{VOzP z&TuY^I*IVJkrUB!^(OkO+{5x}{-n;s$j?SR3wAHRSs*-T8J5fzuc{J^m6`)x@E!gT zBz`>No{O!m0lHRc(rHbnoMoC6tZ%E1@)f({;}^O+!Ed1Lwbq!Hig2EEMMudu2@;dG zJ*-%MNhN{o=%)x8+X3qJkP{j|rS;}r83lrg5oKttU-)UR_fy}Iw0hO{sYck!M`zL4 z7Rlykk$bjYI+^~ScV2U-}*7+9HkO;{lSemWNCxf4e(W=y| z1+9S+iMl&6=Zx5$oR9!-sPCt78h74!V#J%sZR?m{W}+0q%Pt2wISmsPi> zet4;J`uzbKjuAL|@}zRT91Ig^A+qNCavz#e3w#P%iE{5Jf#R}J0(Y(;0<{p+B0uD= zxJ=2n-9@Pfg=dLmw&e_ig)E!WOSDE@tL59hn|z}T-Of@xUzlflAgfRKIq4BO++ckNn>WUCFskn0n>L5!CXS7rI7v#Dm5x$It&D za@r#KIF-f@4X4@tOb5NO;gg;}JfrOuA6w}|D_LZDAz1?p1fiPA4Ea|Pmxf9U${}gs zlG`Y9e|(fnhRGHnGe^>}Wp%>@wQ zH>OVQz&bO6O>uPpdAa)^9$p3!Q#qhwFR7sHaf<64Z70t;M|NiYaKY<{x{+-WRBL$y z);EC@^RhLb+-+ZHb;vRM!;wvi{X@QZ1@M=svcsKJKWB;b2cAFYb2zZGpB%V_$GzI1 zHgD~6k3-WH;=3Ipj#UQcq>H<@7eb707b9l^o2uTkmZ8#NR{-@#?(!vc;rti_)dJP; z(M4>rh6g5Le`(=KH6XKx%5QVClKc_~`75{;e%+tM_^mh*mQuG5-4TXjWx`E5%od0Z zq*~Wx!})5H3G?AIrkML_Okk77jCvT^-g&no5Q;S&cDCjO6ozg~)4ZAww`N;cQ|E}S z4@?=|Jo>y>2336sUvrKErARzl^nU7AP2$7l&ORe^$7JKnu;tkv(qS;NN@toi3>I8) zEfP^R#*{PfYzmLWbhYt7x&$Y5%qL|h_>SEb*w3Q(a8E3k4R?{#ws6f@p@gJ!Q*SLrgw{=e zAT0+w(})$&-8B0SwLN*Bq5(x%bEq<;ffzGCN_}WkWp?;Qee1i~QpjQUZEWWRGDK8< zZ+RsrK+Ccu2E&~UliGXB@XYOvZIgZSp|7GXd?#!WO5+y~Agf__azTr+Kxmt67qG&1 zHKpYA-kAzsksEmWz6^QqURv_dOPv^e=4c#m$g_(8Ct?XTTuVdjr2luIY9HMF6j>kn z$yDI+W-zuHQ|Vt+VMcy!GSFdnOKw zelrvs9KMe?^1xKuMP|P-HraRBb^602fvoV0t)>QNa{K?VXi4V=28Lv+Sd_}~@dO{} z+~g^SMBlRril089L$f;HW}brUk(L{ArxqktLR!e^Ij}rD31j4`RUgJCM5=SPo0J#J ztn^_5cBO!f4!W(HF62b)tSp18PwUOPquLRRuD$eET&-(?<=!U_0#^>L%=H-&kAs)M z|MujPokC6Y;o&sE!0lUSDIY6gf^8_I4Ze@*9(JRx@FLhW`X(!U^-BMkt;p+NHP6#{ zuf>71DoZ717Z40a-`qS3fXdWtd&5#mkvfArgF{v5(3TGC~6nXp$!Xl1e7{M>p^5VRLx}!cLg0DU>T~%38|JnSoO2@D#5)? z{v_LXCu?T=Uq&qOTdrseFl9SUDXmj(Y9}k+eye7Gdl26hG_A@~@7UGO`!DVAQrzIo zGE2Kfzot9S)Zj2U>vZC7s~^HMbPP9n{PpiQTQ{Y&eB>ilEEeRNHzCeJBei$6h4&(f zBupBG3ux5~XTLjpQzr}I_&kE#U#w9k@}Y`ca07fSGd}U_Uq(K0IzW?ef`jrLu5S~z z{wia45O+smBx5%g6Yydu$4>BQcWTOb@Z9q%T)y-`^)?JM=qr|B@a;yegZjVr|tB7S>$M|BQ-9cs;YEZp zAgwaUWOJs+{2!v=9{AJeU6npYfZHDeGsHX%VeXFRY5aZAeROzVRt4F|*%YZuT61I1 zrUug1Fuvym5A?dc?&;LJJ^g8>+pZITJV@Q=DoB=Me56_@Vw-zY3OxXXv)BV+GONU} zcP^sCZ<9e!4dEQl+3etEE17ejWTh(jV;mqmqpyc4YK z^ckX-k-gS5#uFfvto_HCk*2LM#)_%7j}0;ko73>)$-QnE z;QuBdm3VqV$zfP%IWUc!u?!kAWv?&1V9qb>B7e-M#+Aaj`jzdR;4eeUwaCwqCUmC& zq}b76$S;xK!>(FOH0o2kiy{jerPMN6R$t~KGBmaN_Sr-rQD()Cy9!>Waa0KxeD__Y zDV_cR2Zo;-jAEP_h|WQ!fEeU5yR8tb;e&i%j_q)Hv4KqnNqLT67Lw6g)uUk(vYAF> z6IQV&k*==y_9n}{TD8EY9;Q%-u%1wvpDgzPS0q0*$U1UEqdPcdkM}eJOmT?eUr^bf zPy!5n2E@R4Ve6Cj&+l=jm8bix^Y;p-t(f1L`t+3A}XZqgfIZs+LQ+pw9rfm4W z%!a7sY0rXMcp+c<`Fm=^iJuPXGF_+Bs6k!o`dy`cQ-jrUDmNLFkq&L)1rjQ zdq3LiK}m5eRHE|Om6#s;3{K?-YX0=Ax$g|SW><28>p9QWR1475zq)qj-KEiNw`qs^ z*R@t9`T7IhtC9vF{@f`>?%ewVTt`PU70>1^=dBp`ezi+Lm&IC?~86$Z|o2L za=qN1YrY%01KPpml6f4c!k(LfKIOo#HL zA7_!MA+1MT&I~uIyAl1=Ei35++g(&B&%H|UkcarB^PzF3q3t-lFP_u@2yn_Q+vnR@ zt}&iebHg2b{e@E*R%>U{qjb*HP(mwy@U;YbJ7~(`^5P&uXpi08dezQ*U@x6v(hvS@ z0LH}yhSu>3-?}76Zm2P~i4NUxeM)MG_Nnk#eshmTk}aXqpPnH<$Cc%#_2xHMd6*+WX+CaJwv5&=GkF0T+F#%<@Cl&0?H#x7e;^2QB4Xp|F z*Duo$Ze_?Oro2s`NSzvN_P0wSdg$R)T~s4j)$etq7}c@)cotp6|23yiw|QTiQYx3b zqmf$4)R5<@Du~rrG;hh5Z&z1UJx`7myfJLkrb1N^I(@=MchYVvr*_NGZr$d@+L)SW zALbPSa^GzUT7#aSF}lq1g4}iwiqw8@yqqU~oS=`3|2OPX z){p5_RvHm&hw)-&9Kae2ZPa;mp@Pub5XS>Djp*Y15~_Y9uC4! zdsoDVteC0ah8^fE{3%o{KAI>`pNJnFSK-VbnNOKwl+THC(gA(hnG1#Szb8oRn6?QNCJay2%z~{Hp*@3uJre<~XjY zWlHfkxm=ZoNwo(WXrqPEAEN>6lU^k^dxka-%{TL)^>(hbbyLaZmdeZQP{TIw%gMV! z#fcX=^KMWWog#r)@@ghVhsY#N=%q^UVY<=6JZTD_D~WA_X>ePWN{24#gTW5&6j5G| z^(l4!JZPq7BBQM-4V&}nd=}n{!@3M6qbu&`s6(x|CQ|!p#OMPbspN&IOVuD#)Au@`Z8PCf=BAo#MvIr6o~ujX>VCLgz0;t$*`nxiRRf1pLf zM4uh&`~A+*a(UL1Jwv;XW9o|eHxyTMH-x*gmdSJPXX-b8j5*e(zQx`aWLDLk%v_01 znd7IJ#(<2EMzFL8F5F1RHJ3Dd59k(hIG1_OL-l*;J-gxya@OR7^T$?Bp7vLFeTMO3 z%4PRZ@F4yOTwq}5__n53xjp&`@7^OLfJTa6wn;&qduGqlg>8)S7^|1rJJ>iCe1aY1 zH8=BdOTUXB{Jpbwb4HoOpRfL9>8XWRU&Tx}kISg#dXS9Ag-Xcd!~%75+pP;l^RwGS zhQHUW(`8(*$s4+Kqu;C}PLSYc){-tSOJ*A50`q_HWt}FjU9}`Mr~_7u$!>2 zQx-3>gSg`D48tN(y%5*o5%r>7p@cwwVv-tNb6o0Wt1O*%qI=_D=#Vi@7*`vc8ZfF@ ze*2*m;mF1FKhYcrcd7CR2z70;=R`{1J&c5cCN{U_NWBRTtS_+NDPh3AEzW>oRlgO; zZWB#Idpv4Xgu}L=qGijdZJWyTlAfAD;feI#HT*l$=6d6OU*Cg=)8vzFt6eI_6&_k# z6CLtHv^IqW?cz)yj?O$<0ZR!$9qSaH=I|E4v8HR#Ff-(;q+@I3 zX2Ownmo)6{$#Cm=Rbs^c!PRY`F*vtbM{r%XePg@46k)bwD#wVZJNe!Lm*_?9j5DJ! z46kiaIGn&!MEWNr7;euM%Q>YXE{iW5>4h~T2(p&S_Qum;p749Q$cG$0T!71 zCAH|*iM4x`&7REtStN+<$LQc0^N0`HXtey!cv68l1Uc=hGkAYS;}>0lw3c%kVB~YX zbA_Z8D<#cqwLodAd#}GR^ywC74vt8tQ7poUyY=D$!*dhTYw}N;t$aE8*OvSS;|F0)f!ERLDb&p`a-e$ z`+OC}!=S&2l()bH8j!u5@#eTUj~|W8!SB3%0AemB7HZc8KYi0aNRT!85BhC!z%(!$ zc|G3(+0r85rmVGPm{iD}A&0oBY6rcZDryEn1I9IP{?e->?{dd0M?6cC02;ctG;^@@ zGK>(o{;-F|zGl=Gyr}la7u3G@Ig)y8_3b6VH1dD*U}-y?*N(OwV1F=b{`ByFVC`@E zaqH*osar?30fzCSWomgga^`GQw#K!kUr-60%pQU$D1N>DgyJ9gt*C|AlQ5OCO2f*f zfwMPc@9^@J#$r60vpy3sHc}CU2gG0$_zPcQzd=U8E@UPJ!XIN?DMe^w9z)!jlt+OYLJx=iKz$rycm||so<=Bshn}yrwX9;x!n@79&A z1*4XnvX-)8?1j1i$q(#-_`{wry{OXXUerM75;A!E}IaKgbPRs115XQJ9JYOhgpU{m?P=I_Jg85o|Cx**0^#+>%RA&IeY7@uUKmT86 z1I85G)16$XX?Z4toBKlwMv~JEWgZ1LMJ{zHEHxrC9m?OytZ6FA2j^qh$N*SqqbY#3 zTxMBo$}gJrVBB%njkEZ;!OTiQ0+vK6(Gc-X2ly!+OW=v;Nq^`VH194e_+VDv?cwWz zn0q{F9iz?!b3iE5{r9Zc45_7)0em+ARw*r%FiG~L!(`R#E!BlXXX%(@Ty2%a^JtTI zB*X7OzVzuoa8YvYp(zltKxktDoyIGM0_IQc{nnI6#d8rBD%`F@%(>D%O;nN5&z?P? zTvPd?kJd+d+j>qwlSq8{2b%4y*f+G#f*jr*h2b~iyOYBQ^CJ(iH**qq$hdMSHJv7? z?Y^EIg`G%u_w@iX!~=)&Pl7#?TjN^3>w)iTAL`@oX<(GTL;wtzo^>+XcZbknm%}QA z>hBTE!ErAcp;pMwS}i7j${zu7EqC^9VJ+S`Fl+nDPk-S+Soo`dFx0oL{g;ONeq2Bf zXms}fore0@G<8vkLsyiBO-Q=66C82r5G)>d({*(KYbXmPumA-4MR_N>aC5_?VSoBN zUwvanViXXF;t>Y{nXYW1p~P=M^v7=j%^!ZK6i}`|OX-*)z}{8Xo?)r zZ>#!`-F6>`1EQJ`id1lr(GxBf#e(TXB53zAS=zjrc*@7D<%56D#4)F-`L-@7wtE67 z9JkQW9)|w1l#QU$7mLy0Rs?{Zfaj9D>5w4g@@=%M`#3LI{>$Ke2=G{vJ>wKRm&xh_ z>VY!omOM=~~FF1ZIKH02-PA1H}Zh+?@W?w`r#MWBa0}$T?@$im_uGC5O zhYKqiS~AJv+4d8VSb%=A76gCOLwlrWp6d^Rc-$3y5`W6(gCSr4fK$>T%rD4yiCb z#Uahwm2?_(5m~XDT$1pyVrC?>0&o|&M<|hpq3PoIH+~_48xd-1W}e7rmM)5HcsFQb zz*?wj3#m0@OnDwuVovGFpT?;=d%+>vPc;nb9pIBsqsd8*GO!TBaIn3JbjKE|hk*If zl#+qfL^;{H0TeMKrzhjVLY_{A^2mhI+X(r1k~T&w?p&=zj#|iOs*Sctj(~nF= z4}Yopb(JF}bjgj4+8I~Oi8}W74ZuJc3C`01a>H||4%%sm1^1{Cxj$1pLae4$RfQg) zM0up1=?H4|Bc(VnltYa8)+D`n1019ikcT*hhd{qQ`JjOkpg@etWQ%ku1x#M@7vF5n z46v9xqG&A?g|R$ETA^9#$VAMF_2ARGUg3Bo;R*$f_Da?$YMadX>j)%XEE5MW_ZJLR zkW;I1!ZLqp5nK)f)3Q-8cRS}u(g+k^%R zh#&`U+P9a19q^lwp%V8g6aP1osdsu5u|8+6Q&69U{3OED)ik2 ziIGPcbAC;wIvXhS7J*rc*=nxxbuo?cPgiR4C zz!n?I!TU@!?V4zjUf5CYeEPTPE?;ZIzt(HrgcMAQ#b1J1|33C0Ev?{5a8j+7!!gUK z(B~$PQ+P}6=B16n9N6IKD?-`MPS6+z0$A%w zwaSZMlv?*`T1^V~*UwxvQ$DgANDp}DcOu;d@B&7*?Wr%uJ)Ipo` z^-Kjg5Y#a3h`!+!`xpVVflfbRdhsTHQ1pdPIPuX%lb2C3bl=we~!0pO3x@OQj&=RkLCkBq^fv6C8(28c!22`FT`P zo-IV!v*XZ)K#v5xIIxBLY-(m(#WOVYX*BuZ0*BSD`S}b0`dT|ANh#hdnI?CSh5$XJj!EDKbc#e88QsN(?dp z3`U8yJ;S2qP2P-1+vuIg8?Ka0fltOOmS=NR^v&V@jHmUbzkwVZ%zOVx2jq7OS*tNB zn)RBoT{Q=~W_{U2LgW|~_Ff!pI%CBT_Y6Wxt9@{WWRz8Ns}* ze+fzD9-`#;sOq*lHkc)P4Onf@Gh zDQYlKgh0SEUs<%HYNig#X@`>lKi@w8Nq+ul?W62Lw$XxDJLq{tK&30Pg+y;sDkrWE z3=Vm@IaPBKing-a-vrM~uJmOFK8W^WPO}jcyA!44`n2LB#b;(x4?{9#bhv{|M_a>w zK8rDH$)CXxQHdr;wl|ierxsbv+hn$0#`GX7zF}d0?cOq#MdK$*Te4^hvVFRA8VzNx z-Ullq$_tXNNPz}S0dmBN}l$3Rl z%CoSzk%c0yky|YUF$$raWpH^>dS>)CN>_(9Y6jPXXp2$S%tvdwqYFkqu)&nOoOday z51t4F&$Y<7sp!{hL4-#oR9?#8nD5SUMoPAWzBlgZvfR?$j+E~w%HuCp4Es8uX+W0A zO1?k{y+v`Fi=nsjbH zV}J&qs?NP%V%%01$F%A2_?t_TFtVM3GJOSo2`_&}vO^L~c^>R1iYZ}?>#lk^cNY2Y z{RVu@G%emHYl-uPCYYNwp7QZzIYssxTE5IOiyh82)jbmvn*^b$&Ed<0yVdiq7GSP@ zzE-ES{&b5OqT`{)P6d2WwfJ|lDV7kaz_T^mP$k#hpJ$e7;{exP{xLV@;r`LY{%020 z?x}(hZU{tnWIlL~jqcI=5{CCSVfZ_2)Yq3^lwW2%3y@*@g2gdELBa zPqr*PSf3*mp+&|^B|bWQ;~U~A#2ZJ5MP=2vPn_E{e=qHaGpb{>wK(F#qg1QT(H2R| zy|VUr){}yN6`}gcTUHg*>nk>k_fCmPuB{+kt(aI}{fAb)NxO~qzy>@oP?c35Im&Y` z>)xNCh4GeUv5zFAFk#!qc@JE06hcc>r}Z3Z@&gHMIohYx?q>eR2G@*{=@HXV^g2Ue zY9zEFi-D=8m*pzo|L6lxq$h)n4ckc`nn4rA;W%&K3{D{FJvX5a8ZD-CGN< zCW<(buI8sM>W{$Z3q_?a`-qG^)KZ3k4R~&p_p_EX9Qki!?*0*1{i*3c!Bv+m`EMgr z0eJMA4~CA!>Mx+DJ$NSR27vxt0#dAm#PZhCfW!P8$#TOOD241L!p7lC^EJ%al^q`} zS=5;%C^dqunWRu2NVa&vO6T*TmQe&9cNr51kNTo#RKQT*wg>pT_rNH}XXb;`Jupp0 zeU)vYS-#DA2Q`sV8q^q|Rl&0w?J7<=*@U*9hL|9aa=AHAGxCD`_DjOwtdE5z2k-$tYr{VH|2ftqBbh>?}10;2( z|BwqMe4z_Ce4zOC{a?YPB4&G`ZC`F1L0sYoRoj&H&~G4*YajC| zS!_mm##GwG9WXjTZlT~&3#m~^6k`N;!5jy!=f-^3;Focr4ZImx_(M8I%0zW2{XQgN zSkmtY_=skfdA@3cu4{8|Su8Yuew85*-N(x=0#)-uJW(l%6&A|-V?A)+_r3sih64Dy zDFYZ${`OS%*T}f`=AFpo0%8p;L9(`ih*(W*7@oJf8h57^+A{4!`7X{v`asw46aoH# z{sBI#I|D#t80_lixU<1V^Tb+thufX85NVfj^*$(*_{$c%mxd~kRH5Jm@x1p`aKD55 zqr98aU|QP^sWX@@%vUJSoIW9xEnUzAsBU*-PCc4SRSq$28kp5zsZ;4+&ONYuK@(p#9cK$#f%pFyTdJ-NEc!)4sT ze~KXWqLn<|0OrVmpImGuEj$p-kN>OQlUK09zx)?T)Q5{t1IoMjsKW%p6*>g|z5mF+ z`I*9b|D7+H^NWqYy;^~B+*Ta6Cb*J6it|}iOUeTk0f2bOSEZn8jHe9(pFXz>HQvam>Q>6!dx z$X%-HzANFj);GCkpEZ6DRzYn6S*G0(WQ#Oq2YC?+pm*K7C3E!$9!6R|$8KNh3;sf# zNdSoEsPdJg?h_>!8U&Gf|Q;L@`f}ylM}AyBb@x`B3-da&8$6FnjVGs%hYJA9~k(V@KYR z_UB1z)ccS|nF+W|nF#_jTSAWQyrx;+X#?aF}go@ zQk^{7nzN*Yzp#2L0VQ-23V*m83T{Y7Adfcxye(STz#WsaCV=rZnq!V+L+?$XfD~a% zKE$dHBURHVGeK9=0{Z6b?$iS>D^3I0{|W()Ef#%{gl;UmpH~~DSrF|a_(e~!UFjV4 z8c;z54;f+=5L`LRs2Z=K2Y@LCXoQ5yorp%j8_z$ zXcCzKq2p@=FH!p8;3-0BEkyb!3WUw!>0E>q51hm|URl5M#LK<~gU3R!3`*{-hu~C_ zSxLh8ci?C8syv=HMQ!2r2s4mb7(%4!tX5l*<5lU8hxjODkB=0EP0b-wJMV$TP)Qk* zTzxo=B7c|(DU|AHW4;dz>^yA*+I6NwiT!XE6-HF%OSQA)cZ2aia%Uxob^A57qr4gPVjgeszSI(lOX9Jva}LGK`x6SyE>db7rSu;_OA&9G-E^y=Xh7t%L$15MS)MQ=4&OL;(WG7`K z|DQ3e9ArSoJ|$Ia?~_0Fx|$wcY`HQBobKXb8jwLF(hJNAMB+)dT%i#%3mF~)eW;AA zy0|uPLR3z`Y2c`)XRcfPBU5J}SP+4c8UHtG2wvRpmec8fhg%M>`gf_+{|dJh0mIV& zIIh*Lk1;32U>>y_Db@P7^*Si1j;#w{G9hCwJu~T~n zL+@~#n*e8P;@{Qf_(!x@;_y8bX>{~)WCt6`b!x!Fb*Gx&$aa)90*bu@rEw9(4ks5j z>MLHb=l+*bt;aL9s(DeZIU}2`2pM|?AgXo8zm94(_?xKKz|B01fiPcq74HLNWHd~; zccSUJ+W7rr$P669tfVc#HUzw-yVU^|^$S`(`}?Y&4viuWA`&65_Wkm0&Yd4*EJ$@D3pYE&NzH4xs--IzxuRY zkx2O-CR48!0wl|EGN&x8Eejp?q8^z}CkcHk^|)2Fghw$SWeH8XRzm%v}OC0Eu)CujmURJ4Czumwo zU*o8f8#b-J6&pPRcqTs0c7VgfGv~G<_yV+E|>x#^bc8+LQau{+pNf|-~MHIYxZBmTMZY(Tg{1UyAK%X z)q4TzxqjNDZWz=g2jRfSt;twoxbHS?ZZW(z+ZCLO8PCMhQ2Dq5ovf)2jqrb4XS5 z^OqcMI%u0dFx4T43A*jm+;Ss(=_bXxpLKp%iTUN{YW>3xW*+ak5EF3d;AO^B`OIyG zT1WMFT+lyw)aa=8xmB^**3GTP@jfqZt3P@^Fm^8{ z6APl$XWO4rD+f=y%vjeq?XpMeIE5rbv=^El85%xxGb9U?@=(aIZC{9gdq+#>`{(QV zB=n(i5u|Jx9oA?QxUoUQ^coZdi76Y|P9|M*_<*Uie5()j_d*EQc8)iuwBwVhxVx7+ zrlE~5*BvLE96=Q2&tWVLeF@^3k)nh2tRjoJ{kclShvgt4`KCR5d8;quc9Z&dt5@WD z(|;@#CvZ=n_D*g9HxQiRYXo1rRe1x3g*-x~e6@?R9Coxn_E7 z9CxM&no#cvYR3HVbgOtQ?2Zcf^*(6(Sebe15CdGYhLzr0opm3|ip?Z%!?K^HI5bn9 z$$POoScl>wJ#LldK;A_e`)szRyjRk_R}oHc9hJOnPYdO3-D{#9XDr!pA41JWG8iIj z(M33`$_+)k!0b2%Um$B&(eiDLSH<;90CcCi&4sunRp8}EE3@mle&=KGUBT^qx!&~) zK-q&FgXzbnIs2kD=0N;RjIq2^q|JLY$ZFEEBkhpvsG#xC=^=RZF9n1`SrCX}ubS7H zjk)@+zc9?q={hUSqV_uG{+zlMXN{gy8rLBGgI;0#T&X(w{%e8rU6W~Vp~fop|KJlx z%)Ob@35Qdr@?-~=sA&B5MyC!#xST+~jBS_N(=jzvXp>+SSM8x1O7HDdNhA!KZ023E zLbwy}$wjiRQ&>3~N6NY0h0`(EuCm8sCi8P0pB}PJIM>~4(vA&wQlt!vNKB-Y^E9+H zB0A3&UjO>aGYLae0W;p@UTvOT%NrOhHOgoGp3T}j2~GhogB)hsA?5n&a-XeGcf|&q7`iJs2mk``DNCLL}bRe5{JM6Om zjozN`Q^sx){@!X!ciC~wqq)BK@Ah~L{xS3$>rq>^dhlEu?ozs1GTajPdFcHMwNr@3 zD0M_D#Dd%?x$l(f0B_q)fdb_RSp&SnqP zu*dE><%XQpH4?a^rTu+g@!Z;Y^3oe#&)WetyWtjQhjfg%>7UGc(W}11GEt-}+o=Qk z(k8H3N1{t3ICM8>@tHdPvcgKAeB35ZEElV1Ps-~|LJ0FJ+cU*&v+1#k?oQ9JA`3O8 zbbiAb%UG5)WlJX<+uOmm^G>PsX)o|7Dbr|&LP;-rq3GAlSfjFr_gf(m!r{H<;{R#} zUR}OeoGuyC`Tlduoi6&ufSJkL;JDANjxGi4Xd%O1!6c_;gy@L0GUmx5k+`&g^-8Z?Y z=0Rg`Ck9wbHNjf-h{&a6JT!FyJ)_@m&|U-T=i&KV1@asRS(%z$zKxQ=UcU|+^4{N9 zL~>?L+*b4VdN!Fhi<-~^Vt)^`hK_a};V~{;t=5!)TmQ!0o6b_?O7n4mhuRv>or2|S3h=`(El-StJ__&bK}~o z=u!x>Kw|lcj^2X|5$aK;4SB;KAr!)M9jWCAW} zA~{z%H$X*s?9q|XmnhV3j^niWls;`e?HHe}l*yW(jF8H+D53#V%?Ak0pbTqr>;jnk zoTkEtJa;m*AAHS}vlg5BK%p1g?r53sj+d%_*a7}T3CKs$jtX02eq5q4QmXnO*HgGD ziHTlhDd(;iNowaDl`j6_CKCD*#KE{FBLbf-b9Y@`-l#1rG4MS8y25k5Ttv4#bL=Jf ze2)6Qb+qhAFpnE#93t%E3}vMx--8M+U#{n{jH&&34FKBJ_Oz2@w^&=sSmw_|UHlv! zmwz||r%e12`+%$!Dg_k2TewW#bGQyO_IPmH$@&hW9iSWZl+2Dz<^CqI0j1A+RQV1a zm0wJsB|SmW4oql!$eZ z>SxPaq_xQjapZ4W7(%9iYqqOz1YbBYVWGU?A494;YxA%j8DX84oI3a0UV<5GO5keN zQNMhOu09uxG?rc5iE})xX(0%^_{Ko-hy1fBW^SRA6*hl`k$Z0G@4u zcuLtF9tAYm;$3IkqOyHgRe1=BP=vzBYhS|l{t8A~)d4pVfGU#p^P!0r=ec1C%Y0iR zR0zLPJ|P04!b!93Ici*)+a0RxeAC{}&mSvB=)2t2%Wy=N0R?n#rThpwcPgB>ffT^f z(RwR-6`FVex9vxev+}+g5*yA)>V?SIbSoO}DszW6<{9W4d0!ZV_nJ3;vhOb(`?ez` zSB`O*(FNx~++gwI-)ru>up#nvI@cbrG7oL_NFS%|39up zb(BgbARsdL69-D*z_mIVR&r-||MmU8NGd@^s#?5t>?x0O&zoo9^Epol^%bhF%ID z!hcbh%u+q$9X@-ZBSV13ymnt?O=-Zgap6JWV~B`CMFs_3!3w^;C}(ZYOAIG^18_Ym z$tKHUR8VKu&Vv?H3MATMN62s_tVBf!V^!u0FW-zHB-dr3vy=I4pAqL@S5s4|dsl`% zWUBp!@o9~As*w|>gCDVM9{hh4F&%{OM8Y&yzAim(wx0Oijizu5wzDS7a8s9ylIkai zV0HhXCQ)?R3`AaIsJa){ruAKkz6_MekD2e}>iPEmi40qV6Tu517$D@UMk+{DXd3~5 z+D8C2kM78_${%FhWPx}yc4lFU<{;qF_uRt6eY!KCIm83T5h` zxwz7eJrw2XyMKRC@d43@X#Tr|g<97vccd@@3C501dW~!xS_AcIziuj=XfU=rPEyuF zl@3D%y#ixUF1nunhaUswAFm^UJ}QT94yjkUwyQ81O3r-`IkAVpRRY%RE2#0eWiJDd z`LaG8nLuEmK86Ce2A5T+fK&D)hA2xR6)OFhLwl%-fhy4_AG^R|3N4H@TP$R+pQkZJepBc*l%$udD8C%(2$vGZQz;-ffjXdles2X1Z!ABnNs8IAQ}E^ythN;$4P@Y@I`! z&`}U{G&X_(&?-;gwb=l#Cq}7bXrv#@1ev*T*UD)OE;yHg3i%X6USIZ>u3$0*)I69$ z;aw8ljhq>=ZeQ=6DIpDw3}29q;t1)0v*%zVzUM=P%RUBANtFccI-E8yRRs7kVCeZA zWtf)E*7ocIE1nc*&{kim@d~7!V|g@IwF!i%xUf*5CMxBKgcC*cXs5*ltYA5-vg|9n zQy!t2V!~zBO2xpf%EVK?*rhz17#7~T_|&I3kc%&MLnF1SU3^+4xb;sNQE)-Kh(qh( z!+>@G_9T?3_Mto6T;KuM`gAG6f*0So%`7p_r@7svQZTF7zyWmLEl6s5noH?2a6UZf z`)s;NVQJKF<|UbY?RgI7g+cv!49=D1QCsetl95Ud0OGGs@~-?Dn+UHj<0cq`M4?f~ z&9f|XAd9Aa6a0}&zx;zNDA8$Aet8`}El6F|nzI}q$d;P)Uu+C%r~DXzDn)=iS0z|9 z5LDfTL6sNasEqEwy%nKnGkaY{b{)O)pa9m7YS7>a$`v2`fj6_#g{V@f3)>2E=%{z2 zs*dgZdxytN1_|i332~vrC3-|5K1UXm; zw(dK-mVUh{y99dHkGmBkiSQtTfKhx5LioUW4)_J)o0*|1lyLJvep1VH*?M9k8;-v6@+D?o@-9Y6mF*ZXXoG5b> zz^{8ZDP?MQWALe+-VfVQVe<4yXURN+>H;<6la4=UFSS2`75e<~0zsqBmcN?LS#^w- z)Y1ebl4rp@I*+aIh8|^KM_ABb4J0|vYP+;#vS4E~Dnq~tzus0=RD<@Rm6 zooe?fN2i59?}77}Bbq9oj?M-~-66Jwjg0EvP3hFBdjHlP8+mE_=E-GPz}_>5vvY8E zz8B-L_?X%AoOVjwyjamqywidKm6F9Mmuj%fxrF4IIrz~f=r=j39X(au1v~Kb2?#5g zol|_h_@sDhLY@;XzqfuQoD~ycHH-&fz)~MGV*L*d0<6>2y zMDaD)5BMH9pzbyTltHX5WBV5N^hNW_XOb@(uN-c646qXYf5Mfs?uJ++!H6C}(#&b7Q13=7`1_!iadjGZFq2J}CS}7hhwqot(FTDEd3U6A_#p*e zOjbXn(u$56^PaHhfzp}=BK3?Z>*VaJM_udBBy7I{77Ep!J-&>5cOes<>^`$!H|Kzy z=(@2ZN(mPho8ms7#)wz$Yn?aA?+!Sv+7s@~$7rrGH;l7ChU79&EoUtl+4-#W3Jx{A zTn_H2h!>xv#R*B%<6AWH+9JZX#)e4zmQik}Htps=gC4yDp9PL$ngUzG^1F8OX51II zGmKBo{58S1_C_E>=szRJQBzC0il?%TzcUv3#cf`Y(pR%AEdgSYmM9w6y~ji`Mq?0@ zT4VM(HFIG+N{t@lSiV!3zUp0!FQ)-RO7nIIPItDeto|3L{5W{J%B%N*WT9u8;{}K_ zAl<31)EJgCfoA?CNipk=HWnw8S*<7mFv!n4;M9Q1jLW?0}l- z-b_ne@z9Rc!qRi>9*$_W8SyGDg>tRjZz4t-)Y=0rmwMKFMg*%-yCNW8=hDOxD%7v@ zO;bBH#eK1M0V$(%$@s4gMLE3*0&{=e`B%o;mlu%~Ps7yu8|8uvp!-mne9_-`zY^J7 zyt?>0vT3(lZ&VL=g3U0C4lNRR05#>Dd3YXGfRvKp(b40XH zXUu(qFG2Er=Y4dm!+~|;0LkL4_dV(s)syiHdy~GLeV$;yKdG^=&Ml}hxqMd&^T`JZ zri_g|{sdWJ4YleMqf&oPwI%DL9-+JLxW8VrV5A}3>sIrTnw`%Z&Jo1u5Zl<`ypa3G z&K0D%aUqx>7&7wh-gDpi>*Efh`+V}bzx0VKI{@bF-FvP0D>Z&36jZn#Oo<4aG?KLm zMydEe0M2#GAHDt`Q2!!#V7z`fj7xd?PqT;tt=>M_em^edYyN~R=6(IpU2!vIaXz!w zK8tMb`q>Z>DQbcPH^X55#mW|(opiUm!8!rR!cr#U*iVs|q$4seqkDM!xdbOV! zq`^iT+UHa+49?%i)VDvtB{_ItawtVt=Z7O&3-K9r#08NYnZdsS( z_qT83uql&$xB8(%_x6m{?}8u$vKh5GF5|iJH?_-lNL$E*>O#)_M-oaBushyUj`{I! zU+$y30&x&rnyX@?&#YODJZsp;Y9z42Ij_QCMrc{UF(fOixlRlLWD)v@_!Gk_4T>b5 zP_m3SpLh#h4I=lTVz_xhoe_7V-VGKo`1Mrq{~Lf2>X}U?Ec)dA`2fbzOT)fCAQ(Rv ztd)QSS1=jFDOKiCSJmmiPPQvkNvapeN<;!oyiBl}a-K^}QQiAnMmv;kUHS6o?E@*I zfg_5n-W5O8%a*S4UR_}NtMBuOe)oY2D?d39o9!d&$=jB50n3$CfW3+lZh$m%-f13G8&;zfNGt)d^b2 z>rJT2%n2}n=1v=Y8gv~)#Vvn3Bv`emiC@?p34WblndXnqS7m}g2V^@aAwBCxiSY|};E|L8oXt)kp1kZeJmcE7I z@Pc$p_j$_3H7L$g;zgquOxvos45)y7n|TRgGY|Ki{;oK2oK7vL7$Fc<5yor2J0i{v z9;n;Fg(u!y8d+wtoYRU=>9MCrhTsxyKHKlS3DSzD8x4XGR(oB6Krnh1mOSCw_G>FB zBu)lm#T+1q(|v%t^0^%6`6g|IwN;;JV{+*krLpHabhJ-0VMX~nHZH&T!cN^p!U7nE`8 zQRicuEA!$=W;FH#_U&hhlYnX5qY_jUx@IerR`!zCnKnhgtKL)$^7EF}&bCu>Lh zIhz;q)^$lwErWeKA$1@Uu$#4I^%t;hn^OHVP8pH|!}x|=R<6XK1au{;D*jjSb6*Y0 z{)q~J>ZP^Fi5)7pCZ_-l(@ptxFaWyEn&VqKHuG;ZogLOnw-zt_{_-z8ZDC*5Qd6nj zKpik=D(vahKg_cxBnEi#!tr=4A$u2bdlbh>{5cjdE3w2yMQbE6_<`^B8T<=V zzg77!Ox=lc`q(`k`FX70b1S6b#t|V@S1zNgxp%Aheh4!w8 z&H#(#@?05RZP%1q$QU?#fx0zR+|rdSoJd`*-MHGuv;ZlV$3*;}avYG>Jekz9HP|th}P%hIcw>JSa1(tVlV6WJ<*a{tUCco4|aZ~ zHK|o&@YveTy(1AqSk1d8^32ZAhx`Js`1itDPXdUY~xx z#z7@L>I$>m0FG!H5$l%kgA;G}8HsJ7UN#py&-jlZJo@_X{zm=qvGiI!({?S}pRLN0 z|C=cIeNKb9iGdZUj7{k4RbtN1ww8b3;{OGz^54MifBUh}cMfh*>r(vuwBu66!zKhP zIsuv+iBzPh_N8P1A)TJy0fa zM9E`Z5)oDTrzGnk=EotQwqWI(P64ohLXfZ)soTKTbIHGt11!Zv~egKSO zdQj^G()mKaMM!ieDeb|W6%6@3p@wGnely(p?I!D&m0s{4Sth;=IQ}GWG90Lbm(zawQtY0BRPAp*0XN#bGYB?w<^`7?=oZo%zo(Sq{;EY_t3{jrv zW+yRY{5@K%s8L&bx&PfiW~@Rg8Ms#(_px8SXlvM2rd>Pe`a%m6Oq#nNi`MJ z#bg-$lgZ&`QdzVGs{5DQ>ycjD&t3Spc8YDdsW~1$@>as<(|q4Kj1=1Sy5RA4=vBD( zG5(7*O7|%Pn~rTs@WhnrbMm<4?RReRYoH$_`)Gb_$&C`Kz#SN%jO zV2s@AqFk8y?3sqV;!r8|xSZZ}1qR8Su2b76WM3Y+e7htd_9gq!5Q$ zoT){YoF3$-9IJPv+rpvY$&coIE8Do4?l=c4)2sJd@-$m-O7YX22eR(t^3+>?l1C2- z-2xea@YJ^ggyWK5dW_Q;B9}Nr#`D46-vgsa?(?rpJ=BM-r=c^&?k)}}^f{A~ek9|B z7S9h5Vxgw+K}RS}d^PYQ5Xu8rHS=P@&Ey#3>ZRD-P7(h^8%o-rT4nX*TdNP_b>c0i zVm*gmco$I{GmKu8-mx0%t(Ar2j}$QZM+AMQEe&AUk}{DbS~vhIe+Buvh48HEN+c?r zh8W{#(C`|8B1>{_T?Zg8;>e{tGZ0vz4!-s8IY9p94G`Iyi`rH5%rmL|B7EPN$FH%_ zFgOODdE$rDaQ&dCPJ~Xy(C)Lw5#R^H&GsoZ% zZ4>@{O#J=88J@hFZFvsT%Jh{B$&qFJ*zPCw_KpTLL|HPMYRSW>nu#>hpALYX^?)Sd zRT6e@?S73yMnyn?UC&Rt>7A1c9)~-3scBe~K&(!>5&PW*$?B`TBvs_5hvm!grBj5W);p|Og@ zm*t&h@Q5QzTB2>!b*OoDiN+l-9xdmSIfJLqB}@jMI^o~6AZa&-Vl=)KRCc&piW?OH z3g&0Yp^F8GmGh49{`w=%&+Q*uoin`<7l^OPahOm>5+SO`_i z?zcB%B&+eZ?3GrG!F?A#^BN?EcHwNOl!iYO_!vXuoNJcGIV5bHXOJ(}wTl$T`hK;< zw*JBdaQC?(aO^ZCS>VC-RWgQ}i!F7M#W!#-So5fixWo4?&;mc z3v*3DTy!562)M5cipDPhC8PiQu0yZQxy4B^Jb}2*_Y}nozbaMawV;={QOq%GT}gFW zNxd0a38&|YVNuSXJ1wLP2coSz4qntu=_2+rp?IO~vHd^alPmkf;Ms?*pfy=4o;lEH zpMOf%KTw2X?_9={(GGO#~Y7^+z){9@>V11>Ifj*J%^1LFL@r$aC7&cy=Y^~ z%qx8gJ=Dyw=L9U%SI+;j2z#Tw*E3w1jS>TUd-e$4yYcKV!@TSr93hyAG_7QHSvaf~ znvfG?({J);95i(~{_F!o{%UicYS&&UhM$~aq z=PjvgP4~olW>(^}NxiCJv8kU;FC7TG95w!I$$ARrBO27v z;mJeJvfhOJ*%$f+RZaXDBc3*k^T~W>1(pRH3{+&_*Tu|Ut%g_%g#P-CRAqTAN1K$`K2=yLrXb`bs^HsWweMB~D60WjVvHWu z435nK-a)>{We;Dd_lbZko+9hVIIe+pn*CYWJ-M?bczWuOtr-U|PQq4ZUB-O0@7%hU z=sNiKUGDUVBeWA{@7ovuE)Ftc%(>k;XZbtP!k7mYtTZ-)|KK%(NO(mzhu#k6lfc}#4 zQlIR|sJ?xQnUtjmC+H{NTk^a2%lYX1kJTPdCh1b_G@oqT24x7PNimUHIXT2TL#SfX zLth566d)*>&oiyXH}xmWx*y644*7FukOVdHCvQ~nyS{1vNmHGW`Y%Ka`p-*jfO`A@ zi#crR29N@D1l&WSt{t_{5oPrxXYHh`&zr%qQ#${krO-K3`@F~0ke%}Mmo-knajYvt zizMoViGT`(XNZ9E0=`uStRo!dP`X$39VG8dasWm5x^^MsF~_cndDwwB$Id}n)9F`W z(|PB}b`yq&ezdQRZ0$}66t7gxCUNZ~6fc!(b%z-vI{y1KVEXxQ*1t!I`#=_LQN%2@ zyhni~EDjW5Ej499QxLB5Ub6+ZzHMERAePG`BED+;mymPJq>VEij)Z~MU7(fwmS35q z=*OrVI=T#vgsOl(ZOMX^_`{De>@!u^1IwZe>KcIf6cCAfE8BLtHb3i4jyQ1uLz@y*E?5-O#G;@Dj+z@2wmkpeGhu17UF1Pj< zgWLD9TY&ZMZAY5SByfX$Dshv(XO6fgcR0Q})Bw2kv{CK25gsM7i__+B&KW*OL2+D% zIcc!#A@cuvQ!_}}6x8W(>`-tcmr@}_DXP|c$f-n<36Q;M2#5_pNrMbLg#tCuQ=kDu zyPXB<6xiJw)N-);5-7`EW`O2=)tQ~ECYT!8ZXP=s)zafURzD4kcQdOHW}0ntd8oHw z+brsq>E68Sn9z>!%NF-MuX(rxZLD76WbYSfu+87Q?hbyNMd0mxd- zea`uz1R5+HdGZ{TJql_1!K#!-7r-Le|#3@_>ACvCxYJ}woK^@7;BT=(MAJ^o7e z`EqIqD|2r#yTE^pbNIgWkEAu!r*pRy9u zB4c=bgl}n5hmXRj`!0v({2-@Rnk)cXV}iGy>t=ZwoJ5gX%NCv={!@7i^iN0hnus&~ z7%?$D^3$@4(zp-^H?$q}96ZD#Ciimem@w&mk~{F=Xw6;IJ3ZZb#fJxH&r`jLW10gg zmdzM>2MP`1YIYTxJH4pws)@+A3sT^cHYddSPpP$fEzddJ@+|uqlorRQ$t)1e=$8$@ zKr3k-x4D&2Y`|zzqZR0j7v2y+yq2eC$dh&Hvz(29{@vP@m^Q8;HZRZi9_t1jVs8aq zVD*oJ39hC16XTSIm}XmksHkCB{^cgHEtq9B1lZX1rF=5KQa`IdRu@nUD}%jX6;dPt zz21Vq205&fMWymA6>Esxo22YY(bmYq<|mG-`XP_~y4tQ>YY3;6$;X$eScXsPnB3Ya zTbs{nd4765pV3T~-m~cHVy$f%BGL85SRvv=^%B?Cd7fKYMlbg65XYT;Y=Ny1@rv-P zDFh#7=<)5!?CCheDU;rSngjl!_RngBHF)zjDNUX(t;-BaYH^hxp10dRs4(&N*Sx=9 zw~6DwWz5bUurFR-K{#T3Xo^tLcQP&&lsz102~&j~pBvI`w0}Td;Ky~bm6A`@QpXFc zG$cZlCZDnFddvh3J3I6eyt=?xDK_dUaAJ}Jlr+y$|I}n9&fZSzTAu=>8gGw^4jZwm z5HCj=Fvg0tA5$09@4Tf}f<>0h<1lWpo!irh_V8eWPq)31kfKZ2PkxjqFH2bX|M|27%AY`lf-{DbJ5O zfmlI?7ac516uVgF35=+8Stkgf{|+js+7sLSo1tQMazWpX*e-4z`W;UPG)%v8>$8@yGYEAgh?yd6-YuEg4d(fMbeekg}^u7X| zQjdsH(9i2|$i4%Bwb@IzaT(=cI3ni1q~*W~ONRNPK}%zvCqr1ssU_K( z5*ryOFmRd?6c}|ig_Uk`k-$#>F&=)568zyxM+LbN^^TlAKEa;2Ta#c-ryhfB4wnV$ zyjd3AM_W*ms%|=_z70Zmzu~!THE6 zuWr$vdxv5-#L{4DJ9$@RRt%Xm)_Nyi`87kNFsy{e9ZitZ@uxlx=w$9Cgk_Jl=+^7Q+)?FsK`s z9cgwljC$ase7+;ICj#iOq|Vn z?YUXFcY4(wxascN{G>}Uc;qmQMh@;!5}%a^Do9s z0`ee%F~j=p41$qSHMb?CQ#tR$uI8Ez74Hg;(jojdRpy$=nd14Ywo$ zzBrW@dkG7~GyBA)59%dGc2$H#fla)5Hoi=lA@i+Rz<)gMHLf}zY(crTHDm9C zm5C-^a!bZ`Nnh+AKSwg|b^jZT7lPiL{(t1WPNOp?vP-~uk#Cb;d^#TCX9b;i_|(y} z;|QCF3>Z((PhM$pJ_x}H3s-$| zFakhE_7WQ)!It15bb#)HaUu%2CfE$RD8a~u-}N_}hm%6^$^~V+8xG21tvKZ?a7dHM zh=LRvIUsAcEQjSlpuionjh*{4-KCVarS_k6*J@O4^}j}Uo!CR9%I#3{aL!&jal_fN z`G3+~T4QZ5tpX#CJN~{ULu3a-QZ|UX_v09ZD%56H!9m8(sJ~poIQIie16QtrbS}5) z7GW@cX+*53NRNj?A2{|Faf|**YozqKLENIbQU4?H;rM;g%xv;O9ud;pWbv3rTb=}v z;_zsT)a$E#M7#g?XVkw;Afzuk14iK5fyBTq3R+4vIhl@P2EcR(Xhlf9T^Gs`Lx}|l zDch9&nmH%vV29EHUH&`*G3z~v2FbWw<2#8^bt$}|s4pSV*Mb6wjBp7lH4A6gfvh2? zO$n{Y8sfoplz~@p+}6y;a5*@i?awsvEZ8V6kp#5}&q^k*3cf{m&tZy-0Q$dUf-_GcN?B<__avYIMGd~j?bvOyxnAV?)9yIr$KA*~b2-N|x znS8j(&3h5RqI!Ra70a7a6Pe|EjXe$*=8LV?8=LHfoKSVX-v(Yx7BYEVnC|qWO#`KPNU+m!=?n1qhEn-uhrZ$dGD~?)#0Fl~@Pz!1h zKAg^;B3>p4@u~c=)}~e4z^O!PAfS?5IA#fVfwZYP1!PC-#jdiziqfy&CV7p(Jl^*L z_ughPV2X^(03oZAX7le@Q?AsFY?S^9;)?iR6Av#11|}=$F^fgE7Nj>?6^pww+ZA&o zo20FqHCUG%$oYdiRiuwjvl&ghRY&lKm?`mBjR$^sWZ>(Pr>NYhVjW+tl1)-uL=i_z zoL#p5Sa8DNBoS-4#-@bCO2&W6oiW|mcbs|F&?9=k5q2@Re{(0CchCRyAEj~t;fgTd z+_3L3IV~GeqUo!7=F=w9#4(1`sZ~Qf+_~32l@`l@m#DygKFLC>Galz=W7fazM3&)+ zG)e9MNSHAWjO`-wsR*wH-Ih-IU-XlV^$dtFU(WTHZj?}GUc$;&>E<(OGKX7#$Bysv z|I{Ba0ggkiJ9FOUB4-*rguEEYLeqeKKFrQ*@=$8UAfSx}s*$JdjB0qiXa?j?L~?$+ z&wH(`9HzC;VIhbtQ*kAqS|-atJ9z}${n@fvy64lhb-N%KT>uP~tRxcN7W_70Nw{_Z zm~?x@ICkJG2>uUnS7|&pt<*ccObl!w{Vz(@@h9W$^y7%Lh9#ujli~BC-zUuZwr@5t z{gP2N!DBNgX1~Oqon!bkgKmHcNU~3p7%54Yk2zMw(BHV z0EK@VT2kHCrn8?CJH=?bHS5Iap0SB31lDAm>Gowljcw`cXIO>(FTL6>UkGQ?aVWnH zehI1n7g)m$DW*Ygyf*AW^kgA}x@w3G#IpQG1KMFyX?;JHBTUYi&68Brl;b?G_W- zM$ru3c#&tDEni~TzFk=}*3H)&e?4)wds{|Ll&pl68=zhv%ok@3U%?{$w6j28rzG~& z2Z)YQxM`vSEpmPxbtQ$p9~FF#6FNjRk%hs&UT(J@^m^j$x_A$7)JEq+zJk0~Ws zXJEM1=#Br&{+bgf$!5Llb2u(xboSfGv0X?8fjw&5`v8~Ow-?lfM+l(b{D9oAptV0V z*BVz0EVN9v7jmrt`zPT9-j7I7+OO*pbo+99_eU>C%K3iNw4i&A4xKrS`L=<-c(DnC zbYp@*F`OH1fMo+@Aohrs;^>)X%g5HVB+nQLc)Ete5$)xkiPC}q-p#9Gp|lss%)crz z)hM4zc@f4SYQ?>CPik3Q`b@tCohoxzng8>M`pLvo`V?+E)BQHe{ugdLEbfgs)u3+j z>^oiAQS9nl{}0Ui!`mpqCwTORmXribsUZQPsr2k6M~xdw90trsw$aoz2HBaat-?*W zzaE10_Y}@qgss78>Z$_dF&yE{o1-s zJ1oE(v}eh-GqwSFVY5CXz4*E?=A8qdC3Lbjih?#o(iN<_xe~2{^Iz64mC!Fa72sAz z082H1a5k}CKi>cC-A3b5`*m5VTXe_Nhw5oQ+BmNR=Yk7`|!~-==1*eWiqPPl|))Vv| zu&Mp!qObMS*vWi7dUtnXQHGA6wf@p%Igs$L7w-XqtLwXXl1NDFx=Am84oI~KRKeM+ zI*D2OY~+%w+RC0M_$v9Q^;aG1mnKS4O0j{uu72V=i!V9Mk5YQ75Age?POQ;90{1vI z$`B6)&p99}vWkQcyv2Hn>@l(I2@v$zvDOvB`K6(LJ(tsnM`p92vZB>2G->az!b6ie zlO~W3yMEjc`Ez@&)K{n1-=}LN)=f@lZRAp;n(KGE`-ehdIpT@TWOwRK05`s)XY~~_ zG4|IbsEw^MRNRm&z&+>b1L8;Q-1`m(4l`*JQ{m~hRd+i~PdrWaxz6L99@3K9y@vP< z)`_m!CVdEQuMmvVf;=zbG9siXo2SRua@s<94`M1&Q|tA2{p;PqMyeWSj4A~~gh=WT zq{~WJp%V3l`}Z-p#t!myW=_3N9ay`VVvw-Ccsz>ZGPx9Dkg6Yn%>%gM@Yfi?QYK%N z79yZ@dzSrcaTP;~eOt3K*Lu(XkYnOTq3TuScNSPFa@?6B@r=E`j8xW=6eoCL-^TjOcx={3kA~(NJ4Z&edOm)t%a?WaOjQ_)TgMk$^ zn4s0*MalD79hCJ|IgOO;UIWG*QYen!9fh}r_>AwPgObg{>v$6?Iao5?p}-u_ukpwQ zy%EcU*`Hds@bMT47MRP;5=^sRwLHzmDZ=8_iod^>NZiF)S&K;AejEAAhgye8rC40% z>U(hTSU$tO`^EIfa4Dwk*ga*e(>by}i%*AHuCGI1b^hcMh{49jVVrNy$W=*5In9)o zNKlw9^i~gNJ8^bp(~G|$efX<6Njc$sy|a)4trkngu}S?Tkp0!dlMAy$)au97SWTo5 zY#z;;!tv&>uci^U^8QF;kZ@UNH3C{k=Uyf=M79L3OitXfHwNCfqkq<3`1Rx*4$ge= zsz8^y^supCyS9~gNK8oJ&X3MvPYQQK5IG@b4Jn`F7lR6rSpI9^bcNaCDmWv#s8xBldUvXu8qn5;n4wb`{(cNMX>Q$ z>9_aVrgVo+T^&!$Oqe7Z+fx@kH7Qd%+q!4mjTqRsW1<&SVw`|Fc`-Z(tLC}j+R)Tt zPaYQkmQ>wRGPZ^HUgQvW9i(z1z9$l#Ht%20^hEUl;BgGLxu9qRD37)R$=g-5|7*r7 zLeH9#4RA#Ka&~DSM88fhe%&j75UvCES@A|5g5dqw_zW4yBUr~J@S9>I?;h5dL6C{E zj(pP+T?sRY_clrG)cKiYklR;4tLb!{F*rZ>Y72xE{1&1)aS}^_f$diX2Tk!2(>Th z-j0H(-Z397?BH$gb-q~h_T_7tHaWv)_k-Rs?Q`-0V>>f!cETs6Q+6T!@Em`tl=Do% z#tG7&oay5Q&@w;&Msf7buU8=AAO&nYJqjH&!7~+@1xt|qY@b=`T87?|YV~K5C6K^W z)e2-$5AdJ`b6)!4Y-)k|U6N^V`<>uP89w#4BOu|BP&!N>+YdULpJ7St3_YModM9z# zKL4C|4qa;?fQwU~~os_iBH zg#D1 zPvcV2(l+qP_5k~7i^R#`1&*#1I`2LLGB*1OR#3k!36Ne!A=zq{^@_iVrJJ{+n_brx zjl?7%8i|5r*%paY9#ey{!xyW;Q58{(=2JY`58U1?Op*?BL%X%UGj|$$>we` zZO5m0lby#JZBZ_C9vtxP4&+vc+Y9i#z#M4v`DHObD9Sue+4}=%mcJi?4UiNQP8;q9 zZ?q(gxm>a4P#bdvxustCe7qKyN(pK>iPCQ=en6G8<(3TWg%{Lwme5rhGJC(q5XHO&c9>?@*)SKQM|LJg&u2 znP*z!?Nsvw6LQ-K-bVGF+GSl~gS7+*1Qf0<>-9&ORsS*rz*N-BL7crwcI1%vepSq&#F|IWbINU_j1lKJRmZNRjJSZ}8`=FI zpv-58czpr$#JS>_jdFnpm)z&q;zPf=c0Cce1a=(5+_)E?Gpc$AYz1qp0H73gv0Waqf+1jS9pve!&#&*m_B@&FpbDHOvt>Yl}si?=JU9n(^#XgGi#HcEf%#yfERs0wiSNx7& z*{f;OPN_F{&fs{xL$Cq?o6FRSOEWw~J-=RNux#3-{Kr!?9|3lvJ6 z847?kYau^>rot}D*!6u*aCZ^96-NoJ<<(l?qdZ}*jaNS=Q6xTpz&QNiEXz>%8e^2M z+#p3UMR8>Sf9CCp4@(o=6dAtIB?mq?z2I{xcItVi_A{DpaRK2wT|bPU*6vO8@nY`i z!<UtL_d%CiB{HtV%FtP>9x)u(+rR5U!Q75+%Cvr zfszOc4-;Cx_Bh!L8yEnP6oqW&IHoS=8HjrRoM{^YAt$0?J6G*+KP<07ph&aidv{Fs`Dcty;< zh2pyk#g1{R$t)8_?x7jQaqA-KAcfr7&J-v8lK9+xQH!--gRScq-+IJ^>4Z%^q=~^z zN0*Bo-!XU7(Z_0TXOy#2*QBdkL}z19f3(_c`(01dR+l~sE;nV#%du!)f2l~Exlnt| zwBGgm2;6bkOzMV}+4fGivFUeK)iSdCfbOC!=J{7Jom7%*tq5Qh$Jk>6;TB7YZy6rW zbzEBh&i}RiS;4~lwox!kf{e-gt{!PsWbvzw1rWQ(GlwNT`N&38Sr=A+w%M>YI14C_`` zaD>kW8#()F#9}sTVdC2)DSv))9x8Y;a4EuCe$dd4=#!B@CN{+4mZhO=hD*#4dWg1b z@mxz-pcC;WZ5SV%HW7+ZZy^sh&Yc?j=)s)-bcr>f6;oMHsOxFgS>#`FNvR zO^jZD!GNInv4Ci&ttO|@DA=iuN*zSJGdzi7hjqS{*MN2f%*o6v8n{|Zh&t4y0 zwgQe-2!{R2k)J+&WK}|6q4wz1^S)myMH)*;3%Z#S@A@~Yo2QnxhO9Z%zdlf0tiIcl z`dT|YbEa$jdG{S=RkV1mj@o8#Im7e~oLalG-&AAlTjnhz8eY7fA||y+EQGY=&!kDy zp->RL@zz~s&(D| z&|f{}y}aR2lQ;TE{rqUl#f(GB#sTQ>bTlm|F8%Yod4IkIgTEykww6GJl+Ky+ z;_au03NDXP)qCCQE`6_hI}1r(TOR$-jh?LJtUwUy8LQmIvCt*tM`g+Me#1B`Qth zdEq;pYJE%OUk~@JZn}iZkUMl+$1NV%H*_v?fg@w4Pht|7-BiKDvh8k(cGk}YZD#`u zFq*X!;dsh}daKL3Qmp!dy{K>0F<&3AJM1_X(jr4JYE>N1e?4`zb$K^%0EqU$>>uh= zZ%x9b`_#tpjiy&6L>ZD`U>pVJ8hkWZu@9Bz0$IT54T5^r_2 znQI}JnCPD5$@TY7d9`lLtA%_paN|t-oXp7|a|H3iQ!v8}7S|oAJGOB1)h`BZb3)95 zXy$LDQ!1^aL38RNgS|E~i{bJxemk~syQ-Isefn{8bot4B8`Jf9<;hjP^y(t0CE(!j z@1JkQ?CA&8;F|-{&Wl$g#rqXp+~C6IEU41v*f!`q>|d?e_DI<#Qt#P<(KtknMmT`6 zbJA0@{#ZhXEop>@4T4@whUNgs&Z*?*oxRAudRAP2-dhMx3U%Sl5SHaFj1}GB{mUob z$Ih6#@l}a5i*&7htUv3zwP!`C$|m#733hXHMat$`UD86#F)r^t^zPqhOH*hg*P@{; zd*j2N4EPdfl-9k+?g`)k&nWepldR4u}j9@r}<#@ zX-q7m_o>exeRv)74-8^hu9mlrwfn9VJA*I8?!JwbT&=7|D~nEe;79Ko6Y~dej@>K; zXZ(l!O9o*U(v1~T_VTO~A43jNG(S1ng@o;#^0^-sS1!EcQ=9OFys12KyX=tH)Zd@? zl$kUYl8?HLr*zERk(BLkaCff7uo^G?zuyi6$@qHZ#!JxQ?v*1JG3iGe?3Y(z@y^mO zw0cU~f9{+Kh?|=`YOh4W12Mg~8KpLg$Cq%LW-|=4ymM zP8DZ}hu{IF@T33S^M4#$bdC$4-qy^=$PBL6=nA$o`u8Qiz)7V4x7wZ^g)Rujm&M_;nWpfc`+-M*b-ypb;`-_dh(vpxfKk~P2-$P&` zmYsCi^vclc*CGuxlFuRt9Q_O)*Dl*)&oFvFqR4JS#SFdskJ*d(3Kg;Yi7Bf{yS;fu z7L>V_PF`fHk$n#5_v)DIddtQ`EJVKP=#IV{J7t{HmpIoUmD|FJ+IRzUVVNH;n_ms$I({M+p_kO2kTt^ zAV~fZa;{ZAxg|4uL^)*k(c__Kp_A*AzI7R;L}_9k;td_9;tGnV2YNO|w8MD92+^Qu ze>y(6hPA^r3$_Qk*W;DdLw)W%rhI&#`aqW8%Y|dqZ^v4%#ylBx53~19tQpL|)K#@K zjMVfvNilzvR){cRP>}DjF%N8aZ6?b1P`{a;{3G`O-DiVCp}-tn-f_6ZxvJqfVWG2k zVc|ngtbCmF%*)00dQV1NyUv&RsDb?6=0%@CSwcbQqGz=FaAH#L%~rW>?Xt{Zht{jQ z7nKd^-U2ppeJSQRL0Q4~GDe~KPBLvrf+Dpt+fQreW(6u#ypk)|T;Ba*4N2;Fl3->W z=~NRJ_ebweSAm(w_5nas%2Td49>J46o)pu%mJR^YhwTMm4N3B>U5z#18LZNa;|J+W zh&#-+gS|=AH8)VIIT58+6j_6oenC*#@#`NEitZ4BOLJ~6hB&ls&s5Kx)Q9@h>rMU2 zf=)x_d*#J#Ut6BwA+8Miso%%hF z3JfkL@D25qtIj_EqUA)oKc`Om5NC*;dA6GE$NBKZLJJDVM3x6Ya?NUUiT%)$nnPCv z3-M&g@geEi#IyxAzFfE8vinT?7yVBQSka(6urufo(xn5>Xsp-Y^AoE3ibY=x{jAb@ zBte1g)(X(3pG{RUu{gI#@~;}+Y;kr}GM?jS2pLbh_g3B}4KaZ`rHNIG49;5$2K@rN zZRF$c|HR>VY_+%YHgKZvNa8arxWu5j?a)^FH@~xw_y3LdL%Taj=xeFGy$QByzTs`Z z)6zQ=YO{991u!FxBdJpdv_%vjj7%)_N)<8ePr;_XBD;?y|ofJe51 z)GG@ahxY40uxytz1&!;HDSDyfFH`gqX%*i(L*8Auo$GWbPUj831fFY)G^aK@(qsL3 z0}zl$T`zS$mDngFVjqdGH$n6ubRo4wgSDz>vc*9brW2QY))Y-pfXF~9j5M;OA*D5x z*16wXjv^FteR4lPUQ=vuV#>)*ZA|`<8%11To&L%H!U(PLKa9{E|EtQ7e>XxSYhIfn z#G&PdKs(2kypwd%>n`;B4VD0#3ztC_jPc%j#!D_iR@c`a++1r&@em%wG0yEPB1AUKiUl!%l+EpaC;dH49zzpLV;vEFeMqQ~&uSDo zGhv(|60e_{_EDRR!kPZ>&CoahgBe2jM^ zzXx=Y32jR}iiR6?{htzJTyUBoPb4u8{NT`oi(!ol2OUk}s75ifmv;;wf-BY9x-^}+ z47KiDn;s!_-M~B@?q{(hnqwbd&s!e7T9b3~1!gJ4^A<6To|hyiNN_uuW|fL*{{<8*2PT?P7)jM~GtU@ znXc}e;1EIqRDvOVvNgeh90vGbXl4WE4HEsjCk99h7Sfus_jNar6o#+j8d0W#svp+w zNm!P`ysfz@%9ioY=s$~Hs3x8{*^f0ewL+r)#!rHW7HsF0f9Kg{ThLi-v~)M6Zg~}$ zZ$WV%mE_KS3oEUyk>aM*-$9*n0gM&Z@anIhmj{@$h2xdmZJF!!ri1vh18sLNgr^i5 zgadV*YJ2-J^NI-1FPTehuz?G^ZZjw;7tgO-$=IAy#K{R-% zLysTXlCgSix<8VFNU@M5p=#2ayc7?2yqiuT!rw`JPXAg@?a9%|nf7ll97;)X>U zHl`Kb#R>Kw!{W6;=^|Xd*uQqNE$nIH(Ou=((2XS`Csybyk@GEkm;bQp!QP>!rM36S z&mHmiY1zzOI*OY@%f7?cq|v(kudkWl-uOG21_nI8X{7yzUtzXfh398oyvQBF8fl58 zHy`AA32m8wH)=oRr5HABUQHdl6T>UV$)QzP)xusuW->JP5m#wqeOxXCuI$!F!nO-< z?&~AI+BRyu3xe!PAiZ4rEVPeoFc1}7ymLwPe!wa$_li9@72=^o)vEV$=(QagFb6^} z{{9AE>}eftm7o7%gBcSRjk}XPXQ%0JPp6$ClQExn{g%}p;K|FCEOg%@G(qV8%73Xh z$)BgHH~UfxV_&Dc31RO}l-}c2Z_~j0bxjmqEjCoVlOW`a{rTPS*D5L8Db#q)J)+or z>7gOVk{6NVv?uoibh(rF8o|&0`IAW|YUJIfMvXoWb6=n9KW7-m&Dz|EuD6+JGOoB^ zq5bdQ-Kut*v~iI8i;h3`P`i>PZrFzZw?w6oAz^{jI!{Ia`2vcHS>t(rA2nCC7Ye>M zR=fjC#0X)dZ&w*-x{wHUgMsj0FXBGw;jYo-ttZ`FyF%;_3tYfDE6wJe^XuBHCE)qe zZIgQvH@vy78TS>Fp(<`xgxV@ltutv`xUQkbkIaNZ?!^Teo(nI2-p%UG7kDCjRYOT`=i) zrPHpPb5}Bdu(FgV7*gw>>vZPHX#Tv<@kF7^ z5U|8yp~m;}P8nm;vnA?Kh|)#Huu3bYQ30#f&G=GFhnR}a`+wejZ;}ntIOJJhj@I}t z8f%lb6FCf7RrCp?s+60CJ~UE-WOPF6HMKd~JT}dLuvLs}Ck%U2_B!UqY zTY(mhU{FNR8W188(y}l1(I0GH|A2STIro0&`_A0C=R6uNdnne>;C3ddN7h_NMpkZsRd+jC$hV(jD&N+9}Kl1V$I>Luld zViJrKZ4-rxidsCslUEK&!eGDZe?&iab2zC*4rvG zn-Aa%TW%ojrK)^MJuC6f8F5sW#*W(KgNveR zcS8o2&+Od4ff?dv&IWrvA**y_8xv@3wC7MVICD{=ti?4EKIS`-Vu>?61mE9lq!olF zo6`NDF^JK8=m~lp(40=nQr_puGkuAc|M?cJ5Z<4Ux<@@X2%9Jl$5%#uu^QDFt!OSZ|@E^J|1vbxk#%ajK6WYK6Dxf&1 zmp9$rOru~0tq9-}Hp-kx)wFxB%B0Z~xOtT?nE7eNQvu<_rFr@(hE?K%R(7fc8&zIr((D)LriVDml(Q|E&Xi~k5#Ft{CB7b6rze)T++y$ZOjh+y8 zRxhkBjf{`>20E$!4QnMelt8^HTai%SLVjNUJmMIsBfv#T1*Tw9b=by>vh-LKWb@MI z`6Xt-W5uwu8wLk}zfNdrt){&KxV@P-pUuaAku-gWy1LGlRep`tq<(q>Q}gFEbj*0O zakyO=CXlpf5g4e2V-7q??OWNoY70CX-{2R*OeOR4<}>!1o%CLuMb#r~>_6^8)sBOn zm^9p3xzwqvJaou3e>}F6y>t__1>qt1n0i6g`rx`g)yRk-%sxrQVy3yWLkWxPh0s5&bIlw7Wt^>e-C~eD1?yX(C@xDjJaMx`yqSUp-4ID`2QZ)EG6?Uka(j>F z3^uMS^sF@3KLP?7gko2P%$pAx@Rz$oL*%e`XA$0QBlP?o%k_k1sV{@5X<2|^uzZ!BLHWNo(IKMV<^c%qq|34{#|QDO52Ae Xic=g;>uN&jLbVn}j1AZ9-dFGsTUfs{ diff --git a/Firmware_1.26b/INSTRUCTIONS.md b/Firmware_1.26b/INSTRUCTIONS.md deleted file mode 100644 index 9921ba72..00000000 --- a/Firmware_1.26b/INSTRUCTIONS.md +++ /dev/null @@ -1,41 +0,0 @@ - - -# Maslow Firmware Setup - -Installing new firmware on your machine is important. We come out with a new firmware version every other week so be prepared to do this regularly. This process will also install the proper drivers to connect to your Arduino on some older computers so if you have trouble connecting it can be helpful to do this process on the same computer you will control the machine with. - -### Step 1: Connect Your Arduino -Connect your Arduino to your computer using the provided USB cable. - -### Step 2: Download The Arduino IDE -Download and install the last Arduino IDE from [https://www.arduino.cc/en/Main/Software](https://www.arduino.cc/en/Main/Software). Older versions of Arduino IDE have problems with libraries when compiling the firmware, so make sure you have the latest version. - -Note - For Windows there are three options: "Windows Installer", "Windows Zip", and "Windows App". - Some users have reported problems with the "Windows App" version. -![Download IDE](https://raw.githubusercontent.com/MaslowCNC/Firmware/master/Documentation/Download%20IDE.jpg) - -### Step 3: Download The Latest Maslow Firmware -You can do this at http://github.com/MaslowCNC/Firmware/releases/ Click the zip file for the most recent release to download it. Extract the files from the zip folder. -![Download Firmware](https://raw.githubusercontent.com/MaslowCNC/Firmware/master/Documentation/Download%20Firmware.jpg) - -### Step 4: Open Firmware -Click **File -> Open** and then open the firmware by selecting cnc_ctrl_v1.ino -![Open Firmware](https://raw.githubusercontent.com/MaslowCNC/Firmware/master/Documentation/Open%20Firmware.jpg) - -### Step 5: Select The Board Type -Select the board type by clicking **Tools -> Board -> Arduino/Genuino Mega or Mega 2560** -![Select Board Type](https://raw.githubusercontent.com/MaslowCNC/Firmware/master/Documentation/Select%20Board.jpg) - -### Step 6: Select The Serial Port -Select the correct port to connect to by clicking **Tools -> Port -> Your Port**. On Windows this will be something like COM3, on Mac and Linux computers it will be something like dev/tty/. You can find the right one by plugging and unplugging your Arduino compatible board and checking which option disappears. -![Select Serial Port](https://raw.githubusercontent.com/MaslowCNC/Firmware/master/Documentation/Select%20COM%20Port.jpg) - -### Step 7: Upload The Firmware -Upload the newest firmware to your machine by clicking the upload button in the top left corner. The arrow looks disabled until you hover over it! _Linux users_: if you are getting timeout or permissions errors, you may need to add your username to the `dialout` group and then logout and back in. [Instructions here.](https://askubuntu.com/questions/112568/how-do-i-allow-a-non-default-user-to-use-serial-device-ttyusb0) -![Upload Firmware](https://raw.githubusercontent.com/MaslowCNC/Firmware/master/Documentation/Upload.jpg) - -### Step 8: Finish -You are now running the latest firmware. *Great Job!* Make sure you close the Arduino IDE before proceeding. - -### Step 9: Proceed -You have finished setting up the Maslow firmware. Proceed to the [next step](http://maslowcommunitygarden.org/GroundControl.html?instructions=true) to install Ground Control on your OS. diff --git a/Firmware_1.26b/LICENSE b/Firmware_1.26b/LICENSE deleted file mode 100644 index 2f4b8c0b..00000000 --- a/Firmware_1.26b/LICENSE +++ /dev/null @@ -1,189 +0,0 @@ -GNU GENERAL PUBLIC LICENSE - -Version 3, 29 June 2007 - -Copyright © 2007 Free Software Foundation, Inc. - -Everyone is permitted to copy and distribute verbatim copies of this license document, but changing it is not allowed. -Preamble - -The GNU General Public License is a free, copyleft license for software and other kinds of works. - -The licenses for most software and other practical works are designed to take away your freedom to share and change the works. By contrast, the GNU General Public License is intended to guarantee your freedom to share and change all versions of a program--to make sure it remains free software for all its users. We, the Free Software Foundation, use the GNU General Public License for most of our software; it applies also to any other work released this way by its authors. You can apply it to your programs, too. - -When we speak of free software, we are referring to freedom, not price. Our General Public Licenses are designed to make sure that you have the freedom to distribute copies of free software (and charge for them if you wish), that you receive source code or can get it if you want it, that you can change the software or use pieces of it in new free programs, and that you know you can do these things. - -To protect your rights, we need to prevent others from denying you these rights or asking you to surrender the rights. Therefore, you have certain responsibilities if you distribute copies of the software, or if you modify it: responsibilities to respect the freedom of others. - -For example, if you distribute copies of such a program, whether gratis or for a fee, you must pass on to the recipients the same freedoms that you received. You must make sure that they, too, receive or can get the source code. And you must show them these terms so they know their rights. - -Developers that use the GNU GPL protect your rights with two steps: (1) assert copyright on the software, and (2) offer you this License giving you legal permission to copy, distribute and/or modify it. - -For the developers' and authors' protection, the GPL clearly explains that there is no warranty for this free software. For both users' and authors' sake, the GPL requires that modified versions be marked as changed, so that their problems will not be attributed erroneously to authors of previous versions. - -Some devices are designed to deny users access to install or run modified versions of the software inside them, although the manufacturer can do so. This is fundamentally incompatible with the aim of protecting users' freedom to change the software. The systematic pattern of such abuse occurs in the area of products for individuals to use, which is precisely where it is most unacceptable. Therefore, we have designed this version of the GPL to prohibit the practice for those products. If such problems arise substantially in other domains, we stand ready to extend this provision to those domains in future versions of the GPL, as needed to protect the freedom of users. - -Finally, every program is threatened constantly by software patents. States should not allow patents to restrict development and use of software on general-purpose computers, but in those that do, we wish to avoid the special danger that patents applied to a free program could make it effectively proprietary. To prevent this, the GPL assures that patents cannot be used to render the program non-free. - -The precise terms and conditions for copying, distribution and modification follow. -TERMS AND CONDITIONS -0. Definitions. - -“This License” refers to version 3 of the GNU General Public License. - -“Copyright” also means copyright-like laws that apply to other kinds of works, such as semiconductor masks. - -“The Program” refers to any copyrightable work licensed under this License. Each licensee is addressed as “you”. “Licensees” and “recipients” may be individuals or organizations. - -To “modify” a work means to copy from or adapt all or part of the work in a fashion requiring copyright permission, other than the making of an exact copy. The resulting work is called a “modified version” of the earlier work or a work “based on” the earlier work. - -A “covered work” means either the unmodified Program or a work based on the Program. - -To “propagate” a work means to do anything with it that, without permission, would make you directly or secondarily liable for infringement under applicable copyright law, except executing it on a computer or modifying a private copy. Propagation includes copying, distribution (with or without modification), making available to the public, and in some countries other activities as well. - -To “convey” a work means any kind of propagation that enables other parties to make or receive copies. Mere interaction with a user through a computer network, with no transfer of a copy, is not conveying. - -An interactive user interface displays “Appropriate Legal Notices” to the extent that it includes a convenient and prominently visible feature that (1) displays an appropriate copyright notice, and (2) tells the user that there is no warranty for the work (except to the extent that warranties are provided), that licensees may convey the work under this License, and how to view a copy of this License. If the interface presents a list of user commands or options, such as a menu, a prominent item in the list meets this criterion. -1. Source Code. - -The “source code” for a work means the preferred form of the work for making modifications to it. “Object code” means any non-source form of a work. - -A “Standard Interface” means an interface that either is an official standard defined by a recognized standards body, or, in the case of interfaces specified for a particular programming language, one that is widely used among developers working in that language. - -The “System Libraries” of an executable work include anything, other than the work as a whole, that (a) is included in the normal form of packaging a Major Component, but which is not part of that Major Component, and (b) serves only to enable use of the work with that Major Component, or to implement a Standard Interface for which an implementation is available to the public in source code form. A “Major Component”, in this context, means a major essential component (kernel, window system, and so on) of the specific operating system (if any) on which the executable work runs, or a compiler used to produce the work, or an object code interpreter used to run it. - -The “Corresponding Source” for a work in object code form means all the source code needed to generate, install, and (for an executable work) run the object code and to modify the work, including scripts to control those activities. However, it does not include the work's System Libraries, or general-purpose tools or generally available free programs which are used unmodified in performing those activities but which are not part of the work. For example, Corresponding Source includes interface definition files associated with source files for the work, and the source code for shared libraries and dynamically linked subprograms that the work is specifically designed to require, such as by intimate data communication or control flow between those subprograms and other parts of the work. - -The Corresponding Source need not include anything that users can regenerate automatically from other parts of the Corresponding Source. - -The Corresponding Source for a work in source code form is that same work. -2. Basic Permissions. - -All rights granted under this License are granted for the term of copyright on the Program, and are irrevocable provided the stated conditions are met. This License explicitly affirms your unlimited permission to run the unmodified Program. The output from running a covered work is covered by this License only if the output, given its content, constitutes a covered work. This License acknowledges your rights of fair use or other equivalent, as provided by copyright law. - -You may make, run and propagate covered works that you do not convey, without conditions so long as your license otherwise remains in force. You may convey covered works to others for the sole purpose of having them make modifications exclusively for you, or provide you with facilities for running those works, provided that you comply with the terms of this License in conveying all material for which you do not control copyright. Those thus making or running the covered works for you must do so exclusively on your behalf, under your direction and control, on terms that prohibit them from making any copies of your copyrighted material outside their relationship with you. - -Conveying under any other circumstances is permitted solely under the conditions stated below. Sublicensing is not allowed; section 10 makes it unnecessary. -3. Protecting Users' Legal Rights From Anti-Circumvention Law. - -No covered work shall be deemed part of an effective technological measure under any applicable law fulfilling obligations under article 11 of the WIPO copyright treaty adopted on 20 December 1996, or similar laws prohibiting or restricting circumvention of such measures. - -When you convey a covered work, you waive any legal power to forbid circumvention of technological measures to the extent such circumvention is effected by exercising rights under this License with respect to the covered work, and you disclaim any intention to limit operation or modification of the work as a means of enforcing, against the work's users, your or third parties' legal rights to forbid circumvention of technological measures. -4. Conveying Verbatim Copies. - -You may convey verbatim copies of the Program's source code as you receive it, in any medium, provided that you conspicuously and appropriately publish on each copy an appropriate copyright notice; keep intact all notices stating that this License and any non-permissive terms added in accord with section 7 apply to the code; keep intact all notices of the absence of any warranty; and give all recipients a copy of this License along with the Program. - -You may charge any price or no price for each copy that you convey, and you may offer support or warranty protection for a fee. -5. Conveying Modified Source Versions. - -You may convey a work based on the Program, or the modifications to produce it from the Program, in the form of source code under the terms of section 4, provided that you also meet all of these conditions: - - a) The work must carry prominent notices stating that you modified it, and giving a relevant date. - b) The work must carry prominent notices stating that it is released under this License and any conditions added under section 7. This requirement modifies the requirement in section 4 to “keep intact all notices”. - c) You must license the entire work, as a whole, under this License to anyone who comes into possession of a copy. This License will therefore apply, along with any applicable section 7 additional terms, to the whole of the work, and all its parts, regardless of how they are packaged. This License gives no permission to license the work in any other way, but it does not invalidate such permission if you have separately received it. - d) If the work has interactive user interfaces, each must display Appropriate Legal Notices; however, if the Program has interactive interfaces that do not display Appropriate Legal Notices, your work need not make them do so. - -A compilation of a covered work with other separate and independent works, which are not by their nature extensions of the covered work, and which are not combined with it such as to form a larger program, in or on a volume of a storage or distribution medium, is called an “aggregate” if the compilation and its resulting copyright are not used to limit the access or legal rights of the compilation's users beyond what the individual works permit. Inclusion of a covered work in an aggregate does not cause this License to apply to the other parts of the aggregate. -6. Conveying Non-Source Forms. - -You may convey a covered work in object code form under the terms of sections 4 and 5, provided that you also convey the machine-readable Corresponding Source under the terms of this License, in one of these ways: - - a) Convey the object code in, or embodied in, a physical product (including a physical distribution medium), accompanied by the Corresponding Source fixed on a durable physical medium customarily used for software interchange. - b) Convey the object code in, or embodied in, a physical product (including a physical distribution medium), accompanied by a written offer, valid for at least three years and valid for as long as you offer spare parts or customer support for that product model, to give anyone who possesses the object code either (1) a copy of the Corresponding Source for all the software in the product that is covered by this License, on a durable physical medium customarily used for software interchange, for a price no more than your reasonable cost of physically performing this conveying of source, or (2) access to copy the Corresponding Source from a network server at no charge. - c) Convey individual copies of the object code with a copy of the written offer to provide the Corresponding Source. This alternative is allowed only occasionally and noncommercially, and only if you received the object code with such an offer, in accord with subsection 6b. - d) Convey the object code by offering access from a designated place (gratis or for a charge), and offer equivalent access to the Corresponding Source in the same way through the same place at no further charge. You need not require recipients to copy the Corresponding Source along with the object code. If the place to copy the object code is a network server, the Corresponding Source may be on a different server (operated by you or a third party) that supports equivalent copying facilities, provided you maintain clear directions next to the object code saying where to find the Corresponding Source. Regardless of what server hosts the Corresponding Source, you remain obligated to ensure that it is available for as long as needed to satisfy these requirements. - e) Convey the object code using peer-to-peer transmission, provided you inform other peers where the object code and Corresponding Source of the work are being offered to the general public at no charge under subsection 6d. - -A separable portion of the object code, whose source code is excluded from the Corresponding Source as a System Library, need not be included in conveying the object code work. - -A “User Product” is either (1) a “consumer product”, which means any tangible personal property which is normally used for personal, family, or household purposes, or (2) anything designed or sold for incorporation into a dwelling. In determining whether a product is a consumer product, doubtful cases shall be resolved in favor of coverage. For a particular product received by a particular user, “normally used” refers to a typical or common use of that class of product, regardless of the status of the particular user or of the way in which the particular user actually uses, or expects or is expected to use, the product. A product is a consumer product regardless of whether the product has substantial commercial, industrial or non-consumer uses, unless such uses represent the only significant mode of use of the product. - -“Installation Information” for a User Product means any methods, procedures, authorization keys, or other information required to install and execute modified versions of a covered work in that User Product from a modified version of its Corresponding Source. The information must suffice to ensure that the continued functioning of the modified object code is in no case prevented or interfered with solely because modification has been made. - -If you convey an object code work under this section in, or with, or specifically for use in, a User Product, and the conveying occurs as part of a transaction in which the right of possession and use of the User Product is transferred to the recipient in perpetuity or for a fixed term (regardless of how the transaction is characterized), the Corresponding Source conveyed under this section must be accompanied by the Installation Information. But this requirement does not apply if neither you nor any third party retains the ability to install modified object code on the User Product (for example, the work has been installed in ROM). - -The requirement to provide Installation Information does not include a requirement to continue to provide support service, warranty, or updates for a work that has been modified or installed by the recipient, or for the User Product in which it has been modified or installed. Access to a network may be denied when the modification itself materially and adversely affects the operation of the network or violates the rules and protocols for communication across the network. - -Corresponding Source conveyed, and Installation Information provided, in accord with this section must be in a format that is publicly documented (and with an implementation available to the public in source code form), and must require no special password or key for unpacking, reading or copying. -7. Additional Terms. - -“Additional permissions” are terms that supplement the terms of this License by making exceptions from one or more of its conditions. Additional permissions that are applicable to the entire Program shall be treated as though they were included in this License, to the extent that they are valid under applicable law. If additional permissions apply only to part of the Program, that part may be used separately under those permissions, but the entire Program remains governed by this License without regard to the additional permissions. - -When you convey a copy of a covered work, you may at your option remove any additional permissions from that copy, or from any part of it. (Additional permissions may be written to require their own removal in certain cases when you modify the work.) You may place additional permissions on material, added by you to a covered work, for which you have or can give appropriate copyright permission. - -Notwithstanding any other provision of this License, for material you add to a covered work, you may (if authorized by the copyright holders of that material) supplement the terms of this License with terms: - - a) Disclaiming warranty or limiting liability differently from the terms of sections 15 and 16 of this License; or - b) Requiring preservation of specified reasonable legal notices or author attributions in that material or in the Appropriate Legal Notices displayed by works containing it; or - c) Prohibiting misrepresentation of the origin of that material, or requiring that modified versions of such material be marked in reasonable ways as different from the original version; or - d) Limiting the use for publicity purposes of names of licensors or authors of the material; or - e) Declining to grant rights under trademark law for use of some trade names, trademarks, or service marks; or - f) Requiring indemnification of licensors and authors of that material by anyone who conveys the material (or modified versions of it) with contractual assumptions of liability to the recipient, for any liability that these contractual assumptions directly impose on those licensors and authors. - -All other non-permissive additional terms are considered “further restrictions” within the meaning of section 10. If the Program as you received it, or any part of it, contains a notice stating that it is governed by this License along with a term that is a further restriction, you may remove that term. If a license document contains a further restriction but permits relicensing or conveying under this License, you may add to a covered work material governed by the terms of that license document, provided that the further restriction does not survive such relicensing or conveying. - -If you add terms to a covered work in accord with this section, you must place, in the relevant source files, a statement of the additional terms that apply to those files, or a notice indicating where to find the applicable terms. - -Additional terms, permissive or non-permissive, may be stated in the form of a separately written license, or stated as exceptions; the above requirements apply either way. -8. Termination. - -You may not propagate or modify a covered work except as expressly provided under this License. Any attempt otherwise to propagate or modify it is void, and will automatically terminate your rights under this License (including any patent licenses granted under the third paragraph of section 11). - -However, if you cease all violation of this License, then your license from a particular copyright holder is reinstated (a) provisionally, unless and until the copyright holder explicitly and finally terminates your license, and (b) permanently, if the copyright holder fails to notify you of the violation by some reasonable means prior to 60 days after the cessation. - -Moreover, your license from a particular copyright holder is reinstated permanently if the copyright holder notifies you of the violation by some reasonable means, this is the first time you have received notice of violation of this License (for any work) from that copyright holder, and you cure the violation prior to 30 days after your receipt of the notice. - -Termination of your rights under this section does not terminate the licenses of parties who have received copies or rights from you under this License. If your rights have been terminated and not permanently reinstated, you do not qualify to receive new licenses for the same material under section 10. -9. Acceptance Not Required for Having Copies. - -You are not required to accept this License in order to receive or run a copy of the Program. Ancillary propagation of a covered work occurring solely as a consequence of using peer-to-peer transmission to receive a copy likewise does not require acceptance. However, nothing other than this License grants you permission to propagate or modify any covered work. These actions infringe copyright if you do not accept this License. Therefore, by modifying or propagating a covered work, you indicate your acceptance of this License to do so. -10. Automatic Licensing of Downstream Recipients. - -Each time you convey a covered work, the recipient automatically receives a license from the original licensors, to run, modify and propagate that work, subject to this License. You are not responsible for enforcing compliance by third parties with this License. - -An “entity transaction” is a transaction transferring control of an organization, or substantially all assets of one, or subdividing an organization, or merging organizations. If propagation of a covered work results from an entity transaction, each party to that transaction who receives a copy of the work also receives whatever licenses to the work the party's predecessor in interest had or could give under the previous paragraph, plus a right to possession of the Corresponding Source of the work from the predecessor in interest, if the predecessor has it or can get it with reasonable efforts. - -You may not impose any further restrictions on the exercise of the rights granted or affirmed under this License. For example, you may not impose a license fee, royalty, or other charge for exercise of rights granted under this License, and you may not initiate litigation (including a cross-claim or counterclaim in a lawsuit) alleging that any patent claim is infringed by making, using, selling, offering for sale, or importing the Program or any portion of it. -11. Patents. - -A “contributor” is a copyright holder who authorizes use under this License of the Program or a work on which the Program is based. The work thus licensed is called the contributor's “contributor version”. - -A contributor's “essential patent claims” are all patent claims owned or controlled by the contributor, whether already acquired or hereafter acquired, that would be infringed by some manner, permitted by this License, of making, using, or selling its contributor version, but do not include claims that would be infringed only as a consequence of further modification of the contributor version. For purposes of this definition, “control” includes the right to grant patent sublicenses in a manner consistent with the requirements of this License. - -Each contributor grants you a non-exclusive, worldwide, royalty-free patent license under the contributor's essential patent claims, to make, use, sell, offer for sale, import and otherwise run, modify and propagate the contents of its contributor version. - -In the following three paragraphs, a “patent license” is any express agreement or commitment, however denominated, not to enforce a patent (such as an express permission to practice a patent or covenant not to sue for patent infringement). To “grant” such a patent license to a party means to make such an agreement or commitment not to enforce a patent against the party. - -If you convey a covered work, knowingly relying on a patent license, and the Corresponding Source of the work is not available for anyone to copy, free of charge and under the terms of this License, through a publicly available network server or other readily accessible means, then you must either (1) cause the Corresponding Source to be so available, or (2) arrange to deprive yourself of the benefit of the patent license for this particular work, or (3) arrange, in a manner consistent with the requirements of this License, to extend the patent license to downstream recipients. “Knowingly relying” means you have actual knowledge that, but for the patent license, your conveying the covered work in a country, or your recipient's use of the covered work in a country, would infringe one or more identifiable patents in that country that you have reason to believe are valid. - -If, pursuant to or in connection with a single transaction or arrangement, you convey, or propagate by procuring conveyance of, a covered work, and grant a patent license to some of the parties receiving the covered work authorizing them to use, propagate, modify or convey a specific copy of the covered work, then the patent license you grant is automatically extended to all recipients of the covered work and works based on it. - -A patent license is “discriminatory” if it does not include within the scope of its coverage, prohibits the exercise of, or is conditioned on the non-exercise of one or more of the rights that are specifically granted under this License. You may not convey a covered work if you are a party to an arrangement with a third party that is in the business of distributing software, under which you make payment to the third party based on the extent of your activity of conveying the work, and under which the third party grants, to any of the parties who would receive the covered work from you, a discriminatory patent license (a) in connection with copies of the covered work conveyed by you (or copies made from those copies), or (b) primarily for and in connection with specific products or compilations that contain the covered work, unless you entered into that arrangement, or that patent license was granted, prior to 28 March 2007. - -Nothing in this License shall be construed as excluding or limiting any implied license or other defenses to infringement that may otherwise be available to you under applicable patent law. -12. No Surrender of Others' Freedom. - -If conditions are imposed on you (whether by court order, agreement or otherwise) that contradict the conditions of this License, they do not excuse you from the conditions of this License. If you cannot convey a covered work so as to satisfy simultaneously your obligations under this License and any other pertinent obligations, then as a consequence you may not convey it at all. For example, if you agree to terms that obligate you to collect a royalty for further conveying from those to whom you convey the Program, the only way you could satisfy both those terms and this License would be to refrain entirely from conveying the Program. -13. Use with the GNU Affero General Public License. - -Notwithstanding any other provision of this License, you have permission to link or combine any covered work with a work licensed under version 3 of the GNU Affero General Public License into a single combined work, and to convey the resulting work. The terms of this License will continue to apply to the part which is the covered work, but the special requirements of the GNU Affero General Public License, section 13, concerning interaction through a network will apply to the combination as such. -14. Revised Versions of this License. - -The Free Software Foundation may publish revised and/or new versions of the GNU General Public License from time to time. Such new versions will be similar in spirit to the present version, but may differ in detail to address new problems or concerns. - -Each version is given a distinguishing version number. If the Program specifies that a certain numbered version of the GNU General Public License “or any later version” applies to it, you have the option of following the terms and conditions either of that numbered version or of any later version published by the Free Software Foundation. If the Program does not specify a version number of the GNU General Public License, you may choose any version ever published by the Free Software Foundation. - -If the Program specifies that a proxy can decide which future versions of the GNU General Public License can be used, that proxy's public statement of acceptance of a version permanently authorizes you to choose that version for the Program. - -Later license versions may give you additional or different permissions. However, no additional obligations are imposed on any author or copyright holder as a result of your choosing to follow a later version. -15. Disclaimer of Warranty. - -THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM “AS IS” WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION. -16. Limitation of Liability. - -IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGES. -17. Interpretation of Sections 15 and 16. - -If the disclaimer of warranty and limitation of liability provided above cannot be given local legal effect according to their terms, reviewing courts shall apply local law that most closely approximates an absolute waiver of all civil liability in connection with the Program, unless a warranty or assumption of liability accompanies a copy of the Program in return for a fee. - -END OF TERMS AND CONDITIONS \ No newline at end of file diff --git a/Firmware_1.26b/README.md b/Firmware_1.26b/README.md deleted file mode 100644 index 56b5ec48..00000000 --- a/Firmware_1.26b/README.md +++ /dev/null @@ -1,77 +0,0 @@ -# Maslow Firmware - -This is the firmware which controls the Maslow CNC machine - -[![Build Status](https://travis-ci.org/MaslowCNC/Firmware.svg?branch=master)](https://travis-ci.org/MaslowCNC/Firmware) - -This is the firmware for the Maslow CNC Router - - -## Steps to setup the Firmware development environment - -First clone the Firmware repository, then install and setup the IDE of your choice. - -### Using Arduino IDE -1. Download [Arduino IDE](https://www.arduino.cc/en/main/software) 1.8.1 or higher -2. Install Arduino IDE and run Arduino IDE -3. Navigate menus: File, Open -4. In the file chooser navigate to the cloned repository and choose the "cnc_ctrl_v1.ino" file to open -5. Navigate menu: Tools, Board, change to "Arduino/Genuino Mega or Mega 2560" -6. Navigate menu: Sketch -> Upload - -This should compile the project without errors, and possibly some warnings. - -### Using PlatformIO -1. Download package for [Atom](https://atom.io/) -2. Follow directions for [installing PlatformIO within Atom](http://docs.platformio.org/en/latest/ide/atom.html#ide-installation) -3. Within Atom navigate menus: PlatformIO, Open Project -4. Select "Firmware" directory -5. Click "Open Firmware" - -### Using Eclipse Neon C/C++ with Sloeber plugin - -1. Download [Eclipse C/C++](https://eclipse.org/downloads/) Neon or higher -2. Install Eclipse C/C++ and run Eclipse -3. Install Sloeber Arduino plugin - * Navigate menus: Help, Install New Software... - * Copy this URL in the "Work With" field: http://eclipse.baeyens.it/update/V4/stable - * Select "Add" button - * Select "Sloeber Arduino IDE" check box - * Select "Finish" button - * Accept defaults and accept licenses, the plugin will restart Eclipse, and configure the plugin -4. Change to Arduino perspective, navigate menus: Window, Perspective, Open Perspective, Other... - * Choose the "Arduino" perspective and select "Ok" button -5. Create an Arduino project - * Navigate menus: File, New, New Arduino Sketch - * Project Name: cnc_ctrl_v1 - * Select "Next" button - * Select appropriate item from "Platform folder" drop down listing - * Select Board: Arduino/Genuino Mega or Mega 2560 - * Select Upload Protocol: Default - * Select Processor: ATmega2560 (Mega 2560) - * Select "Finish" button -6. Import project source code - * Select project folder, navigate menus: File, Import... - * Expand "General" and select "File system" - * Select "Next" button - * Select the "Browse" button to select the source location (location of the cloned repository cnc_ctrl_v1 directory) - * Select whole source directory in the left pane - * Open Advanced Settings by klicking on "Advanced>>" button - * Select 'Create Links in Workspace' and 'Create virtual folders' leave other settings untouched - * Select 'Finish' button - * Eclipse asks if overwriting the original cnc_ctrl_v1.ino file is ok. Confirm with 'yes'. -7. Update eclipse project include paths - * Select the project folder in the project explorer and click Project->Properties in the menu. - * In the Project properties left Pane select C/C++ Build->Settings - * In the right Pane select the 'Tool Settings' Tab and add the path to the source location to the include paths of all compilers/linkers of the toolchain. - * The last two steps may differ between toolchains. - - -### Using NotePad++ in Conjunction with the Arduino IDE -1. Download NotePad++ (Windows only) [link](https://notepad-plus-plus.org/) -2. Download the Arduino IDE [link](https://www.arduino.cc/en/main/software) -3. Set that you would like use an external editor from within the Arduino IDE by clicking File -> Preferences -> Use External Editor - *The Arduino editor will no longer allow you to edit the files, but instead will only work to compile and upload your code. - *The code can be edited from within NotePad++ - *This method can be used on other platforms with editing programs other than NP++ - diff --git a/Firmware_1.26b/cnc_ctrl_v1/Axis.cpp b/Firmware_1.26b/cnc_ctrl_v1/Axis.cpp deleted file mode 100644 index c6ce84b9..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Axis.cpp +++ /dev/null @@ -1,301 +0,0 @@ -/*This file is part of the Maslow Control Software. - - The Maslow Control Software is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - Maslow Control Software is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with the Maslow Control Software. If not, see . - - Copyright 2014-2017 Bar Smith*/ - - -#include "Maslow.h" - -void Axis::setup(const int& pwmPin, const int& directionPin1, const int& directionPin2, const int& encoderPin1, const int& encoderPin2, const char& axisName, const unsigned long& loopInterval) -{ - // I don't really like this, but I don't know how else to initialize a pointer to a value - float zero = 0.0; - float one = 1.0; - _Kp = _Ki = _Kd = &zero; - - motorGearboxEncoder.setup(pwmPin, directionPin1, directionPin2, encoderPin1, encoderPin2, loopInterval); - _pidController.setup(&_pidInput, &_pidOutput, &_pidSetpoint, _Kp, _Ki, _Kd, &one, REVERSE); - - //initialize variables - _axisName = axisName; - - initializePID(loopInterval); - - motorGearboxEncoder.setName(&_axisName); -} - -void Axis::initializePID(const unsigned long& loopInterval){ - _pidController.SetMode(AUTOMATIC); - _pidController.SetOutputLimits(-20, 20); - _pidController.SetSampleTime( loopInterval / 1000); -} - -void Axis::write(const float& targetPosition){ - _timeLastMoved = millis(); - _pidSetpoint = targetPosition/ *_mmPerRotation; - return; -} - -float Axis::read(){ - //returns the true axis position - - return (motorGearboxEncoder.encoder.read()/ *_encoderSteps) * *_mmPerRotation; - -} - -float Axis::setpoint(){ - return _pidSetpoint * *_mmPerRotation; -} - -void Axis::set(const float& newAxisPosition){ - - //reset everything to the new value - _pidSetpoint = newAxisPosition/ *_mmPerRotation; - motorGearboxEncoder.encoder.write((newAxisPosition * *_encoderSteps)/ *_mmPerRotation); - -} - -long Axis::steps(){ - /* - Returns the number of steps reported by the encoder - */ - return motorGearboxEncoder.encoder.read(); -} - -void Axis::setSteps(const long& steps){ - - //reset everything to the new value - _pidSetpoint = steps/ *_encoderSteps; - motorGearboxEncoder.encoder.write(steps); - -} - -void Axis::computePID(){ - - #ifdef FAKE_SERVO - if (motorGearboxEncoder.motor.attached()){ - // Adds up to 10% error just to simulate servo noise - double rpm = (-1 * _pidOutput) * random(90, 110) / 100; - unsigned long steps = motorGearboxEncoder.encoder.read() + round( rpm * *_encoderSteps * LOOPINTERVAL)/(60 * 1000000); - motorGearboxEncoder.encoder.write(steps); - } - #endif - - if (_disableAxisForTesting || !motorGearboxEncoder.motor.attached()){ - return; - } - - _pidInput = motorGearboxEncoder.encoder.read()/ *_encoderSteps; - - if (_pidController.Compute()){ - // Only write output if the PID calculation was performed - motorGearboxEncoder.write(_pidOutput); - } - - motorGearboxEncoder.computePID(); - -} - -void Axis::disablePositionPID(){ - - _pidController.SetMode(MANUAL); - -} - -void Axis::enablePositionPID(){ - - _pidController.SetMode(AUTOMATIC); - -} - -void Axis::setPIDValues(float* KpPos, float* KiPos, float* KdPos, float* propWeight, float* KpV, float* KiV, float* KdV, float* propWeightV){ - /* - - Sets the positional PID values for the axis - - */ - _Kp = KpPos; - _Ki = KiPos; - _Kd = KdPos; - - _pidController.SetTunings(_Kp, _Ki, _Kd, propWeight); - - motorGearboxEncoder.setPIDValues(KpV, KiV, KdV, propWeightV); -} - -String Axis::getPIDString(){ - /* - - Get PID tuning values - - */ - String PIDString = "Kp="; - return PIDString + *_Kp + ",Ki=" + *_Ki + ",Kd=" + *_Kd; -} - -void Axis::setPIDAggressiveness(float aggressiveness){ - /* - - The setPIDAggressiveness() function sets the aggressiveness of the PID controller to - compensate for a change in the load on the motor. - - */ - - motorGearboxEncoder.setPIDAggressiveness(aggressiveness); -} - -float Axis::error(){ - - float encoderErr = (motorGearboxEncoder.encoder.read()/ *_encoderSteps) - _pidSetpoint; - - return encoderErr * *_mmPerRotation; -} - -void Axis::changePitch(float *newPitch){ - /* - Reassign the distance moved per-rotation for the axis. - */ - _mmPerRotation = newPitch; -} - -float Axis::getPitch(){ - /* - Returns the distance moved per-rotation for the axis. - */ - return *_mmPerRotation; -} - -void Axis::changeEncoderResolution(float *newResolution){ - /* - Reassign the encoder resolution for the axis. - */ - _encoderSteps = newResolution; - - //push to the gearbox for calculating RPM - motorGearboxEncoder.setEncoderResolution(*newResolution); - -} - -int Axis::detach(){ - - motorGearboxEncoder.motor.detach(); - - return 1; -} - -int Axis::attach(){ - motorGearboxEncoder.motor.attach(); - return 1; -} - -bool Axis::attached(){ - /* - - Returns true if the axis is attached, false if it is not. - - */ - - return motorGearboxEncoder.motor.attached(); -} - -void Axis::detachIfIdle(){ - /* - Detaches the axis, turning off the motor and PID control, if it has been - stationary for more than axisDetachTime - */ - if (millis() - _timeLastMoved > sysSettings.axisDetachTime){ - detach(); - } - -} - -void Axis::endMove(const float& finalTarget){ - - _timeLastMoved = millis(); - _pidSetpoint = finalTarget/ *_mmPerRotation; - -} - -void Axis::stop(){ - /* - - Immediately stop the axis where it is, not where it should be - - */ - - _timeLastMoved = millis(); - _pidSetpoint = read()/ *_mmPerRotation; - -} - -void Axis::test(){ - /* - Test the axis by directly commanding the motor and observing if the encoder moves - */ - - Serial.print(F("Testing ")); - Serial.print(_axisName); - Serial.println(F(" motor:")); - - //print something to prevent the connection from timing out - Serial.print(F("")); - - int i = 0; - double encoderPos = motorGearboxEncoder.encoder.read(); //record the position now - - //move the motor - while (i < 1000){ - motorGearboxEncoder.motor.directWrite(255); - i++; - maslowDelay(1); - if (sys.stop){return;} - } - - //check to see if it moved - if(encoderPos - motorGearboxEncoder.encoder.read() > 500){ - Serial.println(F("Direction 1 - Pass")); - } - else{ - Serial.println(F("Direction 1 - Fail")); - } - - //record the position again - encoderPos = motorGearboxEncoder.encoder.read(); - Serial.print(F("")); - - //move the motor in the other direction - i = 0; - while (i < 1000){ - motorGearboxEncoder.motor.directWrite(-255); - i++; - maslowDelay(1); - if (sys.stop){return;} - } - - //check to see if it moved - if(encoderPos - motorGearboxEncoder.encoder.read() < -500){ - Serial.println(F("Direction 2 - Pass")); - } - else{ - Serial.println(F("Direction 2 - Fail")); - } - - //stop the motor - motorGearboxEncoder.motor.directWrite(0); - Serial.print(F("")); -} - -double Axis::pidInput(){ return _pidInput * *_mmPerRotation;} -double Axis::pidOutput(){ return _pidOutput;} diff --git a/Firmware_1.26b/cnc_ctrl_v1/Axis.h b/Firmware_1.26b/cnc_ctrl_v1/Axis.h deleted file mode 100644 index 2f193dbc..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Axis.h +++ /dev/null @@ -1,70 +0,0 @@ - /*This file is part of the Maslow Control Software. - - The Maslow Control Software is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - Maslow Control Software is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with the Maslow Control Software. If not, see . - - Copyright 2014-2017 Bar Smith*/ - - #ifndef Axis_h - #define Axis_h - - class Axis{ - public: - void setup(const int& pwmPin, const int& directionPin1, const int& directionPin2, const int& encoderPin1, const int& encoderPin2, const char& axisName, const unsigned long& loopInterval); - void write(const float& targetPosition); - float read(); - void set(const float& newAxisPosition); - void setSteps(const long& steps); - int updatePositionFromEncoder(); - void initializePID(const unsigned long& loopInterval); - int detach(); - int attach(); - void detachIfIdle(); - void endMove(const float& finalTarget); - void stop(); - float target(); - float error(); - float setpoint(); - void computePID(); - void disablePositionPID(); - void enablePositionPID(); - void setPIDAggressiveness(float aggressiveness); - void test(); - void changePitch(float* newPitch); - float getPitch(); - void changeEncoderResolution(float* newResolution); - bool attached(); - MotorGearboxEncoder motorGearboxEncoder; - void setPIDValues(float* Kp, float* Ki, float* Kd, float* propWeight, float* KpV, float* KiV, float* KdV, float* propWeightV); - String getPIDString(); - double pidInput(); - double pidOutput(); - long steps(); - - private: - int _PWMread(int pin); - void _writeFloat(const unsigned int& addr, const float& x); - float _readFloat(const unsigned int& addr); - unsigned long _timeLastMoved; - volatile double _pidSetpoint; - volatile double _pidInput; - volatile double _pidOutput; - float *_Kp, *_Ki, *_Kd; - PID _pidController; - float *_mmPerRotation; - float *_encoderSteps; - bool _disableAxisForTesting = false; - char _axisName; - }; - - #endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/Config.h b/Firmware_1.26b/cnc_ctrl_v1/Config.h deleted file mode 100644 index b31d2dac..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Config.h +++ /dev/null @@ -1,64 +0,0 @@ -/*This file is part of the Maslow Control Software. - The Maslow Control Software is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - Maslow Control Software is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - You should have received a copy of the GNU General Public License - along with the Maslow Control Software. If not, see . - - Copyright 2014-2017 Bar Smith*/ - -// This file contains precompile configuration settings that apply to the -// whole system - -#ifndef config_h -#define config_h - -// Debugging Options -#define verboseDebug 0 // set to 0 for no debug messages, 1 for single-line messages, 2 to also output ring buffer contents -#define misloopDebug 0 // set to 1 for a warning every time the movement loop fails - // to complete before being interrupted, helpful for loop - // LOOPINTERVAL tuning -#define KINEMATICSDBG 0 // set to 1 for additional kinematics debug messaging - -// #define FAKE_SERVO // Uncomment this line to cause the Firmware to mimic - // a servo updating the encoder steps even if no servo - // is connected. Useful for testing on an arduino only - -// #define SIMAVR // Uncomment this if you plan to run the Firmware in the simavr - // simulator. Normally, you would not define this directly, but - // use PlatformIO to build the simavr environment. - -#define LOOPINTERVAL 10000 // What is the frequency of the PID loop in microseconds - -// Define version detect pins -#define VERS1 22 -#define VERS2 23 -#define VERS3 24 -#define VERS4 25 -#define VERS5 26 -#define VERS6 27 - -// Serial variables -#define INCBUFFERLENGTH 128 // The number of bytes(characters) allocated to the - // incoming buffer. -#define EXPGCODELINE 60 // Maximum expected Gcode line length in characters - // including line ending character(s). Assumes - // client will not send more than this. Ground - // Control is currently set to 60. NIST spec allows - // 256. This value must be <= INCBUFFERLENGTH -#define MAXBUFFERLINES 4 // The maximum number of lines allowed in the buffer -#define POSITIONTIMEOUT 200 // The minimum number of milliseconds between - // position reports sent to Ground Control. This - // cannot be larger than the connection timout in - // Ground Control which is 2000, a smaller number - // takes more processing time for sending data - // a larger number make position updates in GC less - // smooth. This is only a minimum, and the actual - // timeout could be significantly larger. - -#endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/Encoder.cpp b/Firmware_1.26b/cnc_ctrl_v1/Encoder.cpp deleted file mode 100644 index b4492dfe..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Encoder.cpp +++ /dev/null @@ -1,10 +0,0 @@ - -#include "Maslow.h" - -// Yes, all the code is in the header file, to provide the user -// configure options with #define (before they include it), and -// to facilitate some crafty optimizations! - -Encoder_internal_state_t * Encoder::interruptArgs[]; - - diff --git a/Firmware_1.26b/cnc_ctrl_v1/Encoder.h b/Firmware_1.26b/cnc_ctrl_v1/Encoder.h deleted file mode 100644 index 4b428997..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Encoder.h +++ /dev/null @@ -1,976 +0,0 @@ -/* Encoder Library, for measuring quadrature encoded signals - * http://www.pjrc.com/teensy/td_libs_Encoder.html - * Copyright (c) 2011,2013 PJRC.COM, LLC - Paul Stoffregen - * - * Version 1.2 - fix -2 bug in C-only code - * Version 1.1 - expand to support boards with up to 60 interrupts - * Version 1.0 - initial release - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - */ - - -#ifndef Encoder_h_ -#define Encoder_h_ - -#if defined(ARDUINO) && ARDUINO >= 100 -#include "Arduino.h" -#elif defined(WIRING) -#include "Wiring.h" -#else -#include "WProgram.h" -#include "pins_arduino.h" -#endif - -#if defined(ENCODER_USE_INTERRUPTS) || !defined(ENCODER_DO_NOT_USE_INTERRUPTS) -#define ENCODER_USE_INTERRUPTS -#define ENCODER_ARGLIST_SIZE CORE_NUM_INTERRUPT -#include "utility/interrupt_pins.h" -#ifdef ENCODER_OPTIMIZE_INTERRUPTS -#include "utility/interrupt_config.h" -#endif -#else -#define ENCODER_ARGLIST_SIZE 0 -#endif - - - -// All the data needed by interrupts is consolidated into this ugly struct -// to facilitate assembly language optimizing of the speed critical update. -// The assembly code uses auto-incrementing addressing modes, so the struct -// must remain in exactly this order. -typedef struct { - volatile IO_REG_TYPE * pin1_register; - volatile IO_REG_TYPE * pin2_register; - IO_REG_TYPE pin1_bitmask; - IO_REG_TYPE pin2_bitmask; - uint8_t state; - int32_t position; - int32_t elapsedTime; - int32_t lastTime; -} Encoder_internal_state_t; - -class Encoder -{ -public: - void setup(uint8_t pin1, uint8_t pin2) { - #ifdef INPUT_PULLUP - pinMode(pin1, INPUT_PULLUP); - pinMode(pin2, INPUT_PULLUP); - #else - pinMode(pin1, INPUT); - digitalWrite(pin1, HIGH); - pinMode(pin2, INPUT); - digitalWrite(pin2, HIGH); - #endif - encoder.pin1_register = PIN_TO_BASEREG(pin1); - encoder.pin1_bitmask = PIN_TO_BITMASK(pin1); - encoder.pin2_register = PIN_TO_BASEREG(pin2); - encoder.pin2_bitmask = PIN_TO_BITMASK(pin2); - encoder.position = 0; - // allow time for a passive R-C filter to charge - // through the pullup resistors, before reading - // the initial state - delayMicroseconds(2000); - uint8_t s = 0; - if (DIRECT_PIN_READ(encoder.pin1_register, encoder.pin1_bitmask)) s |= 1; - if (DIRECT_PIN_READ(encoder.pin2_register, encoder.pin2_bitmask)) s |= 2; - encoder.state = s; -#ifdef ENCODER_USE_INTERRUPTS - interrupts_in_use = attach_interrupt(pin1, &encoder); - interrupts_in_use += attach_interrupt(pin2, &encoder); -#endif - //update_finishup(); // to force linker to include the code (does not work) - } - - -#ifdef ENCODER_USE_INTERRUPTS - inline int32_t read() { - if (interrupts_in_use < 2) { - noInterrupts(); - update(&encoder); - } else { - noInterrupts(); - } - int32_t ret = encoder.position; - interrupts(); - return ret; - } - inline int32_t elapsedTime() { - if (interrupts_in_use < 2) { - noInterrupts(); - update(&encoder); - } else { - noInterrupts(); - } - int32_t ret = encoder.elapsedTime; - interrupts(); - return ret; - } - inline int32_t lastStepTime() { - if (interrupts_in_use < 2) { - noInterrupts(); - update(&encoder); - } else { - noInterrupts(); - } - int32_t ret = encoder.lastTime; - interrupts(); - return ret; - } - inline void write(int32_t p) { - noInterrupts(); - encoder.position = p; - interrupts(); - } -#else - inline int32_t read() { - update(&encoder); - return encoder.position; - } - inline void write(int32_t p) { - encoder.position = p; - } -#endif -private: - Encoder_internal_state_t encoder; -#ifdef ENCODER_USE_INTERRUPTS - uint8_t interrupts_in_use; -#endif -public: - static Encoder_internal_state_t * interruptArgs[ENCODER_ARGLIST_SIZE]; - -// _______ _______ -// Pin1 ______| |_______| |______ Pin1 -// negative <--- _______ _______ __ --> positive -// Pin2 __| |_______| |_______| Pin2 - - // new new old old - // pin2 pin1 pin2 pin1 Result - // ---- ---- ---- ---- ------ - // 0 0 0 0 no movement - // 0 0 0 1 +1 - // 0 0 1 0 -1 - // 0 0 1 1 +2 (assume pin1 edges only) - // 0 1 0 0 -1 - // 0 1 0 1 no movement - // 0 1 1 0 -2 (assume pin1 edges only) - // 0 1 1 1 +1 - // 1 0 0 0 +1 - // 1 0 0 1 -2 (assume pin1 edges only) - // 1 0 1 0 no movement - // 1 0 1 1 -1 - // 1 1 0 0 +2 (assume pin1 edges only) - // 1 1 0 1 -1 - // 1 1 1 0 +1 - // 1 1 1 1 no movement -/* - // Simple, easy-to-read "documentation" version :-) - // - void update(void) { - uint8_t s = state & 3; - if (digitalRead(pin1)) s |= 4; - if (digitalRead(pin2)) s |= 8; - switch (s) { - case 0: case 5: case 10: case 15: - break; - case 1: case 7: case 8: case 14: - position++; break; - case 2: case 4: case 11: case 13: - position--; break; - case 3: case 12: - position += 2; break; - default: - position -= 2; break; - } - state = (s >> 2); - } -*/ - -private: - static void update(Encoder_internal_state_t *arg) { -#if defined(__AVR_DISABLED__) - // Changed from __AVR__ to force C code below, until someone has - // the chance to write the elapsedTime feature into assembly - // code. The time difference between the two options is - // minimal at best. - // The compiler believes this is just 1 line of code, so - // it will inline this function into each interrupt - // handler. That's a tiny bit faster, but grows the code. - // Especially when used with ENCODER_OPTIMIZE_INTERRUPTS, - // the inline nature allows the ISR prologue and epilogue - // to only save/restore necessary registers, for very nice - // speed increase. - asm volatile ( - "ld r30, X+" "\n\t" - "ld r31, X+" "\n\t" - "ld r24, Z" "\n\t" // r24 = pin1 input - "ld r30, X+" "\n\t" - "ld r31, X+" "\n\t" - "ld r25, Z" "\n\t" // r25 = pin2 input - "ld r30, X+" "\n\t" // r30 = pin1 mask - "ld r31, X+" "\n\t" // r31 = pin2 mask - "ld r22, X" "\n\t" // r22 = state - "andi r22, 3" "\n\t" - "and r24, r30" "\n\t" - "breq L%=1" "\n\t" // if (pin1) - "ori r22, 4" "\n\t" // state |= 4 - "L%=1:" "and r25, r31" "\n\t" - "breq L%=2" "\n\t" // if (pin2) - "ori r22, 8" "\n\t" // state |= 8 - "L%=2:" "ldi r30, lo8(pm(L%=table))" "\n\t" - "ldi r31, hi8(pm(L%=table))" "\n\t" - "add r30, r22" "\n\t" - "adc r31, __zero_reg__" "\n\t" - "asr r22" "\n\t" - "asr r22" "\n\t" - "st X+, r22" "\n\t" // store new state - "ld r22, X+" "\n\t" - "ld r23, X+" "\n\t" - "ld r24, X+" "\n\t" - "ld r25, X+" "\n\t" - "ijmp" "\n\t" // jumps to update_finishup() - // TODO move this table to another static function, - // so it doesn't get needlessly duplicated. Easier - // said than done, due to linker issues and inlining - "L%=table:" "\n\t" - "rjmp L%=end" "\n\t" // 0 - "rjmp L%=plus1" "\n\t" // 1 - "rjmp L%=minus1" "\n\t" // 2 - "rjmp L%=plus2" "\n\t" // 3 - "rjmp L%=minus1" "\n\t" // 4 - "rjmp L%=end" "\n\t" // 5 - "rjmp L%=minus2" "\n\t" // 6 - "rjmp L%=plus1" "\n\t" // 7 - "rjmp L%=plus1" "\n\t" // 8 - "rjmp L%=minus2" "\n\t" // 9 - "rjmp L%=end" "\n\t" // 10 - "rjmp L%=minus1" "\n\t" // 11 - "rjmp L%=plus2" "\n\t" // 12 - "rjmp L%=minus1" "\n\t" // 13 - "rjmp L%=plus1" "\n\t" // 14 - "rjmp L%=end" "\n\t" // 15 - "L%=minus2:" "\n\t" - "subi r22, 2" "\n\t" - "sbci r23, 0" "\n\t" - "sbci r24, 0" "\n\t" - "sbci r25, 0" "\n\t" - "rjmp L%=store" "\n\t" - "L%=minus1:" "\n\t" - "subi r22, 1" "\n\t" - "sbci r23, 0" "\n\t" - "sbci r24, 0" "\n\t" - "sbci r25, 0" "\n\t" - "rjmp L%=store" "\n\t" - "L%=plus2:" "\n\t" - "subi r22, 254" "\n\t" - "rjmp L%=z" "\n\t" - "L%=plus1:" "\n\t" - "subi r22, 255" "\n\t" - "L%=z:" "sbci r23, 255" "\n\t" - "sbci r24, 255" "\n\t" - "sbci r25, 255" "\n\t" - "L%=store:" "\n\t" - "st -X, r25" "\n\t" - "st -X, r24" "\n\t" - "st -X, r23" "\n\t" - "st -X, r22" "\n\t" - "L%=end:" "\n" - : : "x" (arg) : "r22", "r23", "r24", "r25", "r30", "r31"); -#else - uint8_t p1val = DIRECT_PIN_READ(arg->pin1_register, arg->pin1_bitmask); - uint8_t p2val = DIRECT_PIN_READ(arg->pin2_register, arg->pin2_bitmask); - uint8_t state = arg->state & 3; - if (p1val) state |= 4; - if (p2val) state |= 8; - arg->state = (state >> 2); - switch (state) { - case 1: case 7: case 8: case 14: - arg->position++; - arg->elapsedTime = (micros() - arg->lastTime); - arg->lastTime = micros(); - return; - case 2: case 4: case 11: case 13: - arg->position--; - arg->elapsedTime = (arg->lastTime - micros()); - arg->lastTime = micros(); - return; - case 3: case 12: - arg->position += 2; - arg->elapsedTime = (micros() - arg->lastTime) >> 1; - arg->lastTime = micros(); - return; - case 6: case 9: - arg->position -= 2; - arg->elapsedTime = (arg->lastTime - micros()) >> 1; - arg->lastTime = micros(); - return; - } -#endif - } -/* -#if defined(__AVR__) - // TODO: this must be a no inline function - // even noinline does not seem to solve difficult - // problems with this. Oh well, it was only meant - // to shrink code size - there's no performance - // improvement in this, only code size reduction. - __attribute__((noinline)) void update_finishup(void) { - asm volatile ( - "ldi r30, lo8(pm(Ltable))" "\n\t" - "ldi r31, hi8(pm(Ltable))" "\n\t" - "Ltable:" "\n\t" - "rjmp L%=end" "\n\t" // 0 - "rjmp L%=plus1" "\n\t" // 1 - "rjmp L%=minus1" "\n\t" // 2 - "rjmp L%=plus2" "\n\t" // 3 - "rjmp L%=minus1" "\n\t" // 4 - "rjmp L%=end" "\n\t" // 5 - "rjmp L%=minus2" "\n\t" // 6 - "rjmp L%=plus1" "\n\t" // 7 - "rjmp L%=plus1" "\n\t" // 8 - "rjmp L%=minus2" "\n\t" // 9 - "rjmp L%=end" "\n\t" // 10 - "rjmp L%=minus1" "\n\t" // 11 - "rjmp L%=plus2" "\n\t" // 12 - "rjmp L%=minus1" "\n\t" // 13 - "rjmp L%=plus1" "\n\t" // 14 - "rjmp L%=end" "\n\t" // 15 - "L%=minus2:" "\n\t" - "subi r22, 2" "\n\t" - "sbci r23, 0" "\n\t" - "sbci r24, 0" "\n\t" - "sbci r25, 0" "\n\t" - "rjmp L%=store" "\n\t" - "L%=minus1:" "\n\t" - "subi r22, 1" "\n\t" - "sbci r23, 0" "\n\t" - "sbci r24, 0" "\n\t" - "sbci r25, 0" "\n\t" - "rjmp L%=store" "\n\t" - "L%=plus2:" "\n\t" - "subi r22, 254" "\n\t" - "rjmp L%=z" "\n\t" - "L%=plus1:" "\n\t" - "subi r22, 255" "\n\t" - "L%=z:" "sbci r23, 255" "\n\t" - "sbci r24, 255" "\n\t" - "sbci r25, 255" "\n\t" - "L%=store:" "\n\t" - "st -X, r25" "\n\t" - "st -X, r24" "\n\t" - "st -X, r23" "\n\t" - "st -X, r22" "\n\t" - "L%=end:" "\n" - : : : "r22", "r23", "r24", "r25", "r30", "r31"); - } -#endif -*/ - - -#ifdef ENCODER_USE_INTERRUPTS - // this giant function is an unfortunate consequence of Arduino's - // attachInterrupt function not supporting any way to pass a pointer - // or other context to the attached function. - static uint8_t attach_interrupt(uint8_t pin, Encoder_internal_state_t *state) { - switch (pin) { - #ifdef CORE_INT0_PIN - case CORE_INT0_PIN: - interruptArgs[0] = state; - attachInterrupt(0, isr0, CHANGE); - break; - #endif - #ifdef CORE_INT1_PIN - case CORE_INT1_PIN: - interruptArgs[1] = state; - attachInterrupt(1, isr1, CHANGE); - break; - #endif - #ifdef CORE_INT2_PIN - case CORE_INT2_PIN: - interruptArgs[2] = state; - attachInterrupt(2, isr2, CHANGE); - break; - #endif - #ifdef CORE_INT3_PIN - case CORE_INT3_PIN: - interruptArgs[3] = state; - attachInterrupt(3, isr3, CHANGE); - break; - #endif - #ifdef CORE_INT4_PIN - case CORE_INT4_PIN: - interruptArgs[4] = state; - attachInterrupt(4, isr4, CHANGE); - break; - #endif - #ifdef CORE_INT5_PIN - case CORE_INT5_PIN: - interruptArgs[5] = state; - attachInterrupt(5, isr5, CHANGE); - break; - #endif - #ifdef CORE_INT6_PIN - case CORE_INT6_PIN: - interruptArgs[6] = state; - attachInterrupt(6, isr6, CHANGE); - break; - #endif - #ifdef CORE_INT7_PIN - case CORE_INT7_PIN: - interruptArgs[7] = state; - attachInterrupt(7, isr7, CHANGE); - break; - #endif - #ifdef CORE_INT8_PIN - case CORE_INT8_PIN: - interruptArgs[8] = state; - attachInterrupt(8, isr8, CHANGE); - break; - #endif - #ifdef CORE_INT9_PIN - case CORE_INT9_PIN: - interruptArgs[9] = state; - attachInterrupt(9, isr9, CHANGE); - break; - #endif - #ifdef CORE_INT10_PIN - case CORE_INT10_PIN: - interruptArgs[10] = state; - attachInterrupt(10, isr10, CHANGE); - break; - #endif - #ifdef CORE_INT11_PIN - case CORE_INT11_PIN: - interruptArgs[11] = state; - attachInterrupt(11, isr11, CHANGE); - break; - #endif - #ifdef CORE_INT12_PIN - case CORE_INT12_PIN: - interruptArgs[12] = state; - attachInterrupt(12, isr12, CHANGE); - break; - #endif - #ifdef CORE_INT13_PIN - case CORE_INT13_PIN: - interruptArgs[13] = state; - attachInterrupt(13, isr13, CHANGE); - break; - #endif - #ifdef CORE_INT14_PIN - case CORE_INT14_PIN: - interruptArgs[14] = state; - attachInterrupt(14, isr14, CHANGE); - break; - #endif - #ifdef CORE_INT15_PIN - case CORE_INT15_PIN: - interruptArgs[15] = state; - attachInterrupt(15, isr15, CHANGE); - break; - #endif - #ifdef CORE_INT16_PIN - case CORE_INT16_PIN: - interruptArgs[16] = state; - attachInterrupt(16, isr16, CHANGE); - break; - #endif - #ifdef CORE_INT17_PIN - case CORE_INT17_PIN: - interruptArgs[17] = state; - attachInterrupt(17, isr17, CHANGE); - break; - #endif - #ifdef CORE_INT18_PIN - case CORE_INT18_PIN: - interruptArgs[18] = state; - attachInterrupt(18, isr18, CHANGE); - break; - #endif - #ifdef CORE_INT19_PIN - case CORE_INT19_PIN: - interruptArgs[19] = state; - attachInterrupt(19, isr19, CHANGE); - break; - #endif - #ifdef CORE_INT20_PIN - case CORE_INT20_PIN: - interruptArgs[20] = state; - attachInterrupt(20, isr20, CHANGE); - break; - #endif - #ifdef CORE_INT21_PIN - case CORE_INT21_PIN: - interruptArgs[21] = state; - attachInterrupt(21, isr21, CHANGE); - break; - #endif - #ifdef CORE_INT22_PIN - case CORE_INT22_PIN: - interruptArgs[22] = state; - attachInterrupt(22, isr22, CHANGE); - break; - #endif - #ifdef CORE_INT23_PIN - case CORE_INT23_PIN: - interruptArgs[23] = state; - attachInterrupt(23, isr23, CHANGE); - break; - #endif - #ifdef CORE_INT24_PIN - case CORE_INT24_PIN: - interruptArgs[24] = state; - attachInterrupt(24, isr24, CHANGE); - break; - #endif - #ifdef CORE_INT25_PIN - case CORE_INT25_PIN: - interruptArgs[25] = state; - attachInterrupt(25, isr25, CHANGE); - break; - #endif - #ifdef CORE_INT26_PIN - case CORE_INT26_PIN: - interruptArgs[26] = state; - attachInterrupt(26, isr26, CHANGE); - break; - #endif - #ifdef CORE_INT27_PIN - case CORE_INT27_PIN: - interruptArgs[27] = state; - attachInterrupt(27, isr27, CHANGE); - break; - #endif - #ifdef CORE_INT28_PIN - case CORE_INT28_PIN: - interruptArgs[28] = state; - attachInterrupt(28, isr28, CHANGE); - break; - #endif - #ifdef CORE_INT29_PIN - case CORE_INT29_PIN: - interruptArgs[29] = state; - attachInterrupt(29, isr29, CHANGE); - break; - #endif - - #ifdef CORE_INT30_PIN - case CORE_INT30_PIN: - interruptArgs[30] = state; - attachInterrupt(30, isr30, CHANGE); - break; - #endif - #ifdef CORE_INT31_PIN - case CORE_INT31_PIN: - interruptArgs[31] = state; - attachInterrupt(31, isr31, CHANGE); - break; - #endif - #ifdef CORE_INT32_PIN - case CORE_INT32_PIN: - interruptArgs[32] = state; - attachInterrupt(32, isr32, CHANGE); - break; - #endif - #ifdef CORE_INT33_PIN - case CORE_INT33_PIN: - interruptArgs[33] = state; - attachInterrupt(33, isr33, CHANGE); - break; - #endif - #ifdef CORE_INT34_PIN - case CORE_INT34_PIN: - interruptArgs[34] = state; - attachInterrupt(34, isr34, CHANGE); - break; - #endif - #ifdef CORE_INT35_PIN - case CORE_INT35_PIN: - interruptArgs[35] = state; - attachInterrupt(35, isr35, CHANGE); - break; - #endif - #ifdef CORE_INT36_PIN - case CORE_INT36_PIN: - interruptArgs[36] = state; - attachInterrupt(36, isr36, CHANGE); - break; - #endif - #ifdef CORE_INT37_PIN - case CORE_INT37_PIN: - interruptArgs[37] = state; - attachInterrupt(37, isr37, CHANGE); - break; - #endif - #ifdef CORE_INT38_PIN - case CORE_INT38_PIN: - interruptArgs[38] = state; - attachInterrupt(38, isr38, CHANGE); - break; - #endif - #ifdef CORE_INT39_PIN - case CORE_INT39_PIN: - interruptArgs[39] = state; - attachInterrupt(39, isr39, CHANGE); - break; - #endif - #ifdef CORE_INT40_PIN - case CORE_INT40_PIN: - interruptArgs[40] = state; - attachInterrupt(40, isr40, CHANGE); - break; - #endif - #ifdef CORE_INT41_PIN - case CORE_INT41_PIN: - interruptArgs[41] = state; - attachInterrupt(41, isr41, CHANGE); - break; - #endif - #ifdef CORE_INT42_PIN - case CORE_INT42_PIN: - interruptArgs[42] = state; - attachInterrupt(42, isr42, CHANGE); - break; - #endif - #ifdef CORE_INT43_PIN - case CORE_INT43_PIN: - interruptArgs[43] = state; - attachInterrupt(43, isr43, CHANGE); - break; - #endif - #ifdef CORE_INT44_PIN - case CORE_INT44_PIN: - interruptArgs[44] = state; - attachInterrupt(44, isr44, CHANGE); - break; - #endif - #ifdef CORE_INT45_PIN - case CORE_INT45_PIN: - interruptArgs[45] = state; - attachInterrupt(45, isr45, CHANGE); - break; - #endif - #ifdef CORE_INT46_PIN - case CORE_INT46_PIN: - interruptArgs[46] = state; - attachInterrupt(46, isr46, CHANGE); - break; - #endif - #ifdef CORE_INT47_PIN - case CORE_INT47_PIN: - interruptArgs[47] = state; - attachInterrupt(47, isr47, CHANGE); - break; - #endif - #ifdef CORE_INT48_PIN - case CORE_INT48_PIN: - interruptArgs[48] = state; - attachInterrupt(48, isr48, CHANGE); - break; - #endif - #ifdef CORE_INT49_PIN - case CORE_INT49_PIN: - interruptArgs[49] = state; - attachInterrupt(49, isr49, CHANGE); - break; - #endif - #ifdef CORE_INT50_PIN - case CORE_INT50_PIN: - interruptArgs[50] = state; - attachInterrupt(50, isr50, CHANGE); - break; - #endif - #ifdef CORE_INT51_PIN - case CORE_INT51_PIN: - interruptArgs[51] = state; - attachInterrupt(51, isr51, CHANGE); - break; - #endif - #ifdef CORE_INT52_PIN - case CORE_INT52_PIN: - interruptArgs[52] = state; - attachInterrupt(52, isr52, CHANGE); - break; - #endif - #ifdef CORE_INT53_PIN - case CORE_INT53_PIN: - interruptArgs[53] = state; - attachInterrupt(53, isr53, CHANGE); - break; - #endif - #ifdef CORE_INT54_PIN - case CORE_INT54_PIN: - interruptArgs[54] = state; - attachInterrupt(54, isr54, CHANGE); - break; - #endif - #ifdef CORE_INT55_PIN - case CORE_INT55_PIN: - interruptArgs[55] = state; - attachInterrupt(55, isr55, CHANGE); - break; - #endif - #ifdef CORE_INT56_PIN - case CORE_INT56_PIN: - interruptArgs[56] = state; - attachInterrupt(56, isr56, CHANGE); - break; - #endif - #ifdef CORE_INT57_PIN - case CORE_INT57_PIN: - interruptArgs[57] = state; - attachInterrupt(57, isr57, CHANGE); - break; - #endif - #ifdef CORE_INT58_PIN - case CORE_INT58_PIN: - interruptArgs[58] = state; - attachInterrupt(58, isr58, CHANGE); - break; - #endif - #ifdef CORE_INT59_PIN - case CORE_INT59_PIN: - interruptArgs[59] = state; - attachInterrupt(59, isr59, CHANGE); - break; - #endif - default: - return 0; - } - return 1; - } -#endif // ENCODER_USE_INTERRUPTS - - -#if defined(ENCODER_USE_INTERRUPTS) && !defined(ENCODER_OPTIMIZE_INTERRUPTS) - #ifdef CORE_INT0_PIN - static void isr0(void) { update(interruptArgs[0]); } - #endif - #ifdef CORE_INT1_PIN - static void isr1(void) { update(interruptArgs[1]); } - #endif - #ifdef CORE_INT2_PIN - static void isr2(void) { update(interruptArgs[2]); } - #endif - #ifdef CORE_INT3_PIN - static void isr3(void) { update(interruptArgs[3]); } - #endif - #ifdef CORE_INT4_PIN - static void isr4(void) { update(interruptArgs[4]); } - #endif - #ifdef CORE_INT5_PIN - static void isr5(void) { update(interruptArgs[5]); } - #endif - #ifdef CORE_INT6_PIN - static void isr6(void) { update(interruptArgs[6]); } - #endif - #ifdef CORE_INT7_PIN - static void isr7(void) { update(interruptArgs[7]); } - #endif - #ifdef CORE_INT8_PIN - static void isr8(void) { update(interruptArgs[8]); } - #endif - #ifdef CORE_INT9_PIN - static void isr9(void) { update(interruptArgs[9]); } - #endif - #ifdef CORE_INT10_PIN - static void isr10(void) { update(interruptArgs[10]); } - #endif - #ifdef CORE_INT11_PIN - static void isr11(void) { update(interruptArgs[11]); } - #endif - #ifdef CORE_INT12_PIN - static void isr12(void) { update(interruptArgs[12]); } - #endif - #ifdef CORE_INT13_PIN - static void isr13(void) { update(interruptArgs[13]); } - #endif - #ifdef CORE_INT14_PIN - static void isr14(void) { update(interruptArgs[14]); } - #endif - #ifdef CORE_INT15_PIN - static void isr15(void) { update(interruptArgs[15]); } - #endif - #ifdef CORE_INT16_PIN - static void isr16(void) { update(interruptArgs[16]); } - #endif - #ifdef CORE_INT17_PIN - static void isr17(void) { update(interruptArgs[17]); } - #endif - #ifdef CORE_INT18_PIN - static void isr18(void) { update(interruptArgs[18]); } - #endif - #ifdef CORE_INT19_PIN - static void isr19(void) { update(interruptArgs[19]); } - #endif - #ifdef CORE_INT20_PIN - static void isr20(void) { update(interruptArgs[20]); } - #endif - #ifdef CORE_INT21_PIN - static void isr21(void) { update(interruptArgs[21]); } - #endif - #ifdef CORE_INT22_PIN - static void isr22(void) { update(interruptArgs[22]); } - #endif - #ifdef CORE_INT23_PIN - static void isr23(void) { update(interruptArgs[23]); } - #endif - #ifdef CORE_INT24_PIN - static void isr24(void) { update(interruptArgs[24]); } - #endif - #ifdef CORE_INT25_PIN - static void isr25(void) { update(interruptArgs[25]); } - #endif - #ifdef CORE_INT26_PIN - static void isr26(void) { update(interruptArgs[26]); } - #endif - #ifdef CORE_INT27_PIN - static void isr27(void) { update(interruptArgs[27]); } - #endif - #ifdef CORE_INT28_PIN - static void isr28(void) { update(interruptArgs[28]); } - #endif - #ifdef CORE_INT29_PIN - static void isr29(void) { update(interruptArgs[29]); } - #endif - #ifdef CORE_INT30_PIN - static void isr30(void) { update(interruptArgs[30]); } - #endif - #ifdef CORE_INT31_PIN - static void isr31(void) { update(interruptArgs[31]); } - #endif - #ifdef CORE_INT32_PIN - static void isr32(void) { update(interruptArgs[32]); } - #endif - #ifdef CORE_INT33_PIN - static void isr33(void) { update(interruptArgs[33]); } - #endif - #ifdef CORE_INT34_PIN - static void isr34(void) { update(interruptArgs[34]); } - #endif - #ifdef CORE_INT35_PIN - static void isr35(void) { update(interruptArgs[35]); } - #endif - #ifdef CORE_INT36_PIN - static void isr36(void) { update(interruptArgs[36]); } - #endif - #ifdef CORE_INT37_PIN - static void isr37(void) { update(interruptArgs[37]); } - #endif - #ifdef CORE_INT38_PIN - static void isr38(void) { update(interruptArgs[38]); } - #endif - #ifdef CORE_INT39_PIN - static void isr39(void) { update(interruptArgs[39]); } - #endif - #ifdef CORE_INT40_PIN - static void isr40(void) { update(interruptArgs[40]); } - #endif - #ifdef CORE_INT41_PIN - static void isr41(void) { update(interruptArgs[41]); } - #endif - #ifdef CORE_INT42_PIN - static void isr42(void) { update(interruptArgs[42]); } - #endif - #ifdef CORE_INT43_PIN - static void isr43(void) { update(interruptArgs[43]); } - #endif - #ifdef CORE_INT44_PIN - static void isr44(void) { update(interruptArgs[44]); } - #endif - #ifdef CORE_INT45_PIN - static void isr45(void) { update(interruptArgs[45]); } - #endif - #ifdef CORE_INT46_PIN - static void isr46(void) { update(interruptArgs[46]); } - #endif - #ifdef CORE_INT47_PIN - static void isr47(void) { update(interruptArgs[47]); } - #endif - #ifdef CORE_INT48_PIN - static void isr48(void) { update(interruptArgs[48]); } - #endif - #ifdef CORE_INT49_PIN - static void isr49(void) { update(interruptArgs[49]); } - #endif - #ifdef CORE_INT50_PIN - static void isr50(void) { update(interruptArgs[50]); } - #endif - #ifdef CORE_INT51_PIN - static void isr51(void) { update(interruptArgs[51]); } - #endif - #ifdef CORE_INT52_PIN - static void isr52(void) { update(interruptArgs[52]); } - #endif - #ifdef CORE_INT53_PIN - static void isr53(void) { update(interruptArgs[53]); } - #endif - #ifdef CORE_INT54_PIN - static void isr54(void) { update(interruptArgs[54]); } - #endif - #ifdef CORE_INT55_PIN - static void isr55(void) { update(interruptArgs[55]); } - #endif - #ifdef CORE_INT56_PIN - static void isr56(void) { update(interruptArgs[56]); } - #endif - #ifdef CORE_INT57_PIN - static void isr57(void) { update(interruptArgs[57]); } - #endif - #ifdef CORE_INT58_PIN - static void isr58(void) { update(interruptArgs[58]); } - #endif - #ifdef CORE_INT59_PIN - static void isr59(void) { update(interruptArgs[59]); } - #endif -#endif -}; - -#if defined(ENCODER_USE_INTERRUPTS) && defined(ENCODER_OPTIMIZE_INTERRUPTS) -#if defined(__AVR__) -#if defined(INT0_vect) && CORE_NUM_INTERRUPT > 0 -ISR(INT0_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(0)]); } -#endif -#if defined(INT1_vect) && CORE_NUM_INTERRUPT > 1 -ISR(INT1_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(1)]); } -#endif -#if defined(INT2_vect) && CORE_NUM_INTERRUPT > 2 -ISR(INT2_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(2)]); } -#endif -#if defined(INT3_vect) && CORE_NUM_INTERRUPT > 3 -ISR(INT3_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(3)]); } -#endif -#if defined(INT4_vect) && CORE_NUM_INTERRUPT > 4 -ISR(INT4_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(4)]); } -#endif -#if defined(INT5_vect) && CORE_NUM_INTERRUPT > 5 -ISR(INT5_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(5)]); } -#endif -#if defined(INT6_vect) && CORE_NUM_INTERRUPT > 6 -ISR(INT6_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(6)]); } -#endif -#if defined(INT7_vect) && CORE_NUM_INTERRUPT > 7 -ISR(INT7_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(7)]); } -#endif -#endif // AVR -#endif // ENCODER_OPTIMIZE_INTERRUPTS - - -#endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/GCode.cpp b/Firmware_1.26b/cnc_ctrl_v1/GCode.cpp deleted file mode 100644 index 8a0cc684..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/GCode.cpp +++ /dev/null @@ -1,889 +0,0 @@ -/*This file is part of the Maslow Control Software. - -The Maslow Control Software is free software: you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation, either version 3 of the License, or -(at your option) any later version. - -Maslow Control Software is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with the Maslow Control Software. If not, see . - -Copyright 2014-2017 Bar Smith*/ - -// This file contains all the functions used to receive and parse the gcode -// commands - -#include "Maslow.h" - -RingBuffer incSerialBuffer; -String readyCommandString = ""; //KRK why is this a global? -String gcodeLine = ""; //Our use of this is a bit sloppy, at times, - //we pass references to this global and then - //name them the same thing. - -void initGCode(){ - // Called on startup or after a stop command - readyCommandString = ""; - incSerialBuffer.empty(); -} - -void readSerialCommands(){ - /* - Check to see if a new character is available from the serial connection, - if this is a necessary character write to the incSerialBuffer otherwise discard - it. - */ - - static bool quickCommandFlag = false; - - if (Serial.available() > 0) { - while (Serial.available() > 0) { - char c = Serial.read(); - if (c == '!'){ - sys.stop = true; - quickCommandFlag = true; - bit_false(sys.pause, PAUSE_FLAG_USER_PAUSE); - reportStatusMessage(STATUS_OK); - } - else if (c == '~'){ - quickCommandFlag = true; - bit_false(sys.pause, PAUSE_FLAG_USER_PAUSE); - reportStatusMessage(STATUS_OK); - } - else if (quickCommandFlag and c == '\n'){ - // Catch line ending and ignore after quick commands - quickCommandFlag = false; - } - else{ - quickCommandFlag = false; - int bufferOverflow = incSerialBuffer.write(c); //gets one byte from serial buffer, writes it to the internal ring buffer - if (bufferOverflow != 0) { - sys.stop = true; - } - } - if (sys.stop){return;} - } - #if defined (verboseDebug) && verboseDebug > 1 - // print ring buffer contents - Serial.println(F("rSC added to ring buffer")); - incSerialBuffer.print(); - #endif - } -} - -int findEndOfNumber(const String& textString, const int& index){ - //Return the index of the last digit of the number beginning at the index passed in - unsigned int i = index; - - while (i < textString.length()){ - - if(isDigit(textString[i]) or isPunct(textString[i])){ //If we're still looking at a number, keep goin - i++; - } - else{ - return i; //If we've reached the end of the number, return the last index - } - } - return i; //If we've reached the end of the string, return the last number -} - -float extractGcodeValue(const String& readString, char target, const float& defaultReturn){ - - /*Reads a string and returns the value of number following the target character. - If no number is found, defaultReturn is returned*/ - - int begin; - int end; - String numberAsString; - float numberAsFloat; - - begin = readString.indexOf(target); - end = findEndOfNumber(readString,begin+1); - numberAsString = readString.substring(begin+1,end); - - numberAsFloat = numberAsString.toFloat(); - - if (begin == -1){ //if the character was not found, return error - return defaultReturn; - } - - return numberAsFloat; -} - -byte executeBcodeLine(const String& gcodeLine){ - /* - - Executes a single line of gcode beginning with the character 'B'. - - */ - - //Handle B-codes - - if(gcodeLine.substring(0, 3) == "B05"){ - Serial.print(F("Firmware Version ")); - Serial.println(VERSIONNUMBER); - return STATUS_OK; - } - - if(sys.state == STATE_OLD_SETTINGS){ - return STATUS_OLD_SETTINGS; - } - - if(gcodeLine.substring(0, 3) == "B01"){ - - Serial.println(F("Motor Calibration Not Needed")); - - return STATUS_OK; - } - - if(gcodeLine.substring(0, 3) == "B02"){ - calibrateChainLengths(gcodeLine); - return STATUS_OK; - } - - if(gcodeLine.substring(0, 3) == "B04"){ - //set flag to ignore position error limit during the tests - sys.state = (sys.state | STATE_POS_ERR_IGNORE); - //Test each of the axis - maslowDelay(500); - if(sys.stop){return STATUS_OK;} - leftAxis.test(); - maslowDelay(500); - if(sys.stop){return STATUS_OK;} - rightAxis.test(); - maslowDelay(500); - if(sys.stop){return STATUS_OK;} - zAxis.test(); - Serial.println(F("Tests complete.")); - - // update our position - leftAxis.set(leftAxis.read()); - rightAxis.set(rightAxis.read()); - - //clear the flag, re-enable position error limit - sys.state = (sys.state & (!STATE_POS_ERR_IGNORE)); - return STATUS_OK; - } - - if(gcodeLine.substring(0, 3) == "B06"){ - Serial.println(F("Setting Chain Lengths To: ")); - float newL = extractGcodeValue(gcodeLine, 'L', 0); - float newR = extractGcodeValue(gcodeLine, 'R', 0); - - leftAxis.set(newL); - rightAxis.set(newR); - - Serial.print(F("Left: ")); - Serial.print(leftAxis.read()); - Serial.println(F("mm")); - Serial.print(F("Right: ")); - Serial.print(rightAxis.read()); - Serial.println(F("mm")); - - return STATUS_OK; - } - - if(gcodeLine.substring(0, 3) == "B08"){ - //Manually recalibrate chain lengths - leftAxis.set(sysSettings.originalChainLength); - rightAxis.set(sysSettings.originalChainLength); - - Serial.print(F("Left: ")); - Serial.print(leftAxis.read()); - Serial.println(F("mm")); - Serial.print(F("Right: ")); - Serial.print(rightAxis.read()); - Serial.println(F("mm")); - - kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition, 0, 0); - - Serial.println(F("Message: The machine chains have been manually re-calibrated.")); - - return STATUS_OK; - } - - if(gcodeLine.substring(0, 3) == "B09"){ - //Directly command each axis to move to a given distance - float lDist = extractGcodeValue(gcodeLine, 'L', 0); - float rDist = extractGcodeValue(gcodeLine, 'R', 0); - float speed = extractGcodeValue(gcodeLine, 'F', 800); - - if(sys.useRelativeUnits){ - if(abs(lDist) > 0){ - singleAxisMove(&leftAxis, leftAxis.read() + lDist, speed); - } - if(abs(rDist) > 0){ - singleAxisMove(&rightAxis, rightAxis.read() + rDist, speed); - } - } - else{ - singleAxisMove(&leftAxis, lDist, speed); - singleAxisMove(&rightAxis, rDist, speed); - } - - return STATUS_OK; - } - - if(gcodeLine.substring(0, 3) == "B10"){ - //measure the left axis chain length - Serial.print(F("[Measure: ")); - if (gcodeLine.indexOf('L') != -1){ - Serial.print(leftAxis.read()); - } - else{ - Serial.print(rightAxis.read()); - } - Serial.println(F("]")); - return STATUS_OK; - } - - if(gcodeLine.substring(0, 3) == "B11"){ - //run right motor in the given direction at the given speed for the given time - float speed = extractGcodeValue(gcodeLine, 'S', 100); - float time = extractGcodeValue(gcodeLine, 'T', 1); - - double ms = 1000*time; - double begin = millis(); - - int i = 0; - sys.state = (sys.state | STATE_POS_ERR_IGNORE); - while (millis() - begin < ms){ - if (gcodeLine.indexOf('L') != -1){ - leftAxis.motorGearboxEncoder.motor.directWrite(speed); - } - else{ - rightAxis.motorGearboxEncoder.motor.directWrite(speed); - } - - i++; - execSystemRealtime(); - if (sys.stop){return STATUS_OK;} - } - sys.state = (sys.state | (!STATE_POS_ERR_IGNORE)); - return STATUS_OK; - } - - if(gcodeLine.substring(0, 3) == "B13"){ - //PID Testing of Velocity - float left = extractGcodeValue(gcodeLine, 'L', 0); - float useZ = extractGcodeValue(gcodeLine, 'Z', 0); - float start = extractGcodeValue(gcodeLine, 'S', 1); - float stop = extractGcodeValue(gcodeLine, 'F', 1); - float steps = extractGcodeValue(gcodeLine, 'I', 1); - float version = extractGcodeValue(gcodeLine, 'V', 1); - - Axis* axis = &rightAxis; - if (left > 0) axis = &leftAxis; - if (useZ > 0) axis = &zAxis; - PIDTestVelocity(axis, start, stop, steps, version); - return STATUS_OK; - } - - if(gcodeLine.substring(0, 3) == "B14"){ - //PID Testing of Position - float left = extractGcodeValue(gcodeLine, 'L', 0); - float useZ = extractGcodeValue(gcodeLine, 'Z', 0); - float start = extractGcodeValue(gcodeLine, 'S', 1); - float stop = extractGcodeValue(gcodeLine, 'F', 1); - float steps = extractGcodeValue(gcodeLine, 'I', 1); - float stepTime = extractGcodeValue(gcodeLine, 'T', 2000); - float version = extractGcodeValue(gcodeLine, 'V', 1); - - Axis* axis = &rightAxis; - if (left > 0) axis = &leftAxis; - if (useZ > 0) axis = &zAxis; - PIDTestPosition(axis, start, stop, steps, stepTime, version); - return STATUS_OK; - } - - if(gcodeLine.substring(0, 3) == "B16"){ - //Incrementally tests voltages to see what RPMs they produce - float left = extractGcodeValue(gcodeLine, 'L', 0); - float useZ = extractGcodeValue(gcodeLine, 'Z', 0); - float start = extractGcodeValue(gcodeLine, 'S', 1); - float stop = extractGcodeValue(gcodeLine, 'F', 1); - - Axis* axis = &rightAxis; - if (left > 0) axis = &leftAxis; - if (useZ > 0) axis = &zAxis; - voltageTest(axis, start, stop); - return STATUS_OK; - } - - if(gcodeLine.substring(0, 3) == "B15"){ - //The B15 command moves the chains to the length which will put the sled in the center of the sheet - - //Compute chain length for position 0,0 - float chainLengthAtMiddle; - kinematics.inverse(0,0,&chainLengthAtMiddle,&chainLengthAtMiddle); - - //Adjust left chain length - singleAxisMove(&leftAxis, chainLengthAtMiddle, 800); - - //Adjust right chain length - singleAxisMove(&rightAxis, chainLengthAtMiddle, 800); - - //Reload the position - kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition, 0, 0); - - return STATUS_OK; - } - return STATUS_INVALID_STATEMENT; -} - -void executeGcodeLine(const String& gcodeLine){ - /* - - Executes a single line of gcode beginning with the character 'G'. If the G code is - not included on the front of the line, the code from the previous line will be added. - - */ - - //Handle G-Codes - - int gNumber = extractGcodeValue(gcodeLine,'G', -1); - - if (gNumber == -1){ // If the line does not have a G command - gNumber = sys.lastGCommand; // apply the last one - } - - switch(gNumber){ - case 0: // Rapid positioning - case 1: // Linear interpolation - G1(gcodeLine, gNumber); - sys.lastGCommand = gNumber; // remember G number for next time - break; - case 2: // Circular interpolation, clockwise - case 3: // Circular interpolation, counterclockwise - G2(gcodeLine, gNumber); - sys.lastGCommand = gNumber; // remember G number for next time - break; - case 4: - G4(gcodeLine); - break; - case 10: - G10(gcodeLine); - break; - case 20: - setInchesToMillimetersConversion(INCHES); - break; - case 21: - setInchesToMillimetersConversion(MILLIMETERS); - break; - case 40: - break; //the G40 command turns off cutter compensation which is already off so it is safe to ignore - case 38: - G38(gcodeLine); - break; - case 90: - sys.useRelativeUnits = false; - break; - case 91: - sys.useRelativeUnits = true; - break; - default: - Serial.print(F("Command G")); - Serial.print(gNumber); - Serial.println(F(" unsupported and ignored.")); - } - -} - -void executeMcodeLine(const String& gcodeLine){ - /* - - Executes a single line of gcode beginning with the character 'M'. - - */ - - //Handle M-Codes - - int mNumber = extractGcodeValue(gcodeLine,'M', -1); - - switch(mNumber){ - case 0: // Program Pause / Unconditional Halt / Stop - case 1: // Optional Pause / Halt / Sleep - pause(); - break; - case 2: // Program End - case 30: // Program End with return to program top - case 5: // Spindle Off - setSpindlePower(false); // turn off spindle - break; - case 3: // Spindle On - clockwise - case 4: // Spindle On - counterclockwise - // Maslow spindle runs only one direction, but turn spindle on for either code - setSpindlePower(true); // turn on spindle - break; - case 6: // Tool Change - if (sys.nextTool != sys.lastTool) { - setSpindlePower(false); // first, turn off spindle - Serial.print(F("Tool Change: Please insert tool ")); // prompt user to change tool - Serial.println(sys.nextTool); - sys.lastTool = sys.nextTool; - pause(); - } - break; - case 106: - //Turn laser on - laserOn(true); // EBS - break; - case 107: - //Turn laser off - laserOn(false); - break; - default: - Serial.print(F("Command M")); - Serial.print(mNumber); - Serial.println(F(" unsupported and ignored.")); - } - -} - -void executeOtherCodeLine(const String& gcodeLine){ - /* - - Executes a single line of gcode beginning with a character other than 'G', 'B', or 'M'. - - */ - - if (gcodeLine.length() > 1) { - if (gcodeLine[0] == 'T') { - int tNumber = extractGcodeValue(gcodeLine,'T', 0); // get tool number - Serial.print(F("Tool change to tool ")); - Serial.println(tNumber); - sys.nextTool = tNumber; // remember tool number to prompt user when G06 is received - } - else { // try it as a 'G' command without the leading 'G' code - executeGcodeLine(gcodeLine); - } - } - else { - Serial.print(F("Command ")); - Serial.print(gcodeLine); - Serial.println(F(" too short - ignored.")); - } - -} - -int findNextGM(const String& readString, const int& startingPoint){ - int nextGIndex = readString.indexOf('G', startingPoint); - int nextMIndex = readString.indexOf('M', startingPoint); - if (nextMIndex != -1) { // if 'M' was found - if ((nextGIndex == -1) || (nextMIndex < nextGIndex)) { // and 'G' was not found, or if 'M' is before 'G' - nextGIndex = nextMIndex; // then use 'M' - } - } - if (nextGIndex == -1) { // if 'G' was not found (and therefore 'M' was not found) - nextGIndex = readString.length(); // then use the whole string - } - - return nextGIndex; -} - -void sanitizeCommandString(String& cmdString){ - /* - Primarily removes comments and some other non supported characters or functions. - This is taken heavily from the GRBL project at https://github.com/gnea/grbl - */ - - byte line_flags = 0; - size_t pos = 0; - - while (cmdString.length() > pos){ - if (line_flags) { - // Throw away all (except EOL) comment characters and overflow characters. - if (cmdString[pos] == ')') { - // End of '()' comment. Resume line allowed. - cmdString.remove(pos, 1); - if (line_flags & LINE_FLAG_COMMENT_PARENTHESES) { line_flags &= ~(LINE_FLAG_COMMENT_PARENTHESES); } - } - } - else { - if (cmdString[pos] < ' ') { - // Throw away control characters - cmdString.remove(pos, 1); - } - else if (cmdString[pos] == '/') { - // Block delete NOT SUPPORTED. Ignore character. - // NOTE: If supported, would simply need to check the system if block delete is enabled. - cmdString.remove(pos, 1); - } else if (cmdString[pos] == '(') { - // Enable comments flag and ignore all characters until ')' or EOL. - // NOTE: This doesn't follow the NIST definition exactly, but is good enough for now. - // In the future, we could simply remove the items within the comments, but retain the - // comment control characters, so that the g-code parser can error-check it. - cmdString.remove(pos, 1); - line_flags |= LINE_FLAG_COMMENT_PARENTHESES; - } else if (cmdString[pos] == ';') { - // NOTE: ';' comment to EOL is a LinuxCNC definition. Not NIST. - cmdString.remove(pos, 1); - line_flags |= LINE_FLAG_COMMENT_SEMICOLON; - } else if (cmdString[pos] == '%') { - // Program start-end percent sign NOT SUPPORTED. - cmdString.remove(pos, 1); - } else { - pos++; - } - } - } - #if defined (verboseDebug) && verboseDebug > 1 - // print results - Serial.println(F("sCS execution complete")); - Serial.println(cmdString); - #endif -} - -byte interpretCommandString(String& cmdString){ - /* - - Splits a string into lines of gcode which begin with 'G' or 'M', executing each in order - Also executes full lines for 'B' codes, and handles 'T' at beginning of line - - Assumptions: - Leading and trailing white space has already been removed from cmdString - cmdString has been converted to upper case - - */ - - size_t firstG; - size_t secondG; - - if (cmdString.length() > 0) { - if (cmdString[0] == '$') { - // Maslow '$' system command - return(systemExecuteCmdstring(cmdString)); - } - else if (cmdString[0] == 'B'){ //If the command is a B command - #if defined (verboseDebug) && verboseDebug > 0 - Serial.print(F("iCS executing B code line: ")); - #endif - Serial.println(cmdString); - return executeBcodeLine(cmdString); - } - else if (sys.state == STATE_OLD_SETTINGS){ - return STATUS_OLD_SETTINGS; - } - else { - while(cmdString.length() > 0){ //Extract each line of gcode from the string - firstG = findNextGM(cmdString, 0); - secondG = findNextGM(cmdString, firstG + 1); - - if(firstG == cmdString.length()){ //If the line contains no G or M letters - firstG = 0; //send the whole line - } - - if (firstG > 0) { //If there is something before the first 'G' or 'M' - gcodeLine = cmdString.substring(0, firstG); - #if defined (verboseDebug) && verboseDebug > 0 - Serial.print(F("iCS executing other code: ")); - #endif - Serial.println(gcodeLine); - executeOtherCodeLine(gcodeLine); // execute it first - } - - gcodeLine = cmdString.substring(firstG, secondG); - - if (gcodeLine.length() > 0){ - if (gcodeLine[0] == 'M') { - #if defined (verboseDebug) && verboseDebug > 0 - Serial.print(F("iCS executing M code: ")); - #endif - Serial.println(gcodeLine); - executeMcodeLine(gcodeLine); - } - else { - #if defined (verboseDebug) && verboseDebug > 0 - Serial.print(F("iCS executing G code: ")); - #endif - Serial.println(gcodeLine); - executeGcodeLine(gcodeLine); - } - } - - cmdString = cmdString.substring(secondG, cmdString.length()); - - } - return STATUS_OK; - } - return STATUS_INVALID_STATEMENT; - } - return STATUS_OK; -} - -void gcodeExecuteLoop(){ - byte status; - if (incSerialBuffer.numberOfLines() > 0){ - incSerialBuffer.prettyReadLine(readyCommandString); - sanitizeCommandString(readyCommandString); - status = interpretCommandString(readyCommandString); - readyCommandString = ""; - - // Get next line of GCode - if (!sys.stop){reportStatusMessage(status);} - } -} - -void G1(const String& readString, int G0orG1){ - - /*G1() is the function which is called to process the string if it begins with - 'G01' or 'G00'*/ - - float xgoto; - float ygoto; - float zgoto; - - float currentXPos = sys.xPosition; - float currentYPos = sys.yPosition; - - float currentZPos = zAxis.read(); - - xgoto = sys.inchesToMMConversion*extractGcodeValue(readString, 'X', currentXPos/sys.inchesToMMConversion); - ygoto = sys.inchesToMMConversion*extractGcodeValue(readString, 'Y', currentYPos/sys.inchesToMMConversion); - zgoto = sys.inchesToMMConversion*extractGcodeValue(readString, 'Z', currentZPos/sys.inchesToMMConversion); - sys.feedrate = sys.inchesToMMConversion*extractGcodeValue(readString, 'F', sys.feedrate/sys.inchesToMMConversion); - - if (sys.useRelativeUnits){ //if we are using a relative coordinate system - - if(readString.indexOf('X') >= 0){ //if there is an X command - xgoto = currentXPos + xgoto; - } - if(readString.indexOf('Y') >= 0){ //if y has moved - ygoto = currentYPos + ygoto; - } - if(readString.indexOf('Z') >= 0){ //if y has moved - zgoto = currentZPos + zgoto; - } - } - - sys.feedrate = constrain(sys.feedrate, 1, sysSettings.maxFeed); //constrain the maximum feedrate, 35ipm = 900 mmpm - - //if the zaxis is attached - if(!sysSettings.zAxisAttached){ - float threshold = .1; //units of mm - if (abs(currentZPos - zgoto) > threshold){ - Serial.print(F("Message: Please adjust Z-Axis to a depth of ")); - if (zgoto > 0){ - Serial.print(F("+")); - } - Serial.print(zgoto/sys.inchesToMMConversion); - if (sys.inchesToMMConversion == INCHES){ - Serial.println(F(" in")); - } - else{ - Serial.println(F(" mm")); - } - - pause(); //Wait until the z-axis is adjusted - - zAxis.set(zgoto); - - maslowDelay(1000); - } - } - - - if (G0orG1 == 1){ - //if this is a regular move - coordinatedMove(xgoto, ygoto, zgoto, sys.feedrate); //The XY move is performed - } - else{ - //if this is a rapid move - coordinatedMove(xgoto, ygoto, zgoto, sysSettings.maxFeed); //move the same as a regular move, but go fast - } -} - -void G2(const String& readString, int G2orG3){ - /* - - The G2 function handles the processing of the gcode line for both the command G2 and the - command G3 which cut arcs. - - */ - - - float X1 = sys.xPosition; //does this work if units are inches? (It seems to) - float Y1 = sys.yPosition; - float Z1 = zAxis.read(); // I don't know why we treat the zaxis differently - - float X2 = sys.inchesToMMConversion*extractGcodeValue(readString, 'X', X1/sys.inchesToMMConversion); - float Y2 = sys.inchesToMMConversion*extractGcodeValue(readString, 'Y', Y1/sys.inchesToMMConversion); - float Z2 = sys.inchesToMMConversion*extractGcodeValue(readString, 'Z', Z1/sys.inchesToMMConversion); - float I = sys.inchesToMMConversion*extractGcodeValue(readString, 'I', 0.0); - float J = sys.inchesToMMConversion*extractGcodeValue(readString, 'J', 0.0); - sys.feedrate = sys.inchesToMMConversion*extractGcodeValue(readString, 'F', sys.feedrate/sys.inchesToMMConversion); - - float centerX = X1 + I; - float centerY = Y1 + J; - - sys.feedrate = constrain(sys.feedrate, 1, sysSettings.maxFeed); //constrain the maximum feedrate, 35ipm = 900 mmpm - - if (G2orG3 == 2){ - arc(X1, Y1, Z1, X2, Y2, Z2, centerX, centerY, sys.feedrate, CLOCKWISE); - } - else { - arc(X1, Y1, Z1, X2, Y2, Z2, centerX, centerY, sys.feedrate, COUNTERCLOCKWISE); - } -} - -void G4(const String& readString){ - /* - The G4() dwell function handles the G4 gcode which pauses for P milliseconds or S seconds. - Only one of the two is accepted, the other ignored. - Use maslowDelay() to remain responsive to GC during the dwell time. - Because maslowDelay() operates in milliseconds, round to the nearest millisecond. - Negative values are treated as positive (not a time machine). - */ - float dwellMS = abs(extractGcodeValue(readString, 'P', 0)); - float dwellS = abs(extractGcodeValue(readString, 'S', 0)); - - if (dwellMS == 0) { - /* - ignore S parameter unless P is zero - */ - dwellMS = dwellS * 1000; - } - dwellMS = long(dwellMS + .5); - Serial.print(F("dwell time ")); - if (dwellS > 0) { - Serial.print(dwellS); - Serial.println(F(" seconds")); - } else { - Serial.print(dwellMS, 0); - Serial.println(F(" ms.")); - } - maslowDelay(dwellMS); -} - -void G10(const String& readString){ - /*The G10() function handles the G10 gcode which re-zeros one or all of the machine's axes.*/ - float currentZPos = zAxis.read(); - float zgoto = sys.inchesToMMConversion*extractGcodeValue(readString, 'Z', currentZPos/sys.inchesToMMConversion); - - zAxis.set(zgoto); - zAxis.endMove(zgoto); - zAxis.attach(); -} - -void G38(const String& readString) { - //if the zaxis is attached - if (sysSettings.zAxisAttached) { - /* - The G38() function handles the G38 gcode which zeros the machine's z axis. - Currently ignores X and Y options - */ - if (readString.substring(3, 5) == ".2") { - Serial.println(F("probing for z axis zero")); - float zgoto; - - - float currentZPos = zAxis.read(); - int zDirection = sysSettings.zEncoderSteps<0 ? -1 : 1; - - zgoto = zDirection * sys.inchesToMMConversion * extractGcodeValue(readString, 'Z', currentZPos / sys.inchesToMMConversion); - sys.feedrate = sys.inchesToMMConversion * extractGcodeValue(readString, 'F', sys.feedrate / sys.inchesToMMConversion); - sys.feedrate = constrain(sys.feedrate, 1, sysSettings.maxZRPM * abs(zAxis.getPitch())); - - if (sys.useRelativeUnits) { //if we are using a relative coordinate system - if (readString.indexOf('Z') >= 0) { //if z has moved - zgoto = currentZPos + zgoto; - } - } - - Serial.print(F("max depth ")); - Serial.print(zgoto); - Serial.println(F(" mm.")); - Serial.print(F("feedrate ")); - Serial.print(sys.feedrate); - Serial.println(F(" mm per min.")); - - - //set Probe to input with pullup - pinMode(ProbePin, INPUT_PULLUP); - digitalWrite(ProbePin, HIGH); - - if (zgoto != currentZPos / sys.inchesToMMConversion) { - // now move z to the Z destination; - // Currently ignores X and Y options - // we need a version of singleAxisMove that quits if the AUXn input changes (goes LOW) - // which will act the same as the stop found in singleAxisMove (need both?) - // singleAxisMove(&zAxis, zgoto, feedrate); - - /* - Takes a pointer to an axis object and mo ves that axis to endPos at speed MMPerMin - */ - - Axis* axis = &zAxis; - float startingPos = axis->read(); - float endPos = zgoto; - float moveDist = endPos - currentZPos; //total distance to move - - float direction = moveDist / abs(moveDist); //determine the direction of the move - - float stepSizeMM = 0.01; //step size in mm - - //the argument to abs should only be a variable -- splitting calc into 2 lines - long finalNumberOfSteps = moveDist / stepSizeMM; //number of steps taken in move - finalNumberOfSteps = abs(finalNumberOfSteps); - - long numberOfStepsTaken = 0; - float whereAxisShouldBeAtThisStep = startingPos; - - axis->attach(); - // zAxis->attach(); - - while (numberOfStepsTaken < finalNumberOfSteps) { - if (!movementUpdated){ - //find the target point for this step - whereAxisShouldBeAtThisStep += stepSizeMM * direction; - - //write to each axis - axis->write(whereAxisShouldBeAtThisStep); - movementUpdate(); - - // Run realtime commands - execSystemRealtime(); - if (sys.stop){return;} - - //increment the number of steps taken - numberOfStepsTaken++; - } - - //check for Probe touchdown - if (checkForProbeTouch(ProbePin)) { - zAxis.set(0); - zAxis.endMove(0); - zAxis.attach(); - Serial.println(F("z axis zeroed")); - return; - } - } - - /* - If we get here, the probe failed to touch down - - print error - - STOP execution - */ - axis->endMove(endPos); - Serial.println(F("error: probe did not connect\nprogram stopped\nz axis not set\n")); - sys.stop = true; - } // end if zgoto != currentZPos / sys.inchesToMMConversion - - } else { - Serial.print(F("G38")); - Serial.print(readString.substring(3, 5)); - Serial.println(F(" is invalid. Only G38.2 recognized.")); - } - } else { - Serial.println(F("G38.2 gcode only valid with z-axis attached")); - } -} - -void setInchesToMillimetersConversion(float newConversionFactor){ - sys.inchesToMMConversion = newConversionFactor; -} diff --git a/Firmware_1.26b/cnc_ctrl_v1/GCode.h b/Firmware_1.26b/cnc_ctrl_v1/GCode.h deleted file mode 100644 index d2cf12f4..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/GCode.h +++ /dev/null @@ -1,50 +0,0 @@ -/*This file is part of the Maslow Control Software. - -The Maslow Control Software is free software: you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation, either version 3 of the License, or -(at your option) any later version. - -Maslow Control Software is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with the Maslow Control Software. If not, see . - -Copyright 2014-2017 Bar Smith*/ - -#ifndef gcode_h -#define gcode_h - -// Define line flags. Includes comment type tracking and line overflow detection. -#define LINE_FLAG_COMMENT_PARENTHESES bit(0) -#define LINE_FLAG_COMMENT_SEMICOLON bit(1) - -extern String readyCommandString; //next command queued up and ready to send -extern String gcodeLine; //The next individual line of gcode (for example G91 G01 X19 would be run as two lines) - -void initGCode(); -void gcodeExecuteLoop(); -void readSerialCommands(); -String gcodeBufferReadline(); -int findEndOfNumber(const String&, const int&); -float extractGcodeValue(const String&, char, const float&); -byte executeBcodeLine(const String&); -void executeGcodeLine(const String&); -void executeMcodeLine(const String&); -void executeOtherCodeLine(const String&); -int findNextGM(const String&, const int&); -void sanitizeCommandString(String&); -byte interpretCommandString(String&); -void G1(const String&, int); -void G2(const String&, int); -void G4(const String&); -void G10(const String&); -void G38(const String&); -void setInchesToMillimetersConversion(float); -extern int SpindlePowerControlPin; -extern int ProbePin; - -#endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/Kinematics.cpp b/Firmware_1.26b/cnc_ctrl_v1/Kinematics.cpp deleted file mode 100644 index f5415ea3..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Kinematics.cpp +++ /dev/null @@ -1,425 +0,0 @@ -/*This file is part of the Maslow Control Software. - - The Maslow Control Software is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - Maslow Control Software is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with the Maslow Control Software. If not, see . - - Copyright 2014-2017 Bar Smith*/ - -/* -The Kinematics module relates the lengths of the chains to the position of the cutting head -in X-Y space. -*/ - -#include "Maslow.h" - - -Kinematics::Kinematics(){ - recomputeGeometry(); -} - -void Kinematics::init(){ - recomputeGeometry(); - if (sys.state != STATE_OLD_SETTINGS){ - forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition, sys.xPosition, sys.yPosition); - } -} - -void Kinematics::_verifyValidTarget(float* xTarget,float* yTarget){ - //If the target point is beyond one of the edges of the board, the machine stops at the edge - - *xTarget = (*xTarget < -halfWidth) ? -halfWidth : (*xTarget > halfWidth) ? halfWidth : *xTarget; - *yTarget = (*yTarget < -halfHeight) ? -halfHeight : (*yTarget > halfHeight) ? halfHeight : *yTarget; - -} - -void Kinematics::recomputeGeometry(){ - /* - Some variables are computed on class creation for the geometry of the machine to reduce overhead, - calling this function regenerates those values. These are all floats so they take up - ~32bytes of RAM to keep them in memory. - */ - Phi = -0.2; - h = sqrt((sysSettings.sledWidth/2)*(sysSettings.sledWidth/2) + sysSettings.sledHeight * sysSettings.sledHeight); - Theta = atan(2*sysSettings.sledHeight/sysSettings.sledWidth); - Psi1 = Theta - Phi; - Psi2 = Theta + Phi; - - halfWidth = sysSettings.machineWidth / 2.0; - halfHeight = sysSettings.machineHeight / 2.0; - _xCordOfMotor = sysSettings.distBetweenMotors/2; - _yCordOfMotor = halfHeight + sysSettings.motorOffsetY; - -} - -void Kinematics::inverse(float xTarget,float yTarget, float* aChainLength, float* bChainLength){ - /* - - This function works as a switch to call either the quadrilateralInverse kinematic function - or the triangularInverse kinematic function - - */ - - if(sysSettings.kinematicsType == 1){ - quadrilateralInverse(xTarget, yTarget, aChainLength, bChainLength); - } - else{ - triangularInverse(xTarget, yTarget, aChainLength, bChainLength); - } - -} - -void Kinematics::quadrilateralInverse(float xTarget,float yTarget, float* aChainLength, float* bChainLength){ - - //Confirm that the coordinates are on the wood - _verifyValidTarget(&xTarget, &yTarget); - - //coordinate shift to put (0,0) in the center of the plywood from the left sprocket - y = (halfHeight) + sysSettings.motorOffsetY - yTarget; - x = (sysSettings.distBetweenMotors/2.0) + xTarget; - - //Coordinates definition: - // x -->, y | - // v - // (0,0) at center of left sprocket - // upper left corner of plywood (270, 270) - - byte Tries = 0; //initialize - if(x > sysSettings.distBetweenMotors/2.0){ //the right half of the board mirrors the left half so all computations are done using left half coordinates. - x = sysSettings.distBetweenMotors-x; //Chain lengths are swapped at exit if the x,y is on the right half - Mirror = true; - } - else{ - Mirror = false; - } - - TanGamma = y/x; - TanLambda = y/(sysSettings.distBetweenMotors-x); - Y1Plus = R * sqrt(1 + TanGamma * TanGamma); - Y2Plus = R * sqrt(1 + TanLambda * TanLambda); - - - while (Tries <= KINEMATICSMAXINVERSE) { - - _MyTrig(); - //These criteria will be zero when the correct values are reached - //They are negated here as a numerical efficiency expedient - - Crit[0]= - _moment(Y1Plus, Y2Plus, MySinPhi, SinPsi1, CosPsi1, SinPsi2, CosPsi2); - Crit[1] = - _YOffsetEqn(Y1Plus, x - h * CosPsi1, SinPsi1); - Crit[2] = - _YOffsetEqn(Y2Plus, sysSettings.distBetweenMotors - (x + h * CosPsi2), SinPsi2); - - if (abs(Crit[0]) < KINEMATICSMAXERROR) { - if (abs(Crit[1]) < KINEMATICSMAXERROR) { - if (abs(Crit[2]) < KINEMATICSMAXERROR){ - break; - } - } - } - - //estimate the tilt angle that results in zero net _moment about the pen - //and refine the estimate until the error is acceptable or time runs out - - //Estimate the Jacobian components - - Jac[0] = (_moment( Y1Plus, Y2Plus, MySinPhiDelta, SinPsi1D, CosPsi1D, SinPsi2D, CosPsi2D) + Crit[0])/DELTAPHI; - Jac[1] = (_moment( Y1Plus + DELTAY, Y2Plus, MySinPhi, SinPsi1, CosPsi1, SinPsi2, CosPsi2) + Crit[0])/DELTAY; - Jac[2] = (_moment(Y1Plus, Y2Plus + DELTAY, MySinPhi, SinPsi1, CosPsi1, SinPsi2, CosPsi2) + Crit[0])/DELTAY; - Jac[3] = (_YOffsetEqn(Y1Plus, x - h * CosPsi1D, SinPsi1D) + Crit[1])/DELTAPHI; - Jac[4] = (_YOffsetEqn(Y1Plus + DELTAY, x - h * CosPsi1,SinPsi1) + Crit[1])/DELTAY; - Jac[5] = 0.0; - Jac[6] = (_YOffsetEqn(Y2Plus, sysSettings.distBetweenMotors - (x + h * CosPsi2D), SinPsi2D) + Crit[2])/DELTAPHI; - Jac[7] = 0.0; - Jac[8] = (_YOffsetEqn(Y2Plus + DELTAY, sysSettings.distBetweenMotors - (x + h * CosPsi2D), SinPsi2) + Crit[2])/DELTAY; - - - //solve for the next guess - _MatSolv(); // solves the matrix equation Jx=-Criterion - - // update the variables with the new estimate - - Phi = Phi + Solution[0]; - Y1Plus = Y1Plus + Solution[1]; //don't allow the anchor points to be inside a sprocket - Y1Plus = (Y1Plus < R) ? R : Y1Plus; - - Y2Plus = Y2Plus + Solution[2]; //don't allow the anchor points to be inside a sprocke - Y2Plus = (Y2Plus < R) ? R : Y2Plus; - - Psi1 = Theta - Phi; - Psi2 = Theta + Phi; - - Tries++; // increment itteration count - - } - - //Variables are within accuracy limits - // perform output computation - - Offsetx1 = h * CosPsi1; - Offsetx2 = h * CosPsi2; - Offsety1 = h * SinPsi1; - Offsety2 = h * SinPsi2; - TanGamma = (y - Offsety1 + Y1Plus)/(x - Offsetx1); - TanLambda = (y - Offsety2 + Y2Plus)/(sysSettings.distBetweenMotors -(x + Offsetx2)); - Gamma = atan(TanGamma); - Lambda =atan(TanLambda); - - //compute the chain lengths - - if(Mirror){ - Chain2 = sqrt((x - Offsetx1)*(x - Offsetx1) + (y + Y1Plus - Offsety1)*(y + Y1Plus - Offsety1)) - R * TanGamma + R * Gamma; //right chain length - Chain1 = sqrt((sysSettings.distBetweenMotors - (x + Offsetx2))*(sysSettings.distBetweenMotors - (x + Offsetx2))+(y + Y2Plus - Offsety2)*(y + Y2Plus - Offsety2)) - R * TanLambda + R * Lambda; //left chain length - } - else{ - Chain1 = sqrt((x - Offsetx1)*(x - Offsetx1) + (y + Y1Plus - Offsety1)*(y + Y1Plus - Offsety1)) - R * TanGamma + R * Gamma; //left chain length - Chain2 = sqrt((sysSettings.distBetweenMotors - (x + Offsetx2))*(sysSettings.distBetweenMotors - (x + Offsetx2))+(y + Y2Plus - Offsety2)*(y + Y2Plus - Offsety2)) - R * TanLambda + R * Lambda; //right chain length - } - - *aChainLength = Chain1; - *bChainLength = Chain2; - -} - -void Kinematics::triangularInverse(float xTarget,float yTarget, float* aChainLength, float* bChainLength){ - /* - - The inverse kinematics (relating an xy coordinate pair to the required chain lengths to hit that point) - function for a triangular set up where the chains meet at a point, or are arranged so that they simulate - meeting at a point. - - */ - - //Confirm that the coordinates are on the wood - _verifyValidTarget(&xTarget, &yTarget); - - //Set up variables - float Chain1Angle = 0; - float Chain2Angle = 0; - float Chain1AroundSprocket = 0; - float Chain2AroundSprocket = 0; - - //Calculate motor axes length to the bit - float Motor1Distance = sqrt(pow((-1*_xCordOfMotor - xTarget),2)+pow((_yCordOfMotor - yTarget),2)); - float Motor2Distance = sqrt(pow((_xCordOfMotor - xTarget),2)+pow((_yCordOfMotor - yTarget),2)); - - //Calculate the chain angles from horizontal, based on if the chain connects to the sled from the top or bottom of the sprocket - if(sysSettings.chainOverSprocket == 1){ - Chain1Angle = asin((_yCordOfMotor - yTarget)/Motor1Distance) + asin(R/Motor1Distance); - Chain2Angle = asin((_yCordOfMotor - yTarget)/Motor2Distance) + asin(R/Motor2Distance); - - Chain1AroundSprocket = R * Chain1Angle; - Chain2AroundSprocket = R * Chain2Angle; - } - else{ - Chain1Angle = asin((_yCordOfMotor - yTarget)/Motor1Distance) - asin(R/Motor1Distance); - Chain2Angle = asin((_yCordOfMotor - yTarget)/Motor2Distance) - asin(R/Motor2Distance); - - Chain1AroundSprocket = R * (3.14159 - Chain1Angle); - Chain2AroundSprocket = R * (3.14159 - Chain2Angle); - } - - //Calculate the straight chain length from the sprocket to the bit - float Chain1Straight = sqrt(pow(Motor1Distance,2)-pow(R,2)); - float Chain2Straight = sqrt(pow(Motor2Distance,2)-pow(R,2)); - - //Correct the straight chain lengths to account for chain sag - Chain1Straight *= (1 + ((sysSettings.chainSagCorrection / 1000000000000) * pow(cos(Chain1Angle),2) * pow(Chain1Straight,2) * pow((tan(Chain2Angle) * cos(Chain1Angle)) + sin(Chain1Angle),2))); - Chain2Straight *= (1 + ((sysSettings.chainSagCorrection / 1000000000000) * pow(cos(Chain2Angle),2) * pow(Chain2Straight,2) * pow((tan(Chain1Angle) * cos(Chain2Angle)) + sin(Chain2Angle),2))); - - //Calculate total chain lengths accounting for sprocket geometry and chain sag - float Chain1 = Chain1AroundSprocket + Chain1Straight / (1.0f + sysSettings.leftChainTolerance / 100.0f); - float Chain2 = Chain2AroundSprocket + Chain2Straight / (1.0f + sysSettings.rightChainTolerance / 100.0f); - - //Subtract of the virtual length which is added to the chain by the rotation mechanism - Chain1 = Chain1 - sysSettings.rotationDiskRadius; - Chain2 = Chain2 - sysSettings.rotationDiskRadius; - - *aChainLength = Chain1; - *bChainLength = Chain2; -} - -void Kinematics::forward(const float& chainALength, const float& chainBLength, float* xPos, float* yPos, float xGuess, float yGuess){ - - Serial.println(F("[Forward Calculating Position]")); - - - float guessLengthA; - float guessLengthB; - - int guessCount = 0; - - while(1){ - - - //check our guess - inverse(xGuess, yGuess, &guessLengthA, &guessLengthB); - - float aChainError = chainALength - guessLengthA; - float bChainError = chainBLength - guessLengthB; - - - //adjust the guess based on the result - xGuess = xGuess + .1*aChainError - .1*bChainError; - yGuess = yGuess - .1*aChainError - .1*bChainError; - - guessCount++; - - #if defined (KINEMATICSDBG) && KINEMATICSDBG > 0 - Serial.print(F("[PEk:")); - Serial.print(aChainError); - Serial.print(','); - Serial.print(bChainError); - Serial.print(','); - Serial.print('0'); - Serial.println(F("]")); - #endif - - execSystemRealtime(); - // No need for sys.stop check here - - //if we've converged on the point...or it's time to give up, exit the loop - if((abs(aChainError) < .1 && abs(bChainError) < .1) or guessCount > KINEMATICSMAXGUESS or guessLengthA > sysSettings.chainLength or guessLengthB > sysSettings.chainLength){ - if((guessCount > KINEMATICSMAXGUESS) or guessLengthA > sysSettings.chainLength or guessLengthB > sysSettings.chainLength){ - Serial.print(F("Message: Unable to find valid machine position for chain lengths ")); - Serial.print(chainALength); - Serial.print(", "); - Serial.print(chainBLength); - Serial.println(F(" . Please set the chains to a known length (Actions -> Set Chain Lengths)")); - *xPos = 0; - *yPos = 0; - } - else{ - Serial.println("position loaded at:"); - Serial.println(xGuess); - Serial.println(yGuess); - *xPos = xGuess; - *yPos = yGuess; - } - break; - } - } -} - -void Kinematics::_MatSolv(){ - float Sum; - int NN; - int i; - int ii; - int J; - int JJ; - int K; - int KK; - int L; - int M; - int N; - - float fact; - - // gaus elimination, no pivot - - N = 3; - NN = N-1; - for (i=1;i<=NN;i++){ - J = (N+1-i); - JJ = (J-1) * N-1; - L = J-1; - KK = -1; - for (K=0;K. - - Copyright 2014-2017 Bar Smith*/ - - #ifndef Kinematics_h - #define Kinematics_h - - - //Calculation tolerances - #define DELTAPHI 0.001 - #define DELTAY 0.01 - #define KINEMATICSMAXERROR 0.001 - #define KINEMATICSMAXINVERSE 10 - #define KINEMATICSMAXGUESS 200 - - class Kinematics{ - public: - Kinematics(); - void init (); - void inverse (float xTarget,float yTarget, float* aChainLength, float* bChainLength); - void quadrilateralInverse (float xTarget,float yTarget, float* aChainLength, float* bChainLength); - void triangularInverse (float xTarget,float yTarget, float* aChainLength, float* bChainLength); - void recomputeGeometry(); - void forward(const float& chainALength, const float& chainBLength, float* xPos, float* yPos, float xGuess, float yGuess); - //geometry - float h; //distance between sled attach point and bit - float R = 10.1; //sprocket radius - - float halfWidth; //Half the machine width - float halfHeight; //Half the machine height - private: - float _moment(const float& Y1Plus, const float& Y2Plus, const float& MSinPhi, const float& MSinPsi1, const float& MCosPsi1, const float& MSinPsi2, const float& MCosPsi2); - float _YOffsetEqn(const float& YPlus, const float& Denominator, const float& Psi); - void _MatSolv(); - void _MyTrig(); - void _verifyValidTarget(float* xTarget,float* yTarget); - //target router bit coordinates. - float x = 0; - float y = 0; - float _xCordOfMotor; - float _yCordOfMotor; - - //utility variables - boolean Mirror; - - //Criterion Computation Variables - float Phi = -0.2; - float TanGamma; - float TanLambda; - float Y1Plus ; - float Y2Plus; - float Theta; - float Psi1 = Theta - Phi; - float Psi2 = Theta + Phi; - float Jac[9]; - float Solution[3]; - float Crit[3]; - float Offsetx1; - float Offsetx2; - float Offsety1; - float Offsety2; - float SinPsi1; - float CosPsi1; - float SinPsi2; - float CosPsi2; - float SinPsi1D; - float CosPsi1D; - float SinPsi2D; - float CosPsi2D; - float MySinPhi; - float MySinPhiDelta; - - //intermediate output - float Lambda; - float Gamma; - - // Motor axes length to the bit for triangular kinematics - float Motor1Distance; //left motor axis distance to sled - float Motor2Distance; //right motor axis distance to sled - - // output = chain lengths measured from 12 o'clock - float Chain1; //left chain length - float Chain2; //right chain length - }; - - #endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/Maslow.h b/Firmware_1.26b/cnc_ctrl_v1/Maslow.h deleted file mode 100644 index 8380a13e..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Maslow.h +++ /dev/null @@ -1,52 +0,0 @@ -/*This file is part of the Maslow Control Software. - The Maslow Control Software is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - Maslow Control Software is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - You should have received a copy of the GNU General Public License - along with the Maslow Control Software. If not, see . - - Copyright 2014-2017 Bar Smith*/ - -// This is the main maslow include file - -#ifndef maslow_h -#define maslow_h - -// Maslow Firmware Version tracking -#define VERSIONNUMBER 1.26 - -// Define standard libraries used by maslow. -#include -#include -#include -#include - -// Define the maslow system include files. This ensures that dependencies are -// loaded in the proper order. Be careful moving these around. -#include "Config.h" -#include "TimerOne.h" -#include "Motor.h" -#include "PID_v1.h" -#include "utility/direct_pin_read.h" -#include "Encoder.h" -#include "MotorGearboxEncoder.h" -#include "Axis.h" -#include "Kinematics.h" -#include "RingBuffer.h" -#include "GCode.h" -#include "Testing.h" -#include "Motion.h" -#include "Report.h" -#include "Spindle.h" -#include "Probe.h" -#include "Settings.h" -#include "NutsAndBolts.h" -#include "System.h" -#include "SimavrSerial.h" - -#endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/Motion.cpp b/Firmware_1.26b/cnc_ctrl_v1/Motion.cpp deleted file mode 100644 index 358dc222..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Motion.cpp +++ /dev/null @@ -1,376 +0,0 @@ -/*This file is part of the Maslow Control Software. - The Maslow Control Software is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - Maslow Control Software is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - You should have received a copy of the GNU General Public License - along with the Maslow Control Software. If not, see . - - Copyright 2014-2017 Bar Smith*/ - -// This contains all of the Motion commands - -#include "Maslow.h" - -// Flag for when to send movement commands -volatile bool movementUpdated = false; -// Global variables for misloop tracking -#if misloopDebug > 0 - volatile bool inMovementLoop = false; - volatile bool movementFail = false; -#endif - -void initMotion(){ - // Called on startup or after a stop command - leftAxis.stop(); - rightAxis.stop(); - if(sysSettings.zAxisAttached){ - zAxis.stop(); - } -} - - -float calculateFeedrate(const float& stepSizeMM, const float& usPerStep){ - /* - Calculate the time delay between each step for a given feedrate - */ - - #define MINUTEINUS 60000000.0 - - // derivation: ms / step = 1 min in ms / dist in one min - - float tempFeedrate = (stepSizeMM*MINUTEINUS)/usPerStep; - - return tempFeedrate; -} - -float computeStepSize(const float& MMPerMin){ - /* - - Determines the minimum step size which can be taken for the given feed-rate - based on the loop interval frequency. Converts to MM per microsecond first, - then mutiplies by the number of microseconds in each loop interval - - */ - return LOOPINTERVAL*(MMPerMin/(60 * 1000000)); -} - -void movementUpdate(){ - #if misloopDebug > 0 - if (movementFail){ - Serial.println("Movement loop failed to complete before interrupt."); - movementFail = false; - } - #endif - movementUpdated = true; -} - - -// why does this return anything -int coordinatedMove(const float& xEnd, const float& yEnd, const float& zEnd, float MMPerMin){ - - /*The move() function moves the tool in a straight line to the position (xEnd, yEnd) at - the speed moveSpeed. Movements are correlated so that regardless of the distances moved in each - direction, the tool moves to the target in a straight line. This function is used by the G00 - and G01 commands. The units at this point should all be in mm or mm per minute*/ - - float xStartingLocation = sys.xPosition; - float yStartingLocation = sys.yPosition; - float zStartingLocation = zAxis.read(); // I don't know why we treat the zaxis differently - float zMaxFeed = sysSettings.maxZRPM * abs(zAxis.getPitch()); - - //find the total distances to move - float distanceToMoveInMM = sqrt( sq(xEnd - xStartingLocation) + sq(yEnd - yStartingLocation) + sq(zEnd - zStartingLocation)); - float xDistanceToMoveInMM = xEnd - xStartingLocation; - float yDistanceToMoveInMM = yEnd - yStartingLocation; - float zDistanceToMoveInMM = zEnd - zStartingLocation; - - //compute feed details - MMPerMin = constrain(MMPerMin, 1, sysSettings.maxFeed); //constrain the maximum feedrate, 35ipm = 900 mmpm - float stepSizeMM = computeStepSize(MMPerMin); - float finalNumberOfSteps = abs(distanceToMoveInMM/stepSizeMM); - float delayTime = LOOPINTERVAL; - float zFeedrate = calculateFeedrate(fabs(zDistanceToMoveInMM/finalNumberOfSteps), delayTime); - - //throttle back federate if it exceeds zaxis max - if (zFeedrate > zMaxFeed){ - float zStepSizeMM = computeStepSize(zMaxFeed); - finalNumberOfSteps = abs(zDistanceToMoveInMM/zStepSizeMM); - stepSizeMM = (distanceToMoveInMM/finalNumberOfSteps); - MMPerMin = calculateFeedrate(stepSizeMM, delayTime); - } - - // (fraction of distance in x direction)* size of step toward target - float xStepSize = (xDistanceToMoveInMM/finalNumberOfSteps); - float yStepSize = (yDistanceToMoveInMM/finalNumberOfSteps); - float zStepSize = (zDistanceToMoveInMM/finalNumberOfSteps); - - //attach the axes - leftAxis.attach(); - rightAxis.attach(); - if(sysSettings.zAxisAttached){ - zAxis.attach(); - } - - float aChainLength; - float bChainLength; - float zPosition = zStartingLocation; - long numberOfStepsTaken = 0; - - while(numberOfStepsTaken < finalNumberOfSteps){ - - #if misloopDebug > 0 - inMovementLoop = true; - #endif - //if last movment was performed start the next - if (!movementUpdated) { - //find the target point for this step - // This section ~20us - sys.xPosition += xStepSize; - sys.yPosition += yStepSize; - zPosition += zStepSize; - - //find the chain lengths for this step - // This section ~180us - kinematics.inverse(sys.xPosition,sys.yPosition,&aChainLength,&bChainLength); - - //write to each axis - // This section ~180us - leftAxis.write(aChainLength); - rightAxis.write(bChainLength); - if(sysSettings.zAxisAttached){ - zAxis.write(zPosition); - } - - movementUpdate(); - - //increment the number of steps taken - numberOfStepsTaken++; - - // Run realtime commands - execSystemRealtime(); - if (sys.stop){return 1;} - } - } - #if misloopDebug > 0 - inMovementLoop = false; - #endif - - kinematics.inverse(xEnd,yEnd,&aChainLength,&bChainLength); - leftAxis.endMove(aChainLength); - rightAxis.endMove(bChainLength); - if(sysSettings.zAxisAttached){ - zAxis.endMove(zPosition); - } - - sys.xPosition = xEnd; - sys.yPosition = yEnd; - - return 1; - -} - -void singleAxisMove(Axis* axis, const float& endPos, const float& MMPerMin){ - /* - Takes a pointer to an axis object and moves that axis to endPos at speed MMPerMin - */ - - float startingPos = axis->read(); - float moveDist = endPos - startingPos; //total distance to move - - float direction = moveDist/abs(moveDist); //determine the direction of the move - - float stepSizeMM = computeStepSize(MMPerMin); //step size in mm - - //the argument to abs should only be a variable -- splitting calc into 2 lines - long finalNumberOfSteps = abs(moveDist/stepSizeMM); //number of steps taken in move - finalNumberOfSteps = abs(finalNumberOfSteps); - stepSizeMM = stepSizeMM*direction; - - long numberOfStepsTaken = 0; - - //attach the axis we want to move - axis->attach(); - - float whereAxisShouldBeAtThisStep = startingPos; - #if misloopDebug > 0 - inMovementLoop = true; - #endif - while(numberOfStepsTaken < finalNumberOfSteps){ - if (!movementUpdated) { - //find the target point for this step - whereAxisShouldBeAtThisStep += stepSizeMM; - - //write to axis - axis->write(whereAxisShouldBeAtThisStep); - movementUpdate(); - - // Run realtime commands - execSystemRealtime(); - if (sys.stop){return;} - - //increment the number of steps taken - numberOfStepsTaken++; - } - } - #if misloopDebug > 0 - inMovementLoop = false; - #endif - - axis->endMove(endPos); - -} - -// return the sign of the parameter -int sign(double x) { return x<0 ? -1 : 1; } - -// why does this return anything -int arc(const float& X1, const float& Y1, const float& Z1, const float& X2, const float& Y2, const float& Z2, const float& centerX, const float& centerY, const float& MMPerMin, const float& direction){ - /* - - Move the machine through an arc from point (X1, Y1) to point (X2, Y2) along the - arc defined by center (centerX, centerY) at speed MMPerMin - - */ - - //compute geometry - float pi = 3.1415; - float radius = sqrt( sq(centerX - X1) + sq(centerY - Y1) ); - float circumference = 2.0*pi*radius; - - float startingAngle = atan2(Y1 - centerY, X1 - centerX); - float endingAngle = atan2(Y2 - centerY, X2 - centerX); - - // compute chord height of arc - float chordSquared = sqrt(sq(X2 - X1) + sq(Y2 - Y1)); - float tau = sqrt( sq(radius) - (chordSquared/4.0)); - float chordHeight = radius - tau; - - //compute angle between lines - float theta = endingAngle - startingAngle; - if (direction == COUNTERCLOCKWISE){ - if (theta <= 0){ - theta += 2*pi; - } - } - else { - //CLOCKWISE - if (theta >= 0){ - theta -= 2*pi; - } - } - if ((sign(theta) != sign(direction)) || ((abs(chordHeight) < .01) && (abs(theta) < 0.5)) || (radius > 25400)) { - // There is a parameter error in this line of gcode, either in the size of the angle calculated - // or the chord height of the arc between the starting and ending points - // In either case, the gcode cut was essentially a straight line, so - // Replace it with a G1 cut to the endpoint - String gcodeSubstitution = "G1 X"; - gcodeSubstitution = gcodeSubstitution + String(X2 / sys.inchesToMMConversion, 3) + " Y" + String(Y2 / sys.inchesToMMConversion, 3) + " Z" + String(Z2 / sys.inchesToMMConversion, 3) + " "; - Serial.println("Large-radius arc replaced by straight line to improve accuracy: " + gcodeSubstitution); - G1(gcodeSubstitution, 1); - return 1; - } - - float arcLengthMM = fabs(circumference * (theta / (2*pi) )); - float zDistanceToMoveInMM = Z2 - Z1; - - //set up variables for movement - long numberOfStepsTaken = 0; - - float feedMMPerMin = constrain(MMPerMin, 1, sysSettings.maxFeed); - float stepSizeMM = computeStepSize(feedMMPerMin); - - long finalNumberOfSteps = arcLengthMM/stepSizeMM; - float delayTime = LOOPINTERVAL; - - float zFeedRate = calculateFeedrate(fabs(zDistanceToMoveInMM/finalNumberOfSteps), delayTime); - float zMaxFeed = sysSettings.maxZRPM * abs(zAxis.getPitch()); - // float zStepSizeMM = computeStepSize(zMaxFeed); - float zStepSizeMM = zDistanceToMoveInMM/finalNumberOfSteps; - - if (zFeedRate > zMaxFeed){ - zStepSizeMM = computeStepSize(zMaxFeed); - finalNumberOfSteps = fabs(zDistanceToMoveInMM/zStepSizeMM); - stepSizeMM = arcLengthMM/finalNumberOfSteps; - feedMMPerMin = calculateFeedrate(stepSizeMM, delayTime); - } - - zStepSizeMM = zDistanceToMoveInMM/finalNumberOfSteps; - - //Compute the starting position - float angleNow = startingAngle; - float degreeComplete = 0.0; - - float aChainLength; - float bChainLength; - float zPosition = Z1 + zStepSizeMM; - - //attach the axes - leftAxis.attach(); - rightAxis.attach(); - if (sysSettings.zAxisAttached) { - zAxis.attach(); - } - - while(numberOfStepsTaken < abs(finalNumberOfSteps)){ - #if misloopDebug > 0 - inMovementLoop = true; - #endif - - //if last movement was performed start the next one - if (!movementUpdated){ - - degreeComplete = float(numberOfStepsTaken)/float(finalNumberOfSteps); - - angleNow = startingAngle + theta*degreeComplete; - - sys.xPosition = radius * cos(angleNow) + centerX; - sys.yPosition = radius * sin(angleNow) + centerY; - - kinematics.inverse(sys.xPosition,sys.yPosition,&aChainLength,&bChainLength); - - leftAxis.write(aChainLength); - rightAxis.write(bChainLength); - if(sysSettings.zAxisAttached){ - zAxis.write(zPosition); - } - movementUpdate(); - - // Run realtime commands - execSystemRealtime(); - if (sys.stop){return 1;} - - numberOfStepsTaken++; - zPosition += zStepSizeMM; - } - } - #if misloopDebug > 0 - inMovementLoop = false; - #endif - - kinematics.inverse(X2,Y2,&aChainLength,&bChainLength); - leftAxis.endMove(aChainLength); - rightAxis.endMove(bChainLength); - - sys.xPosition = X2; - sys.yPosition = Y2; - - return 1; -} - -void motionDetachIfIdle(){ - /* - - This function is called every time the main loop runs. When the machine is executing a move it is not called, but when the machine is - not executing a line it is called regularly and causes the motors to hold their positions. - - */ - - leftAxis.detachIfIdle(); - rightAxis.detachIfIdle(); - zAxis.detachIfIdle(); -} diff --git a/Firmware_1.26b/cnc_ctrl_v1/Motion.h b/Firmware_1.26b/cnc_ctrl_v1/Motion.h deleted file mode 100644 index b2aa62a1..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Motion.h +++ /dev/null @@ -1,36 +0,0 @@ -/*This file is part of the Maslow Control Software. - The Maslow Control Software is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - Maslow Control Software is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - You should have received a copy of the GNU General Public License - along with the Maslow Control Software. If not, see . - - Copyright 2014-2017 Bar Smith*/ - -// This contains all of the Motion commands - -#ifndef motion_h -#define motion_h - -// These are used for movement tracking and need to be available to the ISR -extern volatile bool movementUpdated; -#if misloopDebug > 0 - extern volatile bool inMovementLoop; - extern volatile bool movementFail; -#endif - -void initMotion(); -int coordinatedMove(const float&, const float&, const float&, float); -void singleAxisMove(Axis*, const float&, const float&); -int arc(const float&, const float&, const float&, const float&, const float&, const float&, const float&, const float&, const float&, const float&); -float calculateFeedrate(const float&, const float&); -float computeStepSize(const float&); -void movementUpdate(); -void motionDetachIfIdle(); - -#endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/Motor.cpp b/Firmware_1.26b/cnc_ctrl_v1/Motor.cpp deleted file mode 100644 index 0833a66f..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Motor.cpp +++ /dev/null @@ -1,227 +0,0 @@ -/*This file is part of the Maslow Control Software. - - The Maslow Control Software is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - Maslow Control Software is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with the Maslow Control Software. If not, see . - - Copyright 2014-2017 Bar Smith*/ - -/* -The Motor module imitates the behavior of the Arduino servo module. It allows a gear motor (or any electric motor) -to be a drop in replacement for a continuous rotation servo. - -*/ - -#include "Maslow.h" - -Motor::Motor(){ - - _attachedState = 0; - - -} - -int Motor::setupMotor(const int& pwmPin, const int& pin1, const int& pin2){ - - //store pin numbers as private variables - _pwmPin = pwmPin; - _pin1 = pin1; - _pin2 = pin2; - _attachedState = 0; - - if (TLE5206 == true ) { - // EBS v1.4 - pinMode(_pwmPin, INPUT); - pinMode(_pin1, OUTPUT); - pinMode(_pin2, OUTPUT); - - //stop the motor - digitalWrite(_pin1, LOW); - digitalWrite(_pin2, LOW) ; - } - else if (TB6643 == true ) { - // EBS V1.5 - pinMode(_pwmPin, INPUT); - pinMode(_pin1, OUTPUT); - pinMode(_pin2, OUTPUT); - - //stop the motor - digitalWrite(_pin1, LOW); - digitalWrite(_pin2, LOW); - } - else { - // V1.2 - //set pinmodes - pinMode(_pwmPin, OUTPUT); - pinMode(_pin1, OUTPUT); - pinMode(_pin2, OUTPUT); - - //stop the motor - digitalWrite(_pin1, HIGH); - digitalWrite(_pin2, LOW) ; - digitalWrite(_pwmPin, LOW); - } - return 1; -} - -void Motor::attach(){ - _attachedState = 1; -} - -void Motor::detach(){ - _attachedState = 0; - - if (TLE5206 == true) { - //stop the motor - digitalWrite(_pin1, LOW); - digitalWrite(_pin2, LOW) ; - } - else if (TB6643 == true){ - //stop the motor - digitalWrite(_pin1, LOW); - digitalWrite(_pin2, LOW) ; - } - else { - //stop the motor - digitalWrite(_pin1, HIGH); - digitalWrite(_pin2, LOW) ; - digitalWrite(_pwmPin, LOW); - } -} - - -int Motor::lastSpeed(){ - /* - Returns the last speed(voltage) value sent to the pwm - */ - return _lastSpeed; -} - -void Motor::additiveWrite(int speed){ - /* - Increases/decreases the motor speed by the passed speed amount - */ - write(_lastSpeed + speed); -} - -void Motor::write(int speed, bool force){ - /* - Sets motor speed from input. Speed = 0 is stopped, -255 is full reverse, 255 is full ahead. If force is true the motor attached state will be ignored - */ - if (_attachedState == 1 or force){ - speed = constrain(speed, -255, 255); - _lastSpeed = speed; //saves speed for use in additive write - bool forward = (speed > 0); - speed = abs(speed); //remove sign from input because direction is set by control pins on H-bridge - - bool usePin1 = ((_pin1 != 4) && (_pin1 != 13) && (_pin1 != 11) && (_pin1 != 12)); // avoid PWM using timer0 or timer1 - bool usePin2 = ((_pin2 != 4) && (_pin2 != 13) && (_pin2 != 11) && (_pin2 != 12)); // avoid PWM using timer0 or timer1 - bool usepwmPin = ((TLE5206 == false) && (_pwmPin != 4) && (_pwmPin != 13) && (_pwmPin != 11) && (_pwmPin != 12)); // avoid PWM using timer0 or timer1 - if (TLE5206) { - if (forward) { - if (speed > 0) { - if (usePin2) { - digitalWrite(_pin1 , HIGH ); - analogWrite(_pin2 , 255 - speed); // invert drive signals - don't alter speed - } - else { - analogWrite(_pin1 , speed); - digitalWrite(_pin2 , LOW ); - } - } - else { // speed = 0 so put on the brakes - digitalWrite(_pin1 , HIGH ); - digitalWrite(_pin2 , HIGH ); - } - } - else { // reverse - if (usePin1) { - analogWrite(_pin1 , 255 - speed); // invert drive signals - don't alter speed - digitalWrite(_pin2 , HIGH ); - } else { - analogWrite(_pin2 , speed); - digitalWrite(_pin1 , LOW ); - } - } - } - else if (TB6643) { //EBS 1.5 - if (forward) { - if (speed > 0) { - analogWrite(_pin1 , speed); - digitalWrite(_pin2 , LOW); - } else { // speed = 0 so put on the brakes - digitalWrite(_pin1 , HIGH); - digitalWrite(_pin2 , HIGH); - } - } else { // reverse - digitalWrite(_pin1 , LOW); - analogWrite(_pin2 , speed); - } - } - else { // V1.2 - if (forward){ - if (usepwmPin){ - digitalWrite(_pin1 , HIGH ); - digitalWrite(_pin2 , LOW ); - analogWrite(_pwmPin, speed); - } - else if (usePin2) { - digitalWrite(_pin1 , HIGH ); - analogWrite(_pin2 , 255 - speed); // invert drive signals - don't alter speed - digitalWrite(_pwmPin, HIGH); - } - else{ - analogWrite(_pin1 , speed); - digitalWrite(_pin2 , LOW ); - digitalWrite(_pwmPin, HIGH); - } - } - else { // reverse or zero speed - if (usepwmPin){ - digitalWrite(_pin2 , HIGH); - digitalWrite(_pin1 , LOW ); - analogWrite(_pwmPin, speed); - } - else if (usePin1) { - analogWrite(_pin1 , 255 - speed); // invert drive signals - don't alter speed - digitalWrite(_pin2 , HIGH ); - digitalWrite(_pwmPin, HIGH); - } - else { - analogWrite(_pin2 , speed); - digitalWrite(_pin1 , LOW ); - digitalWrite(_pwmPin, HIGH); - } - } - } - - } -} - - - - - - - - -void Motor::directWrite(int voltage){ - /* - Write directly to the motor, ignoring if the axis is attached or any applied calibration. - */ - write(voltage, true); -} - -int Motor::attached(){ - - return _attachedState; -} diff --git a/Firmware_1.26b/cnc_ctrl_v1/Motor.h b/Firmware_1.26b/cnc_ctrl_v1/Motor.h deleted file mode 100644 index c393ec89..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Motor.h +++ /dev/null @@ -1,54 +0,0 @@ - /*This file is part of the Makesmith Control Software. - - The Makesmith Control Software is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - Makesmith Control Software is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with the Makesmith Control Software. If not, see . - - Copyright 2014-2017 Bar Smith*/ - - #ifndef Motor_h - #define Motor_h - - struct LinSegment{ - float slope = 1; - float intercept = 0; - //The bounds are strict, so if the bounds are 0,1 .9 would work - //but 1 and 0 will not - int positiveBound = 0; - int negativeBound = 0; - }; - - - - class Motor{ - public: - Motor(); - void attach(); - int setupMotor(const int& pwmPin, const int& pin1, const int& pin2); - void detach(); - void write(int speed, bool force = false); - int lastSpeed(); - void additiveWrite(int speed); - int attached(); - void directWrite(int voltage); - private: - int _pwmPin; - int _pin1; - int _pin2; - bool _attachedState = false; - LinSegment _linSegments[4]; - int _lastSpeed = 0; - - }; - extern bool TLE5206; - extern bool TB6643; - #endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/MotorGearboxEncoder.cpp b/Firmware_1.26b/cnc_ctrl_v1/MotorGearboxEncoder.cpp deleted file mode 100644 index d5befc9d..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/MotorGearboxEncoder.cpp +++ /dev/null @@ -1,205 +0,0 @@ -/*This file is part of the Maslow Control Software. - - The Maslow Control Software is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - Maslow Control Software is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with the Maslow Control Software. If not, see . - - Copyright 2014-2017 Bar Smith*/ - -/* -The Motor module imitates the behavior of the Arduino servo module. It allows a gear motor (or any electric motor) -to be a drop in replacement for a continuous rotation servo. - -*/ - -#include "Maslow.h" - -void MotorGearboxEncoder::setup(const int& pwmPin, const int& directionPin1, const int& directionPin2, const int& encoderPin1, const int& encoderPin2, const unsigned long& loopInterval) -{ - //initialize encoder - encoder.setup(encoderPin1,encoderPin2); - // I don't like this, but I don't know how else to initialize a pointer to a value - float zero = 0.0; - float one = 1.0; - _Kp = _Ki = _Kd = &zero; - - //initialize motor - motor.setupMotor(pwmPin, directionPin1, directionPin2); - motor.write(0); - - //initialize the PID - _PIDController.setup(&_currentSpeed, &_pidOutput, &_targetSpeed, _Kp, _Ki, _Kd, &one, DIRECT); - initializePID(loopInterval); - - -} - -void MotorGearboxEncoder::write(const float& speed){ - /* - Command the motor to turn at the given speed. Should be RPM is PWM right now. - */ - - _targetSpeed = speed; - -} - -void MotorGearboxEncoder::initializePID(const unsigned long& loopInterval){ - //setup positive PID controller - _PIDController.SetMode(AUTOMATIC); - _PIDController.SetOutputLimits(-255, 255); - _PIDController.SetSampleTime(loopInterval / 1000); -} - -void MotorGearboxEncoder::computePID(){ - /* - Recompute the speed control PID loop and command the motor to move. - */ - _currentSpeed = computeSpeed(); - - _PIDController.Compute(); - - motor.additiveWrite(_pidOutput); -} - -void MotorGearboxEncoder::setPIDValues(float* KpV, float* KiV, float* KdV, float* propWeightV){ - /* - - Set PID tuning values - - */ - - _Kp = KpV; - _Ki = KiV; - _Kd = KdV; - - _PIDController.SetTunings(_Kp, _Ki, _Kd, propWeightV); -} - -String MotorGearboxEncoder::getPIDString(){ - /* - - Get PID tuning values - - */ - String PIDString = "Kp="; - return PIDString + *_Kp + ",Ki=" + *_Ki + ",Kd=" + *_Kd; -} - -String MotorGearboxEncoder::pidState(){ - /* - - Get current value of PID variables, setpoint, input, output - - */ - return _PIDController.pidState(); -} - -void MotorGearboxEncoder::setPIDAggressiveness(float aggressiveness){ - /* - - The setPIDAggressiveness() function sets the aggressiveness of the PID controller to - compensate for a change in the load on the motor. - - */ - - float adjustedKp = aggressiveness * *_Kp; - float one = 1.0; - - _PIDController.SetTunings(&adjustedKp, _Ki, _Kd, &one); - -} - -void MotorGearboxEncoder::setEncoderResolution(float resolution){ - /* - - Change the encoder resolution - - */ - - _encoderStepsToRPMScaleFactor = 60000000.0/resolution; //6*10^7 us per minute divided by 8113.73 steps per revolution - -} - -float MotorGearboxEncoder::computeSpeed(){ - /* - - Returns the motors speed in RPM since the last time this function was called - should only be called by the PID process otherwise we are calculating the - distance moved over a varying amount of time. - - */ - - float currentPosition = encoder.read(); - float currentMicros = micros(); - - float distMoved = currentPosition - _lastPosition; - if (distMoved > 3 || distMoved < -3){ - - // This dampens some of the effects of quantization without having - // a big effect on other changes - float saveDistMoved = distMoved; - if (distMoved - _lastDistMoved <= -1){ distMoved += .5;} - else if (distMoved - _lastDistMoved >= 1){distMoved -= .5;} - _lastDistMoved = saveDistMoved; - - unsigned long timeElapsed = currentMicros - _lastTimeStamp; - //Compute the speed in RPM - _RPM = (_encoderStepsToRPMScaleFactor*distMoved)/float(timeElapsed); - - } - else { - float elapsedTime = encoder.elapsedTime(); - float lastTime = micros() - encoder.lastStepTime(); // no direction associated with this - if (lastTime > abs(elapsedTime)) { - // This allows the RPM to approach 0 - if (elapsedTime < 0){ - elapsedTime = -lastTime; - } - else { - elapsedTime = lastTime; - } - }; - - _RPM = 0 ; - if (elapsedTime != 0){ - _RPM = _encoderStepsToRPMScaleFactor / elapsedTime; - } - } - _RPM = _RPM * -1.0; - - //Store values for next time - _lastTimeStamp = currentMicros; - _lastPosition = currentPosition; - - return _RPM; -} - -float MotorGearboxEncoder::cachedSpeed(){ - /* - Returns the last result of computeSpeed - */ - return _RPM; -} - -void MotorGearboxEncoder::setName(char *newName){ - /* - Set the name for the object - */ - _motorName = newName; -} - -char MotorGearboxEncoder::name(){ - /* - Get the name for the object - */ - return *_motorName; -} diff --git a/Firmware_1.26b/cnc_ctrl_v1/MotorGearboxEncoder.h b/Firmware_1.26b/cnc_ctrl_v1/MotorGearboxEncoder.h deleted file mode 100644 index 6a680351..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/MotorGearboxEncoder.h +++ /dev/null @@ -1,56 +0,0 @@ - /*This file is part of the Makesmith Control Software. - - The Makesmith Control Software is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - Makesmith Control Software is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with the Makesmith Control Software. If not, see . - - Copyright 2014-2017 Bar Smith*/ - - #ifndef MotorGearboxEncoder_h - #define MotorGearboxEncoder_h - - class MotorGearboxEncoder{ - public: - void setup(const int& pwmPin, const int& directionPin1, const int& directionPin2, const int& encoderPin1, const int& encoderPin2, const unsigned long& loopInterval); - Encoder encoder; - Motor motor; - float cachedSpeed(); - void write(const float& speed); - void computePID(); - void setName(char *newName); - char name(); - void initializePID(const unsigned long& loopInterval); - void setPIDAggressiveness(float aggressiveness); - void setPIDValues(float* KpV, float* KiV, float* KdV, float* propWeight); - void setEncoderResolution(float resolution); - float computeSpeed(); - String getPIDString(); - String pidState(); - private: - double _targetSpeed; - double _currentSpeed; - volatile double _lastPosition; - volatile double _lastTimeStamp; - float _lastDistMoved; - float _RPM; - char *_motorName; - double _pidOutput; - PID _PIDController; - float *_Kp, *_Ki, *_Kd; - // This could be converted to a pointer to save 4 bytes, but the - // calculation would have to be done at a much higher level and - // passed through each axis for it to have a single pointer to - // both main motors - float _encoderStepsToRPMScaleFactor = 7394.87; //6*10^7 us per minute divided by 8113.73 steps per revolution - }; - - #endif \ No newline at end of file diff --git a/Firmware_1.26b/cnc_ctrl_v1/NutsAndBolts.cpp b/Firmware_1.26b/cnc_ctrl_v1/NutsAndBolts.cpp deleted file mode 100644 index f3711689..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/NutsAndBolts.cpp +++ /dev/null @@ -1,67 +0,0 @@ -/*This file is part of the Maslow Control Software. - -The Maslow Control Software is free software: you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation, either version 3 of the License, or -(at your option) any later version. - -Maslow Control Software is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with the Maslow Control Software. If not, see . - -Copyright 2014-2017 Bar Smith*/ - -// This file contains helper functions that are used throughout - -#include "Maslow.h" - -float readFloat(const String& str, byte& index, float& retVal){ - /* - Takes a string and a starting character index and returns a float if it can - be parsed from the string, it will skip leading spaces. Does not support - scientific notation as this is officially not supported by GCode. - Code was adopted from arduino Stream::parseFloat and some from Grbl's - read_float. It is a custom function because all arduino and c++ functions - appear to handle scientific notation or hexadecimal notation, or some other - type of numerical representation that we don't want supported. - */ - bool isNegative = false; - bool isFraction = false; - long value = 0; - float fraction = 1.0; - byte ndigit = 0; - while (str[index] == ' ' && index < str.length()){ - index++; - } - do{ - if (index < str.length()){ - if(str[index] == '-') - isNegative = true; - else if (str[index] == '.') - isFraction = true; - else if(str[index] >= '0' && str[index] <= '9') {// is a digit? - ndigit++; - value = value * 10 + str[index] - '0'; - if(isFraction) - fraction *= 0.1; - } - index++; - } - } - while(((str[index] >= '0' && str[index] <= '9') || (str[index] == '.' && !isFraction)) && index < str.length()); - - if (!ndigit) { return false; }; - - if(isNegative) - value = -value; - if(isFraction) - retVal = value * fraction; - else - retVal = value; - - return true; -} \ No newline at end of file diff --git a/Firmware_1.26b/cnc_ctrl_v1/NutsAndBolts.h b/Firmware_1.26b/cnc_ctrl_v1/NutsAndBolts.h deleted file mode 100644 index 4f1936f6..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/NutsAndBolts.h +++ /dev/null @@ -1,31 +0,0 @@ -/*This file is part of the Maslow Control Software. - -The Maslow Control Software is free software: you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation, either version 3 of the License, or -(at your option) any later version. - -Maslow Control Software is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with the Maslow Control Software. If not, see . - -Copyright 2014-2017 Bar Smith*/ - -// This file contains helper functions that are used throughout - -#ifndef nutsandbolts_h -#define nutsandbolts_h - -// These are nifty functions from Grbl -#define bit_true(x,mask) (x) |= (mask) -#define bit_false(x,mask) (x) &= ~(mask) -#define bit_istrue(x,mask) ((x & mask) != 0) -#define bit_isfalse(x,mask) ((x & mask) == 0) - -float readFloat(const String&, byte&, float&); - -#endif \ No newline at end of file diff --git a/Firmware_1.26b/cnc_ctrl_v1/PID_v1.cpp b/Firmware_1.26b/cnc_ctrl_v1/PID_v1.cpp deleted file mode 100644 index 8401109c..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/PID_v1.cpp +++ /dev/null @@ -1,236 +0,0 @@ -/********************************************************************************************** - * Arduino PID Library - Version 1.2.1 - * by Brett Beauregard brettbeauregard.com - * - * This Library is licensed under the MIT License - **********************************************************************************************/ - -#if ARDUINO >= 100 - #include "Arduino.h" -#else - #include "WProgram.h" -#endif - -#include "Maslow.h" - -/*Constructor (...)********************************************************* - * The parameters specified here are those for for which we can't set up - * reliable defaults, so we need to have the user set them. - ***************************************************************************/ -PID::PID() -{ - inAuto = false; -} - -void PID::setup(volatile double* Input, volatile double* Output, volatile double* Setpoint, - float* Kp, float* Ki, float* Kd, float* POn, const int& ControllerDirection) -{ - - myOutput = Output; - myInput = Input; - mySetpoint = Setpoint; - inAuto = false; - - PID::SetOutputLimits(0, 255); //default output limit corresponds to - //the arduino pwm limits - - SampleTime = 100; //default Controller Sample Time is 0.1 seconds - - PID::SetControllerDirection(ControllerDirection); - PID::SetTunings(Kp, Ki, Kd, POn); - - lastTime = millis()-SampleTime; -} - -/* Compute() ********************************************************************** - * This, as they say, is where the magic happens. this function should be called - * every time "void loop()" executes. the function will decide for itself whether a new - * pid Output needs to be computed. returns true when the output is computed, - * false when nothing has been done. - **********************************************************************************/ -bool PID::Compute() -{ - if(!inAuto) return false; - //unsigned long now = millis(); - //unsigned long timeChange = (now - lastTime); - //if(timeChange>=SampleTime) - //{ <--- This if statement has been removed to reduce timing jitter on the interrupt. - //because we are calling the function from within an interrupt timer it will be called - //with a consistent sample period - - /*Compute all the working error variables*/ - double input = *myInput; - double error = *mySetpoint - input; - double dInput = (input - lastInput); - outputSum+= (ki * error); - - /*Add Proportional on Measurement, if P_ON_M is specified*/ - if(pOnM) outputSum-= pOnMKp * dInput; - - if(outputSum > outMax) outputSum= outMax; - else if(outputSum < outMin) outputSum= outMin; - - /*Add Proportional on Error, if P_ON_E is specified*/ - double output; - if(pOnE) output = pOnEKp * error; - else output = 0; - - /*Compute Rest of PID Output*/ - output += outputSum - kd * dInput; - - if(output > outMax) output = outMax; - else if(output < outMin) output = outMin; - *myOutput = output; - - /*Remember some variables for next time*/ - lastInput = input; - //lastTime = now; - return true; - //} - //else return false; -} - - -/* SetTunings(...)************************************************************* - * This function allows the controller's dynamic performance to be adjusted. - * it's called automatically from the constructor, but tunings can also - * be adjusted on the fly during normal operation - ******************************************************************************/ -void PID::SetTunings(float* Kp, float* Ki, float* Kd, float* pOn) -{ - if (*Kp<0 || *Ki<0 || *Kd<0 || *pOn<0 || *pOn>1) return; - - pOnE = *pOn>0; //some p on error is desired; - pOnM = *pOn<1; //some p on measurement is desired; - - dispKp = Kp; dispKi = Ki; dispKd = Kd; - - double SampleTimeInSec = ((double)SampleTime)/1000; - kp = *Kp; - ki = *Ki * SampleTimeInSec; - kd = *Kd / SampleTimeInSec; - - if(controllerDirection ==REVERSE) - { - kp = (0 - kp); - ki = (0 - ki); - kd = (0 - kd); - } - pOnEKp = *pOn * kp; - pOnMKp = (1 - *pOn) * kp; -} - -/* SetSampleTime(...) ********************************************************* - * sets the period, in Milliseconds, at which the calculation is performed - ******************************************************************************/ -void PID::SetSampleTime(const int& NewSampleTime) -{ - if (NewSampleTime > 0) - { - double ratio = (double)NewSampleTime - / (double)SampleTime; - ki *= ratio; - kd /= ratio; - SampleTime = (unsigned long)NewSampleTime; - } -} - -/* SetOutputLimits(...)**************************************************** - * This function will be used far more often than SetInputLimits. while - * the input to the controller will generally be in the 0-1023 range (which is - * the default already,) the output will be a little different. maybe they'll - * be doing a time window and will need 0-8000 or something. or maybe they'll - * want to clamp it from 0-125. who knows. at any rate, that can all be done - * here. - **************************************************************************/ -void PID::SetOutputLimits(const double& Min, const double& Max) -{ - if(Min >= Max) return; - outMin = Min; - outMax = Max; - - if(inAuto) - { - - //clamp myOutput and ITerm - *myOutput = - (*myOutput > outMax) ? outMax : (*myOutput < outMin) ? outMin : *myOutput; - - if(outputSum > outMax) outputSum= outMax; - else if(outputSum < outMin) outputSum= outMin; - - } -} - -/* SetMode(...)**************************************************************** - * Allows the controller Mode to be set to manual (0) or Automatic (non-zero) - * when the transition from manual to auto occurs, the controller is - * automatically initialized - ******************************************************************************/ -void PID::SetMode(const int& Mode) -{ - bool newAuto = (Mode == AUTOMATIC); - if(newAuto && !inAuto) - { /*we just went from manual to auto*/ - PID::Initialize(); - } - inAuto = newAuto; -} - -/* Initialize()**************************************************************** - * does all the things that need to happen to ensure a bumpless transfer - * from manual to automatic mode. - ******************************************************************************/ -void PID::Initialize() -{ - outputSum = *myOutput; - lastInput = *myInput; - if(outputSum > outMax) outputSum = outMax; - else if(outputSum < outMin) outputSum = outMin; -} - -/* SetControllerDirection(...)************************************************* - * The PID will either be connected to a DIRECT acting process (+Output leads - * to +Input) or a REVERSE acting process(+Output leads to -Input.) we need to - * know which one, because otherwise we may increase the output when we should - * be decreasing. This is called from the constructor. - ******************************************************************************/ -void PID::SetControllerDirection(const int& Direction) -{ - if(inAuto && Direction !=controllerDirection) - { - kp = (0 - kp); - ki = (0 - ki); - kd = (0 - kd); - } - controllerDirection = Direction; -} - -/* Status Funcions************************************************************* - * Just because you set the Kp=-1 doesn't mean it actually happened. these - * functions query the internal state of the PID. they're here for display - * purposes. this are the functions the PID Front-end uses for example - ******************************************************************************/ -double PID::GetKp(){ return *dispKp;} -double PID::GetKi(){ return *dispKi;} -double PID::GetKd(){ return *dispKd;} -int PID::GetMode(){ return inAuto ? AUTOMATIC : MANUAL;} -int PID::GetDirection(){ return controllerDirection;} -double PID::GetIterm(){ return outputSum; } -String PID::pidState() { - /* - Returns a comma seperated string of the PID setpoint, input, & output - useful for debugging - */ - double input = *myInput; - double setpoint = *mySetpoint; - double output = *myOutput; - String ret = ""; - ret.concat((double)setpoint); - ret.concat(","); - ret.concat((double)input); - ret.concat(","); - ret.concat((double)output); - return ret; -} - diff --git a/Firmware_1.26b/cnc_ctrl_v1/PID_v1.h b/Firmware_1.26b/cnc_ctrl_v1/PID_v1.h deleted file mode 100644 index 803076db..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/PID_v1.h +++ /dev/null @@ -1,98 +0,0 @@ -#ifndef PID_v1_h -#define PID_v1_h -#define LIBRARY_VERSION 1.2.1 - -class PID -{ - - - public: - - //Constants used in some of the functions below - #define AUTOMATIC 1 - #define MANUAL 0 - #define DIRECT 0 - #define REVERSE 1 - #define P_ON_M 0.0 - #define P_ON_E 1.0 - bool pOnE = true, pOnM = false; - double pOnEKp, pOnMKp; - - //commonly used functions ************************************************************************** - - PID(); - - void setup(volatile double*, volatile double*, volatile double*, // * constructor. links the PID to the Input, Output, and - float*, float*, float*, float*, const int&);// Setpoint. Initial tuning parameters are also set here. - // (overload for specifying proportional mode) - - PID(double*, double*, double*, // * constructor. links the PID to the Input, Output, and - double, double, double, int); // Setpoint. Initial tuning parameters are also set here - - void SetMode(const int& Mode); // * sets PID to either Manual (0) or Auto (non-0) - - bool Compute(); // * performs the PID calculation. it should be - // called every time loop() cycles. ON/OFF and - // calculation frequency can be set using SetMode - // SetSampleTime respectively - - void SetOutputLimits(const double&, const double&); //clamps the output to a specific range. 0-255 by default, but - //it's likely the user will want to change this depending on - //the application - - - - //available but not commonly used functions ******************************************************** - void SetTunings(float*, float*, // * While most users will set the tunings once in the - float*); // constructor, this function gives the user the option - // of changing tunings during runtime for Adaptive control - void SetTunings(float*, float*, // * overload for specifying proportional mode - float*, float*); - - void SetControllerDirection(const int&); // * Sets the Direction, or "Action" of the controller. DIRECT - // means the output will increase when error is positive. REVERSE - // means the opposite. it's very unlikely that this will be needed - // once it is set in the constructor. - void SetSampleTime(const int&); // * sets the frequency, in Milliseconds, with which - // the PID calculation is performed. default is 100 - - - //Display functions **************************************************************** - double GetKp(); // These functions query the pid for interal values. - double GetKi(); // they were created mainly for the pid front-end, - double GetKd(); // where it's important to know what is actually - int GetMode(); // inside the PID. - int GetDirection(); // - double GetIterm(); - String pidState(); - - private: - void Initialize(); - - float *dispKp; // * we'll hold on to the tuning parameters in user-entered - float *dispKi; // format for display purposes - float *dispKd; // - -// While shared by both main motors, these are not pointers because they are -// calculated using sample time in this file. - double kp; // * (P)roportional Tuning Parameter - double ki; // * (I)ntegral Tuning Parameter - double kd; // * (D)erivative Tuning Parameter - - int controllerDirection; - int pOn; - - volatile double *myInput; // * Pointers to the Input, Output, and Setpoint variables - volatile double *myOutput; // This creates a hard link between the variables and the - volatile double *mySetpoint; // PID, freeing the user from having to constantly tell us - // what these values are. with pointers we'll just know. - - unsigned long lastTime; - double outputSum, lastInput; - - unsigned long SampleTime; - double outMin, outMax; - bool inAuto; -}; -#endif - diff --git a/Firmware_1.26b/cnc_ctrl_v1/Probe.cpp b/Firmware_1.26b/cnc_ctrl_v1/Probe.cpp deleted file mode 100644 index 619fc09a..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Probe.cpp +++ /dev/null @@ -1,33 +0,0 @@ -/*This file is part of the Maslow Control Software. - -The Maslow Control Software is free software: you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation, either version 3 of the License, or -(at your option) any later version. - -Maslow Control Software is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with the Maslow Control Software. If not, see . - -Copyright 2014-2017 Bar Smith*/ - -// This file contains functions related to the probe - -#include "Maslow.h" - -// the variable probePin is assigned in configAuxLow() in System.cpp - -bool checkForProbeTouch(const int& probePin) { - /* - Check to see if ProbePin has gone LOW - */ - if (digitalRead(probePin) == LOW) { - readyCommandString = ""; - return 1; - } - return 0; -} diff --git a/Firmware_1.26b/cnc_ctrl_v1/Probe.h b/Firmware_1.26b/cnc_ctrl_v1/Probe.h deleted file mode 100644 index c4340366..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Probe.h +++ /dev/null @@ -1,25 +0,0 @@ -/*This file is part of the Maslow Control Software. - -The Maslow Control Software is free software: you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation, either version 3 of the License, or -(at your option) any later version. - -Maslow Control Software is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with the Maslow Control Software. If not, see . - -Copyright 2014-2017 Bar Smith*/ - -// This file contains functions related to the probe - -#ifndef probe_h -#define probe_h - -bool checkForProbeTouch(const int&); - -#endif \ No newline at end of file diff --git a/Firmware_1.26b/cnc_ctrl_v1/Report.cpp b/Firmware_1.26b/cnc_ctrl_v1/Report.cpp deleted file mode 100644 index 0c8b9e4f..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Report.cpp +++ /dev/null @@ -1,316 +0,0 @@ -/*This file is part of the Maslow Control Software. - -The Maslow Control Software is free software: you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation, either version 3 of the License, or -(at your option) any later version. - -Maslow Control Software is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with the Maslow Control Software. If not, see . - -Copyright 2014-2017 Bar Smith*/ - -// This file contains the functions for outgoing Serial responses - -#include "Maslow.h" - -void reportStatusMessage(byte status_code){ - /* - - Sends confirmation protocol response for commands. For every incoming line, - this method responds with an 'ok' for a successful command or an 'error:' - to indicate some error event with the line or some critical system error during - operation. - - Taken from Grbl http://github.com/grbl/grbl - */ - if (status_code == 0) { // STATUS_OK - Serial.println(F("ok")); - } else { - Serial.print(F("error: ")); - #ifdef REPORT_GUI_MODE - Serial.println(status_code); - #else - switch(status_code) { - // case STATUS_EXPECTED_COMMAND_LETTER=")); Serial.println( // Serial.println(F("Expected command letter")); break; - case STATUS_BAD_NUMBER_FORMAT: - Serial.println(F("Bad number format")); break; - case STATUS_INVALID_STATEMENT: - Serial.println(F("Invalid statement")); break; - case STATUS_OLD_SETTINGS: - Serial.println(F("Please set $12, $13, $19, and $20 to load old position data.")); break; - // case STATUS_NEGATIVE_VALUE: - // Serial.println(F("Value < 0")); break; - // case STATUS_SETTING_DISABLED: - // Serial.println(F("Setting disabled")); break; - // case STATUS_SETTING_STEP_PULSE_MIN: - // Serial.println(F("Value < 3 usec")); break; - case STATUS_SETTING_READ_FAIL: - Serial.println(F("EEPROM read fail. Using default settings.")); break; - // case STATUS_IDLE_ERROR: - // Serial.println(F("Not idle")); break; - // case STATUS_ALARM_LOCK: - // Serial.println(F("Alarm lock")); break; - // case STATUS_SOFT_LIMIT_ERROR: - // Serial.println(F("Homing not enabled")); break; - // case STATUS_OVERFLOW: - // Serial.println(F("Line overflow")); break; - // #ifdef MAX_STEP_RATE_HZ - // case STATUS_MAX_STEP_RATE_EXCEEDED: - // Serial.println(F("Step rate > 30kHz")); break; - // #endif - // Common g-code parser errors. - // case STATUS_GCODE_MODAL_GROUP_VIOLATION: - // Serial.println(F("Modal group violation")); break; - // case STATUS_GCODE_UNSUPPORTED_COMMAND: - // Serial.println(F("Unsupported command")); break; - // case STATUS_GCODE_UNDEFINED_FEED_RATE: - // Serial.println(F("Undefined feed rate")); break; - default: - // Remaining g-code parser errors with error codes - Serial.print(F("Invalid gcode ID:")); - Serial.println(status_code); // Print error code for user reference - } - #endif - } -} - -void reportFeedbackMessage(byte message_code){ - Serial.print(F("Message: ")); - switch(message_code) { - // case MESSAGE_CRITICAL_EVENT: - // Serial.print(F("Reset to continue")); break; - // case MESSAGE_ALARM_LOCK: - // Serial.print(F("'$H'|'$X' to unlock")); break; - // case MESSAGE_ALARM_UNLOCK: - // Serial.print(F("Caution: Unlocked")); break; - // case MESSAGE_ENABLED: - // Serial.print(F("Enabled")); break; - // case MESSAGE_DISABLED: - // Serial.print(F("Disabled")); break; - // case MESSAGE_SAFETY_DOOR_AJAR: - // Serial.print(F("Check Door")); break; - // case MESSAGE_CHECK_LIMITS: - // Serial.print(F("Check Limits")); break; - // case MESSAGE_PROGRAM_END: - // Serial.print(F("Pgm End")); break; - case MESSAGE_RESTORE_DEFAULTS: - Serial.print(F("Restoring defaults")); break; - // case MESSAGE_SPINDLE_RESTORE: - // Serial.print(F("Restoring spindle")); break; - // case MESSAGE_SLEEP_MODE: - // Serial.print(F("Sleeping")); break; - } - Serial.println(F(" ")); -} - -// Prints alarm messages. -void reportAlarmMessage(byte alarm_code) { - Serial.print(F("ALARM: ")); - #ifdef REPORT_GUI_MODE - Serial.println(alarm_code); - #else - switch (alarm_code) { - case ALARM_POSITION_LOST: { - Serial.println(F("Position Lost")); break; - } - case ALARM_GCODE_PARAM_ERROR: { - Serial.println(F("There is a parameter error in this line of Gcode - make a note of the line number. Cutting will be put on hold until you choose whether to 'Resume Cut' (skipping this line) or 'Stop'. ")); - pause(); //This pause() waits for user acknowledgement of message - pause(); //Now wait for user decision about 'Stop' or 'Resume' - break; - } - case ALARM_POSITION_LIMIT_ERROR: { - Serial.println(F("The sled is not keeping up with its expected position and has halted. Click the 'Stop' button to clear the alarm. More information at: https://github.com/MaslowCNC/Firmware/wiki/Keeping-Up ")); - sys.stop = true; - break; - } - } - #endif -} - -// Maslow global settings print out. -// NOTE: The numbering scheme here must correlate to storing in settings.c -void reportMaslowSettings() { - // Print Maslow settings. - // Taken from Grbl. http://github.com/grbl/grbl - #ifdef REPORT_GUI_MODE - Serial.print(F("$0=")); Serial.println(sysSettings.machineWidth, 8); - Serial.print(F("$1=")); Serial.println(sysSettings.machineHeight, 8); - Serial.print(F("$2=")); Serial.println(sysSettings.distBetweenMotors, 8); - Serial.print(F("$3=")); Serial.println(sysSettings.motorOffsetY, 8); - Serial.print(F("$4=")); Serial.println(sysSettings.sledWidth, 8); - Serial.print(F("$5=")); Serial.println(sysSettings.sledHeight, 8); - Serial.print(F("$6=")); Serial.println(sysSettings.sledCG, 8); - Serial.print(F("$7=")); Serial.println(sysSettings.kinematicsType); - Serial.print(F("$8=")); Serial.println(sysSettings.rotationDiskRadius, 8); - Serial.print(F("$9=")); Serial.println(sysSettings.axisDetachTime); - Serial.print(F("$10=")); Serial.println(sysSettings.chainLength); - Serial.print(F("$11=")); Serial.println(sysSettings.originalChainLength); - Serial.print(F("$12=")); Serial.println(sysSettings.encoderSteps, 8); - Serial.print(F("$13=")); Serial.println(sysSettings.distPerRot, 8); - Serial.print(F("$15=")); Serial.println(sysSettings.maxFeed); - Serial.print(F("$16=")); Serial.println(sysSettings.zAxisAttached); - Serial.print(F("$17=")); Serial.println(sysSettings.spindleAutomate); - Serial.print(F("$18=")); Serial.println(sysSettings.maxZRPM, 8); - Serial.print(F("$19=")); Serial.println(sysSettings.zDistPerRot, 8); - Serial.print(F("$20=")); Serial.println(sysSettings.zEncoderSteps, 8); - Serial.print(F("$21=")); Serial.println(sysSettings.KpPos, 8); - Serial.print(F("$22=")); Serial.println(sysSettings.KiPos, 8); - Serial.print(F("$23=")); Serial.println(sysSettings.KdPos, 8); - Serial.print(F("$24=")); Serial.println(sysSettings.propWeightPos, 8); - Serial.print(F("$25=")); Serial.println(sysSettings.KpV, 8); - Serial.print(F("$26=")); Serial.println(sysSettings.KiV, 8); - Serial.print(F("$27=")); Serial.println(sysSettings.KdV, 8); - Serial.print(F("$28=")); Serial.println(sysSettings.propWeightV, 8); - Serial.print(F("$29=")); Serial.println(sysSettings.zKpPos, 8); - Serial.print(F("$30=")); Serial.println(sysSettings.zKiPos, 8); - Serial.print(F("$31=")); Serial.println(sysSettings.zKdPos, 8); - Serial.print(F("$32=")); Serial.println(sysSettings.zPropWeightPos, 8); - Serial.print(F("$33=")); Serial.println(sysSettings.zKpV, 8); - Serial.print(F("$34=")); Serial.println(sysSettings.zKiV, 8); - Serial.print(F("$35=")); Serial.println(sysSettings.zKdV, 8); - Serial.print(F("$36=")); Serial.println(sysSettings.zPropWeightV, 8); - Serial.print(F("$37=")); Serial.println(sysSettings.chainSagCorrection, 8); - Serial.print(F("$38=")); Serial.println(sysSettings.chainOverSprocket); - Serial.print(F("$39=")); Serial.println(sysSettings.fPWM); - Serial.print(F("$40=")); Serial.println(sysSettings.leftChainTolerance, 8); - Serial.print(F("$41=")); Serial.println(sysSettings.rightChainTolerance, 8); - Serial.print(F("$42=")); Serial.println(sysSettings.positionErrorLimit, 8); - - #else - Serial.print(F("$0=")); Serial.print(sysSettings.machineWidth); - Serial.print(F(" (machine width, mm)\r\n$1=")); Serial.print(sysSettings.machineHeight, 8); - Serial.print(F(" (machine height, mm)\r\n$2=")); Serial.print(sysSettings.distBetweenMotors, 8); - Serial.print(F(" (motor distance, mm)\r\n$3=")); Serial.print(sysSettings.motorOffsetY, 8); - Serial.print(F(" (motor height, mm)\r\n$4=")); Serial.print(sysSettings.sledWidth, 8); - Serial.print(F(" (sled width, mm)\r\n$5=")); Serial.print(sysSettings.sledHeight, 8); - Serial.print(F(" (sled height, mm)\r\n$6=")); Serial.print(sysSettings.sledCG, 8); - Serial.print(F(" (sled cg, mm)\r\n$7=")); Serial.print(sysSettings.kinematicsType); - Serial.print(F(" (Kinematics Type 1=Quadrilateral, 2=Triangular)\r\n$8=")); Serial.print(sysSettings.rotationDiskRadius, 8); - Serial.print(F(" (rotation radius, mm)\r\n$9=")); Serial.print(sysSettings.axisDetachTime); - Serial.print(F(" (axis idle before detach, ms)\r\n$10=")); Serial.print(sysSettings.chainLength); - Serial.print(F(" (full length of chain, mm)\r\n$11=")); Serial.print(sysSettings.originalChainLength); - Serial.print(F(" (calibration chain length, mm)\r\n$12=")); Serial.print(sysSettings.encoderSteps, 8); - Serial.print(F(" (main steps per revolution)\r\n$13=")); Serial.print(sysSettings.distPerRot, 8); - Serial.print(F(" (distance / rotation, mm)\r\n$15=")); Serial.print(sysSettings.maxFeed); - Serial.print(F(" (max feed, mm/min)\r\n$16=")); Serial.print(sysSettings.zAxisAttached); - Serial.print(F(" (Auto Z Axis, 1 = Yes)\r\n$17=")); Serial.print(sysSettings.spindleAutomateType); - Serial.print(F(" (auto spindle enable 1=servo, 2=relay_h, 3=relay_l)\r\n$18=")); Serial.print(sysSettings.maxZRPM, 8); - Serial.print(F(" (max z axis RPM)\r\n$19=")); Serial.print(sysSettings.zDistPerRot, 8); - Serial.print(F(" (z axis distance / rotation)\r\n$20=")); Serial.print(sysSettings.zEncoderSteps, 8); - Serial.print(F(" (z axis steps per revolution)\r\n$21=")); Serial.print(sysSettings.KpPos, 8); - Serial.print(F(" (main Kp Pos)\r\n$22=")); Serial.print(sysSettings.KiPos, 8); - Serial.print(F(" (main Ki Pos)\r\n$23=")); Serial.print(sysSettings.KdPos, 8); - Serial.print(F(" (main Kd Pos)\r\n$24=")); Serial.print(sysSettings.propWeightPos, 8); - Serial.print(F(" (main Pos proportional weight)\r\n$25=")); Serial.print(sysSettings.KpV, 8); - Serial.print(F(" (main Kp Velocity)\r\n$26=")); Serial.print(sysSettings.KiV, 8); - Serial.print(F(" (main Ki Velocity)\r\n$27=")); Serial.print(sysSettings.KdV, 8); - Serial.print(F(" (main Kd Velocity)\r\n$28=")); Serial.print(sysSettings.propWeightV, 8); - Serial.print(F(" (main Velocity proportional weight)\r\n$29=")); Serial.print(sysSettings.zKpPos, 8); - Serial.print(F(" (z axis Kp Pos)\r\n$30=")); Serial.print(sysSettings.zKiPos, 8); - Serial.print(F(" (z axis Ki Pos)\r\n$31=")); Serial.print(sysSettings.zKdPos, 8); - Serial.print(F(" (z axis Kd Pos)\r\n$32=")); Serial.print(sysSettings.zPropWeightPos, 8); - Serial.print(F(" (z axis Pos proportional weight)\r\n$33=")); Serial.print(sysSettings.zKpV, 8); - Serial.print(F(" (z axis Kp Velocity)\r\n$34=")); Serial.print(sysSettings.zKiV, 8); - Serial.print(F(" (z axis Ki Velocity)\r\n$35=")); Serial.print(sysSettings.zKdV, 8); - Serial.print(F(" (z axis Kd Velocity)\r\n$36=")); Serial.print(sysSettings.zPropWeightV, 8); - Serial.print(F(" (z axis Velocity proportional weight)\r\n$37=")); Serial.print(sysSettings.chainSagCorrection, 8); - Serial.print(F(" (chain sag correction value)\r\n$38=")); Serial.print(sysSettings.chainOverSprocket); - Serial.print(F(" (chain over sprocket)\r\n$39=")); Serial.print(sysSettings.fPWM); - Serial.print(F(" (PWM frequency value 1=39,000Hz, 2=4,100Hz, 3=490Hz)\r\n$40=")); Serial.print(sysSettings.leftChainTolerance, 8); - Serial.print(F(" (chain tolerance, left chain, mm)\r\n$41=")); Serial.print(sysSettings.rightChainTolerance, 8); - Serial.print(F(" (chain tolerance, right chain, mm)\r\n$42=")); Serial.print(sysSettings.positionErrorLimit, 8); - Serial.print(F(" (position error alarm limit, mm)")); - Serial.println(); - #endif -} - -void returnError(){ - /* - Prints the machine's positional error and the amount of space available in the - gcode buffer - */ - Serial.print(F("[PE:")); - Serial.print(leftAxis.error()); - Serial.print(','); - Serial.print(rightAxis.error()); - Serial.print(','); - Serial.print(incSerialBuffer.spaceAvailable()); - Serial.println(F("]")); - if (!sys.stop) { - if (!(sys.state & STATE_POS_ERR_IGNORE)) { - if ((abs(leftAxis.error()) >= sysSettings.positionErrorLimit) || (abs(rightAxis.error()) >= sysSettings.positionErrorLimit)) { - reportAlarmMessage(ALARM_POSITION_LIMIT_ERROR); - } - } - } -} - -void returnPoz(){ - /* - Causes the machine's position (x,y) to be sent over the serial connection updated on the UI - in Ground Control. Also causes the error report to be sent. Only executes - if hasn't been called in at least POSITIONTIMEOUT ms. - */ - - static unsigned long lastRan = millis(); - - if (millis() - lastRan > POSITIONTIMEOUT){ - - - Serial.print(F("<")); - if (sys.stop){ - Serial.print(F("Stop,MPos:")); - } - else if (sys.pause){ - Serial.print(F("Pause,MPos:")); - } - else{ - Serial.print(F("Idle,MPos:")); - } - Serial.print(sys.xPosition/sys.inchesToMMConversion); - Serial.print(F(",")); - Serial.print(sys.yPosition/sys.inchesToMMConversion); - Serial.print(F(",")); - Serial.print(zAxis.read()/sys.inchesToMMConversion); - Serial.println(F(",WPos:0.000,0.000,0.000>")); - - - returnError(); - - lastRan = millis(); - } - -} - -void reportMaslowHelp(){ - /* - This function outputs a brief summary of the $ system commands available. - The list is somewhat aspirational based on what Grbl offers. Maslow - does not currently support all of these features. - - This is taken heavily from grbl. https://github.com/grbl/grbl - */ - #ifndef REPORT_GUI_MODE - Serial.println(F("$$ (view Maslow settings)")); - // Serial.println(F("$# (view # parameters)")); - // Serial.println(F("$G (view parser state)")); - // Serial.println(F("$I (view build info)")); - // Serial.println(F("$N (view startup blocks)")); - Serial.println(F("$x=value (save Maslow setting)")); - // Serial.println(F("$Nx=line (save startup block)")); - // Serial.println(F("$C (check gcode mode)")); - // Serial.println(F("$X (kill alarm lock)")); - // Serial.println(F("$H (run homing cycle)")); - Serial.println(F("~ (cycle start)")); // Maslow treats this as resume or un-pause currently - Serial.println(F("! (feed hold)")); // Maslow treats this as a cycle stop. - // Serial.println(F("? (current status)")); - // Serial.println(F("ctrl-x (reset Maslow)")); - #endif -} diff --git a/Firmware_1.26b/cnc_ctrl_v1/Report.h b/Firmware_1.26b/cnc_ctrl_v1/Report.h deleted file mode 100644 index d62b2289..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Report.h +++ /dev/null @@ -1,85 +0,0 @@ -/*This file is part of the Maslow Control Software. - -The Maslow Control Software is free software: you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation, either version 3 of the License, or -(at your option) any later version. - -Maslow Control Software is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with the Maslow Control Software. If not, see . - -Copyright 2014-2017 Bar Smith*/ - -// This file contains the functions for outgoing Serial responses - -#ifndef report_h -#define report_h - -// Define Maslow status codes. -// Taken from Grbl http://github.com/grbl/grbl -#define STATUS_OK 0 -#define STATUS_EXPECTED_COMMAND_LETTER 1 -#define STATUS_BAD_NUMBER_FORMAT 2 -#define STATUS_INVALID_STATEMENT 3 -#define STATUS_NEGATIVE_VALUE 4 -#define STATUS_SETTING_DISABLED 5 -#define STATUS_SETTING_STEP_PULSE_MIN 6 -#define STATUS_SETTING_READ_FAIL 7 -#define STATUS_IDLE_ERROR 8 -#define STATUS_ALARM_LOCK 9 -#define STATUS_SOFT_LIMIT_ERROR 10 -#define STATUS_OVERFLOW 11 -#define STATUS_MAX_STEP_RATE_EXCEEDED 12 -#define STATUS_OLD_SETTINGS 13 - -#define STATUS_GCODE_UNSUPPORTED_COMMAND 20 -#define STATUS_GCODE_MODAL_GROUP_VIOLATION 21 -#define STATUS_GCODE_UNDEFINED_FEED_RATE 22 -#define STATUS_GCODE_COMMAND_VALUE_NOT_INTEGER 23 -#define STATUS_GCODE_AXIS_COMMAND_CONFLICT 24 -#define STATUS_GCODE_WORD_REPEATED 25 -#define STATUS_GCODE_NO_AXIS_WORDS 26 -#define STATUS_GCODE_INVALID_LINE_NUMBER 27 -#define STATUS_GCODE_VALUE_WORD_MISSING 28 -#define STATUS_GCODE_UNSUPPORTED_COORD_SYS 29 -#define STATUS_GCODE_G53_INVALID_MOTION_MODE 30 -#define STATUS_GCODE_AXIS_WORDS_EXIST 31 -#define STATUS_GCODE_NO_AXIS_WORDS_IN_PLANE 32 -#define STATUS_GCODE_INVALID_TARGET 33 -#define STATUS_GCODE_ARC_RADIUS_ERROR 34 -#define STATUS_GCODE_NO_OFFSETS_IN_PLANE 35 -#define STATUS_GCODE_UNUSED_WORDS 36 -#define STATUS_GCODE_G43_DYNAMIC_AXIS_ERROR 37 - -// Define Maslow alarm codes. -#define ALARM_POSITION_LOST bit(0) -#define ALARM_GCODE_PARAM_ERROR bit(1) -#define ALARM_POSITION_LIMIT_ERROR bit(2) - -// Define Maslow feedback message codes. Valid values (0-255). -#define MESSAGE_CRITICAL_EVENT 1 -#define MESSAGE_ALARM_LOCK 2 -#define MESSAGE_ALARM_UNLOCK 3 -#define MESSAGE_ENABLED 4 -#define MESSAGE_DISABLED 5 -#define MESSAGE_SAFETY_DOOR_AJAR 6 -#define MESSAGE_CHECK_LIMITS 7 -#define MESSAGE_PROGRAM_END 8 -#define MESSAGE_RESTORE_DEFAULTS 9 -#define MESSAGE_SPINDLE_RESTORE 10 -#define MESSAGE_SLEEP_MODE 11 - -void reportStatusMessage(byte); -void reportFeedbackMessage(byte); -void reportMaslowSettings(); -void reportAlarmMessage(byte); -void returnError(); -void returnPoz(); -void reportMaslowHelp(); - -#endif \ No newline at end of file diff --git a/Firmware_1.26b/cnc_ctrl_v1/RingBuffer.cpp b/Firmware_1.26b/cnc_ctrl_v1/RingBuffer.cpp deleted file mode 100644 index c391edc8..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/RingBuffer.cpp +++ /dev/null @@ -1,208 +0,0 @@ -/*This file is part of the Maslow Control Software. - - The Maslow Control Software is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - Maslow Control Software is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with the Maslow Control Software. If not, see . - - Copyright 2014-2017 Bar Smith*/ - -/* -The RingBuffer module creates a circular character buffer used for storing incoming -serial data. -*/ - -#include "Maslow.h" - -RingBuffer::RingBuffer(){ - -} -int RingBuffer::write(char letter){ - /* - - Write one character into the ring buffer. - Return 0 on success - Return 1 on buffer overflow - - */ - if (letter != '?'){ //ignore question marks because grbl sends them all the time - _buffer[_endOfString] = letter; - int bufferOverflow = _incrementEnd(); - return bufferOverflow; - } - return 0; -} - -char RingBuffer::read(){ - /* - - Read one character from the ring buffer. - - */ - - char letter; - if (_beginningOfString == _endOfString){ - letter = '\0'; //if the buffer is empty return null - } - else{ - letter = _buffer[_beginningOfString]; //else return first character - _buffer[_beginningOfString] = '\0'; //set the read character to null so it cannot be read again - _incrementBeginning(); //and increment the pointer - } - - return letter; -} - -int RingBuffer::numberOfLines() { - /* - - Return the number of full lines (as determined by \n terminations) in the buffer - - */ - - int lineCount = 0; - - int i = _beginningOfString; - while (i != _endOfString) { // if we haven't gotten to the end of the buffer yet - if(_buffer[i] == '\n'){ // check to see if the buffer contains a complete line terminated with \n - lineCount++; // yes, so increment lineCount - } - _incrementVariable(&i); // go to the next character in the buffer - } - - return lineCount; -} - -void RingBuffer::readLine(String &lineToReturn){ - /* - - Return one line (terminated with \n) from the buffer - if there are no full lines in the buffer, passed string will be empty - - */ - lineToReturn = ""; // begin with an empty string - - if (numberOfLines() > 0) { // there is at least one full line in the buffer - char lastReadValue = '\0'; - while(lastReadValue != '\n'){ //read until the end of the line is found, building the string - lastReadValue = read(); - lineToReturn += lastReadValue; - } - } -} - -void RingBuffer::prettyReadLine(String &lineToReturn){ - /* - - Return one line (terminated with \n) from the buffer, but in all uppercase - with no leading or trailing whitespaces - - */ - readLine(lineToReturn); - lineToReturn.trim(); // remove leading and trailing white space - lineToReturn.toUpperCase(); -} - -void RingBuffer::print(){ - Serial.print(F("Buffer Used: ")); - Serial.println(length()); - Serial.print(F("Buffer Number of Lines: ")); - Serial.println(numberOfLines()); - Serial.print(F("Buffer Begin: ")); - Serial.println(_beginningOfString); - Serial.print(F("Buffer End: ")); - Serial.println(_endOfString); - - Serial.print(F("Buffer Contents: ")); - int i = _beginningOfString; - while(i != _endOfString){ - if (_buffer[i] == '\n') { - Serial.print(F("\\n")); - } - else if (_buffer[i] == '\r') { - Serial.print(F("\\r")); - } - else if (_buffer[i] == '\t') { - Serial.print(F("\\t")); - } - else { - Serial.print(_buffer[i]); - } - _incrementVariable(&i); - } - - Serial.println(F("(End of Buffer)")); - -} - -void RingBuffer::_incrementBeginning(){ - /* - - Increment the pointer to the beginning of the ring buffer by one. - - */ - - if (_beginningOfString == _endOfString) - return; //don't allow the beginning to pass the end - else - _beginningOfString = (_beginningOfString + 1) % INCBUFFERLENGTH; //move the beginning up one and wrap to zero based upon INCBUFFERLENGTH -} - -int RingBuffer::_incrementEnd(){ - /* - - Increment the pointer to the end of the ring buffer by one. - - */ - if ( spaceAvailable() == 0 ) { - Serial.println(F("Buffer overflow!")); - print(); // print buffer info and contents - return 1; - } - else - _endOfString = (_endOfString+1) % INCBUFFERLENGTH; - return 0; - } - -void RingBuffer::_incrementVariable(int* variable){ - /* - Increment the target variable. - */ - *variable = (*variable + 1 ) % INCBUFFERLENGTH; - } - -int RingBuffer::spaceAvailable(){ - /* - Returns the number of characters available in the buffer - */ - return INCBUFFERLENGTH - length() - 1; -} - -int RingBuffer::length(void) - /* - Returns the number of characters held in the buffer - */ -{ - if ( _endOfString >= _beginningOfString ) // Linear - return _endOfString - _beginningOfString ; - else // must have rolled - return ( INCBUFFERLENGTH - _beginningOfString + _endOfString); -} - - -void RingBuffer::empty(){ - /* - Empty the contents of the ring buffer - */ - - _beginningOfString = 0; - _endOfString = 0; -} diff --git a/Firmware_1.26b/cnc_ctrl_v1/RingBuffer.h b/Firmware_1.26b/cnc_ctrl_v1/RingBuffer.h deleted file mode 100644 index f6369f62..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/RingBuffer.h +++ /dev/null @@ -1,42 +0,0 @@ - /*This file is part of the Maslow Control Software. - - The Maslow Control Software is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - Maslow Control Software is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with the Maslow Control Software. If not, see . - - Copyright 2014-2017 Bar Smith*/ - - #ifndef RingBuffer_h - #define RingBuffer_h - - class RingBuffer{ - public: - RingBuffer(); - int write(char letter); - void print(); - char read(); - int length(); - int numberOfLines(); - int spaceAvailable(); - void empty(); - void readLine(String&); - void prettyReadLine(String&); - private: - void _incrementBeginning(); - int _incrementEnd(); - void _incrementVariable(int* variable); - int _beginningOfString = 0; //points to the first valid character which can be read - int _endOfString = 0; //points to the first open space which can be written - char _buffer[INCBUFFERLENGTH]; - }; - - #endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/Settings.cpp b/Firmware_1.26b/cnc_ctrl_v1/Settings.cpp deleted file mode 100644 index a622e04e..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Settings.cpp +++ /dev/null @@ -1,414 +0,0 @@ -/*This file is part of the Maslow Control Software. - -The Maslow Control Software is free software: you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation, either version 3 of the License, or -(at your option) any later version. - -Maslow Control Software is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with the Maslow Control Software. If not, see . - -Copyright 2014-2017 Bar Smith*/ - -// This file contains the machine settings that are saved to eeprom - -// EEPROM addresses 300 and up can be used by Maslow. Under 300 was used -// previously by pre v1.00 Firmware. - -#include "Maslow.h" -#include - -void settingsLoadFromEEprom(){ - /* - Loads data from EEPROM if EEPROM data is valid, only called on startup - - Settings are stored starting at address 340 all the way up. - */ - settingsVersion_t settingsVersionStruct; - settings_t tempSettings; - - settingsReset(); // Load default values first - EEPROM.get(300, settingsVersionStruct); - EEPROM.get(340, tempSettings); - if (settingsVersionStruct.settingsVersion == SETTINGSVERSION && - settingsVersionStruct.eepromValidData == EEPROMVALIDDATA && - tempSettings.eepromValidData == EEPROMVALIDDATA){ - sysSettings = tempSettings; - } - else { - reportStatusMessage(STATUS_SETTING_READ_FAIL); - } - - // Apply settings - setPWMPrescalers(int(sysSettings.fPWM)); - kinematics.recomputeGeometry(); - leftAxis.changeEncoderResolution(&sysSettings.encoderSteps); - rightAxis.changeEncoderResolution(&sysSettings.encoderSteps); - leftAxis.changePitch(&sysSettings.distPerRot); - rightAxis.changePitch(&sysSettings.distPerRot); - zAxis.changePitch(&sysSettings.zDistPerRot); - zAxis.changeEncoderResolution(&sysSettings.zEncoderSteps); -} - -void settingsReset() { - /* - Loads default data into settings, many of these values are approximations - from the an ideal stock frame. Other values are just the recommended - value. Ideally we want these defaults to match the defaults in GroundControl - so that if a value is not changed by a user or is not used, it doesn't - need to be updated here. - */ - sysSettings.machineWidth = 2438.4; // float machineWidth; - sysSettings.machineHeight = 1219.2; // float machineHeight; - sysSettings.distBetweenMotors = 2978.4; // float distBetweenMotors; - sysSettings.motorOffsetY = 463.0; // float motorOffsetY; - sysSettings.sledWidth = 310.0; // float sledWidth; - sysSettings.sledHeight = 139.0; // float sledHeight; - sysSettings.sledCG = 79.0; // float sledCG; - sysSettings.kinematicsType = 1; // byte kinematicsType; - sysSettings.rotationDiskRadius = 250.0; // float rotationDiskRadius; - sysSettings.axisDetachTime = 2000; // int axisDetachTime; - sysSettings.chainLength = 3360; // int maximum length of chain; - sysSettings.originalChainLength = 1650; // int originalChainLength; - sysSettings.encoderSteps = 8113.73; // float encoderSteps; - sysSettings.distPerRot = 63.5; // float distPerRot; - sysSettings.maxFeed = 700; // int maxFeed; - sysSettings.zAxisAttached = true; // zAxisAttached; - sysSettings.spindleAutomateType = NONE; // bool spindleAutomate; - sysSettings.maxZRPM = 12.60; // float maxZRPM; - sysSettings.zDistPerRot = 3.17; // float zDistPerRot; - sysSettings.zEncoderSteps = 7560.0; // float zEncoderSteps; - sysSettings.KpPos = 1300.0; // float KpPos; - sysSettings.KiPos = 0.0; // float KiPos; - sysSettings.KdPos = 34.0; // float KdPos; - sysSettings.propWeightPos = 1.0; // float propWeightPos; - sysSettings.KpV = 5.0; // float KpV; - sysSettings.KiV = 0.0; // float KiV; - sysSettings.KdV = 0.28; // float KdV; - sysSettings.propWeightV = 1.0; // float propWeightV; - sysSettings.zKdPos = 1300.0; // float zKpPos; - sysSettings.zKiPos = 0.0; // float zKiPos; - sysSettings.zKdPos = 34.0; // float zKdPos; - sysSettings.zPropWeightPos = 1.0; // float zPropWeightPos; - sysSettings.zKpV = 5.0; // float zKpV; - sysSettings.zKiV = 0.0; // float zKiV; - sysSettings.zKdV = 0.28; // float zKdV; - sysSettings.zPropWeightV = 1.0; // float zPropWeightV; - sysSettings.chainSagCorrection = 0.0; // float chainSagCorrection; - sysSettings.chainOverSprocket = 1; // byte chainOverSprocket; - sysSettings.fPWM = 3; // byte fPWM; - sysSettings.leftChainTolerance = 0.0; // float leftChainTolerance; - sysSettings.rightChainTolerance = 0.0; // float rightChainTolerance; - sysSettings.positionErrorLimit = 2.0; // float positionErrorLimit; - sysSettings.eepromValidData = EEPROMVALIDDATA; // byte eepromValidData; -} - -void settingsWipe(byte resetType){ - /* - Wipes certain bytes in the EEPROM, you probably want to reset after calling - this - */ - if (bit_istrue(resetType, SETTINGS_RESTORE_SETTINGS)){ - for (size_t i = 340 ; i < sizeof(sysSettings) + 340 ; i++) { - EEPROM.write(i, 0); - } - } - else if (bit_istrue(resetType, SETTINGS_RESTORE_MASLOW)){ - for (size_t i = 300 ; i < sizeof(sysSettings) + 340; i++) { - EEPROM.write(i, 0); - } - } - else if (bit_istrue(resetType, SETTINGS_RESTORE_ALL)){ - for (size_t i = 0 ; i < EEPROM.length() ; i++) { - EEPROM.write(i, 0); - } - } -} - -void settingsSaveToEEprom(){ - /* - Saves settings to EEPROM, only called when settings change - - Settings are stored starting at address 340 all the way up. - */ - settingsVersion_t settingsVersionStruct = {SETTINGSVERSION, EEPROMVALIDDATA}; - EEPROM.put(300, settingsVersionStruct); - EEPROM.put(340, sysSettings); -} - -void settingsSaveStepstoEEprom(){ - /* - Saves position to EEPROM, is called frequently by execSystemRealtime - - Steps are saved in address 310 -> 339. Room for expansion for additional - axes in the future. - */ - // don't run if old position data has not been incorporated yet - if (!sys.oldSettingsFlag){ - settingsStepsV1_t sysSteps = { - leftAxis.steps(), - rightAxis.steps(), - zAxis.steps(), - EEPROMVALIDDATA - }; - EEPROM.put(310, sysSteps); - } -} - -void settingsLoadStepsFromEEprom(){ - /* - Loads position to EEPROM, is called on startup. - - Steps are saved in address 310 -> 339. Room for expansion for additional - axes in the future. - */ - settingsStepsV1_t tempStepsV1; - - EEPROM.get(310, tempStepsV1); - if (tempStepsV1.eepromValidData == EEPROMVALIDDATA){ - leftAxis.setSteps(tempStepsV1.lSteps); - rightAxis.setSteps(tempStepsV1.rSteps); - zAxis.setSteps(tempStepsV1.zSteps); - } - else if (EEPROM.read(5) == EEPROMVALIDDATA && - EEPROM.read(105) == EEPROMVALIDDATA && - EEPROM.read(205) == EEPROMVALIDDATA){ - bit_true(sys.oldSettingsFlag, NEED_ENCODER_STEPS); - bit_true(sys.oldSettingsFlag, NEED_DIST_PER_ROT); - bit_true(sys.oldSettingsFlag, NEED_Z_ENCODER_STEPS); - bit_true(sys.oldSettingsFlag, NEED_Z_DIST_PER_ROT); - sys.state = STATE_OLD_SETTINGS; - Serial.println(F("Old position data detected.")); - Serial.println(F("Please set $12, $13, $19, and $20 to load position.")); - } - else { - systemRtExecAlarm |= ALARM_POSITION_LOST; // if this same global is touched by ISR then need to make atomic somehow - // also need to consider if need difference between flag with bits and - // error message as a byte. - } -} - -void settingsLoadOldSteps(){ - /* - Loads the old version of step settings, only called once encoder steps - and distance per rotation have been loaded. Wipes the old data once - incorporated to prevent oddities in the future - */ - if (sys.state == STATE_OLD_SETTINGS){ - float l, r , z; - EEPROM.get(9, l); - EEPROM.get(109, r); - EEPROM.get(209, z); - leftAxis.set(l); - rightAxis.set(r); - zAxis.set(z); - for (int i = 0; i <= 200; i = i +100){ - for (int j = 5; j <= 13; j++){ - EEPROM.write(i + j, 0); - } - } - sys.state = STATE_IDLE; - } - } - -byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ - /* - Alters individual settings which are then stored to EEPROM. Returns a - status message byte value - */ - - // We can add whatever sanity checks we want here and error out if we like - switch(parameter) { - case 0: case 1: case 2: case 3: case 4: case 5: case 6: case 7: case 8: - switch(parameter) { - case 0: - sysSettings.machineWidth = value; - break; - case 1: - sysSettings.machineHeight = value; - break; - case 2: - sysSettings.distBetweenMotors = value; - break; - case 3: - sysSettings.motorOffsetY = value; - break; - case 4: - sysSettings.sledWidth = value; - break; - case 5: - sysSettings.sledHeight = value; - break; - case 6: - sysSettings.sledCG = value; - break; - case 7: - sysSettings.kinematicsType = value; - break; - case 8: - sysSettings.rotationDiskRadius = value; - break; - } - kinematics.init(); - break; - case 9: - sysSettings.axisDetachTime = value; - break; - case 10: - sysSettings.chainLength = value; - break; - case 11: - sysSettings.originalChainLength = value; - break; - case 12: - sysSettings.encoderSteps = value; - leftAxis.changeEncoderResolution(&sysSettings.encoderSteps); - rightAxis.changeEncoderResolution(&sysSettings.encoderSteps); - if (sys.oldSettingsFlag){ - bit_false(sys.oldSettingsFlag, NEED_ENCODER_STEPS); - if (!sys.oldSettingsFlag){ - settingsLoadOldSteps(); - } - } - kinematics.init(); - break; - case 13: - sysSettings.distPerRot = value; - kinematics.R = (sysSettings.distPerRot)/(2.0 * 3.14159); - if (sys.oldSettingsFlag){ - bit_false(sys.oldSettingsFlag, NEED_DIST_PER_ROT); - if (!sys.oldSettingsFlag){ - settingsLoadOldSteps(); - } - } - kinematics.init(); - break; - case 15: - sysSettings.maxFeed = value; - break; - case 16: - sysSettings.zAxisAttached = value; - break; - case 17: - sysSettings.spindleAutomateType = static_cast(value); - break; - case 18: - sysSettings.maxZRPM = value; - break; - case 19: - sysSettings.zDistPerRot = value; - zAxis.changePitch(&sysSettings.zDistPerRot); - if (sys.oldSettingsFlag){ - bit_false(sys.oldSettingsFlag, NEED_Z_DIST_PER_ROT); - if (!sys.oldSettingsFlag){ - settingsLoadOldSteps(); - } - } - break; - case 20: - sysSettings.zEncoderSteps = value; - zAxis.changeEncoderResolution(&sysSettings.zEncoderSteps); - if (sys.oldSettingsFlag){ - bit_false(sys.oldSettingsFlag, NEED_Z_ENCODER_STEPS); - if (!sys.oldSettingsFlag){ - settingsLoadOldSteps(); - } - } - break; - case 21: case 22: case 23: case 24: case 25: case 26: case 27: case 28: - switch(parameter) { - case 21: - sysSettings.KpPos = value; - break; - case 22: - sysSettings.KiPos = value; - break; - case 23: - sysSettings.KdPos = value; - break; - case 24: - sysSettings.propWeightPos = value; - break; - case 25: - sysSettings.KpV = value; - break; - case 26: - sysSettings.KiV = value; - break; - case 27: - sysSettings.KdV = value; - break; - case 28: - sysSettings.propWeightV = value; - break; - } - leftAxis.setPIDValues(&sysSettings.KpPos, &sysSettings.KiPos, &sysSettings.KdPos, &sysSettings.propWeightPos, &sysSettings.KpV, &sysSettings.KiV, &sysSettings.KdV, &sysSettings.propWeightV); - rightAxis.setPIDValues(&sysSettings.KpPos, &sysSettings.KiPos, &sysSettings.KdPos, &sysSettings.propWeightPos, &sysSettings.KpV, &sysSettings.KiV, &sysSettings.KdV, &sysSettings.propWeightV); - break; - case 29: case 30: case 31: case 32: case 33: case 34: case 35: case 36: - switch(parameter) { - case 29: - sysSettings.zKpPos = value; - break; - case 30: - sysSettings.zKiPos = value; - break; - case 31: - sysSettings.zKdPos = value; - break; - case 32: - sysSettings.zPropWeightPos = value; - break; - case 33: - sysSettings.zKpV = value; - break; - case 34: - sysSettings.zKiV = value; - break; - case 35: - sysSettings.zKdV = value; - break; - case 36: - sysSettings.zPropWeightV = value; - break; - } - zAxis.setPIDValues(&sysSettings.zKpPos, &sysSettings.zKiPos, &sysSettings.zKdPos, &sysSettings.zPropWeightPos, &sysSettings.zKpV, &sysSettings.zKiV, &sysSettings.zKdV, &sysSettings.zPropWeightV); - break; - case 37: - sysSettings.chainSagCorrection = value; - break; - case 38: - settingsSaveStepstoEEprom(); - sysSettings.chainOverSprocket = value; - setupAxes(); - settingsLoadStepsFromEEprom(); - // Set initial desired position of the machine to its current position - leftAxis.write(leftAxis.read()); - rightAxis.write(rightAxis.read()); - zAxis.write(zAxis.read()); - kinematics.init(); - break; - case 39: - sysSettings.fPWM = value; - setPWMPrescalers(value); - break; - case 40: - sysSettings.leftChainTolerance = value; - break; - case 41: - sysSettings.rightChainTolerance = value; - break; - case 42: - sysSettings.positionErrorLimit = value; - break; - default: - return(STATUS_INVALID_STATEMENT); - } - settingsSaveToEEprom(); - return(STATUS_OK); -} diff --git a/Firmware_1.26b/cnc_ctrl_v1/Settings.h b/Firmware_1.26b/cnc_ctrl_v1/Settings.h deleted file mode 100644 index cd18150b..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Settings.h +++ /dev/null @@ -1,109 +0,0 @@ -/*This file is part of the Maslow Control Software. - -The Maslow Control Software is free software: you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation, either version 3 of the License, or -(at your option) any later version. - -Maslow Control Software is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with the Maslow Control Software. If not, see . - -Copyright 2014-2017 Bar Smith*/ - -// This file contains the machine settings that are saved to eeprom - -#ifndef settings_h -#define settings_h - -#define SETTINGSVERSION 5 // The current version of settings, if this doesn't - // match what is in EEPROM then settings on - // machine are reset to defaults -#define EEPROMVALIDDATA 56 // This is just a random byte value that is used - // to determine if the data in the EEPROM was - // saved by maslow, or something else. - -// Reset Types -#define SETTINGS_RESTORE_SETTINGS bit(0) -#define SETTINGS_RESTORE_MASLOW bit(1) -#define SETTINGS_RESTORE_ALL bit(2) - -enum SpindleAutomationType { - NONE, - SERVO, - RELAY_ACTIVE_HIGH, - RELAY_ACTIVE_LOW }; - -typedef struct { // I think this is about ~128 bytes in size if I counted correctly - float machineWidth; - float machineHeight; - float distBetweenMotors; - float motorOffsetY; - float sledWidth; - float sledHeight; - float sledCG; - byte kinematicsType; - float rotationDiskRadius; - unsigned int axisDetachTime; - unsigned int chainLength; - unsigned int originalChainLength; - float encoderSteps; - float distPerRot; - unsigned int maxFeed; - bool zAxisAttached; - SpindleAutomationType spindleAutomateType; - float maxZRPM; - float zDistPerRot; - float zEncoderSteps; - float KpPos; - float KiPos; - float KdPos; - float propWeightPos; - float KpV; - float KiV; - float KdV; - float propWeightV; - float zKpPos; - float zKiPos; - float zKdPos; - float zPropWeightPos; - float zKpV; - float zKiV; - float zKdV; - float zPropWeightV; - float chainSagCorrection; - byte chainOverSprocket; - byte fPWM; - float leftChainTolerance; - float rightChainTolerance; - float positionErrorLimit; - byte eepromValidData; // This should always be last, that way if an error - // happens in writing, it will not be written and we -} settings_t; // will know to reset the settings -extern settings_t sysSettings; - -typedef struct { - byte settingsVersion; - byte eepromValidData; -} settingsVersion_t; - -typedef struct { - long lSteps; - long rSteps; - long zSteps; - byte eepromValidData; -} settingsStepsV1_t; - -void settingsLoadFromEEprom(); -void settingsReset(); -void settingsWipe(byte); -void settingsSaveToEEprom(); -void settingsSaveStepstoEEprom(); -void settingsLoadStepsFromEEprom(); -byte settingsStoreGlobalSetting(const byte&,const float&); - -#endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/SimavrSerial.cpp b/Firmware_1.26b/cnc_ctrl_v1/SimavrSerial.cpp deleted file mode 100644 index 5ddebd96..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/SimavrSerial.cpp +++ /dev/null @@ -1,27 +0,0 @@ -#include "SimavrSerial.h" - -#ifdef Serial -#undef Serial -#endif - -SimavrSerial_ SimavrSerial; - -size_t SimavrSerial_::write(uint8_t c) -{ - size_t n = Serial.write(c); - Serial.flush(); - - return n; -} - -void SimavrSerial_::begin(unsigned long baud) { - Serial.begin(baud); -} - -int SimavrSerial_::available() { - return Serial.available(); -} - -int SimavrSerial_::read() { - return Serial.read(); -} diff --git a/Firmware_1.26b/cnc_ctrl_v1/SimavrSerial.h b/Firmware_1.26b/cnc_ctrl_v1/SimavrSerial.h deleted file mode 100644 index 879dd362..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/SimavrSerial.h +++ /dev/null @@ -1,32 +0,0 @@ -#include "Maslow.h" - -#ifndef SimavrSerial_h_ -#define SimavrSerial_h_ - -#ifdef SIMAVR -#define Serial SimavrSerial -#endif - -// This class is a wrapper around Serial, to be used when running in the simavr simulator -// (https://github.com/buserror/simavr) -// -// Simavr's UART seems to lock up and crash when you write more than a few characters to it. -// SimavrSerial works around this issue by flushing after every single character. On a real -// controller, this might cause a performance issue, so this class is only used if SIMAVR is defined. -// If SIMAVR is defined, though, any reference to Serial is replaces to a reference to SimavrSerial. -// This means that every Serial method that is used in our code also needs a wrapper in SimavrSerial, -// of the simavr environment will not compile. -// -// Not the cleanest thing ever, but it's the best I could come up with that -// will have zero impact on the actual production code. -class SimavrSerial_ : public Print -{ - public: - virtual size_t write(uint8_t); - virtual int available(); - virtual int read(); - void begin(unsigned long baud); -}; - -extern SimavrSerial_ SimavrSerial; -#endif \ No newline at end of file diff --git a/Firmware_1.26b/cnc_ctrl_v1/Spindle.cpp b/Firmware_1.26b/cnc_ctrl_v1/Spindle.cpp deleted file mode 100644 index 647acf9c..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Spindle.cpp +++ /dev/null @@ -1,117 +0,0 @@ -/*This file is part of the Maslow Control Software. - The Maslow Control Software is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - Maslow Control Software is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - You should have received a copy of the GNU General Public License - along with the Maslow Control Software. If not, see . - - Copyright 2014-2017 Bar Smith*/ - -// This contains all of the Spindle commands - -#include "Maslow.h" -#include "Settings.h" - -// the variables SpindlePowerControlPin and LaserPowerPin are assigned in configAuxLow() in System.cpp - -// Globals for Spindle control, both poorly named -Servo myservo; // create servo object to control a servo - -void setSpindlePower(bool powerState) { - /* - * Turn spindle on/off depending on powerState - */ - SpindleAutomationType spindleAutomateType = sysSettings.spindleAutomateType; - - int delayAfterChange = 1000; // milliseconds - int servoIdle = 90; // degrees - int servoOn = 180; // degrees - int servoOff = 0; // degrees - int servoDelay = 2000; // milliseconds - - // Now for the main code - #if defined (verboseDebug) && verboseDebug > 1 - Serial.print(F("Spindle control uses pin ")); - Serial.print(SpindlePowerControlPin); - Serial.print(F("Spindle automation type ")); - Serial.print(spindleAutomateType); - #endif - if (spindleAutomateType == SERVO) { // use a servo to control a standard wall switch - #if defined (verboseDebug) && verboseDebug > 1 - Serial.print(F(" with servo (idle=")); - Serial.print(servoIdle); - Serial.print(F(", on=")); - Serial.print(servoOn); - Serial.print(F(", off=")); - Serial.print(servoOff); - Serial.println(F(")")); - #endif - myservo.attach(SpindlePowerControlPin); // start servo control - myservo.write(servoIdle); // move servo to idle position - maslowDelay(servoDelay); // wait for move to complete - if(sys.stop){return;} - if (powerState) { // turn on spindle - Serial.println(F("Turning Spindle On")); - myservo.write(servoOn); // move servo to turn on switch - } - else { // turn off spindle - Serial.println(F("Turning Spindle Off")); - myservo.write(servoOff); // move servo to turn off switch - } - maslowDelay(servoDelay); // wait for move to complete - if(sys.stop){return;} - myservo.write(servoIdle); // return servo to idle position - maslowDelay(servoDelay); // wait for move to complete - if(sys.stop){return;} - myservo.detach(); // stop servo control - } - else if (spindleAutomateType == RELAY_ACTIVE_HIGH) { - #if defined (verboseDebug) && verboseDebug > 1 - Serial.print(F(" as digital output, active high")); - #endif - pinMode(SpindlePowerControlPin, OUTPUT); - if (powerState) { // turn on spindle - Serial.println(F("Turning Spindle On")); - digitalWrite(SpindlePowerControlPin, HIGH); - } - else { // turn off spindle - Serial.println(F("Turning Spindle Off")); - digitalWrite(SpindlePowerControlPin, LOW); - } - } - else if (spindleAutomateType == RELAY_ACTIVE_LOW) { // use a digital I/O pin to control a relay - #if defined (verboseDebug) && verboseDebug > 1 - Serial.print(F(" as digital output, active low")); - #endif - pinMode(SpindlePowerControlPin, OUTPUT); - if (powerState) { // turn on spindle - Serial.println(F("Turning Spindle On")); - digitalWrite(SpindlePowerControlPin, LOW); - } - else { // turn off spindle - Serial.println(F("Turning Spindle Off")); - digitalWrite(SpindlePowerControlPin, HIGH); - } - } - if (spindleAutomateType != NONE) { - maslowDelay(delayAfterChange); - } -} - -void laserOn(bool OnOff) { - pinMode(LaserPowerPin, OUTPUT); - if (OnOff) { // turn on Laser - EBS BETTER go LOW on system stop - Serial.println(F("Turning Laser ON")); - digitalWrite(LaserPowerPin, HIGH); - } - else { // turn off Laser - // Serial.println(F("Turning Laser OFF")); - digitalWrite(LaserPowerPin, LOW); - } -} - diff --git a/Firmware_1.26b/cnc_ctrl_v1/Spindle.h b/Firmware_1.26b/cnc_ctrl_v1/Spindle.h deleted file mode 100644 index f42fc442..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Spindle.h +++ /dev/null @@ -1,24 +0,0 @@ -/*This file is part of the Maslow Control Software. - The Maslow Control Software is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - Maslow Control Software is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - You should have received a copy of the GNU General Public License - along with the Maslow Control Software. If not, see . - - Copyright 2014-2017 Bar Smith*/ - -// This contains all of the Spindle commands - -#ifndef spindle_h -#define spindle_h - -void setSpindlePower(bool powerState); -void laserOn(bool OnOff); - - -#endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/System.cpp b/Firmware_1.26b/cnc_ctrl_v1/System.cpp deleted file mode 100644 index e082222d..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/System.cpp +++ /dev/null @@ -1,658 +0,0 @@ -/*This file is part of the Maslow Control Software. - -The Maslow Control Software is free software: you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation, either version 3 of the License, or -(at your option) any later version. - -Maslow Control Software is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with the Maslow Control Software. If not, see . - -Copyright 2014-2017 Bar Smith*/ - -// This file contains system level functions and states - -#include "Maslow.h" - -bool TLE5206; -bool TB6643; - -// extern values using AUX pins defined in configAuxLow() and configAuxHigh() -int SpindlePowerControlPin; // output for controlling spindle power -int ProbePin; // use this input for zeroing zAxis with G38.2 gcode -int LaserPowerPin; // Use this output to turn on and off a laser diode - - -void calibrateChainLengths(String gcodeLine){ - /* - The calibrateChainLengths function lets the machine know that the chains are set to a given length where each chain is ORIGINCHAINLEN - in length - */ - - if (extractGcodeValue(gcodeLine, 'L', 0)){ - //measure out the left chain - Serial.println(F("Measuring out left chain")); - singleAxisMove(&leftAxis, sysSettings.originalChainLength, (sysSettings.maxFeed * .9)); - - Serial.print(leftAxis.read()); - Serial.println(F("mm")); - - leftAxis.detach(); - } - else if(extractGcodeValue(gcodeLine, 'R', 0)){ - //measure out the right chain - Serial.println(F("Measuring out right chain")); - singleAxisMove(&rightAxis, sysSettings.originalChainLength, (sysSettings.maxFeed * .9)); - - Serial.print(rightAxis.read()); - Serial.println(F("mm")); - - rightAxis.detach(); - } - -} - -void setupAxes(){ - /* - - Detect the version of the Arduino shield connected, and use the appropriate pins - - This function runs before the serial port is open so the version is not printed here - - */ - - - int encoder1A; - int encoder1B; - int encoder2A; - int encoder2B; - int encoder3A; - int encoder3B; - - int in1; - int in2; - int in3; - int in4; - int in5; - int in6; - - int enA; - int enB; - int enC; - - int aux1; - int aux2; - int aux3; - int aux4; - int aux5; - int aux6; - int aux7; - int aux8; - int aux9; - - //read the pins which indicate the PCB version - int pcbVersion = getPCBVersion(); - - if(pcbVersion == 0){ - //Beta PCB v1.0 Detected - //MP1 - Right Motor - encoder1A = 18; // INPUT - encoder1B = 19; // INPUT - in1 = 9; // OUTPUT - in2 = 8; // OUTPUT - enA = 6; // PWM - - //MP2 - Z-axis - encoder2A = 2; // INPUT - encoder2B = 3; // INPUT - in3 = 11; // OUTPUT - in4 = 10; // OUTPUT - enB = 7; // PWM - - //MP3 - Left Motor - encoder3A = 21; // INPUT - encoder3B = 20; // INPUT - in5 = 12; // OUTPUT - in6 = 13; // OUTPUT - enC = 5; // PWM - - //AUX pins - aux1 = 17; - aux2 = 16; - aux3 = 15; - aux4 = 14; - aux5 = 0; // warning! this is the serial TX line on the Mega2560 - aux6 = 1; // warning! this is the serial RX line on the Mega2560 - } - else if(pcbVersion == 1){ - //PCB v1.1 Detected - //MP1 - Right Motor - encoder1A = 20; // INPUT - encoder1B = 21; // INPUT - in1 = 6; // OUTPUT - in2 = 4; // OUTPUT - enA = 5; // PWM - - //MP2 - Z-axis - encoder2A = 19; // INPUT - encoder2B = 18; // INPUT - in3 = 9; // OUTPUT - in4 = 7; // OUTPUT - enB = 8; // PWM - - //MP3 - Left Motor - encoder3A = 2; // INPUT - encoder3B = 3; // INPUT - in5 = 10; // OUTPUT - in6 = 11; // OUTPUT - enC = 12; // PWM - - //AUX pins - aux1 = 17; - aux2 = 16; - aux3 = 15; - aux4 = 14; - aux5 = A7; - aux6 = A6; - } - else if(pcbVersion == 2){ - //PCB v1.2 Detected - - //MP1 - Right Motor - encoder1A = 20; // INPUT - encoder1B = 21; // INPUT - in1 = 4; // OUTPUT - in2 = 6; // OUTPUT - enA = 5; // PWM - - //MP2 - Z-axis - encoder2A = 19; // INPUT - encoder2B = 18; // INPUT - in3 = 7; // OUTPUT - in4 = 9; // OUTPUT - enB = 8; // PWM - - //MP3 - Left Motor - encoder3A = 2; // INPUT - encoder3B = 3; // INPUT - in5 = 11; // OUTPUT - in6 = 12; // OUTPUT - enC = 10; // PWM - - //AUX pins - aux1 = 17; - aux2 = 16; - aux3 = 15; - aux4 = 14; - aux5 = A7; - aux6 = A6; - } - else if(pcbVersion == 4){ // TLE5206 - //TLE5206 PCB v1.4 Detected - //MP1 - Right Motor - encoder1A = 20; // INPUT - encoder1B = 21; // INPUT - in1 = 6; // OUTPUT - in2 = 4; // OUTPUT - enA = 5; // errorFlag - - //MP2 - Z-axis - encoder2A = 19; // INPUT - encoder2B = 18; // INPUT - in3 = 7; // OUTPUT - in4 = 9; // OUTPUT - enB = 8; // errorFlag - - //MP3 - Left Motor - encoder3A = 2; // INPUT - encoder3B = 3; // INPUT - in5 = 10; // OUTPUT - in6 = 11; // OUTPUT - enC = 12; // errorFlag - - //AUX pins - aux1 = 40; - aux2 = 41; - aux3 = 42; - aux4 = 43; - aux5 = 68; - aux6 = 69; - aux7 = 45; - aux8 = 46; - aux9 = 47; - } -else if(pcbVersion == 5){ // EBS PCB v1.5 Detected - - //MP1 - Right Motor - encoder1A = 2; // INPUT - encoder1B = 3; // INPUT - in1 = 9; // OUTPUT - in2 = 10; // OUTPUT - //enA = 12; // errorFlag - - //MP2 - Z-axis - encoder2A = 18; // INPUT - encoder2B = 19; // INPUT - in3 = 7; // OUTPUT - in4 = 8; // OUTPUT - //enB = 8; // errorFlag - - //MP3 - Left Motor - encoder3A = 21; // INPUT - encoder3B = 20; // INPUT - in5 = 6; // OUTPUT - in6 = 5; // OUTPUT - //enC = 5; // errorFlag - - //AUX pins - aux1 = 48; - aux2 = 49; - aux3 = 51; - aux4 = 50; - aux5 = 43; - aux6 = 44; - } - - if(sysSettings.chainOverSprocket == 1){ - leftAxis.setup (enC, in6, in5, encoder3B, encoder3A, 'L', LOOPINTERVAL); - rightAxis.setup(enA, in1, in2, encoder1A, encoder1B, 'R', LOOPINTERVAL); - } - else{ - leftAxis.setup (enC, in5, in6, encoder3A, encoder3B, 'L', LOOPINTERVAL); - rightAxis.setup(enA, in2, in1, encoder1B, encoder1A, 'R', LOOPINTERVAL); - } - - zAxis.setup (enB, in3, in4, encoder2B, encoder2A, 'Z', LOOPINTERVAL); - leftAxis.setPIDValues(&sysSettings.KpPos, &sysSettings.KiPos, &sysSettings.KdPos, &sysSettings.propWeightPos, &sysSettings.KpV, &sysSettings.KiV, &sysSettings.KdV, &sysSettings.propWeightV); - rightAxis.setPIDValues(&sysSettings.KpPos, &sysSettings.KiPos, &sysSettings.KdPos, &sysSettings.propWeightPos, &sysSettings.KpV, &sysSettings.KiV, &sysSettings.KdV, &sysSettings.propWeightV); - zAxis.setPIDValues(&sysSettings.zKpPos, &sysSettings.zKiPos, &sysSettings.zKdPos, &sysSettings.zPropWeightPos, &sysSettings.zKpV, &sysSettings.zKiV, &sysSettings.zKdV, &sysSettings.zPropWeightV); - - // implement the AUXx values that are 'used'. This accomplishes setting their values at runtime. - // Using a separate function is a compiler work-around to avoid - // "warning: variable ‘xxxxx’ set but not used [-Wunused-but-set-variable]" - // for AUX pins defined but not connected - configAuxLow(aux1, aux2, aux3, aux4, aux5, aux6); - if(pcbVersion == 4){ // TLE5206 - configAuxHigh(aux7, aux8, aux9); - } -} - -// Assign AUX pins to extern variables used by functions like Spindle and Probe -void configAuxLow(int aux1, int aux2, int aux3, int aux4, int aux5, int aux6) { - SpindlePowerControlPin = aux1; // output for controlling spindle power - LaserPowerPin = aux2; // output for controlling a laser diode - ProbePin = aux4; // use this input for zeroing zAxis with G38.2 gcode - pinMode(LaserPowerPin, OUTPUT); - digitalWrite(LaserPowerPin, LOW); -} - -void configAuxHigh(int aux7, int aux8, int aux9) { -} - -int getPCBVersion(){ - pinMode(VERS1,INPUT_PULLUP); //22 - pinMode(VERS2,INPUT_PULLUP); //23 - pinMode(VERS3,INPUT_PULLUP); //24 - pinMode(VERS4,INPUT_PULLUP); //25 - pinMode(VERS5,INPUT_PULLUP); //26 - pinMode(VERS6,INPUT_PULLUP); //27 - int pinCheck = (32*digitalRead(VERS6) + 16*digitalRead(VERS5) + 8*digitalRead(VERS4) + 4*digitalRead(VERS3) + 2*digitalRead(VERS2) + 1*digitalRead(VERS1)); - switch (pinCheck) { - // boards v1.0, v1.1, v1.2 don't strap VERS3-6 low - case B111101: case B111110: case B111111: // v 1.0, v1.1, v1.2 - pinCheck &= B000011; // strip off the unstrapped bits - TLE5206 = false; - break; - case B110100: case B000100: // some versions of board v1.3, v1.4 don't strap VERS5-6 low - pinCheck = 5; // V1.3 ~ V1.4 - SAME SHIELD - TLE5206 = true; - break; - case B000110: // new v1.5 - pinCheck &= B000110; // - TB6643 = true; - TLE5206 = false; - break; - -} - return pinCheck - 1; -} - - -// -// PWM frequency change -// presently just sets the default value -// different values seem to need specific PWM tunings... -// -void setPWMPrescalers(int prescalerChoice) { - #if defined (verboseDebug) && verboseDebug > 0 - Serial.print(F("fPWM set to ")); - switch (prescalerChoice) { - case 1: - Serial.println(F("31,000Hz")); - break; - case 2: - Serial.println(F("4,100Hz")); - break; - case 3: - Serial.println(F("490Hz")); - } - #endif - - // tailor the PWM frequency to the chip - //if (TLE5206) { - // The upper limit to PWM frequency for TLE5206 is 1,000Hz - // so only '3' is valid - // prescalerChoice = 3; - //} else if (TLE9201) { - // The upper limit to PWM frequency for TLE9201 is 20,000Hz - // prescalerChoice = 3; - // } - //} else if (TB6643) { - // The upper limit to PWM frequency for TB6643 is 100kz - // prescalerChoice = 3; - // } - - - -// first must erase the bits in each TTCRxB register that control the timers prescaler - int prescalerEraser = 7; // this is 111 in binary and is used as an eraser - TCCR2B &= ~prescalerEraser; // this operation sets the three bits in TCCR2B to 0 - TCCR3B &= ~prescalerEraser; // this operation sets the three bits in TCCR3B to 0 - TCCR4B &= ~prescalerEraser; // this operation sets the three bits in TCCR4B to 0 - // now set those same three bits - - -//----------------------------------------------- -//timer 0 ----- pin 4, 13 -//timer 1 ----- pin 11, 12 -//timer 2 ----- pin 9, 10 -//timer 3 ----- pin 2, 3, 5 -//timer 4 ----- pin 6, 7, 8 -//timer 5 ----- pin 44, 45, 46 -// ————————————————————————————– -// TIMER 2  -// Value Divisor Frequency -// 0x01 1 31.374 KHz -// 0x02 8 3.921 KHz -// 0x03 32 980.3 Hz // don;t use this... -// 0x04 64 490.1 Hz // default -// 0x05 128 245 hz -// 0x06 256 122.5 hz -// 0x07 1024 30.63 hz -// Code: TCCR2B = (TCCR2B & 0xF8) | value ; -// —————————————————————————————- -// Timers 3 & 4 -// -// Value Divisor Frequency -// 0x01 1 31.374 KHz -// 0x02 8 3.921 Khz -// 0x03 64 490.1 Hz        // default -// 0x04 256 122.5 Hz -// 0x05 1024 30.63 Hz -// Code: TCCR3B = (TCCR3B & 0xF8) | value ; -// —————————————————————————————- - // and apply it - if (prescalerChoice >= 3) { - TCCR2B |= (prescalerChoice + 1); // pins 9, 10 - change to match timers3&4 - } else { - TCCR2B |= prescalerChoice; // pins 9, 10 - } - TCCR3B |= prescalerChoice; // pins 2, 3, 5 - TCCR4B |= prescalerChoice; // pins 6, 7, 8 -} - - -// This should likely go away and be handled by setting the pause flag and then -// pausing in the execSystemRealtime function -// Need to check if all returns from this subsequently look to sys.stop -void pause(){ - /* - - The pause command pauses the machine in place without flushing the lines stored in the machine's - buffer. - - When paused the machine enters a while() loop and doesn't exit until the '~' cycle resume command - is issued from Ground Control. - - */ - - bit_true(sys.pause, PAUSE_FLAG_USER_PAUSE); - Serial.println(F("Maslow Paused")); - - while(bit_istrue(sys.pause, PAUSE_FLAG_USER_PAUSE)) { - - // Run realtime commands - execSystemRealtime(); - if (sys.stop){return;} - } -} - - -// This is an important concept. I think maybe this should be expanded and Used -// whenever we have a delay. This should be all of the 'realtime' operations -// and should probably include check for stop command. Although, the holdPosition -// would have to be moved out of here, but I think that is probably correct - -// need to check if all returns from here check for sys.stop -void maslowDelay(unsigned long waitTimeMs) { - /* - * Provides a time delay while holding the machine position, reading serial commands, - * and periodically sending the machine position to Ground Control. This prevents - * Ground Control from thinking that the connection is lost. - * - * This is similar to the pause() command above, but provides a time delay rather than - * waiting for the user (through Ground Control) to tell the machine to continue. - */ - - unsigned long startTime = millis(); - - while ((millis() - startTime) < waitTimeMs){ - execSystemRealtime(); - if (sys.stop){return;} - } -} - -// This executes all of the actions that we want to happen in 'realtime'. This -// should be called whenever there is a delay in the code or when it may have -// been a long time since this command was called. Everything that is executed -// by this command should be relatively fast. Should always check for sys.stop -// after returning from this function -void execSystemRealtime(){ - readSerialCommands(); - returnPoz(); - systemSaveAxesPosition(); - motionDetachIfIdle(); - // check systemRtExecAlarm flag and do stuff -} - -void systemSaveAxesPosition(){ - /* - Save steps of axes to EEPROM if they are all detached - */ - if (!leftAxis.attached() && !rightAxis.attached() && !zAxis.attached()){ - settingsSaveStepstoEEprom(); - } -} - -void systemReset(){ - /* - Stops everything and resets the arduino - */ - leftAxis.detach(); - rightAxis.detach(); - zAxis.detach(); - setSpindlePower(false); - laserOn(false); // EBS - // Reruns the initial setup function and calls stop to re-init state - sys.stop = true; - setup(); -} - -byte systemExecuteCmdstring(String& cmdString){ - /* - This function processes the $ system commands - - This is taken heavily from grbl. https://github.com/grbl/grbl - */ - byte char_counter = 1; -// byte helper_var = 0; // Helper variable - float parameter, value; - if (cmdString.length() == 1){ - reportMaslowHelp(); - } - else { - switch( cmdString[char_counter] ) { - case '$': // case 'G': case 'C': case 'X': - if ( cmdString.length() > 2 ) { return(STATUS_INVALID_STATEMENT); } - switch( cmdString[char_counter] ) { - case '$' : // Prints Maslow settings - // if ( sys.state & (STATE_CYCLE | STATE_HOLD) ) { return(STATUS_IDLE_ERROR); } // Block during cycle. Takes too long to print. - // else { - reportMaslowSettings(); - // } - break; - // case 'G' : // Prints gcode parser state - // report_gcode_modes(); - // break; - // case 'C' : // Set check g-code mode [IDLE/CHECK] - // // Perform reset when toggling off. Check g-code mode should only work if Grbl - // // is idle and ready, regardless of alarm locks. This is mainly to keep things - // // simple and consistent. - // if ( sys.state == STATE_CHECK_MODE ) { - // mc_reset(); - // report_feedback_message(MESSAGE_DISABLED); - // } else { - // if (sys.state) { return(STATUS_IDLE_ERROR); } // Requires no alarm mode. - // sys.state = STATE_CHECK_MODE; - // report_feedback_message(MESSAGE_ENABLED); - // } - // break; - // case 'X' : // Disable alarm lock [ALARM] - // if (sys.state == STATE_ALARM) { - // report_feedback_message(MESSAGE_ALARM_UNLOCK); - // sys.state = STATE_IDLE; - // // Don't run startup script. Prevents stored moves in startup from causing accidents. - // if (system_check_safety_door_ajar()) { // Check safety door switch before returning. - // bit_true(sys_rt_exec_state, EXEC_SAFETY_DOOR); - // protocol_execute_realtime(); // Enter safety door mode. - // } - // } // Otherwise, no effect. - // break; - } - break; - //case 'J' : break; // Jogging methods - // TODO: Here jogging can be placed for execution as a seperate subprogram. It does not need to be - // susceptible to other realtime commands except for e-stop. The jogging function is intended to - // be a basic toggle on/off with controlled acceleration and deceleration to prevent skipped - // steps. The user would supply the desired feedrate, axis to move, and direction. Toggle on would - // start motion and toggle off would initiate a deceleration to stop. One could 'feather' the - // motion by repeatedly toggling to slow the motion to the desired location. Location data would - // need to be updated real-time and supplied to the user through status queries. - // More controlled exact motions can be taken care of by inputting G0 or G1 commands, which are - // handled by the planner. It would be possible for the jog subprogram to insert blocks into the - // block buffer without having the planner plan them. It would need to manage de/ac-celerations - // on its own carefully. This approach could be effective and possibly size/memory efficient. - // break; - // } - //break; - default : - // Block any system command that requires the state as IDLE/ALARM. (i.e. EEPROM, homing) - // if ( !(sys.state == STATE_IDLE || sys.state == STATE_ALARM) ) { return(STATUS_IDLE_ERROR); } - switch( cmdString[char_counter] ) { - // case '#' : // Print Grbl NGC parameters - // if ( line[++char_counter] != 0 ) { return(STATUS_INVALID_STATEMENT); } - // else { report_ngc_parameters(); } - // break; - // case 'H' : // Perform homing cycle [IDLE/ALARM] - // if (bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)) { - // sys.state = STATE_HOMING; // Set system state variable - // // Only perform homing if Grbl is idle or lost. - // - // // TODO: Likely not required. - // if (system_check_safety_door_ajar()) { // Check safety door switch before homing. - // bit_true(sys_rt_exec_state, EXEC_SAFETY_DOOR); - // protocol_execute_realtime(); // Enter safety door mode. - // } - // - // - // mc_homing_cycle(); - // if (!sys.abort) { // Execute startup scripts after successful homing. - // sys.state = STATE_IDLE; // Set to IDLE when complete. - // st_go_idle(); // Set steppers to the settings idle state before returning. - // system_execute_startup(line); - // } - // } else { return(STATUS_SETTING_DISABLED); } - // break; - // case 'I' : // Print or store build info. [IDLE/ALARM] - // if ( line[++char_counter] == 0 ) { - // settings_read_build_info(line); - // report_build_info(line); - // } else { // Store startup line [IDLE/ALARM] - // if(line[char_counter++] != '=') { return(STATUS_INVALID_STATEMENT); } - // helper_var = char_counter; // Set helper variable as counter to start of user info line. - // do { - // line[char_counter-helper_var] = line[char_counter]; - // } while (line[char_counter++] != 0); - // settings_store_build_info(line); - // } - // break; - case 'R' : // Restore defaults [IDLE/ALARM] - if (cmdString[++char_counter] != 'S') { return(STATUS_INVALID_STATEMENT); } - if (cmdString[++char_counter] != 'T') { return(STATUS_INVALID_STATEMENT); } - if (cmdString[++char_counter] != '=') { return(STATUS_INVALID_STATEMENT); } - if (cmdString.length() != 6) { return(STATUS_INVALID_STATEMENT); } - switch (cmdString[++char_counter]) { - case '$': settingsWipe(SETTINGS_RESTORE_SETTINGS); break; - case '#': settingsWipe(SETTINGS_RESTORE_MASLOW); break; - case '*': settingsWipe(SETTINGS_RESTORE_ALL); break; - default: return(STATUS_INVALID_STATEMENT); - } - reportFeedbackMessage(MESSAGE_RESTORE_DEFAULTS); - systemReset(); // Force reset to ensure settings are initialized correctly. - break; - // case 'N' : // Startup lines. [IDLE/ALARM] - // if ( line[++char_counter] == 0 ) { // Print startup lines - // for (helper_var=0; helper_var < N_STARTUP_LINE; helper_var++) { - // if (!(settings_read_startup_line(helper_var, line))) { - // report_status_message(STATUS_SETTING_READ_FAIL); - // } else { - // report_startup_line(helper_var,line); - // } - // } - // break; - // } else { // Store startup line [IDLE Only] Prevents motion during ALARM. - // if (sys.state != STATE_IDLE) { return(STATUS_IDLE_ERROR); } // Store only when idle. - // helper_var = true; // Set helper_var to flag storing method. - // // No break. Continues into default: to read remaining command characters. - // } - default : // Storing setting methods [IDLE/ALARM] - if(!readFloat(cmdString, char_counter, parameter)) { return(STATUS_BAD_NUMBER_FORMAT); } - if(cmdString[char_counter++] != '=') { return(STATUS_INVALID_STATEMENT); } - // if (helper_var) { // Store startup line - // // Prepare sending gcode block to gcode parser by shifting all characters - // helper_var = char_counter; // Set helper variable as counter to start of gcode block - // do { - // line[char_counter-helper_var] = line[char_counter]; - // } while (line[char_counter++] != 0); - // // Execute gcode block to ensure block is valid. - // helper_var = gc_execute_line(line); // Set helper_var to returned status code. - // if (helper_var) { return(helper_var); } - // else { - // helper_var = trunc(parameter); // Set helper_var to int value of parameter - // settings_store_startup_line(helper_var,line); - // } - // } else { // Store global setting. - if(!readFloat(cmdString, char_counter, value)) { return(STATUS_BAD_NUMBER_FORMAT); } - if((cmdString[char_counter] != 0) || (parameter > 255)) { return(STATUS_INVALID_STATEMENT); } - return(settingsStoreGlobalSetting((byte)parameter, value)); - // } - } - } - } - return(STATUS_OK); -} diff --git a/Firmware_1.26b/cnc_ctrl_v1/System.h b/Firmware_1.26b/cnc_ctrl_v1/System.h deleted file mode 100644 index 9e297e47..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/System.h +++ /dev/null @@ -1,94 +0,0 @@ -/*This file is part of the Maslow Control Software. - -The Maslow Control Software is free software: you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation, either version 3 of the License, or -(at your option) any later version. - -Maslow Control Software is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with the Maslow Control Software. If not, see . - -Copyright 2014-2017 Bar Smith*/ - -#ifndef system_h -#define system_h - -// Convenience Defines - Maybe move into a nuts and bolts file? -#define FORWARD 1 -#define BACKWARD -1 -#define CLOCKWISE -1 -#define COUNTERCLOCKWISE 1 -#define MILLIMETERS 1 -#define INCHES 25.4 - -// Define various pause bits -#define PAUSE_FLAG_USER_PAUSE bit(0) // a pause triggered within the code that must be cleared by user using the ~ command - -// Define system state bit map. The state variable primarily tracks the individual functions -// of Maslow to manage each without overlapping. It is also used as a messaging flag for -// critical events. -#define STATE_IDLE 0 // Must be zero. No flags. -#define STATE_ALARM bit(0) // In alarm state. Locks out all g-code processes. Allows settings access. -#define STATE_CHECK_MODE bit(1) // G-code check mode. Locks out planner and motion only. -#define STATE_OLD_SETTINGS bit(2) // Locks out all g-code processes, allows settings access until old settings are loaded -#define STATE_CYCLE bit(3) // Cycle is running or motions are being executed. -#define STATE_HOLD bit(4) // Active feed hold -#define STATE_SAFETY_DOOR bit(5) // Safety door is ajar. Feed holds and de-energizes system. -#define STATE_MOTION_CANCEL bit(6) // Motion cancel by feed hold and return to idle. -#define STATE_POS_ERR_IGNORE bit(7) // Motion not checked for position error - -// Define old settings flag details -#define NEED_ENCODER_STEPS bit(0) -#define NEED_DIST_PER_ROT bit(1) -#define NEED_Z_ENCODER_STEPS bit(2) -#define NEED_Z_DIST_PER_ROT bit(3) - -// Storage for global system states -// Some of this could be more appropriately moved to the gcode parser -typedef struct { - bool stop; // Stop flag. - byte state; // State tracking flag - byte pause; // Pause flag. - float xPosition; // Cartessian position of XY axes - float yPosition; // Cached because calculating position is intensive - float steps[3]; // Encoder position of axes - bool useRelativeUnits; // - unsigned long lastSerialRcvd; // The millis of the last rcvd serial command, used by watchdo - int lastGCommand; //Stores the value of the last command run eg: G01 -> 1 - int lastTool; //Stores the value of the last tool number eg: T4 -> 4 - int nextTool; //Stores the value of the next tool number eg: T4 -> 4 - float inchesToMMConversion; //Used to track whether to convert from inches, can probably be done in a way that doesn't require RAM - float feedrate; //The feedrate of the machine in mm/min - // THE FOLLOWING IS USED FOR IMPORTING SETTINGS FROM FIRMWARE v1.00 AND EARLIER - // It can be deleted at some point - byte oldSettingsFlag; -} system_t; -extern system_t sys; -extern Axis leftAxis; -extern Axis rightAxis; -extern Axis zAxis; -extern RingBuffer incSerialBuffer; -extern Kinematics kinematics; -extern byte systemRtExecAlarm; -extern int SpindlePowerControlPin; -extern int LaserPowerPin; -extern int ProbePin; - -void calibrateChainLengths(String); -void setupAxes(); -int getPCBVersion(); -void pause(); -void maslowDelay(unsigned long); -void execSystemRealtime(); -void systemSaveAxesPosition(); -void systemReset(); -byte systemExecuteCmdstring(String&); -void setPWMPrescalers(int prescalerChoice); -void configAuxLow(int A1, int A2, int A3, int A4, int A5, int A6); -void configAuxHigh(int A7, int A8, int A9); -#endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/Testing.cpp b/Firmware_1.26b/cnc_ctrl_v1/Testing.cpp deleted file mode 100644 index 3f8bfa39..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Testing.cpp +++ /dev/null @@ -1,181 +0,0 @@ -/*This file is part of the Maslow Control Software. - The Maslow Control Software is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - Maslow Control Software is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - You should have received a copy of the GNU General Public License - along with the Maslow Control Software. If not, see . - - Copyright 2014-2017 Bar Smith*/ - -// This file contains various testing provisions - -#include "Maslow.h" - -void PIDTestVelocity(Axis* axis, const float start, const float stop, const float steps, const float version){ - // Moves the defined Axis at series of speed steps for PID tuning - // Start Log - Serial.println(F("--PID Velocity Test Start--")); - Serial.println(axis->motorGearboxEncoder.getPIDString()); - if (version == 2) { - Serial.println(F("setpoint,input,output")); - } - - double startTime; - double print = micros(); - double current = micros(); - float error; - float reportedSpeed; - float span = stop - start; - float speed; - - // Start the steps - axis->disablePositionPID(); - axis->attach(); - for(int i = 0; i < steps; i++){ - // 1 step = start, 2 step = start & finish, 3 = start, start + 1/2 span... - speed = start; - if (i > 0){ - speed = start + (span * (i/(steps-1))); - } - startTime = micros(); - axis->motorGearboxEncoder.write(speed); - while (startTime + 2000000 > current){ - if (current - print > LOOPINTERVAL){ - if (version == 2) { - Serial.println(axis->motorGearboxEncoder.pidState()); - } - else { - reportedSpeed= axis->motorGearboxEncoder.cachedSpeed(); - error = reportedSpeed - speed; - print = current; - Serial.println(error); - } - } - current = micros(); - } - } - axis->motorGearboxEncoder.write(0); - - // Print end of log, and update axis for use again - Serial.println(F("--PID Velocity Test Stop--\n")); - axis->write(axis->read()); - axis->detach(); - axis->enablePositionPID(); - kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition, 0.0, 0.0); -} - -void positionPIDOutput (Axis* axis, float setpoint, float startingPoint){ - Serial.print((setpoint - startingPoint), 4); - Serial.print(F(",")); - Serial.print((axis->pidInput() - startingPoint),4); - Serial.print(F(",")); - Serial.print(axis->pidOutput(),4); - Serial.print(F(",")); - Serial.print(axis->motorGearboxEncoder.cachedSpeed(), 4); - Serial.print(F(",")); - Serial.println(axis->motorGearboxEncoder.motor.lastSpeed()); -} - -void PIDTestPosition(Axis* axis, float start, float stop, const float steps, const float stepTime, const float version){ - // Moves the defined Axis at series of chain distance steps for PID tuning - // Start Log - Serial.println(F("--PID Position Test Start--")); - Serial.println(axis->getPIDString()); - if (version == 2) { - Serial.println(F("setpoint,input,output,rpminput,voltage")); - } - - unsigned long startTime; - unsigned long print = micros(); - unsigned long current = micros(); - float error; - float startingPoint = axis->read(); - start = startingPoint + start; - stop = startingPoint + stop; - float span = stop - start; - float location; - - // Start the steps - axis->attach(); - for(int i = 0; i < steps; i++){ - // 1 step = start, 2 step = start & finish, 3 = start, start + 1/2 span... - location = start; - if (i > 0){ - location = start + (span * (i/(steps-1))); - } - startTime = micros(); - current = micros(); - axis->write(location); - while (startTime + (stepTime * 1000) > current){ - if (current - print > LOOPINTERVAL){ - if (version == 2) { - positionPIDOutput(axis, location, startingPoint); - } - else { - error = axis->read() - location; - Serial.println(error); - } - print = current; - } - current = micros(); - } - } - startTime = micros(); - current = micros(); - //Allow 1 seccond to settle out - while (startTime + 1000000 > current){ - if (current - print > LOOPINTERVAL){ - if (version == 2) { - positionPIDOutput(axis, location, startingPoint); - } - else { - error = axis->read() - location; - Serial.println(error); - } - print = current; - } - current = micros(); - } - // Print end of log, and update axis for use again - Serial.println(F("--PID Position Test Stop--\n")); - axis->write(axis->read()); - axis->detach(); - kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition, 0.0, 0.0); -} - -void voltageTest(Axis* axis, int start, int stop){ - // Moves the defined Axis at a series of voltages and reports the resulting - // RPM - Serial.println(F("--Voltage Test Start--")); - int direction = 1; - if (stop < start){ direction = -1;} - int steps = abs(start - stop); - unsigned long startTime = millis() + 200; - unsigned long currentTime = millis(); - unsigned long printTime = 0; - - for (int i = 0; i <= steps; i++){ - axis->motorGearboxEncoder.motor.directWrite((start + (i*direction))); - while (startTime > currentTime - (i * 200)){ - currentTime = millis(); - if ((printTime + 50) <= currentTime){ - Serial.print((start + (i*direction))); - Serial.print(F(",")); - Serial.print(axis->motorGearboxEncoder.computeSpeed(),4); - Serial.print(F("\n")); - printTime = millis(); - } - } - } - - // Print end of log, and update axis for use again - axis->motorGearboxEncoder.motor.directWrite(0); - Serial.println(F("--Voltage Test Stop--\n")); - axis->write(axis->read()); - kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition, 0.0, 0.0); -} \ No newline at end of file diff --git a/Firmware_1.26b/cnc_ctrl_v1/Testing.h b/Firmware_1.26b/cnc_ctrl_v1/Testing.h deleted file mode 100644 index 4673b012..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/Testing.h +++ /dev/null @@ -1,25 +0,0 @@ -/*This file is part of the Maslow Control Software. - The Maslow Control Software is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - Maslow Control Software is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - You should have received a copy of the GNU General Public License - along with the Maslow Control Software. If not, see . - - Copyright 2014-2017 Bar Smith*/ - -// This file contains various testing provisions - -#ifndef testing_h -#define testing_h - -void PIDTestVelocity(Axis*, const float, const float, const float, const float); -void positionPIDOutput (Axis*, float, float); -void PIDTestPosition(Axis*, float, float, const float, const float, const float); -void voltageTest(Axis*, int, int); - -#endif \ No newline at end of file diff --git a/Firmware_1.26b/cnc_ctrl_v1/TimerOne.cpp b/Firmware_1.26b/cnc_ctrl_v1/TimerOne.cpp deleted file mode 100644 index 5db3b317..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/TimerOne.cpp +++ /dev/null @@ -1,209 +0,0 @@ -/* - * Interrupt and PWM utilities for 16 bit Timer1 on ATmega168/328 - * Original code by Jesse Tane for http://labs.ideo.com August 2008 - * Modified March 2009 by Jérôme Despatis and Jesse Tane for ATmega328 support - * Modified June 2009 by Michael Polli and Jesse Tane to fix a bug in setPeriod() which caused the timer to stop - * Modified June 2011 by Lex Talionis to add a function to read the timer - * Modified Oct 2011 by Andrew Richards to avoid certain problems: - * - Add (long) assignments and casts to TimerOne::read() to ensure calculations involving tmp, ICR1 and TCNT1 aren't truncated - * - Ensure 16 bit registers accesses are atomic - run with interrupts disabled when accessing - * - Remove global enable of interrupts (sei())- could be running within an interrupt routine) - * - Disable interrupts whilst TCTN1 == 0. Datasheet vague on this, but experiment shows that overflow interrupt - * flag gets set whilst TCNT1 == 0, resulting in a phantom interrupt. Could just set to 1, but gets inaccurate - * at very short durations - * - startBottom() added to start counter at 0 and handle all interrupt enabling. - * - start() amended to enable interrupts - * - restart() amended to point at startBottom() - * Modiied 7:26 PM Sunday, October 09, 2011 by Lex Talionis - * - renamed start() to resume() to reflect it's actual role - * - renamed startBottom() to start(). This breaks some old code that expects start to continue counting where it left off - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - * See Google Code project http://code.google.com/p/arduino-timerone/ for latest - */ -#ifndef TIMERONE_cpp -#define TIMERONE_cpp - -#include "Maslow.h" - -TimerOne Timer1; // preinstatiate - -ISR(TIMER1_OVF_vect) // interrupt service routine that wraps a user defined function supplied by attachInterrupt -{ - Timer1.isrCallback(); -} - - -void TimerOne::initialize(long microseconds) -{ - TCCR1A = 0; // clear control register A - TCCR1B = _BV(WGM13); // set mode 8: phase and frequency correct pwm, stop the timer - setPeriod(microseconds); -} - - -void TimerOne::setPeriod(long microseconds) // AR modified for atomic access -{ - - long cycles = (F_CPU / 2000000) * microseconds; // the counter runs backwards after TOP, interrupt is at BOTTOM so divide microseconds by 2 - if(cycles < RESOLUTION) clockSelectBits = _BV(CS10); // no prescale, full xtal - else if((cycles >>= 3) < RESOLUTION) clockSelectBits = _BV(CS11); // prescale by /8 - else if((cycles >>= 3) < RESOLUTION) clockSelectBits = _BV(CS11) | _BV(CS10); // prescale by /64 - else if((cycles >>= 2) < RESOLUTION) clockSelectBits = _BV(CS12); // prescale by /256 - else if((cycles >>= 2) < RESOLUTION) clockSelectBits = _BV(CS12) | _BV(CS10); // prescale by /1024 - else cycles = RESOLUTION - 1, clockSelectBits = _BV(CS12) | _BV(CS10); // request was out of bounds, set as maximum - - oldSREG = SREG; - cli(); // Disable interrupts for 16 bit register access - ICR1 = pwmPeriod = cycles; // ICR1 is TOP in p & f correct pwm mode - SREG = oldSREG; - - TCCR1B &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12)); - TCCR1B |= clockSelectBits; // reset clock select register, and starts the clock -} - -void TimerOne::setPwmDuty(char pin, int duty) -{ - unsigned long dutyCycle = pwmPeriod; - - dutyCycle *= duty; - dutyCycle >>= 10; - - oldSREG = SREG; - cli(); - if(pin == 1 || pin == 9) OCR1A = dutyCycle; - else if(pin == 2 || pin == 10) OCR1B = dutyCycle; - SREG = oldSREG; -} - -void TimerOne::pwm(char pin, int duty, long microseconds) // expects duty cycle to be 10 bit (1024) -{ - if(microseconds > 0) setPeriod(microseconds); - if(pin == 1 || pin == 9) { - DDRB |= _BV(PORTB1); // sets data direction register for pwm output pin - TCCR1A |= _BV(COM1A1); // activates the output pin - } - else if(pin == 2 || pin == 10) { - DDRB |= _BV(PORTB2); - TCCR1A |= _BV(COM1B1); - } - setPwmDuty(pin, duty); - resume(); // Lex - make sure the clock is running. We don't want to restart the count, in case we are starting the second WGM - // and the first one is in the middle of a cycle -} - -void TimerOne::disablePwm(char pin) -{ - if(pin == 1 || pin == 9) TCCR1A &= ~_BV(COM1A1); // clear the bit that enables pwm on PB1 - else if(pin == 2 || pin == 10) TCCR1A &= ~_BV(COM1B1); // clear the bit that enables pwm on PB2 -} - -void TimerOne::attachInterrupt(void (*isr)(), long microseconds) -{ - if(microseconds > 0) setPeriod(microseconds); - isrCallback = isr; // register the user's callback with the real ISR - TIMSK1 = _BV(TOIE1); // sets the timer overflow interrupt enable bit - // might be running with interrupts disabled (eg inside an ISR), so don't touch the global state -// sei(); - resume(); -} - -void TimerOne::detachInterrupt() -{ - TIMSK1 &= ~_BV(TOIE1); // clears the timer overflow interrupt enable bit - // timer continues to count without calling the isr -} - -void TimerOne::resume() // AR suggested -{ - TCCR1B |= clockSelectBits; -} - -void TimerOne::restart() // Depricated - Public interface to start at zero - Lex 10/9/2011 -{ - start(); -} - -void TimerOne::start() // AR addition, renamed by Lex to reflect it's actual role -{ - unsigned int tcnt1; - - TIMSK1 &= ~_BV(TOIE1); // AR added - GTCCR |= _BV(PSRSYNC); // AR added - reset prescaler (NB: shared with all 16 bit timers); - - oldSREG = SREG; // AR - save status register - cli(); // AR - Disable interrupts - TCNT1 = 0; - SREG = oldSREG; // AR - Restore status register - resume(); - do { // Nothing -- wait until timer moved on from zero - otherwise get a phantom interrupt - oldSREG = SREG; - cli(); - tcnt1 = TCNT1; - SREG = oldSREG; - } while (tcnt1==0); - -// TIFR1 = 0xff; // AR - Clear interrupt flags -// TIMSK1 = _BV(TOIE1); // sets the timer overflow interrupt enable bit -} - -void TimerOne::stop() -{ - TCCR1B &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12)); // clears all clock selects bits -} - -unsigned long TimerOne::read() //returns the value of the timer in microseconds -{ //rember! phase and freq correct mode counts up to then down again - unsigned long tmp; // AR amended to hold more than 65536 (could be nearly double this) - unsigned int tcnt1; // AR added - - oldSREG= SREG; - cli(); - tmp=TCNT1; - SREG = oldSREG; - - char scale=0; - switch (clockSelectBits) - { - case 1:// no prescalse - scale=0; - break; - case 2:// x8 prescale - scale=3; - break; - case 3:// x64 - scale=6; - break; - case 4:// x256 - scale=8; - break; - case 5:// x1024 - scale=10; - break; - } - - do { // Nothing -- max delay here is ~1023 cycles. AR modified - oldSREG = SREG; - cli(); - tcnt1 = TCNT1; - SREG = oldSREG; - } while (tcnt1==tmp); //if the timer has not ticked yet - - //if we are counting down add the top value to how far we have counted down - tmp = ( (tcnt1>tmp) ? (tmp) : (long)(ICR1-tcnt1)+(long)ICR1 ); // AR amended to add casts and reuse previous TCNT1 - return ((tmp*1000L)/(F_CPU /1000L))<. - * - * See Google Code project http://code.google.com/p/arduino-timerone/ for latest - */ -#ifndef TIMERONE_h -#define TIMERONE_h - -#define RESOLUTION 65536 // Timer1 is 16 bit - -class TimerOne -{ - public: - - // properties - unsigned int pwmPeriod; - unsigned char clockSelectBits; - char oldSREG; // To hold Status Register while ints disabled - - // methods - void initialize(long microseconds=1000000); - void start(); - void stop(); - void restart(); - void resume(); - unsigned long read(); - void pwm(char pin, int duty, long microseconds=-1); - void disablePwm(char pin); - void attachInterrupt(void (*isr)(), long microseconds=-1); - void detachInterrupt(); - void setPeriod(long microseconds); - void setPwmDuty(char pin, int duty); - void (*isrCallback)(); -}; - -extern TimerOne Timer1; -#endif \ No newline at end of file diff --git a/Firmware_1.26b/cnc_ctrl_v1/cnc_ctrl_v1.ino b/Firmware_1.26b/cnc_ctrl_v1/cnc_ctrl_v1.ino deleted file mode 100644 index 3523f955..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/cnc_ctrl_v1.ino +++ /dev/null @@ -1,120 +0,0 @@ -/*This file is part of the Maslow Control Software. - The Maslow Control Software is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - Maslow Control Software is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - You should have received a copy of the GNU General Public License - along with the Maslow Control Software. If not, see . - - Copyright 2014-2017 Bar Smith*/ - - -/* To the projects contributers: - * - * it is highly recommended to activate warning output of the arduino gcc compiler. - * Compiler warnings are a great help to keep the codebase clean and can give clues - * to potentally wrong code. Also, if a codebase produces too many warnings it gets - * more likely that possibly important warnings could be overlooked. - * - * Since the Arduino IDE suppresses any compiler output by default we have to activate it. - * - * Therefore Arduino IDE users need to activate compiler output in the - * preferences dialog. Additionally Arduino IDE needs to tell the compiler to generate - * warning messages. This is done in the Arduino IDE's preferences.txt file - you can - * get there via the Preferences Dialog - there is a link to the file at the bottom. - * Edit the line "compiler.warning_level=none" to "compiler.warning_level=all" - * and restart the IDE. - */ - - -// TLE5206 v1.4 -// EastBaySource TB6643 V1.5 - -#include "Maslow.h" - -// Define system global state structure -system_t sys; - -// Define the global settings storage - treat as readonly -settings_t sysSettings; - -// Global realtime executor bitflag variable for setting various alarms. -byte systemRtExecAlarm; - -// Define axes, it might be tighter to define these within the sys struct -Axis leftAxis; -Axis rightAxis; -Axis zAxis; - -// Define kinematics, is it necessary for this to be a class? Is this really -// going to be reused? -Kinematics kinematics; - -void setup(){ - Serial.begin(57600); - Serial.print(F("PCB v1.")); - Serial.print(getPCBVersion()); - if (TLE5206 == true) { Serial.print(F(" TLE5206 ")); } - Serial.println(F(" Detected")); - sys.inchesToMMConversion = 1; - settingsLoadFromEEprom(); - setupAxes(); - settingsLoadStepsFromEEprom(); - // Set initial desired position of the machine to its current position - leftAxis.write(leftAxis.read()); - rightAxis.write(rightAxis.read()); - zAxis.write(zAxis.read()); - readyCommandString.reserve(INCBUFFERLENGTH); //Allocate memory so that this string doesn't fragment the heap as it grows and shrinks - gcodeLine.reserve(INCBUFFERLENGTH); - - #ifndef SIMAVR // Using the timer will crash simavr, so we disable it. - // Instead, we'll run runsOnATimer periodically in loop(). - Timer1.initialize(LOOPINTERVAL); - Timer1.attachInterrupt(runsOnATimer); - #endif - - Serial.println(F("Grbl v1.00")); // Why GRBL? Apparently because some programs are silly and look for this as an initialization command - Serial.println(F("ready")); - reportStatusMessage(STATUS_OK); - -} - -void runsOnATimer(){ - #if misloopDebug > 0 - if (inMovementLoop && !movementUpdated){ - movementFail = true; - } - #endif - movementUpdated = false; - leftAxis.computePID(); - rightAxis.computePID(); - zAxis.computePID(); -} - -void loop(){ - // This section is called on startup and whenever a stop command is issued - initGCode(); - if (sys.stop){ // only called on sys.stop to prevent stopping - initMotion(); // on USB disconnect. Might consider removing - setSpindlePower(false); // this restriction for safety if we are - laserOn(false); // EBS added laser - } // comfortable that USB disconnects are - // not a common occurrence anymore - kinematics.init(); - - // Let's go! - sys.stop = false; // We should consider an abort option which - // is not reset automatically such as a software - // limit - while (!sys.stop){ - gcodeExecuteLoop(); - #ifdef SIMAVR // Normally, runsOnATimer() will, well, run on a timer. See also setup(). - runsOnATimer(); - #endif - execSystemRealtime(); - } -} diff --git a/Firmware_1.26b/cnc_ctrl_v1/utility/direct_pin_read.h b/Firmware_1.26b/cnc_ctrl_v1/utility/direct_pin_read.h deleted file mode 100644 index 97b88620..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/utility/direct_pin_read.h +++ /dev/null @@ -1,27 +0,0 @@ -#ifndef direct_pin_read_h_ -#define direct_pin_read_h_ - -#if defined(__AVR__) || defined(__MK20DX128__) || defined(__MK20DX256__) - -#define IO_REG_TYPE uint8_t -#define PIN_TO_BASEREG(pin) (portInputRegister(digitalPinToPort(pin))) -#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin)) -#define DIRECT_PIN_READ(base, mask) (((*(base)) & (mask)) ? 1 : 0) - -#elif defined(__SAM3X8E__) - -#define IO_REG_TYPE uint32_t -#define PIN_TO_BASEREG(pin) (portInputRegister(digitalPinToPort(pin))) -#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin)) -#define DIRECT_PIN_READ(base, mask) (((*(base)) & (mask)) ? 1 : 0) - -#elif defined(__PIC32MX__) - -#define IO_REG_TYPE uint32_t -#define PIN_TO_BASEREG(pin) (portModeRegister(digitalPinToPort(pin))) -#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin)) -#define DIRECT_PIN_READ(base, mask) (((*(base+4)) & (mask)) ? 1 : 0) - -#endif - -#endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/utility/interrupt_config.h b/Firmware_1.26b/cnc_ctrl_v1/utility/interrupt_config.h deleted file mode 100644 index cde6adf2..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/utility/interrupt_config.h +++ /dev/null @@ -1,87 +0,0 @@ -#if defined(__AVR__) - -#include -#include - -#define attachInterrupt(num, func, mode) enableInterrupt(num) -#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) -#define SCRAMBLE_INT_ORDER(num) ((num < 4) ? num + 2 : ((num < 6) ? num - 4 : num)) -#define DESCRAMBLE_INT_ORDER(num) ((num < 2) ? num + 4 : ((num < 6) ? num - 2 : num)) -#else -#define SCRAMBLE_INT_ORDER(num) (num) -#define DESCRAMBLE_INT_ORDER(num) (num) -#endif - -static void enableInterrupt(uint8_t num) -{ - switch (DESCRAMBLE_INT_ORDER(num)) { - #if defined(EICRA) && defined(EIMSK) - case 0: - EICRA = (EICRA & 0xFC) | 0x01; - EIMSK |= 0x01; - return; - case 1: - EICRA = (EICRA & 0xF3) | 0x04; - EIMSK |= 0x02; - return; - case 2: - EICRA = (EICRA & 0xCF) | 0x10; - EIMSK |= 0x04; - return; - case 3: - EICRA = (EICRA & 0x3F) | 0x40; - EIMSK |= 0x08; - return; - #elif defined(MCUCR) && defined(GICR) - case 0: - MCUCR = (MCUCR & ~((1 << ISC00) | (1 << ISC01))) | (mode << ISC00); - GICR |= (1 << INT0); - return; - case 1: - MCUCR = (MCUCR & ~((1 << ISC10) | (1 << ISC11))) | (mode << ISC10); - GICR |= (1 << INT1); - return; - #elif defined(MCUCR) && defined(GIMSK) - case 0: - MCUCR = (MCUCR & ~((1 << ISC00) | (1 << ISC01))) | (mode << ISC00); - GIMSK |= (1 << INT0); - return; - case 1: - MCUCR = (MCUCR & ~((1 << ISC10) | (1 << ISC11))) | (mode << ISC10); - GIMSK |= (1 << INT1); - return; - #endif - #if defined(EICRB) && defined(EIMSK) - case 4: - EICRB = (EICRB & 0xFC) | 0x01; - EIMSK |= 0x10; - return; - case 5: - EICRB = (EICRB & 0xF3) | 0x04; - EIMSK |= 0x20; - return; - case 6: - EICRB = (EICRB & 0xCF) | 0x10; - EIMSK |= 0x40; - return; - case 7: - EICRB = (EICRB & 0x3F) | 0x40; - EIMSK |= 0x80; - return; - #endif - } -} - -#elif defined(__PIC32MX__) - -#ifdef ENCODER_OPTIMIZE_INTERRUPTS -#undef ENCODER_OPTIMIZE_INTERRUPTS -#endif - -#else - -#ifdef ENCODER_OPTIMIZE_INTERRUPTS -#undef ENCODER_OPTIMIZE_INTERRUPTS -#endif - -#endif diff --git a/Firmware_1.26b/cnc_ctrl_v1/utility/interrupt_pins.h b/Firmware_1.26b/cnc_ctrl_v1/utility/interrupt_pins.h deleted file mode 100644 index e677c4f8..00000000 --- a/Firmware_1.26b/cnc_ctrl_v1/utility/interrupt_pins.h +++ /dev/null @@ -1,156 +0,0 @@ -// interrupt pins for known boards - -// Teensy (and maybe others) define these automatically -#if !defined(CORE_NUM_INTERRUPT) - -// Wiring boards -#if defined(WIRING) - #define CORE_NUM_INTERRUPT NUM_EXTERNAL_INTERRUPTS - #if NUM_EXTERNAL_INTERRUPTS > 0 - #define CORE_INT0_PIN EI0 - #endif - #if NUM_EXTERNAL_INTERRUPTS > 1 - #define CORE_INT1_PIN EI1 - #endif - #if NUM_EXTERNAL_INTERRUPTS > 2 - #define CORE_INT2_PIN EI2 - #endif - #if NUM_EXTERNAL_INTERRUPTS > 3 - #define CORE_INT3_PIN EI3 - #endif - #if NUM_EXTERNAL_INTERRUPTS > 4 - #define CORE_INT4_PIN EI4 - #endif - #if NUM_EXTERNAL_INTERRUPTS > 5 - #define CORE_INT5_PIN EI5 - #endif - #if NUM_EXTERNAL_INTERRUPTS > 6 - #define CORE_INT6_PIN EI6 - #endif - #if NUM_EXTERNAL_INTERRUPTS > 7 - #define CORE_INT7_PIN EI7 - #endif - -// Arduino Uno, Duemilanove, Diecimila, LilyPad, Mini, Fio, etc... -#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega8__) - #define CORE_NUM_INTERRUPT 2 - #define CORE_INT0_PIN 2 - #define CORE_INT1_PIN 3 - -// Arduino Mega -#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) - #define CORE_NUM_INTERRUPT 6 - #define CORE_INT0_PIN 2 - #define CORE_INT1_PIN 3 - #define CORE_INT2_PIN 21 - #define CORE_INT3_PIN 20 - #define CORE_INT4_PIN 19 - #define CORE_INT5_PIN 18 - -// Arduino Leonardo (untested) -#elif defined(__AVR_ATmega32U4__) && !defined(CORE_TEENSY) - #define CORE_NUM_INTERRUPT 4 - #define CORE_INT0_PIN 3 - #define CORE_INT1_PIN 2 - #define CORE_INT2_PIN 0 - #define CORE_INT3_PIN 1 - -// Sanguino (untested) -#elif defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644__) - #define CORE_NUM_INTERRUPT 3 - #define CORE_INT0_PIN 10 - #define CORE_INT1_PIN 11 - #define CORE_INT2_PIN 2 - -// Chipkit Uno32 - attachInterrupt may not support CHANGE option -#elif defined(__PIC32MX__) && defined(_BOARD_UNO_) - #define CORE_NUM_INTERRUPT 5 - #define CORE_INT0_PIN 38 - #define CORE_INT1_PIN 2 - #define CORE_INT2_PIN 7 - #define CORE_INT3_PIN 8 - #define CORE_INT4_PIN 35 - -// Chipkit Uno32 - attachInterrupt may not support CHANGE option -#elif defined(__PIC32MX__) && defined(_BOARD_MEGA_) - #define CORE_NUM_INTERRUPT 5 - #define CORE_INT0_PIN 3 - #define CORE_INT1_PIN 2 - #define CORE_INT2_PIN 7 - #define CORE_INT3_PIN 21 - #define CORE_INT4_PIN 20 - -// http://hlt.media.mit.edu/?p=1229 -#elif defined(__AVR_ATtiny45__) || defined(__AVR_ATtiny85__) - #define CORE_NUM_INTERRUPT 1 - #define CORE_INT0_PIN 2 - -// Arduino Due (untested) -#elif defined(__SAM3X8E__) - #define CORE_NUM_INTERRUPT 54 - #define CORE_INT0_PIN 0 - #define CORE_INT1_PIN 1 - #define CORE_INT2_PIN 2 - #define CORE_INT3_PIN 3 - #define CORE_INT4_PIN 4 - #define CORE_INT5_PIN 5 - #define CORE_INT6_PIN 6 - #define CORE_INT7_PIN 7 - #define CORE_INT8_PIN 8 - #define CORE_INT9_PIN 9 - #define CORE_INT10_PIN 10 - #define CORE_INT11_PIN 11 - #define CORE_INT12_PIN 12 - #define CORE_INT13_PIN 13 - #define CORE_INT14_PIN 14 - #define CORE_INT15_PIN 15 - #define CORE_INT16_PIN 16 - #define CORE_INT17_PIN 17 - #define CORE_INT18_PIN 18 - #define CORE_INT19_PIN 19 - #define CORE_INT20_PIN 20 - #define CORE_INT21_PIN 21 - #define CORE_INT22_PIN 22 - #define CORE_INT23_PIN 23 - #define CORE_INT24_PIN 24 - #define CORE_INT25_PIN 25 - #define CORE_INT26_PIN 26 - #define CORE_INT27_PIN 27 - #define CORE_INT28_PIN 28 - #define CORE_INT29_PIN 29 - #define CORE_INT30_PIN 30 - #define CORE_INT31_PIN 31 - #define CORE_INT32_PIN 32 - #define CORE_INT33_PIN 33 - #define CORE_INT34_PIN 34 - #define CORE_INT35_PIN 35 - #define CORE_INT36_PIN 36 - #define CORE_INT37_PIN 37 - #define CORE_INT38_PIN 38 - #define CORE_INT39_PIN 39 - #define CORE_INT40_PIN 40 - #define CORE_INT41_PIN 41 - #define CORE_INT42_PIN 42 - #define CORE_INT43_PIN 43 - #define CORE_INT44_PIN 44 - #define CORE_INT45_PIN 45 - #define CORE_INT46_PIN 46 - #define CORE_INT47_PIN 47 - #define CORE_INT48_PIN 48 - #define CORE_INT49_PIN 49 - #define CORE_INT50_PIN 50 - #define CORE_INT51_PIN 51 - #define CORE_INT52_PIN 52 - #define CORE_INT53_PIN 53 - -#endif -#endif - -#if !defined(CORE_NUM_INTERRUPT) -#error "Interrupts are unknown for this board, please add to this code" -#endif -#if CORE_NUM_INTERRUPT <= 0 -#error "Encoder requires interrupt pins, but this board does not have any :(" -#error "You could try defining ENCODER_DO_NOT_USE_INTERRUPTS as a kludge." -#endif - diff --git a/Firmware_1.26b/platformio.ini b/Firmware_1.26b/platformio.ini deleted file mode 100644 index 6dd2a572..00000000 --- a/Firmware_1.26b/platformio.ini +++ /dev/null @@ -1,38 +0,0 @@ -; PlatformIO Project Configuration File -; -; Build options: build flags, source filter -; Upload options: custom upload port, speed and extra flags -; Library options: dependencies, extra library storages -; Advanced options: extra scripting -; -; Please visit documentation for the other options and examples -; http://docs.platformio.org/page/projectconf.html - -[platformio] -src_dir = cnc_ctrl_v1 - -[env:megaatmega2560] -platform = atmelavr -board = megaatmega2560 -framework = arduino - -[env:simavr] -platform = atmelavr -board = megaatmega2560 -framework = arduino -extra_scripts = platformio/simavr_env.py -build_unflags = -Os -build_flags = -g -O0 -DSIMAVR -DFAKE_SERVO -monitor_port = /tmp/simavr-uart0 - -;[env:teensy36] -;platform = teensy -;board = teensy36 -;framework = arduino -;extra_scripts = platformio/teensy_env.py - -;[env:teensy35] -;platform = teensy -;board = teensy35 -;framework = arduino -;extra_scripts = platformio/teensy_env.py diff --git a/Firmware_1.26b/platformio/simavr_env.py b/Firmware_1.26b/platformio/simavr_env.py deleted file mode 100644 index ab5b46bc..00000000 --- a/Firmware_1.26b/platformio/simavr_env.py +++ /dev/null @@ -1,21 +0,0 @@ -from SCons.Script import ARGUMENTS, AlwaysBuild - -Import('env') - -# Run the linker with "-g", to prevent stripping of debugging symbols -env.Append( - LINKFLAGS=[ - "-g" - ] -) - -# Don't try to upload the firmware -env.Replace(UPLOADHEXCMD="echo Upload is not supported for ${PIOENV}. Skipping") - -pioenv = env.get("PIOENV") -progname = env.get("PROGNAME") - -def simulate_callback(*args, **kwargs): - env.Execute("./simduino/simduino .pioenvs/" + pioenv + "/" + progname + ".elf") - -AlwaysBuild(env.Alias("simulate", "", simulate_callback)) diff --git a/Firmware_1.26b/platformio/teensy_env.py b/Firmware_1.26b/platformio/teensy_env.py deleted file mode 100644 index 0f0265e5..00000000 --- a/Firmware_1.26b/platformio/teensy_env.py +++ /dev/null @@ -1,12 +0,0 @@ -import os - -Import('env') - -varname = env.get("PIOENV") + "_UPLOAD" - -if varname in os.environ: - print "$"+ varname + " is set, enabling upload." -else: - # Don't try to upload the firmware - env.Replace(UPLOADHEXCMD="echo Upload is disabled by default for ${PIOENV}. " + - "To enable upload, set " + varname + "environment variable")