From d0229e1ddb1869a26537d1ce7aac4ab4c6865098 Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Fri, 16 Feb 2018 19:42:33 -0800 Subject: [PATCH 01/19] bring current --- cnc_ctrl_v1/Config.h | 14 ++- cnc_ctrl_v1/GCode.cpp | 4 +- cnc_ctrl_v1/GCode.h | 2 + cnc_ctrl_v1/Kinematics.cpp | 11 ++- cnc_ctrl_v1/Kinematics.h | 2 +- cnc_ctrl_v1/Maslow.h | 4 +- cnc_ctrl_v1/Motor.cpp | 131 +++++++++++++-------------- cnc_ctrl_v1/Motor.h | 2 +- cnc_ctrl_v1/Report.cpp | 140 +++++++++++++++-------------- cnc_ctrl_v1/Settings.cpp | 33 ++++--- cnc_ctrl_v1/Settings.h | 6 +- cnc_ctrl_v1/Spindle.cpp | 2 +- cnc_ctrl_v1/System.cpp | 172 ++++++++++++++++++++++++++++++++++-- cnc_ctrl_v1/System.h | 4 +- cnc_ctrl_v1/Testing.cpp | 6 +- cnc_ctrl_v1/cnc_ctrl_v1.ino | 13 +-- 16 files changed, 360 insertions(+), 186 deletions(-) mode change 100644 => 100755 cnc_ctrl_v1/Motor.cpp diff --git a/cnc_ctrl_v1/Config.h b/cnc_ctrl_v1/Config.h index 64574afa..b0834fed 100644 --- a/cnc_ctrl_v1/Config.h +++ b/cnc_ctrl_v1/Config.h @@ -32,13 +32,11 @@ #define LOOPINTERVAL 10000 // What is the frequency of the PID loop in microseconds -// Define extra pins -#define AUX1 17 -#define AUX2 16 -#define AUX3 15 -#define AUX4 14 -#define SpindlePowerControlPin AUX1 // output for controlling spindle power -#define ProbePin AUX4 // use this input for zeroing zAxis with G38.2 gcode +// Define version detect pins +#define VERS1 22 +#define VERS2 23 +#define VERS3 24 +#define VERS4 25 // Serial variables #define INCBUFFERLENGTH 128 // The number of bytes(characters) allocated to the @@ -58,4 +56,4 @@ // smooth. This is only a minimum, and the actual // timeout could be significantly larger. -#endif \ No newline at end of file +#endif diff --git a/cnc_ctrl_v1/GCode.cpp b/cnc_ctrl_v1/GCode.cpp index 3b135cbb..2cb0e4ca 100644 --- a/cnc_ctrl_v1/GCode.cpp +++ b/cnc_ctrl_v1/GCode.cpp @@ -191,7 +191,7 @@ byte executeBcodeLine(const String& gcodeLine){ Serial.print(rightAxis.read()); Serial.println(F("mm")); - kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition); + kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition, 0, 0); Serial.println(F("Message: The machine chains have been manually re-calibrated.")); @@ -311,7 +311,7 @@ byte executeBcodeLine(const String& gcodeLine){ singleAxisMove(&rightAxis, chainLengthAtMiddle, 800); //Reload the position - kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition); + kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition, 0, 0); return STATUS_OK; } diff --git a/cnc_ctrl_v1/GCode.h b/cnc_ctrl_v1/GCode.h index a64a9e1a..1547d35b 100644 --- a/cnc_ctrl_v1/GCode.h +++ b/cnc_ctrl_v1/GCode.h @@ -43,5 +43,7 @@ int G2(const String&, int); void G10(const String&); void G38(const String&); void setInchesToMillimetersConversion(float); +extern int SpindlePowerControlPin; +extern int ProbePin; #endif \ No newline at end of file diff --git a/cnc_ctrl_v1/Kinematics.cpp b/cnc_ctrl_v1/Kinematics.cpp index af96b6e8..9bd8cb19 100644 --- a/cnc_ctrl_v1/Kinematics.cpp +++ b/cnc_ctrl_v1/Kinematics.cpp @@ -30,7 +30,7 @@ Kinematics::Kinematics(){ void Kinematics::init(){ recomputeGeometry(); if (sys.state != STATE_OLD_SETTINGS){ - forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition); + forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition, sys.xPosition, sys.yPosition); } } @@ -48,6 +48,7 @@ void Kinematics::recomputeGeometry(){ 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; @@ -246,12 +247,10 @@ void Kinematics::triangularInverse(float xTarget,float yTarget, float* aChainLe *bChainLength = Chain2; } -void Kinematics::forward(const float& chainALength, const float& chainBLength, float* xPos, float* yPos){ +void Kinematics::forward(const float& chainALength, const float& chainBLength, float* xPos, float* yPos, float xGuess, float yGuess){ Serial.println(F("[Forward Calculating Position]")); - float xGuess = 0; - float yGuess = 0; float guessLengthA; float guessLengthB; @@ -288,8 +287,8 @@ void Kinematics::forward(const float& chainALength, const float& chainBLength, // 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){ - if(guessCount > KINEMATICSMAXGUESS){ + 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(", "); diff --git a/cnc_ctrl_v1/Kinematics.h b/cnc_ctrl_v1/Kinematics.h index 0a0b2a68..92fa33df 100644 --- a/cnc_ctrl_v1/Kinematics.h +++ b/cnc_ctrl_v1/Kinematics.h @@ -34,7 +34,7 @@ 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); + 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 diff --git a/cnc_ctrl_v1/Maslow.h b/cnc_ctrl_v1/Maslow.h index 5e92d42e..40954186 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 1.05 +#define VERSIONNUMBER 1.07 // Define standard libraries used by maslow. #include @@ -49,4 +49,4 @@ #include "NutsAndBolts.h" #include "System.h" -#endif \ No newline at end of file +#endif diff --git a/cnc_ctrl_v1/Motor.cpp b/cnc_ctrl_v1/Motor.cpp old mode 100644 new mode 100755 index e69667a7..841adf31 --- a/cnc_ctrl_v1/Motor.cpp +++ b/cnc_ctrl_v1/Motor.cpp @@ -38,16 +38,25 @@ int Motor::setupMotor(const int& pwmPin, const int& pin1, const int& pin2){ _pin2 = pin2; _attachedState = 0; + if (TLE5206 == false) { //set pinmodes - pinMode(_pwmPin, OUTPUT); - pinMode(_pin1, OUTPUT); - pinMode(_pin2, OUTPUT); - - //stop the motor - digitalWrite(_pin1, HIGH); - digitalWrite(_pin2, LOW) ; - digitalWrite(_pwmPin, LOW); - + pinMode(_pwmPin, OUTPUT); + pinMode(_pin1, OUTPUT); + pinMode(_pin2, OUTPUT); + + //stop the motor + digitalWrite(_pin1, HIGH); + digitalWrite(_pin2, LOW) ; + digitalWrite(_pwmPin, LOW); + } else { + pinMode(_pwmPin, INPUT); + pinMode(_pin1, OUTPUT); + pinMode(_pin2, OUTPUT); + + //stop the motor + digitalWrite(_pin1, LOW); + digitalWrite(_pin2, LOW) ; + } return 1; } @@ -58,10 +67,16 @@ void Motor::attach(){ void Motor::detach(){ _attachedState = 0; + if (TLE5206 == false) { //stop the motor digitalWrite(_pin1, HIGH); digitalWrite(_pin2, LOW) ; digitalWrite(_pwmPin, LOW); + } else { + //stop the motor + digitalWrite(_pin1, LOW); + digitalWrite(_pin2, LOW) ; + } } int Motor::lastSpeed(){ @@ -87,32 +102,33 @@ void Motor::write(int speed){ _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 - - if(_pwmPin == 12){ - if (forward){ - analogWrite(_pin1 , speed); // PWM on this pin to avoid using pin12 (timer1) - digitalWrite(_pin2, LOW); // this pin sets direction with respect to _pin1 - digitalWrite(_pwmPin, HIGH); // this pin enables the outputs of the other two - } - else if (speed == 0){ - } - else{ - analogWrite(_pin1 , 255 - speed); // PWM signal is inverted to cause reverse motion - digitalWrite(_pin2, HIGH); // setting this pin HIGH causes _pin1 PWM to drive reverse - digitalWrite(_pwmPin, HIGH); // enable the output - } - } else { - if (forward){ - digitalWrite(_pin1 , HIGH); - digitalWrite(_pin2 , LOW ); - } - else if (speed == 0){ - } - else{ - digitalWrite(_pin1 , LOW); - digitalWrite(_pin2 , HIGH ); + + 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 + 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 ); } - analogWrite(_pwmPin, speed); + } else { + digitalWrite(_pin1 , LOW ); + digitalWrite(_pin2 , LOW ); + } + } else{ + if (usePin1) { + analogWrite(_pin1 , 255 - speed); // invert drive signals - don't alter speed + digitalWrite(_pin2 , HIGH ); + } else { + analogWrite(_pin2 , speed); + digitalWrite(_pin1 , LOW ); + } + } + if (TLE5206 == false) { + digitalWrite(_pwmPin, HIGH); } } } @@ -121,36 +137,23 @@ void Motor::directWrite(int voltage){ /* Write directly to the motor, ignoring if the axis is attached or any applied calibration. */ - - if(_pwmPin == 12){ - if (voltage > 0){ - analogWrite(_pin1 , abs(voltage)); // PWM on this pin to avoid using pin12 (timer1) - digitalWrite(_pin2, LOW); // this pin sets direction with respect to _pin1 - digitalWrite(_pwmPin, HIGH); // this pin enables the outputs of the other two + bool forward = (voltage >= 0); + if (forward) { + if (voltage > 0) { + digitalWrite(_pin1 , HIGH ); + analogWrite(_pin2 , 255 - abs(voltage)); // invert drive signals - don't alter speed + } else { + digitalWrite(_pin1 , LOW ); + digitalWrite(_pin2 , LOW ); } - else if (voltage == 0){ - voltage = voltage; - } - else{ - analogWrite(_pin1 , 255 - abs(voltage)); // PWM signal is inverted to cause reverse motion - digitalWrite(_pin2, HIGH); // setting this pin HIGH causes _pin1 PWM to drive reverse - digitalWrite(_pwmPin, HIGH); // enable the output - } - } - else{ - if (voltage > 0){ - digitalWrite(_pin1 , HIGH); - digitalWrite(_pin2 , LOW ); - } - else if (voltage == 0){ - voltage = voltage; - } - else{ - digitalWrite(_pin1 , LOW); - digitalWrite(_pin2 , HIGH ); - } - analogWrite(_pwmPin, abs(voltage)); - } + } + else{ + analogWrite(_pin1 , 255 - abs(voltage)); // invert drive signals - don't alter speed + digitalWrite(_pin2 , HIGH ); + } + if (TLE5206 == false) { + digitalWrite(_pwmPin, HIGH); + } } int Motor::attached(){ @@ -190,4 +193,4 @@ void Motor::setSegment(const int& index, const float& slope, const float& interc LinSegment Motor::getSegment(const int& index){ return _linSegments[index]; -} \ No newline at end of file +} diff --git a/cnc_ctrl_v1/Motor.h b/cnc_ctrl_v1/Motor.h index 9b60e3e9..0ee54bfd 100644 --- a/cnc_ctrl_v1/Motor.h +++ b/cnc_ctrl_v1/Motor.h @@ -52,5 +52,5 @@ int _lastSpeed = 0; }; - + extern bool TLE5206; #endif \ No newline at end of file diff --git a/cnc_ctrl_v1/Report.cpp b/cnc_ctrl_v1/Report.cpp index 4b1a1948..6087b19f 100644 --- a/cnc_ctrl_v1/Report.cpp +++ b/cnc_ctrl_v1/Report.cpp @@ -128,82 +128,87 @@ 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); - Serial.print(F("$1=")); Serial.println(sysSettings.machineHeight); - Serial.print(F("$2=")); Serial.println(sysSettings.distBetweenMotors); - Serial.print(F("$3=")); Serial.println(sysSettings.motorOffsetY); - Serial.print(F("$4=")); Serial.println(sysSettings.sledWidth); - Serial.print(F("$5=")); Serial.println(sysSettings.sledHeight); - Serial.print(F("$6=")); Serial.println(sysSettings.sledCG); + 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); + 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); - Serial.print(F("$13=")); Serial.println(sysSettings.distPerRot); + 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.zAxisAuto); - Serial.print(F("$18=")); Serial.println(sysSettings.maxZRPM); - Serial.print(F("$19=")); Serial.println(sysSettings.zDistPerRot); - Serial.print(F("$20=")); Serial.println(sysSettings.zEncoderSteps); - Serial.print(F("$21=")); Serial.println(sysSettings.KpPos); - Serial.print(F("$22=")); Serial.println(sysSettings.KiPos); - Serial.print(F("$23=")); Serial.println(sysSettings.KdPos); - Serial.print(F("$24=")); Serial.println(sysSettings.propWeightPos); - Serial.print(F("$25=")); Serial.println(sysSettings.KpV); - Serial.print(F("$26=")); Serial.println(sysSettings.KiV); - Serial.print(F("$27=")); Serial.println(sysSettings.KdV); - Serial.print(F("$28=")); Serial.println(sysSettings.propWeightV); - Serial.print(F("$29=")); Serial.println(sysSettings.zKpPos); - Serial.print(F("$30=")); Serial.println(sysSettings.zKiPos); - Serial.print(F("$31=")); Serial.println(sysSettings.zKdPos); - Serial.print(F("$32=")); Serial.println(sysSettings.zPropWeightPos); - Serial.print(F("$33=")); Serial.println(sysSettings.zKpV); - Serial.print(F("$34=")); Serial.println(sysSettings.zKiV); - Serial.print(F("$35=")); Serial.println(sysSettings.zKdV); - Serial.print(F("$36=")); Serial.println(sysSettings.zPropWeightV); - Serial.print(F("$37=")); Serial.println(sysSettings.chainSagCorrection); + 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); #else Serial.print(F("$0=")); Serial.print(sysSettings.machineWidth); - Serial.print(F(" (machine width, mm, $K)\r\n$1=")); Serial.print(sysSettings.machineHeight); - Serial.print(F(" (machine height, mm, $K)\r\n$2=")); Serial.print(sysSettings.distBetweenMotors); - Serial.print(F(" (motor distance, mm, $K)\r\n$3=")); Serial.print(sysSettings.motorOffsetY); - Serial.print(F(" (motor height, mm, $K)\r\n$4=")); Serial.print(sysSettings.sledWidth); - Serial.print(F(" (sled width, mm, $K)\r\n$5=")); Serial.print(sysSettings.sledHeight); - Serial.print(F(" (sled height, mm, $K)\r\n$6=")); Serial.print(sysSettings.sledCG); - Serial.print(F(" (sled cg, mm, $K)\r\n$7=")); Serial.print(sysSettings.kinematicsType); - Serial.print(F(" (Kinematics Type 1=Quadrilateral, 2=Triangular, $K)\r\n$8=")); Serial.print(sysSettings.rotationDiskRadius); - Serial.print(F(" (rotation radius, mm, $K)\r\n$9=")); Serial.print(sysSettings.axisDetachTime); - Serial.print(F(" (axis idle before detach, ms)\r\n$11=")); Serial.print(sysSettings.originalChainLength); - Serial.print(F(" (original chain length, mm)\r\n$12=")); Serial.print(sysSettings.encoderSteps); - Serial.print(F(" (main steps per revolution, $K)\r\n$13=")); Serial.print(sysSettings.distPerRot); - Serial.print(F(" (distance / rotation, mm, $K)\r\n$15=")); Serial.print(sysSettings.maxFeed); - Serial.print(F(" (max feed, mm/min, $K)\r\n$16=")); Serial.print(sysSettings.zAxisAttached); - Serial.print(F(" (Auto Z Axis, 1 = Yes)\r\n$17=")); Serial.print(sysSettings.zAxisAuto); - Serial.print(F(" (auto z axis)\r\n$18=")); Serial.print(sysSettings.maxZRPM); - Serial.print(F(" (max z axis RPM)\r\n$19=")); Serial.print(sysSettings.zDistPerRot); - Serial.print(F(" (z axis distance / rotation)\r\n$20=")); Serial.print(sysSettings.zEncoderSteps); - Serial.print(F(" (z axis steps per revolution)\r\n$21=")); Serial.print(sysSettings.KpPos); - Serial.print(F(" (main Kp Pos)\r\n$22=")); Serial.print(sysSettings.KiPos); - Serial.print(F(" (main Ki Pos)\r\n$23=")); Serial.print(sysSettings.KdPos); - Serial.print(F(" (main Kd Pos)\r\n$24=")); Serial.print(sysSettings.propWeightPos); - Serial.print(F(" (main Pos proportional weight)\r\n$25=")); Serial.print(sysSettings.KpV); - Serial.print(F(" (main Kp Velocity)\r\n$26=")); Serial.print(sysSettings.KiV); - Serial.print(F(" (main Ki Velocity)\r\n$27=")); Serial.print(sysSettings.KdV); - Serial.print(F(" (main Kd Velocity)\r\n$28=")); Serial.print(sysSettings.propWeightV); - Serial.print(F(" (main Velocity proportional weight)\r\n$29=")); Serial.print(sysSettings.zKpPos); - Serial.print(F(" (z axis Kp Pos)\r\n$30=")); Serial.print(sysSettings.zKiPos); - Serial.print(F(" (z axis Ki Pos)\r\n$31=")); Serial.print(sysSettings.zKdPos); - Serial.print(F(" (z axis Kd Pos)\r\n$32=")); Serial.print(sysSettings.zPropWeightPos); - Serial.print(F(" (z axis Pos proportional weight)\r\n$33=")); Serial.print(sysSettings.zKpV); - Serial.print(F(" (z axis Kp Velocity)\r\n$34=")); Serial.print(sysSettings.zKiV); - Serial.print(F(" (z axis Ki Velocity)\r\n$35=")); Serial.print(sysSettings.zKdV); - Serial.print(F(" (z axis Kd Velocity)\r\n$36=")); Serial.print(sysSettings.zPropWeightV); - Serial.print(F(" (z axis Velocity proportional weight)\r\n$37=")); Serial.print(sysSettings.chainSagCorrection); + 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.spindleAutomate); + Serial.print(F(" (auto spindle servo/relay)\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.println(F(" (chain over sprocket)")); + 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)")); + Serial.println(); #endif } @@ -263,7 +268,6 @@ void reportMaslowHelp(){ // 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("$K (recompute kinematics)")); // Serial.println(F("$Nx=line (save startup block)")); // Serial.println(F("$C (check gcode mode)")); // Serial.println(F("$X (kill alarm lock)")); diff --git a/cnc_ctrl_v1/Settings.cpp b/cnc_ctrl_v1/Settings.cpp index 66a147fa..34d54eaf 100644 --- a/cnc_ctrl_v1/Settings.cpp +++ b/cnc_ctrl_v1/Settings.cpp @@ -44,6 +44,7 @@ void settingsLoadFromEEprom(){ } // Apply settings + setPWMPrescalers(int(sysSettings.fPWM)); kinematics.recomputeGeometry(); leftAxis.changeEncoderResolution(&sysSettings.encoderSteps); rightAxis.changeEncoderResolution(&sysSettings.encoderSteps); @@ -76,7 +77,7 @@ void settingsReset() { sysSettings.distPerRot = 63.5; // float distPerRot; sysSettings.maxFeed = 1000; // int maxFeed; sysSettings.zAxisAttached = true; // zAxisAttached; - sysSettings.zAxisAuto = false; // bool zAxisAuto; + sysSettings.spindleAutomate = false; // bool spindleAutomate; sysSettings.maxZRPM = 12.60; // float maxZRPM; sysSettings.zDistPerRot = 3.17; // float zDistPerRot; sysSettings.zEncoderSteps = 7560.0; // float zEncoderSteps; @@ -98,6 +99,7 @@ void settingsReset() { sysSettings.zPropWeightV = 1.0; // float zPropWeightV; sysSettings.chainSagCorrection = 0.0; // float chainSagCorrection; sysSettings.chainOverSprocket = 1; // byte chainOverSprocket; + sysSettings.fPWM = 3; // byte fPWM; sysSettings.eepromValidData = EEPROMVALIDDATA; // byte eepromValidData; } @@ -143,14 +145,12 @@ void settingsSaveStepstoEEprom(){ */ // don't run if old position data has not been incorporated yet if (!sys.oldSettingsFlag){ - settingsVersion_t settingsVersionStruct = {SETTINGSVERSION, EEPROMVALIDDATA}; settingsStepsV1_t sysSteps = { leftAxis.steps(), rightAxis.steps(), zAxis.steps(), EEPROMVALIDDATA }; - EEPROM.put(300, settingsVersionStruct); EEPROM.put(310, sysSteps); } } @@ -165,16 +165,12 @@ void settingsLoadStepsFromEEprom(){ settingsStepsV1_t tempStepsV1; settingsVersion_t settingsVersionStruct; - EEPROM.get(300, settingsVersionStruct); EEPROM.get(310, tempStepsV1); - if (settingsVersionStruct.settingsVersion == SETTINGSVERSION && - settingsVersionStruct.eepromValidData == EEPROMVALIDDATA && - tempStepsV1.eepromValidData == EEPROMVALIDDATA){ + if (tempStepsV1.eepromValidData == EEPROMVALIDDATA){ leftAxis.setSteps(tempStepsV1.lSteps); rightAxis.setSteps(tempStepsV1.rSteps); zAxis.setSteps(tempStepsV1.zSteps); - }// We can add additional elseif statements here to check for old settings - // versions and upgrade them without a loss of data. + } else if (EEPROM.read(5) == EEPROMVALIDDATA && EEPROM.read(105) == EEPROMVALIDDATA && EEPROM.read(205) == EEPROMVALIDDATA){ @@ -224,7 +220,7 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& 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 0: case 1: case 2: case 3: case 4: case 5: case 6: case 7: case 8: switch(parameter) { case 0: sysSettings.machineWidth = value; @@ -244,9 +240,6 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ case 5: sysSettings.sledHeight = value; break; - } - kinematics.recomputeGeometry(); - break; case 6: sysSettings.sledCG = value; break; @@ -256,9 +249,15 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ 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; @@ -272,6 +271,7 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ settingsLoadOldSteps(); } } + kinematics.init(); break; case 13: sysSettings.distPerRot = value; @@ -284,6 +284,7 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ settingsLoadOldSteps(); } } + kinematics.init(); break; case 15: sysSettings.maxFeed = value; @@ -292,7 +293,7 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ sysSettings.zAxisAttached = value; break; case 17: - sysSettings.zAxisAuto = value; + sysSettings.spindleAutomate = value; break; case 18: sysSettings.maxZRPM = value; @@ -382,6 +383,10 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ case 38: sysSettings.chainOverSprocket = value; break; + case 39: + sysSettings.fPWM = value; + setPWMPrescalers(value); + break; default: return(STATUS_INVALID_STATEMENT); } diff --git a/cnc_ctrl_v1/Settings.h b/cnc_ctrl_v1/Settings.h index df56f626..f661ac2e 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 2 // The current version of settings, if this doesn't +#define SETTINGSVERSION 4 // 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 @@ -43,12 +43,13 @@ typedef struct { // I think this is about ~128 bytes in size if I counted corre byte kinematicsType; float rotationDiskRadius; unsigned int axisDetachTime; + unsigned int chainLength; unsigned int originalChainLength; float encoderSteps; float distPerRot; unsigned int maxFeed; bool zAxisAttached; - bool zAxisAuto; + bool spindleAutomate; float maxZRPM; float zDistPerRot; float zEncoderSteps; @@ -70,6 +71,7 @@ typedef struct { // I think this is about ~128 bytes in size if I counted corre float zPropWeightV; float chainSagCorrection; byte chainOverSprocket; + byte fPWM; 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 fddfb054..9dec8125 100644 --- a/cnc_ctrl_v1/Spindle.cpp +++ b/cnc_ctrl_v1/Spindle.cpp @@ -23,7 +23,7 @@ void setSpindlePower(bool powerState) { /* * Turn spindle on or off depending on powerState */ - boolean useServo = !sysSettings.zAxisAuto; + boolean useServo = !sysSettings.spindleAutomate; boolean activeHigh = true; int delayAfterChange = 1000; // milliseconds int servoIdle = 90; // degrees diff --git a/cnc_ctrl_v1/System.cpp b/cnc_ctrl_v1/System.cpp index 26464cde..608e884e 100644 --- a/cnc_ctrl_v1/System.cpp +++ b/cnc_ctrl_v1/System.cpp @@ -19,6 +19,11 @@ Copyright 2014-2017 Bar Smith*/ #include "Maslow.h" +bool TLE5206; +int SpindlePowerControlPin; // output for controlling spindle power +int ProbePin; // use this input for zeroing zAxis with G38.2 gcode + + 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 @@ -76,6 +81,16 @@ void setupAxes(){ 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(); @@ -101,6 +116,11 @@ void setupAxes(){ IN5 = 12; // OUTPUT IN6 = 13; // OUTPUT ENC = 5; // PWM + + AUX1 = 17; + AUX2 = 16; + AUX3 = 15; + AUX4 = 14; } else if(pcbVersion == 1){ //PCB v1.1 Detected @@ -124,6 +144,11 @@ void setupAxes(){ IN5 = 10; // OUTPUT IN6 = 11; // OUTPUT ENC = 12; // PWM + + AUX1 = 17; + AUX2 = 16; + AUX3 = 15; + AUX4 = 14; } else if(pcbVersion == 2){ //PCB v1.2 Detected @@ -149,7 +174,43 @@ void setupAxes(){ IN6 = 12; // OUTPUT ENC = 10; // PWM + AUX1 = 17; + AUX2 = 16; + AUX3 = 15; + AUX4 = 14; + } + else if(pcbVersion == 3){ // TLE5206 + //TLE5206 PCB v1.3 Detected + //MP1 - Right Motor + ENCODER1A = 20; // INPUT + ENCODER1B = 21; // INPUT + IN1 = 6; // OUTPUT + IN2 = 4; // OUTPUT + ENA = 5; // errorFlag + + //MP2 - Z-axis + ENCODER2A = 18; // INPUT + ENCODER2B = 19; // INPUT + IN3 = 9; // OUTPUT + IN4 = 7; // OUTPUT + ENB = 8; // errorFlag + + //MP3 - Left Motor + ENCODER3A = 2; // INPUT + ENCODER3B = 3; // INPUT + IN5 = 10; // OUTPUT + IN6 = 11; // OUTPUT + ENC = 12; // errorFlag + AUX1 = 40; + AUX2 = 41; + AUX3 = 42; + AUX4 = 43; + AUX5 = 68; + AUX6 = 69; + AUX7 = 45; + AUX8 = 46; + AUX9 = 47; } if(sysSettings.chainOverSprocket == 1){ @@ -162,10 +223,111 @@ void setupAxes(){ } 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); } int getPCBVersion(){ - return (8*digitalRead(53) + 4*digitalRead(52) + 2*digitalRead(23) + 1*digitalRead(22)) - 1; + pinMode(VERS1,INPUT); + pinMode(VERS2,INPUT); + pinMode(VERS3,INPUT); + pinMode(VERS4,INPUT); + int pinCheck = (8*digitalRead(VERS4) + 4*digitalRead(VERS3) + 2*digitalRead(VERS2) + 1*digitalRead(VERS1)); + switch (pinCheck) { + case 0: case 1: case 2: case 3: // v1.2 board + TLE5206 = false; + break; + case 4: + TLE5206 = true; + break; + } + #define SpindlePowerControlPin = AUX1; // output for controlling spindle power + #define ProbePin = AUX4 // use this input for zeroing zAxis with G38.2 gcode + 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 +// 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 2       (Pin 9, 10) +// 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 ( Pin 2, 3, 5), (Pin 6, 7, 8) +// +// 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 +} + +// +// PWM frequency change +// presently just sets the default value +// different values seem to need specific PWM tunings... +// +void setPWMPrescalers() { +// first must erase the bits in each TTCRxB register that control the timers prescaler + int prescalerEraser = 0B0111; + TCCR2B &= ~prescalerEraser; + TCCR3B &= ~prescalerEraser; + TCCR4B &= ~prescalerEraser; +// now choose how to set those same three bits + // prescaler = 1 ---> PWM frequency is 31000 Hz + // prescaler = 2 ---> PWM frequency is 4000 Hz + // prescaler = 3 ---> PWM frequency is 490 Hz (default value) + // prescaler = 4 ---> PWM frequency is 120 Hz + // prescaler = 5 ---> PWM frequency is 30 Hz + // prescaler = 6 ---> PWM frequency is <20 Hz + int prescalerChoice = 3; +// and apply it + TCCR2B |= prescalerChoice; // pins 9, 10 + TCCR3B |= prescalerChoice; // pins 2, 3, 5 + TCCR4B |= prescalerChoice; // pins 6, 7, 8 } @@ -298,7 +460,7 @@ byte systemExecuteCmdstring(String& cmdString){ } else { switch( cmdString[char_counter] ) { - case '$': case 'K':// case 'G': case 'C': case 'X': + case '$': // case 'G': case 'C': case 'X': if ( cmdString.length() > 2 ) { return(STATUS_INVALID_STATEMENT); } switch( cmdString[char_counter] ) { case '$' : // Prints Maslow settings @@ -307,10 +469,6 @@ byte systemExecuteCmdstring(String& cmdString){ reportMaslowSettings(); // } break; - case 'K' : // forces kinematics update - kinematics.recomputeGeometry(); - kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition); - break; // case 'G' : // Prints gcode parser state // report_gcode_modes(); // break; @@ -450,4 +608,4 @@ byte systemExecuteCmdstring(String& cmdString){ } } return(STATUS_OK); -} \ No newline at end of file +} diff --git a/cnc_ctrl_v1/System.h b/cnc_ctrl_v1/System.h index a2e56e60..670db5c5 100644 --- a/cnc_ctrl_v1/System.h +++ b/cnc_ctrl_v1/System.h @@ -85,5 +85,7 @@ void execSystemRealtime(); void systemSaveAxesPosition(); void systemReset(); byte systemExecuteCmdstring(String&); +void setPWMPrescalers(int prescalerChoice); -#endif \ No newline at end of file + +#endif diff --git a/cnc_ctrl_v1/Testing.cpp b/cnc_ctrl_v1/Testing.cpp index 8179f9ae..3f8bfa39 100644 --- a/cnc_ctrl_v1/Testing.cpp +++ b/cnc_ctrl_v1/Testing.cpp @@ -66,7 +66,7 @@ void PIDTestVelocity(Axis* axis, const float start, const float stop, const floa axis->write(axis->read()); axis->detach(); axis->enablePositionPID(); - kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition); + kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition, 0.0, 0.0); } void positionPIDOutput (Axis* axis, float setpoint, float startingPoint){ @@ -145,7 +145,7 @@ void PIDTestPosition(Axis* axis, float start, float stop, const float steps, con Serial.println(F("--PID Position Test Stop--\n")); axis->write(axis->read()); axis->detach(); - kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition); + kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition, 0.0, 0.0); } void voltageTest(Axis* axis, int start, int stop){ @@ -177,5 +177,5 @@ void voltageTest(Axis* axis, int start, int stop){ 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); + kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition, 0.0, 0.0); } \ No newline at end of file diff --git a/cnc_ctrl_v1/cnc_ctrl_v1.ino b/cnc_ctrl_v1/cnc_ctrl_v1.ino index c3a2f6e9..fb3fbf14 100644 --- a/cnc_ctrl_v1/cnc_ctrl_v1.ino +++ b/cnc_ctrl_v1/cnc_ctrl_v1.ino @@ -11,7 +11,10 @@ along with the Maslow Control Software. If not, see . Copyright 2014-2017 Bar Smith*/ - + +// TLE5206 version + + #include "Maslow.h" // Define system global state structure @@ -36,18 +39,16 @@ 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(); - // TODO This seems wrong, if the encoder steps are changed, axis position - // will be in the wrong place. Would be better if we stored positions as - // steps // Set initial desired position of the machine to its current position leftAxis.write(leftAxis.read()); - rightAxis.write(leftAxis.read()); - zAxis.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); Timer1.initialize(LOOPINTERVAL); From 846fae950a4055d05354c75b44f96bec6d669a49 Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Sun, 11 Mar 2018 18:55:24 -0700 Subject: [PATCH 02/19] Merge branch 'master' into TLE5206-release --- cnc_ctrl_v1/Config.h | 3 +++ cnc_ctrl_v1/GCode.cpp | 2 +- cnc_ctrl_v1/Maslow.h | 3 ++- cnc_ctrl_v1/Motor.cpp | 0 cnc_ctrl_v1/Settings.cpp | 9 ++++++++- cnc_ctrl_v1/SimavrSerial.cpp | 27 +++++++++++++++++++++++++++ cnc_ctrl_v1/SimavrSerial.h | 32 ++++++++++++++++++++++++++++++++ cnc_ctrl_v1/cnc_ctrl_v1.ino | 8 +++++++- 8 files changed, 80 insertions(+), 4 deletions(-) mode change 100755 => 100644 cnc_ctrl_v1/Motor.cpp create mode 100644 cnc_ctrl_v1/SimavrSerial.cpp create mode 100644 cnc_ctrl_v1/SimavrSerial.h diff --git a/cnc_ctrl_v1/Config.h b/cnc_ctrl_v1/Config.h index b0834fed..53d1a05a 100644 --- a/cnc_ctrl_v1/Config.h +++ b/cnc_ctrl_v1/Config.h @@ -29,6 +29,9 @@ // 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 diff --git a/cnc_ctrl_v1/GCode.cpp b/cnc_ctrl_v1/GCode.cpp index 2cb0e4ca..b32ba25f 100644 --- a/cnc_ctrl_v1/GCode.cpp +++ b/cnc_ctrl_v1/GCode.cpp @@ -660,7 +660,7 @@ int G1(const String& readString, int G0orG1){ } else{ //if this is a rapid move - coordinatedMove(xgoto, ygoto, zgoto, 1000); //move the same as a regular move, but go fast + coordinatedMove(xgoto, ygoto, zgoto, sysSettings.maxFeed); //move the same as a regular move, but go fast } } diff --git a/cnc_ctrl_v1/Maslow.h b/cnc_ctrl_v1/Maslow.h index 40954186..e2da7c6d 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 1.07 +#define VERSIONNUMBER 1.09 // Define standard libraries used by maslow. #include @@ -48,5 +48,6 @@ #include "Settings.h" #include "NutsAndBolts.h" #include "System.h" +#include "SimavrSerial.h" #endif diff --git a/cnc_ctrl_v1/Motor.cpp b/cnc_ctrl_v1/Motor.cpp old mode 100755 new mode 100644 diff --git a/cnc_ctrl_v1/Settings.cpp b/cnc_ctrl_v1/Settings.cpp index 34d54eaf..464c93d6 100644 --- a/cnc_ctrl_v1/Settings.cpp +++ b/cnc_ctrl_v1/Settings.cpp @@ -75,7 +75,7 @@ void settingsReset() { sysSettings.originalChainLength = 1650; // int originalChainLength; sysSettings.encoderSteps = 8113.7; // float encoderSteps; sysSettings.distPerRot = 63.5; // float distPerRot; - sysSettings.maxFeed = 1000; // int maxFeed; + sysSettings.maxFeed = 700; // int maxFeed; sysSettings.zAxisAttached = true; // zAxisAttached; sysSettings.spindleAutomate = false; // bool spindleAutomate; sysSettings.maxZRPM = 12.60; // float maxZRPM; @@ -382,6 +382,13 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ break; case 38: 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; diff --git a/cnc_ctrl_v1/SimavrSerial.cpp b/cnc_ctrl_v1/SimavrSerial.cpp new file mode 100644 index 00000000..5ddebd96 --- /dev/null +++ b/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/cnc_ctrl_v1/SimavrSerial.h b/cnc_ctrl_v1/SimavrSerial.h new file mode 100644 index 00000000..879dd362 --- /dev/null +++ b/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/cnc_ctrl_v1/cnc_ctrl_v1.ino b/cnc_ctrl_v1/cnc_ctrl_v1.ino index fb3fbf14..d7ca574a 100644 --- a/cnc_ctrl_v1/cnc_ctrl_v1.ino +++ b/cnc_ctrl_v1/cnc_ctrl_v1.ino @@ -51,8 +51,12 @@ void setup(){ 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? Apparenlty because some programs are silly and look for this as an initailization command Serial.println(F("ready")); @@ -87,7 +91,9 @@ void loop(){ // limit while (!sys.stop){ gcodeExecuteLoop(); - + #ifdef SIMAVR // Normally, runsOnATimer() will, well, run on a timer. See also setup(). + runsOnATimer(); + #endif execSystemRealtime(); } } From 86f1bce548e3332f3ff7ee1ba3b58456adb4a86d Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Sun, 11 Mar 2018 23:02:24 -0700 Subject: [PATCH 03/19] Finish updating to master --- .../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 cnc_ctrl_v1/Config.h | 24 +- guestBook.txt | 8 + platformio/simavr_env.py | 21 ++ platformio/teensy_env.py | 12 + simduino/Makefile | 30 ++ simduino/Makefile.common | 225 ++++++++++++ simduino/simduino.c | 154 +++++++++ simduino/uart_pty.c | 323 ++++++++++++++++++ simduino/uart_pty.h | 76 +++++ 22 files changed, 861 insertions(+), 12 deletions(-) create mode 100644 Documentation/How To Contribute Pictures/Clone.PNG create mode 100644 Documentation/How To Contribute Pictures/Clone2.PNG create mode 100644 Documentation/How To Contribute Pictures/Clone3.PNG create mode 100644 Documentation/How To Contribute Pictures/Commit.PNG create mode 100644 Documentation/How To Contribute Pictures/EditingFile.PNG create mode 100644 Documentation/How To Contribute Pictures/Fork.jpg create mode 100644 Documentation/How To Contribute Pictures/GithubHome.jpg create mode 100644 Documentation/How To Contribute Pictures/GithubWelcome.jpg create mode 100644 Documentation/How To Contribute Pictures/PR0.PNG create mode 100644 Documentation/How To Contribute Pictures/PR1.PNG create mode 100644 Documentation/How To Contribute Pictures/PR2.PNG create mode 100644 Documentation/How To Contribute Pictures/PR3.PNG create mode 100644 Documentation/How To Contribute Pictures/Push Origin.PNG create mode 100755 platformio/simavr_env.py create mode 100755 platformio/teensy_env.py create mode 100644 simduino/Makefile create mode 100644 simduino/Makefile.common create mode 100644 simduino/simduino.c create mode 100644 simduino/uart_pty.c create mode 100644 simduino/uart_pty.h diff --git a/Documentation/How To Contribute Pictures/Clone.PNG b/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/Documentation/How To Contribute Pictures/Clone3.PNG b/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/Documentation/How To Contribute Pictures/Commit.PNG b/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/Documentation/How To Contribute Pictures/EditingFile.PNG b/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/Documentation/How To Contribute Pictures/Fork.jpg b/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/Documentation/How To Contribute Pictures/GithubHome.jpg b/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/Documentation/How To Contribute Pictures/PR0.PNG b/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/Documentation/How To Contribute Pictures/PR1.PNG b/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/Documentation/How To Contribute Pictures/PR2.PNG b/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/Documentation/How To Contribute Pictures/PR3.PNG b/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/Documentation/How To Contribute Pictures/Push Origin.PNG b/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/cnc_ctrl_v1/Config.h b/cnc_ctrl_v1/Config.h index 53d1a05a..0f732b5a 100644 --- a/cnc_ctrl_v1/Config.h +++ b/cnc_ctrl_v1/Config.h @@ -9,18 +9,18 @@ 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 +// 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 +#define verboseDebug 1 // 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 @@ -39,24 +39,24 @@ #define VERS1 22 #define VERS2 23 #define VERS3 24 -#define VERS4 25 +#define VERS4 25 // 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 +#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 +#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. + // timeout could be significantly larger. #endif diff --git a/guestBook.txt b/guestBook.txt index 4bc9202e..0e140f5e 100644 --- a/guestBook.txt +++ b/guestBook.txt @@ -30,3 +30,11 @@ TheRiflesSpiral - confusedly contributing correspondence concordently. 3/30/17 seware74 - When 900 years old, you reach… Look as good, you will not. Hmm. - 5/26/2017 ladams00 - Can't wait for Maslow to show up at my door! Jan 7th 2018 + +Bar - Back to update the how to contribute page for the new look of GitHub :) + +I'm Batman. + +Tanju B - Hello! we finally making cuts down at the Maker Station makerspace in Marietta, GA. Finally! 18-Feb-2018 + +Maslow Bahrain (GeroBH) made it into the guestBook ;-) 21 Feb 2018 diff --git a/platformio/simavr_env.py b/platformio/simavr_env.py new file mode 100755 index 00000000..ab5b46bc --- /dev/null +++ b/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/platformio/teensy_env.py b/platformio/teensy_env.py new file mode 100755 index 00000000..0f0265e5 --- /dev/null +++ b/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/simduino/Makefile b/simduino/Makefile new file mode 100644 index 00000000..a2f18fe5 --- /dev/null +++ b/simduino/Makefile @@ -0,0 +1,30 @@ +# Based on code from simavr (https://github.com/buserror/simavr) + +target= simduino +board = ${OBJ}/${target}.elf +# simavr = ../../ + +# IPATH = . +# IPATH += ../parts +# IPATH += ${simavr}/include +# IPATH += ${simavr}/simavr/sim + +# VPATH = . +# VPATH += ../parts + +LDFLAGS += -lpthread -lutil + +# include ../Makefile.opengl + +all: obj ${target} + +include Makefile.common + +${board} : ${OBJ}/uart_pty.o +${board} : ${OBJ}/${target}.o + +${target}: ${board} + cp ${board} ${target} + +clean: clean-${OBJ} + rm -rf *.a *.axf ${target} *.vcd *.hex diff --git a/simduino/Makefile.common b/simduino/Makefile.common new file mode 100644 index 00000000..9b56e276 --- /dev/null +++ b/simduino/Makefile.common @@ -0,0 +1,225 @@ +# +# This makefile take each "at*" file, extracts it's part name +# And compile it into an ELF binary. +# It also disassemble it for debugging purposes. +# +# The code is compiled "optimized" to the max. +# +# The weird "-Wl,--undefined=_mmcu,--section-start=.mmcu=0x910000" +# is used to tell the linker not to discard the .mmcu section, +# otherwise the --gc-sections will delete it. +# +# Copyright 2008, 2009 Michel Pollet +# +# This file is part of simavr. +# +# simavr 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. +# +# simavr 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 simavr. If not, see . + +# simavr directory +SIMAVR := ${shell for p in . .. ../.. ../../..;do test -d $$p/simavr/sim && echo $$p/simavr; done} + +# You can override the build settings with local changes in this file +# for example: +# export CC=clang +# export CFLAGS=-march=corei7-avx +# etc +-include ${wildcard ${SIMAVR}/../.make.options*} + +# get the first character of what the compiler says it is, unless it's 'x86_64' doh +ARCH := ${shell $(CC) -dumpmachine | sed -e 's/^x/i/' -e 's/\(.\).*/\1/'} + +CFLAGS += -O2 -Wall -Wextra -Wno-unused-parameter \ + -Wno-unused-result -Wno-missing-field-initializers \ + -Wno-sign-compare +CFLAGS += -g +CORE_CFLAGS = -DAVR_CORE=1 + +ifeq (${shell uname}, Darwin) + # gcc 4.2 from MacOS is really not up to scratch anymore + CC = clang + AVR_ROOT := "/Applications/Arduino.app/Contents/Java/hardware/tools/avr/" + AVR := ${AVR_ROOT}/bin/avr- + # Thats for MacPorts libelf + ifeq (${shell test -d /opt/local && echo Exists}, Exists) + ifneq (${shell test -d /opt/local/avr && echo Exists}, Exists) + $(error Please install avr-gcc: port install avr-gcc avr-libc) + endif + ifneq (${shell test -d /opt/local/include/libelf && echo Exists}, Exists) + $(error Please install libelf: port install libelf) + endif + CC = clang + IPATH += /opt/local/include /opt/local/include/libelf + LFLAGS = -L/opt/local/lib/ + AVR := /opt/local/bin/avr- + else + # That's for Homebrew libelf and avr-gcc support + HOMEBREW_PREFIX ?= /usr/local + ifeq (${shell test -d $(HOMEBREW_PREFIX)/Cellar && echo Exists}, Exists) + ifneq (${shell test -d $(HOMEBREW_PREFIX)/Cellar/avr-gcc/ && echo Exists}, Exists) + $(error Please install avr-gcc: brew tap osx-cross/homebrew-avr ; brew install avr-libc) + endif + ifneq (${shell test -d $(HOMEBREW_PREFIX)/Cellar/libelf/ && echo Exists}, Exists) + $(error Please install libelf: brew install libelf) + endif + CC = clang + IPATH += $(HOMEBREW_PREFIX)/include + LFLAGS = -L$(HOMEBREW_PREFIX)/lib/ + CFLAGS += -I/$(HOMEBREW_PREFIX)/include/libelf + AVR_ROOT := $(firstword $(wildcard $(HOMEBREW_PREFIX)/Cellar/avr-libc/*/)) + AVR := $(HOMEBREW_PREFIX)/bin/avr- + endif + endif +else + AVR := avr- +endif + +# FIXME uname -o doesn't work on bsd derivatives +#WIN := ${shell uname -o} + +ifeq (${WIN}, Msys) +AVR_ROOT := ${shell echo "${AVR32_HOME}" | tr '\\' '/'} +AVR := ${AVR_ROOT}/bin/avr- +IPATH += ${PREFIX}/include +CFLAGS += -I${PREFIX}/include +LDFLAGS += -L/lib -L/local/lib +CFLAGS += -DNO_COLOR +else +CFLAGS += -fPIC +endif + +CPPFLAGS += --std=gnu99 -Wall +CPPFLAGS += ${patsubst %,-I%,${subst :, ,${IPATH}}} + +AVR_CPPFLAGS = ${CPPFLAGS} -I${SIMAVR}/cores + +CC ?= clang +AR ?= ar +RANLIB ?= ranlib +MKDIR ?= mkdir -p +INSTALL ?= install +SHELL := ${shell which bash} + +OBJ := obj-${shell $(CC) -dumpmachine} +LIBDIR := ${shell pwd}/${SIMAVR}/${OBJ} +LDFLAGS += -L${LIBDIR} -lsimavr -lm + +LDFLAGS += -lelf + +ifeq (${WIN}, Msys) +LDFLAGS += -lws2_32 +endif + +ifeq (${shell uname}, Linux) +ifeq ($(RELEASE),1) +# allow the shared library to be found in the build directory +# only for linking, the install time location is used at runtime +LFLAGS += -Wl,-rpath-link,${LIBDIR} +else +# allow the shared library to be found in the build directory +LFLAGS += -Wl,-rpath,${LIBDIR} +endif +endif + +ifeq (${V}, 1) +E = +else +E = @ +endif + +# The code is compiled "optimized" to the max. +# +# The weird "-Wl,--undefined=_mmcu,--section-start=.mmcu=0x910000" +# is used to tell the linker not to discard the .mmcu section, +# otherwise the --gc-sections will delete it. + +%.hex: %.axf + @${AVR}objcopy -j .text -j .data -j .eeprom -O ihex ${<} ${@} + +%.s: %.axf + @${AVR}objdump -j .text -j .data -j .bss -d ${<} > ${@} + +# --mcall-prologues can be used here, but messes up debugging a little +%.axf: %.c + @echo AVR-CC ${<} + @part=${<} ; part=$${part/_*}; \ + ${AVR}gcc -Wall -gdwarf-2 -Os -std=gnu99 \ + -mmcu=$$part \ + -DF_CPU=8000000 \ + -fno-inline-small-functions \ + -ffunction-sections -fdata-sections \ + -Wl,--relax,--gc-sections \ + -Wl,--undefined=_mmcu,--section-start=.mmcu=0x910000 \ + -I../simavr/sim/avr -I../../simavr/sim/avr \ + ${^} -o ${@} + @${AVR}size ${@}|sed '1d' + +# this rule has precedence +${OBJ}/sim_%.o : cores/sim_%.c +ifneq ($(E),) + @echo CORE $< +endif + ${E}$(CC) $(CPPFLAGS) $(CFLAGS) $(CORE_CFLAGS) -MMD \ + ${AVR_CPPFLAGS} \ + $< -c -o $@ + +${OBJ}/%.o: %.c +ifneq ($(E),) + @echo CC $< +endif + ${E}$(CC) $(CPPFLAGS) $(CFLAGS) -MMD \ + $< -c -o $@ + +${OBJ}/%.elf: +ifneq ($(E),) + @echo LD $@ +endif + ${E}$(CC) -MMD ${CFLAGS} ${LFLAGS} -o $@ ${filter %.o,$^} $(LDFLAGS) + + +.PRECIOUS: ${OBJ}/%.a ${OBJ}/%.so.1 +# +# Static library +# +${OBJ}/%.a: +ifneq ($(E),) + @echo AR $@ +endif + ${E}$(AR) cru $@ ${filter %.o,$^} && $(RANLIB) $@ + +# +# Shared library (Linux) +# +${OBJ}/%.so.1: ${OBJ}/%.a +ifneq ($(E),) + @echo SHARED $@ +endif + ${E}$(CC) -o $@ -shared \ + -Wl,--whole-archive,-soname,${basename ${notdir $@}}.1 \ + ${filter %.o %.a,$^} \ + -Wl,--no-whole-archive \ + ${filter-out -l%, $(LDFLAGS)} ${EXTRA_LDFLAGS} + +${OBJ}/%.so: ${OBJ}/%.so.1 + ln -sf ${notdir $<} $@ + +obj: ${OBJ} + +${OBJ}: + ${E}mkdir -p ${OBJ} + +clean-${OBJ}: + rm -rf ${OBJ} + +# include the dependency files generated by gcc, if any +-include ${wildcard ${OBJ}/*.d} diff --git a/simduino/simduino.c b/simduino/simduino.c new file mode 100644 index 00000000..5fa32b12 --- /dev/null +++ b/simduino/simduino.c @@ -0,0 +1,154 @@ +// This 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 . + +// This program is heavily based on the simduino example, +// which is part of the Simavr project (https://github.com/buserror/simavr). +// +// Most of the code here it is lifted straight from simduino.c, but I made some adjustments: +// - Removed some unnecessary code +// - Load elf files, instead of hex files, because you can't debug hex files. +// - Default to atmegs2560 +// - Fixed a thread-safety issue in the UART code. + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include "uart_pty.h" +#include + +uart_pty_t uart_pty; +avr_t * avr = NULL; +avr_vcd_t vcd_file; + +struct avr_flash { + char avr_flash_path[1024]; + int avr_flash_fd; +}; + +// avr special flash initalization +// here: open and map a file to enable a persistent storage for the flash memory +void avr_special_init( avr_t * avr, void * data) +{ + struct avr_flash *flash_data = (struct avr_flash *)data; + + printf("%s\n", __func__); + // open the file + flash_data->avr_flash_fd = open(flash_data->avr_flash_path, + O_RDWR|O_CREAT, 0644); + if (flash_data->avr_flash_fd < 0) { + perror(flash_data->avr_flash_path); + exit(1); + } + // resize and map the file the file + (void)ftruncate(flash_data->avr_flash_fd, avr->flashend + 1); + ssize_t r = read(flash_data->avr_flash_fd, avr->flash, avr->flashend + 1); + if (r != avr->flashend + 1) { + fprintf(stderr, "unable to load flash memory\n"); + perror(flash_data->avr_flash_path); + exit(1); + } +} + +// avr special flash deinitalization +// here: cleanup the persistent storage +void avr_special_deinit( avr_t* avr, void * data) +{ + struct avr_flash *flash_data = (struct avr_flash *)data; + + printf("%s\n", __func__); + lseek(flash_data->avr_flash_fd, SEEK_SET, 0); + ssize_t r = write(flash_data->avr_flash_fd, avr->flash, avr->flashend + 1); + if (r != avr->flashend + 1) { + fprintf(stderr, "unable to load flash memory\n"); + perror(flash_data->avr_flash_path); + } + close(flash_data->avr_flash_fd); + uart_pty_stop(&uart_pty); +} + +int main(int argc, char *argv[]) +{ + struct avr_flash flash_data; + char * mmcu = "atmega2560"; + uint32_t freq = 16000000; + int debug = 0; + int verbose = 0; + elf_firmware_t f = {{0}}; + + + for (int i = 1; i < argc; i++) { + if (!strcmp(argv[i] + strlen(argv[i]) - 4, ".elf")) { + if (elf_read_firmware(argv[i], &f) == -1) { + fprintf(stderr, "%s: Unable to load firmware from file %s\n", + argv[0], argv[i]); + exit(1); + } + } + else if (!strcmp(argv[i], "-d")) + debug++; + else if (!strcmp(argv[i], "-v")) + verbose++; + else { + fprintf(stderr, "%s: invalid argument %s\n", argv[0], argv[i]); + exit(1); + } + } + + strcpy(f.mmcu, mmcu); + f.frequency = freq; + + avr = avr_make_mcu_by_name(mmcu); + if (!avr) { + fprintf(stderr, "%s: Error creating the AVR core\n", argv[0]); + exit(1); + } + + snprintf(flash_data.avr_flash_path, sizeof(flash_data.avr_flash_path), + "simduino_%s_flash.bin", mmcu); + flash_data.avr_flash_fd = 0; + // register our own functions + avr->custom.init = avr_special_init; + avr->custom.deinit = avr_special_deinit; + avr->custom.data = &flash_data; + avr_init(avr); + avr->frequency = freq; + + avr_load_firmware(avr, &f); + + avr->log = 1 + verbose; + + // even if not setup at startup, activate gdb if crashing + avr->gdb_port = 1234; + if (debug) { + avr->state = cpu_Stopped; + avr_gdb_init(avr); + } + + uart_pty_init(avr, &uart_pty); + uart_pty_connect(&uart_pty, '0'); + + while (1) { + int state = avr_run(avr); + if ( state == cpu_Done || state == cpu_Crashed) + break; + } + +} diff --git a/simduino/uart_pty.c b/simduino/uart_pty.c new file mode 100644 index 00000000..e8f44ebc --- /dev/null +++ b/simduino/uart_pty.c @@ -0,0 +1,323 @@ +/* + uart_pty.c + + Copyright 2008, 2009 Michel Pollet + + This file is part of simavr. + + simavr 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. + + simavr 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 simavr. If not, see . + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#ifdef __APPLE__ +#include +#else +#include +#endif + +#include "uart_pty.h" +#include +#include +#include + +DEFINE_FIFO(uint8_t,uart_pty_fifo); + +//#define TRACE(_w) _w +#ifndef TRACE +#define TRACE(_w) +#endif + +/* + * called when a byte is send via the uart on the AVR + */ +static void +uart_pty_in_hook( + struct avr_irq_t * irq, + uint32_t value, + void * param) +{ + uart_pty_t * p = (uart_pty_t*)param; + TRACE(printf("uart_pty_in_hook %02x\n", value);) + uart_pty_fifo_write(&p->pty.in, value); + + if (p->tap.s) { + if (p->tap.crlf && value == '\n') + uart_pty_fifo_write(&p->tap.in, '\r'); + uart_pty_fifo_write(&p->tap.in, value); + } +} + +// try to empty our fifo, the uart_pty_xoff_hook() will be called when +// other side is full +static void +uart_pty_flush_incoming( + uart_pty_t * p) +{ + while (p->xon && !uart_pty_fifo_isempty(&p->pty.out)) { + TRACE(int r = p->pty.out.read;) + uint8_t byte = uart_pty_fifo_read(&p->pty.out); + TRACE(printf("uart_pty_flush_incoming send r %03d:%02x\n", r, byte);) + avr_raise_irq(p->irq + IRQ_UART_PTY_BYTE_OUT, byte); + + if (p->tap.s) { + if (p->tap.crlf && byte == '\n') + uart_pty_fifo_write(&p->tap.in, '\r'); + uart_pty_fifo_write(&p->tap.in, byte); + } + } + if (p->tap.s) { + while (p->xon && !uart_pty_fifo_isempty(&p->tap.out)) { + uint8_t byte = uart_pty_fifo_read(&p->tap.out); + if (p->tap.crlf && byte == '\r') { + uart_pty_fifo_write(&p->tap.in, '\n'); + } + if (byte == '\n') + continue; + uart_pty_fifo_write(&p->tap.in, byte); + avr_raise_irq(p->irq + IRQ_UART_PTY_BYTE_OUT, byte); + } + } +} + +avr_cycle_count_t +uart_pty_flush_timer( + struct avr_t * avr, + avr_cycle_count_t when, + void * param) +{ + uart_pty_t * p = (uart_pty_t*)param; + + uart_pty_flush_incoming(p); + /* always return a cycle NUMBER not a cycle count */ + return p->xon ? when + avr_hz_to_cycles(p->avr, 1000) : 0; +} + +/* + * Called when the uart has room in it's input buffer. This is called repeateadly + * if necessary, while the xoff is called only when the uart fifo is FULL + */ +static void +uart_pty_xon_hook( + struct avr_irq_t * irq, + uint32_t value, + void * param) +{ + uart_pty_t * p = (uart_pty_t*)param; + TRACE(if (!p->xon) printf("uart_pty_xon_hook\n");) + p->xon = 1; + + uart_pty_flush_incoming(p); + + // if the buffer is not flushed, try to do it later + if (p->xon) + avr_cycle_timer_register(p->avr, avr_hz_to_cycles(p->avr, 1000), + uart_pty_flush_timer, param); +} + +/* + * Called when the uart ran out of room in it's input buffer + */ +static void +uart_pty_xoff_hook( + struct avr_irq_t * irq, + uint32_t value, + void * param) +{ + uart_pty_t * p = (uart_pty_t*)param; + TRACE(if (p->xon) printf("uart_pty_xoff_hook\n");) + p->xon = 0; + avr_cycle_timer_cancel(p->avr, uart_pty_flush_timer, param); +} + +static void * +uart_pty_thread( + void * param) +{ + uart_pty_t * p = (uart_pty_t*)param; + + while (1) { + fd_set read_set, write_set; + int max = 0; + FD_ZERO(&read_set); + FD_ZERO(&write_set); + + for (int ti = 0; ti < 2; ti++) if (p->port[ti].s) { + // read more only if buffer was flushed + if (p->port[ti].buffer_len == p->port[ti].buffer_done) { + FD_SET(p->port[ti].s, &read_set); + max = p->port[ti].s > max ? p->port[ti].s : max; + } + if (!uart_pty_fifo_isempty(&p->port[ti].in)) { + FD_SET(p->port[ti].s, &write_set); + max = p->port[ti].s > max ? p->port[ti].s : max; + } + } + + // short, but not too short interval + struct timeval timo = { 0, 500 }; + int ret = select(max+1, &read_set, &write_set, NULL, &timo); + + if (!ret) + continue; + if (ret < 0) + break; + + for (int ti = 0; ti < 2; ti++) if (p->port[ti].s) { + if (FD_ISSET(p->port[ti].s, &read_set)) { + ssize_t r = read(p->port[ti].s, p->port[ti].buffer, + sizeof(p->port[ti].buffer)-1); + p->port[ti].buffer_len = r; + p->port[ti].buffer_done = 0; + TRACE(if (!p->port[ti].tap) + hdump("pty recv", p->port[ti].buffer, r);) + } + if (p->port[ti].buffer_done < p->port[ti].buffer_len) { + // write them in fifo + while (p->port[ti].buffer_done < p->port[ti].buffer_len && + !uart_pty_fifo_isfull(&p->port[ti].out)) { + int index = p->port[ti].buffer_done++; + TRACE(int wi = p->port[ti].out.write;) + uart_pty_fifo_write(&p->port[ti].out, + p->port[ti].buffer[index]); + TRACE(printf("w %3d:%02x (%d/%d) %s\n", + wi, p->port[ti].buffer[index], + p->port[ti].out.read, + p->port[ti].out.write, + p->xon ? "XON" : "XOFF");) + } + } + if (FD_ISSET(p->port[ti].s, &write_set)) { + uint8_t buffer[512]; + // write them in fifo + uint8_t * dst = buffer; + while (!uart_pty_fifo_isempty(&p->port[ti].in) && + dst < (buffer + sizeof(buffer))) + *dst++ = uart_pty_fifo_read(&p->port[ti].in); + size_t len = dst - buffer; + TRACE(size_t r =) write(p->port[ti].s, buffer, len); + TRACE(if (!p->port[ti].tap) hdump("pty send", buffer, r);) + } + } + /* DO NOT call this, this create a concurency issue with the + * FIFO that can't be solved cleanly with a memory barrier + uart_pty_flush_incoming(p); + */ + } + return NULL; +} + +static const char * irq_names[IRQ_UART_PTY_COUNT] = { + [IRQ_UART_PTY_BYTE_IN] = "8avr = avr; + p->irq = avr_alloc_irq(&avr->irq_pool, 0, IRQ_UART_PTY_COUNT, irq_names); + avr_irq_register_notify(p->irq + IRQ_UART_PTY_BYTE_IN, uart_pty_in_hook, p); + + int hastap = (getenv("SIMAVR_UART_TAP") && atoi(getenv("SIMAVR_UART_TAP"))) || + (getenv("SIMAVR_UART_XTERM") && atoi(getenv("SIMAVR_UART_XTERM"))) ; + + for (int ti = 0; ti < 1 + hastap; ti++) { + int m, s; + + if (openpty(&m, &s, p->port[ti].slavename, NULL, NULL) < 0) { + fprintf(stderr, "%s: Can't create pty: %s", __FUNCTION__, strerror(errno)); + return ; + } + struct termios tio; + tcgetattr(m, &tio); + cfmakeraw(&tio); + tcsetattr(m, TCSANOW, &tio); + p->port[ti].s = m; + p->port[ti].tap = ti != 0; + p->port[ti].crlf = ti != 0; + printf("uart_pty_init %s on port *** %s ***\n", + ti == 0 ? "bridge" : "tap", p->port[ti].slavename); + } + + pthread_create(&p->thread, NULL, uart_pty_thread, p); + +} + +void +uart_pty_stop( + uart_pty_t * p) +{ + puts(__func__); + pthread_kill(p->thread, SIGINT); + for (int ti = 0; ti < 2; ti++) + if (p->port[ti].s) + close(p->port[ti].s); + void * ret; + pthread_join(p->thread, &ret); +} + +void +uart_pty_connect( + uart_pty_t * p, + char uart) +{ + // disable the stdio dump, as we are sending binary there + uint32_t f = 0; + avr_ioctl(p->avr, AVR_IOCTL_UART_GET_FLAGS(uart), &f); + f &= ~AVR_UART_FLAG_STDIO; + avr_ioctl(p->avr, AVR_IOCTL_UART_SET_FLAGS(uart), &f); + + avr_irq_t * src = avr_io_getirq(p->avr, AVR_IOCTL_UART_GETIRQ(uart), UART_IRQ_OUTPUT); + avr_irq_t * dst = avr_io_getirq(p->avr, AVR_IOCTL_UART_GETIRQ(uart), UART_IRQ_INPUT); + avr_irq_t * xon = avr_io_getirq(p->avr, AVR_IOCTL_UART_GETIRQ(uart), UART_IRQ_OUT_XON); + avr_irq_t * xoff = avr_io_getirq(p->avr, AVR_IOCTL_UART_GETIRQ(uart), UART_IRQ_OUT_XOFF); + if (src && dst) { + avr_connect_irq(src, p->irq + IRQ_UART_PTY_BYTE_IN); + avr_connect_irq(p->irq + IRQ_UART_PTY_BYTE_OUT, dst); + } + if (xon) + avr_irq_register_notify(xon, uart_pty_xon_hook, p); + if (xoff) + avr_irq_register_notify(xoff, uart_pty_xoff_hook, p); + + for (int ti = 0; ti < 1; ti++) if (p->port[ti].s) { + char link[128]; + sprintf(link, "/tmp/simavr-uart%s%c", ti == 1 ? "tap" : "", uart); + unlink(link); + if (symlink(p->port[ti].slavename, link) != 0) { + fprintf(stderr, "WARN %s: Can't create %s: %s", __func__, link, strerror(errno)); + } else { + printf("%s: %s now points to %s\n", __func__, link, p->port[ti].slavename); + } + } + if (getenv("SIMAVR_UART_XTERM") && atoi(getenv("SIMAVR_UART_XTERM"))) { + char cmd[256]; + sprintf(cmd, "xterm -e picocom -b 115200 %s >/dev/null 2>&1 &", + p->tap.slavename); + system(cmd); + } else + printf("note: export SIMAVR_UART_XTERM=1 and install picocom to get a terminal\n"); +} + diff --git a/simduino/uart_pty.h b/simduino/uart_pty.h new file mode 100644 index 00000000..35e13d81 --- /dev/null +++ b/simduino/uart_pty.h @@ -0,0 +1,76 @@ +/* + uart_pty.h + + Copyright 2012 Michel Pollet + + This file is part of simavr. + + simavr 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. + + simavr 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 simavr. If not, see . + */ + + +#ifndef __UART_PTY_H___ +#define __UART_PTY_H___ + +#include +#include +#include + +enum { + IRQ_UART_PTY_BYTE_IN = 0, + IRQ_UART_PTY_BYTE_OUT, + IRQ_UART_PTY_COUNT +}; + +DECLARE_FIFO(uint8_t,uart_pty_fifo, 512); + +typedef struct uart_pty_port_t { + int tap : 1, crlf : 1; + int s; // socket we chat on + char slavename[64]; + uart_pty_fifo_t in; + uart_pty_fifo_t out; + uint8_t buffer[512]; + size_t buffer_len, buffer_done; +} uart_pty_port_t, *uart_pty_port_p; + +typedef struct uart_pty_t { + avr_irq_t * irq; // irq list + struct avr_t *avr; // keep it around so we can pause it + + pthread_t thread; + int xon; + + union { + struct { + uart_pty_port_t pty; + uart_pty_port_t tap; + }; + uart_pty_port_t port[2]; + }; +} uart_pty_t; + +void +uart_pty_init( + struct avr_t * avr, + uart_pty_t * b); +void +uart_pty_stop(uart_pty_t * p); + +void +uart_pty_connect( + uart_pty_t * p, + char uart); + +#endif /* __UART_PTY_H___ */ From 3e47940caa430382fa74b3084b13edea2ba99071 Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Wed, 21 Mar 2018 21:33:02 -0700 Subject: [PATCH 04/19] Move AUX pin assignments into variables to allow runtime definition. --- cnc_ctrl_v1/System.cpp | 22 ++++++++++++++++++++-- cnc_ctrl_v1/System.h | 10 +++++----- 2 files changed, 25 insertions(+), 7 deletions(-) diff --git a/cnc_ctrl_v1/System.cpp b/cnc_ctrl_v1/System.cpp index 43bd5d93..de5cf596 100644 --- a/cnc_ctrl_v1/System.cpp +++ b/cnc_ctrl_v1/System.cpp @@ -121,6 +121,8 @@ void setupAxes(){ AUX2 = 16; AUX3 = 15; AUX4 = 14; + AUX5 = 0; + AUX6 = 1; } else if(pcbVersion == 1){ //PCB v1.1 Detected @@ -149,6 +151,8 @@ void setupAxes(){ AUX2 = 16; AUX3 = 15; AUX4 = 14; + AUX5 = A7; + AUX6 = A6; } else if(pcbVersion == 2){ //PCB v1.2 Detected @@ -178,6 +182,8 @@ void setupAxes(){ AUX2 = 16; AUX3 = 15; AUX4 = 14; + AUX5 = A7; + AUX6 = A6; } else if(pcbVersion == 3){ // TLE5206 //TLE5206 PCB v1.3 Detected @@ -226,6 +232,20 @@ void setupAxes(){ 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. + configAuxLow(AUX1, AUX2, AUX3, AUX4, AUX5, AUX6); + if(pcbVersion == 3){ // TLE5206 + configAuxHigh(AUX7, AUX8, AUX9); + } +} + +void configAuxLow(int AUX1, int AUX2, int AUX3, int AUX4, int AUX5, int AUX6) { + #define SpindlePowerControlPin = AUX1; // output for controlling spindle power + #define ProbePin = AUX4 // use this input for zeroing zAxis with G38.2 gcode +} + +void configAuxHigh(int AUX7, int AUX8, int AUX9) { } int getPCBVersion(){ @@ -242,8 +262,6 @@ int getPCBVersion(){ TLE5206 = true; break; } - #define SpindlePowerControlPin = AUX1; // output for controlling spindle power - #define ProbePin = AUX4 // use this input for zeroing zAxis with G38.2 gcode return pinCheck - 1; } diff --git a/cnc_ctrl_v1/System.h b/cnc_ctrl_v1/System.h index 670db5c5..21c3eb19 100644 --- a/cnc_ctrl_v1/System.h +++ b/cnc_ctrl_v1/System.h @@ -39,7 +39,7 @@ Copyright 2014-2017 Bar Smith*/ #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_MOTION_CANCEL bit(6) // Motion cancel by feed hold and return to idle. // Define old settings flag details #define NEED_ENCODER_STEPS bit(0) @@ -56,14 +56,14 @@ typedef struct { float xPosition; // Cartessian position of XY axes float yPosition; // Cached because calculating position is intensive float steps[3]; // Encoder position of axes - bool useRelativeUnits; // + 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 + // THE FOLLOWING IS USED FOR IMPORTING SETTINGS FROM FIRMWARE v1.00 AND EARLIER // It can be deleted at some point byte oldSettingsFlag; } system_t; @@ -86,6 +86,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 From 234290b375552f9711c49c10bd9a37adcb54fd3e Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Wed, 21 Mar 2018 21:40:28 -0700 Subject: [PATCH 05/19] Digital port values for A6 & A7 --- cnc_ctrl_v1/System.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/cnc_ctrl_v1/System.cpp b/cnc_ctrl_v1/System.cpp index de5cf596..4675124e 100644 --- a/cnc_ctrl_v1/System.cpp +++ b/cnc_ctrl_v1/System.cpp @@ -182,8 +182,8 @@ void setupAxes(){ AUX2 = 16; AUX3 = 15; AUX4 = 14; - AUX5 = A7; - AUX6 = A6; + AUX5 = 61; // A7; + AUX6 = 60; // A6; } else if(pcbVersion == 3){ // TLE5206 //TLE5206 PCB v1.3 Detected From 8d8cfc8304459144eb4a0efcac5c8f3500eeaa79 Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Wed, 21 Mar 2018 21:59:53 -0700 Subject: [PATCH 06/19] add comment about configAux --- cnc_ctrl_v1/System.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/cnc_ctrl_v1/System.cpp b/cnc_ctrl_v1/System.cpp index 4675124e..fa35b9f0 100644 --- a/cnc_ctrl_v1/System.cpp +++ b/cnc_ctrl_v1/System.cpp @@ -234,6 +234,9 @@ void setupAxes(){ 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 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 == 3){ // TLE5206 configAuxHigh(AUX7, AUX8, AUX9); From 1a4f2b33018832b1eaea07483b7d1e7a2a2dd6cb Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Wed, 28 Mar 2018 11:21:27 -0700 Subject: [PATCH 07/19] set AUX pins at runtime This works, but leaving the debugging print statements for now. Those can be removed later. --- cnc_ctrl_v1/System.cpp | 17 +++++++++++++++-- cnc_ctrl_v1/System.h | 3 +++ cnc_ctrl_v1/cnc_ctrl_v1.ino | 7 +++++++ 3 files changed, 25 insertions(+), 2 deletions(-) diff --git a/cnc_ctrl_v1/System.cpp b/cnc_ctrl_v1/System.cpp index fa35b9f0..53817277 100644 --- a/cnc_ctrl_v1/System.cpp +++ b/cnc_ctrl_v1/System.cpp @@ -20,8 +20,11 @@ Copyright 2014-2017 Bar Smith*/ #include "Maslow.h" bool TLE5206; + +// 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 testAUXPin; // prove it works void calibrateChainLengths(String gcodeLine){ @@ -244,11 +247,21 @@ void setupAxes(){ } void configAuxLow(int AUX1, int AUX2, int AUX3, int AUX4, int AUX5, int AUX6) { - #define SpindlePowerControlPin = AUX1; // output for controlling spindle power - #define ProbePin = AUX4 // use this input for zeroing zAxis with G38.2 gcode + SpindlePowerControlPin = AUX1; // output for controlling spindle power + ProbePin = AUX4; // use this input for zeroing zAxis with G38.2 gcode + // SpindlePowerControlPin = AUX1; + // ProbePin = AUX4; + // Serial.print(F("SpindlePowerControlPin = ")); + // Serial.println(SpindlePowerControlPin); // output for controlling spindle power + // Serial.print(F("ProbePin = ")); + // Serial.println(ProbePin); + } void configAuxHigh(int AUX7, int AUX8, int AUX9) { + testAUXPin = AUX9; + Serial.print(F("testAUXPin = ")); + Serial.println(testAUXPin); } int getPCBVersion(){ diff --git a/cnc_ctrl_v1/System.h b/cnc_ctrl_v1/System.h index 21c3eb19..494c6faf 100644 --- a/cnc_ctrl_v1/System.h +++ b/cnc_ctrl_v1/System.h @@ -74,6 +74,9 @@ extern Axis zAxis; extern RingBuffer incSerialBuffer; extern Kinematics kinematics; extern byte systemRtExecAlarm; +extern int SpindlePowerControlPin; +extern int ProbePin; +extern int testAUXPin; void calibrateChainLengths(String); void setupAxes(); diff --git a/cnc_ctrl_v1/cnc_ctrl_v1.ino b/cnc_ctrl_v1/cnc_ctrl_v1.ino index 5c6ac91b..7a5782da 100644 --- a/cnc_ctrl_v1/cnc_ctrl_v1.ino +++ b/cnc_ctrl_v1/cnc_ctrl_v1.ino @@ -70,6 +70,13 @@ void setup(){ readyCommandString.reserve(INCBUFFERLENGTH); //Allocate memory so that this string doesn't fragment the heap as it grows and shrinks gcodeLine.reserve(INCBUFFERLENGTH); + // Serial.print(F("SpindlePowerControlPin = ")); + // Serial.println(SpindlePowerControlPin); // output for controlling spindle power + // Serial.print(F("ProbePin = ")); + // Serial.println(ProbePin); + // Serial.print(F("testAUXPin = ")); + // Serial.println(testAUXPin); + // #ifndef SIMAVR // Using the timer will crash simavr, so we disable it. // Instead, we'll run runsOnATimer periodically in loop(). Timer1.initialize(LOOPINTERVAL); From 2a45ff669ec83f6c0534ce6133719d00c7a55aea Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Mon, 2 Apr 2018 15:37:05 -0700 Subject: [PATCH 08/19] remove auxPin test code --- cnc_ctrl_v1/System.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/cnc_ctrl_v1/System.cpp b/cnc_ctrl_v1/System.cpp index 280c6f5b..b878c030 100644 --- a/cnc_ctrl_v1/System.cpp +++ b/cnc_ctrl_v1/System.cpp @@ -24,7 +24,6 @@ bool TLE5206; // 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 testAUXPin; // prove it works void calibrateChainLengths(String gcodeLine){ @@ -261,9 +260,6 @@ void configAuxLow(int AUX1, int AUX2, int AUX3, int AUX4, int AUX5, int AUX6) { } void configAuxHigh(int AUX7, int AUX8, int AUX9) { - testAUXPin = AUX9; - Serial.print(F("testAUXPin = ")); - Serial.println(testAUXPin); } int getPCBVersion(){ From 8a8e9e74dcd4f470946ec701cedf6000de2ee149 Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Mon, 2 Apr 2018 20:52:39 -0700 Subject: [PATCH 09/19] Correct the z-axis pin assignments --- cnc_ctrl_v1/System.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/cnc_ctrl_v1/System.cpp b/cnc_ctrl_v1/System.cpp index 280c6f5b..d67b8c88 100644 --- a/cnc_ctrl_v1/System.cpp +++ b/cnc_ctrl_v1/System.cpp @@ -200,10 +200,10 @@ void setupAxes(){ ENA = 5; // errorFlag //MP2 - Z-axis - ENCODER2A = 18; // INPUT - ENCODER2B = 19; // INPUT - IN3 = 9; // OUTPUT - IN4 = 7; // OUTPUT + ENCODER2A = 19; // INPUT + ENCODER2B = 18; // INPUT + IN3 = 7; // OUTPUT + IN4 = 9; // OUTPUT ENB = 8; // errorFlag //MP3 - Left Motor @@ -213,6 +213,7 @@ void setupAxes(){ IN6 = 11; // OUTPUT ENC = 12; // errorFlag + //AUX pins AUX1 = 40; AUX2 = 41; AUX3 = 42; From c31ba5c9b3640f2bf8d0632ff597ccabdf6d8f68 Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Tue, 3 Apr 2018 12:51:11 -0700 Subject: [PATCH 10/19] Print a notice that this is the TLE5206 version of firmware Even if a standard board is detected. --- cnc_ctrl_v1/cnc_ctrl_v1.ino | 1 + 1 file changed, 1 insertion(+) diff --git a/cnc_ctrl_v1/cnc_ctrl_v1.ino b/cnc_ctrl_v1/cnc_ctrl_v1.ino index d0562b92..3880cfd6 100644 --- a/cnc_ctrl_v1/cnc_ctrl_v1.ino +++ b/cnc_ctrl_v1/cnc_ctrl_v1.ino @@ -59,6 +59,7 @@ void setup(){ Serial.print(getPCBVersion()); if (TLE5206 == true) { Serial.print(F(" TLE5206 ")); } Serial.println(F(" Detected")); + Serial.println(F("TLE5206-release firmware")); sys.inchesToMMConversion = 1; settingsLoadFromEEprom(); setupAxes(); From c508e249d950b193a4e0167c137289cc84c972b7 Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Sat, 7 Apr 2018 21:15:31 -0700 Subject: [PATCH 11/19] cleanup --- cnc_ctrl_v1/System.cpp | 7 ------- 1 file changed, 7 deletions(-) diff --git a/cnc_ctrl_v1/System.cpp b/cnc_ctrl_v1/System.cpp index 435a668a..6d4279a8 100644 --- a/cnc_ctrl_v1/System.cpp +++ b/cnc_ctrl_v1/System.cpp @@ -251,13 +251,6 @@ void setupAxes(){ void configAuxLow(int AUX1, int AUX2, int AUX3, int AUX4, int AUX5, int AUX6) { SpindlePowerControlPin = AUX1; // output for controlling spindle power ProbePin = AUX4; // use this input for zeroing zAxis with G38.2 gcode - // SpindlePowerControlPin = AUX1; - // ProbePin = AUX4; - // Serial.print(F("SpindlePowerControlPin = ")); - // Serial.println(SpindlePowerControlPin); // output for controlling spindle power - // Serial.print(F("ProbePin = ")); - // Serial.println(ProbePin); - } void configAuxHigh(int AUX7, int AUX8, int AUX9) { From eacaf8dae14aff3293a13a0e6f5676670382a4be Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Thu, 19 Apr 2018 15:41:26 -0700 Subject: [PATCH 12/19] Change logic of getPCBVersion to use pullups --- cnc_ctrl_v1/System.cpp | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/cnc_ctrl_v1/System.cpp b/cnc_ctrl_v1/System.cpp index 6d4279a8..36152fd1 100644 --- a/cnc_ctrl_v1/System.cpp +++ b/cnc_ctrl_v1/System.cpp @@ -257,13 +257,15 @@ void configAuxHigh(int AUX7, int AUX8, int AUX9) { } int getPCBVersion(){ - pinMode(VERS1,INPUT); - pinMode(VERS2,INPUT); - pinMode(VERS3,INPUT); - pinMode(VERS4,INPUT); + pinMode(VERS1,INPUT_PULLUP); + pinMode(VERS2,INPUT_PULLUP); + pinMode(VERS3,INPUT_PULLUP); + pinMode(VERS4,INPUT_PULLUP); int pinCheck = (8*digitalRead(VERS4) + 4*digitalRead(VERS3) + 2*digitalRead(VERS2) + 1*digitalRead(VERS1)); switch (pinCheck) { - case 0: case 1: case 2: case 3: // v1.2 board + // case 0: case 1: case 2: case 3: // v1.2 board + case 12: case 13: case 14: case 15: // v1.2 board + pinCheck -= 12; TLE5206 = false; break; case 4: From 74f83750bf2b602f1ab2436d3eb4c84775561398 Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Thu, 19 Apr 2018 17:28:52 -0700 Subject: [PATCH 13/19] Add more VERS inputs accommodate future boards --- cnc_ctrl_v1/Config.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/cnc_ctrl_v1/Config.h b/cnc_ctrl_v1/Config.h index cb18496d..b31d2dac 100644 --- a/cnc_ctrl_v1/Config.h +++ b/cnc_ctrl_v1/Config.h @@ -40,6 +40,8 @@ #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 From cfeb3d8e6207fcdec2b33f7b9c9613c474472e4f Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Thu, 10 May 2018 18:32:49 -0700 Subject: [PATCH 14/19] implement PR#441, change pin definitions to lower case --- cnc_ctrl_v1/System.cpp | 309 +++++++++++++++++++---------------------- 1 file changed, 142 insertions(+), 167 deletions(-) diff --git a/cnc_ctrl_v1/System.cpp b/cnc_ctrl_v1/System.cpp index 36152fd1..62957ef4 100644 --- a/cnc_ctrl_v1/System.cpp +++ b/cnc_ctrl_v1/System.cpp @@ -64,34 +64,34 @@ void setupAxes(){ */ - // These shouldn't be CAPS, they are not precompile defines - 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; + + 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(); @@ -99,161 +99,163 @@ void setupAxes(){ 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 + 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 + 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 + 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 + 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 + 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 + 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 + 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; + 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 + 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 + 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 - - AUX1 = 17; - AUX2 = 16; - AUX3 = 15; - AUX4 = 14; - AUX5 = 61; // A7; - AUX6 = 60; // A6; + 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 == 3){ // TLE5206 //TLE5206 PCB v1.3 Detected //MP1 - Right Motor - ENCODER1A = 20; // INPUT - ENCODER1B = 21; // INPUT - IN1 = 6; // OUTPUT - IN2 = 4; // OUTPUT - ENA = 5; // errorFlag + 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 + 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 + 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; + aux1 = 40; + aux2 = 41; + aux3 = 42; + aux4 = 43; + aux5 = 68; + aux6 = 69; + aux7 = 45; + aux8 = 46; + aux9 = 47; } if(sysSettings.chainOverSprocket == 1){ - leftAxis.setup (ENC, IN6, IN5, ENCODER3B, ENCODER3A, 'L', LOOPINTERVAL); - rightAxis.setup(ENA, IN1, IN2, ENCODER1A, ENCODER1B, 'R', LOOPINTERVAL); + 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); + 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); + 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 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); + // 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 == 3){ // TLE5206 - configAuxHigh(AUX7, AUX8, AUX9); -} + configAuxHigh(aux7, aux8, aux9); + } } -void configAuxLow(int AUX1, int AUX2, int AUX3, int AUX4, int AUX5, int AUX6) { - SpindlePowerControlPin = AUX1; // output for controlling spindle power - ProbePin = AUX4; // use this input for zeroing zAxis with G38.2 gcode +// 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 + ProbePin = aux4; // use this input for zeroing zAxis with G38.2 gcode } -void configAuxHigh(int AUX7, int AUX8, int AUX9) { +void configAuxHigh(int aux7, int aux8, int aux9) { } int getPCBVersion(){ @@ -261,14 +263,17 @@ int getPCBVersion(){ pinMode(VERS2,INPUT_PULLUP); pinMode(VERS3,INPUT_PULLUP); pinMode(VERS4,INPUT_PULLUP); - int pinCheck = (8*digitalRead(VERS4) + 4*digitalRead(VERS3) + 2*digitalRead(VERS2) + 1*digitalRead(VERS1)); + 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)); switch (pinCheck) { - // case 0: case 1: case 2: case 3: // v1.2 board - case 12: case 13: case 14: case 15: // v1.2 board - pinCheck -= 12; + // 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 TLE5206 = false; break; - case 4: + case B110100: case B000100: // some versions of board v1.4 don't strap VERS5-6 low + pinCheck &= B000111; // strip off the unstrapped bits TLE5206 = true; break; } @@ -406,36 +411,6 @@ void systemSaveAxesPosition(){ } } -// This should be the ultimate fallback, it would be best if we didn't even need -// something like this at all -// TODO delete this function, we are not even using it anymore -void _watchDog(){ - /* - If: - No incoming serial in 5 seconds - Motors are detached - Nothing in Serial buffer - Watchdog has not run in 5 seconds - Then: - Send an ok message - - This fixes the issue where the machine is ready, but Ground Control doesn't know the machine is ready and the system locks up. - */ - static unsigned long lastRan = millis(); - - if ( millis() - sys.lastSerialRcvd > 5000 && - (millis() - lastRan) > 5000 && - !leftAxis.attached() and !rightAxis.attached() and !zAxis.attached() && - incSerialBuffer.length() == 0 - ){ - #if defined (verboseDebug) && verboseDebug > 0 - Serial.println(F("_watchDog requesting new code")); - #endif - reportStatusMessage(STATUS_OK); - lastRan = millis(); - } -} - void systemReset(){ /* Stops everything and resets the arduino From 0e5209c9fa2eba0c2bdf9e47a955df232561e698 Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Thu, 10 May 2018 18:46:14 -0700 Subject: [PATCH 15/19] Clean unused functions in Motor.cpp as PR#441 --- cnc_ctrl_v1/Motor.cpp | 33 --------------------------------- cnc_ctrl_v1/Motor.h | 3 --- 2 files changed, 36 deletions(-) diff --git a/cnc_ctrl_v1/Motor.cpp b/cnc_ctrl_v1/Motor.cpp index b39adc50..58aea7a8 100644 --- a/cnc_ctrl_v1/Motor.cpp +++ b/cnc_ctrl_v1/Motor.cpp @@ -161,36 +161,3 @@ int Motor::attached(){ return _attachedState; } -int Motor::_convolve(const int& input){ - /* - This function distorts the input signal in a manner which is the inverse of the way - the mechanics of the motor distort it to give a linear response. - */ - - int output = input; - - int arrayLen = sizeof(_linSegments)/sizeof(_linSegments[1]); - for (int i = 0; i <= arrayLen - 1; i++){ - if (input > _linSegments[i].negativeBound and input < _linSegments[i].positiveBound){ - output = (input + _linSegments[i].intercept)/_linSegments[i].slope; - break; - } - } - - return output; -} - -void Motor::setSegment(const int& index, const float& slope, const float& intercept, const int& negativeBound, const int& positiveBound){ - - //Adds a linearizion segment to the linSegments object in location index - - _linSegments[index].slope = slope; - _linSegments[index].intercept = intercept; - _linSegments[index].positiveBound = positiveBound; - _linSegments[index].negativeBound = negativeBound; - -} - -LinSegment Motor::getSegment(const int& index){ - return _linSegments[index]; -} diff --git a/cnc_ctrl_v1/Motor.h b/cnc_ctrl_v1/Motor.h index 0ee54bfd..2632f495 100644 --- a/cnc_ctrl_v1/Motor.h +++ b/cnc_ctrl_v1/Motor.h @@ -39,9 +39,6 @@ int lastSpeed(); void additiveWrite(int speed); int attached(); - int _convolve(const int& input); - void setSegment(const int& index, const float& slope, const float& intercept, const int& negativeBound, const int& positiveBound); - LinSegment getSegment(const int& index); void directWrite(int voltage); private: int _pwmPin; From a17823c534ce1b2dff1b6a015ec8cbd4c1822aca Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Thu, 10 May 2018 18:59:10 -0700 Subject: [PATCH 16/19] Change Morot::write() to accept 'force' override as in PR#444 --- cnc_ctrl_v1/Motor.cpp | 24 ++++-------------------- cnc_ctrl_v1/Motor.h | 2 +- 2 files changed, 5 insertions(+), 21 deletions(-) diff --git a/cnc_ctrl_v1/Motor.cpp b/cnc_ctrl_v1/Motor.cpp index 58aea7a8..bb01a71f 100644 --- a/cnc_ctrl_v1/Motor.cpp +++ b/cnc_ctrl_v1/Motor.cpp @@ -93,11 +93,11 @@ void Motor::additiveWrite(int speed){ write(_lastSpeed + speed); } -void Motor::write(int 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. + 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){ + if (_attachedState == 1 or force){ speed = constrain(speed, -255, 255); _lastSpeed = speed; //saves speed for use in additive write bool forward = (speed > 0); @@ -137,23 +137,7 @@ void Motor::directWrite(int voltage){ /* Write directly to the motor, ignoring if the axis is attached or any applied calibration. */ - bool forward = (voltage >= 0); - if (forward) { - if (voltage > 0) { - digitalWrite(_pin1 , HIGH ); - analogWrite(_pin2 , 255 - abs(voltage)); // invert drive signals - don't alter speed - } else { - digitalWrite(_pin1 , LOW ); - digitalWrite(_pin2 , LOW ); - } - } - else{ - analogWrite(_pin1 , 255 - abs(voltage)); // invert drive signals - don't alter speed - digitalWrite(_pin2 , HIGH ); - } - if (TLE5206 == false) { - digitalWrite(_pwmPin, HIGH); - } + write(voltage, true); } int Motor::attached(){ diff --git a/cnc_ctrl_v1/Motor.h b/cnc_ctrl_v1/Motor.h index 2632f495..8efad4a9 100644 --- a/cnc_ctrl_v1/Motor.h +++ b/cnc_ctrl_v1/Motor.h @@ -35,7 +35,7 @@ void attach(); int setupMotor(const int& pwmPin, const int& pin1, const int& pin2); void detach(); - void write(int speed); + void write(int speed, bool force = false); int lastSpeed(); void additiveWrite(int speed); int attached(); From c387c192d5bdb6ccb857ac3b4e0c67bd1689a9b3 Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Thu, 10 May 2018 22:17:42 -0700 Subject: [PATCH 17/19] Add PCB v1..2 specific code from PR#442 FWIW, that code breaks the TLE5206, thus a fully separate section of write() --- cnc_ctrl_v1/Motor.cpp | 83 +++++++++++++++++++++++++++++++------------ 1 file changed, 61 insertions(+), 22 deletions(-) diff --git a/cnc_ctrl_v1/Motor.cpp b/cnc_ctrl_v1/Motor.cpp index bb01a71f..9ef8058c 100644 --- a/cnc_ctrl_v1/Motor.cpp +++ b/cnc_ctrl_v1/Motor.cpp @@ -105,30 +105,69 @@ 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 - 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 { - digitalWrite(_pin1 , LOW ); - digitalWrite(_pin2 , LOW ); + bool usepwmPin = ((TLE5206 == false) && (_pwmPin != 4) && (_pwmPin != 13) && (_pwmPin != 11) && (_pwmPin != 12)); // avoid PWM using timer0 or timer1 + if (!TLE5206) { + 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{ - if (usePin1) { - analogWrite(_pin1 , 255 - speed); // invert drive signals - don't alter speed - digitalWrite(_pin2 , HIGH ); - } else { - analogWrite(_pin2 , speed); - digitalWrite(_pin1 , LOW ); + 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); + } + } + } + else { // 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 , LOW ); + digitalWrite(_pin2 , LOW ); + } + } + 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 ); + } } - } - if (TLE5206 == false) { - digitalWrite(_pwmPin, HIGH); } } } From cb0f69b0bf872326236a04ba3745603d96e7828e Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Thu, 10 May 2018 22:23:03 -0700 Subject: [PATCH 18/19] Add PR#443 - Add robot file --- Robot.md | 3 +++ 1 file changed, 3 insertions(+) create mode 100644 Robot.md diff --git a/Robot.md b/Robot.md new file mode 100644 index 00000000..d29b37cb --- /dev/null +++ b/Robot.md @@ -0,0 +1,3 @@ +ModerationLevel = communityManaged + + Facilitator: barboursmith From f2bb30cdb65839f88a163b22a8922a346f99fcf9 Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Thu, 10 May 2018 22:40:05 -0700 Subject: [PATCH 19/19] purge phantom file from platformio --- cnc_ctrl_v1/cnc_ctrl_v1.ino.cpp | 91 --------------------------------- 1 file changed, 91 deletions(-) delete mode 100644 cnc_ctrl_v1/cnc_ctrl_v1.ino.cpp diff --git a/cnc_ctrl_v1/cnc_ctrl_v1.ino.cpp b/cnc_ctrl_v1/cnc_ctrl_v1.ino.cpp deleted file mode 100644 index 311cf3dc..00000000 --- a/cnc_ctrl_v1/cnc_ctrl_v1.ino.cpp +++ /dev/null @@ -1,91 +0,0 @@ -# 1 "/var/folders/1y/91bw_rsx4fdbc4yzb1wpkhvw0000gp/T/tmphLYhgy" -#include -# 1 "/Users/scottsmi/Documents/GitHub/blurfl/Firmware/cnc_ctrl_v1/cnc_ctrl_v1.ino" -# 36 "/Users/scottsmi/Documents/GitHub/blurfl/Firmware/cnc_ctrl_v1/cnc_ctrl_v1.ino" -#include "Maslow.h" - - -system_t sys; - - -settings_t sysSettings; - - -byte systemRtExecAlarm; - - -Axis leftAxis; -Axis rightAxis; -Axis zAxis; - - - -Kinematics kinematics; -void setup(); -void runsOnATimer(); -void loop(); -#line 56 "/Users/scottsmi/Documents/GitHub/blurfl/Firmware/cnc_ctrl_v1/cnc_ctrl_v1.ino" -void setup(){ - Serial.begin(57600); - Serial.print(F("PCB v1.")); - Serial.print(getPCBVersion()); - if (TLE5206 == true) { Serial.print(F(" TLE5206 ")); } - Serial.println(F(" Detected")); - Serial.println(F("TLE5206-release firmware")); - sys.inchesToMMConversion = 1; - settingsLoadFromEEprom(); - setupAxes(); - settingsLoadStepsFromEEprom(); - - leftAxis.write(leftAxis.read()); - rightAxis.write(rightAxis.read()); - zAxis.write(zAxis.read()); - readyCommandString.reserve(INCBUFFERLENGTH); - gcodeLine.reserve(INCBUFFERLENGTH); - - #ifndef SIMAVR - - Timer1.initialize(LOOPINTERVAL); - Timer1.attachInterrupt(runsOnATimer); - #endif - - Serial.println(F("Grbl v1.00")); - 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(){ - - initGCode(); - if (sys.stop){ - initMotion(); - setSpindlePower(false); - } - - kinematics.init(); - - - sys.stop = false; - - - while (!sys.stop){ - gcodeExecuteLoop(); - #ifdef SIMAVR - runsOnATimer(); - #endif - execSystemRealtime(); - } -} \ No newline at end of file